From e5f22e3b3a9617d55160d585b5b2fc479325470a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 31 Aug 2022 00:24:17 +0200 Subject: [PATCH 01/28] Add topic parameter to thrust plugin (#1681) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Add topic parameter. Signed-off-by: Carlos Agüero --- src/systems/thruster/Thruster.cc | 21 +++++++++++++++++++-- src/systems/thruster/Thruster.hh | 4 +++- test/integration/thruster.cc | 26 +++++++++++++++++--------- test/worlds/thruster_battery.sdf | 1 + 4 files changed, 40 insertions(+), 12 deletions(-) diff --git a/src/systems/thruster/Thruster.cc b/src/systems/thruster/Thruster.cc index 92a74bb3a7..b775cf26e4 100644 --- a/src/systems/thruster/Thruster.cc +++ b/src/systems/thruster/Thruster.cc @@ -104,6 +104,9 @@ class ignition::gazebo::systems::ThrusterPrivateData /// \brief Diameter of propeller in m, default: 0.02 public: double propellerDiameter = 0.02; + /// \brief Topic name used to control thrust. + public: std::string topic = ""; + /// \brief Callback for handling thrust update public: void OnCmdThrust(const msgs::Double &_msg); @@ -171,6 +174,13 @@ void Thruster::Configure( this->dataPtr->fluidDensity = _sdf->Get("fluid_density"); } + // Get a custom topic. + if (_sdf->HasElement("topic")) + { + this->dataPtr->topic = transport::TopicUtils::AsValidTopic( + _sdf->Get("topic")); + } + this->dataPtr->jointEntity = model.JointByName(_ecm, jointName); if (kNullEntity == this->dataPtr->jointEntity) { @@ -191,14 +201,21 @@ void Thruster::Configure( std::string thrusterTopicOld = ignition::transport::TopicUtils::AsValidTopic( "/model/" + ns + "/joint/" + jointName + "/cmd_pos"); + ignwarn << thrusterTopicOld << " topic is deprecated" << std::endl; + this->dataPtr->node.Subscribe( thrusterTopicOld, &ThrusterPrivateData::OnCmdThrust, this->dataPtr.get()); // Subscribe to force commands - std::string thrusterTopic = ignition::transport::TopicUtils::AsValidTopic( - "/model/" + ns + "/joint/" + jointName + "/cmd_thrust"); + std::string thrusterTopic = + "/model/" + ns + "/joint/" + jointName + "/cmd_thrust"; + + if (!this->dataPtr->topic.empty()) + thrusterTopic = ns + "/" + this->dataPtr->topic; + + thrusterTopic = transport::TopicUtils::AsValidTopic(thrusterTopic); this->dataPtr->node.Subscribe( thrusterTopic, diff --git a/src/systems/thruster/Thruster.hh b/src/systems/thruster/Thruster.hh index 6380eb7972..415fa8b660 100644 --- a/src/systems/thruster/Thruster.hh +++ b/src/systems/thruster/Thruster.hh @@ -40,8 +40,10 @@ namespace systems /// /// ## System Parameters /// - - The namespace in which the robot exists. The plugin will - /// listen on the topic `/model/{namespace}/joint/{joint_name}/cmd_thrust`. + /// listen on the topic `/model/{namespace}/joint/{joint_name}/cmd_thrust` + /// or on {namespace}/{topic} if {topic} is set. /// [Optional] + /// - - The topic for receiving thrust commands. [Optional] /// - - This is the joint in the model which corresponds to the /// propeller. [Required] /// - - The fluid density of the liquid in which the thruster diff --git a/test/integration/thruster.cc b/test/integration/thruster.cc index 1d28df8d5d..1e147bfe69 100644 --- a/test/integration/thruster.cc +++ b/test/integration/thruster.cc @@ -43,19 +43,20 @@ class ThrusterTest : public InternalFixture<::testing::Test> /// \brief Test a world file /// \param[in] _world Path to world file /// \param[in] _namespace Namespace for topic + /// \param[in] _topic Thrust topic /// \param[in] _coefficient Thrust coefficient /// \param[in] _density Fluid density /// \param[in] _diameter Propeller diameter /// \param[in] _baseTol Base tolerance for most quantities public: void TestWorld(const std::string &_world, - const std::string &_namespace, double _coefficient, double _density, - double _diameter, double _baseTol); + const std::string &_namespace, const std::string &_topic, + double _coefficient, double _density, double _diameter, double _baseTol); }; ////////////////////////////////////////////////// void ThrusterTest::TestWorld(const std::string &_world, - const std::string &_namespace, double _coefficient, double _density, - double _diameter, double _baseTol) + const std::string &_namespace, const std::string &_topic, + double _coefficient, double _density, double _diameter, double _baseTol) { // Start server ServerConfig serverConfig; @@ -122,8 +123,7 @@ void ThrusterTest::TestWorld(const std::string &_world, // Publish command and check that vehicle moved transport::Node node; - auto pub = node.Advertise( - "/model/" + _namespace + "/joint/propeller_joint/cmd_thrust"); + auto pub = node.Advertise(_topic); int sleep{0}; int maxSleep{30}; @@ -234,31 +234,39 @@ void ThrusterTest::TestWorld(const std::string &_world, // See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 TEST_F(ThrusterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PIDControl)) { + const std::string ns{"sub"}; + const std::string topic = "/model/" + ns + + "/joint/propeller_joint/cmd_thrust"; auto world = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "thruster_pid.sdf"); // Tolerance could be lower (1e-6) if the joint pose had a precise 180 // rotation - this->TestWorld(world, "sub", 0.004, 1000, 0.2, 1e-4); + this->TestWorld(world, ns, topic, 0.004, 1000, 0.2, 1e-4); } ///////////////////////////////////////////////// TEST_F(ThrusterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(VelocityControl)) { + const std::string ns = "custom"; + const std::string topic = "/model/" + ns + + "/joint/propeller_joint/cmd_thrust"; auto world = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "thruster_vel_cmd.sdf"); // Tolerance is high because the joint command disturbs the vehicle body - this->TestWorld(world, "custom", 0.005, 950, 0.25, 1e-2); + this->TestWorld(world, ns, topic, 0.005, 950, 0.25, 1e-2); } ///////////////////////////////////////////////// TEST_F(ThrusterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(BatteryIntegration)) { + const std::string ns = "lowbattery"; + const std::string topic = ns + "/thrust"; auto world = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "thruster_battery.sdf"); // Tolerance is high because the joint command disturbs the vehicle body - this->TestWorld(world, "lowbattery", 0.005, 950, 0.25, 1e-2); + this->TestWorld(world, ns, topic, 0.005, 950, 0.25, 1e-2); } diff --git a/test/worlds/thruster_battery.sdf b/test/worlds/thruster_battery.sdf index 3cf5a3495e..0a76710429 100644 --- a/test/worlds/thruster_battery.sdf +++ b/test/worlds/thruster_battery.sdf @@ -105,6 +105,7 @@ true 300 0 + thrust Date: Tue, 30 Aug 2022 19:16:32 -0700 Subject: [PATCH 02/28] =?UTF-8?q?=F0=9F=8E=88=206.12.0:=20bumped=20minor?= =?UTF-8?q?=20and=20updated=20changelog=20(#1682)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * bumped minor and updated changelog Signed-off-by: Dharini Dutia * fixed changelog as per feedback and updated migration guide Signed-off-by: Dharini Dutia Signed-off-by: Dharini Dutia --- CMakeLists.txt | 2 +- Changelog.md | 14 ++++++++++++++ Migration.md | 6 ++++++ 3 files changed, 21 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5efa74bd84..897ea591a0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-gazebo6 VERSION 6.11.0) +project(ignition-gazebo6 VERSION 6.12.0) set (GZ_DISTRIBUTION "Fortress") #============================================================================ diff --git a/Changelog.md b/Changelog.md index d9bb90509e..2487f3b1ce 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,5 +1,19 @@ ## Ignition Gazebo 6.x +### Gazebo Sim 6.12.0 (2022-08-30) + +1. Add topic parameter to thrust plugin + * [Pull request #1681](https://github.com/gazebosim/gz-sim/pull/1681) + +1. Add information about `` system parameter + * [Pull request #1671](https://github.com/gazebosim/gz-sim/pull/1671) + +1. Adding tests for hydrodynamics + * [Pull request #1617](https://github.com/gazebosim/gz-sim/pull/1617) + +1. Fix Windows and Doxygen + * [Pull request #1643](https://github.com/gazebosim/gz-sim/pull/1643) + ### Gazebo Sim 6.11.0 (2022-08-17) 1. Add support for specifying log record period diff --git a/Migration.md b/Migration.md index 58a4e5c815..ea3bdeea7c 100644 --- a/Migration.md +++ b/Migration.md @@ -5,6 +5,12 @@ Deprecated code produces compile-time warnings. These warning serve as notification to users that their code should be upgraded. The next major release will remove the deprecated code. +## Ignition Gazebo 6.11.X to 6.12.X + + * **Modified**: + + In the Hydrodynamics plugin, inverted the added mass contribution to make it + act in the correct direction. + ## Ignition Gazebo 6.1 to 6.2 * If no `` is given to the `Thruster` plugin, the namespace now From 545b36467c315a2ff45c337d3afce748ee109eff Mon Sep 17 00:00:00 2001 From: Kenji Brameld Date: Thu, 1 Sep 2022 16:29:57 +0900 Subject: [PATCH 03/28] Fix reference link in ackermann steering (#1683) Signed-off-by: Kenji Brameld --- src/systems/ackermann_steering/AckermannSteering.hh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systems/ackermann_steering/AckermannSteering.hh b/src/systems/ackermann_steering/AckermannSteering.hh index 11aacd9159..19b3f8d18c 100644 --- a/src/systems/ackermann_steering/AckermannSteering.hh +++ b/src/systems/ackermann_steering/AckermannSteering.hh @@ -111,7 +111,7 @@ namespace systems /// right_steering_joint /// /// References: - /// https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/systems/diff_drive + /// https://github.com/gazebosim/gz-sim/tree/main/src/systems/ackermann_steering /// https://www.auto.tuwien.ac.at/bib/pdf_TR/TR0183.pdf /// https://github.com/froohoo/ackermansteer/blob/master/ackermansteer/ From 69e77571904c4f1888bbeb5dad0eb6637123dbae Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Fri, 2 Sep 2022 20:38:37 +0200 Subject: [PATCH 04/28] Fix installation instructions on Ubuntu 22.04 (#1686) Signed-off-by: Silvio Traversaro --- tutorials/install.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tutorials/install.md b/tutorials/install.md index 3260f10154..1b1694f402 100644 --- a/tutorials/install.md +++ b/tutorials/install.md @@ -61,7 +61,7 @@ feature which hasn't been released yet. 1. Install tools ``` - sudo apt install -y build-essential cmake g++-8 git gnupg lsb-release wget + sudo apt install -y build-essential cmake git gnupg lsb-release wget ``` 2. Enable the Ignition software repositories: From 0cbe6e7d23c74f481c3a1758b4c62a2559137bc2 Mon Sep 17 00:00:00 2001 From: Liam Han Date: Wed, 7 Sep 2022 09:23:55 -0700 Subject: [PATCH 05/28] Add a service to trigger functionality (#1611) * initial commit to allow plugin to call a service Signed-off-by: Liam Han * adding tutorial and modifying the world sdf Signed-off-by: Liam Han * added test for single input and single service output Signed-off-by: Liam Han * added test for single input and multiple service output Signed-off-by: Liam Han * added test for invalid matching service name => timeout Signed-off-by: Liam Han * modified variables the camelCase Signed-off-by: Liam Han * fixed typo, indentation, grammar, lines that exceeded 80 char Signed-off-by: Liam Han * fixing ubuntu bionic ci issue Signed-off-by: Liam Han * silly syntax mistake on expect_eq Signed-off-by: Liam Han * added three more test cases that addesses incorrect response type, incorrect request type and false result Signed-off-by: Liam Han * WIP: major restructuring and currently working. Requires more cleanup and test Signed-off-by: Liam Han * WIP: fixed preprocessor define bug Signed-off-by: Liam Han * WIP: working but extremely convoluted Signed-off-by: Liam Han * WIP major modification but a lot of errors and tests failed Signed-off-by: Liam Han * stable version: had to revert back to previous work. all tests passed Signed-off-by: Liam Han * modified to use blocking Request method as well as reduce a service worker thread to just one thread with the publisher. all tests passed Signed-off-by: Liam Han * stable version: had to revert back to previous work. all tests passed Signed-off-by: Liam Han * successfully reverted and tested Signed-off-by: Liam Han * fixing PR suggestions Signed-off-by: Liam Han * changed string with 'serv' to 'srv' and included to the header Signed-off-by: Liam Han * fixed indentation and removed rep.set_data since it's unused on the client service Signed-off-by: Liam Han * getting rid of the id Signed-off-by: Liam Han * fixed race condition resulting seldom test failure Signed-off-by: Liam Han * changed from triggerSrv to serviceCount. This compensates for the two threads running at different rate Signed-off-by: Liam Han * braces indentation Signed-off-by: Mabel Zhang * addressing gnu c compiler (gcc) warnings Signed-off-by: Liam Han Signed-off-by: Liam Han Signed-off-by: Mabel Zhang Co-authored-by: Mabel Zhang --- examples/worlds/triggered_publisher.sdf | 35 ++- .../triggered_publisher/TriggeredPublisher.cc | 158 ++++++++-- .../triggered_publisher/TriggeredPublisher.hh | 57 +++- test/integration/triggered_publisher.cc | 269 ++++++++++++++++++ test/worlds/triggered_publisher.sdf | 161 +++++++++-- tutorials/triggered_publisher.md | 39 ++- 6 files changed, 664 insertions(+), 55 deletions(-) diff --git a/examples/worlds/triggered_publisher.sdf b/examples/worlds/triggered_publisher.sdf index 303f78beca..98b7c52c64 100644 --- a/examples/worlds/triggered_publisher.sdf +++ b/examples/worlds/triggered_publisher.sdf @@ -387,13 +387,17 @@ start falling. true - + body box1 box_body /box1/detach - + body box2 box_body @@ -448,19 +452,40 @@ start falling. - + linear: {x: 3} - + + + + linear: {x: 0} + + + + + data: true - + -7.5 diff --git a/src/systems/triggered_publisher/TriggeredPublisher.cc b/src/systems/triggered_publisher/TriggeredPublisher.cc index 94a63b7ac8..cc7a4f88ad 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.cc +++ b/src/systems/triggered_publisher/TriggeredPublisher.cc @@ -252,7 +252,9 @@ FullMatcher::FullMatcher(const std::string &_msgType, bool _logicType, : InputMatcher(_msgType), logicType(_logicType) { if (nullptr == this->matchMsg || !this->matchMsg->IsInitialized()) + { return; + } this->valid = google::protobuf::TextFormat::ParseFromString( _matchString, this->matchMsg.get()); @@ -273,7 +275,9 @@ FieldMatcher::FieldMatcher(const std::string &_msgType, bool _logicType, fieldName(_fieldName) { if (nullptr == this->matchMsg || !this->matchMsg->IsInitialized()) + { return; + } transport::ProtoMsg *matcherSubMsg{nullptr}; if (!FindFieldSubMessage(this->matchMsg.get(), _fieldName, @@ -294,7 +298,9 @@ FieldMatcher::FieldMatcher(const std::string &_msgType, bool _logicType, } if (nullptr == matcherSubMsg) + { return; + } bool result = google::protobuf::TextFormat::ParseFieldValueFromString( _fieldString, this->fieldDescMatcher.back(), matcherSubMsg); @@ -548,7 +554,9 @@ void TriggeredPublisher::Configure(const Entity &, { int ms = sdfClone->Get("delay_ms"); if (ms > 0) + { this->delay = std::chrono::milliseconds(ms); + } } if (sdfClone->HasElement("output")) @@ -595,9 +603,52 @@ void TriggeredPublisher::Configure(const Entity &, } } } - else + + if (sdfClone->HasElement("service")) { - ignerr << "No ouptut specified" << std::endl; + for (auto serviceElem = sdfClone->GetElement("service"); serviceElem; + serviceElem = serviceElem->GetNextElement("service")) + { + SrvOutputInfo serviceInfo; + serviceInfo.srvName = serviceElem->Get("name"); + if (serviceInfo.srvName.empty()) + { + ignerr << "Service name cannot be empty\n"; + return; + } + serviceInfo.reqType = serviceElem->Get("reqType"); + if (serviceInfo.reqType.empty()) + { + ignerr << "Service request type cannot be empty\n"; + return; + } + serviceInfo.repType = serviceElem->Get("repType"); + if (serviceInfo.repType.empty()) + { + ignerr << "Service reply type cannot be empty\n"; + return; + } + serviceInfo.reqMsg = serviceElem->Get("reqMsg"); + if (serviceInfo.reqMsg.empty()) + { + ignerr << "Service request message cannot be empty\n"; + return; + } + std::string timeoutInfo = serviceElem->Get("timeout"); + if (timeoutInfo.empty()) + { + ignerr << "Timeout value cannot be empty\n"; + return; + } + + serviceInfo.timeout = std::stoi(timeoutInfo); + this->srvOutputInfo.push_back(std::move(serviceInfo)); + } + } + if (!sdfClone->HasElement("service") && !sdfClone->HasElement("output")) + { + ignerr << "No output and service specified. Make sure to specify at least" + "one of them." << std::endl; return; } @@ -606,23 +657,27 @@ void TriggeredPublisher::Configure(const Entity &, { if (this->MatchInput(_msg)) { + if (this->delay > 0ms) + { + std::lock_guard lock(this->publishQueueMutex); + this->publishQueue.push_back(this->delay); + } + else { - if (this->delay > 0ms) - { - std::lock_guard lock(this->publishQueueMutex); - this->publishQueue.push_back(this->delay); - } - else { - { - std::lock_guard lock(this->publishCountMutex); - ++this->publishCount; - } - this->newMatchSignal.notify_one(); + std::lock_guard lock(this->publishCountMutex); + ++this->publishCount; } + this->newMatchSignal.notify_one(); + } + if (this->srvOutputInfo.size() > 0) + { + std::lock_guard lock(this->triggerSrvMutex); + ++this->serviceCount; } } }); + if (!this->node.Subscribe(this->inputTopic, msgCb)) { ignerr << "Input subscriber could not be created for topic [" @@ -645,11 +700,69 @@ void TriggeredPublisher::Configure(const Entity &, std::thread(std::bind(&TriggeredPublisher::DoWork, this)); } +////////////////////////////////////////////////// +void TriggeredPublisher::PublishMsg(std::size_t pending) +{ + for (auto &info : this->outputInfo) + { + for (std::size_t i = 0; i < pending; ++i) + { + info.pub.Publish(*info.msgData); + } + } +} + +////////////////////////////////////////////////// +void TriggeredPublisher::CallService(std::size_t pendingSrv) +{ + for (auto &serviceInfo : this->srvOutputInfo) + { + for (std::size_t i = 0; i < pendingSrv; ++i) + { + bool result; + auto req = msgs::Factory::New(serviceInfo.reqType, serviceInfo.reqMsg); + if (!req) + { + ignerr << "Unable to create request for type [" + << serviceInfo.reqType << "].\n"; + return; + } + + auto rep = msgs::Factory::New(serviceInfo.repType); + if (!rep) + { + ignerr << "Unable to create response for type [" + << serviceInfo.repType << "].\n"; + return; + } + + bool executed = this->node.Request(serviceInfo.srvName, *req, + serviceInfo.timeout, *rep, result); + if (executed) + { + if (!result) + { + ignerr << "Service call [" << serviceInfo.srvName << "] failed\n"; + } + else + { + ignmsg << "Service call [" << serviceInfo.srvName << "] succeeded\n"; + } + } + else + { + ignerr << "Service call [" << serviceInfo.srvName << "] timed out\n"; + } + } + } +} + ////////////////////////////////////////////////// void TriggeredPublisher::DoWork() { while (!this->done) { + // check whether to publish a msg by checking publishCount std::size_t pending{0}; { using namespace std::chrono_literals; @@ -661,18 +774,25 @@ void TriggeredPublisher::DoWork() }); if (this->publishCount == 0 || this->done) + { continue; - + } std::swap(pending, this->publishCount); } - for (auto &info : this->outputInfo) + PublishMsg(pending); + + // check whether to call a service by checking serviceCount + std::size_t pendingSrv{0}; { - for (std::size_t i = 0; i < pending; ++i) - { - info.pub.Publish(*info.msgData); + std::lock_guard lock(this->triggerSrvMutex); + if (this->serviceCount == 0 || this->done){ + continue; } + std::swap(pendingSrv, this->serviceCount); } + + CallService(pendingSrv); } } @@ -712,7 +832,9 @@ void TriggeredPublisher::PreUpdate(const ignition::gazebo::UpdateInfo &_info, } if (notify) + { this->newMatchSignal.notify_one(); + } } ////////////////////////////////////////////////// diff --git a/src/systems/triggered_publisher/TriggeredPublisher.hh b/src/systems/triggered_publisher/TriggeredPublisher.hh index f524b119ab..2560e67722 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.hh +++ b/src/systems/triggered_publisher/TriggeredPublisher.hh @@ -20,7 +20,7 @@ #include #include #include - +#include #include #include "ignition/gazebo/System.hh" @@ -37,8 +37,10 @@ namespace systems /// \brief The triggered publisher system publishes a user specified message /// on an output topic in response to an input message that matches user - /// specified criteria. An optional simulation time delay can be used - /// delay message publication. + /// specified criteria. It can also call a user specified service as an + /// output in response to an input message. It currently supports blocking + /// service call. An optional simulation time delay can be used delay message + /// publication. /// /// ## System Parameters /// @@ -75,9 +77,19 @@ namespace systems /// the human-readable representation of a protobuf message as used by /// `ign topic` for publishing messages /// - /// ``: Integer number of milliseconds, in simulation time, to + /// - ``: Integer number of milliseconds, in simulation time, to /// delay publication. /// + /// - ``: Contains configuration for service to call: Multiple + /// `` tags are possible. A service will be called for each input + /// that matches. + /// * Attributes: + /// * `name`: Service name (eg. `/world/triggered_publisher/set_pose`) + /// * `timeout`: Service timeout + /// * `reqType`: Service request message type (eg. ignition.msgs.Pose) + /// * `repType`: Service response message type (eg. ignition.msgs.Empty) + /// * `reqMsg`: String used to construct the service protobuf message. + /// /// Examples: /// 1. Any receipt of a Boolean messages on the input topic triggers an output /// \code{.xml} @@ -182,6 +194,12 @@ namespace systems /// \brief Thread that handles publishing output messages public: void DoWork(); + /// \brief Method that calls a service + private: void CallService(std::size_t pendingSrv); + + /// \brief Method that publishes a message + private: void PublishMsg(std::size_t pending); + /// \brief Helper function that calls Match on every InputMatcher available /// \param[in] _inputMsg Input message /// \return True if all of the matchers return true @@ -210,21 +228,49 @@ namespace systems transport::Node::Publisher pub; }; + /// \brief Class that holds necessary bits for each specified service output + private: struct SrvOutputInfo + { + /// \brief Service name + std::string srvName; + + /// \brief Service request type + std::string reqType; + + /// \brief Service reply type + std::string repType; + + /// \brief Service request message + std::string reqMsg; + + /// \brief Serivce timeout + int timeout; + }; + /// \brief List of InputMatchers private: std::vector> matchers; /// \brief List of outputs private: std::vector outputInfo; + /// \brief List of service outputs + private: std::vector srvOutputInfo; + /// \brief Ignition communication node. private: transport::Node node; + /// \brief Counter that tells how manny times to call the service + private: std::size_t serviceCount{0}; + /// \brief Counter that tells the publisher how many times to publish private: std::size_t publishCount{0}; /// \brief Mutex to synchronize access to publishCount private: std::mutex publishCountMutex; + /// \brief Mutex to synchronize access to serviceCount + private: std::mutex triggerSrvMutex; + /// \brief Condition variable to signal that new matches have occured private: std::condition_variable newMatchSignal; @@ -244,9 +290,8 @@ namespace systems /// \brief Mutex to synchronize access to publishQueue private: std::mutex publishQueueMutex; }; - } } } } - +} #endif diff --git a/test/integration/triggered_publisher.cc b/test/integration/triggered_publisher.cc index 9590a7c421..3ae1070d12 100644 --- a/test/integration/triggered_publisher.cc +++ b/test/integration/triggered_publisher.cc @@ -637,3 +637,272 @@ TEST_F(TriggeredPublisherTest, EXPECT_EQ(0u, recvCount); } + +///////////////////////////////////////////////// +/// Test for invalid service name. A service, `/srv-dummy-test` is advertised +/// and the callback is also provided in this test. Everytime an input msg is +/// published to `/in_14` topic, triggered_publisher plugin will call the +/// service `srv-test`, specified in the test/worlds/triggered_publisher.sdf. +/// However, since the two service names do not match, the callback provided in +/// this test will not be invoked. Therefore, the pubCount, which is set to 10, +/// will not equal to recvCount. The recvCount will be 0, since the callback +/// isn't invoked. +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(InvalidServiceName)) +{ + transport::Node node; + auto inputPub = node.Advertise("/in_14"); + std::atomic recvCount{0}; + + auto srvEchoCb = std::function( + [&recvCount](const auto &req, auto &) + { + EXPECT_EQ(req.data(), "test"); + if (req.data() == "test") + { + ++recvCount; + return true; + } + return false; + }); + + // Advertise a dummy service + std::string service = "/srv-dummy-test"; + node.Advertise(service, srvEchoCb); + + const std::size_t pubCount{10}; + for (std::size_t i = 0; i < pubCount; ++i) + { + EXPECT_TRUE(inputPub.Publish(msgs::Empty())); + IGN_SLEEP_MS(100); + } + + waitUntil(5000, [&]{return recvCount == 0u;}); + EXPECT_EQ(recvCount, 0u); +} + +///////////////////////////////////////////////// +/// Test for triggering a service call in response to an input msg. A service, +/// `srv-test` is advertised and the callback is also provided in this test. +/// Everytime an input msg is published to `/in_14` topic, triggered_publisher +/// plugin will call the service `/srv-test`, specified in the test/worlds/ +/// triggered_publisher.sdf. This time, the name of the services match. By +/// publishing input msg 10 times, the service callback will also be invoked 10 +/// times. The `pubCount` is set to 10 and recvCount is increased everytime +/// request data matches the string "test" inside the service callback. For a +/// successful test, the pubCount will equal to recvCount. +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(InputMessagesTriggerServices)) +{ + transport::Node node; + auto inputPub = node.Advertise("/in_14"); + std::atomic recvCount{0}; + + auto srvEchoCb = std::function( + [&recvCount](const auto &req, auto &) + { + EXPECT_EQ(req.data(), "test"); + if (req.data() == "test") + { + ++recvCount; + return true; + } + return false; + }); + + std::string service = "/srv-test"; + node.Advertise(service, srvEchoCb); + + const std::size_t pubCount{10}; + for (std::size_t i = 0; i < pubCount; ++i) + { + EXPECT_TRUE(inputPub.Publish(msgs::Empty())); + IGN_SLEEP_MS(100); + } + + waitUntil(5000, [&]{return pubCount == recvCount;}); + EXPECT_EQ(pubCount, recvCount); +} + +///////////////////////////////////////////////// +/// Test for triggering multiple services (in sequence) in response to an input +/// msg by publishing 10 times. Two services, `srv-test-0` and `srv-test-1` are +/// specified in the test/worlds/triggered_publisher.sdf. Everytime an input msg +/// is published, triggered_publisher will call the service and invoke the +/// callback. std::vector is passed as a reference and will be populated with +/// the request message, which will be a boolean value of `true`. If successful, +/// `recvMsg0` and `recvMsg1` vectors should both have a size of 10 with all +/// true boolean values. +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(MultipleServiceForOneInput)) +{ + transport::Node node; + auto inputPub = node.Advertise("/in_15"); + std::mutex recvMsgMutex; + std::vector recvMsgs0; + std::vector recvMsgs1; + auto cbCreator = [&recvMsgMutex](std::vector &_msgVector) + { + return std::function( + [&_msgVector, &recvMsgMutex](const auto &req, auto &) + { + std::lock_guard lock(recvMsgMutex); + if (req.data()) + { + _msgVector.push_back(req.data()); + return true; + } + return false; + }); + }; + + auto msgCb0 = cbCreator(recvMsgs0); + auto msgCb1 = cbCreator(recvMsgs1); + + // Advertise two dummy services + node.Advertise("/srv-test-0", msgCb0); + node.Advertise("/srv-test-1", msgCb1); + + const int pubCount{10}; + for (int i = 0; i < pubCount; ++i) + { + EXPECT_TRUE(inputPub.Publish(msgs::Empty())); + IGN_SLEEP_MS(100); + } + + waitUntil(5000, [&] + { + std::lock_guard lock(recvMsgMutex); + return static_cast(pubCount) == recvMsgs0.size() && + static_cast(pubCount) == recvMsgs1.size(); + }); + + EXPECT_EQ(static_cast(pubCount), recvMsgs0.size()); + EXPECT_EQ(static_cast(pubCount), recvMsgs1.size()); + + // The plugin has two outputs. We expect 10 messages in each output topic + EXPECT_EQ(pubCount, std::count(recvMsgs0.begin(), recvMsgs0.end(), true)); + EXPECT_EQ(pubCount, std::count(recvMsgs1.begin(), recvMsgs1.end(), true)); +} + +///////////////////////////////////////////////// +/// Test for triggering a service call with incorrect request type or reply +/// type specified in test/worlds/triggered_publisher.sdf. `InvalidReqType` and +/// `InvalidRepType` do not exist. Hence, the callback will never be invoked and +/// the recvCount will be 0. +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(WrongRequestOrResponseType)) +{ + transport::Node node; + auto inputPub = node.Advertise("/in_16"); + std::atomic recvCount{0}; + + auto srvEchoCb = std::function( + [&recvCount](const auto &req, auto &) + { + EXPECT_EQ(req.data(), "test"); + if (req.data() == "test") + { + ++recvCount; + return true; + } + return false; + }); + + // Advertise a dummy service + std::string service = "/srv-test"; + node.Advertise(service, srvEchoCb); + + const std::size_t pubCount{10}; + for (std::size_t i = 0; i < pubCount; ++i) + { + EXPECT_TRUE(inputPub.Publish(msgs::Empty())); + IGN_SLEEP_MS(100); + } + + waitUntil(5000, [&]{return recvCount == 0u;}); + EXPECT_EQ(0u, recvCount); +} + +///////////////////////////////////////////////// +/// Test for triggering a service call with different request (Boolean) and +/// reply type (StringMsg). Check `InputMessagesTriggerServices` test for more +/// details on how the test works. This test is very similar except that it has +/// different request and reply type. +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(BooleanReqStringMsgRep)) +{ + transport::Node node; + auto inputPub = node.Advertise("/in_18"); + std::atomic recvCount{0}; + + auto srvEchoCb = std::function( + [&recvCount](const auto &req, auto &) + { + EXPECT_EQ(req.data(), true); + if (req.data() == true) + { + ++recvCount; + return true; + } + return false; + }); + + // Advertise a dummy service + std::string service = "/srv-diff-type-0"; + node.Advertise(service, srvEchoCb); + + const std::size_t pubCount{10}; + for (std::size_t i = 0; i < pubCount; ++i) + { + EXPECT_TRUE(inputPub.Publish(msgs::Empty())); + IGN_SLEEP_MS(100); + } + + waitUntil(5000, [&]{return pubCount == recvCount;}); + EXPECT_EQ(pubCount, recvCount); +} + +///////////////////////////////////////////////// +/// Test for triggering a service call with different request (StringMsg) and +/// reply type (Boolean). Check `InputMessagesTriggerServices` test for more +/// details on how the test works. This test is very similar except that it has +/// different request and reply type. +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(StringMsgReqBooleanRep)) +{ + transport::Node node; + auto inputPub = node.Advertise("/in_19"); + std::atomic recvCount{0}; + + auto srvEchoCb = std::function( + [&recvCount](const auto &req, auto &) + { + EXPECT_EQ(req.data(), "test"); + if (req.data() == "test") + { + ++recvCount; + return true; + } + return false; + }); + + // Advertise a dummy service + std::string service = "/srv-diff-type-1"; + node.Advertise(service, srvEchoCb); + + const std::size_t pubCount{10}; + for (std::size_t i = 0; i < pubCount; ++i) + { + EXPECT_TRUE(inputPub.Publish(msgs::Empty())); + IGN_SLEEP_MS(100); + } + + waitUntil(5000, [&]{return pubCount == recvCount;}); + EXPECT_EQ(recvCount, recvCount); +} diff --git a/test/worlds/triggered_publisher.sdf b/test/worlds/triggered_publisher.sdf index 7c9f21c568..2ce7ab2394 100644 --- a/test/worlds/triggered_publisher.sdf +++ b/test/worlds/triggered_publisher.sdf @@ -5,19 +5,25 @@ 0 - + - + data: true - + data: false @@ -27,7 +33,9 @@ - + data: true @@ -36,7 +44,9 @@ - + data: 0 @@ -45,7 +55,9 @@ - + data: 0 @@ -54,7 +66,9 @@ - + data: -5 @@ -75,7 +89,9 @@ - + 1.0 2.0 @@ -83,7 +99,9 @@ - + 1.0 2.0 @@ -91,7 +109,9 @@ - + { @@ -102,7 +122,9 @@ - + { @@ -120,53 +142,152 @@ - + data: 0, data: 1 - + data: 0.5 - + 0.5 - + "value1" - + 1000 - - + + data: 0, data: 1 - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - diff --git a/tutorials/triggered_publisher.md b/tutorials/triggered_publisher.md index d07c74c318..ff4759c3ef 100644 --- a/tutorials/triggered_publisher.md +++ b/tutorials/triggered_publisher.md @@ -1,17 +1,20 @@ \page triggeredpublisher Triggered Publisher The `TriggeredPublisher` system publishes a user specified message on an output -topic in response to an input message that matches user specified criteria. The -system works by checking the input against a set of Matchers. Matchers -contain string representations of protobuf messages which are compared for -equality or containment with the input message. Matchers can match the whole -input message or only a specific field inside the message. +topic in response to an input message that matches user specified criteria. It +can also call a user specified service in response to an input +message. The system works by checking the input against a set of Matchers. +Matchers contain string representations of protobuf messages which are compared +for equality or containment with the input message. Matchers can match the +whole input message or only a specific field inside the message. + This tutorial describes how the Triggered Publisher system can be used to cause a box to fall from its initial position by detaching a detachable joint in response to the motion of a vehicle. The tutorial also covers how Triggered Publisher systems can be chained together by showing how the falling of the box -can trigger another box to fall. The finished world SDFormat file for this +can trigger another box to fall. Last, it covers how a service call can be +triggered to reset the robot pose. The finished world SDFormat file for this tutorial can be found in [examples/worlds/triggered_publisher.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo2/examples/worlds/triggered_publisher.sdf) @@ -263,3 +266,27 @@ and publish the start message ``` ign topic -t "/start" -m ignition.msgs.Empty -p " " ``` + +Once both boxes have fallen, we can publish a message to invoke a service call +to reset the robot position as well as set the speed to 0. As shown below, the +`` sets the linear x speed to 0, and the `` tag contains +metadata to invoke a service call to `/world/triggered_publisher/set_pose`. The +`reqMsg` is expressed in the human-readable form of Google Protobuf meesages. +Multiple `` tags can be used as well as with the `` tag. + +```xml + + + + linear: {x: 0} + + + + +``` From 721bc356a827b26b4edd893110e065f2f74c0963 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 9 Sep 2022 06:30:23 -0700 Subject: [PATCH 06/28] Fix loading render engine plugins in GUI (#1694) Signed-off-by: Ian Chen --- include/ignition/gazebo/rendering/RenderUtil.hh | 4 ++++ src/gui/plugins/scene_manager/GzSceneManager.cc | 9 +++++++++ src/rendering/RenderUtil.cc | 12 +++++++++--- 3 files changed, 22 insertions(+), 3 deletions(-) diff --git a/include/ignition/gazebo/rendering/RenderUtil.hh b/include/ignition/gazebo/rendering/RenderUtil.hh index a757ec5378..444d9c0daa 100644 --- a/include/ignition/gazebo/rendering/RenderUtil.hh +++ b/include/ignition/gazebo/rendering/RenderUtil.hh @@ -201,6 +201,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Clears the set of selected entities and lowlights all of them. public: void DeselectAllEntities(); + /// \brief Init render engine plugins paths. This lets gz-rendering know + /// paths to find render engine plugins + public: void InitRenderEnginePluginPaths(); + /// \brief Helper function to get all child links of a model entity. /// \param[in] _entity Entity to find child links /// \return Vector of child links found for the parent entity diff --git a/src/gui/plugins/scene_manager/GzSceneManager.cc b/src/gui/plugins/scene_manager/GzSceneManager.cc index f04c61d07a..9d0c6b1338 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.cc +++ b/src/gui/plugins/scene_manager/GzSceneManager.cc @@ -59,6 +59,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Rendering utility public: RenderUtil renderUtil; + /// \brief True if render engine plugins paths are initialized + public: bool renderEnginePluginPathsInit{false}; + /// \brief List of new entities from a gui event public: std::set newEntities; @@ -123,6 +126,12 @@ void GzSceneManager::Update(const UpdateInfo &_info, IGN_PROFILE("GzSceneManager::Update"); + if (!this->dataPtr->renderEnginePluginPathsInit) + { + this->dataPtr->renderUtil.InitRenderEnginePluginPaths(); + this->dataPtr->renderEnginePluginPathsInit = true; + } + this->dataPtr->renderUtil.UpdateECM(_info, _ecm); std::lock_guard lock(this->dataPtr->newRemovedEntityMutex); diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 415908ff9c..6f4ef07941 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -2496,6 +2496,14 @@ bool RenderUtil::HeadlessRendering() const return this->dataPtr->isHeadlessRendering; } +///////////////////////////////////////////////// +void RenderUtil::InitRenderEnginePluginPaths() +{ + ignition::common::SystemPaths pluginPath; + pluginPath.SetPluginPathEnv(kRenderPluginPathEnv); + rendering::setPluginPaths(pluginPath.PluginPaths()); +} + ///////////////////////////////////////////////// void RenderUtil::Init() { @@ -2503,9 +2511,7 @@ void RenderUtil::Init() if (nullptr != this->dataPtr->scene) return; - ignition::common::SystemPaths pluginPath; - pluginPath.SetPluginPathEnv(kRenderPluginPathEnv); - rendering::setPluginPaths(pluginPath.PluginPaths()); + this->InitRenderEnginePluginPaths(); std::map params; if (this->dataPtr->useCurrentGLContext) From 6b48eea5e74636ddde6445a167478663cc0f49c2 Mon Sep 17 00:00:00 2001 From: Benjamin Perseghetti Date: Thu, 22 Sep 2022 09:48:40 -0400 Subject: [PATCH 07/28] Enable inherited model topic name. (#1689) Allows for inheriting model name for robotNamespace when SDF element is not set and provides a debug message showing the topics it subscribes to. Signed-off-by: Benjamin Perseghetti Co-authored-by: Nate Koenig --- .../multicopter_motor_model/MulticopterMotorModel.cc | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc index dbb5102d00..db6552555b 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc @@ -6,6 +6,7 @@ * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland * Copyright 2016 Geoffrey Hunter * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2022 Benjamin Perseghetti, Rudis Laboratories * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -49,6 +50,7 @@ #include "ignition/gazebo/components/Wind.hh" #include "ignition/gazebo/Link.hh" #include "ignition/gazebo/Model.hh" +#include "ignition/gazebo/Util.hh" // from rotors_gazebo_plugins/include/rotors_gazebo_plugins/common.h /// \brief This class can be used to apply a first order filter on a signal. @@ -250,7 +252,8 @@ void MulticopterMotorModel::Configure(const Entity &_entity, } else { - ignerr << "Please specify a robotNamespace.\n"; + ignwarn << "No robotNamespace set using entity name.\n"; + this->dataPtr->robotNamespace = this->dataPtr->model.Name(_ecm); } // Get params from SDF @@ -365,6 +368,10 @@ void MulticopterMotorModel::Configure(const Entity &_entity, << "]" << std::endl; return; } + else + { + igndbg << "Listening to topic: " << topic << std::endl; + } this->dataPtr->node.Subscribe(topic, &MulticopterMotorModelPrivate::OnActuatorMsg, this->dataPtr.get()); } From 96b282b872a0a96d54589643e3d8e03d5160d0a3 Mon Sep 17 00:00:00 2001 From: Jose Luis Rivero Date: Fri, 23 Sep 2022 14:14:41 +0200 Subject: [PATCH 08/28] Add ResourceSpawner example file (#1701) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Add an example file for the ResourceSpawner plugin. I'm using this to link from https://github.com/gazebosim/docs/blob/master/garden/Model_insertion_fuel.md. To improve gazebosim/garden-tutorial-party#1991. Signed-off-by: Jose Luis Rivero Co-authored-by: Alejandro Hernández Cordero --- examples/worlds/resource_spawner.sdf | 167 +++++++++++++++++++++++++++ 1 file changed, 167 insertions(+) create mode 100644 examples/worlds/resource_spawner.sdf diff --git a/examples/worlds/resource_spawner.sdf b/examples/worlds/resource_spawner.sdf new file mode 100644 index 0000000000..ec9eb90392 --- /dev/null +++ b/examples/worlds/resource_spawner.sdf @@ -0,0 +1,167 @@ + + + + + + 0.001 + 1.0 + + + + + ogre2 + + + + + + + + + 3D View + false + docked + + ogre2 + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -6 0 6 0 0.5 0 + + + + + + floating + 5 + 5 + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + + World control + false + false + 72 + 121 + 1 + floating + + + + + + true + true + true + true + + + + + + World stats + false + false + 110 + 290 + 1 + + floating + + + + + + + true + true + true + true + + + + + docked + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 20 20 0.1 + + + + + + + 20 20 0.1 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + From 5330437e4eb31dfa1432a7b989ac2e5a83259808 Mon Sep 17 00:00:00 2001 From: Liam Han Date: Mon, 26 Sep 2022 06:07:14 -0700 Subject: [PATCH 09/28] Update triggered_publisher.sdf (#1737) found a silly typo that was pushed back in PR (https://github.com/gazebosim/gz-sim/pull/1611) --- examples/worlds/triggered_publisher.sdf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/worlds/triggered_publisher.sdf b/examples/worlds/triggered_publisher.sdf index 98b7c52c64..07c7eb7396 100644 --- a/examples/worlds/triggered_publisher.sdf +++ b/examples/worlds/triggered_publisher.sdf @@ -472,7 +472,7 @@ start falling. reqType="ignition.msgs.Pose" repType="ignition.msgs.Boolean" timeout="3000" - reqMsg="name: 'blue_vehicle', position: {x: -3, z: 0.325}"> + reqMsg="name: 'vehicle_blue', position: {x: -3, z: 0.325}"> Date: Wed, 28 Sep 2022 08:50:05 -0700 Subject: [PATCH 10/28] Adds sky cubemap URI to the sky.proto's header (#1739) * Adds sky cubemap URI to the sky.proto's header Signed-off-by: Nate Koenig * require sdf 12.6 Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- CMakeLists.txt | 2 +- src/Conversions.cc | 17 +++++++++++++++++ src/Conversions_TEST.cc | 6 ++++++ 3 files changed, 24 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 897ea591a0..38008583c9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -60,7 +60,7 @@ set(CMAKE_POLICY_DEFAULT_CMP0077 NEW) # as protobuf could be find transitively by any dependency set(protobuf_MODULE_COMPATIBLE TRUE) -ign_find_package(sdformat12 REQUIRED VERSION 12.4) +ign_find_package(sdformat12 REQUIRED VERSION 12.6) set(SDF_VER ${sdformat12_VERSION_MAJOR}) #-------------------------------------- diff --git a/src/Conversions.cc b/src/Conversions.cc index ac2bda406a..c5db3be557 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -863,6 +863,13 @@ msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in) skyMsg->set_mean_cloud_size(_in.Sky()->CloudMeanSize()); msgs::Set(skyMsg->mutable_cloud_ambient(), _in.Sky()->CloudAmbient()); + + if (!_in.Sky()->CubemapUri().empty()) + { + auto header = skyMsg->mutable_header()->add_data(); + header->set_key("cubemap_uri"); + header->add_value(_in.Sky()->CubemapUri()); + } } return out; @@ -893,6 +900,16 @@ sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in) sky.SetCloudHumidity(_in.sky().humidity()); sky.SetCloudMeanSize(_in.sky().mean_cloud_size()); sky.SetCloudAmbient(msgs::Convert(_in.sky().cloud_ambient())); + + for (int i = 0; i < _in.sky().header().data_size(); ++i) + { + auto data = _in.sky().header().data(i); + if (data.key() == "cubemap_uri" && data.value_size() > 0) + { + sky.SetCubemapUri(data.value(0)); + } + } + out.SetSky(sky); } return out; diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index f1876943b4..9033949c9d 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -710,6 +710,7 @@ TEST(Conversions, Scene) sky.SetCloudHumidity(0.11); sky.SetCloudMeanSize(0.88); sky.SetCloudAmbient(math::Color::Red); + sky.SetCubemapUri("test.dds"); scene.SetSky(sky); auto sceneSkyMsg = convert(scene); @@ -723,6 +724,10 @@ TEST(Conversions, Scene) EXPECT_DOUBLE_EQ(0.88, sceneSkyMsg.sky().mean_cloud_size()); EXPECT_EQ(math::Color::Red, msgs::Convert(sceneSkyMsg.sky().cloud_ambient())); + ASSERT_GT(sceneSkyMsg.sky().header().data_size(), 0); + auto header = sceneSkyMsg.sky().header().data(0); + EXPECT_EQ("cubemap_uri", header.key()); + EXPECT_EQ("test.dds", header.value(0)); auto newSceneSky = convert(sceneSkyMsg); ASSERT_NE(nullptr, newSceneSky.Sky()); @@ -734,6 +739,7 @@ TEST(Conversions, Scene) EXPECT_DOUBLE_EQ(0.11, newSceneSky.Sky()->CloudHumidity()); EXPECT_DOUBLE_EQ(0.88, newSceneSky.Sky()->CloudMeanSize()); EXPECT_EQ(math::Color::Red, newSceneSky.Sky()->CloudAmbient()); + EXPECT_EQ("test.dds", newSceneSky.Sky()->CubemapUri()); } ///////////////////////////////////////////////// From aff92493203bdd72de7a85fa2f1c114f3d23c834 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 28 Sep 2022 08:50:26 -0700 Subject: [PATCH 11/28] Return absolute path when finding a resource (#1741) * Adds sky cubemap URI to the sky.proto's header Signed-off-by: Nate Koenig * Return absolute path when finding a resource Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- src/ServerPrivate.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 0381c96660..6f1929b82e 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -490,9 +490,9 @@ bool ServerPrivate::ResourcePathsResolveService( std::string req = _req.data(); // Handle the case where the request is already a valid path - if (common::exists(req)) + if (common::exists(common::absPath(req))) { - _res.set_data(req); + _res.set_data(common::absPath(req)); return true; } From cdc9dc291c6d71aa9f2bdf24a45d86fae23c9007 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 3 Oct 2022 11:59:15 -0700 Subject: [PATCH 12/28] Restore Add System GUI plugin (#1685) * cherry pick aef3020cf6d982b483553fd56cf2acea4a3d3f5f Signed-off-by: Ian Chen --- include/ignition/gazebo/SystemLoader.hh | 8 +- src/SystemLoader.cc | 43 ++++-- src/SystemLoader_TEST.cc | 36 +++++ src/SystemManager.cc | 60 +++++++- src/SystemManager.hh | 8 ++ .../component_inspector/ComponentInspector.cc | 129 +++++++++++++++++- .../component_inspector/ComponentInspector.hh | 30 ++++ .../ComponentInspector.qml | 128 ++++++++++++++++- test/integration/entity_system.cc | 48 +++++++ test/worlds/diff_drive_no_plugin.sdf | 4 + 10 files changed, 477 insertions(+), 17 deletions(-) diff --git a/include/ignition/gazebo/SystemLoader.hh b/include/ignition/gazebo/SystemLoader.hh index 592027394a..2ba237bcd3 100644 --- a/include/ignition/gazebo/SystemLoader.hh +++ b/include/ignition/gazebo/SystemLoader.hh @@ -17,6 +17,7 @@ #ifndef IGNITION_GAZEBO_SYSTEMLOADER_HH_ #define IGNITION_GAZEBO_SYSTEMLOADER_HH_ +#include #include #include #include @@ -61,7 +62,8 @@ namespace ignition /// \brief Load and instantiate system plugin from name/filename. /// \param[in] _filename Shared library filename to load plugin from. - /// \param[in] _name Class name to be instantiated. + /// \param[in] _name Class name to be instantiated. If empty, the first + /// plugin in the shared library will be loaded. /// \param[in] _sdf SDF Element describing plugin instance to be loaded. /// \returns Shared pointer to system instance or nullptr. /// \note This will be deprecated in Gazebo 7 (Garden), please the use @@ -81,6 +83,10 @@ namespace ignition /// \returns A pretty string public: std::string PrettyStr() const; + /// \brief Get the plugin search paths used for loading system plugins + /// \return Paths to search for plugins + public: std::list PluginPaths() const; + /// \brief Pointer to private data. private: std::unique_ptr dataPtr; }; diff --git a/src/SystemLoader.cc b/src/SystemLoader.cc index fbf7ae020e..fd8556cb7f 100644 --- a/src/SystemLoader.cc +++ b/src/SystemLoader.cc @@ -41,8 +41,7 @@ class ignition::gazebo::SystemLoaderPrivate public: explicit SystemLoaderPrivate() = default; ////////////////////////////////////////////////// - public: bool InstantiateSystemPlugin(const sdf::Plugin &_sdfPlugin, - ignition::plugin::PluginPtr &_gzPlugin) + public: std::list PluginPaths() const { ignition::common::SystemPaths systemPaths; systemPaths.SetPluginPathEnv(pluginPathEnv); @@ -52,9 +51,24 @@ class ignition::gazebo::SystemLoaderPrivate std::string homePath; ignition::common::env(IGN_HOMEDIR, homePath); - systemPaths.AddPluginPaths(homePath + "/.ignition/gazebo/plugins"); + systemPaths.AddPluginPaths(common::joinPaths( + homePath, ".ignition", "gazebo", "plugins")); systemPaths.AddPluginPaths(IGN_GAZEBO_PLUGIN_INSTALL_DIR); + return systemPaths.PluginPaths(); + } + + ////////////////////////////////////////////////// + public: bool InstantiateSystemPlugin(const sdf::Plugin &_sdfPlugin, + ignition::plugin::PluginPtr &_gzPlugin) + { + std::list paths = this->PluginPaths(); + common::SystemPaths systemPaths; + for (const auto &p : paths) + { + systemPaths.AddPluginPaths(p); + } + auto pathToLib = systemPaths.FindSharedLibrary(_sdfPlugin.Filename()); if (pathToLib.empty()) { @@ -85,7 +99,11 @@ class ignition::gazebo::SystemLoaderPrivate return false; } - _gzPlugin = this->loader.Instantiate(_sdfPlugin.Name()); + // use the first plugin name in the library if not specified + std::string pluginToInstantiate = _sdfPlugin.Name().empty() ? + pluginName : _sdfPlugin.Name(); + + _gzPlugin = this->loader.Instantiate(pluginToInstantiate); if (!_gzPlugin) { ignerr << "Failed to load system plugin [" << _sdfPlugin.Name() << @@ -129,6 +147,12 @@ SystemLoader::SystemLoader() ////////////////////////////////////////////////// SystemLoader::~SystemLoader() = default; +////////////////////////////////////////////////// +std::list SystemLoader::PluginPaths() const +{ + return this->dataPtr->PluginPaths(); +} + ////////////////////////////////////////////////// void SystemLoader::AddSystemPluginPath(const std::string &_path) { @@ -141,11 +165,10 @@ std::optional SystemLoader::LoadPlugin( const std::string &_name, const sdf::ElementPtr &_sdf) { - if (_filename == "" || _name == "") + if (_filename == "") { ignerr << "Failed to instantiate system plugin: empty argument " - "[(filename): " << _filename << "] " << - "[(name): " << _name << "]." << std::endl; + "[(filename): " << _filename << "] " << std::endl; return {}; } @@ -175,18 +198,16 @@ std::optional SystemLoader::LoadPlugin( { ignition::plugin::PluginPtr plugin; - if (_plugin.Filename() == "" || _plugin.Name() == "") + if (_plugin.Filename() == "") { ignerr << "Failed to instantiate system plugin: empty argument " - "[(filename): " << _plugin.Filename() << "] " << - "[(name): " << _plugin.Name() << "]." << std::endl; + "[(filename): " << _plugin.Filename() << "] " << std::endl; return {}; } auto ret = this->dataPtr->InstantiateSystemPlugin(_plugin, plugin); if (ret && plugin) return plugin; - return {}; } diff --git a/src/SystemLoader_TEST.cc b/src/SystemLoader_TEST.cc index 8ca53aff47..d1c8b38bd6 100644 --- a/src/SystemLoader_TEST.cc +++ b/src/SystemLoader_TEST.cc @@ -27,6 +27,7 @@ #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) using namespace ignition; +using namespace gazebo; ///////////////////////////////////////////////// TEST(SystemLoader, Constructor) @@ -67,3 +68,38 @@ TEST(SystemLoader, EmptyNames) auto system = sm.LoadPlugin(plugin); ASSERT_FALSE(system.has_value()); } + +///////////////////////////////////////////////// +TEST(SystemLoader, PluginPaths) +{ + SystemLoader sm; + + // verify that there should exist some default paths + std::list paths = sm.PluginPaths(); + unsigned int pathCount = paths.size(); + EXPECT_LT(0u, pathCount); + + // Add test path and verify that the loader now contains this path + auto testBuildPath = common::joinPaths( + std::string(PROJECT_BINARY_PATH), "lib"); + sm.AddSystemPluginPath(testBuildPath); + paths = sm.PluginPaths(); + + // Number of paths should increase by 1 + EXPECT_EQ(pathCount + 1, paths.size()); + + // verify newly added paths exists + bool hasPath = false; + for (const auto &s : paths) + { + // the returned path string may not be exact match due to extra '/' + // appended at the end of the string. So use absPath to generate + // a path string that matches the format returned by joinPaths + if (common::absPath(s) == testBuildPath) + { + hasPath = true; + break; + } + } + EXPECT_TRUE(hasPath); +} diff --git a/src/SystemManager.cc b/src/SystemManager.cc index 8440364fc8..ff3bc2f65b 100644 --- a/src/SystemManager.cc +++ b/src/SystemManager.cc @@ -15,6 +15,11 @@ * */ +#include +#include + +#include + #include "ignition/gazebo/components/SystemPluginInfo.hh" #include "ignition/gazebo/Conversions.hh" #include "SystemManager.hh" @@ -34,11 +39,15 @@ SystemManager::SystemManager(const SystemLoaderPtr &_systemLoader, transport::NodeOptions opts; opts.SetNameSpace(_namespace); this->node = std::make_unique(opts); - std::string entitySystemService{"entity/system/add"}; - this->node->Advertise(entitySystemService, + std::string entitySystemAddService{"entity/system/add"}; + this->node->Advertise(entitySystemAddService, &SystemManager::EntitySystemAddService, this); ignmsg << "Serving entity system service on [" - << "/" << entitySystemService << "]" << std::endl; + << "/" << entitySystemAddService << "]" << std::endl; + + std::string entitySystemInfoService{"system/info"}; + this->node->Advertise(entitySystemInfoService, + &SystemManager::EntitySystemInfoService, this); } ////////////////////////////////////////////////// @@ -215,6 +224,51 @@ bool SystemManager::EntitySystemAddService(const msgs::EntityPlugin_V &_req, return true; } +////////////////////////////////////////////////// +bool SystemManager::EntitySystemInfoService(const msgs::Empty &, + msgs::EntityPlugin_V &_res) +{ + // loop through all files in paths and populate the list of + // plugin libraries. + std::list paths = this->systemLoader->PluginPaths(); + std::set filenames; + for (const auto &p : paths) + { + if (common::exists(p)) + { + for (common::DirIter file(p); + file != common::DirIter(); ++file) + { + std::string current(*file); + std::string filename = common::basename(current); + if (common::isFile(current) && + (common::EndsWith(filename, ".so") || + common::EndsWith(filename, ".dll") || + common::EndsWith(filename, ".dylib"))) + { + // remove extension and lib prefix + size_t extensionIndex = filename.rfind("."); + std::string nameWithoutExtension = + filename.substr(0, extensionIndex); + if (common::StartsWith(nameWithoutExtension, "lib")) + { + nameWithoutExtension = nameWithoutExtension.substr(3); + } + filenames.insert(nameWithoutExtension); + } + } + } + } + + for (const auto &fn : filenames) + { + auto plugin = _res.add_plugins(); + plugin->set_filename(fn); + } + + return true; +} + ////////////////////////////////////////////////// void SystemManager::ProcessPendingEntitySystems() { diff --git a/src/SystemManager.hh b/src/SystemManager.hh index c23ee38cee..a7bf1484ee 100644 --- a/src/SystemManager.hh +++ b/src/SystemManager.hh @@ -142,6 +142,14 @@ namespace ignition private: bool EntitySystemAddService(const msgs::EntityPlugin_V &_req, msgs::Boolean &_res); + /// \brief Callback for entity info system service. + /// \param[in] _req Empty request message + /// \param[out] _res Response containing a list of plugin names + /// and filenames + /// \return True if request received. + private: bool EntitySystemInfoService(const msgs::Empty &_req, + msgs::EntityPlugin_V &_res); + /// \brief All the systems. private: std::vector systems; diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index d235fce439..0c9fe29d50 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -18,6 +18,7 @@ #include #include #include +#include #include #include #include @@ -68,6 +69,7 @@ #include "ignition/gazebo/components/Volume.hh" #include "ignition/gazebo/components/WindMode.hh" #include "ignition/gazebo/components/World.hh" +#include "ignition/gazebo/config.hh" #include "ignition/gazebo/EntityComponentManager.hh" #include "ignition/gazebo/gui/GuiEvents.hh" @@ -118,9 +120,35 @@ namespace ignition::gazebo /// \brief Handles all system info components. public: std::unique_ptr systemInfo; + + /// \brief A list of system plugin human readable names. + public: QStringList systemNameList; + + /// \brief Maps plugin display names to their filenames. + public: std::unordered_map systemMap; }; } +// Helper to remove a prefix from a string if present +void removePrefix(const std::string &_prefix, std::string &_s) +{ + auto id = _s.find(_prefix); + if (id != std::string::npos) + { + _s = _s.substr(_prefix.length()); + } +} + +// Helper to remove a suffix from a string if present +void removeSuffix(const std::string &_suffix, std::string &_s) +{ + auto id = _s.find(_suffix); + if (id != std::string::npos && id + _suffix.length() == _s.length()) + { + _s.erase(id, _suffix.length()); + } +} + using namespace ignition; using namespace gazebo; @@ -895,7 +923,6 @@ void ComponentInspector::Update(const UpdateInfo &, auto comp = _ecm.Component(this->dataPtr->entity); if (comp) { - this->SetType("material"); setData(item, comp->Data()); } } @@ -1216,6 +1243,106 @@ transport::Node &ComponentInspector::TransportNode() return this->dataPtr->node; } +///////////////////////////////////////////////// +void ComponentInspector::QuerySystems() +{ + msgs::Empty req; + msgs::EntityPlugin_V res; + bool result; + unsigned int timeout = 5000; + std::string service{"/world/" + this->dataPtr->worldName + + "/system/info"}; + if (!this->dataPtr->node.Request(service, req, timeout, res, result)) + { + ignerr << "Unable to query available systems." << std::endl; + return; + } + + this->dataPtr->systemNameList.clear(); + this->dataPtr->systemMap.clear(); + for (const auto &plugin : res.plugins()) + { + if (plugin.filename().empty()) + { + ignerr << "Received empty plugin name. This shouldn't happen." + << std::endl; + continue; + } + + // Remove common prefixes and suffixes + auto humanReadable = plugin.filename(); + removePrefix("ignition-gazebo-", humanReadable); + removePrefix("ignition-gazebo" + + std::string(IGNITION_GAZEBO_MAJOR_VERSION_STR) + "-", humanReadable); + removeSuffix("-system", humanReadable); + removeSuffix("system", humanReadable); + removeSuffix("-plugin", humanReadable); + removeSuffix("plugin", humanReadable); + + // Replace - with space, capitalize + std::replace(humanReadable.begin(), humanReadable.end(), '-', ' '); + humanReadable[0] = std::toupper(humanReadable[0]); + + this->dataPtr->systemMap[humanReadable] = plugin.filename(); + this->dataPtr->systemNameList.push_back( + QString::fromStdString(humanReadable)); + } + this->dataPtr->systemNameList.sort(); + this->dataPtr->systemNameList.removeDuplicates(); + this->SystemNameListChanged(); +} + +///////////////////////////////////////////////// +QStringList ComponentInspector::SystemNameList() const +{ + return this->dataPtr->systemNameList; +} + +///////////////////////////////////////////////// +void ComponentInspector::SetSystemNameList(const QStringList &_list) +{ + this->dataPtr->systemNameList = _list; +} + +///////////////////////////////////////////////// +void ComponentInspector::OnAddSystem(const QString &_name, + const QString &_filename, const QString &_innerxml) +{ + auto filenameStr = _filename.toStdString(); + auto it = this->dataPtr->systemMap.find(filenameStr); + if (it == this->dataPtr->systemMap.end()) + { + ignerr << "Internal error: failed to find [" << filenameStr + << "] in system map." << std::endl; + return; + } + + msgs::EntityPlugin_V req; + auto ent = req.mutable_entity(); + ent->set_id(this->dataPtr->entity); + auto plugin = req.add_plugins(); + std::string name = _name.toStdString(); + std::string filename = this->dataPtr->systemMap[filenameStr]; + std::string innerxml = _innerxml.toStdString(); + plugin->set_name(name); + plugin->set_filename(filename); + plugin->set_innerxml(innerxml); + + msgs::Boolean res; + bool result; + unsigned int timeout = 5000; + std::string service{"/world/" + this->dataPtr->worldName + + "/entity/system/add"}; + if (!this->dataPtr->node.Request(service, req, timeout, res, result)) + { + ignerr << "Error adding new system to entity: " + << this->dataPtr->entity << "\n" + << "Name: " << name << "\n" + << "Filename: " << filename << "\n" + << "Inner XML: " << innerxml << std::endl; + } +} + // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::ComponentInspector, ignition::gui::Plugin) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index a4800795e2..9e8735a928 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -212,6 +212,14 @@ namespace gazebo NOTIFY NestedModelChanged ) + /// \brief System display name list + Q_PROPERTY( + QStringList systemNameList + READ SystemNameList + WRITE SetSystemNameList + NOTIFY SystemNameListChanged + ) + /// \brief Constructor public: ComponentInspector(); @@ -372,6 +380,28 @@ namespace gazebo /// \return Transport node public: transport::Node &TransportNode(); + /// \brief Query system plugin info. + public: Q_INVOKABLE void QuerySystems(); + + /// \brief Get the system plugin display name list + /// \return A list of names that are potentially system plugins + public: Q_INVOKABLE QStringList SystemNameList() const; + + /// \brief Set the system plugin display name list + /// \param[in] _systempFilenameList A list of system plugin display names + public: Q_INVOKABLE void SetSystemNameList( + const QStringList &_systemNameList); + + /// \brief Notify that system plugin display name list has changed + signals: void SystemNameListChanged(); + + /// \brief Callback when a new system is to be added to an entity + /// \param[in] _name Name of system + /// \param[in] _filename Filename of system + /// \param[in] _innerxml Inner XML content of the system + public: Q_INVOKABLE void OnAddSystem(const QString &_name, + const QString &_filename, const QString &_innerxml); + /// \internal /// \brief Pointer to private data. private: std::unique_ptr dataPtr; diff --git a/src/gui/plugins/component_inspector/ComponentInspector.qml b/src/gui/plugins/component_inspector/ComponentInspector.qml index 21f43e9506..14bbee7153 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.qml +++ b/src/gui/plugins/component_inspector/ComponentInspector.qml @@ -15,9 +15,9 @@ * */ import QtQuick 2.9 -import QtQuick.Controls 1.4 import QtQuick.Controls 2.2 import QtQuick.Controls.Material 2.1 +import QtQuick.Dialogs 1.1 import QtQuick.Layouts 1.3 import QtQuick.Controls.Styles 1.4 import IgnGazebo 1.0 as IgnGazebo @@ -216,6 +216,27 @@ Rectangle { } } + ToolButton { + id: addSystemButton + checkable: false + text: "\u002B" + contentItem: Text { + text: addSystemButton.text + color: "#b5b5b5" + horizontalAlignment: Text.AlignHCenter + verticalAlignment: Text.AlignVCenter + } + visible: (entityType == "model" || entityType == "visual" || + entityType == "sensor" || entityType == "world") + ToolTip.text: "Add a system to this entity" + ToolTip.visible: hovered + ToolTip.delay: Qt.styleHints.mousePressAndHoldInterval + onClicked: { + addSystemDialog.open() + } + } + + Label { id: entityLabel text: 'Entity ' + ComponentInspector.entity @@ -227,6 +248,111 @@ Rectangle { } } + Dialog { + id: addSystemDialog + modal: false + focus: true + title: "Add System" + closePolicy: Popup.CloseOnEscape + width: parent.width + + ColumnLayout { + width: parent.width + GridLayout { + columns: 2 + columnSpacing: 30 + Text { + text: "Name" + Layout.row: 0 + Layout.column: 0 + } + + TextField { + id: nameField + selectByMouse: true + Layout.row: 0 + Layout.column: 1 + Layout.fillWidth: true + Layout.minimumWidth: 250 + onTextEdited: { + addSystemDialog.updateButtonState(); + } + placeholderText: "Leave empty to load first plugin" + } + + Text { + text: "Filename" + Layout.row: 1 + Layout.column: 0 + } + + ComboBox { + id: filenameCB + Layout.row: 1 + Layout.column: 1 + Layout.fillWidth: true + Layout.minimumWidth: 250 + model: ComponentInspector.systemNameList + currentIndex: 0 + onCurrentIndexChanged: { + if (currentIndex < 0) + return; + addSystemDialog.updateButtonState(); + } + ToolTip.visible: hovered + ToolTip.delay: tooltipDelay + ToolTip.text: currentText + } + } + + Text { + id: innerxmlLabel + text: "Inner XML" + } + + Flickable { + id: innerxmlFlickable + Layout.minimumHeight: 300 + Layout.fillWidth: true + Layout.fillHeight: true + + flickableDirection: Flickable.VerticalFlick + TextArea.flickable: TextArea { + id: innerxmlField + wrapMode: Text.WordWrap + selectByMouse: true + textFormat: TextEdit.PlainText + font.pointSize: 10 + } + ScrollBar.vertical: ScrollBar { + policy: ScrollBar.AlwaysOn + } + } + } + + footer: DialogButtonBox { + id: buttons + standardButtons: Dialog.Ok | Dialog.Cancel + } + + onOpened: { + ComponentInspector.QuerySystems(); + addSystemDialog.updateButtonState(); + } + + onAccepted: { + ComponentInspector.OnAddSystem(nameField.text.trim(), + filenameCB.currentText.trim(), innerxmlField.text.trim()) + } + + function updateButtonState() { + buttons.standardButton(Dialog.Ok).enabled = + (filenameCB.currentText.trim() != '') + } + } + + + ListView { anchors.top: header.bottom anchors.bottom: parent.bottom diff --git a/test/integration/entity_system.cc b/test/integration/entity_system.cc index d4ea7ce57c..338cf4e685 100644 --- a/test/integration/entity_system.cc +++ b/test/integration/entity_system.cc @@ -158,6 +158,54 @@ TEST_P(EntitySystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) "/model/vehicle/cmd_vel"); } +///////////////////////////////////////////////// +TEST_P(EntitySystemTest, SystemInfo) +{ + // Start server + ServerConfig serverConfig; + const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/empty.sdf"; + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + // get info on systems available + msgs::Empty req; + msgs::EntityPlugin_V res; + bool result; + unsigned int timeout = 5000; + std::string service{"/world/empty/system/info"}; + transport::Node node; + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + + // verify plugins are not empty + EXPECT_FALSE(res.plugins().empty()); + + // check for a few known plugins that we know should exist in gazebo + std::set knownPlugins; + knownPlugins.insert("user-commands-system"); + knownPlugins.insert("physics-system"); + knownPlugins.insert("scene-broadcaster-system"); + knownPlugins.insert("sensors-system"); + + for (const auto &plugin : res.plugins()) + { + for (const auto &kp : knownPlugins) + { + if (plugin.filename().find(kp) != std::string::npos) + { + knownPlugins.erase(kp); + break; + } + } + } + // verify all known plugins are found and removed from the set + EXPECT_TRUE(knownPlugins.empty()); +} + // Run multiple times INSTANTIATE_TEST_SUITE_P(ServerRepeat, EntitySystemTest, ::testing::Range(1, 2)); diff --git a/test/worlds/diff_drive_no_plugin.sdf b/test/worlds/diff_drive_no_plugin.sdf index 1792199086..1a70e4eff1 100644 --- a/test/worlds/diff_drive_no_plugin.sdf +++ b/test/worlds/diff_drive_no_plugin.sdf @@ -10,6 +10,10 @@ filename="ignition-gazebo-physics-system" name="ignition::gazebo::systems::Physics"> + + true From 4dd1858d3a7f35c06f51535b4539690356a9da5f Mon Sep 17 00:00:00 2001 From: "Marco A. Gutierrez" Date: Fri, 7 Oct 2022 01:17:36 +0800 Subject: [PATCH 13/28] Adding thrust coefficient calculation (#1652) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * adding thrust coefficient calculation Signed-off-by: Marco A. Gutierrez * Update src/systems/thruster/Thruster.cc Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Marco A. Gutierrez * Update src/systems/thruster/Thruster.cc Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Marco A. Gutierrez * Update src/systems/thruster/Thruster.cc Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Marco A. Gutierrez * Update src/systems/thruster/Thruster.cc Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Marco A. Gutierrez * Update src/systems/thruster/Thruster.cc Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Marco A. Gutierrez * Update src/systems/thruster/Thruster.cc Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Marco A. Gutierrez * Update src/systems/thruster/Thruster.cc Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Marco A. Gutierrez * Update src/systems/thruster/Thruster.cc Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Marco A. Gutierrez * Update src/systems/thruster/Thruster.hh Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Marco A. Gutierrez * thrust coefficient test and behavior updates Signed-off-by: Marco A. Gutierrez * making float comparision more robust Signed-off-by: Marco A. Gutierrez * fix float comparision and lint Signed-off-by: Marco A. Gutierrez Signed-off-by: Marco A. Gutierrez Co-authored-by: Alejandro Hernández Cordero --- src/systems/thruster/Thruster.cc | 82 +++++++++++++++++++++ src/systems/thruster/Thruster.hh | 16 ++++ test/integration/thruster.cc | 64 ++++++++++++++-- test/worlds/thrust_coefficient.sdf | 114 +++++++++++++++++++++++++++++ 4 files changed, 270 insertions(+), 6 deletions(-) create mode 100644 test/worlds/thrust_coefficient.sdf diff --git a/src/systems/thruster/Thruster.cc b/src/systems/thruster/Thruster.cc index b775cf26e4..bae8bb04d5 100644 --- a/src/systems/thruster/Thruster.cc +++ b/src/systems/thruster/Thruster.cc @@ -16,6 +16,7 @@ */ #include #include +#include #include #include @@ -98,18 +99,39 @@ class ignition::gazebo::systems::ThrusterPrivateData /// thrust public: double thrustCoefficient = 1; + /// \brief True if the thrust coefficient was set by configuration. + public: bool thrustCoefficientSet = false; + + /// \brief Relative speed reduction between the water at the propeller vs + /// behind the vessel. + public: double wakeFraction = 0.2; + + /// \brief Constant given by the open water propeller diagram. Used in the + /// calculation of the thrust coefficient. + public: double alpha1 = 1; + + /// \brief Constant given by the open water propeller diagram. Used in the + /// calculation of the thrust coefficient. + public: double alpha2 = 0; + /// \brief Density of fluid in kgm^-3, default: 1000kgm^-3 public: double fluidDensity = 1000; /// \brief Diameter of propeller in m, default: 0.02 public: double propellerDiameter = 0.02; + /// \brief Linear velocity of the vehicle. + public: double linearVelocity = 0.0; + /// \brief Topic name used to control thrust. public: std::string topic = ""; /// \brief Callback for handling thrust update public: void OnCmdThrust(const msgs::Double &_msg); + /// \brief Recalculates and updates the thrust coefficient. + public: void UpdateThrustCoefficient(); + /// \brief Function which computes angular velocity from thrust /// \param[in] _thrust Thrust in N /// \return Angular velocity in rad/s @@ -160,6 +182,7 @@ void Thruster::Configure( if (_sdf->HasElement("thrust_coefficient")) { this->dataPtr->thrustCoefficient = _sdf->Get("thrust_coefficient"); + this->dataPtr->thrustCoefficientSet = true; } // Get propeller diameter @@ -174,6 +197,40 @@ void Thruster::Configure( this->dataPtr->fluidDensity = _sdf->Get("fluid_density"); } + // Get wake fraction number, default 0.2 otherwise + if (_sdf->HasElement("wake_fraction")) + { + this->dataPtr->wakeFraction = _sdf->Get("wake_fraction"); + } + + // Get alpha_1, default to 1 othwewise + if (_sdf->HasElement("alpha_1")) + { + this->dataPtr->alpha1 = _sdf->Get("alpha_1"); + if (this->dataPtr->thrustCoefficientSet) + { + ignwarn << " The [alpha_2] value will be ignored as a " + << "[thrust_coefficient] was also defined through the SDF file." + << " If you want the system to use the alpha values to calculate" + << " and update the thrust coefficient please remove the " + << "[thrust_coefficient] value from the SDF file." << std::endl; + } + } + + // Get alpha_2, default to 1 othwewise + if (_sdf->HasElement("alpha_2")) + { + this->dataPtr->alpha2 = _sdf->Get("alpha_2"); + if (this->dataPtr->thrustCoefficientSet) + { + ignwarn << " The [alpha_2] value will be ignored as a " + << "[thrust_coefficient] was also defined through the SDF file." + << " If you want the system to use the alpha values to calculate" + << " and update the thrust coefficient please remove the " + << "[thrust_coefficient] value from the SDF file." << std::endl; + } + } + // Get a custom topic. if (_sdf->HasElement("topic")) { @@ -235,6 +292,8 @@ void Thruster::Configure( enableComponent(_ecm, this->dataPtr->linkEntity); enableComponent(_ecm, this->dataPtr->linkEntity); + enableComponent(_ecm, + this->dataPtr->linkEntity); double minThrustCmd = this->dataPtr->cmdMin; double maxThrustCmd = this->dataPtr->cmdMax; @@ -321,6 +380,14 @@ void ThrusterPrivateData::OnCmdThrust(const msgs::Double &_msg) ///////////////////////////////////////////////// double ThrusterPrivateData::ThrustToAngularVec(double _thrust) { + // Only update if the thrust coefficient was not set by configuration + // and angular velocity is not zero. Some velocity is needed to calculate + // the thrust coefficient otherwise it will never start moving. + if (!this->thrustCoefficientSet && + std::abs(this->propellerAngVel) > std::numeric_limits::epsilon()) + { + this->UpdateThrustCoefficient(); + } // Thrust is proportional to the Rotation Rate squared // See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 246 auto propAngularVelocity = sqrt(abs( @@ -333,6 +400,14 @@ double ThrusterPrivateData::ThrustToAngularVec(double _thrust) return propAngularVelocity; } +///////////////////////////////////////////////// +void ThrusterPrivateData::UpdateThrustCoefficient() +{ + this->thrustCoefficient = this->alpha1 + this->alpha2 * + (((1 - this->wakeFraction) * this->linearVelocity) + / (this->propellerAngVel * this->propellerDiameter)); +} + ///////////////////////////////////////////////// bool ThrusterPrivateData::HasSufficientBattery( const EntityComponentManager &_ecm) const @@ -384,6 +459,8 @@ void Thruster::PreUpdate( { std::lock_guard lock(this->dataPtr->mtx); desiredThrust = this->dataPtr->thrust; + this->dataPtr->propellerAngVel = + this->dataPtr->ThrustToAngularVec(this->dataPtr->thrust); desiredPropellerAngVel = this->dataPtr->propellerAngVel; } @@ -422,6 +499,11 @@ void Thruster::PreUpdate( _ecm, unitVector * desiredThrust, unitVector * torque); + + // Update the LinearVelocity of the vehicle + this->dataPtr->linearVelocity = + _ecm.Component( + this->dataPtr->linkEntity)->Data().Length(); } ///////////////////////////////////////////////// diff --git a/src/systems/thruster/Thruster.hh b/src/systems/thruster/Thruster.hh index 415fa8b660..e40627d465 100644 --- a/src/systems/thruster/Thruster.hh +++ b/src/systems/thruster/Thruster.hh @@ -70,6 +70,22 @@ namespace systems /// defaults to 1000N] /// - - Minimum thrust command. [Optional, /// defaults to -1000N] + /// - - Relative speed reduction between the water + /// at the propeller (Va) vs behind the vessel. + /// [Optional, defults to 0.2] + /// See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 95: + /// + /// Va = (1 - wake_fraction) * advance_speed + /// + /// - - Constant given by the open water propeller diagram. Used + /// in the calculation of the thrust coefficient (Kt). + /// [Optional, defults to 1] + /// - - Constant given by the open water propeller diagram. Used + /// in the calculation of the thrust coefficient (Kt). + /// [Optional, defults to 0] + /// See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 95: + /// + /// Kt = alpha_1 * alpha_2 * (Va/(propeller_revolution * propeller_diameter)) /// /// ## Example /// An example configuration is installed with Gazebo. The example diff --git a/test/integration/thruster.cc b/test/integration/thruster.cc index 1e147bfe69..92c60a7d89 100644 --- a/test/integration/thruster.cc +++ b/test/integration/thruster.cc @@ -32,6 +32,9 @@ #include "ignition/gazebo/Util.hh" #include "ignition/gazebo/World.hh" +#include "ignition/gazebo/components/JointAxis.hh" +#include "ignition/gazebo/components/Pose.hh" + #include "ignition/gazebo/test_config.hh" #include "../helpers/EnvTestFixture.hh" @@ -50,13 +53,17 @@ class ThrusterTest : public InternalFixture<::testing::Test> /// \param[in] _baseTol Base tolerance for most quantities public: void TestWorld(const std::string &_world, const std::string &_namespace, const std::string &_topic, - double _coefficient, double _density, double _diameter, double _baseTol); + double _thrustCoefficient, double _density, double _diameter, + double _baseTol, double _wakeFraction = 0.2, double _alpha_1 = 1, + double _alpha_2 = 0, bool _calculateCoefficient = false); }; ////////////////////////////////////////////////// void ThrusterTest::TestWorld(const std::string &_world, const std::string &_namespace, const std::string &_topic, - double _coefficient, double _density, double _diameter, double _baseTol) + double _thrustCoefficient, double _density, double _diameter, + double _baseTol, double _wakeFraction, double _alpha1, double _alpha2, + bool _calculateCoefficient) { // Start server ServerConfig serverConfig; @@ -68,6 +75,9 @@ void ThrusterTest::TestWorld(const std::string &_world, Link propeller; std::vector modelPoses; std::vector propellerAngVels; + std::vector propellerLinVels; + ignition::math::Pose3d jointPose, linkWorldPose; + ignition::math::Vector3d jointAxis; double dt{0.0}; fixture. OnConfigure( @@ -82,11 +92,19 @@ void ThrusterTest::TestWorld(const std::string &_world, EXPECT_NE(modelEntity, kNullEntity); model = Model(modelEntity); + auto jointEntity = model.JointByName(_ecm, "propeller_joint"); + jointAxis = + _ecm.Component( + jointEntity)->Data().Xyz(); + jointPose = _ecm.Component( + jointEntity)->Data(); + auto propellerEntity = model.LinkByName(_ecm, "propeller"); EXPECT_NE(propellerEntity, kNullEntity); propeller = Link(propellerEntity); propeller.EnableVelocityChecks(_ecm); + }). OnPostUpdate([&](const gazebo::UpdateInfo &_info, const gazebo::EntityComponentManager &_ecm) @@ -99,6 +117,10 @@ void ThrusterTest::TestWorld(const std::string &_world, auto propellerAngVel = propeller.WorldAngularVelocity(_ecm); ASSERT_TRUE(propellerAngVel); propellerAngVels.push_back(propellerAngVel.value()); + + auto proellerLinVel = propeller.WorldLinearVelocity(_ecm); + ASSERT_TRUE(proellerLinVel); + propellerLinVels.push_back(proellerLinVel.value()); }). Finalize(); @@ -106,6 +128,7 @@ void ThrusterTest::TestWorld(const std::string &_world, fixture.Server()->Run(true, 100, false); EXPECT_EQ(100u, modelPoses.size()); EXPECT_EQ(100u, propellerAngVels.size()); + EXPECT_EQ(100u, propellerLinVels.size()); EXPECT_NE(model.Entity(), kNullEntity); EXPECT_NE(propeller.Entity(), kNullEntity); @@ -120,6 +143,7 @@ void ThrusterTest::TestWorld(const std::string &_world, EXPECT_EQ(math::Vector3d::Zero, vel); } propellerAngVels.clear(); + propellerLinVels.clear(); // Publish command and check that vehicle moved transport::Node node; @@ -146,8 +170,10 @@ void ThrusterTest::TestWorld(const std::string &_world, EXPECT_DOUBLE_EQ(0.0, modelPoses.back().Pos().X()); EXPECT_EQ(100u, modelPoses.size()); EXPECT_EQ(100u, propellerAngVels.size()); + EXPECT_EQ(100u, propellerLinVels.size()); modelPoses.clear(); propellerAngVels.clear(); + propellerLinVels.clear(); // input force cmd this should be capped to 300 forceCmd = 1000.0; @@ -168,6 +194,7 @@ void ThrusterTest::TestWorld(const std::string &_world, EXPECT_EQ(100u * sleep, modelPoses.size()); EXPECT_EQ(100u * sleep, propellerAngVels.size()); + EXPECT_EQ(100u * sleep, propellerLinVels.size()); } // max allowed force @@ -205,13 +232,26 @@ void ThrusterTest::TestWorld(const std::string &_world, EXPECT_NEAR(0.0, pose.Rot().Roll(), _baseTol); } - // See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 246 - // omega = sqrt(thrust / - // (fluid_density * thrust_coefficient * propeller_diameter ^ 4)) - auto omega = sqrt(force / (_density * _coefficient * pow(_diameter, 4))); + auto jointWorldPose = linkWorldPose * jointPose; + auto unitVector = jointWorldPose.Rot().RotateVector(jointAxis).Normalize(); + double omegaTol{1e-1}; for (unsigned int i = 0; i < propellerAngVels.size(); ++i) { + auto angularVelocity = propellerAngVels[i].Dot(unitVector); + // See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 246: + // thrust_coefficient = alpha_1 + alpha_2 * (((1-wake_fraction) * + // linear_velocity) / (angular_velocity * propeller_diameter)) + // omega = sqrt(thrust / + // (fluid_density * thrust_coefficient * propeller_diameter ^ 4)) + if (_calculateCoefficient && angularVelocity != 0) + { + _thrustCoefficient = _alpha1 + _alpha2 * (((1 - _wakeFraction) * + propellerLinVels[i].Length()) / (angularVelocity * _diameter)); + } + auto omega = sqrt(abs(force / (_density * _thrustCoefficient * + pow(_diameter, 4)))); + auto angVel = propellerAngVels[i]; // It takes a few iterations to reach the speed if (i > 25) @@ -270,3 +310,15 @@ TEST_F(ThrusterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(BatteryIntegration)) this->TestWorld(world, ns, topic, 0.005, 950, 0.25, 1e-2); } +///////////////////////////////////////////////// +TEST_F(ThrusterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(ThrustCoefficient)) +{ + const std::string ns = "custom"; + const std::string topic = "/model/" + ns + + "/joint/propeller_joint/cmd_thrust"; + auto world = common::joinPaths(std::string(PROJECT_SOURCE_PATH), + "test", "worlds", "thrust_coefficient.sdf"); + + // Tolerance is high because the joint command disturbs the vehicle body + this->TestWorld(world, ns, topic, 1, 950, 0.25, 1e-2, 0.2, 0.9, 0.01, true); +} diff --git a/test/worlds/thrust_coefficient.sdf b/test/worlds/thrust_coefficient.sdf new file mode 100644 index 0000000000..f45c5cb1c7 --- /dev/null +++ b/test/worlds/thrust_coefficient.sdf @@ -0,0 +1,114 @@ + + + + + + + 0 + + + + 0 0 0 + + + + + + + + true + 0 0 10 0 0 0 + 1 1 1 1 + 0.5 0.5 0.5 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + + + 0 0 0 0 1.57 0 + + 100 + + 33.89 + 0 + 0 + 33.89 + 0 + 1.125 + + + + + + 2 + 0.15 + + + + + + + -1.05 0 0 0 0 0 + + 0.1 + + 0.000354167 + 0 + 0 + 0.000021667 + 0 + 0.000334167 + + + + + + 0.01 0.25 0.05 + + + + + + + body + propeller + + 1 0 0 + + -1e+12 + 1e+12 + 1e6 + 1e6 + + + + + + custom + propeller_joint + 950 + 0.25 + true + 300 + 0 + 0.2 + 0.9 + 0.01 + + + + + From e502e9fd36544d4dd936ccde2308dc5938ec1950 Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Tue, 11 Oct 2022 17:04:21 +0800 Subject: [PATCH 14/28] Enable/Disable individual hydrodynamic components. (#1692) This commit enables and disables individual components of the hydrodynamics. This is often useful for debugging odd behaviours of a hydrodynamic model. --- src/systems/hydrodynamics/Hydrodynamics.cc | 22 +- src/systems/hydrodynamics/Hydrodynamics.hh | 3 + test/integration/CMakeLists.txt | 1 + test/integration/hydrodynamics_flags.cc | 151 +++++++++ test/worlds/hydrodynamics_flags.sdf | 352 +++++++++++++++++++++ 5 files changed, 528 insertions(+), 1 deletion(-) create mode 100644 test/integration/hydrodynamics_flags.cc create mode 100644 test/worlds/hydrodynamics_flags.sdf diff --git a/src/systems/hydrodynamics/Hydrodynamics.cc b/src/systems/hydrodynamics/Hydrodynamics.cc index ac7f8fdf3d..1a59c06c11 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.cc +++ b/src/systems/hydrodynamics/Hydrodynamics.cc @@ -103,6 +103,14 @@ class ignition::gazebo::systems::HydrodynamicsPrivateData /// \brief The ignition transport node public: transport::Node node; + /// \brief Plugin Parameter: Disable coriolis as part of equation. This is + /// occasionally useful for testing. + public: bool disableCoriolis = false; + + /// \brief Plugin Parameter: Disable added mass as part of equation. This is + /// occasionally useful for testing. + public: bool disableAddedMass = false; + /// \brief Ocean current experienced by this body public: math::Vector3d currentVector {0, 0, 0}; @@ -232,6 +240,9 @@ void Hydrodynamics::Configure( this->dataPtr->paramNr = SdfParamDouble(_sdf, "nR" , 20); this->dataPtr->paramNrr = SdfParamDouble(_sdf, "nRR" , 0); + _sdf->Get("disable_coriolis", this->dataPtr->disableCoriolis, false); + _sdf->Get("disable_added_mass", this->dataPtr->disableAddedMass, false); + // Create model object, to access convenient functions auto model = ignition::gazebo::Model(_entity); @@ -389,7 +400,16 @@ void Hydrodynamics::PreUpdate( const Eigen::VectorXd kDvec = Dmat * state; - const Eigen::VectorXd kTotalWrench = kAmassVec + kDvec + kCmatVec; + Eigen::VectorXd kTotalWrench = kDvec; + + if (!this->dataPtr->disableAddedMass) + { + kTotalWrench += kAmassVec; + } + if (!this->dataPtr->disableCoriolis) + { + kTotalWrench += kCmatVec; + } ignition::math::Vector3d totalForce(-kTotalWrench(0), -kTotalWrench(1), -kTotalWrench(2)); diff --git a/src/systems/hydrodynamics/Hydrodynamics.hh b/src/systems/hydrodynamics/Hydrodynamics.hh index f9f87cfe4c..4719703ac7 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.hh +++ b/src/systems/hydrodynamics/Hydrodynamics.hh @@ -77,6 +77,9 @@ namespace systems /// listens on `/model/{namespace name}/ocean_current`.[String, Optional] /// * - A generic current. /// [vector3d m/s, optional, default = [0,0,0]m/s] + /// * - Disable Coriolis force [Boolean, Default: false] + /// * - Disable Added Mass [Boolean, Default: false]. + /// To be deprecated in Garden. /// /// # Example /// An example configuration is provided in the examples folder. The example diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index ad026ed661..d5776ad20f 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -25,6 +25,7 @@ set(tests fuel_cached_server.cc halt_motion.cc hydrodynamics.cc + hydrodynamics_flags.cc imu_system.cc joint_controller_system.cc joint_position_controller_system.cc diff --git a/test/integration/hydrodynamics_flags.cc b/test/integration/hydrodynamics_flags.cc new file mode 100644 index 0000000000..a997be5826 --- /dev/null +++ b/test/integration/hydrodynamics_flags.cc @@ -0,0 +1,151 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include + +#include + +#include +#include +#include +#include + +#include "ignition/gazebo/Link.hh" +#include "ignition/gazebo/Model.hh" +#include "ignition/gazebo/Server.hh" +#include "ignition/gazebo/SystemLoader.hh" +#include "ignition/gazebo/TestFixture.hh" +#include "ignition/gazebo/Util.hh" +#include "ignition/gazebo/World.hh" + +#include "ignition/gazebo/test_config.hh" +#include "../helpers/EnvTestFixture.hh" + +using namespace ignition; +using namespace gazebo; + +class HydrodynamicsFlagsTest : public InternalFixture<::testing::Test> +{ + /// \brief Test a world file. + /// \param[in] _world Path to world file. + /// \param[in] _modelName Name of the model. + /// \param[in] _numsteps Number of steps to run the server. + /// \param[out] _linearVel Linear velocityies after each step. + /// \param[out] _angularVel Linear velocityies after each step. + public: void TestWorld(const std::string &_world, + const std::string &_modelName, const unsigned int &_numsteps, + std::vector &_linearVel, + std::vector &_angularVel); +}; + +////////////////////////////////////////////////// +void HydrodynamicsFlagsTest::TestWorld(const std::string &_world, + const std::string &_modelName, const unsigned int &_numsteps, + std::vector &_linearVel, + std::vector &_angularVel) +{ + // Maximum verbosity for debugging + ignition::common::Console::SetVerbosity(4); + + // Start server + ServerConfig serverConfig; + serverConfig.SetSdfFile(_world); + + TestFixture fixture(serverConfig); + + Model model; + Link body; + std::vector bodyVels; + fixture. + OnConfigure( + [&](const Entity &_worldEntity, + const std::shared_ptr &/*_sdf*/, + EntityComponentManager &_ecm, + EventManager &/*eventMgr*/) + { + World world(_worldEntity); + + auto modelEntity = world.ModelByName(_ecm, _modelName); + EXPECT_NE(modelEntity, kNullEntity); + model = Model(modelEntity); + + auto bodyEntity = model.LinkByName(_ecm, "base_link"); + EXPECT_NE(bodyEntity, kNullEntity); + + body = Link(bodyEntity); + body.EnableVelocityChecks(_ecm); + + // Forces in Y and Z are needed to make the coriolis + // force appear. + math::Vector3d force(0.0, 1000.0, 1000.0); + math::Vector3d torque(0.0, 0.0, 10.0); + body.AddWorldWrench(_ecm, force, torque); + + }). + OnPostUpdate([&](const UpdateInfo &/*_info*/, + const EntityComponentManager &_ecm) + { + auto bodyVel = body.WorldLinearVelocity(_ecm); + ASSERT_TRUE(bodyVel); + _linearVel.push_back(bodyVel.value()); + auto bodyAngularVel = body.WorldAngularVelocity(_ecm); + ASSERT_TRUE(bodyAngularVel); + _angularVel.push_back(bodyAngularVel.value()); + }). + Finalize(); + + fixture.Server()->Run(true, _numsteps, false); + EXPECT_EQ(_numsteps, _linearVel.size()); + EXPECT_EQ(_numsteps, _angularVel.size()); + + EXPECT_NE(model.Entity(), kNullEntity); + EXPECT_NE(body.Entity(), kNullEntity); + +} + +///////////////////////////////////////////////// +/// This test makes sure that the linear velocity is reuduced +/// disbling the coriolis force and also when disabling the added mass. +TEST_F(HydrodynamicsFlagsTest, AddedMassCoriolisFlags) +{ + auto world = common::joinPaths(std::string(PROJECT_SOURCE_PATH), + "test", "worlds", "hydrodynamics_flags.sdf"); + + unsigned int numsteps = 1000; + + std::vector angularVels, angularCoriolisVels, + angularAddedMassVels; + std::vector linearVels, linearCoriolisVels, + linearAddedMassVels; + + this->TestWorld(world, "tethys", numsteps, linearVels, angularVels); + this->TestWorld(world, "triton", numsteps, linearCoriolisVels, + angularCoriolisVels); + this->TestWorld(world, "daphne", numsteps, linearAddedMassVels, + angularAddedMassVels); + + // Wait a couple of iterations for the body to move + for (unsigned int i = 4; i < numsteps; ++i) + { + // Angular and linear velocity should be lower + // with the produced coriolis and added mass + EXPECT_LT(angularCoriolisVels[i].Z(), angularVels[i].Z()); + EXPECT_LT(linearCoriolisVels[i].Z(), linearVels[i].Z()); + EXPECT_LT(angularAddedMassVels[i].Z(), angularVels[i].Z()); + EXPECT_LT(linearAddedMassVels[i].Z(), linearVels[i].Z()); + } +} diff --git a/test/worlds/hydrodynamics_flags.sdf b/test/worlds/hydrodynamics_flags.sdf new file mode 100644 index 0000000000..51ae7a93bd --- /dev/null +++ b/test/worlds/hydrodynamics_flags.sdf @@ -0,0 +1,352 @@ + + + + + + + + + 0.0 1.0 1.0 + 0.0 0.7 0.8 + + + + 0.001 + 1.0 + + + + + + + + + + + + 1000 + + + + true + 0 0 10 0 0 0 + 1 1 1 1 + 0.5 0.5 0.5 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + 0 0 1 0 0 1.57 + https://fuel.ignitionrobotics.org/1.0/accurrent/models/MBARI Tethys LRAUV + + + + horizontal_fins_joint + 0.1 + + + + vertical_fins_joint + 0.1 + + + + tethys + propeller_joint + 0.004422 + 1000 + 0.2 + + + + + + + 1000 + 4.13 + -1.1 + 0.2 + 0.03 + 0.17 + 0 + 0.0244 + 0 1 0 + 1 0 0 + vertical_fins + 0 0 0 + + + + + 1000 + 4.13 + -1.1 + 0.2 + 0.03 + 0.17 + 0 + 0.0244 + 0 0 1 + 1 0 0 + horizontal_fins + 0 0 0 + + + + base_link + -4.876161 + -126.324739 + -126.324739 + 0 + -33.46 + -33.46 + -6.2282 + 0 + -601.27 + 0 + -601.27 + 0 + -0.1916 + 0 + -632.698957 + 0 + -632.698957 + 0 + true + true + + + + + + 5 0 1 0 0 1.57 + https://fuel.ignitionrobotics.org/1.0/accurrent/models/MBARI Tethys LRAUV + triton + + + + horizontal_fins_joint + 0.1 + + + + vertical_fins_joint + 0.1 + + + + triton + propeller_joint + 0.004422 + 1000 + 0.2 + + + + + + + 1000 + 4.13 + -1.1 + 0.2 + 0.03 + 0.17 + 0 + 0.0244 + 0 1 0 + 1 0 0 + vertical_fins + 0 0 0 + + + + + 1000 + 4.13 + -1.1 + 0.2 + 0.03 + 0.17 + 0 + 0.0244 + 0 0 1 + 1 0 0 + horizontal_fins + 0 0 0 + + + + base_link + -4.876161 + -126.324739 + -126.324739 + 0 + -33.46 + -33.46 + -6.2282 + 0 + -601.27 + 0 + -601.27 + 0 + -0.1916 + 0 + -632.698957 + 0 + -632.698957 + 0 + true + + + + + + -5 0 1 0 0 1.57 + https://fuel.ignitionrobotics.org/1.0/accurrent/models/MBARI Tethys LRAUV + daphne + + + + horizontal_fins_joint + 0.1 + + + + vertical_fins_joint + 0.1 + + + + daphne + propeller_joint + 0.004422 + 1000 + 0.2 + + + + + + + 1000 + 4.13 + -1.1 + 0.2 + 0.03 + 0.17 + 0 + 0.0244 + 0 1 0 + 1 0 0 + vertical_fins + 0 0 0 + + + + + 1000 + 4.13 + -1.1 + 0.2 + 0.03 + 0.17 + 0 + 0.0244 + 0 0 1 + 1 0 0 + horizontal_fins + 0 0 0 + + + + base_link + -4.876161 + -126.324739 + -126.324739 + 0 + -33.46 + -33.46 + -6.2282 + 0 + -601.27 + 0 + -601.27 + 0 + -0.1916 + 0 + -632.698957 + 0 + -632.698957 + 0 + true + + + + + + 0 0 -1 0 0 3.1415926 + https://fuel.ignitionrobotics.org/1.0/mabelzhang/models/ABCSign_5m + start_line + + + 0 -25 -1 0 0 3.1415926 + https://fuel.ignitionrobotics.org/1.0/mabelzhang/models/ABCSign_5m + finish_line + + + + From f91d031184e417d10c680d16ab74ff7b0069dc3e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Tue, 11 Oct 2022 13:48:48 +0200 Subject: [PATCH 15/28] Fortress: Removed warnings (#1754) * Fortress: Removed warnings --- .../optical_tactile_plugin/OpticalTactilePlugin.cc | 3 +-- src/systems/optical_tactile_plugin/Visualization.cc | 6 ++---- src/systems/optical_tactile_plugin/Visualization.hh | 8 +------- test/integration/thruster.cc | 3 ++- 4 files changed, 6 insertions(+), 14 deletions(-) diff --git a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc index 492666b0ec..3fc0458e08 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc @@ -615,8 +615,7 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) this->sensorSize, this->forceLength, this->cameraUpdateRate, - this->depthCameraOffset, - this->visualizationResolution); + this->depthCameraOffset); this->initialized = true; } diff --git a/src/systems/optical_tactile_plugin/Visualization.cc b/src/systems/optical_tactile_plugin/Visualization.cc index 22ba842ebb..d330e6a9d4 100644 --- a/src/systems/optical_tactile_plugin/Visualization.cc +++ b/src/systems/optical_tactile_plugin/Visualization.cc @@ -32,14 +32,12 @@ OpticalTactilePluginVisualization::OpticalTactilePluginVisualization( ignition::math::Vector3d &_sensorSize, double &_forceLength, float &_cameraUpdateRate, - ignition::math::Pose3f &_depthCameraOffset, - int &_visualizationResolution) : + ignition::math::Pose3f &_depthCameraOffset) : modelName(_modelName), sensorSize(_sensorSize), forceLength(_forceLength), cameraUpdateRate(_cameraUpdateRate), - depthCameraOffset(_depthCameraOffset), - visualizationResolution(_visualizationResolution) + depthCameraOffset(_depthCameraOffset) { } diff --git a/src/systems/optical_tactile_plugin/Visualization.hh b/src/systems/optical_tactile_plugin/Visualization.hh index a5e863e139..96c8b46cc0 100644 --- a/src/systems/optical_tactile_plugin/Visualization.hh +++ b/src/systems/optical_tactile_plugin/Visualization.hh @@ -52,15 +52,12 @@ namespace optical_tactile_sensor /// \param[in] _forceLength Value of the forceLength attribute /// \param[in] _cameraUpdateRate Value of the cameraUpdateRate attribute /// \param[in] _depthCameraOffset Value of the depthCameraOffset attribute - /// \param[in] _visualizationResolution Value of the - /// visualizationResolution attribute public: OpticalTactilePluginVisualization( std::string &_modelName, ignition::math::Vector3d &_sensorSize, double &_forceLength, float &_cameraUpdateRate, - ignition::math::Pose3f &_depthCameraOffset, - int &_visualizationResolution); + ignition::math::Pose3f &_depthCameraOffset); /// \brief Initialize the marker message representing the optical tactile /// sensor @@ -153,9 +150,6 @@ namespace optical_tactile_sensor /// \brief Offset between depth camera pose and model pose private: ignition::math::Pose3f depthCameraOffset; - /// \brief Resolution of the sensor in pixels to skip. - private: int visualizationResolution; - /// \brief Whether the normal forces messages are initialized or not private: bool normalForcesMsgsAreInitialized{false}; }; diff --git a/test/integration/thruster.cc b/test/integration/thruster.cc index 92c60a7d89..d92b3f15c3 100644 --- a/test/integration/thruster.cc +++ b/test/integration/thruster.cc @@ -21,6 +21,7 @@ #include #include +#include #include #include @@ -244,7 +245,7 @@ void ThrusterTest::TestWorld(const std::string &_world, // linear_velocity) / (angular_velocity * propeller_diameter)) // omega = sqrt(thrust / // (fluid_density * thrust_coefficient * propeller_diameter ^ 4)) - if (_calculateCoefficient && angularVelocity != 0) + if (_calculateCoefficient && gz::math::equal(angularVelocity, 0.0)) { _thrustCoefficient = _alpha1 + _alpha2 * (((1 - _wakeFraction) * propellerLinVels[i].Length()) / (angularVelocity * _diameter)); From a53c1936ad70390e0a46c8e288b801a27a0afaa6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 13 Oct 2022 22:29:14 +0200 Subject: [PATCH 16/28] Removed unused speedlimit file (#1761) Signed-off-by: ahcorde --- .../ackermann_steering/SpeedLimiter.hh | 130 ------------------ 1 file changed, 130 deletions(-) delete mode 100644 src/systems/ackermann_steering/SpeedLimiter.hh diff --git a/src/systems/ackermann_steering/SpeedLimiter.hh b/src/systems/ackermann_steering/SpeedLimiter.hh deleted file mode 100644 index 34286bc3ae..0000000000 --- a/src/systems/ackermann_steering/SpeedLimiter.hh +++ /dev/null @@ -1,130 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2013, PAL Robotics, S.L. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the PAL Robotics nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* - * Author: Enrique Fernández - * Modified: Carlos Agüero - */ - -#ifndef IGNITION_GAZEBO_SYSTEMS_SPEEDLIMITER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_SPEEDLIMITER_HH_ - -#include - -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace systems -{ - // Forward declaration. - class SpeedLimiterPrivate; - - /// \brief Class to limit velocity, acceleration and jerk. - /// \ref https://github.com/ros-controls/ros_controllers/tree/melodic-devel/diff_drive_controller - class SpeedLimiter - { - /// \brief Constructor. - /// \param [in] _hasVelocityLimits if true, applies velocity limits. - /// \param [in] _hasAccelerationLimits if true, applies acceleration limits. - /// \param [in] _hasJerkLimits if true, applies jerk limits. - /// \param [in] _minVelocity Minimum velocity [m/s], usually <= 0. - /// \param [in] _maxVelocity Maximum velocity [m/s], usually >= 0. - /// \param [in] _minAcceleration Minimum acceleration [m/s^2], usually <= 0. - /// \param [in] _maxAcceleration Maximum acceleration [m/s^2], usually >= 0. - /// \param [in] _minJerk Minimum jerk [m/s^3], usually <= 0. - /// \param [in] _maxJerk Maximum jerk [m/s^3], usually >= 0. - public: SpeedLimiter(bool _hasVelocityLimits = false, - bool _hasAccelerationLimits = false, - bool _hasJerkLimits = false, - double _minVelocity = 0.0, - double _maxVelocity = 0.0, - double _minAcceleration = 0.0, - double _maxAcceleration = 0.0, - double _minJerk = 0.0, - double _maxJerk = 0.0); - - /// \brief Destructor. - public: ~SpeedLimiter(); - - /// \brief Limit the velocity and acceleration. - /// \param [in, out] _v Velocity [m/s]. - /// \param [in] _v0 Previous velocity to v [m/s]. - /// \param [in] _v1 Previous velocity to v0 [m/s]. - /// \param [in] _dt Time step [s]. - /// \return Limiting factor (1.0 if none). - public: double Limit(double &_v, - double _v0, - double _v1, - double _dt) const; - - /// \brief Limit the velocity. - /// \param [in, out] _v Velocity [m/s]. - /// \return Limiting factor (1.0 if none). - public: double LimitVelocity(double &_v) const; - - /// \brief Limit the acceleration. - /// \param [in, out] _v Velocity [m/s]. - /// \param [in] _v0 Previous velocity [m/s]. - /// \param [in] _dt Time step [s]. - /// \return Limiting factor (1.0 if none). - public: double LimitAcceleration(double &_v, - double _v0, - double _dt) const; - - /// \brief Limit the jerk. - /// \param [in, out] _v Velocity [m/s]. - /// \param [in] _v0 Previous velocity to v [m/s]. - /// \param [in] _v1 Previous velocity to v0 [m/s]. - /// \param [in] _dt Time step [s]. - /// \return Limiting factor (1.0 if none). - /// \see http://en.wikipedia.org/wiki/Jerk_%28physics%29#Motion_control. - public: double LimitJerk(double &_v, - double _v0, - double _v1, - double _dt) const; - - /// \brief Private data pointer. - private: std::unique_ptr dataPtr; - }; - } -} -} -} - -#endif From 4e10c35624b554eb9bd4cfaabea5dd4e2dd0f0ab Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Thu, 20 Oct 2022 01:41:04 +0200 Subject: [PATCH 17/28] Enable use of ign gazebo -s on Windows (take two) (#1764) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Enable use of ign gazebo -s on Windows Signed-off-by: Silvio * Update src/CMakeLists.txt Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Silvio * Fix cmdmodel6.rb and cmdgazebo6.rb contining the same code Signed-off-by: Silvio Signed-off-by: Silvio Co-authored-by: Alejandro Hernández Cordero --- src/CMakeLists.txt | 32 ++++++++-- src/cmd/CMakeLists.txt | 121 +++++++++++++++++++++---------------- src/cmd/ModelCommandAPI.hh | 6 +- src/cmd/cmdgazebo.rb.in | 16 ++++- src/cmd/cmdmodel.rb.in | 4 +- src/ign.hh | 16 ++--- src/ign_TEST.cc | 13 ++-- src/systems/CMakeLists.txt | 7 +-- 8 files changed, 136 insertions(+), 79 deletions(-) diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index ff178007c3..d4ea8bc402 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -92,7 +92,6 @@ set (gtest_sources TestFixture_TEST.cc Util_TEST.cc World_TEST.cc - ign_TEST.cc comms/Broker_TEST.cc comms/MsgManager_TEST.cc network/NetworkConfig_TEST.cc @@ -100,11 +99,22 @@ set (gtest_sources network/NetworkManager_TEST.cc ) +# ign_TEST and ModelCommandAPI_TEST are not supported with multi config +# CMake generators, see also cmd/CMakeLists.txt +get_property(GENERATOR_IS_MULTI_CONFIG GLOBAL PROPERTY GENERATOR_IS_MULTI_CONFIG) +if(NOT GENERATOR_IS_MULTI_CONFIG) + list(APPEND gtest_sources ign_TEST.cc) +endif() + + # Tests that require a valid display set(tests_needing_display - ModelCommandAPI_TEST.cc ) +if(NOT GENERATOR_IS_MULTI_CONFIG) + list(APPEND tests_needing_display ModelCommandAPI_TEST.cc) +endif() + # Add systems that need a valid display here. # \todo(anyone) Find a way to run these tests with a virtual display such Xvfb # or Xdummy instead of skipping them @@ -222,9 +232,19 @@ foreach(CMD_TEST set_tests_properties(${CMD_TEST} PROPERTIES ENVIRONMENT "${_env_vars}") -endforeach() + # On Windows there is no RPATH, so an alternative way for tests for finding .dll libraries + # in build directory in necessary. For regular tests, the trick is to place all libraries + # and executables in a common CMAKE_RUNTIME_OUTPUT_DIRECTORY, so that the .dll are found + # as they are in the same directory where the executable is loaded. For tests that are + # launched via Ruby, this does not work, so we need to manually add CMAKE_RUNTIME_OUTPUT_DIRECTORY + # to the PATH. This is done via the ENVIRONMENT_MODIFICATION that is only available + # since CMake 3.22. However, if an older CMake is used another trick to install the libraries + # beforehand + if (WIN32 AND CMAKE_VERSION STRGREATER "3.22") + set_tests_properties(${CMD_TEST} PROPERTIES + ENVIRONMENT_MODIFICATION "PATH=path_list_prepend:${CMAKE_RUNTIME_OUTPUT_DIRECTORY}") + endif() -if(NOT WIN32) - add_subdirectory(cmd) -endif() +endforeach() +add_subdirectory(cmd) diff --git a/src/cmd/CMakeLists.txt b/src/cmd/CMakeLists.txt index 11e7ef7e00..f19fd0d6af 100644 --- a/src/cmd/CMakeLists.txt +++ b/src/cmd/CMakeLists.txt @@ -2,12 +2,19 @@ # Generate the ruby script. # Note that the major version of the library is included in the name. # Ex: cmdgazebo0.rb -set(cmd_script_generated "${CMAKE_CURRENT_BINARY_DIR}/cmd${IGN_DESIGNATION}${PROJECT_VERSION_MAJOR}.rb") -set(cmd_script_configured "${cmd_script_generated}.configured") +set(cmd_script_name "cmd${IGN_DESIGNATION}${PROJECT_VERSION_MAJOR}.rb") +set(cmd_script_generated "${CMAKE_CURRENT_BINARY_DIR}/$_${cmd_script_name}") +set(cmd_script_configured "${CMAKE_CURRENT_BINARY_DIR}/${cmd_script_name}.configured") # Set the library_location variable to the relative path to the library file # within the install directory structure. -set(library_location "../../../${CMAKE_INSTALL_LIBDIR}/$") +if(WIN32) + set(plugin_location ${CMAKE_INSTALL_BINDIR}) +else() + set(plugin_location ${CMAKE_INSTALL_LIBDIR}) +endif() + +set(library_location "../../../${plugin_location}/$") configure_file( "cmd${IGN_DESIGNATION}.rb.in" @@ -19,7 +26,7 @@ file(GENERATE INPUT "${cmd_script_configured}") # Install the ruby command line library in an unversioned location. -install(FILES ${cmd_script_generated} DESTINATION lib/ruby/ignition) +install(FILES ${cmd_script_generated} DESTINATION lib/ruby/ignition RENAME ${cmd_script_name}) set(ign_library_path "${CMAKE_INSTALL_PREFIX}/lib/ruby/ignition/cmd${IGN_DESIGNATION}${PROJECT_VERSION_MAJOR}") @@ -40,8 +47,9 @@ install( FILES # Used for the installed model command version. # Generate the ruby script that gets installed. # Note that the major version of the library is included in the name. -set(cmd_model_script_generated "${CMAKE_CURRENT_BINARY_DIR}/cmdmodel${PROJECT_VERSION_MAJOR}.rb") -set(cmd_model_script_configured "${cmd_model_script_generated}.configured") +set(cmd_model_script_name "cmdmodel${PROJECT_VERSION_MAJOR}.rb") +set(cmd_model_script_generated "${CMAKE_CURRENT_BINARY_DIR}/$_${cmd_model_script_name}") +set(cmd_model_script_configured "${CMAKE_CURRENT_BINARY_DIR}/${cmd_model_script_name}.configured") configure_file( "cmdmodel.rb.in" @@ -51,7 +59,7 @@ file(GENERATE OUTPUT "${cmd_model_script_generated}" INPUT "${cmd_model_script_configured}") -install(FILES ${cmd_model_script_generated} DESTINATION lib/ruby/ignition) +install(FILES ${cmd_model_script_generated} DESTINATION lib/ruby/ignition RENAME ${cmd_model_script_name}) # Used for the installed version. set(ign_model_ruby_path "${CMAKE_INSTALL_PREFIX}/lib/ruby/ignition/cmdmodel${PROJECT_VERSION_MAJOR}") @@ -68,55 +76,64 @@ install(FILES ${model_configured} DESTINATION ${CMAKE_INSTALL_PREFIX}/${CMAKE_IN # Generate the ruby script for internal testing. # Note that the major version of the library is included in the name. # Ex: cmdgazebo0.rb -set(cmd_script_generated_test "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition/cmd${IGN_DESIGNATION}${PROJECT_VERSION_MAJOR}.rb") -set(cmd_script_configured_test "${cmd_script_generated_test}.configured") - -# Set the library_location variable to the relative path to the library file -# within the install directory structure. -set(library_location "$") - -configure_file( - "cmd${IGN_DESIGNATION}.rb.in" - "${cmd_script_configured_test}" - @ONLY) - -file(GENERATE - OUTPUT "${cmd_script_generated_test}" - INPUT "${cmd_script_configured_test}") - -# Used only for internal testing. -set(ign_library_path - "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition/cmd${IGN_DESIGNATION}${PROJECT_VERSION_MAJOR}") - -# Generate a configuration file for internal testing. -# Note that the major version of the library is included in the name. -# Ex: gazebo0.yaml -configure_file( - "${IGN_DESIGNATION}.yaml.in" - "${CMAKE_BINARY_DIR}/test/conf/${IGN_DESIGNATION}${PROJECT_VERSION_MAJOR}.yaml" @ONLY) +# The logic is valid only for single-config CMake generators, so no script is +# generated if a multiple-config CMake geneator is used +get_property(GENERATOR_IS_MULTI_CONFIG GLOBAL PROPERTY GENERATOR_IS_MULTI_CONFIG) +if(NOT GENERATOR_IS_MULTI_CONFIG) + set(cmd_script_generated_test "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition/cmd${IGN_DESIGNATION}${PROJECT_VERSION_MAJOR}.rb") + set(cmd_script_configured_test "${cmd_script_generated_test}.configured") + + # Set the library_location variable to the relative path to the library file + # within the install directory structure. + set(library_location "$") + + configure_file( + "cmd${IGN_DESIGNATION}.rb.in" + "${cmd_script_configured_test}" + @ONLY) + + file(GENERATE + OUTPUT "${cmd_script_generated_test}" + INPUT "${cmd_script_configured_test}") + + # Used only for internal testing. + set(ign_library_path + "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition/cmd${IGN_DESIGNATION}${PROJECT_VERSION_MAJOR}") + + # Generate a configuration file for internal testing. + # Note that the major version of the library is included in the name. + # Ex: gazebo0.yaml + configure_file( + "${IGN_DESIGNATION}.yaml.in" + "${CMAKE_BINARY_DIR}/test/conf/${IGN_DESIGNATION}${PROJECT_VERSION_MAJOR}.yaml" @ONLY) +endif() #=============================================================================== # Generate the ruby script for internal testing. # Note that the major version of the library is included in the name. -set(cmd_model_ruby_test_dir "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition") -set(cmd_model_script_generated_test "${cmd_model_ruby_test_dir}/cmdmodel${PROJECT_VERSION_MAJOR}.rb") -set(cmd_model_script_configured_test "${cmd_model_script_generated_test}.configured") - -configure_file( - "cmdmodel.rb.in" - "${cmd_model_script_configured_test}" - @ONLY) - -file(GENERATE - OUTPUT "${cmd_model_script_generated_test}" - INPUT "${cmd_model_script_configured_test}") - -# Used for internal testing. -set(ign_model_ruby_path "${cmd_model_script_generated_test}") - -configure_file( - "model.yaml.in" - "${CMAKE_BINARY_DIR}/test/conf/model${PROJECT_VERSION_MAJOR}.yaml" @ONLY) +# The logic is valid only for single-config CMake generators, so no script is +# generated if a multiple-config CMake geneator is used +if(NOT GENERATOR_IS_MULTI_CONFIG) + set(cmd_model_ruby_test_dir "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition") + set(cmd_model_script_generated_test "${cmd_model_ruby_test_dir}/cmdmodel${PROJECT_VERSION_MAJOR}.rb") + set(cmd_model_script_configured_test "${cmd_model_script_generated_test}.configured") + + configure_file( + "cmdmodel.rb.in" + "${cmd_model_script_configured_test}" + @ONLY) + + file(GENERATE + OUTPUT "${cmd_model_script_generated_test}" + INPUT "${cmd_model_script_configured_test}") + + # Used for internal testing. + set(ign_model_ruby_path "${cmd_model_script_generated_test}") + + configure_file( + "model.yaml.in" + "${CMAKE_BINARY_DIR}/test/conf/model${PROJECT_VERSION_MAJOR}.yaml" @ONLY) +endif() #=============================================================================== # Bash completion diff --git a/src/cmd/ModelCommandAPI.hh b/src/cmd/ModelCommandAPI.hh index 2ca7248c60..c941936471 100644 --- a/src/cmd/ModelCommandAPI.hh +++ b/src/cmd/ModelCommandAPI.hh @@ -15,8 +15,10 @@ * */ +#include "ignition/gazebo/Export.hh" + /// \brief External hook to get a list of available models. -extern "C" void cmdModelList(); +extern "C" IGNITION_GAZEBO_VISIBLE void cmdModelList(); /// \brief External hook to dump model information. /// \param[in] _modelName Model name. @@ -24,7 +26,7 @@ extern "C" void cmdModelList(); /// \param[in] _linkName Link name. /// \param[in] _jointName Joint name. /// \param[in] _sensorName Sensor name. -extern "C" void cmdModelInfo( +extern "C" IGNITION_GAZEBO_VISIBLE void cmdModelInfo( const char *_modelName, int _pose, const char *_linkName, const char *_jointName, const char *_sensorName); diff --git a/src/cmd/cmdgazebo.rb.in b/src/cmd/cmdgazebo.rb.in index 16ee5e1cac..023843ce1d 100755 --- a/src/cmd/cmdgazebo.rb.in +++ b/src/cmd/cmdgazebo.rb.in @@ -27,6 +27,7 @@ end require 'optparse' require 'erb' +require 'pathname' # Constants. LIBRARY_NAME = '@library_location@' @@ -337,7 +338,8 @@ class Cmd def execute(args) options = parse(args) - if LIBRARY_NAME[0] == '/' + library_name_path = Pathname.new(LIBRARY_NAME) + if library_name_path.absolute? # If the first character is a slash, we'll assume that we've been given an # absolute path to the library. This is only used during test mode. plugin = LIBRARY_NAME @@ -467,6 +469,12 @@ See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." exit(-1) end + if plugin.end_with? ".dll" + puts "`ign gazebo` currently only works with the -s argument on Windows. +See https://github.com/gazebosim/gz-sim/issues/168 for more info." + exit(-1) + end + serverPid = Process.fork do ENV['RMT_PORT'] = '1500' Process.setpgid(0, 0) @@ -526,6 +534,12 @@ See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." exit(-1) end + if plugin.end_with? ".dll" + puts "`ign gazebo` currently only works with the -s argument on Windows. +See https://github.com/gazebosim/gz-sim/issues/168 for more info." + exit(-1) + end + ENV['RMT_PORT'] = '1501' Importer.runGui(options['gui_config'], options['file'], options['wait_gui'], options['render_engine_gui']) diff --git a/src/cmd/cmdmodel.rb.in b/src/cmd/cmdmodel.rb.in index 88e65a50f3..e49eb30749 100644 --- a/src/cmd/cmdmodel.rb.in +++ b/src/cmd/cmdmodel.rb.in @@ -26,6 +26,7 @@ else end require 'optparse' +require 'pathname' # Constants. LIBRARY_NAME = '@library_location@' @@ -157,7 +158,8 @@ class Cmd options = parse(args) # Read the plugin that handles the command. - if LIBRARY_NAME[0] == '/' + library_name_path = Pathname.new(LIBRARY_NAME) + if library_name_path.absolute? # If the first character is a slash, we'll assume that we've been given an # absolute path to the library. This is only used during test mode. plugin = LIBRARY_NAME diff --git a/src/ign.hh b/src/ign.hh index 38de2a88e6..18eac3cfc5 100644 --- a/src/ign.hh +++ b/src/ign.hh @@ -21,18 +21,18 @@ /// \brief External hook to read the library version. /// \return C-string representing the version. Ex.: 0.1.2 -extern "C" char *ignitionGazeboVersion(); +extern "C" IGNITION_GAZEBO_VISIBLE char *ignitionGazeboVersion(); /// \brief Get the Gazebo version header. /// \return C-string containing the Gazebo version information. -extern "C" char *gazeboVersionHeader(); +extern "C" IGNITION_GAZEBO_VISIBLE char *gazeboVersionHeader(); /// \brief Set verbosity level /// \param[in] _verbosity 0 to 4 -extern "C" void cmdVerbosity( +extern "C" IGNITION_GAZEBO_VISIBLE void cmdVerbosity( const char *_verbosity); -extern "C" const char *worldInstallDir(); +extern "C" IGNITION_GAZEBO_VISIBLE const char *worldInstallDir(); /// \brief External hook to run simulation server. /// \param[in] _sdfString SDF file to run, as a string. @@ -59,7 +59,7 @@ extern "C" const char *worldInstallDir(); /// \param[in] _headless True if server rendering should run headless /// \param[in] _recordPeriod --record-period option /// \return 0 if successful, 1 if not. -extern "C" int runServer(const char *_sdfString, +extern "C" IGNITION_GAZEBO_VISIBLE int runServer(const char *_sdfString, int _iterations, int _run, float _hz, int _levels, const char *_networkRole, int _networkSecondaries, int _record, const char *_recordPath, int _recordResources, int _logOverwrite, @@ -77,14 +77,14 @@ extern "C" int runServer(const char *_sdfString, /// it receives a world path from GUI. /// \param[in] _renderEngine --render-engine-gui option /// \return 0 if successful, 1 if not. -extern "C" int runGui(const char *_guiConfig, const char *_file, int _waitGui, - const char *_renderEngine); +extern "C" IGNITION_GAZEBO_VISIBLE int runGui(const char *_guiConfig, + const char *_file, int _waitGui, const char *_renderEngine); /// \brief External hook to find or download a fuel world provided a URL. /// \param[in] _pathToResource Path to the fuel world resource, ie, /// https://staging-fuel.ignitionrobotics.org/1.0/gmas/worlds/ShapesClone /// \return C-string containing the path to the local world sdf file -extern "C" const char *findFuelResource( +extern "C" IGNITION_GAZEBO_VISIBLE const char *findFuelResource( char *_pathToResource); #endif diff --git a/src/ign_TEST.cc b/src/ign_TEST.cc index fbf01162bf..397441bed4 100644 --- a/src/ign_TEST.cc +++ b/src/ign_TEST.cc @@ -59,8 +59,7 @@ std::string customExecStr(std::string _cmd) } ///////////////////////////////////////////////// -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 -TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(Server)) +TEST(CmdLine, Server) { std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + std::string(PROJECT_SOURCE_PATH) + "/test/worlds/plugins.sdf"; @@ -75,6 +74,9 @@ TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(Server)) << output; } +// Disable on WIN32 as on Windows it is not support to prepend +// a command with the env variable to set +#ifndef _WIN32 // Use IGN_GAZEBO_RESOURCE_PATH instead of specifying the complete path cmd = std::string("IGN_GAZEBO_RESOURCE_PATH=") + PROJECT_SOURCE_PATH + "/test/worlds " + kIgnCommand + @@ -89,10 +91,11 @@ TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(Server)) EXPECT_NE(output.find("iteration " + std::to_string(i)), std::string::npos) << output; } +#endif } ///////////////////////////////////////////////// -TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(CachedFuelWorld)) +TEST(CmdLine, CachedFuelWorld) { std::string projectPath = std::string(PROJECT_SOURCE_PATH) + "/test/worlds"; ignition::common::setenv("IGN_FUEL_CACHE_PATH", projectPath.c_str()); @@ -106,7 +109,7 @@ TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(CachedFuelWorld)) } ///////////////////////////////////////////////// -TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(GazeboServer)) +TEST(CmdLine, GazeboServer) { std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + std::string(PROJECT_SOURCE_PATH) + "/test/worlds/plugins.sdf"; @@ -123,7 +126,7 @@ TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(GazeboServer)) } ///////////////////////////////////////////////// -TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(Gazebo)) +TEST(CmdLine, Gazebo) { std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + std::string(PROJECT_SOURCE_PATH) + "/test/worlds/plugins.sdf"; diff --git a/src/systems/CMakeLists.txt b/src/systems/CMakeLists.txt index 303c6fc7d9..330b267f25 100644 --- a/src/systems/CMakeLists.txt +++ b/src/systems/CMakeLists.txt @@ -82,10 +82,9 @@ function(gz_add_system system_name) set(unversioned ${CMAKE_SHARED_LIBRARY_PREFIX}${PROJECT_NAME_NO_VERSION_LOWER}-${system_name}${CMAKE_SHARED_LIBRARY_SUFFIX}) if(WIN32) # symlinks on Windows require admin priviledges, fallback to copy - ADD_CUSTOM_COMMAND(TARGET ${system_target} POST_BUILD - COMMAND "${CMAKE_COMMAND}" -E copy - "$" - "$/${unversioned}") + INSTALL(CODE "EXECUTE_PROCESS(COMMAND ${CMAKE_COMMAND} -E copy + ${IGNITION_GAZEBO_PLUGIN_INSTALL_DIR}\/${versioned} + ${IGNITION_GAZEBO_PLUGIN_INSTALL_DIR}\/${unversioned})") else() file(MAKE_DIRECTORY "${PROJECT_BINARY_DIR}/lib") EXECUTE_PROCESS(COMMAND ${CMAKE_COMMAND} -E create_symlink ${versioned} ${unversioned} WORKING_DIRECTORY "${PROJECT_BINARY_DIR}/lib") From 205bc32949e06b9dccde248be2c249321db7c588 Mon Sep 17 00:00:00 2001 From: Andrej Orsula Date: Fri, 21 Oct 2022 13:55:40 +0900 Subject: [PATCH 18/28] Script and tutorial for generating procedural datasets with Blender (#1412) Signed-off-by: Andrej Orsula --- .../blender/procedural_dataset_generator.py | 1945 +++++++++++++++++ tutorials.md.in | 1 + tutorials/blender_procedural_datasets.md | 257 +++ .../blender_instructions.png | Bin 0 -> 43374 bytes .../demo_blender_rock.gif | Bin 0 -> 751047 bytes .../demo_blender_woodland.gif | Bin 0 -> 756691 bytes .../demo_gazebo_rock.png | Bin 0 -> 793502 bytes .../demo_gazebo_woodland.png | Bin 0 -> 971531 bytes .../blender_procedural_datasets/rock.blend | Bin 0 -> 1439687 bytes .../woodland.blend | Bin 0 -> 336259 bytes 10 files changed, 2203 insertions(+) create mode 100755 examples/scripts/blender/procedural_dataset_generator.py create mode 100644 tutorials/blender_procedural_datasets.md create mode 100644 tutorials/files/blender_procedural_datasets/blender_instructions.png create mode 100644 tutorials/files/blender_procedural_datasets/demo_blender_rock.gif create mode 100644 tutorials/files/blender_procedural_datasets/demo_blender_woodland.gif create mode 100644 tutorials/files/blender_procedural_datasets/demo_gazebo_rock.png create mode 100644 tutorials/files/blender_procedural_datasets/demo_gazebo_woodland.png create mode 100644 tutorials/files/blender_procedural_datasets/rock.blend create mode 100644 tutorials/files/blender_procedural_datasets/woodland.blend diff --git a/examples/scripts/blender/procedural_dataset_generator.py b/examples/scripts/blender/procedural_dataset_generator.py new file mode 100755 index 0000000000..ee0b7b50eb --- /dev/null +++ b/examples/scripts/blender/procedural_dataset_generator.py @@ -0,0 +1,1945 @@ +#!/usr/bin/env -S blender --python +""" +This script contains a Blender exporter of SDF models `sdf_model_exporter` for Gazebo +and a generator of procedural SDF datasets `procedural_dataset_generator`. + +The SDF exporter outputs models that are compatible with Fuel. It processes all selected +objects in the Blender scene (or all existing objects if none is selected). The exporter +is fully configurable via CLI arguments. It can export separate visual and collision +geometry at different resolution levels. It supports automatic estimation of inertial +properties for non-static models by `trimesh` Python module. Several attributes such as +model mass and surface friction can be randomized via uniform distribution by specifying +a range of minimum and maximum values. + +The dataset generator is based on Blender's `Geometry Nodes` modifiers with support +for variations via `random_seed` input attribute (seed for the pseudorandom generation). +This module-based class inherits all functionalities of the SDF model exporter. + +You can run this script in multiple ways: +a) Directly in Blender's [Text Editor] tab | with the default parameters (configurable) + 1. Copy this script into a [New Text] data block in your 'file.blend' + 2. Configure the default script parameters for your model via constants below + 3. Run the script using the [Run script] button at the top of the [Text Editor] tab +b) Running an internal script (saved within 'file.blend') | with CLI args (configurable) + $ blender [blender options] file.blend --python-text script.py -- [script options] +c) Running an external script | with CLI args (configurable) + $ blender [blender options] file.blend --python external_script.py -- [script options] + +Show the help message of this script ([script options]): + $ blender -b file.blend --python-text script.py -- -h + $ blender -b file.blend --python external_script.py -- -h + +Show the help message of Blender ([blender options]): + $ blender -h +""" +from __future__ import annotations + +# Raise an informative error in case the script is run outside Python env of Blender +try: + import bpy +except ImportError as err: + raise ImportError( + "Python module of Blender 'bpy' not found! Please, execute this script inside " + "a Blender environment (e.g. run inside the Scripting tab of Blender)." + ) from err + +import argparse +import enum +import os +import random +import shutil +import sys +from os import path +from types import ModuleType +from typing import Any, Dict, Iterable, List, Optional, TextIO, Tuple, Union +from xml.dom import minidom +from xml.etree import ElementTree + +# Last tested and working version of Blender for this script (MAJOR, MINOR) +LAST_WORKING_VERSION: Tuple(int, int) = (3, 2) + +### Default script parameters (adjustable via CLI arguments) +## Parameters for SDF model exporter `sdf_model_exporter` +OUTPUT_DIR: str = path.join(os.getcwd(), "sdf_models") +MODEL_VERSION: Optional[int] = None +## Parameters for procedural dataset generator `procedural_dataset_generator` +FIRST_SEED: int = 0 +NUMBER_OF_VARIANTS: int = 8 + +### Default model-specific parameters (adjustable via CLI arguments) +## Default level of detail for exported geometry, e.g. subdivision level +DETAIL_LEVEL_VISUAL: int = 1 +DETAIL_LEVEL_COLLISION: int = 0 +## Default objects to ignore while exporting visual/collision geometry, even if selected +IGNORE_OBJECTS_VISUAL: List[str] = [] +IGNORE_OBJECTS_COLLISION: List[str] = [] +## Default source of textures for the model +# Options: "collada" == "dae" | "wavefront" == "obj" | "stl" +FILETYPE_VISUAL: str = "wavefront" +FILETYPE_COLLISION: str = "stl" +## Default source of textures for the model +# If true, symbolic links will be created for all textures instead of copies +SYMLINK_EXTERNAL_TEXTURES: bool = True +# Options: "none" | "path" +TEXTURE_SOURCE_MODE: str = "none" +TEXTURE_SOURCE_VALUE: Optional[str] = None +MATERIAL_TEXTURE_DIFFUSE: Optional[Tuple[float, float, float]] = (1.0, 1.0, 1.0) +MATERIAL_TEXTURE_SPECULAR: Optional[Tuple[float, float, float]] = (0.2, 0.2, 0.2) +## Default inertial and dynamic properties of exported models +# If true, the model is immovable and it won't be updated by physics engine +STATIC: bool = False +# Options: "none" | "density" | "random_density" | "mass" | "random_mass" +INERTIAL_ESTIMATION_MODE: str = "none" +INERTIAL_ESTIMATION_VALUE: Optional[List[float]] = None +# (Random) coefficient of the surface friction (equal in both directions) +FRICTION_COEFFICIENT: List[float] = [1.0] + +### Default keyword arguments for additional parameters (overwritten by CLI arguments) +DEFAULT_KWARGS: Any = {} + + +class sdf_model_exporter(ModuleType): + """ + Blender exporter of objects as SDF models. + + Note: This class is designed as a "module class" to enable simple copy-pasting + among Blender projects and environments, i.e. methods do not require an instance + during their call while still supporting inheritance. + """ + + ## Directory structure compatible with Gazebo Fuel + MODEL_ROOT: str = "" + BASENAME_SDF: str = path.join(MODEL_ROOT, "model.sdf") + BASENAME_SDF_MODEL_CONFIG: str = path.join(MODEL_ROOT, "model.config") + DIRNAME_MESHES: str = path.join(MODEL_ROOT, "meshes") + DIRNAME_MESHES_VISUAL: str = path.join(DIRNAME_MESHES, "visual") + DIRNAME_MESHES_COLLISION: str = path.join(DIRNAME_MESHES, "collision") + DIRNAME_MATERIALS: str = path.join(MODEL_ROOT, "materials") + DIRNAME_TEXTURES: str = path.join(DIRNAME_MATERIALS, "textures") + DIRNAME_THUMBNAILS: str = path.join(MODEL_ROOT, "thumbnails") + + # Targeted version of SDF + SDF_VERSION: str = "1.9" + + @enum.unique + class ExportFormat(enum.Enum): + """ + Helper enum of supported mesh file formats coupled with their configured + exporters. + """ + + COLLADA = enum.auto() + STL = enum.auto() + WAVEFRONT = enum.auto() + + def export(self, filepath: str) -> str: + """ + Use Blender exporter of the corresponding mesh format. The desired + `filepath` might be adjusted to include the appropriate file extension. Upon + success, the absolute filepath of the exported mesh is returned. Note, that + only the selected object(s) will be exported. + """ + + # Make sure the file has the correct extension + if not filepath.endswith(self.extension): + # Truncate incorrect extension(s) if there are any + split_path = path.basename(filepath).split(".") + if len(split_path) > 1: + filepath = path.join(path.dirname(filepath), split_path[0]) + # Append the correct extension + filepath += self.extension + filepath = path.abspath(filepath) + os.makedirs(name=path.dirname(filepath), exist_ok=True) + + # Export with Blender based on the file format + if self.COLLADA == self: + bpy.ops.wm.collada_export( + filepath=filepath, + check_existing=False, + filter_blender=False, + filter_backup=False, + filter_image=False, + filter_movie=False, + filter_python=False, + filter_font=False, + filter_sound=False, + filter_text=False, + filter_archive=False, + filter_btx=False, + filter_collada=True, + filter_alembic=False, + filter_usd=False, + filter_obj=False, + filter_volume=False, + filter_folder=True, + filter_blenlib=False, + filemode=8, + display_type="DEFAULT", + sort_method="DEFAULT", + prop_bc_export_ui_section="main", + apply_modifiers=True, + export_mesh_type=0, + export_mesh_type_selection="view", + export_global_forward_selection="Y", + export_global_up_selection="Z", + apply_global_orientation=False, + selected=True, + include_children=False, + include_armatures=False, + include_shapekeys=False, + deform_bones_only=False, + include_animations=False, + include_all_actions=False, + export_animation_type_selection="sample", + sampling_rate=1, + keep_smooth_curves=False, + keep_keyframes=False, + keep_flat_curves=False, + active_uv_only=False, + use_texture_copies=True, + triangulate=True, + use_object_instantiation=True, + use_blender_profile=True, + sort_by_name=False, + export_object_transformation_type=0, + export_object_transformation_type_selection="matrix", + export_animation_transformation_type=0, + export_animation_transformation_type_selection="matrix", + open_sim=False, + limit_precision=False, + keep_bind_info=False, + ) + elif self.STL == self: + bpy.ops.export_mesh.stl( + filepath=filepath, + check_existing=False, + use_selection=True, + axis_forward="Y", + axis_up="Z", + global_scale=1, + use_scene_unit=False, + ascii=False, + use_mesh_modifiers=True, + ) + elif self.WAVEFRONT == self: + bpy.ops.export_scene.obj( + filepath=filepath, + check_existing=False, + axis_forward="Y", + axis_up="Z", + use_selection=True, + use_animation=False, + use_mesh_modifiers=True, + use_edges=True, + use_smooth_groups=False, + use_smooth_groups_bitflags=False, + use_normals=True, + use_uvs=True, + use_materials=True, + use_triangles=True, + use_nurbs=False, + use_vertex_groups=False, + use_blen_objects=True, + group_by_object=False, + group_by_material=False, + keep_vertex_order=False, + global_scale=1, + path_mode="AUTO", + ) + else: + raise ValueError(f"Filetype '{self}' is not supported for export.") + + return filepath + + @classmethod + def from_str(cls, filetype_str: str) -> sdf_model_exporter.ExportFormat: + """ + Return ExportFormat that corresponds with a matched `filetype_str` string. + """ + + filetype_str = filetype_str.strip().upper() + if "COLLADA" in filetype_str or "DAE" in filetype_str: + return cls.COLLADA + elif "STL" in filetype_str: + return cls.STL + elif "WAVEFRONT" in filetype_str or "OBJ" in filetype_str: + return cls.WAVEFRONT + else: + raise ValueError(f"Unknown '{filetype_str}' filetype.") + + @classmethod + def default_visual(cls) -> sdf_model_exporter.ExportFormat: + """ + Return the default filetype for visual mesh geometry. + """ + + return cls.from_str(FILETYPE_VISUAL) + + @classmethod + def default_collision(cls) -> sdf_model_exporter.ExportFormat: + """ + Return the default filetype for collision mesh geometry. + """ + + return cls.from_str(FILETYPE_COLLISION) + + @property + def extension(self) -> str: + """ + Return file extension of the corresponding filetype. + """ + + if self.COLLADA == self: + return ".dae" + elif self.STL == self: + return ".stl" + elif self.WAVEFRONT == self: + return ".obj" + else: + raise ValueError(f"Unknown extension for '{self}' filetype.") + + @enum.unique + class TextureSource(enum.Enum): + """ + Helper enum of possible sources for textures. Each source should provide a path + to searchable directory with the following structure (each texture type is + optional and image format must be supported by Gazebo): + ├── ./ + ├── texture_0/ + ├── *albedo*.png || *color*.png + ├── *normal*.png + ├── *roughness*.png + └── *specular*.png || *metalness*.png + ├── ... + └── texture_n/ + Alternatively, it can point to a directory that directly contains textures and + no other subdirectories. + """ + + NONE = enum.auto() + BLENDER_MODEL = enum.auto() + FILEPATH = enum.auto() + ONLINE = enum.auto() + + def get_path(self, value: Optional[str] = None) -> Optional[str]: + """ + Return a path to a directory with PBR textures. + """ + + if self.NONE == self: + return None + elif self.BLENDER_MODEL == self: + return path.abspath(self._generate_baked_textures()) + elif self.FILEPATH == self: + if not value or not path.isdir(value): + raise ValueError( + f"Value '{value}' is an invalid path to a directory with " + "textures." + ) + return path.abspath(value) + elif self.ONLINE == self: + return path.abspath(self._pull_online_textures(value)) + else: + raise ValueError(f"Texture source '{self}' is not supported.") + + def is_enabled(self) -> bool: + """ + Returns true if textures are enabled. + """ + + return not self.NONE == self + + @classmethod + def from_str(cls, source_str: str) -> sdf_model_exporter.TextureSource: + """ + Return TextureSource that corresponds with a matched `source_str` string. + """ + + source_str = source_str.strip().upper() + if not source_str or "NONE" in source_str: + return cls.NONE + elif "BLENDER" in source_str: + return cls.BLENDER_MODEL + elif "PATH" in source_str: + return cls.FILEPATH + elif "ONLINE" in source_str: + return cls.ONLINE + else: + raise ValueError(f"Unknown '{source_str}' texture source.") + + @classmethod + def default(cls) -> sdf_model_exporter.TextureSource: + """ + Return the default texture source. + """ + + return cls.from_str(TEXTURE_SOURCE_MODE) + + def _generate_baked_textures( + cls, + ) -> str: + """ + Bake PBR textures for the model and return a path to a directory that + contains them. + """ + + # TODO[feature]: Implement baking of textures from Blender materials + return NotImplementedError("Baking of textures is not yet implemented!") + + def _pull_online_textures( + cls, + value: Optional[Any] = None, + ) -> str: + """ + Get PBR textures from an online source. + """ + + # TODO[feature]: Add option for pulling PBR textures from an online source + return NotImplementedError( + "Getting textures from an online source is not yet implemented!" + ) + + @enum.unique + class InertialEstimator(enum.Enum): + """ + Helper enum for estimating inertial properties of a model. + """ + + ## Modes of estimation + NONE = enum.auto() + DENSITY = enum.auto() + RANDOM_DENSITY = enum.auto() + MASS = enum.auto() + RANDOM_MASS = enum.auto() + + def estimate_inertial_properties( + self, + analysed_mesh_filepath: str, + value: List[float], + ) -> Dict[ + str, + Union[ + float, + Tuple[float, float, float], + Tuple[ + Tuple[float, float, float], + Tuple[float, float, float], + Tuple[float, float, float], + ], + ], + ]: + """ + Estimate inertial properties of the mesh assuming uniform density. + """ + + # Try to import trimesh or try to install it within the Python environment + # Note: This step might throw an exception if it is not possible + # TODO[enhancement]: Add other methods for estimating inertial properties + self._try_install_trimesh() + import trimesh + + # Load the mesh + mesh = trimesh.load( + analysed_mesh_filepath, force="mesh", ignore_materials=True + ) + + # Extract or sample a floating point value from the input + value = self.sample_value(value) + + # Set the density (either via density or mass) + if self.DENSITY == self or self.RANDOM_DENSITY == self: + mesh.density = value + elif self.MASS == self or self.RANDOM_MASS == self: + mesh.density = value / mesh.volume + else: + raise ValueError( + f"Mode for estimation of inertial properties '{self}' is not " + "supported." + ) + + return { + "mass": mesh.mass, + "inertia": mesh.moment_inertia, + "centre_of_mass": mesh.center_mass, + } + + def sample_value(self, value: Optional[List[float]] = None) -> Optional[float]: + """ + Extract or sample a value that should be used when estimating inertial + properties. + """ + + if self.NONE == self: + return None + elif self.DENSITY == self or self.MASS == self: + if not value or (isinstance(value, Iterable) and len(value) != 1): + raise ValueError( + "Exactly a single value must be provided when estimating " + "inertial properties with either target density of mass." + ) + return value[0] if isinstance(value, Iterable) else value + elif self.RANDOM_DENSITY == self or self.RANDOM_MASS == self: + if not value or (isinstance(value, Iterable) and len(value) != 2): + raise ValueError( + "A range with two values (MIN and MAX) must be provided when " + "sampling a random density of mass during estimation of " + "inertial properties." + ) + return random.uniform(value[0], value[1]) + else: + raise ValueError( + f"Mode for estimation of inertial properties '{self}' is not " + "supported." + ) + + def is_enabled(self) -> bool: + """ + Returns true if estimation of inertial properties is enabled. + """ + + return not self.NONE == self + + @classmethod + def from_str(cls, source_str: str) -> sdf_model_exporter.InertialEstimator: + """ + Return InertialEstimator that corresponds with a matched `source_str` + string. + """ + + source_str = source_str.strip().upper() + if not source_str or "NONE" in source_str: + return cls.NONE + elif "RANDOM" in source_str: + if "DENSITY" in source_str: + return cls.RANDOM_DENSITY + elif "MASS" in source_str: + return cls.RANDOM_MASS + elif "DENSITY" in source_str: + return cls.DENSITY + elif "MASS" in source_str: + return cls.MASS + else: + raise ValueError( + f"Unknown '{source_str}' mode for estimation of inertial " + "properties." + ) + + @classmethod + def default(cls) -> sdf_model_exporter.InertialEstimator: + """ + Return the default mode for estimating inertial properties. + """ + + return cls.from_str(INERTIAL_ESTIMATION_MODE) + + @classmethod + def _try_install_trimesh(cls): + """ + Return the default mode for estimating inertial properties. + """ + + try: + import trimesh + except ImportError as err: + import site + import subprocess + + cls._print_bpy( + "Warn: Python module 'trimesh' could not found! This module is " + "necessary to estimate inertial properties of objects. Attempting " + "to install the module automatically via 'pip'...", + file=sys.stderr, + ) + try: + subprocess.check_call([sys.executable, "-m", "ensurepip", "--user"]) + subprocess.check_call( + [ + sys.executable, + "-m", + "pip", + "install", + "--upgrade", + "trimesh", + "pycollada", + "--target", + str(site.getsitepackages()[0]), + ] + ) + import trimesh + except subprocess.CalledProcessError as err: + err_msg = ( + "Python module 'trimesh' cannot be installed automatically! To " + "enable estimation of inertial properties, please install the " + "module manually (within Blender's Python environment) or use " + "the Python environment of your system (by passing Blender " + "option `--python-use-system-env`). Alternatively, you can " + "disable the estimation of inertial properties via script " + "argument `--inertial-estimation-mode none`." + ) + cls._print_bpy( + f"Err: {err_msg}", + file=sys.stderr, + ) + raise ImportError(err_msg) from err + + @classmethod + def export( + cls, + output_dir: Optional[str] = OUTPUT_DIR, + model_version: Optional[int] = MODEL_VERSION, + model_name_prefix: str = "", + model_name_suffix: str = "", + filetype_visual: Union[ExportFormat, str] = ExportFormat.default_visual(), + filetype_collision: Union[ExportFormat, str] = ExportFormat.default_collision(), + detail_level_visual: int = DETAIL_LEVEL_VISUAL, + detail_level_collision: int = DETAIL_LEVEL_COLLISION, + ignore_objects_visual: List[str] = IGNORE_OBJECTS_VISUAL, + ignore_objects_collision: List[str] = IGNORE_OBJECTS_COLLISION, + symlink_external_textures: bool = SYMLINK_EXTERNAL_TEXTURES, + texture_source_mode: Union[TextureSource, str] = TextureSource.default(), + texture_source_value: Optional[str] = TEXTURE_SOURCE_VALUE, + material_texture_diffuse: Optional[ + Tuple[float, float, float] + ] = MATERIAL_TEXTURE_DIFFUSE, + material_texture_specular: Optional[ + Tuple[float, float, float] + ] = MATERIAL_TEXTURE_SPECULAR, + static: bool = STATIC, + inertial_estimation_mode: Union[ + InertialEstimator, str + ] = InertialEstimator.default(), + inertial_estimation_value: Optional[List[float]] = INERTIAL_ESTIMATION_VALUE, + inertial_estimation_use_collision_mesh: bool = True, + friction_coefficient: Optional[ + Union[float, Tuple[float, float]] + ] = FRICTION_COEFFICIENT, + generate_thumbnails: bool = True, + **kwargs, + ): + """ + The primary function enables exporting of a single SDF model. + """ + + # Store the list of originally selected objects + selected_objects_original = bpy.context.selected_objects + # Create a list of objects to process + if selected_objects_original: + # Use currently selected objects if any is selected + objects_to_process = selected_objects_original + else: + # Otherwise, use all objects if nothing is selected + objects_to_process = bpy.context.selectable_objects + + # Separate different object types to process them differently + # Note: Not all types are currently supported by this script + # TODO[feature]: Support exporting of cameras and lights as SDF entities + meshes_to_process = cameras_to_process = lights_to_process = [] + for obj in objects_to_process: + if obj.type == "MESH": + meshes_to_process.append(obj) + cls._print_bpy( + f"Info: Processing mesh '{obj.name}'...", + ) + # elif obj.type == "CAMERA": + # cameras_to_process.append(obj) + # cls._print_bpy( + # f"Info: Processing camera '{obj.name}'...", + # ) + # elif obj.type == "LIGHT": + # lights_to_process.append(obj) + # cls._print_bpy( + # f"Info: Processing light '{obj.name}'...", + # ) + else: + cls._print_bpy( + f"Warn: Blender object '{obj.name}' with type '{obj.type}' will " + "not be processed.", + file=sys.stderr, + ) + + # Determine name of the exported model + if len(meshes_to_process) == 0: + raise EnvironmentError("Blender scene has no mesh models to export.") + elif len(meshes_to_process) == 1: + # Use object name as the model name if there is only one + model_name = meshes_to_process[0].name + else: + # Use the project name as a joint model name if there are multiple meshes + model_name = bpy.path.basename(bpy.data.filepath).split(".")[0] + # Add prefix and suffix if desired + model_name = f"{model_name_prefix}{model_name}{model_name_suffix}" + + # If output directory is not set (None), use the default Fuel model path + if output_dir is None: + output_dir = path.join( + os.environ.get( + "GZ_FUEL_CACHE_PATH", + default=path.join(path.expanduser("~"), ".gazebo", "fuel"), + ), + "fuel.gazebosim.org", + os.getlogin(), + "models", + ) + # Fuel requires model versioning, therefore, default to the next available + # version if the model already exists (begins with version 1) + if model_version is None: + model_version = -1 + + # Get the absolute path and create the directory if it does not already exist + output_dir = path.abspath(output_dir) + os.makedirs(name=output_dir, exist_ok=True) + + # Get a versioned model path (if desired) + output_path = cls._try_get_versioned_model_path( + output_dir=output_dir, + model_name=model_name, + model_version=model_version, + ) + + # Store all data necessary for SDF creation inside a dictionary + sdf_data = {} + + # Process and export meshes + exported_meshes = cls._process_meshes( + meshes_to_process=meshes_to_process, + output_path=output_path, + model_name=model_name, + filetype_visual=filetype_visual, + filetype_collision=filetype_collision, + detail_level_visual=detail_level_visual, + detail_level_collision=detail_level_collision, + ignore_objects_visual=ignore_objects_visual, + ignore_objects_collision=ignore_objects_collision, + ) + sdf_data.update(exported_meshes) + + # Sample textures + texture_source = ( + texture_source_mode + if isinstance(texture_source_mode, cls.TextureSource) + else cls.TextureSource.from_str(texture_source_mode) + ) + if texture_source.is_enabled(): + textures_dirpath = texture_source.get_path(texture_source_value) + textures = cls._sample_textures(textures_dirpath=textures_dirpath) + sdf_data.update(textures) + + # Estimate inertial properties (if enabled) + if not static: + inertial_estimator = ( + inertial_estimation_mode + if isinstance(inertial_estimation_mode, cls.InertialEstimator) + else cls.InertialEstimator.from_str(inertial_estimation_mode) + ) + if inertial_estimator.is_enabled(): + analysis_mesh_filepath = path.join( + output_path, + exported_meshes["filepath_mesh_collision"] + if inertial_estimation_use_collision_mesh + else exported_meshes["filepath_mesh_visual"], + ) + inertial_properties = inertial_estimator.estimate_inertial_properties( + analysed_mesh_filepath=analysis_mesh_filepath, + value=inertial_estimation_value, + ) + sdf_data.update(inertial_properties) + + # Write data into an SDF file + cls._generate_sdf_file( + output_path=output_path, + model_name=model_name, + static=static, + friction_coefficient=friction_coefficient, + symlink_external_textures=symlink_external_textures, + material_texture_diffuse=material_texture_diffuse, + material_texture_specular=material_texture_specular, + **sdf_data, + ) + + # Create a corresponding config file for the SDF model + cls._generate_model_config_file(output_path=output_path, model_name=model_name) + + # Render few images to generate thumbnails + if not bpy.app.background and generate_thumbnails: + cls._generate_thumbnails(output_path=output_path) + + cls._print_bpy( + f"Info: Model '{model_name}' exported to 'file://{output_path}'." + ) + + # Select the original objects again to keep the UI (almost) the same + bpy.ops.object.select_all(action="DESELECT") + # Select all desired meshes at the same time + for obj in selected_objects_original: + obj.select_set(True) + + def _print_bpy(msg: Any, file: Optional[TextIO] = sys.stdout, *args, **kwargs): + """ + Helper print function that also provides output inside the Blender console, + in addition to the system console. + """ + + print(msg, file=file, *args, **kwargs) + for window in bpy.context.window_manager.windows: + for area in window.screen.areas: + if area.type == "CONSOLE": + with bpy.context.temp_override( + window=window, screen=window.screen, area=area + ): + bpy.ops.console.scrollback_append( + text=str(msg), + type="ERROR" if file == sys.stderr else "OUTPUT", + ) + + @classmethod + def _process_meshes( + cls, + meshes_to_process: List, + output_path: str, + model_name: str, + filetype_visual: Union[ExportFormat, str], + filetype_collision: Union[ExportFormat, str], + detail_level_visual: int, + detail_level_collision: int, + ignore_objects_visual: List[str], + ignore_objects_collision: List[str], + ) -> Dict[str, str]: + """ + Process and export meshes of the model. + """ + + # Convert to Enum if strings were passed + if isinstance(filetype_visual, str): + filetype_visual = cls.ExportFormat.from_str(filetype_visual) + if isinstance(filetype_collision, str): + filetype_collision = cls.ExportFormat.from_str(filetype_collision) + + # Keep only object names that need processing in the ignore list + meshes_to_process_names = [mesh.name for mesh in meshes_to_process] + ignore_objects_visual = [ + name for name in ignore_objects_visual if name in meshes_to_process_names + ] + ignore_objects_collision = [ + name for name in ignore_objects_collision if name in meshes_to_process_names + ] + + # Deselect all objects + bpy.ops.object.select_all(action="DESELECT") + # Select all desired meshes at the same time + for obj in meshes_to_process: + obj.select_set(True) + + return cls._export_geometry( + output_path=output_path, + model_name=model_name, + filetype_visual=filetype_visual, + filetype_collision=filetype_collision, + detail_level_visual=detail_level_visual, + detail_level_collision=detail_level_collision, + ignore_objects_visual=ignore_objects_visual, + ignore_objects_collision=ignore_objects_collision, + ) + + @classmethod + def _export_geometry( + cls, + output_path: str, + model_name: str, + filetype_visual: ExportFormat, + filetype_collision: ExportFormat, + detail_level_visual: int, + detail_level_collision: int, + ignore_objects_visual: List[str], + ignore_objects_collision: List[str], + ) -> Dict[str, str]: + """ + Export both visual and collision mesh geometry. + """ + + filepath_collision = cls._export_geometry_collision( + output_path=output_path, + model_name=model_name, + filetype=filetype_collision, + detail_level=detail_level_collision, + ignore_object_names=ignore_objects_collision, + ) + filepath_visual = cls._export_geometry_visual( + output_path=output_path, + model_name=model_name, + filetype=filetype_visual, + detail_level=detail_level_visual, + ignore_object_names=ignore_objects_visual, + ) + + return { + "filepath_mesh_collision": path.relpath( + path=filepath_collision, start=output_path + ), + "filepath_mesh_visual": path.relpath( + path=filepath_visual, start=output_path + ), + } + + @classmethod + def _export_geometry_collision( + cls, + output_path: str, + model_name: str, + filetype: ExportFormat, + detail_level: int, + ignore_object_names: List[str], + ) -> str: + """ + Export collision geometry of the model with the specified `filetype`. + Method `_pre_export_geometry_collision()` is called before the export. + Method `_post_export_geometry_collision()` is called after the export. + """ + + # Hook call before export of collision geometry + cls._pre_export_geometry_collision( + detail_level=detail_level, ignore_object_names=ignore_object_names + ) + + resulting_output_path = filetype.export( + path.join(output_path, cls.DIRNAME_MESHES_COLLISION, model_name) + ) + + # Hook call after export of collision geometry + cls._post_export_geometry_collision(ignore_object_names=ignore_object_names) + + return resulting_output_path + + @classmethod + def _export_geometry_visual( + cls, + output_path: str, + model_name: str, + filetype: ExportFormat, + detail_level: int, + ignore_object_names: List[str], + ) -> str: + """ + Export visual geometry of the model with the specified `filetype`. + Method `_pre_export_geometry_visual()` is called before the export. + Method `_post_export_geometry_visual()` is called after the export. + """ + + # Hook call before export of visual geometry + cls._pre_export_geometry_visual( + detail_level=detail_level, + ignore_object_names=ignore_object_names, + ) + + resulting_output_path = filetype.export( + path.join(output_path, cls.DIRNAME_MESHES_VISUAL, model_name) + ) + + # Hook call after export of visual geometry + cls._post_export_geometry_collision(ignore_object_names=ignore_object_names) + + return resulting_output_path + + @classmethod + def _sample_textures( + cls, textures_dirpath: Optional[str] + ) -> Dict[str, Optional[str]]: + """ + Get PBR textures for the exported model from `textures_dirpath`. If the + directory contains multiple texture sets, it is selected at random. + """ + + # Do not process if the texture directory is None + if not textures_dirpath: + return {} + + # Get the content of the texture directory + textures = os.listdir(textures_dirpath) + + # Determine whether the directory contains multiple sets of textures + choose_sample_random: bool = False + for texture in textures: + if path.isdir(path.join(textures_dirpath, texture)): + choose_sample_random = True + break + + if choose_sample_random: + # Select a random set of PBR textures + texture_dirpath = path.join(textures_dirpath, random.choice(textures)) + else: + # The directory already points to a set of PBR textures + texture_dirpath = textures_dirpath + + # Get the appropriate texture files + texture_albedo: Optional[str] = None + texture_roughness: Optional[str] = None + texture_metalness: Optional[str] = None + texture_normal: Optional[str] = None + for texture in os.listdir(texture_dirpath): + texture_cmp = cls._unify_string(texture) + if not texture_albedo and ( + "color" in texture_cmp or "albedo" in texture_cmp + ): + texture_albedo = path.join(texture_dirpath, texture) + elif not texture_roughness and "roughness" in texture_cmp: + texture_roughness = path.join(texture_dirpath, texture) + elif not texture_metalness and ( + "specular" in texture_cmp or "metalness" in texture_cmp + ): + texture_metalness = path.join(texture_dirpath, texture) + elif not texture_normal and "normal" in texture_cmp: + texture_normal = path.join(texture_dirpath, texture) + else: + cls._print_bpy( + f"Warn: File 'file://{path.join(texture_dirpath, texture)}' is " + "not a recognized texture type or there are multiple textures " + "of the same type inside 'file://{texture_dirpath}'.", + file=sys.stderr, + ) + + return { + "texture_albedo": texture_albedo, + "texture_roughness": texture_roughness, + "texture_metalness": texture_metalness, + "texture_normal": texture_normal, + } + + @classmethod + def _generate_sdf_file( + cls, + output_path: str, + model_name: str, + filepath_mesh_visual: str, + filepath_mesh_collision: str, + texture_albedo: Optional[str] = None, + texture_roughness: Optional[str] = None, + texture_metalness: Optional[str] = None, + texture_normal: Optional[str] = None, + material_texture_diffuse: Optional[ + Tuple[float, float, float] + ] = MATERIAL_TEXTURE_DIFFUSE, + material_texture_specular: Optional[ + Tuple[float, float, float] + ] = MATERIAL_TEXTURE_SPECULAR, + symlink_external_textures: bool = SYMLINK_EXTERNAL_TEXTURES, + static: bool = STATIC, + mass: Optional[float] = None, + inertia: Optional[ + Tuple[ + Tuple[float, float, float], + Tuple[float, float, float], + Tuple[float, float, float], + ] + ] = None, + centre_of_mass: Optional[Tuple[float, float, float]] = None, + friction_coefficient: Optional[ + Union[float, Tuple[float, float]] + ] = FRICTION_COEFFICIENT, + ): + """ + Generate SDF file from passed arguments and export to `output_path`. + """ + + # Initialize SDF with a single model and a link + sdf = ElementTree.Element("sdf", attrib={"version": cls.SDF_VERSION}) + model = ElementTree.SubElement(sdf, "model", attrib={"name": model_name}) + statit_xml = ElementTree.SubElement(model, "static") + statit_xml.text = str(static) + link = ElementTree.SubElement( + model, "link", attrib={"name": f"{model_name}_link"} + ) + + # Visual geometry + visual = ElementTree.SubElement( + link, "visual", attrib={"name": f"{model_name}_visual"} + ) + visual_geometry = ElementTree.SubElement(visual, "geometry") + visual_mesh = ElementTree.SubElement(visual_geometry, "mesh") + visual_mesh_uri = ElementTree.SubElement(visual_mesh, "uri") + visual_mesh_uri.text = filepath_mesh_visual + # Material + textures = ( + texture_albedo, + texture_roughness, + texture_metalness, + texture_normal, + ) + if any(texture for texture in textures): + material = ElementTree.SubElement(visual, "material") + pbr = ElementTree.SubElement(material, "pbr") + metal = ElementTree.SubElement(pbr, "metal") + + texture_albedo, texture_roughness, texture_metalness, texture_normal = ( + cls._preprocess_texture_path( + texture, + output_path=output_path, + symlink_external_textures=symlink_external_textures, + ) + for texture in textures + ) + + if texture_albedo: + diffuse = ElementTree.SubElement(material, "diffuse") + if material_texture_diffuse: + diffuse.text = " ".join(map(str, material_texture_diffuse)) + specular = ElementTree.SubElement(material, "specular") + if material_texture_specular: + specular.text = " ".join(map(str, material_texture_specular)) + albedo_map = ElementTree.SubElement(metal, "albedo_map") + albedo_map.text = texture_albedo + if texture_roughness: + roughness_map = ElementTree.SubElement(metal, "roughness_map") + roughness_map.text = texture_roughness + if texture_metalness: + metalness_map = ElementTree.SubElement(metal, "metalness_map") + metalness_map.text = texture_metalness + if texture_normal: + normal_map = ElementTree.SubElement(metal, "normal_map") + normal_map.text = texture_normal + + # Collision geometry + collision = ElementTree.SubElement( + link, "collision", attrib={"name": f"{model_name}_collision"} + ) + collision_geometry = ElementTree.SubElement(collision, "geometry") + collision_mesh = ElementTree.SubElement(collision_geometry, "mesh") + collision_mesh_uri = ElementTree.SubElement(collision_mesh, "uri") + collision_mesh_uri.text = filepath_mesh_collision + # Surface friction + surface = ElementTree.SubElement(collision, "surface") + surface_friction = ElementTree.SubElement(surface, "friction") + ode_friction = ElementTree.SubElement(surface_friction, "ode") + ode_friction_mu = ElementTree.SubElement(ode_friction, "mu") + ode_friction_mu2 = ElementTree.SubElement(ode_friction, "mu2") + if isinstance(friction_coefficient, Iterable): + if len(friction_coefficient) == 2: + # Randomize friction coefficient if a range is passed + friction_coefficient = random.uniform( + friction_coefficient[0], friction_coefficient[1] + ) + else: + friction_coefficient = friction_coefficient[0] + + ode_friction_mu.text = ode_friction_mu2.text = str(friction_coefficient) + bullet_friction = ElementTree.SubElement(surface_friction, "bullet") + bullet_friction_coef = ElementTree.SubElement(bullet_friction, "friction") + bullet_friction_coef2 = ElementTree.SubElement(bullet_friction, "friction2") + bullet_friction_coef.text = bullet_friction_coef2.text = str( + friction_coefficient + ) + + # Inertial + if not static and ( + centre_of_mass is not None and mass is not None and inertia is not None + ): + inertial = ElementTree.SubElement(link, "inertial") + pose = ElementTree.SubElement(inertial, "pose") + pose.text = f"{' '.join(map(str, centre_of_mass))} 0.0 0.0 0.0" + mass_xml = ElementTree.SubElement(inertial, "mass") + mass_xml.text = str(mass) + inertia_xml = ElementTree.SubElement(inertial, "inertia") + inertia_xx = ElementTree.SubElement(inertia_xml, "ixx") + inertia_xx.text = str(inertia[0][0]) + inertia_xy = ElementTree.SubElement(inertia_xml, "ixy") + inertia_xy.text = str(inertia[0][1]) + inertia_xz = ElementTree.SubElement(inertia_xml, "ixz") + inertia_xz.text = str(inertia[0][2]) + inertia_yy = ElementTree.SubElement(inertia_xml, "iyy") + inertia_yy.text = str(inertia[1][1]) + inertia_yz = ElementTree.SubElement(inertia_xml, "iyz") + inertia_yz.text = str(inertia[1][2]) + inertia_zz = ElementTree.SubElement(inertia_xml, "izz") + inertia_zz.text = str(inertia[2][2]) + + # Convert SDF to xml string and write to file + sdf_xml_string = minidom.parseString( + ElementTree.tostring(sdf, encoding="unicode") + ).toprettyxml(indent=" ") + sdf_file = open(path.join(output_path, cls.BASENAME_SDF), "w") + sdf_file.write(sdf_xml_string) + sdf_file.close() + + @classmethod + def _generate_model_config_file( + cls, + output_path: str, + model_name: str, + ): + """ + Generate model config for the SDF model. + """ + + # Initialize model config with its corresponding name + model_config = ElementTree.Element("model") + name = ElementTree.SubElement(model_config, "name") + name.text = model_name + + # Version of the model (try to match version from the exported path) + maybe_version = path.basename(output_path) + if maybe_version.isnumeric(): + version = ElementTree.SubElement(model_config, "version") + version.text = maybe_version + + # Path to SDF + sdf_tag = ElementTree.SubElement( + model_config, "sdf", attrib={"version": cls.SDF_VERSION} + ) + sdf_tag.text = cls.BASENAME_SDF + + # Author name is based on ${USER} + author = ElementTree.SubElement(model_config, "author") + name = ElementTree.SubElement(author, "name") + name.text = os.getlogin() + # Keep track of Blender version that produced the model + producer = ElementTree.SubElement(author, "producer") + producer.text = f"Blender {bpy.app.version_string}" + + # Describe how the model was generated + description = ElementTree.SubElement(model_config, "description") + description.text = ( + f"Model generated from '{bpy.path.basename(bpy.data.filepath)}' by " + f"'{path.relpath(path=__file__, start=bpy.data.filepath)}' Python script" + ) + + # Convert config to xml string and write to file + model_config_xml_string = minidom.parseString( + ElementTree.tostring(model_config, encoding="unicode") + ).toprettyxml(indent=" ") + model_config_file = open( + path.join(output_path, cls.BASENAME_SDF_MODEL_CONFIG), "w" + ) + model_config_file.write(model_config_xml_string) + model_config_file.close() + + @classmethod + def _generate_thumbnails(cls, output_path: str): + """ + Render thumbnails for the SDF model. + Currently, only a single viewport render is created using OpenGL. + """ + + # Create thumbnails directory for the model + thumbnails_dir = path.join(output_path, cls.DIRNAME_THUMBNAILS) + os.makedirs(name=thumbnails_dir, exist_ok=True) + + # Specify path for the thumbnail + bpy.context.scene.render.filepath = path.join(thumbnails_dir, "0") + + # Set render parameters + bpy.context.scene.render.resolution_x = 256 + bpy.context.scene.render.resolution_y = 256 + bpy.context.scene.render.pixel_aspect_x = 1.0 + bpy.context.scene.render.pixel_aspect_x = 1.0 + + # Render image through viewport + bpy.ops.render.opengl(write_still=True) + + @classmethod + def _pre_export_geometry_collision( + cls, detail_level: int, ignore_object_names: List[str] = [] + ): + """ + A hook that is called before exporting collision geometry. Always chain up the + parent implementation. + By default, this hook handles reselecting objects from `ignore_object_names`. + """ + + cls._select_objects(names=ignore_object_names, type_filter="MESH", select=False) + + @classmethod + def _post_export_geometry_collision(cls, ignore_object_names: List[str] = []): + """ + A hook that is called after exporting collision geometry. Always chain up the + parent implementation. + By default, this hook handles deselecting objects from `ignore_object_names`. + """ + + cls._select_objects(names=ignore_object_names, type_filter="MESH", select=True) + + @classmethod + def _pre_export_geometry_visual( + cls, + detail_level: int, + ignore_object_names: List[str] = [], + ): + """ + A hook that is called before exporting visual geometry. Always chain up the + parent implementation. + By default, this hook handles reselecting objects from `ignore_object_names`. + """ + + cls._select_objects(names=ignore_object_names, type_filter="MESH", select=False) + + @classmethod + def _post_export_geometry_visual(cls, ignore_object_names: List[str] = []): + """ + A hook that is called after exporting visual geometry. Always chain up the + parent implementation. + By default, this hook handles deselecting objects from `ignore_object_names`. + """ + + cls._select_objects(names=ignore_object_names, type_filter="MESH", select=True) + + def _select_objects( + names=List[str], type_filter: Optional[str] = None, select: bool = True + ): + """ + (De)select list of objects based on their `names`. List can be filtered + according to the object type via `type_filter`. + """ + + for obj in bpy.context.selectable_objects: + if type_filter and obj.type != type_filter: + continue + if obj.name in names: + obj.select_set(select) + + def _unify_string( + string: str, + chars_to_remove: Union[str, Iterable[str]] = ( + " ", + "_", + "-", + "(", + ")", + "[", + "]", + "{", + "}", + ), + lowercase: bool = True, + ) -> str: + """ + Helper function unifies string for a more robust matching. The strings is + changed to lower-case and `chars_to_remove` are removed. + """ + + string = string.strip() + for char in chars_to_remove: + string = string.replace(char, "") + if lowercase: + return string.lower() + else: + return string.upper() + + @classmethod + def _preprocess_texture_path( + cls, + texture_original_filepath: Optional[str], + output_path: str, + symlink_external_textures: bool, + ): + """ + Preprocess filepath of a texture such that it is in the local model directory + path. If `symlink_external_textures` is enabled, symbolic links will be + created. No copy or symlink will be made if the `texture_original_filepath` is + already a subpath of `output_path`. + This can fail due to the lack of filesystem permissions. + """ + + # Skip processing of unset textures + if not texture_original_filepath: + return None + + # Make sure the texture is valid + if not path.exists(texture_original_filepath): + raise ValueError( + f"Texture 'file://{texture_original_filepath}' does not exist!" + ) + + # Copy over the texture inside the model directory, or create a symbolic link + # Only do this if the texture is not already under the export directory + if texture_original_filepath.startswith(output_path): + texture_target_filepath = texture_original_filepath + else: + texture_dir = path.join(output_path, cls.DIRNAME_TEXTURES) + texture_target_filepath = path.join( + texture_dir, path.basename(texture_original_filepath) + ) + os.makedirs(name=texture_dir, exist_ok=True) + if symlink_external_textures: + try: + os.symlink( + src=texture_original_filepath, dst=texture_target_filepath + ) + except OSError as err: + import errno + + if err.errno == errno.EEXIST: + os.remove(texture_target_filepath) + os.symlink( + src=texture_original_filepath, dst=texture_target_filepath + ) + else: + raise err + else: + shutil.copy(src=texture_original_filepath, dst=texture_target_filepath) + + return path.relpath(path=texture_target_filepath, start=output_path) + + @classmethod + def _try_get_versioned_model_path( + cls, output_dir: str, model_name: str, model_version: Optional[int] + ) -> str: + """ + Return versioned model directory path if `model_version` is specified. For + negative `model_version` and an existing model directory, the next version will + be used to avoid overwriting. + """ + + unversioned_model_path = path.join(output_dir, model_name) + + if model_version is None: + return unversioned_model_path + elif model_version < 0: + return path.join( + unversioned_model_path, + str(cls._get_next_model_version(model_path=unversioned_model_path)), + ) + else: + return path.join(unversioned_model_path, model_version) + + def _get_next_model_version(model_path: str) -> int: + """ + Return the next version if model already exists. Otherwise, return '1' as the + initial (first) version. + """ + + if path.exists(model_path): + last_version = max( + [ + int(path.basename(subdir)) + for subdir in os.scandir(model_path) + if subdir.is_dir() and path.basename(subdir).isnumeric() + ] + ) + return last_version + 1 + else: + return 1 + + +class procedural_dataset_generator(sdf_model_exporter): + """ + Generator of procedural datasets using Blender's Geometry Nodes. + """ + + # The following lookup phrases are used to find the corresponding input attributes + # of the node system (exact match, insensitive to case, insensitive to '_'/'-'/...) + LOOKUP_PHRASES_RANDOM_SEED: List[str] = [ + "rng", + "seed", + "randomseed", + "pseodorandomseed", + ] + LOOKUP_PHRASES_DETAIL_LEVEL: List[str] = [ + "detail", + "detaillevel", + "detailobject", + "levelofdetail", + "subdivisionlevel", + "subdivlevel", + ] + + @classmethod + def generate( + cls, + first_seed: int = FIRST_SEED, + number_of_variants: int = NUMBER_OF_VARIANTS, + redraw_viewport_during_processing: bool = True, + **kwargs, + ): + """ + Generate `number_of_variants` different models by changing the random seed in + the Geometry Nodes system of the individual meshes. + """ + + cls._print_bpy( + f"Info: Generating {number_of_variants} model variants in the seed range " + f"[{first_seed}:{first_seed + number_of_variants}]." + ) + + # Export models for the entire range of random seeds + global current_seed + for seed in range(first_seed, first_seed + number_of_variants): + current_seed = seed + random.seed(seed) + name_suffix = str(seed) + if "model_name_suffix" in kwargs: + name_suffix = f'{kwargs.pop("model_name_suffix")}{name_suffix}' + cls.export(model_name_suffix=name_suffix, **kwargs) + + # Update the viewport to keep track of progress (only if GUI is enabled) + # Performance might be lowered because the scene needs to be re-rendered + if not bpy.app.background and redraw_viewport_during_processing: + bpy.ops.wm.redraw_timer(type="DRAW_WIN_SWAP", iterations=1) + + @classmethod + def _pre_export_geometry_collision( + cls, detail_level: int, ignore_object_names: List[str] = [] + ): + """ + A hook that is called before exporting collision geometry. This implementation + adjusts input attributes of the Geometry Nodes system for each mesh. + """ + + # Call parent impl + sdf_model_exporter._pre_export_geometry_collision( + detail_level=detail_level, + ignore_object_names=ignore_object_names, + ) + + global current_seed + selected_meshes = bpy.context.selected_objects + for obj in selected_meshes: + for nodes_modifier in cls._get_all_nodes_modifiers(obj): + cls._try_set_nodes_input_attribute( + obj, + nodes_modifier, + cls.LOOKUP_PHRASES_RANDOM_SEED, + current_seed, + print_warning=True, + ) + cls._try_set_nodes_input_attribute( + obj, + nodes_modifier, + cls.LOOKUP_PHRASES_DETAIL_LEVEL, + detail_level, + ) + cls._trigger_modifier_update(obj) + + @classmethod + def _pre_export_geometry_visual( + cls, + detail_level: int, + ignore_object_names: List[str] = [], + ): + """ + A hook that is called before exporting visual geometry. This implementation + adjusts input attributes of the Geometry Nodes system for each mesh. + """ + + # Call parent impl + sdf_model_exporter._pre_export_geometry_visual( + detail_level=detail_level, + ignore_object_names=ignore_object_names, + ) + + global current_seed + selected_meshes = bpy.context.selected_objects + for obj in selected_meshes: + for nodes_modifier in cls._get_all_nodes_modifiers(obj): + cls._try_set_nodes_input_attribute( + obj, + nodes_modifier, + cls.LOOKUP_PHRASES_RANDOM_SEED, + current_seed, + print_warning=True, + ) + cls._try_set_nodes_input_attribute( + obj, + nodes_modifier, + cls.LOOKUP_PHRASES_DETAIL_LEVEL, + detail_level, + ) + + cls._trigger_modifier_update(obj) + + def _get_all_nodes_modifiers(obj: bpy.types.Object) -> List[bpy.types.Modifier]: + """ + Return all node-based modifiers of an object. + """ + + return [modifier for modifier in obj.modifiers if modifier.type == "NODES"] + + @classmethod + def _try_set_nodes_input_attribute( + cls, + obj: bpy.types.Object, + modifier: bpy.types.NodesModifier, + lookup_phrases: Iterable[str], + value: Any, + print_warning: bool = False, + ): + """ + Try to set an input attribute of a nodes system to a `value`. The attribute + looked is performed by using `lookup_phrases`. + """ + + # Try to find the corresponding ID of the input attribute + input_id: Optional[str] = None + for attribute in modifier.node_group.inputs: + if cls._unify_string(attribute.name) in lookup_phrases: + input_id = attribute.identifier + break + if input_id is None: + if print_warning: + cls._print_bpy( + "Warn: Unable to find a matching input attribute of the object's " + f"'{obj.name}' modifier '{modifier.name}' for any of the requested " + f"lookup phrases {lookup_phrases}. You can ignore this warning if " + "the modifier is not supposed to have the requested input.", + file=sys.stderr, + ) + return + + # Set the attribute + modifier[input_id] = value + + def _trigger_modifier_update(obj: bpy.types.Object): + """ + Trigger an update of object's modifiers after changing its attributes. + """ + + # Not sure how else to trigger update of the modifiers, but setting the index + # of any modifier does the trick (even if the index stays the same) + # TODO[enhancement]: Improve updating of modifiers after programmatic changes + bpy.context.view_layer.objects.active = obj + if len(obj.modifiers.values()): + bpy.ops.object.modifier_move_to_index( + modifier=obj.modifiers.values()[0].name, + index=0, + ) + + +def main(**kwargs): + + # Warn the user in case an untested version of Blender is used + if bpy.app.version[0] != LAST_WORKING_VERSION[0]: + sdf_model_exporter._print_bpy( + f"Err: Untested major version of Blender ({bpy.app.version_string})! " + "This script will likely fail. Please, use Blender version " + f"[~{LAST_WORKING_VERSION[0]}.{LAST_WORKING_VERSION[1]}].", + file=sys.stderr, + ) + elif bpy.app.version[1] < LAST_WORKING_VERSION[1]: + sdf_model_exporter._print_bpy( + f"Warn: Untested minor version of Blender ({bpy.app.version_string})! " + "This script might not work as intended. Please, consider using Blender " + f"version [~{LAST_WORKING_VERSION[0]}.{LAST_WORKING_VERSION[1]}].", + file=sys.stderr, + ) + + # Update default keyword arguments with parsed arguments + export_kwargs = DEFAULT_KWARGS + export_kwargs.update(kwargs) + + if export_kwargs.pop("export_dataset"): + # Generate a dataset of procedural models + procedural_dataset_generator.generate(**export_kwargs) + sdf_model_exporter._print_bpy( + f'Info: A dataset with {export_kwargs["number_of_variants"]} models was ' + "exported." + ) + else: + # Export a single SDF model + sdf_model_exporter.export(**export_kwargs) + sdf_model_exporter._print_bpy("Info: A single SDF models was exported.") + + # Inform user how to make the models discoverable by Gazebo + if export_kwargs["output_dir"] is not None: + output_dir = path.abspath(export_kwargs["output_dir"]) + sdf_model_exporter._print_bpy( + "Info: Please, set GZ_SIM_RESOURCE_PATH environment variable to make the " + "exported models discoverable." + f'\n\texport GZ_SIM_RESOURCE_PATH="{output_dir}' + '${GZ_SIM_RESOURCE_PATH:+:${GZ_SIM_RESOURCE_PATH}}"', + ) + + +if __name__ == "__main__": + + # Setup argument parser + parser = argparse.ArgumentParser( + description="Generate a procedural dataset of SDF models using Blender.", + usage=( + f"\n\t{sys.argv[0]} [blender options] file.blend --python-text " + "script.py -- [script options]" + f"\n\t{sys.argv[0]} [blender options] file.blend --python " + "external_script.py -- [script options]" + "\nlist script options:" + f"\n\t{sys.argv[0]} -b file.blend --python-text script.py -- -h" + f"\n\t{sys.argv[0]} -b file.blend --python external_script.py -- -h" + "\nlist blender options:" + f"\n\t{sys.argv[0]} -h" + ), + epilog=f"Default keyword arguments of the script (model): {DEFAULT_KWARGS}" + if DEFAULT_KWARGS + else "", + argument_default=argparse.SUPPRESS, + formatter_class=argparse.ArgumentDefaultsHelpFormatter, + ) + + # Append example to usage (with the specific internal/external script) + if "--python-text" in sys.argv and bpy.data.filepath: + blend_relpath = path.relpath(path=bpy.data.filepath, start=os.getcwd()) + py_relpath = path.relpath(path=__file__, start=bpy.data.filepath) + parser.usage += ( + f"\nexample:\n\t{sys.argv[0]} {blend_relpath} --python-text {py_relpath} " + f"-- -o {OUTPUT_DIR}" + ) + else: + py_relpath = path.relpath(path=__file__, start=os.getcwd()) + parser.usage += ( + f"\nexample:\n\t{sys.argv[0]} file.blend --python {py_relpath} " + f"-- -o {OUTPUT_DIR}" + ) + + # Exit if opened without a Blender project + if not bpy.data.filepath: + print( + "Err: Blender project was not opened before running the script.", + file=sys.stderr, + ) + parser.print_usage() + + sys.exit(22) + + ### Specify all CLI arguments + ## Helper argparse types + def str2bool(value: Union[str, bool]) -> bool: + """ + Convert logical string to boolean. Can be used as argparse type. + """ + + if isinstance(value, bool): + return value + if value.lower() in ("yes", "true", "t", "y", "1"): + return True + elif value.lower() in ("no", "false", "f", "n", "0"): + return False + else: + raise argparse.ArgumentTypeError("Boolean value expected.") + + def str_empty2none(value: Optional[str]) -> Optional[str]: + """ + If string is empty, convert to None. Can be used as argparse type. + """ + + return str(value) if value else None + + ## Command mode of the script + parser.add_argument( + "--export-dataset", + action="store_true", + default=True, + help="[default mode] Generate a procedural dataset.", + ) + parser.add_argument( + "--export-model", + dest="export_dataset", + action="store_false", + help="[alternative mode] Export a single model.", + ) + ## Parameters for SDF model exporter `sdf_model_exporter` + parser.add_argument( + "-o", + "--output-dir", + type=str_empty2none, + default=OUTPUT_DIR, + help="The output directory for all models (each model is located under its own " + "subdirectory). When exporting a single SDF model, its output path is " + "'OUTPUT_DIR/MODEL_NAME'. For datasets, the path of each SDF model name is " + "appended by the random seed used during its generation as " + "'OUTPUT_DIR/MODEL_NAME+VARIANT_SEED'. If set to empty, Fuel cache " + "'${GZ_FUEL_CACHE_PATH}/fuel.gazebosim.org/${USER}/models' is used.", + ) + parser.add_argument( + "-v", + "--model-version", + type=int, + default=MODEL_VERSION, + help="The version of exported model path that is joined with the model output " + "path 'OUTPUT_DIR/MODEL_NAME/MODEL_VERSION', or " + "'OUTPUT_DIR/MODEL_NAME+VARIANT_SEED/MODEL_VERSION'. The output path is " + "modified only if 'MODEL_VERSION' is set (not None). For negative values " + "and an existing model directory, the next unique version is used to avoid " + "overwriting. If 'OUTPUT_DIR' is empty (export to Fuel cache), a negative " + "value is used to guarantee a unique version.", + ) + parser.add_argument( + "--model-name-prefix", + type=str, + help="Prefix of exported model as 'OUTPUT_DIR/MODEL_NAME_PREFIX+MODEL_NAME' " + ", or 'OUTPUT_DIR/MODEL_NAME_PREFIX+MODEL_NAME+VARIANT_SEED' (default: '').", + ) + parser.add_argument( + "--model-name-suffix", + type=str, + help="Suffix of exported model as 'OUTPUT_DIR/MODEL_NAME+MODEL_NAME_SUFFIX' " + ", or 'OUTPUT_DIR/MODEL_NAME+MODEL_NAME_SUFFIX+VARIANT_SEED' (default: '').", + ) + ## Parameters for procedural dataset generator `procedural_dataset_generator` + parser.add_argument( + "-s", + "--first-seed", + type=int, + default=FIRST_SEED, + help="The random seed of the first model when generating a dataset.", + ) + parser.add_argument( + "-n", + "--number-of-variants", + type=int, + default=NUMBER_OF_VARIANTS, + help="Number of model variants to export when generating a dataset.", + ) + ## Filetypes of exported geometry + parser.add_argument( + "--filetype-visual", + type=str, + default=FILETYPE_VISUAL, + choices=["collada", "dae", "wavefront", "obj", "stl"], + help="The format of exported visual geometry ['collada' == 'dae', " + "'wavefront' == 'obj'].", + ) + parser.add_argument( + "--filetype-collision", + type=str, + default=FILETYPE_COLLISION, + choices=["collada", "dae", "wavefront", "obj", "stl"], + help="The format of exported collision geometry ['collada' == 'dae', " + "'wavefront' == 'obj'].", + ) + ## Level of detail for exported visual/collision geometry, e.g. subdivision level + parser.add_argument( + "--detail-level-visual", + type=int, + default=DETAIL_LEVEL_VISUAL, + help="Level of detail for exported visual geometry, e.g. subdivision level.", + ) + parser.add_argument( + "--detail-level-collision", + type=int, + default=DETAIL_LEVEL_COLLISION, + help="Level of detail for exported collision geometry, e.g. subdivision level.", + ) + ## Objects to ignore while exporting visual/collision geometry, even if selected + parser.add_argument( + "--ignore-objects-visual", + type=str, + nargs="+", + default=IGNORE_OBJECTS_VISUAL, + help="List of objects to ignore when exporting visual geometry.", + ) + parser.add_argument( + "--ignore-objects-collision", + type=str, + nargs="+", + default=IGNORE_OBJECTS_COLLISION, + help="List of objects to ignore when exporting collision geometry.", + ) + ## Source of textures for the model + parser.add_argument( + "--symlink-external-textures", + type=str2bool, + default=SYMLINK_EXTERNAL_TEXTURES, + help="If true, symbolic links will be created for all textures instead of " + "copies. No copy or symlink will be if the texture is already under the output " + "path.", + ) + parser.add_argument( + "--texture-source-mode", + type=str, + choices=["none", "path", "online", "blender"], + default=TEXTURE_SOURCE_MODE, + help="The source from which to select/extract (PBR) textures for the model. " + "Option 'none' disables texturing in SDF and relies on mesh exporters. " + "Option 'path' should either point to a single set of textures or a number of " + "texture sets, from which a set would be sampled at random. " + "Options 'online' (textures from an online source) and 'blender' (baking of " + "textures) are currently not implemented. " + "The value must be specified using the 'TEXTURE_SOURCE_VALUE' option.", + ) + parser.add_argument( + "--texture-source-value", + type=str_empty2none, + default=TEXTURE_SOURCE_VALUE, + help="Value for the texture source, with the context based on the selected " + "'TEXTURE_SOURCE_MODE'. For example, this value expresses path to a directory " + "with textures or a name of the environment.", + ) + parser.add_argument( + "--material-texture-diffuse", + type=float, + nargs="+", + default=MATERIAL_TEXTURE_DIFFUSE, + help="Diffuse intensity of the albedo texture map. " + "Please, enter values for each channel as `--material-texture-diffuse R G B`.", + ) + parser.add_argument( + "--material-texture-specular", + type=float, + nargs="+", + default=MATERIAL_TEXTURE_SPECULAR, + help="Specular intensity of the albedo texture map. " + "Please, enter values for each channel as `--material-texture-specular R G B`.", + ) + ## Inertial and dynamic properties of exported models + parser.add_argument( + "--static", + type=str2bool, + default=STATIC, + help="If true, the SDF model is exported as immovable and it won't be updated " + "by the physics engine.", + ) + parser.add_argument( + "--inertial-estimation-mode", + type=str, + choices=["none", "density", "random_density", "mass", "random_mass"], + default=INERTIAL_ESTIMATION_MODE, + help="The mode used during the estimation of inertial properties. " + "Option 'none' disables estimation of inertial properties. " + "Option '[random_]density' assumes a uniform density of the model. " + "Option '[random_]mass' determines a uniform density based on the target mass. " + "Random options uniformly sample the target value from a specified range. " + "The value must be specified using the 'INERTIAL_ESTIMATION_VALUE' option. " + "Estimation of inertial properties is always disabled for 'STATIC' models.", + ) + parser.add_argument( + "--inertial-estimation-value", + type=float, + nargs="+", + default=INERTIAL_ESTIMATION_VALUE, + help="Value for the inertial estimation, with the context based on the " + "selected 'INERTIAL_ESTIMATION_MODE'. " + "For non-random modes, please use a single value as " + "`--inertial-estimation-value TARGER_VALUE`. " + "For a random range, please enter min and max values as " + "`--inertial-estimation-value MIN MAX`.", + ) + parser.add_argument( + "--inertial-estimation-use-collision-mesh", + type=str2bool, + help="If true, collision geometry will be used for the estimation of inertial " + "properties instead of the visual geometry of the model. (default: True)", + ) + parser.add_argument( + "--friction-coefficient", + type=float, + nargs="+", + default=FRICTION_COEFFICIENT, + help="Coefficient of the surface friction, equal in both directions. " + "For a random range, please enter min and max values as " + "`--friction-coefficient MIN MAX`.", + ) + ## Miscellaneous + parser.add_argument( + "--generate-thumbnails", + type=str2bool, + help="If true, thumbnails will be generated for the exported models. Only " + "applicable if Blender is run in the foreground without `-b`. (default: True)", + ) + + # Parse arguments + if "--" in sys.argv: + args = parser.parse_args(sys.argv[sys.argv.index("--") + 1 :]) + else: + args, unknown_args = parser.parse_known_args() + sdf_model_exporter._print_bpy( + f"Warn: The following arguments are not recognized by '{py_relpath}'!" + f"\n\t{unknown_args}\nHint: Please, delimit your arguments for Python " + "script with '--' (see usage).", + file=sys.stderr, + ) + + # Pass as keyword arguments to the main function + main(**vars(args)) diff --git a/tutorials.md.in b/tutorials.md.in index 74988a1c5c..60bc3172d2 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -33,6 +33,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. * \subpage underwater_vehicles "Underwater Vehicles": Understand how to simulate underwater vehicles. * \subpage particle_emitter "Particle emitter": Using particle emitters in simulation * \subpage blender_sdf_exporter "Blender SDF Exporter": Use a blender script to export a model to the SDF format. +* \subpage blender_procedural_datasets "Generation of Procedural Datasets with Blender": Use Blender with a Python script to generate procedural datasets of SDF models. * \subpage model_and_optimize_meshes "Model and optimize meshes": Some recomendations when creating meshes in blender for simulations. * \subpage model_command "Model Command": Use the CLI to get information about the models in a simulation. * \subpage test_fixture "Test Fixture": Writing automated CI tests diff --git a/tutorials/blender_procedural_datasets.md b/tutorials/blender_procedural_datasets.md new file mode 100644 index 0000000000..4f8104c186 --- /dev/null +++ b/tutorials/blender_procedural_datasets.md @@ -0,0 +1,257 @@ +\page blender_procedural_datasets Generation of Procedural Datasets with Blender + +Procedurally-generated datasets of 3D models allow us to create diverse +simulation environments with nearly unlimited variety. Such environments enable +developers to evaluate their algorithms under various conditions that their +robots might experience. Furthermore, it is a simple way of producing a large +quantity of synthetic training data for applications within machine learning. + +## Overview + +[Blender](https://blender.org) is a free and open-source 3D software suite with +several tools and features for creating models that can be utilized inside +robotics simulators like Gazebo. In addition to manually modelling, sculpting +and texturing models, Blender also enables procedural generation of datasets +that can facilitate diversity in simulation environments. Furthermore, its +Python API allows us to generate such datasets programmatically. + +### Procedural Geometry + +[Geometry Nodes](https://docs.blender.org/manual/en/latest/modeling/geometry_nodes/introduction.html) +is a system of Blender for creating and modifying geometry through node-based +operations. It enables the synthesis of many model variations by combining +procedural operations with randomization. Although it enables a relatively +simple and fast method for creating datasets, it can be tricky to get started. +Fortunately, there are several helpful resources that can help you with the +creation of your own custom 3D models, e.g. an [overview video](https://www.youtube.com/watch?v=kMDB7c0ZiKA), +[demo files](https://blender.org/download/demo-files/#geometry-nodes), +[training from Blender Studio](https://studio.blender.org/training/geometry-nodes-from-scratch), +[tutorial by Blender Guru](https://www.youtube.com/watch?v=aO0eUnu0hO0) and many +others. + + + +### Python Script for Generating Procedural Datasets of SDF models + +Python script [`procedural_dataset_generator.py`](https://github.com/gazebosim/gz-sim/tree/gz-sim7/examples/scripts/blender/procedural_dataset_generator.py) +contains a Blender exporter of SDF models and a generator of procedural SDF +dataset. The exporter outputs models that are compatible with the SDF format +and the directory structure of [Fuel](https://app.gazebosim.org), which can be +used with any existing `.blend` project. The dataset generator leverages +Blender's Geometry Nodes modifiers that are configured to generate countless +model variations via the Random Seed input attribute (seed for the pseudorandom +generation). + +This script processes all selected objects in the opened Blender scene (or all +existing objects if none is selected). The exporter is configurable via CLI +arguments (or by adjusting default model-specific parameters). Currently, the +following features are supported: + +- Export of mesh geometry as COLLADA (`.dae`), Wavefront (`.obj`) or STL + (`.stl`) file formats. +- Option to exclude specific Blender objects from being exported to visual or + collision geometry. +- Export separate visual and collision geometry at different levels of + resolution to improve collision-checking performance with low-poly geometry. +- Estimation of inertial properties while assuming a uniform density. +- Optional randomization of model properties via uniform distribution, e.g. mass + and surface friction. +- Linking of PBR textures sets via symbolic links or copies. +- Generation of thumbnails for the exported models. + +## Instructions + +### Dependencies + +Blender is required to open `.blend` projects and run the script that employs +the Python API of Blender (`bpy`). Versions `[>=3.0, <3.3]` were tested with the +script, but newer versions are also expected to work. + +- [Blender `[>=3.0]`](https://blender.org/download) + +### Run the Python Script + +#### Option A — Run Script Inside Blender + +The first option is to run the Python script directly in Blender's *Text Editor* +tab for scripting while using the default parameters that are configurable via +constants at the beginning of the script. For new projects, you can follow these +steps: + +1. Open the desired Blender `.blend` project. It is recommended to open Blender + using a console to get full access to the standard output and error. + +```bash +blender [blender options] file.blend +``` + +2. Copy the [`procedural_dataset_generator.py`](https://github.com/gazebosim/gz-sim/tree/gz-sim7/examples/scripts/blender/procedural_dataset_generator.py) + Python script into a new text data block in your `.blend` under the + *Text Editor* tab. +3. Configure the default parameters of the script for your specific models via + constants at the beginning of the file. +4. Run the script using the *Run script* button in the panel of the + *Text Editor* tab at the top of the screen. + +@image html https://github.com/gazebosim/gz-sim/tree/gz-sim7/tutorials/files/blender_procedural_datasets/blender_instructions.png "Instructions in Blender" width=100% + +Once you follow these steps and configure the script for your `.blend` project, +you can save it and use Option B in the future. + +#### Option B — Run an Internal Script + +The second option is to run a script that is already saved inside a `.blend` +project, i.e. saved and configured through the procedure above. Therefore, this +approach is applicable only for `.blend` projects previously configured with the +[`procedural_dataset_generator.py`](https://github.com/gazebosim/gz-sim/tree/gz-sim7/examples/scripts/blender/procedural_dataset_generator.py) +Python script. This option enables configuring the script via CLI arguments +instead of modifying its contents, which is unnecessary if the project is +already configured. + +```bash +# Note: `procedural_dataset_generator.py` is the name of the Python script inside the `file.blend` +blender [blender options] file.blend --python-text procedural_dataset_generator.py -- [script options] +``` + +#### Option C — Run an External Script + +It is also possible to run the Python script externally without configuring it +first inside a `.blend` project. This option also enables configuring the script +via CLI arguments, which is often required for new models. + +```bash +# Note: `/path/to/procedural_dataset_generator.py` can be an absolute or relative system path +blender [blender options] file.blend --python /path/to/procedural_dataset_generator.py -- [script options] +``` + +## Examples + +In order to demonstrate the generation of procedural datasets, the following two +`.blend` projects are provided: + +- [rock.blend](https://github.com/gazebosim/gz-sim/tree/gz-sim7/tutorials/files/blender_procedural_datasets/rock.blend) + — Models of randomized rocks for Gazebo that robots can interact with +- [woodland.blend](https://github.com/gazebosim/gz-sim/tree/gz-sim7/tutorials/files/blender_procedural_datasets/woodland.blend) + — Static environments of natural scenery with randomly scattered assets of + low-poly trees, rocks, grass and flowers (these assets were adapted from + [Blender Studio](https://studio.blender.org)) + +You need to download these `.blend` projects to follow the examples. You can do +that either manually on GitHub or via `wget`/`curl`. + +```bash +wget https://raw.githubusercontent.com/gazebosim/gz-sim/gz-sim7/tutorials/files/blender_procedural_datasets/rock.blend +wget https://raw.githubusercontent.com/gazebosim/gz-sim/gz-sim7/tutorials/files/blender_procedural_datasets/woodland.blend +``` + +### Try Demo Files + +Now you can open these projects with Blender and run the scripts. Alternatively, +you could run the pre-configured Python scripts for each `.blend` project +directly from the console and configure CLI arguments as desired. + +```bash +blender rock.blend --python-text procedural_dataset_generator.py -- -o sdf_models/rock +blender woodland.blend --python-text procedural_dataset_generator.py -- -o sdf_models/woodland +``` + +@image html https://github.com/gazebosim/gz-sim/tree/gz-sim7/tutorials/files/blender_procedural_datasets/demo_blender_rock.gif "Example of generating a dataset of rock SDF models" width=100% + +@image html https://github.com/gazebosim/gz-sim/tree/gz-sim7/tutorials/files/blender_procedural_datasets/demo_blender_woodland.gif "Example of generating a dataset of woodland SDF models" width=100% + +You can configure the script in several ways (see +`blender rock.blend --python-text procedural_dataset_generator.py -- -h`). For +example, you can set a combination of `--texture-source-mode` and +`--texture-source-value` arguments to link models to (random) PBR textures. + +```bash +## Configure `--texture-source-value` with a path to one of the following directories +# ├── ./ # <-- Here to randomly sample a texture set +# ├── texture0/ # <-- Here to use texture0 +# ├── *albedo*.png || *color*.png +# ├── *normal*.png +# ├── *roughness*.png +# └── *specular*.png || *metalness*.png +# ├── texture1/ +# └── ... +blender rock.blend --python-text procedural_dataset_generator.py -- --texture-source-mode path --texture-source-value /path/to/textures +``` + +### Expected Output + +Once the models are generated, you can see the generated directory structure for +each model. + +```bash +./sdf_models/ +├── rock/ # Parent directory of the generated dataset for rock models + ├── rock0/ # SDF Model directory of the 1st model + │ ├── meshes/ # Directory for mesh geometry + │ │ ├── collision/ # Collision geometry, defaults to `.stl` + │ │ └── visual/ # Visual geometry, defaults to `.obj`+`.mtl` + │ ├── thumbnails/ # Directory for the generated thumbnail + │ ├── model.config # Meta data about the model + │ └── model.sdf # SDF description of the model + ├── rock1/ # SDF Model directory of the 2nd model + └── ... +└── woodland/ # Identical structure for the dataset of woodland models ... +  ├── woodland0/ + ├── woodland1/ + └── ... +``` + +### `GZ_SIM_RESOURCE_PATH` Environment Variable + +In order to make the models discoverable by Gazebo, you need to set the +`GZ_SIM_RESOURCE_PATH` environment variable such that it includes the path to +the parent directory of the models. + +Note that the Python script will always print the adequate command with the +exact path after the export of models is finished. + +```bash +export GZ_SIM_RESOURCE_PATH="${PWD}/sdf_models/rock${GZ_SIM_RESOURCE_PATH:+:${GZ_SIM_RESOURCE_PATH}}" +export GZ_SIM_RESOURCE_PATH="${PWD}/sdf_models/woodland${GZ_SIM_RESOURCE_PATH:+:${GZ_SIM_RESOURCE_PATH}}" +``` + +### Spawn Models in Gazebo + +Hereafter, you can spawn the generated models inside Gazebo with your preferred +approach, e.g. via the Resource Spawner GUI plugin. Below are some examples of +Gazebo environments using the rock and woodland SDF models. + +@image html https://github.com/gazebosim/gz-sim/tree/gz-sim7/tutorials/files/blender_procedural_datasets/demo_gazebo_rock.png "Example of the generated rock SDF models in Gazebo" width=100% + +@image html https://github.com/gazebosim/gz-sim/tree/gz-sim7/tutorials/files/blender_procedural_datasets/demo_gazebo_woodland.png "Example of the generated woodland SDF models in Gazebo" width=100% + +Every object that uses Geometry Nodes in these projects has several input +attributes that can be configured. You can open the `.blend` projects again, +navigate to the `Modifier Properties` tab for each object, and try tweaking them +yourself. + +## Known Issues + +### Installation of Modules in Blender's Python Environment (`trimesh`) + +The [trimesh](https://trimsh.org) Python module is used to estimate inertial +properties. This module is not included by default with the Python environment +of Blender and thus needs to be installed. It is installed automatically during +the first run of the Python script. However, installing a new Python module +within Blender will not be possible if you use it from +[Snap Store](https://snapcraft.io/blender). If this is the case, you must use +the `--python-use-system-env` Blender option when running the Python script. +Furthermore, you might need to run the script as `sudo` for the first time if +the installation fails due to a lack of permission. + +## Future Work + +The Python script is not fully featured yet. Below is a list of features that +could be eventually added to improve its functionality: + +- Add support for exporting processed objects as separate `` and + `` entities of a single SDF model. +- Add support for baking textures for all processed models. Separate `` + entities would be required to prevent overlapping of UV maps. +- Add support for pulling PBR textures from an online source, e.g. repository. +- Add support for exporting lights as SDF entities. +- Add support for exporting cameras as SDF entities. diff --git a/tutorials/files/blender_procedural_datasets/blender_instructions.png b/tutorials/files/blender_procedural_datasets/blender_instructions.png new file mode 100644 index 0000000000000000000000000000000000000000..3fbf50619a28f1ad87cffcc0193061bfd279d5dc GIT binary patch literal 43374 zcmZ5{1yogA)b2sLyOHkhP(m63DQW2jk?!u02I(#VDUp`$5)qK@l9KLz>v;cvyf@ys zN5dUuqUFYY$a=cJ6Mb5jZC!Z#MPT0|GIv5DwJS5l?=h=-X3SD3`RZms z`O)j=SheBi#YO#bX{Y&yp_9=YSO#wWo2YWVgp>Ew&QfbgfUdn=OYj z?ASfUJU26yms_h^BWeb*w>8Wn+jIF`cfavkPvgY-^wsZAe=bmn{gNWP^)luDaAD;^ z)9!C8j{==@?GHNt8;?i3E-}x=7962rp~Tm_XCPK zohcY6qf85o#=yq%iZ!P3J@uxvLsX_U48*R7+Y4<@3yQwF)1_5>qSTqrU}GRW$%>LM zd=)$>9i_+||33LmyqbEA8YXON|5Vm5%cNG-nH@~GH7?%~{S_MK*<0P~ z`pETJG249FdeSn}Hx}MUQ^$4gbV}3EbYxoJZK=Vxap_9%22#BJ>22I|v4e9ScI_6g zk;<8>6}P+RD;jrS_9)1oB&SZbrZy|pE6$F-oRoPl?zBl`iuSQ&1d<7Wfn94H>*D>1}7z{c==wxB{%tQz}0*3VrA;hA z{iVkuo0mIwZTNRC#+$rMOYYxxt8_1Y?O5!%M@04`vNdj7Eo)t33PU{iwNn*7A7H$` ze63J4=W;uLcj(f%>^kBxJ<6$lS+r~?WIjUXxHkAD_|IGX5HsHOX-BfW51I3O&4u<( z{nm0#cg}YPEhx#+5yV?fE>G1I8ho4|q&hOm6!%oPYP1=!*0&i8$DsqIDUVJzIDx6L2UZ1VS zQu|xg>m9sn`Uj5gk(Q?AjFl#%har7L)C1A-1h2zPp3E3z^QBSx&C0|S9K^&4t?g6k z=jgUGyolmgj|jh2H4gTLs>-{4@;BMkObtv+DtwY=xd}6lOkQpKY-uO)+|SBp%KO-?p&4n{wr2{%e`?i9y3_7$JrA;IGcF=^o-9n)-r1) zw#~SOzFI1X$$7_bGxp+A=dZE)SBl#=wpgefwQEewzd|CW`)hfdoC_7Geam04&Tgtb zre8j@&KW7%%182Gij#*eS%gm+)*q|TN7eY)J;UWmO+{v1&9|0cpUc~1ee~MW{red~ zfYPu9X-hrwi%EKyTEFq35$iWYFm_vqY}M0-QNtpYUa^k|%1SjFf4E;P*lN#(AKG1K zBh+D#Y2d$h`2H;#%{isG_$V7?TA7~S$1nOuw!$QVi>agpz} zFY^ziaXi#8I9psZ_ssY3s(Q1T%t_V}NV<5{MCa1#jHET8eGc$2-w2_9+DxW-{k#VT4ky z_O7!$qmKL0#^)1=9K|Y4f!lfsYOgnP6lPJwTuSrX$1-j|Po|#e34DxThu8129QiuU zuhfB|i74IxQ#v2wW_QFT@mJdY7dv?`Cj)Kaxf6NpSep#B+Esl3ij2~XRG*~<7wgwn z>JUzpIi1G17j2$ej@Gk4FXz7Q+V!u@Fwg)xVzltDH;uuqwy>EMCUY-LZ=; znl9o?ocPP9|SuBTl=;MWF_$*(2B;D#={28lxC?J>_Ms=avn4Y1->mfhWjWXRR z*=+lc$sHw8Ka5HV%X^#4RsSqGh>Bm4!xBYUWNa{=4r<`a7vxWKlNBZX1Cuy;XqJxG z;B(WsceipN{EK)|Y*o$uFVS0N!>^ATm_*}5chiwACk}#nna!K>ymsl=*v-F-cbf?@ zUpt{%f5nyJVxs5!LfRowKQFFg=f?T?ImnB0oqk}@6pnr zA}vXvB>X;+`S$v3Y?3OIj8RbpTBp>GJVrF<`%0&!{+=TQQ;X{;Zq&axwX;;^e%OT= zl`t6Gel^l*1ii&Vb#VH2DN{sxHHkOr+8K*YtmhQsnPw#_+R`FdXcAd(yNTqknYsum zt-ijnLy#)KHZ^&8yJ%JL$7YcA@j~RK;O}$<&%*K@-e-B|tP+#(Sjc|X?6Y$;`?IK0 zsuaSIh9ugBpq25K^gu($44FSE-_z-~N%(#U$XZmL1^oH3itUqE`jrFTliv<@z~U%6 ztH*CG&ihodvzu*aE!`$nB&r1cLXMZTVF>Pf4mPZjCBd368}U@<#Ywkc9k&)7kE4;G z&s~uX%CXfpH_@)Xo>V~^81qx6bpmw4zS^U+~4?D<=Utkh6Ev$ z@pW^8^!MpKc;vJ%F<22r4|D4%)U(m=pPQ;t3fu3`!LqF))*GW<^S#6%vN-3gcYPj~ z0Xxq=&GjM)7w1edjO*nG3*Hfa0fucs5!-L)UlDusa0G*gor`5y{pILOX|{SL-xbJL zbJa<@2sku_>ICnN$KwxdA!~AfN6>oJLz__`?pZfTZWekwNa^yvTTIoQ`s%+|Ag3<1itPKL37D z&vH1YzHdd1a^Mwvh!2UjIvD}71V8R-TVaT~a9*X3lp7<LA3tB$+r&Up7lqy;qR28ra6wmVFX6E)KyA^$oDW)Hoac#d#Y(ddMhba&zGj` z;hh!2b%jNDw-&oqCv0K*#*&+20TSPclD<}Fl@$d~O=*qBBVZ{j#Vg`KzNy;oH+|sG zJ$*cY7YW2D^WOZ_EM>@zJc_Slj6!T5-hFg!8pc6i9W&8S+cn;Q*%M*AhQUcgXDNg8 zrynl0;s@Jn0UJ{y@9*%`ioqxWrX)?3Q@Jjkcps*W(_`Z~50xUW;e0o;@>$I9-wIY? z^MquZq@d%Aa9vl!e^g+;c>RM@`!sZ4S_mnWD#y;qi15e3a}rUkpJA--+2}SQd*j(@ z<_j29b9Ev-AJ(|DPQG&z@azd@(ZOcGm6Zodw@W_Z;=0|3u8|yLTw$>jnVq#MF6VA@ zc1h-s;zN;&) z?@Mr0Z52jU5al(@`p#z24mI5)2UA_d$!ZhD(V@uUGR&h)Xqm+fQJzgof)ag*t(^u^ zJ9P*n0#i+y3-+J2tz!>DUdgRPkla_oBQ8DE%al3ubuK^eda*SV z@z$N!RfE~(?gw4xwgi4khd&7On3zqR^)+XlTDB}#^X%zbSPn(CH5m?r% znO1tA5{8}44|C60%Ovztr%*}+M3W4cc1mPv#^B*v&ntUehm&>4v8U^qb2_o+q2MQO zAU*}JEM-kB019X=cV{=uJO!R-tVNf=g3cfs%jgeSLXWZBv|>onOrPh-Yy4Tz!lH!XR=@ZsOJ^UZS|Lqw-B?^^55tV4oJ~>Ox{Zy zOZh*SA4Mkjju5jyIW_h9$3_A2gkYi|D+PIi{+HKQk_6sCc97F?27D?K`VU56XrvMX zp@h7a5?A+_|C{aZqi%lrB<6m2p8lgqOG2VL9}yldMOvLz8zSBpG`vpe|DFGO`1Inv zPN;?!w)>L4zHLMmJiPRGc?~Qykw7>J1rDC{jNPlpN2Du1OKzSa+H}0tRznWMu$S&R z-apTT&ptViIb$ScW&H@IL<;(UUh60l^S{H-@KM0~^XY$BF91FifMzlSRG!ahxqRYF06Kqq!zWr7Z(@ex$xSe z#cE7yYHCu!Rx zN1KR&ow6b5AxwTOtc*$qJ&qO4bCEb)IBb$)HBTMk!s7j#OOi}#PlSJGqV=;quem-@ zzBov?k|1s>Doiy-X40&f2@gfPQd2PdCx)t2zRIhT$*wIY)oMEE$MduMz3?I@1gGBJ z?7Ury9ifo%_pfcKGhuyY{89@HWN%TrRP2}pTzCP!p@xRWE6)#XEsma*eY-B*w){O? zPN9ogNTx{!)%NvVjm?(-76n`QYS?=b$$Fg1tKxd#7s%;;t4>YL8 zT*QO42w1A+R+NvrHyT+HBvqh7;^P6k)i#-2o0x8RTOXRaehM=I) zL$_n=3VEQliE@C2a!_5!=V2T9*w69wXb^})Ne6lhfBeYSle<4{s61_AJURXQ>58ss zVxF(olb&A0`#<^O;p6kQFrBQV@eWQ1^{W@F5nq<(NKqqC)YdG1@cr+u z1v*#ru02H;NP5w)o}>$iH{d|CQ#Mm~fC&kFOU%M`B4P?0g z7Sr#Suo70~k~*gfi}ucMr}G2ysQ0q2JrV7%jfhq|j)-ITW!!r(5#?1qy5JPrNH5p{ zfzT>b_qg3H2{w>oHEbut6ualttkRn+ay(DgGC)R3GH+a{F&j!$=$>?0ZuN|aiRqiK zfA4sEZvBE>8CnkGf7UbnF7 z*bx`Q-+ubfv}L9E{PgW&lVjnIxzk3BK$to`j`Am~?r*Guv8aim<~km22H*}M++7~* z*NGDS4EpJ)H~Yp~mNHpBn7@rYu4FteU|_b!w8s0&PS1Ii??5dMt>+bcDh)qBfm_RS zw-%AVaUmOm(WC+x-dBeQ=QYKS53X+B2Fwq&EcI04dXX-Do~?z=kGK0Zo@amfiTylt z1}Ogvc(LmBUPOkp8kMBl@tt>&`Q!deRl8FA)0{duzU6m7^ zO4-bIY5aDJM5j5ii;9k9;Uzg|Z6EKEGcc(v79+6iQ8=2(oI4iozU;{` zcwO(ZtER4{g(&R&cz<)fTaw%Bb$;WcniRb4shG)+p2VOmBP|UNJ>dTS$>|73c=Fv^ zI0eC$)o$&4?PDyt$j7S{{|-t1*6|6tjE7n}*BL!hnc7OEpq=?M580kG;T-QnA=~-7 zvNs#31CH9?%#hs<7l~EZ2mj=ZoCz=coV^h~`@y5igH$h@elW+buQN?l&r1C~BqmUa z#{P6!$oWr14YyX69`U7U<|sm?CTf}bN6^zuPS*RdNACY*+VkId78w+y60)P6{xKs$ zX!E-0{?ND-2CkEa`9nV^noJBysCY1f@x$%KY>PWb=;^-(&3HQd&YQhT=UH{*wCV3$ zh8&M)OD*o0O`7lCMHMTgHh5$oA3Z(lw@gcBq8C0!-BhhwuU~kbfE8SuerMm;@L{2s zCg|brDtur=TwFZRgZDLiYOpbp94*eyg%{{_*FK`E46z$hun9B!@MC8to|XD(p2Fm; z+Fv1Ho9pQ4cs$;0pZt=ijiVT)9x51!c%RVsmgT{s8>Uk$3k1!MCR_4W02*){eYxJ7*jJsq5IR3G(a zpViJp#^Y|ag7de#m2C&XRks$&24mV=zNu-iHgeXHf~u-mepNU}1j$xC4O+=5C@>or(95S#(iOv+ngoAOPk$_t4DsaR;=<<7d?Rd48IAk;^=nR& zm}3v&b=PEh_S(f~tYRS<(bPL}NK{s?y(37mkD4nci=J&b8l$01q|Tr#neQoSxZIC$YWW0g?% zlx3-#&6h`-vN4rg)cwT%gOw)XsJ;oal~coQKD&J@V|TBb%_ZM>c{&f@t~867L-}GH z7Og56p%aN$h z=@5e|1%)~@{$cBxQZ$(mj-l@bJ~Io;koPBOxy~n8c|^BgOuti&a`$`vy!Z$uhaRnm zl7j;i+PKx;zE#!NN6*>jGVX@E2gim4K)b}*pHbKWMk$bF#5+1KdaTGK)5nU~NbNtK|i#u3oY#gqYqE3jAt%9d1f2vn4 zlrf&J&?yjpx*79VQB@7J%=IN0Nnw+8b>*{bIpFUF^W-e?7r;rijop8{WBcV0~F>E3yBYisS{YQtR3{I#ytoX z`YoEak`V0u)TAWb-_xO?p&ozIEv0B`_1Fg{iWRIaXd>8!dgozVAMPg=Vj!#Gk?09-Onyt0O{H&ZC>wVaaNJmFkT3QO} z;rwOAtKDdqZAF$MM|%yLw!*f4=@v(Z{N{{`@##N{0)f10Ab>M>{Tq655wB{T4Ul?Vs7#xBJ!O zg|e6~N6XL4H7mOTWRRHdaPWV7K`j4NlIutE_Ol|g&C|v}9O9?O4-5PiI<3S1ZpY5N(Gz*=v=*(jmsYya(!^1#KzgSYX?oY-zvjEFepT$p$iF^ z+S&FP6yThIi!~mMr}8*#-u~)wVv;55OOizYru!4qTj*)b82Ud4lWf(KTwuus*YB!j zWvzBhG%ACgZ8ujTl^x$Sn4jS;fkqa>8$twa40XC}%YJtsY!@2XR&Nq^2q`Eieou3> zUsH?T{pA6t<5)ZLja574gL4Z`@0OzF*haU{DfA2ghWNFApjO~5Y{Q3lNml|Ix%ubHZ{G9;!J|H#f10z*?E^ascKA$S zGkotIh2J$50lQv=|NREV^}@;{LU>PLrhPl{Lc<41Utize_b*#|X!?mR#FT!Xb#9Ag z^^XlOV;82Z%?Z%}#KP+49{yNG%3%0Wu7rTr>V@|ut0;6}9CyMR5g}0c-#doW$|uUv zrU`p;dtLsG#Anfr-)4kz&j%}U+Smc#F;V7~{dGfSJB(*cH{P8zh)6n_ekS?|EW#&)iM ze>|1saWAg&sfY)h+?f{*wy z7!ec58J|*9du-~V7y#h3iV8HavBSo;CGG6k`(sEEvy~8&-G`_6*VC-5$CvKttVWdjG~8g2f*ogR-8yUfUb6?$_dHAT_bzx zhUV$%N!6AQ=)sG#CeB8d=rI6^NPBs`fEW$LJ_q|a7y%tR0MQVF1;;v$yHSbw zZHbg}gd-;=)Km?sXQBY258Upa>2Yaskp1pYWQFhk)~<`h5ZVR# zymb4EH9{m{M+U9!*;#EXUXl|Rc|pL2Is;*YbMC~R&cwhOm=46EGggB;VHKM!M=O4% z-{b(3>w8HIE#g!IFXWELTNXfEBD;bS5qHT+Nu$8+2;i24?>(BSrT{Dm1>jatN$+Ra zoAj#U&A+HKgPsZLJX~s_N{|D92?pS5Fe2%X?7xVT?sL>VMdC6%oA;mlX1?yF$T+t0 zi}Z^kM_~NbpC^u<8%5Nx@8&{olre; zFlV#s%#*a#)SeZNM}TE8?G8b{2H=%4K`w~fB17>rWaBqS$NjUUp%Ac`#@EMdK%x+I zT!%aN5|N1}3IuP$v$Yo152DhIfwD2?B+64Oi%(BSj_L~v2?+^!13U7~m?yIF6M%W3 z8l$-0@bK{TSq^TU=51elPt|E)P_-ASl}Ua0z~*H zwt47wq5gfUl?Sd17MAeq0v&%KZ53#J!CFz^{DtB;aWC*5>}cj>`TK07ei^E&%GDcM zpPZbWSm-7Or_Mb*GQ#C^?ErW$o6Uz`fXb{OteM#_Du=A(JN#C?_G`3T%9v87PIyI~ z05|jv^pQ`WKCQ<2-_wMl5eESTBz3D0~qmq%ZPv=Y#1-V5JsCUFv>ftR4~txMFjTe#9xfxU&Tq`!H5f4XYx`H3Zc&4YKHkBFg$uu`;wwc}uw$Xq4&W?CW@a0K!s1^* zOJ0n8lgXdp_#eX=+)P+H?u>b$G^NvSt4CUSav~RAajEzzm&8%2T|;g3KyDQfV~f$T z)gj<2Cn9yh_y9(d?!B+^+lz3qdn#rb)hFrW%Yy|jF!cb@q2b`*u)=lN`^`j4Pu~qX zTSJ59InkCN#y}j!fXLM%jaOGTX!Fqh1;FOKUDR)fQ^47Or1KzJ{>nx3A2ph!VE7zHag(Qvef6i05nv zM@OZtt;=@$b~@(lg^iG&2(WMz04f18jU;{2TE_b-?4!sAD7G0LIy?$=n$plR24e%j zeb96ptu_hQTlq?Id)APcqI4_6z-wen!oYwWgG?~MeZ`m1ral9$@E;2YfV>y1V&2R? zm&58SE{hV*u+8o54KT~`4L`lf62#sf%N+nv^DAHpX6EMkt*v@lBe4`>vA=(-1BKvI zO3E{<;|Ly-7^sqnO-P7XKE>S6*|2Z`A&E_#nVvTJJ6l7w-Lko922Q=OwUtb*3=cpx zU#VrMo0}W$CI{nAXP~G8NYkBSS+Cm%=bWFzk}Qu+N{R~b0+c9#VQ>xZg9Ff}D3@Gc zJlA7S)&4wXgD#{+CgOz`MaUszVL=bJt>eIRcR(G%fMGRDe{>{&7`RorSh;@uv-dWB z%9cOe_6cA#gkCuO95KIp47ZuT#+M|>3BKhBp7^=K|3)`$0D@);v2N1Je4YpGc z$F}3bHMz>LPV2D>drIpS%TG;h7>FriiOKYlca)53<3KoiN7jHO+qKB7E&u&Rwf~1x za;m?IvXg++K#|JzW|A_r{s0jHNQ#n@>TTWDx+ghMPOgEBrmCSK4J!bJEK-5*`pq}| zwa5b&HhT8sV!OiH2s_Vw)Dt;EhvhMOTdn-JlC^Z}G>@-r(K|G)d=;-s$&2mTK$S** zQB~&@e7HXwOXIP`Xs}yCsh&YCRzqHW5`N7}fV%8^r4NNQU;vwZ%LPb;93CD%A}($K z0O8JWtkC<&^!D@W^~r`RU-T_$vc%BF+09qLY|oEYDEx0Hb5~tnoB$ra0RUweV6-)U z4_>Wc6axiiOzg=g^VvA6Inu?3TgwSh#MXc!+0Rnl8Uz{m6}li<01gC zpjs{F51YR_)nqfp4E^-dvNCZWAK_)MeKxK&nbM>1yGDRh{QN|r%1P__gaS}u896uz zFXBG4CtNB&@kgkq!oVUJ-Cv&!4i0vL@woS7Fl>KL>D?e*TOA z#9sbo?;{Z~wP=Kdh@n-fum2p1m>XC8NQ;Y$BO)WaypP(#bNwHQ0UZIl152-C=f(*j z&+t%E4~P#1;P_H#GhLi$&?B`1A%>BKMbgo+Mvx!b34(4cN$ztj4t*PXc>pAM8g9I( zDl0?ws+!rC2AliOXeQyeR%NjVyrcFzc3XZ@=+o(Q-TCdYJgc0K{*s{qIdCnqO^ zBO^USNesa*mP80ZBf=d4dauV$e)zNQ7$juORB+lrs(}TQQtbX1)*~mp%Lqy556~tk ziW&jR)z{aTf`b2`3XE`A|LY!#pn3nHL^>lP`aI#-4Nm_@pZmL&r+%PQN?cX~Z~+8N zpNESXkH0koy_;EV`O|-UJ7#h_3mY*dDl`MN9v$!v?vDi^ok_J}A9DzV$2Qt77*yWd z>1Y!^{XL7hQ?vAz2O>69B9H*9!8kHkYYA1ZOmEM3J-~4bZLlh zkSzr-}JeRktgv2wj;uV@Kn@&PRVc2b0pXBKTV{zlGk;#+CIbR^l z!X*Q-Fb6Ynz?L6$^T>XxbVUTPZ*#{O3<%d_hRwcdQWO&GNi!;N9=O;X!L@)X#yav5!Kq}D z>GEaQ!T^wpKfq8jf3GX@=eG-X_|~GwE|{$ZWu;9(iiCD)aNYntU`@U$QwPkRuRIr= zP26w3$4a0Gw;5o9a|W+;MS_d8PB_Q1e0AoRuH<0w>&=eovlC*F3rAqn$h@ka>Df4m zaBiebRiuX3WSrih18xIwmHjuez1%9!x*90C{$3S>ntbUFY&$ldE49 zVv07ksV8x2))O|S{1F(`g=uxXs;sDpx6QaF7vIsE|3@%)jPP7uh2;O(SUv`_~&OfOPJUR$D|ls z;4dYEYOSovjPD&~x92k}E19*9cLILx$F}*4fLg&{uo;s#gN=uUiyI8cC|vfcm7<#) z|L^9gpekk3)X;EyVx)9l5B;4BNA2cExc0jnG7oZ(%h7ibh`*Inx6fVv>5J=*j)dmoE}kjk*dCfioFDgs8JrqV`x1-gW(N7C`m33Ss11LB34< z*vhMQ3fOUznusVH<626OG!#@bDV-Nixl`S5??M*s1QF;<> zyh<-9%^0q3e87EN_kARN<=?!(9InE^o~rQUko^;zM<^)bJpZ=`OubHL9qheIQ7Ma$ z7wd79Nn_i=Q#SY;4ag6Qd5)|vsj4!cIzk_jc*$yThY9$jC7!Ixp^zwMfimlF&=vdG zS^SV0_z++%uo`-V9siI!$MqwO@n?bb61hE|=pYB}d_QY4TEvO14VS0g7DFJ4k#W?+ zdK^1zwYtY|XZVqh5KLwC7ZK}NV(ck2uV)P_#pdE;E4hACoU?S zvjrIO&EWPkB<3-Hy>n%|4gcJyMMg3XyHU zd1+RT$olidAZaQxb1jo+w=V~Y(~V^lW}~)!8GB_J<`X|^vA@C|y`DG!%+C*H9n;fq zN{{Xg-?!eNUbR|Xj!$2XIeb$nR%^XK9VsvtoLI4ad&@_sAZs~97om_)#Tmzg7Cb=V zFKjE3*MAj8de`%?Oha5k{d|lj9hZ*;-LB)|GH;t4z=cc!d%GH#?`#{|Z(R$fY`A=H z&-1+hS0#i>G{F44J7_enoeM%sNtjkvII>p?{{ytB?@;^ScjUm$6iBa7-3=H+ncF`% zEccIhGFwi5y?Jn4+EKK9sq*nkAS<8;zuCPWdZ+8&jDMO57UR!E*R5=j_HxnuG0}g2 zmituHmHy9;!OcM=LfDNY5q2>32mhV|3U}W05q;Pj{64bPeZD*Sj`ri~t0}z7m+}-h z8T19od7yaJ%FuM9M*&BJIDom;sPK*{d6LwW;+ZkN0OZ2BcDEL>C^y z0McL+l0Odwgj`WkFQ8wpO$p)JQ^%l>7T!iZyK%gT;zJepZrzJy<5>>{`c(Wh1a`>XMBnO1zN_f4n^8vCZZ4~ej0E{dAChX)Qk7BV5OL^ zxwRNKE-Z*V#>e|+6A1p>LC;?}kzWmLIlyQv3k_?^ovUf~=|uU%X$TB#{A-q{XL4ABFoF`fCg5k)a9>59mJXi0c2PnWP}l z$P{dzshw&FAa(!li98#`^( z0&u7=SnD4Hwgp)Q{mBajF}At6kGDC~HSjMkw1M9k^h2@L7rw$i)Qfn?5#-k(v^dvh z+)cbBf1@J1O4OKKDgRy3i_ov-@e^r8f8Un(`ICx}>si)NDwX%ep};pq%_QR>|2<$_ zbtuPg<|f7}4yEbg1V{rQqV;}s2oU7qW#PhBe^T=C;RD%nYikQVhCZ1Z3}N=v^4Bzj zz^esP=g%CGsNvyZO|cIDr^kq>C`oH;CV6>z_7)0p!3TQ9v;d&^0j2A?AkdM@M<{^h zf`CR80D=M=z!}-)zQukMhg()w1`JFNuzbLjS1~liteuMn+9{yZGNTbQ8GfJD$~eu3 z@i@_FhEX9v4Q$&)D{Nf$VgX39{dyf$U0q#eyG4;m%ug8DxKPQFOxPoyIi#sz6$Y)e ztV;tJof;D1wQ%S1beDbo-OnJxn9U0@W)gwQINjH6MC$ca>vH(SbK1eN|kglE-Lbkkinh6EmD8^U|WZF)*|EBiNxlE4K!0OUS$i1wy>m+(A1_lPR1#}8gGN8R{*V|~6)W7%j6#*F-#z*hX!2~%4g~EQC z`DCcY2_X0WOm)X5+A-XCf=9AEQMM9moi^u7egcCpIFMHr5`p+6Z(jMz)$86XTQkuU z$7rW#pqz3r{M$fJi1+2UMI`qSzY^u# zupu)X5kC%r2X=w}*ymAMS!BTUgX-nbpN(1sOXR--^cmC=rB{ag{O5&zbWWG6{h2tD zSSxoRuma=ZSCn)R<+Frcmup@69@awaxUwnjZu-#vNo_qH|;7g8~lKhD>%KSwB>Ja9=t+}tr@|V(At}+OZjY-?pc{hse z1J%s<-(QmL{5)ecBI5e}%3KD)z>1b*z|muUQAja1rmynk1l_zz&!eOQ4UvbZW^}tJ z+k(eydPZ`Ta}|8<#Qq89sm#B|Lye}ou(YXN>9J@Qq*>TibL~MSgnK->H@K^A=|7iQu;sL{K=@7gubGE5xkbq{kz*e6WKzY%4d??ME?ujf ztNIIy!1PqUw>%0vCz_20vrqB(DpeA49Aolzs`^K=a{MG=^3CERqpLn`#qBL8pTTb) z<7Pqc@;et)1>28KJYMv@nj-k_x{r{vEp0CeHagJnh+_KP#BOtwl3>C2P=P)<8Q!-_ zvz#hfe$C~DWdFP0R=mI%10L+LS1@KG7g{jT*SNw8CwD`pYye-u_YpPJZssLH2jMg_ z3`EfVfl~wh48RhB9}V_JL?RhqiJ_?uE-r3DRu&qh^vjnZpgg=M0~}U-Mvt8^OUbg< zODJ0jBuPuBY|JbyJ|Zj1D=0`#o4&g+B|-o+aCdiCrF;tPK&W!lXM$X2_$8uq{v=j1c)^;`{ zJ#y?GEe|F1*~svSqqDDwsQqX3e`ugdV#aQq(ag$MWCCKV#TdUZn5R*p)@4^~{B0~8 zlY?E|?_*4#N(rt2aSUT*Oy3bJ0Wi5*l?L?UQ&Pf!w+2D4!AJsWGf>{3K618!B+Ou^ zcXxHfVHdW)w^zW72&_tA8)z->cy8O<; z*OR!_5-0hHR;0)~sug!zwLE`)a#9MjdgjITd#%$t8$;HUyrXsw3urkJ2tB4^)r5a$ zXO-escDDoTwnOi4YK?$Q^`}I?&?G`=*5P@ z5=V0!{2r^%Bk-}?Tr~yHaC;VUx9#r}<&MRDguSMJum0S#*)ivC#lnTv{RRQvbw99i zVfnvHAlN*;2MyZfTQX?dvP+!v;O>EFA`x2HSA^kdYJfXH@PV419swa324uAWe*pS` z-0RokV>u%E7iTF*(C`e%hQPdvh9w3v&iVOyJb7m2lzndmHlQ7hjEvwB06vg|MZhGF z&Jpo80U66{kdO-I-$leE$6H{2`H~daH`p`E;D8Ak86OJ@sDWn#f^qo(Day&ob%K%t zxv?+{5hR*%Ww5aQ(Zm2JNCAwalqCo=(wB+{i-7hDaJ+oY@*2CP@9{F-DT6xN+Kkib z>dff7OtaO7Vw`BfAnEF&OU>J5MGf>uVA}x4#(g&723lyp5)LqUJ=&DBU*H25zpf4s zm<=Wm%Px~|jC30GH>3Ln$CHWqZ14a~KRpA_+P;O&Rtg7DWBhBo^(1}GbMPjY&2L7~ zTP48L1hyFbVt~s+!4?S2gH#zL0Eqh_6&Gnb2W$dhApk=jxn+s`_`v~TFXb{7GhGqt{AMXJaC3A2Dp96@#Ub zv3ieV{A*f9u=wH;@D#AC5{0AHI{B}1)ISaxaO~CTk{xzCioQ$)u|HsC09y&V3ShVh zy8R`JmMLr^p0?t>2F6I=#-DMey&e!TjwM45GoGj8HwV@L$QA*+5CHY4JoI`!_Bh7o z(O>zJV6lVIN%`}DD%;AQG=$~PMd{Cb4iY8MG|j8lA@Es0GWbwIUmE=Rvmc1uuhn<>RUmtbJU9|kkcpsmZh6GG>Xnv{lm*erO z_@e8K{?2mSOVCzvPqjT2Hd)!&LZ@s%l2=kwQ!^fs3o@SPe7ZTL#G?nu1T-H41PL7k0ssUCMP;(u83-cS_9~vB&_O;C>?tht zQQ(ij)KoY-Ie~(LN;&`wxDk&*Qz!pYxDnv8B<}x$LlKGk2ttVnFukL~PNBmS`va{S zlPJhlYHHv=4%iL&R1%N{^z%f{ZwE)4tA5HLabweW8u!qyQ1ABQ`ni*;#uPSx5TV8R zRh3!#c>pS;Unu)pqP*`_2`+O=UkZJz#>Ud<$J28-$%q1q{Z83ZKKJqJW& zb*cZ+Z@&F{E4=kja-Ao_?WrRt<`GZr@gp^j<2CEcZZGLQ+8pGHRnkYB3M11JwQxWH zvJ<#Qjyu1o#uY4A+I>AuwV#KousI(rw2(Q{Qx|IF8Z%k$Hm#Z5sTV2U~mDFR^i8%{5D?t80~@q z&|ctVgQsqo`#Yw)&xHAHXDPjYUmPxxLX*3|UkV2n79rqw(m?QO5pJQm)sb!V29OBY zA`mD|MdxI0(X0AuOkP0sUsZsa3VbHms^rwv4d8p5_@8V8v(dzt592IA#+$>d|1hH!HeqtM};yS~WZ5=5(6Sc`}ZB!;jguSZA(=3HC=(z5fRkw(8z zT$PZM#KxT4$3ZnWn*_amVjpBj!UwuNvcj`UgfN)*)c!GJsf1D@83jC)YY+0bG|?+P zUcw%~%p^W*Ms?6JY#@zo7$+f@t?@T#t=0%M>#@`8;P9V=_5hqYY|BDI{^UafRzaAE zMXJi8)9|a<4Gy(#IAQqiVbjF?GA|Vv^(GS zykB>p_|v2rh0^l8v3Y4{`=UUl@-R_$&>uWp#1#o=`rhW(ihbo#v$oh5tbPB;nJ5>O z@P9l<3NLb4^;Xh`?+Y8jW`-hBQX0|b^NcP>#ukqlkO4F2EvS|X>e#ywWKYO@!H%JW z0BfLHb{y}2=@}M?95ze3|GmEG0S`4VV&uyhP6MaC3KZMmL?{CMJYPaz;07 z&Kd#i52Ezo`W=B;?6&Yr>pu?$8h-*E9rPs?4UJF`NR`bBZE0v|=o`p*S7_MucP0pi zD$%2q4LlGL?voQA&8Vl?pR&V1dkx%v@V5#oPp~AhB&c&mk{9(U!#dyr6Y$gmSj~Kp zlU>I)0)yj%=;3&+N1DUj9|Z-a7Yje;#6uVeNSvS@q5-}Ia+g5cGzCu>sW9R-9e&>j zk{h+C(xS${9jK^?Mihqp-nMqmc2$tQv|38?XG1jZ^Qp15y#Vx0$itV9hH+h7L?jIzx2>q&Ov=-t z3CF=@qDMk5UB(HY;iU9gMn>*vX@vG^vK)4#@hy*je0+Q)=e(? ze=>9uP)0yx2jKvH+^DcGK!qSzOy$~ZUL(Z43tWMTeOFm7Jt#ABN}65zjP-{iwK z5djd#&x(QRr>7SYAIs&LB^cY6KE`ZU$c#Ax!BkLE4M4U)Tm`aREth#G6r!kj6ikW8 z%F4<+C_*xZum=+%{P5c_ARh2{*c^NX z6d+*C_#mMBhDA!G(rzkoQW<9Lvej9xHT){sJ2X^fB%+dORaD}va>AQM3yOX%f=8aR zbhz5h20*A2VBA3_yT> zlul8<)_Hm>;`O*hD5CW>@x5QYFCNhg)(F+ayg!$#s2?M9UzNJux|&Fe8b{Th1glUv zZ`G|sqnLmya*4A2WkLhaUmKu*h6}_$fKm89pGYT{mjnx}SYl#g#2JTK6N&>*z(#XjRd4dN7){& z+_h2i~3CJ*;AyO1!56U-Cefj=`cJI z6B7f1M*ys1B=i^N0T;p!v3a0;mlTy<`HP0pi$rg3MEpkL+Rd0?}UQZRH?V{oAL-fSPY9Ez|MP zA5}mkWK)cn^oBfc)w%Gw04R+z?I{%6@lfBt@g6IZ`F1z9^PowG#I%YTBBm4s@V#lJ18zr^$bX6PT_O~(Mz znzk?c_t-xKXgF#}21-Y(TZ#mD+COCUqd%$8(Z~k-Ess);(a{zxSL(t#;lq%;2pnPacvm;{%&sjzFL>>J|~v=Sl*9K;i8ZIOQvVX7?5ZV~Lp0hZQvn zQa=HGGhMJw>4Q%J*kVrim`3FPhz9R0Eye(R3&iCBJopA!t(j?QZ)9r7J6?uzh2oS~ z#av#x|KWe}{YOr5Rd(v5*3ONvM=p+yNdv}z_*u4x0c?$5LB?13uf+mte~^Ji0xSh^ z?lSW7B(JWYKuw z^OLd^n?^Gwro#KaOJ8Z{-(#jO!9Xy6Yok$Dzo6{jbbItDeo`zdlv9l*Su2c6z~jD` ziMAHWgkK_1N|i6PNN0Tm8ONLX}zQ>&GQ0D1(>1BmWq z0FVV#Z*Q#t3OfSa4;$ONDnQYNcnZEiZbyJMeAbV5KE|`60~*S@%@mJefQf)9Pje;# z>IHB-9=yCv$z$3xxp`H(b)~}Q_?j!pg07+T|6pEP(dsI11a`ey&7;mJU z1C$m)X$>i_ppPL3sxg2Pfsg~((%{7OqUy^>fcSxgCjb!}i8+HDIaScB!*C~5AdXr- zh2$v*D<}b?APbqFGTVSq0sLbha_tRY#|KJVqzVmiYPo?wrXdmpLNpLJ--(g-Ln@vM z^f3Vdg7nm2=_!s4OflQu!=}Mb07&VaZ966ss4gn{3W_@bcQ!D{nDPcS$6rH3;oFs( zGecLefp`q~d!)ioz0$Z1v}M>l4h$T$p_Uv0N)kl-WhPR!B$-Eff6%v z1(NyQDtb&DNbv3Ws#S%MttLp2igW-(0TP!Ce^(FqKgsJafJuzj6A6Wq;_9lf*1?I_ ziHVuNZu-F(v@~l}g#b4laAn9ro`h7%fJ1pVth8a?8rX?+AVXfNFOGqw0(b_Ax&Sc^ z7y@;4{=1MTpw_`-yMzKT7GLnO@@6zpqd;A&>qn z-T$&0=Iq!AGWONRgO>K{Nu6MDAyNeR##i5FwJQ`@1@T{h(28R!t5-X+y8v*26aoUN zMerjyPgr}ph(FLSrBI)ifNeTrDhil}fEmd|rfU-hx>*1q)`k-UiAO$8UV!h6P~R*Iz|N zodQPcSH=7eWFrSlPc)(^mh7AyVd`ig@(m1BN)$xrd^N%3p`wjYT3aIzK=XmP5l{~Sn+D7rtWw#98lVvXae7Z512A*&?fbsz z^E+7-2z7}XzIIjs%6=Bl{5)@sFJkxp){>CJWKa}@r$}87vLFg>1|mUlf&oSD8I&GK z8eD<66*z^%0q(^mAePZqR0H%U5J>|PV&i-mDBjt=Vt4!7DFbPFP~Nz^H@KSDvVrUG z)bo99dZk!U!;l1~S%f(*6Qs^!hwrXI0tQ&NW{2lm%xaA^bAjKy?}8>1VD_7LX8^|# zQdm-AeRQ!GBM!uDxdg3z6{$`}jmP}q03h8?Rp>IVMEfco@D=cm-=x3)VaZjy^-)1> zEcD-;iwvp={S)*}fQcXtz_@ucV>n@yH#j;^!<%*-d67zWkk^B553ioc{F|szVwz!2 zu4J#CHi7Y<@*-=(BJWT`6o{bhxWP-neqf7UG&8*5-h5Y7>*93%l7 z9ZnR9cswMscl;_xfsyB5#E-c5{Bj^FxE)%6`gf~LV36FVa99|#_w*adCk}I2!E&sA z>-@gU^zx;-_M1Q3Xv(7B8PHgWWA+jvT=M5&~H8EUCx1i$#NB;oZC96r^|C6WT+%vv!vAqPT8?eZsC@gmYZ5P=glA8YQ)TN&5(* zIbZOFuBnA#)R4al?1$0MnD}2aU+*P`BM{*eh=(V1HqR`-cT z^@!%r56b;mJG6BdLG>x0t{byHI5zir5Bsox9Jy-G)@PvK*#35&bv_;M@0ye2<b8`CvC| zczwlUZ!aRcz169qZZi_O%Hp+x6rY%7S1UiG#B_T}<`!7)rkFx5J+)>Qe3W!sd*!X#WoZd$pkV2jB`2R;a&l~p`N)Q_%{bF)R>I`ZTl!2QO1lP6S5 zY|NIsjXAhqRJJ$Y{hgF3DKERu@aU0Z!QY88P{sf!(#??KTgc-Q9%F6A0rU0V0(xe1 z)0Z?f{`6vPAItyLt{Ih>n=a8;CM*&^ma#F@|7b#^>0m!Kb#3kz)6M&K2c%ZxcyA`*oXL+e&|IRE)_ygiUUj`;NW1PhlF5(8da+??OjqVJt>UDS)jB4A%XA`^Fwc+y%~rc;erU1S$!gUmCOh zVm_nz?5C`09@yG8%npcQVk+}Mljp}oD_}j>6!mTqZ9h<7zt+-L>#my7C{a>rh>D&z zsyzH{=kciDxl!tlj-=c^ch?gd8n(y-Onb#D33EloR4Ii|8(;4&a3@HbSy2rwr^zhP z zvLJ`kn5R6_!3sat&YqTeNwD^1aIh^j>Ds$RL07(Hez1Ld+VVk(xh17l+EDmXJzbD+ zXpiU{*zf5(O99g|U`*56?dL~6awaCN{t$?)VMVv^+uWU6w(m00=tzh0tMb!qzwumR zm)gwiYwy=5$FsA9V`maU!h8|C=jRCGStdMlTt5{nD{OnY z>5Ciex4mz7$`$NqEW6rQT&%DsVM{()mLNl=Mdbhfcx<4AHFG+z&@;Uar-Zz>_;O>>UEOQU)otXxeY-Y&|w zpg=lsx_^t5l)nU4K4RKYLOYib@o7M~+103u@9);066yvq=L)mh-~M-3mLGi4>=Mwr=J|3tZb-= zB5H)PL&Hkmd@`y{`p8SFD<$8J0qp-WNom~m>(@=N>oLRV@m>rr;<(942fv<<7mY5T z)l_1%RT;#Ji?4Lgd1ljT=M1a695bn9VIMSf2E%c%c?{S`N?;>Jv`gn4)9d7#3KzLB zsi7*XVap9df8WBSBzVl?&_ajk_CtY3jkE-7t%{1@nx;n&J&if~=o!@4Y~L45uI}v` z89Q*$iBp7AQk~Z0J&KcX(I{4A0l`v$T@EmT?@VYoh=>thzX~Rg9aU8iloD-tNG@cl znL+GT(cS(Siq$&MrBN7@P+d&}B|vlS+@j3P_JdnB)Bl} z;8Ox6&AV?iBR9sBy(1#tINYPzK1a|oF_Hc`2cQYEo(NbY?aP2RAZPCXcTW*;WlKrT z8A6UaYq+SnIoVhUM8~)OXflGD)StWJso@MsiNEZ4>Tc>l`)^0ygxQg{O=6;{h=iV- zeH!vbX;~_fTtjaQhGPh(|2!63%83%LUo#!uTEl!+byWn}!!#va5P6g3Mhj6>A8pv} zq*^=k9wrWG4Nr*ch@j&5zGY4LGquN-P-P`Ax1le#+{cX1AwVX>OZwK|SBRSG@Y2pK zP~xAU>;!iH*wUL*|7XN~;hiGY2|q%9TodD?UAEg|4x)N4?%LZI3MwhKJgz^NA9{p{ zP~)5@$r?WA&o$Hi)o?h?l}yZZzlbqMmY*(D70hU*JDSG- z8d@;vu-FkeH)->!Xmx8$IYo|i!D&UPX8K~vn0VABhzT!705XsHsg(rj0IN=@pyv%}XvX>OpKZ_c`v~ru zSAosR5j}py+XU8-&H5uyPiSikae?+qwDX~{PQJ1X|hho5JE>62-@%vL**m@DFjr*qll2E00j6S z8q!|(e3SkAVN}9e`4Ej_RnUGiu*YZxAbh)X^-AWx|5&TPA6f0FOD5n<8Yucuez$O3 z8uTMf;0*S8qj=T}mwcW}g>esImC?vv=QsyshX=C^P`K5n9*A;2U z$yPAA^LnSK65tH!pd;Ps&Lqymds%q@^K=i{21Akt;*?cB!jIO$oWcMLh>xy-R=Rbl z*W&b_C;a>AuJA9Ja9hoE0QO7PKQ`u{+u8+L;i&Ltg{s<^MXf2hy3!-MFz#LYe!I*+NgU3$M0&l{%>gZ_3zM?9%n+W#H(^Z9C6 z0qs>dL;y{_uH?F7iWKh7rU zQbG_9ohnHtN8C7DZY3P#^RDEi_b?D*i%0_y=sqZ2$ibtlr!B!EuR8Jqy$tATaQ8C` z6B85Aaw`F92%ayk5rl|hKOTSR-HTBd-ljV@M^}O<-gdJIj45$#?cw;xllbQnB=3EW zuHnh85zeEyW4v?b4#Kdsb_d5OBaIg5dN2o~ zBXgogu9sn!md+}tl0(w=)5~b6+4|3z`fCFX9(h4cX|=HMbe$c==QnzyqudS+(G1K?Z(duk%^jyM(|cF;5g(^zn{^m{`OpEH^ZofD z&4?#ZJ9iy9mq51c8R?Asx>;wvw-5cj3f1>;l7a4&;E;JlV*O^D{NSMSHq|`ci0=FLN@!Zp z(OK-+1`@{5aY_dMCycSx&Th zdwQu~!BOOS`c7%Op)y5nv4o&@PkuWWoOtA3EpH}%OfS@U`q)@jzHN1Hg=Of#uzf>g z&RS?XL3L0)r5%mIp-1vv#J5+M1Zp^$pt#T5rgu9T4fg6G+!M6rVh2jB8k@zi#e;B< z%b;_JpO@b%gKqq&0GkH)nnX^x*M(!*qGs#i!yRt2$cbkZ6p^VxMu>pT;Hu223tI=w z1JC#4G~U-+^@`p;x9B82)T-L7cKxj>cv8uD*l}_ygl2fkDs79;vvzHFQ+K5*2 zqZM%LZe93X;REenGxH1A%r`gogd7;j%QjIKe|Cc(T=Mr++RE|P7OVfL^5o<8Yz*Mr zpXXn)IQ8+^`a##cU)53h`Fb(+ovVuoClvZwK@+PTytBv~eal8dKAGqFEJCdn5|aRf zUhtyM+3q~popw1%uP7kmPO2F{9Gb+^-_?0{svKm24a?vtp%!nK4LU=zkvNR|K{rRx zS_1fe!=}%)JW-+jP^h?lROB`hx26l%V*;Z}j^bESe$6!P+9C%r$@&2qPN=2pqydYt1Uw>#L z@uBNo8Z8Oyymhi3c&I2Mm|EAMxS|0nfJjW>;|tA?j#7Ak*<}5~3hK-&)1MOgMPNFh zF*6ug^06`JuL7;6z48je82dvE(iG!nIX&wiVKk?}da}uzKn@vo;0cx-2GvA=5U3D{ zpDv=ud?Y#7~y?r7kCsnXq2OH0@yh-ZJG)bS_rpG6#4Xw|uzvhSUl3~TxhW@%JrC}jX zYLe-%WHT)AZI7|CWWj1~X04@-ncEdTdtsSwWaBX9jw9tk5a`N^}7m`l1Vj?fawk07=!UaZ6AG;?31S! z?|ufAn?&47teB0&%LUzy^Ab!gY~e!neY>X}eW2$?%w017MmwH#BgK0y-tT9lN2Jj8 z-da+Zj385Bs;7^j5;fJi=7X~0=IGQLbA}g|1%c`!!5c_ht?FaJ^$!1|A1_&0$um`@ z$u{jLmima2n^J+r%XYMWXiV>Q>+E1l1)lYFn`Z@kQMXK;#oTSPdft)4UZNlF z^PE3RhJ1ANj=)6jE}YPzH(h%_Kj*)Alwuew|G}wEw4^?x%td=9#c#j6`K}m zFT-8u(qKxVTp8(&R<)sz+eRL#LkM0}urN9)-rl;cdfvy|^~fm0hKxmAfk3%Aj9M3X z|F&8d7D^uj`_|(lr~9rOe%Jhm{V8R>d6K;XQOCrAXZW%$kNeO*xjS05evqmmtl!tH zgpUP1YK|@zSpRd``26aqb{4Vsf!GXAho0lxqQns9;Z7@K)$ersM!>ku3Q$H7*-STxWMm` zd6=IEgxv8k7%jAkbGQl8Qa=5?!9o`{taKKHeL0O9zP|*I>$|L~loIRXg6emwSBP%@$9$SHLO<{|8T@~8IJlX0J%bI*0y!p{~HWcH22!()9 z%QoWREa^{JP72`(dhLy#;HD$XSMw3fq|t$t=lMV;v`7N14|O95i(s}M0QB57}N zoVYIOdWpo;9WG^uJpL1+)OPEQFERD^zPwHG$S)egVO&l*A}E+~e`1}NY<9zf)hs)v|iO-za;iJPI>T`wAJBYdy8M`RiUFjM^u}U}UD6WBZXbD0=L-~I;GyUip+0aq2 z@-l=59bK0BMU2FpUHxEwp7ka;2|wjRaRQ^A)r+RBibC{h0*>taa~dqx8iG6Il2OG~2{6d06$K(>KewgruY;Ghd~_m$kJ zm>=ETWo5YALHqVXU8{o&g+&Xu|Ht5pGL6%!>htE{KfiDq-EUiA`o;$PJv5GZ1F|%n zoideueJ(Z{lLukn#xtJGCxj|Ei@WoSeb#IddXYOXvvmib8=#1WUrjy-)^oALm}vNK zI#Ux!8rq$Px*;!)y(-nav*xn$j*m^Bayo2YYr0;~2Q4_LgLvx6LUo8k+~%KfpSV*w z9`JHSJxx220~a-Io=3hq>-9b{r|L>nHQdhNTD7`L z1mK;iuEkyDsN7nknqQpy@_N}ng&U`SB_Rb6IHYYkgw<@FEwhs`d zrbk^xbN(~dtMfM*J#nTqMtuBt-n3hea=e=D-DFArI$dOVa0j2I*_(%Y({+#Am>nF0 z#0IRA>k$vH!Q}+}v%}wB3?F!CpfT?pTrIqACvE&SybD`7iJRrtp-&3xt`{=#pWM2x zzYJgS;OcoD*d8?~xuVX0d|V%g#cE=VZURjh2%StBoYDPyWIR};d~+OS=6Lx9*yZC- zF2nxVLWa-czC|JJZMoup3^Rqx*7D^2??F?z=Kzc_nrnE~@nPs8zb3vV++lXz6?ebKAeL>$(m1y4uS| zO}{bF;ibdk@bN7FZlW_4p3|1$Mkw>EA}S?uSQGD`eY;F1(WRNS6;egAG7W;uu9TD7 z)ymdT<*Yq{ly&_4ru`Z%_4&c~sR;omye7Kp7_IcP(+7OinPIx~)wmA@uHF9FYRc@W z7r^@EU(EF~*u=&OGx~`d+l)LKOH|ZZ*Y9EkTqz_PmLwm;#T}Oe$f>FESJJq{b zR+B*zK&^_2iD?2aW`S^pU6W>=li8Nvv{QHy4O<*253fJTfYHf>D6l&73hxXmPdYCh zp6PP5&yRFQ&P;I@NrrQKh@<RCe&P2;SycrteK7F);qGR)E z9%0~ue+_~Qo2FTAlzm#WwansbQzET0au?AZHA=V{*A~wX04~tTe2i^cIW3T3dbJbT zV|S+?r2MNYrL_m=CjU^_M~zQgZA^{<-J2^Wl^JUMd#9$~&!BK$hNIy3fgV4vo*VIXT+JKs+)h!cU2w zMO-Rmt;Y$m1zrItYw|(r%)H6Vnf=3tI7S{=+N8QAz(s@8w z$Ms0~=3@A@=gtwKQ5IF2XxTdniSv73I@$j?Jebtg?kE=e@bpagZHqw0>Nh2IQg?(D zENwf0Sl0KbH`7LxG#~StaojAd;7VMCpSXB+!Zn9u)SiG2SUY94tX9&vYpbTvn4@=9 zL=A>U@zn~?(Ny*jHgzQqxM)zcvKsT!n-Z^4i>DHgRI5>Yz<8rOtHe850 z+;}ElRbW1s)^?Kb9LwA*nyd7_aT1LPE0WA+d2X1OKKp?dNss}@SIi`H+j`G-9q**t zNxy4&Ea|DKX@C3%!N}!vDQ~%i?;+&~mF$7poy+-C^!uDOmZcIffG00;7WnuUa9@^>*``$N z_je&D_n(K?1~bj>C_G$WFTXw8eNv18@d~2Yt;rFgYyEkb2E_?8rL6SQaz^#VnVbvb zC}FrOo)z!x%=Mi2fw3p_P7Ao%ev{j?t^7w#C=THZa7o0C8Fp4+=xW3TRymF%mn%T>+pc@P(R z7|tBtniKQ0d2H`a9n*?UeFQifWNiid{OB3WJ|w(PyzR1MJ&4hcN4!>v7op8P`7J%W83p! z_ZlaOYm~jxJD8zA%_Lg6W4lZ!%(Pmhb#-;+y{<=kjjA=&n_SrddlOmNo7C~x`^q;J z?u;3_P-d|YZ*URj_-)AXqQy-UkQ5u^1;+>Hg>+;@qT@)ZLU*SRR#uCvY383Z>2&vP zE!dS7c?iTvlJZOuRYFVUvvNu(cJ0h}gp+Esa>I5n)gsqShOE8ztbJNPlDI2RHjE74 z=Wlf#w@^{J_?b&%x3ziPv#+zWF|~T8MN5p?@a%8&LlMJ*^hSIylux%hXpCs=Z%N-F zQ-Y=zlqa`>4NkHiIv(SYIz((|GiuWCEm`wyL0W_nM+QB5+iI^l?Rp$Axs6ilbrGY( zzh6BazMLNj6XRWdHe?VvIG;Vhf7y+Fvs0iB%9DOa1!s3as0;D#B4-YbxeAfsHB3l7 zTspn)x}S~8e?EE#yZFAbtV@Nf4lghs5*gz^!b?*n#GDWj6Dp7d$7^b@u=C-A;MJqV znev^4Q!PreMmhB~kK|dLByy(Kk*7oAJ9V5XNP{mPG$y}glif zWRT1i3XoG_B~U)${rI88AqZXRVu9P_*+bK!>rP|y9lmebDVTFN!rkv=*}|v)9@m$( zvjd>B*^dI1Lhu%twT%sX&^DUQL+~>X=JuDjp~REcOGhmDwhKojipj>Rj048&qa-EQ zmoi*dg{yN$vi5?kqp1<}2hf1QM&}Eu+zUy?oR6Vk3V`3@q#74fn z6se3qoA|poMc$%2r%q}ED=R}AnPx;ug87+QRe{uTrRU^pAclIyLc_KpAOHCDYGwXL zoL={5ev$R&a(8h3b&j9sAuRf0Rrh>!bcWCk%H@Cm1#o5w^YU?DVGgw)O4WX&i|Tmi z?C18lZ(kikn8p^ueTca5wn8NMgH?Dv_G3}MtJU~ALJ#;A)35&x?PUaUW&}Q#+__#lF3T;(GiR&T@M!K$Rt`?w$E6C3M1@~Q=8U2BTks1nKbBFatI=>du@!0PrdMt*{G1<FMPkB?K%cym@wa%G^9Z1$ z*Q8uB7r3?CE89Eh==)egeRw8^ox#+H;c-t={v2RZd3Uihhn^u%M7MOZPyz_%Sz6uV zZ<}0+U`NsZC-YKnT)1ce>L7Gjt(WYxfpk=k@LPwffdunGerjf+x3mw#^*`!X10cuwREruBB^lFS+b!Ivn z)1sh(1q!B^TrB4Sh23)m%%exdTdrJFJVHcW#qHCr5*k>F zLJ~ID-)~eeHMbW1jbSuSX@1mu@+>lhCr(mTldpsB3SA6t^~Z1P>8jrj#D2?6!JN8j zh->0g^l*enD4BV3B^w!3B>{!N)?MgXI(?xuM_ zn#X}}e1-^XORLb6BMQ3PC}-;(No3h_(j>ip{-E7ixewn&zk0h{8$oOZ&!A{O7R){iWOBwfKrc(((B~XfL>wOO+;#n8YqmD|Ck*(*}x|I=GqJ}ann;$@_ zB707PSLgxh&M!da`+ zdaGBGA)2fIo_hJeQ$MRzeBCJk_1B!PT=dInQ)^-UIBY>L;Q-B~{ev_)%k}lB)-@24 zQ_Hrkt>2Ewsh^L&-0h(<#wn^1IpCG2uHcKW#fSZysM?Y+t>*%&XU@3XDLvwfFC zuy$CMw_ex$)J8OCh?}ABAvef<&0PFr z_b-kYrQt>rs0mwm)|U%&cOEo~1g08N0grC~V(W^eD5UBhnU5Y-DlcEHZcAaoPqEFE zE;kcdl%?xXiJv!^+VcDrgz6Qn(GT{udZYXjOicma$M*+*H-z(_w5_cR9!XH!Rp}F6 zMe;u$Bv%7L{0NB-zhV8A;kKoPI8`SIXE;a+4KQ$mDk;bR^zm}Q(|CGw-oi9C;c=;r zgC!x*2OLXZ;Sr*$)z4v6gxlkj+Cs_i`D8Q3m_*AfD?Jn3;t|W^r+- z9&5n3d8c)4CM|km4w6$aGc(hrLWN9GrKEY?A6Q-DJ_x#NlA1v3-qEOe`i#5P%|PwI z2VbWAIP{h_Eq$bqhL0H3H@l3+*cw^=642xz5VG68l=xyQ?1965_$dv)>!hN+1Gd|W z8pCv1e(X^JSBN+%M-Fei_V2Z2A>43NZ!+TK((5jn4gBo#(tcoFV=Ci}GSmL76h4^t z=)b$w?Qu9R(w_wFs^|n+`S0AkJo5u>8F-inH*9o*Fxnx6Qs{+;IXA!)!4Y46@}y`D zWc8*F2)e{bVFi8Dr>DQ78%>?v4F7I7K4~IQY%@0g9R1)xr)zenFfV`SB}04f^t+0@ z!t=7y{?4(Uv-mg<{@M2TV$m!kmxreg_3(!J^qz;>rZiHr7<;(tlS|7bhzB|t`*jk!5f zw)8oy$;^t>6=;YiZqe?DQ(JdfP=9SXJ038E|I$X7+z%#f^H7b{u6vDlGs8h%q*QI| z&jox#E%$h!RPISqNuy77Oi;mD{CFj(c4#?#e03Z=I#t=40IKl}aqDTc=*Z|m+avKZ zL=42YASfb%aC0kxhW$W=0`zu3oqh&y?prqiZ!rVyQ$iZ59{3WqrG0ab(hld`>qy})cE2(*;8YYf3(b0@**vIitV)P#9*{{j-&A6tK7ngnc|Ev2-<$`j z8M!h3!x56w{OLZQYf}L=U7cTO4EC=rr0^o1_tw6&Tu>bXyZ`5=g?tO<5kL9B5ZO?( za#sgGF(_020*E)ty#~n5+0o~P>g@X!)*_rPbF~Q|%nG~;?CDRjbM%V&urEp^6f;rR2GN z-5(QB%(>$w)f- zSEVE-C$u2L_ITTkhtybbT75{#hh;CW>l-zT5aN_(?sQem6LBOAe6fP!42jBB2!y$l zT*x20v>TwmNvYj6NpEajv1flD9p!FHtJhN|%_WQC^~>%YBS3f_x5(fBB4q()vU*<@ zBO3!PMEtpr+EcaQxT6B+n*F@Z)KapH`c7`W$9wR7Tlt35j;yll5NAs=7->=lOKW71 ziAd=2Az5vgM-#Ex>yAo5q#&vLC#aMh;CP(V9Bu^19LFdn$;xPe9%#LeHj9o{FF*OM z83JNifHlU`q)g*P?vD>Vi|gk1<4FyhtQL&kL0Dfg zJj-qWdY2@BXK87ww#98%xWjAVn){R_}3z-+wa^yP#9QVShQTt zo_rFy4dM701=V|R2+DOD8hjET;Sy1)W^~5Xsj(p=d85N?*(aY0T{fFW3_y(oK)?-m ziGUXt4*u{CLCgWi#)Qi01E^dPYJ8>rcAJ=Anas|Af-J}>HH#KkraF2X0-IXk~$fd0{|Vp^gsAF@E83-uN5+p2WD59OSfri&ZHiRfhE;zB6>A=Z1Ysm)wY8PzTB%!K};~WrK!~$5AcFI zZ?9NURVLdr7b@mQudaihlGl6(v>;5-$1`;3@q1k4t1a8~UIGmhXfk}d2q6m1RVHh` z8WW?O4)HwCIj3EKQ5K5_ytSQ?oojMu2H5fL@v%h8T&HfzA`Kzsq2(`7dbnD5*-S4; zXK)1XrT@Gr)a(x!I~(6?VuDY^Jyy?zW12wCB;$7_|@j%Z&LbwxWsYP^|} z%9vA-<9kq~KAB5~VJ1OA_@9Sk2W`H<8*!d&yI5ISed1@6_VyM8Z-0ENfcvHGCGst! z(VBe1k9%K`eF*H#*o39$*sWvMvE^hzEKHEyg`0&z`9ThgSuA~&P%P@NW@_DO_;O|CHi7_M z>Us9LiS#*sQwy_>>-tl`J;QhLZ(TgBU}w~V#|*p3Pdpboy%KD=i!HQ%MP3US1m{8x zzMOzJ_00y~Zm3k~6~TA5G=k~6Z^hE#C@92vQlf8_8TM2M3+Oa0IEAG1td=5>&^R1 z9N4Bb@|#SB!}t0y)B$34b%Vmv;vC>aTwrE;5*2T%r}{biSZyQfyXiw&B9h4)-^4DE zN&D&K8q_Am3$#nUZGqlitl)xB@2I`{#fteMrt5C&^)bpG>CK&0={O(D2gynT-eEDv zh{+xQp24!CaTeK+JA>{zUX8+ELJ3Cd{?~&L^8kUrvPyPU)psBU&c__yJQX8k40t<9 z-19{cIJLZjFRcuc)B0}YZ&#+Lz8i7a_n6RR(%Rl0IR80H@<*(#{uhsDv1)i}8vn_O zo1(#TvZJ+Tv;FtCV-9zQJ-XKQ6UYLI`Yhv<- zsHH=@M?UbKaIgI3^H*I7c6@BS;3b^^=$@{&z_+gTP;M41rA?p2f+-Hj^u8nK>0DbVka*JDg&=V{Y0Ez|#38c9l*h?VsAz0W(GX|7NCS zZd_#ui|ABcg?$DU-@w-eeTa zcgwLw&ztWZPbXet-Ti#C1)44ahnV1~fo&Wec6tBFtTX3|U|Y0)WU_A6x5U8|d$ou2 zBlrJ9f_YqzB*6&tD+|Dv|34W*-Bm53n%)9VeE$#oD9=ytJqF@haz=#mus_oBCzz#~ z2|{OqJY0W5-?!P*>+SeC*Ik*{owNOSAGrGlExuSgb&5faJt%4R)m{BRg`Igg)NR|x zpZl&9N-5iIEy|MYTh^(NL{t;9j)+P2eJ5lWN!bPyGD7y<46ADdFg zq}{x(Hp40X*rI_&!r5Ov^atLvDauE|)ZPL-DE!hidSlqsgZ>512vYtD&P+KgS_uE0 z2Jyv=jOdI^qyJEUbhm9!UFxPhA;xaR&yhhh(jQ9_*zxPpb(BA0oONZDm)t4KH|lRI zi!_q>?bNArg>n#BV0AEz;^EuKbsHcW_u@w9MtDTciC>-&sZ$2CQE=Dy^D-1woK*z$lam(be*8l($@Y~%( zSQ3X5S4L(AOqy2{A6JCv1~G8GtLjc(h{t!1T1Ia!KeKnmya$JP0g#aN==o zo048&CJ<$RmJ)Dc>NvFq1t!Sea)-ZJK@9vLTCSk&!hJM~G3J@Vv=OXr+W_1CQo@P2 zL90amPGn5?i}=*gsu*w=3IkzLt8N1XDU|Tew{diHs*0==uwPKYtA}z(tMq25wL?P5Hmy$FdmCDwpkocrOqv|-CARkvwAF#P@V7`7<;H+7H&@d!R?+2xH=KTv_pgJ!_FaG=rYmEFc`}*=S+uSaag=vizzvGL)wLOz7T_m4xVb~8dVi@2q)&P}|QIkgzs3u%Efa?$~RDT2%?(a z2mOA%H;B<`(cH=@-AB*pgp;gYdznL*-01=jZI@}g{Y&tydH05DK`Ip9rCQvpxM~e5 zI$Ge^7AVl}D@oL$rK=EP{s0?w{_*DU;El`uZjTMsRWELu@Cl2jB^aw!dQVf>Ci81_bx z{ypFc?2uU%J>|+4eO;ec3DOtn=^7sl7{etoHd020L) zr`<||&BY6NoFh2A2U!Xc6G&g&Xgq+R0(y6*37zN+Rt{yIR2HCn5>S@$i_uwMMR3Tt zAqUjft7r~K5_+bu{3}@dDa(n;6^&ki-l=NzngGiWWP&;f^SO3gUHCf2ZQ8pr%D(MQ zrt46I*T%=X_TEXuy!nieN}$pFsj^UNl>{iJ*7?qidju`a9Q@O^)xe}1z)Pjk7!b|6 zA7vbt8f|3?3|1^1G`{E)8+40hibP-Z3{Pmy8DRXIOJL*r?(ANc-<72vedf-er?-7AGfu9!^}4~STyhgNWNwzZYu>^ zT--}|2axR}DEdJAX9fD`aF3KD(P+!Pws%gQ(s~t8yr4dehJ4tnom<|f*&V_)BauUY zf(e3jO23vE*bxT|ZwVarN(apW!Kv+`_<3@J3Kz(AXT3TW@zg^u)f zBixR;!>HfmAm!CKc0^!cZOpjBd765kK`z*7-vGY!J}>#F)9oB2GFQppp$oYcK)=GQ zvG+1dE^j^gIn_AM?!mgD%4}~p`Iy7~Pd=4p9QFw`4krQ{B0&s)dF$oRaT$8=nNIq> zIaU0x!fyE6_{3XR3ku!bU}ubPoWLRLDJ#4H>f0I#jb(G6xN@8-93rI6qnkY*s0978K zu>#bRE2?6N=~=2=p?7><{to!MtI6B-tU=1fbRgJj3Gl=dDY`{Buc{9B?9MZ=v`9bv*klBW?oGo0FeMo65 zgRp=3kGJ_u3fmh+L~lEo)CxpefNEaMN=1HtGpmYnq!t9J>#;L_twU71$Yba7-4M~$ z9S-(-e-&IdTthd6vK0El=j9y|@8OIBChYF{pjTn}*Fj(##=CYEKRUlLL!z^gBrEG< z3F)acp187_YN_)_j!RS!P%tsQv%3p;b+5_a!X7h}-ZYClaoV_r+f%JO)3@-mM|C6C zR;eSu$UQqVKEr3$eV*noE6&R!oI&tZx@Szwa@z;oO%Rh$$*j}USJ_28imwWfkAPcd z9;tT|&i$IyI(^)vziM=@CzbddIFMs@5QM}$Fi2d~3i(PQ(pECG&-UX3u77av`>)f& z9HaIBWvH@_1#obrXef8Q_Mjsg)IrKXZB+Td)DKgc7_wl0l(-*Z6)3$F*?#6fS?=*I zMT6l0g_`mw*o^PF&@wso45^nyq zeI0bgL@BurIRa|aEflk%k3&3P%^zy?0xyCcx<@Jc`3kvACv{6xJe=kPe|FIh(eb9T zr`)zrXwj{|Y}V<#%lfWYVo0s;#ZPc279CwKX@m}E;$+6mgt$oJa!gWR-_L(6pLH88 zT-uaM_0zm}=BOHeW`V`Vm#q&p8?D9JCtx=!(MP}`bb~&i(q?l2cfI2&P$&{Jl}t}BU01Lo@QbdFuIZd;A8v&~lPwOZm^LhMWf5u9-5p0l?2Zb2&|4gs0s zB9=-e_bJyD7WB;_g*y$Zu636^A1iy_u`aw0y-BN+s)6_5NFlSrL(RL%J4G@tihVn^ckIkq3jQic;rves_zGSe{7xwla$` z9}~*kHU83zoSKQx@jEG25D$d#1d$1_+fljEH@vS1YT*1%z0i7e*K#A93VawN@SGRnuh}}6) zv0Ta?vBfG|?O7ci_pQC@BhwN4&Mf-~L|j@*K=Rqw7mHy0KT@t2$$Gxgw8N^6FU)G2 z2$T!i4&YlXR>tn6?`x+8Mz{6XYEnuX!^QkOm<#eZiV0&;%-(`@X-e)_?8zO9W{;-= zBNOq6GoT5|rL=B$+98)#HzeJ-y2h}vDk5=_w_&4=zhQf6pw>HaWn0WlQQcGBGbx)G zC2Ex@8i~6S5RU2`%?ftnb86v?+4ob~+W&z#tEY!&(5at(q4WU&gcU!=p4h4mG%cI) z*lW<>MJ@pNAy3%b(f71<5o1jnDtX;9t*v$`!Rtt9c$=^m*FIu2BbzNJs1|Hs((9aJ zX{M2Sj-jF1UPm)6>q$})CZK;&c4gGUNzfqo4o%GE4*W=gT5h5vF6lxekUH3kuw`EcvD zjIh5qQ%5_hzh9h<#i50++MCFZGbUwdA=cJolb#UZlB2zp+mNG>05WE<+tgFvl{$6K z&I}fub)vb`ERIFL(QA!qih0U3wobV2eQn*#6R zkTDO)C+z5SoXIpl33Xr*=~Yh})_r77;5S&sk7K1|nA;8CYq?s^=&`Ph*+tP#q|9!- z8wNA3)aW;gxdiKh($LOb56fs*Gp@2SH@}LppscU3y1PTDOImGxS~iAIX~%>@!IEdD z5_EKHnk7>49`bH(XQZDRCTc*_MHYAKT}(O@c`gn}k-WC7lDktB#SZdwn=-yT@ph&L zW=k19pSp&sO*YpwjXSFVK48?2I?gUkN7sTEpf2K|OyW!Ke#;qmnbe=T-T2z13Lld7 zoaGYB8^Nk|p+{1kch{Cw1SUQ=t`aJq7i!QK!Z03D#3-Vu#uT$@7pLjPM%BaEC*{rd zi$MoUN?ufr-K`FTF3k^@KV3+dzHL1)gg+sY`k=UKJW40hn)bWUfSe7iq1tA8QG#)w z=8%)Xd3)$5lH_o!cQ6~uOoB*q);I;&#FL{%^?BeEtu{NEr2q; zw58h(HyxHBcs9xPl6Erqvuym1gl#`ReOB8uGFG5HAzNGPZ*16%2m|K$CE(_;Vl1ku zZ=y>gpC>k5c*4y`p{HBQuz*CFe91{p>+Ztfi;V0>?0ydtKY$T*Ck~CTdzeK{*vytA z^VM<>`ulnbS}zkZR+x_SSvW8c4yOFb2#UDZ)0{x-!Wb_s+dgZ~iiZgtV{<3CWhaLup&^{PF{9IjF(Z z3P~Q{x^y08KPiF|Lk6Wuc6^$%^~HBr0*hSGt>nDrUzp1?T6qDwhnSFd1&$oiOIYOq zVNyK=9GH1%Y?-t6?SidxsKlI;@-~k2$QXJHTK@*QHr+mx-QuU1BqemV}z(+Y)mKzZExk$yz681EA{=^@8!Ne%(4%MEhpJ}ppJU!$dMH#L9f z_DpDf?#+Nf1lePcI2X8BO0q-s*e~KClR6U!)h+VDLp^18DN9NR*6pg5N^1eUxC$H} zhJ9{%m%H(Or)s_3SoI|8&SXUq8&2(Q(3QZgmzFfkKWDO4foV4lnd3XDb)i95AVW=O zQfa8wDP^{1XDgq7(HJdPX|>H=Dq14C44Dq(^bA~ES8OF+I62dP z+fg!w`*(3Rhe@f&h~BX71>TF1{bOS(UfC;`6xICZ3a{jMiM+4vd19~#9?-qv`}7?O z8heX;8c!Qh$rc)-;js(@?wyOi9V3rTbcVE1jiug!o}&WSzg2$*Q`?Xk4Ux4}9?<&B zwq*jl*WkrVZ`@^9Ued9#XUszyd|z`JcRwt5t00n0``tU+@?jY52ch2E+W}u#_=G2| zO>{1KTYsoO-S?|r0Jq?Z&VQt*EVe4|Zg@7;>1lL>`giI4>l=ASHce2+sr-?+#7!!^}DufI8slZ(&uCFWyrZ^J*jg^G&hp! zpXV!zSg?a&JiJ~>R!4TZ&==T#@mg79Qgr#{le;?uUBlFnw)D>5FRBiRj7d^kJt~OI)i<7d7DNF;m1LE5d-82(zhnq#!mcET*X5oFd+sjk8w=TtH(EHe@ zel6u5TASt$#-)U(Tr($M3E4$QpFyK|u2ME?Ri4v-hf{2g@XXEb`pn*i;*3+MX1AS~ zp)%B&X!V@@=H`{_!aQl*ctjkgv(R`_0&lN?N78WmS-zU&Ji*{A3oc1NI%+s;13d!W zCcU|HUGzHsLrgXy_oP~_Qt;x6X#WlK)B_U-#=*w0yVZVga zWtN2PG)s3teht<&CXo(*+A9>fxEFr<(YiK~1f<(r56Ia*X*wbUc6_~zL=kyRwI*h zjbA@;fsxL3Yio~<&1mvxzk>QR_ctHz7|Zfy|5m5t#VR9gkx!5_)=235`Wg~}Qn&0` z1>J6mCHKRl`hz0&SH{H#pNqcb_9s3NXPTMZ(*&E)z*G6?^>*ISg`8|2PO{zg?#)Mf zTzHKW7-~?G)6LB?73;Eeh|jLI(zXY;|16i;q-QGlykTa2UdA^?36>^o$i8nL68S#* zdWNNo1u+MxWkmw~`Hi<*$Bz%}0eLVhJ~?Au+$-b|+%I}OZaFz{-MpM#NUXcXLZ3F2 zFOBD1zrRnKxnQ%)<>~czE0pMJjFKx0uuQvCcbUx1cX@Mt{OI#7ua9P{t^OIsI2=bY zfBZX&5dlK0K#9{7+_UqV3+8T&_ePpNzg1!iO?Et~48C-r7yUH-(4_Z{884&Z)zF-# z4-9quss=#l(hdAtR|Gnn4(7A+Y#-*en#(%g+y0!J=>FCzYr^sgeHr)di25`xxS8kt zR`BWr@SlIZ8dZVc2)q4GjJBIQd*JJ6119k_k$%X1uzTz_L_hkzW#PGK^@S&-o7kiM zqnO(KKL<@7D|a4;U1yqS`A%mym%&{mTMO)uq~%x!C(Uzfn;5>H!bvy!=ON$$W1&=w zhwS&CK33ypkB{Kz;XGE}Cer=U8dljR*tHEw>Ri{!p|VT|&U%8s+)%#SzQlW3;;s}c zv?xfa{JuEbv+o>lcg_FO3cWM9+a5ybUoN6PUt54|50Do>O8=Bxf&6*pk9CzK?o#Pe XVtx0;J>!=moF%SM9+%3NF literal 0 HcmV?d00001 diff --git a/tutorials/files/blender_procedural_datasets/demo_blender_rock.gif b/tutorials/files/blender_procedural_datasets/demo_blender_rock.gif new file mode 100644 index 0000000000000000000000000000000000000000..e6978faab422329375f8230f04d3d403b5a75449 GIT binary patch literal 751047 zcmeF2`#;lf{QqCG*=C!WL(Z`|&Up?wAGVP*IlZNnb52R4goqs+Mh>eK6_PU{O432i zu_-hq(Q#Bl(nv_OPoM9<@%`Lx*L6LwU$4XC`Mj?C^SYc|9L+64*uN{Uz|H6vvO8D&L;vZ9poZmjZd zbu4x_P8o;8s^b0`6-|}hGAc?+Dp*w&teOf=Sw&4xRSB!Aq^7Fxs-~o(hEr0*{cF|K zR20-yG}N@L)K$dQRW&tsD{1al(^SK2s^c|{T=5!sJYE;CZ-e*t)KXK`QdiW{GSUi& z(ALz_#_MQn>FQ|f>6p0b;?cTV(z<5edOG@gPT~4Gs`~nS^sRjKZG!aed<}GT40II? z^a%f3Oi2W7JwpQ{Lt{%L6Ki8b6BB9d9^*Zx1U*wjB~ueKQ!`sLQ%f@olDX+_3wbRI zQ+*37dkb=~rMZ=rg|(H9qm7lVjZ=t?M}qAhJzH~}t)-c*m93ro5uz=L=#@g&-$N$i z>`8kah^7vH346&pdjqJB`%|6vIy?JBx;UA+xwyISPw)sx@pLrwbT#mFCGPX^^1`Tk z$r^Zh5WM^%ygf+Xha$a$Xg-=IK3=}QffV21RNsiA{|L7Jen$R&`}g~K@BeRaz<*W& zQP~If2Oc=pc1Y3e(80rp0)r04Ukdt<6m%#!=y-APA#$juZD?>nJ1QWR_`v4<(~#}X+gPEb5gs@tDT3`{zil5%Qa%Bhp7$$_cKVW~x(r&H3> zlY`SwXP!A7d?qd9OnUg4^vulDVVP;(nP(z0&tzntp;6O9sTnl74~d=@#-JT$(4rZ% zEau5@W=?K?Zq(TtZb5$0xuUqz63XS$E9D_!<(CsH%CBFquCKnDdb73tPG|SMvqyU# z^z@I+jEy{h{b8Q>@$>g@Keo4a{{H62yg~)BYgrG1ONc;H$)in z&+7iG!2il5_y0uleW*`HPN zxZk^YnL03CnZ3ukeD zpW8Lhp8LPPC0xze`*OiYrY)BDUGVMo@!$vZ@%$8o%-G?cy_Zg_mfG*Tre<%4UX53zqGf zdMRduFunNk8WpNNUzH^tJAa+2(L7&WV7fS8!*bMKs4el2T{z}-r^b_Zz0-Hh;_7;} zr`6?@W>1Uw0eYU=Xk!hUb@P(IxY@F-@#m2}CrdsRnk}aI>R3NC{S>pO$j{fq=<0p# zT(f(ZUTSN64^fG;SXqYucc6c&|ZI3unpVO9<`;?v-=cQG*v(&Uad#bg%KmxhTwfSX?iWbTgQY z&3D;zSaZj;tDpVS9sja%+}%Luk|5ml@hd79WpmQ6BkaZ~`+|#UnVK(JBks1_t>-2C z<9~lCi)#BlSDsvSLZ*Xlzv!E6S>36)=qv%v@TyqU-W^rtE!>YT1t(ZJRDqlnzYoR~ znQl4l+ds#g#CFzR?BBQZYci^MXZ=m`^PPX3XQkcw5ykTLudX4DV+7sj_l;tU$x0p~+$I!Jk*AMl_V(ZVr7OKbIQIR2@G5I{VZTLwTDZChnh{W8B$` zN)CXe^{p^XM>?*)8ELTH7#2Lw*!p=55XIXa(HgTf-AhV?fE8EdoU;4Q!I^LgWf5&B zy%*lsrSGWj{SqxnJH1we6>V~Ma(zKGI>}PH^&g(ivLe>Ga`HTjf2ov255BGivG`8K$|YCia@IiMn3;T$zf+x%pb zzVMBTL#~tAl{i$?t7gAlPbUeTzgpu9bq;;ietrMNueMX8Izb!FuOF@cx|xw3F3%-Q z^+~L^=XmIb$=sM4GFtB_D%6e8)R}(jvwrK+sBWa$jp?z(_1l%AdeMefQ{(yTo%J4i zvHNelnY^`rr>#&gE=uR^8^Me9uCCEzVaOX(IC$?}GJN@XF7e&0{6;s&qb;%Y*}FN* zjeFd}wv!ER?-vhl+@Bh4J9YQj`{mOc4|t+CQ=YheSiQ3GaNgtQ>DSLbtSiX~@e6OJ z&jix8-rNL`eE|0Mrbc1VFkElM8w1bt=( zR)F7P<+^_sZ8slubWCJjbpNa>^Lu!otzM)z&zxsIyknW5G3W>qXgEXT8V{X!qALNFb(Px~o0QTZbePjOmy0_kbG0XC~T< z?zBXCd^`AdYqBA}PkNPCZpU%Z$lmOi>uO&NyLnoqVhq6e^$2SKAUGKik{rOshFu7q z@CYGG*0PUj6x5jI9|9S6p@>AWksm0cn%F~j?ZRqRN38iEF+QjR1`^{Pu`L6SJYlQ}2m9nEy@bW=!U`YJ zM0{tVstID7Y-A>ocHRjZ<&{doLN6x=LqibjA!3`DoQGJ7{9VYR7a|pabzq?uRoM%7 zK`=IQ6pOHCLwYD832bDSQv?))9Oj}ts?yXj$Cdfu%&J_IfLNkTbbKkwP2h!2!y;PQ zU@{S^fQ4kUkqTaEY80>9SW_lfq)-!~oC3XZ z63WEJMS0Pm|BJO;#8)b-2%D?P6(Ul=W<vRZLDP z0IOyp(pV@@CP0#jkhzS?_CmldP;zR}ReS`Pi>x4sx?M&|^dUP!?08&cNGdw}U-VA_ zIw&H^W|z_^=rET{57|in--|x=%xBQPFY~p(YT_CM68R27EP> z9GEGZ+%j5Jp&Ab^M}%5a0na=@j{t+S0cz<*3uwXU9Gu5RQC>q_S>Q-bh#MBlSmX%=tZg=n%6f2zcIUZuelp`vz}8w=60 za0DJ=7vY5%=ELf|l3xqBs8MV#uL@$e0qdZMHgVBRiby5}-GPC9KMBpoBC-Kra11>? z3h~ejz1A+q#6n+UAx#u8e;TsKJnbbGI*dW45i8$g5!0-a;dU4pfPqa=fnKGbFJCD$ zi_y79U&J7bsPHhe3lRiZDMduNEIW{yw2KE1*@UfAiM$Yiv<|od=vHZDofm?~tro>c z$fSyRuuxx9L^HVv5Fg~wb#a&=TG~$UsLK1!gWGY@Aiq*@`&sf3kjX6_CZIZ4c?zsL zBGPqd#0e@PIHV#N=`Bgic1oxBW=Ma#g!mZ8%v9Qpj$jhR2&#a1Yyi!8)607(F} ztNCEqd<>;ZUk(F^Xw}-Wk$e`S1DoEP8nbv=vM7c_ABjrt2 zE4TT3JIvo1O5s);T)A*18N9+q{$wF~yx=-I4I6hM{RF^6z(Q2F!}__11YSugn0y}3bMi#8l~R$(7w|XVn<&n z{m&96MvU0Sh4f&6CNFqDzq5jEHq3^ESVj~55thvAA}>Te7qZ_CT2F!Q{|2vMA&3-_ z7%E)-D#)55QUqLMwhLobpdDBQGXzmbfl3B6&vZfRYxIjka;gDz9T%Mmh<$B`z4k)a zd7=4U@J6?S9#3LpF+AVCwTQxE~^VWDOr!Q@D~4;!M16}D(Ez{F(Q zPsV6$_Ek9x*>NG0u>N8Hh+XXCXEs1;6d|>CkVQL04s#Cf#W=HZ#`9gWCSTYLlbgyD znz4$uz6T4$BC7eYV6I3Y_pUV$ek=}=**+9V5h3%zJpc@bg_O1n2U%1#VNyG|BCj2x zt<=8S*eihq$wdK1EH)h-!xMF9!ubT#mjL<%_k0l`mR5C?ladGnAVvJTPT7aGho07_ zKW((`zr(p=#&0gAh#rBVeXtNB{@9Pka61arjtT_xi{5qhU068Q)*Z7Zi~LHxecoL3 z$8<44*cVp@C5F&nPPauaw#D#4)>Jyzkzq9l+IAE|@%vO4(s%Je9_^4SMXR zC#CJIX?2emqMCcLng`D&W=Dl&Ki}>}?N7i^f$S>u>naE>If<`+a{W~qvFnT`EXCI; zxF>f&Vm^7-4h7gL*$YiNFc%}elXd`l1hpb9mv`mi=)8&BIx*$w$tR?`{BgQ%k zR)y0jP)!QBm3Tga1qL^%C9ltWl z>(m#5n7}Od!R2r>?n}wCrxAxIBhO5}a!uV)<4B<{(8F*H9aQa|^jrkSS6yv}B zSy``NXPilrBV6QhiC-zXr7T$N{?wzTVD^*2U(rKX(}e8W6YadF1A#|tg8+FGfMb(b zzX2ECLyWdoQKeI~!KxWNi-2jL+ z7edAg-)n*-un=b3u?;yNGFhnBkOE3_;=`Da(G?%JdOmKCo-l5W-ztq?)HnnQ;z2Wb z@Jb#cp63>F{81N7Y*`WEd`!yom@6@Rrp7Z8ce4z?tr%%c&-4%_u8)m`|@5` z&35M<4N+ddWjamRzaIH9(E|9@;m^Cc6E}@I@qF%!kS0%K-?3oI*!9SbU?Oy;B6h~{ zn9RO4!Vi8{@Mf0shn(jdwR1maUvDxq3(}P1^9A=@*~2r^zXzmYJsO|J&OuF;4mAz^ z>^F^Fojf`=qqtcgUp)js+aWO_+28$E!&tqs$#1(d|8!sbbN}(5hadku68vE+Z}(-s zm3#PHUF=W)we6>mx7m-aPGDdO?N;1~Ap6Wu_(!X)7}o>cm!#&?$a#y%HquuIvF z?zR6U)^%+3)|Xx|=fGXNL~c^xuUy$Wp`ERZtNZyOG@6LA<00{c8I6oT`i}0A!-Y1j zSp%&{O`nJ=S*VS*zMX}!M&e3Y;`qqfFM1EJ?6Nd`gTp)u6pWcKo*YiP9Z;&DckWMT zo*BgfcX03fpFWzttp_hIPBeK*E_#%)dYxyfWyTR>apEr=o?bSNx&OLTOG8v{{qx)8 zjlW8^X%aSx_t}AdsNS>!z-u=j3BCVT{0NXy^m=Uk2>!gwgy(FJ zI!pAS-xqTR3?0OsP%HKlE`*K&$^8)>du8^2{v_pLVzGC~JJLbzuA5Ju`Xx`r1jsoz z3~Aupm-Gj<7`0MGiK69I-~~th>(p_Q&dmWMH@&-`Z@C#fh8U0N3a8gd?Dv!#yy*R+ zMb*jMl_u%A5bftXy2n1X2KD2hInngZ!Fh*@#4GTk&b+CuK0%{i*?e4HWPOar3qAUu z>v;y-EeNK1EtLm?V=y(PL1Q6RLcaUySNyVIgKkg_%&bE@zc z*Hu$^wpcw}+^@uL!e^FId+DHxhJ>p(>{@DBhznD_-E}_8=P#icW&YQ>PB=HiIlNez z7cvVqukAi-a<4@87?Lbgh-4~WqSgd86iLp)vi@$-oAhR<>=6u{WFyP2t1-IR810X` z(a&MK<{Qj~%!c({DXYO~tz#H@c4bB_5u7m$T_kBK!2xb~iT^WKeZ4IFtcm3_T%r2d zqHdwa`o(!;buV96jmx*R>R5@Ggx>2pu~z+eBkE`B1f_AO6CmadiJ0(fXEQ3|3<)m5aN*HUv<&5l@gHlLC-y_~3j&c||mbi-C!_P@1yR%*`E0I(<>ooDn_n0L<+a9s-WXeRS~nEA3wUD7zrN>S69k^; z6-wIR)GlP&09ctfW$#h)N+xIOhDa1o*w$}Tcx;;oac3j^5Aq1< z|H$DczO?%wB`?vWe^2R@kjf)$w)r*>nYw9je1%UtTJj0D(w!wm!9$(Y>_tuxN_@jk zfCFqIkr8D%vIs*_2a`~-Z@QUE(K;s4<$qUvreel!(+M~ zjJjCvICzdoDc{j3* z$MSr`vhjPh(=S~8>Yi&EMi`WFCFOJeo9C9`PM^m353DN7!a)DLvyC)4%>uJDvpWhS6U>x9!g|GwEo>3 zVIjmY92?k&1B5U{T>%8jgDXK+0I?K6NJA$Z0UQUIKpzN=$yKn%b`-P{Bllro(1Ec| zI7c_~$hUxzj75MFO^TDF{3B32;A}QAHawX|D(GWu6PIo8?}xjbtWj9RJ7}(JSNQ#d z&zoMs);!$qZBd5IF@>DtbICdDz2V9~=Y_Ws-s=6L+@2rV$J1d`=43p9w&484rq&Q{ z>0TrC+{Q`MHG$;uPE{Fsh(~MSDk-eRsA$d5Boq^%N^E_w==ZmxiB%G%NgVM}XQ;X5 zx%{I`GY~T(Qa0w7I94e{HWTw*IVS!Jmstaxtlyk-#Hk%U&|vaZ`PTI!w-K=N;>iK!T2}szciR5eQ*_0R>tdFD zb&4?@z9ij?d(Is_M<_&?S4)*vAuvidg<>P2V#ChD%x9!UH?=!*Yvs=9zIPC#uPaY{ zsty`0bwIoa!bIvh|L%5o24j40OR=_fodr}(P4h-ws1nmQQ3-UsEVs$0r?*^Ze`ya8|FfqZSKe&mv=N^ zdEfDqs+KABax$L$bj_zs@k^1cqtU^0s7sov+S%}%mK3Km8QF)Zf;v(aQ3^r6x zlj&eG-eSg)-Y8q=uNSNhW?6|2d@?HO)1dn5FPKOQPbghhIPu)ok7<0t-CbXK+0U$S z2#Q+a^A+Y3>k?%#Z~THpN3@gi8}YR1+YK0Ibnff5>u7Jayq;Cz%*{c&zw3UX7`cZA z8Fl0Jk)7l-@29-?d?vs}Ri@Y*WkSi0^C8&Ufud>-!>}zVsuh~;mlgptcQo#~H?upIj zQ_yUjddQi6_vy~#){%dv^hN#tdBF#1n8 zgZnqnYNXhwL}v$-4kLnV*c%}9#~WrN$vB12HZOx_{zhs6xz+$ZF6DO6 zgFa6nHz0*-U!W2aC={xbyB-4~{|4c@K@N>M(p9&ukJ3WDVCS@RKR(N8Vm8^}`#k^Q zgf060m~0e2D`Gw?7Ms5Z0=sqV@@|ovZqYf`-ym;!+3QV197$0rl!;Pzqd!KNDrrua z6cf?O3Q5R902lA!XpvR0+_Tb2L~0`@I}%VF9PVts*B4>l8R%QTy-D}fhTOS|bwojo4?@IMqJlr@a4kA->T$ew@D0`A1|9$#jvGr!Kso#R7tFcLgPSgFFxi;N(0Fo0C4fCFI&ZiBL z;qCJ3F2|?tZ-w0VV>vkBbAbmr>(!UzQbu5O&p`&!fdlQ&vvBef@_*{m@Qz_V;j{_K z{m6gfr#{@c$?$&wEzzyruy%0*nsLLoeRp9Vo_}z?eBwk3Re?RBG0&O`1(Kq#o{HAI zFLg_rd)ryt2zQmNL2xW}sD`of6aQ`J3-&En!AEq@$C%RwuQW7EosGc=%}WYf#0iB% zrXrYN!5LJ61>sgufc?L$BDx(|GHl<|p&zrU^NOH2(Df<$XE8V5wngA zm-*-ajLR6xii*eKmo4To6(nZb@3$A*MFVhPk36u)dzqHQgW0mEmgoZYGKNJoO5kQu zkcb20${6M>86!Z>uu<*@*Z$VQ`$POofi!TAT!97?JaI?Py!(~G6eDmUXij}lvW#PY z;Zf?m%;W14MOc}WJ7{(8<+8^7XYGeV;y?}nEb{@h#$0MV1y@(~@=LVYM|fGkD%cxK zyKuBIBc{>#J$>FN+vZ!Azq9b2Y5K))7+jefIH0@a7VPGVd=ekH&1IhMEH>u}YY}z4 z=dr*z$yWEZ$I_dV-qN?|Y_IaK7t9Fg{a-PG2onD=btGqK_ zxd^OiO>~8rEa04w)q!FBI8Tp_@S8rH?Jql3Ye9R;LSvovjF{OhHwE*6djS|>CuVka zzOeaxmK~?%!3d*M3lhozEB|Il^6z?589vk+vg|E$I41zZ@Z$-C`9SgE(f4ar%UaX% znEQ4QbHe)@)wf6Xe9~_}p|E3ezEk_=&#ebvWJiTorjJCL00#XXy3xQ^0!L&AW{!d3Ep(Kri*7o zs5m-!d`s^`?^|loZv3jsBR$g9O={P~V3`V%uxduZWHZ;Hg2L+O+JQ9_Q*yR(GzHlR z#~7qX?%1-pCl&55yDGu~ytX{8!8#1z=vx$E8(ysKTN?9tiVWrYXtq0h|H zB=JK5(R9Ut-QC#6#ys?3+EDiW(%Vy)T`ym3U(TE7%zY(BuCP$b_u;mNO^@$fwOdt9 z!b{~6%1eKv|K(V(-%>P`E#50q@Pu2eH;+mEjn5(|US!ep7vfSwmkgo{*tqf*BUB4k zu`jgj<159tRY7NF(cVO3`qQ#LLfQDb3l6_K1-m5p{^{d5n~C7-Idp@-=F|zJWiVkG z=C$1K8V@E=2Yr@7jSu~&gyx6h$HRb6wz^+TmqApE*XuUcVm`9E@C^wo^s|Zvh8LwRm%hY+?U5!D z%(G*ZuV;C8n2x45*RQgt0@YbU&`pLhPtSK4m|1RBk6P78Ue(N9)x1fSmL)MNccq37 zT1l6>hav@Fy3Kr+*V~K7x4~E2Zwa2vBhP9T^m-k8xA*n=1N3VjWE<*F^b&OXIC+*& zM692muxa>N-FAX5Bs<7I!SOm)?v;O*lYc#I&FUjPc#Gk@kw?a8WXb6mPBE@=*RIV6 z)tVMah5#4BnC$sWBI0?Mqi_D%RE8$7jvrwmlYc$W!$1~_D|S_Y6T}=F%4L*xBXGL; zy@%J}Vp^M2Nh}TJd`<==9v*xO^P85>0f~pM$Jl`)lTR(0gLp2dj+({9o2|#1#Y}<3 zUx(5XH9@wU$0yx4NL+>+MmWe=*q2j?y$6{$-?NXGu$iaqKrNPsN@&ce2fpUhG*kYh zfK5U@CO?DuF4;N9Q+%Tz2~O^-%6pxq)hM(Yy+V#DICdVcl;V?f4z7NCiM5&Xm}gj! zLQwYkeKG3yrR3kGxv7_6Vmb{f=YpjyWD3q)Vd~+ltLA?%A1)NDTCJ%sD$~@hZiCnC z->Qq+D)#!lNZqQrwAGZm)p%{|#^dkJueVyiZnbS}wU*LZSmp)npIgNzRye0`Z(Lst zpIVo6&2J?fPWz4yJKaQfM=);3Ak5RBJ=x(E3u(f^;)#CK@GCt6)Z^xbo?uZ1#jn_Uo{i_bP}xX7yOD6tS1XLas`{Eg5M2-t-FFh zPXu_98rVGT8vxf3f}y2UvalEQ;oi zaV0{sKyja^RP=b*)ARblbd*+m*l4L`@@lQfKmJ%r&Xv%MUBkbqbv@@fu`uZNRKvM8 zcBFb$d-8@>$MT5$Nv)~&uqWsB-X?`fYS>SrFUKYxaZ-0H;r_QefgF*9r2q>$12;b^ zn{*B3Ru*YwYvyln&4 zj+kHGvD*A0<72HY;ADwN=zF%?jaTpev$+BT-wO@q6f3U7#O4xevd{e3G2^8P|1G_g zu@1VfEEbISu1Z_#b)sV|*f1PbIF@-mXSwGIBUe$VTRBfHKBYQGy}4WEtls@il>)=3 z(X&j8O&(axbgGJu&;riUi%du0HB|lT6t(j%+V|8hcv${cEAhV1qa*MEsdX2L)fAOt z?WuXNsKA87qhHjEpb(>q2UlQMkM$+Ul_xy4(5y&u)fkAX5xpH{*n?%b8)l-x^OgS| zS)vRo@b~dG`9Uv+Yl=-Rn`%k}w6*Fg_(tvqxu>_Z8n5SDYB$wgIj!B?)O=t2MwLda zR&9r)wodEqH*cO+4o5$E5AE4{a|0@$!Xu@Iw|LQ@lC1reh8N;`2h=4jRkG8}%DJW4 zcKDe})rdp4veHuH#>r^1!@RSkSy`HW1}JiBM!CXV#erHeU|3eipMha95<%o45pqNT z?)Lt>SeI;m%qc4Xa;GPo&|yDfYsG zXxsIE<@#D9?72Y{clRoIKa=qK=sg_r9wd-!C z`K)tI(RRX~dRF|Iq{%?lM6KzHuG6M(Vs7-9zK#0WG9?x>duUoLjMw}Pz(nwMJ}N|W zNvZn^K)p~cU4$b=d-h8D$3+3$M@cd&ec zD-?HC%}SySs5=;nrEwYA75D*lOaeNsovZY66TIRuPL?0Dmm-|ZGQ-?yN|XxoJ!YjM zaiMWQU1sftNsZR1|L|hS7IF{?R6hyYJ3GMfTxOCDxwCP{7!GL&gyhZ7XBc~K8?pvs;0bGpP2C|`asBTox+KpnG$)K*LPCO zAxr!+{^jKt|DJJ9pfFv8f=DU)=}Zh=^$~zQwW~Zx~WGl7bv?pme zA}%y+GFC_~p0DdYf+M%Gaf%#lzVrYeHQe$^QS2zfoJm5|HD01}xcfEAX&nUXex=RR zU~j)JNe}9TlK$&Fb*75L%XGcCaGkf)kGihdc1P~;{GGfz!Ajq~VAj0rjgLHQB*Uoo zx)>bP7b_&*!TzM4fys?22cgrLd&LcUk%qN>;+(w>reO&p4nr#FCgz~xUoGyhRb6_n z_K;!acwsoRQ(kfjYLTCCg;`%yT_Zbyf6)tbX<_ATIxi?aJ%-fRPw+m_${`(F6=*(v!Mh!dwNd38_6T`w#Dnl#!U?%3fzH?(UE*Ic_^9OZ7G zSvNl*9na5=SgV%XIz%xZqcMX@7&6mX`$8QGJ#?EUGfG_`gn1Vp-6kPkau}QKfufb` zDj`cfr^ep>`M_A7Rs6#iI9bdpi0+X6s{h_;R5OhYDUKcU3I8;2v5w6z2{WmC-G9yO z)eLiV@Z`YXzh>+Wzp&Aga3reR(W?9{+FZ?kDBIl0V!aA|*e;<{FWwQIUT%hkO@no0 z`(+(?fY_lB>%AXnr4cL!E+xjM=*Ihj`eX*I=j#{E`CTI}?ODj)^3#(lwB9w}GRbsc zetiZcV(O*0ClER3@#Ef=8T$^^bHruiXF1y`1>A z)K@1q^TWh7ZCX1gW*`uO*LN@)VDo&;XGdQ;_bWzPi#o+=?;>7(SFo4%{^-CgvcKK5 zOVvR07_v}tZSaY;U?KsPX#Gi6>9c+2^NJ!h=jv?O+{|YEIKr)otF%&i*TyyVh0@

A=}P&ojp!tp-hrSmYs;Z<;4euOscA6G)RmUyG+>v zVA+YzQ_jQ>PwYKMd-yD;+iltg3vsN11fj&@XcBQmVQauNVQ6BhwN1n^(cFY6_UB{qt!X_ zeeLa!JJ%K3Joq4zB%f@=qLK5+ik;*YX5T+?;qWBKi$WRO*D1D}( zHW4D5Y;hh{+=Q&u0${gE(tavRRcz!4`cDfSK#SyUeuPx2XxCS3R~F#E(_}|L5JhTa zfVlJ*>Kw4&>T|Uv<{AlL+U?HC#6o)%4+ksec<)vv+(KG`NEz1SVtnGeO_-iEZjU^U zBx-LM@yWP~5zTZoisq(^ATnL-sos9@6&h}dl@(e%i4SN{>t9Z~j(+7OCN9{Aqk>z1 z30YTTW_qsM{SCjtqILOwTwC&%j9`zRAtHH-++)NSJIclyjzhTF^=xlwI$OHMMR@J0 z(HAP}9qmgVl|TezJA2LH_K1hnKP(kD&-dDo)ZB+^-4V_>EE(6?Cr4m|;H1NAwY%ir zD2>p(=15*Ivc)kuI2HAMV}pk{d-v&+e5F}_@+|R)aotF9|HwN3c=i3K>h@>U`76y- z0SKeAe#nE~zFUe{$l>D<0RiRchsPU3FPe^`S!5GEt&* zeQ5quF1#l}5TsBejcs+7_SX z*qG&s&-QQ34#MX|Hs-|Rb5AwqI^qrHaSZK7+NF8smBv#|QHpW7D)B_9A60gnBuqUw zKFvm!v5`|$kqI{PAr;n6JPK`Mp|#FcjvPJp+%QH^bxfk+&^wL8icvT(uW|PUecsCp zMhh2Ce@)JB*p)=X)%Id^Nz!bpf*MJ@lO`)gl28J?p;unm3QL>@to%c*Gf)_wM*-ecH3O+km7=Jd9Uce z?D?>m6K^#9w0ljn?QPU<+{$4b+8vc(`z0kl#_v2yJxfT1N|lJ9A-u@qUi8ZvBndAv z0!5NUfht{f?$_VA-=_0GDJlg)(sZ{s8WHr0DSnk^k&IG&KX^9~%Zb)&U^cYH4%K3} z&FGbnV{5eZ>Ff5Jw)ETT4mh?9cWlU_JFgJpJg{#6X-Xc=+~8% zk+l9Ky_21JQb^8kydu6SSsR2hC-277(Oi;T1PRd?BQDh|iHR2{g6{o|d0^W1$+qo* zDGfulx0(pBmJ-4cNXSDB+Yy1iMM=LkuU`(|OY8*x4c?B=uxr$}+qPePq`y?(_H8VF zX|nD62mR%_wk0LqAM0&D{_69gH~DCT73rHRN(QSMH&^w4tgiQ4r0X{2j29%nYku^P ziW5=n#cai6qn^W;yhg^Ffg#rLh0pUy*`k?r_9co7nkBN~KT^VHa$hXIs3f{R$`!38 zW|adMIYbfu@$>Uz&wX4(N~qaY&LWM}(Pnpa72BxiM_T7`W;YRZ*8uP8!p%QU``kFP zi&HXh@aj?S(Zk8<-JiADqVpGaS1O8Rv1_BQR_Hj4eaDdb($ z1G;4)ihLoR8J3iZU?JHEbax3{Zw z+ij4|0NHBFUXuFEVji5EM>bnoAeOTi>X#SW+P=-{fB(?2ylklaN&n|xLoDnTR?G+| zllartfTKOToentt{U{yLD?`jiv2#D?^B=(5f&SbbQ_yHCGfTHhGtekqb_|)q6pf>a zb^-|Zk##aWa;HTqf&@$NRjggjjy6jFOqJ?f)r{i6KN>~4a5Qr{I{i;d%GlB+pntO? zT19+6@kF{R7h}$OhQ4ipm=saFEXpHEml0nc<4b%73EG@SN$!X^n%D0{yxGqY^#cf5 zT6e90$jyi6LT;zMi)GeQMJUFxWVq$eRhzrV8D(cRWjaM8Ncd|6gbe*(INc+xbD@%L z!UJ1xgZ?=M?K5=E35HdRp0+z#tH90Z$gPpwP(gi}>Gfu&u z_Vk&6rYfj%Rbb;5x^k7h$xEsX3lQ~M|20c8%mR*V{1PL8Xr0su0rlvgClXxh7|8U2 zE@&5g*% z>osIjB|fvo3H|y^>i+NV(mpq8dV#1*dyo_Ce;iA$ykG4hv25hfyA-y>JK)a@$hd%g z`UlaZmJY`g(%aWX_`&mo`Ei7$VVt}2d+lvJH)XJz&yQw0bAWL^L z3=ax{t&g1(K`Vky9Qu$Ev}|S!dVngyp~@*TB>sIK`YK@O=&Z%o^O0ZJmx(3`mv{oq zw?l)NTXXH2Qocx(z2g6H^xaWOfB*lyc(FkQK}1CbcczIOM+&aY6`GZ+0w<;R#xh4* zABHPaqq5SnM6y>?L1Rq%N{Aa5z-uI~!BD&S zZsVEx9?xv41^bts40NOcm^LL|33UtZv37?#jROVCBy_gal_s{U2AzaGz9^7^5 zlVuOm>qUAp5k0=wh0S4J1?lpqX!a%J8Hm@okG%}E>QrH;*k}~gt2$^A+0RWNc8!;M zJXICPsu)Tr90heNfs%(rhzSvKMp=9Yu(Ahz=QxA=uju!QZtd({$b`Dnz|oyj&ynt4 zi=N_T=)1i=E|HS)UWr8|=t1!Fp!MSAP%p=;e&bN`Z1?d!y_?sH7DsKrdqZl03ViZH z=^*UAc8Yx~Rf?JsS^SnfkV-t25;J=#a}MzRQaq4!ZJ1uP-l2#wHLpa_A#YB;o2Ye) zi~eC#+UuiuZ{13OEHFy&h9-DCn#~q>W-KI)0TJ&YI67y~zIP^~EaK4R#^rX0kvCpo zN@=fD#^X-4o1x7M>wM~Zjh-%O`Pb#`x1iQlH@>b7_?CHNHhRmKPf>8;9a?s45WZZm zzSv5j@_Y(-R4Scm5|mKNtOw=~h=|!ix(i2Lk5H*}kwe)t1jY=(FmG931OJRf)ljCgF4Inh{?YK?nG6NBM#I(Jykz}XLw9?6 zFP*9RZGS`o_SYEh8Mt=tTks=?yxaJOLM>zWxgE*U1*H5;(|fr)@SCgMH{7c&U$jA8 z`LXW+^GH@3`crRYAKt>8;?iBYVbodYnl`WLLp?;9E)st6%lf+C`1I2M?0;3QFQo{U zwf;?()?#YOc8Q%rZ3>*8X?gt_!#>*(Pg~?KG_b8~uvp7z3Qlrc^yXAfQg`%Q!l7+j ze|`V>`q7Q1|LG)t0FJ8!eswp?qJ0)vSK#nm$#x{8n$Tlo-pbt`82kpdH?^`Mq%Iai zOhMD@2v8KgRHF*E*(MimH{xffpckBEPU%_8=D9ssv;BgUO3SLSmP$Leyk`)@kBq%( z(~y1drd@N%uI)CZTuBe|phjCtx?feh-By`4S(^V-J2>L{>&KE&kH^_#qh8u-ox%Q1 z``B&Yk0Zo7asH_aUA%h#1u=A#EdoL=?`Z8E&3NU>pdlP6ADcZ3+D- zzk1?;#3*q{h0l;^(~R8mS;uw}^DAHNc}exgo3i7#2n^##AXBEHi>e}Ip|y_z6Yj%= zDg4Gx)_}g`1L^{38n3i+&dV17W$Ay~styFrum|~(yPDxvn(2I6^bo(*K`&dO z0#l?vwv*CFYGC#$kh@UAhFW>b?#(0id>^BYG8M{~+#8l$7ucq%FptF+nQo1EZc9z3 zXcw3`M0cr5J=Ml@vMrB3f^A`PV&AEC7dnF0_&%&0fRQe?|6_TtuE9D>;@_o(Q}!J# zFijI5eThylAx_n9h5;v6a^zOrSryv(>1;3Y9~B#hy)5PskECtH2V+h&e)8VO?HM-m z+DQv#@YpTkqes&MQBLKhEtO{F)XA_r{GF@6J#O#=XeG0ckx|?J&OH16uULQ0oOb*7 zLl#?w|JaH!xTyO-LcY)22XDvV_qtb@hO%054$SmmLVBLdi#`3YVpZje(vDPQa%s%v zYC@Bm5LKPm+&A`B2iFQPcYJGeGNsI`1{$6B^nL<$Bl`Ajszvj->P_4!D0k#49LhE{}9 zYNSFs#BOHRhKI*r-bm=MqATLI*0%N+wZN#bWdaA<7g{LGgu@ zxw4z#$-gC-C9<`h{vTn6L-Gud3E<}kMLDliziM$M2j|Bv4`HSxTf3z`>6G_4c6AU< zSo30ZJhyMDKvn*Z8*08+8~naQgxDd1lhdeZ`&dQx-P}ZqiB@#xerU0}p_X7o*`M5* z;kW&Fzlnf>3lMOOn?yZ%21b#5{GR&$_B)dXc~T4w5)vqU<<@K*B{*q=4A7`NiiDOq z8}=N0HuFkf`2(ahphAMeI2bk$nitD~2hopvX^oc^-QIKfYiH)(>oQN^61AGPK%LSM9V4dJUBzCLe1OrVr7%^wuM|y zL?lx}jC=?8RC07ym=J?J5j@uBq<)HM?683$l73W!U8@i`O7dXNhQN}eiJ0-SUk<{cq z5AIpWS#adDXU#b}IA+PgwMZLGvo9k346{+}CqO|0`-Hi0zl+Lr&Bt1=0Iwmb)uN6H zn&a5v=P*0>WnZMxW1R-{v5m~F z&js{^G;m~C1L{;CRnF)4QMf`M@4~kuExi&d&a1!vv~g`gWAGcfvfD+oNH0wx#={;B zTIU?-bCsC1$77gUW|;yBUl3+tu5WJrt>1t_{#x!%|g&% ziap@XuE*7};WpIfV~!uF8Os}?jWs4 zeGXUubx~~;(}@%(hdDte2b!&1D6E#XHnXB$;POj+WY+oB|A`E2iBNLb`cq~saY2o+ zI!JgfRX;c3>inTHN64f3D<5w!3fn7#*Q5+QrLXW#y+jil$1iSQ@vt#8fDJYNM+C-+ z;QEJ2U5js+JSbY!adPeAtkE6hM~A-ue*LjmYMZ?j6VL{M?mP7Jo6mB1oQU(k6&A%0 ze8(RDbQc~tcc|DuA<5#}_iO&&v^%rj9iCH8j=NX7Vnzb z((et!C_k;fP-FO9O9<7RsD=>z7+4|X*Aw3SIUd|ZOTyI7*YXV1+6!$E{cH%-RBOH55>hhUDO} zUPK*4Kc4-^gaLaZC#wG=;rZ}$?BA{m!pT&l`>E(zCF%*!z@LNb`v<;~WAyj*`)_Qc zb`I8G^;0gUJ)vWtFunYm^@KbF6D_JmYougGFR^xmOVAkdAV$f^i z{>sQ<(u}P|H;9cN(i0wvOdZ3pUpn+)R?s{#rBjP%i)n32Se-y`oNw4DrU&qepC(J| zIqpN+Dv8S3QfxdTGC}Po&B%#AV_@~oxD+-#jtyHWrm?hyHZA&7idi-X%gln+GR*%# zZ2sh$;Td3183~f%ou@MX%>(sP42R`ld<)$CCX{St(ivphSxyO*n)qw+$x<2@Fd6Bm z!1zWVG}LyL{uN?|WiPm%4d>G7&w|7cIllQVdiQe|@EN=6IkfpsgvqcHh8x8XsggG~ zJ9`6Wm0Cd^hbFOd0#v3=aFbY+QM=Z$LrW-uJlhyaUi{gOvq>0smmEW+M3GQWZwAZW zyC*C^oJK6j8;mSGZrre|=^J42gkkK%$KTUn??Lb)68;`t?=}y6o2OsZY&OFw*tg5` z(C4UHyJi``sI>#ysxk1<#<=PtH9k(QVVHXZCe=O0hegH%I}-(B%0n@cwgK6t-7vI^ z#9~lKdW{~6No%zDHV!N_#jB2wrYygI6BZ~kZEqvCltIJFU?Xf(R?zZbkzcS< zV9S7HbNx^C7_(Hy>>%v7F`QiM$ST7$Vi5Bs@~R<@OZF#22?s0G>88V* zkRwXtjm-`cz{FB)wnj`kEHbI(!7WuL{v4S7ZH6PyZzVw9#wXI)wDq?Z2eV-V4C-|^ z>S2xLkPQ_thF;(Ej|o7rlp{voFU)I+^nw}&izq{P%WtPgtmEsk0WwwN877J{l}1>J zP4e?-b-JQc8nt~ftZZJ-)sko$Q#sv;%Ais>Fah07ARi6fwA}l`^7pCkNgDFwQyxn% z#6_(*D9|?_p0Y^Wl*ANkGk)?_u8*3 z{-`WQ(zv#7CtNk)Ng{r}zQT9;2pEVkdo_lO?Kgg?!V8rMA9~u!40tjRW~(xOuF?+- zUHwNyah1dx2ErclLN0M&WDsML>fFFbTGu$K%S=buzK$ASu84j}Ye;TEw#i*SxjFyV z@Qj;-P91ZxCz<5)^!l{+!AeR!fQe6m`E$~q^Gz+qBsS2UqJiftNnH=p-1B!*gN!e7 zR$rd9wA5};K*@4|63m9jzlXPNq@4_;Lc~yiKJ7VZVZ|`O=j)mD8dLeEYAt>}KnSI$ z1@?I1n=>OsZnB<`Q{_n|3@UZApg!OEkBHX(4dxHQ$eUe6FAWce?6m!Acv$4PfbMcK zlrTTUx4PKukPQ%4Y7ixmt`Bq*+o9!#1-TqzT!`V->Q9F7E?g4nfw+aYE4_ z+cxi(clr}@@41D!36NBa4rHAs(?@nLNqddJ@dZEo6>SO`D$7suhXy{?&)O>7zurc+) z6E@a1q8NJ{Un}}k3qgL6*VKycN-ou`6k(P>%iFji8vNX&!oAe;opj{LAbwbRd{GWM>I=%<$<4hQ^QtEIaaYaFTe%UN zHoh#ZP3?Fb_jRMo{`?Cy7BhgcZl7=)!dhA&LqFCFU!}Lv5U=L3ZptzHc=#t;<(F~q z950Buyt#36%eh?BrpQ5`0pzRdJvN9d*0w(9cm^|~xVrY#c<76k-Br<$JJ217;a4zP zm%n?^y?vyk6Bgiec4gnt!Zyoz%v%3gclE3l` zPn3xKkp@mREItqs%^uj$0E521^zFw5h^q3p<7hPG;EF1E1gwb$swspCUb!f|cdx=BhPxTf5HTFK|e)wD44&z_9&%b$5R#%k0M&s>}m^)LX zI1+T~eS_9>W=DC|k>lVQulI_}MQ4&A|3=cmfed(jd*7!c?-P|b&*+F>%$blaol7T# znz>wo-Gvp!7ZSQJtnOY~Cpvbk@7NI^x%rIABt$0Ov?`<^@3V+1p3o~ju!>Z)YkwlH zkB8kyr|izn&nkX$%w&&Ql?hR+e{8V8JHZLjeX83hfVFJ&ex%Ua_u#22$@9ds$h50F zjRR&6)X(|!2}b=92Nm#x*F&OO{i6P7(p~quyYAoO^I4F=pVIS3+TRD7UW@Qm8D0&b z8KJ0s;m4*f*p&1vxZ0DM8J=dkvuUDfZo9dk%1i2&rwcEd|D?H8_EDcp>)-LS&G5&n z{XX%Rg%p1O9>U)lZOUQ$Dn=;{m8-1|w& z$HjwHZ?2^~1w1JZVBWd<=kjd<{pybwH{cV>cLxFlr>~6`tM2-Z{y3s?g8($^9w)!s zFH3IQ{N_ZnSL8gs_=98iNrVeb?pyl((vFY%4#(9iuC^ulowx(RWnaLwDwkXo83~?V z{@f@RK1~RaqhD$C4#Q}Xy+$a_#UD7dt9dosFw`HU&+58ME-wQP?Fk{O-ht0<-SWS`HRJiU=g8x){&9MK=jp2= z|N0Nt9{yN7U3R$V&z~1H%PbK7dGl8<5!YymQ$fLuARm>MaXqhiFU$DZwntn}{o8x%_2Phe_oV9~zx>(VH~&Zx zgj=8DB7e%0&wl8=C0%#su4&)g6?U@uxsPk^%=R8zxwZY}*5{wE``0F)F`d6ZP(-qs zZzulm?B3+hHaA`u{eAs;>vY16ug=Mlh1X`V;T9r=%0+i;ZyY+4wpPx0?kqRz|p z>pYSoOLj3}J4{`Yr+5?0vgkuhGYPDL5^}rJU@hwOiP^Fx2JRc=!AYNNqq=$gloH3@ z((PBxlURP^o}JToTO$to*Z5p``=C8(|0@Rk)jkVDf+PQ&^`#Hbt``6LtLN7>tL@ui z8c_Sxi)3r3`T7gF_{x_z_fI9=s9oIs?fsKq9}k8i@QtjgTZ0X5nRl83D;I5cc;K+o zam}Zs3*j~=_gDr0Z|FE@&ww#c#t1b`3UdjT1i5$g8zptB=ZF38RR;3UR$Z z4n^D7aiK`-E_M$B6wh%e2|`gI((Ecvf;8=`>qVQk()XgR!|wJWtV_5O9HL`ZLUm;J ztI$TdZ^X#(^|NA(1y>w~G0nD(v^KAorw6+=aLdu*kp_VrBbi!akT4Q5hP0q|ijfgp z2-017n`J#{vwCG9vcmGM3TvMIBhc8T6%uUaOOFkOEuoDK?J0TK7Z_|oy*q?;tjvWP z*0wYE{Q=Rwg$<~`L!R(#p~axAORvYK99RT_i0xgWNw#+CJkilpYws<75W zHbH3XA%YZX*QIGqbCSyeU0=Fs2vtGb1Pfhq`WFXlCu9a%4YEJhb$gYl0c@PT_QWx# z1z8f#-z%XTZ`w9hZyY|ZvNhE=q{(3$ZjMH78uk3Q`m^wshZn!xe;(Ia{%3?FFMQEZ za9H=`y0?A7=dbr}F|VqPA{>t9ZA4p^O}PyI55U`pies708bWM#2b^TuHnvH<;fCJ# z&8GQt+Dgj|wZtlOiu=9F`>7D=qpbzQO<9o}QSqL6gc`eicggLAs`kJdi#4rNJ;cN0 z-Ei|zjd;+yrdl-U5T{Yk57`wmKaUzOF4;JQ$tiK&uJ2h18?uY*Yz{WfUX{4LwS96HNkzm=rbj;2yfjVXTVN0 zL(uaosAG>Yn%w!)KRM%Cw4oQzTIyOT*#eG8te$#xhqlu{9d-#)bH&uh%Cm?6Y`9 zsBkZ-!NFX)q~QTrrw0R>qF6HFfF9v($lO3^JNS$Z6Wdl!>Sx*?JFsEai^v2C-1sF< zr7_raS*rd)hH4?o4wdQ0r=5*o!aPTi_M=}=U+{t#UGJz&MM;h28iZ3R056K1#9!ed z$feD=T+}4>A)!w{jVpDmPBrYAE2H<=R11DDr>Y_SF2l-drAr`oT2y8n&65%%Q|4*Y z+;Ud|pcl=3VK|{I^MvQ3;<*~qI02?FkhS`@rxG*b2N%}!5sB?D@WclaPPR2PH^-IA!6-p)6xZsS;WGC1jRi;m&P;j@3`4UWtp zLJi8uGhbc48I{t0iW}M+Nr&aLUNq~&;ojT$HFnG+xP_HrQ7gHK4V6m$X~o_Udu}z4 z^#Tw3DqXamqsNK+g6~$_S`7eLC+bQ<2D`#Z-htWZIB8?203Fpa<@LJFyIKtmU&9lx z5K46^rvv!5X1JT|NYgI4+_+SWbNVeYE}a)^@KFIw(*xzRV$`4AH>@ePE;U6X7Q$QN4o@ArKhRvgR-n4lqwbj(5}>pjllVs2AW5P{a#=yfzJx&&xeF8{ znk3=rOKKmnnV9K5*s0>4x<7<7q4FMJm;kfSYsR^;gF2QGI93in0b@rd)qBk#sS>DJ zJ5C+!?CNEdYDKP!IP_+YI3<@27u2ha&)OfKr`s}??@`Ecx99p{u5F4IeNl!i{GII>pq?_H4BW$??EM0P}J=JKN@7%M! zQCzU5xmVwpRZidb5tA?biB`)4^-FZ&Wpi@47gJ@V{#h!xuYu2#R4%_2RbkUm0$E*7 z5p-ZWp-IMPXL~K%el8OP2Tq)2N;CEKTm~CVAEwUHFriOKy!uJ9f$yJq`vwcmL z5c=A@IZR|Vgq%fLQoEK>otwe4eU@|i*4pTEoZGhG3#YS1V$tWucO|d={=0nVfA}wQ z?AGaE=PP%2Uf*Ps&Awr?;pd%2^KU9=QH9EvH>Fz$Pq)YQwHV?2ZMM!@RYfHC5X4UMk^4o)ln6bisTlij%}tVpTd*$qxci#BVwq=;k=>2OvxC~|{u_bVEcT!!?Bl3o zYcSlGSH4KuSm?iOLcdq_JUoag93tN{ZES^v#J%w&c7nEnBNUlhj zDR7&Sjpu zD*t~nWJjwGc1Nrg(OH8aTM08608I({f8`a;DEBRw3h285yIIh3(rXPL7Al0DMZuQ| z=aB^vSP2JS$c7glg|mdPClZPsBq3j@1Jl4|bX=1hzEHSB=UNZtfnGc?T_{TDu|k!g z<7;O3CRpKS9}gX{NWeA9;Y;o#LV3_7T*R~h=?gK~0>HVtH+jemd36Q^Uibj9L|%Q` z9<@XSWlch_#v{1us5GkVRr7klGmyBCOR1cLgC6RXz` zl~27a-#lHv6Wy?DK}7*8rA5#%uh##iMjwP#idjf$<>tgy;iGEa)mdImm&Nao$YT2T ztX12SlzhrvevoK8PKe)I)Npy7S!;Zi^=?aJnccR}UTOiTngl})C`2Mi<1mp-b)|GSF-$5uCUQT`cm3 ztDue|gO4Xjq}Nc47}|fClH(fcC4~OBe?Hou02Wa|w~y8CL@@ju`LQv0{2qa_>(GzO zjgN0a-!E-?a)OFyIEP!>I}*Sr+YO9^>TxFxlcAJ1Z=i{MT_HfNiF?9g999K4`lu*& zv*ZmQx7l{+*0Y*^fhwFd#-}8`I)aRi8C{Y-?+MPT{8A3yyCJKfW=%;mV1Fe|Y+bZZ3Vz=e^UK zM{lY;ejj_1oS(WR|4iqB-C+^bmGlS*%$sNA`yJ>|>i-rUEUY?yHKEFjEoYpwJnV47 zYZjcIqDH7;EBQtVF^!H)LS*bbA@!n5a;z;+eAK=J9zj23q&;ys99$#xP7xvR6hYkp z3abZPqolfOPQ*H#%mUc9#3Ogm#PSaE0;Pe69CkZ?5hRb86b|+r*i*zsu;3)?7-P~S z>RLHzfh@Xym+3{f-2EJoqHS8l1NZNa-WS_quRR;@bJ$o5_1*2RK}48|QTzSIl(4JkG{39AZNtHdo~Z>WHv^!C6P&{ssU!5Svo6A~ZFB~Wu&g`%biS(Cev zwMPN%7NU}fU;=vqer)-d;DjV4)QNE3Qzz=z5DJtyY8q_KdRT-8JbWN}4G*?shrt@5 z&Jh4Z+JI3SWB4v;_axk$*X^wV14IG;@L_Rus7QhT7>`phq2?TeA6KB=-G=Ya>rz5t z_6L1D6wp0tL`|;3MFB&WS%s-!4m?CZ54M;Kp6P_TieT=uz>h7gTKSf6Im|;gPjyzK za_GL(5R5qwbUOg9ksXRqf~4cHOJmn-v=l_+b$=PWM9V~9=$?48^+q`~LUYBQ4)U|j3Zwp{%vtWA`xbPfoED($kg0;6m zYr<8Vw^y_Ioh!2YkBB=xk(Z)x^{;-~&n>=GSg^EM*>Gs7c~ip$6eavfUge26Oyx&@wn72xXaE~nu(Um35VxSgWT3hJ(w1M4v=NA^2#jW+?$U8t^!O_zy$S_5 z2FGM*hO(G=oE_>*p3$om#8Wkb%hOYfitJs2W@LpgM9H1F}_gXsug!g5Rc3H_p|Jp^=p2BJxb^Htw$lfw`C?Hp$gkIQ0PLhw0ksDm0P zmW>wZfN>?7%hr2=!wxdhi5lF$mu_xT4+VeOSuN2k;O6|NL9*1{YF!V^)*GVfJ%nHc z7kf#Wci-7B%bA6OSs-MyUk^8}LWZ%N<%WDi@1dbT5panR?C1z;n66(Shu`JZQivqi zeYX;o_z5ODUzz!G3uw*c4hoS9`TVU@ve86B%!}V~bH`VS=wsYj^iv+zj~8UMsXuFV zXTsC^HMmE)P7OT2p{Pgt@3|LN77s|f%-`?Y+?p32JBHzVUEJAqAbm%^VgBHyKE9t4 z#NLA$G=iUb1)EQwC@YDq6hW0I?9>A2I3(kgY}=FqOuC5pPo8iEg3(zo$*}zf*}%xBy0;LwpjIRXt$${#id?fgMyJj=jcRdtF2q z8~BR!eqX{cN}r4#N}W;0E}1=QHj7qhAWtC~)xv6DNR%f8hN)kFAF{hfbj^ql9Xh{a z8S|+X7jc&f-NnYgn3;cKMS%7wVm$0ivbbCu4b)0__lg4ZP_D5QVXWMr#-qd&=P{NL z&5LTN&NxS8GZ}q2O9JtrExtg5J7|OZv2u&buE-oxV;Oz(@il}k!7y}oeFhIdb`6yc z-#S$n{~V=T=8&z^GHLX~k+V$Bi`JW* zH&2wF&*s0QeTBW*qpyM&ZVF&;TH4*eG3xbZ^NPHj$G`SA#AIGrb?ecL*8C^|+g6IZ z#ye2DI=?FMVmfyFy8RcC_h6Zy!2nrAYA;AodKO(jL7R-ch6Yl&s6*E+caXN;hG3=% z=;m+eChq)Ji4ci1+$%G>W_*0VHC1nVENPqxwUI-uAWq%3DDQ{Gg$gG-0;_Iwa)lZ( zt$CYci?jET{vJThTcf^D64{emWlP{9HvY^a+%{3pdu!CwPXO`-1Tl&ed_yucCmcn{ zsZzWpL2m~ETFl0CnMcw*bC~e0dSt&uA!~Wxman6FtkVwR+C+s5|6(e5`@Ck4D&Ue|nE-(g zg8iAyd+dRbb;TaZo44z2;~}5nyQ`Hm!x^yG6Nq0a25z>QcMqjj3q{UqU}Sb4Q*MMy z{yWp7jID;~t@4Cg+2O2ksDXGCL;Y&qzYjY&VV%J7Z}9KA&fhmJ`>xYvN7xM=zR#!IWoP~DPIyD-piYoF3!*WjXd>ut|nkGb9P#ABqAd{djNWDvCo*Xs1xz zTS>RC9zg|#yd>0BT->&@k_LEi2@jAEMYH~37+tp z@2*-k#3>Ig80W)iY3KNA`&=ex%q~i)l2W-&pC|AwSG9MdiL0BXy@^BNrDk=(4-h8n zJ;*EUf^;OmMT}Xqp2Od(3z658yFS5fmrv8-acigV!AXwniwKPWy51GV#P^zVQ+c&E z+%BPzfqWWBDN5TN;c4vktnl-Dh)q4c)~7yoUs1+^to$?E--X5HW*#oapKaRe^J5a% zvc0_b+T5$5BiDZsa;J7j|NQ05UX!veq%MM1B;5Jqo6`A4;H$9I9&Clbw8yDj5Lm_F zhG}*Zx9%(6a7C4RH-x(GzNrN1I!7OzH+wu4r=@L>YbzGih*lx0|ItNRnG{YxsBqAJ z;MXp-)Nbk7nPWqp0ZMjjR@Y%AV^y4b2 z{uZ8ilK6NJc^2c2SK&_{_a*Zlc4*9>4b>8Zo-(+1bNiPObQ{6rn$beY2izD;oXaekSSR*=(l26@&w~YTu2@ zs&K&?%%=HH@%6XP^^UdbaLqZ@{6C4`To2mBY>!B@9Br2#x)KsowXkRKan(ihR+}9C zueq|Zx#gI7oRx9hju0_zm)vjUwf@hWiHuLO^7C7pG31t1!&YUfElvxfsS^J@&k#0Z zqhCSsuIGX}vGWXoGKDJ1cBpBu@VOnI^ zBOk!l-xKIiUd3vG7F82wfb?WbNJARXd1`s>%2^{Ut=ZaF3t1ErCb`$4MAcM2Xo%-t ziQEdMq_cwYoeEt^kz*ARt z=#4Cu7zpI`Eb-IJ;osTIE#IIj3IRMzDgKwU6JfzU#-wTi$?5GdM%Y@U<0N1c8JJMN z2Z&rQ6BEWY)QZY97rAacJ}1B<2h;b4&x#G|c%Y71KpecsdIvbhvUTB`qgz%o4DMDg z%1TLk_H$*I|Hqw@)>C(W0{Sj8ZB;_a&XRo(<-b{$>rc!sbHyF3UK1Zh&YUu#ed1O| z*Fm!?$Ad~;OBp^Z!!SipUm#~)9$hJ?$Vx{JGQ4Cuag_vD*>%^c=)PpHj1QO01{>eA zq0ASdTJ*v-kL*f`fP)STk7e~Pucr677D5S2=K2^V>dGev#AbIzfmZ%n64zaV$ss_^ zSN=r%(xA2@@o!Q79av1)Q6hP9lzFudNM;wn(&u1wp-@7pRFXz!d(DRUrG^5&+0k*; zx;6CjpZRjVJ#(cLe;2faMup0U^hrZc4uFKJWI>p$}Cj_T_-=>*ucyOk#K1p|j! zeXX`GXt(>1bS(kWxSEN6eNPE@kTFa2wdf`xt0z<`HLmN1{u?^4Nn93KTK#6C(i}2r zbY~pU+o+T{-T#h?!*d!h=(qxn^2$QF#4gemz3jdcHM-)9-LPo!#4~*R!xy&_7XMkt z-QjpTB+WQUyJdac@hv_Z4RcPdxUVm4J1$75+gUQ*+y9$&nsiJM;#inF&c_Xr53&0! zKFuEXCQlmdz6MKw!Mu3u)!y2qt|M3jF0e)P@WI3f<8@J{M{qLbIw6mZ$eRi?WHU^@ zg$z1m`v$R&yg>I5`WE$Iv4W6ZTpZKDJsRR|6%UffOW_`t9r$?K3-r6WJ|ab|hnbl) zd{?Op#U|)E4ZR>0)R#s{nsEZuB%xcVbgtvn1{KQT^H$T5ft5BAUuBA!;Q}#AaTh^k z^J$?>F=}5TZ|McT;X5_dt&M?7$6cGu5SF{CUGT}(y;H;7a+cyI&b~xqD&d+hqpu2g zD*<1<;{~rvRETQ>T3uB`Wv>1sP!pltaf+bhD;Oxg$j{)ZJbb|G3@$T`4|gkt`tUgL zJ)5MYcZFsBcK&tUAe1t#v~?#~;x_)~!xzm#t}TY5va2D6dCt=Q8uubMM<|8Z2CUV| z<^`}+mxq<59s&lQIJfkfX$9P|EB8MlO*Ls{5AzJ3-9F;`RCk&N+}%=)U(EuKHEf^( zkMF>WiPV*q>)F{&PxXV-K^jFCFu_w8TKXg69xA zUcL+kz+C}9E&{2B2gom7sT5f$SwsS2gWB3yiP}H_Fl_gvLU?*SC?EhC0x4cC(OqN} zLen*{bSAi74b2({9E6CZ@p9g*bVWTZv<;4=R`A;30du0gAWR@EH;d;GyOrTSce zSXmy#f;iDD%0FHX8W)EF=p=Rp$*|%TSEAFMxL}i&(X?bRg|CrjnTIK&CBCO1D;eQJ~W=#VstA}hI0+8)PU&eHO@~IZF zKC6CbQtE-^u?w+bWxwB*{$UYdO9@^weU?yqY{A6x9%VMUk*mRX1l5S8Z$%XKGzRS!jE7MA6Xm;2gFb7!St zC`1xdO49M`g}{I*z~@zj6_)YhkpWB~1AuKrm3zcjB67={^?4}X!aQU*oy z5c#uU)=FDnW-7#jN>gX3q`^;Df0T0&R zhj3zY{W{_8(z5w%?#4n1uMmlSR-V%~?7>4Eo@}J>_Pp(_FRP9*e$RN;B_?qfR@8-= zJ&QTmJk;bD@V`o=OIM4VX6Q#{z%SIz<1R;9I`w~zTYBkoD!J0cAn>Q~-eMuh8YW-> zsT%}5w@zXUfr6}x!@pzPuN}Pp!&8_gwwZ$%GsI81z+OnThd^ppNg>NRtz-t#jsyz^0u7J`BQ9`%i1D0pl2&MKTyGQO(s-|d5#VBjs{+X5*lJ@lXKI%| z3s`=IMznNTE@@n`PJBw~tc!$u+yVS80;Y{u4<)qS4cYBq)O^ncFqk0kI|L(uC&-0j zgH2)*PfSuDzvogGa=Dn5r0CENLwM% z)+bUnXx|PQUw?UVn;IFc9y;@W;ZLCqxsITFU0OVmxJTcew{&5R)IKW7vfT4vwmu6g z#Xp7`h9S09@*VynZ={cnS&C^xkWIc`w6}+H6DUKw3|_wx+ubA^ZP{(8F?+3&8|lh+ z+vBw{$E@0bFMMFTnZ&>zJh<9W5MCFueYI&f&$;7y@GkUWCEawEw0*u`cgSYbijP3U zIk96GaMz&Ed}(@K?BFfNu>g?^uxia-(^)8^68O7oJ6W;jfw$S7XLK9k z<6sp4vvoKdxYEC9_m>26?zh9Y#LmVV@f+g(5DMeWJv)wzf;{wU&qlySDb@4Qqk8bS zeaL*s=EsttHUy|-kwEG%D2*1Btr3)O5L9dvRMrZ%9~P9Yl;|s-IN(ojQ&w~^Vy#BC zwwv$49=G_hCs@;`=(dx4LO~Yq%@4twJsTz$ZPwrS{GP+S{Gz*};@aqRPWNPUHt?Gu z^$0n3j{(@!Q}$gW+02S9<^Un$b!dI5{;K0IJ6V~K7D~XJe7%IU$wIuQ}*{R-^ z5_ZPg`)$ZgiHVY0#z!O#5pCvxo5pKx*ef$cW$rg$8Fgu1M**hX@&XpDqpP#S6;LDU zO$q@9glf)}IK)7ij2xR;$vVpp2a(vN`;bP>gSmr0K;Vuq}7bY-JsrFiW|*n);q zcTt;;fofoO*yv>CL+{Ni-*PvXdd{)a4b|dO>irLV zE7W&bY{Ilr+E6C<{Jn<rH( zpaIg+{oLAkY3}rZm7;uca+%dQJl7K%N2m;uRq(=YS7k-*CWt*{pNq~%NLUDa2s}3) z-kMr1ke7ebVO3#b$~-S&BM-rm!^Lz;Jpr*^P->?3av+pBir}F#Wc;}JbY<&!P@n)( zrpFeqODIj0L)ev=kKx%@KX2kF;43rBSI{$pHvmyJ z;`ch>B+Gw2ue{H{JWK@LDB8jPg3Im#X|u4`BtS4Lc|o}?DHZOs*z z;mDC1mZdog%eEDbZ`t_fbHC?#{sG{)gM-g_z0Yqxc;_e8J6AXIi~YOu0>1eBxMTAU z@cfghn&Y31ydTshzulYh{5!*F-XSYjTuF6Ml0)gygHOdeyz)b@Hedg;_F*3&f4uwQ z^<%4)qWFAFA|D$(QRdl$j>|9ObFga+vBYg?0t?){6}heuofzU^%o4|+{C#T}*%)&8 z9~C!k?_E=2nO}wV8mj1~Q}}8Qn#L%@Z1A)sw*ti#Vw_cF zrYgAc)Vb^TqAi{!rn>#B3ej1kMVS__0%y@!HReRpQXbHGeU0S0To`DGjR-+#DS)YM z47%n#O(nLTsnMSmzTPGAlVgs@lr5TLl#M5qtXKG^BuK=#z*Q3D`h>9l9SAeSB4+3D zK;0b^T9|8_FjospA6H72$pPX2*79}pc!i^!&q^(L!Jb`p&>H#ZG)-56Pwnhqt_Zn2 z`V(=x;Y9=7H5to84aa?KA%2H!@9nJ=pLN!XJ9A^>+S- zh;IB@-~5Kh8=l{6EIICJ;vsm@JU2x;{x!!f6_O%8yt;H?cx`9)6J+}C1>5Tn2kv&+ zwq?5b9g@?dNb&pek?w|j^7Vumt7V-tQK58tz>atm;jpVYT&CbF@4ocSPp?r}t#A9l z+T))!%m;~um0tg%Mgz& z{>2XOt;5nsg!MeDcGEW|dFAx-mJXa(<*?y^MTVfG*W0r4B9rfu@@b=1WZ<^m>6^jjNWafH-RfT)| zEY}k6Cd2IvD;ORXH@dL!=-_r?jiXr>?_vP%4}L1pQ(qh2WWcwfaB5Ya!zK^@36_~LeG+R=m=W(h7)p;mE(*6=j%7h2qXuOYF7r8LzbPy%c10Z zMrT-7QC5ix>7pHQ(}t)kY-M zIo^70E7q5}oyi=+=~c<3NG%_ajTQQrN0D7diWv^ush~YC#CSSjPpO?Bv=*FD)fM*4 z^XL65V%*5CCIt6c&jtnh7T6;htJM&4l2=h&j`vgxf+osC&hDZwF5LgGT^6go!h8=Z zZ5KVZ@QJol#w?d!HHsjvQSqxyLH#*HuWSq!q*A z%}r5PU)84QV~HMzmag&_c0EGT0v!0~Ho|2+{Q?V|KQqwa#zXYmrS2?Q?#+I~Q znVnYW77>=)kFGFz)oB;tx-(KDORdQ0a$IoS{8vSZA^S1CT68ykGmG3CdiOwWSMcg{ zrv`FQYf9(!lf3h?2LyR#2j_j80bAABg^D-b3nT9Oj^-vlxLS+AnXLDF-K)fZ1mJ!4 z6jV*8==wUom@>>+DLpOPD^MehO{NTmhTL(LT`w)&4aHP&sY|IMnhdhE#hFvmsU_4= z2c+rM>AfM0-h|_Fkj)aIlLerWNiE8?f{Tq)h+`IPKv@g8SWC{5C1y%+&VnymlmLmT zoSo>7PA(x^02=2*2X#3wz3oqh83$$Vs|i=KqNM)Da343mW}28S@LrPGyWes)$T&!G zg*F3VYw~T0+3+xFi?Ej36-tPp-=lqVN13s>IA0Z_;v;m#p0UH)UK3vR-MyAd76o+d zkI-qUJxX<6J9`;U7GB`q6z?X&n|%}StXAXdTDX)#>E4)+40JqlozwaDq4j?+9F<;g zrhT^#vQG6plQ_9fyWX(gHq^Bx)zophh_i@u#4|IoA<$qxc=r*6S#!$O$|R!fg2y>0 zimzXZ;b}#wLxnQUmzb72eLddQBL(L(id=A7_P9GWO1dLxZfuhoPef)!`@LMAPEo~{ zTzQ#ZaO9%|sAVSxG*4 zp#$XFeedrh^MqzkEOoAXWHR&9!b%v)=*zBxljJ&lQtvhhyHJHEMDrqy3;CBXcsgfS z@k$Jvv9}iuhys_$^~%o~Ty>s>ChO|O8^-u$rpp=^?!FfO?g9Ts+g=gzd!61HARgmi z@j;T}IJlwjvhsV~gpVH;Y1GEwZ>is!pJJQ@Dp7YX-r}xbekuun-vt|bX_=_*H5i8+ zLciZDYCQMgei7ZX(?gKC#oDRFT@3wvK3;d^d_NG0)i-Ey!+DpWB9_q5ca0J z;tQ`ycQH#u%n^eA&~qKk1ukhFZw_Nzlr-^H;(;}sKpL-zeqyFM3vU_Xa?2qMn1Uet zL%C-|eo)(?4nm*%+qZ7+w_Hb^ZtZ4}7OR2znwA1B-vK1uLrEl)3kcPM%fW3HsP4L2 zQYTQmH)aCd^!~N?{l((9M@B$a_=&(}zu_yb_9ni7p>Cv;Y`|1;krz(uw-UBaNQ?uV!LolTzW z@MPOQ7*8G7E1WBLfe?)USG?D0IUH0P5Q&DVB@&#f>(s~5gDEysIp+@TwxG;VW+DVOYl{5Jm?1rXactopTCM5}0|%RB63B78Gf|0cX(Da4s{II=;fQKjf4p4%Hn z4^dlu;~)=kv(bZgMePTmDvF{1zM{i3w{a51oSpR`m~4*S1h@*tzG;kz&W#I zIH82pzE8gebisknH<2DrNZ*_7CyPV|x}9^ni>yo#b*vKlw;r0}C@v^q&O=Deh9l=H zOPo0!4yta47I5pI0FM@qhfJv>2OVUH3izlU0$rTi=iO}FOve!oMQ-8g`ZqzlnF=p| zk$d5^V`U(V4KigQqebbf60`DwWfMYzT!?jmsYax`yt9ggXJbm{={6sL-Ldc$IFEL= zyyTb)=^;RR3i&P^D#HosQUS56LB@nh_7I1hj__p%K4x`z7qz=iAlz}*J|2DEII*b; z=_^xOLSmeJv52$7O&4u71G$Db>-Th6t9E-;2#;C6bp6&DcsGp20^!TjvLQwyNBS@* z?k&nKtPaZwgx?=n9;@*YwYxGqPT<6}PT|~+UXG>F>)gNhEbpR`PTUQ?uQvp&$q#*< z4-aZ5zTTL+reNLcg1j{w-IRD>!0oiD{q;xo&&%%CksNn++cYEphnhCG+vv8NPhedB zVh;ZI$N*J7@A2K<>1Fp?=-Sf&p22bdwx`gNndXu9z@L)?AS^==mYKqWgfuL_(*d|= z$riFXT<4qZ`?5jb>H9_~(255ceB@|3A>0{DSSqnOtKF-p9XAb;S#q}uz&n%c!a@ee zLfQKfo}`yv{s?E4*iDA;NYAjUfUMz)*LmzR=)n>|(XxN>rfUen} z+GhCDSJ3V#6U}3nn6pas*`V$Ggk@%+2QFac@fQ?U2QB1ub54oA;oG2S(00Ggk#nGo zUE<=e^qLO1)IxA#a}sYOd+iYxl>Oux$hxv4>UO&<0kkq%?GiFz$pf5P>=_>I^C~z6 z+mxrh@cW`6yFw)T8;Z?EG$o&$mtgBbI)=lEkKAt8VI0#|1K~1m&M$M}lflRIz)h_Q#)|~^Td2s-eiO^wjHyO<+EwkGlX4;eObUYA+wrS$yj}mu? z?m{c)o^1=>QaxmzkDO;6=tc^3T+wdcuRPF2>i_o00MIuSVzwXQvMz)_+ktSc0l>EQ z1wk!vwA~P3v?&(mt=nw?uEmOEH1A~KM&Ns8iT)oXgH+e(CUL)s{9Ad3+{)2n2C}FW zKNj-uY`c*l0QVr1(gMK0`Rx+GJ%8IRIO8o{?~VQ-?XpWeaRID;+lWqx(jp!vNLcEf zffWE85apx@w4Q!DPbSiu<;0w{$K`Z5_Be-xthcV@xUfs~i^Oon+GUEP-%{c}E5 zW6ehJ*$2&qJM~!|6pt>ypms+TdgiwHKf_}Tlak?v$YX>cD+xsSBl7p>&Sh?quEvy1 z)cZ;dZU-w?7@6GpfjHOYJUpnpc6eoaPz{!dEqAyWAzMc~hw#PzrRPst?&2hA4#r zkd1nVIPZnnl8k52@eKe~3SoGeSE_((JS71qq79pvQQpm&Dsqh5lr)@DE7p{5$fe6f z^cl#sO-X4}D(Me9=pvIB9P`~mnu%!rzXxfvLMl$J-zi*otv>saaPARA#3>O6xW*=3 zG^bVcX*HoxWNIR6o`ke2iB5gLAbMxW)x32P`HIe*R}@}AVb{S^nB zov@@S7=!fFMf72ac9ozD{~;Vh=)GySIRQQRx6$%9pbNFT=&mz$4TW?0oZhXfag|L_MKuV0_y1zc}eau3y`75nq+?d$5ZhtMg z@XNSbWbjQ$F4BZ`Kurp2E;oGw24<0@Nj5puWCwG}`dPCg6bQamYAQ zGimZL|7SPp&=_jN$V#0FsZ9c@Q0LS7MIPgQPTTacbHfocl2tzva?#%-KM&(&@g842 zS3OLUCGUbAsN)R)zL}HZKKb*T(EHZNiB@6m(1o+jkZ8u0z=$WRAiPZG*2S4&>KSZs zjkJG+@-FZI3*w4Kw)|W%Cp^W$hd-QDWd+h2!m>&?PcF6T&~a`$5V-BKXn1tD&6S*^ z!fhW=Te1zeOmK*G5ProXkB-NZ%?}Iq00wIca+-t%dxYNG#ss;!#O#6!(PeL+y0Ru{ z65a#YDkREb1T((MC~Fn=ki#Hicwzw;$wvywDBUacqTa0zu-WB;H` zHgG6S4EuDA=fSlKf7u3F`>4h z@?qCww*epF4d9=(32`!r{$hIn9e`Yf7#c7xILy(1how^C<>!4+EDe1Q}UTZZw3&jeX>s#_^elA-X&NZ7$t{r zOK9;WG}GKZPPKB$ro+%AtlrNA=@*H7Hf~Z=kBG*BPa8LhYkym~%qDrvmc-0nzxeyQ zpHt_T!bF?Es1wiWd!IOn!!7ayoP;es`T-_t%^G!?&b>Vj+GaX)YjUpk8^9$&sS(v9 z?&fa0x%>LjXr|Ieia|Wvgfyl|TeeR(e1u>E_O9k)XA!=I*8)Eadw#&O zw$iOBNmPiS&Tb?!MFvFxnW@z3ZpcGyh1;tee82!gH9cG#*9mCxZc%y40^0TY$AoAoz^X`x z?4&%gf5h!GbT$LAPjfMQwXOE6Ghc8Ba-Gsnu7CQsaGvq3E3O^GyS8w9I{^lM!)1-E zk*eMzGP@l&DSEscX!@tV2m3{9LgsS_qRa$1Zbee^p`P<o0D4+Z?$qzcq^M zAXDN!7Qpn4Hcwl1UmyNHcjbxjGQ({?x-XdswM;DG9x{=2&jJWdqcgGyz&JALi|4^sKM#b7Pc7y&_V+Kf$#&y(ucGw8#DX`ZX z9vA7Xi3nn6>ccT%*nuwgI+uu+!r)4oLv*ZkmM2cWv)ys|<@}%88R2lu{NuK@7Y|_@DzsViU`eK=pxMVs3v8&IT zd$@WB)q2Ko@9QBNvHjIbV%8XoyI+NB4VGCoU$i-WDne=@3BGW>WC3mLSJ1AluHU~obp;r`IHGchGH(LZsZ+Jl~#>iPBdS#%qE^|)Q?>6ACGvM)PMeTssWRcDw z`(;CIgxO{Gl*C!sBNW-l5|Anm+O$p;K%TEV6r{JZZYbDvTN}^z02^VpH|M(U!*I{8 z9gXfiY;c%oDt^&a9Wr0IB>P25>E)mV(9}7OHD_f+3wX+vMDpoe$x2k~3uEVosIoo$ z?+^k_<}Y6@u}Y3&%j5`q7nFR}lfiVO^x1c{v_Fc~rV%aII_PUAR{q+NE6xozjFrn@ zRnR!1F4qm+%S(*7sXZ3gkDU^3F833pESA0wq6SM>eft8Vui0xQNUn^AIACqiJG6ZQR|GK5VdR4tD?&tN5x)BK_ z#)Eg#GRXS!gOY}j$Bft4a~tU8I(dzmNwUCTAc#)mC~b_~`F|ZU%Rd>~NsLwqM1$WR ztvdYQ_sKQSBK)t+T7alO65Y8!|2~^LJondNZ(a1z>Bj*6>Z#&}qxhz1*#Fipk7;tS z+&l|frgEtXm!2~!#c5{Bch@MerW5loRXS(e#z$S$^iO1Wv~Q5swnz<)VLT9w^lbe_|#qpz%X zo0u}}mvi_t97;rGAl>jNJh{cC(BuHx69V1yuMqP1GgQX}5&NSGlXo-KL_S+eN4ZkC z021q?=HfKei}1Jy8lLs>X%p^TDN|yq*>`D;)T+n{u1N?9W9BCnlUf1{mIIyaxD>C- z|C;zT{$1EMn+sW}MquGSZykk;$dsp=ZV}N`Dq6#$gpRy38qfxjVz#g%jkbwx=?l<6 zIy|w@4yF6Z)g&Ig84pvAXnt!Dj~Z$0Coi+x0^ruMh4ejq%w3=rxtbYhc;*d24u(j< z^0YOtngXmIBhV4q4+{L=aLt-eRKAp3E`CucX1}{uKHQ~aBqL6Lfi$;lb~`-&&lO&oSg%je3MTc7cEB*q>!(_8xa zo{pA-0I&hxMgFaQ7kesk*0PTp-GwFE-kxBzixBA~ zrr|j<1T~g}-Vnq&ZW{86()6fHhZ0q0rjpYVISKz9<`Gjer!EdeeISnU$3!(*Yimc( zvQBbJSKZuKodN3wA2s8FMHXmhj*^m}yFdOLEC6KY5Rz4h;5SHpzY2+)(Nu$pT7J#y z>iu~iRTWlFmTk8aqK(i>eU8%yYNhNY&B%fj++tx+l8yKkArCjPcAC>3qg&(C6=E+` zhyEtEM4vK+y(bghwS05WAxJf03cqS06@?dmOI_7q*SI8loF<`71Y48!|E5b=$)8bG z5do+w2(8CQw0Sbq7T2l*thNB%pMP;tZ&)A5iIwGiVJi83$P1m~ToRLgZU@YyRV`M4 zc^;|gO9}TZPYQ7EMeUo-DiG21$;`zIeNS!bi=i+C034-*+yD66ai7Vxk=u=ioAm!Z zxn$+Kn8QYo4#%})94;lq$KN}{M?VS_dp<6&+sWKctw7hhl9Dw?^o|Hnmi`I2AZk+l z23(4fi(9~o0i~oqgqST^Cj(lPUv1UK7`)6Fy`ebg)3}_}r;8?JXnGhP&aAdLm zn^urrxanscRjfB5MAI{s37J$-UjaR}GE@?RRS08=ypAb=3*c%IRl>k{%wB=+*?|@X zd^Nl9>do!xU`bXH%0e|u*uv77pSp~mm%t^jQy`6j-lv`w*X~;V6zB~9o^)m)2zeaP zcvud8FD}IX9T4k|GSK$aS*YZx$Ver`cr&;pp>DnqG*z3v;bMIi$g^7kXKHS>&+yv_O%D%7L+AO8#PgB2PC%&D zcOpsaq#NNZ1<+51npz-S5He>rtBgM!eFcgQBO-9U@qfSUe^&H*q4}?&`oG^!t=jf} zmHF@c2FNpOX4ikZZ~gef@r{ZQo492bM|AYU9o>pdiBXK^(T>LVX2bHCWTnW8HkB1P z$f~g*Szy^hg&BZ&)%5$e7Gj>wM1GH5|5-bj)~^%W=LoTd!ti7Yc=$QS_eIh0V0ezY z={{>6!MC5Ar*wU#By$jUD!lR+um<=F=ifEa%b+cyFEYZcBAnsNflg zcS+YC8!JctJcIH(id!}phFKv5mpOu~K0Zqp-bscq$q=f>1+9?~&uh><(-=}2>7I%o z?Lr(-kS_8_F)pNs)2OG@MWc%F!S0j(ilrJ2_%P^0gc=vFMtxI}-%^(jVz>Egw4U*B zZcMdZL274tEI)o@>6ckzulsAy!Yt%4e6Zu=XatrV)192yi|Pp2h!btD0f4x zGMA2oiVU1i(zl#7NQFa(GS5}6kMjyia7wj|+hfH#k^n(tdGbsL;RK06{wC5r_}Nxp z)0)SiT-KtzQe#}Qkd6wpKZIhb?EN8RxEyri5Un`jovmzN2-P z6?PWpg#4KgAAu&4;5?}7j6vqv!@K@_s*RUJNMDFn#n%?7UnVm&4_b|vLWKE3^Cb}I zB}8dZk^XX|zZ#=H>GH7>FG-Ugaw%vvYwo}cd z-f8l~X*ljET#~0f)Je*UURv-V9QiqXP+_}_gWehKaN@#H#qMH?99;+CqN^NlJaD|D z?bJ~-TnHe7hUiON?X*uO=$?$tu6k_3q7F7mIP zv2N|6!eetgccWa?2nK-E<^#|aa6j5@4q+|p2wI%nSCN7pv?KaY>CEQ(?*{6{ME#Etu1$w};H%G* zTFn=0@-!T@g44}cBFEIarvQq73Q^a3XX6VWVI;X%V*9Am{)vQn>H-=yj6EC7NprL9 z(Aep<1(1h-4BDZ2LayI%;7GTFI|NiBam7$jr0$}a*hTSmi;{*HtBis6>25#d?giFI)m10{bsl$t8b zL3up0-Ky**Ynf1Cco9hj5Hl8To7(7(F-Z)_!b}Y?EGHM#ejEezVH|hN3Vm5^%5J(L zn=%X{8e1ZavQvzcxrRMcTH#RX{|9jqra2v$1@fxUcN_fIm?lr?osk5y;WbAt@^Qd)$d2E=JfdB1!fdECD(`C4BXTA?9Ue+aR-4NoZU zSR8Ad@Lr4Rm@*W*R3u(H1t2c-wH}O>Fsv--QqTscw zV8WF1suLz?Q?x(A;Vf$O3So39x9#-34e}}9^x&SG-}Nplwepl%B~#Z!Io>CyvKQNT zN)UvWspbfVc7GgQyiaFZNiqTS9cCg2Y&JbEIBM4HbX7!)6X~ybLFFqE5=2_E2sW^F zU}W|-oPWT_X%DYlIA@R_7@xn$AX!U|@RBc&j^7w#uyI?!M!FOcA75|~U63_W@Q=YJ zQEI`a`c0d!6f6Wb9V|s1c*nn=pK;~1`L8CE+v`MqyY+T?oUi;a>T8kav+r!8Qa6aJ z>x)QVTPlgml}Nf0q6;i5N>`gR5Es^mKbkVX{-Mz3Vumpb>vS0(grIfGkwumledX~h z1Eb!Yf z;rHxrL}tnier(U`!Q-w13++*x)ND11!Zi@a-G7_{v6Tk??8QY~$rXfYDBGY>ZJ+ruyWR>zu!r0z&v zmOrHHu`ewNhW}Ew`iZudpDmeSJbA?^Dvb)eRF_beJH{l_E#P||$9!UB_aWEf5;3Y+ zh($)>@)#Ax6vB*8kshn@Fd$ng$4V>o<6cp+Ayh2?cIJNfeQM--_{!!G z<=04kYTQXa_Vkmjm2d}&Lu`b%>tXm-UB5~=5T~YmWHcPUcHjeq(_VrRsB!I^_uZI# zvbv2!yxC2ZZzkQOcQ-!4RRWkWDPaqL-$gk#0V1yZd2lO))5!OIhO+?o6OvtaIgTBf zXLNM3)8XJdtTYmLn_pbW$6ppUhh1;J!`XchSbmv9H~<|x1}slKFxGtjm`y1@c|TSH z9oux^#MZGB+l@|&5~DA392e&Pyv)$bvx!%q#y>XX6(v@S)ClVLx+^=)^}lO(3Z=v+ zn`2&DK3{iEwcBNcP;z-Bbso3o#z=|FwUAr7tLeyCNJxVCV>xPsgAifH2aYQX&m^Yg zhDkLm+bv0SwWW~`9mRFFZQNex%(a6 zHGXyX_)c#lM9nAcZTTrB*VMNO-S7!}fI}+gH`jh*UKr8+&cOQn{^S|`+Q%W_egi%H zC0zhwxc=7o_^oHgw_o^;=kbdx6Muf^8;v!Y4yW81Pcizd#tJzEOaruE9#nrG?|%Sw za_oH8$?;zn#wKxL<`p8j_mW#T2Q^mMN30&p@lG2y57SPG?+ua!7;W6wX1clh|bNqE9?<=>hQ@hryp!S>$rL!-MUM|Yd{?cYk=$H6~`XhJp0K@Em*aD{MoAat*k-~5kS zYnW>)6JnpMweqf`out^|qMP-MagxyBF9d(bYn9DS0UsNl=6XlY`v3f^*4CZuxHo0u z+e9tq5H2*C5N@k)r4&n`AQ3}(#q9wMs-Asm(k!$HJ@%*O*AvT3u|u40s4|Uf(&>CT zb*Yl=M%2u%j7Rt&j$&Y^}ZvXTbWH{{%Lh!XsOkRM8-MsWY4qdfZd1Q z?0WiUcjHjat)TkuOs;eDKa+jJ(E|*<(@V#9ebR!_bTwb=xsn#4CWc#JO{TP( zr5@Hj2!C1tK z#A@@WuP!+_JDNOvNjUcfu(Za}9QF-gim$me7r%9pS^E4HTQ<1H3!|*cY)WN(-0j&p z3534z0l>)V>u!IxH+{VkhdlimAp~fz7~2=>yxnd-Te52QO!R|SCr;H(LR}0x6=Cv? zYpxNI)SMx|sfmlX(Lr2Nj-0NsFniua%@G<5BTPcJ3>>~6>2ePsG@1J1Oy1o5_{^O7 zvGM+#aBGrsJZ+A9(){}GU`Xqcu3d)i>n3_y zk9O};U$(B)u}f)OSYe{~D==@caban6vi74>$C)u_qjy}-@7)u*xPpM!`?cnNqff}A zwxHTq{rU|5vJkXe^P*A`i4ydu=hB&xx$}I_?=c2IKp8pnVNQ<}VT(6gMLjghc^HOcJQ~)P6Pm%#X4^N2= zo3kZtT}N$slw6tF%D{9;@A;!$;iX#Zj)onM zxV2@Bw7)#-+2F0;ha>7!Ph}bGT4Q11>~bk)Q%;e63FkKRr&47Rv?Jx~`)7w+pDl=4 zRS6rPb`}p}EEdydqrUe&V4D~6V70_S*1*;hMPY@AwMzp|W$m+h&uS#DSp>h-ocIedZr z%evUOwX6C2QjXKtG>Y^a3_BRngA0DCH(+9YaG#B+=MORZ%&O}iMEHDYOI48%;gS!XT9cUT9g^CyJ}J1dYxt&lOCc32@X7)PO6>1 zP>=cx%6!*0ymQgM<-@B11S)G8pP9(LOts;A)P;3ijkn$5QWyMGaqjB2YrjXN&#z~F zx;6XsUzgiaUw*sPY2JsXF{>q zKBPXi&&(&&;N7-I!Om$5zj}1N3&VVughXx5pPyw>T@hfhbpGeItg_p;Q94n|L5ozQ z)Q~3Rg+{Wn17ErTINKKeWBuu>(TIBGvdooe)0NIQHAo_@h}wbmU^WI2b~+}PkpCB} zMV>zjwG(Y+f{|ATpY25wP96m`D|cS}D<&x(jt5X&>VO+sKA90)u6^v2UeogK5yZa> zx~@jPcdjGeAbTnV*T_5n$;p|Uo+sys(N5WBC1gcM&YzVoCyN7LUfdLUoxJ%8U-Hhi zP=nBVedAz>mjCpE?Ha|JkH5(;b6i0DsTd`Bh2Y$b>nDtt8lfrVAa7-#!+5glwX!*4 z6R8>{`^wR(1bpT;ekyV6IrJ$LP#R0sCC+RvK{X=A2J^N*yk|c5ZDhW=)9%e)Y;Jo& zPoRTyb{J(tkA4|D$W{ZT2TimaT$ZD%Jew*^YQ@w#d8ZAf6;ECpt7C~l*|M70$)ux( z-640~4t%amu1mfDnAzYwlVY>3Bu&S#y~Ou%BrYvmtnF{*aQo+n-DYnWhYUgvvV?cq zN#lWLiT~DM_NE4?=cbm0ZrST~)ai}g4*#9TYE_*x!vf0`a39WmN1*(Lh^=6=!x|LZ z24l{idgaTjSQ-8t*DdQLq(dUD9wFLPcnGBK zDb?$V+3zZEw@6pr)>6Mj#cCwl;f#uvaE;iBkC=;?U8t>+ZyR?6iFrQ|-L3gsy&%z? z)tIWx!*D02(ow?m6I}b}0N=(|HARkqHD4J64IH!8TR=njOQ%qN!bMiWigI@-XMf}G z5a3`RuZGaXHYr>KS#y($O?6E&* z(~a>#2NCLM;xR$wrQHz~Q>3-RKr^Ty1hu>-u2i-|5-RFx>O`$yaq!U+S(46P-Isw4 z)*bpYWllOz)`O%%&YB~h6W_(h_KI&HET3xti;Cx@i2xIq5g{c32ba*{!9f4Hp^E!2 zdBj>yIfDWZ`vGE8IXl409~L91h3NIO5<1XI;njUaCC&y}{V$6LPHQ==Vloyqp^g7c z>8$5#Xl5jWiMmP2<_nA?dc@8%0q3`Bg8bGh;C(1icR9zE5eMKR>k!z(Y*cLuT+%nZ zkMe#TU~DVGnMkC_p~5aU%5_KD4A8e#sR)I=Evz@@W>!zU>Q$K%B6e5jd zM1-{4Z%Yq0lqx${p~m{83ZuPdmb#d)5YBI%c8+{brFtPAImN+ma2xfM=*=Z7=o z2W0`ePfZEu)lA3bDIb=lC*h;joR-h8IOwS`eXRuwOUxhPE!^(Si`9On3zZh&hS?5! z_6`FY4x}c+B5xg+m{F0Y^>{|eifg5Coy7D$^*k#93!ed}bdCZNy6W?;%n6v`E#wmC zE52`Bg-th77xX`vny%d4PUD zqx|418fn!{q-oAyv}c>9+H*Vsb(m4km`U{?hU;nV2_@!_BPhJ07kYyNjPKn&#CL%& z-tU38z2&Wc0{{49Jg7?cWzkx|(aP}3Zj>*~+VXI7n8z36u~b(|KD*@2uuS4rp~p-)PjYvYqM7^E=(Cl*pt7W?|<=dfiZ!aX_Mxc zBS%6oDN6cdu)~j!Q86-LVO0g;W+41|4NAp8dPzY~K5_y;_X&x+?&6gKESzw2_A2Hv z0|^6ikJjuE{!ehFWC3I=1yY#?QUGE(16j)_%M}PWA-GyWj#Q94H3a@9+#Ea|GcGJ{ z`+<7KKq{?pDh+CoO1fuY>G+Y z?j7~SK@NJJ6#Q}#S*4K<&!ReoyN2EXZ33Jw1J}+#p2y;ffs_U{_V-of9tF9Pg@l>T zVg==mf^5kndi~6#Fi7`)U>(&+I|XK-K$IaU7ApvM6rw>6B~nU!$HeIhP$~szr&!}V zx-VzHfq#!A?^jK#&_rwT}hq;WO&K*iby1^C)7$61Z2?V%J4*A{cCJ0V=3 zhFHlFFTylfQb~8HRgX1WzHyU!H8r#i5tcNv00k)q?deTdR-CXaT#KzZP`48#lHRPo`G~=^0F7p7Pplk7qU7o;wR)dmIlAPv+d z!W6I&#(~!hK|git$3#phA9Ro-Z8__CJjtR2mw9qj0Ux9Ov8KKPyO@`P%)n$Qz(ndr zKln1vKnAEViBfoU2gzgLVyPGOwxS9&sL8Rjk!mb`3o1zn9t%NcaVV=<$lBUtMnv>{ z;)T_Ui#+PZSi!lg*7KaxQ6I<7y52*E@-S9mSG9kP7>mnd~P)ZV<)w(Y6tgGPkn?i3l#Wm0Jwk4&7N`QL8BFY z4xaxBC`%cqbEO-CK4WuJ&m5O7VeQd25L;AxtkinWSmN##l6IzEgWaGwv((kK{eYcZ zw*e+Z7( zF8p~kP#zRX9-gmtCdL^kcAZf+rupfl2L?}oX8b_4-8{QB{sm2ezHL5E3Zz-M^4ANc z8OiTSNuI+gq>T!5%=Vo4M~u(L6TFvElO+qEU0kNI?DSN0dUbXzDZMmri_bvq{E)qO zH$^2_*TvMQxxi6mn)Ze489z@B#wKi?@$_z5K6vrBLUwWf!&-xJ_v`zLY>tgHt)-;T zRN{dtx}B8tQh@ouI#VyFY*yn=DX?exaGex;rk`m35Ff6n7q0`a05`LF$ZZ;JDP|^}*XW zwqSG~qCOK*8#=&n2KsbVte%R}mEB)ldnXfSjui+!#SLqzK6x6c{0bKGQDzehJ$XL! z1TK0jT)cwdHybmb+98_pQ@lWjQoFAmNsU#LO5ayp#U?OI9T*O&(h*&S+Y&|BpXxA?eS$YfRv zi`s3W8vxZp&%Yzz{{l%X7lNIjy=GbMSL9O7oyHhUs@eza_e(SZzly@9tP0))`n~?L zxtPdxY4cgAMqi8RweMUr=K^ql27}1;xh}HYmqe*U~m=Z>etQRViL$zAaN;Z zF9{3P_}4c)iLB|J{ET=g)Y3p6auZ^&lr+G%eBXA zs-A;D6h`!S|edPtL|d zsn1-f3Um^l9e;uTy59f61~B$VYp4`W&Nm2uyqdH!MgG$NE23BrR!G9Y(RC9R^x0n^PPpMsNY~Pq^kema!}{FgVawe3kA1OV;Naa)aMI@3&Qv) zrY-V@B0Bh%&vHiAu{UT}b0 zQy)GfOmI@(PppTCrvy)1Rirc9$Q3I5O$E9GA|4Wu2Nc)}0G^WkFqVQ^D5%edFi;kr z#h>W;?^E8Xi9hq52hO5mulDm}2!j)ZL(=`G*iRXmUWXI|w}emCODCsSjvbpMw#s#8 zK0M{~7j5uB^;)8nc<6Bcd;{K{&;AZOXDTgycd6(qS~x z&e#`r=@U7WegzzULfQlS#?qeG+1g z)4^vOklTK2Q3<4@z>fnMI5rP=WCIesOR9x%U*yC@`Ie63(sB*nhfaDUAa%#RDraaZ zsabHt#YO=7^N`|sNFhL$1Ha`wQ9FzeKx8WjWGRr{8cH!x-LC-QC>DhP#pJ+OoYg-k?+cbiG2`!z$xstKUBhFXVibha$>Ldj|K*g{SJFaP<546 zEMy_6T{u8lIdLGq-*Vdp%u=FLMy*_$cKMCY#lT(DXus!gWjO9o_1Pt}JCH3)OtafK z`=eim?sHywTSAYSdli1bbN$oKQ#Jp;mMH{!ct;kM6MA#O3hEIb!XBU2*Sk-}Zuiy8 z8zu~y+ixdyy^~}{Iz%lkHnef*>}g!OZQ|N^CkB&vedC9xT?gYoCEo}Lfw%D^HT?Ec zvUzYr!spbxRoEYnCnVuU>W^@AUp!yZh#gkA&`bc=YyxO;l?k`F+=} zc&Cx`wdAmUEz2(?ob{dCQTu;ry7zFV|NnpBd+mI-Igep;Tu#lgImE_DNJ~zk8VQwz zB$d2(WJ;w{ElDF4MU5nh-kTvwrQXs~?;5ET_15vN^3M15`CZrV-(8pMnwRJG@_IgB z_s8x2CenyG=e`aD_+zUUc)|6tVwX1t!XkgAB@IQ!-CJs?6U#!=^=|WBMMIEGDB9J$p&DL>b zR(XPNB?g|iY9naAQI4gDk`gvI%51!Q&~`tylg44}Sx%Xi?VC&Kr?&O~aQzeV>vG1K zKSJ@Xb_1-lt%0N)^_BO+Z`4;TWg9eC)F*ASyB6WQ>BBW``j)1+P+>8g|!S|k3(5s?+`P)|9xZb_h}$luN&XxD@3`Ib}9Vz6D!8SSgG49 zVwS0}k;*P9FS`pMLfSR}fO; zRls_9FgK2~3~rdrF1zJjhXD@dt}A<_jjb+AGvDYRV=w2+mp?*L$M|ow@$i&1YT!pf z2{|9~^c(V9ijjoM7)dj-aNj--w-`CJ<}^}ohK8E6Xaah%_VjX_N^pi=skZ#tTON;o zWiYIR`&jNoJ+Xl5t#uDV#Tg0RnW+}zN$?NrT4W(?p2$Z4;J&NyScceOD07tV3Atn} z(;1kPOKABm*iYjCD%V|uYOa-rfO$-LxDlfmr6z?yOK!5@h&pxI4nYrP@F!^K+Q~?< z{}_PO4eI=bzFf3uO%MOY%&35{fStR%{hR?8_nqyV$s!vz`05-39txd{df;eS8V%tS z7F5Sg2>|wKqT0hkYa%g`W!hCVjN5YWBZm)3t%mwWiE4b^S7T$kkxre zna^@mY^1wj9Jl2tRKE(c#4QX!+s&~tGzBrX{ZaK>_=A^&1|5VL2wFO)(XWRZesR8> z>z4^Ph*V)x+5qeU6@X3DLCuHm5dD-=rhTn6v`L3n%4=G(Y7yYM97)trW6WMf^MLl? zFAXCs6Zm42rUeC|T`RPb*WyHseAFV+6nmvY8mt79I;2orcnb1RUFz;FU~|n!B|4N^ zhq7a+tBZ3{E|Wo~i8&M2;O=jIVJ+(Y>X*23<-X4rJ^0dDjjt%TG-l}zx^ylD|Hc*{ zRjwl`1wFsMv!$Uj2v%uY+01Vd$120&+aC8o9E33Q=K^FR18F$JJ8u&?VS0GDXEDEa z)rn3T%Aq32aP>9p^>#IU@zipHM1kW#MA%YBu&v={5w(&g8#I0C#%qB&xcA@(8>AGT zCq~f|1mDBZpdn;@((`c=kJW1?`V_-sYV?W|xSQfh7rf>tEP^+N+8D1w9`Y^FUs#sO zAnN;;SwISmhWOlz0i4xUA9Xf%S`h<8OoK+B-1@ig3VoMo08eG3BOo~f1fIXL>X9n! z4qz7xkATcwHmAbSxjL`ls@dkv6eQxbvVa-b#kgx z2cEDv;w*)KvE+D*V8yo1QQUJ+&F!1xAx_orWI>YvaTEJ9Y#gumz7=1x<6Z@YE&kTJwjV6HdBh&xCdjv#azKVqY)L-EvHR7 zM}<K>-}a~f?(BJWbwL*Yl^xm*dp`LRo0hB>Ex30sKz?6Q5U^Hy(76CXx*Or- z0-AsDFUhte5QGsARWKN^>&y;H&dhVR{6R8+tiDm>lJgj)`ywIY(#);JS3dST`LajV$=7SE>^nV%^Jg ztmT2IzyzpKD_>&CpZ|XEkgy?vzvuBK$v4kg;XhmSly9~*!dML)Jy%PI*ZVL27>wWh z`^%v{R%*rvl177F55d19LW4yW9aDn>U&$t{XDDUu&)tWkT$n z0OYpVUjQ4eK5|m{>@Hx*YJd0T&)JBj<@;}yZ&<3`q8_`n6kQ)kRfs-aT58rIbRl!z zuI@H_u5Sjvg(yF|5P?0ly2map=(x(~bTGtDp*(|Q+6&~6zv@Be%rXJ&EAoZf_?|Ne zKIi943lrOhLBrV^TT%%)A${g-535q+Q?K!D)A;pjYBoSy&UOVvmS2syIjB1q5r(+m zaqa@shUG}Hk4J*h*8LaD* zCMF+$_m{i+j*vxyqBBKH`3ukoNmMf(z?+jM^Ch9CLep7@E;>Mu$HL$N9LxLVD~O{U zu7@_UVU<*wc^OxzLK!fZga-->rcUkPC35_hfs_+MviNF||Yz>3tp$$6>qEX2&T z!8}12OoQot6_7IFZmLj<>ME`ru*sB+`iU*WgiG!&75N4lGvMh0D3w)G(sNBDl9ohw z>&;x(qj`P!qFS0MX8jN>1YgXm7m_n28w#Nm9+W#Jw9JIbU;~0Rw=5fkk35>@zW~N0 z$@&VB30iKJDFy|@m0`;$jBC56%cLM6DUhyF2m_ST#7yz0VAW3B@RwhJBZjd5QiLHY zs}~UqnEHK3KTWq4Bm<9M2~209i)lb}7dy-Y+H}O@RL*su{deu#?%wQLT>VRkXA5f1 zYCPsJe*ohPDB!QH}?R|{=v6+wHL<9BKu1sd!5kr4lv+%@7;Xxr!eZ!U5F(c&Y}U!SYmT!pRrDDey8>~eMv&5 zm@kpK^M&SxLYFzoN{FO%GXu0+vuI2FSy00=f!VAiSn(%zs%CkEa3!e7@)n>+5&&@H zR$bPi4(mMs-ZAy9Y%3FbH_SB`=-%@{ zvvVb+VQ=oL^=p7-I%m%R0PLpNFwh@GaOJnxD#ajVX~qQDS_Fd$E66FaX9DIdfcc-~ zH(Tni8V+t)Vt@v~PBA|gJYOMQuRy#V6Fs{m44#9p9EP%XJiM=l`3Vq?h3Lg9(0TxD z=2kimz-%CJfBArsYQ!0GW#tq)FB3+UOM;mTi^A#7O+9y$`W`2*#dPDb>T->FSjjFO zxIy=^hm7XQ#05E$D48@UQyMWqST!JyV+W zZ4Y^p|KE+Jo-5whcYzF}4+-YZzc;MHs(-<_kz6i=5SqnR2TKG5ZBLim6J3k8p^Bde z=jNC_gd6~q*PguAO}_qpm!OMGp|rv%q8tXEVC_V#`4c0U?)68r-0euxK$dvAE5wWh zm_8EiV4z>5kn^>xg_|Gc7V1yrmH6$JZk>~+w}?Y#o7eM@xe&Mw+I1tZB$EVpNHxlX zNW5sEq+AorI<4O^xLme?o*k2Vf0m#>Sh>u?b4hTULSVv;%$7ZkS6Xh=B137V>t#rn zLevX=_!d*ZZ;r-bqY{`f(EbhE4-#X#KIieeU@rnwxdB>En1V(anxwIB%}}> zgGR39AwhuevX_xmzHE36=qbXf2@-aSY+FT=$_4n>7IuGC349!G3F$UKJ6$>Qls|yj zXj&SG7D7@ic?puIYb{&qM5`_V8SK*6EhPtjO51TM(z^z|&Z$bsfkY8G=<2yjUSJoQfk)je0Sl)DGWYu}_HKbq~^>wBVlVPos)S zh((Ml*09|=thVUb3d*H>L6L|{n1sU5`+_>2jLn!mnIg1q8ow@X@nOR>XYK8OL8k-< z+bN>`y9DcWrH3rW|C(_>ve5xeBHHCh400rTb6u=mYp&##IIw7mBse(%o&`Y=2Y{ls z8opBBsjtxrPV9;M@+AS&aZHBUhnS!uAtXVO7YlD8V547}R84#uk}<$Q;ktU{7aOZ_0n$ZSMR4kWu4@fz#^ zYyj+L1IrJ;JmS6SSKa#c=Yo2=;EPmo3m>ErI%$k)NqRy8SB}g9&&*h*VD;RSIe>^% z+UE>=IYY@|!Z))+dg<@aU)GQgPP9&!77rj3>hMMfZw3x8Y<{SXA7vddgC&^v+cn?9 ziyoK1;Aze7KWVvtPAAt|$DQinK;P(qpRFkJ!Og9wCgS`L;Rl3|!IIMZ;vI?A#)SZx zg=}AOoX_}s>u_`4L(ii8XYq4Sx6Xk$+y!1pjOn-oNVkt6(x&HM&$pde3jSf-_ zH7<}PMd_LrriC{0nKSo{qqIm&qh)Bv#|;9JJ`YsaBs=38gG==95;GH7ANkX;UuEzN zh15Ys^4}k7PMl@vy z_agz9Oyb*|_ihf`6|Xd1FWlKw;$TC3BP5lwfv~D#`-+(9YsG%euJGbMvk{2atUaam zz8$M@dULcnFZm!{2cR<%#X3}1==S`vEi<5WDln z;$L?gl0;OY$U!M~PFMgIE5$Y}QCy(NQUP_G0zgN)4e=R@b@kBhaGY&00$ppS*rEgW z_wnwn9%6$P0LrCc#nu99FU*k@WJTJMcS*<#{9kL9O(yK`0O&V2Sl-cZ?kuQ#VJtQ# z00gw@DxnDjw)^Hcc@RKlL5tSIJSuh+UC8*aKEsihm>&=I6F_qwlA`54KykmTBlWBGKb<{40$zlzA^pfetXXa z*A>hD$iH>+eO?08Zo~G`az9!ex9RW~`pr!x(hEzhwlpz@l<7s({*;n?@z*cg2L-0S zNj??4Q)tjJed|nD80spXd9?sqy0NKQ7YAkXhNps)f2n*gcP(l<%Bp08gHuUsDO zbZg{n|LECJvsqPEC4g8gWHl}~DL24Mj*YMJ1eFFu7J%*j%Rtb$8y57}FXzeuz(lt9 z@DK~E;p;ily~@wqSm_*H9`U;Lzga7^@SA98Vs%DMxL3y#=D$OoFY{F}YDv+%Y1ySqCVud@#>$rMJX-PWm#0gvpNIk(Ay zBmcVl0AK)hsA|dfk260!riSa59UXmsWxbDm#z3|3mGAv(pFO{aT_>lGG(^`GtnZwh zT2iNzekVQHP+j;zC&RjJTNn1@bKv$zO~_zmxqNY|a)0CJjS)xf*rfW2+j`p<-hF-l zlb=U2}`mo8XkPv5Jz$uc@*n%%`i3wX>S)z#69I{aOBoD1)gAU zrxBt9wEA58$2`q4s}R-%&gq7tXPILI|6w?Mlj(S=%j4l-{L(O^$Klvp4aY=w;6qaR zQrcI(9(fR5uZMpvt0lm;);|oke%){wzeEz2id}P_fB3i!R6Bgkrah-8JgH#On{eaP znHrf{$=vx^J675`+=g4qQH*}`MiItYryCc0SL`ybm748l)Rj46;}W-QRR<$b=voQs zSmN$R5<9bV(S_5ye=cgM!n(oHMIr?P9n-*spKtE`>DbgV=rPj? z4;Cc)L{zB9D4SHksjNTzO9!^zc-Nlf&<&IhSoOVjTV~n2$uDVZo89fK{J##ptZI4f2_aWZa!As|kg*fj% zMlW@@Eq{E%Ajx^OIO)UnPyHrWDqC*T_xrow+2=htsz(V6-*m3FbKZUE^g&Os~XM|do|ZDtp7354ExAy8)alMtw@ZhUugw`=dk zOQZ8Q9$b4??Drrji{|;FTkr1&0nK5#A1QrSr%JUaxZO#M8r$?EoSWNH2OqDA-?R0v z^?RnPw{KYAnrxX z9aMn6Qh@YV+!^UPes|-+g3~`m`iZJW>U=2XAp37ZR8HCAYIeR41HL#>&AF(x-C=bX z6g2sbu}_DD9ee2blm@>SeOF38JY7a_&v8w)*y1hYy?8AD*MHqC6kH?=eg9^PyJsGk z_zdrw*e3W=$|^sU9LsolSI>~{6~LH38!y!+jgzKY zAcHLj3%YD9zf83Zy5&SyO&em4kPjtfsq@(^j{8VUDHzW*kqLqw2Up3WlP6F)@{%o& zNVwP6QoW;ddcXWunA^wfi~XaV?zsBtRmx~{`DOTuz^{i<7R0-S${#S&Is0qT{)>(2 z{&m~1tD2kpYD=HtqDJfF*Bo4z1sVy=VSBIaTYc< z$;X8^2>$pTUw5oauwpvWuxBvH+ATKn(DyEffG^A415)oFavd2#Eu0tX70%F6RldT- zdpNxz=^Kdm7|WbnbCKL$YgEfrFBnJLA5<7Dd79Zz9n2+gW$$;?thNhZjrEAzef8Wf z4T{>f`tE2iU9VjjH&U?N>-~>@a*uOVR`SuNjf<`}^!!+4bQiJ0E%NHVzn8z{-;(vX zb+%nR2{^o*xh?RF6BPgcC0|L3f3UmwHP<0p?*C*_ZHeS^luO}-fLD%BZajMIG@qrI z_T2$XU!+!`UiVq44inbRq?i&;hx%~GWp>F&@GW7X&Sq<5TY9177h(O@E;!Vm7u&AZ z{P*-@;-=X6?;1;unTg((pQX>joc8(Lt72|~jj#;=@)|HO_c*3msGcr+&=|3GbEjg{ zy>B<{jPlK!BU%yz(Tc0kp$}(b0|Xb8yQQ5OcXZ)lB)a+Roz8gR=}wO@d;f=UCvP4m zp<4tkyQYHMSPKaa`$hUieK&V>FE0M#bmQhvk1N&sJ#u_wqh2;};=l}-ns|8M(y%KS zpW%i@-+3}~nYD2SBjl^(9!+9A!^hVeN6uu@5Z+~D#8R!f-R!!%^PUL zEuF<4lWLe{*nm8$LR>SfgRS@89@O>R!2OgD5}SJ!6+l{lX`w<55103%qyCpa7Opg( z(%p`l&G=o!kNk>JTaKwjo|i-Lp2|UjFBtvp5(K!-E=MBTjrB}ZOiCLt6yH=ysE+^8 zV(KeBl9pK`IR+1)bBYIV9{-)6+<%!4TI;DSeObIC zG3OBLJ9<$vLh8|d9b;~`Zb$FVSuUzRp3wYm%<{6)sVs5^@v_gqHyT%WrFPqUkJkjd zZE|`QX{@((^5-Yz{T=`OQ<%{atm6=qX9b^~eV*Og?!MQ3R>!JVk<%D(-&YA@;(V&n z5D9MS&yjkkjpNs_Nkp?xWj3;E>_#xnt2NBAp-wCq6l99YW5dYGWgG29{8EP@0WqdX zjk}qtLC-?=yEoVdiRQSJ-LyPXuesO zYcSRM>EIt-afKF*zsD}dI&7t!|9#V!-ath6pU3Kz^I?PWx4xbaT>5_fHMsupu_;wyy!cd>$d62uk1a31kbpCBcI&cv**Ng+fU?Yr2|u)kr2}xJUW+CTU9R@+f_liZt|1260TN2T#=-0`*Y@Gnry5s+dNFI`bg32E~(AVl+eJ z#uHo2(GX~uhYUuWTW$6$N1sjg{lq=S*3r>Wj~SIWLt}x~ zST(T;VFD(%2U02YAZfheVk@|YUarC^1r%_-@Bq&yp+}dx`e05Rlgh;qOKgeheZ z7v~iU=4QSE}A`njuqTAb}V$#OQgERacPhoB}P=1dahjoeIm+usjuzgBr7Pu?JgC zPk=czL5xg+R|n|f=hKpprPMRjsXXNRDd{>zZRF3s)S=0BXf^l;@LBj;zw%=coxw@g z(pMRuTXi2{*Qn$zX-XAAz{GOc=RKjL*mP$pV-?xfot=ee?M^}?Fjjr0_Zx{3+}iydNqN-qu?a+xjap6QYj?EH`PQ*K^KY4 z25!gN8l{2L9gQce0K)|ajFF$AmnJk(3WhAyGI*mgcZ2zWg^wH{n!XT!WmHv4*L1&4 zYCPt*qc5@9Xif9eSG{lJ!t9$xePvC@${OAmy-D2LX&W`sM`@Erj7m*=gBA~|?PS8= z6~cGU!godBGJ94JDKVAxI4i||LqRNg@Y10kE951~L8lvULM#UvFDj4kyX-_MVwe!( z*Le!N?mKngcPguCh-`6+EoqR|*{NztNBYD`b(bg)8D<;V@wvz1o8RxcW^jg!2(guf z=ER53mR){?32QUJRIrbCsg8R_B3o2JBZB36RatXFX_TqY5djlrzh7-e}x=#rfRE9T1#OXfY$W)5<;; zC&59gVzuw(8~X^!T$N9+f*0A^xB2*9Zhy6`y1Y5IOK`C-ejhbl*1%pR#0fTK|6Ne?2fASGxv{^Fsv zy&>y|orLbf?iX9iN;d8zSbaV))#Yu4{Tl*pfPH*(c{lG&vVAgAw+vaqem=R3dTsT~ zgnxYa--XqwBcF9VSbQd-cME63MZZ)$GEASrAGzUE7DrGBFx{ zB2Np!rU4{w3r5Q}qeefyxQY68HgQrCTTuqK%E_B0%^{yo!(AxLT8dmaR|#0^(dAgS z0j6?tBCCaRHy7LSPtjfuH4J@n5@ImfJn{1))F?W_`|{d00b8xHT7UrSBViQ(Y#+fR zpL{55HppjI)Ml@-$`{*E7e`(EXgd_NG)wGPG;J#jG8(z;bZGiR>Oa!Y8c$E*qpYb9 zkLC3Ajr(gZckRoZ9li8fSJ`vaygg7Ge_gti`qD-UF!SCWhgY%hX*(}X;|~A z#?>mli?xBga*4IyE*709|8O zF3iZ8V~{*X7*>&=Z+Cm-5tnlx(=n-Fv_u?%=uu;Ex^e##YD~l8qH6;Em#VXA6!7Nn z%5>B#%_L{cji+8?^tsvX za>pow^t{9n-jECtzW&W|PZrzsLRqq)&~rUZnVM<~qtJqUdO0mG`b-$c))KL(MB|_< zd3UR|z~z4O;T&y`ni97xqPuA-in(B^yGJQsQAm|#4h9?v-qiC`*0<(LC=R-AFq zR68&=wp@`vT0>;eopbok=@k^d*di0~WNRFn1R?c0haxc=EWe|2T);GkK;*?1XCBme z&k4yvfFpm7Sk!ajqlh^tETEs%I|xBAVKy>|^HiaYC)8QX2{k^CC3*T?tjoXrx9n~( zGgIx#3$|qgOQv)N9XrrrvvAk9PL>)Ar5Loe&HPOtUUa;mRznB~Eq znH)@m3cC;~^4A7ogJ2FryQ03Z(VilArPvB&%eg&fU1BEa`CWVd{F<6R14Rf}&Y8k} z<=`@_Ggd&sE>c68xKb>tpXgzgYpg-|TmZEZ_!{Q?w9OQHF<>@RA|^Tr@{)~*Kt0MK zXBK)!*T8H9P%qm~_ppq8ztlu3%ySaTc+RkEG3TewuKVPRz|hw}fiF#{@M4$S>lk1w?oofUkfVY(g^w*d-v_ zpgP}L-_Wc$ht<-Kb<{OHSr(ynDheW3=n!_KXL|e|=kh zor|aZb>Ts^5a!@TaZBPyeDY1&XQ)l;tqeH5aBAm2i?0h&3-0r{ZQ6D39Lw&COUJ0l zBYTeroZkKIK^@G0Kq=hwFM;Ad|KliUpeE3${V4d=!8f(j#+3}e=9ag2; zu%E$48nZ`9sEWlk3M81hD0?Hb8O<#bndFbrt5yyQ(hp=7Flr@!qc>ou9qN4GdinDm z!IZ$_Pl&2xmAhV7*c|kkgqcKT0w_N@*k;A#0I3~0H1W!<`=KhEJ8b;au7z53^9eA zmjjf#zo6W%vXHxN(l3{gmoJd?V;a=xY`7cjq?aQ1&9T6S0Xm9%eKM^&@=} zEBzC~bwZ4*Rwu?}zi(_fADxP^qh&WKFUd2vq~5NCKo16D-44B4S|XcnK5TJZJ9%_f z)DPut>#O%)pGY}=`OIG5!xNq(_ruP5xfLI6cDmHnN@#zc?cIF+tT-a^olAXT0=m>D zj);C!b+cAfXuE&S!gTZ6{wTkHIxj)c2fbWvOY#1*0=P*gjYHbVuMHw4_!iPplu=&) zaff+csHqEN(FTNL@f~SWx^)W4m{A~jO(OTFq$Qds6eh|2h!5+?20R|H&k{iaD%L7w zTzLq@?JU`Yx2nW|k@W+yPqi|KgQS=(ygq0cjs8r^+MG~(*qbYtoD8;pI6?BLnM07M z*&r^MA_q1SQi|PP8D-i(9Vev}%=OybThAXSW={okcs5yNE@|e8%IJ{MbL!UzH|-F8 zdjsW|60A!;T{dD-hj(Ce2nj0L%*KP{L@*24kRzrxDF|wG$@_y3WfowK`LYHnv*|*4 z@&XS)DKjPLl6t9r0~>xj?6E;+EiNiE8xdLF4ar9z;uzOwivU$*okH-&e25U8<-bBISOq_*{Wq#vHLMf$1xBkSoxrF7{GU2hkJ zYx!L#HO~@mpgQ$heV>)G&5l%_^L)K%)yeSK%h46#bL_hv#u00xE?9k+!?I=RRU_4E zuRovmJZOS?)*4;N>>DEF9`E<8{rkN4iiDu#M9Q_-lL8-y1kut~?})A0Uly#^JtJy6 zjtWtk7oeoMH^`A-m|3q528xuFDn*o;R);X2V&fBdLef_O!U+UUz)~l82_G@@4zkpb zE&S($uE4uNh_NOC21**zT&WIOPZN@qimf(GfU`y=vMf}D(X|(rZ_xp})>R_tQxGDv z3hELm!lLT|VjP>N-?aL)5nml*VJ0G%(=M2QV8e^Y9+`HGz&+)0ug!$3mwa-ChS*(P z9!P_kPc`6`S`IFIr?{*nA5QPcL?28L8)RKWICsD0EEm8|^n9f`gqcI*dBaA!zv?Zg zIERbFdFEefaIX#y4y*X`&EsVSJ~)-;ov}0e&YN36>1De*Vv!o^NteuSV)dO4I>2!|CQv2O3v- zpv-k(33%>$!j^ldbdym&bS3!a7v(>dCG_8$v&yVmSMYJ<4vvrCU_KXz3>Z)cUJDmL z>rUu5RwiNc=S7B-nJZlf0AAy3s1c(DVHlmUfKO%nlwMwq+<8>(U;BL6LDO;78OH_v(fNZi|{dLjGaf^Qf4u~dQPd&XCrOl%h z2)?zR@OkuF&C$8LA8y_`HWI70N^d#1yL`{{kAe_K*Kt{T?^%Nr^4tF0Po>m>6ED8C z|J(iYv**uj`OD<#(tzIzN$t1mCm_hg_^Jiw5cGQblH2}K@tX~*(|5miJdl|4o@Y)X3bY98-Lt~e#ezD=(^C~G z&LyPC7MRl%g!V`$(#xbhY)==Wq80gi)hhUv4=T&C+5CMIv}wgL;WpS?sQ&Yhr|p@) zMv`=mn;Q*>rn59|2bunUZR&IG#X?MCj>x7c$fQ#n%zi?N2KyVZmP`?IjQ7^)77eVw z3P#14iJSDkUidN;M3?NAt)w!ZtNpjREMa zv#cT;Z^l7y!^`r0{p0dbx%I)5^=xM4tBN-3o?`X~M`z=?+FR^d6erjM3R&v!4AZ|) zu7{8(6r`a$y&Wr0Gi1~_I&44>)gYi+1A65ugWoDNR&CJA#%&kFqxgul34>9EIZusm zfEYg#AZAqy2Ko=)P4II5pIk|>PtkAXn+!rwADOs$frUTF1ePMY_$H$&q}jN^5SxVl z1fGf;AEzPn_>VqTU@s3fmW07a0kg~$eNe7`rYM=EE$bj!Oq?h9tMQ*{xcdr%JcVkE zGmaaF?tTkb@b!6fRpGTlib6qNp~E(+;1kO8jJKxJ zRXFfw_mymRS7+dj0$FZzF548MhDY<~r>2wzLBFz^kv&-t86O^`Jy>XW)PF)d5>z>a zc#r-stkw2##DBkK|JCn@AE8^O(j8w+Acyzkbu?oVosg&|Q|ZRO05MukCee+*^Iz0O zKyc#*)LP5uLW3b7;HScn3Q(p}EIa9xBjftc6^tc0PB$KPf4v72GMzm(q;rL+Du{Pv zMMfoNoaTxwD?^yyKM|vJq2PTs^PVZv55qUP3{KDzX_oUGXT)}Qm? z^~nLWrM8b8Hq)SNq4E3vpNTa1EX154fb!MG3cCL2I2a!w7jQ@c3Pgc|@G*@Lx|-rV z3GN>);%f1skRgSDI*~3T0;^^b*amvQ3&6-fb-{uNoQES&;c%=r#i%lcFf1ewLCo1g zN+=B#13~pJqeQQMXR0>lswnN8)%|pn{#xruRP$yXWHT2xJZ_>;>oo~2#cE0`ttEgC zi`JbDPqhFm?&P&B$~d~bl!D!Y8034_rl4xn_#rk{nj(uvS@Z)W(~F2W-A*n$p<|p# z-3l)l-^1pZ^J;Tml-erCSzgiTN8qp~-@+b1nF@m|SL50QREf|`QI2S5+bKBkq26$b zdRsm?Oaqv$6H*y$e3fcN^QRXGmm_Y z;WvyzZD(%5L`_?dS1pn&MXAK7%tDPkdGA zry{^|@6NdOm+&;+Q>(E1(Q0V3V)@sspg|It%u=k!>GxP`CC^ zA@?9epCdF-Nll%nFufdj7<+H!ituso?AOMN8e+!AoKU23eYxsJO~2Q95D-*EuC66j zjpI_sso?exIlH-nb>1pf-!VGQ3z8PV|?I|s_OHMGZ9e{u?yai1?q3QCi-6#?hBL7 z*Yg!dkU5xO=Xhb=%HfpwA%$rHd+*d8N;O@donqcj-*Q@L%7s{L=D>M06u&9$gU)mm zk~}K3i%X^Fd@*PT46BVysxmkbdNJxDC65EI95;<=Kzwxz;-(UQ_ij@_ic-eCSMdp5 zndZg!5a9|kv&ZH|%39UNHOsgon`!W%ub3gB>AcQ}&7pi$#Y2S9-{)Y3x1n*V7S<{L zf5cGoGpKRxiY8_;Olv&#(5xN2xLV_nkYu^AHXMTGk6YYYO&YuXILOo@k3%bA>G!9^ zkG;Jxb`Z&Jl}e_KUZm)AbteASq1Lt1_g+E7?+YfCYJC3_y-2Oe=0fw)(fz0Mv%eJ{ z`q7cy922$p@U|;Ba$&8(8iCr07Mlmog%q2Sq;qAuf@zuHj6VZU3^WLl3{V zmY*qGd@9(*)ivha8<#v2UU2>`X^vCX^_@2MjM>HKp4}Z<7oH;e8najZitN= z<(r3ZM1VSTSIeDN1p$Ookz?o_+Cs->Hf}~Id$g0M9p2w}UvEf~+r~#J6w#JkT#oJx z)ls{fpQTq->ryp)5R&VyLyTfM5o37Ja^9^%|7LAIuxOWoD6-cwHx`kc5wAW>o zv^(WGoOZbG%oMGTheKX4{8AwiHQ)0lH*FSR-`pV%(QpR`@HuSU7#p{l?Gwd5d!_+7 zs6v)Q&Mh7T$CQbpds|<|*@i?rC|5FE_Z=eqQhpdX)Sb5&^X{(eD(COpUi1bj8y7*2 zZNT+z(f3zVvjM%Das4nA+4>1NJjLvMt>L5TL#uXOdl^yj-K8o%)@o#Y`*k)tjO`bu z@(WNwh>Gh5M^W$V7T|~OoJeP$Tz?|^-1*}NZlsACClsNtz8`{*aNHG?_8%_0QjDNM z&M^Gy*ZD@HJOMm`fRJ56P*=RGbFTk9jLKAi=e}^o(APNU$KDUY3+>mObzv5q*4om) z&P;D#_DC8V@mvCD44xlLzu@XPn0Tc*VQ2vI46CYU3Czi;ON(6|K4DH%&BYS z?#`H}ofgNezNc7y1+3nv$^Fo(Q7Acbk6GckzD{?dMucgH?EH{daSft|Ist8}0fdZ7}mqj_TyZ@L#^gcwtXm?0u8-`#d$0iJ~12fICj>CX?+T`Irk9(`xz z?Qou80q(CD#;5jI@zGH<#8fAt!R}@3^DT#*>#=?xVg%if-zjqv9rDuDYYxU`p6lQB zo|eqU7OEbntpugdd0$IJUB>OPqN%bPhXzBy6n4@k>)pv)?@q5<{0|;c$VYcs$54_s zDg(gu?nXJpop)lC!}RR^{qS4u41KNDZl))-d*(x}MIjKiO@~6Bov3zlYWls&`tfQD zywl}rW$F!Rn8IjQ*qLE5a~*SYSrq>3Jly?Xw;STeMM1X96l6t;c`FUs{|`J%ZPvC5 zQ?3~7+KW0!H$(qpaEtgB_<*81;>u}=O2Ol)JMiy0sGyksjcja9s(Q;oiZ2^e4F3KV zwxQj+2lmZ*qjX%P0(`DSH=N#?#mD986s>|p!84@&IDV#6zfoc2J1|)N-@o({M3Deh z&v&lWT|oZ4(4~U4(u@Y#UFX<)qu3atwIk#ig3T58)(tk?Itb}0VH*@ncapQn{9>iu6wzMzu+ab4mk*u@_H-ACy+QgWpCjkdT<#@ zl$6X9+S!L5wR6j+mJ2f-S6Ez zb}j2!=U&{B%g=A*Pmf9OZn#@!kW?JQR!A^M?Ibvp^g7$z)qVRhP79khn|^-PcgVrv zvU5nxrMSk#)4(I!w#~_1xCjdNQnhV)cI$xO^^bpd?fLbaK;8N0 zc<+9_3tOwLZtZ&VJ#AokqW=KZzZiYPnTxKNK7{a~xP%N2_XZU|*G52l$_jp^qyEqf zyfy#wzx#*=CH>Fh|7h^Mqy6e?#iyrj$+YW(cx=2clw&OOIp;d~RH=oyrc=oUXtoK5Dlkfn|%Ux4O`;6Ys zCAydE?yv?k!93q#wtB^W1=FC+{d(e5DHA@(pdfG5U zEOyYUthqR+HULMw#LP>fDCgmb{h~@m5AkOChC0`W)E>0Q%p3<-?#JGMjPh10-`fi2 zZ@?^9Myq?u)0yJ&#n(kpf+x@aDbi+NanBI_Ow7%G*7O`5?Qw=phY_rq;)CvsEH!sJ z*XU??&xWQ}(M222{P;hA|HkF0pnBye))oC%0q`R#3(O3jlH;m0fe^KF6FE5f)5aC& z$ooxmWDm=IGn~m)JMH6V5(gcx47qPs-tk^PwBY_A@=Huvi7 z-0JHl1ylIjwuagDvBBx8&r<3XJg5a1Ry%#e%Nea#1fKDUYH6;bpOXhYEeuL_t)z1R z>b{M-TAK%v+9WHduCs~gxM_iYr#2F}>ETjq#L*&ZskfZdmFMIkDTN#a!EZvn!L>(l zHnBRTYopZaOe48A=&}FR+aKe4J|@=}PzkaST^9>{YSrA+XamDj5qM;Zn2L|ZCD#Nc z-`l-4crHbC6hVofz~}_AeivG5Jq#x{p5%=%4)Yn;?^27-$FCZVH9BvmWFgFNJwro) zx^aYy*`CV=+rtpN7iHAaFdR!KlW@@jsFj7Hk73&lv;1F-%J1`T)Xuk9446jPR(+fB zfL5MYIVHL_nIA#-(-OOV%OBsg5-I_tPhrTq$(vU8-%zW2*d~!g-Ct5QoJz~gdUWZ| zCcpLoaP+|<48rvuE3Vu7x_DQ`$oS2XjpvyrB}&cy+fh@g_46lQfu-p2o7|DX{p3aK z7u~4eTp~DZLeY?BRJKmhn4zDAbp<~fG*lEnYauZGR;qo9cd9n41?n^+FCTY6zodu3!rG) ztw08c)XhRMoOXrKT+AkN+`}yLpp zi6&6dzXB-D?|^6z1!0pzSod2Cc_ed2w541i##8vP8wM10f6em)Yl|A&x->Q>-BspS zzT@nu2JgS_DJ{#Ow%S3cWnsczYl^w;9_~Hw9%>{dbc}ii^1xoKt&dQNkHqE0;Pa=C z$9D0nzx^wt5?C@$qm$W?LEXGrbs;`)&WZeo0cvUM1ZBeY*17S;wOarLP18#B?qx+~ zw$wySX}DbCN7Vk0*yt_}xspt(U#N-9&G>?;9gC3_t95*V&a{Rob#yQ8u%|$+;*5O( zwty_Q)`*s0mSFO^djsLY*dbm&0diL^OPoMdGON(HRJgQAZHw0i_=vMu!YTbh*l}5J zTk;X>tK{7l56eiaOC%eHwt+@HMp$%E71R(Wk(aBD+A zh;I`z%J>mQ^+`g{$>Im-2T~R8!Q*B(jQt@)+M3)(JxM=_^f%J?Yx9!O0%O08kyzyq z$t1TkG^X`6)6$DRmtGh3>UWHfyfQBa91eM*)U~#J|AjQ%k*(jX|a_K7cIMlMPQ1JS#1QGQ(WOrDyH3? z^-_YA53cvd8~PXTJs}lJg8z2}L4=ykFvCN5+V`~JFAi!Il0g=sm(jnH9x&hdOas_( zdV{)*IVrHdxiDV?HQ_R`>S6mk-gJALDWiE2*j?3jRZK2pQm=8gnTGSfofgjD;KHBN zVxy=^g5s(d)JcmhREnQ zzebg4ww+s|qP>A_L-7P#F0A_X-X87sVT;F?n}Fb^TbQUJY2+Tplw0Zt8gsNg$@*mv9#?_qI5lil0?65o9Q5uE?AoQ5pog@*34 zf_|&uw?svM-)L#r*pvf%&;pHCLF*d97q{Y)6qYp#3x&+vFbv%=19fYO0?oQo9_*qA z5uaL-y$&A5hnKH|#cH4dswgN>T23Q+uZ2Yl&4Y=s1*6$uD9cENIT<#t{kYLBK=Edy zBD*Cjin??2Iz=CsDR#uAyO+c$*z8o zGJm?gS#f3v)qcLRYLI4ML?bp1SA}XyJ?U0~f>M3S`isXERZXS*>)WrFZF}>1Q}$h` zdEfRSg?ye7@PSkZ3#y>q#66RMJl>wwTJUk*mcw(_a*blgf0MiR9NV#?r^xT9{hm>B zx0}f}BDP+LUP(lCE0x68=#^abG49GAa#3}r#WodTjR10c8U?5UPO%uQpTHfLdUj^` zqb29>n$D_BXAFeDjcAW)$h>k0OaKW}qS_6(cXZPkwW<571h4gte(N36dL1n_@NLrw zM+j=01{QMMY91ddRAU>|ZhT;#j}oDVU{^xSX;i)gv(DTJwnB-pFre2Gf!Aizj^$e& z)I>)n^z|ozVgSk@sNKsIp-kj0nms?WDsUQDTeZ%^2slEj-|}|8E2rKMj~1K{|3vpg41Pbb1D@ypdy)cxQp#FQcix z+w>Mdcs^&u|E(g-s7&vyrNrbPGaL&^>~yqL!516R3#o{WTy*eqSwSW=$FOd#rhdPt z*ETw#SvhYJ1eI$*ALb&1H83AKcZ`qJfj22a)DaZ|jH8pyJBl=*Ym13BAVFv^O^yAP zb{u4TrXVKKbW*4Rxx#?tz_H8BIvHH_=B@A}%H(=|!QSwwBWfgrj;RvD9xjFX^XFAE z34dq19em?!c_NAdK_4<81L!CI8Shy082qu$o#Pk~2cDq9FRg%{Jb?gXh9WM~purcZ z7%Bn0jG0@+Kf&&Y1y3Um4unsD9P2mecMc(U8oLhJarkxpHyC~blq%;;(CgjZax%f4 zBlKY=Vy%WSr15cUVI1KjCxs>}xF=-vlQ+-79w#E2H3T8|#14AQv#sijeUaDcp0N=0 zc_BXh5i$gVALpJu!b~YLqK{Ca*Nhk!BB^tyiRCxUmwUcLoE_AmbMp(VhX-H>ToblW z9JP)=+F5L~(+S=L0=fbSO4HhhXj}4!z^m-o@|zh0nUr6`^SnR6&nL$>BJ?}~q?m~E z*|H}0F0pgQq(pMh*j;tG=snV(Tf0>~Ojs3m_*fi|87VXZg|52O;EGLz2`amk-N(jj<;Ak!XV z(qV+`5o0f@3C$WztVR}Ufw@M<5Hy@BYMEMq)_s8wWaA?Y&`AE0q)^Xj(5KtRUe7A02E zH5kjkF2M^B@UO|M)JLFK5-7vLT&y!~L&y9Wu)iTtF2C5s*|#XGKf zT0&H!FrM&MAv$N8vQ}@U>%xumkwrv2LwQ)J!u6HTUu20>UxAKVz$)pBdO-f08|L!m zNGJr}ti~fk2$!be7c}b=k@(7K0@$GAY`n;(lYAh<<2uY8wMl`7pxPGYGJ*S`M!L@t zs{+(1lP8xnK=O0xqzkn-#mZ$*1@qtXpQv%S!XStv{ItBcEz87mTQz6mu5=POBanQ4JZ_pR81y++P)Tm55o^0wq(? zBSzGNEZ6Jr%H5fWr$$_l+HZ@RxU?H)U_WswP0rOo^%r5os`j-i(D*KN9*O8v`(?Ls z_DBc;t~XCDB%~Xj3IAhWRBR{0h+qQafVhZjIfLhA0jJwNAsA|Yy3e{N~) z6Q|(hjnL>leGf(b(M;qiF8YuF*-Bp-@bf`5VS=@~KebM}tY{)`^~0n&^aU0ppaTn^ z$6b?EWVK8IeP4%4pUwq&=C*S9dh_UNe^DJp}nr4mJqgWrF?yp)E_rNZ+n;RW2}bi?01>Q@`<*G6!Wppttx^XBXW zSeo%g93PbqLB!Hu&8K>Va*^M|p(}(aVJ!@#64w&_iXaH)ZiI`{JB|w@6~ogYOWj|j z_;bMv2Q=20^3Vja-9a&r3;NJ6cPAiZPl&n6h{Kg|-i4QMTs%V5h!uS3AzMFCr(T$5 z)k_#W{2oSff??PNrIqjq0cx{R-iUHprTy#NdQ|D$Rp^a#uR2!~HI--5z;~Jok;^Rb zS0irR@BH=|7A1h+Qspk%R`vbPhp=4a=Ro^io2-`QjajeRL3@7RZ*~6~72H?Y7p;Mx zqT{Y8QAk}psG%>`#4G#yA|Zj@N|SX4%pn0L%5Ng<%;)4q6Y=jqM@K*8y_2Rk0hYv# zvzeYto)`M5t@S0Ob3bbXQ(-g#6rTzG^#dvmcX_zfDmQMzZ+a^HkY=_Rj{xAC~qHfd&7);p~cKua@D23p>MXp z=%Y}#(IbZM^L+#h_liTYcjYLvU285be$QB%d!#B>4Ilq$7O1uk=2|_JL4RGk5JfG$ zy?je!(@uIoy?+C&-Y;$4Buw7~EuH+=n)UJKu8%K{d<=hQZTDOM|A(Bni~6#R_#MV{ z90sM}61s)xQ)*NggvbPUTn5LJy5=8ioAvw>hhZs5Zpm%DyJHJ#ZM?mHK+gOVt#n#Y z@4DjNL_(wI($hJQ@4Z;q6tMPA+ltR?qBj9vg~rF{UR6;Xy(Wy^dpxSG5`G`<_$a=C zxArUPRd>f!S9hcqUEv=X>;Kz7bgr-`ew4kS+G-wGHF$v2pKg(`vYD4Pu>fZqoTF5d z(&RYDz&yq82lObsOZkv-k?q$rrl$5=XX{9uYSM+mHEL#qOI(e$Y9D>AXx>1zUEtzZ zO3~N=#%^Ih!OG61hG^qBo!kBI!QFulDjl9e@{wpSD_sITy&T7<>Vz%iUlEs?{t3h!WrXbOk9r+q8I4UfpP z(;}2@7T*c`Jz25P&tco#mydB&iA71gb4~E4c-K8?V9a=dF)Fq42Jg6>ynga+D~yj_ zs>I3Umo+(Mmj+0i{A^yDt}Y9cpmtsm>Q%upulpLRg3o?Vj{N*!Beg#A?CTUJ%(9fr z#)f?PtMbm>8y-izh)0#|^kG;-kk_CF*0y?(*~BTFHY!u1@#oVPVi zy8?v!*DACq|4%V=7<1$UDDIya^~DY*FGov7&W(k;)oegAKZu}HT*HFlfxC=i}9JZ^e4@D$UgwCS!6 zS6DVzHtNgj%FMCjzMlb4&3aJ?+q|Bc2{MV4hcE^%QzruCqxn!GYTi@`YmfE~o zhWKEfP)zznL|PQK)TS^qDMN~wV3oEy6f8)I;K%retDJ3AN#rfu1N3^eNnuwOemD}N*-V(RJYjFch?n5RY;d&Cm{oy?1>hG|mE6wN zkp>^F-GUaI93Iwc-2=oAz?N;@v}6NM)kSIotd@+hTqZv53{j7Z<{VT2c8FOYWil@C z&Vz-;@TC-7p5?8)K2l$5bSBfqx{^QOQE#;QrBNzwDWp`DXdwLbsJ&LG`w=5R=PEhG z!(1!Nt1Y;HANrH;N}x6z4JQ*ER=X=?W1d693Uiknd^*xTq51;zOzm`LH{CQvf09tB zY?F0)3#P6Ls@Z+5=BH-#c$%{`8hkcn!+Ns~-&2Ih#uWRztEO>Vxl;GEmcRsyk2@~{ zNJXY8aRzXH2?0#`UY>ttOMRK$u!5XXgda`hI4r7#$l zMHgq&$1GLU?0m$(JBvoNHcxr_P{_wKPT^217k(YMevV}cm`EQwH0f^QeM`d^Os-Mx zsA}-FGP3NP1scDo0O-Q3vxrErSeOCyd8o!QHT(hlo_Y1VObSkq7{pe+#ZnSK8?T#@ zhRh0Avu&D)lwC+SW)6RY?h-LTmedk)&Y6jaTha`|mT z3+?xt_f4m6NP24bp(3d!skBcLx1RT#&b*aIBerH!#yz)SUli}!KAZgy{sUlBmWQ}% zRJeitEm;CM-0$}j);x_(4<8JliFg;I2H~oHVcSf?B@18{Lp)g0f2vvzT1=@s<>c!y zxCHe~L}?~hCCWZNwTkz!J(9->zQxCPKwI&X#2CAu&4cU89@{kYsvLJWy?9_$;cpob zG-;~bfdbb2)(v>wQrAz-*V+g>SZNuP>nKK+jc&T&=o+V8fqIa@RUr?>31JJbf`2lR z+KO%hfW zUlCI>Em(Hy;?=&CEc;xV2qyq{MVKNxp$h7IcPAh6PYY}t*WWkwXKqkTHoT;=AG)Tv zc7b9u>W(tRa`GqKvcss4cvb$Fwe=Wnmji% z`mO*XwIa7%=kx#_wH@D_hBVc`@gK3kt}J@K&Bs8c25FGLwzma2;n~GxhEYm)7nM`^ z4koqJ9QxqUOm^H8bDdhBf<>djH7DZ9Z~E}c(W*7?$I$vW8gLFjCbMhw)@6gv)|f0? zGr`7o5Ro1{s=do_F=>mc)TUOz8FthW)E%D|<9D>$mF0Tn=EcBs&(t()$B5}=|9+V% zQ(SZ$MXPxy{P?NzuR&SYCZki4cgf3bjQj0=LV9K(EbueS_87JR&QpnRM!>HKi2R*! zCV0o+iYQRPkDdjb)QIa6aqO_jeg^*V$r-pAj`b5R0i-|IADLUKiM&ZJjA0(t!K znJvArg$Jb`^!-2XBVsk4z5jZ~3Zbj0Q4XyT3q#nE0=7p5+X2%}G8embu)VLaeQvRR zN7#N-Z2ws{9mffvZ~`aT?hGLMM|emECp3fR6BT66Tq8o4^_futTSLtJkyvCePd4RcrL+Jpz8RAf5+@D4pULMSTMGbLMNaXjURc%CJzy31S zj$3D`xNa%vvqS?X3h(ZCV1Dg_tCMcO>-zPrL^~BUvg|-!?Z9?UT;&&GQ3hf;n%|B>*J$y0DBR;)n~{Q8z5jqR%b$ky4dYKZ1=LEj?%>T#>5j3 zbSL`Qon48iD~1AR6VJ^bYAYk9?Z(+4P^y`0&0uOS!9UuqV(RCRtkwqSGwDpfOkh(Kv z!0k4Ikw}D(0_16tk$PPfaDAQA9U#-Bn|OzN7I09Cz)7x0Gd0)BEUzm?)^xy%R@dHb zd1Vm$Wwz!Dv1Vr2)UccQhTr`#rq)FR;=Lj}BC)6wXZ6RyQQ@M&v^!VnwkyBXxAAJO zP3{^{{qc}o`?jmMFCYC)jSh#52+WhcdLAaL8-I@}3mSX$9LHkOv^T({Nh~sf z7?5C~Llkzg(F$cNg6toBr zUZW_r9aNB`uIc{*_3v1~WJqpw^o|TeQa%dF4Dl+6)SkIGg(O|05`#*vCEwpkbDl7X zvx^73nxwVi_kFSf&RP+E5MphFcnRQE5WI1AksYJPj3zSea5WtSInw4pw8-`&Wc8G= zusYc;4~Fw>P|Vhtsl+GMq6Q3(vuRgh13(z0v2NlCG!bY?%>ALUw(G17UGUeT$2%`m zZXIDu?K>8)?z%T*gxK;#^C6FF$NEG0fHlASsMmnQj1aM2G{HX|tEnMCcAEAI-Ma3P z7}8b40C_O%935*3o@pQBR&D1EU;?PaLKttzFA_%DcGs&B8aE70B}$_6WWK$Csih>D zYwy*zoA?a68f1v`5biTTYtZpy+Z4q=fQ@57v!$4PEcM8LkNta6&yA$E`aYr9J6!rw zjpK{m1yW0IS&;DNrP+oKD!CL5%H3EjADO9q;JH)iG9yh6Xbu#L6R16*({M@{JS7iy zqX2L}D@lPNy!a=H8VMy|l9C6vBEoqZ`JBB#$}zSjG{IfscbaQpJg&HBJ{;$QiXM># z4*F%Klds-}rS!t8JNNgfT{rWQUXb4{=`AbI!_J=q9GIdLpWwdq79SpPWzoQ&{Qz?Y zQ7l~GdI)=b+wS=P;CsMz+B{euwdz~vkv~=;cC;OE=-6e+fP>9i@1|Ep@-v`zsI?R& zS(6dL2lN5rP+CUNFk)>m#h3WMhAWz;Cdy)^KSPqHCtPb2HLt`TA6MENk&$KXDKwb) zBYX$^A5k!rdl$;&qqxdNRtJx8CRag2jn7vBhzr04UzpSI%1W22{H)FO-(s7l8pjsut>6usYs5O=k!XKF{Sf+r3ovE5y~w2SPBoikGkLSdWbCw9WQCMK&oWO;n)CY~&d(`i2gD^&XMRLI!g^h^k10}p;Q z6G<}~O&#)E{miP5@oJvwta{}>KVZ}jwgXYNS|JNgK*lx6*^DY46TXRVFPM}SOd?kI z0*of4-Fq3EEH7w6#*pR7ld_UL`TSn_Mx$&!4HbtrXYew;-xthzx!=q&jQKef>Xvm> zPNG($A$TDt_J+`WM&flvx{xWwQ3FH1HGHg)74Nyu`XpJ}1Q&0Dlz^hC0v`C(_qTT0 zCL=ul$!YTNGthEfjSObi$X)23T%$D0Ze1qvJa{M*ZzAUqMICg}e1UxblFp?@Y5cUb zV8kgxD4%%r2Q1RkWCnaI0_g+*juovp18@;gCa)-62z8wXf(*!uTcNqc-$3a$;R`H- z`pQEsCz3tQgwbAV(JBT!NG1RI4Yr}9Gi3&jnvsFc4=^*JrS*NKC~eiiyX8dD7NH}T z2`)T{z-_9$Ng9_fL@PVd0?3MgKX?#Pa~Df?QD*)}xc>DLzLH!OKWJq;_*-T#P8tAQ z5CAxD7)2pndqEaU^}Qb6bQRWfe5=<~>8|23C}PKnBBA*BCx{y#NrLpu-;4~R9Vy@I zp1)gZ#NBCi_#6kx`9o>STq)OdQ>x>p z#r~U?L~lw<*|c=cre(ivTE63}{%{qF0U5}(Ko7%Ghe43wFeA_5#Gi4@;q&j#16ZN+ z37uE8;oWlDpB`iIb$P+-Xhn05PeeVvc?EQdXtO+nD9Yd>gXlrOd%b&hmUXXEynJ$< z{1o6eEH7&6D>nLue1_FjBmKt@uf2$1L1aZ`2ow(ym4#(xIZ}x7?|Xd)c7FRK0?90c zZZ>?AG#t)b2hW;@@%Yl|$4Kmq33Fr-(-l~?b2EvFT1ffey-T$8 zK6I@b@%T;Ts0%9LYpuHO+w-AyUyni}d8l=C&#HYY`#e|<5m;OHJ%k7^7eeK~V=c&7 zCZ(pP9_bkEPfBFKeo9Ck^HVpJtyG3~*((W*GsVQ8>CB(dd!TwN{rt&45c|D&y2Q6^ zYv8qQfzkQLdQ9f7J{s~WzU!tGFH?#a@)Ze>p>aeR4 z(?ACtkvaqG^^6z^#*S0_V zYy0zmw*T{CyK!#&sA=VxW2IeG!o``W3wLQZJbb0edF@UovdTG_tKa!5u1}B`?v9p%L}u zfReVln{)R4QSX?eWBu6up;sCMHtOX%4{?WDl?A`vXYZXmCM-#7Z?I2)&rHys>wjeB z%WJy3dEIr}4Y{#xgKR_<-fP)YW_Knh7i(Lxt0^pyG?e~lL`P1y)&)g45FyCXnt$f+ zRTXsY*NTqD+E8LU6vWt)xD#ufO9rRkJd|PY`o@1C@_Os)EYqg?9>lxl*%cJz4>K0W zx|ljfJmChwif)svVu#3&v*d~R$O0GJ)RMHmmb|cq2k)HT9`XJC^J@}Q|H{Z8pI-j; zdAMY(&x&e8q^)q?5%r&2(t+SiUCz~CjteW%PEs?b4N|a;GPdu7z9J*w8k5BQCIy$-(*b@g-QAGC_y&Z>G27 zJ^BnV{Cu@AcXQza5M!WCOoNW;bmv2C`g#6KjB6V>yXw_Jm0;(M5MP;S_8ToRZoNu( zQyMz|<=(&v!(Mzy?Pl2Vz@&7siJK}Nit?KOiTkarIp$XZemh z6JlKOF^#^{&3NN=i$rU9f&cRf5r$E9GbOm%KwAk;@?*Ml8Lfgj_qwO#m{LqCs}Ml< zhrckcv`HlYtsuGc*4wUctCNe@lFHXF$3Oh`b825~?*kn^KpM6$V~tlPig5hYcQ?Gp zAQOhY`z=wAg89onlsif&X9r#OWSm|9`qagKQyU7EU*YlS`=^SJ@4jc=_V8-yGY!;_ zock*ph7U6LpfJVTXPgf8+*=fXx95He$Nv0-B}-PFf4DsR(D_Fzesfyz_nK|?p~KlV zt3n^IJ9sGcNx{iyp-+GN!*?@*NbYQVw&c?^3+XYzWbaPfx`~5*8}d<-;ZL5DS-T4I z|27_N*sHhlY*Okvb{%KtzTC9^bt*P&f_ob8uj2Z>@aJKF{`q!A`JAr59R7`cQgQMo z>16h0uDHT|dbPeikQ&u%9X)MPjEnqJE$hy{N|j}le6`hECt@~8tyj>rC$C|v%8T*t z(rMlC9apKT*B)%@0{DZ>C85kUx}a4a-xi{)lTqfu9`=AX##)KERTq{0XCS0c{=mf=?Gf(U#4CH z2pU0?2R1w53-a`KV_Y=WgnN>_R!xBhDA*KdlB`2&N>yR9X2j$JGcpf$DlVtV*``m8 zpk)Qrq>ngT|1sI`FAk{9qKuO-@&|%i1M2cKTz z$;4E&17plIv4h#z(PwTu%QUfL^m+Mc%+0_;?FWzr=m}kin=t_s$z$0>ieOY63+549<5DW1E;veGrmz@8Ty^)%!H!%cP-4`7as ziioS})uBoaVj%n4|Z6W8Hq>0=AXUvGqC+eL{hvKBh9RPT-J&V zrZt-~Vc~W;BGf_^6tVfPV#gfF_jvN4rfdT`rB>teU9uXmS$Vp{sZH8jsOC6IXdHxqgoQ`%(xHEhH{Ing8%)R>;ZpXK$94a}~?loGniY;Nsr= zN9S5YPUVN3Bt{v;-iZyEH8ZeP->0kQS7@WYKh~N3tymDg`Xg3o?~{ow7}h(7cJEwO zNV&%BiG1@BW+{j<_ajxA6HAu=9taDPg5_0wJ(8hmq+WGW6eW!jjzHkSD!?R-C$Z(u zNa-=^osaTaWW#Vj`q4&s3SB}{36Y^H!%5;4nEmy_d@P0(TPC3r<4%B6LwVYS+IHGkoac}4nJMpyChF>f#re~8n7z55?V8X+PZB2kkOH$41T+};L zBX09kmTp;cEII7viUF&Ae@wk-7l+--@*7>UlD70*`t*r;5H_|_33Eu>bRxXxP4nx* zN0h!X(1R1m>I!Yg-zq}4-fOO?X%PMo9H_0 z${7T$YZSE>?qW6siLvT(g07|6Sr7H!>@8A05yrW1*l<$zYmfPfIT=U7b23{!>qp^nQ0d{EJ76+fXrbn z{NE7vI+@7C@E&6FpiK8iOSjls4KclQ=ay@XK@wQOfoF*ay$4PqN+U;!^b1Ir0br-S z@J?WV2*YAC|KJ*f*tSw7N6Ul6flLluDMETQWg_#NfR|vzId@^ZRj(R@X6GVTZSXfP8r^J! zt#3kNjD=eF_HIn2h1ey%SpF~X!1^P}M=ksU>TdW0(Y+UYEcPnpX>iB;?W?0cAN){} zx&wHqJa6atyZ(A2nXmZiEvPuv=LCZ2jNH+J<3@Z7$=QBboq?eFN8YWr+J8 zJ`%I|8Ow2SOc#w)}mo9g&NZsknIBPG+k&U5Dd{_`Flb!I)sXei`VqtkT^ov^ClK-J1>H7 zkf3H4TB#(|+P?$3VqCf;R<+Mej9SJOXm}TJ_c1U}pkq*NBDh-czj0W0gv6GdZ4uuO zTe(dJp=u~SHq`soda%O?Jq(0RuAyHM&#hH~N|>*Y*ow=#JbL4a=+5I~M50K8{ZZPCCI1oYjUgp#C5rNEN#%bRknB7b@G^Ld<)ib!!xpOW8gO z*1P{$o~7*3981%r=LbK|X^t;t3d^4ReacD~9iFTPUayGvn7-|h1lu+uG>Zq0wcItM zvV#h>Aw6u00_tDN_O#Nup{;Baw2qB1%9J)}v(C+x?0+BXz?pFiA2!EFXPZNIp@>-r z09pm--fOt;W43Er&Vp75zBiUWET#rexK0WGWU)XH)g_PR(mNmz5mV6;-x#D%unsM} zL(=F<-Z4`gv`&p$G(=3F6gzft=rh134b*}mctmQ?UtyvvbRM8q3*To& z(|hGiUhQ(G8ogY^d_n3Kn z=E3I~?y8)m0`Ya&=uJG;bg_-Y(ZL1B`P}>`!p7eZ6-AkDxs{7@8xxp$4Ekiba|_VBgEEp}&N0t1 zJ>tWQNEi!tP`noVHLLQ?tEK-ruR)9lTd;k;Kp8X^_yU^>B`(4_y<@z{vUuDoN#cpl z^XkykeV!b3gPFJ8H7nK8dmabRvI0Bw;fG=VjnHs0%s+_}*sOOjjMwP$YUSyp#}1re zX<(5|BohK>S{akL$XX2=f0>pW1Y!M8DyUykjr*IZv9#5BLe8=2@@ z2!XsFZ4{y!O|i8QM4r|Q%=#%JOpFFQYYNrs?5PWz%7lnC2*x!(2C?3xRD&(mOvVo! z7}J;ppV%$-94qVFT@U#%G2j6*x?OXxO(6Fto3IY#^~(25_?7%iJV-}wJp%qZ`<~7m z{u(`d^EfqM<>yIn>BPX-XLc5;Jh%cv>CwA2 zL#B%IJo`8fIF47NKI8-^ut!4kVNJbYg&7`(Ja`qRUu#ter39~SEqquRUh=Tti? zrsh{LabKyat`L*gR&CNzZ`}IeyaIXj%g|naZO5R{1nlX&l3+S4oHzjaz0bXwfM|-j zc_dFZMv%Rjl41w zhZ{YScRMe%dS6~#oe}fkk2g0u?z#V|`)&5g+hrJ#+ftZKI-B?C%rbP28o+;sv~{P} zEracqp$lu9V>>mny=JxUyIJqT#Ga*Mi#(sDtaVtlmi~neA-h1~nwR?v(WbUT$ng*j z>v9DI)8+6F1ZWP(wmro1p^IFUqS9Y1u_mqVuP`x%w?2bdw}6SNm>V|hNkEm| zu(~e!M&|gyZ*lq$v-f_( zciRwWc8xvLn9ih_ZWp;UGso8w#TE5)&B4oy^St|XHictmV6yl5%d7K;C%0>nwDj`5 zuflo@<;+3skp@1XeP+34`f*j@*@ipBcp+`v%z#_=HqN|n?z;K5ugmXeTf9w01-yL4*eT9*J_+Vq?|08kqQILhD}srI_0$oh3)xyn3Mz!pJCZmh^Smq|356sIEDRny6S3;ARXC6&}g@BWPCN#d!96QDGtKf9pgN$#e z{w)N&3;_-gm{!9;a4ih@>4=>Ge2BL^s8E717DpDXK5`TEi>PXe$78Jr^}17;*xoQN z)}Dwofe#hJM*3B$aBS2K#z;~g>3adNH z`av(!p%#+2PisPZ5W@`xoZ~hf1gL5ljm+xqd*k##v+&r=&d*;LmgyXgnuVwOJTy5r z;8a7*o;YlI@z9|(OA>zcOxx=*+_N)FuPb+7C;l4y4S#;;I7C2mMhS`Ob*1aLU!4!Ky9N^R&>6|;@l{kV9 zB}fxchD}!AUpM5a0#8JpEm=9X>{C5w&#>^ zc`q_tp!3Y;tc!&u)^hw}^szUEHeDR~d>}{#51)kw8NP;swEKiEv_hyJ6q+>x^z9Ce-OTB)2IJnjA-{NG=B7-&a=>Ybhe2f^!$I~B71I zml3-SS0EOplFX8)PE$hguAP&mhn&@up9A3)t6HT8L7LN*uD6fjG?&SU6{3tn7QgET zw)Q6pRQRt1f}Lj;bV+D%Ofbm&3NO$3I_c8Baqb=C2UGQ*#Hpkw^Wt~wiBIltfA+WX$*bCm944Xg zsD*E;Rl;41umZtFYVHo0X#V7)WW#Pbf zlQA!zVn5RA9(n4$1uL;<`Sb}L_=I{z9zqvx#i~{c3Y!@!JBt}0LLlDzljR53`@4>W z8b)oK0}y3Oj8XLGkzS3kTGgTKzaLUQUC7R)7VU{ag>l#U-Zs6}&dS{kAL*$>&m z;XOq|v$JNdF4xf|L#x5iJLTq{Ja2gScuzh)gp}K~e{^Q&Ar(jMY}E7~Z8#UNX5!IK zNd`1ZZN&=s-uJ{jFH|r)6X1NnF})$LVSGXxTVpD&$Amdg5o@}9H^+FNb2jUVzvLc9 zES@r;P1J<_3E|1F_gKu!Z<_fgedN6^m5o7Jk z*z#@GrZn&F(S&`W+if?2sl$r@mv`=Uv>_Do@4>fhc($nN%eVjR$^@gj;%%=bc}tE& z2^xJy=U2>ZczwTf`Nc~6ZJVDh+(4yj$5BLTWJ%+^9Z}co?BV zv2Jy_Zm*il)WY3DE8NJX7XmoM68NQT`~3IA0|}M|B)CQ1>K2VTZ^n)FPx^VTV?3mqgd%%9||!`&BX1`k1U)p^UWd z!f4Ebn#AeMs)WYTKGQtL-LP`nqYrdWS^B-nWJ9NlqV>ejNY3xTn|W+-=^|rt$ju zzsM82R!J6xJ~5HvUo#OEX&sV(KxBZvRq)Jv<4ucbf zR0+;2{=n<@LzT8~I*uJa@aDv+tF~{u&Obl!_Vk~>e!e~CNTX}drl3Da&Y5>{du;P( z`gWOa$QzZq+#1Z1S$3#&PeSwQt;nlS4Oyr;+O$fCbP^b+boTW>a^Sx2ZDkN@VfcybEv^@Qlul+vRR$$h^09j&#k&x2LD)K6Z)kKhY(5EdC_ z0KzF>(}D}?&}ij>0wG)ZqO(l9ab$U!wtTXaG4|ojuCh^tA%mgC6$<9Q`cQJBb@Dq) z|7rPrXJwfa(rW8J&!sbm{&xOpT`RBF!BLZonMZ2rmpB_!u zg-%ho^xgz4&%U^9ugS7@CLZo(1kL*^IGMa>m}T<>91_TB!N=0sgw=G`!=h|_s3yav za2k4XRE1BY>*q1Ai(RJaHal(H_VI9Rs4X7?V=!%>@!}$$lXjIq7(i$NSy1-0vd+#~i~FbMq-G^*1xe$chWdv{C0ePho}ll$$A zR74sbFuC_gY@rlpxT9ap#Fs;@RhoTE?vdBg=7~dnoDeTa4)j!|WMz9z5F42K_B5y<7rBLH&so$W@kl>LRd(4QKAKb!t z{Y`AH6qYS%wVR7BF1=aNu0if##JCLd#pWs_qS3{p-eITs=^`%_?f+Q1@2DjI_YL6e zE#TgYo7^kKjhob5nW>fG$dMy7Gc7BYGY5`OnpxpY&5G1ao47}2SXQPDOf9oT+sx$0 z_nhCKoC8PnJa``7_kF#t+51&~WSCwJA6CL+AiWN;M7d@s-3W@v)8pF}mjE{U_yMTo zEH$Kp1F;-FC-N`UQRR`1dHwI2A_4ue*sfFCcCH4WnLA^4+OOC#LDF~5gIKKX=%Q1P(<*{XN7<%ch?aa8t9E%C3_ zC4ThXodm+sd%7m1T2YS{eVfupU>9HT!+Z`slN9dE8H1nb*T8?x_X|$gI(=Pm zSjVV#>U>6Td$w@`)30{aKeN~K#N}A!(U>QJz4@g+pGxiGUVL`$>AjcHh9dbcmxTXe zkL!K0-`=%n`B&B`wdYIi^A~X&p#Wf*ygPPCP%J(~Z&Z1#l&6#>c;_s>G05myRczvQ zW6Xt^J1eZtk(g!Gw=4mhbYQ?Ia9cdr^n#*r`WOC@Uv zX)ysk%1^JwZO;yL*dKltcH>57ilfG+AbxI+~=s?NErfmpi*?}P5CzWRFFw#avHkNc@8 z+!+rKY(?JUKJl$*D;79DGLpv9-1Dqo;}@)@A9q4m6+7uakDJj+NxyJ?4rWg_`xQ9i zf*Az-=a=?q=y;l|SkdvrA6GQjOYf-{$ocC5TJdOt&kz=;)#1I3$6j} z{QEi?jhgE3x4D!ITwRAg6Gf|xD|uOFY31qHG(fA@z|8HXX-Nl#fZH`JAeNUOH8b*9 znV9{|uK1g31_&E%KAg1&`@QzH`j>3n&j->WKueDmNO0gl$-kEtDgwg$191;H|M?`L zaC_dDS8psyP5p2cQ_+K>k+*02(HFnFsS9TZ6m=i`x)xVQE=U;F+yr1P=?e*)W+v52bk}s7_ zuRA-h!lJp7v_EXJ@gaZs8h!E)e>v!dWQ2qp$36_oDE?-O2U`i+BEiLP4lLA0Y5rnp z{;0=$Xes+kc88+SD;+=LzO=WefHi~|K2U)#TM)%0M|d{{I7@ z0r{bARws(^!%Udiw8?R-40Bv4nsM)mCcwu8*F?y(on_DjDn5pOq0?+a4ce*(<%XtR zkOZCLEmn*VzO>;gOSZ?iah^}LKnDij9F=$!WZ3-$%orAExos&V8J;^0KZixI2~KS8 z@|E_NIR}wlL8{d}q!AVQO9D%o;I<}!fOZ2& zPY@s{+Cda*sxCs>OOkBhgIk44`dSb_F4&I%!5?U{CunUagKZj5Zz3-!e1kgjLF5UL zqcCG=3pjlOvI4qrfDXOQM|*Lle_Sh60m4yeF6We$z2xOay8F0b$43a2en==EB$f$A zc5=bL5}_)t$S{C{emzR@5sU)hZMI4FHgF&L-~>x3XY}tLa=wkFh9peLd51nyvB&KZ ztUcJ+k8lwir5GUt_dv=dN}Dczd!1bVu!o>L1vG1%dOt9@B}<_E_Z09K9iw8Bhwbbos}XG*yF2OU6~CmC!~l3XRtq;f#O{hhX*ul~5pV5};1*M@tCX zUtFo%T(F3We(R0wV5m)!l}dqGBChOhp_?BU<6oI?T941<%Vsh_b3$4AyPz;3&T&Du zn2&YTLYMMoRifY`zN~~Cp#t$OW3nIl2(<;=Q7V3ZR2Hzn5-%~N4-~;p6I2d-SE6+h zouZ(0p$tCC%m$2bj*{WLb37u%J1$_c3$meHDam|gf~oph2!8Ph)1c))84nQ&W#_2Q z2jgY*qa6OVNH=xqI%>t7NZVS*b?;-VJ4PAoVnB4%L>0y=@yX=JVDf_X_V4m+hC+J3azm8NhD6~cTqq_hDY+|E^{Xf` z)FgVU{(g8XRh{QSxgD!dBrDYbRm2bmG@1(My80Tv4G3bW0$e4it9;msyg*B)qhF!5 zUQ*QKTXzs5A!hXt%Zx=yvAut9%Awd=9#4gMo-4$ep^EKCu;U?)3{@o{s$oGE;)-61 zl9?3Zdl{e_SLHfay!KA?m2t5Cf}$=L_CM5=u0~~`v>D1+APTY*UrJEH)_aFCB&Bm9 ziUvBF{R(vq>8BElb^$A>moBAC^BAC&ohDBi3ROTkNxGw$Z{A7(IWzPpxDi7E6ob>z z)vFKQB+owG9`h^(UDq9RT`tx=H1_gW#PCdPK$TgASziapv;xM2LSg1$UFA~Gx~8EK>W;M zy=0(O&p4!$tjJx!_SS>ds1g$y;>9XrR zc0bTds07ghY12(7g~Smcirb(2@oLI-f_V=^GGmb_tmu$|Xb{*k*;Yw14laFy@Zv}P zwm=^s>l>ZUKC2ijG6LfPjvK{C+Y}LA0Wsd8$8J1>-jmyZPci3DJ5td@?kyE5KH%pT z_v<3bb+=MfC{t_u2rx1}Rx_$-hx0OJgB~z84(Z|QF|}msJRC+{y+&L^bKfCPXnFF6 zcA#c4q^OVr#;y&jJ9ocoq$@gy4=+BVYV3tC{=VtQ_5Dot%y7jgGt{*gb{yDoHWYw! zTS8(EONTL`2MCI@-io>6>VHNYOJ!23swNS zl~D_aqqARyl`0;sXMLK3pc{17%P7<`qqzo$jxu0)qwP9p%=%ANUL|%&Qd+EbyeKGv zoA>Z5x*5|PPJbF}gdQ}}pkPiY;t#jzc)|u`a8z%W=QzaYD>@3kKbVUPAm{N%Q;a$Fif6B>&vA(B4LZ9! zy9^uc<~q$(UB`Zav*?iZ^4IoT6r5Op0xdd4cCb_et`mT{T-&n64^|i5jKk}^x(W@Y znqAoivl+Y~5lJ^cKx)azDk1G{9&`iV8fqPuO}L&I(G%-%wF`haF&m`zrF|Z^X($a% z<|37#dtl|D-Cx`L^{&i+Q4_zcMMaHXi9d=zQvibFF@Maip1Yd9B7oi%i6ZoQU3APR z+=kNpy~WvUXk@3sS-#oLP7Brktw(cWI`HX29EyQCo#*Cuiyciymewn*Tmxs;OCP1f zBq>8{I;2(zAL1ba*HP&WRA-1_IN=owB% zZoa#iOh8lXF?A2otiM5>LioU*2TnlvtUFAlU%HqJyljS!;3KprV1D=SCUWf2u7h2yN^Wu-TBR%|3LN4Fx<&Pmc#?i*c*QVcHJ!kyKj2aNTDTJvlyd&0G zc~Iq_GNh}FK%H!5uJ<9Jt5TS*3Ku8`VJJt(`u{zwRu_fyBRheNAQOCVM=eMQ7orBw zzs^??(LoB5Xb0fge~dzBU5|zZM8|Om?VM)^6p&2)bK3U9#i?4((SdUD$zH z*GXQ$&ep%UzM!NHRzZdE&ePS7<{GgVu+(~K@&bNIOG#J;$@wRnN!YFrM0L0-3p|we z>{X43R(o0>Nd@oOtLI>_fVU<yeID5$P@8M z5pu3xE`qN3gQ3V4wx4%@eClq06CD{Hr6lCX;P%X1cojQtJ^xDxAuP#|&-P;E)azW4 zgkg}RRFPKyEXox!<{BcwyFUX|xUTX0qSVvn)w$Hvk7f2B+)iANf{z3ko^geAHcJz^ z(qpeaj!FP#y5#ggX+UEE`dWDe`021hzW#N{`2fUy+t z6(RAink)6lXrN}EE3%_q^6()RVOv9$R1}Dt0fbuf=WaZ1KMNsixMz%4KbVh4SDevl z-%%G8i|V0^qFAG41otAfZJkZymBbzGd&WDP?^m10Ow_&q+Rwn~8Wp7dh#4%iJ877u zo7R{+-RQL|FncR@8l|dGbw{R0QXXY6K}E{QrIc9hFCJm27_>f6Np{$?G`7$H<66c& zH7V-R$uE|t*A&i5KX_c~KJ8)7I$Yp$W*ak6{gRLE2W^*`+e}Y`6*flI7H~bh94f#@ zU8+I8(LMM8o0|DFc)19T#-3A|iGz3ZyjwDafi|fJy8Za8t0~?6HEXi(d)7tkB zuOHsKCl&)FoBDK!LV}Qi&~N3^9h0xUQg8{OReH;trxgNA3)}{*4MNBRt}d-zWzN+f zExcu+CTadg@f*{ATaICLiii(}zKxn+_Gnrxb^NuW;~M?r(S%-bhRi7?l{AmX6@E7F zmns9jw&+#bELaCa;|bqJrQ+oV+@U1t|1O|S*@6+$)xdH$w5oMF#@PEKZBjQ5(det1 zpI|Yra?>0o_WDna09c@CY8}{eS@`##B5c8rIUG9WGW*_iD&B9Z-VZN0cML z_puKA&H{yjjp$L`lUJlMR&hh*K`EOWksH>m#++$6U%U#pH|pRajN_L6Y&&-;VY;AG zpF?LNLlBh)7n#Q2hPe4^gYGC|4&k+dgK@fFl;l>_(_+P3(lX4Gv{RXv1d6t)z8E$b zAmtZuz$gpd38qxx2v6gfK}X=MZpsYxH4|ei$syytjlT}b*{)I9vZ;X#xn>CdzIAqY zB`Y6h@fGg;w{AzNy>Lhi>bjlq=7IIHT<5UegSyA1I*+?6{Tz;Q*A@jHit5vP)qn-c z7BhqA(^Y}qCO>CFcHN2nPj4rH5hyRFCpOotKWT?zx5(`uMCoKu**Ie%{TIq2O8~}d zu?4PDW<0)|l=zkKw^Zgof;+;fd%HW@Mj+~!%E%XhUvIsg0!HV;Z@J-|NY1|z))jQWeq*|=-(?Ej!m1anNJzEA*sYq5rRlOh#!2GB$< zJ{f*HpX!G4crF-3Xw%cZq1S!*pJ4hmz*Ast<8NpzsZQW_&qmjOa2ox|=30X9pKQSWNJ4fsFmnSgrLzkF}onS}y>KX(Lld{B8} z8tYL2RJ%ilkc6Txaaaauo0o4rYUdc+YUqv3<(ffPn{U>ao{REGll9mb=Jh&907&H+ z`B~n;1x3G7sP~yVTn-hYkU>3eyy7b7aKkzLCB4v^$B=$h?R-x;7xKrB0iXDOOQWOg zR03qSBUR9+BH+W{-;aI+PyqMH8N&BiYh$|;AZkhsn7CF=bw8Qn*z&M|NYT`~L}6(_ z9v-yh1*|Vs-~C20gPo|1QA;6jQ=Qd2?#y+SY6=6tYNl@YT8O?^+^Ny{;wp69S0h*< zn4D=_0HG3guW9Ia*p+z`umJCLAvi)aS8qX4jrF^C_m{eDk^?_lH zis?cnDRH7fu9BDWUEV-?ZKZc`4cJU5D2(I^5*>;!I=dy-t!h!t)K?l$mq@hcuBc1H1lcM8BcP7*vnE@F@m}M~_RrSSQ9YWcGR=TwQbb*fAfNY3B zcK?K^&{z$Kzd(2Q2~T8Na>4T9t&AWV;M5U`kjx{wBlxO7S9Le2S*t6ecRo;LNxhxl zddXk{kh_X%fE*Zi{hTaf?&#^4E#VF*A0QOC^9GMDNmj~=g@x`y$?7kGg{-&%a?D|( zvdrC7Cxn<(-H)>QR997fMuANZNO~*XLcWxYwW7`vy+vY3MVk;wR;!mj&#&B9`~smv zW~pYGGthywWeH4y^Oj%+h*O}!2I{0&8W8EhL&vGP9jScKb^iBc{J$UHI#m{djw{os zvSG=0^_>*iA#OnZ@~>&m=W?am(|8qy-;Zjhx*f}mD(pyZm;wq*$C4n&d6R#+IU25` z@srs~)KNJ>f*1>RFxNU76$ZwJ4F%H3bcBvdL>Am2Hn~bteTE9B!VlBPE$TTS^@uDt zYZVKoS5AP^q;N#z=riDFuR(050>iZGtCT-?QNH--us!4}u;;B19n1sDPEbMnsb^&; zd)@CY%P2-5SPGX4Mzm5NU{JaTC7b}vS`3Mj+V7~PG({gUtFgcycOS$}AYir|fTEa{ zT$MQU3A8;Om1_J3F$eIJbo5~TyMg!@c*Y&Y&30q+vyim#+;iA#Xjcw>x9RMFj6Z>G zCbvxVU1K6jgFaZV+;|vRc5~+7pLf7iK#j|Na9&0r)~iS-bVEtA z!&*;yB?dGwO34POf$|3q1X5*qT!0<(E6P!_C-(B!pdnc+X{hjIeq z_?lrE^007^@RXT@gx$XURm|QsJFqZ|XP|rt1*h-5L4H}wMUa3fR59yE5=Q~bT*%+k zJ@Wg}QxM8J2V~{9fwjOflqy_6dMnL`uL_5>1Eqnghy_S{_Q3GyS9MGyq2((GG0N2^ za;eY1nI6GoPVzv8Wc?k#>3AguI{5HCh@UN=Y$uYg-pSNg^Ez;pIZiReIW$0pvUndqT)6C*(-D6|Mas z2Qu`75YyP8P-}pZ6T&~xr6PDRhgp@YTxbeFN}Ff8y(O24M+O7g{RH+$AzY6OYI*FS zmIs#RiY2m|RGbk0jRrB$!#r1H&zob(W0*t+D3FhN@f)Rn1kNO58@1#EsAxJFC^62i z15opL%sc_q$H%Nro4mBe;x1w`1~582@GarKslfasA$$>l$bcat2)O_0Yjo^Q0!Yaw z&WH|f&T#zTPRY>$MM%8l;k$F&zShIa^bro50+4 z1ianc(m)`qGN!qe26;LNdj1oX=mkCG4vjMhr3hf&G{|+uoDd#30)Y6lAL10a^Eou$ zOwxZug|sehBLht00%5b|&=4NzhyeCpa<9ZIO>u`xDVIsk1|(r#5>+hc$Ord*FURR& zxPqYDz+A6Vf)2ZsxG`cNV9)3APT?0z07#!LT;JGfhJ8=q2X z@&|@8fAOpJNVzr|!R}4C+AFoGqd>ITY5g_sb5Ou2a zzhF-rGUc{x<)=K5n;!UWV@!4ooQd}wch}#e>yldKxs~Jmuh-*%R<%g^LZElGK~!~i z_Jx_=>JxnzHu@5kb!3!jATk-GOsI>42L4UUph$avc+5Tdor_!7jBMh{pz0Nl)%}ckgnrltC z=oV@2n`@4ZXo;Hx$<@fzL*a)6Evf4*G!^m1bo+}L5f?L$Ud*b!c=YDQgDUVZGfjai zt;|(j`X8V#4M`|OnDU$BQPr{EPM4^(Rj6D@jHrfLz|%NwwKv=9=Gy8eE^<}c8|>Q~ zj>7m`TU%?}t${URZxFUTU;$qrVc*srajEC%rJj(spNaVMMQvwLa0!2Sey*)4qGRM} zN8^EZ2(Yz%u45`fhCU9qr6Yp*;A$>p*KcO;&C4(5F2C|2+$?Im-QLz;)HYDtRxLyv z0>G11;2+nod@SntW`A|8wk<^kez3h`H^1ZI+|_>*CH4!MnjF1&4lwH5WyDz?YX0)V zda+v+&)womn#5lObQI8#i4twuTr72))BIo=agx)VdIXtEzxv~7C-Kt7W7Ou8)MkB4 z`1-`vP5Z94i4qks5YGYP`2ahIOFtiL?z3-!bv6KGx*^)#eT@x3W_R_L`t6sx!2{iB zhwHs6SMX%eJ{|-|b&lMHKRbcGE#aK;2jYcNujq(70BnOfW|?Ps(bH-*uyc#UjSQoU zUk_YOQR(t=>&p3iHCRPPUgU0X^%?z)B9vR(bFTc-*)E zQ$X!Jta^9LE%?$c_(>i-n{xy56>2$uH1P8NAH3EU-gTR9$ z4k=@fFS3DpG_V?{SFOh^<|m0KkX*?-y#VNLGL#;OsZks_w+PfEheVnq(|bX_?0Y+x zL531=mkTjAACw<)%;y(ckU@%6XN?7riez1#270jtY|RJ0UG&kVpU!?_wmW>s!D%}+ zA$VtpI7k;S`6q!X?}caaK{3DL?%f)#^r^%X0_!QzoljZ z{U8u)U5R?|*TObk>X`t2%J^=bpCo77!LNm_wYz?pzx(Cb#2kW0=0U4@klg?|9Q~fI z5R~CA)k=k@(6QV=m`<~DxBz%elJ#wd2*}vyM=&Ma?DK-1^bptw9%?@wTq;t%K*PvU zV@;n%Nf^3Iv>45v*z@K{V>(=RB(f?!vgJ3D&NVj$gsko{{KiLEjevgTqUN~J?FyhJ zKWL^1St0;GbyXzyfG&MQW-Wmv5$$QbU27Cvg94L`tkz(4DgU( z7(wWeC)_tBNcd;e&5wes1o^7~DFM}Kf(-K-vX?f%Oi-nYg-HUTvoR0)fu1U9K70c} zbiM^l@G&z41bawv#T+|C!1e>AS_#;TOzb5Ijw(Xkj+3fcLrsyfr}#V0#iP-`lOseR z-#xG|JgEr+XqpO3vq&2tVBX-70ugFngwi_>AEk?>@;T0?B48yKt-}LN3ri)3+fxM4 z47L2}{(=dBR54Ymk0&*HgEc^vGR*`pdrM^D)T{ak{Eb*p{=?-5&-(kHqkbZ}cu)u+ zS&N6Jn}bGYA8$A{X7pJ!2teI>(3E2{G7c9%PqciUxUxEF7Qz3++2Ngh|81LO{N#b zccACUATkZ?5-8ktOo-R`(22b$lRBYr;={>5H#EzECT}FXHcG?#hzZ_~D|%VX&rc*R zBSwh<FJL|{uI zNW>|Gq~*FCznpIgx**Drqr*dpMn=L(yaA|(kBOiboZzCFRP>pR};m71cxeSM;;I13)o3ls39xMVbw zj&20z$_XAw3)Lj+w-t(@_V87=gN^@5_|5AOf;Hw22eV4Ux^c!J_R3z8yqaz#ub6x1cy6cfY`B+EXik;RPKPUJOP1v3q0)t!TWi!UU-8*(Y~=lkRz=u zEgF`|^LX!B;luN`2s~!;{+DWY-0xXR&HjY$g@HJcg0z#<}DzM8IxWmme=&sy%TDd|lLSJbLjV zS|ymv^Z&W}dOS2>AzZw9CU1dh=aK7hU)C7B-;cu4j^Db`3Yc!ll~T2g710-Tq6(3Q z=`Uz$jl)tZ&N+hKsK&fPn~3093d3!Sa}h(tlmks|k!^PB=L9k{C; zk%EcUVrk#6GEHAHC%StUp4*x*wvyf8Su9I|-_6nzL0wh6T6H~r1bG4SrXgcAMuSH{ zUBG?>d&S)gqmXh}rI<0peWmJ>!)FJ5gUhRJO}^dQznFk!l&HJpsfokC#ZLTZvTvj= z{CnKgIj55_^*O6D69fO`KS2xRJjvTvqpKhL36t5Ke6X9o^aFDZUwjkR`8 zRV-|g4xep@$)?n_LRo&+7A__J>>yXBUxwD8!XA%n&<=>D@5LMba;LZ|T?2-f1}!tL z!A1|PXt^r%HZTZ(X#543at=qJ-9)rcz67q)$Q`Ldgvjx+P+m!=YjQ1NKDGD zxzu?R?DFR!s{p6pGnIDlxRqEZSGZnxpgYdfI>`0OsmC`_J(4w8g6XByxISS!PSBGtOr`#~O3>x&_hq#z00*-Qh}bY zb8RED-!&fz^tyIm2-Y(lXRsYNv*=s>G%uBd!k&gV4X9`%VCr$_!ypPMK#H7kr+{A%{)z{{hf`nQt19@>0~ z{AEKKESJq9#$pi>syv5yOX=GjyfOvw77HrCWb!NUv83)2TMyq zN;|w1I7Psz(|f_e+rP0*S`wl7>Ezg_vWce5W@S7vw*;9G!k1Dc4N$G|aqs?8!J?2_>Dc zwy}Wo>8&c|J{#95?*8Yo5={{g!ds8C{w#estouSrEuy|Ot{Ws>Py^Oh z`wI6Ss>hd7nsw9|1~ktKgbqR~C9}>~cCAnUS%#?vRfY3F?5M8{_@l>9_S=5k^-573P z#T%WTxYlsU&dDGZd-1NDPoG?wKe{4;z1T%6*VX0!^@D9t6EB-w)k}%{toT8tiE<6s zJ_ULkx1^QWSvRUZAhApq3Aq?^D)PV$l9vwi`ejLSGwHsG=bpn}n|5@*pWpgYo|71fQTz)BGB} zdXtw=ZoP&c%-UM{3}p;dJBjx+@cEjbYOG~{0kW*@S6`Z_yQn4{^Rh&hW4wtyRqH#w z?J5?oD_fGQ*Mxe`o%qQ|D668rrC~i&>FM|rgj!xob#ltBDC|L{8&`q`6xN1W!F3D3 zpMSPVP#0{JxPYuQ3-C}L(JEGN4#*ft4=o+O6{GQc?Mik@fR&H5Ff=1t#a2MfaXpjg zB6xHvzEuzXo$e!l^jhJeS$A11)qNSIg+8V z8#A~Y`nc+Zezi?A^K8-y0UEbC^Bl^LLECuC9WhyiQ3`__>w8ov3)FTeJ%g;{%%HH|H#2-L}WyOtQ(e2+j{ib{HtF!b2CGt>$3`~&&9B;JI;H6mezmZ2D4zb zw_d8uCu7jZCZ})cIj0pl$h^251uzoh(cX2(!0$tCFF5{7tf+pmWZ<1WvGZfBOj$4?l;bA;g6M+RhHE&uB|`bJ*!y#2jTXG~UhJv+%{s&R!dpHqx@e*(;s;z`&q zKI!*-JNU>bWys8#st`xMxBl?ttM6BBA0V4}?5F785Si@1FAm>3X8lCnf$+>BeT)Wv zUngALCg$(@?_SPZ+t+^{=AZb{9Kgg`GhPox=KQ)|b`Iwb2+m#WH#|f5qwpgZb9NS@ z8a4oyBaRSpZGI|q3pRi1xXhZTM( zAxUEVf2Cgb%BuLWjI6L)S@d>E_?`kiPRs=tG&~*0%4As$&EM63;aodU*Aw@$^?TWN z2@LWXM>#rsKQ-5z2MHxWDUw+W9TFM_3+J2~>%9|Oknco&|GsLl$1t8HNSH@XxVZGx?3~$Pig_sKUrFl>Yxfa&27}2Tge{Z|g zSe8WL zO2~JkjwO;I-R%2`G{|^5+i1}XOvzX1IGB29HLeRizG%juzY1qVZo7ftEyw zFsk=F&BKi3LJ^MA))=9KcHIG{P|-ER&ION_ftE+j_D-7MBa^FMUi zN0!A3k|4~D>Sb>!QT3pLJh+cSiLP7zu?+t)^;V#_>hhxS;Gmj3YwlyKthUfS554Y4 z*7ch7DS5stkR2457R8d=*YCF0DpiszB@ZQ$wm?3yrMCM7k+uZQ2D0n!A^x%4@VQwl zdDlaxLTmDzRvv~(TuQFGRv_gBKR=2(eA}8{X61b`J!my*KzV;?%%FYvy#1B=X+}Bl zjFM5Kd13N#v?JLMur@@6T}#Ms;cCFQVrZk zM4l0I8M0g;kBL5_oEOYDZnQM7D;BuQ6$+xR^?7X7`G~sl3Q{7zQYH|j+w4F{!nN_o*VzU{|eiw zbtZjrr)2Wz!p+aFnE}!uk>+kOPwbL>p0*`DZCy6s-(`3QrF1T4Vq^t*N`OS#1GNZ> z^JDyc!tOs|n9oJ0hdBZ1^>@yXU8&;ksvHCMwJNM0E$*pAK;3Q?E$=>+5^x@AKp@rs zG0cVIp?f+5c6XMjKw7MXj+PW~=JvcWJovdZn5e@t!GlSBFU#2%cA^(n1hA!;JR-RM z;^DHCc{Cl@3)D}@8xNkA-#Pgv$ZaIquxQ8q2H|@MFl0+>m1<3C$Fg+( zA?hgg72>oI85()#aPj`^NJ(`3!_L#6ehP7=m~R7N$gS-r!!tutcNfSbDjogP`=b;z zUMihlP;OaJ=~+-6i8_$85WD2sDlgQ$qF;NTZil}>(gjb(QtwkDQE}1wV%UN~UbJB4 z)r`Gfcr<9ibwTdw8Cn{>U?)hJn}9F)}R{Z4ZyxV zsSpRkYFv42gcvjI+A(-b-t=z2;~pdT=RBuJE>*e^wvxuc*)Ldum-J*;AxAvfa&P*b!a$H3 zmTyf*ES)9XJFWCz!`#pPqmY%>(~7k^jNkbEILwv8JhTQC)cco_Pg^M@&EKdfK)pQ> zpN-I8Az$;q_3T)&8V9twvNF$lJ70&mb$4DLk+=|?P?1`!7v}oH$my;^^5_~v9^=Gz z{`j9w;utUK-sz(GAGg&6Nsj}IbDeJ;k-anTI5qG&;lRj;3h}06i-m(;80fhy>-P5Y z7fE|JX&+9%J$*Z3_4)bA@1E7x_}pxYmN$`|9BAf|@Y<<$%8tScA?U@{g%vK!VW4qlUbBb{N z{;A~k&uBf0{pJc3eZ*qzD$2kRO|nXL4MSPRfrZvC1Mqqbhj~?N=ivSb9{tFDE!s^dmF@ z7~>S0Jn{L&=Ke2Uhu!M!j`u+{r~n1GHxK7ok>os=72FOIOXlo-J1R4npBBCjvgGLL zaX7O0%x~MxcEdlo^|EpFC;kAC|Ghmy{I2Vc^&!M-tCK7eXS+tLfBZhC6NM!^klsu9 ztx3%FC-w%@(hl4MCV78USj+su{Pj>=33@VTBCQLSdjs4#kY331h@?IWp=YN5zHRAc zyd?udAVM-;42I?*Q zyW^ECiO9|(#{))NyrVQW(5(UKDUB`Xb^q#+`36tyZNu%8G~+m zz`hDl&=}pffF;hjj>1Fh1Hf`Ofep2fUB6NH`#Wzs9ea2D^*y#VrwF(9UW%^zlgSDxkj%g~LwIYuE(2a)(2EQ+@z=NTo=w{i zN9;HmkweSy+GeQVz%B?*Z}2>&s;bs(7qt55w5%;6bG>UpM%nwMPoeZr(U5YGug6}Q z#R3UhuKa6g?r}pQQKq?PkKxe$^0pEKHb(Y(d|9KfZ?qfD`eM9+-Z|6$zL0Cf$Q|b* z)|xy*ktOSfpZeG2DjMRrWxSD5 zGuiW~Q0G|qtebdCY#rIl$k(_Z?bXJ2h3($m-Pt6kf1J7#w)NEtLJj3Mq>Up){lOzo z5;}*JTf&G#YS;MXJ}S`=uK|tf6{TRUmZpAP57o#wh~Vun$nr?Lj2U)q!x8~?K09;9 zEuuOHFkKZNLLbv?+pq}TVvrJqQacw|i&73)=6cln;*lN(X<-v>N^Ta@D7@wp-q*lt zZ~B05shswNay32n$+q+7UGs=RsA*pV-PSBn*tww<;_m2f?UX%G1gNq=qSl=posFgvRm~m3#kcPs7z{LqKn>lS5H7 zl|vY{r(%sme62V>gw^Fe&|-0M=+N|g9nZthQbey$XdSBVhrj(VFEW1hnt|nglUo~> zlNR^u_MIe@8F*=>#qx6Th`5VFPP{pA7I}<#ZCEXr^ivXN*kDY{WI5HiqZ2dMJk`jP z({4p}1zWvU{MdIOYMR#5kCBPi<(X>nb@dq<215%7eD2KbfTr8qv~e|D)b-zL3DHn* zuXtSS<=1;oUhbJYA*L7T_>r;R5#Uei-fzf(8F_Lv^RFSV@ypyF3XzYulYEYymp%u4ZH5M6KcAE zub0IFx6wbj0vZQeE_Z8`@fMj|Cq3=uD4))fse$XWug2%#gR#d3)4XKYT+Zc7e4+mA zH#2&CpbU==+oQO@hpIf85Qp{+ggeWCa9JGJeSg0x!h&S;NyN!0HMv=s9myPPk72+4 z<38-y1x0X#%EI1}tv9DJKV!Lh%B=v1A$L&y8!z8^LkrI$4yn5VK(>ShwZI%>G-cT)mFgG;rNau!hz)kXH}7ntj{1 z$e#mr_!V4o9uuVAFE=uj5?k%2jM)P0QgARdD$z7=(ZjVqNJ;NHdn&5>mQpWNf1_Vx zoiwWai?2MjV#NBK6Ay#K@*NXI=(f<2h{MkoU zZ?~0iz0>A*&|azbZCkUAyq{loQH`le-kIXB@BJ7)O781FE*6O=+k&%EUKdy8T2&e9 z>j!EdwHW?aGgKA(>}Jp7D{Vx0y7dRY#hL~Z>dD#E<3@WPK>eY2eXX{S!JOY(6f3s4 zp%gq+9KlAjN4z?Cc}~XBvX^FuEi$>!NlY{r?b}ztg^o%&A zro6k!pQJ2ceh9qnIxR33dt$IB)r~W|F1`Geu6V0FWo7@M(W|d{wq1+T1K~@ad2ZD5 zszy(sE`3_k?^%!g`KcdwTgbBfLAJOn@0VO|Bm~N4T|7NwA`W9XgbFQt`)`|=vvrD1 zm!BTCddc&)YLUL39QKT<|G~7tLTNy{vUf<|*`jDiN3=|g`95EWS$2%^qO!yE?Zq=J zor(Nr_(pQKN!E}h!2%XK29jx_v-MUTPHi?&Tl3Gfvm1?~Z_D$)Up& zk(-@VVzKhQ)Ow`6^|1Ao>1X#UqK5yEqH~XD>i^^T+1dTRF>J2e%r%#}RBmaTYmx6r zl9ag>qDB&>+T2MRsSq_%sVF4rem0V%nv!m+xm3DoUBBvE`R(`r_IT`^oy+I*e!t$& z=f<5b^^>h}l&YG$=G~hypRe#2?QQSN-Px)WbH&+E_mZlpd+(lrZmEDWRBg1y5f=@i zB4$N|LzGT~10Cf~vk+#Hrez-yp2*#IX#_FyCG2AByXLw}52^ZJ(SM&7+;`QSjhO|L zGTPp+`FiQmwZHS*^XKe8#Ohvt+<$kz=W^7fkIQB4P;<+jp5?F_rXXY2Y%l!pgHT%V zQ=RyB1SdhApGZH7POP~>&;9Uj%el+XXLeplkNxu~=Y0@i`$oHKU)w(I_ z75cL$Gj>K%N?AMIhvG?Jakkr4$m{NR=WQ1kZ2DHTcc+_g5(Pe-RzG1YR1gzH`5BA$ zO@-|87&&@v*}i=Q&qtr>mfv4x9K3zy{o1*0DM=2~_4}@Vpg#Y3GXy~BgfoTSo6p83 z$kyA0iN_%(c+@bR#{FDqM!(WdFar{08=fM09PzA3uABa=y9??BUf z=6$ao=?|h?i$) zmv1Kn=TX#_?I5RJVM(iXvg^%l1h9{9&(|{Us`Jyj@+cbc6aNUNf{E3s`DXJ1PC(*# zkY#1Sj}>d@>@hD_TZy|+QV;ET-YYJ;Lix}h3K zG3KNSv=l<(6@bwNX9xSZbO~Il2fSnoyH_li1xH=H`%TyJFyEw}J^3O*lcWLpl)nYD71fHTLR{il=&+jo*M{jY)ZC)SsUWb0V0=S!S ztG7U3#X`Lxsw?@Rz!1)rDa{G$`G@t5I8W%!JneX?Q$OFi-p4K%GHb~uF*r^||c5#Xy|8q5n<;A@>>M6fgXjq~}%x*;q;*kvMLoA;g35DadJ~gwtTL+|PgY z9?t4+iyFUp-%h1{wU(R7H>2}0xxm6p(GWA#SO#N2e8a9~bD}EgvwFUebS&=6Zi@b^ zQ192jEslk)3+;AKToLPcc=`p=H_Eu}071)mtXYAL25>d|wJg(>e<$!zIA%}>zidTt zM|i}RRk2*%v`ZEnUmutF9X+<=kf;2aWit@${~}I*y_JV$g5~-r7Kx}afbn6-bc~0J zd>Pex0QtfsqV+)50RWeJoX`W2e@prsXaY{JO*&w*D(2G~2sNN{OJ4BwhQM*^@y(Lq zUG<^ctAJaCqL<@qmhBia-XS5%c<35n-8;)X%cSVqdQ>#z`X$cI&d2l{ADPW--P8Y? zaiVDF8snbGX&b8&{jooM=)rHm@3-_jqe=g%fzkBAxt-q?xjC@iKcoi1b$0aU!)rh< ziNZ`%81w-_uDOMdTviOh&vyB+nxzz`z_w@4Sy!nIGY{3LsL%k(9o8RLr~^JrPN+ky zGV>@jfvuWP$X499v93FQ5>`8gw1((YeCCTh<_}=o+UX>~^6=}Ehi7b#XnjC`ZRDs^ za*}PM{;9*49zQN@Y0`;aymQnnRa(r<+j+`5!htz2Qfcoo@tU+_Acs!SQhy;;MG?yb-02nofaM zc4O46J<$;Pby2H6$mq*ISEHyRHq6znJKcR?cg+e3Dm;l?zzdIhiAsW4FKigbtIslQ zFL$55d~L&J_Pb&S+pGFd?>t5BC&I!%qjpk01#zHJ(U94DuLNIfFpZmZ`y28 z4SjqCA?s|@G+>%Fe?h&Et_EZi;B41`gwecZXQIY(L^{g0gftIR)O}iJMuT#kKgKJSff#C#t4>aCgtIeGuNkJ z8Qa=46$YEDZgQ~-eWb~bP~#J|`bGus`aAgG)59N+l@RI2L70LJDcqa+208bz*04_} zpEER&f$%O7kd^_8S$4%NN{&+*7hi|{_%^I2N}<~@4MBP8e$zlD&_hMBW;BSbpJRK1ADI_nI>NG;GEf5V8T za8Y*UOUjC2eXgF-N7%}diNtj5V(#lL170V!V9q@H2Bpo26nb1@4g|;81{*W|FrOXJ z+f8@hfoUq5FfTh2msr~PE&qaQ_)uCslY9ctS)*gskyUhpa77a}EJ3SyvswL26T0c5 zeI||dbZax(zb~Hec)h+``+$fW8;0<$>+}wG)~!wN%DK5q+|f%@x-vmiHz}tav=8cC zq~RNUP`GO`#nXctrZV)yJd&ZG(e)VP{57WXwZSw&?@0QcaVOV*!oviTpj==sZ2Aq) zp+BW#6G;QDfBI<2XMjw|!07auK|b!k0Wu(^bV+okB&}TOs>3{8!a!SJo(Hp+(b8~a ztnX7AUq1VlK9qN&wv&Is!FKme+r33GN(FmH3&Q~I_bL}P!yPUN+!Od=eelyDI=#A= z+tTYQfpcCDIc;4VQzdh;N^!mLjrROVMWy63X88i$W?XO`+*ZEBU4BgZ%wZ#FR31U% z@fI+Z#`XCgT9T}!*ELnKc8!w!q0_wH$8$(Q_J8B?MXCS6pY=^?fm1llDNM#dQp*hg z$oFo`%xt^N^{FO~AC$(CQdV>CqVR7v1dv`Ma4%7~CupJ3{5cn~+O)O$l?4Gmg=vhm&6ty8@D`nl8-w* zzTIJhA%Rb>6}ZTF(_p4EQ-G{ax#bqOK*o2^2Ila;V=> z)|zTM@ZFcJwASz`7=jil)GHi9BZo|@LAO-Rw#{pEH{0(B$QcOUjLL=4cJ5B}PQ;HG zoUmXD97MjRPt2ojjWiNmCXbcb>r#MZPx0p`CEzoauJk)?s&lvXmGfQU!Oi?y4*`Bs zoe?d-sUcnYYVsKGIjP^;r!OU~4=?$W;;=2g-1*q@OMu@tJf<^NHIQ77*Q-ir2_NLeMY_F8)`9oz6w2rRIetWk9XnU zQp#h%W#7V|k8;{gg50}y6R_r(IRq2f`!F-E55ShtP9#TPhnfM+5>kl>ppr zH}&KFqnv1i6_BM954R1%&a&~30sOaELXQL$`HEg6rOG-*tr1D5Bw3~=Ne6hOmgA6P z|Is;i-@@M)F;|Wo^fS#b9lZe9xa>diNI!hdwv$1*qJk>}F57M%y>v;Qk^ci?Rcj?8 z0HPYkoaJHE9zG}f<88_fTVRG$US4ZV&z*j`FJIhca5YyZ?p_4IU5~Bnjoa4<^#(+- z=b7|XN)#?_*zyeA$T0cb3S*lh;s}q}4&bvBi8T`J$Va>|;YH$pVm5Dd*Ean{OD}7n z`?VgAIQ>Tt@o-lpb6Clju=6@`-22e`&>OlaZ0inOY9I5f=an~yPgwm5v+s`@9dSPV z$|vD!O3Jl34NZhVymohCCO)>h?LKMPDAEH+M^%?=HvB{u`f7^Q-6#I)rQun;zV*kgiBp#!d-BY4`Ir$N##rejEX)wJrR#Jkf5oU?rO?pPb%{F>YI5rCpmrbHMLk}yhTLqg<}n!Qu|6O z0|rYg7tV#GK33)RX{%&`<;L!y%E8{udq6%s(TA0}rux=|_Xjo_I7atCo19HjG5l|AzuOnw z^Sd8Ys?G5?7RE`+D=mVG4LDNfpyEp}QD1-2hvd!5{HmZ6!P>-jx1k^y;Cl zn_ga*q7A(3vp>J^>UMpuH1CxX4BavVDQDJxU&W>ctJ(`a|8NRUSIecQ} z^}{>1|NCkD=E0ZOJpa|Fcu$X9KeB7r+#HM`gkV@Z6$GaS3l&I4s*3-|R6KK?U^{zs zpZ?snnxhm{5j#B*Tz7g&41LjX>o2f>raw&>$ z`O_Ec<<+Rfgs5Q6dsye0R=W*XK50VHqPfyQ+ab{jy1h`yFGyO;2%re#R*jeZ1GrC6 z{uz{m)tt?ClO_J%tJ<`VBDdpvbVHr;3IC89oAwy~5XBnsmqxxTFgAKJzLfVER#>bb z?H0RdON|uV`%h=2&R*xgv&{r+OMU>wWgr%Y){ExGn}qZ``PBD*Py;wv-sA7ZP>^_gBt=GE9_`76OT3=20y2@*{bg&OPOHhQ+n>Z%3B&_~2K|^j5WZeUjrp@lH2PV^NQN!Gf!S0O2516 zO+(JilQ&1CD8mZJOP3w5qbozA-X5#n`1I|G$_j4&ob6-wUO}Ln=rzt`ivC!?Jk4kK zmbFhTYy5UneGQTh3oYsC`W@@`i}FI(8GA*_73lSsJ)qx| zLf6ng_5=5bupamDXa{`%-C?QU?wFd;O1lfTi$V?7{f7MMuXd!b+sa3z6I|4rayIaa zxlJ8;tsm6%)T2fVXPB6cLbdJ`rLQ?mBwZn!q&xi-Z*PcBewz_E|4L!#7aUI{pJGN4=h^in!hGTx@3tK zEWQG=oo8Xs2m8ydQnds7@Iq&8(B%ss7F8d4gCx{Q&wBBV+4BC_Xc;`lIgef+iJ0zh zEMMs>V5}4OFF4FBpOJ#Jt@3_MFt_SnGlbZx>esCwCoFCSX|Z*Eq=>kDeXSPix~BK7 z?ae(_zVYZZY{bM66O&XTG8)w6bJxBNPIC64tdHXpqlI}-r6A5zjW&e#0L|< zf8F*%v%HA|wCw59v@P#fzckd+Jcr?o7O9D;qEt+u#2$bYNH^gTm;Ts_!ucO!sfQwa z4=XAHzD~xoj8@$WIl!0vzK5-rU@S^NYK+>@{OW=Im1-v5;iGnKJdVc!6GdG;J`VH_ z;#|W+eXY@kST5VGxXP|StuAmG9WPEBh(L4?RJ*KA4>6DfxX0T5Y!Zg1huO#IU9=y` zaB}0BgBU$PhF@eHNAe7l>u@q`RjqxeiHtEjzg+7`LwpSt_&5?Xi6 z1g=`PsqVpC!;7Pd@LK8NDFCxDlC#=9OV3!Xt)sS3-ACK=3=^cd07%+)QdDeCAIAu| zO1!-Dy}2=8*zJ(dD3>9<=={;d$I^~LZik^-g3E>!xN_mc(<40LDxqH6N?}nPV|>(2 ztWT4-TcyMtJ4ManoPX91m!!m^yW0z~sq)DS3C}QN8}o@_%mU{zk;mVCVXJNo=8b&8ROCOMIJ*r%%TNIIBiwSoRr)r zD>NOJqi&Ao4dv|cjWaWP1J{?DWbM}*?yvorw)MY_ucQ4cwIO@&X&z=97iA_+fQQjD z8RJ6STIM#AIM9z3HC*a)Whilb5|S|>nRcybk+uh-+&uV2E|E!}*SCCo!@t+R_=EJ@ zcIKqizZT<5ej(Eq*XamnbBA;?Ro^_#Kveb&3ZKUCXTdE}gnzdv9scZW0 zmGdiGN3O!pp$cw>*lV-EogcGNwx7nkd-y@(ien}JR6RZhS$d}|yDH#% z4=oTlKUq=zG642p+o_Pr3z9?L6V#9}NFAyE+4J^KFyLri6hP0PpvQCa<^q@rd8h=y zk)A&rrbZ6ze&Qg07Ac3j+(oZd26(iiB1OoECd78=;ez&`mXj{o98?$=b-(m^c*T`K zAu~h-E`bov&?@V^0Oz{_agyJrle42`HYIye%71Q-&U~!bU|-tJ2-d+7rRKC-xZdec zL)QA)taW{A!@IGDUnB-~EPao0ayCmZjAc~Cryb`LJR41LEOJ~Uql#r3#$psHRD!eQ z|JuI=o-KDs!Js&MHaabs*{HclN0VU z|MM-toZ9-a+kDqdD!^O-&0&ZUy8baG}l?4S_g=lZ(#` zz&mB082fei0Vu8i$!D>@lZ8;y(` zO?(yPw$A&upUD3I%=;;(;GL)nXS*A7_mlP07c+ST<8j0ffO;1IkE8zO9^Y98)6Y_) zyLl+*N@Tx3gQpm*_Cqx@vvWUMe2_5MP#|d#Qw;@hdr_hp^{+dq4RY#T<|f+LQ<%G` z1Cmn-Gx94$=T&m5@%STuC8AtS?-Ice02psLQY^rBw*7IQL3iCXjS0oZsaJLI9OA(pn*wYKAZ&G-v3@6R@$kL+NJW#4>jODwkJ zeR@4(5ubryr$eH|8XnO3eul*ulp2hTYmW16&W;=Yl`}?IB>XrT$EQv3O?(^m24l$+ zD(Zc;?J?I5wVL3u>2qBFJeM@Pi(NriyLf|PR)(Lo73|p`TE(^6zScS;3#L`p>Gk+Y z!yt*$7g5i`iy{32mX0^fu%3@kO)~nM?8%oJZ=7P=l{45ZPwYGYlvrZBf@}=w_K)k? z4T|M3L!Lt4;Vng-8S1iP+bE18K8ei!K(}T}Qd0lZ0&$PG5+fulyz?7)vBsjgSiPr^ zE&^ucs^`>#qZLT=T49EAo_`X_D68;ltAd;|P?#Y{u=%D1<6+&gI%fjtnr}!CKwQp5 zbe_|i7L71CS_L1mR$)je-W+0KIKzxS`F|jup{NZJE$3=Eb;jk4&JD&je0)S4(hz1? z&Bs@;249>d_DglIjR#Gq8E8pzow|lQPhG9q;<-51IF*kO#p*<81wm@$HJ$-aQ7P<7 zST=emJafiF4tJBlBQjI^Fd7F1Ro|ZI5lc3XU2;f4l{GT%s&zbKNgjM{G{+{ti$Q7B zs~gveW9b()8hjC1p2$qGSQfPMQ&7i(4Od-*7s^3`z5T8^kjNKMwb@57C2{^Hw zpoQH9ZaDITrmw$6PYdd(7^l=tkq+DRBeViO$ACSxS%A?DkFKxC z^%MPfX64mt#X&i6Eu-M^ydQSUyJ#Jsok7L(Y=BSb}}oa`{r3s z)~ZL_6(nD~;Oe(@eU?qgz+Tw+JZnkxx;I5VvlQP{YFxr)@6!G0Ql0`2l>0!ZzaugH=So3)x^4# zxH_xJye?=>=1iut$z9@iF$=EoA&h(>SBp}QOskU`rSU5oEBIUec$6#{j?LFzKH9_9 za#?k&Svp-jgA@W~NRId$8e0=fB{dQZ8wsNlebK2^`?ev6)bt2G-jI)XYivSjZ|$ho zp*iNsMxFslij1m!ss+sg53O4OeSh_dQH8eLtt*Et>m5%$<1tbdq=5_6of@=vDV5GT z@kylv zfCEgAB3yO0Q9`Aao6JD;hP~9C3PO^?fGw>N$D%phvDvCFQY`w#Jw1P zll3o|%O^og;F_c8+8a-}19a`}>V(X^YdD#!m5dt;b4Y1+S3#`VJ%hcESv+%A-xC67`d%oZN z=)T1sD*s$C(%5EgbnluhI4@iKfyNl;Yj2Efq9gh$>-#IOAVe97He(9d?!F-70?+#1 zy+!6xS%WKoALWBh=dbj6)<8#mZd=uvqsBl}!#>YT{p)`>vH%#{X=F?XWU9|Kxw!>9 z-#gfZ9C&4aDkX8d1Qlmxs|j(mW1>P%!}XrS1=>X#(3j4$7~R_t9%tbtTI?f1_=ryV z%aFXW2j?GZN#_U;2qAzFA>4&4l&DT6O8sd@AaOFDyFx_0!K8@bacGCsJOnR# zj6-hFB2=IpWqK8E&P1@U!V`#ndpB`-g4Ho1wg7Um_CwaJd17YraM2`^Edj0Nb#~Ax zJ7~Cf#PK-_(f@B;KsFGcu6Z0-8;@!OF#O>n;P zCtfr&O*C$t+?KK9GRu1+-8^yS0YIS8)0erR{ zmZBa}7JXyBlW{(tk$513l6{*hRG4fK$2n5X^z82I4>EMmbMPsqM4@cKe6l2nv< z@UO-U0&SVg+DeAwcRuh@Pj`504b6R4ixC{r11qypAEJ--5m6&>JLsc@2<{!(YxWDKzGCq+U*P83yt*ni$J}r=#DV8W|GI)C z%z)?2FeXc2E5(2McKv=vUMTu(4^I9rJ!<%UnYD4UPY%be?%tnI3BS{Q{*@f_{Tg%V z-4S2dL?O?}F$&{l-R@U5M?-Gv>KSh;>?@sLPyH{(We-B#u=L=DMc3$!@47%3oK8M zwnbmw_6N71^>IhS?Yc#mR}4M0w`WI6hLMcXEmCj^yYYyzX1I;f%NHv)?yg-*Uh2g#tH3#AFl^alpCaDMDB>oBsZTM{o!*@Yremd}^-Gn*=BBMaN`l0v|->h-dPG0{Q8DJ#L`59+%Q0;nTU+GCo?DDFrF9BB3DD z3{xaE47Ao1(sjeB{;(C{>DpSPxczY2)ss>wk`XNfsoeU5FShAs!a$uhBCa$KCxP`M z=#T^^v#^c?(Z?)MK6Ckz3u;7CZ2r4fQmm<6pEa(+`(09iETl}i^uXG( zlS`{N4xT(}oBhjr8D`1U{UCFb=HVp=vbx>{I~G(|;jvHDf@AK`$f;$=GUi;VXPeLT z*|skt2BmiNo9<5ST=0iBBJ@jy)@*j^Vc%h%sSj&FZ)k7|xbR{peq+x>MbO5JuMh9u zct20~kI%7vt0 z^0XA2HF|QQ&!{HwJ`YKWWMM7o*2g5~xCO%q@``Gq((L>SCtvZZ6fPfo>PlnUqryfx zAGVQGRWh6*jD$U4Tu3cs)kId7JkS+Os*%10_mTRw)^P&d;-_JVGY3OMG0X_1d`IYlt#`LE1s6BS_h1z90B@P zW>+weS$jp%ZK_-dnIK9i(j_l!+>$|R6`@fAgakF!;tf;ZC=SL}VE^Xq%B)h5kJX35 z!qT1=2=MVk_XEhTW9ob=G@vY^?r2x|o2~t}3F}y{2(^QJYz9U7g8EN{!wYO=W$8f>bShjL9h-_^ z_JPi^_A6YWsCq@6= z>fxafGAtXz+mm27$<&7iwqu!;sIfg;-w8_}EMvl?C3z+;PWc!&jP}jNL(A_2e)R&~ zOF@00paUp|IR~4~LI{=2v&KT1zD=amia4Z>DNQCha_Zz28 zwcZ_2Zib$bRQYMNw2G-=ufCh(5t8v)4}1m#FzCuHi=8%eJ&0dfK?^UfF2ZsV!}(ejCUQ zi8QU_n&uk~f!fEw{iOG{LEj>b)xa6IZ|B!Y_B6$kcR#i|+*pPa0xVl90t}BsjXvO8 zHp#IonBQny#D1BUav*qGL?Qe)0X{`7DLs(BKaj^u#Pgi23Ysc5CGo@<36^cm)Ma9l z*UuTK5zFeEV5VCHz|-UK<#kD@#&#IqK_c;R7_{wv^@7pWyR@y|a?zQ(NC}|zlO=EDmA=UH zu`;eiUH=VZ|a!f$}oGKLlwQLBP)D{D%&H=Cq?2DXx+jsXL;^+9?HW~Am#?}daDV&by zl-b*jo3bB+0tgVa#Nn1}S0Uf#7xK%~GSrjqQT zNx1cocS*1|iSlTELAPH7*855$iG7g2YfUZ2Lm6hXHp6BX+L~v@ z%uEh^D~1u}@Hy}HFmyL8;>Xs6Dj0`JKi_BRxgU&g#|pW;y>H-K+2QVLcs#UNaK6l& z33m{KOWV<_)$kxWf2j=atl6fpF7FL2zmZgKMcvNpGhxUiO_ub_>-EkbK$Xad+chf> z0;C5j>>UmI4M2LOB3)JC)nZbi)s8nM6(8A=_a51gJp!#Jv^YO7`o6KL3O?2d3#|5b z%z#Dq0{SAu<1m=97>0!a6UZn^U@q+33urq|8K&`ZYyzW_A%c-9mavnqFn3Gi95$@f zG=Nog9JV|u3|5qBIt{BlG7Wn=Ts6}t{g3W#SnD0AsJytf3d}KmwSM0dnCt~rHfNm! zihXa)Hf$E6|%PqBYEJHMg;h^VhZ3fb%sxlXSQGr{j zww#L7-RO>5^v6iQgk;9~Oqec!S}f<7N)X;)8K-3a8yH+9gX;+lGSuLF#{M-;rDANu zuua2*B@G9bG{h;*4kel1Th;I&C-J#W!%F>1^^(KlpZlMWhvY6lJon&9ef-3Mmke)t zHs}tNz0lXFX-Hj7umtb~{f8T=pxZ6!M9 z2D6D?dg@rpsT12G*4oll6GsF1DO2}X?(*BP>)3{_AIC2k?l7%`^;x7QHKo<<*K*xh zDJPQk{XIOJmLVmW2nkRmMtv;U|7`im2TR)?rnEguIk^dYkOHMts6YW1y-NcG@DH}6 zoOx4r=4}*z(+&8&D#>Iz*cxT{?xKF0$MGD=*`H7C&$*+24xa77wHJMNNR5RVNmduC z*!pU*RFk%n=ZNRI>mAJ!nP+55R+n+G2K}(;yf%~f9cK8>k!>f%wWwV(9FK)66lcFW zb;kaErz8HHiQ>$?` z;k$OP@Y4~;an+)8XcI3Tj=OWQ4FGDBVHWBV4*`v_OC4#Jx?sOI+elnPk463eHFhJnot26~^9(zuYnJvMK&T zLk(lf zvf_b9vcaVHyW+jolL?tNqZlVY2ha&hPg5 z4{zv=)ftR|46in0f^x%9|A%?XbS!L_80#)cac^(1`v9iOa=b;@eUH#PxTv-5iyi87 zv}QeU%6g$1bF3ZVF2Nk

{EGbDNp+7w<4l!uhKYq_l}q?o3>XrmxX%@Py$F0~I0@ zh~f&dQu+2pr*G`Mk&?e3wH|7m8$26CL$8s*`PtM2Vg&*ffdSiG5{NrNVqK;2=c=n(qJx#u<1pMoyx(5D(nLl zA&f$fi6Chyv|8ZollGI3xWphWg0&s}j)D*45*}#Z8c^raaut?X8|np1k+@o|Lbpcm zT={wMIa_{J7`a}S+binqvO}E|-r1$X$H{WX0&k1Os9g|#@gdZ9Vcjhurb&%SkTu3Z z_#-Fo8!sK|Mje{#d}6;Ycj&>>s)^e}erY3B?}j2HV1@08Vl9Svo9VpzJ7ouRWZd`aQD-bec@Q0-lmmdtnLNwW-M4Ag2Wct;rF&qD!9ZBCTge2$W9abDL!Y{LY{$%q0$;E zl}}nIKaai2nc@vT)7ZRvbh2uudU>$n_3qU$elEC}Nq_tSbcaxLy{NMTs7_hVZ{6K> z2iK(nz5A=cF*af$6T#=dY*XQn0klXK!d;HgaoS)n28{>d|J|A16O#PrDr^ord*)gG z^QF!tseP>^Fewv;#(oT>82>DX; zWukqtO!Nzr}3dpMVSl5fj1vITZ?hv2rn zZ+=JMzV{9;U{X00T8RTyi^=u^&|w-FZ|Gae3}xBgnngo>6*J#s&icsCaGI(6RTG1- zZP*f7%4QjA^?L5}Ep9Pis)^k!HLFK*)C${FOZ+jE6Dp^+H?%N?Fy zCIzd~;V~kFKEP&4s*JI+YX?lc(OA1LWk4$Sy z5D8Vl6Q=U`N_Z)5*(q5I2uD%r9-NStCc%y3-PM`d8c5pv|EYSVP^Dp&(R52N4NNqm zGMGq9rRqqhi-=@O_y90!_qbCpFtw+0()S6G6E(E|bAB=Th^=ryR@qy)+t~K+CDm@h zjj@YXI`jUvHzG@QE2;k+kACtcaj16wrq^RnzOGj_`t7w`^YmNt$jKFF*EQ7MJTS0& zXM!7GU>8a<_0Apm6MOrU{hWAWh($t^(kGJ3_pv6eSIu)059G33-V7a>PUveMCY^Y4 zcye>o5%+!mgw1a2n~zwT-u$zD_VcTICt_ay-SK;%*!=q6%Y`7umf_1|bFgfh2{*7A zHZQzGP%PwO5W2yb0SLLw)!lC&&x7N;k6*&|^#!K~nssy^Qg}L);Au6eyPzaJ|9MK+ zXE-@HvO`C(Eto^477HcTc#@E#E1-oI$b8qye9=gn%7?n*43|^6&^Qy^7aRw?^+RCB zJ9I1#RU?Wh0y$jQY1fFk?tIGLoT;Bmu8@}7^L21Y= zTizs}4Df;9`cg)BQ>k0HH|<<7OSI|(*phWB^PqY9JPO&zU4cMN#EZ$`@4~Zc-M&YA|4gX< zeD3GE`pw5bz53fd>j=$5xhG0f;4m0!DK3ep1H)mOVLtUEQYj5pn@3)$PxsYpL)XIQ z25|Gn^Y_l1Rl(sq7Ks|+x^`SX+;CG@WsBZ=wRtrXQ`=O6& zN|sXFezr_jGYC}mo}01Ia6X=bNq~75{W!04Yl(`fdlyem!1+u=as*@gIA_z9#bjS8 z9uerf!H!E6ZB~BWX)g1ytYO|qWH0Wm)y{g8^&*`pCp?>k<>lez8uTY(x8N<6xS^9iOPSq-!Oz+ z3c+bm((2W-%1vq+np+fF9?v1s-*Ek1kAF_wkPvV5eAeHs|8wFx8eF{7QqG@RqPx_-xuoJm2m9XnqD|pxO2;U`@&7Q(9WiO^#SA7yaCVYTS4p~Ve-x}gBwFJml7pry34Z78Xl)Tnmp<^aOr>5mFKPiL zLZZE6gV1KdkoCm;0$nZ_9?V;a<|a#VkdU<~5_aj(L%Vg3QWz;y1h)xnTU2;R4`bI1 zEU1OH1l*1pvIS5+G8kg1$WKqgBYV$EP|lF(OWjt9*DQc5lI53)yRpGcKGtn_0WFmo z;5+9bxge^8In&sBf?1_m>j#DY-w}Fe3CkujT|miGp;OxnEOIsZMluoU9j}j3)lqyp z@2Kv(z<$@F;WAwP3RS*kW+QP&((UH`@#0W`en}{?Ln$dwPHnhF*q$7`KI*}t*RFAY z;L?>7KlWQ>Lurn@YCKN_KDertdZ}S}mBUi~!1*m^O4yArmLvb&z5{1|AFPbj)_vtB z2&P#2bf?8evyv*%?zE)NnwK3gZjXp4mxAGZ^v%N?k>wvh#;@eTR$PI)Hcv_^zVaLM z{p~-BH^8to0I~4!jK)o~FqXQyfBLyH!GbBpPOHz&zyEInOPxagofhd^3e6qi$w2%x zlyTyPKB5_-(Srf7k8qw>;;9ock0-smZV=-y{($L=f^}8sY)iJ<7!e~Me`#`{dfY_J z@M3o2dg{?Czr43QMVA`SG@--^pzUhL@oRrUtv9#;C(Cef0$4W8^eyzkJernefV-(e zn@vfGtc2c6f#T9+W)mgO8o^jPTpmOde9V#In?CN`dgaZUPpzS@t6k*aLc2$L`OKMI zcVVaF@zBq^*XK@}%w-P*to^cY<MT)l%y+l_VU$jr z-e#3)sl1sj{Cm9|q2b!W+Ob4?LJWs~ds+Hpiet*HZt5Yv9J%rB_~pAB7v`U)n)p?D zRD3zK{yEF!1>BT&3VixkHqu990UcMjSotK7aXER7gKzCcQr10W8A&DX0*o5-w*DL1>d>WaTgnK49j=k<_S>; zJ={LP*v6}BB1_yTobOt6a|hUvZgpq6>3o$!xBP_eB-k^$h6)#xUBR|_fXe97A6;b{ zz%`5Fsx*L?jka_?5|NslK}Q?$VZ-6WWi`4hXSnu@TsFbe!AsY%)r5bc^zR^Gt%@1I zQ>m`t_eh*xn#KzECAAjDrGQ~^(kmhn7TP9?o~!)+!{FKyBz>OK+a>wO8bxVD1jsK* z80vEm?x6R3oD08Go8=*#w>hh6wn5WPrg?qOOJd;zqF$x#V2$g-zc97L7S#i7iM=b_ zwBlUs^~gbaXq@-muk@dqH;L20M$IdKj$Mtew%b6}rWzEK3gmAR@A0DVefoXs?uQ%k zoj{H1bTn?3lnUQKK1YA|5?KnWyMh*S(|QMISCLz5iMmQ5xsz&jHnrI(Yk4PMm{qEi z^SmQf0@g$Frd=LuT?vMp*6K1*I4Y=WFU`5`BvT>xbV87c~N`YHNR`qelaLt z|2e;w5x?3>jg|oaR@8$wr^2=z|Bhn+8vzQfI)))bOqds~o(D7MWGnWc$W-~G$BOh* zg?kL>My+6vtI%lD_d1K$R~*n^J^0L(7ak0=`N;7uUsHS6m0Nl)WnKTo^u~=YRYR_5 zm4U@3X0Q~X)fR}na2H=)ahTpMyz-&+ei8$0MBZwWTrMy`v@S!($VQkjr36kn=J%`I zf4+GA@9OmnEq`Bq?bqJ6{?F_6tup_XK>(+sq0WQ8eOK?iZqgPkw-<;#T2UI~Cmd!) z9s;D%ECPExciXJUVYoQ4bp8!r0VA%#CA1?ktIaV~}s3 zcnvQ%9g+mWs+SS3mah5-6}bGsN!L-N7hA{p4RV|jcor+lWSa#>^^y$pSE)$(%)%vm=k{yIoyh;hG;7ns2x>KiV}vIWccfWnPADep1KtELLuuGIzHtHWSGAXAdo3J?b1Y z^xTW&x>FeR;CybS-4i{7u4|XZBbSl->^wG>e9G}5l;XZbbO4U}Bzp`z5Mp8&WZXMcm2HBbG{u6DU>TG%`MBEbFS z#`H+dL9cT|0~b*zcM6*p-9s<_sR;Q~L1+YSSm!RE7n?ySqoShIZlJ!TMs+9`x}W-n zGsEcOGgl>sv*4)(agwVroq^l}G$Qt`m5g$y|B5=bCrj)vp|{{|J6b9@b7yKcyy(Bn$pN`T>qF@7+|q^1|uJ ztFI$9zO2{2J)p_jWX3+RdRCjtzU3Q^xu}1wJ@b|0Dys%WjR#$v86ips^20}w3@W{Q zS&Xq=jA?dQ$K2uJ&J7!sxnq4|Cl)%h0|VRUr-kMx%`RV7g}H5uva<_P5nTVre;y6z z@8IRJcIL)aE+5*df-L8T$(EXz&u(@LJL$?pPRS?!B!(w#TJ0dePQ=|{oxG$O_4EN! z9=B;t=_4Rn#AO4bu_8ccgHLTE?DRocB85t`R%_3$Yz$aIpB52exEv{`qypzNAMEv9 zL#3?LW%!)`0plr10uDLsf9$tj0k%Z6anJg#MFRv<`_a#UT5DuN(Xk9owQohIUWfOt zm%vsk0K&P;RwW=w3Tvp=;looTz-5Q2&(!kbtBj`_b_v&}Us^u^sPoNFxjJn-K^=h@ z9V&8|6?S9}JIsUl&C6-6!WFkbqg0_j1e#Zh^#!8U6gqW9OkPT2z7Ns#pubuBhRM|6 z$v&hjONVK@BvA#1SYbntO~qqUvHLXdd1tKhk2t+gJOfFN3z5q6>x@-YVxHLXVr;ef zmgN$_x)1df6yKsCnSCIcjnJhaZN>|m1%+n>HuWVfNBY3zLYUQ<=Qa%X&x98?A~a!u z$q?D8Jmjjc?+!r6Rp{gZX6%#h2@?7ZcQdC8&U8r4ag*w>(3~!!HHv7%1?TsP&m~>4 zqTmUF9;y726{U>Q3TUxV^b#A>)a_?rkVr?c>B+_nJP{I|nFDCjJA_0yphKbt3+-9L zDmtRSSwP}{?!zD-XM1^OiS>cV-aVg+q@T=7>@34ySOLfy2EO#;T7l_O!fv~SjIdB0 zn>!gvpk8Xq-br=c@a1}QLMo#;Q+JvMfd?mj`xAx#J43h^KAms3>$}JQw58K+)zeB= z@PusWmo{mlap>5=qfc{oO^qUdz`K6m;Vn9kR+Cc8nf+=kI6#$P9o4FcDtqN1fhaV` zeiSaPUXyvus}KsZEbC7eWr$`MIxOYjaFE+v=oi2!OXDs+}+*resnN^_gn zdMgLmxZGQsPR~=@HD{L@Y!US%#d>eO#{G5Sr-ehu`*p#ynU0Hx?dOlGxy~Z8PD8j{%u9V< z;fO9>^3KaIdVRUC*wAxW7-J4RzVSr!x!$|v5I+il)`0uKI;I?czCUg1m~&Af4rE9= z3+kX$5tb#?Xej@ZbJllCj5I3sb~K~#!8c=?&_LIl2*8uBe`yRE%77y_NWc;bg5R>= z6Y()jxM)&1MYVeqLE)9vu@k?oI$rl>atVpZYTRZYzbZ|8is~%^O{IsRc$y$9JIgSbj%5lSwsV#uzyZnr$gs#<$bjSCk~w~GAa@2 zk0So+6Pg3N4ChHy_^<(Al_gpT{$KWG`wgb`$Hta}jPSc}SSP2mGOusl-@a@AU-wTE z5l8Ghz}Rbu0GZfVPvVRI+e)qK!WDgwZ^tzx4gCd_k>SITOxSlUlBJE^kt}@d7na|GO3PCK?&M97L5&M@)%55 z(2YSCVlO`Y`f|CA?#Xnen^qO(@-RE~M0V4vU-@1|M-1192$t!l{blCsYXh3n%^p

{wOd~iZv!#H5L1}Q#*(R>>SI|ywF6iq*P7(^g(bSv{lK7TKwjHzQ24h!S# zK~PvLV72b~vLsPw*qK;5FtLT|rXIMV9SjHHIkgjnNBnF#Me84*%GUCB4$GJ^Wd zbmNquFY2%YuU|petaYd>F)p$xX+@~95v9{&vI}h_z{+${;lJv1`LX*el+|hLte^AJ z0++uqjrGI0GEdf(`8&R-JGP#yd%oQML(j4G&^G8bO3!tSM_WFtxKGw`T~To|q4s2b z)zXfuFX~V2>e6kfj(YcU2k@qBJ-Ar(j#IxsQZ7d}6!tb^OSj8lME>b}7U!=;G89O|j1sV+ zC$v@AXc#2}v7TweLR7i~rR!1&{`&bV0D@&5qw4nKpbc@yLDVvdeCL(>c@!a9BVh06 z9hcH&oGZ(`7|$cLS^D5v>DRS0JM@7L+1(|CL8_35&lKq8)?GzW_AOqym}e_fBJ@v% zclA0NS5!J!A8j4)rdK47BgxBF4+k)DaIoL1^HH8Y&QDxx11+Z*L4l4-&k0WkN`t?> zzV`PT({L8P@qy+wNm{u-K$fW-9ekLKiwF6`bY4#2&E7c8d3wHbH4p< zL{Uahen8_xO1q-X`5T4pr1dV-WP^FY6Wy_$&(SiIZHD3r8Dn{v-hm-7so~B-F8x_3 zR#~gV5Q-4e2nr%bkGGe8`>ctxHA;(quK}Z9t(?Ug!Rko*$uIZ+xuO+^X+lS&r)tCL z3EIMUvuE_d>tG7wO6pv{xG3M-%> z56fN~&jFK)WSe2KN6zSdI_dz7)74)rCD^B`lvm>fLM(mL62*J@Pd?6fF`8__&_n7^ z%duRx3i7n}_>nv_UbLK2HQZx)Nr1NK8$w3vGu8YPyIhW&1&8;cma+M0ooc1JJ0!%$ z@I_YhGSrsvE)>2-q#nXSo0cF5rm(~|fFae%Dl&x_1$N1bbk9Zv;lE)6wo3U=mjfD( z90a;g6^R#gVfnI)1eTn5e7GAcdfr5;gn&pJ5Z^2i>trx6=D3a6b{Iv4$FOE4U1TX- zVC0&MJp>Aw1uB)SND7L8< z;~M#{-9=MZWC;lM*H`z&y*jcq*Yf_sRt#Z3wu^#t285xUU7l8{kLWq7-DzmcNxQ0g zLLz&e5oHpi-yw9qorxH!dARANM4nLSD>4XRpPq@bSoP{dU};FI`akOUI&A@NV-!bI zB17UBE3Rv*R#u4Hkr8pn3v>xENfJKIMMnP(v0`eD^Ccw5M}S*MOl=_#rA0<5Fxb~H<;LaPr zAO3@I>F8Q!7dT$fwmK6)?xOdwoE)TV0lePWfR%Y+$D8HH&jWaRGr+n6b0jgCe+|4C zPKtch@nA@qiL5Rssjloq=<>$oE%xvuT z-PED8TaBR^%G!=*!;ky`A#w@*#8R6v8i49TSeC@<;7g>KS!SnXSjfat3YXkaF_=rO zT%;)n#`iEP%vz`YwfKm+7%o=Z6<{j$3(=;CbGGq9EbZ$Xx7jgTuoj>_uf!XA*!K!NKCsgw*hZI>RlsJKky=t>#Itvg z(PREfzDpkSZs) z3u>IWL5Vci6X2GO_BU4!i{l@2QO11`a_M3Z!>Z*(FMt2c0fAy#9ms zO<#&J?Rs87=Yox~U$l)#YHs0!HxQhZbtU`3hOF*G_RYBWJ~!mMa8E1+GGMxNCFhG( z#mQA)z6zr&ATnDM_A{%v8l|8-#S+D#?JFV3~SWWx~`-+o)Hu6 zSLw+N`ziLX8%O!M=F_+D_|V|FdM4<9y7gkmW_-^SHs(p#SD(*6F2`Q9xn*2TdMpy& z?en%nK-{c%BHf#~?WLi-BFf`?)i>I59j%7dP4ppnmZj=0Vh~cB`TDdHrOh=iLc@mP z7V$d}+;0IJCMNU#TJ#2!6a066K~&yuyf?m7wL!6SZdezXQnh-!52Ca0X(Lcv5(#2p;vtDTT$il^hl}jDl@n9?t56AU2DU0^D5c3$l(S&>LbHwk%MTwmQ z*LwVJW+*dy)}cq$&c^vQ5DZ_egHe}`wA-k_l1G|C z5TB8!mH{Nr4XGdxC|CUL;y}Ag>b4s9D=i1EFrLpg`rqlHnhw-v{D81?5GD~gb^r*@ z2)rqIVS&e)#zebp8T(4)p`{8V23OsHuLsE!uEXkm(2xGE-%{z1(|@nxa{J~X{cOde z3?fx>otNskHlILy2EtYK7q6n`u{icU-Krsv9U!K|cMT9`0k4ZE;nZ_3j_0*R=ioRw(TSrTB3EOS!O1v0u7|3uCZ`5CT~VCAfg^?o zZ+r>))`13X0A&`SyjF$kgp_JPRYFdd3hAG`NF&?4zir#Pa2~nYRA{r!CnYYrFcNR+ zw_E6mW5N5c-x!#=o z8gRZ2kvib*&F0Bt@6;$>zO(T>uevluB8*Q=`(gB$aumA=P*fEy5VR=|6U|MKAj&f? z9mx!PpZPO?&gT3H%kz2of9^(^?~Q*KP?%6KV;oSGP}rO(l3Ad7Kx4TAJ1I2D3C=Ez zHtIaOqd=Riq6f}G2l6V2od#sw%bmB)a_smdgAcG{(lNIWej&@QFX136KS_fI9uE>C zDq%^wWz!q@wInW&y~0<&D{EqtaI;Tq(StJIdd6A6DF0GoTA&#|Fp+e}{n~D*uKU^HQy5wj)6KY9|N}|$0G!KZ# zNV;-_A2I*X#1{W?Wc*5&>D4)6nn7UgMc4f> zcE9ySCs&{57iIE*wh-){dE?APnDm8lwtRxy69&~d=a^eM?ss^A)W%b<3Rl>O(=TRP_COD70P<)t zJ%eliiRn4_Zs*kYp_evkJ|9j*e9-(PCjl35Gen(<5{CJ@1G?Von9Xw`qYYlikhc zkLo@f(02;agnm8aEmtK$IWv_5@fx`|weQJ}tK#LpzTP+=I>>(LtrvT(xz}QCd$Wquq?dd5wY6G|Eo#7Ss ziHgESW}QcUdlZ~9XjN1F(Z<1LeDFBlhYiT;#~s+3n~@BA6GE&__C zREtbHhN&=Q?ur1ViuKB8GA^)8(4{X>;a|12-ju{I0$P6#Gr{{ta+r_|Qp)8zi^DJb zK=W_~ipRCV$=eA+nv+6h3PQjfD;Uxqg_)T?_2DG7Q8RLmoGkyJkxWj^5fXcV)C|y^ zCB#UDlmO;`6fZ46L3?~g^ACrxOL5|6Q81twX_KRqIe3U|KC(Ga1y&^}bUNe|P>6i5 z0wr>)mn<#ts2BPIggGo%{l>ITR5Ig4{PRKtfjr}AcCU=Xtm9y+75%w2^R0;A!|I!-E59w&d-`^NO&T%H1}B_`o%LX#beADD|j zgVL)RJ8%@pm~qmWz@_0f8M8#!ZPT_H&~VC-C&?k<+qkMV+p;L3X`Ejv&ODqU9KvT&8S9XU)M6P#C(W4#f*E(Y3ib(6#g1QQ?HPX zO*Q*euYRgIsdTH^iKo@A!^ z1FZ7K;XG%iMAp?h?HqZ?Q=vI@a+}4gy%7e{qa(DX-b z11O3Nev)>KTrx$h-nQC_nyV|B4^n?;Nub%qyE~hJ%pi zX>aqbia0E{vctXsB{ZbZGfMU}WOkT`8%#C2mM^V*-Zpi0-&b&1Nbly5SNdMZuM6c` zPD2DQ@Q^;YU@d|wfuH-$?F!b;Zhm2Cqh~Ov_?76?Q~j(*m6D@K)F)xWNCRO$EcrBq znNC2L07GvfvSf;04JAK@auymwF?xsE<$R_2{_Mxv5M0B7_MZAxzuRpc<2||(zKprf zkG-68YT?;P!8U>c=Jmboau_pz27}vhh(+8vjEQP}Gc!-$Ihh}0fZZfNwPmXc`U4?y zK1(fhQYeZoA;Nz`g(MY}oZc(*Gkp6wH>nT60r@GdH}SI=!u;EoS;N%2UQ{uJ?YXzJ zGZ&yJC{YhHRaJ$T@5wLbX_D|6OVhbujsukx1V{m?IS_filIbc`%HE(_|4k17@B+X* zU{o1#->>%f{moYWE76abDPhghe0eq0X)qW%xU)u%UF2A2DacZh$!qP1gSdx3IQQgH zM)ISB`-DRmr33%LCgok)QjXQ4f*jYqvPALsN^XPxpGUWP8gu|OA67$Mtgr&EoVl5E z!rS5EP_wF_F;$LaLlbTTHC6aSi61{y??B%i82vwW&2i}wTbFt2lzceX>=D(LoO(+>g6NrE&n+&2%W zPLK&Vw-nm!gbyqgt48Je1g#?3;80I&bdl9RM%4gfP+`z_^5N<(+wd-Waf?}{v>v_)mDuAR zuB}U%Nx8@)mB}xHqq{??wtShOyKso^U-E@(Z029#5bKvyGQaz?*Nx?!a@(dNuKiYp zXziclKcrfw5wY3ORnu-?l5Wg^8u+|uNrXFa2o#;Q|a>(#N_K%M* z{@S}__}_xPi=lhv*uVy{tqT-aD~?um$?=3@vMJuHlpjA25_FpB2$5Cuu&mI)l@co@ z8w!-kt;f>4{Yu`s@tBkqD+vzBowrUW6L*z9W9C;t7()o zDj_=CIK-bEK<)l6F&nV7sBq8P&`_W`BZ||F;5nGH-43rT*9vmqtx4@1-dyl9agN)Xe(g)<2R^ysesI-*BuHC`qjPG#5<|Z0auA)qT5`&fw5qifAC<^)ZYt$SAX;Jjl8bNINhZ*0(M^Q@5QvZI2N=bB_FCh8=b za0*vOhQ}PWjqDI&s$R?*2Ra)z+1Q_dQ~k2YC?^%nT|TgOBGI+IZ%kreM;XUn-PQUz z@7j)F{b%iO4(fmDm^yPR2*ZPQUxb|i!r{qaU zaIQgmDkqQX2V6w8d~Dw7_Od>B6QA~aV>H63B=s7KEj8My>Kq!DL1?>FA@v)CQ0WW^ zO9&*!s4AHP-lGy9C|`{9wrdM!QHCwAaBIW4nrA4v12^<9&Y4rxD`Bkj^eHtb$W{L> zC0}%kjABsG8>fY2m2%gn2jz1JF_Eqd0E*xsMlciEsMIjpI2f?}MxT}I;a)&E;Y zEiDL%+aPZ!C)e#nCcP@0n-0>^T3k|M!;xdLj=WR)BU8zz+ty*G-kU!X9LBQd1(>I8 z9%zpeXR6IpHB~#e!ARM`0KVu?JAgHme8Y_Y?xK3#P>>C6bNfTyIi7qm7<`evE3qF! z+mseYw2l*2hvTs6qw97Z4EAtQ4VREi%rQ+m^T z0UIpcB1h0SP5MQ=4Ens{DvJUmjg_e)cbbTxB{O|Cin3@C4q==j4k<+D_wUMDP5TE7 za->|MnFFgW+4n2753UR`V%3miAr3z09l}r+glQiHDZRt_MmgV5c6_XHy+#qoq!*j4YYO_$d`pN-J)Hq4t%6&}7G&2~DInlB$X8F*PR(@R7}{)@{-_@BhzK;e6{= zt%B$iW;&YEpi7QdJ4~BydJ5HlcLsrNvnAHwhAv4OoRU#~6rtnol_?@9O-ov^rf+PU9ABEJ=t*%nK_Na;4S+i)Z~%9uRF>($Qtsz+w= z11nVCQ_}!e1Y{hPb;avkBB6nv1K>UbzN@kxsi(S%F3v(;*6oxcP1uvLa(Kjy!X|o2 zncCdGkd;-BCgU^4kwseHEBm9~g|Ef#I&xc1k7q`NN#J!BvvRESri4}46c2JAK#=p% z=#HNtmoHu$dkf4v$nf@a1=nsDNvM1YE=-_6Z?6T_ljO`66&jY53Y#s;5JnUv-fk92 zO%+%(rEq9V*DF%EHxl1efT|r)IsGNqZH6s<4p1WvDj9Y9%tv8M+Jd^Bow`JS)Tp0EF$88c4?YL*W`FqHUWkDo>6i;=IruVe;Oz z!^eoJ0KqB?APQpoE>ptqJmU0_)1lzi`c-x=@_=e*PT`$!AGVJwB=5{G40D%hc31i^ zN0^w@#tFTdX)ot8CI;KCY}V8!2vRzWw|Q9wRnWT!uU8=$0Vet{SofXU`A2qFkLjJR z%%gX55UIRq@>gE(N-M#Xe)&1AE4)0Dm`6*5tiff;@!E?@wXO4SoqpO7qdiYqtb!dF zUD!1@zE4^jon00t&(DAr+7-iafGYy2TKr++pc`uC%82Gvu6DA_cpF-ZJ6RIFE*Yg- zrgG*4fCw#BW#u!Nhfnf*jPhG|Xnj>VS>AnDSMjP0vjE(IdXxr_Uqe;}ncMf?CiyWi z%(=)CdY{CQ&A?JZK!I*w7ts+yYO`Q$8LQFMTrP%C#y++p1-Tu5ZaX4CK|qPudUQL0 z3o+F+ZNT#d>H;Nl62>tgGz&zT%8?#*YIYD7Xj0D-AlQ?LcA1)^K-~|*vY6g-0WQ^_ zst0*->oR+HEg@Ub7`|z;jReQ8!GL&y8$-QLjzG1dJnDem0HPhj8gPhyc+4aYa|g!O zegd22zlIs}PVar$Q51E!WF|f3y|a>91>!`>dR4Mz z_-MWQ8ZG>o`nXKDN`W|%7oQ>|Qqb%fFLvt@txhm^`2=}Ke|T!dFst+S}&TzmQzUlIwy|i7c&a3MsEekp|UmR8Yuk6BVs$d(a}4P;ro{1_onN&Ziu*1W?xQMT05Vjh^)%O3^qGdS=0jP)@l$PtCc zG+Xx@d@qkf2)iO2kq{STfqKXI#X@`S-AUy>y@@h(x?Cd*Ace)MsKTc=$1pkHsa_vK2|KjUYPy}f=Da-(V=W^uFhH22YCixE zZlK={rWcd~N3Imm@2AmyHA(;!%eM{_jmIdoa5Cx^tj9+gNxR|9%`3(@J57`<>zx^{ zJfC@irC9=jm$*zPg~$IU@L>s*z-af&fTo)j1qE@AV)w*(fgubH=LV3?!SZ6Vza>dg zatg*$0|#-4(V!y<#pW!b>#0bO4EN0mpcO~+S)bO7Jc9)y-@@cC+dv#gGtUX{y_}2`9b-9<77AvF<(CUO5)>yfBS5rbN>tW&N}kG!IhLo2*Nhuk*^>UJla? z#}3r{pmShseJ?gyDK;#qaTK`qy>E&cM>#7&o}kKuf&CAUdxr=8KoUcVitB3Sepm{r z{_gS^b8{FBYTQn#iDROe{j*USqv86*$hYQ4*Y z+m$~96^D$`2VwtB}G25G~$RZiaeyjJ*q--~8ZZ`*=>A93HU{#>vstKJ>Hu z&X5}JVd#N$r8pfHr|w;G$a1G)-$o6V6OHFIf)%F76WkNGJ$`qv{I7!}@!4I)SVu^_ z$8$GRe(c$bh|?Q4uQo6DL!TUe8sehd^x}uO^F-ADEL`3lMtMoaDN2;`BAReym|Cn!CEw{)4MyP@p0Xw#8jy`-hq1;138aLL`jb&alP3}JD zzNjJ3;80HUb9wSw(KwO^pJM|SG^H0?z;GEbVOt^1WlO(aHUU%xp5K9gX?eEK(wiT5 z8UoJKW6pjlI1~W*IS-+%@F@Od&Fot2Xj9#5f%pwWJOv&Oxdx3phJZL`h}f;4aV0^Jj1aXjd6_ zJAjLED)=y8h?ZA>Qp0?sBWvYY%(pzv7u7GD7PID&j#;PKQ0a^QGZZ}X(++FD?aw`) zTmQU@s1%U<80L2%wZ7J}9JzX2fG|#Vc}`cnf1eCvhRRQ%-qj-hV-Qo|bdSEaJE;c} z&DHTHhisbcB7Zrs3ox_31TV#bh^{5k>tB`A_cgMaWEGo~qBw9-eV*LcxU`*_&yj%{SUfp*fqD8ap>2RRZe!cQ6 z(rxfkf?Kv!r_2oi)sGNHEUIUKSG>leTfRh#&feTP?Wnslt&N3x~d=MtYH`98= zIu8My0aNRtK+S86S}D)k1O;yIr8fS%{9ib}@fCIe>Wv%IZpm|I$h7!h2_ySeGX?rT zB{oHj8ewXUFo^~=G@CvRuQByYV+P}bgX>ilKtde}+%?9)x`7%V0Lg8P+Q-oPPo-Nj zJ5MN=40;&IcZ|;Wem=#y@z@u9%*SPXmv`mvWE8G3!1@88op*K zh(mC`MhTSB$`skVCNMu`%ff6(D$MUUftnKd{7~hXg!>*sidPQ@u5{`=7LdvXBqbc+ zAsApPu~5#zwK9slM(v?$s=0+WVD=vp^q;CGyxZGAKD{z~A&hR^;ZW3Qv@D-ax8J62 z*HUZJ{zcWth4}C0+Dk*R1k-lAlsM>PTY$`*^?n#Q)zVa_|Fw+S+hl%(JJMi%8z0wd z{jWv1(n3OS{n&rNy>~d^CyjH zrDw&oVvB=f3kekArFX!+6SvA3ApJ3gZG6wMB}Ml&3O#A1UkU5*e^6i6Xk8k^%4;Zf zvSo9ZbRvbpJUKcACOU)E1vs$fh*nC=26F=a=eRwt8&f|)I1!a9NZq; z>(5b86x06E7qb|;6?Z;tT)WKXApNEX=_RNUdC4HY+QEQ1c}loMnBT7451vmGgL#+K zM#erb2|k4_==CUpdS*b?7-mFRnKCh}9<6?LjIhwEdvi>lJqDCT>qR-BlaYU4i&m3! z?)4aG$c6tqYBSlu$<}!DQ*+r+IIk*8`YYexim_~dXJS52UTrN_Ev#N0P3Lx6{zlq|S~srFna@&jmK*W< zl~E67x6xeFpu%ZkRtmm>iydSh3PFrlH`Z_Kr_RUY(3Kmd!7( zBJ30V=cH3JzV30DtA-GJ=ig^{_>a69wcKm9-D~Tm(vuaR)?WyeX6y1#6hAlA<{ubl zZ0OS`r}lrNVS|3B$2%x_0n66k>HPhD`pJc@f8V+N@2}a32WQvcbw6rr5t#hDbPUQP z0`Uwbj7(|0C&ZaIDn$h6X{DIr!y1#&!dPQEE+Ml^9LphTnV;k7y2k`FbN85W6XPhA zB^79&9xr0|vL=e1o+VBkc74}4am4-S^u$qUU>-i?7{=&LSXn)bHJ|`2L%gP-Cy!hK zIr42O721Klws-gL1hkf{=G)HT0Gbw4opob}z;G0t>%zth)GX(Dx7_p8MfS2Nn) z`$X28Zd`kynA3$mO}KV%#n7im{)YPp&v}urg{%0Sf(p-J>g}H0{f0BMS92?Kiyi!H zSd&nf;n(Wj$i_p1FYpby?(6`^&#sS;RFUT%59&Ob9q+>*uM&8wYxO+d&g|@&=rinW ze9~k1zC3$|UYWuubbG&88gH-fBqlU`Wf(8{t(@xo{gge__Wi!jOca%S-rnF90@cs> z*1h63gIdJu9|U*Qok$vZ&{;9EO6!jFHJ{`&Q?r(dzv(NF!CjnQ`+ zW^3WM+NAZajFE028Cb9$xlq=;E-cMQf5{?$LaH236Il2imQ zsLBh*1t@=;TI_0>f*2^5tQ@q*a_7O1PSUeRZ2-=xsD_Zh>(=WXj9(Zdm+pDCy!Q8O zK18Vfn~egg(prkeG>UrMRfuz6hqA7Xd|uDHXBGLiFuYR(wTFHV56KW)7L8x>As^j7 z1~$>_93e;5ztaH(Pux)4Uvg%&&Yu@c(Lk1=Ml6}pAe@M z>A#kviglg$CbEB&zP$;}z~g!}YDgwWQ#qMiA<0>C3_}i}!<7XFjlk$t-lM|Exmvmwbo*O=D`>-@|QDMA|kI<^TQW~68r`zAR<{SJ?eWkz* zpTfwabpUZ(Uj4dFvxw&Q`=v*UP4=}8gof$$u6D^PByNElE*fGkOpndD_lps^*8`61 z-1dH73NUoBR;zK(Q2pjdg@4~!_;DFFJL-|?`iTBJSSDT95@Y1$rFB4g<>+lW%1$73 zsO|%GDkFVd9=v#%-M(EHlKX5z30)b+M3<}zs_9LkMUATQeYB@MLr_^=WLwS}Q(9sdcbTP;xQgd~=Eii@k+*2rTtu4B-%!|{x9gTYc0JzGVg z!>4d<#ubMn+cr(u+IG`#n5JI`Fv74n6a4^|x1$H_ko5`Fo$BaW*L)sa82|N9IAnF^ z*Wi1PQ@(f49oTRP44CGUiJk-%jetG?`;aR^wRLcvW-9ErY2k6@!?t>tp$~!k7nYvL zNY@*E*Ubc-S{P{z{L!$^KxUMz(D37T8T>a3FS!?>OrpidZ5_&v&J~y>?+~K>9FE$X zcI)@E(TUPiMqU9((u)p^LDtye_$U+It*K4;pl>Rdxu^Dn(LP%bQLO*qVXdQ#3AL=@ z;uO*VBRN*xWcuai@*MC+-ju9=Z&*{G4`B+&A64vPFBUTNVPcmlh6X%waT4LIUo zj`SLmhL7G&MQAm`#ECEI6&;doWg%X$x(d zyirO?!Fv#)CN^Q}1x=YDTyvK)wrA|FDtT=ivyN*%l^9P*Y6ZvuC{raVa zS8MV}e{Gm@_lw5aB%%G+VK^CYc zHPta1^~sm43nw+IO|YYR&ID>)^Fc^f1c-7?6t4a z$%}E#(>V@mSMpsGVm6KJi2WV@%%0p*O16-#O zqiE!sS)>^tag+r~My282KFUeIE-wVtEO^g~jcdL-2qba)=kr4=b7l0x+R@a~zt)2| z#=q}#o9DMSaPltA7q&`Q=;1&$GavTVJnwJraVq{#Kr1#N)p=PWQfj&>ZqkP(=aoz% zzk4AB-$432vR{car1+Y)g1;YS5A-Zw6Rl^&2NTMJ*YH_pFyjB1y6>+x3q!7A&Y)Gx+-j8wqkSDUI@>_NuK9Gn~2g%LN6UQyn~u`xC}y@K%U1zM^eCP zRLO9n#(sf>?kl)Q2Q;YM(~ESH&6S>ub5{}%7jogw=n9k&GJ=v}A)mo-~t$AwMZ9@8K z?*DWBqHHuXrIwZDALPfKh>?!G5#(*7{{d|_W>KLTXg&(aCNUB7<)&iJZ-r|zK$Xo} z1n*%c3tDye#qYlYNNbYi*?{!IDmd_!?0s%^9}URcBilZzBv(=2I3=CPHqsQ>DhVaN z(y=Slj67StjNF>py7R9)YApI|PW?LX3aQPtzp#ib%U895(-CQOgbAtMFD5r*w5fGOkW?XOqni5j`EtKX#U_yErTv zNlVtpSApB0sscnG7dtv3*+(-Pn2;SsOQqeA5YWKS0jMSbU*UmbaYvH;CErY8)1v%d z-?`)z#-3Bveuun3`E9undci%bnREOC+5>ix4>7KTqk)3hLD&s9-C(9}Sif%d8U#Kq zeSQKvfR;LsllVYK>?a~mMnR9QAoS7ZCOoOr0?>J)%vCn*8E|%t1x|`W?o)0QC^v?F zLsSdw?hV5%=wK9G`V&$501mdFX?_(asr^_=Yf94F1@@E#meYn>zHWHV1<9LBi^*0o zz85=lslC24Wa|=9zS-q>r$Rupr^Ds$EPt=pS}~#lsCNdKA}FTKf~|nu)MzHF`Or|9 zt(oF(U!s#U$8aA`Vml8e23sgx_*UZ%TYxvWA9FXQUl}?I`Cy~*DB)PFuHV3**MO^c z`ABfGE5shKjX%J&y~kqf?7Z3R(b-+n*zM(fNbRf6E^Vl<$!4L{y>4+~Q0Ai+O1&%K z98Td-SMZ5jWM)@8!9$bouC;k#oqS_i1S&KUh(=~{`vR%#vD)goVj<$vDvLN^nUpLJ(q9ARD>}D z5&j=~VKse~Z~7J-AHaV0O`dq*f}~GB0j)m)1!&{M!&2WIA8v#{{Bh#pwjb7R7S)MV zP&hYCW0aO6W>mc&Aokp@P2epadax=wcTcnjq$~vFh~jo&@n;lFB2BH2kDcRd{NdxU z{ibaRs2Y$e!rk=7U8Ks*MBURFXKsHa^X4z_X7*-$HP0hv@6LYF?--$J+NW`T%WJR1 zpo`N^Tirp)2Jz;@JNNHt)I@?+TS7n*aOPz~aQ0A0!%$e?P{iC&~M_Ju$T^w z&mK-_7>*fB)BEF=Ji>4=+&v2o=2ix;lDmzU0xTkU+zqdcKNcBd8P*XI$K1h>n)ifR z`*^*%vC}Qj(|DI{gYT&bjjuWyC%Qpq=RDH7@7~N6cfETUzxM*aVz%-}clKTK9vfu5 zNk9q#2NINveS)K>m9`E?ivA4l$xiE;8@k)~wk78~S*h8jSD4xiz3aeUma$JKG9Yw6v@H{d0wN{yv}y6kSh zdL1~_dA`p_5F0pe>}O*A?A4#qL%a8U$n>oZLU^-bH3G`-Ii~Yhh~oUsd8`NM)5OtR zc3tis*KQ`$*iSu;CyAFUUd@5uB^@Byn|J~6Sa$iDfpQZ7Udn?S%XluOfVmLpX%eiI zhYqfT9a42>Ztv0ZI^Kmvg6 zahmRw$gcI6f_l^6=B``e0a4^xHsXrHx~DG_S8wX ziGG{=P9Qn&&9ZBx?@GeEaIoDf7>)_-^dHb^s=`MVsVlZJ2L$DLbZpB+xh4(SWHRmK zHSKow-mVBBWMVpy4YihqNeDnSJRtQj03oWUpG*nP24Lt#=VXRk>5ywOpie`(jsp-O zJb;?$k^I8#^Fs*xNlM8gIT@�Iy|&T|XnPlEBfCiQ&F4X25B zPoKr~!%OH1q(1G1i(guV>{>+WqT97K-5!Z!*VbI*XJU!)ng=r|IEW>Bb)gguFGYH9 zd!Sd|Tl=&dex8OrEjDQ1BhK@n_u|$`w0}C#;==}FNkNLnmAFd#hxbV8>QD21RK%3* zLJjSCAMUj+2U=SrWwbZB8013oqJ3^H-BtJFCs z^p`|sBbEJPJalr6F7C(3L;(SGgn$E$r6C(73~Q*Mwu>MbeP{MF zNT%rLInB2x*byw@_iR);>!C!}{e%@T905QLdzPhXuyzr!eib+n%aI-mV+7ya)2?{}uzuON+zE+SBH$*gu7`ZxNQDpBU9_A>hz zaA_Az8u%AZ(*f|q0LnESc7Y7dExx3S61i68w~wRD&17PHd99=kFxM3a3ucDEoiM(SMv$<<)- z?n*hvwG?Y0x7+JOwKvUX8tS_&pBq4&w{y73SSxI+QNA!bxdt8ca~9Z`*Z&-Zf6}jv z=oGMg8n91%N{N(Kis#R z3wiAWY4|j5u%sr!4+nWjx}6Jcs`ASKb*e%Zh>HGhZP7uM$NcOdf#PxQ4aULn5#U*T zvT(Z0Ic7eu#-y2*Qw+lTd-TQL(23sV;paK57-$$J073nDf#>z||66Da zL5dbjHw6Ls{jwePp1o*!(-d)tuVCwai21NqK%Bch+zL~3B3tMmf zw`qyr2+OS!;``)%dE^7kp${SGLa8#lo(GJACaG6U75{JYaof!Yy^ZGsYG?n=nXX@T zBUG5ly|xs&#^ggjdM~dwvkQ}CW&51H3|a_-)s6#-uVefmWs%FQy7ob@JxzRj#JSgH zkpi}NrQTq|(6Yh<9?IG7r7}g))pZTZ3h*&#R=6Nl)}+|l@Oyub_X4I>(GLA;|5}h& z-Trqku?+3Q3J>AV*`B{!c5DgU2)=-z~M;9l}SVY;(@*l z^{R67g7}~)0D^{?fra8ND+<-&>BjU-xE&4Us8TRIVn!5@Mdkr8O#Z>31T}vsNkq-L z8!a2&HDDD%!|eIsY9WZCpT!8IEGqj!1?J*B+%;fSfb7g?kTpM(^I}5!ou-d=f~=@T zj*4!m({}V&=`NOsPyWHzU1U8N&bgKM1Rx~I3x*E`y49wxc=Ou2fr66;Au+T-+4VG~f@ zIRVU`^#(NNN?1Y7-FbS_3xCd;%_OD) z)YdD32z}B4sYr3qI0q*c$t6oC3w&`bGQx=pLI-i6W&qiGAD7`6F6KTb=rBV8Su%i| z_g5&6m5E`Z1#8dsxZmM13HmgzgHN&9%v}IR9suUlH_jL>o(z->Gx`EG6Y?#L$NPwwUatqQL zaFDK99@5=W#-e@y?r^(#Y%*KMjyDfs{q7e*dZ;ouoB(oPNZO3?FETE(kqrwd2ETO*^`LUkVH#t1X)rMbdXL2W-gZ%1;iPru^iE%16Avr<2j7(l#G>ggvhoFf!v& zOD(nh!%@}Xt|z=m$rra~%If1(%rxkF>KAJ6gw+qHJ>cRRqmJi zRQud&B6QzAJgd)YS_SGFeL0MY1oh_nONe9iWZGjPnnYw?P<+MobS|{q{=46Zbc1`##ud0)bs>$eE_YWtd zY`T(SlH|4Cgb-9ophu~LFdkpZ11o@j5b!~UQAG-~TonSu!wmfu@DRqJbQ*8p7YTu_ z?sHWs7y!Ev2rXZ^lDI7i0x=(HDd|&t2Zl)b zkZd8#i%7)w5aFWIBOE1LPdl@KG7$Q4`9DojJdMw9(;!ZQkPbnp#9tDVGW!XX##L8v z_*WhxT#zEMT(Ge_3Znn;0pE+?bgNG=Ws3V2^><~$263>^2Q(&i2cQZ~rEgC^Khj5# zcwXfPYufV#OQ87}ECw?uNjO=DJ^!jEFCq5xe^wzz1}26$83Yd@{6hkN$l{ncub%}K zj`3D3f%tL|{Jf8U+reh)GgUD*Yz?AFp|hBJ#CZrsFe=~73)BF@jgH(J-T5AtYr>wt z?9DC~_u=Kd^(I?S>FA*azx*Fy4p^Z3|3HIQaIL~Wd=dg5LIPRw5?y%EAfCkZO`a_-+9@7%Tv#-7}3*xc#1tchV}f%dzx?;8*YHXOnfu zRBr#vu&Sl#()cPmd=Q#xuxP5k*kqO6s0PM=tH(j3z&UnWp=tw~4Y=D1l}&;DD*gRr zd-}J2OwFNwYo{j1bn;Mb|73`%+9F@vbVzU|i@&Ejr(e5L7uxP5Dr7;PzUedi=u}Ck z+mUju5*U;aEU$?z%_>3>&K%pKdjkd0BjdScY7R zW))Bf@ck*d(Exl6CpG+p5$g#P51Dx&hULEJM{m{acZD7$z+DpxObYM&rRi&kEk`Q6 zC$mjGgej_pMPlxYJO8)NN!XAWk6t0qvzhH3=z6e>`ACs66};~tS_6|4N@QxY820;7N zUTx*hWN%{_iw>qUM(UZM*P~+Jt7NpMDgzK9Mi}Ht6_jLQAw;3%mkZ%?3tYfZPOQ++ zYBCJ>x(r2J-V*GtAJgVN#I9I{*c3pd+ zBqsm-6MAGqfmJUok_wh5niSs!?e>91_U0d(ZBDF(xdQ(qF9YawD=J)y3P0G8AI87m z>Y0-|n-lMuA6~w z!_J-g@r0ZmwRz@S%+%VP|GvRQ{2H!)c+^e#)Ve-JdK zd&^4$8lbz$xp28f3yQz}2cZ@-W&C2wWT^ITcbCpnmEk!r(-#3FV=em+)>AUhni}0# zZl^~A4mfH-(!_B5thq&kNycv=DhdAT4i@}nYSx=?CPqhvc8K{r5Vhb? zLd}lZT>Xi$4!Z)U5tzm*tn;9x;)s=4H1s`5kEiAOd9fuiIc~F1up3C*4jP4ko2@cR z)pBSYrqb$&4i%(8wEp)V155xT^O!Wk?ozeMqj59Gj_&zpFnQ?2s8Y*JmQwkk104ZW zkakYB{uwnorxN-YKsnH5JYhHtecM>GY5hQOh6iMp86t4CXbI7~^`z*I69JJvgK}0g%=xIS=1IJ+7%?CB^)-n zqEvS1Q3U%Km6=L_W?^8>+grNY=^?dnJx^aTy-KTvusE;8g6y#^(8aw$)g=Wi;~Wj# zWyuj3)xN;bt}=x7!g(ZLIU)a6G=yZgOIes7V3(6bnpOw=)QMoysyO5bG{IBWrByq7 z2IDX}z9Gm1G=7`C0cl0zPg2j{IkvPDKkkfGoR4SdPRZCBL%Fu|qb=>Xk^zOGW zt`=q--C4@md7|p=tE*-8(=*u&06FotG5s+GlaIoIA~E^FBzgb_c60*b|Ek z-QL{Rk(-)aN$Q>aklAz6o@iW@S|kDfCIK8cq7fbICcj0uWJy$v!uGg9Wmvt5tUO&n zz^u&=wi9PF=LFkUy=KmjF>|mv&I$R^BM=WZ(|d~^X9fP= z5TUfH8(9nU;GF9SVOqatWH~VvJVDqHhWRXL>j_9P0}R^EB#q>n5lcYC(e@C%dba7vFjSLXV>>F6Gt(0hu(PA`8-xsNG-7tle$Ou4zNrjSIx-&&4 ze10tS8XZoGN`6%;Z3ptZ0Fft^pfc!^QEm}X%iX4N_C|%D#ILdKmQwdY_BR(9RTtnR zW3#UT)T$WJq$0FD`z5#-de#{75DCcu*i=EBCY#5pjz0= z-;hcMMBEvhwtmLB7UnAl3D(kfd%0S&yjnUO;=ZF$nzk5VT3FXkka~emNF@j?<*JrD zP~@KQf1PDV3GonFRUzZY6Lx76LxaZtXF1H%A1s0y%s#l=y`1P5i0hG^{Cv)t(w}WAowBhVIP=*o#me8JeBI( z@gq)Whd=hc{MZLuBYrgbJez~XsLCUFG6p?DgPwjH%^|;A{1@mTZOhY(XrBrYigEBz zPvJ$d?D;7JB`!#%J?V<_r%AoTS7nW_{rE85L*n*$A;d~F6M)fZ~34(olAv%lr8eGv5)U9UANyY{fQ z95iyRP-6FolGmTtY`%P#-7k8ctT`S0=|}6Rdeqdr$j8?jbhTU`>zJ5%!~#h>KL7pk zMPwSdYZ1dEBUwf0VMWq-YEo`f42-mUZmv0vO z-z{fSEqA3^t)$wBQmv1Cx32ka*Y@4^_;+GKn&b6vhF?CKDs)QPf$*zN{V>hS$RsU~ zBl~uw>K@o|e|AvCcJle(6_I}1hQ>}~SrSNoBwgN@&R#m_k}1ipOFUY~llNO8x5oO5TtS z{Q>H}DOYB_{S8{{r^d$f%eBWgk`Ccd6Jvg8_3-<@HaM_=~?W@D!O<>@5ws!>RrOV zYRNAggpE`>d&V%MfBS{Ry;XHN+kujp->vnlXS;a%3BNluF|DL8_xWG$R|I6&{BDcU zXV`_@)nxsPtu4{q%9;ImQ<>e`gfqa;0#ogU_rB=HfVaFNJfJ>$6Z=~HH+OlQ&NzT-~nqNBS`XMM5QU3z@$dKNVD=XW?u zM%AK$kRTM05pav7gjFs+mvVYANx(oz42Ywdy6w6OW{9pW8Ml7htv@R)ZEa3}95^!B zU^0p}`ITlce!=W?GmpFxJwArT?rM32B{ zHEeGfD`PvK&+7RAZPqX7DXorm(}~@sc1{N~b2#O_%Z!Xqz}JK>a^mCC+<|v)m2DLr zmU-1UN@ZuzuG-VCqN4|6ifU>tPlOZXhP03UvpUrlcs=<)hac;&Z>N3v{Ga2NaN*JE z70}jTwWg}_j-)Tbf$FVqE6=YV5$*W<=l9R=U%rUMDn|wyf^hRG8x*&hmbqdig}5TP zDjOh6XtITTqz;=lk%tKe_%I3UTr^S!gnx|0CyOmgwP3UsQYnZAMjvqEMw2xWt`m7` zaR7thog_e@&5y~SL2Hu4;FL+WaDnU~TR9KMT%Zl)o98D?z@3`S-&feFi3c@xZOEut98{64qdlO(E9dU9iJnJv7t~N6o`<@mm173FwL=>r!?y za}7knqzQPca(ZG>ak+3n6&>4N)?zm9Kcd0b%4Jhj@4!Jmd7fWETKciwavphXMGvE{ z4R`q{LvfNhq0cVBOX@WKMIoV-=k+Fj}8j|1~!*Wh@FgF zE>DS(tzpl5VxK01a^s#9F+H)Yu}K9epxrkKKdp0XP@WKJyvIwkQp+7isZ7neYCCj{ zva2uK{0p*$+xzX&m>BT4!gJpM}7qU|wqt`au z70=t67ifpa7T$e4@8H<`(U-_qZnmuq7}wDEob2w*y7lt;()A-Le^hOG{$w>u_k>SY z$8FA*3aZc4P3^|>z`MGDt? zWPfENR#r2C@{cDk*NGY@>wAxESX*$xd+W&YnuJ&XX>dE`dLAdKXYgGAiiCNZ5n#k^ zwIV_czQ}%1OZfz5r$HsLvb-_|)k=3cqxB;%NF0u{Y$2hFsK`-gF{Mx1^W_ETGiFvP zNMH0&{y4ARTX8`?k&8pWJPOtuq?oxEx~WYxwK)&=nzGSO_EmqQ73#dY;ODCtbf@T|5^~tx!ci%xHem0R1V~ez=+0eExp64(`7}62BX#V zJ%_PT(A-0{3u-Y`52G7hd5O(UnPv3{wtuNBO7bL23s`ejt|=u!J^tY`col@QN8scX1x;QujBKuU_nJ=IR zm`AaoPArMFYR+VmF~~!6*2O-*qclW3F+MZ9y2H&}#$4E>IBLhhwE8m&tM{vwdcu4k za{NoP6q~hlJ3MM=0eKX5%U3mbvvE@X_Av&?NO#663?wcuGF57*l*sU}4bn)yI@Nd8 zNVfY%!#cWM!dfr^tq< z@g!BJaCzr<>ZK|-K#+fNP#1@Oqn{QyzI1SXX){XBMEuz4z@(-fIJ}0wUy3eZS;gid zhrJeb&(UE2$Ryppk~gpi-3Y}){g5?KW>R75&PJNf?Gr>D{(}H3y~=*4pRXw@Lt>{O zX}L1fb0A9wS)dzx{6HQ(C%$XQ%605m^nua0y3eDE4iClKc(F#`XE6S`)*MZIm^+|a z&(7BkS(J{!%_66$M)5a#hfGhI7e9JG*5wvhU(l~tns(*=p&kw-#fTywREEl098e;S zt1Gmo04IHOKz*}0($~G1;wedK(R1;w0CqAq64#{gG-@%oGkeL{_B{}x!K)aZkoC8E zk9wZK2jPhDNNI6K89Tu^Ol}}P>eVSkZT@okWNy9nB?C@77K>{RYbqKiPM34Q`2oCLElLy`~>vY}&PYJG$ebVnT2N@tzG*2@O zzZQ$(sGNeO!=SziF7GRmMe%8uP+W<1DUJmfg&tR0D?tzHXh z*|+UutYVX@PVLSss`sx$=14Oiw!qkYxew<53@e^ZMv(n*h7+&v41ZD`DUcrm_RM<~ z?=eJ-2i&-Jw4_~I{f-DU7|zzsVaYA1cKYStNX@}6uA;)X01xA4u5R-og1UjHhp}RZ z=XNL8){i68RMYdC+4BpbcgnTV^UPv>CmZ!i^u&G_!(1cddAobm$Jb-)D;*QPQ7bII zZ_Z7#jr{lf9WsV}YrbM{38W5|n9mNF{^-(A8=f#ehn&Cp{?^U=pML$Kob{amjEz^% zT>>oLNwOu5E=H@JwtIwaEpyGVTL3w2y_DyH;Kwdp`a+}CJJ8uVA&VrWfCX_haxAgL za#T(b*6-vJWqf)B(lfQ6c5NFz6Y?isEvZ{VTyQWJXe=^9mUvc+AUoh9fdz)J`1U-qV-kO3CrBYglME6F=ULyj zkPi(8TWYB=C!mT9RM|tX)#i^G%qbimneu%)Ovawr=`o}`m+m^J;07Pu-q?R-?)fNo zY}+8UwzS{#ZNCy;!E{@?bhMPyBW15`nB{-^xBCaP0R>89Iu1MCGAK`uR#~P~of;D} zM5t;1M^%b@m4D-2{fEcFns5gTUX_)UAah^eIj?29PXDl5fT;TTYZ}2R<*5KkRh>7hM0a~m)yMBgi z56`oid2#)Ty;eVDkZkQWFV0@{e~JT7b53|74xI=5ggjDv@QK3=41p{=_=qax>4Jvy zUEkIs8p%Wk$bNJbKdw?vQd4>{5VzNZM8zk8wAxEC8!*q7xkl<}>mYwVVT7mneA-y< z@!N*L;g(=p{$NYv)X~9_$^e7WNqutuRNP2VYHr)pmw5oDccL*o-c6}B`a~ik$gg3b z4EVr}+qW@~i`0vc*PB&pdRP*yWuYZ5&%Lp0g4Y5t!8Tn}1jdIXIpQf{3^Ho~Al-E7 z!$@cntC&Pm7}O)%xsvBbkiE;f*(1nqa8n(!l{lE+ASx6qwJxh8=U){Suc|}V-xNbv zAai=W7M6Pwe`Jua9GhE8dt7OTdd*bu_vF=6<0Rb%XM#`Wn`mvz4sl0RQTUo7v z>yrEuiT#(3S)^mu6R=S)Gzp9!KG3pd5l?dvRQ_Ow+HO#S_L6F^B_Kd%NilhHk|;K) z_A`0=!i+r8O`&^fxMi)rXYG7{N5hUh%yc5Ve@(m=^b+;j^E=xu6b>})^*hy?(AwGg ztw1}OBpF4QC9s%2WH~x;D3X;wy(B{*7qbeLQX59Qun$YhUdUYT(lEN=#f~WBC+S{3 zrYq-J#_A#)-Czb^3pVPBH+on`XPxJ(dV^bpEHZwu|9hWzNMxcxcfT&yn6_G;zPEpjQ1Y<4U$xua10WlZ zF%)@|`!@UiT)ps>gSU;BzDpW6G#&Rs~57J!gO4aPk z`BgH$f2T2qwu?RcgmFU(<<%!!s8~<*o9x382s<5e#+Z$x6gjP&b`W3l13ew%IY#wlMbTbAknK$;MRvMX$HZI{A~D zu@C)tMiiwS5=c)%Q}(2nT__|Yl>0Fk0oCUIh@+I%MYkE*Jk+^Xv6* z(<#_{d61*3;aP*axAGoCi?uh+8A`6W{VDo5a9Xq*)`Dwz-D1{(TSDeSAEkEQxSG!e zkhOs6iUqP6s7pE`yFsxS>_^s8EV^?tbzKY)AhKkt#>8$c-9>g<5otA`GDwr%XK8cb zrp=MG9tzL5`Y?jw^Hd<63nKh5yQT$_^NSe`4NMU8!zvEnNmA5oyWe^SDi zut7#{@ZJf}vUfmSYOYeC_l}D^`-*u-5rA4G^x} zYDG5MrjRhT!#Q2$hXh($w}fuwrjXu=1fgrY(bIDus80l*{ORUL8J~i)5#+zSi<8gO z(Ta(fBCDN_3ob6_<8D|4+FIl8-mv1|Fy6JP6~I-zRutP>`8{qo-Up%pTyU^sZt}yv zNaut)_FH%NTPadneo5Irw2pXmD`H>TU9aaiPa^n@jWJ>K;WkT8{pX&@y^VPg5vROu zEEG|J-rza|tW#_kWZ0rrM3tvS zbC{)&4zU@4@GdwgGFSR@ihfkBMdkoc`5?Ah>ND$%g4-EqZ$CJ?>@wyl8^oIy#G*cE z-g0_`8hoTu-2DZ&ERQMGPIdK9HBlJ!kWJVaZUiK8@i7iN)3Y0;bb6&m=%`s<@&@hK=P$#fte}%pzfATZBML`G>X`( zGDw$eV8{*f5}%V~N9fXnfE1T5!zC#rKr$mFnOKmvWkNlV7kxG$BeaVtEd#B|b8SGkIV7n*68jBM zpq~CWbQ12#$d6Mx;M(wg5v`GeRplT`gd`M(Z;S!m-r*s8g&LlZSD;}PYPqIgd2ODI z$z)fPAG}+dd}A(1GW`zoxmcEB5&;U7z>uG&%gmCkSahOmj&cJaGfl4&k)*Tj#Wsoz z7NUXvg%I!^sC?uIPkDr{N`x4%lbC6u+_Pr@V=M$$OOnhW%TCZ$k`O2>hO(kd-F3b> zkBLa4Xwyhi4R`AQaT?zPKX>ja?ctqgffa{>E@$_BM=ol%CzStCG(ZLMzG)Pd{#mn& zFNWJWyx4R9g}Q0;r38F>T*Vmqli`7p^DbDO0c)QDpLpKtPKE>PqQiR3^9IOtT|i8S zOS<=rw^7-UpwkL5)4 zW*Pj6)6ake&|NGOye&h3{h1J@4Zd+PUo+Ol(wI-2)icS+~DaMizx4n#Ow24Lmow40J6NoR7MQgB@L+cR3%T=Q)Gka zH%l166Tz0;9L+0WOCKhJn4`MRGsos^a~0{YlcaiqM^EU8Z1DF(AbVmC4l3r`55>CI zU2`1Y;cKD2{=C%uX7Ltxk{RQ6M#VgSy0>h<$5~BszM_43?9K{(|K$HK>xmKXd(O%^ zY4T3Rfn67!889V>$^`#Q9%X8WyBgyH+jcp->XH|ryX7_8PjNCgp}}oB7SyMc3yGmO z4@|c1zE^!X{PvOg;VQ?P2(H}=i`oF#{!>i|J5yJW+kq{OOw;k5IICo6Cvl2E2yn16>Go3ID~yg*@lDCpI>0AMgE)McEj*%U)dqZ8^^SY7>_g#_cCCX zO>%tM>Z;5*6~i%sJ0{$dOU_f&XzKS;?7#B*!{x5=utR0T>Bv^+$tydb+KrmNS-&}x zgwNUWD*4T)+w-OOKHVE1Gs?mKrC-Y1{x_tF={oB0zCOf{^!Y3tyK{e`ce>Lh)yRy5 zrixC_*{Cz|S)mJOhZabSIevW!N)m`&=-XA;S`17MhxuZhr+93(u|PY4%U~R+-m6s| zZ8{3bMGpS2@6~hm(pk&{LR+C(>3?|T1<7AcYzqywOC|dmv)g5rfs_}OX?^}NwbAv| zrW#7BK)24!!Jrv!QBHO*(vMe#6ot-WE}i{-h;>6kErAGjLO>Knj$4D~Bs|kSwh?Zz z#gqI&W4X)#bz1@g#p+0#pkPD&V)L5OX;mDt!jMYE<#^oXfLm)J5I-u&w?_ae{6ms*5cSiA)aOm!K^CGdU z?m?EUR3-{Q`>oa>)UYY@rs-yrqif#LYJqj*m95sd)_hay1J8f1Y}>xMw(Cd{02Lp< z_cxD59b^vMN4He$1+~7WzbaP`T7-H}AkkxXRa{!?;X~6rgL_kolx2=(qgS&em3ywU zIi)l4%1F?>mz?q-Pr_>ps1~&cyd2+}IuYUCiLp@?XI96Bj6&N+P;o6l~dFQD_qLdbmj&K!#V5I*Ex?=E-(`>N$ z`8Z!a@@r{L-;(v0%*k_+o7ZaYFUIjs%&YJFHD2>z^VXM>U(fyXuLe+Tg9l;7#;c6D zE%)?gUAN?kLKEBqishN#m|s?)+})&7I^sf?NrSld3ZzfZ)@WlJ9pvq_R8v?k_vr$G z#G`20M9y;Z$Zt^{{4^aBl-RF)@K=FVcdo&1P%}NwI9DU1@sv6t_g!uIuq7v|Zqt(Q zbh#Y7uSr=v9K%qLd~^ZDA+b#|bt-M-XUa!tw#xI91k44 zTXCnqPx-HWu6uTbnVgO%LCMD%6MF%^*Us0G8x+#yQk-}^pSSvBhr^U`Gr39qe5B9u z<9#|+=}o%lr>K{L9=6zQcKBc2_g8+m*~vr-j82ubaKicPZ-JchC&dY)+DbEa9>&xD zh@*BC>HF<6yPx1;kwVJ0^9~;R(|F0FV+?8U1P|kJj%>iK{j~ETWYvRF{mOH#GnoVl ztqg(8Q4w!m>ONf@NQge8H-=ZL5s>wLCZQTS_eS@#`-$U1h--I0Rmd8WYo|X{8M`SV zHwvosqe2rE8S*lOeoYb%?t%kBSp=|51h8y(wqa4%_SccodiN4T75$UPem!}v{1!~d zBdvEaH4gg0F^V`aVq_!p?npEK{+hS?`Bk)MmPGz3dSlM*Rf7_%EVytL zB+Xle&HjeS5&?)))JJjj!L0v>O%VO$M>zE!2*chim)-v2=s{ycMF_rh0{Q|*A} zV3eT0frMD1KANu}Gt=6&kKU)lV>A3E9RixcR}+S;{-Vzwz{QwD9UoauMFC?u%OdCs z`<@-kt`;(x0kRqM@?x{k7j(oE2N$&nAsIMjv4|LkR}Pz( zMn|D6c)(y3>g8wfS5ui6#23LbRdW+Ent)t2{Rp;E0nIO#Efx~;LR%T|>3M8@lv>O@ z_CXXRt5HFkZaD%LYo)4AOHy8EUp3RAoKHY&G)fYLrSmqtqBXFMaIGfG9op)WsPAF( z@}^`(T#1S#9z_{YFOL?}nToBAD)lYueH^%ua|%XRy3J94fKyM3QcDFC^Oi=lc(VO? zY;v?TjRYy8qsyZdgBlS@+8j+)^TAiX4&x&TxI2vPR6)eMrXYLq5i?5@pA6F&j4RHPq0-~kUf zs0)|H4b}4i3l2IXF;c(*U-3hr=cO_7a0^+D*1eSr+pi4`VrME7FQBjb3zV7(^_G%7xSs+yp zU?1QF7hI(MIM@sU&=7|jBpIH)g8YV?%^(>b5lUJV-+tddZ@FVBZO7Wp9iP7M_-g6Andbbw;{Uih^LHr!_kZ8BF9!G6_hu~F z*Q}9dkbN1Vglb5l?S)d5G{a!*V+|=o$kKukSsFr;G_+XLkfbbGS}5|F_fOyB`2Gd= zEXVUcuIqX}uJc44T9$jKPx|`(HJq^HSt8@*zsrw^`8EVEJtw1eKuk_wntzkj#|BRF zZ+JYh3ZA|;L_WE*-N4f-mo!l^jm!t+#6*r3PNTG57OG63LSpOqB(Ll#^Spkh))jpm;Hwm}b8N1h6bDbx=#>S1D6zJdy z@NaB(H|qYP;V#bLHgP;MhMSQ1q!LcJc3~GBh52L z2i=W?20XAGJmC(GKtB!3qYASTUN3lue^Y&y*tmMCKpR1zp6YkiNC18xt@QxS0dP%h zY%-O9ScJMc9!p-NRiooSBaUx2p53u0eLoA8{~JO5#E}0GhV>)v8Yb@Yo0eJ7M^yL& z8;1NZFY${fmPlR@;)O$L;@SQ{z_jpL1l}<3#6F3@9rg)vJ9*O!!WG1291Ryq1S|{| zggA$?GEUx{7Kr4XFw5EVg)L1z6ci#+4gydc@;HNv$)W={c_&W%Izi-!mAT+5Akgmg zU{NZNH4QJMxkPn#O0m1s?}#-KU@t;t#>Mb$BMuqInHC=85q+sZm&i&JAU7$L zUC+nsJ^)^%Oa7xSO8pESp?n)m@Q9dkSI-^H=eb`l^(bd!_>tjVjTpHbs)Jstln7Ny z?x59SRjJ>{RDXNyv;$sOz5H}=Up>8Q`qpX+AfAEkmP0+8$%esltQ)0uMU7HF(GeC75u6 zEN~WfDMY}4aGg#lFKv*^`Hl)F?ZNX3Ta{2``8-&MAZB;prGZB|DCkt z`fbNYGO8-rXTPL+JsWo=BBF+!QbW63!xQMrPkzyy`f4LJF*fqE8+Ax3O7Ok;Dd-Ui~{VUmp*0p>WP#ykL9BF0}~a)Lm$#>8-5*+d#pzAO^p9}co}PITo71Ci%1 z<+-yYy$c|Qn-_Fi5NmA7e{ASK0Q!#x?|1#SQG;j;6#&^{kwggwNz4-ktsFBjFDV>L zlytp|sV;yM0DLti_A$-M0h>G~{jMxB+(`0Vg;eB2Q#I;kwT{sXS4UKLzO|%nZx%y* zXK_1>d~^>sdRswJOl{p#0fj*{cVOgRYB% z%O$rq)df~cTGAKCmn)nK7YbVn?0miroJahJTN;n5@e+h+82Rk5!9h;=Q<;NL+2Ojm zgK9>%H4o#m9Cc1JC&@^kmQmA(KYy~l2nw73VUyVawcx1~@C{3$ zlrInE$PA15R?6HQVpMlfp~G3}9kI(p2CZ*3{dou<~~JBy20642M$Cg=+()2xcGhK}5PG~!$T!ThV# zxu@PYJM3NfHHAhP*EZ>a&d1jFRh`G57KR2Pi7@h`|i zqWE};^dLk*r}IZeiF{;<{#D3m{>j@KKa>J1G)@7cTz6z&Y7y6 zzrA5w?YYZemM5O7r#+3DY+p3*d-t+kIQsEbU#!e0-vo#>wo_pTERi0jVUCqb-~M7O z)nahdU#6QNd;X5(lg^dOww@Pl1Fz)RUUDwpTLT4W$`l2mTAXq*cB%qLNfW3f@CH|l zD!lv4|Fo6=i!S#({TkEG72M|Hk5*i{D&TQZC;%cCP;%_be=>th$Sfis+b%eJM~pfo zmIYD$4<^T%Hc`3p%4Pel`@Z8uJoSd=yG>l8(yLSh4lFnpcJ>y`f-n+t^j~CqzTwvq z`o7WlYoqQVqiNftnfu0akB)s@5xlWIR@@#Lb#1(=ef<8uR7SNbpZHhNTCqo5$Uxjj z*9&LpMKOGQ>@Py-*VwzU_75NA%MKkKhyD6c;DkF*s5_-NvU6tpeZ;kqhua?^e2P&F z57WUD{Kvyvo()j!RK0Q0=rKldB>ehJnA6C#(T(n}`#u@Pd`g-*{<-~~Sxj;V@A$&j zC((bi?v|guVm=?~`1~JqQHTbwH<=CTm^;^ze4X}GfipX@HJ2INP@wbrWcyfB$9&rD zd28*VT!o4s(O(fq-xkHZHq-ug;ajWJt44hT6yFaJ!(M3rx6o<1*b}q(qGR#Zzr`WT zrFSt)V;xH${w+;gE`N?${@Ss;^ly39^83%JSpF!_W4ZC#`3eor_vh6sf;%ht{j1{F zSEZk>%I~ZacdcEkt#kS|sLwZc-Rd*CJ}f~A#avq_?{8O|fbLXHRmh!tZoU7f*Y%%A zp8h<#^V5I-uann*h3x+^UGpPs|L=(6*Dj9P$zLI$fe;p=w+wbB=5`}p#m7wb*UNsMLGb zlO|_=WeaUkW`_>@xA;}L*F8lLBfb_qtQcooVBog3F$A@b7c|(<-BLeT#x1egA7mO9 zl9CnvZOww)C)y>fu1X*gR^y&0@!^Jn!Q@ga1e=^vxG%-{{?2&g*@-9D1WX=Gwp?5o zZ%;9KIMp6KecDq|c|MCH;Hx){x#%A+%X@p&0Duq0F=Po_`jJq3p_>JJw(yU>tS5{ua=R@AH^Q83NTS6oTsds3X zfys5TKX+z zwVQ7HFNPz*^lst-^-W^H@Gjr{H9Lh1ej;}2fjMeoJ8(xr7fI+%&L=cX;3TC}#Y~FT zsX$6Vc0;aT%(7Jv#d$N;6qi?@?Ggr)f(lPRcoB5-d)sqo9T3EowhY-uMhYPrYH91%oMfRE>)~^`fCgwPW~q z5m5~W&jD?*E*k~aiz4Iy;rvQV7@oaH#xjLxdu?P+t%>nv4L}_#p#)R%S)p``j!u<1 zPpT<%T}wXKG=Bc&xyMs6<~Pn>$j3kug)MlhY?RJ48fvgP?twT(61ZP%GC;qR9!1ie z*_CdC?Yw*5lJX6P11I55mY+il>SMBa{yPd`vvoa>q#T={H-;VJz_a)*Jws_w8{R27 zyhIEjhAn1(-sL>YLdwN2hV?3FR#<2?@BKb-;kD%suHmTkB%m$l%N%m7I&P>>prQVS zIv|A!D+h?e8aW!Ess&9nM|!2U(>ve;Ph8kCO(pcEu-IBpCupk3=(64*5zQ$go;zA-sy`<)<}d_)?y>pz<8xY(xH#m{-i)1&4JA6I1tJeM#A0MVe#&e0})*eCJ}r$MmbqPreUc{oY_#@kj3A<74KF^>6+?fj9jf zj9wqy^L`MdnoZF}wI zm%%vDs*JODb>;hObIdQ8|C8dC|7guuk8bDCp5nkzI_@kRwhP^fb_|UbyT?Z8j<(SN zfVc@qzyScz0suI`fk{F6O(x%NBxhgC?uq>i4r1qSi?5n%; zJcD4JEay;P_99#DU^N_rq!s4so#-!ecvSJ~rs;)mlP@0KeO*l27vT5?JjT6apRIAU zzoF{QUCJHDv?q6O-OC0>YD4XXuhy8^{Vypu<(^V8w##%&8weG%7Nh0FoCr(Wybzu z*L}Y;=vMUtD1gw+^uro@C;U)f$Q;dpP#hp#8xOj>cQ`h!F+oXEo5@Y4KrA|W9kFD!1MHj|{5*8@9$ zTshvJEL?^bN!s1d#}qps^_YzQAEr23qvs$P+0gS?EXj0tm9nc7n3F~}JNvlo015zv z3^ID8+==O|I*@kVuffj2$TeiHK=oD_H@S((|I~R;%7sEg*mMiz z;W;Z=Jq`yJD$xMRv~ld_#QPK)sukuO^2rQGK!$up2i&{6?Ln@(T%@Fs;oYh$M%c`1 zpsxT-#C7hB<1ctLP&zN)Gd}sHO7Rfz-BfM1<*a6H$?~`Aa>|E4ofz57Qxzo% zLJUshh>*=v(@ie{+U+Uh&$}PF@1ria%w=8mE&Fz8c2Z)cN%OyBfstkp!%qG=TqPBN z{?Q}3J>`^F=pf=pkwL3!g$Ch8#QeL^$KNWpIFGijcmpCiy%MCrdpCQ;lcrZmzLAr& zJ$G}hG6mKCelBYJ%pw(aN`Ji|h$)1!_K+7HY^G54O&0G6@t*6-Hlklf&U1vS3Sd42 z-KaDY_x;-!hxwe?WU}Z9!!(lY$_flTi~T{rExe?~x_zTfi>2h0`nQ2g@~Y$Rsgm2K zJhhP8A(;qYI92`Y;-*7^^i}PPWoyy)^n(ti{ijali(jyF*V5L7lE?|))E={lz{Wfb_}Nn)kVB3;TmjikKOhLa z!Kv)YLLxCHq&?C^*!UI6obzIV3cvKQhcnVE%?X!yyuWgkT*R2EJZp5k>{3FYJ_M zre7^nk}s`6OG8zyfQIzFt1uEy`;DN8)cHM&C(sq}`U8xj>69b@a?RM-d>SZ zl&JmP2dAX>+Utq4&$uam871tCEEN~?SM1*{ZBO49u9(3HRK(QVn^{$$sU&OLsklDm z5eVQ;V2VzOW?HgJ7=_R-aVLj?eC9MDe=t^r!G;UUFbW2`?IjNyxTM(A4|+5Q8S6*9 zqEnL(0W7F!aKx+Kf!Sf7XT^+-p20sir-i+A|3aR^0K2uww?^;Hh1GL*sv-;D+?;-^ zB+^8KItrc$M;}0b2C<6UW@5k}QF|-=6>hS}k5Y+OYPKfTL+J)N;Y7@vc;*2Q;Yc=2 zK3F`{lfn`MsFx)CMVN~20l!8)xRBB z;UQ$)t4ZOGtfHx$y|&`jg5Fr5#5hc<2dE+?>x2E7jror1hsaihA^|W^I?a2~+Hk(* zK^Oy`9-Ob_N_xi-8z$~VSCRiX;!CdlG|)PjcH@-8{nU&f5tpOnsWPeb&{y6$-q+;2R8PXMh5YV7^SLpLXQENDUT&Q%{AxB{i z9z>|kxB;+V6uq|gQR=T$3~bC=3(QRLWX?puTOe5wt`)$XiH=f>SLzOJv}mgY_XQ1H zx!?T^E)ZBEklAf5v+;?w!6w)OfVhx5uQ;$}XCPDpO%wSWclR^!>}-GMo2EUF7iz02 zuXJ?s_e%W<=v0t>D&ye+{#$vPJNf7P1$K`b4 zmbkeEIKjSaYCsIuIPq*CM?&I?Or@I}52wx_V$@Eu? znOf6h+y~4(ZkN8r0`>&}dJ@EWSoJE8zQmST%L97LLEqs%T2wO5zV*a~)~iZRwWk`E zlCpx%PhhgpFp=8r<(R*%16-lVwwk5P-GU`~02>ZuvE%8cZ*+Gy60Nt$tJi(EW&-e$ zoOtihIU4nXO(YCZ=!lDp#(q-Uaog;gxxcz@87Oq&RV*nS19$->lqbO+4_{*t&-#8Q z2|HuY65{zo-*R$Ba&Pfcct+|$!roA8c`>qd>^;a=K+5WFVdz@f)ei(iHl6>0p-NJ8 zWIzciQMNuI!c_6;@!}W5H^80@3t6PD4?xZdm2VcF#T>BjeBY{YIY-4H-Z5Mm>rFS&Sx)6c@NEs+Qyhn#gzu53M%vhA36K5I9TPAE1zB9TvuH&X8W0eHjE zm0U)#X0cxoK-y8R)Mt%acMA=IFNhwFK6JS*WgP%e080yFol3~i@>JDWm=`Hlfp;Ta-J2QXriVG& z2o}-6R6SZ{E$qr}m>Dk?g^$5Zql8T*QjEc9RnVHPD>mn0&4!vCzHDTw(f|OOD|oy4 z;}WZoeR|+N(pi*0Og>)(D#c&3g@Je|f(X$HWl;E9WHrzQ4bZ^DCAJ`u#juu=uv&p# zYml$B12uT3t(p@|W8>xBVaBxhTO(28tA++7%gaF$3v-~^3QSrwL7#RB;4m-kFeUbT zgA)>GGDeSRhQbWEQM-7F;+-*Ye|XGq@jG7EVbjdqN~y!M*Y0lk>6(J4BJqhl48lLg zk}e3a_@zAJRAj>OdGKL#auPX-Gw;`}Dy*!A|APXaqX8}e_)Cf3R0W3!=vYF^88(=4 z7p!4jcvdO-0q^{Qd8iA7n1a_~Ly;5wC0Ak`K;l0aYQ~0sK#B{o@$bR(jr#k5(ryKGq{WvY5t^a!r_EAhqo~`x zEJd>{p_21(A|E{j8tgImPLxWD^G~yfX&q!LAITPof|>15ql{a!Eyl7fH?v97IaX#l zHb-)7s|d<^8Fno>&R+=)qd64m+<;6?k0ZHT)00!ofw1F>#qm z!qd3#H}Xz4AsBZvWH$^Kkb;j#uISTYnyeV07VXBtDbWg`o$2!K=>R)@`S8{E0HTo# zzGcM%H0&9cK4Z znp3VSKyJc1li(%kpY()+IM*@$0(i2JJAIp4SEtT5QdQ7F#yHr>dUW}9fFako56LvY$SxO5(!@7A|06Vk*o_x zxX9oy2!IO<;v(Bsi)oDgN-f8idJh*p77=?7HD+b$atw6Jvn9w-g9|XP3#T->NJoHX z7zOo4X&X?W*r6!(0#N8QC_nFErvj!1!%v{S?yHrqtArT^rvsru3CvqY5HBlUo}_*@ zq9jMM4t|UTb#nmKc+g`S<*yHvpFIuQv5tG{oi_F_SEQGsOZH0NDgO`a8=wK6Kb;7Z z78~GU?yKHWBH!w#WVY_m3RS|&uK5H-coSk+sq%Qt+bHl_)YtUAOax>H_ysL#g5=IFNSnG6x5BXY8%R*8cHpNLIh31nREeZOJs%2V-hO z;SB}1WIDZSY4kJ3?3eFvz=^mt2QX8QElfn;X?Z9?#DyFZ_@0;upMGeVN$ldJ!KZ6Q ziMVqtDCJ%8<=P_gBO-Vvn8HS+vT>h)2T1bW>2ac-q{y~ajW6ZFPqBcWA*clbW=c9+ zhyl1eFYtEa5cq29Yg1?i7Eo_wOJp((YcEMaZgnTrLctB3^TRBsRKkk?Gkz?A^op=;>i&r+fgt<6|tfmY^);zJF$QlMWTfClHTN@fc@S;}|?`nLy?>g3$87t~%wc=76=(fupX=wdGN zb~Aq43>;u1>b${7R!|8VFlSL?S^O71{={W|Ql=1xKa3$4n$D&8PJ_??(9@93ibGdkqJb5)vKaDxn7=?j z5Ayp+hnjWGXBn9%FI(G6IuMW>cdp_aDGY;3Ty5w5CQ~qD^O|I!CG)dGHEJq4)9 zQ)7jCMW6}ys%)!dMU7M}i`viXA#e2vWkzo1LN6ubDe*80>8$Mv^c+xvaLxgGcBeRumPTKdaG38EkAh!C_a^Vi;Z;G{DJg+LvO{U*^|efm6I0-OmRJ-J9%xu+{&p)2TL9RhO3m)M7sY zXy{)&{AS&wt(V(}UiN5$ys=OkH@(8lZm<$m3g)b>}@(Y9*cV3qjD6 zEl_!G$8hTI)Ab?Kej=xzh{Qxf&-e_g8VoL`NUluC$7F>%}f#(FFN3^q2yDQttG+Tk5+ybw-)Lq#(>JSXSzMby*3^b;^fS-nG>>H`j#$UPS>31Kh!aq~( zqE}xXwsfqEXax-}LqiUUr=z~+4bbzb#a#8KJlM6sKtfB z6UAI=&p$Bk!4e^@p=e_+<1?CUWCOoS-wjfwCrFapYs22r;RI7%-(>eDC&MtHnI0)yz zfn`4Jpgp9}Aje!6eWfd%-M>|q7-qIS(k~gn{lns1K?)W2T4>3@b*XX{lHG4Wl)j!Z zg*OO>cNAR^#~^rGa8sb)fDRMiyq#ysedE%!m?e{DwXD@&TKwQ<&Nkj(@{(QS`Ld%c zDfuggD_{M;JU4KMU1?^rg|w|DTW?vu%=T$T^R=kstL|PgyLZHtUk?tFOItd9mRO{9 zkrtnweKNcYpq~12Msomc+V;2NTHTP}(xr7%;nW~az2O*{SKA)y`+ty8X1@(|>WB*0 zL!sA{e>lIE7Pga9T{+XGE*HOoYP-6w>makgN6g7BXT(*`RkuiX1>j9?=TEJg^c(;m&PlmQR1L2Z?p*SaB|$wqzRTe+l?iVCZkbRbkLT?` zz0a&dr7j&r9Q2bH^?C9*Wb8W zIp;#7bEk8NpXLT{83ChA2>W@bjHQF(+ZPx7g(L;sCM$>TAo*F@*xf&faY*2ni?EER z%%Mf^`je-!YDd4hb*X5)>WG&;yzKWRV$U4O{zT2ujw|<yfNR$!`vZ`Fkm; z1C?t2pW^L1a3L0C6wGto=z})c)AiLdxhDFGNU_J!hn_jPFLUuoTMuq1MqfGw<YFqly3o8WPNlZ<@Li;cF2g1bd^ z0iab8#g)JUZsX`jcv&A9$^TxvZD01o@A+_=c)~xdTqd|2T>Q)O9exxxLv+_B1QbD-~Eew$m5Jf%Dfu9N%Z z8DCh(Nw9bcb@v1BX=Gp{_8OZzeJwqXwXM>vYPOe&ZZd}2pyQx*j(xiDI)k8wRYIE6 zO#-~rqDNa99(e+d{0`7$6yY+8k@kZ10L@4-5aH5Eb_(VHwuomEf(|~SEhF&V%y7dU zJ(Y_RFTe}R3~a%@K4b5CA$}p2g42)Fa|U-`YW_~_%qIf*b!PGGcuNdDUi#42XNv9n@e0& zd^rwlt!^!xuIG@lNV*0DAKfcHjNIeAPPB^@x9Wl;EC|Xd}9Cc!jKgA|>3@lSn&Jk3nwk`&QaAj{OzQO z4b1kIgQ{8GQqu$FtoQeRH2_SFP=dE-0w3ASkul0dXg^&G5cSh4HmQMNLdqWe9+Wenzy%bFlb)csn zTpXaH#UHp{F>4Eucs$w@hEHmevI@XvnD*%QhNVZeeY&aK)cwg_KO^2EP*Jjl_^G^h zIA$Bt`95H_MP&DqgPkoL)O{(%1oy%z6)oL;R*yym>?x@>#V=8}7YQjQA|?Rv3nvs6Td z@}%ofP+@M3)(MBpPe==2=g9m4)5?|cw|8xS-ck>A1!$}^E$4`PC-dv!Wx1myjxP${kB~+Z~3K<1P~>2ka$6d+{o@Y&A!{Sg^8oc_;U5 zImWi%K0la}5I~!l7XF^5YRljEn1smJaBXdx^q=|m)}04T6D+LPG1cm2vhrcQd*LOd zMkHZDRVYdd}crDNpSZx>hvP*yp+vra}g2Tah5)D{YBYf zTqLVKpn+J!2J2qV49C&BR3;*=!bwL9^b`YS`!`DUv`dTQqOF(6iB~7BPb8$C(Ifgg zGY!N>L1$uj-ee)u6apr()_03w>f+D_I?KTxHuSW|)_O-3Q*&DODzPs1X&{D7J%dTh z#i;fpp*(1``D_usAOk}Q)lJlb0zux4=B2Kr2BpB0S|OWL=HU!Cg`GhB162#V({%=O zlbt`YA;C6q2oP`&GJ-LKs?I%%3dRoog4{-N0NU7{*hyaGJfQDelQXm5z z=p0f+xQ1}6K;e*9!bW~yY%cCC69pp+UqlzLJjEDxie3~vT9e8SWuVLwa)y!?s?o2b z=wkMe22(m`9Bt;r)CxAc0gyqPPNH%bkMr2$PD)Nxg3&zC_L7-pj&3LB8S_+u6|+Pt z#FQ!|JBrmOp>2GU2#i|AB8*!;!ocQPomzVVo3?{LEt31ElgUiT`I^wX&deQ)H)j#k z@}C$QreGGBP9#R09_ljp)}hfjrdz0k5$o2Pol2G@pTc04G#>3GI;AZkHUKg zHl)s)p>wmC=FRG&1u06kusu?EJgzs_`x%RaJ^;UYgw-DWwzq|nszlj!s8bY;%grWB z#`n=flm%qDP3M%;tT=J|nJ@t=5F)V8<;3&1TExxc>N>x2}O7Y7^|%prZx`o=gJyT_V#^ixNM8J@BrZ9TcR?<4a<4AQrIgYM{yS3Za#s`Ur@p^5f!NpO3> z``+zty|+I1#W&z#U33kc#D1EicmeF#O6u1ZM%FhVKOs>?WAU{edq|iw~8(~N)xTzt3cfS{YeCutUim7bIq;m_YUm~RcjaI$K3Ht0`tkQz<`+EY} zIp_&b<~u($jO}tO%kh0RcITq0)RkF1iCUNmoEB^<^hPTU7*CMbBdo7muPZ)Ox-+O@ z&RqMGG3BRwi_3S7K|Z|IljK2s7N5M#6r_w6Z|0XAHf1!1IlKHd!1@-JPY?dRC(zlN z<^rVwUERSp&*N9DwkGQ$!}aAhR3}z2nHK2yIxA>A7o8@6-qO7=kZN{ERAwF$oWm9R zNy+cSZ>}Z1-J)~=-698u3OQ|YYDn)H+$O;hVJS20Aq^==&^aSG%nJFWp(DcZ? zoKL@GD=^Xh1h0oO+`SC$fl2W7FsE%wR_NbWH?t%aIA^bX^x=Pw=IAsq^H8m|FS`aDnqNp`Z{93E2iYF{A zJGQ03s=(bTOwdP)-b;5MVY3#SS#cY{+(kiIW{!~FYpb80E9imvd{N^P_koq9QkuNn zEx{gimK>$iE#AxF0=hF?Gfl9bhj@-6 z3=nXbil7|Lk?mc|~ZM)&2agAxfHgB#)7XD@6 z^IiD)k2i5t(LX_w8tZo+Y}||F_oL~ zSvbNp@dD?_tyg2WevaKn_}msBFW#3JD3uUMLf+ZOWUGu98~K!78^4n~URgd~)i_?= zGhXv<{NCsB`|o^S0Tce{i8}F#dXN zy~JMB{z6`knRI==#9{iOv3Ze;Rri{Mli}@t>-Jj3boAIOrd-`ofTon({NY2-hpEpW zc0T_6z(Y(;i%-p{Onv%*FLpl$uwoDYY&77}Wz_mc-qqKTVSlLw?KUDXd2w zrgn;~nukK&RBogrbM!bg2BR$n(J~UWyZ9!~Tlm8TYJD@^v$Aj1`y+#tqiaw7kc(E) zdm*Fm;NcOw@!sDJ$YwAA})!kjPnTwaRcgFeK+bk@m~ykIKBl*h=AlgXP&1srBVKj_V2a%&ZK)|v4k zv^UAT)C5*Nb3Wdr1>F^P7&an%wLg%F)Aku?e)H zEXA*YIh)E95!?P`bKZcnLa$~WmoK>SwFfPnKig}e>#PHgZz6tbroA7dPpHGNqw!wz zo~8a=3q2_J7P`xQ*W4%qQ2Qiy4LJB9o%)PGSt(9$O`UK;+YjGVb(CftmkJ4Kl>$zL|C$a%7&{7=Fp~h+lypNstNmV%k$7ejR8m=$VE9 zG9m^{=i_n$p_&R`zJaKPgUCXsv|uTsH>>$3^X*5jqc*Q8jTXD}W@!JV(S)gI?DNm! ze~?D$TR@i72O2Wt5xpE$lK*=~px6`|KSsZN4Kw1Ex;4W*xUKzhrT1oXrBsJi{Kn^_ zhO~d;A^%vZ+2LuTm1Lfycs?tHEq!uKjd9!cKD7WxV*zcCq`=Vo&-(2@W0K_w^$e0rNT2+qC%e3PNs04kak$9ZGxHvB=fQ5dOu~ zTSGXNWMgA6w$#1N%(FQa=p(a9@@n)7iKU5zlrQ0s!Ye8}0BCZb){zPQoJgr+Dwh4^ z2pDhX%LHT9#zHcfVuzyWAtFdhBq$e|EyIRhuIaiz29Yy88b1p0de8jQyR=@B^lS_J zrn}&NAB6!Nb>B?#@M3BPitgHQ1^^?AA%V7e5op-`AuoL)6^LWv9EXQ%;O1R1PW61`qkVgi3;~r-cn2=HWxgW-1H-jN_(U9QJ)yMCnpA$@h zKB!s}U8a^Em@O8k=fpT8CIJK|qw)4ryDvIub_Ag%K(*EEDYn`wBQ)os{X&B2km%j; za{JX=eIJw1ba8K}rn&s0EAtUOsf0Vg2!-#+=|PB0aZ&cE^bLrTcWmF2tOnx+jmH;m zH?J}Ez86YSuURr3)!QCZ&ZUA0WRyw}kuLiim}y(LeH{Mg9t3M<$!STyVR|T`Qf#;> zRjC%K9lREqcP_aWViN)<2VJzYi^!mK;{d3QrS@DZO&>{fa$}k^gAxfKTI}|#mUgWT zhJ`EIZ{u}Bd^z6KJDrxW+1a9SEmhZ@>G=J1Jhz>+{|hBkJt-L8>-_WF4W=9|Zhs#{ zYjA!0(diPij#p#x)}}(f-YT511FqBrTN<=0Y$~of0}NsC*ZRCe+mCY(%vH8CD&vhQ zzduPIh|2$KQo7|Dj>?{2~cIsb2GyRkPwIsE;x-*!d za@tBl3gtd}Er@yT^uO=L0(cUFQ8}96ok$xI6z9eyt#l`F3T>e~8@efO$I%;KGKyq( zN#5AmHUaO$(Et=Bq7}SC=we`nziF5X(R5Gkm+-h3ysFrnDq|A9IKQgY$5OP*(h6Bq z?$6OUTz~fKn#w@F_`$P=2eW#5v=CPTn&JvNnb9AJolP1-4wX6HFgW+^hx*$}kGmfC zPruU`j@R`rGR1#dz=#<*=T|~#2U72$d~1(N-RXJ%&=BYY2!|h}wy6fM+`7q47^A1b z=R);YY#nyQ%;0PM=>vmf1>MJOE@`5o=^@+4mKHbn%yUcavUSe=`Oz;4Y|N>Q1`sBi zfV12R`BCc9OYCuhoV367=NbBQ!z+ZirZf404uprVMj{SPRsKIr@xiBb)AHYZOmWJH zntagNxGyb_{`>xK-`4++Dc(!>TZT zy-TPKeUpP1fXraTp+*5#?5gS~8Z{G$gDIr9=x%3e)d(}LaR+PtCHds2K4{p&^mNq& za4IY#5AwmGyZ870)oK`WJef`E06k&nDxn~$4r6A$R0r?^SU5MSA6Vd_vN`xqNSx?%zj0?;s{ebFaN@&5j&jhLk8({68TTi+k0+g^s zX>)*5XCLbwa)E5B=VI{I-DzK=lmD@@uKW`n1EZ&P=5hS!|B#rcP*i52iOA=*z#$ zWf5P*JZ=nyHj|73byzsdw<@OJs%p+tXLM(i++__hfv_C;mQeEnpwH~+`I^7S0u(w0 z_HTW!+OsYMH0mj_OzkCiEPglvCEbN?`kgkSV`p@GBwVyQVW3MKa%=VF{{7oOC$8`Rv(uAO8})D7?iK{t!x4ihC<_7<)Qko1DeJ41lz}e+9xs-X z9Ze?4O7$TPDmw+kYvUBQ2xucF>l=h82W$Xxip>w@ZD=mABM^aOoc-d%pbxQ)D0E?z zoU8_cs@?N%2uF1jebnOB%mBc6zChTM2DepKtg(ULc}J>Cz8}j$8W6f_SX7uQKMnd! ztylj&3Ib84dKuXF8r9dOosU+M`=s{VY`8A{Qk#;(dgb$dYjqhhTS^3&dLLPa8C|@J zCyG|}v0jl0NKfo0p|;P#V=Xl?~-uBkhp(0Ef&{iDpdUEK+;hAmoaxLfU1myx z*6%dlKYvX#xeGbcG8|!USgm<%y?Ug5t?^;Zwk8#p0-AzNwd#gv{UJ2(E{#idX$KZh z2+EFiW1H&p+O>lA)Qr6fZ+dilTPxVQbu2Qusi9CMF67|LF%Q2JQq}K9jE=SHhUP0a z)t?j>=nnN|IRrhv=L6Nvnx2S`=(_RD>z$uiq+f7YR?W+6Iv4NM6n}7d{KT=HstO-Y z_f;$tb(XT%xUV^t{YwImY&mIG=Ew>c>-z80HNL^q9qn-C85Iga=_3MY;n7|MVVW+# zt+9{)Va!1)RD(kIsKp+aJB4EO7)n~xn1jt-5*>O8dvMJ?40xK%KRsFZP;#iUb^DH@ z`T---y#USI92hP*z<#a!uK1hg1XjpP8hO}kXtuf6vVwx@DD}&n{TjI6GF%}pVOC}T zLr*x~)}iP*ZciXY{(XQ!Uio{dNSkXgOqyI_V{r0_V4yq@?0IlXg@sSmd3nCVafvD- zh5tcQ?Sj&}jAL~f=mq+29|bZzEY~`fXHMxrD^1~ihQ!MS;bCib9`BKjUFQg%;D-^d zw{sPt`GnBFv69FvaeGOd7tk^KL%$cJ$V|^R`>F;z4}!S{l>G*vIcLdiu?Jp7s!Mt@ zajtp`&nB;M41>uTqGLV>jvI%ouo^SGK@C94KjEJiV{d=|;y{r98$4oX&h_!pGIO{2 zi_)tYN6R|>o0nn>W)5K}tIssUyw#3a$6&Q=S&NtBe#V|s3%&jiLEHC`evopTp_fXF zJN6MJ&W{$8z4gxW#gFHU9COe%(9js+7qI@%0LpR&!V>NNbg!Rd4rxHg>OnzR6rYDS zeQs-GQ*k(|2kU4Ar8`?F=@f5fIV`9O(u!a*rhiDoW!1+Mm5p6TejdD13%$)_AT;Mm zx77}^W$w|C1uuFuZc~ktM``~(ctk&Ka0_4Nj4x2Xe)`7C-?6p!=fk%T)?k+V!**L= z`)+A_ANULa&HzaS03awaLL~5(7}0o|?mxM3Ip{innP{Y&w6m86iS@KXc{-7Wjfa@x z8`Q<@;x?q19%uz$M(*?O-VJ~)Z`OVJ^c*OF%)|f|1Zc8a9|3wQQDKzx1DJm%6`U~( zb{{2JasbTmY!sbC{qxuVUvO+adKb7W47N(17$vauH%MFkhgaIwvtj_XYXk+t9AaHS zMmwtvihUdK*Zi4;(grWoB((F)B`^BhPx6FhuDZ? z1Y{5!d7gl}#74ys&4gv=0h#0D%h%^xtHB@OLARr=OC<1ouU2fj*p6}dq%UXA>^FPd*WS-}@ z_g+KnBeY4M#69H^CkQ*GuOU)N)EZI~KEdFL7zq${t-)bTAPxg~_>~lI#%lf=?i2uL z0s;Vy0I=ZkWSKUC^oaS(W@#x59Bo6AM%Jc;0w2b%qzl#HRq(U&GO`_oqW8>@E&j3t z=KQYavdaDmw+7rxQeAD=Uoc8z^4(OE0$%Up6)wuCG}fvtIHcaFRn5#4Y#NZfFQa~H z)4YreR;Cd@3_I3R|Hdv=77a?R~y--Lv^in3j?nW{oGwW#UyC7Osi*~J+@TYB; z$U^NJLZYf%N-c`OBEW;>oVtLVd+Ld~IK~ABLuu|KK|a57AUr1gn=gFxg$Wr1)GE|I zgQBmHA@WVW3%pGICWsE@b=-x7!|8!`=5A&ozB*f>_`Oshs4?V_-}59=QFNp4D`0KR zg!c<8ARt}1T!JvqwAlqto=J}qnfFO-@bmDqiKmOVcz8R(QO-2rV~CWaFuAMNX>rMX zlO+4@qC*%Bxg!5yI^;UfRhuSX=SmiwDbHSX4Q*oUcZmYi4OYwZym*#{B$MS`e_V*1P{0R&y z!(rNKr(A@bl^K6s8agMbT0u`qa)YTDlVQTK^kHL>mP_OwS8{r-O&2UvA)`A6evWGh z9+mES9FOBmpST74*)<4)>1b~t(G{l^zejqmlztpLbpM`7(mj)=7!w{SP^{KWspqso z2BUKEXQ~mvABg=QI@DQ`jC++8wv+mUh5NEhF=(b#vG^;Pa%0C(CM3AhwBDzyIZ&Ga zY+xL^M$3qVOkyFE0B-y>WSi`j07fWA1~z&O8DEc*yv+4>x$cwBc1`6h%k_?mia>qK!nGT#Dy>`BTHmYO{C4f;Kb1D*^)^1$ zc9H+m6f0cs&`|Bvz20f0+GX~p^&+X>ps6dCjVgb7>nxQo=uLMj^Y+<@*F+Y;43sCB z_5Cc6lYWEjO3jL;^0i#=aoS_{OWLe6l@nIHK#;QTa=Gw-}(KpQDQD#lb7A9d%xaq=J6WM2#vU&poU4YCa z=lFrrSJ*EfDfyFAZjGlTRj5-!BPeJHTYO0TP-;xCI=Sne`+Sr6+jk0uE_~7^ilOrn zRe)I6JAom(&`>z(;+|)ilDq{E%kl?$BVY*VX(G`yOtX)hbQ%9a276}h_# zbdZCplFd}IuO_-QpYBTgaVPztHvMC_`8@@A0RCbwekdP5gsNhFUK;hB4mV#E4`}&7 z*}a(u%JXMa(xvNNY;Gtq)K7mIfQUv}Gf2w;judT(4E{tIkA|hv2?~*(oIk&hebdTe z*W$+s6T6yYO?Wtib@zA{swn-%ee>(7aOhrS={>>lF=8h+1W|mGH&9Hbz90GHEnlDq z-!AD+H5ztwFKF}H*sxC}!HxFIH7G)MzyBI?RJR=?Sli4vvP?37PU{p;8NTXP&^HS2jEpI8D{{mAP4S0%4AT8 z4Cl3N%lNDT=bHR*;|vYdzpiu5T|7JVl|VVU+?3nhi@ZY?rqY6Tcsms!?_WWJbDwh? zQ80OyH(2eNDmh7#8K@X*Z#G`xD;@KSLO*Qf}*>z;17?>n-tTGWwqNCCql-{ApmAc%6#T?^l3 z*tp-wGsZ}qX8J-Fe7YghH)1vsDCli(Qf8)K5+Ck=;P82qzW|nNP}9T@jTO|ia%ed{ zeyqOsO9q7TyQo&55+qj&X)ZXERnDuz^A@T94au< zxo$wRFy?jn-RycDBSR#)9W(K;w>8yF*vR~vRxE5>G~{9a=zyh}cjv97;Wi(M^2Du# zLOA^Y$@z-@?{L18J7$l@%l69BuY3@82wwyqm`T;rFi=Ftt2O)o-e=H?CT} zx~_%ubbo!b*ctI+>fYUxH}5?-zqil+{%J2|P^-!9#Ql4}zbBV~eVNf*8&7}%zYKf{ z`JuKV+8GUa*?h?&p$4w9Q?;cYdL#(TJr#tC-PkTp7a-7Buz74TlpL$45SiwRzzG-EOR|0R2<#kkF9z4cNYdQC_~1zI{og?#Kh0kydr<{$CSy6tT1FE zj->w*uGP#H7rl<^-?N%U1_?NC8Q;EBIj4OG3V8CBE%i({xXR0B3ca@#FUqrvT9dJq zmQ25N2{GIY-r}lQdSkz06Ep-F8n|sP$Qv~?aP|4Rb7OZVLB>HDki%WP1(%{(?B~(H z2G+fLtvyPb{c_2n2T)1@nbo%Att>SCfa3vFa-6^o*e!ttC7Af3QKdbZ0aak%ffjJU zu|&}MK$*DOCv)(8dJU;d8~~bM8{GZm9B*)-(9;amUV225xb-kdTrEDQ&ohjI0#^8( zc}?2$4vrhXT9$o;&p6%UHSN6}4;{;YW-|*37N%Gp?z76fstpk={%lr~sD3*kC|ad( z<%no~xYsFQZ<-5eEUztWc|J2Uwh*UyR`Gfee(A>s^qCY+#D^yy`5@8^!V-of2w+{A zS9}$ivJct4eq5dKLZF4)+KHZQZgSjWRC+F5$Vt21MDUJ;^Ih`hdiCKCof4aGKTcT@ zbb*0`=UfFnfegI^On3$&`^yx^Q zAFRw}b{e{!i8dc4wE<)rPMJVik$_r@HN@{pE2I0h=zHin@*_9=#aLess03?RuwOrtGbpBXD#F4>@V^D|Ez zxG9MsTp^ihPL$~Zz||@_vNJGJklkK(&-q#G=*PUkE`EScYP34Urt^BUq32Ggl3dvX zI>Jw6AfM{ZT9j-H|3=Bgm3tiG)f(+fk_{gQXjAZu7J01eRlJ4$BqtI_W5VG+jq3*X z0fkWR_0LREeLfhM86)G2gO@&0I9d+fEwYJ6)#T=TGYWZvcJd^j=pp&Ar!Fdq*IxlZ zBoOb5I(^qfC#)9KsgLy!VhZmQ8xR@ST#s}d&4jxkmY+)l9mh%ocV!yxf}@(X-Sg#b0H8qZ=LXpH+udJV zwXhN7YoO>Ua7Y>kQS(JvyVs4z$XWt`yhDXa+n0^@3+mZNFxJn;p~F{sXZmM(YHisb z-#VEu?E-mc588S|;Wf5VPUT8A^CJzaK4RG-xeoBBd(zIxB-(kgDb1YTrG++hg%4gF zv;{&763}7qPMG)R_w*TqoDaj;W~Vz#16`+po!9ZgSM$2{U<5Vyp~Rw#h)Pkk z)0NTiRFXg176;AmI=uSpBIj<07*25>M*}|~z#NXud%8^_Wbvu;U9Z${XedW=8Gnoa>IPTKpJKl0uX_YNyEvD0_9g-DGNmeOess4S#2d?TCne^l?MQ|) z?`_~cc4M5v3E&Q9NE`@-sR6VX=`H?*HeyUo{wHzq6XHiJjk0|%f8qvggn_p`XlB!u~2tve~1K-|e1@zoT*71cx>q`9Y94obJ^o}r&jD>O#UiDz7Hw;O z@!A0>86-(Fl$Z0olQwucF{uVbtv`8}_6Stm{N`J9_eJK?1Bjx91`z$ZWVdI=ftZkT zu=a*lv?MS|OyvsKV_1MD++Cq)Z5jVLH-IJjeD@29RmBK+xa@F1H2VkTxevhb9{%@N z0XTI1qMDFCv{xyG9PcQg9k_Y-FM?}~@HfFI$7Q@G>Sis%DUHCti9V@d$(wnWk#Rm~ zj;x68Fpq{)VYH9$-&u&|E}yi4kP#|L`C3QbY-C)?L?~F$6&q~dmGm(YF-VrGB|CK? z&`VY$nkwQO4GTHCi+C?R%0|te%I%wf*#E)ck{QhP?sMI5d|d4wZI9w#8h<^;v_BmT zc~>Q*?ft`$+O$XNIsR8Tf9vzhgQJQ|)>Dj8A6(_Xmn7H1vwa03M#=W*u@nu^9rxp| zz9#h6F%h|F*!_e=D8U!r&&7`tVB)D?Z>#qh$9dshdz_U{n}G$c*c~?NB-1JWB=%Hy zIJ_qD5P>AOgB_qkUMPZj3%*EQP*sGktt1qD8}lVgAhgkm(4QvN&Tae{<(ufQKEVWsA^*`RKX9Nx^*nSscR6 zN>4y>_XvQ84WATfJ4iZCKT%hn4P3=m1K22L0+b9n)PK&`H&yo9jCZEN3 zp-1xAUYwvR5D@K{GmVRDqxs9V$4*j{5$&-&gmZaY;67T&Ia;1PFJXqvSNh`dnco02r!;vXg3P* zC535%c=_FITLNiSPe5tj6hR1hcT8AP`z(}xLC>Q^f{d)Yin|h8;{6Jzsx0$H!4 zX^=;0NSO55>GWg0rAaRXlUTg2D1b@gOPxkXCYK%fYIO(X8cfUpcDVqM(M`jq;tP_J z%WG$$U-aAv(-6mFMRkt7{m+V8{mOce%3yz3bZF(Z zX1)2_m95R^c$$R@iO_CEv1&%ouAK?jrsyphI3KQF_{Q9672LQj|pNhG6bD3jj?{s%<66j~JygY**W5 z6{}zul7_egm zNotw00@zbgmoW!N$iVj3NhUS~$+kgLc9ioW#PCb6a{>N z?knPoR*t>~Er!6qH?Mz-GLAu>E>Waef>(%Kh&42Atfpl=ycHvq(5{}=dwrl%>h~z< z=>Wyi3I;19|1yP)RKR=UI34XoSYf8>T7qvGcg&avKnvVp^T^$fo48YY#0n>xl`*0K z?%!5u4O;c9WEiqUKoAqQ}>gdy6W4aZ{DGn2*2btXh1ense==E{IM>|}st@9a&doRWCbzAm& z7v)#CH)tr~`0zXriG1P=*w|!0m)Pd_5bmLW4_(-h(jQ#)8cTh7bze-%^vUWkiLUS%_xIM) zslOjUZE*gFSjf{X^s=ixi8r+^HVT02Q(>Pkv4oaIy6>Qi6u=^OBge7eL8=#)98mb! zl@+n;&D6q=yafS}*Kq_FSbVNhRf02gxs6{Mm@f*stAj1*~a zT!$$oz`orDtHSP~YV5V516@mDX1&o)E#PA50M`r*n*!>vphnDL#79?@(1`Rd>{mQY zhuEaWh8Y1cj>c-Ioa32{HVnZe%}v?iB09FsVBn z9JUhp6gmi{Pr_qv@;llzG5Wat%Wo=yKvaMy(1)U<+M=rvn(>AyhAFBA zB`Cl-x=2>@`gzF^k9wZx;zHfJ*bqGV3aghd=CPnA*CcxuyI0d|W=ebm6v95DmbF3V zZUfXmL6;aLjvV0r$jhgh_URCqc-QAnt|Ixmo*jxaxjS>SjnAIO4J*8(@5q8eDn5k= zTm67*=YvK{*gCH}0)>xx9FbGhbZ#B@Hvp zrx`zJ4F(uky-QgVT7zziwio3N%w#Mh*8+|9L{>0ls0Svb_7C=#^O;}T%dnWhtUPd^ z2~3e$BoBGOHDf9g@5n)m|Gm9DoPH4l8D@K}hIKzZ^NHX42{h^a0NY29nFSUtMGu<8 zAbsF7-jzx8J+b!NuT^dnC$N-<6#4sq}2jb2z`wRrqBWX#%}kDu@=SaA(}eMx}# z>YA+P`u^xO+`q=7V|mtZurlNTZH+|~YVePl~|Eq+q zt_$B8Dw?_C{=U=mzNq)=%Yd`O{zhA7+>e7Dw?gi3+1G4E@--iewx_RcRgWomhi=Ii z!{mb;Wqz;0hD-$QMBG{{o!N^&buLHlt%}oXcjN+zv`;T1+6S+Cf#cDr9TwW<-&W=Q zS5+F446*vl(y#3yvnm1PWu@2u6iD`u@I3L%rhl)^{oC8#pD-MRYO<4}NSm0odk6i4 zT{F>9ZLgzCogOn0@Pf-T!7yto%$W(716~PZiw&u8v*}e788L&u)wvojDisDWCNKo( z1L}_c8dt9i*qMTT%SPpia2;quG(}@0pT3icsS$Ntcz!=hpA=>OJrljgkiROJtuiaF z$tN@IJ!y-*$#_a2pf~xj*E3OBr5~idFCO0j(4sA+fMN zU#uhvnx+D#RgQ6M-Y;B+n4sI7j~w68ryP+Mb`=`o?@v~ignhY(rQ3tnzB6b1j*FT? zB^<~*uLRdE0@4p-Bke`Rr8h6!JU);PMe2OgEku};_<}*`wl6k``c&FhkIx^PM9kZG zHQ##scF%{OSN1M%wtW)Tygon-lWE}jYuD^|Ria)7eAf0`3(MP8`b`hZTlgJbwSo;O zXQSKa#znXf?-hfZ6MqZ|d`FK6=DCAu&4|dqU;#$pCdgHNBkn^Z4cXqw<`+B}4L@^V zFp8a|*LD%0!&szL1g|uQ^CeK!qq^n*X3*OI%J~|eg^R`F84}3kdks+wjYml0uwt$boNcQ3Nw@{PYPxql28QFD{j9PRuVG|u6C zr5A(nMUT+jfyn$)zt9PJ?D#Gz8UZ}1{}1PzqHv)Q*gFdVpJd-t0`}D{iW|}m5^R+s1U*y})5~tKQ3U^A!haO=7f)@}% zcdSvc=Jh9Xp7R7yC<1Ol?ae$s#F~7OWA!m613a%au8W`C{5UKTzh2m&>#M1R7!%Us zr-9p6TBE`lfXscmb9{%DxHadVUAU>MqgL?XsRpEkuUx)1LIIgQC2Ye!xy& zXDL|LEMRfsg8ui-&c`3{pFTI>O69m8YhhCJ_V8M;;4Vk=eScdK7)UfxUEEb7lx%VE zW!F)A@`1IZj^^^W=2R{eaytOu4kX;)@0Fpmklt2&%eAk&P3P&B`{)I{p+sj0p75_y zu11H)lkRZ8cIK;wbW%9|>etGK1+7Sc*smRW77;8tPI;HGpIrN_zd{>A8{wH?_SP-k zm5V*NI&!FopQbAV0gC-lvjKP&KCWUhPY$mJn9V*n^-=i-4NlLPk{cCER&3O>6L(j7 zjX&iFd}{Sn(kt@4Ptil8vbY6yNWGZq9Yi6AGYF_S7NR+qTil>(BI!#_xGE^}^?dL~ zEb$R)Vb`f7q@nEi$I)E9QTJBf=#acUL}U5Lp@dG}+hO7!wgRJec` za7*;}W{2?|jnU^{WKf1*K3^2ejDJ#;6P#AQI8+pVzrdoHX_n~J;s-R*^deJ5G|;{? z=TJtY5=|qW`!CmqyiFHj$Q(-AzVe;V?GSP1*vh{ z{K(&@@hxpmuIP!^0!z{(j$naBgo8MFkLgB&f(V4W-S@20|FJZ%K&r zGnD1^gXGyhE+C+dbCY?M{5OWUcTRd}ANqsh0MGI1bSZ;1)KT1ka6wy!yoo=Li;}U( z>~w~NP@&jDJ319uM{I1IA3_gsO~j<7n)gle9_twr*K*9UO`yDZ&>nSzt2b1%6W-Y+>0@kmtBX9mM??p?U%cH_6&-%S+D#p5A&un5#Kg+0-$Pd%0hTNt_@+GIN`x8m3 zxy3_gwuX)w$sPd1wVDvhR7+j^-I`q7(JLs^P>S#!hfLkM8vcw>6Zu1qxvq1yZM7TR z+PU}6C(hN$)sh{9sLTtcbM=a*VOB18oJzZ$)gyo_*1?CKtbHkJJUAR?mvHBasoj%C z1BA+>$b*a&C~#Ct{~Fn$S$YXVI;t#zb~c_JrO(mIfJM5ZNF$G3&qcgBk@6M^ov6>; z2~PxQ?uIh+%+ zXL?J5(tIXjm+~selHHc~i5s!cOmE)xzEmjxDpqx$!-_c@Ct}8yx%WNcDYEzymODP< z+ATe_8t07I`;N%bY8P&ek9Vm)g?V`8HabcK4M?KPWyUR3T|F)$+>^8jUBtn+7%k`2 zwgYmWZNp|Fx-ZUWyW^LlwmGb9V$XamYl&%m3ak5jsNXhQK!>VAe$#h|K|NKhhN_XkKm z3{0aZ#U^B!KskhVbr;H>l3F8$gc*d2kf&s<$6I($MJ&=snJBd#GXJ0Q_B*FGFC<-~ zPk%Y(F8hP(a7x~JpV)KpyCUf}x@~fPWyOo@!7Yfzqb@w2H?;1F)X#x6{VoS$p*X>% zr-v!I??ESs$KVkBjw_nUkXg@gx0Tf(Dw)PppoINHC^x(8#e)hc!iU~mmf=M!CNJritQrS%=CtZeeR0c@*fPU^s*0nrB!y;Pw)|+n=0;$zB zxR_upLHr}Cbc}|OcqqipP><_)sw96)*COJJXZV7}_&Y8#mz9c^frLfwJ6%74=coXt zwqX4u>khilZ#$=wD%S3zOvT`6`o-I-;VxEt{?Fw1n(jXsdRO-F^p?7l=92V8#~6c>#N_&G-G{i)AkKK*lUn$Jvhqc%}f=L z94j}8=nu0!nqoD7pq|+pVWIhrQ6Zd4(0uIG$LV6xjteO`AjFPfdGH=kWhI~6G+KmG7bG5YNC!|dIMXL&4WU(8cC zAHEuRn64&_rjBODk7lKhW*3jSC^7}?FZVH`d zp}4gyD{*uzk*;Y?XL?y4u^g+Y;=0#4<~WnpJTX>1DSn290-7|g#OLH+w5+WvVmUxd ziqFRzk6%q6Zz>*dt{=bFHGX|)yk&0uhPM3G)0mr^<867ldPKBdQvtmxHy>}EM+MSx zW4F^MdcIh+*IRduS^yR>JzCmb?TK8yGrw8s`==uJb8KLtJhW}=rC_xMNgy@YJQ)jRVGlIj|r^Pekw`L@UXC&umq+ZTQe|4;_ zvMC^Tefd4}u8%IXQ=alATQEuRB{m~$G3}|E)0;`UrQ^(nB)UWLc^=whWuHe2(R7WK z?0hWHTD>ra8%T#CvEsMf+$bJ-u>U>9(UD_7!?h z>Idj6lxuV)oPiR~C=m>&@&3I$=tL3cK>xUfvyuZ~<;nTw zM=zJBzAisTtV|29%*e0I>a095U72%PnGarBNLYEAv9egQ@~mNH>DJ2g;g#k2m6ew( zt6w>sFJhG~yt*d8x~{XjVY<5MvidT3bt_?YJ7aaHWc5|U>g!vpZ-!Uj&ab|E`Cptb zuR|Q{#qI$*6!!w%2M9XQK4-AFEnYy;!aooIg6jHB%5Ywj&K)ZMdEW20so~dozwZft zyr2ALJ0Ja%&lXUlPIm$#%=~{)fLCcA(a6Shv$;pudLIF`2{zw1cDn<>U(V()?ZYbg zXKw(9-fF#jNtFqL$n2yNSt1`FHRmBzc!}AVQ2*yg9X}B0+~u^(;dEFi@^)nvCJ7jQ zw)VWUeaX3U-|oWf7aHv=Af>S~(N`e2u&%zfuJLVsKXQX8vZ1N4p{2WVz-(hr+jT=H zWJ5P`<6!27Ug?H@f zbh8DOg1^W>G}QwIkt#0TXkXu#e#kAV$dPRXYtn^+Y0nc1$N29dLo~MeT3^P8Y$qmepUm7&D&0rSq03vP*UWo-v8^!i?SD!Ux=rcS z%$4vc*gj4vBBtHz88-lM4d>T`0D0(1|T{(oY~gb_KNe6SHi+pUDzvU00W|* z>1Rhhfe1iPiJgV_or9i0MPX%(AGnb4fJz9XHdj>uzL7@^f4QEoA(I}MwY|2pW^!;g zal_mRU0fB#Q{7W|!Ps|b^MvK6Q8^QP*PnG4oo2crT*xy3z(qCNe0hq$IC&o|v{Bii zLb&5+`6XCbc_HU3F>L$)T##M)%i6x;Q3%;#p6P{~Q=;WgDb+~+98_}i{9+xSkA=f2ekt&c zUBK>IA#-dE({y9xB_MXKlDBBGMIq+LOsy9={~0sPV{-C0Ntxjwy|2b^=1s?w59f~G#aZYBAn(s-@6H*_ z(5!xCv5>lQ$#)1SV2;c<2H?-~y&d}j*UIE*(vX`l7MHeG?f00_Q!FXwl37)G$k*RGO4AA$!IoHD4x`M@m|O+IR9 z8wH_)Lt(;yEJnMUZ#W4#4!mCN!74y&oNS^cd=uOI0@=}`5be<^jEA5|^rs>o{U96H z+h8PQL>gX$QgRy`zlQG!<0S-}D?w;-q5k-emh(sceZ1h){i%$_$hwTIhkx z7TU%NfAOHwX-Xdqxm!LHRAP)uzhR&UPK*}a!)=|kj z6xBHIQC$InoGhde7qkXOE@mTcI8|{+agFJOD6^zV1R} zRqmrj9Cmhq2$R|z2u=9rT=i&BAp0XPg00!I&xa{K&By>J(3$~g0V!tYTK zxz!ve>m~5~1yo{DR$Y(Yyqe5L9{$k}hRh$4v01}-{TRSawPhZhT;ogmF=%&ykZo=g zaA~u3NXf3o`r{f6Ac9#E+4E8aGVA_SCdKk%yt_!jTzRUUljLB}3mV z`~pC8i8Sdw>Hd&V(B_in4g>BqA#?yBKLb6$gTlTeLnW~ON_BN4yJsSv7<=M@&AodL z%rRf?jx;^~^f8f-3!+^FM(7-XVhZ<@f4l|5i2)}8qA`)#?wOe_(uKjoYa!8SK=0tA z_B*S(HLuU7qGj&E$jvsCUCbXSb=Ju+=aS+lUu{MBV}NOD99zRf+@|0+Xr^SF{8zp& z6sF7;m4zdBp+w_KydLg^#aT6m7W+$@=8UF^YZNLE4Sj~_Hx78%ld8Mi-+G_ZpKbUF z4V_@ZYlHhyshA#OZk)VqKsOo@3#E-cmvs(Rzw1LB5bdJ%BWGGkL&+vtZ9pDi-@+Sj zbN_MX@3ltkXJfs)g7Owsav!8eh2qvtvQz$OKNhjNP=b%TTg5(Owzosmhmg|FpZjBP zz<58wA28ULMDBW9tv|hxBOj~>2a6Iv>@U6Tm`WQ!vO}^TlLJ#lXs7V!o8qnB-}vlK z&#&=fP#To7D>uI+;oneAY?q$<6o?05B>`GCgj68^+Z)H+wSL48jmS}gK?xjiH>N$? zYbjbduPJ37wI}#&?3BFakv5!(CAr##93q7;;jpy{Zc_bw#0Mb63up55>9_1{ zF8fn?LRGRFB=T#5Occv#2o<4dF=eZjQf0!PMG)dl4owG!>=Q{kOi~0+{YfY(?(4m? z-|&_FKEblOjLwI?mV9}%sYSPRhezt4Rq{S+xCE&Ez56Ub=pI>4KZl@LffLPsapu%0xpv1ZdS zUsAGO|G8Lyx5wW+9Z0a$@=P$xR(%(mvzLUunE^FdunUYw?PJM9(Ew1ClY@2EX-oGS z&WYu`xZ5*xlXB%9k>xMNUS{UDT1d`(5j!AkcGLZQchdPDJq?$y8NG|=pEw_nCi2-W z1aYk4PUZq$Tj$5o+Ds9iEFhwAJIF67VnG2+Wuc9d907p)VNc#_sPa$>^L(-4I=`U~8J^w`5Hkh8T)7dWMeUp*K8EMEAh1ZwL!>T}d??u?L;S>~AFb(+1SW~mq*6XYg9);^h~U%}gsrm<07 zBp&!0*}(8 z-44j}!zKM^Z=RyA*aOb^e8?LBJO{Z1%t1Paj8NV^uFEBKH|#vuQpB-#y@+*5Zhx3M z;H=qpZa+0wvOUpg*Z7(;c!bMS@mPj(A)O>2vU(AEL!Hn@tv3D}{8NxD@L?)-lZQ7CRQrX~nr{Ug+!^TJh?@*lj2+Vz4hFVF9LbWBFRN01X^+J?{2Q{bx@sFQGbhhKsatP=ctimwx#$q)GPU(Ib2E zpdQstV$_Q-OHg~a=-9Qquxp@7G_8nUty4oUaEO8ydX>Gtu*2foOHh0>9o!JkNL1kI zVe))@g%bj}CrNzGKLs@xuW>)CWMKWsg*mAs*Z*c;xuD4hZI2hc6@Or@4Asu-`6K#p z1?Xqh68;d>dWh2`Awr_vlN>zF+OiD&vlfz^l9-5GPybipH@FBe_R}-|CNRJar@swr z2!<&VkE*}EEZ?3!UmvK)w!F0s)53ddF(k8&UR83v@z%5Synof}g95)zF39vB?=Y^D zSTIM=aKFt}3}M`mlIV~*+#%msE0@yYM#sQwcoU~H02&Hb5vz2#vjBV2aZd-#YO9IH zW>nmQ8(B+R@50Vnb+*&nIg+1yPieB6r4P6OYzj7IsTE!m!IW#14L;B@2Y1_$wse34 zAl}3pL^uE6?Jo8QyZcmnyMT#k_@|^0|uDEmOjCv zbxhS*F!=M^@HNFFU>SlC(&_@+J#>vcY-GeTF+Oa1#3bQ#3K(dKcq>vPrrm{F>zq?j zDyBL3PsHwHL0>3_Y|cS$4(myQFlo?M7hj2*snd?WOoN5dqLGHgwhxK0*XBsWU8t-H zEb%U9-4QF_=9abz`6Z|&&xQ;up3Vub+7vH`_e1N&9c}jJVTo*rGn-=_Z&RIy>;!c| zW1=}}899bmnb|cyGW6zWdqp;c91OE~W@Bpw9%hC~JwE~Mry&dT-o1`3;s7pIpa(Vi zM);g!n9w*lNkXJl*6^>PD6Zwun!aAw(ggYXR>(OZDU2K$j&0%&azh(=94(++bp^Ey&|8QS^1qLNx zv+%7aMq;@N!{M3^2zm>^91`^(qy!(cmJh19rf7!I9?!t$Gr|*D=Mf)$Gh}ZIV2{yq zu)dRmWFeDjFqt+DsYM^N0#ZOaOJ=VS7Q*9T3`9f#2t3h3Em%1!&n$xB2=zxQupuc` zg5)oJPTpAU@s`8bcJXAestvP!3AQID_+HidJp_t!f!i~jjoU_?Jx$DLFnI$|2fW3t zX<^6?`7AClg~~=jJmZwW)D8i{GWKV8G~#2b@$*2T(VILofhTF6KpV{H7;;kImPZ1c zwwWy5h3xvHvvAE`LlM^IR>El;Y)pbsH|X05=F=tcXCx?3YJ(9x{|c5MCUP{m9=~70 z@>zq1)DA&{oh${qIt$H9gBUT~%@{FDJl?iM4`hu4Z?N)T_Te|bOn7V5JYTj-NMZ56 znKMt%oLV~bRZ@U^?+mDpaWkSl`3rNqc|c|}ZgS%7G;e=oYcPnotG8I}@>leXT6ApyZ4clEg&MXf1OeLB|qPQ9!O==OJL<)WU<)X^t%PqGbZZpPfyt{#Qk+pg~2Z(podxpyIgS9zXqu)>a!gVg*slC1dqMLx!LL+ z1`L=g+>A(suOXflsy{2be5bSl_xJZRf-3xPEp)&IS7*BndD@8vj266LEbI-z87xCJOCXB9HLx}u#dQ7q~;uy?7rKY3KM0KM2-|4}kr9bUfTVRKI1RsRdUEN<-aPXOS zK^*tashbto$h?5SOIE|_Uv%Q`8HFFMM?{9YFo>s}&U3#aOYhu#C@A|vTI4wGYh~vgO5|^BNC5v{(9xr1cvXIFurM>~~ujjT-$BnkA%^4XCdqG6m z^H|qbK-~V{B4L?OgS4iLf=z7LqXqqMLB?K+z<4JEWUH#23_Y=bFGc)Akh!ng7b>`1 zu`d4)LDnmP3LRHwB!vx$2}M6to~`a3yKErKQw(8oxLyCJAoG0dam({gK<@>;;QSg< zi-^!oNS#9t(ibxdA#C`x#LoYFDdNW6@zmP)bEZfC{6$FkY>~S%xusoqRjwM6Hlw&t zBKTi9a9$A*w{ZsT!p1I}okmLfH3bU6_vnOHE|y^^AlrXe%%GZEBXHt+kd7`T=Re5@uUBs*~VX)6myVkAKSrv@AB*NuP#m+skCj zH`>dcv(|P{I3LpJpy&o)#c9Md3hMPL8?>A>xRZFUD}crcc2d2+3!J4#-(yF$XdXp2 z`U~(z7o#QhqA{Hh&iqgHR;DIh%=hy6d-cWx={QrCIA*VfDhnZV$F|S~3{+%4DCcK< zfp3pFYu!njG-F?tpClOxHhZ}5|1&k^;r1 z(DZ%IXEa^U7tsRZi3*vJt;&}ZTi+cbJk>`vRWg_o9SZ`Mr`(Ydi6R-Qo z*r2&@?o_LGgmuI|SjaMoYumWq5!b;MWJezTSnoLUWDjY&l`<*hsNBhGXPUqnYOk8z zB$#cQIH+{vVdAi6ziHB_!N$X+rxqM$$rECI7_sOS7JsHSW zOE)N5Oi*%a==@!rNZY~6vuE5d{zkeB-DTqT2uE=P+&+MmbltUd!JYxGAV8op1b<4C zzT^qBO27qkoi9k$AtF`DeyaHis7<+Y@rjDOD z;~g`E(F`(IKRS_XS5!`Hs>S*NWGq!C-~Y@v8~v6BIg<5&NK%qGb;L$Lt|wSZPqsfx zy(`piwsYUurtqzaOnt7YVA+Np3iZ8fp6hQ{&b&k#m{$p#ct;S^bZ5DwvyQ5^5gWZK zMO=7lV0sjLVgNZqOkeUat zf;>USGlX(EX=d`u54Ip{Yst5KGg-06UV(rZlQQz{E60LtCAr#3YOWZ$K{b0(qHj zRMz-2k%l!yt`J*T7+()k(*}jz-&KMOyMxU%giCa&^in}3q=H$bmx-N6p2!&DLlZ>U zAl2hY=~}J7pd&4;OszR+y>>6>>SPeh0rHqvhbfWcoPeg(ac|Y_h;yP{aR=@QwbaMj z!~{*hoURm^X*ib|vlpUZ;ydIu(|Eo&CQPrxcdQG34-?7!a%Q|MhDkhFV%jc_sMOK9qy;!aHB8pp-05xtORz@R!j9}{X$GPi zMjHPy3YhO)F2X@chmMI>!)lUN}fg06LK zxR<_mr4B(7X9ZV<;RW~i9sNRAzVYH|%%sgD(EWD)wkS}qX5WqB!>nLJxGyo;_W%jX zMb;RZg3bFH-wCVi2LAYp&x)nb_i*iSi@Al^tC~BXl&(?KvL~J~~29nZ#+@uh})SXnVq> zJL+BfZyo)&46kG2Wnu*#{e*@;jjVPqlLot`bRU1t*uJJIVBv6&__*z~Xw53Z$cX4} z&MZ0iaA{xm@#JIp#j@uo8y~dnE^P<$O0GS`n=pWCSKosbPwFI}Xy=%_`X{%x5*D0K zzYt|V60I$POAFDA14VAkXNDg-vNO&B+)|dk_bRkC^pkilon+JWVE)4q_EN-}`LXur z^B<4(r@j96_{V5wf@=Ck+G4XV2d$^m9VTy8h3zy5Om#=}Lu z{Wp7Igtq|2N^A_srq)2@u0LV$4Lm+Rv%oEJnSo&3=**1-YXo6$5WoqUGXapjN`APg z?YqpwZHd6*cL3<$DtU5p-C$w&X?EHM*Rsy0_mf1=3a-UFPfj@&uxZ*4(;vNiRhZge zno0PRKe>4+-N6bx&!kWPUb8s;^ZCNxO!WGnZ%)n%HTx z5FspNGK(Xo^cszYu3>RDvAB9zXb+2T!z`X{7B9RL6zIgtck;29BCIt9jf^g5-9mG`tHZ&?WOwDffP>5zcf+uB(vsI0N-~`e0XH zeXHRB&5#A#KG3C1N57ry+PB@M3Gc=WbZg0XYwLFF#MHn3%J{a+xu=`lP1}^LN$WQ9 zzm-F^46N=pt>O7FX$2X%U=Ft~LNycQt(j#7mexHPTN$|wjQI-Yb7hjM@AplT_ngwSWk zf(awC*34mBNTT=*|12-yLp=o77{YSJ3H0|+`%XmlAFI1~BbebAjE>or;BB=%;d~)j z1dSEBpZ2!DkYINDq-dt>K>sqpLwOj});*9Q3b6Xa+;jF;U*rl7Kz+(Y>f9yLby1(x zYI$)Eg%2qi5muop1BDEYnn0=`3+=v&3dNvv$%+E40Nu)-xkU*qwqU$;=r@Mgr;5jN z4L#jtw(Ua5IEFcyc2&U69RQptL)JZ_`l&;=My$kwGBXAo?^s)1l}G90M5W0v>G3L8 z`0&>yy9$34qUIcDyi+Ut`q$esAp%6WmRoRBL}0eP89u@i80nNB>CzqPwjSy680ife z=}R8zr;iL2j||p~3^k1m_l%58jf}32jBPuQx(z=q?z9jX{kI?+oemkDNgjPpADt~8 zeNi*|vT5{H&*+R76_!wJ|jV;NKE$fc0SdXoGjID+ITaXoxy{Y+6K{obr zd+ZbZ>6XCL&+<>d=sx{w{dC*o={L3@OMd!;&K6|**PSW5{}g1ur=I><{g)skolETn zE_W=-jkia4!TyIJyEe|*JkHfSj+y?yf(#U#U<)!ny$ODs2?5Uu!O#hzlnLR?36YWs z(QE%hkWEMty57HVz3~-fNev{~reyTUklm@&K-btWp zr-Sso@OLPsG^ca8(clvCpcJoZ-7AjSoHXQBQ- zoCVJ2EF%9eoTaX|@BdE_>5aW};HCfIEN^u&V)xv*vdmCfw_n`aa5>i5@!UZsE`|N{L1MCOK$lVzw6=r2-^^HUIgcwi*?Y$=OLF}|HLl^X~+s} z+Ojkz=&?rHaG6rBYyBI}boCHNeg4m6AYGcLX_Y{W`qp1=@n_JxS~920Q`JBVqI8+h zt<6K_kLTV5(-@$99Y1-o@qF~%p3j_qGVFqJ!5vwZgo`0j`On96z?*~JkaIz$BfJ3V z-Fc)z>Vu%rL7tj(#@8JUhH%g-zsROdZO;l~kk^`W`aGw=@KJ^{>~`Cm(y%*$^7sq) zygot4V+~$i>*kOgv9+crKK}XZQ@5a~ldz~j|0`zitwTYobz*^ahxpFhLq88hyQ#uvFw~YP1x3kmqwmWYmB;I%fkR2#^=&Vw&$3sBc^Mp{wW#R{k|>L}&X6`Yjjr zLj_ar7V^E*u6B~mL{I)zUH<(R8epwZ_ z7!JNJyz2tKy$!2hMW^>aHhPD?`FQ+&6Kv7w{lo6N9f3_h{z`K8Tm>lH$}x8XwYa#= zlSzeKO*YqsViPP|BGat9Y|Fl$Hvx`wh5Y)OuVPVSv{`x1{411@wTF{;gZecW8m0llAHv+3fvQi zS@LR+XBp-!5U${}uwYLrq4PEPb?ugI)j0ksURD!enSWQwKlupP%`0EZFO7nOimYy# z8XVnr5rWXHpA*;^z|J@n;0y*zYvF|&e@~9#Hwm`da69fq|853mq{x-@9GSsBp9uvA zxHjz_GEqx~JSGfmA`>RHMJbx<;ydr0U7pfPlU!%u0I1vG`6hr9iY3ZH2$^0l8-3*6 zh=?Vq?#z0NO1+<%tTQ28<{D2stGBe#+w^GtY#jUdT z*>zk8WC<|_+)1s(x;UhL^b;e~)esj`Lcpu7ucC!Ffl zSl~bnZfLR_Pq&4YPEta-fAUL=tkM;6#NVqv1w4BI3wHf-ZjAlGmvblj;P-z!$VI3y zwd*L?G!xXKH$OA9CU66F1Oy(x;&us}XVUXv-`1ZaYWK{sW}~ zIKUGR&fPR^tzu6lg9RN${7lx-SNDffV=I^VF7Et;vz+lBSr+Qp>BZ+aO0)M+$bay94&N31LMet7YoPZJ)(977N25#g=`2dXeyBka}9d z4n*?oETmL3XpuVCfMXy4?ubS35I%Tsh?MB(*{#M5HC|z-SuLHT$k0#$Yxo5-9iRn+ zjj#^FMQ`=$)8k)cyk9JcIMpcqx)W`9&{z*{+kd=`2--l|ZyWZb1kNu!0MLG3$|%{g zkP}dfqe(;$WLk#A76^vS2*c1>((p#E%z&TI%Nl5+?)4)y(h|b9Y!HjI%v8t7zmV{S zWr=D#Nz76?50%DS&Bhd{tEb^8@!y-MXDiIs^pMg%YL@n7Q=W^f7tbOIoR*Hzmx-@r zm6WL;moH}u&k<5IaKwhw-WlLId8D4my#;?tyHtGf9C!rt?&B!fv@BnvT$Q?RT1{8% zAA3BP&3`kM_9BZtFUU5r-cLs9~NCtta&z7L7loMWBJmdPpZzAsz8?nnXlmILx_KXk{-2 zZbzUdpu$zhp?3;>E87fR*J+X*RZJySP(=B|%C&(4`f z!`!BSah5WEF)$th;atU`l97D<@$93x%(m1#TXt>F%w6^6w_i|;4iX@RN{(t5*4=_O(6AXL3R zYh~x$YNvw`F-Qo6^ywTa+XT%xm>9Iy@^g^)1(PpQ0XK!@)z9WHFR=WYDLBCp+bytZ z=DF5g1j3wgis(02+9 z3#`M7nIrH7WS$6C7gUz9#|{O$$#vD;6LY^ESX7JYhb^LH#ZA!bTDQE>tPR zC|*S1>;UveE8jjcJSa4u*UcwP1)LDZK7IhIZ$YsRrRgt3O4s6~>&L;H5#ZiT&WR z-~td|SSWg-Q3bo%Op_)?C>`gMYCquTAvfs3W&5#I~@T#y@OTXTl8L00UHKDNf3I>2#9OBpIN($^S93~n#<2^LiyvIoTy2(Dk zM4kk_d^HT#8Fu&rzZT2r@=D;7Br|i}d_70erZ0q2MPqz{Mj6fQxW_dk>W$`E`E@VR z27nicw^&c0mCD?}J34G^MQ5F;&D*;mnftPq`Bvhb*v%-cYw-pCEaTGjsvCNpH$}fE zntNrQ$4V2!!fKOlU1=9OZhg&w5M)tvQ8MAO$D4i3Wj1-xNKsUCi9NJQQX)dl8h1659~(6i(A;RNFO3!0_;l~=TQD#tITHE_P71a!rx z5fXUhXYcJL-Yx4?g~?pblJWXSLkL%I+TeBVO}$jEAP*oQ(0|x)w?Xl?Km;RMN;eCS z4aF>BIKLlTKGAr#;8fe55qLKR4)5SQfdcFRghfZp5*p~TMLaL9(><7ocMy?#4#gio z;(FsSz6z>o2rA=Xx**IT?SAcXSoAmF170@JiR%tdAWj&Dyddny1*qei72KezKs}1e z6!{E`L)d977MSbb4>gfX%mqDPJ;+cKRWNDIN^520?u#wcIFXw>?dhF!Te4UQJd4Xw zk--#^$_s862oO%IEH!FVVLeKq8Y^FI$y$;Hy*o&*GzKS{+V-6|64Mg4-w9?O4~r?) zhzU!U?{jnVP3hnO3>I6~tte+rD8B;}YRiqVgU!&1*1)I^r(95`G7s7r_EYerIld$A zU4=l94R!Ix(c*%lJAXS!=`IPxg4uT?R2X4_o5GX93MQh)6lCb3M|>W7+T7h; zvP@1!rP>}}+2U~giM@j3VRw4YO@T#Bj|nC%lm$J(8PyRVQPct6#-DKX$$%}fr&7;q z)q;b**dbgwqYg~_2L4zdO3vf^!{S{k)SP8vvzeL4fFaE1%nTBA{1*5w8oa$V;uh9k z8XbTgM|I$!npMl%!xIY!vU8+btvdzGRR>H=!)aRQgveLWJ_Q+05k11MWr zB&obsrg_Nc50YidVg zpCYv!OdOw~wX#WD#St3pue#V!GV)a(_GC18*cbG}#pJ4khPYx6W(w+!X?#M%B z%9qAF*FNcNdm+X#hFGebMIHHSJL9DWe%#(t|7{MTM(+ayvi2h)QL^&^~3ODjdVGxvE2Sg?5{^`yvFmbr2nRd;IVqxOG1-eXMuD> zfSUq%6u)KlgY)4Cm`%A#0U|0WecL>KkK_li6G+PUu%+Jd?8*V7&O`5Gu(CL+Az?$Z z6Sdj=URVp=w~651o6dqtV%jN13cLUX-P4KcpSSBd(=qUwm*8*ul}1FnL6iUqCsTARe@ zHwFbUVT+LC@z?}1T+a|J(3QTw{R7U<9M0S~|Bn9fWk(Q8n@@!g#g9o9+>KrO0)zbG zcRRen<5%m7y^K@;NanfEMuuA)H}C!Alo^#vSoe|S=e>t8I)dF#$QW8YoI!5KZ=jZd zL8un8Z*NcJT^zR09(3M|W&l9!>p$m+d2g?TEcD;J3;@SZa-~xK9-+d#PF70G%)3{d zNE=77M|1!{0QS!y5}UJdOPbR~+?M|tM53eME4KNP|IJx=`|u(wbca%nLyzgA2iBc0 zNO-4<7}l)2UNJib-TZN2bG$->AvNF1_s0DnoF(+;>Y8Y+=bfJz&h58ecVS18W24T7 ziPnd*gGjl|K|aOE`NyHVydUSz9hPC|pu3QVs>T3RP`@{uvsh)~r&>SPcPeB`T4Z6K zeX&;7}{~cyzA?UL6sc&=1ddb2LE42Kh8foy`Vg|7_jB#R%%xvb=BkB zhxvnoyo-HjOuNLcrS4C5O8bh6=@QEkaTM2qQ*WzNnu&8E2ohD&@XeV*yv-J3;e{hz$F-=_O zicB>u+xm;0Tp^pYC{@t4hx+w(H{q(-#41&3z=t^WrNwd`QVqfGjT)@v%uqkRb$XB25GgXzx`W-gy>OISTj`vhLW5Yzk(5 zB%nC1B;t!ZWFaJ;1_2WVz5B5|%eM6?aO|+=3Qi~ZBAE?f&I!tgzCpS=tu=ceHqu`5 z1jLA_1FApe)!o|3FrZW)h)BjA0>Go!dHquZ2P2g(Skn(bK|FB%jXYBY6R#EDY+sGH zye-6el%Z}?Gmw=3@~cF(tpBMWl9TYvxK`mRii%j7qPXsS{+UzBD*_j*M?mC@W5|6u>O4dio&x1<5c_tB#(kDcj3JP7Cp1?RU6n8OG)xOtb zEz~HYs@!8nhLe7?peV&llo6SIbf-wJ;mf;cdrGPI>thAyvew(91#?UWW^yhfD3@k< z&issws8yExKvOqMbISxEy2BB`_*68TvwVP*UC@a*`vmiaR;^Sks*I0>fOGEIF%Wq6 z(44qT_91R#J-@Pn<&KA%<4%g@frUid?GV7wPIAiALTP)#N!sk_qY>B3np1P82_cwK|C_G>%>58|~w-8lkWb{MvOyMdeZ0DuNR91(^gBse(8Y9?+k2E z32rGwtvL;RCl}age_v&&M{-#fv*3zkY%a&~tHk9UV&=$adP+~Q<@?rtQ(5}C z6Yu3DU@HB@XIN(TcCd^$90jus(+{P~A2Rj9y3J}8%89NJmUDdlc|vr??8Y zx^QX0nv)kjf3f!)Pc}3UMpimq}Ct2%(Ws?ULOq z{N&n@&?OfBypc=PM;8&op4BkV7Qi)TvssRok+tS=8@>9QfX>BYjXD%<*ngGT!9H=L zS2ta+>r$`yo4~as@H}+FipQaXY9+70VZ@!~f&x^zO=2Jz2$13NP(aXCuQ`n!M7o5^ zT6tDIQI?F;tAG%MwSsb$es_7Hb~mg}YB6VGhN}e}UN~vkKB2CT8cx3)!nVKQyCeq2 zNEjV{T~^pf%WH@b*2>@(b3m9l!#Q}0BRz6=GD;pUmV~OoO@mHi4D5TFK?b3ock}E^uMRIY;o~6{>)o)14vo2PZ zBt2l9Bs+JCky;ueaFy&WZ`(R{nEx4U>&jD^XQl(#kq%I`Nrp>CLDDtI81B(HI zulX!vK)kn94N^1JQ|^~ZFn9ZTfAsNat1i{6pGWAXTd{-iAMcp^yjl>Kzi9wrdk(>h zN?-E;cQwwuyj4Z-7unjb2e{0?X9)P?GQ5yq{{q>$oh4`GYq#?k`Jf|05v!ok0Ijmi zG`u{K^WnZotLdZT{d)C)CTv81ArZtFI4~#hzA;h#RDPUM`e_WuK8|eA4NSE zAyaAga*xysI2RU?4lbXqIcNADEwYfJrYPo{P+BnG=YYcw9vPB_o*E}KF=&)yY0694$>=K7?H*BfAUt+zUH*{E&71z#(s{ehuB2u8cGMb z<3Qx}A;HcDwq>X?wH&=n!N3+4qDl(i({Wo^NF)`fO)8z@aEHBLe~vm8x^3f8?^ird zIVAaxQd0Ag6|ErpHd}a-lGz3xOIuU3wf)KMhufw7o*D?yvR~P2zVM)stYCoaTs6`x z;*Ma!$w?0$a4-9E%D(>QOF#KObbr-_)`O8C!XJV|@~WAF8kCmiWpnHDFPg)7t^ zoM(h4(b857EQnDG;~NnCaf$sEpV4iFo3R#ugl2&^2eKL4RbT!L6)o&;EbwGSfDQFf z7R&}(@6D?XA*;&219XTSVv)|=i}F+7q*1vvG%sje7|}{+nrt5+d~4ObRmQj+#YlkA z_p|b7J8)|j#B>Y3IIDQ$Ad5Eyn?Pa2`V^D5bO2@Ab#2r^5r&zl5;~U=XKxJFbOr>9 zjV__WNcU-s8(FEDc9tlo3I0sOTa4B=n&HJ;`z`kg;hQ z-dkKwz8ucCALoF`m8i3RWX|YWV$<<1J@~mjs3~gUC7&vb2;lXUS+s~MXjOHF32;^M zJ<0-ae4Rx_1b18h&X>K!&}f5*gQWsn(f|%3$nF{`GahZ3(q;?MZ>d%hbV+*_gT<6! zwN|8-!eEsBJ=Rtpz2gy(ht-ARK4tm#)DnD#YGt>@L6id=cu+(|zifNZdh=rjkGPL1 zjYa*_4z3^U4b{!PS4$1L$`FpoP#EmUi7*Xq;tW)^WfwU9Zgo?4vRvNTwq1~q(|wX~ zQiV$BPYJQhoXq@^({&Wici=>h=l%Y)p8k_l{ijy@(^mViB9Q8@#>eIDwKF<1tOq<^ z8U*>9t~uG8PyvAPB)eunJE(f^mQVAUse%6tA{EFF7U~WbSq~OV6dBes4C5UNzzp08 zPOk%l7wBB2CmA{{hb#~Q#1m-a*oy*=xIrWX-&AEiRO2ypEoA6=^3VY*!!dZvf ze+H4dO=uM(LwDhYMq5Mm0>cgR!;QMb_pOJUJcgS?hFg-IrcxW-Q-|B;^1YXb$|)36 za-)3pa7lww^=yd`x&5*H$UK40u4r|6j4)A;s&;@|w4NmYkwJNM_8fY!$a(0$ILpXW z_~^L6=!E=#a~7BW+M(%xahCVYNanvei+{nRN{9LXGmFRo?V2x1v!9*m@XvP%-8A zXh|)^w4NqdKa#A2dwRc6JRUM|iLvjciNFp;0B>5rG!$wxcGEu7ajWoKFp0Y`pYu-M zzFT=yw-_pqp6#u*KD|3aYn*wB>WkKpi#W6|wNyBB?56yU|v2w5Z`B(GNWyXJ*;ARi{ZVD0f65qxeZv zJe5m}@!M|-9SQ#=!>J*n6e&j4-lE&`weGiJuu_;8)%;>x zewGUQK8|(b*`fTD_rE7_lUgZtscfi6(5WhOu2BHs-|&w{GcUmU+STj_fSkN<>}=^wGy*)f=+K`X7@VR=Kps=B*em& z;KFBxg)e#wUu_n)Jr}-(E-ZUezL)fK)_Uz+Tlm?$@T+&>_w>S_wS~WbN~^yeuCS-% zeVxCefMF4*Be~|5Qvg7j4oDbWW?*o$8HWl0x-vaY@3rq11a@5~Px5R60#FxW7>tuw z*C+_7CSw4AGB6Mk)RYT~|1~e~zWED><`X)gx!l~?bRSwREv@&^z&8j&`O#k!y+H)^ z#Hl>AGH_6xecLi)^_o=jFh%CN*3t6ifyLRJ(R^@|f@0iR5}YPI3Zh$0?{(Hb!Qdg2 zI#jncad$t4`kj%2+dvYHV%is^_?5CNn3uPWJ@X6la@+Ckm;NRNV;XY>2n%^FPUXbS z$I++02vWJ~mu&w>5J_mwO>xa#f9-(nnuph#XV{w8(KYX^HJ{Qo-|K6BEo%q+*8FGI z4y~^Rd|%VQIeu7Z{rBaU#wzQ9E!sm?>v<;Yq5mC3axIj(x*pxP9y7BZyS^Uxef`My zH4bni;k$UER5*YSPq5uc4hT<*3r|enNOIjsyz9BOO=d$)Wk@O1 zoBOyB<$}%9h%j2jn^gj15XYnZ0p%KtDmUM}H1p>2`kO1?-&DLdJBtddRD4^l|MseF z)cA+Vny|OmkG}n3zj8zIPSBM+@5ab1%D%@o0DXjV+ZE;WHELx(=(sbYDUnerAdp)c zaMUHEM}%BZV+T}5ym853ABwHR9mLDBN?Ze8NTRG4oo?o^_67$4Rdzh*w|eP8E7Zk7Hgzykn~4KFzV9{}E&x_B_-f4xW;H9yq+e-{b= z4e(ToTKLrJ=b--u@N9;H?{#v(u>=B(b?;w`g#IM-3Y~BPU}6?OtPGd27YSo@y9s>K z=JEogZB1_`YY*HG7;SHU_q;xM_{u*P316kJ^gw_cKjP+CY=Fn^Nqt@!DEj9j;nxlG zLFEnDKYCKQB_K|fbESMW=p=Nn^L5$7<745h9FM(=RcJ2NCl%R7uT!~z^Xu=tH6+)h zfh652;z`8Pq^r`e9FN1qN&A9D8hFc7#O}CqF%n?BmtP<}B!oM<8d)nZGY*LoNUEIW zA`?fU4f3Qwj`-wJn|y(7Y2Y<;77HH4%lIBMMyiDPD)}Ts(ehw%NFmoLQnn=uN_JFL zR`eLM5)49JmT~J_U1XB8BFjWVN_Uz3LUFC2=pU7y>t*qMD&fBFQ@huQN7sFCSh?$V z_EbXg|gzG!73FUD6PW@umyCRcbM)b!+7ME_{by(_=MO3}(Q~UI=teni`vjtf4 zkAC}kMn3^8YFG%wiz+JL@p^Ep3uExU1c_S1(Ygh^O-WiCJ`blj41p~aQD3?4^8j%1 zz&@aX=|6=8c1SQDJ5&!8cRHlt-jLzK>THwD%nY{<%nU{`nqQUh;Mq3^VQE2$FoHPr z8hLwa@h%K71|EJL8T9yCV>tqQ0bz|EILG`~RV0$up^F^j$5S4kFsfbrIqEW3TXtHs`NyK80PcX!t>S=hj;bPa6< zbp)E!Noul8vhPOSgS%xywek0dc~mP&0(y5h?*0nxq-1n+DKl{cCY`wEfsX@9r=QDw zf2%ewGi0avD8&!Z{_}0tO1O*Yey_3^t;W7&_kH#JCy%Gzz2v_?-~aG9<|PHN5`S$! zmp<^A{0j2N<3bDi3?9~40dVXT=vmWnyxo31*{mZ5LPkm?=drKm$Z-B`78HN4kxjr)BeHh>HNE>ze3q@*trqFG@6*13m0K{r zD%R^mHR+}Eb71?#HtcOYfU`JRuv4C(RRFiN%LjJ)T!ifVEx*t+kb$;e%a*wSpHbe` z@#liWK}c$GoWu&AhP29{$?DOuP->;(Ze*{vQ` zM`1Lxw*aI6*yq_-x7Xp09a#=5?+ojf! zEw^u2A+4Wh?%-}|e;wdS_bI)TUwIwzMlI;WkWW6iEvK{^$dmH;O z5rfA;rfWO~mSfbsrzp*cYlJ=`Q<8ZHXSmtv3n9@Kc?QnQXmw$}h9XB^$~Rp^06djA zKUDNYwi0HL>toU)wT$XuUbc^@*fPzyvWU2GXK*V8*4iO!Cel2Ssg3mZYdsjOgdH=%mWiOAq-Mvw|Rfw~w+rvi$$T36$wP@k9ep+PydE$QNs>fmP5|~>BCIWmSRyRGvk`lZtm$6J1Pdjuk{v|;u zhM5vlayWjC%H47zMtKqn0A4M`tvO9@zxywmwdaljgizdkvf;xA0)6To5^ni`HJKxd!6c2s7tJx#k6OTOB zonfEneL-2v1P3f`erpkipUCjZOxJ{R{ds$S0e$la%Jx0@+ZYbU#($7q-GN`zU)~fl z>d}gTWICW=#VPqI?DY3TBoCdlRC?gW{Oj-7OYU$p5o!wBeIaudm-SkF-RmYdMYujd z=C%}yD+)Y9UnHlQMX)X8=_o23|As4Ykh5|ug9mdTCY1Wes_zHu)9WjfsT(IpoGc2) z+z-p15gK?kWEt#2)SpG1KCP-NPwkG zI%2P#Ci43`*b>yDU-97`f2y2bc{55JucSiR|CH**R{ z^es&RZzF@{v@$2XvhUa>8W*TP-|(m$Fpu*%qrU`^WI-n6VV0=|Y6f6qgozUT%=JPw zBhU}|?Zj;_nEGPq!A)$+4phG;4-R1zm+)T+G5H}w2d(L>O#wZeuOar7Xq9=zhA2-3ziVJytkT< z<@fmu$KLa%sz%yx%H?8+Bm$b>oDAQB^7*!U8o$7*5@2n7X%#8O2&|QtXmMy$F5eQY zTtvLOHw}v|@)JEQC6DTe=X#8;EUAY|bg8(739I8}P8V;h_jPzw;U zy763tC={YE0}}~>1?YnpJTKlmZngl|lO9iOM*uV5%Fb?;$xXl{_r?>X(aN)bvnJ3Sr==V|a*NE(f4&@ED0(V-F%FPjoEJSdEFTkTXOs_iy#G)ta3!rY6 zxqa+?91K4S=pu9TyOGgv`SLNhQJ^l}E@BNnaFPDDDw%bK=N7z`ez7X5}n1EiE;(G;q(tnXAH)nmMq{ zo#7~FhTGE0m04P0S=r>~{rOzqbzMK)_w~d5A8-H%ypHpEo{tBrn^p^t0*D=`EiAb6 z3%=P-Kns7Kr!vBWwV^nWM9RAl^H~pK7vywapyThLJlSH&>O=$@DKv^q&qBEwqCCb> z?L?H(iknUzL={_oOWE4Ozq(-S4x+UXR_S0uv;*j+e1y>cHlNwHDv?&$1&W5Gd(;J> z4!TQ)=iO1*H)XeGRYe2@FF=!U_O$nw7Ff~aT?Z-lnth|nv(YEm=$yb&v>NW5MQRkB zZR$gv)#Q<_nzX(%7ahRQUuUf4MtLJLfQ8V;;dI0 zEb2gCRjP-bQ+o!At2}1H?wZRfv>rCoC_TINUYMY;E85B<7~yQ?c3dSLf)ESe$#Pk$ zq4BZ^hjoA5)*+{d1Y9#LziNC$Nc-3QABq(m(ol0$Td-!EC3mLnU9fGrkmFLDkhipG z0h%cOz|G;ovFq|d4Jb*lsBL*tnC1h&OYJrR?f&1Kc-zuClxQ z>O}C5?k=hkyXhhF8pA_Y=AW^;A&P&?AC5L+;B8iFUY-t>rZfv{VqXuP+A$E=dJ(nq9K{CTMftFs ze2>0}cmEgwpK(CNUZP*^ISt^wXYZmGd%S;b)6?!ac;Fm)J?)C*e18y7arm>x@uVsdb!v267*3^Bs-gEP@v?Eaul zE;e*x8b6ew*jz9y=F$j;?S-T2|)-0NZDc5eL~t@NC)O*|J5#9_5# z+)HXJ=}7Y3k#LD$O#O~l>08F)%Hcu9{AlHTlT1hP&Dp-gu4fp(1p56;Cy^)o54GFg zh5oF#I$Os>!fIKH3c8@&`%!)7ARZUMpJVsvHzbgXs!!IQ40 zje-qg1$)DKuDU)m)1<&Y087{*T@$N3%(z75S$Q^tW<|$Yd(vDw54;N{I-&HLT{2Pl zb>g&>iJrWi*9qFip(q5A-e8n>JLIW>ZOAaPAH2AOYI(qgOb~p1yIlhfW~rcz@DovL zCJheg=I;g3xtRCYRiJZpS&(n)ORETRq1X?~-^%#q^}G@2#e!UIEAvHkzlFJ>0Og^u z`Td1kFZGPPCedgW7y2NLJSQKO>_Ke0`%+KXZ|2!Ns@Bb}b7n-jf6SKvYK}MupvKn^ zxph4}=m!^1K#Ze+A%Q?hB7_)GEewRp{8NNaCv4%~grMRsNgERvHKr$*+~QB(m$I@4qHV4(#@T#ZvO?ngkY{ zP{KMWP|lL+2lOz-@8ZI;b+zex0T-+Z+SU!F$|ylaf!hUIPFO?iGY%Wj54-nIA4I!$ zgm1XRGqb?}FFR^meRGT#?a$r;OKq;03y1OoM`(+onwr8K^A==fQ|eeqLdMvA=(D53 zZvHs{6*~MhK}`-ay|WHMPn8r*zGa;=-k=Pr-Dnfi1D|OUjPo*Ii>qc0pKt=AtRScr zX>Q%Loh3dyaBSyE;?9WFu%iVClGzCm2S@v?Z$^lO>dUN>G69j$)-d#|) z)-89|R7W3_+%YA8T3bv&cLXMrpoP(ld#(-<uI2CEbVOC^g)jf z4mPmBSb?kUoc`!ou*SY0FATnPZQo6kS@PQIXadH727Y`FDo0trb=>#iFHR{6M1+PZ zu#djO7vRG1+w=W!-z@J14XlTf+2Ijn$S!xa5UtikFhjrOHaT*sbJhV2fL=WK%(KZW z5FF(k9RiVJKvWoClv%A;0eTUatkw}hu%7Uru$1B2f>e=tl=IE!YMJOOE^of6pxrp% zZeDX4jznnPX#d_~4MZXS&6ASI2ovUzMet}v{zn0CsKoVu6!88xp43F)A#?0+jumky zb^-4%RLoXqF^ca;0Tc~buv36DNZ_ zzOq0Dbpk6v)R^RcmQc73GadO!&vBEkKG==q2e?4{K|>bV;)lY9Xj6+_p==`|i(SA2 zIfSWJz2*&THb_r2qEKO1+#|ck&QWpcLcVdtj(7Z+oc^~SUr2-%rCwg(lZTcxRKS|V z=oCv-iNK4VtZB6tKReV~FA&fjIZVDhq4~e_r2Z-3*&nQ{xo5A^GNk38*0FKVLE{lr z+fj3PXv`RxkVA}QpYi`PEb!Fw3-*w9*^Fgb@0Ywj@|xUz7c&-gR%rw4h#UBD?7lV& z{z7hmc1WCd-`#xrn5}fGh*h*STsQf=wEGC4)HI_bANFi$wMzSJy9Bd`FjX`rt^|J< zOhTE7`}kM(<1hSEz;pN<-14F3(iy6-x@tX2>kOEbe1K=H|9O&q203;5vJr23Sk!GY zR1C%qN_8=luS`Y0=wYU<;y$z0xTYeZnJ(4<6#{gg&wN1NamsnF8~Js`n+#Xz^iKw! za~F~QPeJ(rnGpye0Qd})Md?%t_ez>ZK#M)u5x&qP|1Kziw~yjP&jR!lR3<42cB3!l zR1gOq`NZJl4G>Rlu{V`mixs%6trVIya&Sa6sYV4Md@j*$9IO3;V#gAtRvlEje}m1F zI<1x}sU%VfLa?_)J3f{oz|c(&AWq|FoMh|Kd-3%MC9IMdy5e&;nzKq<$|YCl7OSlB%n$=j=xD{{ug=FcNZ*g&PU8bXV& zHT$E?7UC{?`zcm!XK}k(7WO{i0$`aDyj$osJYFZ|1;e+Jy;y(l&DPcR{e0k|)Q`m| zn@D%^w~4c>gWvAvr1tm#`KK^RvV^JU!J$t#>~xdWy_g+e$nb5pk&xAR;_f`znFf`H zP6PlW{fSxwW#WhcZgr6bJT?YZTYAu}vh`W%8La7n&N0@N1JD4($s{Eo;2@5MAn>J8 zA6=W}@DO^3ImMJW7qdRaYgTF@72P=~b|%xs1iA(<$63k!x%_{Pgeu!!ar{&p_By3fvwKifp_wcvr>saGqjZ_22 zK%tqEVapR*Mb90))MrYc$+?S-0B|?+nX(1ej@zNqHc)u%Ou5h6rru)%XT{Wlino@E zc@w41vF+!rx1&!Qzd0xtH_7Hn6*`#gcDW=bS>5^r4aGNob|DMRQmv%72y7!^nOq^; zNLX(#A;vZmV&nuKgjyd8L+6~Ctv;Y;YeO(}%grkMFC*dXZH?4ZjvR! z$%ZzbxJB~5qgJ^9#s6qzqtLyZFMNvzPPgc5tDQJGaAZ~JyZzA7gN8CE{SL`o?|PPy zf4*}3_IG*_WMK{;dx%Eni39Gk=#pAP#8V8%#5$ z5#(Mv(2`Y*1DkWmSetlbtnkJ0g&DN z5Tw_Yc(3Q9lYD?bTU1NpIajP!(Gt!8L8xHJyYuwE9#M!u3Pg%VhwBhQh|4wLY=tGf zX(Wipk3^qNC<=*Z>LXi6;c6xRDGsO`CfCc%(zIe4JRgR6b-b8sNsDO=F*)s9&O7(u z$=4&6MW>H_f3ffg7E4Pt2@gCTGyK^4o7)q5nvLAAm@)mSH3XPB-#-a$t5#C7 zS$rPUWS-(lH~${LWWDxlwxdbWJ|b-jRYZgUs?;;_a4WvAPcAq>*;6Q{^lMfcCpQR% zU;#DafRjjutQZ6I6tujm5cLUq&pXM?YOOksq#*K;D)~tSJ2Ukz@H1 zSsuVbg_!CEJ0avO2nk-ca9~~Slha3Kf2gJ@O-meBb} zKLB@%gSxWQf0Bt6!=X4jZ?3qPOk*xzyBwwa6D&ZZe|^~eO|j@0eD=UwcCQ-5ok9gS zq~|Y!mBw1nAQ-o|M1O2g;?rq1O9o)LegPc0)PM4%nOFT{-CnxZQcy;OCW3xND*CLzAm+=G@U=w7%Fjd}#;qbHw`chK&d2Ng{NFgc%{rjU??H+SIgF zFQYx5ro?+>9dWQ#c6*XBs}xu>5}iFXlJl{%T5ZW&I~(RrVKqVml0z; znjSb>>`@;~1ef^LpSDe#tR6k{BDq3U=|Xst!e@j6V1H9?ES1aBOl9m+x6Fum#%;&3 zOKZ(s^+R>biWN|s2Gv^7&{)&PSo5C!qn@!Axf&AiUt%i&5Mn>Y0RNXo1iLJA=LWyg zd$-50vDKnJ=?|BbV<+w3MTCjY*7aeEY&lf1>tAB4CF5!XxysZ#-7)`&txgr4 zf}ZO;^1aR46o08p{gmt*w%96$S9~8Zzo%1m%GckP6Mu(%<=iihs@@GLsflujTg{*O zN#VfsS{v?ifSxN~zdOs@;Hf-C15q9!`mFEauW~c&h6L}C)d%K)8%T*|dP1Ar)EIs2 z3REa`#U29SY)F9I{*(uYK_}%h5PFUx(Nqt)s<$Y)<#zE|+{kpiOmV1;mE2_}h|dW( zW$p#f!^(2PI3M&wU^l2i=BAQ5f}B!HHKQ2CzKzU8sTW=w`HquvPYMEcpz?))aKg%EV*5Q}MwwGQLRn<~Sf)a9Hi0oW)K^3d)*tt=B`ePUJPV&d@o%ZdIJs2)LZi;9kWd?Nsk;F2iS&`WrdX#XxueE;Fw$j@!sGs}RTwuLj(uy%G4;bZUj#O{SY_$_gz7s$OyMW!``u5p3;lktg3 z#Gw8hhLqIX*(W8JbchJ3^YdsKYa||C!q3DZFfS`l?5}sUJV!uQ0sMnQh!l%8@IzeF zU#Kg25Dk>P;EMEzCyhKyKu9?91fu#5095w$_oanCu|^^?+Zydih4B51$<%F6X&>%>$~G!`K(%%8+d z<%{FWBTFCAN^<&GlPil}2RPhxl5lQV$LJd64)7SQkfCvZ>=+@K-skz^o`#A(h=V66 z*^S@w%FW)}ILYd^v^Ihrx4|3snnlNFAD2FnvpLCskaFBdPV5S^Qm5mh=A)tji7}-N z(Gd}waf6h+b|%EIbJRKQ0f;O8K1cyX?Ms#j$bA9@1YeA@T#{O`R`N<9fPKQ}_a{;{ zgFU&N83T!ivw_=oWSZ>{M%K;nFsNuHe<(HOz&`e}DyhoKCSEIyvRCs`24?RauXz_? zc@xUM6wl)Y{45p6Zm>{0St3;}6}i&u8ZPt@mgA%REce*b*$# z0tAQ#GCV*eK3k%W(8QPKjN8{aeSdhS`RlY&ZeQnqFFe_CaHx#?l2!21Xu}h0Fktht zG4$))VKTeKO4EmO5CeEJ<)+WZqoI0xNr$ajhz*q7NPmD$xs644Z4l>kL5-uC!~ zpU+`OIyG-*?qCDRb7gt)E0USJztkUV@gv##@FnA)Qu;O($T@w<->ax=okNPwyIDsr`&xGCd+#+x zm1i`p>zq1^bSA1@)v)wxV3{LuMr+C`Z564F{IYlRPk%0*Esf@dcST0R0kH{TY4%Z+ z#Fz9eGx%Du>BuXE8^1sLy~M)~ej4G|6n=GuFXa{B-RW?-D&|H(+lT>L-S(AAvZwGH zq;N^i!c(!;2R%nM7?=#L(0*i;&J)mp{uBKde`B-xF3D_;JG}hq9G5!OgnNHFW>qmU z<&>}_5KA3ktjfeDGnt>VZ|U;{;*L+O8mMcf2RuW|EL`TA0kM z<>>>OSFstL-mG6PS!cQUSdZ>%%lWbbKKFskat#C+-80Y0j$z=%i<9Iow`JhpOwwej5m4`J)jAY|9 z#NCa^il}!dMU+Ee)^v!lPqMFTN^3R8M5N~q{#52JS3MpS|G<)H>*huyb8 zKsil>c^;~dGk=_dAGA)!UI@`ar*M-aBEP0WG@(B}^QlzZl?DrFFT_Yn2i-Bxi0CI$ z2Gd`6C_Az$<5#}hjHC#g-A+d-LQ58f`GYgzY(Vo!Cch#SPdR^~HIrHrHldkyD=w?O zI4db2t5GCd2b6s;&fERL(RM9VUsA>e*USg|*&3^->H0ZCJ~>a~az;vW#yWE*7IP-| za~LJMukOPP5gc_wxr_BE7vRYA#au+CDeFz{n*P;|5|j$bfZ}ttT2StpypUeqRi?)wGGPT}B#fDlPcpH0>z3L(G$k2EUYPfTV;Fz>j17@7dY63w!laoLp z-od2n6_Wtt9)Hw9`t|Waj1v1#OsgbFGu(ixV?&RMz);`CwcYOKT37 z{jw^uS;yCQl{H>OznCqX8&0M@H}F_VzW*Zuh$}yoQ6?i}z3LvX>1u9vr~DGc9iWts zxyJBWR&Z21rPGS_cKstFEpE~vzM~b(a^PW#1(n46O1s#;GMJZ@d846?n-_2fhyg%k z+{T^b`UCt48}LV-E{-5Bny0QT?&b$kLl}eq?S+aE#&PiOEf-XT%@o3j8u4q?$t@b3 z`i%?_b)<&M5ACLL$5)Cp;GCE@MU^l6J+F)gmte~-HXPQi7GYQT-8yc2d}x7`eH zd-&e=iofmiFR_(hSX7lFgnRLJpkZyWZ|#Zr+R(Dvu%CiCD5Pk6E%A+=5tSpBR*EM4 zgNivPZ*BJ+4bDQ_kWT+d%Vyhj61eI#w9DZA%GRt>GExo#{t7W01zXwk!)?(Y>MD|M zA3;RHx(6Vp^pcD$?GjmzQ`X0tWgCvW))X0{0t_3>EiN_6m~Htd(Zr7Lp!B4v;MMB9 zjCpSwR0DSV`jD+3)M z)+VLtDWRxhy>$PVxvbb-RDlIb@z;r03Z5kSdm6$qLTvNL+qRRTEnKUH2j6BWoo=;1 zf_DF^>|TEM)sqNAnRenO4H_=|fFNO27Gg@smM4Osnn|k#q+MZ1g`Qa|`x-<9wGDx^ z=#W*<<6k|&dUQ}{5JZD^oxc_IX%o~l3oTgD--1-g6TmC(XCZkUZYOkc!Lcz$8nL)T z=vtk0Jj{dA1d)brRtKgNYqnfbtkP`y0_-Nu<>m?}NUmB|lhZ@@2;g6?-jCeyhaU#G zFVH<7|LXoxg$(L)=bG{rWJwbNrmnsc?*KhlbM>w|Ie(`1;SU)%4f}j3JKnW*$)&oj zrf>n+z5)DcfX=yMhx*yW|JOkPgR%p!KKyt@!#t*qCm?d!)|u^sO6LNaby273oJ#oel7bO#iV4(ukyc-yGL2;Cg35GhNDtR3oRopqeumA1D9bLL>G zFIb0E5tyg)x8bb6Z1l+9s|*>nCTb!Ve43p>|k-+KOJUB>z@ z(OiSpz30s>#ae;bV@pud=kFw)yITq`^cyX{JX%sQTGl&Sgaj_q;8cmRqzXfeMgH5D z9d3Q)ZZQ~ZG}eh^jO`4uiBscky+XlmmU;<2%`f+M1kf`7zH~_Xh$r{oGa@zP7< z6{t3xwyvAFt~B>tl);w!iWWUwR8L*URD$x=FpfbW<5%lf zH6;Y`ws}E;*wxRN!jv zh;goHLE)x^f0q;$RP}NT**bH3bw->zTVaa+Ve-B<@qPWx_Y&%Y4S%I1UcCQEmgU23 zw>fXq61O{VZg=->_rBWh`@2n-+8Hq28Txk-;pWa*-_FFVoyosD3|_+w`je?+ALbK3 zEZ+R^VsZ?@_^{NBe&H$*zL|b};Jp34@6+#B zpZ@;+1ZaF3Fp-5GXTq*95x1CJkC@2UOkNffbzqm@Y!`E2cPDXI`6V*X zgp+sA^7!6q@6XoHgbv@>b9}w$%-SO!`08dh8EEp=ceUH=fY4grSHIU^kFma9kmv9> z`)2jIC-@Wpe$=;1yYResBVnv>GkH~!uQ3Dq-(#{e@iGi*$HI_WFG{uPX!=^ge{HQpNtSt_8Xy94yL1I?JI0s zs~%^IXooG2v{nya!&+oX*xjocEl_fg4k5L!Z2Q0kG6b>&+G)_w?kD&-4*Cu%GD zYs8_-QIPe0=V9-UcB>Q72ImvyL~y`l+ooFE!#}@7%C}nTAF=)_Nc~AaU}KA#O~F7E z>Zvh$IvFS;KOw_4*#I#F0d!S;+_?F}IvKc;;LX(xIcuM_Or_fTwJg>4t+j026Q%VW zo%zu9T>Z`Z^{d9;w$`uVVHdrS=0b;sQ1^BNYkVxZJYMG$&!h$u1k=)xz=of|8}AUr z-axVcnV8j+TL6t0*eN+5QsV2{zgZp$j+{_G52kTz{4@Mf$R8TTaI5OPdrLj?!kto? zqR_BarNd7A%>V8~NHqmoVef92oM?DgTM_&IT^%(|`F(xOKM7@ht$j7Fv;O`2yR;`P zf>F9N|M=r#}#r3`4T9 zP|iTODo`>t@?fL*Qi(S74;bJ8dSw{WoBvKIvz0Mm$pCgj`N9*z^9S}%LOJ-=r5~aA zPeQ4;!yH8YlTgabIP5+adE`N0CzO8EaH)SMl)aHW3U$abhlDd3?^wA zi3DrA`$C_n15H_lO&06c_%BmN9NHA^B~);d`xv68?Wi&}7zQxCf^%`U7ZPUJNh1JA zL7r18@v1sTl*b%%cn*yF-5QNCU~x+OXg7Z}d#Cf91)?Kt>TjI2iatII<53L;;rULq z<=tPP+%1IAqrVVuJ>!FyOJ+Dd)Ezeq<(D6-oPze>me<{ zJk8fHbUEFB%lqro?a9O$eqdz9h&ggx>;ZmY`2+qlLjcCD4NylUGu6Lj-RA(B#PwawRG0 zH@`*dO;BK#3|ogbc6}7nu#1(g&*U^`kWIBepi_*wt_VC1PUWKk_KpidKpz8ol#ybCdSF>nZo zbimerd81dYC|$0`K!6)F1TIin?YNs(-iK*#toOd=8Fg~X#o`8eCZ9aL_;;5>OhPQs zH!{UsfKF}N z0y-;&wYA1_mIM4kLXHs^lu?|9H8AxN5I5V##4#@z5waw2VYuOymZ3(JV+L5bQIfi| zW@J@5Rczjub#zxb5^*8h#tS19VPd;%P+69xm5k$PyspCM->NOV3NNPP)7v0R{UJ`{ zFXp@3y`*z8L<`Y&WEN`hXv9y#PwOw>H|Ka*){pSTzroj2z~ZR$N(u67 zPolFiGf`}Wz#k>9V^}xw#(At3P=fSbc_~oe#-WHObI)^=6kO+{UkPUNN1&1?3H4pN z%(voXqU8IqT8rMVBQe?rek`$lI>MQjBs{SKJDnECdu;52EK)#$=p(O2T#r%gZ5Qap zSF_2-=?Cr|TbCY+6OtR{*0Su-AeUfeO*6UUwy`OHNHU;4riCFLL>|F*bN=8D5OiZ3 zr-ILQ3fKk*5s!15ddr^p#m~EEKLCP|9_oX*exGYxSD6Q53@)Ct(d7ojhT4@*)dLPa zezqPo_Eahaec(%EWlqfJRPc-}oVdDk{EfLBCH#lzEqLx^_rA2>xOm&?T&g#Kd5(?H zH?JO-*(5WbKFc~25$9?+CtQ$vMrVr*?8c$;uXa6jS_`Xf3SH}E&|yk<_iQ_R-}@#% zu4|u+Ic$D+``E9a3v}MtrkWQB0ZXsNk$KfS1t0uRcQV6c_Qx!sjZ#@ko(U zipYL5OjU{IjGB^v9io0qcC>g6V3LgsrC-3hhjav9B)2lM2AdJJdAW=w}=e<<%Y_Berq6S8`e1{*eR za8E55J^9KXsxNT0za^Ly~~?7 zOavzN_{VvY`{y(H*N=0D*hfr#-#U6XNt)WHCgqoK#)a?t;`rYO%BZBynZRF54zZn{ zGYKCOUi((=B&t1BOmwgUm29Xys?m9r{r(nfd>x|jY4%y)w~l9jK3-z|TH$-d+8=iL z`?;L;d+S!I$IP?8DaNflF5zao93U?MIQDn{6B(j5ec|^n7HeoB63{0>eMnF;uhV_- z^*R(Wgf!Lxu3o>)h1TQsAqy!bQZA4;-d+^j!ptv_*K7`A^^-nKh5oTgqMwUanRYhO zmGnwa!igl$uOZ*dB)?jK$O0GMu=grhUGC82H*5r-uvqI!2scN{hlO*toiVhP*e}5V zjHZ(RR`WGAlB*R4pllDK5}e39A1yS@@lp<37zPtMN!1y^BGgGS08N{^AZRqG(o%;S z&`S$eLcLvgzJK4Hg8;t0fFUlZJPS-e8l`sv0$4M=6*~p9Z8PLqL*%P*m+TQhkZ@*k zoaXts%(BkRiqOO)U6euc5%4NYQ(zYwlB1=w_Q8l>b(F7eRyLI5NtGJLR9Ax(Y0Puqq#~3# z8N$DxH(Lb05}L2vm9P3dpB+cyL<_VG3Um$^=w2+)XO$Khb`==ElNqB^Ohi3wXpp?N za45maB@&uMS{?3>J@?$2xp&!0 zA5mj~gIGgW_c2#R%MtG3LmB0d_c#YuqI*Rv21dnO0ImqyxxvzkF$1g(fY_dgG#C)a zMYZ%PcwjIXpsHA!%ZYTM7TW^NY|ELfLZ`2(-jJvpP}hrako)DCB8A-`s4D_s!mU?8 zqP3Qq!08aL@)=S2pQ3>%w;pGQL#`@l{G?Rm#4(7)vK1fgn_1h*}v+Oh$?b|iFu#Cf6QRT;`qH|KARxR>BFryHAr8h+5*Ur zi&Qx@)kfFQY}4<@DG2FvwQ-j0O}gc(r}3o6iR1UIErW<-$NnGQ}N1 zko!=;bi*RC1XMaGt>|ndh036sG>jB$gLt+`@DMhN zAFE5FUayLm?Z;{Z%p@-9CZy|?prTZOp|io{F1m=;WgO{|MLTa;G@|C+A=8XLM1-@Fxu$`rZ*Z8g4t<>hrXwUHM{M4h7n z2-=TmATo3Zk7}WDkr6cQ&-wsW!r#Sz1cHcAVX*<%>eyOLkyr;XTr+2BR z?^h39ym!E;cj!p(lS{oL<-KD)y%S5llfQZy;t!{d9?l+lIDhHkV)?@tJr9?c9=`hZ zaD^q_w`SD0ainkaQr}j2-}|1vou$5yzxtTsk3Jhc+B@>-+oebIN32S+9{pZ=^!L{z zK!ScIim0hV&%Ad+L5n>SV(-N1yuaxviGF_Lei;iI=5l{>Qb<@<|LrvnIsmX!tZ)Wg zBK#opKB62)P-nlbk=*jV2ZI0vo2cs&1P!7LaO@(W{agSevdxw2*Z#o8N=O}*Gc{8v z76)q?gCSPIU>_vFfIr2yp^y-HnpK1}$tD~vf<+179RLOgfy6#kfvs9OZGaoMtx>9u zVMj6TJmDZA0GN>?9%Uz#RmNjAeq*(l$LcG_K#pAv%VQ(DaIj`~GdrR5 z8*jh-uY^(peXn<%zz=`8GtN#Zhx{gBDwm{^{e{Evik*6->3<)@1kPucP0 z^78-B2_=tg=L>d1IjsmCmN`1DkT9)uV>&VxP;Ht<=SdtV16n*Y>db#9ls9G!AI{K! z0Vw7SUUJslWY+TNtaZYy?TuNh4>N*{S!W)QY16Em$(+a0Ij@8{`#(T!FUarZ+_67% z{*v>7CiB5Z=T9Wehu)YEdpIBda{f&2yh$t7_^430(L!v(LYxVu7YnoRInSLB+mS}c z8K7?fLVW~Opbv_y#(#x5wbE;ye1m>$>XLjWI-sZUVb|38L66j_Ixj{mNyoqjdZb^q-%>a|)B9jmi;N}XKNrxg6) z^wWCjO%X)8f=neaRJbizFtJ^2)+Z7Ert5BX+Jh@9tfT5D3o3y%=D;178})DWuK2&6 zd}u`Sh&m(00y9CA2Y{xO@9HAsMou5#8ZRSV9{ml5KmZZ{60@LpX-ElRC_=q8nyB|} z6nZ=fsk^@b7Yt|ir(nE7S5xFD>8peT$UP9Jq|^{ZAfQ!VnjlwGvPwAU+)0KBc&)7b z69NU<1a7cHpumm!>Z_*Ui>PZxVzcWMOR2*sirJ>fj3}INalO#P>(1hNx8OT(iv40a zZx9?)Mxn({IFJJ1RCDJvfQh$xEnRLNT(P65l&c2AGO|Q!zwY+VeTG)sBz_Y!h%{`qy8EGh zIWSt{LaW~llJFQz5AWEjz1vK~E zd^7M*2xK<@RP#M*4{7ii(S3IC@MAid9Re-q89YN66Lp?pgP4SBq!t647I(Q&2poX~ z1l1QB=kC@7T3@|4rZAXe@Dg+WuK8u#!22#*ZJI>fl*9)ePd$5k0F<77T?`hG`%F;d^RRht8uR$uQse<0K9es)5#L|Ny`6P=b@@B%!}r%DxcdG| zitw5J)r_URL0ZDU$R8G^$KSq+#w1~f7b$$`NbT96hFqdvCj0kkNahN*f^P zmY~ep8t+ekzMp@p0HFaRl)<|;j{!C>r{{5x&!-Lz)^D#VBwkdZ^C?Cb2>z#ohZ|9j zUIqOWWs*z-h6(LNNPVw)9Aq~cYb;G!5JZthCRQ9Lh?J-dl9=mr7{U21Kvtrm#n>T` z=UPtER`WTPoJu737Xu(vl?2d1yhFN!Qa>3Qidgbrme=0k|KR29W)gGQyd2v?zKxuJ zcsVXwR5P{s-E3V>u77wr#o^SPP{(Sqg^?%K)Rx@H99au2U9mKB5Zg_umMT~@C%5%O zd%&ZLkyhm7%NE>iSWX^TzD)`Zg6WX8mHuu!dUgMdThq*lW@O~UI{g-`0-k(Q2t@Lw zBBVS0ZRM0l$Fg?-AQorN{#UfhUL<4nXk>gO$$|`>cF_myaFXYYQ={qJO^ymy!B~h` z1-?*ZwE%e;1rb-(f*Uh#+uE!x$oPaFRrIcAQqU{Pe zQ7A13;}(;6+D@?!u!XWfc1|5$aR3CU_Ctja))6obm|q{XaEkS^PK7u|mfJtrnvi3b zBy;oz7LNQn@g(@fRDM`6kB`8rby91_hO4}w)MK_G&VFWq$`+h;W^frN8NGD16mA(o zAV5HW1sYxfSP8u{>Qi#(y0*fEy1?Qh|N%_7(;4 zA=ZFf&NXaU8$t(@&rOC77GkErY$`^c_nzj#LnYyMp|#Ux%$CA223W@@`>5AI6~#yp z!66fnn~ezK89xo-j+W-L78w%tr5@Gb3G@Qw&J`=)`K013oLM(1&o4M{=jyU_+#aUQ z!J5qwioJb=TuA2f=nP4?MoW?vAwPtz`Y*<9QN()NWjbb;dHof-yV(apBkF);TJN~` zK*}Te=3s6&hF21m1XZS-wPaj}^gID9fk*-;Olx!AS=k~dE3@SoG5J;Z5X<{ehAJSD z?VZ=@Z_Z9bbsQ*fK3n~GW-FZ>J4Q>b>O8Cva&zR)E2VtPXEm+>-9j7W^e#C^Pg}pa ztyb~+jMJr`8j1eu0r;Qq+yp`-vbXjed3O!mbf0255=SI8c!bX(z+JVIhwOAwM*xN( z;1gl1Xm+ocCKW79v}K=bnFfR{p9RLI-3?8*NnRf;RACFxC89<_`TOANxX5s=m*{g4 z($LhmHrGxgFs*$%K=C za=kbaa`V~s9|-=Sj0;jjgTkX1XoP#b))_x#F7$G9p1~bWgI|A0Wa(z03nMp{MFO}_ zltfZgs`@lW@Q8z-5K_&0=kdXn8z&b}64;fsa{%cT;Qygg(QQ!Zg5@0K-J5dtf#lS3 zznMo;2&`tW(%rWk916q(oT#ufLNs^#g9I{<*wkj$WpO}6moVAle4%IKle7UMu*mFl zZ2XCPA4wfK#e!?PSem=?F}~il$6B-5*mJv-M|oO6-q#dM07wEz+O>i|CQn+4_AOdB z8iBJ`yKAnECnK7wt6ZP;+{Bg+?_0qRq5?M7IKg(8%`F+88NdLtWyS<>#5ustZjV4N zzT7rx=@X>0G5T=&oioH_!5n}1{G*ZPNczIqfsM8U#CDd2YGmO|AA4bpYGhu&5_3j7 z_}w^$g>M}H`_mov5@3=zQ1;Wv!uh|zqGYnAwv!+UW-FUc^%O$8!xu?~t?|f84tWxY z_?BearYG?wNND#8FFKHyeCfS5?*Nl2H0Cn(r6(@_dk@Ygno0adZb&EmT( z+M3DkJ-G(_Cfy3Itapi;3YId5+Q377_vYs#z$S`UdHl6}&q(s0lo=ycx13O$=8=0!D7kMgelCdn^ z&IUqjoPGq5w>|qC(&{W-(nXFQ!iMa*l2bNyev7%3*?#$x+2l@yI2yBS=dy|sLcGEU zBp}#Z4=(N82pq$TGmn^W2>W@&?QM+iLb&i;@Y7+acPm1B&`qq;?f~QpBtr)KIF1ch zh;{2sL`|0I;spgOJtd%k0|TGdvNKPQ(x)0|TVVvJGX_o@tQ>)sT;-k3;?baQ;4GIK z)d2mq5LQ`eBB!0jaY3ns!GWLe7(NsMS~XY{NoewF;TSx`5Qh&%`u13e1#ma`aZGGj zzgW0oR4p{Jl^26Sc_Jih{7%ZKrk#Wa-d?{`xlO(WyzlW<1hDyq68 z$#^u0L&qJm>ww*WTM?Bl&n7d;G(cx36KzqzX<`*@lTm##RL+Zl3bBe=y7WR7Ws$GP z5lqA>G>V7|?lDK#QO84mq5u7O|w{M~}RiqwEHl!`NG^%a0J}T#V_ZCC3fTVFY41o*$`~5L30D zP8HO!KZp%Vl`Qwa92F6RiC5o3QAwRPULnaPYZ+KnR4e4As z!|(|Syv2@3Lc4xNy)2R{8jHsHO6HtSSoPCnFbc~w^A56BfYeMF`YVU5clx!bkZ+aQ zEO~Cx?QsJe%n4YQ2rA2wQfO+!+D<|z>)xGjDSbD0Io>EkCEE>fkfEFxb~CpPy@@Cq zM<3!&o+9YqNKtpPjcmW0D<6`F2S_|d_h6)OmQAMI$-1)>1U$iMD9p)%fM8(aV10tT zB@YGe?{c_LBHbr(%JcVFEcAU{N5v{tvdu8M0T>x9T#C?>*UXhDI9|O6wYrbjvta7V zWiOSFTWmJ^eqm=mR1?1>Jm}eApm@x4FlYMlcrF4MZ$TDEAP0v_*`M)Ln5JLtOD8hj zgR3}=FXZ%|M~^JAEGzJ);wT!69$Xn7_nVXa&_Hr^tilFWaS}YZVbFKyUa*SG)#Wow zE*!$Z_;n$(Ymed8{&q*T1!XSr37Ql=yVF(^(TwDW5nGs3TNE6leB~xVVIp3~mEU+= z9vM;tzihNeW3SB(2zG;Ph!Gl+@U0*|w_Y6$rvR_V(8*W;HEHk*65##;t$A8M-@iI= zsgk)f%tDR;?{9`8j&nT+k`7fP5W=O?*8ESXeXvS;+qf6nWYQ-LYKjdv5zuTKjE(F1 zjhm>N4Jp*-gV?z#^FhWjiKi-H>8o~Tjz#9omNA`>#;?cCPvZq66*$#{cq$T2lmwqS z`oMpUbDAFKF6gU>^O#M!Fq`%<=D8Hh8cvtZoILv#ZhEZfjf>Zf`eQH*cRmhYWen>xIfCJiACb z0Z^XHjKgd|DVW~?P zIx?ld8q1|YKL1E}@vdw_B^^^SkRPzOqLHje>ha7WLMQL#3>~+#1t`;RO%|0a= z>Z|J_+IILA)+2B=;C`3A&ViT8H}0@@et%zgD<(AXLy6!cF_lXXU%lg9{4mZImF1+H zue=IX+I03~Z26|^C`_U%N?ZY8aU`k*`(joYvxE+)ZF|ONB=^bSV`*n{>GT4J7ySK| z_}T=H0#!%@SM)iUs6sHRlN(ys-p~-<}OQnGB!V^XIuC0PEdau72 z?0>}03I`c``OTKjnvN>1r++eFrD{WoaPs!jt{+y%i#jj;MFHONz_lmUn z>P23$nUm*29T-?ON1(`lNOd9gz#=~I#J9E%w(^#x(1GG%PiOir!{RpQX)O9~CPpf1 z+c(Kx$OmCSWw3Ddi{Fc_`Vx2H5#+{>X&yPH4_(7x4%>9X4s^MCNkFd&HmnXi3e`4> zM3)Her%2L3U6o4z4DAXF5Nrs&Y=(N8aXccc~$X=EEWyMFysu;v<&?RAR1ot84@e^J=tNzxYl# zZQJ%+SXcHJUe57S1V2>WdeiF#*M(S(7wdP1M|i?nMa|1yH@)v>(S>zF->>FcWxbG} zpulJg4)K!lbYb0=|Kl3Euuk|(8SWSmUc%kpI>snE_coTB& z2dJDbkxUvyn1_lq?1aC2dhO)BD;~NYp@}3>Ek;Gn0`t=A+9YT*mJAI>V$;<#>?TnMdjHYH%ps{TT9`2lC&n15WK@=ul+Qr(q8Lz z^PxLzAKUZn_?aedw!n^9d%;<4M>+Qao%bv^9W6wY)ec+P35FlGIXI$r#7=X${fL7h zgSwNWg;a;r5eGB%qeoqQJC3@XOjdVx^Q+;mW%-*V;^4_|x-Mo?+?=_No_d z`_H-;`*ylnSkX_JX1bD0Kvmn2x}EMJmcWO&u*>-muXKLoCZ2PcCDsRBJFw|&&fpPd zSJXd_m#c{K_=2eF4DCD_zu!?{$ZxqrM*a*=s!w9N663{4y7-1j#Q?H{^;~W5Xi2`-v# z4yQb@L&r93Yz#|q7F7G^QF`bts?(z(>_sHKsUiJ@amp+w6ZLd);FwHZxu)-l){zo_ z*|wD`6U5;ZEI(@3tlV?xM1AHj;~E1(Rb7KNEF zP%)alciK{~VEu*dPpC)~pA|AjNw2;LB^r`^PWp4K5bE@krHFj}abF%4-`D%X(ha=$KzJG9i#%wJlqM;A)q-}%$zFB79|Ni zdQr`2+~Nr(Ynf(6v4}r)AAKa7kib*zsXP#C>6M^y2-pjfQ_xEK947&n+QqqO^Np@W zO%5jN<)-HMrJ~IIjp@7``q6>T%kejr(xLNmo>cLU(0Mu5OwR3b~-Lj5L@66Ndkt1hL zeC>7V|Mv7oJVTJ@ec#^4TC?-D7lNU1!(G+2HeMuGmp7ox8=L)O>eRK@$0_yJ>t-BInle6^-p1FX*o< zCy0`XI?sAb63qEmB0N6DSR*dK4~}ZOX;NhCfOUrsy4#n&qB!wNZ6JW02u~wroodv{ zh0$PBPt-_jV131A`>^f+e zdJMxY%g7I4@2L69p1vyX1>>E3h(Ls{kRcpaDh-G)pJaf^5+8*PJ`%r6K;-ay;XRLk zF&a}%SlQYwUZgV(|77`0t2hP1?iPR&n$&<((_L#cQK2ox?PPM>84_1+J@ z!!(%8bQnBmo`}KnPTrh!K*IEME_YUcBQgNkNM?Tr7%ae2{bhe-|Mts2;!$x642Drd zystJ=E#lsA4@BM7e6^W#E^|)IFnZkO)#u`SaVzQr(GMeEeW^fQSTi$>d0hNztIp!W zyQ2d!GhMH~-blUh!PhW${@JT=Td$O9yHAQQe(M;x@G0{3kJqU9osmbIsDjsfs}}LQPX{i3>w5k3kCTSL8}|6! zXRm*4-;4jXZg}xMnYO==q5)hqP?82yqrpvS@F&F#TrG%j8Y+o~E}$_c(R#E7&w&4$0VJZCZ%{=+OvqR7QU=tEbGLTJIU!U zcl|Mqb_ABbc&V66(da8NG1szxKSzsf>jjhMYf(E+{%S12Qf=}9M^qmkI<#A@cbt46 zC|!DE@D+8ahh~5a=dOOws)aT&n~=wmhOfsATlpyNtX<;T04}zf28RwlA*;wu4%!bl zvIwG`ux5?kDLvo~r*e5iq7Xni2tX;%2_toH5F`rU9k=9Xl-y%+jSz*xodyU|DCs3C zo=%N=Mj&WI@^QL*agkUq#>`fT`8H%Lya)$3A25-bI-MjbW&PCJ4c!cFu?^=>tqo&$u5|^Gdel#U~ zG&N~7tzb00dNiYbl$p-UVdNanY_B8!Wh4RsGIWg1m;d=lL@CJV@Sh`*{{my9HtSvY zr~;SBRG9Yg#pJ&*HuQc#R?Nf;6`!eWyTAB!oaJu>OaqdfJGKig9lrk>iL`xi#=oce z+yS7+Hvhob#C>slPJ>&h{G%Tbsc%6(ek_5ccIh|9hVIjm;h{f^EnvrB-z}~G^yzem zX_^(W@B@KMz;R!#QSzt1`*hyuB$L$CE9`&!bUGrz*=0?h8y-$rO2u$C;tW7ta zJUAmlpKiTiPBM%ax$teLu9uKIFtGpp7y5~VApoK2>?Nu0Cl{GC*62PRbJ@i|`vJ*( zr|TC}gd)}!Q?V(sZ>%hysQzsva(EoQbU)+Ik%$Z<9CyjXEK~v@`WyW@5)t4&xtPXm zl!|VkV{F8E5?#ca@p!cGg0eB%?liq0!0{M6iDG_ATc*%`Iu)qXwGGvzz(!tHz;40I zR1is`4>r!OG^}2!o)bqKCCq|!C<{Q8sYsJ<^!IuQZ7~B}=&j>{W%Zh%FL{9yL z1BO6-SUN6XVsM>45@~#*98a$Nb0kta&4036{{6M?mBzo0M230JC<2ljgb!^K!M#Qf z56l(LR&m>&`Pku`kWTLh{E4x-5@ABe*u3{*I815!?=UuJCPjYHMc zGAaGHkw{3QjV&Ex!{^t$`M-m)IaKjR&+EY>)7MR>rYxrw5-`Hy*cES$On}D3mD!T; zL^?_>;i=Wh(s%5JMBh8z1!Gt^tJ>%Se2&AZz{J=g;((_0{Nps~`4bPXX?9l#?SI~S z^=Cie_zF3ZB}wMQv#U9(FpO@3+V~4bZJ%p9%Mpc@WMO@Ps%=zsN-3r`8jgcAs!ZY& zSY#o(6X_s8gE6<|1jjzocyT@U##wU9k3V|f0DBwx`i?Lb)JNRj=R$EMDI@)s7BqlY zK6fESUeZSbn2b3LaS?3`hIoL?g{%IiOv9PD#gl*ZJ9w{P_lytj-JWCwCJsVZq6{9n zvWty+RKK#Im8)fn%{8IfUpdo|Z|Y=jhK*M8y&CR+EpC&1jGT^M=3~07*Ee*m|(aHQbo(?lejUAi-KV|=sC!IHwqGHUqCcm zI`(P7a#(XED~m@?cpjOc2~@M4MVX30oueZx88wngap>>EWXpQ4)?6~nl!Szp6`NgK z9;I(m>QH)dMhJ&oK8vKOX*6{BVxF|E*0N)-D`cXvlyxx8!-CJ0-<1BwrNqY@@4h}x ztg$Jy+{B@@u!(%5K+YB%$8;D+)`wBg{}7X!5AsY55Wgwm-F)=~^=WT<0EQCM0RG~8 zeE)4G#tyc5*$6UfWC{Yx)lEm@XT_jngI}(^4=F#%^k%;%WFen??(n0qCnyFCRx%jo zh|K=Aj*B<1E}e)T`o_mJrXge$&*VnJbo<%Nqm85S-Bq}@qGaBn0^k?k8fM zR4(+T%^{3+{q7zhv62>TjtUIjDP&Vgd)t6dwRQ^2x>;{&*Lb+@Je=c&R|Ech+5xV& zaDE{pELGXxsVk7oEA&*kC;u>7XS)wgP;ZPrWu*OR-1!a-0z`KLPS9p&dZmYhgdpUh zJ!!Jyth#)I&=H|bv+Qp_kDmM?JL2UxlSEUB5Mwr5J=LX(xM%+j>mdBbw@x)l8ldId zg^IN<_0H8p>5N4WF8O^GpMM;B^s>%#_5&Wz3yt8kyA2@Xf9i)f+FI^@{uP zymFrY4J`F8gx%!Dl1`W0gA3Qgb2(nFyYtF+-@YEvb^qn3nC)8&tT&?W*}VE(y4|;C zcO&N6{a4?5w{LG`-H2PYdA&Qo-M{nT#>MS2dD~6i{-6FI<59K?Fu}i%L_TonHG3Ab zWVa;A*e)_1+Zp0R&bc3Ie#yOH#FynMy{)C!df~&Jfwh2ukCrbma6Y03?6gWo(uN)X zIhSsYhppL>6K_R+?A*h#wUJY8m&7YlNHC+e+LoWH8dVV5W(u#~ zT4Yf3`AVm^6hu6fyP_q2S0&}niw?SKWM4FmUH*1~04`*SPw>>*6*-7>XKzJoe@a(i zd7%8q-YPDB$B|cH3%QHKYAJ*2XIrMLEIz=WhLY!lH#%i?^&Ro?_<8B5uV%it-!ts# z%)XZS)_U^Bhtqx{^ZB38rTg34`cjAX_7p!;(;7Z;T`xirZ%01gx`2(3w_0FU-Dzlk zDQOqa@v*d@EI6E3%6jLd0K?E0XS-*Kzs*bAux-hM%OBTj;Y5nS45whX-X~=>7<-Ts z=gl6y$Se2G&l`nDk*Q~E5u_Q`wk&c@*X7clI!z0!gswNYS{c-2wU>+SA!XyOHD}Rf zu;~K%rNr=;Q~5tXm^uCU`2PBjS6#yUJ9iHDZszZYt{BF@c^sb?a{1Wq)g>#_SEAgz zP4W64*sUBSJ$@czi_aHgh=#Ss`h*2f`^j={1uK!^Z6ick8c~}TD;EMgc^>{PRdKsZ zMjHnkE`VA(U`A%}R#Ui&vaSXVCPdT_#lp3fb!A&@UaCR;CLBJT@PjBIQ5+i8fQ&j2 z6)lD`7`Uf6X%7KR`9Ud#BsXIN0DlSv1|!7O$=)bHnGrFCZXpn0mD*Pp^tE;vxQ$?_ zBvwWeS|7!ISj*cwO8Afsye1m3AfhZ_yoFZ$~+#hJ)=keq(Gt zYvpXY=6plvG@Ms?U(dmYVsjjX& zJ{bvMbJcndy_(F&@fR3t7nr&gm`4{_mK0d`6xhxc*ncm;^A{f0E_8A$bdD}`Eh%*G zDLg(`c;b7ZCx4N*c9D-;(dpo}!?+qTugE1peYs?c#8^;)v+tsFLECp5nN< z;)~yliTo6jwrc|8!6Y|IS_vhihmtu*$^K3uTLn9<`MG1&o%l*-L*aE{PAcRq%J&i~ ze`%F=X?419Y!?{gTza1)>bMLfL<1Y$ln(Nj(NxR0ysXK%va{Z0f{XM($s9z?=xvaq z`&Y^c=u>3%Q#hyy%X~*$dPEK*it+`p<&VasrnE5^TFL=sBvl4_9(@_R55l#~_>`%D zFbTXK03tyc9o@j3dzoF#`}@uK*XwYLdq~*gqZ!q%<5Kom=#w1gWK50Myd>k3${+;%at$PnC3}|EmT}Yp%5~wT(xN~G z(<1mGy)N2a?qW=xe`%4mKz&JQeOhmQ=Kg$r_HI2{pdnAEp}@VND5il@+ECitP(I&q zWw(JU&{(C@Snb|eJAbhLJJ>i5zKm#;<)G5JCUtK0*O|lxs31T@&{??kCDe{y@o*w| zk_>k&_85>CKSxDXia{oX=0gbxECJU4u35$ym8cBeKgwfDWqLBt{lN+nZoI+?)JW0b z!lfVs4uQzkU!JQ(gD_4U@U9W9PSOMLwQ)?qyOJB)D%XL9s|XcPnOvzpe~q0e4FTZL z6Y%6SjpHs+bX`o%g`ap?v)IiR9-w)WU3muX)lR`@q2;- zfOK~t$lMDaRJiuXzG>6FK>GWto>6b4pe}~JC3`vsgrI782*^m_s+WrrX=#UVmclk8 z?G>OS&#wV^kQ+iE24mz&GWJn?H{Z3#xn;I9L zt|u97>7E_Rhf((%yJV}H==}w`K~xeRHvO)v$MJyau}-B*_}MTHX{hp#Evm>5jK58X z+K|!tTJ?ki>*L4^9 zTLA6Kn(58VGqO74b!xlqh)P94qP^WIP^%Mz=cV>Bw|v(D*~f3i#&kfF)lFv52s5x@ zRSE2Gzzt(B*I}WPlYNdV{pv>P4`QGK3e*t6;l0t%L26?dgqz30YjvS;GGiJuh8GV2 zv};CFU92RAlT!oF8u}F~89lI2p3x2X<~4!EtGDa1E)Y{MQ+=h?pbCkGAYBnu0oSxa z4m~sl2V8UGJmN`<#Gs#zH*f+iSkD{6x$1_@-PE^W!Vivby1Y6-4ce<|0$=eLcf7+^q|usdk?h5Pi=TROLfYR14g6sI%+WKrw`h)o-E9e?=1P929t zal<;5zz0U@7P;QTDq*PB#;ZL!{oeskibx$JP%g+5zge)=MCEja+moQu!<8e9;?zZ zHpPFAL|*M#&Sg$Vk^1${@-OU68)wOmt(KV3MZcFFaIZ8aeZl8%Y4rG=T9^$2nFWqhlb_WGwO} zw|Yh?Hx+U9@v{?Cw{PQS(=N|WSLG`nz_1f~GA?t(3C|USa|I7DAoy40uoV4Pv-Ll} z)%+9a(Kvzj`H#q9`j+F*TaEC)13mt_<@n33=5Je$e<6o2+x*>q{PKR+jn@N2IP-r( z4*#buhsi%~HUG(d+#UA*)q`7If4u(B?&Ha;Hh;U-%-%dh-*VjA{$t_JvHg!S{e9p6 zyw&_h4sUO~yJQ^Lalxr#d`&Of|zLbwQms_T9IRcgoU4P$djz_F7 z7kj42t zFxINf7z<|LA<*J~wct7*3)hfSV?($COTkDj)!_7y!@=1}6C;B-Y$A(N(%*m{rL)Ox zGx9mn$3mX{3TRaH}GNO6Als$4>U3FTi7t=kIQso0s64bCNk}W#Bmuiwar|vt`Ebi zvV(;W7zT-bepuKs{3mjFYtoeWteTgt(6uM5*3a5ar

Ri|wY+e4WT$QHEPDwPL0 z&*<#3oVVpkLIbQKy2EtYab_tr!bv(Xo6I|||Bd>(bS4ewcYJ?g@MUrWY-i!PnF3k0 zU0LE`kmfOysB$MKwE+K*Y)iJvIomyUE9Ga-BU<5uc4T3vZq^cE2OmVtYS82I2%|T( z3+_EY(8TV??!O_2KmGWFhB~;nG0b}|&hdR5ru^uxPoA%fzex zT9gd6-8m65dZ?mMi0{{)V6^#tWFd7B^H7Pe@i48e=|XX_7P1l5&ef%sn{mj);3wssW3)>At1xu()|rjQKy@$N$)JjL5rh z(zhH{JYA!|-N%_eO$krhw5diRZg{<@D}(&8MUod zEgqXVt@EX1GP72#Ze7xxWf-I}BW_8)1?(U6*azJ@64$pnEdD%!5zn0FjsD4-x_N z0xp=~STf22sI-6|v6LsHisvQwmn@%&hbDGscU)gY;BfF5jijh%Ctj{mLk0oPj+uoD z`LpkRUNyQZt8})Wh*9+Ek(?U~Y-lSQ;W+I8n@NOb#47Bp{JcJ^-qt__RX+IOp%I(+ zgbh(Ht)a+SF2jn)W;v4$^zKuTgV<^zq)o%V33*D=L-c$1l=7_2DAGx~*)DTt37 z64yB~sxU#mln``CqU?}0LROiK<T8)N_9m62x5%A4^g>HKH}^EA+O2ao9ScnQ zMxclHL&~YiqJ$9N`Q}e-jFl=zEOli5BVc&vG@)8n)dxTuGwZK|UG{pAJhpJ^d^Rf@ zR9;W2KP0B=$}=1sQCYU$B<{*7tLIBzE}5iFYg0CG-h_8TqX0#9bnsR-Vcjy;oKbvh ztMREk^vv7mDE#{;xADODPiR$eeOH+Fk;m$Sk{a2Im&SxX<30v9tzQ^&qW=xTj#`9U z*4K7A3;GTO%Z*h2<5m-K>&MHD?5@65yYevJ;a6KLn11HZ6>;13oYNa!G?e{Dg5cf) z+M#=h_u)p0?q86@dvEw2b>G!|xS1Wh_ZG|EGiqV~Ij?MQNp|0%XWZrC=b~GC%gQ-D z6MptzN}tnjHII58Mn3#<<@c?Iow+CR(-pO0uh&1Md!w>1hS%u+T*v41KB@bqdk>_Q zI&HJDwc}G%m06f{iS02kwXL!)8bVQv6nUyeBc`#A|5?j-|C{#Pz0ZGsiek4$$p;;0 z-w_tWJ@^s2qqH-0GvrfBT{cINn3sm6h|WB0SUQ3x4@7}{usMW+$bPvBU5s$blEf6J zoMK0~q7zf347e^v*+hwLS^^*-O$6sIF~BzvxKD}16&m7#%wU)zuNf6;*+03Q+dC(r{KMMP7GR?B}TP3U4*IEbE#i$?)})Di1* z)nidgrbLJv&j2&JAeI2I6^FAYAU^t`jg%qh763*9GnAn~9JHKDx-JGh(!{9yCpLL8 z0G?<7hhk_=U~Wy+qXSXEsc_f54XvfO*^?SPRiclNARRq4WeL)GxIo~>XZw}i--02b8?`;SKD!meqj8mB;k;g%#NTS?jS#wB-oudoDOg*w`9dE zlGzwjacdmA-Rb^|amtlU@&ph;%MAiy${V0&1c#h9hx9^@WB?}zL}vG-Ly6Ur2DCZfHP|oc+!+drPap zJsP^_U+@R_MThms=Q1Gw1~_vMBvU|cYQd9Y(04kLhgu*)0B6yFqa69-TAZ|Uv65R7 zOeG8ESO`-w5wuF&a8y7c7w+2V4D?W&d9}!C2ett7g}*k5(>pWN2+&|rSGL(6=%3# zbx4DhEMr~F+E6Jro?#w+0aMB;NC3sYRC;e-Js4eWX)RQnUu|0|VLo4tcb8x!SfY$; z4n~sL$u;i1HOJ>`PVClr3e^4^a=5oPh^ZE!0nR!Qnp)!+$j{6{@o^;K(ppH@XEFM zZcOuNY4dn*^Td4f!`|lM(&nk%<|ppgW@4_*mR`HtSaUBU|9oB5Uy;LW8P}7#uZxne zf7-piA#mff&W*Q$g>N$Ihe~hk_TIpKLGA6{0M1Avp%za^w$qj^-h=h%ChogEEo?tp zAi-9BO$Ux!+z2Q2A?H?CG2QycR=YuE5e4pmBkCPIZT5rC((k!zirUPL92Et*dB3!& z>fTg4c2gttpUC0oHwPL`49;*pAO}Z|W6T6GR|2?3y4!7-YizAJg84fR>vlLD>u`?k za4qX_ztwU4d54D}-{ZuP6S|!~$2w2PcKVlf2EH%4QA);6)e_FsBBm||$3%t*w9|ne zF}J$neyA``cIo~bR}uwC0X_d`F|mS(`L`H4E3BWkF_VzQH@|Imj@xI=E4Gh3^&BPoKZ&7oOJvgw zq*1PALZ?@VlH_{zX>Yy%!x*~mceZ9vZjBmx4WOYF`fzJi+b?OqkplAT)dkM~#+B?D z@x(Jq6942%Hoj|Y?))7??e{GPJ@f&bU30fak_nrgQaFrBD=qy=Gu&T8;AEeTYo<_o{mcJlZ$vuh9WjS~-LX1f^%p-tRsKQwc2ykj4Juj$A z*nZ`qvTs6G?v^#Nw~(_j|DYB3w!zG7O0hk$zSu~Kta@L%U-k_f!>R8pR{UNcaq`$F zcQF+QoqGK)h1u7!s8Kxd*A92B902l~f`9zy7%Ixu=`DDp&u(jMJAlysDHXsDExchq`s>pf$|*8Rto`*gwEFs$$qu~3C*h|q zKMW|H)c?tv!gRS9L)o66|$$>K;=Ir2|MRmNqtL$|JC&ob*8TR+abn~agRYp|X^3~##j z#8h;2)@GAyx@4uHR^v9OeVBXQ<iA?)pf?9*ZlO2B0J90hhl3Vgm&6q z`T2ojtT3;fTO?h0dj@ydChtzaPXNs8?1;4>WqLm)=~Tq79=ao*hK47@JH5%-4hFowN=+)f$Lk<>KW3tcp->!80GU5 z&G_moiL=`o>&9ov?~YR(75BNebly&a$LdznRtUC&lC-9$qVGVPl9=^JYX%Rogtmh~ z3tt-jQ1v!RO<}l|lww*=g3h2#`AiKik*64a-uq{Zo!Lmn^)mvueGy@1A-JE2wxwh~ zP>}a*TX3Fjt~$Y65Wvdl;4?7CxJ>uMI%da&0W2D5Ho^KMM-&i7my(0rCaz*uwHew{ zlK2X-g-0y;vx%t^FE-Im-HH6lZHWmxl?_^hgQ6etkVI0>GM-5(LEPsunsl5+ z$Sgr*UX&C&}ih$?=-Nl7;fdlq#l z$$?n{P>(Y;Jzq0TL`*L8owAWSwrP7xz;d8v9_6qzB=~E?ntlk{kcUPTM8w!}eM>S9 z-^Y*r^7}eJEOys3A^OBC9eq~>5P^k1ihreZK}+A4Yr`+q764eOjBL9GJ1i{KFriW0 z!3S;NOFt|;qAAT*VF7%;+FzW*YsnCPBZ`$kg-vQ&E*%xU{PM{D?(BcXl^ht$endnS zu>&O!bFkBf1Lu?gV$sskW%uI0#8CYARq;(!=#B;vq!5|9i7c~3wjCnGN8->TanZSw zQ6xSJNuZk~G)ofMAz}FvR#rj91yIs6L0UFJzB@s2HbH6UH&;@X5*`_*IVA%L0Kk9@ zM1S^~S;c%xg(7@G0i3viC#VypNsl(NG*G=ec1$zTwi48y*VYuqrJ{ z*D}6vG@Z_(fi1;lt%7(dh{w~4n}i6&!%m*kzNic0y@=bZHIUd^1;i{X5;HS(;`6 zYj-Q_j4tagDeLVi>zgaKNw%FWaY`S1boLw$T;lxjI{J zTu(w(v%)Kka?k9!aU;G}7%o=8+_@@`P|>ASrd}$`Je6&i3JFwl=u~o9Um)HKeHo3> z_2(LRRw+DAN#^^Hl>sUFWX0VoWr3@zI#<=)uPXNzE%0+V_WZ+qBT#K<4Ozgdxnrs= zORKGWt8J|X?7w4X=Bm;EmR|rsmi~ zjKVKfDLXPKfzI`N>F&czR1XDv8O5IH;h z=QCPaz`#XhJp2zj7k~5bmFJ!>tCMqgjr=9dw%-5c8ST=(sKbB#jP|$uV)!B+K%%L? z&7Gb;F#0nZ5oKL8!tYcdh8KiowPYxXsMRkTeL(bhgfF`SiF@80GOpy`2vd z4GCpN`{ecJ_KQok6#!FLj{cnwDi%TkX`3UwM**_Az{#Loq)@TiP5EllE4evjhx3_h zX6GX^9_cNI!|w4CfLKLXc}S?ccYd=X51Hgo1&LGZ6m2i=AbDj)b4 zf4K*Dhty*%gy408!2*79AWm%KSA!e#wsX)X&OaiM{h(i(k-0z!H6w6z8r*0S82FWO zcW_xr5XFD=gG#3U4*(D{%rcrB9?^ULL&~uH^Gy{YKOx(;QFBoi;*?BIP)pBpFWAgS z2#4Kh(x;m{J^VilD2~d>9O#@K=xx0x8vjA;>!5%6@lU<6w(yTL;m@*)iVuIg;zwKqpnXkTvKMKC6EM?aze!k(& zZg6ig9{VYc{wW@!dLJojYtGp)ocO3BbLILiy7=!?to@PDR}-u7)a-X6u}h@A&-F@| zE#9T`9!`@e4u4}Q)}Qz48@+BDa#wV8_{-YPPJ39kPIYJEqpQmmIlr{G*4{P}2A-YU zw=QckIX{HBl({GRSOEb5J1Af;CngOiDDEu78LeUj z@A6=r``A}D2)ZA<0AAS)=k_-o0n_vHeeUZ>GpK$L zi~Dlus-#RnZQmR`+$!uU40CU6n03SJiGrD;yCahY)h@Nz-%RmvE^VKm?R>wrz@T{K zh`W5AuRnUWryrZ*IxCS`z_KFwr8CDlPK*$St$HUU28jr?l$hI^DVn>DuTACVMD4v6 z;w}u z+Oo0&cV$ItsZIAND=RCTe);@<|G{~j$9?W|-`DH9o>%9scjq+Z8)6ppBrE$CqP9lz zGF2aLRJ!(BpGbd z*i5)Xh^d;*aHE>!N%=?9j?#l2TO+d@x9n*FN|zXkmh zRep9U8W}#{77=%T?y~GMOth1K=ja_}>~yM8oEnLLE^3x`;F&ixY1V!bDLk~AXSEu@ z#F9f8y1k_9;^v>$_0dzdiMg^#(9=T0))y$hV-=nA7F$h?GM=tl zcjkYPx0i1saC8!{-z8k%8uO&yP;Wnu*+6#GLq9AG)6!HD_np5N)Y!axls3rS_y|#v z=pC&Ixbx3_QT5pE>()&m%>6PjHkVTRGk4>D0&ULD?GRP=ZDPiGzR}jSr-h0W*9C3c zqddP=&ABHYPM&nH{*v`4f-twXd82vH-rS38IXb`${Bxpd`43y2TZJ$yww1sV!YuDd!#^zSyLlFtzjJ_^3vva-aDfm=2~MyZ~HluH2y|`lu=2 zC^;2cUl~vQBr80h)f{ztvfHZkaln%^+B>vWSN_{np0qD{r6l0b7?}$vu|Qr|^{)RE zSpHiaG^@URpXM@cG)`%Zg@Ir55R7WWNCW%8)$VOmD{^J8A}_ApWEmxVk~uxLb6TL? z;s2@R2lDFYz>mW3#YpcW)B5JkxR)VEuU%dInKVJPekOOQ@~({NOGMMq?=ZEK_?O2eA}{D<9vqH2>RG-0;CuJ@^gaKD zd~|y+7d!jq&8-*OG;M&0&ncafd;g2L>tM(UNepA>lhHkvLxf;2A^P^c3diQtsFmYN3`w6MR?M2 z+2tJg`Vu%tBdc#o;~q=8ljqrRgwhUmj&;J$m^y+F89u8_%$~Cv(@m)!avB&rDw~?p z%y#^EE{N((b0`x%6!f*GJ}Xkd151A*Bf{eg~*q=Zp(^)o9hVLt-x zhRB2A?y(HRMDkJXM)Sx@|F_?dN>`-3A3dl&4E5-Mrlx?!jb7>d_ie@I8i~L<6!rBarwx5+Odz{57Gdr!xC480UQ?`s?&yUCFcU7ZL?_V5(4CYd ztqzb98F+^cCryL560na&MQ{z(ItUTY6ORLW zTdW!lHn7se9f+E5Cd;!t$0|-Ive4*CiOfx&Ph`2jIqOo4;{@LK`o_^qn#OZ^+=7k5 zoof|41(0q3Gm!#mGi3uOz<;ZV*!q*<_4yY3e2h%i_WUi%jZ){Z2>Y7_zAHT7B*(3p zXSbA&IT`9}?XB?tY}ATVtjLJM=hu%2sqYWNm7WzJwI)B~oBBT<%#ekE=)b_v*7|kP*s7Pc8+`aZ;(l2N=|4HrlZMAb~TsQm($)6#ic%-9{M64%WjV~DrAO!etk2ybq> zV|Po6nr7|XVa`ZYg_1*LAt#cic_g%)h?DcY~?*o&yZ)2{@kYON`=j(&rLvWnP5^P z_+Lwd-Y*b>hdK78VPB1^z(l&F12zP$ut3+o;pWLdV0my)l>Tf~9X_2iRp)1Qp}nO( zE8m!KE5x?a`28tEdmvSd-@tM^w{IATCU4__VAA!N+nae{qr{Vt6B1s04HJS)XdD2ZTk<==2kL+OS%7~sL7LSXeph^M8J^p{WI`HLB7PYx;r zn+cXDcgmjzAw`%8YrHzWP_Mst17XY~zwrM2-ozwb> ze)zYo*x3izvj7knf8Ao(dZJ_B#K!fc_q*AU^w8Ag@NJenSQF9BY2P-}2K)55wbtho zCxY%f%?=rBtV7NQfmGH&3h}@hMp03{q?(Cl)$ROV&BHvuEC1c@vCh0=pX0w>JKn0? z!#byMf2A|)qG>==;u~Gl9f}vOZ@z?*HbC6dAl9w!N^|(m#yfvg0u1qD)_NCC?GnlWWg#^-VN+Xhqrl2 zT~=B} zJaY;X26d)mKS}`PoA4+@>`07EgdsL05xR#A*DdNbB|;-dr8m|PJ#n`Z_7<*an+E*o zF)y-wy6*LQ!FAg}AFw%ZpBKS+rDfrp)Iq(SSK3#8?N->XL^f$E=e9xTPO`M3hy1og zNL5vXQOBSZ_1xbTE{XX7<(;Xj0x@4ZW;YEnPkeZzwq4QWA+UB#RRS=gv}@7NC5_;A z(siEbz!#qlwcFevuU?m~bj=hEk6G+$f?9ny35FpP8SfK3i?|NV92)%_i)`1?oD zN!4x8og%P09dzqAsG=;o-d4UiM)uOG%+Gxz7Bgh2liGg?tu5R83_UzUZ}_*Kk9)dm zHSyf5wO;~cL6^Q_pLZp&@Re)yenEPov1YU5{65FHfSf%Jh9AmuC?arh;9Y3}@PXeM ze(1>`)iLGIy2+d0_Qm`8-;5Hew%pTdJdyDH-Z%s>ih6{M+5wfJT+rI_kP`v7MSQ4m z40nr$zbw9a%ecpURIMK>b6T9%0Qfh3(l;M2kS;gOgJoDVj-Y0%0&!cus zVPzUi080%B?X`nVg>9|n%bp0$36DlwKR-s7_O8@jjJB`jf>YyTb0}kN^mLJJ)-7Yz zek$iclg6VImB@s|iDyNUAl z$akJd&b%FZt>8}At{p@9$~J^Yzv3N`AKYbv?RS zzbyGoYaANB=K|^R%a8jLc8X?;g2g)*T2QF)KUOORqD6rOj9_bGz?JSYH}_$;CTed5 zrlmKZJ^&xecRTdZbZvQE7sB<#?oH?#iW-96eRYUye&Srgp2-8>MRo(fkae*o2~{oy+~Y5MPgd%o1|KlGx`CqHi6QOX%Y z;MH#*6+gZUQ+T6zz^`2-@n{Xx!=v9^Jn~`q&0bLrR_X1%l0&7-v;Bcf#o~r-Dhw97&=k;IKF%N(F5Rq8bu->JpLS%!^@!ZA^TMdT*Q4?*=!oy{ zpqsW&tu1%A3nYHNkvKR031c5ktz67P)v{l|fgcBj>;T39VDPb0Y5-PmdNt>eMv)u# zDFJ&zjQxniu18BMep359?|bk0=f{uAA@}ODR4QPQU|`(dz>hK6rX2J=`KdmKb;?veSn6%S>0Q#*ERQ^-}{rQf(GHT8lc8TU4d*(_|h7 zo<~S4s_NU46EAH6>UJFc2UYf6rZ+eit2@^CHmm9D(gT!{Z$;R@%8qajdN;|s3G+t*=jjEsd$ShbmM`{ieIC5Z0`Dn_?=IZ^qu2J1P78AwJ z>buRfq7qM=`RI84hV(@i2QL zMpxhd9=jkhOh^z>trg=jG;{1la*0H+2U2D-A^Stw(M$T?Vbg5F->?art>7^1 z^?3ihV*_sQ&Hksh8Cr8g1fiG-T4wtTd|&%mcfBjlzxYe((N`{+3lgX zaE+y|ZRq1{b3#Vr4bteThC|ByxHt#&&PBWQ`eXx&c+e{BnV;7rff=~L@(avSbSkZ` zE17ZNMc~hOhZk-g3^Wd3vf^nilslgCL?ASkovL2#A*8n^KEttL8b2RWDcI#`cUK@BkN%;1vD>M_vP5UUoB%rrjQf>hc=}p zcFM=w3z9q6{bLf--*foZr1#63r#@QXFuY%XQ=efh6TfiKo*mKg*8-MoBmmLp`_+EX zFi!Hz|Auy?-sToJeh_$Qpf;wdo<$uw`>xn__WbZqFH!u@Y@psJ@%jfG;D-8@$OXub zYXh#ia!!@oYtwIV4?jkJEuq~C(0Y827hbr$XHo!Zb>B%T4@h1L4I`~i-cI?TXzcv1xzw9Y@b4qQDcN5N@nE%u7Yv z&0w{pi%vtDx-7a6v`aWN#LlR{!Xjp_JvsXEy`t=~X)rF5!8n%<*!m7puD3B@0GWzm z;=npxIhZ|oA#!jO1jLvW`avV`12LV))+3bnQn16Grqog+1L+)WPHYDCP7wo6CD}vn zhnVZ_ZbAYEWlG;)McKWpm&lsT5I2J5(xk+i*MMHW^wG&O9Sk+D(cm>|`3CGLA))9X zs8nv}eFc56zS?YGiPvLeI-LK{7cJ>AgaO;h03kq}PsO_jI)>kj|5hPf8?>pVO6z>WX^85s2vP_z zCLqm-0skL~Cg~Ph^L=}3YkzBf++P2wJvR!vWA$=I$+%Mq_2|EQddu`hAZ;znGkRq4 z<$cC=#DC(}MDR4WrXctd)sD7MU7Z)W^NLjiFy3dg3^N^0%b z!_*ukXrPN$+k#AL<6R@3H@{JcBr6ugSe3pn(?${zDjiIjF6QpqK>_4lnqevnS5%ki z-M0mPs3S&s_M%mXY^c?9%G_em7kvY%%tQwR8@H8O6L7Ta`F4qm9Nx3jU1dmDhjzoddtc=$&fd7nmz4Ua{j(ET# zx&M0n*PU}jmz#Mu z#*dXtC74SX;%lu9K;jfO8#zr>|F@jC^N%o2(k$Qg7d%7sRfF>?O5kDh-w=*+8{Y^0 z9fH`Q5VpV2DkSM@jAEExxQ^E6Bx>f~vRicx$}MK4Umco;R#R?klruo*=X7)~=2;JWFvrHz&=dzpd z)-IEhZu_#A7q?520V`47nT-};T&OnQ0kZA6_Icajk?TX6sO;PNUw>s!g`1CxiXBkr zPvI^qzL%A%E$6zxI{U8PFS{E0kcUT|pmoZ~qDua`L4ZIMKH;V+33R#{*i0rh9v`Nv zm-ksW^%=U}H51-U=YfeQRBWlrn$WGBMq5FU`Dje>#727<4YO2D+qq)N*SonQQyXJ; z`>t|}@hay(s-%iujSs%Wnq&`PA^5hPiW`6w1@P_`9%l^LBn<>`9D$qm3x!vVfcERL zm|?SC$kaJWYJGK(&c;jPrH5E&u2C+tzf3}?17X@)nMTd!=QQ7Ked$mTDCsrA^^_er za&n714MaM`8V?)rFB&*(K6IqNFv$F*|5%=X3_HYKb8d2AIzL-+N+J4IFT+;nURkel z7m?ptZQx-rg=~pVl97z9Z2fwLys!8>ctG5-;u8cm5I^Y*Y?GtpeAr>Acz(EKzGmS! z_u?MSIV7stEWe;jGDR<^qPEVf978iRnA{i`R?>Pykr5uMhu2@VyUB@uM~dWg6Jud* znZsNy-QGA*--D84!!E_^!xuOYnw#XU=3vCCA-4Ygy&M(2acu6eRohE(J_EHB#Fdh1 zns}dcR_=iu@wWTw$>j9&uL+(u`^~nUpknqtJ~WQm)9z#hFQH?R(BwuG9y3G0j`Nz zbkby||1{zlFd{Gf~2>83neKW>LdVlL?(&r(0>pSYM5LnAqxk#&TT_^Yn zFg25+_>2?pK4Wy+ZY54hGJa)0k{uw7K2(W$1d4&5uif>^{K;2`CpX9@7i)(Ef%${0 z_I1@n$_qkt=0iE0a)bBfF+MT`3sZF4;h@p+h*8-)LsFjE8nNq%OU@8cBCG< z7$PWti*Cub)e{-k*2G?Zqok|$$epnKbgbHVQ#^RlNFEcTWfxvTbhtfqq1jNA>~q;J zxfPxAU#Bs@Fw(DzUkjXY=Dv5joFi3>?Rt?VM99IWF1US#PCC;(&=Hk0=JCw8*-$fM zI9sQAZ2Q3O=ueZCy>@$kQT<5%^CvyUF-M;7*<}FvttP+s zl*>gGh(Y&OhV@}TcJFUiHSk1s19T{IVl(yHWTDz!(-+r_T%PMBcaC2f(s_9Pi5wUI zH^4ojyfOVGQi(P`cY+f6y-%Gn--C~;7B08l9(d_J?*!Kl0IULZh%CtsW(xPwW!T>SsMpW0875Cp zMt&oj64bXx_$Q$(zw9Zxws5j{?eeDlY5rri3r5SRTy4Ww5ImB8&Gf-kL2_^*tJDlz z3fMs71t1_1Z#JDDllJCgvIIgO7V>`bg32=s8wJ^-Q|!W?sNnw4%=$7^(P#9YJ4f@? zU_i*Xo9IMN`tH}yzJ-L_?B|*W{7GHN!&% zcIR(d zS0{CHZcV!e9s}jSedQ>xiSs=9_Q$+v=3G|~M%ItTl#M}L{t&u3FcTyWpe2TF2tb;Q z3)@MM%NuAapZ)%u(7ch z<)UW()_NV2(w-Ji$3>E9OoU6W+@)}PyU1W2S-C`3%Hc%?GQ^83?pTO^lYVPgNIubX z@y-EuC4SNC4S4X+OzUWbYeNKlEtwgDpSA!E^m%Ul}$Y zq1)ttkBox9)(&JB9*hou6SJcvHu)fV#ic@$$%G6uchC`Wm-dgC>I<7#x`8Vd9}BI? zOFfU44{1--IE@r7(o0UoX+8DJefAKsg9#dD`YzuI$X$4U_{@3#c%h-@7}GY5Nu!2>uKSVo%s6}$KmuGRb zDbe3Q*JqTBZ{}8@R$^GvR!nJ9j?nVM$&?TC{s&DD@ne@4hO^&4bi%D1i!NP^%l&rX z&m#beXUdXuga<8{B~iHDs|$mR5G%m*H6oF_#qRMk@#AvF`Hx--VQ-x#G{Tt(UZ52g zCe&G-yt;qM;uGkyvH0CJbHu1Z){gPL-=FSvMem2V#~1iNTBPlUGnlei_Rg4`NID`z zkav{y!AfflH_IbM8zMAL6{7KZXH|-^NfB_cL=q#n)Dm^`!73z{E?vhS!3yo@eQ2Sl|0`KmI4-h zu`Y2_t0nZN|B;$YrqwYZcr(+yD!1#+;jK5mZbx7_Q;6iMYzzRl99muif`boSqHUW{ zNds`hx9`XvwoP4kuG9`!%GDvTR2iRX+Y)QOf5`KTGK^;#O~cj(Z`$Oo`)o`8XmvPa zI>!iErO=T?WPW>lunaTIR2|L^MSVYmYpTxFp4`X!(@`T0%Z zE`n}yXx{gjQVFBCh|HKgcXA?OlD)qwZ)NmwY-p8yHz+YWCT=3{sMQZ|-PGJp7(n`z zJhbRPc9{5IN@n(tkb2$DKDgOK20NG(aFNy?bMm zTe;EB2l?t}%afo0y)b`iqhu@k@N~Y*28u!vXRW~i1r{9$0b)36JQi+kqv~GjmX5Hx zDkuWae=&oiEa(3R05Mi+)ruL1pRkJG!cT7bwQgQMy62bu4C=zxA)0kwOF-TcdR}BR z5WXwEjt`o!{t1|}-uo>#>Ha>RCtU}~;+Q|Xez?pgXEx8j?2fip?+~R%|Gqu+yJzC} zou%J*fBe3O_#;sKBh>xVyX{Y(^Pm2JKLgQ!22=kG<^371{B!@pp9eSoXvm)oWNie5 zzcaq|=gCqjV0kie5w)>#(>o55`GBBr^IP=h_tecFKTrp9H-Ao0CtNRFUe5Y8alAg_LmhyW6$j%1 zN+Y3{gH|+6SY9Lcb8)&pZ84uU28)!p9bR4jtU1ina4s{9{i5}tTtA>IVdaaqM~=@y zl9tR@oyWB{sb5xCzUqqjv^<&K>l=T%-sY=qX|bN^tqZz zr2135WD|U(w}eSQFB?57KYw0QS57M%W7N%Hqbw%{7tq=O;Y@PIyPx}$f$2mN%@V_b zNE}eDR|A}f1$|B={@PR2p*lG8bXHlaek;sTB*cc{!=O-Wj<+M;#h2d;4a3ya(E3^8 zfHQ^ZJ%G~{&>a;W2;PqJ_RN_+gi8ljs1QmvfaAh_K@Ko$^FvPZ#5le{VW#eLHdc3% z0akKPBfzD1mh%DWzJFpiSBzkqDy_Xihrtznh4wJDK)@bv>boXHpatZ9n1aJA7JF~G z2sD5WeYyg&004Q>mzSD@K|-;|Slh>t({x3fx24=&)ucRh1l>6#>^LurA`Q z9ms6N&gDXfURbKYUfz^YY=HZwWJ^`t62RhsU6|BMczisah9~Sx6e36l8&nBD58fO$ zrkPJsCeNSlgIOA2uR^y1R4~4qZPE`#A71OjlGi^72j%5Xv!G5q!d3v^7&PU^9_`pq zH3t!v9k*SbPPebrO@ge{RDMjCXgM2_@y;kRB!gDZep9h%aPAH7ee>-){ZAJzMI&`8 zd~psM$+b8a5)|))B33l}I1@Zbe2RSQvP^+`*7%H@+K898E1|%gUm)-AYnr3p3Ox+_ zk#A0SCKdFU2w|{p;&H-e1*zeIm;mIHC%?|ir{FcvFf!-QvKSVJ6hUz$$~W#B+=I>r zG`UQ9Eml4}Pym4?LS-0y!#*JeewYM8-{o^Kfy{8F4RI|qF%QK_1dDNoC__GAL0FS4 zSY`t@1dsuNE?wc$FW;LAvyYq&h%N(UXfsg5NSX|(7J!(^z;@8V5aTrg#+M4!&<8`x zrbi}`OqANjnq;7WqheN%z>R;xaghB`oem1=94vWl45;HwW|Qe zbI^VR*x5tDvQQ)oAveucifl;7H-j;56sX4^J~%FcqLEvXEtgK(bthBXFd_)M3G-!Q zcZ>Sv>U04|Lq0A$F-Kov?IATL967cd*m^W5AGT(Sz24^VqiyY;+cE{X-L`1@jhREm zG~fdGXT{Pl6l8d$>b02RV%o{1#CQWgPt#C?DXfp3bn*DnUJm~GjuM>!g)v#$_EED5kPAYVrycgtD?Q*54G$lpD_DJPLJy(lLqeB@!yXW;n`Ht)&Y zHA%Y61ttsJX2adxQ(s2lQN&P5w;qPFwS-xT6#GSwfg>1bHf#! zci_eSd$*&n`1iKOukuo0?jttiRM`=Z5ZW8Gdo(v3r1TY7P`$Wdv^DQkE|LaP58Cy) zV50i4T0h3=DQATxl+QvsVE3^ez}G-E59jU4Kj}+0oNmye=Y3#b8JOL$3=EBBs_NJ0 zeLQ6L$itr_BTp4WE~GQR-V&(yIy3OhX}Km?sE-O386W~dh_aOQ75^HJM$($Y(OHBxWmY0cI*7f=kkckR<>O9fgrp$8qIv^CH(d!GG9IRcEodi~@do=G7M60MBY>Q8Ps>oQ2lXqpra z6m2}KL8J_ehELAt2p}9vo}35bPN+ohP=y~8@(RvL=tPNgZ@+1~ z_>Dhym=0SE|DCx%*gmUYGdx(_Kq?6*g^#2=7UgrohidOnmcP0T zFeMMxB02<9Jc?eOEAB8&2dHcFpRWjzGyHlSLy2tzqyc4dw9ZJ5{r! zFB;_5Fw~y{m{$KVe@NLaf|}rg=xCTPpEZBbz?$4-3>RVapU)IebM_dbKax33fM8|S zlbZE-MXpJ5)pN_><7K={epAWnvXn!H)bcV^vfH(ZAw@ViAI5x3S`qYU0qfmf2nVL@ zvd|voi*05r<3o`SAXyo?$6;V)5|hHg49@e=*EwiYz6n?`Y|hcEnYG7iJFhlXu4?(z zxHweJ4w`7&)pdND~9X)K@y^+jSUR7n837I2MXe_;wiIaJU*eHb_g zPs$BI=OqV1oK`7RaRvnt5VfF$ELyluzb*j`OtW+oIH)W%EhgLEgT@HgNqK!aD zhA>cCKCxu<=`%!(Ah!hsXVQI&Wz_@fYM^_%6ugaMilM~T$0?9wmW!!{%I+gJ@E16!*72jJyVd9@l7 zkF+gPf`=IVpTWa#7Q6*6A>6u_fUG=<4)m--znTLy4hf+#=4n+dnMshmsxVQ5qtLXR zuaF!1PVbzhW6gu`pgN7da?SIjbH#ytxTy4iU09ueYtZ~TmZbyQgY%vTNG8Gohx1M$ zoU>J}?Uv3L)aTBpv|hL#day(i#RK%fl$JO8zJ^pPN4sU5DG4~8N^xkti;^H+?DUV1 zFe$o}5qBxBwc}k}QJ{fqq>?+y$&=@KmThor5O?{K!R?Gz@Oc9lu7SJZCb;K$d;*z; zo4M)*CHlc9%|D-A{kM z`Z(j&6NNb+r*n@=kp5rV;8o#IjQefE7ko7wp7@_*7hx=~H#{+Qc;aL9?D6U_2`T5+ z$o4fHDlwW0;lMc~+^QLv3*}+0B>3^U4o~I*CxDxP`J)$(xh|^ij~G!{sGgsFbJ(L+ zAE~>4WH78KOHC6&5!{(yyn~$ew~1^XtS70riyBlqsK%aB?bG~C;_bWRHZ}W{YhFo) zgwgOtlmq+`saf2fX@Y5lMHg>24l~f9IevJKTZO?rUaGNV3Z!l!6v9VD zS$OEN88pKK{vRg!=2oyqB1ZGnrH@+%DOGUaO%|HTQWif`6nC^~xXzR13Qr!OsAoxraM|?;W2(rW=u!k_X?UTey^ciL?mR004E9*aQ&ARA?ID->2v@55x7 zXmv$e-V=Cdtxhv7Ua3qS%GSYvW$XV0Otd(}bXf4`nIr)mIh+a92XuW$3 z)2*2G8Ar5IBCaN>O-Gkp-4<;mAl|watR`wYOyRo`C&b2cd8$al(?VgPHQ20V{2(@a#dcjOtj$pkEF_wPGu8qKQ*hD zat_-P+94OQUY(F{w)rKZ5^A3Z zQ;Xna%D=P;M}(NMT!SX3RA{Hk)v~oXifTZnpxZdk+4{E1Mex2&V0NZMt3@#SHdZNH3WPf?~EuLDpaJdCN{!~~Z|Kg+3< zX8^kQDNkR&dYJzP+RS`qL4k-^63B*jqR{4mt?tv;52LaO!&HdJndPS}KgHKzPJmpI zuEQPXmq6->m)DdwTcr7B_9+WfR0Q(?9wOKeqrvy7)e5Q9Lg(*ZPcxA%Om!wDuVWts zdS~hY7O@7L(75wVhH|;cR`_WzXu4oo+t2nUcjO@mytweNunX5}*>WIn_U%@m%bz5RFb=MU+3iJS_sa*n^+9?2K^?Q%Yry z&8fybQ}zt^(fss*aO;?CcNHqzkejHXr;ntpH}i$;d<9&Gd8q5D6Krq?NL@OHhed87b7( zI=c5%d2;+mMm-ybM4LyiCC)$&RX&kEM&ArOxBJJZnW4&^XOA8I{p0h}#Jx@3VQG|B zx;+fmN+)tX;7~n|6q@HCh1oyc1jW#v+Go$XB*q}Ma_Lk<4RS0&#+u^7g343ILD@74 zMZ*DTqO%P8_Tjdk8&cowE4p#t__xPxsk*+lD<|nSBPOc5anf3!ubM4el`|TQUG*C0 zC9Q@$*{k&!em|<|k%PvUD`IGa&+RupU|DCQvzf6wzHb!ner&zcHuiY?=aJn{tSkO_ z$vEOrS|{iVE|F~?6yyje+~h!195#u*P%PFYnzQBfy|v{Gajx?PyD#CJ%BWh^LadE% zCoRvzx1R&pki8?o?~~$JZd&A&-}fNzj33i7IUamvf_KbgrRiLkLzn-V5spM)=`y`2+JP(~OL9xz*hWe`U>M5UxFri1HPXxRPJX{rfb;V!R-T%ecCsgU+ z^`{FSHs{O%D+n;|8lVrsF2~Gd2bqXifZ98eA_UI}s0T~CF@+6aGCmwEufv=v3xW&+ z928;mz;qh6E}%XI%bfuE;AhX(A(eEduWjp--t_*=d)_wXHuBs98Fl|?WILqdMt1R` zc(b#yU1BeE&$mqwo+1`Im{WvlAHxpNrSd$8dYS;TPXxn?6&Yo^w7ou^4L>G8$S*Td z@8q`vSsYk^wJ-o!)BNDVpt3ItAkYbA@&X!+C2T1tU9c)6dqQk`-5u=Kx&}$QmX&?` zsAvs!9i=7L;!fgXTp1qea(X;0Vgla2821XF4JCQZ2m_RCx>uiq#U9%*+AF$AJBqENCkes>Ed>)Uo@pzAUZ+5d>d0q{{DO zfW+xai7Js0)=Ge)@LvqJWEO#a$)0kUdP?{(2y1B$I=@0VYfH$MNWyB^4};*^$Pjte zTMaLAxD=0JZTK>u&DLNc{5Dwd)fRd#%@C~C9Idmda}F#OXbP1a=4j~v9DUxj1er;d ztr1k>5@L|H*lhH^alpPu2vZbcJpBaTI_v9*Ez{A6A^|c1rwoVTODNzY4WTrdJ24b*6rZa^nw6_S zI_iMKkkm&M`HVD3^D+;$ElUz5FB&Zt8pl9_hVyo zt61@VhhS+rpMgc9D0{0dmn{6r2m4xuucN@_!Va zXH*ku8-`~llVlPCq|oamgx*3gq7D#{riP9^AR;OtASxp2B!mtc5ET$L6af(tJGz!o zRKSLayVwIZKvzK#(N+2K{mZYMlXG%r-uHU0=e`3TvKe_gk1d@+5|IwDTAE=kZrL2g z1`mp0PhiB3;=<34(F~EoW>b?af6R>kf5>ilr7l{YQrT@dGns#c6VpY-nJS2+8=4~Z zY^+N@Q0aXII)e+&m(smu%eAS3LQl93R2lsY(K^XFCq8Jv0kD?RSY)x}JsBwQWoT`v znoSQ~6@^S;SphM^hm{?`r|U??qA3wQ++Bwa3&?qwGh_3lG3fb46bKe2DLFn7R;-*) z6RWof4p|{QgsURk49UYN1pt9Ks~~70b!86d6PuGKneqPJyK}sd1;#e9Dj%ZBSyP6qR24|+LeoyJWG)T_2?%ksPlC$tGTL$>aR~NN>cfuQQg*!YIwuGTv^=a zv3uLBx?h@Bx4^h%d3 z0^DKv6Q>F4GLCT6iDrq4cY5Jsd>wy|;EREeR#npvEkP*gET-lu+0Jdo2%fnWOlJ%- z(x@Ph+`<2`{2TCFR(mCkjGJ34u0HXQxb$~ptL>H^%^gZvV;dPPkKonv4=G^Gz4Pr> z6N1?FMYvA0Ims(kJcfTm+kdPYC^gC+Q9m~8vmcLc?L9!Ll)GD^v>jPTrTwxKt~Utf zlsbdz+<8o4lLY{9oG;&NwJFR$ ze+o*+Kqk%(GC5S?3)v{x&c3$jdmlT%dg#H$>vdd%_Cqm*dHu@xv%ueW*aWv5>W~Ec zkA5#Y4KJRALsM7G87Wn23e8Mb8rPh=(%0z|4Z4W=Z|j5Usf6v8P)Ro&4-*&Q;-`r9 zMLB8Pi34E@pbJxVm9DOMgX;MnYyoJKW9vSBgyegzFZ%vQ&0XRPc>#(a0bToIa$J5j z%lIbnf%rogu?9!sA;-W&S!xu4;$Z*Uxr_CwsTNzXxI>>p=J|A`4)WS;kO?uBlM2FsB|89M2{Gmsg-Z7A zle-n_tu55yV6`A2i3jdTq1RO_2rCu8G~}wc0&V>TUIwji;5ZwV{fNb@7`o}qH z1Ka>0SUkm%L5zP>!xbTXj;U51(<*jH*0`vb07V56!(^<*aF( z|7dt8@qN{$Hq_qI3u8i3mN&TuW7>RJ`jXh>=*^f$HJ;;-r3%m!0~|pLRfw8lYRbN8 znSZGN@w0Y=^gLn3bL`wSa0Xq%D8EOY7DkN8=@aOaHigINai$i^`b7k?iq(P`AgT6F zFGG-kF*7g-72b|uQ{6vYc#b0r24~t4vl8FpgvIP1XYJ>HhcRB~wvzx>$lX|E ztf`H-`WII0g5zpMwh_HssN3wG*0d5Fh2Trar_OBZGzMhIH79WTr^PJi#jRs9laay5 zr@>H3kg8)R-I24S03#;?z;*vebN%IX1if;d1YeQetq${9e6y!fNEM#H^wf0ipqaGy z%wvBP&cKnRPy!v_$j=Rp(onhH2+oxF{BwNO7gkD8+Wc4Nf=*2b74P#^0m7)5-{`tE zJPa^Xd>AEWVffDLDW7GF{4xNF8E#*Be>?%pN?MwkA%inypq@N9y^l$*`q$1c^J)E#xKJ(Oha3*(LmcP?#>q|2^F*9FnwIv%hT|JcJd=+x_ z7ACaW;N;YH=RBT@E#DfWv*QNOjz^%|Fu% zW31OYUVUAaZNiy*dEaAqK6|BpU`?T;1#Q z1J+W4WOhRdCmLZ+k_v5)Z}hjVYkpi*yNqw=F*KV*KKn_)yn%k=xcSySQ%E%(__D zgmqC1v|d;4ejROUY33-)>vt)>|CYeb@yuN7nMC3iop2p9HOs!>dOp`w208n42s-P7 z&KCSi?^9>x{Q5gTp7t7Tv|nbvEwG=IHmooj>O18_i$LVm>;@{*C=0qA2Pczv_G1rpFDqf#Mc0jlQf>m1)rXc0on zpM6E;fpfx-0ECdFT=S#Z1uQh|RX188hkj1x`XopsKw z=y(icUEz%$E3 zX3FP6E?uJ(aAZ@hYR@mJ1vRj{-07iTNvo!1YA@GC@w=&dNlvfI3%}CfMs%LbNG$zb z+*wl(_dh1Hb2#1*X zgQ}N~S+S|&lgyQ(K&78nmo`saRhj&=5wzyCol3c-+N-B1AbYna&X%;{24w$NI%ZFM zPI(_bFX;JKV**p}eUvi5dX8s-ttbnTK>}Ga$MG3|-R(x%W`kIF8yUzvZxi?>PNr8+ z_8zTyddmv5p?~kH`Ec+?-RN9{r$y*Fc-R7|{-R16q1KhQ|MT|i1SfV|iO(@>pJ&U} z`4h@-ba;h__DnRDZ324=L%U_(O3)MkFFh^meBghF;{!9B-v=jehW=>O2Vky%BJ$XJ z{%hh6rtNA}PArgt;^CH==^aLoQ-)q||8qXXUPkr;LQED(zHOo;Uo}d0_*=3k7|IWWzDgT|wKrU0I6f z;Cc18fna{T!g|gOMacqtcbr@Uz)7229dlfKWMnmT`?|5M#P5!}9JUb-(xrjR>$}`0 z?@x;}31?PqKcO-o+l_LZ;L-0GWbRGZT=*{F(=^0&&p0&k zcIDpp4p+KO5Us8!SMU9Wq@0vd)wY`q)IIGn0WV3&%38QGjv#FLd4gCIk)+$x|TbfWcKo1f5Zzy@mHRlOc&<&~(>co{9ba+{GPHPRLZ6M*QxH zbtjUx_Pd%71wJ2KXyH0aj2>7Ny!(yM^@h3USO3}d8|QEoSGKEUqS+Kc%N8YKqsn_X zV{XA9r@4-r=zc#CKiVVD{750h1my=mJo+;l%)_YFsEw;0Z8<|F8?*9KY?3v~?vIn{ z+LSRlbvKY4G!-z^{mYYFEaq}?Eyo2HO~c-KCB`dMj&A8V=eqI`B9O-x-E@ghFYZ-e2eqy7FN<3HoIFULwe_*!PSGD8?O zK|5~=oNcU;F~>V{4-K>M+ihXJMvdM(l4ASMuEH^}vf@GGvRCkQ?B8J!K%vZ)(>~nv zKuEZ{zqcAJZ#|-(nXrhIemvoC)~A{U6S_C1HY{!;w%r^4x5>JA&C}iNnR`GB8apOC z+Xh%2@TAUSj5^eZ)uwhgPq;+XpfvfvJ)(SUyobpMMMch1`8~LTUR2$FTIT75U+Y+8 zYc8j2s5<=$9ly6ZUCm)i`;Ud|qLJETrWLQ2R}nWZyft-Z?w`wqFGCTZ7N8&Oy1>$h zgaNhZ$*28fO`qk@uARuw`gHi5)+jXm{nw?vNWU|&R(}+SS>Y zr;aZvHB3zK+7Zg}tFSB#GnioK|(BA&Q^Hw^1rfvQ(aq!&&1!U zo?q;G>gk1~XIFNqxV1gMoblo5wPLr^FRyKIi_e@?Zsw|L8Ug6t+OAOI64mtf7U5`a zmnJPCbLC}m{@sOF#xjK?4zP;EHltU-CQQ`pIXW7)j(8JKw%EpW{OpAK3JrpwW;%yY z8a!tmAfSGmd{kiKmJ+4MTL0jYV{FPd+2J2SH*M#?SvmfqX~{cowCB>JAf7wIys|m_ z##F~5mD{^EF8TCwdgt-U!s?mTo&M~Y+tDJDQGrlQwd)n;s4YO|VkOL52S8dZnkGu7 z(rRzP7oWTd??YYc%%OO-n54>FB@A%q$JK@P{1!iCt27mldE&l_hD(8v=g0$ zhTa0OT+;&Yp%^qrbxDi9{jEVW^1}J~0Tn==zD~>}P~HLxVkvgz0+1F^nOc+7Y#CJ* zxG)<4V@0aV{3^okyTakl=ly-O`P>C7#o z;-oXaq}n1AG>Hu(l>?$qEw_jP@gi1;Y_4CUh0o4ap+dcc`v~+kZ)Dz@7APOqsYGi<8dxF*n=Q;-PBinBqPNub z8r($O6$x<&ZI4jkXNK~#39zkHd1fdVqUVZ5Tn?G08FME`BRExax7g zZZrZ$oQ7R9@NEw_#-075wRj~UW}DKc{8ZLFpTsph-3N(?L%3K(Un5JMB&--ZNxJ^? z%N;oCx><16c;m6Xb6FEDr|)OQD6dI?nJQdPVTaay$ulbaxT%+3aza*U)|ALZ*f)=L z<#P_$NDHW@7A~Nk^T{tHb|E+2j}tW(+NXbDWi5pn+e>eTGlb=R`l2^0DC{fdjyYCY zS8Mw5L3W-3{Sv2+)gI;4iTx>C(6-?Gr;f1B6X*Lo{Q;qfSIKjkf3tZ*;@h* zb!vv|z_U^Tek=lGZEfzRtxU`HR7#C4D9&k@BH-O6z=4?KW?C{trzebfE`m>Bdczb+ z!V0|rJ^>b-rEtYSZF3G=Pnx6REEn=jzI0q|W5J7$;@jSycUgq+W&-d-7$RlvpF1F;%V|(;e(5%_;Z8XGRgWiT zIAiMB1FsxIPatn}w7+4^W_@~LjyXph_{p?6%X zW6RkkEy$XpFm;2E3N%Ot6vqgulCd#;&t}R3H8I_r#|Nph0yo~p`b%#_O$&IBJuSLw zMr#5BZn@`#kBNZ70UKjyt4_D8oj`7;lGvlTsO{{jx$_@{$^R`~Op7BquNn&^@^ZgX zaJ5y^90S#~I~J3oeYteN7^SG;i@6e}6P@5}BEH|o zDx;tviDw~)p;#gf!Eah_qtdYU2zsjy{IvE7oFSF^aBhd7N~b=|i^EL{yqSWF=7ciP zEnx3$FEglOhfTa;W*}%m5LJXf@1scEZ;w@r^tfautr@)?stB#{md90`$m}(hI?!Tl z$bBc|_kwf5Inv$u9Ia;gpx57`qOAk?@vZ|21tgJX!t=4@GaW#{WJb|=rZsJ#N<(yzdI9Np~??2azKhAFG2=DFb-5B-4dog*MRq_7nym_gEAz7%R!ZQtX#r~8EVG~oN z!JKe6D&&0NfuqYDVpWcD8j_^k!-1-lQQv9}n7c&x32o!j<{y~$&;XH}ShQfX-e7XX z{_1(_WG;HcMMSl=HBacjtUml$yfN<$!;+XAar4vV2Yb|}WrvqI@aQ=jb_4qg%X&VFYicFNhrF3&6^6u5zubSSJW!x9RrF$? zPh)|GquF8YEAJPo{~Rb@ZLism(N~VxSWe2os#F+kP;OiF3a#~o7%F$qF~+?~!uCj( zXJoGKo{>A#R-MKX^wYYVLBtU0BE~Ix@rGt%NV7-{uc(aoRB*l7%ne$MdTc@Yt8dRWfAkCP8-q>)tZIN+FU6 zC}+O{1_EGJ`-Udm_n+7PG4lCCOb-Tq$FDQHcQoxD`@a3R+n$uEJ=ytM-=bN2nzsKu zvwh9OJ7LjUs4? z2>QHDqGXa>5hJQHAZtCOe?~LjAvZKM*Xp6G$ro&50TCv-@j0qBls}-u9ohp zP@M?!=DyD83AWC~GWMx1;6RzqIma!d8cs)R_04z&_DyrT^-O~x2OXY+!B-Nhr>HpP zv&}Ho+V6{TVCR-SXY`KeGw8}*obUQ!WqR%&W`1YVfdCDtX~&MshjI!Hsk8=~$ zuB#z~H>LpXT0MJ_mH!5vg|$hNLmG!b)(#Jbvx|`1_1GH zWeq|00B>h-C^YodcEl0XeFUt)Ay1s*#bkW^LeLgCzr1bYN#DIE4|CxmYOIS$rWF2no-}U3GZQj(_`= znYr=b5d$W{NFjm2bJh}PPnS2~;m+nL@tPUg69BD%9Ao9VPY$mn5LWv_D`c=S(6Y{H zLj{jB&2;(<&$;ct0@xts>#Y)uCW%Jj4hwnly1why48WQ)LOHtjP&hGsIWbN`a+)D9 zr;pmwodX2+g9K6wkpJvZOnH9&v;I>r^pYClLjQUsXu`t2t^3&G~nHL%}5cIRoey0ZY zQvCv<#7^0`m_bK8+kNLx`$i1}J%Yr73j2@@YLtv0B{&}gh_f&R;Lo2Z6IaXTkV}^q z%`T_Jaw(<~if+8U3NE_z-has*@j@;+Va5FVt;8yvm?uLXyoHHFo3_0_we!xUUHVZ{ z?!5bnfg*fyRYsne5mfI?y)OxB=^=Yck;M##<3MSEte{GR%9jFv#jnUpy#z%wwFj2m zl7vW3E<7AhtV97FIs)^;{%Jr=MmayG7k_vRTB0D78vnjwwem#QBgr>5v%SA|>0sA# z>dmE>BEs7QWWrl)vm&%w5cp60ymS1JNj}swvI>a))we@&c-~r_OfrVf9U*~;XGw_%2lxE5AbwtEJ zrcl^TC}S`V8a{35tgT_L0|0*oLx4iS0IBY7e`f8R&Z>7C*^L{mW@7!iKnl1nC9fQk zuFY~?dvpvObq22lZyM}3;l^$9sOb)Vy8%Lhr}gniA^`G}brMF%%FK69LVQvb zQB_EE!yX*fDm#AbuI0?Jqm2nFBWpvWfYNsa|4G6RgN;Wt*1`DkM>T5+hQz6c^;7|L zG-^{@9+=TnPA*)>z4gFKxQSk7_$hHYD^p z_W9tpD7JoAhVgxe8>^}qk@;Ky^Wavy&sm=;>psi|HF(hAk9F*U?6?=8smO5f$+2Yf zzZvW!@m0Imeor@<(*JrgvLyDX9>>#fFuN(%4S28d)Yb5_!?CRG;6OC6B$Syk4pPr# z#%?zb)6I$ZvC1q>-yf@QDAzF7CV6hrs~9ny_O?>LSi8S=IO8{W)%f0)%%m^F*vPYk7tlCO6b&feQn zIA3<*)QJB55hMn@-BW+LKWi`Um{1M9>;x%t|JaD*k#a&vxq0WI2A&-3jD~Unf(J_S z6};vRfQ)u_Kx)Q{flWfe-oNuR4CQu_1pC`hw~o9gd2t-Igb+LJ$^GcguT6Io{sp-M zZ$JLa_^_%I;MK24dAI%#$i-g{^u4qwWAuMyB&NKxjfK?g-VYr#Dg4dUq`gm4d%ybr zyPaz9`tKSnOM#xYN(|e^iWfXvpfm3fzvR-|g+IgGeWfOv?!?+u;)`-o42E3x74zTR zs#L%zor+@07%d;KxH&lo_J95wwzHUb+W|b{1S|7Zp5{_T%=KOq&64+1vN)?=v6l{rAbyk0tm2ePJ~8`^Vi^+`P*8B{eWq zTAsJLH?O$zGCeXRBPNiT7kEE2c(}*pYRA=^J>HMQ3!{PWjb0w zxmIeSHVzG5i@f#c?bD|zkme4aO0~$k_&Qm zY+lA_No!QtmUVC=pjgZM!79~a?97Xq8|N5BeV?p@=BnsE2}oOfyyf2;`2MhI>V^d7 zey%sP)Bg@F0{THaVi%`rp?K>702}90HW)KDoW5&Hx48cBy<|aA=NYK;VfI$FBl;Lr zffx%HGHn3BMxlT8!OP|~&_Lij2KztFtKj;VGajwql0Lm}zVWvCGiU~|G}`VqE-io1 zcJJ{G@c65lO~yZ89GfvJo5^E*f4liloi-%s1kPw!7}1qaJA!W<^T|?kYO1cy_N1%c zL)Wh*m4I|@=ed=$GQeNkkm(rTP6xY)D%$Re1M*nTO`5)YwqiC`k*lI>C!JMv#^;ry z%4KrK2q9lpUuWBxQeewFpoJz*wu9KBy;?p4Z``L$1*g)3u zJp+|)NPnH*VB}dzPweU|DUaJbL{dEulO!0bDvWt=2+{KYnN^oGo30TQ&s<2 zx)GPp0e$KSuS?F$j3eBxX4p8F^sQ>m{a|Ug^550D{^=?K!>7eP&b>lNCqTI|^_O-t0Yn% z$f=pw8BVb~4v1-7sjxx%Zhs;9gT)m9r|3ikH&B7*Faoiq62NUtVN^Wo2>5i8<67}r zYPFzNEX9ZK2a4-RL`CN|e#T+}a@`<2=7OGK1hXU5V*elAhuOW&Nj>SU|;0kAP1jw5Oa9ay@9K=h< zg$sxsM3m(lG;0zbf(e8w1}l`*Oo#gHkI{dKvZe0YNrJ7 ztsFjWj=f%O*?7;aBJWR&_qYmi)`cth`x^ zmptT3`4EM#xd3QZI znn{w%Ae&W{*=<=T^ER)1K-I|*8!6#d_^M7=7X{3ggcd4@UGyXK3_we7fY!p^l^z33 z@eUz2=iAh(2D<0ecFvM~V0D#BIW#eb0#9P)6gLIs`A-cu>~XRHAMR0$S3t(?BU-r0 zTHSk@{?3h|rJGvsfm{^7K(VK*@c4x0LkOo?K|n)0(MBE;?X0AkF~HYZc|MUF2R$2+ z6E&pAgAkl9ZiN{%IXU{OH;`!~hvOXSi-&5}oKkOU&hm1+0UQ93I)FzKL3O z6+o)ZKz44hWNio!BqkMRrSiMJBXlY-6iTEjG)TPmi|gB%2dV)jTuti@on+Hpy5;(_ z!ppjoB56^Fm=ky69%-Of<-tmTZL>aTzOyhnyt&&_d6J%g7gYjYzTuKN${qd$2$#z- z`mBKLbAAgbN(2_`$@0B{hpWJh?ZUv+VDU#Jo8=CU5~y9QY^5w zw*lZf5Ei9NNYR}ftqa449a`gQmNA9uF`fQ0Qe?BQ>Bi8~Abk=KMcR0^3$_Xih|?)_ zLM}+wkclxxJCkuL$L05rJd#dVxar8F5*izKixAgHI>bipih0pPV5Qj)jM#`3xDAPp zRuHggO{F=g0T3jWVz==Pi)TUr!kZ)mK#wlcj1rb{OpY5N_&*D;ivUhN!H|aK`!v{} z&qBltmDy}*husj# zEhon2RA|n#7`K`f(GgXmp?)<;8yJxtkfubR?jzqb6RX`Y{b&jUF+jssdbIqc(eS1M zHw%E$e$|@YE-2hteKtK^vlr&p=1>RDH}1Z2V)MrVf_`cOOA27d!>JL-qL?mLV`{Gc zOq^ABm35c;h^ zQo#TKHexhk5eR8J_7p|kuRH4!iJ#^L*!%gCM< zo%mj1&aCl*(ljV(AijXB4?=^dec{c)yE2QNiia_9&hT%=GOT2ae&GJ zvn~5T!CHT7EsE8r&dB8l%dFMh1$kCOL3`!8dVpNn@9V2(^D8NF(Tb;!_PP?cHO|V?feC&^i;eytM`Yk*EL%s#c_X4wUT- zm$aEq$$i}SGw#Cu*z8o`fwui%KPH3prS4=Sfhg^mr9THOtg*tlRe+Ff^6IY7%uQ3v z#Bt9#$A|766iEt_`p$Em)of2RG*!Cq4n)^hCkG7V+Q~rDFsabTET_sTcIR_9?H?CU z_Ly(KEpfEH;qf5aZol}!zeP1*Mg8*ja;@y&Bs;A0A4)EyEm-mIru93Yy->3xdC4}0 zRTg>=PJ%~<8kWWd{c|Cisc_mMd_HFOouBdpFRtI|=|I0D*yzJiQEs$9x;#O4q>JgY zXN1=+a(X7uShGUtP~wrbA#Z+lZ1DV%CVN$(d_F@O@$lQ(*!joywgD%fj#*upVkIQi z|GY$AGuv&xdn%_o!o1l>R9$Xph~cM|J+n)da8-3H4)dfK?PKULu|?5p&tDR5YB2|s zyoSzxzHyTfEJ#0ikU|n&W0U_I$4&+8n)tfYn9{l2?5rctZt#xk<2xmfQm>&8=l{{s z*e@%5;v@-CEfi&sGDgl5|2E=hcK~m%h z#>9}+bVgYWlgVke@_o7-Xt<2$dvc@Qn=J&k%C%(vfQW42t|GPfn?r#KibQ~lA))2s zu6;BVEOSy(#Y9`r`S1+E#;oOKZYxEMglyS2(CU+^_;b90qkQ zoJu(ozv^>K37}5FqUKBrFi@sm;3BXFuoX_aa$vu7kuSY{Ad4jYtP zs&l4__T{*%G#9i9iwl}@H3Y1c?#pckNQv6kb7uf$oAwVGMb*1t6i1}P_2V6TZ_gIi zAfjB}r3@BQkmHb7aLrH`A=Q+O;~v)Dm#&C9fTSy}tjqGRL4#YanKg8k6<@aUx+3>= z8%Pbl?_M~LQQie$)>U^7q;`9~=*9tC+RhS#N!Sc!A{fWU{5nk41?$(xpx3fcf zOYT0(1P~pFS5Q@JAofV4ie)~ zar&*-h{wZ1sjQ&y&P6)XK3Tahx00dDqpJ&~;*$mGuR&&jx=R5QDU+&Y0#_>c9+*`c zTvDb2&}|m$i~+6`H~HZb>YSVoQTFBcmNVsEcr!9WbAFHYQF(}}@KW(wgrp-jZpMu)s!Str_IO8% z2tX~4Pz4}!HlQygRC876mh3VVJsP45?f6ph`3}w!(wYRhZUUltFBBT9Nlz4O^d9@+ zRJeQuWM~r9PdIS~lpe6YTYxvnlMHf^Lum(@F=3w%FEm2MyxG&VNr*kG6*8vzxm&U& z_MpLug`2r`v7G?=4cKr3&=-nMa+*ax^x|@Y=LtyZ>)TI?nX`~lCeUJaBuAvCoSYg? zN-gG2IC-EDQ2~}Qe2tnROXY%|2Quvoecl9p4i{CQP*V!@N74=)0tqARx8{u#c(@%0ntog$LNU2y)GW;1GH5&lOE}f?P|*(S#Ews(Qzk z$j(Oa7Iqcfs?n9&;0T&xYpGY&zCo>FoAyzQdM;;FZt&;pxlAOrWEt8?8A$ z)<$8(Ctv*h5;=P`0bMR`m#X!lC#s`##pUF`Zlk`tmN#p)m>NzV%=85pLJfDqa!I^~ z@F0nLrId#3vnca@dX|6i%dl>xAyEiwr8WrY$B7ol*Bdl!yCM#;03iIhV3e@DAEr4V zleI?vk$aINK;BdC=gYMMaf=!Z2Jvo06`GCIo+4$Q8ZA1Roi%*5uEwYCcu$}t=IoQ_ z>EiVp0lxu>pb}ajBkbrum+Xv0C z9$;5dQ~o{Uz!p=f9x%VRK}#II#mZptUoj}>P8Y631;Bnq&*k|-c!>h}3qTTYdLrTl zu;@Q41K-q2HSd>}!&Yz3HjcIsE>3C4@q4Q@@bozATUSnzLD{gYb-n%PkHZlxb6q7E_w*M^2c$ylg!YDSP1qc+L{e>)9foTD;vG)~&Q% zoNhbpcuG(J%~u|V2DzRc=;8_6UCWQSb@Z^V*!mz)LAmY3Dm(K^ThB}aJYeBBTR+iK z&(Hxsd^>45(=xux)KhruF{QOhjDC+j{i~eqIcGGI&M{w@e){`JPEbr^-=OGWgmCf8 z_$6lbAKaYj`SHQxX#?JWNfjKeeYyLQKbhKtUXg%x1J;uw6}(6o=0F@ySYMt)>KId-x8Cp0g{8IUOMy$C zclztsUR#o~;n41JZ}ugsY{^D{FZDTDA4AyR)!;Gd<#u|&>rQ5g30PPUm#20Yo^F1d zmsp6T?med1cTd0Q1AfN;xmSm*u)5dBre^O++P>0f*Lr5%7uDS$!dE{4K_%xHRq+&u zk3i9Y!?1yPtLLWL*?UwAkchNb$v0By-COquwjQ*R@;+4G!PUk z*Qr$+Drb6^)*LN9gP5h=4XT!^-|fEoL(#L}{fe-db}(dOtOI!=rakPKJkK~RK%f!ea3Z8JeEA0sXbP`d zf%rWs3lZpry%RBek)pY=2?O1G_e=`9x4Lx>_!KvnhyrLPAC!+3mAmfGyNQKAc*Wxd zg}0?eqDr3^Yke*VeB=Rznm>@DNlNPhq5Uaz&A< z3@KMAU%8^=It7O;l4HZ?Us#!}xn^qU==kyU>sGVilQh`YQ%V5ZMfS5I)d3APdLg?vvT8%sx&yGytf>Fu4OKvFl?n=X0jA+i zLE-3IOnz@C<=MQnyB!?2{KKrdh6@(Sf7(kt|3NBazPi8Kvi~HFwXdYFeT(w5kNq^Z z11AX6{N~n7Zz|1sD8HKQ0@GF+%mluYqqUx z+7iEhTVnJKv^Hbo>6wkmg^L{x{F2Nei<*+nd;Yp`bh4MZg$yii@4jt|Uuy*>d+`$%U|+$u+%=hbOJ~<^&Ma6s zwc*mXqSLeGJ%PawbHc+=)0fzuP+*ZG%)xNRACrrmR!ac4E`W67fAn||50{=YAVDf~ z0ZqQuqn7Uc^^#i`?-yI)$5+3}(f@SPS{PB4al-Sff8Z=gY@ctfH@$H4%=)?g&Fg2a zmv5f0J>B7f-lcfBunq&8_3zJ_faFEaKYYYmD0uc6z?3dJ*X*R$ z3%Z=9wW@(0|7^U|(bv^pLfDhp^m+g3^?OnF&Oh$IPrDU9TKIds^6RG#ps#}?+L`re zO<83}e>J`fJV(1O$?7}O4810*3*5u@_#9B_M1 zc1N{x;sgEDv9XS;w_Hp918X(PZlHVBu>GY@9tE3HN#+H^ced0OeBqqIi*!)kCYd6Y zXUb~feN+!mNdQ&e^+ZM4@_1x2)`v)3Xk8hB!?|~9+Gum@q>=;cn{jBO?%E&riEOd%prM|yw?m&?ToBCv_`DkSh==*S!31ux~j(NP0YMddW$>MrL_>3 z7Mj4>poC~4m3P9X&Ej0EC7Ip?@*1I7SKV_iz7E=}9fJ1JslNodDv`ai7xavbP%)Gj zABM9-Vxqf>fJr=7Z3U19Hd1M2x~2iy@(D7Z+aiY}1AJg$%jgV9%0oroW*PFyJgTP< z5<~w*;!4adM=2y!SO?HV@E0=8D7zM-g`sJkT0Rkgn9IY{#Hw2$f#10^2bJ0?t5+ns zSb<}qYHMg^pRPnUPkL)E{@BkyT7smC_H@Cg~!ozYgH2rvi*c2pwgLMz$xOV_3LMF>w4Qyt;WS>)irgLOW786L55Wk zXE6>prYTI%5slr3D&bmJX$MU87HzwT|%eJ)g7HcaC)%L!tI7o)yCY3Iy3G zvnK^{s2=@l2=JbupZE-IRDw-Fs3f0qbV=<3LnZliFAv<>B2dypsI(gO0VfnimLUV0 zN9zJ8&ay(!$yid`>uw0Cr9u{vN);VIAU3dgvR18HF}lH7CguZY!NLJ=VqD!x3bzhi z^PlJpLND^vi35W+0ylYpYdBNBB?lpDGdz%JB}RSMjcdOC`?epGLoIZVx1nHU7g;&I z8p+ihZwEr?3e~MTtI)Cb9?R!t`|?)S8MWt%bh(b3=W+&C5R@&<%DYBhQ{p=2($0L$ z24ljAm_0oJw2uScMS)DRopypTFB`@5(mJ2PBn?X|O{rb(Mv${=`7O zkB0sK7p2E!{Ox*m;ATM&D%WjSX-4UN*+#$w8nR$Ama1qVkla&6ss=D6&qD4`Nz271 zK$SwIOVcq_%p3>>H=`2ASMvNzs>O~h;(Pvm_yma4>^a3q*RNtMC5_1&oB22dIU zEXo5wKUER<^I9xD1I4)*-IFj-OYhx(lAVAr`eYg=&d&5*qQWbvSBoR%=@`r=WIei& z9;B8*$BoQ%h*xskfajibs4>Ej=!`x*QkdDjj^dr~hT@1Mz=|DH^{`>qu`EaD6kH#e ze_(;Dc(2l-<$6Ezrj1esk9{#!@TrxK4-hVZ*{y;?>mhH6*FA|&sH0cWb6(xx5xcD? zH@)}}x7~gf0Yoxz1bEzHfIuD4LMA@E_+F^Pu0bXS0|OvXftfPI{vAMtTeBep8UQ@gWVSyDAq4grb*HP zxkU5@P;ZELWjw`}YVGpP*EwPNptFGJIc@k6llf{7mWHMJd{oT{An>~ab1^=*IvXRX z3%j%>rTc@rb`Akq@;uiFQBX7n{kHrcZEqe9)gS+VpEI#|IIbm zb*|@JGv|F?ujlje96-Z;Un)n>jC=lMGj8`SO}<G-Pr5!0d|X645JNCdp@mrGKtY zSaUAnWkUNwv!WR*WmhbbK%8OyFa@Z>Z><=54g~T{j+6>u&^a|CYL|1CtYy!>6$o_F1~Nz<=fbr z7rrQl#wVGZCs#aoqey|Y&7hGKG!vk`I?^m46heAd3QkqX5j5l~^d$b<^lqVB_gB*Kg5c44En55Z-Z?^|fF| zk9(Fnrc^xmWq9IOYAF8rxq&fl#nx2CLhQnWP~~1{|GtS0ys**9(7%Rq9bdJVwvDNt zXR6t_s#TVuZ%;0%w}xqSOvW?Ja|$^%kSW7_LdMIlMs%ZAs6!S#q&d`OcawIzAk_ZQ6x%XLO_Fuua$)! z0I%kbpKB)1bDRdH;VbW@-jH+hnF|^0o;ZbssVF;jTw$u~Y%w$1((y3N+-BOGt6QNd zLGgzcO{ms8=nFh)#qkm*rX^W*K!!+Td!k%}Tee`8wf&Q{E}ja(a#hwm{?SfjR?uVr z76{(4y+kQk3nBGozGqmgI)F^hAXajZ1Ga@${9z9ah5vgu<-pZjwSRI|Y^I{`_=bmsk1GnzC#WuxgQ82 zyBA6@jYX~x!e3Mu<(sOCJ=vsSWE#aD`}s=LvLR_l@d?eB7=uh~HQW2Y5sZnN5_jtc z`&Z|CoHsajx$w6tIXm%!w=%Ztb!h6E?SJJGz18*6>)?THA-NAxY&OPP5-U55eheWv zA{%%baW5gS!$_+pdl@y;tr+9<>TH8GieP|s;IZ-5FD5c^9!xy37Wn-YgBLhrj!RMu zk*qj&>)9YLsiT8qN;H&$nZ?}bKhGF`8C0*&jmHF4JSZGGyJ@a-WB1ukVd~OAB>San z`(KWu>sa5F%pfyVI!bDUE&OoT15A>zBkL{M6kwcN9Qt{2lBjbch9-S@*fI>bXqF|%_ zOY#|=suUEa8gMYc#zrlRO<~82AMh#w2S*^nmfW-hAR4^vpVU^Um7rmv`epo`sJ_@y zOw-7-+{v)Mu6a%-7nU)-)?JQF>3OT7o^+y91$osp4XAg4rJB_4-l>wd$Z zBhMn&g|vSUQQAJ!Svp?vRphAe*z%o9zwwDgvCcXj&=PQ@rSB_1wKy(+7@_|`@X{=5 z)Y;}gDlN_V_>A|Mt=!djQ4|)L;K){{x5$VH(P*~o1PTcrzWfjyOAIhqN1S+lA{kfCQG zxm?IrGH9jfT{_?)QGhv$^icU2_EH<~GO1LSx5!qBLvD8gcZ!YkcMIiZcv=a9dxhL2 z2pRPVV-~@{EtOqD%)ck!JxN`f?|Z*RJ+Xn&fdCvP*3siW3l!*Fmh-BXylC!`VnCoc zkMbT^W{}CIBN{P9Dym7OI+1UG%gbO+R!Bjb>{NGG$m~Ngw{mrcgn9|`GtC@v{-<|~ zKIwJ6Gh(?>o)ZcYev+R2oSkEfJ|o_q^#0haa79QX1q&NYez z-x`4Li~X>sGPaUjtHIo$ay(T_Q}JX<%0*i;Q!RW4wFPMGH?m|K#Eov4 zY+wFxKr3v}Fy(}o5`bgSbTprW2Hb-_**w*$<%yCkFQhus_q>4p<*=_oJj3u=;Kyb^ zqs&#tJ6c1x>1cJFG<(oPO9jc!LLEq=*`!z%6=Njlr+adCo9JZ)Jk zOM2-Aj33|QoGJrXi>-h3D^ru!JT0(U(Z9>*xFS5LHLUop*$4ejagoMdCO)OE>Aloz z=u|3M>fE+x;r3Vcw!IG9)PY7WiZ~2z9df>Sf?3<6OO??5L2`q#)>DpA-O%|R>APEU zJX86xPJM&>pL?<;e5C@L|7tO-qhQ%hK1Jm3^Ardxq2@ zp!`42uU!Sv8s)A198`kBwwx1~ zNuSSA!`lqyHT3{$pXaU%c{ffXtDKM;;!<_d4P@CJ*kR&mFxdVUWSGt=soug2i&h#VuK$aEl>&E9*}aHQi=^) z*K5eyi)a8P-Wz};4+GDCsyMV!C>IRix=x=eW4qsq8~n5(XB$YJ&A2N2g1S$iq+Td7 zTz&XuMSFEz-nLyymZv>b08+3-ZWMq@pPhJFeCpvyj0D(jfhaDr#~-rS`#cjVWuFM! z?Q9(=z9>olG3oJ5@cJNI-Xv08F>cG+`7P&&y{-~ecZq)-5Z52#6O07&$FKT4NIQxl zSF~@;-|l!k1rt?$ad+gV!zsQAih_Hp`%QuyqjtwYv&5%M$Do#)`ZfLb5K~j>2@eF+K1rJ3T zXt>1*TM9oy}2*@R&()6_4QkF%yPJc*j{B|17>3!B=-ItuH<3MlYej>SwBgLa!eT z-JiN||MrO6Q)j9ic`1^gs*C5)iDE@(XN=Go<|fIZ8fxazFfg)7N^wbFyF3su7yMGnb8ag>=SnsQTJx2X6dK}Bu zbiV0wXG_MNrt-s&F8z6WykkVKpO$k?%P7zz7^%oJr9xA-%=32GulmCr$lzpu${v*; zKIQB7>g%g4FY&goY)@gf*lUIx#0mf1PWr}@>v@~vB}P1F5;o0Yxuy*QQFE_Z$HQxX zo|PYYp7(ISufGXV*;I|jid@Lf2Yk1( za%qHrMryn4oHwpm6m6JCc!xM>e3;E=b7|89b55i9v<7nHLwxG|k63mzr?$94f0qsHu0 z_Ns`F6uBb)d;cTgJ!sn}WkhaaOz<6Ur+)vtekJIKmhU*V1MtGfFdvJb^NNY_aleD&q`o5x)NiGg4 zGf1BUhOBQQ_#u-lU)VNM2UteIlfq=Y+_L)3 z)c~B#l~=cMoDr0@O-jI}HH3P&%z;3r8nLS-00Lf9wmwi;VvXk9)Ouey4u~h;$y~CB z8~IiaY4s|W|6S!X_ohIqHisD=ja#@aCsxPsG<1^EDWJls+CGtZuvHFwQj_rl+$9IW zk=9YDgDInBo#?C3uUh}%tE&6@iW|8fQmZxp)gRM7cJ%M>p9>31+7bY(!Ky4rfGycq zZ5jmx3m^u@jET)rnZz_c3TTu0GQr-O7~N~l0H4!Tu9LwAiSpJ00^>ReWRhbS1bdB>)Y$OzBgs{=nhX#o7nm$eA&K}7LL)c8L5>0gVsmozbjxan7lTTq zPnj=0G5hAx2xKTU-tINlbE_3JkVT7}WKzN?a^srOsLa(@a(vaj#wkBzG_8K>xRH`Y zpw~lEI=^kT$(qMfOF240(b#m%K+K{)_Wi!%vl)^{)arHEmqbY%s!3vcqyjDE#v#B4 z+G{^z`ix@PVabZoqf_Y$-DlZYoeZ%fUZDb*0(ENd zN|TLP%%rpx9(GZntITRC^Q9VK(5W1em?#_4m!YuUiPOT32o@rhf-W- zKguOwk=g{Zu3E>|G>@5>E0;_B7F)4$^fY0l9t*{JsjtP~m==5N-XzLU6jPB+3KL;c zv>U90u!I`MdC^L?2(4(0VO0>Hzeg+2^*L#uog466rx~C3-<<{_8{q2^l4cfpD7r=e zE4nB6%ud8#gn4*}SnEB>#6E*CLcq8*S>z})(39=VPM@bG=@Z)U3tFQ8L{?zg7Lgla zQdi`-ou4Xi=hc)X?_owvIpvqoCjhO2!$PTUEa}orBBeEBKdOuk;%FSe&Ok?zEC@!; z@Cm5CNjai8SqWs`v(Y)_~}eZiXH_fTYhLt|2}xn#WuaPIYSzu=om4_V*A;-#t}e6lCV^7Ak+=&_sB;`WUVOo8Sr# zLb}w4g-X6+fH5O|4C4T5;~HTZ%)#4qwNu6rA*mQSBg^l<&K(AH=%)$G0Mr>joWH6B z7BEC;Lakd$_9s=enG~VKib18Ayvi}heOcL=C0M6HMCPhG67OyrW*(QdTy!xg1LB?ldN6p1QuqLDVLA$Ld?-xx>I|_fToX9gW7^ zO~WU2bsjid)Lr!Uv1DINW52bWp6tOkNXpK8{Fas2k#@Y-RQW#EVT@$TiMi;nFJ@k& z!}tyiLCk-otr7nEOXLe?SC?Ju%ks@PQrxK}6}|Z5RIb(M8`&JLnjttm%2D~%m$`Ya zPYH{|_^@yI(Y~g$fiWuc;fC8_aXL#=uc3v{qs>ycuD!D?{#oYeJ99>(=klMA6ozn|0o`|ea`So8TPzHW1@$NY2^Vg^{&1TVol9*-`8&aq~o>3p2DB}_+DnP=X<~PUpBS>$-Brl zV;xz$=8_l4pa5x7U8%SE^ByPLTGC23F2e}C(?`C~8qL6>+oie*68kYk!5;-!cUCt< z6AnHI4hBiEtL8B#?v;;d7t@k}d#K>1B!Y<$#tOP%6c3hxAK{ zb%{`f1@GxO-30%E)5* zC7zGUfgBa#ClZZGpbLR|*)EKWB_UylFWjYdAEpR_(Q7K@K5A96EGhTSRxLe=28w_F=Jg*6Mv$R4iXvqxw?<4o9BKO$DM#q-Q{1j|ZhXHhT8AkGQ7`pLcq>A42k z0|uvPhIzh*MY)D&d_N~j49k6us&b7k4H#Xc8JC^HUe7hYGhlq5rE=fbq%+qfT@Dpz z1~S;-sE(77bOj*(;1=QZCU)iC)RphP*?+#i@^S8}-`_sd#2<2#P`EsnD!@{dQQO$2 zDtV^rgQnVwX1ac6%k#{P2hCO~nw$HXTjiOrH8)oPP?k%qDK6SVbszdKZM9$Ca>$QG z9$c+BXuieIG9u4%*P!JdMJvNR7F7cLL*Rb`r(i{tf1Y)Ap1$qpH~uRpySyile_v)P zuqJ{aB=B}?dta)!_Qs%|EsW#IUZ*gv-+$Y)ZC$09UPZe>Kf94UyBC9Y6N>iJe)ezk z>^}_Je^Ffb-EZCZedwfcbni4Kh|R{vVQvnx73!aRiJ84Ou+dT+q26}EkGnjdYdpkV zMRzbCvfq)yqa@kAg*XmF)=hbs5;37t>X?nlX8~k?0PDd!|VOsauuS4wPhv4q-zX7QWN@BZb$(a{FCo2u$-FM`b)w@1Xz+?MZ{Z%Hw61AreZU~v3&3Q-9#t^$aDfL|Ow8p(wVI!yKXrX_ zV@HX_nR^NZc(ol0!J8qnw{~?8Qro55k4kJ&Fg_YaOC|K-8{TmIMsGH~lH+=&a??J6 zvlLbuzJX1HLY^+&-2BiS9TcVj2sWn?=unP%!J!8M)RM4-^XtP8m8n`R zS;~Kd74oIH1SWn!pynmkm8)JFlZX1RJW@YM+_J&n;R>@x)#su>?i!W$sxJsPS(RTlYmt zIE2bch2An^NtnV_rjq3k*C!i@Lks&~E}(M56e`%78Yqo_0yQa{&~B;vaSn5xsT6qg z*aoXT#?pArG7Z35{^WuJDbQ{KR(c*rR4#(s*&!%EzC>ti8mQSNRl^ixj2ON`san2( z+&6O6EBz`DNEg_633EPP*AsGiJDUwNauWrIk zXTg*2sI)T33^{nC(e7MP_8qfCb!5Y}1KO829BP?FB}~$;mSrsgNn6T5FNvS$D3FGt zUS*=a){}xJ)vjM8dP!37uqwnK~dP~kafqdE|Fcn8`4$E78Q?<7(IeUr{-c+!_)|?Wk$>vS` zHL4Veac)c4jTRumS~V6{{fDHbGv%7;K-^EX&Z1f@0H)PwKxJx#bi4#bV6cf2rmU!& z*vrIgNdj^L4>ARefAEHzqi6eXWKaJzTDyc`+2V*cf3=Q$f<8Mlr%ZLTmFm1TUdmK3 zf)5l)F(OOV5^?0Z_4M#E)i*yhprEp!R;v4d0tu4}JlRj9Oeq%Lxn&Yx2prwSCg`h$ z9Av5<6_;<~5MrhK_8}^XljZKr%2eR!9>f*}RBhpC-jm|&Z(#*C%3e}@35S??TQdc& zIL0PG#dx4eZSY9QhIPPb3i8U(281w8a z7vQ`Ti@3@#;&48`Qs^~t`r7Mf*Qy54?|(YBSsXv|G=$G4?k}qNEE1P>}be z6qhemdn55~faU+_T|c&DftMogM*;cIHge6Alp0m}dlI-8p#(`W`D{wCdYQMF$o`Fv z2IMWD2Hahj&WFp~d3neLzFg?Yr?MlrE{QkZorU%R8d7fBrhVRC51} zS?zK$xg*XaUJCNrXO#Dso5Oe;&L-V>+kMEk_&M+0bFQvptRsqgbWYMU;=OFltzgd9 zZqB8A$f0x4&6rIgaUML8O0EofZ&M1|F{kEm*o~}XO9nT-^lSGFK6AXj{a9(c-C^I5 zP4^e>+&{IXVYsgV;|~*(#DwkQhvfpCFB_Ay`o65EWc>T158o}p`1SZWUUqPI=O6o= zvF>cM(4+p>hlA^U1t29Dcidv*!_wXlW4#ambbq%sFqXQx0$9Ej?F;#oYzTo^eGr_N~Xd3bm0(*n=soYtq_;m_Bwo?W$Do`2%SmA|_8Uh0m5KzqoG$A8Ce9MS6z(W?o0 z-fuS+u%u&Hcy|0y-2#`3f{>TH!Y4SbFI_;8RX%ZWYQl~?p){yV8rMDlmr2(e_nxx& z+cs$oPZ8^|?=`14aOJgHHynvKjK6Db%9?hu*L$A{=fb~!<-PKpQrj^8nt2}Zs{a!$ zejREbpO1v@-u%`ZU%XH7*843UCFLBuXH@GGIrBfGRhwtZ#@}6}y|z0q z3&7JV$Biy*{&4m>!M1fe9sn%+0G#;46Rl4lq8A9Izb_{KPH6v|4*mD`+;TAg!#nMzvm=CW=azn| z!@dB6S1WEwCMX&Och#1)r9--IrM$ZH53(8NJIA`}$~#ZN4p|zm*DD_88Ti!%KfHe7 zaS?0Fqf*x!l|5&y_q`u`c%#ZY+cIiw(Y3z1znqt66!NJ4;$RiO-0iH}&6=l|0&nbm z`RL}Qk@0JSwk%EehRYi>EFu|{uq{%OqG|7=v+lR9zPyw0J=SrOdu`%Af+lNuG}cbG zWhfeN?ryA`?iA^||L4(kT^7qX-!@|ui> z|8Md>Imb>WX}bOI^8R0SpWTQYtOFm4Yohmm z)RnenFKPdeyx(UAFa5vBdsT0Cc0wlaEsiTzzgoOU$z(>FTz>?ZOrfujl*vnqcaX^& z*}v{s0GyhxR~R{!Y2ZBXl4a7+HKMw*!(jTj#c<^G3F|l2(hr|F+A=y*(S zu3n#+=JU6R#R}H>{XN7 zP^x(xo4GfwL!s!_CsXD0?62&tQBh_9&FWQTIXWO{O#Vfh$u~}T#alE-9)NrAB?02p z?pEJme!J?v`kE`pJX^b&Ye!MnNo!Y|LF8=~I!SChV8wKPf|uToN;Ovxi$|-|(;Nsu zoV1PTa1)um5AejRPgI?6GArNr_KH=o{>PCYb2?D`)kgvvavo5F zKGv?`y3ws&CQs>(B*}FiI|P1!a*)>V2F(&Kse4uXevZXhY0d}mVJ%Z`jO5t12(+{8 z<;GUYJ0``i8fm?0ap6nOpZmu3SYX?iqK<#ubqh!Te)#48JNNrKpk^1+Z74>mSgT{r z`b^ws6qe>y&VmEim?|GBf9l&YUq{_n>C(D>jK?-7MM25S6I#gh+?LLIF?JQ8`OYJu zRV@_?(hcIy@&E+)-~n1wiriY-%DnT0h39(}`n<6dd^fGtHRIgeRTMf5q-mbCe1 zY_*d%h@jIhwh&yVi2wi!71|Y4h~I#AF?V$yZyJ&HENPM|IJ+^lMbft{L6^@u-$)QB z6w9hpF<@3^N2DY`bm{L``vo*xvjE1xLouvrQIF;D*RG#q*N7f{IzSN2#AzU`-PWLd z(DxgXJJ@FAVekGDeE#R-Rh!bpUI(Aw zFmZskV!k|F@~*=iC;p&k!@o~EGZ}MYoE$}g_}nY9@O3N&E8xmKq$Fi&8GO*w^~%3(N%JB3o6VzKX<`*ub~IJh}7N{S9x?Al@u#N!~FWfeeVps z(6{d89*wK!dDi$AJsPUC`EikdqQ<|OFsk*jR4yE?uGbKkd)9<&Q@cvMeShU#TMN_vPGHIqpnz^N+2I`ypribbo?H87 zXMhgIXX$9(A!PJJluK;?%U|=iByv|{(%r|V)D{}MJfqd7FO0phS!n7zaW$^W{pI_h zh1;V&SNGq#Q@*cyT4NmhWeqNg^0{Q8`L0?{V*lgu`P&P3XHQ%^{MLQq*YkyYi#^wl zE783rS4j(s!wLm9pQ(3jsT||NSIg2bKlIvuJ-6JJWzbf+30;N*>N(rS0)MWy$T+>~_T@9H6fb1Z4bj^l zvs2q|Utf~gFyFAH&d}QYu%K$E@7zY}h-IP#RPEY=qr{?sNI@TdhX_%e5;~C`(Xzi! zwxs})BREPlX3ryrM}*G1q@ehpxeTKJPIy>4sNIO*tR*{HCvW$k)XF%oc~=;8Obrw} zS6sm6y2v(I;Qh-8PHnd+h@3KTS(#VH`Rl~03_>*)TGWxbI~>+YQ77I=u4abpPKFNk zsmf;mJ3~;ep_266hPZlSZWOt66Iz=$f58r!k!yTD%go;)iWh>a={v zF~u#9MA3fkPTq6+6mH@=N6x6|=H=5TVJkSC@@Upv$l$OIn+$=YQj~U|U}|b9k2mo# z=Ic#mwVf=3cUZQ4N-B+$D_~?$KA(kL-~JhtHB8X}xJ+Xx7!GG7UBddm7gEZ|KrKSl z=O>*}*xJvV;mYgTp=78EluEG#8)v&GHNgi|W-MR@(ho*alVHaFS++oCcalg$I-Lm$ zL$ZLVL`;_X_R61~6ejs2=*jgwC1*R)N&zsgGPBkZ(~iatX#xRA5Xrw!0I)TIy%B2x z0kBifB2ui3=o3vecNH90c#Prn$t9MG9<5hq-rDn$Os)T|TzU#e)1Dv;_lWf6^`@kk z#?xHiZp`dH3hU1_IM6%8268@Qwv_IMF|nya*&)bB!d=n_SgGm9LtzM2W0^5BKr{{z6U;@#iRDyJJdn)B zYx&5G)C6q5(9Var6amSJj-ty5stg91pF%Jtc*$JxY^b;v;D{g_04Re~KvVSm2n1I_ zYyv=KfdESgqEgXRf}Hr60aL~S*hLFNA5s$1nEtxL6g)K*_f=RT!MisqXNuEtR6+_1 zO$)S@iiGW5o3YN}P-9sx=bv6SD7x}8B?Kavd~!fOQJMuM!; zF4f)|BK29Fx7ty`P~K*+i$F!?GLGQuj^;+D$N|2<%fzIFjEU~{@D=;a=`3{Q{;Zs6%}Rt#ys04(?hCr zYd|Xpg6~Ff0W@TLboyLW4IGi zxlmH>2a$&>SI1PZP@#(b(C3!Wz@fRS<@2bb=|by)gMa|j2@{k@p^%+WNK^i*S{J1{ z?lB^8p=P~qz`F7akd-A(Y8V_xzjWQ^Qhm^+hQv#Ck1%NLiqhKBll1dgX8N>g4hFTO zHZ4!`$V3Cq1;bFH?Yr(2URD)47oG?17+uj0Th=(00f@3#K+)(gXvoa~6dxtg8m)0oF2gcPNH`eS7#a{X@(5it4n;#^(W` zE{6D8T-wGbJzE0gd-~+=#>lrx$Uq;d2as>;BM!n)QQ!4u@cL^uG%nU1NUwhsp3ADm zdIIN(rg4rcb^OQ1qChAS-oI%rK6Dn++@&XjMT2nV_gjUV?m*8U>1v7qF97(p0Z%nW zVUf$bcR|x`x|fyHw1XmlR_=_tb1P{e_dt7O;;u&VRAhHYW1G$%(b}f`O-&tT87eKQ zxV@yqK!!R8vxHOhi)`wgj64&R0E&=r3#nM2gfngsm?kW7hu~j`q9mJPjpE7RShPK| z2$3lt_2Jf0sSWiaZ$GhRr;7BlIWRiIDBmCD_3cST;p?Qq(;Ln$VquwmEYp@g&z`^R2D?-zH94-_8I zJ7T>fN?md}%^5n9&g1b>+5(go`~HvNyW#<#^pX4Y(iXMm7LBnMtv@Z#Q!cH)SiF;B?;B)oU>Q)46hF*XPFx`<}m)|X!f0rg1CweE_?br z9iH9VNRw-~iyLHg$k$~Z6r$E=KQ7ygBFzF5zuO;Vbi}o6WD0Uyqtqa2x6Wjg z1`D)9n*e^4(GO!4cw@-bL1bp&1p?O)#C z@imxPS^A{ixB1UUEeCPa;2MW-8a!X0L}-0-Q#?C6jTs{jjw%JxgOdBWjTJ*a#N1O zib268h#~C+b2^E2kME3KxisU1fA(}f3>8=ko!g#Z+6~bJ;QjRw;r*_oaw8w9uBEBN zlpK`vU&vuMWF#6zLbNtt$I34Qyv9aNL1(vOf*S+-$_1Y(=}(jRlKTg+R1zHXSiS$q zX^&_9!X$M$U`d655e*vFq8{wZCYavQppvZKHr4Fba^TBM|AUyX$3iwi<}sOxeJ}n} zPk=t)3Vry&CV(YIUpsWS{6OEe$JEhFW6$b#g)J=~#0tAi4o81{;~)q2tN9>vmXW`^ zUk;*B)QT;da1U=W0R$sHL@sKc*~1HT>C^cM#c}E$af;?>twLSo@lV;mgQlJeQQgkK zw+Qf)9rW(w&bgP=QLj${-m7Iv7*F}v{+nN~ zzo(jE@SGakpu;h9G4En#YO@5P#6m>Ad_wc00rv$S^-~Csg>@-|dRc;~y+@ z#*FHKGWIAfC$pySQ7j8x-1F4d=P`+zJ$-9<&DT%T&$JU-*9?7tSq*9p8z^BBPA6mn zvqya7z9a*^1>$E-XQ_v!BsmsAM-JF;jb@JmF^!7zN57bGzL*(6+N)@(Rit2fY7GU@ z{*wIpbCZu4Z@+jfPlI}R$zbxW7vXdC7+8jn6MdnSrMz5DQ-AW+hy#-2cY-;orrOkH zv+wz6&}d~`&nL5Em+#uJvN;=m;87nH7E>?V9b3;j+p!YLb~#p?u$Y9(J%Jiu*fP0ua3gX=R*Cw8>Mc(riFYGkeh-=EbUymi5Jt$75}5LT z70gJnY@k&Rh*~OtHLR^pB%pi9^gZmm6W$sm_}^m%MIM40-UMDQ{72~j{q~DmEz#$| z;ZaMJb4OO8Ec`B!RXbWmv8?;hh@6JCh6!UY+@6W2n&}btwsA8x?Goz~`W(_k7?s#R z#b&w=CuC;DStR$hQ=!rB@%GbxZ@vDrJMs^s=0C$f?{q@Tsl@-CZ>8s1`&6}no&6Nr znyx?A7`YZBlB)lY7;2Y<30TmFMC;K#!U$J_Mj#3plh@=1RvVeFLge-5%nrjNCIBsB zb&U06wB%*Yrl_68NJWZNs0yNsCAF>F397dK31XJMf}Dz5+h5V?^rUhHc~Pm_runGn zH9S6dg>)oJN+4yFuR*%+|uY9Ka-$Nf1 zWpE@)c+TbA=D&&apI+Wi*Is8pO)5(hh#lGg{M>-?SC>;@lQ?> zr?9xhsLv0I19=HAdu`q^o*_Jk^HW zN4T@~6$*fwwE@#SiNpp|-T;!RCaY;ZUaC^qrR(17mM|84&az+wH2J@vuBD_LYZ1@g zN&(C6uN;zOV($SWvhQW(8-Q;k{W+Xmqi0}{R9>QC5fHFp+s%OLnwWi$XbexIn+gN( z1^VC3!aw-ERQ@F{7wl1MFdSKoTfK2x(YA(-Ezk~W_SxJ`tM$`0XuC%mr|!%@7v6rL zTv=?nyCHbr6DO;e`K%!p2e>**5NaF0R&N@&tk0>9F6)l|Se;^dBw%&$sSVqkwiRu zXRDs47+I6`iOEmrx1BqNvzb}nson+V27q}(_|vc=!ora_kr%5fZ!f)9Yw|cLPibdO zCCL!Vs+$-1`)k(7;46=I-W=I}=hKCJFP78;;4f=ynkF*v z0R{|z`iQoQk$c9pO}O&SnFf3?fC;FT9lr(Fg>YEPT9hpH&O*&_u--Gb!#x_TU2NRs zK$Thm?eQRq7%e^Y{IM&Zw@gF|7AJX{J}nC@2iVtlGL>R7G+rm1xjWRKTXfi0kZ>!N zJahqESM2cT54ZhfR~TqjgZvk#f5VM-VbvOR7T6$OZsj2`uZZ%|-BHfi8a7aL|1zJJ zEGD@mymg5fbJgeb)$#u@=-9<6^a?3Muzs*)Wa&@FMLsTqP%q`$yuYsO4!+pGopEj`F z95d+vjjqWzx{43aUF^#BFSw;fO4Xg+70GilQVNvEoU4naQP}JinT;si*;j{WA>)ltH-cW z4%(7xi;#!4=cZ8p=sSTO|I93Ym}f8DgbzKIH@R6?^xz{dKB(~OD>qa`9($V#Hz{lT zaDA00j4=XCleVrF1n`AeFC^&su(A-ccGpoBWB^JZNr}ZD*mTyq7s?}zso5LH)qa%b zYK=5KQPQY*&+1?5ir!OXq91qjw-=-I3dVq?Nx+zyJQ#=!Gz)Nj&PGs_6dxT1Y`_Um zB@X|>T|hrX1)nU;?S{gtPK z$k9oC)*YdIL!}OrtYG4|#@2aX>1&T=M3Yx$-tne@huGh`CS`?bSr@dDkH1gfBKkap&J~r9IPW(8(+6kTRHnVZ%fUv&%LY&p^3+H!4m1#V_ zWpn{25t?2I!l1>(br~_+%wka3uGfAP>oXPVc2UV^xqAk(c!yu>e#|f3{S?bQ=|cBQ zT?PP@ZJOSS9-29Q#pXuAuZaqd-N{Bw-FlStU`1@XYTzmY~acaxG{-}(Z zA&C3=JnLHvIEPtorqb~J<@ci`7?8EvZM{M1o7Sz5QeLsL^z!DX=hBbd4x%15G6Uw5sQ9*Qf0&`UxGL4yn;HYz3@9h27GqY#TPiOxLnOT{Y+}C|wpN`?_O%Cd zLXc*W^kU~ba7K5eE2k&vsirQi=|1e!oA2B3sc$2)pDNj}uhwt2pJ^bx6Xelv6wrU)IHrGdYQIU6 z)fslbS!@56fqwIc{abYVx8=&v5!UpN{dBbfOTz&x>j7(z0h@pU+n52n)B*c~0f&kK z$JPO-fr0H02X@R4IDZ=0i5zs19CTG1bTb@uw;uHH81xJn^okkuP95|q81$_e^lKg5 zH88mQ;ozS6!M&db_aTQEl0*J#L;DSf4pWH&|&0oq~vgv+Hkbt@Dc0b7!NyY67$}!Vdt3Pqq76?1$OI2g@uOy&G?0k z4DspzfbsvYD->hcfdA$S#s7a9|G&FJfz_ztCyN?)@^Ip|T6010b|K?uhcoAdjDLA9 zgPgAQBJ*F2zbbP^NvC~T#p~eB|H}AHuAA@_qF_^u0!^b<%{C2dhym<2XfG73Gs?mO zCut6FzDL}vO4<&HJX{oTPMfWe$T_%Jx)<-jQ`mW3yZTJjy@N{^;umX|E+&cl1YcsJ zb(T4)QlZP`nHqJ=mvfC@FJEEXcJEaHTy$Pl76;Y6syZL{`c*Y2UFUU8#ktVewKY|B zuZ#K`La&sW_pVXiG>H4wEkyfv>V)QYf9Wo6+|||l;?iv?k==PCldsa7$Ha>ciq@lT`{AN5RDf{^l*JHQzQ6ZmuvY}qG1HtpoDPS| z6E|IMO_mZ1jwIiJwmLoPJ2nV#MK;i4EJZd8W+9x`Ea&VvFhWL%!E1~t=I)?|15VC% zdY>P9c!z&}wJ?Vzq<0pbh2!Ba@@mck`i1Cze>y+5%S!l|li~Z4O^Cw;S$wtfZ z&(2aIYgj;Rqxk>?XcY5hA0QsF5jcJBt&V1s;@vZakSG7^%kJdsrNV9M-c5^n?Plyv zt-?L{<(i*1Ha5J9_doVNxf$^pz2Qmh00HR`!B+H;*^u~1blJvAlqIhgjqlOC_G@)) z^M_v_d3GCre|qSB`1j|j;A_9X%ogw*#M_IsE7Qa`m-sQT2$X&p!lD46T2C zy1VaW%;}yQ2(UbF)A!q1BKg^fFnV=bCy*k`_rZs7(U((M;<<&t|@vfAE8~)T zu{B%GW9QDhogj}oYAh#zE938#8_s41xSG0;MGMLHoVdV55l9B>}G^tG85?*eV;lF46+OqOf zoQT=~&G?tMSO3HKyFXqKOh1POCKOLi6;Uuk7}_L@4)}Rh%MH{Z^0+j=%gOj8I-Y+)hwcHR zNpC-3jvLvFtMFK&v~aAykIt?H^0V*s3QO`EZ9J3&e$dD#OEYIseO!c0#T;7V*(Dh_ zsT5@oPco>1J&L*vajt)^M9uYL3SJWrN2lgugvWrImuGq$1~7<(UBN4p5>2C>S+Vel zBz`|?y>-BLc~^iS^#J&UN20B1mh>-nu!Ik}2dAH^Lfgd3BBZuL6PwTgu$ac-bQO`2 zfCiOy+TL=FToQ?mRs3#B6gypvz%P_AxTUD2ssH&rEgsK~6F;0*D}!CaH!v z9g(Tw9G!AoE?Gr=cBD#PWgj4FIbOb3L>VHari_%5kC6fO7`L}6=T%e>!}e#>uFvP0 zZ=n?0$L*O(V(UM)#=!K=fFl_eon5bD&1FJVCn78?;{Y71l=?#SSJb z6}bDt%L%IzDcF66482AH{i=Lsit4QT*9UJb&3P%9)`#`;Cq|^#1CI(*`G{w0zndH_ z1rL*(k{X?D?NRx4E7bxM%KnsHe_Wu=k(OtlhUtZlo$3Sg_TD5P|4qXMmP!}C`J~M- z=#@Ii-=F$ccbIR@p*;)gNUq?-i*|uwm{q&F$DG%ck|$^MHhs~)Tn?P5XQH-qCvW^2 zXlMzv-;L_ue}PJcd=DLLlHP;^e%)`~IQ8All?jO@@tz_ZMIRQfR7HM0}o5X;=+hb=g$ zX-ga2w-fgp>xz}@R;3|2UhWmA9Kk^WbGS^scqA`a7U{OGTyv7$j&tL*v>^(MN zOkj$g!+gbvFu8{FPAv48*^V`FNI)w0@-UNgyQ^~q_sSIzfX-;t^MOaMo+(KrOq zQ=D_-o9a!rSTmPi$rJgDCvur53Qgb!msR;>)%q!)zdF?pGqb0Q)i__^Jup6&zh_hm zGcX8eXR637!{KN|T4x4tRVCRNf#}5$TmcE-U}AixjvJ^1Ae@+op^4ykaZxG7N1ukM zsAj-yAD<7!Y;Bc&a&R_`Q}G&*p01)Atq7`fL;VkK~0--s)~*Qf__@d(Rob0iS)2`*?(+zypD9dvTx??;PynnV=3oTi7G> z65MKZ1TU~zEZj$mhVbM-G{pyM2G9M)2>_)fA>qCJq>N%dH6h}{?;0khNOE(bRPh^%hOqX8$UfLvEX29CJ0pX)S&2vDx$0c|O zd%()l?w4fU4?OZYYvajRhaCpJ^aEq`K7*$#L75hJ=OOTxLmpfX_P;t~xZneDK$k(U zFqEh5TBXmhDSU_oUHTpzhr1B8;B)7dPqvM>vaP#jo4b3~{_6?S`d`m>Y%0c<@0I3l zPJIRHx_GY>xNW7KRu=%i+OQN18hWBg43o*)65~fnViVq!NKlz`=0b;uejv16^WaXq z^VBwXC6^d{R9^I>XhidQ^u$s3l1pb<1qhapehpNl#f*r$z<^B1JudaN-*=##)CxBH5iON zR`c3FtZ}k}{hIPtDti+LRMR19GcFW{Dqs9j>z-VFxm)pw2JG2n(R~D_IpV}zU}-K` zbOp3N2%|beoM?G?9&(*m-P}YaG7nqrf+>N6vpJ9i)1At}L-a6Pbnr0%D3e0dq@$4K zL0NFXZ9hffOBVS(k4im;pJ)tIzlwAPtkU6fGx*a~!xKkEx>TcqEHRaeIz~P8M(P}< zyz$GotIJ@q8JVr70ee-!=%ENIGh*GVYtMQ)=7q4XRMdj3@4D%8F}|=y(^b@*$B&Vw zPxLKH^4HyjyMZv)i-Y$jU$e>!x7E3RYX$gjQ;P&4HBK{XZ4N0)ze*tlOb0b?Sg&Bl zx&CIbJY22;V21KPF>NLKC}pHPm~HHX!Em)uZ}tX5r<*7*td@hEUg12kYAu&f9o} zuix!d>wd$xR8`$A*3-0f?N#9cN7#9AM5e#IkCaW?-~0?EygQIrY(AQn)`9Y`X^HiW z7(I93bCWF18zIM$+GPr{MxRW#H*WVil1l={;C&9nhfiSE?z@P*GL`K&T0|A9Wyc1D zn=}gMj`ZF^Q8^hl){@5<5e59hB+PG)HIzeFf&*Q)NSHB(L|l6uzcCCrg-Ien2MV#6Ux0T(DKol=%u&eIv)Fvs zuT-|DXK8tSFZK{2TJ(V#2oV$rACH{I>f66V0}+QLo=Ro!hyV62BwRDpp$5s&Zp!3USW|$uDoplqg2fmi>FHzr z=1C-F01z$`xL^;v0MRrIiiUCKV9s73y*ftt;x{hqI(_aIQIRo-)YmxS2Sfmfgrx!> zN>c;}di555(m=TSdqyYf#u?*k=;nEDgG731xjSk1Az5F66D+4SYyGR%DgDyni45IX zcxf$6qUY(upvve|zCMP7PdDn%8qSm~#XE#BLZ7Yi7ZLQAMy$PfI9rqlc9mSt zZG#^RyO=m%x#c}cIxgy!Jv&@uRMhMH4^7V~l5(z;eh|6sZu+3&s^mIu&vt#}pZMpa z8)O#7B*W9e1E_Zs5sG6M-#s8Ky5D_Qr9ZAoNaQQYeK&e%y24oymnD+tqNaV8l_Xa7 z!dt~Zzm%i~hXdkHG)c&b3qqWj(^uN%oiGDlelj5WUAmTvX)TDvVF&-;t8b_(A9^{<%GB3E;m7u}~O47oxT+lE&Y2<=L06@|KZ&qvfLur*%QblMBxl&N$V2#pzyfS|c6(bFg#w#_LZu zNKYvdHXgrsY#-6&!k@R#|GZ!OBee$LV=nWVROpxE^#Ed`-1h2)k)!^s#-5H0Ka%Ry0$dMJRbrr+KcoE#9oZSH@>yJ_Q5VLYY|~8~Spjl)MT;;;c{_z=jaM|5?6gqX-H9 z^=2`7G&^iUZi9JrMY<>q)VNU9_MdLprMGYByzj@Ldl$BzL@WBW2Ew}va&5yuIX%sl zaLak>Wca}r1lCF`{ukp%D+yN@UUW zEzlO@zTTMnTUQ1IZtEcRtqFE&6D?g{I{E{5;x_rGh=5u=6>*|tv#tE$0e!n06;yvR z5ty>HqZp_hvR6H0y=nBd5|1VsQ1CCtf8B9hsfLjg@bEiAc0(i5V7vaX+F3{Rwq+zB zVXm!)0`S@f&ZbKhEzWC7BTNu|)l6tb$TS(a&@t+*yjhtV+8RgvmwAnym2#S)n}ep} zYk;Q5m8|U4T4;6OX`%QDa0OAqh?tJfde(JXp#;inUz(>gQv90)xa%;9BrIs2DjZWd zhBEf?&uCm(xBrZdv2Wn`PyTS=r8Hx|gQh=Y{lcz&zJ@w)sm z^!{xARo)`L=IHa2m~HWM8Jf4_UuNB3j$bGWzMZgiY2S(9r`3Nm{%gbA65n+!-A??_ zgRw|j8P@Dc`gq^Y;`rys!9B;nKF_c?@qMYf=fuws!xlouztnSbZ4JW!P$o1;iuX6; zhe(|?v@wshE|q~)H=*Obc*)WOe=~l%cpPs>iZaq4Yhz+bJjYAbwD!k)c3Mic^U^k^ z`iqK58_Q0*IFC2^i^q0aDShE(SRnVqX(rYxLdI`ry`NavX{}*Ak+m~dCXHia!$Ttf zzacDI|JM^17mwNxpv;cG;c6mC))|@vyi12SeNJt^_N+c^i3awXW*QeXm`+TW^TZ4_&d;2z%Ed#4O=0 z{BvbxoinBN@4Ftjt><02W2Dm89a|NZe(M|F+BTOoKB3iusdSyit)F7{<3DLM2>L`f zzZLYucDgGAlHRlKatwexBn{Zl6{izR%EuI?o?th|Yz`@a@Gw3#MNIrrB$Dot+iEpV z@WyKQ9J>I}MD(^;LwM^e0!T!gE1LHJIU&dsp5o9D4~dB0s8OH9Nw>+}N8f#Z%*fFD zGS#d%p{x*c<yLbJlBo&9}CEa&XvC{37A`QBX9Fgc{@L5uovc??z)-EfEf zv3qG({8*6`$>vDnq#D`y-Uq3~Ltkie+ZaUz6SxAh3|E*iU)dAfRJ2$q{}2IOaJSH3 z7m>K}&$s!ae-V~HKi+nH`14aRym9TD0X^j5i#BaFQSP}qOu z>0QGocLx&0Pt{o8?Sm9d!Y@nxVBVu1(>fI` z>8kX*rrc7;%`&gGBH2va5v+7;Rq#J=YPy6Es!G)rY*d})UVa5|Zi@QcCtK)^AdI`+ zQ{Q?7%h|t1p&?dE2)7LN{S}(*Vg`ipAs-YI1@Kv7hZwb_<=1FrG;7^%8bZN-Jw~VX zugg*chzQb%XYDao)izJ^odY_6ag*!SY)=G9P)EC2>UI4=EaEhR=}Y20to-qaq5$a9 zhq}G*D5)Wou)2UwlSf^?^HpJHia~f|BBJXl6!7XlH!Ojd-WxTKys3AhI^@Z({TfH- zeVm@4N~cIS>7k2q>7pBS*mCi1Do@sDin?(6&&)Oz?lHk)*o@@VfF@k@EiO`$naY}H zV3j2MVTEDDb-4iSMBCp|9i##WRNH4p_zDG&zoj}rDAhTV*?NM^dH@xEE5>4DO%@c96+;@Wg!k;(TI4lRbhA8tN)!V4M<{AOb!rgEB=UZbacC{kOzDxO3`jSpd!u`J}*}27%I=$!C0a_6vlC(uqKR)mA)+ds?smx)aHQ1&Pa5ogM(pci@h8#o66fc3M>?~< zwckOrqUo85`RBU$kuvlfa{U~j@=B5xiBEHpRhjBF`KhTC*~^oDfCZ-X(0a?q=ssLX z4*M9rewlX0lkf8q;)XLYz!;+x9+oa5|B?p*UB_MW!cmKGt>bbcw<>mSSD`e)UOL-c z5i}vRyJUj2vc)j>Y)ASJbB4A|kE;cX&fn`K4{t19$xbe2ktaj2S|iQrlH3dAJ`8Ph z@*GTW%GbOE*sP5ypH_IUiB!DCACOA|#ZnrqR8p4i5H9y_S?yR{BKsqOOps|5xnG{c zC-e!Dpx)zcRMO=lTNzG(id$fg8sQG_Z^i4u0Stn^X$wr)ve^Kd!{7}`rfgfI$0|aG zqW%qjs(RE}Xn6^a{FOrZg)%bb#(h9;(ieayzfv3lpnDOqfZDwm;|LK>J`RQ{_Hc9u zOm#8@AoSMaKAK#KmXC7iS#n%!t7P(Fe5713&}Obw`>~=%eUJl=l}+O?PjfoV9rP zuV{5?hQ*n0nx9cXVn?QVi$*phEI)FeYIRl>M?8v%T?fa0(WDl33WdqAhAH)Id-$YG zbn&)iQ06#Sd}k;qnO5?(d)S;xmFKEmZ*O>4;y)+e5&XL zsu&c78}m_nMpiB8JjIteO{631I2Z{*VOmD&$9g^NUat!kat-VYLaQR0Lg>~}USn@2RwlT47Q<_f30Nu6GK?d6Ci zEm%fq{JR8yvq4G-@&t>*?L44nG6GG=hsqHY9Hd-paQX^De~stuvN@QTmmd^ovMm7? z9b$^GKr#n`bO}O4Mapx}DBxsa4n>Lq$~JlWr0sK00HqjaJ3T2d?2&iQC!^S7(j9al z`G%l;G#^L4W~CGxs3AxEG_mw|SmRw23`4Sm>u-M5{DV z7Y@KS7lvhJkt}@=z4AQ%wLl~PXje#yj$29Tbjii>>)VR+ zzJ|LnX6jjLRNN+0#x^ZY>SZ5)q-$*o6X3F}wJC%WnPJ=Exs78W+~*ET@HW`&Z%fRU#$qUalY+$p$j*4wQB0868A_K*Do!=J-%WjUHk(H%8 zz`i~bbcy}NY{?Q1T4Zy1!9PycnK;P{>1XWx!<^v=vY+hIB??1qiSY9Al}Ql%Y)e!JHrdqxK?$H!5eLdkaja9e;GI)0 zt^BBuD(4VoT)mnsS|pX3J3coH?qdM#M_)4qGu5NBQiP93m_6U;tW0f+j?#5wm=p?UbMQ$VY|1$- zmFXoso~kCpN$Ds=`9Xjex`$>Ystsq_Vvn(Frzi5;ZR-&%aJ&*W5bO<3hY{S%nC2Lx zJN2DrigW;&Ge)HI^3Tf=|2D9=btC=$*t|TTss65+qO?n}P}guW0%e#`c_zGoh91lW zKZ{`_C;^l#@V#f{^HN1`6yT;4n&wmK=*1wx9>tZg1_16LdGBe1r5Mp)k10A&6Ko$h z5#{Z(IM^&0RZT_3xJY^ffVx@p=v)?~2ur~)Y zwq^_ubsu^-bA1?uARHh=i_9LpB08~Wn-lzAJwW+8!LF;-TwdXoT#+oZ=x7Ek&Er7L zUXUxryNu8kVrKoLwa*pYVoxCLM=9}rl0pgIfrSv^VoNhfqo(cuDQU{M7F(u3E$I+R z4xu)kC9E_luyD#VmCaEQ`6WB)E_|5ZNTarhvpN*?QDyC&gL$4Zw9sSIu%T%~*bM@i z78+a?Nlu825s`GgOY#rv!j~0A-i4u{Qh)Utc1pNN#*7FZq5Z@oddQ}3fpZLrn9C0wiV8U#(I&Tm?a0$QhUs?TMv&ubDd zzqNtVDMtV))Futtdc6E&&)?Z+ z&gjwX-KXm%wVJ~Xria%FF0=J}B^8LXKP3KTJiW4&6-t%zl+eN(l1bFQY}Y;wa{{jV zHo+AdbSl38S1oyTUt-R!{%nwP@Tz@N6~sbnI1%hZ;DvU0^LDs9ZU8m6_wASJO_8V7 z`K>nE11fWU8$}5cL${Fn^*C_X&PQJBZh)a(ZBbq4Lr6_ng75Ap#TK6n-QMf~CjAZs z2G}gQS6!iGdIn@1j7bgz6As0s9-=2Zz>!{u53Z5C!aTv+N9RgnGixiopcQv1?ogsl z(XO1)T@9o^Pv8R!J>Cmd-+c*pzQf6$M<=I8$H3bSzwSKySl_f=PP$G)+x+f|{?&E# zJB}-(o#v8IT({AjN%c+GM$@Op_X1;!-v^`fg=6QtYs+?+`jvFKx0x2@1r3+a7TnwJ z>u(cNKIU#*biOlTY_BJ$_F!qu`SXu+vu^*oYfd?HBMep^JtnH{6K5b~YXKT@-Um>O zO>cI1)?LwHfX_QXt5~m{g#o@l&w;}h_RJnVJ=utGB6%;Ac={$;#F$_tQE zJ>McP_W)!5aICr3@%O#$7l>0LQs=#i)=eGn7rD}uhpvheRqp*hlnH#V7pC|2VbA?2 z*EUk`qu|$p`8gyB*f&UwpwlQ(D|~kL(`OTJQhO(j9gFmz0I$E17T*v~hZJp}IGQo_ zC^uX=K`m_alc|Mr%JC_}CO9=ovfy@@q%54Ed9O8?rnT~Ae6GeK9S<%nSXK{M0Z7w8Fa*CU29Fl(&e zcI2Y8eUn$!6{O`_^bIN3y&rc=T-XDPIm<9Eboi`?JplxnjdRH#Ah2+jTb4UnIFZPf zYL^yL9u_es&w{5*!WW3W7&GQGImU}EbF?RM^;ALdrPESSBwu2VMtTu*b*y`%NTbxs z^VEZqNai!71162pncD1m$!8|%jW0mGO24~EC@*jjV!8%Il5DoPn%c1w(n@ghse3J_ z1~0xkLGttU@XUgrH^gLs^X7Lg7R05Li`vM4&2#pW9xuz_ooB*CIBhkAecL+eL3lzZwMZTIxGht*T!HkJBpuK;Dl9;(y>(BrM$DNkp zuh0_f)S0(VfAkPHe0U&3wETyptWOJ{0;2DO;dJ(b?jC z>zKYVz5@9PMxF!gCtnnlnUa;@`xs%_E zuc^LMBDHnhNn7_FHE~b8?hCY1c(cphVPR04^5eR1=99OaC)+EU5Bs*32>%(ne@gtS zVkhkKfUtUL|#e~LG0tqCcC1n z){umx63MKW!e{$aOY!$^@R_d8pT#o-iqEI>t_?!)|GwuB#kD1ciF+9*Tkxb=c+nM@ z_{X9YQ?f30nX^n6Q`{!p3w>do{cnWD_O#;G6T+iz;Rc`jj*HgcBm2082wyCc(Px!a zfOUO1FbyLCQNZKVnCySFDAkY2g!F0;i|w!oDGt4!@{mB-AB2+kdh2sNaQvc8*(5nb zRNjO=Sm*VAL`-9YN4T$`|4G;J-+xdFJ_1G`tjuUEtrYAZ!WbB)EBLMk+$sEzgymDn zgUTJ3Y%lnI4xMb=)03|FUo6Uh5thMI%61oj#fmJ9U$D4eN)`r*MH>v57jL}~d-wF# zNsRK|U-7F8@a#9(6VFm^VEMMEL%Pd80_5ob-v|(y4oiL7gGXulMQ{Hr^MP8g?Co1u6F+-ES0Tp zP8$ae-FIwWkW@o%duQn3dh&+zgzHWlqkmbH-uu#wynKTz+q`xi9yIdab9AB2d!N3Z zk&v*cxBDCr5|-&VM7MU|;C~29&hIwA=iLLwyTUsb+IJoPo3KPm5Ig>{DEGwPZ)+D4 zmbA@#6P7AF{w6GcTa*hO`%bQ*OoW6*qm%J(7G+SUe}?jZA}m6S^330aCC^Ty>u9!V+B76;yV3$TaxE(Z#Odzb(p;@_!>NW(O;ag1Qe@Uy{0ho|Vt)RudAI zA+xZ?j>YbKhnj~qZX9a4FC;8&k56~#v_BVLPyYAd;Qu(k7=PgZ()^AchowbyoN1%OMi%hGMvl95F=Vjn1Nm<&<% zUVmrVRc`Z_OAvwsyF~2wB~GfBTJV2RGyVr~ zAXGDS+;`(Eh9cJUBVX6=tX!*0KizR0c+*((0E>}>E`ZEyEfd0m)Bs+DCaTY`d+QQ9 z)%CXJch{V5>%-T>>*=0J6rPl-*PF(~$M}MG9rK&M?DTz{T&`!mR3#-U*#~g#yAFOq zEQmvMY!p45_vUbdb_D?7)Ht+cw1Uj94@IpyuafaP1!NvhP502sQT_PdKH5g?Lo6UX z&|V!8b|zOx_q(aGjkP-7uHL0?nTLR@5c8U?(Llq;d*($7eGY_p-p5N~>%u=xSZ0yQ z54Im&-2Ru##>rk=1#30?hd#1ow zbyDvb?Xx0Fo2FHW8Kj3X{>Xi+h|qfj zM*Gu|Iy3~4M-C91F2-#KBqa^+p$zV3HzVCr`uQUD| zq@gWyr0v>DETjtph;INc-nMkd8Hg`2hP9Qd;kpGnH=*R8`s~Pf_25)9kiEsG(#{*m znRh_^d;Ui$jxg-hox`(3?24J%zPtXWqvazsyX<=zQ^RY<2Q&*J{`lTR!FQ{0?Od z`yJ49n!e-r<$CdWL(t~C)Av*~WQE6eAy!T^6Q%8~HCr1)-S5sk>TYjqI^KB5UBvJH z8Zi_AxQ!77wX?9MoqjO~I)#$viCl(HKLTvQ@L)H4Huid_OPmXVh z>!^SFKKkp8XJQ+V&OM%873LS0cU(L6_`l{C_e?%qebavmUva=-{=>T zDOq}qkKXdF_iEN|CgtDqi}#w+H;?@*zxe(h;?8#+sb$F;O8Q8q`&bL9#V2^f3H`DC zx(A9TI)}7w=%3zE_0l_!hmL%@QfSPiU%SaX(do2G_71?K!_INV}8ZW&T(iR4oj5bQry2S7Ij*T<#piW6f{wZ@oKz_$A%;1irX3u_+aqMA5Z2M zpVimjdb>x}dV1e%T*qU@_nyPfmQUh3XhV(RhdWBA{t`cGD8H2`Y2c}%NAnW*0Qv%^ zIm}ILx=4`mP;L?u-)uwFCU$@+jHe}wzWcG@@Rk9cN6nZ-hn%#8`p|?YY*42mu_HZI< z#<{aa=OzNO$mCBdq2b+pNLi-didm8(@<|cc5A%d2IiVus&qq+y0S`W_edoKAL?N_v zBvU%-ks~pWu=A6TO(o@>$>}+q)Rdh`+y0y&pLxO--Hp%3*`-EH&bl~Y(HrSwlI(KDy2aj}_jDmLTj8Vke&F-pBB zg~#a#9~ec;f>5^9_QYdAy5S1xQ~+#0g_@QGO!7E<6$LcAT$?I6d&px zl>~51(L?ZZ41#{fWCiqmdFDeVZ1x#UZOg;^g9ogoK20TW zbtTG2vr(h8!H={-O@FRk5+ctyPt~*R2qeE232iV+8dNnkazNl@(>J4%NT8`2=Paf& zLkSDeX_!OaFe9Gj8w}l>jPt$3!$*|LBI*Etn{*{O1r9 z1^T@y7y)80QE{>hIK$7lOeP|pkAwWrBUy+`09Frad>02a@!)s?uGbW|m5gnILoQK+ zp(vVbPGBeZm4`o;8AA+Cvua72!ITg+$SF|@_7(V-?T|j9LI6jq&C4{vH#cundDigS6!%+;*6%G08 zs>JHz{E_}KNJkW4kKerG4y=`aP=o>@=Ayr&%Eo=F5St?`k0bzaj;l%*W33X7v@XCl zQp$I0)0CSVa?Y+S&r!+TC-;+SC_Fq_>~Gp6{+h&+)GASa6%X@)wrm5e886c zWz&lX5G6lgQ$)axJC<9%fOoz`WE0ELgyXsi1nq-t9aEQNH+b9;zHbIk=)iwvug@V% z+?DhAcm+8-)9BQMeEPbPFL%}3=<3{$#(BT1ud+R>gg%u(k3J@h%~+G?F{ zFMf;KxocATdVl1apf`@GE=))t#8I1`Md#w5G>QLgnrPmfRD)^j53wsYEAkgtEGi;*i!73iQz{Omx^$+$fn$+di<(dD@q@)UIT~8RuT|+WilG%Rry&U5R~Fu0CdUp2m3WnS&dqcX zyoYWVZN7H*uAINut?4rDNf97_jhh|9kA3Q-?WvWra6_8}BexabKIn##j6%6nvD6Td z#7Kdn@XlJW(Dyp!lhgE?sIYu{v^nnLa;*&a>#HUja)=hZVHF! ztpzz{ScDAKNL^rK%>||5Ab+nqX?j+wAFM0@r8vO##TFSVVp}m+f`iz$1upQpfozZi zyo>JJhIeU%ws?iga+@j_53NmxEq<|injS%d2kWFx!L-BmUZFlx@%fd9h>5UkLqt|~ z+;3ZW_F|6Eia$S`G&_9a*DzCIk@AK4Xdq66ASVdbzzy#fb^;!e^KHUD`PC%8 zg-3ftZ^qXK>lNd0*_4P3K5`yiFv2ry)B4!`!pcgS$dTqOW_gPp& zgy1FJi2`Hx93l)E6RCV~7l8bvb$=cUWRo$NoA+wUF~TTh^Dfv6Ae!3?g?^xFmn5kM zTMoo5C&IJR$ldn5`ia}(D?L$j5$i`LnpnprSGv@0sd3`7*1ye3(g%mi9#oZsQEN*B zU2kFPO=(M2Fk9!Z3L%7&B5oZ9B?M91o@#F6g0Hn;>EjRamoXZ*h(8|*Kl5MCJIF9C zv$K=$`tCYh0Ug$EoCffdP*Q@KpBmC5SgN>VUtx+Bxq9xjLnZS-Jj zyl_13K_6Netp-wriWhli#TRx59&|lbf*ILl#!bB)utd`%V2ySgAC)EDI6d%X^pT$O z!NgEF9DXi3(57J+{X6c&w_B1WLu>KRK2fH`zy!H(u)1LU+byM5d!SQ+Z#(#k{4o17fp6n`zH+2@kOziHnL9{;8Rcp1K`y;coaa_33s~SY9tv z=?|g#_uL}_q{w*+Vy9P5!Si~s>WwUDh1c;dYwL!Wk5>Rif%(A<0v=9qYIO3l8<(1k zP^5*sIM4IuPMvH4iR4H`{F!xg5u?^Q^|anV&vmB3bxT+zFQ&{- zLWhxmcYKjY$W4bI@t$T|&rLYFVqMb2K!JVCgv2m83-+TI;WxC*zsfu{Ee2lRS8d!Ljm$tcVoflSOL7zvyW z1be}e+GlWpU)Dt};N{U5wB{a^f2J|{R!fBR)*ZJjTHb_AzgBWJf~q^W=bd`^>}?D< z{#NhI?0c2g8UnTH-JH1ctAzK~mQP>bqfDo#D$S+7eGgx`P1M^Bt1;ew)p=(h^`Wlz z!#ih*zA}OgGrO_FCsU`@i)KxN?P&@xJf#+;`X^(<84``mdCnk%H&7 zRp+~>iTI|2pepI>lI0!Y?7bNe-#2-oKQpqXHXS4giJuSZ9Xb-yv<%uE{48(PA5aV{ z11D5?^M?YyUiz7#&~#8fJhSgfmA2|<)scDN_q-xleY>~n?*0cD*3hLV7hLX+p=>@A zo!5?w5@ne~o0x}dW$&O2q4g(;J3qm4P2j?hD#?*@Sg_$K7D%X=y3;*W-e&L>0cuftHOvmK&`PyQ{){71>cuSPn z_V_pqwqtap$CO8wGFFo+U7sX}V^WxyXi9GMS!oLW$!P<8$}lHR90;S~*>_2IlTMAx z;gg$2G$e>Sg|o>IO)(QENuAGsP`da44LHOBlb8wb4oVmPY0q(D%}_BMIA!kj>SrWb z7((+V0W16;{Gzyu`Vy9(i$z5d|)n;MIEY>GecK_m8_fqCY$(W8+8WKr<4)UPw{h2uvIzhM z{#e38G5y(+VkTUhcJOtNLDbL2-B8(`coX1qAc(O26KsSYQfa5BwXhf|<9e0xMGddc zzYYhxmm^=@DN)U&H9ImZv^y*De(l$Ll>ammW*?dq%@jg$-bOgD{B1YD#KFJgo}VxItL|y zG@}?wy!hM~J`MHY=0~IxC=h57n~$FVm&1XoPC54!-j85dE{Yd>)6r^1XQF_U|EOl@ zUFb2|l0qK4xMlT?zg061>902`L$w+G+u>m4)Rw!srfBXQMLH?x(%+aR^Fam%R*Up})-MB9dA?fCb@LA2UOtdAI5bm`JNi?qEO z_Pv}obv*5Z(-Wq9@{aepR)FL*(*oQ%K)L0+-*~~n!p`TtCqSKzFJW=zTtCRFUl#H4HMwXf@VwLT? z_2+OP@l{fc1J@BKN{X|h)DIegsV5v1LU_8|w)4sPW^3|=yw%ta5LgZH)Y4h@7;7>1 z3jTOiQS4ubgS?BW@nS)J8s|ft&};RK2NEdevh=Eq8j^e;VZE0{(ZRo}8COFHm1Q*S z0aqz@VKo{x5{OD}&^}vX+mMDOAER(cC}6JQZijuu1NVSy(Rn#(KX?uJaujIs8y2Kn zqlfp`S!^P0Glzg9DcoVL4j-Or=uuSoC25GpYucv!B>GP^xiK0Pk%@w`_Oh}W~ZS>{fijvcgJJx@YL8=)}ikqZc8wi1v zlf*a7_ytTC#=4f0VU^x(ZP1n1wpxgux8ii0ppjW;kfO$Ac8A^vmpv%x>0}AOn#RRR z7)0ZHkZMLPNu9geNj0C3Q)+9B4+I?W1#Ylbc;#oMWW(KsQ>ZX9rQqu(KMCn%;FKRE zo=;h)LOX-AZz4e-htmRVr)>w4VC)|Lxw-M>vmC+c?mu?F*fPli># zY1@mtu1Y^;>$_r)Q71>+hjN-}bzIuq!O?B>^jZb0H^pq2!(^i6hgaBtZDMZ88_lV) zeQD3s%u;)hre^M7O^FKcaD6zMcjdDB8%LghE6ejpxJLkN zi+gzg?D~sN*8l+?;i}+eX`l!Pf4YmFbQGYYuoO7Yrp~v-s4VRyz`K0ZZLC}_H_b{Z zHif0$ou%K8mOZflP-ERxiu30Aqa0*%)da z4JU4(D$G&oa2s%YxaFbo=|le2fDOd7n6AWM)rQV$p7><>v%K1G=haCiYhVMfktn7< ztaq>e7FyGcbRhcb<29oLFohSG6Rwe+znpdDwq0nX~2*Y+H+=X-_IfIW$e!C|=w?V{T%GU4CV*z=y&E;#bk=&hf5C}`2qm-fj&I*q@ zZkTcH+nzLUFUw5U7#QZ*MrTlc*Kh}Zi8N}PgNX?;en$6Q_S{%^cH0)x{+S_~j8_K! zD-b>N>D;-YBiFU@3_;P4;QsUIF21+OY5Lor8b)EkhG%82?J9DmA%FXPu92XGJa?OY zTq(4mI{S^?k+>GkR6X{9^qORW)+$xO<(i$>-cDNzz%}-TRz0+4GrPhES9-tgKI_YI zG&6s61ADkBaeau7;%3RqEBnr*UJLQh-ZF;PVTA>chXlJno_y4MxV7cl!O$(bH=kmU zv^||6W8OPFdA(_|(BkNJkDA9%KP4UMT-T_Mnd71B?w+oCW=Fis0ML*@wUs7tU-*fb za6F6k`Gr%t!gq_xruOfxof;B4;+C}am(sn@2-aM;*bq zUny3nF;jJsf4u{bA4Ri_)n~)^E_RJo)s)y27%YUNzO9 z(!UPulc?KP!*RB-NdZ%blYcdBZ*n{7-PFK!2J#OFf`3JH4o zHvp#_*pQ4<@_0PG^v>M%7iOn%<>FERY|wFGC|uVRU`^X3zsSbxX|D(PEqfSP1f>W!{)D&Z(pB04t$xbP#{=m3NFiD7WpV( zikEk=%q+8;*0DW!pCZfBQaSPj)-0E++tXzjl}a~4y04O9IvfU3Rw&NPkc-H8QZDg9 zyYd4=)Ihg;M?ced0x#}FTuZ%4OAu9AiI*~C_Dlf5qZK+KsjaBwK;pm0FCH^89Qzmi zqI3?517PX$@nq2*zIJZ=nJ6;=O=G(K1HZVT|K{$Q)>G4e@QZ%)w;1Z1UcSBN6Lm!z z*>BtS`j4%eqOm~;HmeU_G#obk9lGT^)EhN)J7K6VXQ;n&XyEeDV9(Id z*wCGsp}Sw5nmUu>$+z#lAMiCp#d~ZX9di^eu~l8RHibYsTm^u^o;Y^ranGG6V|Sj; z+gKUGzFVs^y* z6JuHX0#Q}YzDPCr4^)*jtPWDLlnt86ve!hi5>6&>kgUWe1Y_yyhGZo?{1H{G(auh$K#BW4M|Yd2hmUTXtQ zx;gcGc5)S~M9XXrY>w}6?AzrkYC==8 z5z|785k<6p)4D}hRx&$^VLfh7>+HK)C`^-$vwYsh?W)x}x0&p`% zQAvN5?rHaD(|yw(zYiK$+@f)f1~@$P#)8|ecPuL8CVPp|7ppNq4oMv^*9?fm^{jSPNjT$JIdg71oP7-q=~@wRB! zc1aW_#H)x+ZN_SMlM3e&w4KTb{~s}y+ng9^)_B*R9i4l}LSP8^xgvG4qTm@YClUql zq8XRZj$4A_`{-2BAlC}3zNFscx0>U8-T^>d)0K7ltAowV5>#6_Tm^wQB~VG-R*V5u zuTS55!$sXLfnhe-A_jZp%-AT@{(Fq2k)`{(mtQ2R{v(W~U0ueZ;)*jjzG@hp(i!r> ze#!5#tv1Z=AM&$sDHsm%H!jt=6TIU~;r*fNwJq&Vtgn%0)(`-o$Kh^7;ickP%NmRO z{dc1~E|tt3tFfGR*dEKizm7Vf1$;$HmdC$eDg}Pk&`^%UEQPVsBMy((|7%vFqgE!0 zhc)Nb-b8v}?Lo$S6ModTy8)c-;~?VeOSGT11GgXZK_B0()3#wMS(!(xp1FttXl0~L z9tbB6&r*)CIIq_85izY6O>hb|FA!}-b`AFJ!0lj5+2+;-b?E+6RrxMq$Yf`8H|L!0 zFkvE;xARgtr_nF^z-1@C$+P~Qo@qB(ucMAU@-nA6kB#?Fe6LrpB-oNq0D$faQz-(h zj*Hh=d3u1(UB{$fOe}|_rMFfaEBLVZG9(~LnJr%D+&b;DW4^FrZ+p#z_Sk)5^Fo)TfpG}eb5=WDc zG2&(L>gfG&vUrYS(<_LFI(&4+es7b#_bj5WO(;trn^vq{9$nnNa4oEKzTx@$&sT07 zK25_J(?Ljb1|+ipG%(CNL-C-f&H;dtfQ2(&q9_dmRu;V5Tx~O5`TQnp1@$S|v=UOW zZ%&XqmQ9cS*tX+Z*H&WWMX4P1Yq~|vR)T6X7Ppl$y_Q2Xnmj$I;0(z#L9(q8OSAHk z21(yjL=ym3sHrysZL~ad#_86*i8z$lO=}e~mL_>wLn|9htE%4*q!|jSaf7VlLo^e% z)6Os-)ML>Qo{>V%(0PDz;QBT_V(Y6&5Y>+cs`(^QZ6>~K7DCXJfS3oL>LZ)1jt6BO z@wOw9W%D!xKyY!kOs#+e)k-}j$-0+Q2mp(=36S5qyNpz9Vvo`_#B3caqgcYxb^R-V z46zlDAP2z80P&OaDzmKUwgG!fU|*MYBhJHU)ugAnJ}Bh(I*_>u@`lCeUX&!tT?#-? zj#is_GWN{m${-uU>;?v@U8Z<@aVgJrn{XBSoO3pmDK-NTVBkKC(m~{~&7%lQj=1QH z11Se)MyVX2QF#vRMN%Acp~))dbAnsQ^<7q2%S^s=0G2pbjFMwCC*ivN8sNeMBzMlO zpp5eSlY#>#W{P)0!`UiV<*gzVJbXXrYKd&TbJFF$;=K^T%i@_gugpvDh*(RrQb8U$ zeeS$a`V^aq@PpK64X^JKu)e)*L}8BDcdgqEOAZTeuU}TC1d221E#~h=%J>e)+2Sl? zw)Vl<7g`W&nl+T`w?Stb7Y7)o0`fT4>Y*SWevC!EO?F;joWAfQG>?i;Wa z+E_~CER`jeR3ezb!#U3#pm5|OV4a$aauguc%>dS=Swk%J&jpfAIM|i#W-te89%df` zaWrzm^ddRp2ubjoWHcM!Km;!yA;DbQ`r2?u4~h;S4BEeDsh4D$3sN<4koQp+vV1Hc z#}S0GiRjm|Nj8Q_p{&3pZ#FO-5xgXIh>uQpg;6}2nLM~2sfQV0`WE0fSO6&^&Q}v{ znMV%glcPC+hmd%rTNBRm2qHMg6Q+`g)KId)U*@-7KMNQoemKY>hUjrP3=vSSF^xy^ zAy!Ng2t*Kl$X+)bPmD+nl)B#S<3Wr>MSxziKAM{%bWIOoTVZ8>q9Q*L)trK7G30?r zfa@cs>7x*yPW~Jr)te^vDpmAz#H2@rrzR|#gq8tTqpKs^+cKVX1CNOr@5!0-W|?0- zG8by473m4l?%`*uGXeg-F><;BF{2YtRO0%4!DLEVrAuKm7CjVX89vm=Ag?4QZXyj} ztbvFbD#NJX99KLVXfMuo)OB-9CIo);z-E{2c;G5QiiX?H71qqn|ONP%MBDN=!VFz zW2u>8v2Zrx%PnYkHJ6}6+Mtj#nOtJw2v03ln0I8&B~}{gO6xL`#hpWb_l9ZAf%P$a zRho9mOo5ucl>px_-aOwa7;-j)m4_1~BC=HA>I4TVrh^oY!rfX3>(?WSIMCjtRE8I+ z%s`Si;Mh{N%I8S^D@a(U{BaOhWaO}-kn2sHilBOfR7&M4Voi=k4RNZbaw1wmixI9> zt6T;u!9Ig{f5IG!M5x>}fm}&T@y<0$pHb_)>+&s#6t5yEB3+f|jZ+8x7SCu+g+ZhK zWL|-87Zm#H;3l!f}zp0;L7gO$hK>CUTF(|q~?{mbXn7UI9^0{NO0(^Vc(f0hJ_QI>} zqtg}AU}o;sthe|MnXYs!SYLdVEVoR&V{u6B5SaD`RN$k=JQ*+W4QQ*v`(_y@gDWL@ ze(|0lX#l)R0HD)EFMn?tn%~czYjrnW)$3}m`ysOh$webjJm-YpCNRSQjTEr5glZU> zri&sGod6y4Y8`2G-8HSx*9^QXq*&Pqg&~d`tZOBLqzCrmfz{)%2krV>(U$i`q>oog z%SQ?EvA@^}Ai&XmyEBdz0}mV~ zlABH;#a-bfoI$<@Av#MCm4%0rw!l#j!gZ+!qIm`HY3QH_=*R0wy}=k` z?oG(Os8#0%7}9Qx+;odbA@M$&zGrTdH%~hN4{K+v_eh}9n=r&)bXS#B7Faf4CsW;v zpQ?E+1D*D|Dn9m_<-k$ghr%O^=@-s&jqT4_60$ z2MNKDn(ktJmkSaBx;OCIs{PRwH;l6hdZs&XZxDnC-p7;9tyYg8Muj(SN=w7Ly z-dlK2lw+c|3eq)13hKbL-#_oIAYyQ3_;<4S`ne-zU9IzJSBu}*%SVJZ2EobUR)m8J za;-yf7QVO|@6Le5R>9L=xU%Juh7pD>4@HK1M1@wDu@QIe1z~y(c+!W_^5*=HeclZr z@EY9F)-C-9y|{7j?w5nu9SjCpnJ7;Ov3JI5BZ8cHgp6Te=Un(V3;5>#2e-Wuq-$iY>xtid5;JfJ}ft{dod z@;(>V+_UQSXoy3G65o5`O{9K}v^eQd_%&JgjvCf4Kz`0hBi1`~?o6iA_|4{;RlhK$ ztq=C`QSwYEs{;JUnH1Y`C{+94bTEQS9c(R8TuccR<>D=x;%}@{(%K3Gryile((AvZ zcaxuvl=x6(2ad8T9*S3pZ;B_yx%3M0QeD%JC|2IAb3XApH6KH&)1FjUT1vfKMS6F9 zvb}+KhyaqxJLSs!-h5~=ECb3dCc;;GN2b9cYwo3Y4EE2q8Ge3N@C3%GREsn}FK*cU zra0ZZsDX5zShWZAs@~jB_UZb9QfG|ZuLUo9F%sGtuKwWQ5~->Yj8k|Z7m+UR!`Nx_ z;>^_&21TT>4pjhKdMZiFQ!v(CkZ}l<#GxeJrw;jog*sTHxg)KCgGyz%i$!2;x!KLl z#CX3o?{5!2AprHjsbv0)cvskqgCud_4#51w|5QzbM|;E8P(x zM*T86P0CP)eNS?=tSZ9@#O**_voY-yxJT}2xh<$Ql;GQ9filXDu#Mk)GSc1WY zWECm#VQ}C(G2TOj6^>bI?EgYepoUkkH_%agxe$O7fU zOC$t)R`h;7-vzjZeS;zZ*NuuT$~SijzcEx7d^Rrl?pyFbxe!>o5PV}H>Q#)V{^TCl_N%7vnD24_{wQ&O#mkw3tL(V((i@I=RFtT}rvJl=gfnL%76MT|WJ9 zCCk#~!W+xQ&zH{%mwBq+%Qt?n-1oiu?*4GLD)-g-=`%&ZQNQ+<$~X+4!cc<-Zv5OAad-5jj2P|bgB!AA zrN0=yQ~*N*uipFRYIW5rB_O z5nln2Cip8W@n0%g7VPk){p;dY1K^|H{*ON>Rj9iCdgt<&+4~Lq?p?q3V{vYJuyp&4 z>%V?1eR=o%-i;f`z=hQoFwwGs0@i=sAM}4=@fraPzbgDY-R|G~LH}I5%El=xaWsQx z%Ll8v{`iCb_a(Kz`Ge}uc+jl)d4$%VWz!|Ar5(e_OoH_t>^suifP(YNk)!yK(*+!=~v@;XC-^ zD&CK5(VmQGo9jIfw+xHV7jjm$>v-}I)oJG(EQ&N(*#RRGt~bS1$m_Ub==;ex8>^@g z5_jJ%umeu_A0TY~%O4cb`0ZclcD`p0E=-_JSPPROR~mCCLvOEId=mAjQT8s7 zc3|RlUGm^=4sEy2-FH6Lsvt~X`$b^% z$M#p{nW613s>9CPzCCy4xAlL#zx*il$A`Ap=YM?cT>SXs6Cbzw=Uk6m*w6ph z;`K+n^~k|7`n5aeX`S;6>eHf3HK-9dF|ZC046XJQ9N*BdXYljHz)D-oKXkj&m*B)G z<;HJ}=bkI`NHRylHxlc_gXH@7Sc^Hrms+Wxl1Lm!Hd}=_X_m0KR+PZV?S| z&Yl&5ydYcJYpri$iN_$%zB1?X_XnUcwb_iMMRP^mt8P za%92^JRllaDzyrx^Vv$&bon$I4oQGy9RoxLTpc8_Y!>3{!4X(pG{oZLnlh8JJGo1e z+s~E2S3+B~m7RL*?3ITRcZmyrkj7Ov&1{9 z)0w)pY&)GnO`9Ogel=g)~zwA^#1HEZCtu#8>}$2(mS=5J}XQ0d{KOHP6$N8)SECZN?z0 zwk9Bbu8V@^_0ZHUlsLgJ&f%#EPMFi97i9e)xqQH4J)6avWk7}_UHc7mxy>ZoV&(7v zD;fYb6MFtgM;|C`fyKukXr}Buw<$cBMYII~wOK${Pr!1&hOUtruk<0U<4V}`A!vD} zwc|UMq|gIs1%UUoU~`$IXNNK`YV_d@(B}B%yizSQaD$u$%ub1*Kx;Yez1pyL@NC;W z8tBLwd@@*n3ca^Y$2RF`nnP4hewQPw-DwUw6q&JKoBR>Cy9xAtCP1s;AKFN~dd5ls zyq;mW_`+GKQ2Y!GesnfP&tGF3sC8MAdaUEHQ$NjYDE@8921YBng%8-2tTqE6q#0N2 zmcPLd=KKnMfmYD5D^^WEm0jcXQg_$#fXCg7c~^$~T<>&I4=qKWSvOOwCZ{g$ugR(C{aF^0<0GV$ z2V#p}JH57eynHw2?xA5pc+!R%&wI**LrU27vwccp!_>E{!-&VJK0*A8p)lS-{`i^o zbOqa^`1vZ+p6PfpO)nZFvTKhsu07NiXZq}`m&K~Q>#{vXm zG_(Z&`=$4lcrooQT#=bnDk1y=LsXRMgh!*u`AiAUL0DYL>w#i_eDw{VgWE>uOHd>H zaw#82fO`q)x&Z2O-H$y(1z@f8M2psZpg7-)lJ$gRdMX^ezu{srI##0Nri7{$b=yhUNO%;y1ro%sLU# zZ@9f#FzU*C4JkjC%kP&c(13Ce`9&;-`?U?u`{))nou9G6cagaPC`W z@IBgnddr{870%u0wQvTwhnmqH{z}AyRqiVM7r4u3c#@l{87d%rlCm;FrxMF1L zNACiTY7M3BEAF`xg=gI8cft4szYMaX7%kk#bUFZ-u{~<`WVZ0Na!d%IeuS>c0fMyV zS$oz9&1X;C`1yLf@cZL^v8oi!`TL~7AA^3Vk4K~t>wN4Yu{1jJ_accfcQn2%N@R%% zlUbxbnear?15*}*g=Vikya7aYtc9~>4<4^#A-OqBK9LN>QRtYYweSm5k{boZ+zCm+ z$H_4y#io;M3?tNBs293fj{`!fQbt!WBqc5=Ne5dlhbmHzDNr3qT!;Oqn5KBSg;xi6 z<|lf!CGH+i+-qhdxtN$k-Bw+-Pu3eWi)Ob!g7dxx%F&>_D$oKi<*J>OOpQGJ7v1jI z_^G#_<4%w{Y%@-R2PY|p!-)wn$>)fXm}$Z#4!6(x>L%P?ndDX$Xiov`xsiDuifU33 zCFGQHvy@7Y6k}v1Yq!?JT znJfi7V+@~rl$!1gZlqxC`Cwr*F_IoHy|@*V6*gc-Ce0z;FZe`u`al-`3MpN{QLy0R zvwJ~rkBn3h3gh8j)}pudW#oV$rWUHuf-eO+WY}lsPuU|j@Oob_RUQ~Un^|DB3Y(RH zcTgaR07*=6CxB*-bMw6opb>y22thgl?u@KT!y~I+(#3grdjRUfp3Ws=0A>o-S)^Js zQ;HF#t0SN1mx>k=6R0Myu}e8 zArXj-*_k-2Gds#M9t0jE4m-coO7jtscbUjM{-+rThvxi)X`qlIZne~x z`{J1S*%{BXuVT;67My+Ce)j#u*^kR-=j2Q0%}c*}mM+AWE)|r1Z!i5hQTlti6j0zn z7Cc-{A-Y3~5zZrY@Gf?3M3)he6%7vFeI70|nc~S7mMMH!@NOw1y)82uDFa~e=ludo zFo^^phNLLKAWEx)lv$m#x`POU|Njgm|AX89KjXIlFAO9IM*BY>NcQ}FAnE$A4kY#7 z4NVt?(eayfct9D=Y`jTI=Byj}-F7WtxVupzi`m_*-O0BmbUcf)7S#sk-d`$(KHs`9 zF8grD-v^RENf66bR_EzG87A-2ksLXePe zS9jo)@ai^~#9tO!6VCS2=r>l5uY<+0_dRWzs$wBP1#oRb29omfNiFrTele?VLAjWD zOS%oLJy2O(g@CN%3yqM0q9JkHo&(RB?r0l9cjG&sEwtiqx>H&8O$R;I4K}=)_O;Vr zektmivHS`fba$DTT=8=Gb#dl4i&v?o8OzV=|N8@p`@I^GO?Y3N=)=b$HhAFY=<$Ic z3~iM7+$irlYR5p(pvoU<0m#9-(Fu3{&rX3H;Nkyo?B@@T15-r&V;Cxe+(pW z8s&qvRu`f5mVj}#>Pgz=~U_@WhO|dq9vUrhVRM7*D-Pab^WgXw=kw0S?fR=D%frn z)_Aze%7+qffQ6|hoE27S+;~S7+iXau3yBsCB`9sB$hFbBH?7#**vZ7z?dsD20hVTd zsIER--ISxM%1%n0bc*W~#(2>B6p+U0BHxAxg!NcUO3D+q;x zn~njaQcivy3f2WSYp5XN-$MXFo*@E9@6|}Zc8OJpM|9Q#OE#UMF*WO zc`dyXum`9~Be@&1^fswIlxt^{@jR97t$ZB#hBCVu&8y~^ZjUBdH74l78eD( zdA+zB&_;gU^3|U%UZGG%<0-#b#z`XY{LKd4P+J=a+S1B3#+)X2e~@Dy8n{|C5>_(ahPi zf0B5pFBiRhF4<7JQLJr;1YuWmT7c7Z1KL_W3GUNbqPwQUWi5_iaQX+MZR$$4RVb@S zJ59Rtxzksu8Z`FlEIOOuAs7JWXm2A|63=a`gygs{X=y8wToWJ#fnc^3Z;V|VB`mV3 zPTl2f$qj+{x!V4y87WH8w4s(DJ!2XwDk<95l6yeZ zo-u6X&`_bl7?9vbK1dX)I{SdxKl02=3~J_=mK=vwm+H~7vop1N&=#+&zImiRpebu> zzOHT0wKd7IE&X?tS2EFel4-1xiS=g{?-$V)u3us5)_(%_@H&1;wDED<=GcmV29hN) z@O=29F+~ch>lQ?YgB#BHJ{HGi=mNA;YrZII*us4sYpxfakwuG8gu`42{~`r5bXo0w zk6HgwH4(P4fZ~!L8#^Y#tf=Fmr+R>@^+u5;)4h%E+g=959^|$tJhdbR+GERqf33fI za2mj)HA6$ceZl9x1ITfYZmmH9D+LsrT0Z(ZAuC%#{rUdY+xX|@x298~A;*lXhbiIx zSq&ba-j1xG`pZ_|0K<$%!!I$5Qe97x`WjPNeX=n9X zl}>EUSS|hhfbAoN@Dom_FB~gSf4^YoZDxGI^aaN+|dnXC&&g{Z2^=) zFMQIJXdAw@7za@3kb%HYw#*gjLfdeUY%qZ5-K8M2!$YS?UR6x2Gg#&t0T{4+Wa0rn zUALN9;zlfy_LrUWTxm}%@r|&PGt$H#n>-?|V32?!lh0jB*tV2FCnxUE*1Dt)KQe`< zHYcE`z{J*o%ANqne4_Uf(bHZ^%Pdj0%;!~}pBR$6q=R>CQRku#O!o#%%mg)!!4pvl zP#Fl%9YOdF8#%;yGgy*qigGs4jzC(Y#QnlrXCEFXw~Lc*M)KeS9D#g}M>3TKiqj93 zG$$9&5)&zK7#B#QA18a@avx5JxNnO10nw_tda& znW-R}LBX_X!W)M*3GFZ`Jm%=bLt+!;5_R|tB@42`)yokJ_=gmi$pye+WJ(Dej*#}o zN7bZj)sb;##ApLlj?iH1&iqqr`pIu*T~fjiSp(@b-u@Tj^|dCoi^^v^_7<=@f@sox`feTPJZ6mEc%QG zoTz;!V=740FjloGEykQIaw!ST@^zhnDNJ<96{5_y9KWSAdx?&g%dn~enA#h7oI}ie zlYfASRi45Iw#zcB3pA~>tgFg9p-TlI!>zWS@XRgepGe2KPx`tJv3nw#Y2tRFQo8@Ok5_G=2)LCY>n{(0 zuidHRLL?&KDV^01uW%{3{4WDZs$rfx`G8c!8T6DMdr79#f6Lji;7@fv!<&c<*%G`n zG_xp!;JGvY|tn%up+C5pd_j?sXq1wly+SjYvKdw5kusXP-I%Kjs^m}!9 zhvo_SnkcWD`Yc5HjB^OzD#EB)n}yCZg>m7AKZmZDBBg8%`?MmBKQC+QNDr-;nKZwHr6j3OT-uiz%cCRe0(XJD~(v-Hn zSse5Biuc)L)_vCh-fc8no@Ns4N67e>>yN@iDUHClI*~^Br8l+wt=9jz{O9M@KGepZ684Y)M>#={d7J1&ETgS8Ox$`{A3ZQa91ZK zr|cUqH;sh{&VO%9i2212FaU_A=+HKTd1^rmI-+<#hw!M!8Z9$SgT!xHd__P?zirRc z^xJqluR;&P<8e?4lig>!ZI_XYnfewlHQ;hYFUC?*Sx0-@X5|Voz(cL2YB()v4R9Cz zrRPC%s9MpQ_ssRR%C0?~lSDv3=PLWtS%(MxFTGh=+4ze+ z$}_h*-d(=^)#^hlVUHWO?Y=G=4saO1dX5H!<;~r^UBAw=PwV;HdB3%vetuPP*#7IA zyl3XG1?ixBzy8GT|6{k&*GFN0u0P1I_499TBOZW5Hueg0OgwV^>ADQHYHSS?wS96E zy#jSsM2($#G+)%wC^;HnV8~8S(3p70KO^;UOa>q+jv zxQ+hp`eS@nO+IF*LgjzC{t#xA-qud1A`R9}79=1uOK@tiIk}VQ6;S4_$erVHEb#?jNb%Xct0AQen}cUc zjL)Ar&t75VV#nGZ!}b{1{i@EgIfY2xT3G9q*ksh2W$$}XvA3tXsGNE(bBvFNz!#!> z0pp0XZ!p#j+0B!0)`WK4cbf0~7q`*D?QN6tbSd$%v#ZT(9fosJ^)kkG2Jr%?Za=mU z^=sLtNC7^?hpi?J0Xj>3tbWP}^*E%Zcu-N&ak5ewVnR^A!WNAxF&6U$>UQy)@}9E$ zcE2cCXc?nD0Cb;KsmB^Ob&1$hxa1{D&B_RnkknF^l2Pem)Wm|*gR2V5D20kvT_VA< z=j8O=+(xvZrd&$ zYYYk4@_14>xzMT<%%z#|*FCdl9>Gt22wlTvRkJD~8IEIQb`clrz-brj=VN1j>~5T) zVWQUbb$Br@fz=0?xh6f(t+oAYTP}{0 zJKs^;AQ~o*=F~tQ!qPQ3EwY^q%zX7-o!w+o*|<}dM?fL7GhQ&B z|MyE9Uk`=^c_#7N_8^18g+u(og4&xD$QdSU3vOMCu-2eU?Pmp+Q}WxaHB!WU4T#nh zyYn{Lu@&*R;Vz0e%%n*Vvj8bHngTHMKn6?H1K8oM$-!0+DJZ(rgjZ7E7+I-PSU#I5 zR22aew}AnQ;(Z}BOMj=qdjk{6p#8tuZ)rHl2#9)@|3tbVL6gHvE7S8aovSKa7j<>N zlTSqn6ij&G>O3vm6Y#Qf0z30|Rw{D|v6M}JOJB-{HoZ<{||^m9gAxZRxh!hmZ|OL(dK+F1bz$L5Qw ziwBv-Ta7Zl0b-`+8L=5ACK9}r*1hUEno1RzitG@O%k)OHq#d_}U-I{!vK8!JK-=+9!lo%HRPP~7a>A|~pN%r#7 zQ^n2Y;Zo@$j)oXYR0*y`VJR4VUkwgI!YrNRN<2_Wa6+mXw6xi+NCzdkOx-R}Es%}2XUlNp$FzJhE01=Fns#$yq6^ru5lZWF)3{RrK^;)0Z?6nhL{3VX*UnKQ! z{)1?;z$ZN)*&Cv*ws|2**&3Nrjv$_KfDWAWKNT5BJ>eD)g#SsGcR(Dt*?$krIqpG$ z8JttXw!^99WQH-OjFPO;4cN8D<&9I55T-Byl(Z$wokoRv#P#olfcr)%IYgKz0qWxh3P> z2zZf``LmXm%*Ee(l!=-@s;>!K@Sq88?sp>cBApC@=#5K)s{!E1mc=uN^83mrav9sg{uHkR^^d$J!Fv~j4=`$hgj12 zIKMZr(DQwU~;OkmYMF-HGbF-)W=`Ej$bI6wP#vqH*o%A?c z3gA_Z+E#CY@m`}Bw8kYGeiU=co}U9X`|I_`85vgEcEI=jAbv7QJrIPn89m7?fDh_v zQ+sm3XSa{{zuc`b=Z_aU?iTL?`_{spUv|kez?-jYemD^2!Xr9SoULkmbj)g^CuPdb z>*Ys_stfDuJL=C(*0-#n_9n(UYi9xiW@#b#P^T1U*bo^}cwU!;2P+RSm2~a>Jt1+>3+|*%T@?!j94=}2hL!=iHnoGn$(20*4N-Wj3 zs=1Lul%epT2sd%_l`oS6U=XE1$GBC(y9BmC_yx=e81?{N@K$QC7ItZY`0@LB1w%Zg zqZ%Ss%3I;whSRjl@PSM~Q8!89tyC1BB>t{Rz6?L3O#*{R?sG@oVzaCaL3@6gmf=Np zMWTYx9HU>9VpN0|=N^!cNRQ*=h}6q45v{KWulWuuiAt4f!!Asb1O_ITR;FZiY3(~$ z7xv$IIDKQxIt0rH(a>6+4U4ldnRhBoqg?!Re5(ggcLoMUAY&|~1Naq0KZJ;u+N)cormmcP2OlskmbW^k*>reg|8bmN9Y>@?mR0{->%eRfQG{cO#}}y& zUnQ4yG>8&Uyy}p1t{2UUxwV%0P>YysdaZN9cx>0n@!AG`tJ)87ozH$;dnL4K7raxl z;THLRwDlr3hgV{L3% zLNj(kD21qzof4AJhHRm-B+}xV&*%F+&f~a_<2?E$_G=6_{*PP!4i{{8W?k8rOGe{Vy%VbGHdPoHj+Hg~tP{$O<+&H$4 z&K?bjyTnR?Cqo8{jBxb^8b})HX;>nQ1B92wWg;|6R8kvGop3+s0bYoT(He>}ba>jQ zf;-I7F_ew}ZC1UX85!;Ze#L+;zwpgA;aMu3{6lBQb0Ci-!I+6Iowl4uK3zN@7~(~9 z_$4Stqkv)fi)!8cM(x*AyM=W5Qk%QJ=04#&fkW<4nEXrKcUFO3-6T;BWWFPFF8~}; zfC5?c6jxDR;wg*XAbi_Hq!B_=xiO_i4XMi z2*y?&vSlSfN1xwd!tLjZr6_dKTBM6(F7p}02PAuhR9*8Oh^=$g)PsCVuO7riJ^Tf+ z1i+5YzK?M)GC_m2?K2nD!QR09ednVl5(nd~qYiKZ<`)usA9ZuLWeX8Y`6Wc&a{$?l zOii)&91{KVCa(I&GwEdEQI{A5GgE1Y3G;vbe9tZs87|-~M=Bf9VM!ros*rB}%c#1h zYf9I8(-Pp+K4EK5b~(tuf~`7(iM!#hpl&ya4pNvm6l$;EY^vY|x+H2VIIJHWERDia z!m*$$!u8yj#0WSOFbTs)V1QfwEpcFVHV4X_MB}6~f)>uUE=B8@pQ(L&_Il}S$vPw) z^p1UtJ9kbn!TAyP6LO~knhJxgSdMTH1NBMF1yY;(Dj2~o?x5g;bflv6Lrab4)!V%= z28J8LP?DgNI+$qp%-qRgZYIVbii0r@M^Ii6ciMvPu_p*cV?vahg9b~ ziW=-G6ei zUiwox4{mp9`-cT#m)1pObAep&$NKl8jl*8g0>Mly<>7l#Dfby4QwoCF60r)JJOjJ_ zELF9=diG~|Q1bJz;pdT)pGS`=cU}EF@%Z!G_n+VY`8+B4W!mt|%*iiv;a?UCzAQfe zvi$zbmp@-tB)_g1e*JdxD{^}LyP>d9`d1qD>#sjw0jYnP-AAloZm(dUtZ;o;;n`V% zq*n0Sz12_xikl)^u;bnq*e3%PcO@D@0@(z+_3bz_Dp|))uRWW z-!xucdjI^=D$QJhl8S{heB_N1$x8fa-+pC2r;ynU>-d1Gnpp3jGY)<>IPC)@u^ zi}jDGEO;cBw$eM4yq?ljbiX}uDn=N!X~fQ|EKJ1_VzWoMWo~+(Hr@GUPvuwqhblyP zLP~Sg`{OCEx8)yG48AXXyzxJ+3i&kmFFp4E-eUd2!vA1a<-fx$BRig&iv5|ftZrGm z62%SNm!@+9BLr)#k_iUjVeu5Ju_2vjw4hm4rO91`2KT538XaWgdk}j=()jm=WOB3v zR%^J$uCZurLG8qK*x*wR#UxRY2m2d{)Alb0nvuZimBjQXD8(?5r&t{|k#-)lB;gMH z{sxmy4GnR16R|T~e0<9#*|#4cfBzh8-P6J#b?+Xh*BI@FLRAtayJw8h;yq9l*B;g4 zOIT$nK*f{-sOt6n&{r=j*TaL9;!-zl}Kh|K1q$y8HY4+iPF{-~acV_pQTg0TZMrCzefCNC~ zH5@aFspCS&DM^nyIlv9LOrliOXdoBsZp!bip)J?wexiqpYD^Z!ndy?Z1e8wGK=*u2ct>%Dae_vVgd8KasuGN$) z9YqrB<)&1+b<#d8g@`y}4)CwhV~@(o2vzi$YObZG{F7N~;_3QnkqR2U|5Sy%L`|~j zd!p;@Uoys(?O!F>H?L*ZCY7jp{ncZ)Axk#OmsTEz+&hnErEQn6<2*n*_-}gb_d+%J zO1A~S9X-NbmpfKwl@7Su4*S!N*o7eMKlFAI`kGu$( zSTEROXH|68cRh#PNC7h6$7ogIwa zNn(e`djO;ZoMWy22Ne%d2~D0o$lWY3T{vCEfc;4K$elsy zr6Qys;4z655a1(VP=c47<04A|j5Yh|Uo&!8i-AX2o0uf{xW3Q@03!kod8|42oq`qF?O83oV^!@gSBb8yA9-GsS|nD@M8uJL;re3H+0fk#I};xJ-03&Pc=L=-bJ+ zv>*bEXEhORd^&%Oh1fS(*)KCwpD{j(bXZdJ0-?Pr_!;E>??f&On>3zi2+$x_4?8T4 z77C=_zxA0$N6Q>dco3wacGlu#A_&yw6VLDQruI2eqJ)9E9fBM!7mFHxrIfBj^^s68 za@U~CUhz5UmPzHcAjBL`0??|2YNC@bE-2W&=F~Y}^r??a(NnT0G*r&6mzNSA5Ve@-EiX5f^|01VO<1Q7*xS zuy%{1J_UxSv%~IP#EiNnq0a=_%citv3dWx=oGE|fqhx+ZZ`vnL{SfCfh_)MW=ZxI) z5Q9;Xgo0&1)VL90_Wk5hM5=F;>j}coJ35)i=wI=Tulixf8{s~02lNmLQ=fe!I~0$t zCY<>77qjfhA?Yg`xlUnI$r*+`Yr9fgW}J5>l>43(uVs40KLWg)`s+r(lD@DxN0-Ik zfIr1NaQArw|6vjm_Kk6{V!_lOKb-!!xMc5vBgb}bxASRkMA`lRWGW*sUc(bt^Fo@( z<#_uj(%7Pk_Xs~g>y+<=(g588ivoja=P1DL|%vPT`+}fBJOjQVx|%?!)c={(Ey*5EnJtP-W6_vv=Lf>pxMjTo6yg)NMze}ym!2|SpocPB=&9p-&*9t{DA}_?qM)t9B)I+xI;H^X^5GC?rFm%KM2xV#I&_7oZZs5RUXD9B zhC5UXo~n&K(rE+A_gZ<4#=nf+Cjd2v3#;Ooa5pOJNN~2}d5*leq zV>I@CCXFr}f7=))LXJ%fiqFoD_pnBa12MTu((hd>zWV~;T9DVbNb+^t8}K1GBF2_r58{J` z-`GQfX|XfZ6w^8UdgQs~GoWsXodlVNZZnWv0Y#KW_B2VB-Najvj2_XA^>(hF`TR0% zTNtKsUi47628KoHUf~=YbTXPhW`LO6X6lZCddFO z6vjNc7y}tiVl9kdVv*NT)a!gbH!En+g(DFp;Viy#yMTD=u1~3Jn>Q88qxR6Uf@b62 zq#8F*`o6S9SY1+ z-2l~RDHY>c6?yfQ$-Alc+^Z{q+FmTUA#Ei%A-=8m*5^k=kU`nd$pc_1xt|EW!G&$ z(MtRW+Noqg1USOcq-3L~3V5xH4edc` z(j7r-7?6GaCmzPLh%5BE0jxNouHt1y%k6M^7d;R$So}+i>cP4ksk-XR&49O2vaL1n zn*+#TCllH-C$P6iwo%I#(4|VTZ4O|*5K)Wz1gnGqOvW=^6flj-~x23Ig2ThXWYqdMSyG@ z#cp{!vHcgg9~p4fCCl&J!Tp#hHJ~tbtRuu9TvwonCCuItZ-gxOMHFmDS}cVyMJpd) zfUMr!H&o3n?yC@kGK@sB-#XrZn=44zXb^nUumnDERei8x^uWXC!Gh6);qy24_TzVr z)t$Zbpc<@KKMUej`K&D;o^Q)A2-qt~hZ{V?YwxQk^jB(YM1_gr+(|=0;2%kf9Df&PKJDV3F*U6a#&N z7DC_oya{mCJN)>=yHUI&TrV@*Mvq=N7}9N(0oaQ1t^{f>FC~VsuTgXe$xW=1)vz_re2`(?UX~3K0hG;-da>Lx zN@L@e9T(0Vx}(f=N=*{Blm{iulHSfH+mnQI+)F!e?$zDqkM`{j#u*O@VG;;#W#mWf zZJ!kN(Wk_|MrsTacQXFTKPuMRg ztPXD5ch_RTaWqI2J%bO!HJR))lm`_BIveXDp_P0oQX>bLtY97ylMOmHZJB)Cuc3hJ5L>Kzz4Q;% zemlDN*QmA=qZqS8P{xLaF7DqLBwc1`5j_Nol-d;6gOa%1*FK zrH!muTjCzHXU{O8C=rOS1!5;(DtSDDX&~!_P!b-m3OvTo{7U#E*P^BY+(Bn@KtjNb|OEuiT;_`ns^hVv6CYglXGU8ctyzuX&6N4uMahlMGKmsPkVhpm;?K-p^T$Y*A$LAKtJik%IIn!y7N;O~bc!b-y! z@U)~Azve?b8Plf+T)?D|QGPH6NAB1@AR(ZR5a0fQI5~+5pUj+ki}@lhCQ_o3>A30# zsdTzwxra1<3dWW>9m;$lfwDe~1gHGEn>qjt@k&YiUtF_B$XMt(^jIXfsSwm7!gj}? zgtT!w&x&ByFkAtj9LWx9ECxt#B~jM0B{qmxRZ6XsQaHL4fI0|G^DyIFSCIxlE%MN@ zqXXh^enI`ZcM++joHZP71gMCB{(S4*i7#SP3)K=+ulCf(@y_5kH%BO?C=AR1Po?y`h7 z<-5)h+4SC7&@MCPwL%?e#JSL4wBRL?LHRBAjreAMT!EJ`d*mzs(GTB_u6`r&{=4zxU+Rl*{|Bir zfJ+2<-hmF8Vt{8Yw>Raq=&_nH44NUT&r6OotW zsv2uN|C4U9wSEyb2gi)w9=*ewdLEW&)3%d8q~X_i7$7C@$(y(KX7X6-tl|FWB&%$Ow>pk ze46)o>FW`}APm60$DjiSC}dOYx?sJ8_71r-(d~DMR(O~ZPu8-gDWgU0p3PIJm}}QF z+TQg62WxAbmf;j@eURVp(6=EIi2#I=l9(r2KvH&B1L<9)>tK!Y(f_Ev@Gh%nt1tGB zn!F+3(CUD;yZo-1`hWN*NPK8*2q$fRh*s1xnWCv)37Td#h!mxWY@GI@`1mH+Rwn7*AXyV^on*F7|Fzv!5`e@g-aYL~! zm&&NA{UXFTiD%IlRJ9+^+plOfqZnK|~6maBr=Ji41xoh3lzYK@7M=qa{+) zoqE>T-5Ka1qO>`zqVsqGfu2(IgW$)$Yz?j;p+_6NW>I*bfYKnhapyjum&e~hus zv=w%XG8nD{2}Uqv{Z6g!C0e~XZfxziLCt#SbUYZ2% z^^`D|7p)(q4OUhq^-dV^GvHk#0)UAUjYpIKP?dljkziF<*?aYw_Nlxv zw~C{JjV;Me<+>M@vLt+cBF*U+nls>{x_z9QrN`o)uimeQQ$7l6+fmEcQT+IKeW%@{ z_;z}T9;2ssHE-*6r2ty? z1_fkDbLBg?KgGEq0mI2CMbDXs=n8cpiG5ze%04vb)NZIT>=LtJOd$STjS2e>YbrF! zvUp4q1IRFmtmp>ozttDByF-8UyYt-3?mjxF>F;-ow(oMX3d?HWruRytO#+M&w2K1Ke#rbHzyhX2NBRR)Ruc?4jGz-1KAZA^_o&mblB1bTb05 znZo#I7!&FiI<#`z63+t+vFuoDJ%F5I_h|c7ZAwFxmzB?v#}7wU*VKUBWYG2J_G^~H zvAYu19L9{@V=}ocXa7h_Lb1R&CG`serTLk|9ROZ-(Ew4hBfw82m^VH+L{|sTToUAv zrz>6c_oHRlO~QQ7u~&8!5E^NC18Z7BZgcsy_!8k$(dX3TdY61HwDQI>delEi9OYF@ z9N-wDpyc*LE>s8jBm(Hzdj*Chv`M$#Q~(N;t>QL^r=XpKJ=(kIbKZa6+=Ax>v3};~ z_2RSU&QGs10tVI#e*T*OIlOOh_33l+caZ@YhvINuBHh4jJvTkSXJ4}Nx1=P#k5`Tb z8-;Nk^OSj+JsREYE-~qrF;w+(amhCCo;ijw`-=EO5n4UYCJ9OG3%d9o|nuxu#!7w>hh;`wP-Q z{gr??5GLpppmsRIb{M9>f+-S@ZzBNRt6E8C!7?wXd&Z{K)8?~|Fy%1RD;H&tcfAVV z&)#rZc89}gQpbd1Jo$}d_5WuXTk%$@mP1bviea*_7&pTmFynq&6R87dt=>{j;T?u z-LJP1Z1W1qI?}3?1P}sLhA#C8nuy7Q2Wr(6gFvPd)T#}Zm4!`tUIzw|`jbwLso_JI zD{4Brt^9bd!H`AiIFWeL0Nirfq0{ zBKismpsr9g+U#AV>9yYhNyrAPgkMLomx6FH5q_U?0DBl1i*;O&h53x7Djvc2cO|R0 zr73!(-gN+j6`Wt}+y^gW@S+4TWuM=u*R}hX!sal1B4p6$3Mk0}_M*Uvt)wGDDF7?F z+Y9{J6@5PL>Z5W<>D48sJ?Ovz3f#*S_5cT?uih`r7>-GqP(++2@y(h+9*1v!9}}^4 z$_lD5h@xjLdeFn-CF!>Q5l18ifCQn*40xLl=31l!Ic6kCP7q)mhnuA#1h|mS5nQmNV{E#dY%)KdE^Xz(5@h$nsuI zgYC4zx3_SwIl>bdXn+{nvWmJ?3;fi@&;JMu7(>DdsUB3i1C@%T-X>_=etr#^iUy+9 zkw^_j^D4>*1NhT1>=I%W6ghV!mTx5$R_A-KSIj&fE@$6;Ew2Vxh*el}} zx0RuiA65#iYXQA%w|tmb27mB((0e|oORMmBv(Mmtt4aPqv__$90*>aCfLFW}XP#BA zQ;c5qCokr*FU_uolm+RFVTsnk+Y(|cKx-49Fa*N^(bHpP2{?-j?Egh~fUq<=Qynaf z1uJNk;og&QU?mQg>VVg0HyQnOs2t8nK=V@p!=)k;EI<%3OcJzxgby)T2@Fy%y#{J^ zG4%-2wRqQpPIQBm! zaBOZYcW<2&)E1pt2DAnV%9s_EFP54NX`HCM!|tPtGHSfN!L`L2a)AAJ3o(Rxr8JWR zpm0o|$8Y4`^_jXOi=!cail&L;qvy?fGq8rS-2+o zsk`9~c!Bn2-&AR90AQ<@_qs!w?rBb;I943nEuAJ?7yI(6ZvR@zeN{oV_+7x{Lt$2) z=xf~8oQ4V`UOd%LcCV&N2xR!E#bpP)QPx3=E60_YSyes+@f#OKhHNNeqA_o-H#@`& zu3lriTT~Jc3tEFqHb+aW!R@qa&mg2QD9YZXxj|{Lwqwe`y*jY@`MW@C1`2)vhWk8ivx7#l7tP6?Qp`?^srw^y zsXw&OyjaTZ961W3K1CZjf8q4DJ(BBknj^L98MC%x@S`PD;D56<53$+h;kh0dgt*!AJaM{R+9aejDgp1qD?>m**_=d_>L1y-s3Yd{+tRaK7YM8u0dhpLQJ0(y=em zs8scAB#+e#ezzgP>qEl%L!#FeFoQ#qzlR7C!!iek<=lp!UxgI%hvjzh%eD@2v+unn zUTPkAsrAh5rS`6u$bgsX$&miLmj`z7@B2Kg(*~GWjf4dZ8|RN$w2mBoH*!ouM2s+a z{J<+aw^t6=UpeK!a%p|lzyG=B)GJqs(bES;J>5pnT_0U-CwfbWzHS*!V#ZvQczx-> z>nm=ruU>y0l>a)U^>x_0*WtfkQzXVB4~#{-jm2Icqvek!w2mdc8%y~;Mwb{*J20N% zHh%N^cy|7HZtHm7yYYhG;|z(3!UGe#= z0>12}Sk`r5nkJeiP3J#FXRCxLC7_w8T9;ChTfj5#kI6yLacEJ1)%H@six)o;!?ECpP59dCxVZLxkXDTuvplX`=MiIRU|sjMLhLFT-To~FkqMZ z62zeto%mM{YGv6k|O2w!%UP`Klkc z6j#f5h%M?cX;)|K zu^+X;USW9r4R{`Y{{Dvi54Y*REX5L!{N*;4)o3$$N)aj;5{&)Fb!+$t`_F(cTQeNi zMn7h;ZIs}Ep55a%UT2Yyg3DC4P6%=oMO@H#E-xzxS*r2p30=;Lyg0gi|9DF1m*m8O z(2r?5yZ;ln>AwP=|F9H$d__T6nl7PM^`Vwqn!OAAg}uhfQhYvrxAy+v3R0kc@=0tm z1BLW;;uXI6x7+lLChLhWaSsOO9tglqeo4}dIRDjc`gFYJuc*}bZRS(K=9L)rBqo=a zdAsPuO04cPCeO8hx=pzXp`AE$6IEpo*)~;~eErvunHD^tf=Cn2@Gf_W4b_iEb zpT3Zv&tr>ZsfoDLeJT8AhC9 z2!PjE0nWd?EL;AwL{l|#;GQ=Rpx($r>N2Re~groMcYOf-ZJR&lKM1nXl0@0>{f1Wb1Pf3ADu+%Gkk<@^bzP2%@fnI}MKV2S4M6x(sAo$Iv%c$*Q@BkP; zE}CQ~_iRo0B&Vz+wW=Xw+~h3D0IE8InL((B8gXiM!Nhm&^U17Lsqr}z_Uy~GC)`v; z0jG(sK#wiTP>ITKr~wnNA{4-yR86nyxU7wVg6xmW2~jZ79sqbDy+}m`YLxh2-dD@$UWykGpB5f5zw5KQ5`P3!-;5HSFa`CXQ|28afD;0EcI#xM`g0_> zt4IHfV$vxxoc;5yjShE!i7XRjPb@hZl`B9--a&^xsz;4$8@tDi853ZJ0Wlb-sLq=+ z?V6)>34jIrls1FVbSJ08{W?&G&#^Eytj|cRnvtvCcgNdLGhN%A%J^g7XS3~nzAnjg zw`~O{K)#bzQH;@tOzxZsALgQC0slh1o#)3VT=st8@{)IB-SSGgl%Lfxb3mx#MYtrM zO%aQYKJuC)jqV$n&QnrqLOPOh=3(wS#TllQ_Tc4h#Dtb*$ zb02xwZ1#ojoBMX=_)fvr$z^VUdgqtXx!9S0FCOE?;a_uW`*jCI_(!%s|C%TAHV?)f z`}S|HTeyFpd)fPVs1rN>r1}0i zT;lNel@ua!e|DP-TT+L)+M)w_^VAf0Z030rBYQ9Uy$u_r>WFGVMXf18&3jk4s zy4tD0Z|;uMXTUEG`oW}u1Z&FahyKX2%j_w}^r(ZD2NmmKabwOwgk&Y;e%3Y>{OJHn zIr>lDk5Kfuh{nMrCL`5!qqG*zG99C4aACUUl8?~b(qu~@ZaBPLN+!o`R#c^&_(sL}3lK`2J*v@Bm z!HIf?oq+-zjszlMMi~9J#?Bw3F;|@Z9I%QXBG{Rzzq~|sE0bUlNx*SVc=!& zt2<|7ZvMR#%N14-A{*Zdk`M*J_09O#*0kbA@f9=3DwD%$CAO?wT&kNEt_yLKqu>EZ zrw!Y?TjFpGVAYV=MGZd?1eue3+c8N4Lm-|I)gvt7GL|%0uJS-QxroZ4io+h6jUSnOEF&6SwPwW|8_?kx@ZqO<&@q~XR+JdN{|6= zmI1P#(krCFm8$?f9g?GET*qn3OPiZh*jGjXhsJ(IVlatA$fy=?3jmpenUAP(r#JwP zNt)-lP=Y#!n~3*ciH#y+bee8n4@iR5?NbNB#i?0lKk)kMhy&-d%I z0*o{jNQ$=vr$U6|tes6F${5zoZ}nx?$_ zx2WrinGNxxrztRdI{a5qJ_C32J=<-%!*-kYUbx^~a8vryU9(HV-379aX}vnoN<8_F zj+ZqJ`ushlG7#!kjQ^>8TSVvfQgB%AdCiSa7kAAT^gl%xa;gN|7T4cm5()kya z(3>rgZuWmy2{jv-sqoo~{u`ChqWqDOl5l2_yQq+>-hWUDiI!c`|4SwG7vRY)3u!J3 zn0hv87>t!Ln^X!D{`AF@+K+@ zwksH-m4*71#V(blA(d>2kl|2Xr9SlkYl8kOCpXc*zASyX+j^TFiP#px9sD~I@k_qk z{WPe(;C>Lvp$k!dE#JFgC_MdgKyQ8F9`8ZkSd26kCgJ4nDm7C(nV`0N=2XmjUeSP_ z<}my4UecwJmjbvpo;mnyA?monqFlSBO3HFwoahO2=`N`XxuOAst&Z}6%zXp8vIit1 zG17oS+Li-K@xJ$54$xwLT$4ttGvOmY?Tr?`Jkk^=TeuR*rE52k{#^2WvF4e*wBpn* z!P9xE-lAj%7{~Oa4b6z0rw<|cvd<-af-DV`E%vSkDM?2L7*XabezkfZ-$SMunTlpS z-I2ai_|>-dzf^#8RJZmlhq-#=}a znq+wDG17=n`*wR6O!OWD3!=h3~xW!!PZ zgV&MsL3q)Rqa|mZaaS zHec=&w>Mwx=}Nym@tqWlI?QqBg4e>~rvu$YRLxf^WMF=9+C$$|Vz(R1#rXx-W?jAY z*Qo6`?t^poW%w?SP*&xHP;^7gt~{y`bK4E>CEO-jb3>|iE0WdopkDIN4KK+PqL`gH zCq15&XW?diG%-?KtX|MvtPOFb78s1)r8_OovHs#9M(fb}_)6k!pHrW%(lmdRT#Pd| zIQ@r)F>XNCMa#Ej&3xZ5Q8s5{+imQs*}Vbb(^iRY-(-Z*&U+*7M>%br$)9yF)A~7N zdH#5mtayC(-7O=lv@`?@|4AUOf(km?5T6RJU}C*Mg43zS(}F*7J!`nN%&7@8HFi~z zz>|D-IHW*aI{3)Z?XOvn@4poPPB@~|QxlpQS;!v?9kwyPrnGc$%CsT0_SLe6P=&SM!jJ)jJwk$(Me_$7OQ>h;`-mD6kI`nONK~ zaKc$qcZ!)rM^UNRh8H-2pB_f*;~MuWG~y4XOJbt*;tXcm3YX+c#b>>bhA^ix-05~o z2lZcA8*`pCf0@NpinSqP(@LEDc;mNI??v+La*i!>{X73Rt)otjQk5?A%HE;u(@p10vEko(R0k!f9qpaJu@r~ukYgv`0Pg{IeF-+YNQlQ`W- z5V6FJ+_t#ncjJ1#KXcTA@J>!#hx5+y=?k3X$|Y!J%T9M$;Bvt4Nd6!aPq=SD z?R%@0tEP^$?7sVHf%R%6#R{!A&Q*R(fp0yh?u_I6bW&_>GqAU!qZP&ktOq}5b<&+b zeD$LieEe7w>2*|sz#VnWP}buj)#Yth=@411$S&e%_mtc4QhP3UfQ^}N_YLi-g1V<- zl#k7>zhF~b-`!^qdOw>LebXK zjsti%?A+U4zo#H>FnSNs(Jf9glbIs2&^QSETE%O`8+C4fhM|EnYlW={yRs z*r!`uP^-%uXvgX&w(}51k+E6JH>ATOITiImz>VB-#s+ z)3bc;gq}sv#S2Ok)*IM|Zo@xkXyoW=36H?)yRL+u8Smms?de^Fsiv&C@|jM6QhTbB z!;;u0`F)D_cK7dZwK-d#hLcXTh^=}zj07FGEC|dzhzF=Ujkf|KLMKkV!)0Oq$n)RW zsGbk?Ohq3mPD|(xPuEQ#J=iM@kQ#1vU*^!E!$yzZ*#2@y;oxd5V`phT(0Nqs;@6CU z+vjHU1E=4d4E@pmyLz6u(Sd%#x7EGFzIBY#M@l-ET)En=dAje4*(uWHenlwL%gl;^ z&>KW-PhQ6_h^_-li;lME_gT;B7{3&7IEVyj=&-Coj`p}q(I4L&Sp6b`3a0UgVwIHU$^{WW)Lz6H|3NK%Fbh$>r!le_!y4IpS0kvKS z;Y^1J0C4t-$X|&pC1LYfK@Z|0f0Q1xM~Cgn##Yl~>mbf*LX@0$;6`jz@587~EsDqM zqo;`1pX*R|bx;n`;RoqwEp%x`ZM?5Z*J5mK=Q{&rbRhX1v%s@Tktb-e=NDqNy+hY# zQOjj9>W#525N8XN;FFEj(hWOtZBMFVa9>$ipi}Uk*TETaW(7!#3!897fHyij@wT+- znKLHY{0?N#liwX;WrJchXt4!7vBg_4zjXXBYafka1ZAy6Rs#vGgPiU3z&h8rVU))0e)=u1fMG+wJu!<7DIf?uk;yD4i-SxV5MmunM9+OYU z76>OGoasdi$yt;@=W9`CoC4!tbCkFzk7slB(7D=clYJLrIL?PXxp`rRMycuv(|MTk zNl9&ycIpt@Rm)P}7)wh7BG^y)^OPSViM7)LdWb1a+7P>-vJkt{rpJ!u}s z86UW$wMWr05aLMS`;;!I$Mv>6m5lMlMD7 zwfF6e>A~;OHySg{&PNnNoUL@O=j5#C?pcO<8HdM%Hm*gj6w2A_Br`CXvB9Y=gULVV zlM)m>ONxWj94`Z`6dlK$rG+pn7W^{lrq_5*Z0gPDA5HJ-gvMpXIFP#kqbG4 zdcwp@+@)tMQM1&?o1sr%M^-v#k#e$X$Fc8s7P92K!*#ON27@@>Ij6S7XN&YE#gLr$ zztp@@5jK}?moYAPH6sQ6&^2Qmp#yOuG;a(!GeR_YlOp$wD(8;dTCbJnpTI51OCxlX777)fS4R)& zW+@~T+BC&hyJNL5c^w(M_f#gN1*d4~M<3d{RP-$cR8cV0FS|TsIAFW~^*H03V6v52ANusuS zv*yGj-Buct`YMQNDpRnv8Oi8LSDuK? zr(g&cCET+N6&-5}4!U4p!NH2;!m-#qY@TuZ?os$q6nt0((R0je!=L6}a(| zgCZG&+wtd>O8tdz2M=a{Ny{vp2-CtUmMm8HDkJq6JTn(+2ulKldfqG|>c*`0vyZyX zGt4lHz_>A)n1?j%5-1zj8nq5 z6VB~f(a&yej&LxmC|D@YR!PVWq02Q!#E`0Yow?dqT7AvwwD5_;el9uI8F22bh7)2< zBo9Nr5w(OX)nD+w#_+pm6O$NQ1u5$O8#)yyysN4*F1dejsG81gYccYq{LG;>b!K-roKD;^DlYli5ez*FaDX{{n{fhms&H?t---CG3sC^${_DQr z4OT~tfgIs9`e6aD%LAbuEpTY8X$b>b6{ zsKto`{2gSL+shW>qVXS@R?DBPuduu4l$ammFTD~)KX3`;2@X_i@mawFd&N@w%%jrF zV-MfLx|uU~XGgSMi(k>!tew7}hi*}wDb<>Y^ATlT*Nr|p*%X^TD{>8oKy(bbn%^r)d zx0a3vHJBZ3?2J6&l|eexCBk!U99#F;M||F&*Y$injtn`p8&Inz2PYkm6*C$uEPYRO@Yxqq+zbtS zld~fYYYjeg8WRdf4!0{kPMh80)1QO}2>S5i+zce}!1nr>Rew*&V+S6R4hlVeo&?oC z`DjZ_ugrZn49X;Ls!ccfJ~^m)z064EO4Ry?LACu!MK611bmN0tQ1N&K48OR@c%rCXu9wgf+k z7e1aZe5#{8Xd8!#760dO zyQ@8~sx!wFbtj@cCt`2i9=$LD&wQ31n&rIy@!8hE*PdBM=OeCG9ol_2Kk4&D=9N?=d1hJ@em` zth?~--%K~)-KG-_kI-HsTeT^~r9Q%>Xsv4qU;R+-UjeYo@WT`xP0`g>dwl=TbgJWa zx+tRe$c*|A*mGft3;QhqzLNBLGPc3>@sQbbmatdtom98Q^sv*HQq1QcLImxOTdbk& zyg{lxgn9bztFOrBKztA{+w?g0(D8>)t&_g3?`e#3$@~>Cyb*#uef5o%?OU~{NOv-_ zQqp(v`0nKUum-^kmu|Q;6J`#=&B+6j-Ee>f*8xbcVxDXg!Qt!$fQ&E|yqBU4njd}j z-C@jHa#(ow!y)_6eQ(}9DB2+XPrz$GC+s*`%CgbR#1{(U;R+z01iP)x=~NOzi8~ zSa!tuNv$uaU2isD9JS>w?tV3oIlpMSzU@0^W${DZwS`$fQe5dwtVzlO>iEmc==m=UB{}nw{07WylpvfU0VB@R2>-&yxH{AzQDuID1NPcvv+@# z`ghy3@3LOgF1d$+ZrB;rZ_#hPt zldxwawqGW*SGImguze=6;wJh1zoS1Zz56kvV~FpbmF~t5&VDF$?N2RBy`A~<8&^Lw z{#)gn74~Li)^6|LgGi8%(1p5KS0s*09cZl&{jgDzn=eLLrJvfpb}!?%v6j&}iP^Gk zYvStq$fu*pyH9z>u4Sg_XI@6S34d=agpilj|NJ%d-o{5@_!1~1*;EkKdiPK0*q^83 zYrwU3aqof$_g=>Ye{?=}&{F;P@Rvn^^8S&Ky%VqIm_`8UIT8)#`+6esi20;!pnEk7 zL!h{k-C%=`IKHy%=nn+nch0TCIP@-8(eJ&-X&?q*`1pPBI%}8t52@ro&#ZGguI6;w z|D$iCXSIE{Qo#O4#{yb+{e9^@RbdW@>e(`uPZY044Dh5oQ1xXw_?LGxvBiUv+V1a7 z_raG%^6i;_|DlZdterhLdAU^aE3Q-dbd^2GWyDot*8zD%;uWO&!{%zcV`$ajmFSTM z&l>0I;2-9C@yDht>Q|H_3G!}Jq}(=Tb_GT<5IKh@8O>fq4&l z>sQ-C?%69Mf#*f@2R)muK59I4zjT{GO1SdC#^7rQa7@#ecC#>o>WbC8%Io>0WyrkE zs~~@52d+-*IvL-bz3RUC9@6ab^T4ha^&_kmw}#7cTYHV#lS?mc>nuE1`V?y@Mx;H0 zK1tuwDDW?!&7UrC?!Niks($(d${U0wEMbmzF%f%+PdIUW8K$w!cyt` z!S7G3KdM}^u{CUYZmssiZT_Cxx|XSH7TWmYP#zaD9dEWzf2Una4WL>jPZX*3&yU;+_!l7QOl7u zzI%&Ul9rm6wWuWXEXtb2#^`jg#_Im|tDAiQEVL(=zaMCu(weXcLHxP!f_%4+eEo7V z4z)6AY=7g&*kAPQ^<70RS@?nJw1HZ<{%6`4>rDKEEqkjE1>&ZU{)V}T#cq`=yj7a* ze%*#*rk1|v+WtvPYMg7}ul1=r$qpxL(=y*ZvmQ7c`=3ie_CRg6geC8M)Y+F&w_|U< zwU?g0_<747@gmAk>+M+mREzE$%lE5=ikRHP^Y^r(c!K8RaRvLiWG(8sPa$5Na|Lna zZeZ7{k8<3zZ5X>19r{VPuSb90;^Ks2@bpmF`qxkUtltZ&e_BU$9bdA%{zGAkUGFRo z^q)zc_g|2_!w9h5Ji^P}70+TxW?t30bNJKce)~Vw9*gHy)Bx{CtvSSYn{VSaUYbRA zKUcH<{`lT>r@=a!)OFE{eNqW(Pl)`R_=tbWYZ=*L@V+}nQ)vtPiuHLrwB-=HOsQvH zEr@h05~ZG^e2NwRqav&0(t5^+->SjOn%35{(^ALu94THMJwL7|WC9(kK~Y@gdmBAm zxA<=Q@0Ze!k$e#`RqmJ<>GtDC~C23r|zbL;`wILw$zE(O~$e0Y`(M z3dd)KXEPpmi#}2KMmyGNJwy^ z(7`N^RFyP$pL|6o%n@bf6QdD+=46_Ize{sZ(nS9`a%hc$cbb=VM^g3HNs*bfmNam+ zJ?Y2eZi(Q8tgEpCocZ&8A#=YU6<8lYEELxTdJQRSeu-tc$cFjG>iOgcj!FX^j^VO~ z0ls(n6>t6FK>PSi=oiiy)zxXK2 zQ#-JCGSB3MVuw;_Ed%rT{jXcEj1p4$oxF!uT^+xy7FCvO+r<3>%|vclq~wc{b_dD{ zN~ZuuRN%@qPx=tQ&&%+|)GVWg@$zN!UE^$hH(FHl!&NC@AXzE#alrQFH1XV5k`7W4 z`$bDnu08(4b{_o=Pr4^;J=&Pk`Qpx3DR*i0g9EfA7V5L_;IDo6CEs1y>XYwZAO1=h zn@SNpiCTv*PFJ0q2&}r&s_?PX&09UJzm~R`qRCszy9g{w=wRA(M z5iRaM{;Z-@?7A82!tr1Kk_rard0v%uvaL&2!ZVo6mF_>KyjuTzvNKF9%0afw zw*N}^`s;wMFPrBWn}6I$pJi<|R>j(m$6eXQLdc8*Q`=oKW@Oh(FRu3kh$$|IYjOpL*n77ry^e8`mx^t*cx zwiM1ZlHBrs4qo|Ka5{MhPDL7btw-k05!y>-oMs!Fv|$0*vcW35r$XvAL2h38l$$yZ zSL4G6W$5dVzBgSkrSu-Q-+ROofYfyz#d{ffu3|zt+akk=rs*NNavJQ_Ye;EL(bT`s zX_UJ12XiEWt1=D`KhQgw?qIzlY_>70dA{v+TX7izC#%(Bzv7_wv2<@;5v?7j%n)EY zavUT2g36pm>Dw}y7?aAr%Q8KWjyOoHHT8s>>9ki{yt+If9@xbHHKOsA_k!M3U+GiP{r^2F|+?SJCG#m75a27!qNp ztkv4s>$FLEY|vHeXn)ZPW8|aV+XHa%i+u?;4U@NQEpXx!44f5P27gM%SwonfKX7|M zqy9{hwso0GkdrZzBQp-AiUv+-J*kQJ$ zU8x1~8QZ3fRBL&54`G@Lk5mB8CR^Kc{*SJ&R9$?H@fmPx90jjJZcT-58v(?+^g*AH zjZM`>-%>2ul<%k2a!5&1b zYJ~)~?3pt>kEdI&6eVPpr0p-KJU^G<_c+AYP<&ivy#49gsJF~1k0Wg!Wf7WBNVmUz zuKve%^;dlQ%iks6jBHaUCcP6?oJ4tBe$A$Wb&EB+|Xv)w$WRb?-0+HxOsOO zxVBE|`j75Ff;XkpY}n@N@gPNm_M*$_&B`4EDzY5XI6~sfkUDClW3cm}=;`1EbxMru z8+|1|AKsnrhw9DR%CTO71OsUg<@?1{AQF95xr##-fgRRNPvut9U zrTD9Gg+Y40md1Czcj8DHlK;{MY<~Da+x2$2(hKih}fA6`P(!br>jc|B!i9?Ya# z&f^yQ+@q4`NQL-bC8B#wm%zM92%@6g0S$@ahiFPG!^!h^> zNl%W%2)MByhMV^}CK_{SE!z=^ldpW?8iWCYV4+SgmmMA!lkQF{pLTyi&Ia$KE7nEW znfm>;fAyV?Y`4BqHY`G=~|0Or>2`M2Z&zqIQ8h{%xUasedb`6f^ zZVQ6n6*&GEe15s?W%j_0yxwcx68^}~JyOh9nbme9Hanv1VC=sDkt`?2V{@y|#{C$J zkHr-n7%gML3S=kxdcBVEPFTd45B3^cZ?!9DHs#izKe^wg@=Fgp;8l6#j>;F?Hz&hL z#5*s{7B36UQsC!Eyq2ZRG0~@xhDCT)8H&nIc=Ez+)cNarSwlTs_fxXF|&Q zjIjFE#TOGY^F7Fg31m21k_UxHKfXFwaxFAZ7U15v9&+>V(1H0!+V^Y9MYV@Ko|MFP zmi^sXE-@)F0O1Lfy~ZJBKj;TM1(Hk9zO<0N#UbTXwk0!9aAz{v4q8VDItOPl3C!MX zYoGh+GS6C1&)b}RKlqaE6#Bw$YTk27tO@w2Iyv^`b*na8j0Z~*1wyw%fuIXA^Ha65 zPet0dRt$3Q9c(%vb9Oa_zr*x#(-YkhyEFKvr^Hx+X)k;{M- z3o^5o8)zlTv+`_(?C+l2$sL_Ps_Rk-2v_sM{=5!s>q}*e5Mk@CPubA=)Z2e{%H^Jd zquQ-KQ@e0jn9q`r*o|pro&1~C8b=7(a!i_*;*OLmrq)&%@e+WAAdL0&C%dV8kvm3y zzqBlvw+F90SEy+CE7#f=gelweEzIT<~Tx)_25kX%XRo^-&bZcT1NrxsG07_ z(2XdI-mWp^Rkl)^jnP-YTZqYqy#wVUs)wf2qTv*(XZ_Z*1N`P;iy5)BcUJacFIt0p zB>WAIkA2aGQ6<=f1jtAfUadOoqZ4^DXm_L%n#d%@yIX`9C}*NVM(x720>iP)P|njED*~oG5M9 zi<{b%0U&s6dL{aZ2oq<#caQV?WVJbtZ{y0jlJtq4(J8Y+i?9Q7qVT~8yU6RiqQ;~K z0JJqEL)d#H+M`-xcZzeguci5q5^;p9ho6%$=;`itAazDAED(oLm@G}*?+$}Sb}n8yPVUgTr;0HuQ)5uKYZ#AFWT_Kf9b zGCyaEs%qHxJ90h`c;z)YBRP>zKC}kI$NUPtUP13s8PT6>^!N7b#FnQW7<7*9_)1C{ z&$<>i_V{a*uoXZkKvMI_q@$ll$G%J*#jTgM-4D{^8h2p1b`T7Nc1lhHM>p~oE*efQZEjK+HlhA>7Ar~F_4`#wZ$1^cKW0>-%v7e$Af5zdCvOcfo z#6L(~{4F^Wp^y^+qSxLpuKiqG+a>nz&ElFD8nDKsP!o{bmXO}KlxPgV#2`;3U|p8V znYjlUIr|3|VT+5B-Z@g3Zv^>o(z@S>R^Mb?zLB;k%6jLaZZ687e*gmj#q-}3Z+=ti z|EB!%o63i8s=vOeVV2e9m&unC6|9nO-nyY>wM%>Zasw;rUCOfd$z`3~w^7Z@n*Ga0 zFPDu!EN}Xi)D&I0S^oRLdswC3%z7D_UD>oOshqz@>AThWrz*^j%?eGw8F?ycxa^%c zGq=1z7S35VC9d9D4sshHdh+V$*aX z&hBlVS3;ie!xi5e&n?@AB`R}XttL0V_^u6d+x+s}?j_f)a)PaXgzR>-`_)|5l(QQH z?FS%=-gi(wIpi&e0>br~sZK4N@_`N1W~z7;PKWtZ2jpPs@N(gg%Cyu_%&+BZ71~_O zElnJ4rq=oFpWr&jAo`a9bm-7}YB?{pl7Gkq`jv|Lk?`S{${Jj!BV|K(r{4tE8s``Y z4;8uMZjEz>!wNVqY3o|6scH9;4;@PL@$X)hxUZA;Gfg)wVjET`IxQVYcfC{nae9@hr+XLSYr5rN`B&OlMAINs$mPZRr{y#T;VOu~{T~7BNUY@NbsR zY8G`B;R3=PnVfmNrVAs>Cn<}#nq|IY>fi_f1NIDt0U6kd>gVQVF9$2^=z{V=TaQqDn7H7R* zDq|Rv1#3cV*F(ZK!0=4~aUQ^t+2S3L`Aw*N2$0bG_p#>RwPwKN3iSEq#&7#!O+cPJ zdAIuAKesvoEDyfDk^@%49HIf&XuyVvbczNX2pq8v2ubCV^#D~W5(e;(2 zRz9nG`9#KWpM4!Drs>&YVtfT6)k(V6(BxByYyCMo z8lJ=Qm`8?l>ea<;2|t9>dbv`r+o(U5Ha>?s=6T=N{XY!GE(YIBYISQzjJL5GQjHJ% zG@5AN|MF_=r=PJeE$ z@fka6`?%sovMdl@2VhlY24WpW(+t7OeX zm{j&5*fRq+>f+EjPJTa?>RmHbtLH27u~YbZHvqA^B)U_&IsTvR@0Ep@*Wwrd*{!Wc zCkC?wAUhi?t43`jcXM#60F#aS&uIzVaK-AfF%(BpO_Y*9nSJzhD4&KAYZ^jfd()xm z6j{<74W-IWP|Z_}V8MbAEvq$=vI%@5#$cBKhEZx`jOM%S1K8X?n5$fXA{YSkR}}e| z=WD`QvjGIKxxUzd?i5&R>pM5=zr#M=AH6=Qjq8Rs0z137N?NyO3#DQ(D6W{9oDPMGw9Si7bA;BDERsl*hk$vd^jlikW;>BdI*GU zbYi!FsL-Hq>=c~@p#x6ui>p6eRQutLPysDp5U;stf)1(;NTf5m%5937fPb>>&rl?0S6L1j{F z{YWX@If5E;^01&=N-anvIwqgfF>?>NctPO&OnnsOn`au5y>1)_5?vj$YLON>J8iJh$qC+8*PPu*$Rr%Y#e_5 z?35H86KOO|TMUu!*t{fw?;K)NMgjQC|0L17qr2ten6Qpv+6GN9YYIQi70+vqR$C)u z9rSvnOP1{Pr9llP7SF?cmV`;?iG5E|^c-T!w231r=G}acd12y)*%BuvLQgTYq@BAs z8f`4B(+~|f+{S@-LhvWHkYwdRpEA4_L)V+h$*W`=tO#=bLfDe01{__yx=V2#?80OQ zQilov;v|8%0+~KG`Qemf%xt~{V<$|EoedufIO8PjaE3J+&WuAmYs+0f{B|k zkRGg&VkY^E1ef8c6UE2r>In!bO<9t&f;_k64g5ogmW-J+cioEBgA07zNAe0onFV*3 z2Pw?S1tex)OcBBr1V}Ae_Mi=cu8}XAUWopPraugW?Z^rx%7&rr61;%qHjZS-fRhv1 zC(nZfQR)N`br#Cf&d{}er~fQ{q?EfZE!2`Q$pVc)X$hv|HbuWvkMQAQSqUhZL2W)N zq+T*(o)SeD!lU#BVy6fIMTx*;62bt#glrWt0mgUXxV1d?zP`LD-*D->#(FzP0|`Qo zSWxEtsN=R{0@!yHXG8vpl&1Q_u_OR7@31#+HQMj!vIs6A>_bus{pX)1qq$g=L&^YV zd%by4d=o;eHQ$f!SWC31W+3K8$mXZ(WjTH#glg089FtwOlF8$HRbw9JX39ZW?ohAa zV#ff97!K3lkm_MfumJ?t74c{t^`ED)_|ImS$^=F_NGh*CCmfAR%QAceLXR{kjry}$ zI>9?I+etlnUJMA{lgv5a)qGa7tRN)j!t1H!8#kdrcEC>=)TLz#HYW(8fTBU#d<0fk zpXPm@nMX59BG};jNXhW)(yiRa_{vShdj_R?;Ii{e{in)c-J1YO4ayw!Kd1=1G{?(oihbMX$k4$4 zaDq(WMV&eU<|Nd2W_JQJ;RjRq(gUa17uF|tfX_&dfng@XtCtry+E>|mijr8>%0)|^v(G6 z^Na5-E_^`8$l(c`o$Mj%dy`?9cbtv@PGo*Gxk-Uzk%BCAvU99$7|q8tMJa|&j_~9? zjiw)j*(zou6o%N6EHXd}h9Tgh<7d^+oyM_#7m+(46uQ3B{TxeA^EVJBXLdK>6J#=+ zh(Ie`gj2#nm}!SZvoZ+1#&*I22iPXCDM(5n8ae;*M?>*YFIiA);dAGS9G09r7NUea z)U|$mAF|p?cEuB;z;`$o0L;gE17?=g9;u_A(FgCLk;tYLpW-%Ucu+UGC~OSFM_6q; z_XnT_`Q&uL8MF8O;Dt9v-}3yrX5>zuNcg#@4jUv%dth3T&+Tm`ko0Ji`nLwF z=U{TseYoe~^V@_{VvDHRkuJ$bKEPDSNN4Le{oIb>hLGzrCTWz85uSaSeq#pYC?)cD zl@Yd-I7f7Si0<5Ds&7Jb7!Z@m6u4s@bzx_=(3essXn!s z9`6Z1UjZjmAnpYs@NQh0wz7e3QEG&|@woarQmNk5j3g$`TunsIbKL#k!z=6U2X*Ur zcYQy*-W7k3D!Tz9!wVK49VK7S7Pmcwjjr5|7CO|G388A!5@sG_6gJ~849GYwz$Zs& zNvY=fNin67B!Ts=zlInsrr%`uwK_`B8H}Fjxzzo#Q%zvD{?z#|JR3pXw?}6k2U>pn zmMt$gM&Cim!+|vqeq(Vq%3FQlXqvffx!pdrm&yhSBpUkts>avx4N}hu?jhtw^gqhO z_>2ywf~?hA?1&x97c4-*-JhoneM}KxjpYfQZ12c&% zlumU(dzfNyc1=|+SyF={r$ISdLoS(COxlIBtkblgsWoSlcx0_kRD(zcX6q>aL{^6l zQLwZ{3P54V%Qf|ow0d-173Jo;%@X}cT{N90wj>wMzCtj|hTo)=>Lf^ih@g`QbnU)j zDNj(oqewrzgul{t%K#eUG z=eC^fmjZ-xG2L5Q?rS#^oR<8&J&986b>S^uxb}vRv#)F$Y!871c@8@k?+B22(G6!J z_urDj>w$>*ZWn^Qd-{mBG5GoKfZNhLT9QBPVnvSZ{lEXATRe)lrkt~`h_LoWSuST= z7G7(RG=ZhLh% z^uqc9(hI z2JP~Sqn&wy_{34wvu(m7SFu5Wc;*AhF9SIKFaOtH^g*E#&V1^SoJb@qlTQ+@JDn>v z&&x-ys~#$=iIRK%lmVK!0vc*4KfW**E8wpY)?%vssps24Crl+!HnO)oj$C(Tpp;s7 z^pgIW8~ZRLY6>xIxPKuW&sOpf_K@_v@U-d{plqhEm6?BoimFQoq-@oTW(N|e8+tc3 zvt!o*A(*mDmq_b0~yLqZO!T-Ux#D}l#f)^u&OSaKmful^>Q$p1`O)Lod{_6ah z_ZRMdH9Y+vX2iNjj05Ue!(qU)i%)rp*ym$0?3ezq@eH=uW8j}2SzPdh5DgJ|Y^fNw zw89W!h^{v4GKLX7V0th^q7=!j` zjV9aIvRJu8GKMBswSNMT+Fy7=j`&P`@)@yAD3|tdq{8`;Kif0mDGtI&nRgR2gmN7a z+FTOfe!Tae)`o)?q@6kWP5lVsUpNUDasOmEm7RQT9n`_s)*LZ2+ z(k3h$1#9;v`_mn;rE07aAKEm2A6%=uh=Sx8P#v}BL5(KRF9cNB=$3h<8hjZY7EP7v z1GAQx`dm=?hUhZH*6{Cghay(g~*mNww ziXDSc(Ui2>Y-m}$V$)6ff?c?}zKN)Ng{bVtemqL^iXe}VZ-bp~2O%-iD9vJw9_kpO zSW$UuI+M)aAwfp~d*t!L{b4YhC&ElDD-o$BrZIwVYdik81c)ZV=4HJCdgu#^>i?B` zR$Wf?07>$IPN9@~04HDpOol)eSJ_%0IE=vwFbT}HizvQBg=NS}?2rw#KzatyiyLGw z6~~zsQ$w~$z&v0rY54HS}QnhXzMQmZhLzO1Tw2(%nc8H*6({r-p&(=xWSGM|UieR#>M-9?|rKT_T{adC=&iFx^9yN1i~G zzLy!_V1_$i(vv`(7G2Re9x?mf$JRNC;^{4`Krg6R{2WBSrNG_dLts{hI|art+Dl~t zil8FbXFMRU(w$V9XHjVt@ZF)k5?+Wjcoby!9mbjpDw2Q?$N>txz7v$~r_urR5N$h= zeq_f>_N&TZyFO(G2TmTUU~i`*%_$)};AIW&1o+0EPkU5W<71p^1iFYheOtw3%Ug?G zA1rp+=I{0Be+%YBKVHBHkiaB5is}rTMZ@qRxH72`6Q|2KaK9GjK!f4N<&54@V4+fOOAP)>`bospb`8WpmAqJb14_@5rS`M8ufUOFpGh#8W^4MoQ~u;;7=}BpRJ|=(b7jHSHUc1C8x$A!Y>#^1%H1 zc%7|o&AD)Ys2`Tb_BAFHWDD%N5x_Oq!zazp{vJ` zlf8$>-&y1tz#EyLb=KO z+`^g?(OKV(ck|$>K1D(<8sDAt3-Q}JD2DaY3yPg47*TFtD^bHC>4igWbt&6_-xGK*9B4vP` z{Pe|PXY^Wsw%l`sISq$BRUFMoD7ybVR_})$BUvx|bSGxVDuZ9uxtpF1PY_->==yAE z%h{Kmt#8j`OIQIap1*>vq}s_aM55FG5Ly`IX)yfs27jMF{1wY#Xs|+!{@? z1CUPj7Ao8)3Xe-gAr;bQl-p%|fA={ zSDoGV!>@7boZ{j+Q!8Mgj;xNh%I9_S9DC4Eic?dxcakA>j9(q@wBXQSqdEm3} zZ0DqUKxMw2h^k2!;zrl1-*!E{XE$l3;r(07X&wgmDbbLgb0tIE4OmM}WSZ(YonS$6 zv|1g5ASIT&Ox5Hrv`HGt~CfgwyL%>gY=G>R6ny6L%+YCsUSdnhYcTvjCt z80x0yhy(V}nsC~I0jSx)o0zZ-n6#`~Ow;&P4UD81Ec)>dN-z41B_(bt{dvPssT%hx zY5!=JSGh54JVdFycSK@~MNZcapY?h<;n^t7exO(SOmEt(4dT#XK` zl?#aq+Hq~+MH@ZK>-xekn164sv~FNmW#YR&NV&)XnHTw_RNlt(ASwDG;}wVYMU0gxjWHzI5nIyYwI%(-n>Dl2$kXr~g-(ED9D${9vGi3iivov&`mx}6!8FB#}cTwkXgnd zZ6Z|JMz>vV<)28;SJ7#L%c!1aP_Q0p9l~0;mh=pq(#H%Fm+f)jNLoQU<8`j@mgq5K=xhu~CXY&!t(E6Fl;R6c@hU<#|{ z7$*%0bIgzNkqCm;e?X26wiuBk-nZe+(LcQ^2*V|)Y2X!-#_4(T&$40oBgZPTc$hRk z61keTT8ES3^N~3X>5elTgVWJIC{-#Aj-aCdQHs$m5G>n(cxpPLLX=zKNW2DnUiQ2@YD1jP;`^|pks!&W0g>!RIZdBu6SA7P%UBw( zA|(MmC8I{Ek{8>1%Uk+XB}}J^PqR~iBa^UB+MPn0(Z?^unRaAp~Y_ z2nZOW6uogr%B4AD@H}b23+zS>wKwFF=aM-->(yV#imt9+B_-wUv)U#*R54ruP!02ZkgO}m2K5#Mxr!Zdu9+yyz%4J^5ep#LWa09HAkR;uCH{>{9~@tcz$KHn$><3u zk$kKI3*?k!6kL{er{JJo>Jq z+R49-)`O?}1w|w1AD979n`A9sm)@!mXcV@UDUf@}eG2Z$mLkgScfDl)#D`V(C!|*U zkZ5{yE}Fr|mJuM0^>D>}JuD0qUUn)1j@;HVo1gwUrv@D+KNR^;)#gYvP@JhNinuaymB-MyyAT_8$nJjKU z0nX5%)PX$1(P^=~rrx!o4}6@SNP=5QS5*ndd16xwYyAN<@mr2zds5qPe<2c`n9b3F z1JYC)#skz<^LkD|roAO$zvWD^MH0zW5TkmV=CGkv9acutZT_N?YC5a}}86LyjM(q37SzDZ1JBULRK$bYwd>xPuNu{s0m z7!!k;Tj=ZBsvrw%^B79MUk%LytnGt`Ph4F-f`Idfg0>%icI_~5NiEHiy|ND^E|`Y~ zom_5iYb(ERocgUGOl6OvcrHwgd`gnqcHXWSgjtV)$G#$==i$QG=~prvZzF(T!+SCo zfFeMEP$o9FfOmWm>CI>gE98k66;Kukl`mq;Gls#me0p&0Kehd zLa->0Z<@gdF~*6?KnnoC$TUn%n2xj(-v!kKVULV;pY+@(b!_6i=L)oU{COYqrxf9&(74LR!1UzT9&p`IpA+$LF zQz&EUD2WCcHq6(D{089kM6ACSft__g@15b6fog#ZYKu`i^o3JFI&%U)>A9&IIy=xw6w5= zd#FhCygKdv=Cj|5BZP>YAysV&hOLYO4Y}#+qjCU-x11kvQxgzsXFuo|;FyOA}Clk;%0AQUT3hQ%R@-evg=fsjkG2`#z{e^qKI@c`dxaKrQ-w=d? z&crr|1|fIlu-sapunYm5AG4dqf{)|@p zX5^J%U(;*Pm{JOf6w*p_LD_lS4*^l*0+HGsX(|9ZK@?v^+Ej4l4Oz{M#=raZqYm6Y zE{-6T_3=i%(LaK8)_uBlvGQhD388g@NCv1y$26F-MyS@k)b?)b zl1Qcr0Q|3FkTAK9Ze8yYNu6n#Bv7k7N&i#{=BvVu%ziG z`@Gv?Kvf+mq~~?6u*%SGRV0dJ>_Yhhbaho&9vlr*(U@7TH_XkIqO-ALqLy_eR%mp*@d)FTZSW(N z1RO;rGmC(O7K2YPZ(DA0$kl0#o~Ofe1hRnyfcx#%a|yf}^HDdn_WYercbfS`K-;Rkrp+gE#?j;CB9qer4}2}L{$4lH33|#Kh}N^9DIj}xg77m zuUtpukPu;a5swCiEKrnS-zxS7KVs`?g`oB2Je#;{G`f*@TQ58DXk%{Z_&65-z{w3j zF|+>t&f4Y%Ar$%u+eDhDn~ezP7p)+~5TxQk~5LovbS!!x?uEV*iyY~;21;Zqq^j_%4A*F%G^ zGhW#K^eVnF>wqsM&t5|OODL{eu{#j1WlaXH>nQ8?Qt-!Su$TJ&FX2JIB;Ajh7ux`y z=1DqaF9d1jy-kmN=tX=mT}jHpqU^rZVWNp6U{C}wzx>$sO*Tj^KBfiSFe-e_0VV7K zS9@=ljC(=fiEA zdgwj9sQNxSc1FWv#<9)RtLNRGa4pT#gJd!fVLb--7l;+s>#KOZ{RwyZ-up(y3GoK0 z^R*S81EP$$nDNcOjAk)iT(ZD(|6<=ZbC!px$eDP<3GXbi=J1vbd5Dp`Z;&%dfU^$Z zHZ%+O7a=PuzLEv|PV~Wbp1u+Dk6xF^)pldCHbuIAmjz7UQ8$@k##0hx4<#yE*=*eP zaabq#9ypLJLtq0pL}&v5wK8-4u6Ds`A?jf^5oC$`vS6mL%;27_?m6E-JE8V_@17MP z4TJ2yp|#0jp?pXE7b&vFWj>yCC-AT!`0uLkJYB5MuYD6Blw~L!!iUz+?K;h#Z!< z=oeZI6ypQZ>vuP?O<34IC@c+x*WV`)ePJ=%0X!QQ1P@iV%1uejO<%QE5FoH*8T)1; z_xsKn18GML7Cn>3cafRRJw|6s?Pp*}Y%6*=d0LN~eC&JlMUNEdVfS3f1&65eXI5!d?5wfsTj!c?-(6q9*V~Lmb zh76krxCUWdQZ3PoA#+$aIfy~@jV8>vNc(s15cTJj@v>5za*qy3RJutSf0a<{gNJjp*eu6;J-)ZSm9FI{c|<-G*^u zQnyHLx!|=fHqH&G5@O7Y?d8wGk62gTPp>M_mU@^!g+FkpzN9SYeC+RDL}x?!F8zum zu`O?tU{u&EGQF>74*_zm{CRbA^PnIEh9E&+mY)P}`KRl?pT-|3LJG=|K-FjxHhT2T z#12dv-F0$boEXSr761ZVu%IG1&Y6?&pe>4ZJL;o=xL_PVaAg5Z4-Br;x=@FVfl&DKA*n({sa4AkN17Q?)UY&uIKd%s+YCd|2g@!;hb1bW^;SsD-inO z{PWOuAv@g>pO)KYP?^nq@4KPu#3ivt$8!{D&($gl)S5!GYdzU7 z&PkqsIXNTiXuNX;4_-}V5pOmuP!wua$vVigPO)w~8P$eru5DtUTVY$2{#LU}zN5+* zT;6=~PvJ@X|1S$FE~y=RPvCD1@{c<@WF#F6Xjr&=YSt{!oakysx<40Om~(1DHiNw4 z&jmMGPabXGqO_JDJ9}pRJ9`rLt*Fk9=InoT=Hr7EBT0K0eEio30gRDwGIqIU>dVwW zW^F<}8L&PW;AmpJF^>ZffZHYf9Mn%$kS$J=DMq`0knUwL6kOm^_^STcfaB>A3-MbX zB0^za%dIhAT!38jWKfa~FsKLM^hWM9xAbmB2(1jl(m;X{3h)N*yvaWv9ZYZu7U`i_ z?~NivPRTYp_qp^C}RsdV@*Vl66y_jcrxA)kzI%s8=h1m?T0i-85Yb^iTn00>iurGt| zQ@$a)XZ4K@Fkx{>xz#s1I>-Crb62C1n+NR6x?bf0C@g;jTb8s7dc6g%M-qJJ&XFsS1aOo ztHZJYEJPi*M9>u^ZD64R-3Y0cc-txF+Sbr)eGX%7%ku-YbQH2PrTx@axr^Ct`9 zp&zq?zZ1(RGf*CI_drnR>BZY@9q2maTB;bse(k*$yg}?(oeyU9XD}sbLhsC{T)jYt z(BE=4PjKts%-VnOFX!4zp=C?PME`vYS@gZB8?;~$V--46Ylz5g_)HFgEjx8Cea}52 z>Ey`-hKwYYS?^g)$(54>mD(JkhNCim&nBX@C3egJ-#18PDC1Z)GnU%8_r1___%2PR z?jruf_W=SeJ|AAb!ZgSFqnW?#bjbJr-Ym$m|9c%&@TSdgsJh7(zd6%}>+FHVZoIY` z*2pEQMx2vF@r>$|aS7N2E{zIKl+%C6|xso+Yns;)b z(q+Sw&ir`|_o}^i{r*dGX&kKK6&fupaA_K@)OLpDBMhm9U&zvHHS;crYM3+!2E)br z0WD%PWE~)}eqan#I*<0hdKG+<<>9;zC*^B1gS}jY@{E8m3%^ZHIA$5?eK!Krf(p|H6rn4}f#G^tGNdZXXQ1b97O$_qE^O zKR&&>S9{U*tSSnFh^{BThI}>k<_aWOqE*KC2*=2Z4z=Tay6Gg_mNtSk3*lIz>On-=;E3OaOL#J>9?N z=%(wWwN>f&{MTkt_^CN|Td~gFxqq*5YnO8nB`ttBCCmdhvwZq!Wx?D&V=kZO$B=|y zXwcfFRZGgF52j5r_Ad^(#n?I^>|0|Ro2n?vk1rtt2Ov(3m4^g|@TI8Cj;hQ5(v36S z{qyy@rE9jYId{9X=k@0J1MRD~Cmo1hb3x!>7kXstraQA6FFoI*v8iM7z^UPCfB^z{ z-Ih~b*tdxQKv`@fDTT~~WB}fyQ2-G6@9`E;~ks1l_M)O zGH_8V+)K-!lonN&QatS*2SOm-DSb+!i zQBwupC=*)(c_km>2CRv6U$I`l0`}21+%oqB{>Pp{F42sKeTHe@sA|P`9T6C%7$R~Y z<2+Y5IB{}^EE8W42`Gwb@J|yi>%`63r(7S)?H#Wn?l+HvGJlEj7Gt@?;8Syevtmi- zg{qEihV5QEee^Tp6&Q+Mh7mS?^Aa632;cRxD%IEO-&b=&iZ=#CH2=z&nJiwm=hvI# z_vIL0R3yRc@Z~6+CLE}IQ>UG#fLZ8n5sn|Ls&j~%h{sLHwK;EeUfT0OGTlduEyw)e zA~>rtfaKK*cmKMFF%clM?fN2%=zAD)qqxKwk7|3#*5B-xYbFXntGAeB4C=MDI|f4VI|gyI;IBU2)AKZU$GgW zcIF@;>s<}wLpMm`0VG6#l7~514M2gV4I&qpTSyP309kMCPS`HXza8Fu&Pyj1fy223 zIGl-8%DS=Fr5LR~6ho>6qQfU7_G3aQ0==zogGhp2$>Ypml&Mx;8F^e>L{z<&6d}xq z5$YCO)anrDrbak3j?4nd7p2)6Sqi)kr%S}D$)<*Xg}8j4bs%wB;u@#rVi;sB6;5P}mCCF-_#kkbedBj{qU$A%#=3eMt3Vr}R$X9>F= zA-m6@CK+mJ3V97W%_#J90T32ISYEQhpB{G!Rb5hELGPM-`HMQKB|GvZyoUlE0r&k2 zkb)Ts{VWw|AxLa?M<5$SC34IJ0iBH^m-{=i34AUg1HmkgPzjiMHMm5j2rK1aJ^DmI zE?T%CyV-ggo@-MVdm=%*aIA;Dyj*)w9@ZX8YUpxyE>QpFr~t%OA-Ywgl4$n($2_$O zJ3rZgtF{zVC=+@+-2yF4a&W#ZAMMSTp;gFgNL?q!+05ywb*>@y4*crFAyVnuK{Lt;iem@kLL z97ZNa|GhiS&nhvYneLD@&j}OcmeAQgDl+j&kU^bXEw1#mnbP7gt8;;FSgN1ilr-O= z;t_c>oNB69Q_vQxVD1gc5!O?QZ@z#|9#fn4jdH+i4uCUl_uLiFPZ7S}t^uVJ*?V53 zuJQ|-m>bp?r2oOSO3_u{TDbAt!Q+(ItQ-9)KPO-&edIV^hQ(8x5R%-P7#Yi_Y0!IY zt#~W+g5(%}DBwimqC6KAc4x~Ev@%e9$|b<4<1l1VzYj-0to?rxzE+G2`eqlRGnsAk z-^)|^crj3rjLa62BRjTkOQNBn*5(87p0$Z;WvV0h=dhDq*?PuPv zX|!6qRMjtVs4NTJ)X{DJ{FR%WH)&tlZNj)$D&Z+;?SAE2P{@mCUub)E)!o9d``%7`9&bmpm-NSCFkyIMuIV8~csO7y?{Zzql+E{?tqoM4BH)vR!D z(EouyJ;)?`UoU|2q>X;_$?rdW|5QUg@ij1Fvg1Gjg{h*s`ZK@}y)~qRPFjDJ8aK+; z0dhmufl`ezxF19><6NS?gUc=tP02u;lg)pKN~)XxM3`2afmYIa@Cgc}{O_)`mXCK$h; zbfib1*wkQ(8@P!PpRQDwd4y<(rBi)5owXP|9{T0X!3rQYLu~SLU4)dxm5Da#JMq;Q zUm@n*n&Nt;b41xF?Eh#8g{!1F<$BiC0&Ar8MxG7>jh4{K_EoB)H>BU z+Ip`6pM%A@nuVd%4#y8-?89C|-$du`d088$ayK^y90q_UCGoL<%+k@Q9i-fqYdipe zXUbff3S7Nm!X!ro&tgQcR>0u1aKhEmp%GI6AaTRPRD2fqf@PC)FCp) zP6Gi}u8aL(9fs@oY&!;TvC(Ri&0A(c_ivsiL+tAM`F4XKQVI%tz&S6uqlbNlArk{e z;Z35^Ma6t=1-!(^WL_waECXwY7W1)wbI-%y5=~Ajz};)C{yo2-qOmCUD`-84TPnjd z2KQ4-KbwAI!1EC6~11-U%{JBn(A>~BSII* zva!|(>%c1i&ynhGnPP1fz?WhuJs4}12?UxPTMe7MGrqypxz8+E{&K&^t%>*%u;%jcDAtO45=Z$TYhBk6`O1|-Oh-WR09_cHuodSKk zbZRFIZNoil`5x=nSsA5reVr?IeJ#6LVsvn97p1>q|GSFf$8%S7Z_OJ7rbd9<5gd*b zoRjKiBnPqtq&ggCrA$p9#0<|XVp!l16_}`U#6}!ptUA(B3;Hr}d?6Sk^|MS;`!=zD zBOt^eEiMmb1NcQMAee*Qsl+o@+1+#l|3OD9Bs~8Loo5J)uzjPrCpgHYnP`5J zMA9L1Qx`WB^l7>{K1l3=#JdiFkj7!jAa-f8|c?5;gWA|g@kE_E- z#|RVEq5j9d>^OEi{a9qd3G-BL%mV>j zMl8Ds9MH#ZdqaNR3#aS=HP3@{RQ3FV>dGy~PooRN*#*|1tl8s4> zQ82y^4)dU%VxKr`bRx{XtgG!*;*nFAb{^9>+8Rx6(XngOeOf^gID@sj_wyiYn4!yH z)YX8W&OtV^-6m>M$+@Hm)G0zP1|K*a2qEORIsmBCdn$(`J7?1E^z#en{Un_(*uzlT z(&b#QkwrFP*5qWk*2#KP9SF}DFYcPZpH&d}*yBzc+)_Jxwx-9*)~d{gW7M5?Y(ZEt z`k+0~!%BFxl^+VNU>9uMb+}GPHv7(S0vfm>G#jtHV?z<)3s1W_xz-Ju8oh`p%~-e0WQy?z>A{1qLJdYx_;Ud zZvV{D*%0Qoy6hm#adVyLwdz5o3CGwZ#5(I&b(Ss|)WycNT{2DeFiqvcX@?zan@wOp zrm*OH)Phq9p5J$XtHQW4#hP35PVH;+9D+836eV z%>D>m3}eC1U)8&OO`7f)cGsCM3ts@IfqVpNeYt1pRZUf`pvTteq~Jm|C1 z8!|9RMZ6@~=x?qKL;G{pfm<1%G2ta30q#9KLm3~M;2j_He>TNiG~8{NI_La^+qVk% zUkrA%Mn2DWNsZIOh9M*C3}-l1j%Mf}97b@BY3mS{JxDVIu)3`WR>YVFsg9Bv_y~ZD ztoHb((I>L+ZATlK|d;Fmze0wSf5OdxSm%cc2Ke5jd9u7!HG!HnPH?9E?Gs5i3Q65UT@+*p5P0 zgV>ae(Emblb6asotq2il_mxXtYJj4TI&P43!=Am|q!kw|17lJl-UX~R=l){~CMFf> z4L8VbJ?u58#v+3;3=9Bo_HFHs$1RVL-{&((-T)>s73!#8&Q~|J0v6*G$Ok!c#l6cH zB_0vs%7i$akQl_US9$g=(j4L5wJ{yU6w`>GtZR0LtjiTTGoMBuiwKd($ll9I(uUo; zU1z}rb$gyGtyPTU+0etJAuKtMiY62w1W_xiymjSTCrk|z!^};nlqNPP`wWv~Pv@-v zR5412@yv@rjmlBxnxNTg=dmV!-x9)dd3?5zm@gpl33ZZb+jI`5ltcWLq`zzDn$QxG zhB8ukn7te(SIY2ja&V0nb=<)OE<&jNj&Dd!sJWW}oixZcAa6$0!yG7s>1%aHn^g&Q zuM;a|_@8TV9<4QNMYyxy_1#ZK-d>11lY=WzjS6c>WhI7lTj3tNkr$fJC-$3Zw}Km< zF#n{j|5vABqi4u|gEd&;rlf6ahHTE~v)tzS5dUpx;4uKtbQ}O<%Ts6f=!hJ3LJ4Bm z)k)iu&z6%Q1UUFGx%ecJJ3mDB#yp>cxe)_xItl!p2<{YiV3+|GsiMypaxLzq~OQ!Q>ygo5NHFze^bs!KNf{z|$Fb zgoA4`+3d&$wvmK8vN;y5YlvTtfXAuZC8_WC+ic562nT%(b7eqYEsK3A zzIlN3yd4i-ZTHj&~1sJ51{?o8G1iF{(xE@%IH=3mrq$h0&Ae@egR&5+hw1rod%uz7XeH2p-CC>|Z%%MI2ut586jxn>Ge`*~zJ^a$| zf@#`nW$DIQF2umdSKY6U=XiUpqtdPBOVoW{LWBdZaxzK9xFexUJN8mnZRFCHc)tLa zqY?0`AFhAYa8evY#fiSLH?$GMk~-qDK?9flHV5C*9Dmn2K6eZS)phnTn!gMS?$+=B z_Un4x1H(~8pskB~zUWYu#-tihxGIll`L$Wc$~t5d0J?_aWr zTlcc3*6zxt_P^$XxHte_FPshUlZqGsQEizOL8pR9+=+*qj zG|vnH@G_gArN>+mr1Zl}v>XCfD>-B7gyY7WHYvv+&s%#s2DI9fDe}b^))ucYIgMt2 z7-_D&cQWqjkB#G(xBm0y+0&n!m5NGr8zGNo3P(uMJ|3Z4-_k5O>#vF-tqtNGD{X{c zLZxi;i?Tu0tRE4b>m&FpD)FThQJ*c$8026{rKFhfSODWo)wi^7Z3O&tD*!x4ZK)*U z%Idl`X)bC5V^888&Gs@cjZc=tOACY5-Ug$h`4a&y(>%Sf@H9XDn2c#Zr41E0h^K_` zN?74LvJdc*?NwrJ24i)Bpk>fW$|EX#N^HOJt#lVUlP32E)h06z;-P+t)PqRE;c-Oy zE4|<|cj^zYNljQ?%5SPngC=!zF5#UKyxPw)Rme0bE-zaw@A6{}FeYEk zQHg9(D@fNu2T=^wc@W6yaUIWy-}&Lf&-kpbquXB?SW6k?$Ztd|qA!1=az7W}ltyGQ z2QBlUJPr?CKxFpZTku}_azAUP(TeCzBu$oiK$W6m1n=&L!x_o4wbw5AoGBGqg9?k0 zj_MgrKZi4~3Ovq8C3(cfusXGE#hpy%TrDVD*;sdI=lbST7k{tUwNwFks|-1c)w2;O z9L{R5{+_LI^CF5pesmWzg4PcgAkdYbZzz+OQRK-5wpOJ>w!pzvkf2 zGsHCfDHJ@l4UJ+Q3hdt(~S1){2~~)()Q!|3x!)cH z%Bwg*Cirv{T!dFgww7`xxEl0v4p`dZun}#M8@dY*{pOciG<=j}yyU=0DuUrF6_`VC zt_rA$TNaiu|MZUFlr;xkee?Qp0W!;oC=l>sfpiWio;!vTE647m07vp0<>CNgG%W+! z_p*rzH&>v{+}S~Y?Vf!EHbX=?_9a_0k6Y?R#OScNSZYd5X`CEOagi~CV5aw?#z{O8 zivbW4CLI8EI3S?OS9scTxCvGwaMpwci=^4xy{Qd0SrP&ai0*c&3tzf>=8V|H${H9`UD`J4gZh7S$HxO&tOSM=MR5Yl$QCtA^R~X9urN`Ay17E} z+)g=$+t|2Gik=`#BAQFxV0tVg*E}2{|KwpPTHl75YPpy^%BGrOq20}s$vz#x`t}{s z18bI_Kl+SBcBvsbGn=&X)%ICu5XD*f;0{j9u`^Z;r9->xz^3Id7tKBwDYLI zb2zWydysI{L(6n&8g8L*4xHtNqmTuFdn0stAp~;C@;MfbiDV5TE>^7*dI+JwYQzU5 zPv=7F=sZ!@O*>OZoD)$?ZEloUcthd^QB0!$l@bdd{eqGq5nLdbXaP#>*N0qf4{5dy zdjby*a<%43B^Fa^i*u}7_gJNvT`QaTmM99~@;|37o6fzRC=5!n;8}d*5cSt4f~5?g z{1u#FH>KqByL>EK(US@OnP4+3x^NezJz)GH{AhGzo!g()tR>O6t-}@484ej@`Oq`~ z)Xv)(1AI)|eI{kFMUDf~MisOu7GhDQJfsMkMZhDh$CTKK=f#baF;Q~0nOR7L1}|$J zL1@|z0xtjt!f~!P@p>E)&t4gZoZ!g<@#-L+gsLkCtc_%oi;mmtX*Q}Y4&QZz3AHz~ zZQ2hDXgSeC?yxe#7vpt0?|wWtiXqfJcHopSM03TeIl5@$H~EH3Y45@%{EZm)pvcI5 z!ySn_wy{*?OkRbAXCwnhGX~!#?MuYJ+uCa!ZZZ;W+qJyI2t6`nN1D@zn?I)_{o1G9 zo3sA0+j#z%*oOMhI=H@m@x6EEYp*JJ5kmyTp}<|9KZqc z-jk_L3ju_-{i+;WQBUw`^uW&g^aKtg983fq!iZ$ux9)Bv!i|To<;dvwHJvaEM9gu-aE~!!WA9YAPv%IN^5B&8T)nj` zaDb_LYlo{q7%iy_c6wj2%-C{N1Om``w`H5K#CZ-n$&iN2(oHj>cW=2j%om{jnhXKp z{{ZT6gU|<>^4Wzz>!9n<0`x)0@uy~U7?;?q6YWjCX%9r~{ z>9y1-gNI6Vxnb8mCAr5|FSS0ehjiSq3+|piu4Ah=NSF0+Wy?PT*&6i^7{XKM_ zFsl;Jp4xdvMVXh6j|qK;E6_)>?niCJ-;ZxC5t+6-?bqH}b|<-9+ha)qopKwzrPBt- zQT$6x{0GjTt&$gS5{u?W<&$J{eAR$gq2_^kmH>d!OO_QkHWkkb*{R{T=JZI9sLbCB zeQ{6#p_xAi6M!2&exl6akjy+YBcL)*?@nNTb1X?(cDrSD{wXW}vws6x+ifh~X>Nj0 zM40cv@dxApPrVnVlkY~AwN?dQX$idAX@F;4`En}%d@MP5N_8T33-4b*soJj%lId+#TRlSE)L3OJBJ0`)y_Q4PI4mhtTl__r* zr$WzO7L@VtKBx+Q(h~f%^YDKifLTXy6&)hAT5=|XCrp-3dXasRgJt}}$qdpQ_tQ}H z(y5}Q?^;Oe`dBWVZ797n72CmW#6sx7ca&w*lx5ztGeqfR!D!h%kId}*8k9N4%Vvs} zJ!roddhoc4;yz#GL;;w;J}#RzxqI2&dnN_^8eX>K_cCm-peOdSXTklSAp+ul0qOhg zlT`wZYXZt$f#x%T7EY_^XpNR;h>mHGtGw#xv)(qBPC+ABf~ zu7#L9Gw=}_Qr)iqTt#m96<{>C@614m<-*WF<_)d9p5&^K;wXbtS<9@dL)ja3a5Hyz zu;&;w?kD&9X&6Ct;Mj2wDSK|%ymGyl-GFfjc775WY*WOVKprzhf0-^gS7qJ?DoU{$y+c8rh^B+RfR|HjyRF*Rg_(M6+q223)++W%Tz9}4R6PWV`T~m zn7P6gpo_&3^>WdnOf|@`#2ElAXNW8q1d=hUtAqZu78WZPEz>OM6^*E+#+X-bW%eRP ze~|69<$KnN^!cI~9I9KPwbgpy%Q}*dc(^9BrkHUc2MC;4*K1K7DKZ^<)@PxtB6msj z#Bou%pEPwFBQA|Zwq`6DkeV;u7*%vPs!w~&xP7vIV%AhLQ8JfM5(7$=}m@VKmFVLIhD z=1as;;gbqR+0iIdm?=6LTV1$6^j=>dniSn?eUDm!j@Z|QjQ~F>tZ9vTIOWMhor^jE zG(uc+f7gKXaD*BU@M?yr(p{9w({yHwtjDwgw`Hmg{$@aJ+t6{}ax-njWW>#q60+pJ z%>2%UC^W0adjGK2lpasgL4it*=8Jle{bx>x6s!7+tB%{+6IGE z-0#R!!%B;S`Qc1NRd0{+pd3Te)al6Z-0`JC0ldco}?6)H@HoI$~%>%tW2vlWDudCcu-u z(WE6t$Nu|;9>Uh1nX(?=9Sglb?)kTG_!H|+0O=aXZM2T8?PjT~Ec9$4K3eypJhQK- z&7!!GF_>BNbVv1>)@xsEiEr~!F=G5=>v8&&M&VTL5b^j~zj%|y1Lq{i>sn>SD5{Hy zTiOoI}HWh$X3JBvfN+=0XP250A zz$24ANyFnSjtjDngyZI9VuGgT`457)-#w5{Y=D~8BX0FkDeo_Sdv90pVL zfo!G7MyQ4?wUE?{GiX&1{U|$GOy(r3F-(rhqE&m)xkAW8kiEV>nLaxM0Y!y2D9D=< zlQ>!y((E9W{)y?l5j3g(vj7~-W~oze(nTDVDBK?4O)d3sy9Zig=QQcRXvS!tx_69( zU2S{PPU=u*iFNTVVAg+o*XjKkOZVU&2N%~@!k9yv42Z3 z76OTtA=Xdm8Iio9=wMrrAe;CAQ`IdN$gy@DM|%e3ahcQH%`t0|ESP!Ux75*2{+eQm zJ?n|Hm!l(w*x&2hconu0O3d^MG(h(~i|^<@*!JT0i1n|wH_A`UI*e5aH3)HF=>Wb_ zoqH@tbfYLQgV(=bEI77{F1(A4-(#)8K<7x_-MJ<4~tCW8D7fW}^=t!9;zZZk^3d z*oqQQZv~aEk#qJ`_NEQ0uspGc3={J1l7|KsvIjlHNPY3I?ty0(;NSFY_pj~7&y z4vBbUi;jF~`u7eN6fAJmF-TX4|7!Cb zP^``(?)l^3+}Zuji26M}wJq$UVU)AeWhm?@RAYRBfVv84t)>y`=jCFZZPSLZc3Y(4 zsPS64?^z$@%D$3;EAuXJ;jasXo9MH~|5$ACSO^35gYP|0cpTHc5}=}K_?|ud?aG0d zo;4U0&+-g*d39YR%^;NeZ4FdV0tntRC8U`pP8lBoVCq!Fjt!=gFPpPqi*#yc`%P*X(M=zOj&l)~`r}56UvRI3LbWz6Z zwVQw6dFoTn5WV0{y}^;Sl#hDc1%^IN?E*&Jd@)0OtA}-Y<#2)C^MWPsiQ>F6O+@og zh|Q|>XFu{8+L^$76LpX_4{;_EjaKd#Ogtl#w(rQhB&^>zMyBEO<2UWPKv0fcR;KjV zeqg?s=)YOW0$rxW&7pu?`_a#YEXHb-@saqp zTbHCWZ}!CHGekvCG6N4Gq8IJvbiuXcb}oG^n67|#)D!t5q{b@JYr=8&&aNFTyFV1) zU%r*}Y9(2F@a3u5kUc|!kVC-UjtuiZmnS|f+xv82PmI;9Mi*S;LiYK^|9*DwyRxW1 z_xJv5UQMXji2{sNhC+z15qPgu9Ev5gaB9|vTn31(`&#`- z@GGP%ZNs_8Cy#FKGHj^2u@wa9%~&;xN2n*v)1swv6a=0eNF=cVAR8Ys`$`5AR)aVO)#6cSf-g=+ zX66`}XH8?UNEsPV2Ev(G4XzOCuJi0dMJ5NIuW!M-hYw*7p2!Vh(S3>Sy|@S=inZ}5 zQ#(y*<77w&$r{Aj%#*RF2pk5pmz4MlHnm}(kDDpFDa;%QP&RiNuu>9uJADU-aIpS( zGelYWN}h&`nL-FgbZkw4!OrHP2H4=+{DwP@-6rP;<~{H-F@s2%=BR}1RyXIv`<$O-sQq9NUrr~?Twst)#m}SZ^Ka=Lca`EtairO#OWdX%t~E^ zeyp-65yFhb>bRPg11dbgovPupHaDjC8du0d!Lt zcbnh%`}M)fMgMA2R-;Iio@|K$W{SBD{elp%(tMAR1pJvih`B~ih_Gj5RRHK2qJZSB z;_7P1c^D#V0cbT_3l>PbaGg|rNS(fiI6MrZ&hM{=vh!Eat($X5lpsJC%kQD2Ujkkx z4AO`rBCQuvMZka%HnNiFQkiG~LkeUFFnGNowB?=FI?dF{yGzxb*i#93;Rx@+8nu`- zz|hGUQ=d*a&x4W(N}>>pt_%i6Yf>*iTWIz{zV9{Z|Fliae;fqsM?`dVC^#LwoDkVp z1D0{DY>*BVk@)P+NbNOd@5{wbDM-hrZ<9W*y&YETT;3e}I_QinPZY#m`!cMTu|`%9 z1k3F{=>Vq0v>Xrm(E98~%*;R(00}3_ZGT@ge1=eR6i^u{H)RT>Wj`_i%&h%L7=y^j zx3&7Dc?IG!r&2HZ5D~36F6te&TOL;h0$J!=y(wfLjoo%=Px#~~tP1bbDLT9~(|1mO zbpA@VSPLBW#h- z^1x2)`Y~R@{9Bo?$~mj0rO9Igvg{+*x$7d;`v!n<-41*IPFJrDTLip#f~_& ze)QBi>Y|*0G9(-YO{W-fz7+_b@vU3~rD1P{OLUDGXzNm;hk*bj+9)4f>OxygD*y_j z8kKDXyy7ndXMjz_SzWEP87c)9LMzpl&i4f(oH|U2OKsNb z(tAWgBM6lYAA|J4@VjD!(5$Xc4OLO;Fc;TCJ$*oHB+^0%Xzb|y^fhA;xVue`cULOD za#Rr_n49A$`jp_LHmRn{u+{S294{!? zyFYAr@n`bq0(;%NaW1I_=d#{#j9cY#h? z3Y|P)U;D^mIQBKDYm^r<(>~IZ#`eS-#2TLM!E_0G&pbl8WJGVh`3sdo)A7(d7fY< z5Lx%IL-6Se!tLKL$+~a+B1`TNusERMcD-xOj zCsiw|{spxwP+J?RYYsU0aVDx4axl7+_5I`L?cJWwKjWb!syeNfQvNLCI&c|lff09b z+q{!XR*<`AMe(~$G)n0w@WZ2ZQ(6bN@N|((A3q3wLg)hYm>LLGdNihrsITZN{r7 z%ehzl%gm@p4|~1wI_@!gYSY%{7%s#6Y@f&`LmYch-ejM+bNE8nhKj4C_lMT0MxTEE zajCny{8>_8jzQve$qWq$tO!087IyToXZ29>vc5YYX3K?LyifS;?n(5O(_PYkrw)r6yhI$K72SF9h~;Bi)e4l2IH+b zY{ovUSNsR}#p-#BSKT7;0nCVTUB9`^GAb5Xvu)KjN9@GA?4i)9eI+_$M1VQx>kzru%dbBsbat-W{VrdZ2Lh`hJpXn~ zJF!Kb+8;->Qbdw)#VSoME#tP74{Gz4oHQZn@VoS34efBGVPSdGYO$pYvbO2ad_@4R z9rqQf)qjzuJT7@$uK!n#&nRfm$WEP$IXHz>jZ9FUMABC9z{ut@zYu#jR+?4b&*tQ!wm66FzqNY7s3{|1es z1O;9Uu-zzH(hQs-D)g(=Fg3LwT>-m^bt$h;m&xHgh3S7R!EgHphf0bD9mRbl7yq?K_BlOW@A@^bKtc6tl)?+<99E!8Psu15bLr4i%yWp*ZywR<(MQk3qN3DkNniL(T^%N6N-OL ziHwN|X0=aQ6H=Hu9s?z#Kc1&p^Hq^U$ET!BTD0(-d( zmmsj_4MLf{r^CyL@A@>C1E5zpSVksJ30N~BE7utSuLi8zSa__Dc6FDw>3z#zLtkK2 zry8OrNloSt=_W|^LQ1rB#5UnRLTaeaw8&t(h#st%*3(v3;?ReNs!}yg5s;Mbzb7x05;R-J zP>c1o?DtEnDtz=tX|Ru8RhMTP6(8$|&q5b5H91LA8;UN|3R-L^*Rs_ORD`hXfzkwI z=di*vc;5=I3fKNSwiySlrWA`tMJ-xAca?WN+y^V;)lHW=<|AQq41K))MwaA=bw~8{ z;rq|zHSVL_&pd_K<1onNLk2a>MLmuwVmDkDEh~h<(t|37I62{ru@KS}_W=cB)|XM| z-#ug`eja6KYK73~;*UKx_5V=;_1H))Tk`9{aL2G?0++#m?^*3*8jHxhBEn7I*M_F_ zuCSlwmmzWaetFiCDRrPSN1*AxMzZ zoq16#`MQ}$g;7U7nc)+X_^7C^q zRw6PIR6^*I(^;Q4wf0S4$*p6WyO1RIhaz?;aS`r4 zIXkD)V%i`(xq(XFyaR;+M7O=}Vp0!fTWexg>Vzrwux<5hV_Gah0x*nt8VinpwUzDK zU%B_chF59Ps-)-Bw4UDRybzQA?Q&&adtRYE?gvw%b!%K{$YaFhWyMWfg`FFnXbo^% z<4TsWQC=kW=$X-DgxP&21`?ygt)C5*X0vIx?@pgAKf0CGW;RPO53Dv{8=IYk`?@Lm zzaI(NCjZ=Y#crlEeG%t7?&;Q+Tby4;AEEX5h78)3@GLUx6YoAic&oTQ6?l5J#j7GD z8PXY8#|=j)nK+I5R5CA$Ks>JTK{*gIO}{UEqiL+|I8C{EWUeJo!+eXs-dAh8uZuA4 z=(c$QB;Ez61#yv63?%RDB~}#4)D9=vugHy!=Vk*aMeFn z{2F*)`tk9Mx}?E*w?n=e2Oj-o%hM=!IavN}M^%Q?*^J0t-`SUYwXURb^`3_A;$eUz zQOVI?p64ZJA#J0JwPCEx7MB;B8V=(^C{AG={FOl&1n&y$$6l0_pgY_5`Cg9GN|QA~ zDGTS_TG=^X($|yS-`n#mGCJQfFw#Oo=n-Rel zK)a$p8_xZ!lPVq5xZ{@-I=-MVDi3e3&_)!}4_hFC%qA_k3OUD-WN?r63>u94qYg9c>OqqvkHm@hWl zsn8};C{aJ%&YUKD<;~)yWQttS+y_z`A8y-Pr#pQ6gYy8kPxI`!{H$EA%@^rqp?c#0 z);~`pEr(zhiJWs{Ne8!qM)k<{DITno&3S`6Jz<-FoOr=u z$HqWO#>ks~wZ(i#YM*fT`x=Ecy2w_I1fH|XxGekn^4l4a=zm?op%(ACWc&k>ySke0 zKeJ$=PHz~`zm`~>(Y&-I^BXMrxJT=l~)~0tI~k zBP1$qbLGtM>AR-R&;Y6VH|Y=b{FDUQbHbXSp}v_V&b}IEeC;f+n$ZbMF=kC7V3PRS znV2>=m#Z#i@>p z`GAI&xSf=o*BY96#&|{5Bs|E`bPborC2emKSTZ4+-CcNrs?n<>Zu0kyFjQ8t+6wIJ z=+3t+0&eWfg9tf^=k&3+J4hFz4!WaMUGQ6ZH$J<+=V67SqSRV1{%SOL8$^f{{5g`I;jZh!dhZJ4kt-&paTY|8R3jHE>B?Bh0vpabW`{n^!YfKa&G`xPy zRCI3n8&mn6Rgkm+b_=vIDswa370ehDj~>L3CRW1|4~UW_YzNlgqFM`dJqJ*`}H7em0TS# zUBl(VHV-aiG$jIG=fT}Xq)RemVZcJ;p68n^6*OGbfM2YTu;-oZAR*=Rxfa5v_)#kf z|NK!Kc_$GV|0vnXSfx`R?;HJ|7H<>s{DKF>0hAqF1e&2CCIFNo0-3r+a3`5=%!Brp zb@!9~4otCOB1UTxWKp9jnm222GdoGxXoE)&-37c&Ui$^}dhrdY))Ij4PU3AV`iWca$$eR)&Wsfj~E;vo{L~Mk~hfY}n+k}JB;urE) zt{v}|SuHs=SG-zw(b*{kU=d%!oP@Kzle_in_--Pljy4nL!fk&T>VxEg3Q^58go1@~ zVDjk5OTx@$2PbYaR+mRgUg=Y%zZWu-KAr4`{!Z`(a-EI$dGvl*Pwx18dZdGs{*o71 zx6k{^)bX~5q>tU3Ue{+%q(A%<=&@=bHzTZ{dT1K!*iJYk>J8A4EbeI|U)e2{-oUfH zq4GyeD}_yBOu^l+5J4wHUQXXg*;%%=kZrE;bEzO~*BHSswhG)W@O%eO=3^c{or-V1R=VwS-98sPK~gpF-oh&U z&VVsC~rR^&&K}qkF5>L^Kg%DB|Z)cKm|99|_2a zu~Q4sLpb8JP{|x&MRz!?u3k7&j0Gg^Ws&}D3VRBw5PqMwG`rt>#b`-92wgm7rEZ4H zaLW%8-^smd1#lpxucWGtY6E~_W4fu#J2t4^k~9C9sZe}GYryuQ~>~>GSh6vR*L^J%rfvFv;r@5i{s+|HK zrtDl2#q!JFFMV?*(%<$EnVay6VyvoU@$Z=crH^w;tAG23LMS0(M8+ZP&HKaFWKs2!fQ?f64wK2^nI&taC{ILtxIwySJ z2g%8Sjo)8Ue(m~F(!D^fceLJfMA((ye@^;R{3}E3f^&?bri_}kk8835z8wAhb@zxg zrENu*BPAjDC?~5f2!3zxczM)>71`*HN(2;+=55>*_Z19Kc^4P z6LXCpk%9P|T1dP%2SMBt*=;%YNKk9z(1hD{0j;=Q>Bq|vI>|myn!XY5pB08#x+cSf zumXlvg8qt%1+TO=lDTX)MuRmKr7ofSq(c%`eeD)3SLK>8=_8D?1$HNpw4!!J!@Kfn z?O$tdS07Z-FMIb2nZPDo*gOrZ*wx!Aea^DHS`bEcO`g{A#RVEP!g7oY5q&Bk*7XP6 z;(=6a5l>Bm03!KfujtnuyB_?K;DC}FG(i*OJQoy}UQ5!NaRn@?7C<$fB%n)5+Fi#+ z?r5fKrJS9|asVMKPCul^MGSa>+v0>NFKOaDQs{!B;EOw+5kwZ+mdb{-pxCTx0D*nL zq5jJOg;a2gmeMfnpIMk_G$BPTii+J|2SD~7DUv1BAvFR_mE(bwq9_WAvn(a_NlQCR z9t#|%CJEGKF|_LLU>vqMQr9@3=8Tj$g?0y0;`11ms91|NPGK1JD5z04@QG_g5<{E>Ar3Nndy8V4p*{-r z@Eh4z9j!-C|JsYP@EhGt=Qt@fbES+gsA62{G13=+T$mAm8_hdip~8t-rjmqeNU)T5 z#vx6EmBe$m-K^o>r;!K!$f6mp2y{aw5c-1jpD+q}L1+{()~FB@CiX*kQXUMyAgtG7 zLC`8kHF;Ku)uND!ob01I5E+-gfmYlip$>A+t7Z&Zm3I-vjVUm-at=cR?~2lf_sK59S4K*V1Zy9H9BjX#iAvlkLdBQ$hgk>;2 zgO6`hfdv@B%GZL-05^IiPLT4L%RPXZiK@C^AO=AbsUYC=dnFbgA&hAP(UBh&Aegc% zOse|8g`*l@0W6BHr$rX*WdCHSB9v%AT7}3OTSUM@7Y}MJ!KVloN|Lk?A^{hyJNp;6H0<)nn;X=NHB~imxX!<02|q&z&3}l#Up0HGz9_$XjdSMUNl|_ z{)VQ-{{VwP?It4TT#^V(H}hV_!s8eX0lJ7RZK{I3>nl$bLr`3@kdP!mR1)0XYIpFU zC|c`OeT|r z5CX{sSYlJ0BFT}1YE5R8~swaWsw`5LYBZ!=Uxnxvy zKPHY~O{y{>(PR%&1!Mtu!#4XW6F?x?7(OCKF4#_%gCQaW8b~d}m55<00Z$V0bnwpf z-~-=dEp!PM6$m+Pn)w35P7Oe?sOHo@*$|#(LksYr-`YsbE?C8sh&1(H>2b!X9d%c8 z$~mkO>Je25d{ztprF7_5kiHr=v@Zm$Mu@mq8)ej3=KM4|Za@u5AtxTwH>-#`w|4P+ zNR(QX%lE3NsJI*jPVBWf-(M9Mr)yz+bYexw;Tl!H!qC`}l=2BJzjM}FE{ppA1pJ$= z$zlS+(l(%0g_0Hg>i3kxahhI_ZExv3^C(Ku>ah-TJ({Dd_Hgc4yd&)dCr)j*xSpPe zp8q2cB>*@beh}E!-uJ66=T{QwtsD_kTPF9;jkg-JHdM|U%)Jw5s$UZ@6RmgB!|+U= zA<`P22<$xe=wLH^r`^eY_F;MMM@uAC>43(G0Cyuo-36_B!^Uyr+u{e1);M=dQ5%n7 z6SikU3fot&gu9xwBxrciGOs<|`0lvr8*#HmJp;9deZhp7AgXCujmdJJ`R{S_?Y!Gc zcL0Dr;w4TJ#goN7$qp#1X**wcwkZH0%kG*=O<3&4Tk7c>dOoH_E_+*j@$gm-Qc(-v z5bzsIo#m<~-%Rmnf9LlRcEbqinTzz(Ik_+RtIdz#KCXw0#!b&(w)+R%YZ+fJGVf7t zhcKH|uf%PC^{xA?+n?((5>iWG-kPlC4>S7b4`fA#6zESl^xz$jTZTY9ppYl1LlbCV zBjQLxeuKxjYOu)^ogZPHg*CA6VQJov4>gcTaRUhF%8O!Eus9lm->75WMpK^&KSmy^ zNQWm9dZ=uK0l>xVBYyho*Pao@74yURLN1xGMnY1j4SLSeTZ>aRRN) z6M%huhHxhdT_b^U98b2MEARJ&&;YoxSB$Cs0nqYqv7EhYkYlBq#0MokV|EFqaX(d{hH^QQcZ77du z@k`7}f)r9eCR;>}YFb!@b|&$I>wvq?%Skr@T`KktHFTE~vK45ZIW;ENi%xy^g3%Ju zLlZP|5`={QHE;BmumP3c6wWEXMXzY_d+#4}i5NDPN;rf8aL`9#p>lOb#ja*2iFZ_t zb1!Brdrwmgzt}z_W{5L_#cHv!M9#}ODtN9OByk`jO=RzOxtP%z6hzo(=EOr?hQ87u zmW8;a^Pio z@Pwmv#Y+gYBTf>{qcCsI0<&pXKJjhgh;XT{I7I}oGM2JK&rMDSro;^)O{2V zKO+$4DmwU4yYA5RMyv8zT=cdS?e`Z=&q|>4F2KjG#uLE!l&^eHupfx!Gle_@&6-Ke zam||wyFXK#U+9R6uffnz+96%e7tfYCt52V3yB)qJi``*}owmaHo)8ER2PI>njVtQ$ zv~O!P(NyOj`hnouqaQSjtxgh<<%09wHr)G_4YprV>l6m!D+u}^AZG+M-%d~#%@pq2 z*x0Z$U?a6ewhK2zUS1K6C-B){%Y`n^3s)c^7xDL^+s*9sF3~ zf@%ZsnwoOh6if8AaSH)wWGQ~`%I2M?a0DAtuoP8-{ctB@@JWE@2uCUC$F+#OT9UE= zSwNql;*C+2CHx0d6s+Y59u87b*-VJ7fG#_!=M$%CF9@j>Lh@0VGkvGam2hcES~o4! z?({{U|0#qP1tuVkHLBU95`<}i*0_-S8QphE4|Peq!`DQMgD`P1#H=O_`?x)Fn_|L> zV(PK$D`y1c-9($HIS02D#hdsFX&T&YPd!w8EB0H#Ih(TbE1Bn7Nbg5UvOHTg zwt{)^fv;{B<1Mz){laA`PF#zf`>d=<1QThio!XDAL(^4AV)h$u*_u@d6PiFAO_0)0 zid>@%W^pPJ3y(-d5)g?n^*eWfX9eC_q7?^QJv~avxADQR>+>dWEc!OR5jj0F z;Q1AKTc%F^q%|zd&Hd=U!_KeOKY6C<5Kex6tbMUs-4^MurGzkf+&Yzfs^U>5KHSuT z;BvkGFdk3=w$=P}AA1tV;B(f3OrQe!WLFzSe|jkT`)aT>(`F}CbTlNwb0nk_XhyN_KT;dx^vH4gtD?6IByQhM^_{W1gFFLV6;+?&RiH4jmEMPp&b(Y3}* zu{c*{Ut^P)2eoIQs^E{RFG~V#+j$L<(}R3d)8L+tZU|3kKFJhzu_k( z!_Q`hU&uWl_j~@Tle)6dQWLW9svDwKJ@~=+%zdBR;>iq1hOY&36{!?kCQ<<|l^aZmHyMUf0Oh1FDBabUHNG}Ngx{d@4oy@@!$U*n$A4C__}9yX54@F zRq5=1v$JpH=N9Mv=T=MS)@SEF$-nvH|K>;Oo8Pl z-!V78Q(-|lU_rfXL3?gtx5A=cz@lN<;(@tEbA=_#fF;|qC5O2s7lmbyfaODF%ZKNd zk0`7h4Oj^)TRAqjazbJCWWef~veol*tCtkkk^|P#%GNUH)~+bL%?o&Ywe0QnxwkhI z-c<&?t1WxiIQQ5IZyX~NTQbDxe>e%cP$u#De$Xhs0|{S^cf0RVsw0BG<9tZ(j8DY;Ob3)-X{}GMpN_BR`&( zB=pORoDA7e{u31Q3ZGAr4y`M9HH=!DPb)k~Kr&Uv1Z~MDRpNuvby_tJ$qEiA9+lIb z3}5t*;c7tH5nrbkNyIsgC01x@U1gS)TD^+T-Xnn%eQRYn3r-n738=Wp+?`L1=@fh4DMIa?P#}dt4Q+7h)=^G&)rpNLAO~MW*YI zY{#xP-kZ$eDxAED$t`RB-Vk^bp8hNCcE7WI<>f|^15uU_B-h`wp1@dX&4AAD_xEF( z>=y4KZ)s__@(R=6*@ZKXMbo`&rr&qGpDYTgxZA3IJJZjYvGicezC+hFjF$7M=gITl zU3YE1VQJEUx}#qs_QU$P3_znd_u&t$#yE!?MKnwQ^LoE0?j#3y$3;f;UQ3VMrJJAW zr!WYco?sg8ORxOxD81v)7dq3LOnTjPfrtqcZoi?F>5dmJxKdXM;6m@cQCHht-zJJo zA6iQ|A8`6M>34>YrB_beWpFyI3fx29Td5OIcK81Kbt-1}lkl1NyhGogomzF8d$uQU z8@EY1jA9@F<VSx#P8%9F|1&GXu1}8fDegyytL_};q$yNUdLWc#GXKIv?( zPSfvlQu7n5k%$ncm5$Qky|q>|<*sqP&oKDPBFVp_X>PVU4p6~VzfMpHQMW$5a#M}JmZ!Y7H7D4+4S7~pNM~p6FfAIr9A|YsbhE4s;A~} zPyn`PH8H#1G0cAa+O)ob)6`m(-&v1MA#$y$aHQ`wB7%J1vu;Vo!kKPd4M{R;VX>;7 zIi2zna_{PZ7*((ObMlaDZ$p@-LL7tRaVzfSfx{A5bpGN~)uK}kVHaQe7F3$&bm})v zpN;TY`6Z{gCUJY>=XyZSqX~MIMDw+UW3lfuypL!~8aYcaDSv;#j~GmPUI}pulv?mC zjsAXzU4Yh?=wrM{{eBM-IOU-93>vSHyszFVZSVJcdV1R|IL$Ed=J7M@xvE?P#p+$V zPNX%8wOdr72SaXYrJo;P)r|B*k{Kk-C~k4@k2|9tIplvT{+Sng8OXpS%B}M`JC~@* zT@OAwJzKfP&9!BH~skI9_2hU&V0f8 zi)6wT!IgIk|A_N$Lk17}K2YKW7v7+H3Qx<}FfYhk1c=@+=-P!2Om&C~YAOSRcH6{S zTeLGCja+^F>p!i3zFDp^KU(kqygO*)GrXvDg3*$+Z*KrOGDk%F=a9_ifg)}Q7G{KYf3 zi2hp6XN(o)`GZuS9p0IdW%ZN#dlh~C>v6@`^pb9Z3Ibx0j@tyd=^h&R7#^CYVK@@$ z{Hb2}jwyCb7BEkM3L-2fH>1j*izvpVo$deu;6FWG1f%TYU-2F0zh~B*&zxP`@dnq} zHP9>ZiKqyppILu(%YN`ocM3H+g~S8DPhM7LmntOgFd2zUq#*YaCTah*-qd)x*K+U1 z2VqyrYZ3EX36)yVKJ#Gs?1)jP&#uq8*Z(YOY`b(kJv8#UuxlnfHL+tjY()1|$)cRW zlb_E|j+|s|Tv%NNXwOp=zLx*zCyyKL7`xORU%K<*Ti3A83A)0m2A7BLyn8w)Z;8a0 z!+}+OLtg+Oe!r9V_kF0#f$3LG-&^ng{SbZSz|5-dnY(H7q!i_nxi4jBSR4MI65n+3 zeqZhqll}Md^MkGhsTW(15B%FaTCcsN?s8Vix$<+-iw7%)FMf`k|M%tL{y+0%^V^`r zlIVCeMH(@NoNOeCM5EBCB`$LR15jjtOtQ)#iI=j$`@z}%+apaD21v??%9=lI`^J8` zqWaMQ+Y%Ds+hHm}za&~XpFtXWJq)HK1<t*q`hB1X;|(E$2+axtQUo9!05DX&54MnM3@l#YtQ5dE0OnYrC;}7! zCQXE_2#^)^Ac2MuCxS2{qzd8qjlREUAb#=_84D`do-_0S0YOlT@AWrd#O+Ch01%x3 zeiHz`d7Y5wfs$aH0t=kBg_dgZifQ5|l;kCP0xlNBkPvZ15JQE@6Owo4M6MV@J7Yje z0w^4tC{Ql2XOpnEJQeN+;;3MByI8#qj6z8nRYYpA;Q)UUrCtevj39Xkrb3JsXvvV6&wOhHt!rGl z#H3-sC{^O6{ceCJE_`D%LZJ0*kSbl3kcFR5`&kDaq=Di@#1n5^%M=|JlMc(F3FoAV zqX10}aVt)$x*I@60uK!#xj|O@n!IFlk|-+@M_>u(L@M%96$p7A+mtle=5f~A@lzC> zDl5_$9VJP~6QMJtx5R+6V%9zo9tB811q-i0TyyTsCLrpLbcDx<$7Jmahh%`X135lI zWLWT!#LkFAwjT(viCz*hWLL43|7up%8O+%ztNAN!B|#BT$Np=L zy`cFJH2#yHC~xqSXo&(jHiSnJ ziDUKqVViLO!W&h+*N^wYWj0_68<*r!IHh;uZzd5M8%WWFj67v{w+aQbABuboSAqe| zjjM!d*yn))>CeT4m{0J(C7yzOHt~ z04G>iVJ#W?Ta~vI!D~K}|HAnvbrrW+EwBgWMa6$(Lg~Ep5Z|j5Qq9e_{5TSjON4X0 zGQ;g<4Zg?PSpqb)+C;* zYg7d51u|V;OYCUAK!7rdT)H*VOFD+Xf(}LlFbPtjAqLQGz7b=ettpGU^_s4!MYrNM z@Fg7Kjl3(1u*vX)S{(X71KhylIDekTKy|Wc~b;uz+^)DKbbv?0z3eKk`FFeVatOMVuF-$bBx}`HV zF$rk569eAGuvoCZ-cG8$#Pw&g6c8m^kqM^@+udWaLalgfqNr;uQ}%& zI)}XFft2GI%^M;jnM^N-{gk>|Y5Emd%cY~*2l83Ckuyo~Ucv8etv9|T#~xswvJSq8$?Hf$5BAl(>v&|!*x3`~`5575YxgQojfWLQ3>!GJS#Rjez& zhgtyFaLq-;7VcgJiOuI0-r+(Aaf)o!KWugvf(YWoD6As&qxFKowS-UkrjJ}LD7)vWKzS~adCQAM!S8)2Z{@$GkIN=~$VnY?<*lHfhV7Z{^>++CayAkOOK z^rnnsaVu@NcNC||bNUdJ#QX>e9TMEY6;AzQYrso9i~tPTQ6Y}d`eLF0NK$~{W~Pv6 zd#eQT;$_}&x8gP1; zF^|r6AU|^sy9M_%+ z01ATGP58|X)WpB-$$MWG1VuM7CCvieq*-{5Bfv2c=;a{ElXFg`k>Ok$OQB20ps|M{ zL-KE=0&fG1{j4GHe%SGQ+ zOobhKY#(`JElSXhBiapB@23awf7$+;NNn<2%>Eg zI(-<5@yA`R&EA7vZPC1KfuWp$Wu zQcFWEYd00%HGxs&rgvve#QllDv5)Txlt6<mEj73+&x*9>Dp{NA_8dZ08b zX=ls}g@`qdnM%0#30yW56ppKWhBJ|8gT7sO@WZ}6>wlj^e|3ysH`(*9l3nl4_^EN#bb7r!zK9@-)Ix!wuq2F3`oHkzpMif&EpecLdhk z4#Uw#x3Z8#MB0lV2yjmXNBd8naxCp|1i4?KZsgj}F>gqB_Xd0q_(!PimhHI1 zI9;4@RnrcKsfU~M-tP-U?jc-Vk+lu&fnJKjVs=L!QX;dAq#C@E3-#yt~M)Sd{KG7)xgf06R;>i{1Gnkp=}*Aw8)!v%%q5M~T% z97g~RSWx14*6qq zP&Tk!D$mbO*`le=lAylDLiNgERP5S*d+Rx|h3}kaBAH6~Is{ttLbIi)Ibx3$?q?D~ zoqso=?Zw;I?NSyuCV{jPJU~uED_B?{=|nCL5Jq+iD?==3&F0r$;&FH};ujksg8ovU zEaH591AaqkjNq_KuQSeScMn3(agS*hwo26T!df!Aj4`MxGIH~HHE_sYwDOt4Q=sOz zF)c!kp@Zs8dI%-k!8BFJ*xN~kI%@ zB+0-$s`J%^A|^al)}k)mA*}ko*WnYwQCJy13RN6xrBOhAO?eoAui^!&sl3bAZc=mI zve1x8`UTSDv>E|#zqaMp!zX&2v}|JRl$3CEB2FXkB+`9A%2-T*O&8(IR5Th=$){ag2n5JO@w}h&+W1jntQj<66j6OObh>ee zI`Ok2GOI*p`@ZUKIH)8a70_xcp%!CF&?ZS6Xei%(%w%d%+r=w(Xz`cT=o*ixL6E+V zfszE17MR25;j}qDP!&btie$BLeG<0pTjt+ti7%eb&$aW?8@G%FetQ+x^LH)AxS$bRbpLX~ zk55m`FZ~^mi@&tJEl36O#Pk7%3r*093X`b2_fdyS7iCZpszzjt7dJ`jUIE7DsJYN- z?soD{M0wD{nYs^}1ULBpY)3VHTu}^5%|Yx&qg-w-_GXOoYjP<&p`tof)NV& zk)z!~RMsQAfAwlN)=uH3yOdA`7k-ps>uBdi>tO;Ms8!gBdCu-9<)<2O^GbW9hAb0n zq03>R!>N&y#0o1w64$!aL{aM`$tmaNl>lU$ns;@O=tSUw`2lS|ey)q*E?cEFA9UtKa&utVG3Apy<-)1ZeE`L+#c$p~} zl9!>7KaPZ`NdU!8#xqLNAxLt(=-JsvLrn_^KqHTMBAi5A-w=F~!wBR1KLB{8!znsI z=<3H}K&+v|w27c-^qY=CY1kIXIcEC7-sXsKZF;h(AOhtRX85h+MRc!~%l~ZS*tGGr z-KFy`nqFo*-S5}O_oBl|*R7~Q6$e`EloX^V&3|^dU3SMDXj><^hQ4;oEu5%Qw~nws z*y&!_I#InlCBiYp*yGydM2+Dy=*u%5b1Tl^I+5ImyJh|$GiuOz3vpgycuSF%=cxdSF6pk?eUajem(u_ z9g{Dc&I}w2XhY}zOJDOnhm4{k4|w-s1WHpLzQEv53eveSAe(e^dyhJs)@CDl$pWIt z3`0eG0jgj~b8^T&!A>U8^WN11WQ^-Zl2i!|v4?ASB#4tFd5?Eb;af(;iR&HsuU?0{ zb}bvy&v%@XQ$p@ecxIdr=7`X7!G4 z4>o^BC!8lp?^vQDk0%U@SHuQD793?5PWNK9_;ead2`gGpKN27B{|SSDemyS{*4M%x zhfz&XAGu0wkfy#>PSmIaB}&S(;Fd;Kgtbx2J~VL7cmVp(jg;;XM^~F=Qp9;eCM{oC zJLD!FwZwiJj-)CAzXt>iAd0XCAxYsYz%&#Y%_-l8CF>GE*orCI)hwtd@B=hte|Hyf z=R%0++d?hfK#rw77a_6Krq=Wes8oT#!kE|37ao#BEPjOkd09B}=`}j)E6v^#krXhJ zZ*TRuFY9Ad-j@$eN%X5t|-MK|~ybzVgx>12N7x87-tie&JBa zfeS!L0LGEcS87mqn$m=MSkKjzvr;&IvLTC zw{&t67?ho6GC=YX+Y^R&>O2yMig(IS+NvAdH6JmJuE}z~Ao`k<^b;noH&(4IIuD|a zsGz(U;|{!j(4zl%?n_OKn$djOPhFMD?UJQ>m3v(x{&BTW+=s#mdOs-{Z$|B zuSq_nis*U`JGVydaoNLLA9qaW%&1>-MVowQVf?CK@;sWL++If58$op$SFxw3x=)t< zm{~O!JjYEji?5K9zd2`cZmdhQZlp*{_sG|0j=E)4TvU~!Ok1p#+LD;6?b2Y{LVAIk z%A@3SBo~TS_+;^&&QwyBz0WnnCk19d(in6~+%|S1B50+uWM!{jaRs)4ry_%6tV{2? zA<*e8w(xxT%2rAqN4{c#!IRfC48l@Q*=`hSV1OviNqYr;v|ZcOyeWne$IM6DLImI9 zkB(BrJq+}pw%s-WP2FxxSryo(6+7lgNV9l((&tkIgMKE7BHSIAED#8yO4v+r2gkHa zV_~j`2nrWcJR567KIIO=re=!0q(TIwfBsEYJv#K!ym~@d2{F94BJIr~^S5U@o}cFD zWluh=850`?r;@My6GvHUh}scoG6YVe2FuV}{hcxzj*^AnF|X*#qh@3WK1E?lt_Upk zXvZXxCBG>t@WmLVT4h!oE_r3Ay*=cH{3XFW;#;2N{QL0D`Gn98`7)%@Vs z29O+icf^vJNrG>`5l_n2+kdS&x0sfWqUk;qXEv1U(wTt4jvgHqi1H~Lh7U&qZl&r1HOLs-|OIrJy*>gA%J9j7-4g{Q!1NvUGRF+ckJU}6}3o9Snwm} z01hRkkr}FD8gkFZ8&?0jkEu2)7Fb^%)%7?=r8;4}u8?5G0?>e_Wo)qRrL$RIXzF@= zbdM*9uS@C%X$!}mT%3?Q^%E;gNVlROEFsDO7jbY+*mvnkO1y~Bz0S@x6zD1QQo}s; z9%XwaT*X=0oZile#bjkX7-VH-tC4Zx`TBp{v!oiY_i;fO0SLnn75Qb~;fS2fQhZTV z+73Kvia`}oM4#pju^old=#?ec3!c&TU#D7^2S4p(F$6Y}(ujzs^K_x9J3Ui&15@ZS z?*}zspZ1_&EZpU@zX0}yj7_5+`C=JmI(R4{`2$fZTS!Qvue|!t)2{doLFs&k4*;w= zgu@@zxiSnrFOw>+ivsv^vYY-ZaXy zKm=DXMYv`?)1J$hxa5R~Es+1h-Y%aU5N8rvn2rKOPxI%SOH&@zg0uO?UK4$?lg1KYz#_v@bWn3#eMFJyeaFj($N z^X(foeCg4YaL4*EV99c5&=3KbdQ6&iHaiRF&-I)hw@Dd1_!;8_p$Oj1?s?|SDOgIp zoNnBN^L@-`dxs8BkPGK^dl_XL(3>bqx*^j^O8 zyz*zSxGKH8$;!7huRQ9Y^+5Rb2g?~*dh{uu$u*dXM&seK^R4J&mU88PBA~O5;!K~! z(?SlE%CdSv@@w(W=tp`C-lx#M0>-D%&zEOLL$Y_Y-~hI1lj`hCRU!F~9K9Ul;gH$a z%R}pwnep&021#l5zI<8?dRxS*w3t+Sa@@VL-Pm**tFqr?c3+0_Nr}!Wixg9gbW+}A z2T%kR3{=k^`d#~sG*fwBp(JzK&a|!fF1cZ?B#Zdu6dvQ@rt*zaf~Bm<2gq<67$slbqb*pI&q#UD5!Jc@K=q4Ae~p zoxYxdDk|10SlG@K3TOK2Pgdc6-0?!;5jawHFJYF=JTr^!-H2c12F0e$BTq3J2 zSr{x?+ALXlEm?;y*_>XoO~65^ zVYBS%wR|vi+3WQ3q10vX!eyVDWlOCI-?=Hd_7K15DgTw_BLXW_$(2C0l^}zaqc$tS zUMnG?E1{=X!ctel3s)j)Rw7$hjy+z9np`=)vJ(A$<%Ga$jO1#p+G?D^>Pef`c(2t{ zp{u7)ubxR=O(s+q)Rl z{~aGw<;Taq{y)UWo{#bRqixDK1N8@SYWCYh6hn%`S*kjSa0k?Ch@VxVpe+xWii`mrEc-E z$@jHI{wRp%63a?5Vkw6*xAd5F5`|Bbji~|wnS&}3%LRhFe7JcAL2s9@`ik{0UkwhD zSs}&h`>b5EX&73${`VAmwIqH7UvvG`%3FmpliB)Jetb+T{N$zgn@`wGwT88dEQ5Dz zl`I=AetgU;@@;id=yYkxwbM^`)|RDey{oG#jC@yLSJUvW;b!Z*ca6=Dx3$)9-kXeE zztz6du-;T@-@AT$;HN!T5_XWR(>(aOUn!tZlD|*-LQVUFldgTeq|A6|{4iSYEem)3*qg2I=i;N=0#gn{twQ@0t?zzVIX~X!KXjnF8^9I_^zbk$HXPJ% ztC&8aGp#X?AiXW?dl|6+eovy+g$DfLnD?8K>!(AKZPe;$eWU|Rta01{xpE{~SM=-N zW*J~3nPflwW5fFh0DLBGJ(Yk1yW4?L^sX6JJXVDr19zs}hf21e}7N)U{bm^HY2&iyLkFcUG01d4M zAOlyfD(hHPR~n{18nUrgAg(3rA?-K%y9R{FeY^^x{R4)#Uk!_s7yo=cbKLUpw{RIc zoUBC%7L;f?y1UzFFPGIvR=#2W@7Mdb+Xp*8J~<)z=kqIbY4bl*w=cOIJ*NNsA24J0 z7Dgd863b)uYqMcDV6FYTHt5bn@(A^!{JvQcfK$m9NQ>*mM)S|YCE_}5r8-a4ost`N$MKAl0YbM##Not=GnfNq3qegMT>Z1WE2~bQ9#p7h@;~b;8 zx)e@CrTmY4Fg!GKwRhIBrDcd^ z5vxlTb@ys`-_N{(k_#2fVC=rf?NUnOF zmyww}g3Um|!41XFfX{nn?A)ortg$8FE&htMjc?9Qenk`5kT<$o$?%JQl7Zh-|MWD9 zCJK-&tA-wZ_ma&u{QR|+B;4SdcC8QteXFBb5C1Rn-uxfR$N&Gmu50$OT{HH5EFq+^ zOVN;>G|EnleaW7^(u{qrL3U}#u0&;x8j__XS|m}URi#2jyECuX=X}rm^ZlN4emLjX z??2#nb2GTE=i~mkKemyxW#rfd1)cq&Yi8L8vmM#Z2M<3dMz}a-9cMSX@wK^*+00(9 z{B|LDf1CT`+q2#M-!4WKw0XX@dE7t$tv&H>o7aaT?T}C3F41>5XhXJh!x9@E+50c} zir#Vk%Q7MPz*q^J4oo4p^J%7%F7=QF?TVG>-L>4>Bri7@9!vALK0!AjcLH|QbSyBP zPN@R`qpe9ADF>j-RnrM5jtG#BMYV>~kTJxMsEU1|8E9hmQ~p(bf?_0ZxG z^@?d8;5ktdf@kOy`yfV|Cs!FZMZu`19!jsa->!Qz2Q8$|dG$3?UKl$}QQA|4^A`i8 znki_BNw`Dgm7T_rs-3DjjCCbJ%AZyf=WL5qvzi;5fWyKC%ZENTj2hmBwSYuZJ+i=I#J2U107P zC!OO+)UDlTf{Y>}MPEHgXusK{$p^S4SjO#Iz2qu+;yDhPC~q5qtq=y%f-Dr-o;AR6 z%)zkCD9WJrc5NFawqI3<2ML0|R;4MtWVo^+vy^f4{V*nfNBOu`JN?Y|bq40C7$C?G z4xQBUIeO9z5)`$%`;~VM?LvC|>)HMc8z7BA(;YM2(u^FRh}BlS^!qh=>|VbgzZwsj zMoN#0aJy~;*9eTf-GTnlaw9pk{=3w&Zd|9y8T&7HM=D5?i81u>(1!wcB&1w9lBBum+O z8|+xUVsNdI$4B`-Zr#7~>S0oJ5H>aZBa^rK=lY4wU%sU2NT7L9EtE<>C%g_KY@b1b z5!NWq)YSNc`Z;lZE70l!6J6Gc5FckdX#)(*?{KWtqvO8(Cq)h=XWSE})LG?spvJn` z(0%}ten|Q~cD!cF-vk=aO%0Y;G$o`pYi~t4IS2|&*C@tDeW9>DPmJ?=k-MF;<3jE; z;Ou#My2yAt&%w7Ghz5Mz6ceBvi(?%PkPAaPU>(<@#2s*u2{w|22}c8w9FJ$Zs9f&n zlS3C0qvtdHNR+_MZ^DrY@VpEB&=QWB20AyxxfoZY3ry-b0fW%$wn!k#+YpXGGEgKq zEw$Ug`aHBv8TO3#PJeSmQ6F~ZAnG0oAz&F)eiU}SJqThB3Q zCi3vAE8m+;i*K2wTUl8E7gt-2KE4e0H*qgWNiHS6D)CNGtz0NJ$+t;D6aFVJ*W?%m zZwoMOl=N)^JPqKo9zsQeWP35H`HS;jJ>xkFT$|_xEx9vDDWA^shM3b3ONWKzJc4G) zpRPKOH>U{J9=3SFdkMyQujNCGf}pNA0nkezkS4|g489ABujbi0;islq^UN-qO2hNn=;`jePO`x z?3j=~RnO+UAwYLWb?#CPKwJpXYuZ)Sl(VaHU)75YVyhC|rR_YDMc|{TYcp~B%q$WC zy_b?EE{9ov9Rqaa;pNcgb4Xe0Hc^q1+X;k2)^LONQG6kHl_SY%3+q9qf*zcMJe?>N zcA7_F)nP6;CoXh zoS^{x+2{1Z46~&Z22Hr1+*MR6xSYsJt_5Z@g>Y=YLzDv18I}Qf_&BXjgK=0+6Lf!D zORsf*nj^HQv6|p;-p~Lf!)aOs+A}xe&(Q#@X&{E}WsnRvxWR@LBq=HjP(FXM&_^*u zsBbe##6eqF9wf4k=?x{x5!|5YlmKN=hIUAreyAghpynL!ui9{Y4G<IDh(XMScq+IqpjXY@jlECXAA;6sIqam(Y;CHYS4o||y!%wFq?_+}G6Q+omQ7EV9ql{tm?r$9;M^UtrsDdfHL!C|DB@{^ zpz4+_Lm|!wLf5fu3l!+(K3EW~ZABl1`v%c+!J8{6u2z45G&ZXh~2eHj=u7K2AB?^>a+h=kdgc)X`zu>bt z;rnU?6-&sYqwmZr!V0)7ydp7@4dF@I?@@>*5+jF+^%_l)BCv=K6}AKxMT&5>30Dha zb7*yH5;toL)5#q^4HI?9+PJ3K2&rX4uq44>6#8`Ql5rt6uMK}mk0DHerbaP;ty74# z0~hZot3l!pIpA;={5~M=H}|hK89_9FebHgOL-rETHRIZp1m`h<8Q}Pq8$tXh*Z<%N zF#tpQxR#9uilDJ1uR&*kPv6yFH$Rl)ehRyEA)nVvl^SNnj1+Q!Hk~p)*$R?i)P;$F z4;F!fnjPp`1epXZiS!9B-HEE?YXE?=Fi+hy?_D;})&ss1(HDiM5iy3a1UYdf_M#dI zOnw&`>2_V18|x$!B)IMwgolm%IBeb#r^BBPdk9)<@S9u9EQ99Bo3OwZoJDHCc&crFP z?U&L5Uh>Q|4&CG#3aDTmju=H4+uS$v?Iz5i5F`)WR%bAJXh!3%f;Ro!ueWd-8HG)R zPk6#A@5L?0Vt=7xXt3+uVKa!ly>Yt+7t7BHhlAosr;5 zMu3Q40+unhzd)3i=6K=AAzAW$rZxPryB3Z=D$0tp{@Hk#k&MDbqdpP^Ev6ZRv$=(V zy}Se=PZ7S4g55!LRhpn#mB>m+%)ZV(CZ9ykT{xopi9&2p&7yQH8RS_IY+4OEM8&ZF z5c7BlCI!UX;|y4Z5#h|R0v^z%=97oK#Av;+#i5KpL@AfBrywM)^ zN~gQxoq|H2M4x3o-0fFB2KH}8OH5>CBxZ7lJtS6vn2T9Yc#@cX{(?YWscU6wVwNze z$pw`V*j%X62>$7=KV9OdEHcd;x2KI~b+*EiG|gyi=Fvswj!(}5XNUrsnKaG3?TiZC zU&618gx&lvy)==IdaxdFBg5pC@syORZ;m6NoKE$xTJ*r8gBS@%=$B^#ejj zXIo__S`R;yy} z!pgAhH20fabQMm}e*gwd0B^s?ml!R35zbFV z2ROYdRLTl-opNKSK()$ zTHt!zGN=H`djk zuWM|rlb@5WZ-s~4JtA_#F6HkomF;;v0C4H4;%8)Z$npImV&sQ;^2la$R6qw&+waQA zp)cYNVTM$|ihMa}#z~?1QzX&phAOPidLwMI3yOy77s#z~zQ0lk68xgdE-;4M$M&KK z6Z_9!C#XifKDy+4@UGG_8K=bjfbwCFzdFqqe=%mwDf_gF-s<$;Ez_N}*13n-eb4R- z#q!G2SR;aUrv?NAtG-};795V74s~GjJoktK-u$154x6+uiJ-%FIQkg4%_UCqDw@#Q0`8AtgRy676DYU>X+q4`W&+ZbmmpoL_+r|}45hRa z;8yt?CyNxoGydfruP7Cgfq#(_|8Mx1*NLA)L8e4vhm7tzNWlP-dQluEb13aHT=4S( zwf5qH9;{s8ocmDtVs`YqQKM$LM$7D&E~uF$cQcJQW@l^%-Q}~1fWSwnTlG5weYHeZ zsq}*!;(3n8-4yfx;A0*eVe?&E;m;exXWu$644&9R%Xof|dU2~j*0RR)$A8DiE_#pE z9R3ymX>sr*M%L?h;`-~m=Pb{8{Yl>V_#b@i`Pez{t-tjHAC(sHI|qL6&emVFQ_Ev# z+h57kxGH0(R?qk9{tjJ%uLq+{!PhS?{ezEn?#^lr#%Tf%T~A-Q3}lmQiPt+WKvz{B zHh0dXO7H?a+*gxYK8rg*YMF0xNFD!x=|!zU$vX{3eTsVHZ`hK$hFvcOXtx3j8FiOr;vOetP>3$nmHUW*LC{Cdmo#o&o9qy zVLNu6f=@f{YBqCEc-{4QU40eE%vAz#jcFS6p>(M(GkLpJ{B*5+di}R9_am3?Mp*XA z&&@z0iV~o~y^e3emVkWrIMh8S-*Y(O`3`>9^w_i5oljMpClU8bzr(2_IX@}ti5R6` znwJa2)td{xcz0crFVny`N4c@rmy3_}4rrh`3Vx^eqIdZhS}OJV7tb8QX6}*Pu*xW- zP#Ld_gBttZ6gln5-gnEtpOac{=sFu%o2AtMLdpi~(=K}vL>BQG%O>_6vY(5HcCC9z0 z#c47qIz5WV0Go5@EA{E@Eth@Q6W-jjJn5n+XoI9v>RhnEj9OFc%k23c5|VH7t_<)U zTrQWwvTuA9o~Bce&=vXXvQ2(p3Na*)K#wd+(5z2%(Gkvr^m-V+kiMmGOO@d5n+l?6 z04~WR_bNGvkn2C4u~Vo5;*~EOwmM+>HE+BJV9|NF748yi;99yV1r^JaX=(O??VkX? zoTx{h_sA8ppFUr=lC5Js;wy47fT_|9*#Tn1M+WN6wMy4~MO-W8RDCS;x(TsVB(UKs zi2Bqwb1Gp#L=>cEQ6>T1mpr$HVc#3+vHYjA%<8j-9U%)jBpT0Qq|yX4w!)DB*4AH1 z*G*Q=H^7ugx1$!tGX*F#&yaVol$`o(oJ>YyP1o4CQ*jK(%lAur_BhSvr>Xc<uP>^l)1DS#%tn%MeO^7bs}*}rTA0wO51RIE&Px3VTV)-xcHdO7+x!y zh^=ws;$y;c>CNeKA?I^!gaqYMD~Cxc0fo5odu@@2-@dXKP9us5>7m5lTP&9r57vFn z-Al-}2e!?;nL{GPmfIXgBnl1P73~T#j%@jV6J%sOvB1evDQqH9Fg_Zv-fdIUC-Yv` z8fw-Q017%64$hy4tw6Pcaqm20Lyer0Qgp}*I}St|%vK7D@_7`ZdWJM1Qs&!t7K{1X zu=6&lNB_cLE{0#nvlT1aKYB}Jl-wtEkDPt{@!g2T5{&2^lw~rxzbJM{&1>U+yOv@z z1#__D-p1_X>yAq`MzZe~er-IyVe*8)s|4)kxv+TyW6^OyUQnFhk)qCfIRYg^t-$SQ zHbuA>h83rZ;?rEL8#O!32C7&SVE}ZwtuO+SE+^?GHndZtJgAgs?9{5g_l}tC1FdF$ z56k&)S-q=3dzrd62;po7!zu+5wy=Im9v6ymjKa*e2S@;p)b;x5QQY<0*930^WMWNQ zy7vTbo#L8xw;io~G!UrwCAYpAA6)f%rER=E6uG-~rTQDM%ejwF?wv%(vQS3BrlRxH zSr)N%!h^vU`tviVGh^$w8HL!m%-=5?jcwE&46#p`e{c>R*KBSSda!K%VUtB%tJ7ep zbI<&vOPO&O0*sEhKc1iM8I5a?8$9B*IsfD-t_{N<9tut5E%Pwr*L zUu`f74|RDu|9CXMyK68!BH`)N=jepqTSgHvWltC0S|s#88jOhVdAj&HGhyJhQDpMt zr_VM=6Rv+7j7-^l`g{wW$VM4Q9ZeNo;9x8hhlQ_4W$G_131lUXY%`9|by;{JI+i%9 zdp-J8!oo{gOwzcyaZFL!!YgIVq}xu{V@i7#Uhm9GnhY>LTKRb4js95D)c=Z)EiPMH zCf_f)9^0tD`0hYf^21B=0WDdE|Fg#9|9=jv^1po!OXc}DhZX)ehduFs%V8~}u{szj zbVK6*nZxREH6H&xhwZ-Q%gtevit;R!T3$IF#r_k`)SI5b>e$(kw`aBA6k=+QzxZzXPY%1xN*4)TuKj4xK2cnIpo^T1P&1&EX}&Duz>|EiTO970m^$tibT@WnYmnlOXzxsu+}`IW4ju zAfbprb=9ZqMHinkFCWA@MzDX2gsl!?l`pIg^WN*p5JF-amktaq%tSQ_1ckK=-A;~6 zv)Il8YAFVD%wiFvU=x&yyObs@bi;W(jbdw{8fohBHMxCsS6Lhc?8sk%aVkOu!#wKs zwDtY!(=dWh=Q~FSI3Qq#=%!#DBkO+>m19l3z1277{L8{Op8S);`srR8bexO0Gh()& zQ?W42C%gCIFmC6-7I2170V92tLcK#uqeQ*Lo3VH7x;?V6LA-kOv7Z}2=hYnVh~1ac z#Du7to)O=d&}xKtFERW7y729le3U%2my+9W()ud{zv%zrskZwtT+h2>GCS=Tx2Rq- zdt1m{d(X{Vo4Ql$ILXuMhb?>ez<6v|G?IVX+b+q|{#Q6v0LXs+XO3|0(my%uXXE-` zU%&kQ?d!B}>(BSMm$v?{KMFJ40*>FFoflz4#;;Ezat^=b9cS13Uu3}fETpp45Z=9G zFORwvdgr)FG2D?x%AZ)k_71`G!M=A)Sh#RAXysLShGM83Z%`sp{QhdDe5V|L!W=<* zeKkvLO%C45G9bti*RuJ3kcegDBT9yAIo$A7sLAStvls&-g8kkGT7IzId5Op4qk8>o1yT9urQTYN8P0d^P$H*NR@kY#(bNAr5PoCXLnl)G(~%rJ zx5n*FmE*~oJjWNtHex&^75)AI0Le@PyZ%c>H4EN+tFTRu7#sKn4hzI^XKG3=>zPt( zPb4zaPIpBhfN@F)Ff-<&VTRrIwSk;vJ?VRj0FBx;Y8Ai00wYtDcF)GAS}fa;nn*M{_ouB9kKl=y~ ztXy^W3_lW$swnsO!>6)E(i;q;icN{O1l}ze1Qg7-1KCmcQ@L|_?YBe$b@!`jSWY*h z0`THne_Sr}sz;&-w9TP|bFH-c;XiDQ4)gB$qHY6^#rLS@kX?tp*pQ~~5Gp>|3+Kpz z;JFsm93J2grXc#SvQgExumDyV66UlX5kCm>QJoNwTO@r)&*CqL1;N>oXh0oqYpvx$ ztpOTFY_Dtl{s<|R4hG0}A*gYnrzkdhmIvUQxoV0))6v~O7vC5>VvF|zscl@h0(N8w zqq%xY+xL;g+t&;W`^!aTlm5?<3S#-empu%r{*8`F+T^^PZ_F&B+w~%p@mZ_EzW>)#Kjh6PF=30U8YYuqd*)*VZ|T=6?Nx@%o$rVbkJ#nseIdcGd_dLi zY@P_ZQ99)#m&BKP6iof#Iz~F0r6BtQb}tfS(PJBgbVBop5bArc{M^H7bZ-9w-i1}^ z`G_q*?Rd#HCEeRAVwJJ+8$n!17!&XC#K})HU^BX0#xn~23hw!@Mu}r|nf0XSyugx7 zdYe%VKvZG@D7GyatYn2!qy~P%^I}y*#*zGkht|9RZ@gSXma(SPP;Tgkhf2@g|sl1p?(QTq4K`b%N zQc8_!g9Ub59sHY>7M}3K9xY`Ce8;0(tFkI3_KEtMtXVz7y}1N|HPIp14w5B zsV9O(-xxZ;%>vAwFk*{M7@unlO2Sz^|N0 zs*1FE5JpX7D%?d&4^~mUu-zRd!T$Ok%_iw zf^_lpt>6)P4{WXIRXQ@rp7B}WzM(L+3nd|gO;2vI1eWI&D`Rm*BJ^F3rrw-sT8S zvQUSxz$KCuYK?2-;4vGQ`O}1gI#Y2bDBp29G=s3@V1f*Ud=1ip4utodjEmqAZvLxE zivcJISbpE$n~1C{P!=UsFHumRtTpo*Qsp>sBH*V52e1H%9gD0`xT6Q(nq%&&17J3jm{fRlJYKBDxV5A3%S>VRCi)N=Ycz8j;S*1+ zMF>#52_~3(rEpn^n;{L0mP?TNA+EEf=UCK)NXSCsJF>YUx!|gjGgr&<4o=*bB*1{C z;trPRJCm4s`+zeT2b35+j~jZavLNy*6XOsLkT83g%zKXj39W;IQAvGq#RlSDDjPvb z-CiQF_lK@SYZ-PdkwRV*C&!FXlmjT)5ril#TWtV-3VTaMfjmkP{7R9J9tL5ZQ>dA zRMlHiC0`45y{+iqrO=ra2z6Gp&IU4CeCBk*PwEj0XM>F2fC}AkN~SG+HfTQ1d#cZ? zaJG8qL?pKRY#7S>!&XM9aaT}!DO~ZUO1SZG<3`n)Xi#+(WCWDZRu%itR7*zD35B6( zJ_N@7|jk;X(A7}nJ=;?HoO z4Jbsqs9-A@^|MQf2#KNkine`}+l=W$bZWpi$SbN<$R z^QoWBOo^5v!`h zKJryplbX$YwV^G!t+%qR-$p^0b?zEoVhZDMp#6pojkw*;1EBB z;OcjvGznCrC*Kz`h(4NoX{K6BeRi{^r6ePejtFZX=a#GOXAr2J*QIhD2+;I}a1C!AGo1py-3j4T$fT zOW~X>b@OKFwe~xDaV48BQh7BsKf^rZnuFK8KE(OHK-W5!L`a6h#H|gQda3OdH@V%q zev#eY%H4;Q1Ix=R_E(yDzrA%?mQen9Bj}M3>-9EA9!9wO_Df|9znRc3_iJ6APrJN+ zbuD4aB=Ls58V z8q5a=9wb~aUvi5mgOlmkZXFRsvc7;;oYzpS#yhrcz8Q}GH%2@Urd+{=)49u%nwPkok%=H&6Pt0GGusslo_oq ztktQwgwo`k5ar|~?h$W~60|ftXvjL2wzVQQ9-H7(iQ@&&R8onD0Yq2^wxnY`f9C9z z8l1iwS2PFAv=Msmp!>4@|8rOf?Yk0Gs-HWy*r#B21g)0TIjiL)+M6dl;VER>55WLaEAw z6y+%vJ&5kSWRf)a*X~~T+e4L($NJ8MBPWN`et4~Y1IL9+ctK zFBz03Od=T%tuG2bnSHQ(rY8Ofan6kGP#`D~19{vU+CBKF5%f?uXUVG1p6ficF?O(d z^kMKHabt8j16LNQ2B-EpiA3G&ORqe)(G6_UV)DD=jJgypx>nJJXPtw?s>+2ofgJ^~ zPx#}ojL_)5$mn0QI8DciA44X551>L_<9PLNRYZZVKHfFZ^BYxQ_T2G#?r#vNZa#$o z&zKiH!PTBALd<#2sB!9uV(5wP0*Nfl1d4@mpxzleEa5k zlEn2Tsb@ZQCisCj94 z{pFr#FOC1cq{zH7HGXC0^~xgUl~v6vE14%Yr(h8L?=6D=&l1{1zyG}?w7>r&q5WpU z|F48rygG{8BKV8`F9|LBKN8v<|4L|0rjh@&2wvo!WVCBA9lN@zFU{o5k=@7F8ksY1+oW@g`OaT?Phq=5?vThvzv zS_C$+>MY-!_YMas!rtlswg?PMTAEU}7^HkcAXro-d0ZB-&{#wf4Mj3bU5G zGyquDmh$NWv@D7Wu$pS7)I5EOvKuyF^65x-LV!CQYjzVdk@_eA;pAj5KU<7Sr_N3I1$z&^Vo;GqMWEf{rj7uI!{l$$sB z|EnyJ5i_CDOM>431Nj$kF%M*IuSr;uSK~JG(61_Qp+%=> zQP%1Nog02XP;1Y_iwDXk_XZ*Pku7wlv}5ewJtZ^Vn4@@%9Pi(a1sVqE^;P+5%a0?AUR!@Lg&_M+c#9;E4qVGyRoMI6mgS5sFAPy3du|HKc;LUY z|Kxylq7IK>yu}cHeP<%#otH~|cRGJEnQ?kVe2YuYPUQr;cJf5x?0PB zt?q_&Q4rSX_srtfaf2Eq-ok9F0X&=~w2$$sgLJ@7KDH7VQFw0^4|LQCT|ppJ%%k(} zGZ^q2mr`D_ricR%<;5EI?dzZh8yG3Rl<53Ax~u5GDc=@_sFgs=Pn>A=bQK|2I}k&{0WopNRjN$4emFP)Y)^iJE2#cOSYb9y5*)eKT8^HKJ-t$2plQVZ`ttpOP zS&%PNP@PbS*JmES1)EvNyM2!=qqp64(;b5<7URnI90o~$-`mwxviK04YCeZ!=!max zF?&?rI_x-az{DNx)N~j&e~xg23MnL6fW1vq!7%j|Be^`zdjFw2^RxXMT^;);tpuQZ zb6fKp-3@(6!1?L9doMQ9k;v32<%5j*sg<7Hufk1?VfR;tn|;#-?XgX^i|^ex`{(Yq z$M@V>{FJ6=y z$UgQ@)G=COSGYd*w^kufpqKBpdz!?`~UBAfI=pxsqwG?W=x1eBpp>z4Ryp#J=JaBO?iVQVgfZmXl^V(1DTPnK(%Z zI7HPwcZr&%576NDj;`Z+ya*WU4_T>wycGJWZ&UDvZ3ThAk zJwDHYmmmkQ)>|063OwmXVXrWP7yR`jVu3-N(dT(No zNX;2Ty*(csC;B1&aAsy?`UCgVlPM3THo8w*3INSFDa&NoGi&%`TfeDkDvfEfGA@28 z8~Ln+7zvb%A)Ejx#H}DKO}CsB-wXDdN;vy zT|598Qik1kaFKJCt71nHk5AUNC9v|SeOU>df&yfxk;SkxVP;p~6)k~Tx#JaONCwD# zq2$VWE!||7>3Hsq^i&jwyJX0^>hK!Rte9kW5 z2ztRjME(4~1l)KZ8s&q=5_p&82{9AIF&cV^1g{KhAeVR{2cFM3AJO38EcBUQwT=KY zY10x8>_`IWuGT(h#qfZ92aD@NhN;N_9rF4iyMykd=l~~{2JN7ebvkN@wXW)5Hn8fZ z!Gf4Bbtt<95LBZSNjH|}GWG$~1TB45h^b7a10#3V+xmJ3ybjuSAM z408-3V@}beE|$ByibNk?CD{PLV2Dq2}NrAdzPev3DJOt7APQqIv zXs%ai^vx;MFJbc-^lA}0BnmCk=D^a_xSoMjr2=wj=6mN9vSt%jjxI)t6c+Dvt@UW( zV4qO&5aD0WdyCD(|B#Qh<|{A^S-l0d^^>(mLC^j+nJCbuAI3+4cXiv;KM4PWa+4)Q zDAA2Xko3LHsumd+`cP;_AKKG08TmA2H{Epo64 zQFyh=BE>tXM|i!V*Wz4sReSBbo;QV+{EVy7Z*x^F;LG1dp4q@?OPWX&!`%^^ z%VWy@gt4slOdj!6+o)<)(MX-1!?y5j&n|NdNR$SNuafK&g3q=Qf`7$jOZMk<`W4(3 z5e1Nr8^I#A}_)nMP{p4i$km4J z(FyJ7u%EV4zj*)#85KwG**(*~)!c+H%*e1HoFWzChmPP^^V)+^B^^u#lZmUAL~N!4 z?29Cd?>;if!Xi+s{@mj?-}C@4+gr@Xh;iLxV zRYcd3h{aJKsIyQ~BwW@4smca3JcgUs;vCV@J4aKrm5*{fj=jdj5gm>y9s#W}*Rei% zJJEyZT|8G6kJ?zrr7Im(8;d)xPsW%8XIW@UcNFuIlCF;3d}JrNUY@ZL1Nz-2_)u_$WF(CYD;8mRQF4ApKGTl!IZ!d3LCJ_kBxY| zLSRq;fQ9Cx;Fetp@B*y&JHqg=oX__TJrm4pD>#{ol^7UeqJif>9u9O~hK4SZz?`Fc zmDW;n95je$ol{*y>C(%zI(N#`FcOBA znj1cgjfg+;bCWNiZ4^l6i>3x`QECmU_JgFi9?+}52rAPSgDTA|tU&k7biLW6g*u~M z_%^8}&Es=BZ)JN(ItNY-fK5*{B$-KawMZ)igPp6>_X5C@?&nWmRI`(a+-Qw&8Ga6U z1l-v%JV@+b#YwUT$G?$8D4d1M3p?b_8^5}7uM2+z08&`I+}JN}0_IZTJT->rRBw5U zgeM;nnpIfrx^T=UX#Q!cJCEQ?9!*Gr0~)iTK1m&3z(-aD3gf-%zjlYcVyfApW%E-P z>C6b0J681mY42gVn~9(Y8?pK-eYcQd^cTP=N)$_mv*{?eKd;X%z4mA1FaT&)p*KcG zLSPm6YBe0DiBkK8Mp3b`^g_&5=R?)n&@|GcJto)`%NNJm313^@27uuf@6pf_n#_E( zdJ*2f@s1~YR``kedbu}=H0y%rj*>4)oA_F*pOy=WP6y1h-)V2nF; zA2klXw+-WO(gu&!fX2#jX%!s!D#imFy}jp*5{dh)5sh>J-F~d7IQUaVkB|I}x|08~ z-_EJ~?`s*BC%HDw^qC0R`FOF+=XK-HU%fuBbbZ+1my@P~w(T#s`wT?z1xu2rw);d! zDkX((SQNdDxs+$_~j4|IlZe;x0-PHr$OK7WtDYh*L&EwiVDL*0zA#`M@{2 zkgUTS?YX{f9Vm@e8vj=7Xa;(4|A~7BXy8}IaT)!(@;q3Yb79Iez}g-*#vGVMoN;W3 z`J@iwDYV^zF9DkBZo_rB7XNr&6#Hccqe&Jy)Gl7=J+w}v-G!a71mWO!*g{or(sgJC z^(*+BfXTx%a_@M-4WvVRLQ}rU+hwc?wDJMoj)ruM;Aa(ZEE~f(3CB`S#~hIQT#1d% z!a*?d2M^$_M^5M9kyPBV=MQ*DH=;!&AQK>d3&urV)Zh9Jal04KB%&-I<*uTqtgx|E zETR^x!FPJWf{kDR6t0K$#|?Zf9*TZ>VJ}Ru;hpr&T74KZSwK)`TKVuodpanJPa)_OVxGUjSw? z;IjnM833=0SvhsdG?P!7E1`9GVU{br!)v76;ibhXX`>XR_`z3JTnTNBS;c)0szhcl zrFoSF(JPP@S4S#}x$0WH>cg;QMh1o`Yn4a|eKDMIcGrI-v|hI=ojy3X%LK%tc%pA+ zb_Cq5F|Ts|=-wT^c>SXd_LFCS+{b6Ps$4#M{Vx()*EQeK0_nY(QsSCe80P@=a!l3( zr_LIkL`%DOq5#;r(o6M!NN7(GEhGT^mLoI!tjA`=v%wQ-j}|WT0Q=B+TNeM-A`tZ2 zl?}4tmfo}fwg@(E@&SpDK?PkK<@*Bh!0p5Twg`@%I21xf?0fk9-xfhimmpU#WRg*0 zJWbz=5HKTiF|>J(GM{`lo5U|t-(kwLbAXyAU?9fxUlQ6Cj2zLl>`}B5pi_9=IoHyRmmMq>PMc|2H_51A<)nF&5%eFVFaG9Ehia^((M!8zD;C4g$gmujt8)yMHB#q~yX54wl<=FN?#sb(D9J#oF^o zxeD}|M*bqke&JTQBUjt@b(f3xri6-fb}4xrm1e(&%}YaOYs$f%`BwXZ#_#{M2y|_g z0Ah$$p@jf(l>~8h6SwT;UWlZ>>(WT?vjAri6$Rqip`VbD4(k^X(Kwx8zPV zj2a%fs8%=25;sl6zPdQ3^vh@`$mVEuxn35aU*VJgPO{n-M&8AvGfh(;xbx;(WCpsG zlqT`0m6Lk(x!*+Otv?pN!#Dp_{?aG$2C+${qGM8_J5#86UsMyV76y5y^t3Z}YFYjX zF+@@885FIVUcjuQd6Ff2Xzaw>)ZRr`fzQ0HiU~_`0zcmyIIR)rLpxMCtnD;ePt7+lTS(O*~2K%@9NIgOFMD`I25$7Ba*l@;(4NN-6;4H?-M`+WQ0;M`O0% z&)zS`cbkqOIWhQxxsM9h=(u&g%h1nznfhlQjxl{r+j*xBs5k%^p^kk({;h0X9qTM6 zcS&4th9tcV9Ax&IO;KlZTt?(=G^QCs67?o`Jnrx(SrNAzlk+Si zq+XAo{i=Hjccs!#=G$Dg&_gt!@||*SwAa#9dEiujPT)B4ssfQ5 za7|(YrNb7?THymKty!XX6Nl3%oNSDgEhjfv`Lxh9g7FlR&$Gr$5PUG zk-1idXUb%<8!O$WQe`zg2Mooo=3WR(J9Zziy?`kiF`?7AEqXWEKZ&*xr5_Wd327$v z%%bN>pB454{|9^T;nY;a=Y5}(p3qJxfzV8l-UOtBn$ShTgx-XJ^d=x6B5DGmDjE=w zCK9A$0R*XPKtP%bDu^9a5IcB@qM|(U+Uwr?zIUJ9XLjd(=Y40M{R1+?OlHD4-{0r^ z`7)*W+Z?+a2Fx7+K)KuGw!XTBSSf#ReK;L7^#B#=qu5V7VR8p>JjgMWutg%-`kP>? z2rl;Fwlkk-dAvVJUw$ZWlI*76+fqXOhuRHn~qjj*KDmEfoJzM!ow_Eyj{`tLp3GKY8d-q=w+Ldnit6!!r9{Ec` zOPFrXw2lmr=Nw)gD*ka)l68FFvZpqcNdqWitCtoJ5Q_4t0deE-VF^t~zb zW`5uKErPFudk?Sl`2FIy2-cA?Or$vjCON}H+r*?w^fFLJGkqc%F>EDsf1LYFzvNI% zh5=vGv47_J22^a8wRwQ(shI&4o7f!J-T*?!%;2Vs*keKFd!+Br3>gi@9#81qBmZ^g z#x_(OC*3?yLGr<{txa5hpvsugJZGbVtS`CzkG%Wa3%y_7yuHXnX}oJ5AVi#t){M0JO{H^bIu{Z9 z-nAJ%VZebX%u5(xU{?Uc;b6?`?eKINKA#Rytf{tw2{`lxJ9rm+<^BelLq5LyZ=YV==C*0;e#^ikzrNcFwdj4lV0{3W(Jm4tI2?k9Br_KtA{L+q|gKU~T%9w&b=uD>oXuZZ3%SjFev z?FJMG2n+(odvMI76KrHtY-kFABLFH}+{#vOVc{bI#1+q$m?iJ+!pC^x^d7PPFT!0{HyM9A zD2Rta%0w#GX$V0_Fy-%vhlNd32a!tseQ-S0QF1JDj z?w))W(z$>QT}{P#HY**A$=-42^LY3PF}n`-YlYp?oBx~&>>L_@OBX_C)-S*t+~DSd ziX{&Pvq3>p>lx1-{&V`-kl?r095D6dYXnyH#lPp>0U>_*%YGtN`g7$!%vM6V^;RnO zlQ~|WtE6t$+Zc^b9#8&!mL$|*XKQ~azw~pps>ACTbCQ!Ot!X!+t4QGT{G>gC45eZE zn}ba`?I16gj08m~l`v%eXLn)}1QaCSt2O=2yEnRI>pNFCt~7ewY;@}wow|^`(!}^T z-myj}1#t!m#u*UQ0|0EZgstg$J9rgQbSuCV=Ckx9U9^uG#jpfDDq+M5`egq zrBqSlZdPRFwfHN%gXmW9mFa%c_Z14t7y!G4SE{gty&qrdbosr1!IM`)2!P zOmw2bl;@kYB)bis-bES4yuiL%y+ILf<@{lhE+^QfCNZ)1=z(`H*r61-nQ%+mfnI;$ zdJ@UlFzXmH?nSER{ehb`y6I>Ocb!XZIp_z=X=pu0rn$%Zs6gKZis{Z-IsX6K#M)7z z1w-r1)dEtorAiF)4tzs(L7$J9e4_4t1$Sn*9=Lu`5pG1dVqA<*DmQ* z5U4o!Oi)%<<>t!{=Cs_)p{!H4-_Lpk?FaR@m zKWC9eBI(pn)=aZXzRJFG@G=BYzIYH~wW^cOQ=E>+tB!nAaI&>Sv$wwa;$?LOKDmF2 zy4ZXkANUA|J@pW8agmTjLiz05bGgpAW#5S>R`MRxiu@Ne(FxvBcvrc#2cuc3RI&61 z%|d8vOjOzc(<1SjS=LSf*cG@>`KhekM#c4wTD=tHFPm&4D%JiLJiAsS?7r#Fb>-mD zJ|gVEpqhY!7BG{#vhg*LeKaueamdS#h+E7SR@*CrqB~O0?!a~6Z_#$za{o&yHk6Dpx>#H|*9sc;ovR+CtOwOnK(1WZ)`mIshiYc1w-yg02 zTD^Vk*Vo(YzkcxNtEHGQV$z%U8dGqFDZI*rq*$WHtoLBBxQC*aP52H& zs9?Y7goJ|}Cq!~_gS0Z#^d(@|7Z#pj@A(x!J_SlQvo>N#`U&8!p&(y0Xw!aBHjn>H z1#Vx7*u1)7!xFNmW=EnD6u^LUJMgkGy3)~KZ$jZlY*iFCto zSw?sgApm0T<_rgm-0>T_91L+1#;o1DSAArbK&=@cfDz88Md5vEEA0Ue$_)Dz-*6`C zvvu%i6$aTIl35C~u=Aft-(!RdIFghzK9{hO9DpMQKkXzbtorPBJ8pg__sz_4+~A%M zog3*Y{v%Q+jP?9O7s3@TpZHN9F=H1IZWx5|4@nAU?Z3RoC>UgX33U4spt{Hre&B=o z<{N6r*`v$>7#ttB6KnOs3Jd;Uq==H0unkM3a2<#-i;~ju6Pr#FrG`t!cpI(;ps6sq zYzkr>1$1<}=o9yRTsg|WeTwUyJe!!i!xa>91DkB1&xHJf7O$OX;Fh@P8UY^;z%c{n zn_^Mw6cgt#{x1|%t^{T9933A>IhaTZ#o&?|9$0c_hzU`hgMk5=8O?wRa6E~Xj-X%) zCy;3W-LYZB6bc$a!XD|%fX5=EO^Qp%+4=R75)@e7N__i#acOK&D%p3=AhP&dNhPtg z%A~Z~v-BsJSKFmfUs9^p4{i@GIM+ayT|%0W!e2?2Nd%;Kc9r!$D7*Ttj7Kc*Hz^+`Hxj?<@l8sQ4lR$hDh_!;lKd22$8&AF zCw=4$K=HIJgf=|nI&kxkH?6`bV2D;#h1h7hLX=^<1s0A5`2Roi-E*)%SKHlrF6heIAAjk+KiJh zrFfe%xo9#lyegnMjwV3( zu9TVcAY)fq1Cl>;_%>4VOT#Ho2y;|SB01i4DemB-%ib(scNtIJMtEINL_#>Ev*bN? zIY5>MlSCcrNvJZ#U$$d<7Fc`3biwo1ot~3^o@mCoqC7dCyS68klHhIRk$W={;xFJ5 zp)?WTC=k*ck2x&@+lwU*Pz|W(;n&~xC^dA3=plwu!2<=K-ALl}s|1O)3mnGm`H>8K@HBqX2 zh?Tf^vsN6?lHl)NWwYBwl50AT(JF{gYXpzWH$pDOKnIpR)^H<_+80Q*|Oof?-P@&OqP* zIIa@av+k;zoFZYYd7U=N`nW=BDek!?aXt5(%(XAz&Z3dAmYj%pBUR?3?>l{~+U#&^=)8bY}s=Tf9Nx3_;`^!l}56xi&d_GMLU+NCG#&g*uvS?rWF-3`Vg@}Q6LuX%99VOY zqn+A@=kc%h@g(%I)vJMxE+M^yC`~9#!xP56=|@MCA9e)dK=aP?k-C@!CK$WJBOSQC zbs2>d0@5MT_iHGxb9KuG;E@ywtuNVdI?S92mIt{sAz?V6)sVlT*^IbV6A#OUq}Siw zAub?iwOWajb$-d_*Nl`5t9D9|I7gM(t95U=In z^_P5n2TtrceLshOgUs?YWqKmNj-}>Gz0B&AY4I)&O4CdqJ$h5>+@gFVlezc_(^VfY{O?)Fz-?tJ>v@z+b5{Jaz2JLWs@c6i>SV&3cO zU$d1A`GtV33xU21!G{+@D;C19E<`?Ei2k(@BmXLH>#KO*SBZyTB~`pizWPcubtL7g zIA`tE7W`tWJRbZfhW@{AfcU@I#9vx>+!XfuXK-|mI{`VMo1?va)V@2 z{>8-qo1ve1CaeCNq5pq85gYnHGW7pw;_p5!UKHFdQ;Ucq(OGn#xF>C@{j+$Oi z6jvW4JhP{hJ$3n%ya051qF?CkWeN;uG+X@vYg9f9!%d8Sx2zvFC49W7wW6`aLrDH< zfG8)3;Wn&na?%1O`UmhwyREKkUtw5wEpL4c^@zdeVcp0pF`OHDsAJ1J2z*_*kh0kT z4B#Kf?xl;J=>2p{eU7u~HsvDHe!|LGNsu}^(SOX?+DK^nvN-j{=X<-OELWx+3ZdvNgo=fk)Jc=nJWcmu;i2C{@>D757&%lrC@AuO}9w#h6 zWB(D~BATvpA&KQ6n7#U(V_V_(qC1=XZT{>Qej--hflheRc8JAkjlfQRi?Mu%F$GG` z$ostMraQX7O>`?iivxg>_L-7`Pxc_)#S^Uk(*Pm;NAWP<0C8$$ zJlOP)lKhQ`Jx_s~^E+or_hs!2H>M(hVGt1G@u&;{5L5-o1NK?M!cI&Uk68{6qacM9 z;6Qv7NebdWS5~gyWEW6Kc2FIa5_9v2s1+J~QcKZq22XXJEA8Ohtwi$q1UC;xSfZf# zE7wAlN^eZbE6Rc=OCTnmBwtTK8jDxu@}Hf{od7i7m3*M$b2*UodWRNY9pX~yy=}f8 zW!&wA@tK7YIspWU!HQlM7TOI^oO=u=b8s(fFvK^GuBFbWc2mw0mw0q=mQ{1rrCLEQ z3#EvoKVymmcoOHe7+_3XNxw$UW-SCY-4(!%yDV=3!@4K%%;jb zK1tHAWOausbCw8*qkMwfBAS$zTSyhyY{teXe&dMqxp+OEJT>xb>zKS)Gq9*Eh5E!y zD*&31Bk$0TqYrP&v+I;FEI-NQJ3?zfkIDJh+f7PYxeF_e=5lW>C^ECy@_jsP*qd-{ zzNb+AES#XK=Efh`PEzQ+(I4@Y#f~I(iVqJbpW|#02<+)xOOc4`F0w7>^|egmhHFB9O7bTI^fLE~R|hEACZjRj+`n z^T^W2=3@kDm&nPXSrRxW?4eKYw=U!BU8}o7@+QDZR{10^dagP*(TbM!^%CCAuOSpn?(i! zc<))~w00vKqy#(|2v)BQSx@zpkOv9AA(D;kUy%QbsS0cjFMEtgwcdz{`kUa2tzsl45+Ym@Mj1?eG}sd1Dje6JJlEC?&mqQPj-omVDd{o9H!b48((gcf1u* z^F)@95$(b2wnxgTydt}1*U@q@_I}w5VVNU4E00|6*jR7HiUuDL#kt#l`<<@;X6SoH@6WN- zP{hbJT;HKc&9nERl1>?3^^ZFOJst%2M?+cb5)|g$k=UG0I7#(o4?Gd0V0L&i!7x%6ncRyd-FhC;8yn8ZT*1GG7xfs|3Q8JoXj3ko)QN zhIG4j7lQ-{KjSH16R>54HBjX#I4sA268s9(EE?ak~8T2;rf0 zBFy8-oqZBZAgV4e?3NLm=;L~JCbTeBwe+eHlYJBe$79mIhbB}ER~7{pwO^MV0JN=OLkmTIb@f2XajfG zg0VDv2_?nA1TCY4c*lPi{3jd*s3(M55q9QxP!#V6HM$Q3QGLb`2LnVme^8 z6z4HMV50#<3xxt!AUViTJewr)El07p6XmrSFwGd) z<~@d+ofDiN6#9NEWDtu2Ozbxr6+NWG6`G^IHu?8Ht!e%ccw92(I!CK*k^K{9T%Eeh|QeY?j~ft`^1cxjJ0O!y0xbC64)44 zz8N$_F8hRec%xX_N|1uG1WU~|GeQEdG*hz4HB+^ZjE=RC1`ztwTIPkOvT?bKo?B2-#IphZRVw5|Uy3pAvxvSr^fN_>O*+1z-PUD;vytHG(h9@FZgEQcdgGUiBHt^?x%!bW5{HHH|t@F#yXTZGrMmTY*)%qvHDM z*smDCq!ep=p+TO+?%R^&mDeVU1L6XoS#7Oq{T&ooUU|wkqq*%tZ;{VNO_{p zxX;-J2_O^CZ}n#rQBD)Z;K9|?cvi!kQK^g==5Y#8w6AXEJ8=NUQNwqGI7ma14AH2M@t%q3k5Xh%AS&m5~Ae?+z zTP+p1=MIIvX)C3Mc%WhRMa3=$n=iRLBW;`|5;D9W5nl&_z{1fzV`4?ggbgv7VP#_U zrOR<<%4|lFgG9s?#+_1Xzr-v8&?cELtC|@(|ti;!6ly!b3H?jfvSYv0IE;3=_ zEQ|{u4iP^BbeZ-=JW$NS*d19bfQwC3Q^*LFsbF*iBu1e*?+{gIw!y)RDGfk~-96~Ps1U9jwz1GP#}mp1koj#&dQ{o=!l}LE4AcF z+Gq{Evd`_+dTm$8GW)q1^zbd7W!D?ocjdD8RdKw6A`Rs0otqY~7EL;Wu6uA3SHDC^ z5g0IjrNU!M@23D!I>Axv56?rL0g>}vHq=T|!WAK|Pi|Jnsd{|$L6-}4r#HP->#?DG z@r^T5ITS9xqqGOc0O|sTt_W$u@1F$m>#YgYeBvELl*LuGEMW zlnn01CzBd~7x_so*5d>LfaBJPzxI8=&73rr0}@LeUdiAY$%EmOpeDyjMSquh9llEd z*a!@9=oOJ`Lou>9;>>Tv``k!Oxsg6Du@v)mtWB=+3@_rXN?>qLTYV?%U_@Nds#O84vf zrUZMM1i@_?+3%RdatFrf-O_c)R&#kkysq79&{oaoo&d0@ktSHJ$7f->(nrCh+)B=)FhK4Yg{(MG#0?)4gfc08oS7+IhzD3V6RDL;2@6SHB`ocUrMfYWayJMxem0l!2n0T@OLnL~?c5>*+6Vcya zzZW9YUSB#bu9)2q79Iw&dKeFTGq6V7u_FvSL z{~SzA9IMr@+kP|LNfSEOm1=M@Ej5k7B+Vbp5(Z}Z+$?}VQ(qyJnUIhw8-vF4C_0th zEG7j+FN1&&XZ;oos087CDi&Ayy8q&vBq3Gm1TGaJH%#HqerBQ(ahIYV2E%12!${3a z0PDj~*gBaM&Dlw|OMLahIK>8?&nmJ90I?|^(o|6caG}7(ZUR8OI!7>uclyISnw?o7 z3-|b34c}6Uq8j(L*hJ8%EDi9n8C^HiOnp{W^7(_ZHd zD4(fSX{$4s7Emah2Wz`| z9&d|Tu-eJr5;u({t;r6z_q*@Ba@gL*a0>?4ug0l)?naWHeZ5yr` zuUo7E=qy1Sk{Fl68R^8CO&0gO(nYfh8nIoPJFyB3VcsmP@MqW|tkdo1hnZKs@Uzru z*XyjuKoaag3uSt~HGMdVq@wC6U>x%_qx{^B9HHHok3Dy>vdCx@^^;W+FHb?_Wi^%x z6P(4SJ+Hu3Ax7YstqdC={v;{Bxu2@^RwmWg8eiI(s!q_$O0`Q}2jXM0_-45DRKe$E ze#(DD4fzxrs-!CJo!ET*Gv6@4W+3nlX_ePD?owm`@OLRWK-QAOR!am{h?8cqF*h$3 zHd}M_R<1Ld#u~M-uHKTKh32?=x%5bER757!AN&leIu9VCa+}UK#KDg=6q6_wvE%g; zks0US4r&sHu}t)fbdm!@uq$>PcjukwZELvn>RWeZ*5YxK{iNp4y6s5OH0gV9AEC&7 zHv?ut;Vj9G2FAK~a)-Yr7m!80#a|+e zl@On0Eo4N)NW>0RBsbd6lXJ%eLgM8ZnfK@?YtBF(Qwa7 z)4?sz{C|GWw^0AmTK4l@=&qiJ_x~PDV5Kq%H=o!XGqa@L;-Id6{rN$s8v!`YWknWP zkXj(?&82-u!+=T|W(VB_;8hNL|N2yXyLX|d)k%D>y!FG{#hYtCzlj}UUXfc=Yn1U$ z7CLbCJYWYRmcG52K4Uix*wwt>sGnu>@t1Y!>d&-V65d*{>L!f3)v|m7|Ga15>!64} z(5=1JU+G2ec24{7k_4IPlYAf~xK7y+u#hNDI&kvR|A#+cP?>Jx$Wn`v%j4Yn*}$)4PLw4zOTRMf(lLt5xVIpU1w>6qg7#YS*M$kC3CMe zeGty_ry-9?WyP}&!(+kN7kH@*1Y=2j8x1_O5v5K-?RIl)Rh2qI2npjCCi#kEf5T5! zhit%Hxx6FetA9c&&Bp>+xsEEo8jI59_H?hwH9MRH*{ z=;%U{T*H3%{m2|-EC`!|2#lPsS)?9A4(b30Q^LV@aReW5guihhVxFi;p15Zo;Xs~L zNuG39p6r7>`EPk7V*c-7LM`DD395C;pNmDfFwntET0kXoBLl5Yl;lfi*XH;-A1L%tlWWTo&jElm(jm|7 z#MOZ?6f1~7k!3fF(qXdl++g4;^cc--gu`BEiQTKGJ!2yl2Uz}LV!SCA!BDTjbT^2X zsX6ZwC86Ek?qZq%VisIB%|Iar0n7((=7Ys1njffz0w@)>EXNGW8Nt6%DWe^tTpfs&fdYV{?`pCyRH1Arq?iOymn!AS z0P4q!EfI7=|Vicb81TA{mF^|ib+Uh1;+S2+G6 z?d}IPeaj*9_3(u4wb%17l%*5l-7+VpPjr2&ZI0dSU|(0oFOM74C6&q`AJm=8!y;q( zp9ZZ}@WNZUgY%7T_x-_$za_LUvi`o;}eho&xNu zut68n@UhCA4~p1d@lZjx7~QCmPKPNmL3Pe4(o&tkGF+@V0_J)uSnTW;Ixt|@L}jsT zTq7caykU7ZUp$UJRD=9oIlhBp_VXq1NpffAIm%q1w?S5Dq5D-VzM;-}y?qyX;`}xi z`)RoN+;iOV3BZ?W@$2DX#l7RwgB!+(CdyX_QouBAo-g`C+kf0nIa+lcR=(RFA@1T93f9_qrK)z$^I&G^>Fc8nV6`W^4n zgIBD{Yv2P{+Tc7Aj8`itU6r5B~SE()F5q}np$v5Zcvbemd7 zZQkU~GS5ACatF=o$Q{Rf^y6CNnL7Xd7CZ&XF za%>m=R~F*eqs={`J$DX*gt$7x$s@9PXM#Svne_0c1c3HmX0K z3wLxsF0(NsQ)NSYITsg){l^mF>k~#P)3wb; z&(b8Lr=KBC>q?60Yk-&ME)RjX(k$nAIiNyE6Q&JHNB7hrfr^RDRuGehZ}qDBW~Wb6%m)P z1Y-1}urll)UgJBq?asb^D&fl4mw$Zja~VCgZT>}IQ01=+6=l|QKe}LZ-#z}gdqU&K z>f0k4>wzO@)=@K}py(1)RhI;lloCbi{bnEjTEF;v#E`s{ma8s}(H*{oFI{4*?&J>K zsk6XZTuj&bjA;+}TN{Wgynpz*{P(5I_n*kmaGyY&k|NY!4P^!GMUa;3H)gY??~rwlMLItAAB<}6`(@q7v}D}*pW0JW7E zfI%fCB*6jHT+UJZ%qm0)Aj(jON=>bhzx(LtbRaoqB?!fmfKXg27l(iY6D&u8I4AZ5 z6aHEcgW`B`L{+V7U6e2c3T0B%Ljp^pF`afWoPp1k@F&$1DE1qtr{@gd(tNx^ubCxC zp}>jFO!TZepTFQ8!ZZMYHp!zaP8^WnX;3wR8CLc9pTJjLzxx9Z>B7XD1qxn%nS#sHv@MM(zQW9oF4+l6-2Fz%GHO3* z)L_;dt>?K2V_bHP)J&IWLMzFzR2lV(TQ;|l}$PNhgY(J0A2PqZ@H8U4; zNhxeaph_Z5-cG9k)c|H~OWmGTzL)z(A`7iZ;s`8?3#u<%q}s=@QY(3vQgbzcPu+V2 zmKe>LXkA-N+GKi4B_i~FAv#c#BW%UIMvOTlphvS7zUM*0W2n(sr&O)4Q?1C?{WNeV zr}I`JN#O+#74z_>K;_grOhlEAq-8okd+4rdxLR`cSNo;dZ^RIRWu~BqsQ#N#5aBw^ zrd-ys%Ogj4TWLu7W+`B*3Bv}Vu(SfZI#U`Sm!KgtmS%6^Ct2hP04}^H1(@62 zbL!GKEt+*tg{otcE%2k);hCyg${PjyiyiLu)XogGK$0bTi#h;Fz4*J zA(Q&)I}xxlz91Gki-@#RIkTOjWARJIQdU(9kOrAzDLg+EUe?B(WDrwZ9X_sOA!x_@ z$Tl|!5m~=ayR0M{u!s?BuU#% zS(_0~0$jfV_!G^1OnG#T`6H5-Hm$F+Fddfd{PXSJhbwCO+$?*H%)3zc4Pwk2iL+YN z{ZY>pA3yr_rIT-+OgLetVzlRj+64DOm{IOkOUui=T_cCwl`qX*EO_G_7QqW7iB zu5Y7%MGQu_zn!$Z@CW^SFU20sXCHojuHSX#jr;BI*K|5obi>W5$C{F6p4oM|3Q!S- zz$|}f%-Y?Ji42eY`0QF1ols*{-4ngGaAULh{@8v?+c#@t z{p;@4QR#dn;xS8S{|Yh9EtS_(k5*$^a45_`BZ}~A!{KvcPH`-cK2#c-K2i&Ps?(&+ z^LN%^Isp8K5fo%_#HGgBo$qw241RlGihoA#vUbM>d-fK398Q4dYP@AR9yv98Q?1Ee z^PVnlsVKU2;R*{E8w|&L1}y}^$-!oZ2SxI?eMn1#x45SlLUDzuOo^a`bdL`SES`Uw z%A8OA5c`i>;p^J(_>LVhsjW$J?I^(kmu?RENp$X&$lE2dRyb0)4r#yHsBjF zQ?SKt10}6=#VrEqn>6ejKIP8nOj9?6gui6$@JJJJ^X)-q`KwC();O*60_v3@D-v34 zb}PM(KL_q9Ig#|zm2Y+fKb&QJa|SCCK#@=Gj-hx0l+bPqO{9918GHORg5;I}c^;r; z2OaFlVpCmfl%XSvq9w|BzPm|(<){vb(x#aAB|$d~A$}PrAE5NEN(xCy2~^?|X6e}2 zh^bI1DGHWnZ&RISP(P7LraJ&x?c?OG++* zI!HGd@5G7a%%r|O00cW9`VSGqc4CT0o@9RJ-mE-j?RJW2_?#!2i#vgvxTjkJ76G((b; zvs2F>9+HGvFco@T^qdQn)S8S1gk^Ne?`@9C^^`0iN$v=Pyd_GaxlRP|uopi3-YbYb zTfoUKap#_TYXgyH_af$wZ};c7vp4_^5SuL#&T{cV0#X!uTXvZZ5_VsTUEL*KW zIl^*O7SSBJ)2rr)KgRI@!LzX@L>GML1_{t0)8@1Gx@E@=A!MZsBZt65CJ>vm%jUtb z2jVTR#a}am_P!y^Pu025UHF6E$DW^Jj>_Ig1KAv`%epnq^g#VBDo_Hr@CTy~VH<8y z8#MSGuccC8sUE{@7^1`U7_K(fehQ{8l1t30?=tlLpyzbsEq~B(-us?f(qn|7=qu8Kl3W-ysxc$JAcwh6JEojA?tpi|Z`Sgoz`ayVRhL9O$}gR&myaXQPcK zlVMV`rJs`}RK5U5g6gzTfE>?re=?Lh)nt+gDbrGn=7Qua_ns(icAC^+FcGp#fE!ejSX8H&4LT0M1>yw{tpVO$u23Hvz;shVBTFC%uQLn;!OlI9Cd-ys(- zh+-YhM=ZGf>Y5h9+@TVRy-Nhq>qh~bhJE|pQ;2&AhcDdI zL{t@ky|$rm7dUbRbA(&#y!7>Q?cCPy)29)!*=3=AVi7W}9ecKnbePhUz^2YVF5t(3 zOEf1OZ;}yUg2fzHiqhpmGnwK?U48y1V3Sc#G2J`-n~&`vC>c5HR059zyLa~a?VGy9 zAbadI^l0u8S1j`iiEZ#TI^WeJ?#sLsvJ5h1dbchEk|ci10kApRdzrjv6?0|M8*=m+F2s6ds9#-(*x|qfZzf%h|Q;qRKSg>;{je$ulPpR>|p@EkHykK+# zWoDX&`58#3U4dS?C6ZUhazmLO)EXPut6L>K7yKrh+omyiMmJRQRqL*EgEjtTpH5v( z7Z|D_8za(TUdES#1*PA3deMhG(?gGfwRuZJ|H}UxL5br)jSLe}P_n6^0@SyRlc1#xw#;Ke{g2GAogHln-qoEWo zZeuJmnF2X7N3r}h8xF>fb0fU3M0R-;&27jP9807EO9w@l-i#&TFGw+KDtX%*;~)eZ@u)nwUBaa@o(!FAJ%Ry$=?2Ce*3e}?Jp^}_qUjZ zWZzEIHDeClPNeGp5S#!VCQyeaFsCPQSNNkz6T&|yAh}7=EtBHACkclpoAS0uU74Jm z#KQVaWe*X0r0)1}NgHSZidzVG%I|1CxugB_j*i@2y)Ae3Eq32EJapIi^j*^{cg>&N z-TLz`Med%(mU~va@7Wx>XLtIZ{grz=pWJi&d5&g@o z|Ig&ce>qn9AIZx9A0#XPX{_Q3ELm6mORTamut;$Id#qA8{JL&ryRO>V%0DG5|NB@) zogg4XUv<{mzo`Ds(P##s$iTV)ijZgxGc^^MWxS(I3{_i;05n}l!gio>pxL~gk=Cg@ z5YyiV@u7|GKcS7q>46AA_$1>)*Nci6i}pGg7~Lu7JNWUuH$WP?X50?x^b2mPjkyk$ zwWW)Tx$kTdcL-gH8IU~^xI9o1*B*Ogm)5dM!=5PfB})yF6&RpDK}r)muNT|u`JB+! zY^hbg)IWx8f1EG0jQbonzPUqMZ$$UN1c=rfAX!f0u9REgwzf}L2pW!;>jM^NziZvK zpNg@dow1@^r-Yn*Z|G3ptM&D9e21jNlcb9Vj!#oAu1^i&jX!H8dCtJLtj;xjV;UDb z%=8Y-9JST{_Oj){IW|-f;y5*5x?f&mp(3;5o~Uw~_V?FTCF3S<&Z*4recSxVMF-ef zEC{@8F$%eKTujU=`2+7+Tl~_5!LJt|2DTX?J{bz1>D^};7-@FA=e{=Q_3aIHT4Ljw zg)K4TFDkBZ6iF(-R)?KtxJDm z9tst&vwVrg)4&oo-fApc>S6!8V6-&%08IL7r3IncgRB*vrw`xgHH+xi)U(MtT7&mO z0~2Y@U3rmO*ZcVTmd>InKm_i&af3_%0AGs;8mzic+Ni+(gM7@7NqVk847j%aUn?d5 zKyLguVin~h=9S|+6ONLG;#jSv2UNp^5fQ))(V%1GW_0o&Wxq#7_o+HW9RD|?q9IA< zym3|}18&Y$p??0h4hhFlNNX?aC?8B{Df~w|5vnQ`YMe;JxKs@L*HSm%VL`^WPqKD-JGroiSwMa<6$OyM+J~8tTx__dC~}IW&p1w= zg9D2k06@Tiy?_Swf)2)^yuWFTOT(J$u`(7b6(oT^KV&M%Vgmek=}78JfGO~jK{}St z>ZZ{+*KkY>qKo3E^*rsSs1-6@P7^SFL+3m%G?HJcxBk_@I6VhH)VufYxRIO_3oti zH`vlNT1zYdtJY5LCT#;~t6vp0Xx zG)#7kDZ)U<$d1!@$7qHwR^a2?Z?XDhMe6i!1#-7aL)i%eJ7tBQqidir0iAv-y?|O$ z0E~um>-ZrI`plxJ{IzrLh$4^&GLj6@H-h(L2t`hW&ZV{oSz9k&&B@M|rFZ*TR9 zYJpQ<<5|b>t3N!#Zn~00wSE@qJ=spe?f}VPK^Ow$r3#pU# zA9!e^!kn^qT1z5MRbMCg^b-47Pd*&<99o!MzOOq`r2i2l$kDfaFEp5BpxNx6y+1}P zNvp#KG$Axkn&|LDWUSX2wYzZVz}Rgkv}RV=-2*kn`taXdQbn-E)`hr#)7)s0UkSf< zKePA4znhc{9RL1?W9VC^G(H>=zPJrVWvs*pQUK+UU8pLI`)N}MPv|H!Y;#OOZ1(6$ z_@D12hWu1Oa zm&(bTySjsC7B`~kl8>{w`^G@8`ezdU&**io@}2b@*u8ek;k%a88!=wusjh7yp8sd~ zam`WeMcTaT27MQ#C6en6%~Pu)Un^MY@0e0LIrzT0ZX2hml?k4zGl%LK;>zNBbQKvm z;Do%k?#)<2h1T>{mW6>LRNSUirX*bYt`*fTMFP1ehPQ~70R+BrAbU-NBnA=q)`|@ki)c z86yhbI3^NQn|yb);|0mtdNuju-5b?xg9TtbO<{^6>~9pwy$)NJCP+U5!nO>79XQhk zUwt`l$iW(4q3rh~0sJTovZ2i>ca7gY1TO`HAAX=!PP6R;x}57e!$Ev_WoJUuFhrHW zR7glFK1?F9Czq-umwR#tViPByJJrM+({?x_0-_p1%^x4q4woMh=E>Br9H5 z=8b}vP{^1>oW;Wx4pGC_sj&Iz_Y-V8c}yi}CgDX?n>!c=rsGPWN&Y?&PJekNU$8R4 zomi+JrsIbx15H?ih>Rufb}&;SH3yrP3b<9xqEpRC9+}iBLtb9V2rNmEUr7;lj$904 zoD|LslJ&naAASa(Ch^ZniR@`sfXXDAyegsGLl2BYwAb$>2Y1y{0c~@^zCdAP5_c)b z&6>#+pn}YiPihS*j6)U4HA8+W6u?(f#zc#vb|D3xnbVtRdRgu*9I3}l<~p%mkX#v0>>Sy8a4wQ=IU(Z6)e)d2_O@I8S9r0YBta~Az@@p z{Bo6xE@3B`Tf>qPF9VZ4w1_3YFQLufxnqy1xmkw{-3}n(70|LuXhI%Y`xyVNps9V= z`KuLVo4=gBklPvOerB!$yIyqGj@xg88khs@oX*94ZV0NY`xu$!|ia2p8jS; zwoXqY-VIJfe($NSw&T*UY-ptEL_nHcOCnc3GoLIte97(|QFSk{W8o&*%1qX`axuTN z>NLiiiv{(epv6y8I2~ou$usNu@P6^Vb{|OF;xQAu8e9MAi+LBR z`-;sr0tVwA&Jg}(TiHIwlA7`BDEomJvx3l@3=$7h15)|6dcFVOPfE)EO>?7>{5`tO z2Aflx?$PQn*Qmkyl-`Bq_h~hgq9~dv)r*u%>?f7=CTq!)k|JR;x5?#r>c2QC`M-Zw zS;~L7r~V&wl7B5uddZRRDF8uolO0;au}CH{`-!HK(L|76zX;o0I-bHV@BL(YCinXM5ANv@bP)Pg}g;6!GGop9&SjNymz3(ZF5@D-hl&<16bl^g_iC+U? zu$_tEgmrNmjzM|sRMnaOnHV;M2k%_TLvzwO(Va` z{-y1Tg#~=(nZ=EEqvzK0L1QTRrZ3ss*jDsoQGXtUO;N}eLYI6y|3YC5w)?*ceEAO) z#?N;VKTp5>e2?pVuCpB1s4xcJVrx*r#!7!Z{6N%`QeA)wY8-t8>F`JEj9yQUZeTuC zLjkR#izA;hsZnw^Y^6M#pRcul{k2UodHMJYu$XpSQc+fM{I&X&Uj0)Q!?zyBhr*2~ zd(+C_PQK6SN&ntoxN_t7k42Bh-v@7QfBXG&`9DQroc%y;51Z4a+dEq=;iXDOT0A|{ zHu-?%m)AqOk}JV;fAm{nfXW9p8-gvA(p7cg0mh9<0Nk?}jVW;3iAA>=BD6&c$&*5V zL&743^A%1`Ct@6IX*m+N1LNruVo<^H0@h?WEV&MX`5O*9(R~)&C8ID(8FMGbgw)83 zlhjh?D(twJ?QXL5bSZ1+#JE)0Zi*9a8T%vbL%D+8RL_5+Fm~_wbA$X8E|8OPl*tbm zz-&A8;M}j>bR2Ctn(|*z81|)fzW%UO!T$t>F?o5U8D30YoZQhOm?qbN2-7&xL>-AZ zClXo)7!nV{#lmMhQo$sMu#nz{y9gucz&oP`j7m5&bK(q zavM2Z!G0O?x3J=Q&QkFCcRq9wQtJw*dFKR%LQ*7m(T{p6b`C&{!-i<+%woA&*O2GS zs`bsB@YLA5u(xePn5Z4RAH9y991;Sw)q*Z=S(N-gFq7(Nh_}N+9oO=Z)L;!B83zb;nWPHUivjX1l9@=nDXQZS59j?+CLA&A!((t zi>p=_!pH@eLy+)ZgNh2>1obG(Gyt4lbZu+`lK{yu2KzkvPxz4fV^L-r>~i;9WIBa@ zhhdDxPy@zmDe$o!TUxwSQ=}nb2gxY?DB-1;m}Ihw^k=q+T}!mKC3g06&s_b~Q0&j^ zPk9*)%l(jW99dOH7O@fH;nzkq851}tZm!sZ0*p^Ug5<%FCGGbK21W@2k|I-&>07mj zDyAvL!|>YR$C8Iw&Se8#!Uvw?f52fA4cGX%jwY~|TQYN}*M!a;P2O@wWw~Wh07b)S zudcl;^Q=2&v^vZ)i!FJN4AG3G@Zy2>i^K1LbI z*%ds3)LOGPkU#_Zw{yM+ItLP8JIBm(oX``Ezf*}fRyhEWh=D7WN)o?*=cCla20_r4 zGF|wzsWnKg_y{ojgG>6Dj|OFE#7N6t8n}J>r^{1;_pWx`8@0|H>K4beGuUS*7jy_m zGlk!Mvt7|2&oT7OC0^by<@&vWHST$u`((fJ-0w}3^qz$(GThki_h;+bo)?`@el(EZ zEu7Mg(4R@4&2pZ0I={U0n4fRc@DsHi;3<3Jumq@9AZUyz^Hc=CTY~ zw_Sv8^P8Y(`{+TnU$p8aeYuGLJ$G}MKz`OIqXzle&{{$H{Ggl(jO_cPA?7ZjM+-03 zI9fu1wt@X7;b-I5Zkz#6oY7@>V^ChR$L|suHwKL9sZOfu9mL{ZJp6>EI%r@PCvpQb zmV{kR6F@-c!lAm&$=3G=+ce+;Y|LBbR7VPZy&{nGVC)5kV(K?YhkXY7^=D(H+4x`K zu+bkq7zDoWo0ph@b7s(8Q;L!sOnBU$yBQc@3eSe5B;MxL^fwf;WRrn=FB^sEN~{O6 z0Ifz)UZdwMd;k&^&KjV{Ya}KE$y1DeM1DCS0qr_Iyq{RURRoGuqty7}kdEjJyGETK zV^b+25d4&pgHlLB zO9>@Gg!`oj`0%s}mr~6sjY!I{PKw(@^m>r{4}Yb@XPe@44mk&c5KxpI4_k7(reXCW zS8|hA9hOVDDFEbP}%VFC|NPk zz!C$Dsi2@HVA~?9f59HHY)pL#oZdI&zvu&sFdr>I7$?BQpP4L>XkJev`P&f5FV~=n z)|u){cQyX8IO%4s%Vk2gXEt~cshcCg>MT@-S;$W_ZJWF5!@MC6fx|4+tC$o{oX1y6 zfH5Bx@{qT^{EqpiQ8C|L1TN5qqt5?p;V~NO$g50AyO3=~y8% z!iI&{3G!SqKx!EBha8dYCe`c6abdzzz1T%rZrlyc&&$s*=*}-%$}j#maM*t=PHMXg z9xN3!92GQi6t<`qw%HVRgcf$G^3xIvy_~iBR9WTr3*Clk!u`Q$boNMo(Rg#=6d4XH z%1@q#s2vo^{DkU>jTyK1R+|~bU zWd0Cr_aC8=2HZx++W+{=8lLe-6KQ|TG2f&XJ&gN0CAZ*9oDu$XVoJA8!2+R!j?c9| z(MgQcpT`=E(`t?^m(r?U()*Il%5sta$8)-%bzJKB3*}PU@mJ{Plkn1-vX95#S{RJg zH|x$C|5~5=|8@cV4Z}MvrP4*ZQqmlpWmol7B7Y`E%@4xQG$_a)>$Fp2NvHAd=Ta9fu~Jgf)8oUL~c#2NF_`or5;BNr{3uyHeoP{BZt>f)Zhvie^vi7ZQRL z@}WZ?DvxqL`R4^d)xmjdQ|T9>BGsLSaiCX%>mOR3FY>A49G11L^%9*5MiVkZk}g|y(n8Y6%P zga86)7|Yy>7Q|L+1^Q1XpjUF4HK9li5}wW%gMJxU5!j+iqyzUB-J3 z!JyBD!W2yK-o*mN^oVMmf1`&mXPl+=#lbicI892I8A{B41?mog(ux`vl4C)VjrXKL ztC^5%MEtVxNaM{(e8R{_2jQW)SKIN>xG@Zc_FY~r-=^Uhc3w)BOT%-zoEc15QZYcP z#HeK%^Dx7U&WPdRYRh0t!8G*T44J}5GNH@+4ioDVQisUQ(pUox05Mx%&SbuzI1o+E zeord2>3J7PoRT<$r?U-~#v5Ak@`h{DeiMW-oS*tv|w(p-?1Ip0|zs3ICw57}UYI>AH#AowI=4pw223JK75IQUj^j$KcU|HzJh4 zg|*P3Y7LG?s)0iF?z|^~6y1;*luKU>5zr18r3J9Dn#*Vp<+=&3N_MPp zrSm6^l|#_iX~?+%}I4*Zy4EJ7BN;IhD!x#_2?SH9IpIrQ2`nzU2CInD z;%G({VQYOuhA2M+dgMM#>C0{BAv%D?!a2L+)Uc~_(1#d9Uk;uBO6aswen!2`$hS1j z%*nWV-MHQiE%fE8q-eoxR&tSy+5|O9L>9KB)|yYv0flpi1b$(Ei!NwTONy)e@nfN6 z>)WL;?K~TlWo*Ct8Dxu2Sk(UlhWBriORhgV1mnI{w%Nmn?| zTnK*>?r^h-_VXvb*`}S$VwF@~0)1w9*oOtKE;Rc`j1w?J0g`_7WQc#wxHhv$wGS2R zQmv1)@e2-ig_i0kbCY;{2!SCldhbuFAjGa@$%XfEJUWEQp-bH^z@hJIl}=5Y>P-f2 zE<@i1O+tblK~%J(yCXShk$mcl(z|lSRHib6kgA$S2ed4l9~=VZiyt5jTCPdit zbxJNT6%B9LP&LQ1crYIpGj7d6zJ*oTtsXCOh_c^Vu)gymo$7|Mf%hK?DEJs^N`me5Z_q$;yUCd$tv<&8R zgCOCD1}|J;5}Pxi<~6c%3TA*rZd%8#tb4~*-%)illTZm%ftW1m5aNO|D4PwG9+|*+ zGnoUN&wsqK+?FwWkp4emcvOt+PVG!$q0UpfsgQV(;p1HvSqlz~AIv%Hc+pmUMUr92 z537oTBBF#QeZL11IZ#o6zw)!{G$s>GkxNYWhbTZBRG$m94!TR=4fdR5$2aBpUE(WO zin(#b#zhK_W&1DI1^;`6`QIzd|9`A7)tKP7rW=y&TMQ+1Odxaub8`>0B><-wDvc8G z`ZW9kop_htUjs~al=>y494&L;OV3Aeeew$POK|ucxh`n?diwfL+h7yTA8#Y>p1NJ9 z)?K2(4Mwv09lkZ3djNl#s7!u#Z=RQcgTyPBpReV3@UW2Ug2l{CoVUInZRmLQ#ch;V zMOh5hcKY4@YkL`oN$q`CG_PW2NMvk%{k7Mq>y-X2IJ|{zC3gk`PVS78-;w?vV5ads zmNNPFg#SwEo|_Q^_t(cB7uF~z;-&utw5MkeAGN#qvBq!DQo}!A8$Ns5>9G_&Shsn% z;`9%&KXD4h4yDpI;gIDM5T<_;sQipL&gH8mY_L7j%)zO*W-GAip;TiL1_* z)v}kk!}fYncep>m&%qvo{<^3vT|lCP1(554H*qlJG-1fBtC??An*W{bS4y~Or>7p5zf{#h4%!24q4(vzD7|E4b3is2%B zg1)b*2(c=M@iq-1_q|SIkUDX&L45)RMJ*(aOp1oJ3u{dzX3((fltA$!=a;@i5}>3~ zw&xR#6jLZF!$8gN4@Te;nGo`~FCcW$OIr)X|KN3vq@2NMo_~r+X<5@eJM-kMLQLGo z^|3POZm}LW^<61oh&mG>cl+l0ii9Ysn6PocJ`tHj>w=CofdiNwie%W6SPJm znPc$VP;@u20XRd@rY{a2!npjs7{#0Lt*?S3IaEYU$)A#VvcHXG0vClR?>HB(pocGt zMxD~&Xd}=t7Ix1l)C0#~enT+20RX<(t8v1rlC-u3<)q&O7KB`3KjObdf3JferO{Pf z3QXfqGe!V5~{pXmerS@r8uJXx(6W$Ih&p5Q0!N_Q^$9TNIDY} zB|P#eS~1U6GtJ~v@|;Zu*esfkiitV48frg1@5P9^`2rb7#!5FgMTHXaln*+Gz$Q#Y zdTI=X&oT*0b~}k!ATq$k5>EfEOAPuYM_RaB^MaaJA71paWpcHLmMAJApsid@b=r|n zIOf+wGQ8+}cwMZe%rBUDQ_#X`#gGTunR(4DY~>38)>^yPJ5$AVf05_2w-YLps?h%h z`i>;F8zDz{<-qplKvZ0a_NE_RofW|6UFuo6e*d|dD;TyRb{1m?Y8h(Q0n19mjxmU+ z*Ht|T61Juu^X40)Kxccr7(fJ8C=OhOqW}j zaJD2R;YRqsz&q9l;j9pu+_BnI1}gRM9yfGJ(@N4Acw`}J*vGks`9r}GYEvsT7|n5!i4XUE8H|`^9Sk+izycxN4Fb{KtM1rqN75R z=vm!7u@20o$#+FKxU3L@0EOR>YeD60HWiTmqc`KSFo)2 zxm5PmAC|7zpP=dv+NlXKsgi=*Mf1owo)@_)yke#Ck#XQ7NJd2kEP%R-pn>8!n~6I? zWInaYjVnl|O7hM{7)+A6A=>P}hvjU~zVegew*1Nst>zox@GZy@Til$bB7`V`CyJQH z?Jg2S<`bm??3q2{g?Hmvc4L`MQ`wg|w?<7;L>RBBpqQ;QWAUb%yW%tiM$CGk)V~s_ z%LG!?sf_pb?^3Qp&ID&@)ttTY39I+Nt_#}#gFxLaI>`qO2C&XvJi-{LFc|K!^cR8J zpCk7snLurm8yuQz&KRdj$bE+LKr{oDld}%KB$S}ZO)M&YLJ`&eBmb@!6Riz+AM41h>p+Gcahf=?`ja71 zkU^*;nBiz%c?&xa(ZA~;=VoSbAWo@JXz(*80O<_m6_A~5a~$`cs^05t3pz^7Tvfbl z7T^YgDd#!^_4V9DPxC>2N)v7OEDh&C4R>7VBe2HWiMb_}bco*AjASq~;YtXUTS_rm zF+W>%8?MRw>Ij5eL0)5-e`Lp=jNc4i%#T*iM&qagagfChmNR-FWf*Fn503xD@{*lt z>kxMX$QVEZ-`rWk1*t-_+27=3CpD3ye78+gfSRfVs!5qGgA7N&IXHQ)kSMPZkyl96 z<{TbuJ8|BMBuhMmTkjsZ8D*4c_UogGWIoGT@P3ge`%IQG>kh!XT&QP*;AXeuawo=H zvy`iVGdAqGLRpOdX0^naVizRyE7E0e?ldY}ov^A$&7>ppPI#(n()7l8EM=?-Rj6fJ z%oG=R>U4_}lw|uwO6lPOcOZ-hfK&DDiz+pPkO}}G(={PZQ#BJS2pGx=AVFE1Bp9)^ z?YrXN-I3VgylMfmKyl1N`n+WyoypSI?BOBKN`F)EoMNOe*} z1HRTtx3L3-925iNaMg#lT#qfUzEm_rFPr%MYOFMcTzy!0QKcC9nzN+VjNvht!;l)2 z0T+Wm1WH2Efyk|3P(^XB+ae1T4%E;(e^S^#N%5{R=w@^ zy;_VMjM2~AC1f4oTTL{Y1uCXhi1`Z`b|)xkZ4eJv^Fi@v+aHUR+4rU>o&#qrAf6kY zD!d6a;V8&8v;2o{R_jjgT&TDWr`98M_GGZj-*v&9@b0|A?$r!eBQB=km&Gj27^}*5 zx)Kwf9Y=Zh2L*Mhm;f`LJd{kliB5dcO%h7y2YR->rtTPIBZ};KvA8&aG8lM1`g(62 z$8cC*iF3=;>po*S^V?f}Im3_?@%|TFX#2(Pm%aUOUiZH{?q9Cs8dyCyux2-~9zL*9 zIPkf5VEgsJ*W-a5uED)?gZp-a2jPQw*!(>_x+zeZ$;uhIvkg(cB|^>LUX7BSH})B1I!&eIpWYM##iL8SYUz z^-%@;QKg7cm7-C#zESlzqZ%ip816AG^)Vg$G2MtUY|+1fo}^kjFa8ILk}x?m`~IJV zX1t@WqiFq9Y(VLFGP|_*10*_s^xxIy>?d0)9_Pwjn<~20S~*jwa_jS($yT?EK*&9?2U&rQ*mHCi=Lh(X7LrB=^pwO1c^)Z4{O z5(T%iYoAqUMgJM&9aU!F)4OLjzM4IKZKM$Z2d_?dHGg;$Khs zBwcj=#?pxLO!0+WIKR$=u9mHrP1hb58})X4iQ~DZ`l>a*_1pWQ$mpfLc-kVZiZ0fJ zu-@+PpXSO8?qBW~kaI{oNM11z>iYSuXa#-B$WmAK=*9DAb&j(G{l`Bs7r(4b_YeF& zKI}dgitXuhJ_IO4mT_=a>^=UsAFGyQ4gxyj**yqPv+>MUo-6U}?jg+5gtrRIQo{gKb2=$d5fm}-e98Ph+g0PR23FB z^^ugwY3o_)QNAm}?hrFS#ZPIg+iI^G0tNnZQCuRVL#mEEVIX`FG(tN8K5`3JqRy069B zA6%xfRb7foVWp7;oZx`!2H7BW<6zYIT;ILArjcl+2MMiD7{jVdQBz2@+8=Kj2i-gT!7$F$eDo1|xXzrT>L+mabm`?h^6|9NGyH_PM(Q^UeVDmkJI zpfWnCG}T0|%`L>IFi6)_o*v81*w5O_H>o84`nockW^};eoM)u;O83KCa{*XBgn;qC zzzZ@bV!s}JYKZrl6?`a|@?%8qTgk7_vW0esFP)Xo$=13TzcpMVZ7tv#fc?2)>VBF9 z?XP2Or&e7bidPyoZK@i6ovpgq7{)W&gZjKR6?3L>bzb-QB1`A2cb`#TI@uuQ!|{fm z+uD0mdHRX={g)?oby5$wh6jp0o@{^i@}7OW#mL?vL-(fS8xCnm@~wW6njWa9s-&1Eo3MYerlkc?QSF=iWmKGT#ym{_IrA`Gi8 z_{NS+*&Jkz_gly|_@=H-tGl+3DfR5$QJQ}(I7Xxpy^QivXkDc}T_tE7$fnr#IXhT= zN{}uU_h>nnT^eIuuNzQF?N3TPT*i_OQa1%w3iNnNk+tWk#M7@#m-0)^Cz&~{X65ei zqYG1!awP+fCU^;2*N4b+zxUYoTNr}z3mxGm*Bmwthtm8CnTulUUdd*Q z-}C2B_!TLWPNhPEq%GUt2zhkb#7kEX@%M9AX|aV3MYU;DTYt{dIS!PlKmSeoo5Z+! zdnQZ0ryxs(r@MkQ3M;j~V;z^73w#QCjQ>+fvctqMuLtNPyxOn4zx7Ccb#5Rjsqdzq80*@Pwk zmEE3a7(W$zab92|;*ZH2}=6#^H+W95pRhQuEi$3jXBT6#M`0| z+8fzg^L(6p;)N7=DVyhVuCqNZrW2{?+%Wp4Uu{MEft1~)9Q)1oc*E)m{kquU)vq3Q z5VQGArJj>=KYbPikO~>9UAkUl)%!Y*7ddPMZT=E2MtVnWcgR2ZJn=bUQ)-aK+-DL# z?Y=UV;y_!*W;H2ol|}vZQ|62E%4~0Mh6pEKR(4Oe@HKz-H*s8XY%QJFXDOw~wK@JV zr)TWzd+PSn&rag=56+}!R;I2p+J%nSlj_VN+)e;myxoJ*MG3WCJ(Tva*9;h8^bCI; z&3<$`;~zDvPEs7lpz0>0C&=2e2Li5!N3;6+vS#L{vy!7Kv5p-Ld5yhdcC3L-MouxH z2|!OZ_=zImNn6-tZT`8QZ%>%(N&GsRE)Iq^Qn){@q$4|O?GHQUP>NO#Hp#K%^Ph9h z`Nc5j$-vpRHP8M*%7u%e5k_2v%}ZuBqPFbS_vv5WW$Dwo+34aT$U?yvbvY>6=8HEi zy;NfaOKbftZfnuJaI!ZSN|mbe?pp8h+q;u5H7a)z8k##*UUz~`ckR9q?9V+nckmOp z{k?i+G|U)SG|L+ttJNK}pnm&Nk$fglr?nq7?L6svxU}~=^pLjxr?y(u~3;@n=`m*^{b0f|Lx1k z`=4L0i5PcJwHke_>pB^H5cdNEsQ4(fSoNmIg_J-09m|lVy)mNH^Xlbg<|qN}t})lJ zXWB-4W^ewg_x&2I>AP<3%TXJGV0P?XkV6WpTzh{U(|yh0fDt{i>gmzDCOpU#HLYrc z9^|hs_;N9`aP_M&Sv&>1=i=bn{ruTl%jZ6BN??b@D9Wuq4ROvo=@dY!5(QpK8Xdhm zj_N;HzH?veT_D>-UWRD)AEwP(*X#DRq|6xFqOL*AdQX&lo@RG1&%!H5UYk9#s~$P^ z?3fBczxe}QssHj-(D2>+-qYVSC7d+*ox(FWiob_rbc79?Bj$2dKF%zA#N=4OJ~>8O zXbZK6z4p+3+sTo3U^~hiRc0E#NkI<8ARZ*8Ew<2|mv|l|Fjzr<-ZDbUBE}X9Jj#tY zerbcfc>PZf?F@i=-0ng)1qVa0whQ|5k0P5Wd2tAH#x6@{B%GB1<-}-x?!}^S!4NFNhVoQXRu@<=s!bDXbfNsOUMXm{9vEZ0_`C!iyFT zFJzQvSID)W2~tFefDRc3oLHO}VDXH~aVYWUr$n38Ft=5=@FA;dS7QMyf>@^j8Rv2$ zm{2EhmFg$qX-op{hpo><0@goC-5-{J7;b%BwLNO4>`cV3!n8apV~H z`1A0lSPo%9&)+!c%E1RI53P{Qjo1bR9wQProad)bf=UtXG!s*|I#c(pU4Q%2YoYIy zt3(KG$af(mE_%cn52ooWrm5`ae%9)optp%6hHD)o9>>_S0f>kPD^i5N3LH0^3c3F|g z5WO&!O^f#;*nf1L) z-LjKz#=v)lx5uo?*0aN|g#C7BvEfbd$j1$v=~@U%YV&1jiR5-Zf~lM2st!R0b8^G- zt=T{2*4CK(oPax;otsmMSGY|PCHXZ z`@Wghgj2B>p2TsFd&uv^zhJVfV3EUcAK-LpNf*mcwiT7AJEa6dE2EEJ#3y#eLp`Xo zyoxI0lTk-^-8*jeD#7WL;P*N1k!m0pa(rJ*hA(lDvUC*Bm>EQ93R$V#wo$z$A|lbF z3Qn$B+3m*Q*KMpH5^G(xPxj?^j|2-Z>98kd+&n6}K)SDvBkK?tPC(z&?l|bLQok{V zQ8eNJPnul}B%^`0+9*L=ZANeJrMzMRT^zfbk*uzzi&@BEfV)Ez{H7}0KnCu22ovPI z#|1J}E|tpkR2Zz8FtnVZ{8cdaNto6aWVO72`dlc)$_D9ld6P$7iZ+VO(x*G39F9r8 zW){-Fg0_1OcbJ1;o`T1SRc{1`uTvJNnn3D-P|4GRVEbRy)H+tK0Ot>gkjAr1cAqj4 zD0xzOv^OWJS}5n}Vq}1Rm2MB^S3Z!qAsF_Vi;0jC&FK}Z7EGUTKd}HNyaO{>s{TS* zGZ3bMO++%7mEo}2T^vN9oAgRgUd;1$2pgM1&2?)?)i@Ql5+T{HDzwfX3{uvyZ(d#2 zuWr|`7+r)in0TF<-0OQ)H~6aIA%B?xP?@ckZ6N~QE=UmxdEh;sJP_(#qZ{;0%vP}d zZU8agrKNsFIm@%sXMgkRO;NZGdx35qrC3ix^=1RRojScBVsGjU@^hlYI;k`1^01ua z@omRH)c%=NRnkfq^u(l{TIv}^f;~Gdl}=wb&5AaQ>_E2NnDpxeeiE|P3jX_#WwEJ}v3#`-Hw1>NOW zx7y!Qcf9>of71&uWddbsLiDwDT<`6^*3NJX>>T5a7qXV%H)xqiG>r(ikg)a^U%xFN zcvWqz>{afA^sb_Gfw+CI)($MwT6p2dr@iVq9mBK-3o07(S`u5Jr zSd7vHJnl2B%C4^(oad4Vt+e5E>*u-Xxwl{gdr1`}c0r2f{JXlYHDuJsbDXPJOz!h? zrf)TE2*J0H0k695@5jS$U1VlReanPzy<;s@Es&QroKU9!`CP;p89QP)$39sj}7@Urqk(2To9 zCZGBmM>|Uai>>+)wD<1psM^9Qf7$~v?sFZz%-q(486iFrao6;!)lDEFo5O)`CIk7T z=r;rvgm3@sA?15FUZ!BL2T~G{sQw`rnQa%sknxXaYPR8|k>*~OqKCtp!`TuYeM;4s z9Y{P0zx8=?LR~nYajMiHqTok>#}=E|MKHoWHJ5 z^MSn+Y(vANHzptVbK^grig#?PcSsRS#lxoA-ab=bHQ|b!jZl$*J13jjYs=d33CcxE zs~g+<+WvT%`5<{tcl8Y2_12YSKST0gyR9eRwx2om^Zj;W@R}R@Lufnd8+=wRm|)iq zfW}L8J;ey1$TG6AkgYiLLCsUSAEwXcjh^{VT;mt325BIhSLU7XEplopmYQ(u7B=2y z9si|5j0b>R%*(Su{Whp80LjAmyh?$-Wqm<{<4+OQ)Q5u;y+bGEV0ft=;Ojt_nSA~= zduF1++?eo$>!VkhJE3KDD*CpDxRZ({{;RRoop*~@GqGx~z!9+}M6epgVxRb8d|0)} z5JX{ovaSCuywv>lsp*3Xu6`R1%&ZFWH!X0X**<>T)J%!?-qn;hw6CZV%NawjMt*z~ z&iS^6uA9%cTJRT4bq9C}zIL2>OF@r*Ov}5^`7ZKi@-?l-fTrY{-RxNID*|_Bpu;l{ zZYS^0^tCBSR(*M_sq%K&_N_Xw%wmE}oq9(3ZuN`o?7b$0s~I@?YI!lt$>nC*WG=Vp z6}OWFZ-pd_3K@`8pTc9CrsS>rxnw;Tep(+&%KHy^}oRu7rDy&Negm*>h0|hzrQvG%YF>` zvfa8}@G;>lcgv|6eM9%MM19RE`#Ln^Y-4`3`oQ{2*4P>1rr6IZe?RR9pTblml5)bb zZ-0F{)cooAZM$IFeM{SJDk5z_>f()IsJN`FDT?;C|HkbN6a6{4q|!G;jrYVSXh$gJ zWG?lKqRj%Hlp+V?#@--b(a&ku;_Y*FtLPW2)1E}V`<&yG+8i~O5&%;Ifa_#=$W<6$ z22{k~0l>jNXn@;1%(gP>7HCixgAkMlj~ce*OW>&=-##`dgh7f&cs3&-KxVPn#LK0t z)!XyG))#(lpYs&@aZ@+3`@GxrFQI=@`2WkZRGVs1E$xX2>pLwX# z@}4XR6F%Mfiq<6m$nPRMPzfSb!I8P`oir2$Q<#I1Efoqw-;`xpPtzFum$w=@FmThe z6vhwE-d=A;2l-u2d56`$b$R!>)|c>#cDJ_^T<>@B^*-+qds?_^fg5{Lr0_qJdtUR< zJYA06VlXIuU%nXupedZQMZd2Is%U(6(D*@lPVP+kSa$Z-%%p`Wh}qJTWt{+ zSoqnn=Mhh?Wpu#n&lE_4zl3*ySe~CZqgewRf7ZSSkBQXfyUUH2t{tF$eAgF(iC%Z? zUdJ6wJ(@9IwmOP|ij=pcsIqZh<{8eB=q_fsr;7P0xlFEl(zd((T7Jh`Gx%#U9rV-V zj6G#Irs&B>@NW7ODIY9S|6vW9bPBsid>SiH=@h)nC@;JCeC?^xs*+^&f2StK2b7FQ{B)6Sfaf^(RyVKW7digohMKI-R4 zULAqjS(5j-T%_XpwCFqy`w-woZcYkv4d^E+GSL=-P6-M`kmS%bKr8V$SG^c{-d~)k4 zMB+|s6|u~qRKLQT<*|2*Yrnp#*gpCHLgm(Uw#SX;ZNJcmA}1{j4s4NXsw%8 zMw9G{ZflMp`X{p98tBq7%HvoCwjMpY?|2&Z=eMc+t~3U6{j=Wv^Bv2R?THBmGaYGB zG1t->sWsOaX$-t7YTYxv;_KE%7=7r0^1Er0?N3_L8hYA3)b&c{?MO8ZC7>Caxt^Tk z?WcU@_3ivwE>4+JR$qc=S-P#tN<5oH4}$_tyS(l^=FKx5 z#`#)$S~=?9t0rvyc3D(v zL082&{^}|v5Y%IVnnuKHSzYXzOZ9(!y`sK}>Ag<(7)mFLi3ZU44QCsdAF~ea?JHkg z?Hw57_kDZ&#>4KXT$h(s^%!ZFFTTJ0GxEktl8LOES4FOSk5`pySrwI>gpmBH;bNT2 zjzJ2)gP4w|YH&GIvv%+;)s`uJj&X&t@w9XK5SVlm_ALU6EZU-2r5q0tT8X$U;9EA^KT3qtB|;dsiaRfJ=rNWLRJ!mdD@+?IhR(;*999XJ(j+3t46Uu zXJ@90d-#vG3Tq#o)FR;ddc1So{EFG$PTHA+zFQkdaRYW}2!!X9qu};o7Ee{k@1LIr zqfgC~AF*b!sV1sC4z-Pa*KFTf*+ICd%p8^+&)rttfFSOgTJMF5{)82qp~kQAIb6bKRSZjC>4GZ#QePN(p$K2Zl0zyL6R0 z=I>A*KT<7d8lAXAucTrB;yYtV^LouB{^={a1KmesZmPSyuah`JyxryZET~h|7hME8 zvF8MK@4y8PhhSJBU(Rg(&V9I>$VJtuyC-FsG;n$0v!|ZA6+PaLiSI1_>5!+UjA|$j z7Q0?rDyHrl^f5f^$U7^Kdu=%*UBaDBGU*b0+xcwlmVh=^)yUiGS%KfF0`|fX1fHU} zk!F3o;w!=W*zcjP(M(OnP5*qw9^||fz3D=T|3Sl&Ah~fauugZAG%fA02hJpDoZv7)JV{ZnDuH{750vJBLsc=_a+44vDoYa->=i^tkL z zX!DN2bL*TRvVS{hRvcc)?%ia{T}uq}6m2-4$DxLxLcRUn${G$2NF20u!tZ?9R<}+p zGngIGJfEuDl<%Dqr+Y#>hmx@1q@ZnHFK)yArH1_Tp58}n_iem>6A&y)uNyTFei?RZ zT(>bexAxILe~|_aGFoQKtk+w*=H;_z|08RCTK@7P=5}8lqH%-iy7<4kg7VPArdVVh zyvDo#_jiwl&Yxqxx^e8A{|DO9;!}hfYrgDwe$zqsoaet5%w@y6Oa4Urr2JQ2T_$ym z_x`Chy)H}7%zVRq=s%Z1FSxc~=qLuC?EN?HzqO$LkgUc@vOHaTb@%Rp^B*_w(7ECvOxL9RcfJFX_Fk!GcW1gUxL6tvEe>P1r7*m#HpS*dZ&0%WhBQ ztlJi|wfJe%aKWo#g?AMB?KSML*PjTV=b!PiJq5(y5U()SBhhx1!B#?d0p*9|i$(0r z)(fjI*yeN{wIsORD`%!Zb`m}QYj3b+dh{3yB&|6g_2SXaAex}j_|0-Bd4OI=e3V%w z(=`A3$%2iqYae-xI{E7F_t$I75-L`m(oh&?WZRr_zP&-9G19^6yyPwhkdr$M+Llkh z-x7HKjkTpMt1xCkozdTc0e{CGWk;^oIhX_n{e1a6)KGNV&ud(HM*g_&)WZfd{};WW zci^VRN842b$K8`fUB;f59L)SUH?OYff3!^4T=!>F`q2~1!vI)7`tV`x>kJy);vhYI zJN^o&&v|H|9(*8O--f@Z%hmsKzC}aA{H(Wog@45r$By%Bx48_D6j}(I+mGv55H7y> zwj|+liEcS=l4$?mvlYkQdOz88?pN1UOV>AIeuqWZ<|l{EW&ZQw_a}uvM?7Wc zQbzARUe`HS5w^L1_2`~$zhVrc{|2TbC!!VqvmEI;CaZ5tnM0$Moz1H=w>9s)ZD~vU zKEimD8v5m(c0lsE+c};Y@BWQd4m=ni_;P9Xx99T)OK-Ppb#L^q+sZ?fn?74$qJ1vt zzfs!n(jV=#pU%1RZq5;D(;zQ#;&tT3YYEQsmGOgHOFC(yUsvdn-XF z8>!KR75LwM?jz*odtM$j|B$!FcqO%l#_EP0TI81+>Pa3a!Rb$eTt?xrH zY`)-G`iGaQ(|I}bV~~!x<(l?g&mX57_s(@ZE`7D%B=XX2@z+H$ZVnpz0z2}Js||HR{MVDz&iu9ZpnvleuiS!FrTq>y^x(>Ls0@oaHEeb>MsemX+7qvJXZ^eS z+GLd=tx4_OwV7R>H{%xf?{>=BLj{Be4iwlX5`^F~jZ6gn$8%+@%%GM%{OM@6B)<^t zG+PZPvekN zqxmr`JyvbgQbVsMBBzznHWli1yeE6MRMXBi4kc;&dZSgsiWlfy6|L*ar z9qkOs;2bAO%PV}-@~Xvm=mGa?K})d?-8{?5&&l#8s^oSTnHt7js0He{3)KM8$}6XX zojT*E8e>PWbi^ayzhiya)#`NbXMVPnIIpOtt8t=x7Rt+0taG=3`xU{Wf0G8W<~}dH zIy1uV=d`ikj5>0bUg&mPbc(iEW9pi+L~9fGwD8@1;bKe6S>~2X>#0x0x|mKK7T`;$ zKfmUFUIs73wuF-`3N^nHR?{-Scd6H)mge!T`a^zhT9dw}fXMe3S(I^X8w$8byO_JM zGe4vIXhu!8HQvtbY0BG9-m&~_wIido34M-;Z2=5Mvq)ju@u-Y zVXqW**O&VngdBLI!${bFt)Z$#IP7hEqgU%YY3Pj!h|<=Od#{gk0R%Ip5Wbr#>n1UPZ^H)gc&+Nf{fXMe@~vVINK$?T$=>;1hKdtcNB z)_u(1n}*pr`=H>4`U5m$f9dl1H)9X`#-NhPThgrZHYfIq@_RlFrN%8NBfu3W$(5t; zzHEOq)XUn}l=9v7SLpk9UYme&&gWJYHK02X@X+75m9{tz; zm}x`d0wUc0y07K3J1J*pqAY&rSp3>=w4L6|GgxxnU;lKN)5(HI6H^Qeh54KA$D~2N z%}4z9G~b8ZJAjGw0des%_wu=!%UQEaoOu zx@ZjQ^oT!&6SkBqCj4x?h&kZxx1ldzLd}nK>Xh=0T#+Qivbw*YIT-SEB0t*|Pgfn( zkwUz5`os1R)R`u&CI6fE3J!T5`{XzZ@ZHdRqqKQ%VbG6b3rMe@EE|9Nkan)1yb1ok zl3`beX{tF{ec#gDIfgN^4N2HASkiIzPDGwT;%nz z>4#Bc@1DEGQ7e{hqgED##ikRqD!EBw$8IOHl^ui8fd$zB63Z9qv8mvJ1Drz@5~L*5 zq|y6xM+ORcK7IGZE=da-@Eu)fN)cHCqCFSG?>!kz{r;?kud(E?*O$4+Cb#_7r!03` zHkcf0!98TOKKy$73cuYVmyNHj;%Asp{mNy3pJjhvwO^5+Fc(h#-E{lUZO5xMQl5H3 z?vfqa&wr4rhK@b=dC8auT0+fQP-YX4Ev>~vV@LO4UzBVo+!rw~Og&29*crY;XS+$G zEB|Rk(Xl7S{?@PW7ak5Nat0r3gJ*}Ieb#<)`unQEp&WaMqsNEMlD00*ON7#dcN?}k z%aG@70R9T3m*jK3?@q};rXaNOl^nFduhB8TukOCmY^62j&rxrIwm;70~`(*8&s}ZTaAiZAL_xVMSbX|eu(MK#| zIPq2!caCh*PItbL?r7H@XwY%vO!M&0aDiaAXM2mY%fQ{T-$D!7OC}#Qnt1hVuOXvT=*1d! z_+oo9^S&cHa-L+~|2C}s>MZzvh>ZQ z9cR$r*=J4XXK!zjbJ_2fa{n{`{(y@jMT@2Rfj{C#HpIZtaPSVl2cK`)2jc8rT>{p= zqsP5l_2rtrkIkL3J9m0eJDH?YpJQX6z5g?X&xFSlJcp(e#vUg;eeGP71>W{MlVl2A zxcx9bD6e7jk@bH(5(ayF)4s&iZ1#EW{NYdN`i=HyI=LlGBuC!!ewR=3OAk}ixd&D$ z316G)_nPwO$?1=_Jvy6$o~XZpvVd|d=W?bd$HjUZdZ;fKVLl}Ncu-?vRk)D>40e!iVTv5rLfw(L7+0ei)XfkI#frHyK|~UQ$+Z=Dpq=O7%4z|KEnn zBa=sm^Al6z^DRSBS6eb2C!aBG+=3c1>@9tf$?9X1my3Jyt_S+^LHPClt`neQD94yklwsrd>*gK4clj~; zf>_SF-_=gYQXqG1@aGa`Lwjl#EHK*mpo+jb+AwNEzaJoFr$a$dIH*Ip^3#lF;0O^EG z1TO$EFn}IH(@qn%yW;aVq+9NsvCf~d**9Z*G=1UOnT5}1m><%aKWFUb)2(+-JM61L z!N@!s{^qpmoAdf@W;?f;ZTaSMbepU1H#4hmOP}}Q_oaD!_~!ZZ+j9IYtUt@Pn&r66 zdilzhBzJ38xkcGmye?247M^!C|67vm>gZf>m@KuU40*XzRmA z`GJ!OD9!g7+wNg>Gq;zzipT}M1ka%9alYj;0kbU2| zh)VwihD&y=eh#dAniBvZ{t^)%7TH^G-~ZveIRG##P@b+>b8BSl2Pdmc0uvI!d@Rix z(3qQBTB94kYFFS*QGP4vNy8*PM$+$r-T=ZT{Lq%{^r-2pHQjA{4kQV7m?H#+;HTZJ zvxzkdD+6c{NT~VK=}cL9;V^GksI`2TL- zpB3T}I^k#j5SYK{nnv26`#*QJU7L-)OYo}4ocM6%{_{WWNB{Vp{o^l{xI@<-?)&rT zZbl&VUXr$3QUQ=v9IuJGd;&&dy&K2`I`!~<&NHb{c<>QQHh2UGy} z-s3b?5c94UdP9EwN*AEzmoO)+-q_XS^$lmQJTkykxpLrpVH$=W39MMUZN8=-arbzM z9R2ca@L=QX#^?7!&jx?hu5`c33Y%|FL(PpJKXT!%#tP@Ix~P^*iC2R)8Z9zMKw?k% z@=O-{h54k|F{)h<+v2@{;L`f1&71#Q@@4qO&Tn5n8;$jf;>;-G7M-^BXY`kp3`tQ< zp(5QSVO;_?_=;@85tl$an#5;T4rUj(WMI_>e?9Zx>He8ZdXrYwJNLz z@T1+~CXp8Q;U(M3Uw3eDKvsl2QmY~jm34Rf7ziv83pnb_c_U_Jezw=m4+XmaGA|GI znSFuQq_(5Ay@gdARr5%iym)@uvsEXf1_oCxNDL^w`bN*(`l>cY5Dve=dR%c58)8#} zL9O&GoL*K6N{MFgu$6+^wjPKXJ0LvMQgcDOL9(VX)bF*^q<0reTWtC}27CH2wjKX{ zD_*>OwrY39o`p_b58hyHggvy~=^W^t1`=G5T zLiy|;l;#@NR{3KGd7m~r++!`anslfoS6dH(h?+UsEiL3@G)H-(8?V2exNc09Kf`ZQK;UGgSplZ|6a`3pB$i?@2n6~vAt$#75!1~R7e7zF}|sJ+SC+5Q&x zddY&Nb?5H5e>#8jpZgSpD9zVB9Ie#@Zjki}@mPq%v&^7XRyapehdsACfx)CA-~5zwg>EuybYu=qf?mn_e6{q ze!haJLP%YXWwanf=0uhDZVE!LmP%}rLE>7d5GQtoo?PEAsEg!IJ*n?>zI5?GYF3%) zmCW1#3LRx3QA0Tf<2{)&-Bk)RP``w*Fo6SL2pE*@Mc+UspyOVTykOA*ZzqJpYtg!F z2?GEk1@iiYz`$8wPef|9SPr0A(}%JQ7zDtz!_par%(GkL4!ZN-8cj+I{CfqIB4aL9 zTXl;W6i{#iVGtA#_|bIA_GG|f+pa=u+BTfHFVTd=rl5KuN=7nbd$S>*%|s~b1Ps9v zHt-~gG@Bv97u?oDcT9CD4dOtvFyKFYSsR477G7*Is`Z-&jbBGLKPE}fD^Zcty)fgE zL- zsIl|G2_eDOguC>UBJ_m+JZ1kK^LEmNpM>AS2O?X~0Pl0LT&k43?SN?AM<96fjS@|9 z+BkHEMF5;2tyK~ZMC~60F>=bXaIvkPfIzcG9C!0SL4=Eu>t^I<9BXoPNDJj4B&UEC z9826*tao%3`5}o*S5fT!2nr3cpn>s5n!h|I_GqYb9npP{aBtP*GDC~!WIzE9T~Rfz zu{iep#@CrhFRAhXa8F)MXxP2)abfyQs1Ak5wk!Ky6--DOcq%#)6)$5z;y42{X5eS zsW*)?4eNvIVlha=AAk3AA)4F8+Kq`D1gn+T)$8tqmY*ca=(<$3>ec2)NiaYRpF_Y* z{1J_&vxA0R-4}Cb3|3w!L|1k?)tzMcL~7l{#7>9|1xf=f^kGoHWgdyKeRy%5+kN}i zRJ}-3MfpG0k~65c1$0ruY85IX%R}%_DZ2n^vz#3MI0s+lLH_3 zEKUzuPiw1k*gej4?bbZG%yGJYn2R!Y{ogiq`1x5g}&|C(I#Mfh*b;$4krukSzY z^zx^--Y>c9_Gp`__Tdj7hJFRR@km~j&#loPe3rXEIn+E`xA^wQpndKGHTK^dLT^t- z+`aK=f17jDw%ea#=G}+3=`>zssvjDR_0J~TouL?Wi%xu$on2IdDv94+gdXLG40)LV zVSWze-ZWMp-l5F#|}L~a8{B)HG($UPzuu>O5{W}?VQ{pDURU4 zA*XtYS{C2^l{yTdj~vcX+d{|szthwlHqU&V^&WibHdx7_pokR!)ACZ#5lN8YZ^gum z7x+rUv~ZBs8oR1~$1Pm8(xN&L#=UOT4B~h19`?p5fw_}W_-L747K}~9e+6KjfZ|w|%z`d7Du2WwH0u!ifcgp8|$WF23AwZ_f{j7zd2C4Xa0B{S@ zm@);rU_C?bU6fynSbWOuw85!Z!|xb2!oE!r+9D``25O57{f9}oBZwM}jL(t>oAt%R zzv_Lf?IC*+pxcmvvh0PG0^oy15w#L9V5z2AkYKL%Hd;0ezzPA}mZrX5WlZW58qpLl z02xKXR{n*tS@S3@b216Twr)jfxv@cB8)d5cb`_niSIaJ=MsBBk?mK8ih4rrpzV@Lk z6WYLj6x|x6Qx4A5i%bLLHYo>ZRTxlbSxBUiXdz-`b*sifvgV^_Ima6w6T?OS5!inO zLWgcP#*GcpG?!_B^K%Dh1@K=IpAkKVvfyiZM_BUBFn%R;ehC&EOpiu+#&Ym`b%B-= z2EX2+#~D8`K#=af^Ig!243Y1YZ-8UM$56@k0bk0 zdX#>njDzv9AnyrEFSdm4Dg?9o&zqPh_?$`Td<5vWPr0%&Rj6TWZ#)$-9h{ewT1C1T zk@M=65U&*I>b3kFY~iF$NbyDUK$LZxo3q@$48SAMI3}W zE*7GdCl5he_3*9m1})J-^AL}Rq0j^npe4`Lw$ie0TYmVEWriFW5H1w3(aNWG*knlD zMxx579$^@EiK(j)%kozSp2+I2i7kQ z6biItt{cD&UrHItBAwP}y0g^387RFz6ga?UB!dDikswwJXr=gbg|VphXiS?ChMn+H z81x9CC)6$){8$n$!`FwKWKAS*0GBx&q4%*}?85O^BTxgR6&6P}(+{rt-nXghux<FwPOzbZ{r?1`$$4q7&VtX0jS-24rw7GzlvNF z{|6Kyxt2x>knPAqNJz->^X&(tWd1DL!O~S$uN#8{hK_76Go<8}qB<=8wy(@IAhDy4 zAE4zQs|bYH=i)f0XNyX=mXT$MF(Rv?%(Kz5YPTE5Qc*Cm;$4^)QlSeMYjOA3064Ks zy&h3RkZYY7HZStZ@%VE)B1v0iyHT*N00A;z{4WlrnHfza0QtHymoqv=(-oqRvMX6W z7a3iR|7&`1C&dpse1;!|wMO`SZ)xRm>|6jTQ}+A(@O^d&roJ0Rz-3YJ02kIS&c$cF z3SoB4{Z+#>`D2;6;7}9DLNIA3b|&*`ii&qMsTImk952G&+G_+Ti&g(#EeboB)w#Q} zJ2zo5_?Z9)tXW;3|06gb7wPxXhxgLH zgRo>pSn_>z%SjA#e$8GUQc$^|>NU1s!@T#D{p6WuPP8f7-ajZ>hKZD+6U@?wj^dR0 z(zg6FVGpDepMohvfh`>ui5v5IC-`&G=UHmarTAtxo{)`O!;Oh(!JOSJE0zR}?~sMo zO7bFe&mZWxw|&9M7wr>i?=!P1aVfrRsUm{fF&I%1o&~RNz5m;w{fGOj%Niy*3D}Tu z?_Wm>68{i0k~<0zj(67<0WR}|pAwtNvsX}n5tysuk1^%omH6!o*<(O96jD8LxF zX`D|eWLwYEPj*Lp1ypX+l92GGAFX3gKa5eZxhrOQ_}VUZCZIuDfZOLl+ljG^7S9-B z=;mTTjH2h=-ywzzSh+i--fM?0sGIq$%9MP}+iK)2GW~gRK@HBo>m|E#+5io(b;U@4 zEU*^gOJ%P@qC0N0wC=G?=N+cX(QIokPVyy-otLbZw&PQ@y$EI%ENnBSol51#p@4OU z7>ikM7}!C{%8T!vo|H!?q)GCJ)^h5jBYL9~c+=i}$_T<`p9$87V{Z(8v%S)0td=i! zy0EAg1$XL+a}PXU9}wL^WF>Dm819sM6CkI+1uUc=AV$9-?!{dD7+|UV16y> zXVjFKWu$OZ1XYW zW@w4Eq*ny-N~|#eu;iK^GGZ9}BqG#^1T-tW!StdA4XCi5`!El8nKyr)T8`{secG)g z2mnM)Kvi++u3l%`=X--M{rTRO^{My3 zYNjBE6X5itYc=wG#&$prknh7Ek$=aROxdYzhlJNWWa>%KYL8qs=G#U|{#5#6piM@M zmQ}aD%veyQp7BFdqB_=sGrwJWa#c*?jtIW)T(Abvnr$x%XW!-@vK2l`&+5F(3?hdG zzC<*hSqIoAbnCGKbu;7lM)u-qMWMXH`vQ?!Mui%`CU>t~GeOql>c1kTx|dt3ZEQyI zC>AduQMh#h$U}VV=zgn*;*~Pf;kW@A(0E0rk0>9j=6_nN43{OWMai@?fu0oM4a;3G zDg(dT$#E26J5mHB<0(A3Hh{c_4J{`E$-RJOmkb-mhX0Xp1i4-%+}Znu(uXp{^u8#E zJ#NVQcnB2|nq>vQk6r^&%jix*K9#l4>PGdUVVaRB;bF0^IY1Dc%~}H!=89*Tl);x^Oo{R;}#Cuuy%U-FD~SnrE#SxEc)6wcG8=KSUz zAz?m&rfxbU=$M+o3aEclYxKcj5wO8-y~%Ld&dG91`0T@#>n+M7(2-U+^QVr1Y$!n9 z`(eQM89UQ*FB$9TvP;Lc;Naq`XWX>fLSG=Ux=)#jM?CruWoxm0BL40RDnrQSOJn8i z*N0gBmP(A!YppyH_mN}`fKB3Sy~FaKe;2r*6!<#|P0tbiJ0lA`6^q$At?EG_3>76O zJ7_k6*BV-X@u`0UwL0Xlvi2E7&;tdNRKZxvV8r5S_75H5reAt#^7(h? zz^I3Z-s)jt-jiUt7aPE9S%$Ti#Cqjx(tXNZOXIxv>pLV3w3f#E9$diAqq>zP_#Lte zK9yBcW&tp4Ediv;3r{lV`6nn_==ZSdP)R)>hDvn-P*ToEV%snz;M61q06Q^yCjMQ3 zP&iK@shg-g8vGHj0(DyfQo#o?fCSq zdus2VpI=ArA6j+c%$kgT8_Q4EpCQGCVH&w#Z8GWAr*a@1y?`sJvZcFBY)qdJ7q zj8q~ye{K8V9E~MPnJA}I?EwdOU!-cHWYi-lb^Ayy1kdb}f-QRU+-cE8TSN-#Wc?-s zI8-ZyR(I-B$mxw~{otwHFSXjH^|GXG^i{S8L2-P?VXpS(sUNE}OlJmPdb$Lxej}>2<0a-qM)ZY?$Hs$uwH7wB^Yu-d{3?B&T+M$Ac&0YTsl^{y_Uw105QYi8aU1KUY5A z5RZLPF`G@czaXy?k7J>WFMRNdO0rmLuD*q{qdmK!fAvUT*1jpKscKnNgwP7 z&@I+nD~pQID{396@^F~%^HPSVDuu*~!Yx~RWM~?Hk&$;3AlKaIH+#5<@dqtsdk}8*aY4|RX`7?ozy|(8h&NS`OZt0m+KXvu|lrrPdP^s z3sj_48KL%jjwS`eyuPswOBLJ?jSvty4oRZCv6`prV^+`dZ zO374^Gv>=S3@OdK602g|tqL0v+tWZDS}TUY;n%2zq3kww%k?Cya}BuwP5^-xd^4f2OS*i-aq zg)>ivA@Gz~3rd7G1hr`fl{_~{5Rr9QM*@$?M2qI&hH`+dmjYt~lmalWM5G!ikp!?w zc0(df(=^rIHXUzF*hI`z=ITj=cul2n6cPV zXiOI|ZGixHYZ0(k2D8=R{D6c}jl4cDhAo@0%$lLKn4fDpnKoZ&J>{aKGW6IQ_6aEh zwr)h^1%~80^JmCU4fhFeGz%t@x~^$MtageD0L!HD$kSIr`plYqZbG$oV;_c2EhSQJ z$#>yLE-+?cNhp7nrcg4Se3Os3^vP9oF~^z}n|tGykl^{u%c2rM0!WcstCn`?jv3)} z?xJ*phAvn(OV!*6ihMEOJ9}@6B2-E5bmw7kW2|u^)TZXn?=T`&N)}dJB^OG)vc_A0 z@IF-MZq@&5769BSQgQ?ZHnC*`Rzou04V|xb4ktGR{`|BN4XgNt3NbjLxO6vxjU$v4 zxGQ5(&8^@$d{rS91FDZ%Am$i8(Q{r|rL8V&2X~Cdg4Wfj!qziaGI`W-OdP6>+|hhZ z`_vIr3>xaf1Si1+fC+0IAG*45l8+CGS7>CpdRru^Ow3G3E11u1{zQ@BZpk%hJT7`* zZGnxlimahJYJS7VhjZEe?7j<@5zBI5f&lkpGm^T#guq*bP^R>Hu)LN{p3!9Bl4-k5 z#OEZC!oI74`0J{`<=*^T+FWbcBwC0Cqn|wlTYnbTK!{6goZ95z4Cp8y;8ZEV@sIX@ z(@Sy|z~?m`OXTdRmJJOnZ<}p{dB#)_e=hW-MI^+fKKhHBvTTKz{6+LL{Cs2+M<=KL z9;B^>Sw>aNKii@*B|Y(!@SR{Tm*`p)>s2BW$S4|6n++&L`Sqb5Z)yErq)rEJ4&;(S zRy(O}8R6PDl^vGypOKn?;F$~p6`JB3IW0;TO4~G$)>g70kifcoa$1U$P3daox>Mo? zUj?-rgUCk{z`665n{j$%P`ys@80iW~l@o z^2Wd1cMl?L9c^Asrv&q{d(ZpK#-;AuZ|T&@9zww8ucznr-Bd#td?JHn0*gEfkbfUE zYtL~}tG7&U6sU>ZlNqeWPBj8xBNk0mg7gfSB>>RP1gGC3SB}{K8N(w3g6AzE>;{Gh z3)VQrP$g1qk27q^aSJhC_$BumPjT#rtL^IFfqFRvb1$;(JA3fm;yg3->;+U3!^JZm zyR{ngW74?^!ct|<(oqMWkLXkxt_a@aW6x4?h%x|=A3clm;w{QY-6uqD6(G6=w)WW& z=-vV-lr1UMmNx**o%rRI@g7RNHmwa0C~yFR*G|(ixJbVxrvflFuZnsJWqiEK2!M;vACP z;qabOsHI?qV^Sm}SneT4???!|!}SuJ;q-QZoq31nB`}&Q@H)QLYBFJ^z?+%m;A<+GcVT&_g$Ki$fm=mos7TcpUFIG7*so zGLip*?YNXNk!t)l5FevY{Hi8GLL4E z*^?C6*%p}P{Q)&RN>Lv%FKV#ZD@LF(I>m zhM^(KlaJSaINF+717-07V&%wx16V8p4`aV#oL$Y(52XYr|j`( zyl`2Hk6G|M#=)Uuo5!+{jRILs*QbqC&e9u-BMgoP1@tI1k9cH(5#?pw%5_Hs8M|Z_WS4SC9sHUo)H^yw789-brJu)TjFI#d7F8*ZD)Kd1Wdi z5HB3(Z$J%6g+e~$a8KK>u=^guwzVWN&xt1>jLeP&Sdke*s-S$vi(U>|TemoRnByJu zCN8Cgk9B$_pW)PAhMw_KECt8X4u`j!8|=FbrCTJEL{=V5o4ZX~8h9wdT$hO<-DB+*yS?MCc85WMZ$R9c zHJg2+BH&{EA6e)L>jX2g%9aoA%^u$-OZsyjJ&e*nybHJZ`bKN~`2<{Zo;n^k!b-kp2=4}puw>@=|e13sBoin6S`gcyf!kIo3fyFc;d956io83ssU3iLcJG`s>vmvmoBi&IAwR_1JMBcPg8 z)vf7{_9%3gIsUkm7^F~75P&j3Cj(MXg&YMSF%L!qG<2pyoi96YE>N!!w5BUq=4>1y zP|x~=gA_Y!Hr?QikVp{4kv=PyPE_i7mK@#ndhUSH)-SU%HAAuv1`!800F+pYV#{|b z>b`c>T>w(xf;3rGGIA5j+Pt?}aF;4)?l31cO+M0tsP4+QuFNI@)J}=(ok0GEOdVXv z)|pw@xg>xrQ9%5FKXb6|pG||=OdU}Xc~+_{W_FLNtMlx&S~iuSAi@NoV>_aO3%Zl^ zLamilG5A?62&K-Fme0r8-34FB!sy!^?0oJIhdk@{ikXwd`wyFkidDv_H z@)Zs>JckSb&19b2YmV^M@Bsi9`3S8OI(^^X}`ZoT3v>656K)G|RGKw{y6q9`}e0~$8 zWmx>B>)eWOsb{^h=x4t)Y-1_)@p_+fl^zdt=Md{Ng70VGX&51^jXX{M@0Lih!uc!Y zl&UtNcwBhlbCTfsjRSKSsB#Y(xB;kB=s!4gwK;@BdpzUwRc(jn4ScLx^I4R~%8@@! z6gBBc(Mp}xn~wIXbY$;u0Dd*F`ML2Tt@_8mv)7x(1a2hu3>4J%AH$L>2QA zM$d1KjUWz8m&Pj69P;Y%R2Y{ba1sDn94>k;?n0Su7}l(TT&;-`%;b5YB*i2L(!FLh zaY;O=CmXAX!|p|IS%DBr6pa#@+UO}s$WBH? zZ>{=(V8vQ1`rO#co_A~1#$O#YugpsDYOkyC$0pY%z+cRGn3<3tn6~HdTI_DW`Ft|_ z3VJ!mJCl5tm;TPvE$>7of|}~j;l~}Yic8B*_l@ezWRGs4O&YHFnDjIr2L8Qq@O&3M zdy$M`wCoh%tk&E+JF>XTY!0`@$#XnBd)$DtYyl?&Z8^5RK3F%*yzRrl_{s6@*&h~r zCcDPaW61Of(T9RN69@ifU-=AWKr5`{FdP~DG7h2qn`pQ*dEPXn`kyoB8`FXzZ2tF2 z?m6{67v3QjXqeI!4s;Iuc2y_DN{r@>an{yFC6%o<6}ZpWh5DJ+ZYGSs#|EpUJz09< zsEL97@884c#sdp=WB!eWX@N%UEGyE-q%%*SEvxk{=O%u^Za8~!6~;T2fZY(hJ~E}< zXc2EJc=`9EXUg-qYS~hd;ff7YkjiZFq{CL?v;5j|c1E?nA7s2A!v$UZ4gI&70o)_l zR126evBdfh(e`Ox;)8esZKJfvCT+i?&#ZZb2Zo)L$V@XPCMeivrolWJ<#Gw8y50-M z;M&7ivDU2-b&X!GJ0d%M$sWKxfunsxV4#hI)6gvmXo0Hs8;f)uT``U$ZMhl-OHx|- zv64a!W2Zk*Fk6tTX1pW-2GL-lt$tXg!F+mb7hVGZGL`(rXCIyP*z@}j(W$<#io4%% zS)o(Ile&Nt?t9go8wVP~&PClWbUyd&eDuzUU|n;*r4?u{PjkJfMlv-`knul_JkTVo zs$_XsVw=9HPNM*n%kQlz15Z)8rrCrz38R=7S73Q0S;BB0)KcXN zyMmEey$n8LcG!9*kG_RcO`z|_%$&5{Jy2DsYoFAHr#CVoA!Ze|!Ix2ZWrq-q4PfQi zZef-bkRh4~WpXTRW?Y*z5C*8C>TtfU(7Kve9)BvmhH*^10jmWl3F{$o@~F7PW5+R~ zA@){PK3zkg2GQ(gUZtn#UTMXq%6M&&{ zV2dnea5wnn07ZTjw0;6Jy0*&LSVKw)fdJB~(W;mwrSLWjk-|hkz}Ha`Syfv|i!q~H zERF*#$-*C#2oaT`tn#y1tW@PW3%ON1`H#tAEY9s(RJT#qM1MsyP#KqdWBGH3Z6?k{ zrK3sk-RS#J>uAp_tfSI_u;A>}^@Ii&s}Mj-IDl&F=2|lVy2c;Bc3^v}DEA3%_`4F! zO3=pCHwUokH#NjFIiPM%*yiWcLX1fY=)nMx@VsGYTlsSDY!K z6@k9P#-sQXYZXO$~Yw#OtF+!hmIHNh6P_KU^-v)3SWTwn9qZf5lq_%E%k; zx-+=k#S`prpMQ|GyQZHQI!Y{adZA6fgQouZK)YLBV1fJ3sw9@d$|{1%2eh<7* zW=m<;%o3$gGY!VO!$L4BDHo?&uJ-(gU@fI0tNBR*=&m?`edOv0W=w&GEj;`ZDX^e8 z<$z^;{Py>UbX))_P#TQ%uppqkvI#{~R2##5fYb{Y*~Z7ej;aADh{Aqx3ulw1^ip7) zqI6fK(DIwekyMEx8uH~`5*S!0gWRli04<1^qd6ux3h`G58d5rN=GvHKZoyGgH-M{YpVn zfbx+>a$X!Q{dMk`MV}-cLhCL5oa+HZJ&(djcYX#;3?@;97ej0AV`UqcOOdG^m>V_o zb+j$lcCRWNY(G_J5%;Mj^3aQ<(kj53O$=MeKar*1GJF2Q-mm-L{#lZk2~b2qsxKP2 zJAz~C!YeZsI+XJ8TaC92+|NwjRe`&e2m3wBE_r z?fgGhlS=CaWCYGk2JUGqe3*GOG6=>zurPRq4l@9#?XcYFU}IYbjlcQPpwCyW-I?F4;8@TvyX+g&o83Bj zE$IqAuW(kI!%kwlX~Prm#M;D1UJIRQxcv6hfkCgyjISNHF7mA0`J|#GLpB+IQP5h% zp!8k3eA2-S4#-PtdB<$81cAhfS%-pvQ$wFmyJ+xnADJ7dZTb;8Wgp;m?)0>7sc6CJ zfiLRX9Zz|GehCg*3AxUCJ}yG-xO=|7aAsCOsXA}9H}Nt%NiBZihFL9dlxbFx2RE=- z>x@)aUoA>1Qe2G*L*chxT;+8GcO^6XR61XGTT79trMe`kvgejR~x7VNl68ZtkF{A@EM~d~*K{EkWcH*V-jsOuBVc0Nq_^ZwQ+a%d# zqz&=$+d6m9nE92Hj_?a|(vh6=M6(xIM`>esq6$N?V~ zNTI`}G@e5Eg4MMt39L=iS#YX6r%F#&Rlo}lm&;-7b)!>xB5apCCocZ|erw06lb($< zkQH>G!xdQoaGi>P04MQgq#=6;-iSZ|bht<}at;QkM2K*#BAiFd1rWxgDXP#cQ?4tJ zMMYd*6}?D?X;ZO=1d#0nY7m@bADzx3fQPd%Cn<0VHd3DrcV;3aBd9n6!sI)W)3xLc zAf%>|1#CD8k5X<%>XTvTB2M@78A?aM4>u!3SYmiG(vU2m<)3Vf;Sf2jIV56B2IpEr zZKgqUB37G@&8LFKXoS%wczBu$utn_SMDDvI1((GTctj8troRc0rV%kL)Eo?!Lx!2L zk%^;lems)I!Z=Vt!^cQ>I@X;mOyCR2J94p9IlWvo{ezi~0l&lnRt%DgNu*;}%h5^X z9qfTJ%o`ABGt=D@K(J{AWFfFRKt8}E41!P!H451?nmLeSAst()iNF!j9#nP4Tg603 zsnr7;qovHlMnw_eb!M2S9%!2^g|p0qg{+hnQ*>Gx+#SLdu$5CO$Ty-&xh%xTS(PKR zdz~mMpMsHP{26s@dD;! zt~9l#9vPM4M8@8i1AHlPGxKz{u`G?A2oF4P7D5ye;JFO=8O~8&z~0R$WPCGVlb|^T z14{jMh~)$xRtBHhULFQ!l*V_!0ssK(t1YScL=)FVd*`%Es@Xf*X>4sw&H-4HKhXud)2d%It$#6ke{wB6hpwNJXpkO_e3W2N%0dcd zJErno+=DG{Q7PU^Hqzz8RJWQ;6#%SZ#d!Qahuzv;2ADJmkwOMUqmeEE(7M}%BnIQb zW4HLPC`W*>7Ep+7%tJ)9YZ2PkbsocEC)uWNtx2;3`Ci(XT+S;mH$6*NT`oVsML1B( z+zX>3lkghAG}42Gff26M2%Q#_=OE-iNm#+%{F;K9WXo5#J^2R zryLvKoDVlcn-H$Vuu(X&DJl=E9B8H?h`C6$UtdSH#UT^f>KZYspT@L5e}FhKzVXP3 zwz2a4pUM|q0W$(ZtNB9FV@-2{z2FD1sS-|_7N$l$tbiE-W=iGoc$zE$po9%Y zis1LY&XM$c>-V@q+$jkRZ?=ny&7HZGYA_uBOCc6T0G6x3IqdDGC;x$Al8IibZpyas)v%m;XL^99Gi=(xdw4E{>*7QQt?I<{BDzI;>ykE6pu+A{dO(Cb! z$>WK`B2AXvE(T4XmZBiu>NxtOIGb5S3=4V7u14mbIwHDenXk<+f_A)-a+b%$*CT~2 zXyT(28!161i}X7zo)yp@KzOrr)71t*rgcRRT^EeY=OKl?QOOt6Wo$+@75NBxCb zf{a^y4qb{`t=RET=@9rK?)Mp$zE`dDh;66b>?LUm%taYI&ewO{nrk!dI&sUhGuyT&_qQO8 zseO=qwzC#f00|C{cs_?rJbe`ah1%0uu60blv~8!SVNV4eMAULOqqLPQ{4jtYhTrHy zsxT49D3E@H=j3{<;kM;IeJ@Wp=jZ97vm*}jcreu;oXrIf;^8;|pj(NWQ_eq`Gd?Zo zd$4&Yl)&~gCR*a_L9B)JbUsKVv>}`nM5qX50>12qu6lx{iTLd`TvdFAH_M(!vckftfjN9@J{jfW4lCORWy#=wx03 z!Vm!8`%C-NMS5aJ5>_7W%x8r&uGg^;2tgbxEl6;k`Zx{Neoe!h0+(V7hhivMMg|vG zEfZ;AgTDntG~t0XM9G-MY-}SaqQivknA-zDVyQpIgE5hEEy<4zb7sPuXywj}FaR%b zy1x=7ht!{zfQw4DeFqOVBkie=@RUosr3iU8(vC$vX(FXEeQCUYN9y1-{IsUn6{e9G zUEH30DSknOz(O7XqCmo@mVaJt8r9l8iA)`Ci2Z3SctTU z>5@+4EUxLa#^;!7xwyCkz7*T_M@aTtP=Ja#Wr|KAqSFW&G(g_4{Yp=;(v3zO58Kk6 zEFS|XjVJQ?QWd;rfjbO1pMYZFngWpu0Qk!x1B&kWi~|F^=L|AB%e2=$1R`K+{Q^j@ zsB6oq*p)R@;j1f`*OZeZkZ)44F_h!^3E13bl|w9*JAdfq&Z^aGD1qBxV;MG`tq2g* zxC_;yn$t$t)DEsG)*g|Um{Sz&*)4P2tblOvEPe-#W$aTrGbz>g9NWao=&8X&$V#5s!eO2hmMr0h4!n{aI?1=)%*xfq?7-*RclD(K9eQh6}=M zk0>@psGnt^;=Uqy$rCf@?r~jNPV+nZ)I(rPt~^Eyp3VRimHa~!cDK2xe@Z;q)3y&m z#7=xH_7}kMFkOb%)s0QB@6Xs@EWfk=vG%@1Hi}jIs#%*f|8D=6Y&~?g-pKlmk8KCO zlwKm&WyE%{A2UEz+&;}&&~wHyEdHm!+lzEJv@B=yJ=-Qv!5kv}pnR)4`SIIxnD z6z20-EY#aJYFb?4AlPLN=zg;b@v>niSrT0J4^#joBe9yyFr{)Wb9#+}8G;8&;gYFt zy3MvdiPU3>yD_x<0(MC95paDb{En-@3;A5Bn^tD@3!-@2r0r-E&8Dw46Zz`#QwDb&a(H z4AIF5bB6ELh9d`K&kN=^)mSYz>l(^iQ6B_pisM}conX#SkZUg;I0iGc0=P9^^wDnI zhKpS1b~|v%MS|@opg*>zwL7BY+Zmz5b84HPAO3wW4;|b-jqeW=rXWNjwxEcUyMF+- z0Kyyz0X7_IIsh<{Ng_t-?b8v1C|+rU2nfR(L?sG>>hW>pK`TIJe_$$xI*87ZkxT#H zJk2t@A}ZicrGvYvsa(6|;(Pqd#(0Dd1Y~Zq%Plix6c20z6xb!4q>W8ZjcXm6ZlDk% z-y;}c&dYn}uTD)zVsf&GouE!ld!T1`tl2_5^Iop3I zO=$1Y`RA)gMz8JOQ3hF7Xe_E8U-%o9dbpEc)NeDwWH6Nvxi3VcPE#SRx!J`}{@V9M zju`bv83HICLh-lp6ydS%AM9@r3|?5`l<8l>Jt&4zjLz%YWHR;HH%NTHr{+Z4iZ*L@ zOxDhP|M=wAu{W>(oZDPodRTqD=pGMX+5*X)h_N2pv#y9AZBJCcO)2Y=Hf?Ii zIh)NUysk0Zqk!H|wXJ^hbpUF}Gs18+VQO9WR<5U8pKC5@m>~K9p50^%~%o!1*7e> zCUn;Abmq9quC%%`Z|y}Iy!$-W8YdUhlSLR(9$;OFCJdB)^?A^Qqn+SV*d={-f>DO= z!}KZV4t$ietd0NN`;Aocz`UgMU08?NIoy*0+&#N>S63IeST}d?*dGKzmN;E$hx@12 zH$>uMpDi5NJL+$)2}jz&U-2KQzkMj%?Ud)y;@F>_1UG<)#+GHMwGHVpuWAGjP67kr zgF>f$q9$}j?7}%$X@H7iYDWYAp3Tk%KDlMqd|*Ab6ei97v2mCR7mlOcOJE!!!T?q% zETeNXlj7RX7^K_bJ2wL|wV%d4(O2zHq7o?6kwPKaAF8xKknSS%ZIQamDh;B>BR9`@5MyA&Ai~& ziRMA!mp*a;nNppAE9h)6F9E=Vf|)sa3qBL3MgEXFL2%NGCrfzG4g_F)`~iY!$sQ@< zCJ|Zj?omHuL^l(|Y*Fjlj+*SxNhP%#Q!kI4(b%NGxZ(`_4>sxqhrnK!J))RcYHupv zzCZDHw(n%m((K+7;PU=k%eYyhS&|@`s)ST00|`lcsEkr>1A=2Bw`JAD){BXOpH(Xp zvk@Dus*JJIT&kO$yVtc2T|EEu<-zr_qlX_7{dh)QX3lS~Kf8GG@9&MBivWsDh09Yw zo;V^xkxb(R(Qv6vBF2)OAYg2_p&VzzeUzMdypFTaOfSs6^WpURuh)r0jtKVr=lIU( zY3zqqaNWFO-=Y37?%`Rf9Oy)f;LL&}b3}Yh<)fn1*p(gouUS$~PnIr81O^Cz&rN`& zeyg{|OlUmo?z&(FmobaT`KP(PL0Y{F~d)gdT|u z&?POjJo++zu%Z$)IF8-`B2DIc9Lap^q0p6JqNnOn`h_uI|5;L!JUC7Bt z%_en|AE*GpQl@EtyScn60C<>Y@&B^%IO+gbfS9}0!2Bu|xjlR0>;wh*lE~^zym2X9 z5dd^KJ7veA-b#~Y$O16dwmi!Y5;UC|^*HKMeB|>h7&i#`!iWVCvNWW?yCkv4CPL;U zqBu`s3z$0$*|#lnza1+BNds6T)}Tt!PDEQ6%9XMAv#(Ul&+b-NIe+)0NfmB>j2VTc zxZ(Ulkb6MUK2U=ade#iiABj{#$nl+}n|Wep+J!%6@e&8#5q-Cu6WmyEd`-eG0vX1w z6NFFeeS4$=2@`cSfsd$V(6|$5ZYj=TGJtYV3X>qu1WF@4mljswFu7%PmG{yoX4yL$ zBGpk%C=ReNGN`%l!}JoOFyWTLbj)O>2Q2Z5^?OnUcWTFhf;1{(`-K}5_0&h0F{@l# zfr=e-h1(iW-sTQy>w2J&diO*nMdO_3HhTisPIsjdtQ3*!>o8JM*wc(?dC?EG(UR%g1siAS-?Kq1Bvb*N_|=xe54(6#YV zO1oj$*TbW4b3YwD)SE^Na7m~(x-b1c(dQ527c?;PrRva~3w$Byk5$rmhOD1k>O0~^ z2qlz5_f1o^=(Z3STEmBg=1=o+{7u4xBQZN?FCVc73FXvG4{@idp-|b8o z&fl|^1~e-P~!)vS_DwQXx%KA~BJ zH+5bj0%n}*hC`!CyHaysn*ZIbu~r-sQl%lvK6y+`CIeTw2hb|zm+UoAOuoING=`mmMvh$2i6 z;X0!;G1%vWiwGW}L!_F=JsOUp(e7|1IzMpFdQB93 z!dlF6Cm=!j02FN6OauXZ4ZQ*bNPE2BWS^$-uy9{9lvq_fSz%+ruDrriNvc(ZM3=w> zK=@6S(5M|+&Y&INsy(_-?BdzKUw-X3PBtm6d~JUGR}I1_&gZ)UbGfbDZ)0mc>Z_D? z>#m3!B&kI`x!9z}w)pssi4S$I=DTn37Wfr!tnFWKym)@)*x}zVKU~G1YD zk)3<}bMSlADw3+T%{$Ul(+iv0WbnwO8eDS6hF;PE=Otdg^LA$ki7OE#!G*}64nYFo zyJ?gltEh^>h$hI8sWK!uKn8K!`ut2yV4k>bf*8UXRY@45+JyNxVM4*6l4*h|r+O-m zV8=`VJu98x62(_!qEArmFzu4&iIO$IUk2PzyVeGuM1*PwdKsdR`jBL0poS(MZ~8Yf zxnCP0hX<^uX-R3jxJaC&#`wBQhFZbC#2Uoea||^>DzN~>;H8v9&9)=kj)*6@FcMLl zItORrHE9{=W(hz|qLw)$2u3BwX`41118LIwcIH3M?3E7&q?*fociyG-L`d|IsXKT{ zpm`tMsN}ASq!cj$8wXXmm^*Ka57gD~sxj#ENbr1g+2tKjpH1yn&BQyGUNYl7mc4s` zm6ovC{#`5$SC&QQx|u=+C@L0#f)bfbVW40*Fy1nFJ3}bdGNi%sM4x5oq-EH=W%!Ea z$!*IBZmZWl!ya%hQP0b7kMJ#y0()nKrzIi}M*h)DP%m5EiMh{g9c*IQIhsIBz0BZ937;LqWY>Fok=}{WxIf zK{e>DfNJh?Z#DCtt7!M8UTG;h>}q|j!I}`6%v(NSx3k!QW{jEf1J?Cie;7oHB+I~`fl@#WKoNb$qCUO+rG@o9J=%_k5uvzC?lBbj`8H9b?YG?yZfPb zBk^{lnRa6(cH<3p9M8<;q}|lK-Gddohue13-1ak)_Ot5tkBsdf+u3s}GoOaqKa012 zo@vjyPkhl}|FX}1e$xKcy#4DH`#0P6EN+JdNr$)U4)2T|7VR9Cd>r0~I(&$CSk83# zSmN-h!QpeC!^-3XZfC(hY$egQN;w1CO3D4s!E9ESw;k|TrYWw`y*z4YmM+le<1?(}Ya zV-05P$T;5Z`?bCtG-&;AhFiA6jWox5{}^u9Kfif+xNo7+E?uw|lUE2zxP7Hk22J=QeQ-ReqZ)pSMZZQmm?Zn=WiBFlNx-to$xh=l-QK zVPLxqiP!zP{O;;p3qZukHsHxTM8(?0EW3X<+^Q_)xVj%-%Jn!}yOig1>f=&ArL5hr zATaOv`@-O=+V@4Fogd#jY*W|Ym&6p+J~$EkzP36~{OiXLH=VQi(2_@BAk<#fw&JR*x@xV<3ZQ}?l|JA)jh%s_H(~HFSRZRNs7mNA+_< z`_qum|7N&t>ihZW^DQQdW4Ij>J`rlQBU!)FI;r=0rES_$?MwS(_Y+?_o*%9M@{i&6 zOBX9e?Q8d9-ifb0%T@JXZ?ANI{@TmFulB9)`_mKO?rgrV|8{r#=jU(t0JJ*i3P~iC z-H%afU=MKXudoLpEA`bO!9$^|9JtxAdSCMN%IXOIlKR@Hd_Ko;t6Uu~jwbTGyEIOC z7MN(MSVJ8k?pvfk;@c-l+YQ)+mY7V24FgQBJ;WGOE`7o)7*=_n`e;^ZJ|cljd6YQ# z^uT1pDz7(WfBi9c2Q$((pt|wri_oqwKVL?a-#4F+xMr_!XFGpqmP=1`N2B8vkM664 zxr2PWs9dQ^;q(Rm^2RP(;XoX~v)5R@0;{;0G%y8lU+E?$9^7MOZ4j}`6(a~E4lG+M z_9`nkjQo9m39e$srTuoa>Gv^NXT;Q3W^|`Ldr0Zj5Fet@k1pjJ=(oKdI|G?5p{7b; z-=815_2=jO>2H5FSeN$x-CWG)7;cxVZyhMMZ}|52H{0szh3)UpPVW5Ky!!O_{I3ni z8R#z;YX{*WcmIhE5}=chyIT>{u>FzcXI$YD$HcJ?>;y~;9;I&p@kBxXxCR#5YPp}! zflgEGqf9%G4hY|7ClfMDxsQeTUPSDWCi2JY3Kj4FDI*Y}2!2yGJBA&~y z#4Yr@rMZW$MCV+mdk_{(m;qki!SQ;HJNu{^An7)3ShnB==;fYk%ZY67u;dU*n zU@{Qe3j)?5YuOC$N@XkSap$77oEp1I)k9mpve5~z7i)RloF@CzV-tS= z7;d?%2$!rU1H{)0MiJK2f}3a^xiTnRxqnb@wKpt=d7@_ zBs__vWD1oD0=pm>EtnW9{hYeUU34=eOPMc8H1(k23uz00$XhU-$ocs=DS%kC+c`;^ zl+Gy4t=R=1<781f26124;OYW15;!eRg(mX`_J!9jXAxU@DiH)EG2DnK8p98RfE6+k zbO7LvpumkPKb|or+)sc3W#TNNhyEhx^#5@qBy{53WC$IdiKzuBV!lgfZ^&Q}oZc`% z@K@2^>^3(_wMr5WR$n+GA%V`jQ zQezpzvFHZ3cQjk5hUiawJ=xhc)LHuq@Wg6))1E)Y9|{>?$=8Q%tHetT} z?GOCD^O*3{UimVj_IQSJqPW6mfs)rNu9AMjCNST0B@~oU(vu^ct<*s{=3D&9+QD zx4_L6*!k0q6dkP!@yY}a3El-_1rl5Z;+Qvv?74YDBVec(GpOf_;SN>l5LWOpj7LoT zJd!_w8zDTZt~mCo$kuy%mwAzh3Gy}B5NrDSldx>YIG8QUHX1_elgh8!H}4h`3H)k@ftNP;NYJu9+HkM^5&Zu-0j0xinkY) zcXosvTpq0DU8({U$ek1SVrdzlyg_KQ1u4&Z{mNYbwgCF92~qN!-I;Ar{7G$ywyI&N zgn5T}Bhllaw1n6w18E(7NNKKg7I2bi77-Hs>$& zPSXmWz(okBK85~;(C5Cx3@KA_e~gMHME|l=lrUG2S(`}(myg>@NTNlbxwL^z54gLg z&~;?b^ayuuqk2<@#f?PXq%W|@s!?I8{pUdZ+4nDI62-H$&lv@pqu;0}5piUUy2n1g z6hedfQ6rb<)peU9*r9RkEcNQ7A0FPQjJqsTtJ1B_SBL^+m)R(UPay8;)Ak)AKQSp& z{_T&)r*|C+a*%|kz3>XGx?M$wH`1a0N(I1V^V|WbT9}CboO|I`Lb%ziJ519H0#0N2 zPI8tsr10JV9o({n#8^Q?!hAvs)I9zm(owe^U4Nb#(AFIqPv(aui(l=6GO8g3SI7+x zY%?90Br?cLz{F#`isfS@84U zgCQycj7w&%*^iD~a-3D_<-<`)3UV9#+X5nmDad5Z9@0)k=;dw=$|(>pnwA%rCTWsb zFsfnPoOWX~jX~P0%t$NsNUsWpu(9cN-RTW+8YsMi5)f-h5;taOhZ5snYNL^S=t!!j z$groTu*3uaoF|~>vrzzn1dBu+XJ$@`${>l5C;*$xlb0m8y*w&m{cisp83#;bTkyE4 zY3@D(4=|ndh3|;veT@T5_)FyjO91d;I$g5@{GFpQ8*?gI)Y%XSo6UkBu(&$W8kzU} z4D7hNr5iep3VOxTr(op3W%>Z@Fp2E>W$*(3FEx6>wfkl0T;{chYu7lp6#~>ie2-cZ zgn%y~5`F@_7ILwStmp-6r9!>|6!3J%GCdUxy z`EdaO2I|DoG_R$?XhFJS{EGKQ#i)TsxuB~E|El82n2sPx`Wfk&T<2=h z$Z1!`RQV5yT>R**M2p~C_O{p05Y_aF405roj_LUk;j7}511ri^2|7{%ti!{93noU$ zf`B4OOx82{$oKK*$*nvm#g-s$3~-PPHX#wuo`9#2?yv>8Py{S77Zv@ysMzTOat8Z* zLjunv=38H1aEgB+5BTm73i_@cKSXd1UA^@Bml%wF!T6Bm8*^y2=SG7mng?>$vW8L! zH@{m;iBdv^#4f`%5l@fjb(g|z0dnqA&YxN-z|9@bsURljSp_jV`ymOgstEDw03(FD%F$OU)#(An5bJ7OoyxiA)wyNIVEs3#FO(DA zp=B%p+uD6}$D%O#EPp!W45w8Ve%C%3td(J8qjwf|2CF5AbMiY?ebuPWNe7`0hszSH zD#n!$_tZ71T9}iM>oMwX)hVIGoN*LaQP27dT5co&6dkX>Fncs-7NM`wF#5?nC8GS` zEUc`kLEitIO%`a5X(ad`f}5aa6&gh%k@IK8rt+a1L5+Q-UOu;p%jTwpA%7re@ z74Y{L$SAgT*tFsn!i%ut@#qpv3vy3$u{g8pvoMT*8VoxM<}NwKTSL4`P@_0a<(zS_iafPWpoKwwsXp&_NKcTN383H&!w~c4K>tAvs=VJYL~5UKKxHQ!-xHH{LKm-n2d5EIH9?Jkjnm(HTF{ zT{3aIZ=!F0;_mhYQ*v^^cyh>R@_zi}XvySw-{j={q{vXMK42k3xc;C-Oo@8vB6;fi z4D8`B@V;iMuz%`ymys9OgUm=cNdag5`SN>pu}Lh@hliqO9~AZjLKMB{HV?1z={U3D zhR?iCH$032@i5EthI*(f+Q{%Cp-2t1#bSc}; zhPk%jM|Hm5r$m9Sh&Q-QZ$g82PvrXBR}-DL-rS?Yxuos7oBi9(F3Bc#Z?a9gG^A{A z*!8q7alnUTXyt!`4{>D|+I2*_%GB+S&(ApEqtp2NEOT$$zrcs|2jG7KA9rs5`26qS zW8csFum1~tJgPtZ@8ILz#LfQ#ANMZ)mfYLTdP7AB2jj__%8{%D?$;ZRi3CmfLXsc{ ze3-3Z1i66$pXG&1c;RIi^%t2O&C;JCu-*lxbk+V)w2zXMZqOZ^@~*4_(dTIs89?kA}5z^{$n*3Bri_`lQaY z(6%$#e+4I{^f%@Ou8CDr6G~wV6f*~}?+m06Osv1P{J_mv7@z@tfjG;Tmj}4iDq44SX-8&Hm_EHgeI(N3V;2E6Crt6OnS`~ZfT(I!3TQ<6O zQmzOcjNssBi?wwn)$R?y!X!90F+*!{GkiPP%T;h{buv-UVSQTSXwp@9EtM=`MV9&V zGjWV)_7SxpYPj()@bPzRrRyK?F|v2(AMkOpBjNR}oxj_OofbO)Hv>SEm~X#xgcoWI znBhP>(kNm#Ar7BPsIJcgOmqyh8Dp;Gu7`ADqVi|Pu>+U^e#@jJMLStDa*gR#-v}M` z&{A$J|Df0dLZV)YKP>vcgAbBj8GruhkYd%Xfd3tQ%nJ&(6&&b_ymn#dcbVu2Mtg78 zYG!awf!L$&yO}~`2nRS-%7b}d<xI*qRXWwyQz2gKMb9Uz^t#5T!q2W3v$(4bMywxLX(osR zR7;Gc=YtHX1q^IqPR{e$gG)0mcqL`p%BQiNhskFcHy1hezn>Ek<_7)@kzN=eXmZJp z)0u~8B4SJP>8tgkv&tl_Y6V$MbSN6-waBBaJcZdMUnY#pB@&4A ziy=A(CBq=JD#e8sgU{06FKUzcLPkEAT0^q0bIu=kmA^0zS2PH5skV7i=k=q`qvMlF zn`*rgfXDeMOb7|CqG;>|Tu}`Ic1i>N+mEs#TI@LG*0>>G~l2PjkwK;yS+ReZ!2!D2sF8%O8? z=+J3TIoA#{bkz_w7 z7z9G=<(6$r9LYx8Q!lbJvn=2W+q`Br>n0tv|R zzZ;;^NW4--T&|le`IJ)Mo-}-67%a>Q?-daqvBrDi~Gj zV93b{m>6R>8d2nT#hm%_$8P>?=Tnh?CyvhJmK(@i#F~o$ zJIzRw?PeYt2lEhldfE~GYY8h9d}K~fyCu%(`tR)zhXr>{_XZgh==d*_9F3Z#jiEoP ze?F40-hN!|@T1QA&!^h~k<^w4Kbp?{`Ao6eEtw?!^Dw8y<(Lvi@~QMCgNi#V-TX)( zATlkgB4AJDD9WH{h6f0Qe`UhZfNHpfOr|8ee~rcqM8pk!`-GB-?ORlG{59_Vcdg)I z-+TR&`1Gg)HasL!qpmaB6f=aCJr9>17w5~~RffN@vwii7Eq(AxAwDSzo^|{(?V&>m z%p3qg1Q(!h=Z>$ljLrI{$_GJtZNRiziQ9gH>my-U3R>1+!a24k+cH>)EA{| z-aikR9GBPq!w2nXzt^bxifmS+M}9a3f0fKUyPr;-PLK%MZ3%V9g3=UFIKtbkzUJB+;7H$aN&eoZXiVV2AJSbM=Y+?=P?pc zqQ|nu!EK z*9DVYmF1aJ3D?m@2+)(e!z7g97@EP|q78GaYV$Lk(&qYV^2mFQ=1DMcBQh)5FOVaC+|pvVx?!~$LRFU8PP z{U0F#uHcl?Qg7p62p2&F2uEv{yuRy0M8LBv*GZ-7A}ZA{i9bOA@8(8^(Vj!^IeURj zF#CDXjY4a`YdOv-c*87t&n(3= zS;~c3sy$iib6I*|^7ekRwWFxRUm*XP$>f26?UOVF)jXMN8|!gRf*NEfjE z={)_xp&y}|`;mM?PDT-7SP+IV1Qnoke%V9Fh_Ip4e3e2b=AL=FtBD^zct8IEy#L`i zmkaJGfYg*P^0^lrt;!Q;6^JkZ9Nq^<0VPj)RX_1z-3P6Ns8S{gGVYgfk^U?BiPZ{O zDZeBRruvF8KquX#ww~g?x#GLOikY6KcJKXhGcK^oYx^zy9lN24v@~8lilAQF)zPGD zqcQO+{IDROXTP!}u|U52#p$P>lpXi*yamH+G5*+9q(X$NRmXMWrsHB7ghO5Qx|BB^ zMA0wxxmKIqM8)v1kzIipQ8F@#->+#w=glw3TZj+GHbu~`z-fW8$WmPsRe{sl5_q6F z4-=vb#o(`%9=qDYhsh;ltI60~$2G-J08hXok!Oh&1vavsl~9Rzo%C8oRk~cJ z!ZFGGx~95=hFf*5HhZ`z7!9L(5m;UKmMo0`@7rmtH~ zZ1G!bMz_9u-TEoc`Fp~Qpu~;a(qggHKjO`>ea#5(X4JXnk%7d#G|sQp%>BC=l4#-I z*COcMB7Ckzw75mQw?*=0i}ddnyhN+qzE*kfR>gCz%Ehg!y{+mmTlf5KB}lYs?Q7HV zZqqw+uFash&8WA{_&>qNzIJo(cFS|^q~dm)-gdi}?GC@&IeR+J`#M~`JKWE8cocVd z^>+BY?C|^DLGf-gk81Mw?mT*~Gq|`jq_;ElWoP*B&IpOFsC`{A-d(58b;T8To$c+4 zf7x~6cNbNnJE7P#(6$TYY`Fec46nqA;n)Ai7~UVi+hmd=%Z6#tHMjY=$bg~1L1H?$ zbyUSzma=1=-B?uRL>?jADTdTmHC1d7{b_!z?VlJv5hrESUNcip%2xFqZ?An+ec;+y z4z{E2Nxer~$g6SP&zGAhga0;-dX^9B{In_Hle6zSmKK8G?`nG08@K-H)kGI(8Z}*j z{WFa&4E}ozzdE(|%I^Q1MvMQH|K~L7bxU-#(xu+-U(@If``*qk|Hl~qzoyauh~aO( zDjVKhUw%}-6IQ;xwZVQjacrs#B?RaK+XWBr-P^gby{(i-fE(`S#PEtW6pwFE#bg3x zsl1S6^(TQVS@dYlLJHhsfHRGzU>0x(QaRJ;r77CmboI{E>*;&$bEeVJscY!V2JdU$ zT`~SAhWEdI?Y@|Q3HWc*XaU_^ymm30YeR0Iwn4mlgfVaGU`hM+)8{toDD~Ud9D$9)HorTlFHGG^H-s-)Wav4mv zKPg;hk-1!1peL*hq^;%kV+&JM>-=dKIO8nbxxvA%!3xaoF7`}`@1$6{_-{*7IW zc^M)H#{$oJh{I@VP2DJK*nmR!rc<>gV7rXM30rcxO*&hrsXE$1Sf_sYdMD!lNzz%Orz)CFOF#Z$27V=W$>Y4 z{ekhu%KAehTI2h)xk%Xe8In@t_gOprFW(=Ltu%f-c0CmK$C`eJzL8a`Qck1YpR>JJ~ecGH99E;44e24ZLV&8 z$(*C#l!BFVwgdDF842HDUx@WYz0lYp93Ux6=eL^IhXk9rXuXH^=UJv)N+r_+hxE=| zG&`d~r@}UUhXH^GK8A<$u=C@7UwF2mdm(UH4bk|S9_w|_cjNa>;GqB$6ld>48Z%%W z*-WGZ%43(hEwFw}0B6Zox9w&iHk6=UdV%p@tx0R0Z%yFgYOaAK*>^{W5-_e*lsp4u zOAc@1BUasG+K6Wq?BO$AA4@1AT7jaz54@**oRH3Wtf$VUyUc<~v! zxeDks1-Gl8IxgYkS|m~)h*o70GOZ-uWoPBXbS_L?49|QQfma$ax_>k|roCMH@Vb)b z=FHV|+!c8AoPv;eR%()6g`CJoxjUL`*XWsxmmn4Evg;99yGjEU^yftFqqKs}x+^k` ze_1nhWfLpyf&yxYdoguuxrv@nRZQO5c)Z{z$aGgqG>Q~)FKcC*GHioG6$*|2aza!{ zF*x;%o!VMd;Z(_6?Mq@)Ay1PFpH5bJG}m_WheYq2w=3Q%`7ssswjOPzQ*Bf~UT68ijbkJ8fHs|==8 z)K6BpB)xuYt`;E;yrAE_akNfMIqVt|DF^2Ts6tT9PeKfe%9|vcW-ZXYz(v*#R1@<=%^=%Fj11%=i51ONlLoyAL*LSEkOka z|K&Z(BSVlFjCT--O$;@{}LZyz3+pW*ZV!Ox!Q zKUsYoPnVlDt!ief=~UOmtFLD_dRaWT;zn#=uN7_dE!*EZ`)tC`%`zb4{ z)C7O#JdO8`^_!>3WV{j)y!hLeqT|J2V(yP4sSFxo-)28_C88%zc|q7;){I?#EZMVy z%5!dW5WlM>)ynQIzayvPs1T-jlu1qE_J=wA!J-YC!GI9feQ`E1Q%Jx;;8q$!NHi5j z2Vg>?=17@tCef9gFxL?>avOGcAsd55l)+s2yzoX4 zh8yFXjKY|MS0AJ?E|+{vGCzy=p!OqBTKl*G0DBWfWq?$g<6+i)*lOjCNY^8@$7kU} zqd=1<67W65g!3=|aESUc!5zo~2b!?;dUV?1L)7O(D2`AnEL6?b8*Xyp6#aM^sBn^5 z`_dtGZ?wh=KAHjhaG{f!FduqEzZl;kP3k*#{7^iJD=P;7ZB>L9sPm}?C#C5pY($Jj7UxsFYl+?SATjbtGkoJ zgqOTvCqC}JFG6Kbbp46)e$ovSrc|Nhu8VJU;9HKx9L5U&fk`}uF6a zq$x=6C82|W0qIgguhOKcpn!;gil9;j1w;Ww1uP&fXS&v2Yw!KO`~Aju&Nt3E{}>~G zG6o^c=YH<%dg@wfCt>-d4*;HZcl`xQsPK z66$To5gc7in7{&NF+I}Hv&7_xz59xp^LId{2ZNf_D>E-k&uC_m^NY@07Xb=+uW|Ft zMi$Y{uyFuM40Vn|Ux4p?JFiraUMHYAoxB zN7wFDoV<&w;!(gTOwVmR{M>)1*hAAJbZ71C^h?C&6@T0cw^SV{RcAz>B`+I7%F8C` zb%p)Ypv1I@^$Zx)1nJG$iwuS#3p9BAsiz{4`2bFFFyOEUPMS|~7a}5P9)h>*`o_>x zD8eWrP)Q74w6h-3Ry^PY{ob{UMgHEk+YkU7mLL*E-ApNzV1g1uAjOOf&6M;~ky5Qu zHhj?%J%(@_UDrL@$;nKQ7VX%Iy4)M>)*J029pizEX)=m-e(2@j8pE;z?COx=b_c_I zV=leCGV$|Doo1}PS8VK9NIYXfF~JOsTaUHoj7x2eP4JJqcrh;9ERMIs*FwoJS0%m} zUc>vxmzQ&T&>)Yx_{>L`WBQTT?d5BvA!njQ%Yt^KF}1eXykZ&$FV_)xmcl{SXB{jr z0YF*X3@#YSOd}t^JOyvoTZhfA&;!tNW)Fe=4Uen_d6ue|;5r9#N2nPcXXws(RTGC^ z!7$eMhzy1hDX1b7NOJ^TwFiQ+eBo02TO$CUjWbdV%SLld_f19{AXfZ1xtW|%1^(PR zDF`wuOUXrovEaPm2L)hmRPKR9AsUlyU;q}d{OM!HliVxki;?q$Cq912^GUNS57BK5 z1IS?kp$=c?$5#*@X~47*1b~O5W05PDv2us?(;+sK%VZw^7fNm^e4b0CZi)sMUFN}* zb)ccgt-a^UTxkZ`;i}xo4Xmc8no{P$vef*c8=7*yrWp6e`b-`CRjJ3BJyg`|53#m) z(laX#xnqHD4Y&NoL;EoROgQpT5WLgW9P?}yPH?wAR0Zp6F*nsC5TXRnl(?HJ7eR;+ z%R4RWFz*R;gcLGeeX10G=;vj99yjDry0g?(MP<*hJDiGTmv?JWE^43?7LP%$6dq0{*E(`)(3sfk(ML#-vAfyH zp!R%O&GN@Yeq5#Q9Vj3<0_VPz^}2D8Hf^O0n)O+vZ2ysR=LXjw!>Mf z9SrI!1VHT0rOkoD_lr|-L$=*_QXGgFQcVrJbt+A(o|1}ubyl7r@#5Xm+s%c(*UW2J#j+0Zq_>aU z#C3We+}BwDvBJ{fW}hm`#T{gYVrxhE*?8jvgsy`dGuiF=hfJ2C5d5{vh=Lg8 zklUII*XhIgX3nW?81PzpXrT<)S<0LQAQVav{1k-mYk@w)Vs<=A#RGgPQ}S2}y5<{W zSzp{K01A_UOaPz~p-M`~kfUHE9S1933#Ms<@lc^2R{;@%;xGV^EE&Wt6$E7*hBQ9Z zS5m8t@%IqPu)GKOy_l!myJg8es*F6o7lLPgHXEG!a&wLCy)zyme{SfpIyi444WQ%h z3AUZW=al_SlV%V>8TVvO2YXi*LC!%J6Dmp5plw~+``a}^P^U+xZBN>&%w=sB z!L8RIzk8F(5ZIgUI34YU*L$FeKWsxmS&oCNcN+CN+alyHa#nSu&7k?VB)1)LX*35U z9+yQ6){O=PpY9H30*0_{h#^4Qp;2mbcW5S5E%;FDg<~Yo{W}V=?-z_tTz+_n!wpb_ zjF>Ot5(G9w2@Y5Vv}y^THf_-e48q=$J0Kc05Z^O8WV5RS*d<`k+|fY1@>r$oJ`bsra%4B`J32=w zj$$l{?}EiG6ef#=;^=$5D&j#%x!=q9tQ-j<1*G2VJ5<@uC+&QIubIndQ+@c~vqFB{>` z)s~p>DETR*Rm=pJM=JHJ1kM4m6trMp*W|vSo0gmdEaHKr8=_YphG|2YZP1B0@m5yA zkWx&lc6y@AnXCzDd`Ng1$k~-3>^I-e{fv`PS40>LntXC4;#9pF-rg)d)slff%pv7E z$;v$wePv-1;&HdZ_GAdRT%3}+923AkI$nHvTOz`bT}?ufVAO-DBGBh)WIjOq_jxa2vn& zUV4&o_)l&lHUDhYgEF*PCO)+&6aA2hF)#jgg&+o;n`w=WH&Rv>3)DsD;*7rG8 zzReFB$P423|50B!bV*A;^XFITea{(~Ke>&URmy$N?VG;?qx`ehSMoMsZsT!C*aHRw za7%wI0`mOkHujXm^@THOJ^Z_(ho<5B!uoIo-U1GcgpNgt@c}uYI6omCw2P50Ef+s6 z8m(d%Cs_jrMk}Aa1`M1B;lOCU>GmT7@w?g>z$TVloP1Qgh2+tPzg=nKM;``H4fp z=}3pArZMKU-P-Mlx=(t84luV-Mg`y34i)MR@(icI+=l!!d`#PEx9;jwS9IeJ@LA6> z$+Q7j)?wmW4eA!3BPyu4gH?IUsP>`vHI7vK95GCsn;KkS(B`gAN#*l`10ydn{>9?s z6Tbr^ze}F!miBw0d;3SPco`oI!yjrwZo9*Q(eC#ja*y}3Qu={)AviGFR8Yu64^4i5 zWi3H7^txzmxP@$1*ZSDC~67t48HCoEL7oT*l` zXZe8zZX-$bPp$W~TF&17N+wjzd^iy7TZVjp81PWYDth!#Ise1gj;~*~zUwhtd~JT^ zXnhnIk=oVK{Pgm{V~OEv%#YW0CDk7L)my{}iJhrEcsx=6i`&XJZvHr9r^Pluh4JIz z+wBvt_JE~{VK}bS?E~{1jJ+t`Cskt;9NJ_I`BV5x6&)k@kQB_MPZ;bPME_{%c9>OmU*SRcRCy>zj*ab@-Fp5`2C(1s&6MM|h}^n7&#BD?``|DG1Qn5CNyzBvKGu z-AsTAah8_Xfy_$tF$w>(k{)D|cjYgFzI=1!% zu?C$}GLJ0s6qxy0R<&Xpr%?y}sVCGHQ&gi@3EJOoKv62G14nz1!qXI1I|9;FMk8&n zHubCpB*o8Xh^dv(<^#Fg#8$hVS}Qu4!dK&P({fqmE~Wa-gebEf4ENZn9Hofx#<8ex zIp+LQs!^P5-o9)e><07kJu_z>_T83hp5WyCd54j$Bm`oAa7`YK@zi-?WsnALTZzdb z3ZprSZ!(!XoREs=v9##6V#~dmX=I`wALuR1f4ltT02(MV7E2f2F4ujqS`qr=+HU`@ zY*ka;mz^3e4vNnz%(^>X=B;|~HkZ#<_R%%EyOm1NylG^R5tue>K39&c=;8@&MC;4L z^@V3Hp*a=9_szMFSt)9p-P1K`N@%JMxXc?q5O31PHdE!A_{l7~t}M0xM~!u#`0+k@ z!?q1>S&8+17HdvCg3KmWGEkQ}BFO9(Gr8Wu_R7WEx?>I6z72Y}uGq^xF|V>}zD@V( zcU0G#DCYY~RNsHg#q`O<$X%tQEW$V|Ydy=GjHk`bt!X;eUQb@X*%*;Jvwh1wMsKn_ zwz0MMy>_16&B+hC-TG1XHC|;bN{eUK?y||9bFY7LKH90}-t_s{2PnI#W#1OBCyKR! zMGn#>HGb_CAqRtR4o0r`uiXb!4uq~fc{}%}=E2(30m>=55HLoK2AW^B$jt5mSz^+Z za3BzxY-5$iE5?4NZ)B%I#||;gxj?atQj9KUy;j_yieudePBS^JhciFsmwTwY^)PK| z$Z@YpJ^6|alEQ2sC;uih?l2;fjnm=L?{=y~i#zw8sAsDC1d57%&%m=aU&X7nd8Nf4j}hjdc&fd9blyyx#e9DVS!E0n#F zj$~dSSBl`)L1Nada-A{NHlGru~hllBE90BP(HgNKsxH;le+P$ z_)JrUapFhgdv}NH9Ga@FkA5P%PY#`FQIrYUi z6FZjsayM6ZY)wIn*0=qTEyCvM#_zx=&!z;wHH|yl+9fwH5PEQH2D;wbEp=uk-g0Y} z?|EyFX<;l?fr1p|EkbD15fKXj5@2Lfn01L%n&2uDYNcRgXjE1sI)dP*Dk^8Ajs~WY zJPQ;iC7OM%asxtu@7B;aTnQaXVTZ96!Sn+?<@+c|(Xozz9FotvhL~8{_5in99*x6$ z`!E5*Vc^I3)T@L#UTvKxmh1?=!6||p0HSQVe1X)qIV|}O3Ai5FxNAo&`k*$`Q#UBR zOi0Xx57*C~=FcagffS8B415UrId2aDLdz61W){r3*^SJ3&;eU{K^8&?GN+{jWmF6A z+TVz0*HS)iqJpA=MSw%209J*t)q0tP>@eMae!Z5;La|!!J$`IC>?$prQ{&Tv7T^bH z69P<5ewTmS#y}mj26s8-ZqCM@W?DRo;S^_X{pB1GOPIZpMo&2M7&Hi9&(Qnc#~xP?{2qNcQ43!@uVBJM16L zJ17NA2P0NMJMBRJ!ANFUCR`U0Z-+REtV@oUJ4wUj&nUBV{;CAMvp^N!)YpF zC;&j%aFHooStKmR0N^MD8qKaTzX(HhV&jspp@z^%G21Zh1kOU{!E$nnN@8LJN~atz zYy<8B!ec$WaLLgly+ZMx2!~#Uv#Ci{8j$1=_9(8n>tdKgp>!a zqd^v=2g-jA?EUTq=p*!&nK(XxDmV@~y7bO^7?Eagun;nV4f-%j{5gXAts|qdL7mB~ z{v3idul@7!uH|wA0NmyQo}}aZi7B!MiQ4WyyOI9F4EzoGI~={rpeTTpBm_$s(gbI) zuL)2cfP3D0Lv%}$H z0?}vG4_g4fY0Vsmxhf~#`E`8nS_oY^I7=tX{ULbc4qiBuN{>_iX__ozkWKW@{%YW* zH_nq1m;BJot67KYngvy>X4eFW2ut&}#6j$1)QmW&Wc=ngk1*Q|-g|q)AH?OX6y$^s zJWgQEdUaImtKqJYW%c`sib>kIozd02si8 zFAYa=gy)rk$bDEKJ%%HT2<~^xIKGlkGysi(ta)eXX?cD<*;l$C!4E75)Mw%yLaQv& zi{+5<5`BlN9HA2AWE7Jc&c&u#B*{vY2nK`;pJhw zEuF1EI!hU>ALrs`I2T5`NM??Pd|5BgH}?Vu#oSgG6oAE5}Q61bFW{ z(ipZ`d}fstTR&`tsFDn=5ugi$9HRQ@vnF_=&Gp@Sm8zXhyKv3-S1^4OfUHcF2DO1M z1)bm5Vw8gGiRUu+2lo)Nq^2oSbrqqPm3J?fB8U9c>2=pOl_lIk_rrJmy($&Uq`Ahj zh5SS2wQ|nf%>FQ1Vs))id?Cc+bu+ulwc=0B!TYEss<$(Pg!$>x?_(ft(w;7zdyKnT zIDDw}&3LYrpgU_(y?$WU8dZn}l1PYdm@J~8CUqcwTE?g##*G#*7!xcxC^f{miFfR{ z*K}Cm!$_y?V@JC#X9e$1}7v8%GaRP~;PXh5rG1Mh8G9%^w)Kzg)* zTS_c&rDoYDj+lY$yoF6rix)4_uB*ng61glP3ufwbYzJ@7enMHRC@Y^34G@!o<_>o` zegjzvJ~CFyEjIyVXYIjB#p944eAD1N3m_JlsrXb;vI3O!3l*v>JKm2ev5$KTvKeI5^Sd1PEqisyy@-OM%%NVK zJr=OJ3eeHJZET$0BN6yQ+bhM)6i+|+JCKBwAf84TL|ht1;-M!fxiBxBXNH;+zQQ;~ z^%2UpiS{?Q(I(n0)%EDqfd|;qz9R>e9o@BFKb`dib&Jd-JF8x79q=Y~j3?|Lj)kt; zbfW98O+6KeZR4(x?t6cQLs%c&JK{Gx$*q}yPr)JYPu|xP!xCT|&hIg=`!yoP^RQX1 z8ZDlW;@N$T%KfXi%PN$68BmtW7IpU`t$7tLcIwO|_Rfdfwu1Lr!)v6dA*%re+Ftpi zA>^UkiR1N+V?ilQ!HmG5{Iw=-20bL$ve7Z;sW1^mSdIRsgmN16l=lNe?hSa#2hPbt zgH~vmggfQ%%Eb=+#EVNK`F>;_zGerSa`hi+1AysaME&DRnTKYdrP|{mUl!DiGQ@O# z#9|f5(m^Egjv#CUd@>P^A4e=_2d7nHJVv9wVZuDLp6JVERp|vH>qCg;)Sp^jw?A?5 zF~N@#`f!#-J)9Ag5&s__I2&>3TK@Mop|MDIlo-|gS{ZN$o00;4EJTQV2 zV`41EnsX*a0q(>J{uKbW)2S7wIWsYM!2G(Vv zmjZlLQs32~uz*{mWs;++z5YiW1De>liF9Py67)m&;o+wvZ%^?=YXS2t!*>LI^O$+| zZU*osjZOM_na1dST;sVafJnOhR>tz2{@8RdzLM|OtQ$FQc;7p#6rAvykD1LoN}-Q| zBTmP4%KQW(f3)j}o8)&@D0q1iu<6rE+LJ9MBS}GUl4Pa>K^eNV+|JzI7n%9WO_l@i zg=f9(Libs^J6=kX@!do+<$Vy6zbf@~4h6n-yD-1X?d8J;6oK6y6&ySaWQwZ<$bkc5a~${ zV`r6HT*i2Z1I>nTmXc9&MR+=KZUjF+n_TxPl%q>mW_RuKo@wuO>39Uy`$ZB5FOhoh zGl$5V8dg`xmWT=z@RKhKa*%EiHSh|;#+W}?ePz0&@SL#sK7ZkzpE4)zx*uQjwqEmn z!1445=Z*HY8zEG72FEAA_DN-`-*qnTe9nBo5k9dHW|}1DL45rI=(N7)k@HZm(T}JH z{L$jCAKGzjTmx5ge>E2{9V|$=esH5Cd6{5~)4VuZE-FN4Y+$>lCH24a*89TGqS~Z~ z4Wfd2#{)CZ;=f4QcI+g?yxq*fSN1;Gdir*2fUz|wy8Yt#_ABe{k+AKt{OySc+mnp9 z+iw`#)1o`G$9LwecRqyeEadNee6X|hcIOLYXIYdHXCQb-mXS*~Q`Kkue9m8*0-J6~ z)1+`Tn}|lH{>+JJHsNEDdaH)iYPC}p$z zk^F`qPGu{)zUj^~oIjIyG-L-QV6>oLcrsDsWVX@bxzf|Q$D#y`KN?jU-@5Q9+xU}7 z&H46Fw4lk7S;M7gc_(k0e70zIow^?-X!^zKuFvN;k8YZNy>LHddj~CKwrm66U=r2L zFb1iAd=C%_H|^e zXe99jlT>lt36_K1M0GahxjOY-$5C<`crA%~4bHO~awoY>?dwnST1U!h@;esSYYJZN zmeUgUo2%Cn4MWLmi^WJZXz#wRA+IBuVc(!5l^-duySJ>kL3dwmx4d4S$QViQpxDx? zo*XZ$*QrD8EVzG`BT;}P(Dwh#QB?guIg0*Y%)0+BNB(z5(SI#RrnxpcQU7ohot_|a z{NX6t#jFQAio9Nb#bJWZz~#u7T~6m=M^Vt6_Wy+Hg$ zx6;CN#2@8I7}cBkvm7bpi<@K;iI$#qf)e0zWTq?ScR6xl_8RebIZ|Q7>7Ay>!k9@2H-851e&-!>C@a{|C4n8T=E@ zy5WFgfzB^SUMLVbKwT*OvJH|%5V;_wIKjk)UKE5&-Ce@1Q-6{Z(6(JH|AhX9FE1_? z5Ge+_lXs^f4H*5-WtAf?=S5l@Tx3ob#=Cr~9o|lME=ATeFV%l#V(F;s{va2lX=y}V zYV2gHTB<`FeLciussHKL)ox#j&%AH{lcT6~@ofA0M$g&%TQ5rO{@qbTbQc0nCWx|V zP2OM=$f6^dk)LVmXS9~wBYDt{gnHQOu^i3<hB zoatBrMGm;UTE3r|X?mXLS_R@L($^Bqg6X*ODzY(`oE2S)!+JgTkn{~`ux}94V zYoQcY1OR3-rSpfAAETwcB1tBslOvx2U|{_uPwD8RSGNeRm+XaEoM=5tcMXmR23>Sy zrzr@~4U*W*ZCjR%`&8~H;gR(n903&vBoF}eembArKTy47XT&c0 zKTti5m)yW|Gzp-vqsNk9r%i;31E&IyO4%*>LD1*!x7_7~vLo}(N2PF)yS@vhu>%wa z3h1Sy;I%yIn@%~_Xc{3YUVehNe=u6j`)Gu}bU|}p#&3>}N3mbC z0EDC9K-V$sg>V#vv(E=8WHJPBrV2zB!xxTq(Bg(v1rqzw5Zo!I@JJ?{Mlk9Zpu;^) zW8p%T9hIb<&Xqa$Si^uI(pt$xAQ`8YFMxvRJ z)ka%Qrf&g*l-_P;3hUMr0+04Q33373P3Q!{byJM&^e78)m=Kg$Wymi$+R?)eMBS>i zM;+#D6zRE*a<0N?R*nBvjx-IT$xbFW9qy|n36xTHF{~)am`5MANl$3i4owJ=X^Okx zi0O0oj8^0d2~*P#y}+0vnJFEfm#!IqWcDL)Lp7dg`H4?~(@185>jm_z(R=w8Sp_<^ z|J5GacV-FKD+!&$m~#zlJof1avm^ygCk8pZhY7o;Z=IY7)L*@zQP&*uDa@c0nmbmE zu;r^gF)3g{ZR|$)`BcUy#6#T4qz=bqLGlYdJ0*6B_IDD!ZUZK2z#!>r-FYUaL+21u zE)uNK2qee4C5`P(cd0yElpyBBOTLFXusI7w<{CurZrPiIOYR^c7VHn9yO@m!8qy6t z&BHYa)t05_M|f5hcXb27VgMz0Ta{KDXT~7RZNr`;ETU zMU_8(r4^3rdR4Xa!mSab&p)R+QY)tcQ+shs+uWn)Jx{^whv)CC`{w540{bqk{}HbHo`FSky1r`ldEt~ zG6$6!r)N1ax7=_qwU7ajWDgi58R6{t{^sc3X}>zDt0vcW${irR)Y*V-y6&s-H_8@_ z`hW|G1KxYGN&Tn&UW66>iRzg>zdO=0@S|CQAm%xyEzH9XNG(urMvj$h$m>FC-nnYd zULek0m&SHVSZss+qs{IUlpK*cq#1BrvlR}*A{WpSH6sE4%bxdBYDFYL79j z1bhQN3rg0%V>i9CB$NPATTEO zJVu|%!??)@+)4{Y)_bFp&rCf6T~9&{X<(NzmCGaWrJ@zL6IHKAvI&z9RT1)?;aWacm{_DGOo; zjN>vh<0Bk@c;%KE;X3y8i8bw@07BR!Or z*{40+eJ-@ZuW4QTQ4ezYLDjKIU)GbB`L3_3T>t(r<;bp}|J6il~5)`Qp3rr{-lyZKI9`9xVdacP#@ z!m>lQ&fre13%!!ybI0U=LG|wVn4a`*F+OjA3VZt@l$dGCRz&SQX(jGu#h00Uq#)$2 zl7-zR3hPWzpYaWPdAy03!u=D_9qyAH(vY+vLT1*4us0;i3EIuaeQqR)g^D^tymnNT z3txdhLA(f`+D6%)buM7;|KR7{8t2w>IhuBq*(Sz~jEko;CF%J3%=jXQfb&3XzSA|d z9sI8)^E4gMkBbv~#7hg{UH4ARa>~9+HKh7MYWm4eRIq$8_Wc-dT$7ba1rN{Q894o& z*Nzt&boJrS@#4hY+mo{>hwS+!qMe>IC1%Ly1{i;GFp zlEAGj!w9Bi05BXk1Rd{y+E`BY=3E0R=oP~;%wxD4iy+XEdx+o@?&~5Q!558lnK~WE zjG2KmF5sw*{V;U?wR z;zt&7$n{H^Rp@(H4s!VDN#k9_2tJTH_aoi?S2@d21*ss7-$UOh3XB>nzG|(+8ioRK5Ef)eEd$&#v9LTe~$; zyR%UX2>uh*!`-Z7zE{Wkx{m!{P`#hddOSCIKcv>Xt~d$(U5@-;pnBT>hp3)l^8l*W z4z>~hbGZCJ5#at$9+>|Rhs(qO5IQaJhXD7#4wruja5tTjcn<{rA;9ey*q``^0QZE$ zK#^Ylu^eHt?JHP-%f88b;LC3TZtYX&-vZqK;DN!OEc%~@%RMVdcDP7omak@K1{bN8 z-go{c@1#@sjDy8s56l6r!Z?7?sS!`?X?@LucwcAAA`g>yde%lDkQi!Q_l~Af`IG$L zJTTA5{}?Ve%==&gZkMm-KRhsQ+%cN%#V~oN+r;$m!{r_GEnBlLIAZ>kR|`E*c8@*2+uU+yiQHtaEbLQopEe{J;e z5&0x3f+Uyvx%pIi+x`~QK{g521O2o^Yj0ef83qOl!H0kCihYN2Ycfp{V z!K~{$8$1=ykF|^!z2DjVe$|Sx&F-3?vBEN*#3+CA`Wm0r&j$#BWeR4-T0J(p10i2W zWxVD_NojWuMb(7!J+=9MpuCek5MHlu(Q#VZe+-wy%wo*f%euJ#s{nVV;gk)EIz~mS zZS7iSj9rX?fN5T`5QKe+Ibt@UFE5c(Ib?|FlSCtygQHyY@QeH+lE>a4F8)r#=4TqI=?h z9xj*S5>Ld{Iwb!V;7YFSl*0nthNF71C9)SQZkP|OrY+sh`zS64?Q&wv82ea2O0q#d z17QK~zk6V8BN~KyZT`&z({`QeSp@GxY;{s(ZQ_F)6q~@$T(O6l5MbuQ zG$8>AXv?{u1Bx4SO{U2jnz|5#<0?k(r5;u6hkV1mi)FcEF$V&(LL6)e66GEGhMq<& zID4cBUoYwa0H9TTcJEy2H2{gP3Oq?jQ^Sv>1MXDjU=q@)y<-?yHm>pYslxODR$v`` z*#)RH6^^w+pQGOQq$7+JwT(6dO@Z$|NN(C?Yf#^;@Ion4vCq*?;xdiRY@{LSS+#@m zlRwD2eFX>s@;@9R>{p1)h*c@GO#TC(c0BF{xS>KgVK{}ghvFV0;ix(pd zrh3tXcVCs5MA`|BNnKkNki)=4T!|)-1D1Y?_UMU!$dtlaC zMO{E%Bo|{JIf*q8y*;IW_Tj0sSR#Xf0D74{&t5)?|##hR&wrT8D9fSnRL|{f; zJ!08iR@#o4Q_hhrab|tl<_tz{+WFv}q;tsv8sFGfR2I8Jzn{Id|;%Gb@8%Il*G@f zxT7@*QTrarlj`3_57(XO?_m7EhfhA*X?}2)TV{&C!LOfrZ)^MYYuFFFwpOe!ZST5s zMMw7D*81B=RdY&VJ1vqgO(+?X6lARA8BJ5C8x(T{a-^u6UN>uaU|`G1j!gi z?M|i`lQW={Gz)Hm`LdQNb|v&di{;%COY9i6P115e$}+JeEIo>XSOG@0%rnz0HXfTD zFUMC$g^QT+@^_rMBProRfc7>8J^k=9IoAD zg6V;(TP$p+F^pMjNx+Ozg6~6mpIjGE+yhlN;*FPQB!d2DaWPBO9!PI|@+%@9?oy z^|MskWm^rT1mO}dCsGMIX04&Ln*_CClUT%kFj+L_J2cjD8v8FA#GlNen#^UM%oC7o zNTtD(e!W&8Qvp(Y8bc&T3K+xgT`mGCh|MF8*%o{-pV%C$$~vg`bkqW z_C|x+n&y+EMpIZ&(%;Cp$vCbg*)k*Ie6KM;^JOjoKfOQuVGqPZPrbbkAZKh%9|rPO zh@L57J~)piT*7_-9%#K+RM^I!W!W8_j6>MstTWQT4uN(VIFS}WJnaIGl<|4Ubk}?6 z=|aZ*km<{ZfufN9Hwk@9?aYrJ5)d)c)bQLdRK#hy@YqY?nJ1GFV`foN=JIAyQfAkV zQz@^02F*$1FDOE>ClkHmLe=RQUSg!>iq8cd+Ty6^YH^g6qU*12P>>X4hvPmooXIMO z+U-oM89ZZ5RJ83(5m-T9pg=bI5Sh-?=bnq8UVPMi?En){*bM11^m(cJOuu*O1b3fK z_xU;07tKUB9Wf*TtgE0Zd=e*gppSQWdwqF77)8G-k3+720|C6zSfDfm(k2Cx zRZZk9ij)G2RI-cI?iL-fzz2>NkpxuG0>ul-`5J-6+S$drcZ*L=6rb5B))y!_r&eNQ zQDPEUVwPQEk-c9U$R*gst#X~^q};IV7Z~idfbBV+EuO~arS*7_sWZTBf>&Lwtj)IA zH(Qj?2FH|L7H{h=l0lf)fk59x#K&_oQ9;5WLW-fvzH0TG-XbcvM`1m5Tg2GOkS zH!Th7kK;`*WgIWCd0m!5^f20W7g98d?y10k8nLK4X+|207u=|rC1;0b^LAuawM|sr z->B-)#Y;JHqRpz&+BfiWRvRtG$rX61R*MA1qRwpm$q$@ns(91Ppi5}rdgTSnI?;6XL@GQ9mH+X8I|4@E;a7>^4%*1ubpcn;Nxa4g_0h(w$$p( zQUWAN6?((5Jk$#9!7|iqULF!c2=e*HZO!jttjPuP==*-$sQcgYz$E>r;ZobqPGgf7 zgtNGrOS=DS4~$^5-Qi~Y|63jy_@c38YjjX+?9JBrd#wqtTaz|hX+c%Vg82VK*2n+i z|9`B{f8T#zb{jhJ=Z%(Tvc(^&(oNT)NR36&hTp2v!_^Jcfj>sn^&vl0nBYHew74m7 z{G}?rH=_E-{_~)~k>4Y#UfvC@zgV9K_g@@x9*9)E_C2`|jZt%|v^SHl8R41~Bl`2*!=6@Pd@!QD%=|)Qf zs)%I#s`66}veWDlFQ8B##dU7kMYg&H6SUOOi=b7Jw2Axn2iwR0xKeitO8wk88M+~x ztQb8GI7g={M`n-~h3Yu4L)_tD*bS1V=)E`Pld7Tbu<>3{S0jTS8TV;;1WkhC}w ztXzKRBF;*Ac)`^msvB}-wUB4CWRdL=h-n*FCB#T-*6?J=uJ)%*NssV8D1Ey6H2pLG zNG;HN>KlxH1bb)U`DBvU_SYwqVEf@7|lZ@xf)lt>MxAv6;E;Vv0 z2Yqh+>KpW>?O}7!SKBz2HvQYTMUqz@@-}I#s&D6gP|s{hr%fvyecndex^R$-1#d(` zGAYb`hFE}1oA9&J-*fN$Xxn$c@Xr`kyVlnyGC;(=ryP&pNZUql z-Q6v+eMqz6yN9yH9B;2bp_e>RM!TeHf3=yU6TU@HPRdD>2>2Ft(8!YjpKGaB`jx#m zFh!!!o@X!iVx!SNZnPMFduTq9BH7eda=<|T(fNPgXldxE$?VO+btPpzb+|i_H5lxm zP<97$IQK0ZS-(dq*ZGjE+l`yZ`f=slaUH6^S5Eg8NwpiQvU|(Da)-F2j?C*kH)}4- zdzD%iWa7?1Q5$XD){mS!^y;A|zdrzU;TAR(#FgFdJv-K7b;0O6Tr&Q3PoZ1(w5@W_;SL`7d&q58=~@ z&p#&62Z+Z34Hl+jnSdXtAO6Xz9_jp&6rAOyk8`3U07|W&8jZTZK6V+0p`b-%bN6{V z;+W}m-ta&OIGH|NOzb+rRc8$ypJx+RV&}mW(0196bwBB&V2>?>U&2XP8EK04^i5ld zw$b~T`f%n8OB~|x-I}eFu>dCA-cga#w`-`AyoVkh5ey&!f+x9-NZYAldx8MJk(KBm z%W>YG`d=O7t1JLc+Kkaf7$*t6mz`%;Xhn>+-^NO~QxBQW-QoAA5)NXMs$kH1IM=DL^=^VLgK!nQ=Si9oe8`y~He!G)$;#d9uHBl-kx zrm0$V|3#|%^e`~plyI~IWOH(!Kn(p!Bz9392MazdjS_P*?<&Y}Z4G>OS$kw#>g$m|q* zK!M+-EWfx?Y+JpEs4QoP^chmT_;(u!?Jd@+IKLUhYCuzy(0q(Ccu0DY?)~Uf^fFK$ zxo4e_VrZ6Uxyh!%B|rqlZKl6VyunQ#KX~htMe8u9X3))jc2wN*9l38Od!L#=zlmM9 z_?-Sx=*RtXsF1l>;xV^ zE%2+F&~_BqqPaKZJ(LUy{kFL12jEojqI8=rsr~S|l)iN8+6x3)I()~&Kda6ju|nBn zCZiY4B#p-ykAw@^ilA*HP}B%yLB!b?p>Ul7L1q#!xTL^`KSf7rXGS{0JLuNP(+iQO zdrzK~jxt!-Et+n}4DA<`!^xUNYEeCoH3UYM;)&B2neeU`{AHfMclzEOq<{r>Edz$< zz;8_yXB8RjNk^}qaE^K>krwAA-1JzOjK_S2ZI{>t2q{lj7!lb zrkceeyy7xjW%+?aqjQhc_-C5;hZu>$Mi60Ue0 zS1s;Z=qe^}%@$LDJ+{Dkh8W!D#LqGqCV2LNy%zQc?Q>hO5;Lvo>jiL=uIo`~Zq zpd`&d*EZ(E4@tHtVLcw4$+91xN4zeG;7Yb_(Bh2oOGx!N$!QV*xBr*4Ar9!Oshmp% z#`-eSO?}4eJKvt?iWiwiTvz;QFF0I<=407ali&YvuF_6^*X55W&=4A=@i9s4Azb7i zw4RXW+WwhrR0zJnfTdvS`us}ZHtxm~MuR6nJWh?d@njYGZCH710saBD zusQUX^Ji+MR*0eQ%=4S-V?RAkEwfD(s8iaO+~)K@)lt1Jb1n zNEcL^qAL^;Q4|mmYztHnuz?jTzo~oez1P`i?{j|p-aGC%_ix8=$S{ME_w#+<=TT3@ z=(F(BzOt~Nd=;Qf@gisz*y9D~X83W&VFix4^B>(8qCDypgGvhMr0W6nS$ONGLZURi zHY!BP2`+Lx_@FM3DolK893-Xg#nEvney7NtPuRd z74zGOzDC8dplX;(&lMcNe<2-BBu!YUYvQFH+OjBgMX z>3QQHOYg-fus6DhLKL}o4uuU$hwe@@SLFBqJ{{C~<6yW@8mF{B$DR{JuhYwmU`9%D zue^Ua0&@5WylDtOv3PpEM@*jO#YZiIq(PPuEV!D>nRB#U3y!D{Bt~uKC+@ws{e%ch z6CuWkkm*^SpdO4m69qbuv*{vULS)c`%)wzC=&Jz=w*_Jgh=K4PyqO4J4>FzS+oMqf zfly>m5d>oI6yo-!gSkDCIy6{U8CDCm(i2s1TE+5$<=lO>F3O7L(^+W!Ie@JA4{jU-w0E`EwkhyRjly z^FxP6TdZ<+m&8F@)1^yIy(4_$_nS`Vma?^*2VI+oF1epr1cQX*uPZC&0#H<4#pr!S zQ)N(u+F+>J(mXThgec=-#{Pvy@Cf@ZDRx$<|ewe zYQh->G(%A(Rt*pesn#0ge`>+3fd`&erdEMl>OyQTZGC>-P*_}{X&LY<9Q9S$d?(BGR1Oy)OU{>->>q~hvg>euv&Jt{~O$Y-jd z245Gry1mu><|e+-QwT=J4RC>~AQ4K_DNb1;1?C2lpejPeWjStbxaL7aXVj&=GT!Dl z@*^l&B>A4!(=rE#@)c5{hrXH0RNpQ!S&~BPv1xx1THypi@GR~SCd@Cj<`k;xpvpZu z=1TzB#Q!b566;m*P3gdQk-)wUH<+GzFz8-|w^ub6;+bJ}O=CTZQi^@iEQ__v-$@s6 zHst`NcIT!8^O-QRr0{%(Lj$V)rosuQR19dU+_O7~1R*(og0B+nuyV=T5l(uZ$Q>tW zEstLz5g*p$OJG7_EWD{yhrGK ze-$ddKCtIN>LVB5)mliHQhVQAQ0(h5qB=;LE8wKT+CZmYRWgY@*!5sYz+uImH*(kpnE=F0uDp-fhvW)hu6x#9~FMu0Q0A$9BJMZqyS`4E^U5z z-BN~5F&VbvOC@X|WSOzPG@VUNSm5={4BLgMq(Q z{{<+sYJc|Drq#${NID9w4f2IID{ycgc3m(Nmv!&w&Rmhm>qGpa}ApeO6S+Em*qKxS?w6T}p zUq1WQUVxuoqxSOH))tYl;as^9{_()GaamP*qar44nqp=AH%cc@&tpnn@V`NPBV1EC zYk)8?oRBre0mXd~75Kg~RVx*W(C1@gi< z-QQuKx(6q}&VHzSXnlC{)+?zE{DV8c;4mYjCEKJceh<9zJKlr3p&rsw7kJhGkx|a| z-RfS6EySK9;P{hS9&lg95ZaD__CkK~hK4_TB=Rj6#lPAlGd~EC2R?_0*1h0cS$d4J z5>b}m%cazq`HbMpMJ|fZBSlW6;o;azB+q4Q1JDhF`AU!;X!nrECZ_6i#FiUlO6j``{OB9@|l6|Gb7Ju#>bwSls_}O`pn|- zGpirZXp#%Ix(mBn_iQs?$Pd&0EpeeVM;;macn{3uF8Uo?3@Bd=y1E$rc=6zm z#ZbxT;kwTwJfBA$dmdf>Jof7IxW~_r{dmrhTuRVgO7dJvIkuFhSH6^Sbt&udQudD} zmgI7-?sA^za>23XqVnaEtIMU2m&<=FS4yr_>#o#zu6)0V(DhfWb5KXE5#i@-EK71Rwtc)YBfS6kRb*3;VgGyl=T}|(7(e+rMuDooHU&viOdkM9Aqjbt z5Pl9e?Xd{TVP+oj9{;?l)j12{b?T8#!Bhy157`vdyJIvL>oT^+QoH!1rT!*6LgX&xTcGK@NW+hKFxJIfsvTsdQU4+f3Kw{LbI zyUFv*)}v^2(Ok6artE}f%oxbAb&za0Mc7kjK+x@=oZ$+%Nmc9LnUF^3RzQC+MU(e? zR6hW#y+4&jzu9XSNfw;zSFq;Ck0_{~cUjWZYb6+zUh94Tlwfnk z<=*}+uivS}N~x_s%sh0}^ijpRV|$m+z0oxu|LrgOAH;k7{HOls(;MUy$n{JA^RxDW zv#5lGhuK)|RVJKO`Lp&xa9u@eAIME@UFucnSX9H-=|~GY1(@k`m*RRf84N?fH<{!! z{3Wx%Dn8;RXNs~#n!;a79jO)kCEOdqt6Iz%&b0E=qJTEQkW?h5vrdch@PK>9EL*VA zBokuOI*cL#{zgZgu6Jt@rQ5gz6;NoxjV0Er_O%nCS!cwbn_Snv|JT~bb=@y(|GD<@ zUu_EP$AyedM{H7TU3E-qmF<@0cuQ?v_bTFg-KpoC)G`ZD(qcf7-=Dq5dJ}ww|4IL2 z=~qx$($Sw|Wh9IBf{b6Vk6WKx4wwz$U&e7utW$EiDYZO68l;;Z zzJb}(%n!tMC&(*wB3_5vpa#uy&08Dg%DNc7XO1O=R(PA;%gB-}h3;a2lbMMr~>XdBwm5?B>L6C>+gJR3Q zJc#gfo``+nf!4>FTiQ%j9RoWLPUVZS8zFg$BQQCIVt+6>!~rpR0!Di! zXH@(-58UAnoysp39FFF`={ff?s`o`pn!8FRgM0mB18t!(?#+cNc*~)_+ zXby581)`I835kx)q2dRDu3O^wy!onYlEyI>dVn07NS3gHkuZ`(Kjp zCKXUYW4U3Dw);5`gBVSsRDhr`l~_oxXpJjd6Z8ew_Ck%;gN62Zmb? z5ncD6vjVDJK5mAib>L4y_Mmb-gtaHbM{}tgmjcz@cottK2!G=&_OtVz^rWMBn?|v^ z&NsNDMW)Ix<&hQFhee`UeoQvMj6(oa%)ys(=EHNc<(T{)MUbJqw9aW;6rrC+wFOq^ ze!~Qg3wvL>OY5E|hZ-LY;o8l@GT88L2P2CgrYuEOS)9BJReOO9Qw}8Y0F*&}0r-H+ z&AQ7dQzQMQzyfVFB`mD_89_b`$wc3SyA)ef>^8<{kL{@8Qb;zfC+*&fL#<$4v30 zyQ#+F+C;FBAINQ`W0dxM;i}z6-P=GLmAN}Oo!_{bK^(0v(3UuFw3c&UI_B+a*8BSB z^5<++MGO)YM4!R^Fiuq-1a#uO`8K~zlh7r;m;R*~qVn)mCkxlpPe4^E)DdaemkTY5 zQvYf?=ou-~E+XBblP1OUw*P$BZmXa~+_sAp*aKh-q1Og9^LWx4A3w5An7gbWMPczt zmRoCmFQEp^C5Y-B(+mO_GO;7~2iQ&6HxTua*|C@hKF7$jp0~c-GZso=S@QuAYrdNCQN8(EVgS9&f z6OE-g=ThNNnDNa?Art^mCU9sQBMj!?SXWiAHLV7K_E7u+ivX!})v~zf5EUZ;%#Nu_ zj0KmWc>rn@rYJ$VJ3)0O;gZckZR0R!uXr^RiTXMyxMP37{ITsO;wkqMsiY(Wtt2Do zB)JIyuODn|BFE2)^Y!!4aM-WSP&>%lkAOr-4BGb;CkY~>z{%GEI0O;n)f{Y4Ysqir zVE1*{Q4z+h(#=gsB~zeas58{(FuUMDuXTDQ=#rD~=py9SpS&rsHr2HQJmlacX5;8Q zWw~zyL!7^sD6rsAxDc22f!-6jKY198#Q-lp9miK$K1rg<(>=nvg~85njcy@ljQi#; zzK(ofpXiJz5TzrZ_|jJ(x<3BmjKs%5P-=Bw(@drtpBuu2b%}yr9f7({vYfX);&j{}9hcsXxUDeWx>K*RMK zms&!l*q!zxcv(&?uu*H7wq80NQ#MmvcE9I8Z3(K9nlO@a3;fLDGeS z_c0Y%Syxn82tdv&Nv+_OapZ}#mm0Gng<5iB01B%F5f$;Voy&_{+R`^UEV!*qRc?5J z6aZ^d3EVC`h-~6`fea8@$2czfZVLe7t3Q$O)gY^B?tHhs>T_7}{qY7srlA|#q z$$O~+lVg=ZwX^&nXqQf68&}*`s2S0O`~7i-aG4_$99c|qiy?j$5bFPQ2D=7`uG*3j z>ntk(+he=*#GXT2P$niN0F#OfJB^!X+0GY`sJ3rYK!xo#(aQzg<0&&P;K#{0t7J8c zMYECxPXwV~yP@bJRT)~g;J}Olc|#prWgE)mtZ?clfmKJV$n-s4uIIH7%Mx(lnj>Dp ztE@3K*TE603ZzauJ&JL32n90;KoA9_U)q0vU7&HfHd(zIm?M1ujPXY|gWjM(R9*z- zplL?)3UME_R)fjGj}gdjD@h))EgQ(E_nFmh3`+S%%VVP31R>`<0`S2LN-}5<jbGTDTH?UmGr#>0`@uaF=UPUy08yI>@{IC-Z0rt8Fd)fJR`QvvdlDQOmpG zMJY_Ng_x9+LV~(;paU&vbPw#Nph6I>fEhuiO0Y8x`A<7}G_1g3%`UdmiXGefO$pW} zNV%0*X}+l41^`A26))5=C@>Jv0&8S4V;?ZP`g|Us}cE{dsNpU(PM#~_roCn%4hF_(`PkYFZ973~joOB$zqvn~m zl-Bu+RX3%PQ;m`m!@nSN09}Q%H@^$z~>p4-+5i^6>AY^oVkJp zT#Io!UoQVXpY3%3Hc0MWXoNkq(IG3nx78hY?XgY&2yUJ03?S4`a!Q14d;o?DeOK1^ z|NcONGN&m^y8PTtTx;S2u!{1Yk=eYO|LU~3I2q6h>ivuc6nuNTG;6wQrlV#bnh7?l$v-xnJg0g+d{enUD=7JRPsv4 z{*STU?>?s~ggIt(+igC7ibvh;u9#>k4!oMMKaf7Kw(~cD9wFp)Ap^L?o1>iABpOkP zC5>GKRt{_&?WNA05nHS2cO%|BUD_Ph_tvy?SAM^MJ}_xUTs8vkD2rx{)lO9ALw%(W zI681CY$+>RlhJ}cclK3v|> z*m!)lAz%4A*2YN!aCvt4w;cVR1|dEv=sLM0V}(8j5d?**Ravx5T%QFsSfZtT|n&1JEwU&UAo8XMbgL5#B(aWuig82 z^l=AOJ7rbxFqv047WxA36L;;zi6%q4<$C9pVWkgX7v3iP@{NS{?c!~jzrO%2G)GjQ z6N5hh-h!;VF*O9R=-Dn24z3o81zh5%##$zFuwa#q5D}eK@QDiCm3i49ZtF%C-}cQS zf@3k*!;sRuE4Ey>GgfU?vB1_QJaculv8`5|7+GBfM36bGOfF4w4i$9W5w{sSW5cl; zb!Yg+HFVCk(_Yg`Rh`fp_JJ}nk=l&v^W!Tm(|F!#LeJErK_AWS(NsI25_-%@G*01P z6Tj0U#;*)BH?IYKOX-H!Y^?(9jWCcl9pY!)d|3>d$H6JvCt@-ME~M4-Mm5H~$S=e2 z`=o5rk0(yoTDHbdEG^OTVvg{b<%!69P`r5jwFg%a;PUQ=gB}luzAL-SIbN-Gc*;qK z9J8-g)0$1`D1yT8%7{@G;(rJ`|*wD;LgV1hrL=LuYkJXxjrwPM$ZhF1 z8u=eiW^xE}`u)FwoEA4d|Cbutt^e5=j$ccue>|D}y@vJ^!|{hP`;U{E6oQ;y(OCQ^ zOR0a2;c!#XK^$e}`cwqNVb!UhA|CbAn2prX{(3U2|3?hRpB!bsPG)~#I2xYiTKpeB znf>df)UO&^kmD~9#@Wu;Tm*!%fy^rZPQrkcqyw?7Uy#bxmTq7izxg36m{Ybg6lFDB z9y)+mt0WK9>ID;%lJ}z49(?(tt+q>R&5YV+6+4FOaJGUM(#yd)z&U+CM11A8mG>EGEaLKQh*zr6qk< zRZvh+|IFK))*+~Ox2O_fXni4J9}YpzyDu+TYYfuc^xNuIw`KT<|8qxKs%0=zL!*D4 zjQqnG0oDFfs|7qNRAyX)bNT*0c}6S2C}b4hnjL_ayS z<@S2{(K8F{PyMZ}VrJv_9qT+-^3NS*f5&iKrtN!pJL2`Fuf55g0Py?K5nC?n3j&rJ zHoa?R?{0s4H@0`n_oRNeuKrQrqRqhjS-GcikvpRS_VB|a3PTZUq!(#agz&e@18BW7 z7dmiR>J0(+fS1ClvGns~_HqL3+>`hX(?%}kcajVZWiv^we>#~R*6aSSYH0tsl&a!6 z@@Hcyh=i@cp48HLXkqz_;Ohs?im0j>%1kGX2~jZOqiLh04U)Z23D60 z)3|*HbsSPdBBf-nzx>f?R5dy z^tZ`~%&@oapxrv;NG`>C)nIx9S==t{LP3DNV;g(J`e5BDGU{t>49NxLu4$AO!_}Mc zHPToVjVkEG9qet9@eJ4Z)uhq-6X)q{rtF%+5h`711ZU$70g%`TfUfzRlN3vh`!cDp zYd4#gL3mcR9H*%6MF4n0=|#I2sD_*R$MPYdTFz40u&KwMaZs^J5H6y|xq=npY*g<< zB^MuZq7bRc-(3PHz+r$A@M%4RX#i22;b@Un08p%VG;wF`OlZhK3jqmYKwGbUY|UxG zB`Sv+Ir&5~87%=1&+z5WFx|JKBykFQU?r0u;H<~&tT$8>u>e#rlxCo*Lul_&PUkc- zrCtROC5uu1};^cp3Qu6mLo z%^|m5ZluA zZh#C9UzKQ7O68M4uqnywX_5eip6E`lc)k0CCf++OVRBxT869dmNns7%ckI9$k1EYg z%rSeJJoqJ9W4`vsTz40HgGGGtL9=FDq{+cM?NoGLPXX-ADBN;F$t3ti@#VgCL$+Yr zN#65SPat+UWK(eQ{T|e&4U&;8o8l@clh_wC=PDJ@FY7o4@{Uy=2S_hY8D31?r16O? zKU}O&SBI^esT*+H92U?W#{n~5d==eOMQ&(}*t1H1RC` z(R~>|k<%fS2d;#Zw+4`E4`1B9CCZhY{`g`*DGe9~y7u*!xk=U_T4Xc?aKXbIk~=50 zvhT@-d}T>vCR}U~5R^%M?Ya28J8@7`!`_w;ZH1#R{dWCaXK;D-!)ev;@86hKdWa&Z z?lb$oYACW|D^)pLxENs=>y&28F+EoA=BX+-%Elxpf!)GJP!5W52`}ovd9m>AK-W>z znPnoU2^H+S1;$Kf@YU>FUQsP#vL=ERe&FDm}qD1ZP zM4g#L-F4(-Cf*AH76M80VSam4e2lx3EM}673~*MYWL^F!XnZdx1%?%qCv0eJtf|~; z@~J#`e%6l5HOaTV+yoiG<>z)&lg{b2QGVUxmcm#!*g}kNN0^C(4+rvNMUZLxVzeZN z6ku+~K?3s_vtE2d4$gFjLpO>9@%5x{4vCy(Jfw~gHGeh>kjh`7rXWO5myw4Lg%aZh zgfhkwq5WoE8Y#I(3;+QSt6L}onKY#1&ou2!ix5~#x6x;oM}TMsX6ZvZX7w0K-JHa> z`!3AX*=`|D17S8;;slG4ExBg|@KccwHEhu87DYR(C=RhMshKr$R$q*gMOV|PHV&x6 z7JZWul4Co>R_&DJ;vf20vBRS*3xo6aBz*SC6k)_V5~I^iggsgM9O)AI6xgYfBQpSp zzsS0qlOYf&fsCc5t4u%FIXbTFA{1QBjT?5fO1z|=i$GEdtLabaHMh&)b5Ij-o4}X1j zYOhzY2zfv9<$0$c9iUhnvQhAAUVI|-Js`oYl0~mN*1scTq84t;^&res3}Do{oFGCh zee;P5g&p5j=o!syM}$c0B4#e9MysoT_hdpI3^7Tg(hk{ zK|!6Qz9>PYdN8O3%bJ=ikt|eeC3j5Q*(vBYcerBvn3AUAQgfg@JGu)mv27~)ib!cc zUa?)XbSS2DxVUtrr}Wlr>Fv*@V~pbdx@IXm1}a{H zg~=4D`=Zw;!7B=-Ki-E2-hi)6ALZnzfCysrwoE;3F~LS$W>HT1&YFwr03^*}W+s+M ztAx~1ou6x(i59Ed^Bf6cTeKbAzSPo1>%6t=M#d}6Z1B8hX75ew#Jn(;jU`)|V8n8P zo|jqw&|wn>D5eb#57nLTf|a&gD+F3vWBAANN_MDQeUsH?ZOEU%VZrw2XX~V6b6pz> zVjGG|8cHtl(>?%CwpmSg+pERoZtF97(Vb0Qqb=H>#K^%|UmC}U{KAm{g0%CNT9>+r zDtUeDo%i|IwDK%g9jW9zO@PC28MV>ffU+s$$l2w*lm9`jz{>MF$Sa)ypBV`f;Z}m> zu4m6`i{!2zGyB}~Oj|U~wY4zJx_G>4=^u>Q|0agx-!^7z|Ffmke`Cy6F}P#a@gG-B z|Lbw`e*k!+((vDFVElJ+GU(rplbe6VNrzu?^5g$=aZ>Duz%2YXZ5+IS(gI3PQd35UXO>l!rx#IWNik+92+A!HyZo9d~?QjR54D; ztq)LYSIXZJU0&o12IBAi^|3s_m zC-^W*c0^EM4a;1eCzRBq0klg3r#mCNS0BP52S-_)PmaPk_-Ly%3r{w}@GCMAq9P~* zAYWcqpDE}U6Rlmt$)q;u5nlqBNT-4)(F`7OC6)sp14m{caWd2d35_{j?J$QLz~ssr zG!SkZ!|KpLM)zQXT_2Nn1~gB45B%>9-O{ z?;wJSyuJ<#jCD0Z0ikvHw7?AzQ)E~84!szwRS9}&8ll!@@!Ez7G=LmY1ts%xV1@n~ zCt2CBz&3#-f+y|_$FXG^pvcY@uSb?4TgTH0NhMdsO?DBtPUJYUQJW=Zuzr`A+%y4T zx17=*9mW`eom;(0(8LyG*`-?9*PDH><*1&erSiRlHnluA_fi%LDkB@{pB4htqFR`P zRIC6BkraBPz6uWFbk+;GXe`H*p*dtZ%6_~6f`9`U1pxb@v1B7NCkTO1L{p6_zkr@X zlc$-Hpf1Lo$mPr+<0KZP-)X~!R@4#{Xkc)5nQ5m?#W=9pqYMJTcPnD^wGn2p2OSpP z7%Oo8vT69LCz+iYIgZsGQ#5w{Y-&Y7W2APXcxeZ6#vuj=fJ61NSuAtIMetn zui62!)#NxWa|y^RSB=XE0+2slQJ$NuhtzVBfAZr>fbA*^JJz>_m^29O^`_^yp!G3| zDo>u}y#w9%aPGof2ZOY`HW35VN9d7Vm*t)n_Ov{t)(f_D-e;$23*~TlH&3Rr<_a~J zsGjC?$<|o_he|*bHLmm-3|3>^)o}RmU99(bAHLmMNfc*nrYQhy@KzL|BQ8Ib+1yLT z;Kgye<&x^MLYho;Qbv>Z>e_9xt}wfU35$g1=F zVLOLgR%RbUwH*z^ zZzoHC!BC|M6nJ+;ukQSY<1jY17?xN)aZvi4JVEj3$jMv!7(%6nk@IU9F6Em<=_kb6 z{ct+LDt)f7H*@Qwo``+9lPr-X-xJIr=1or_KxB-KVno{c7yv6n52+ZnHrs6b%C^EQ z)IMGrt7JAEO3Cua3@%%8zsxT}Nr&og4vz%H!z)akGA}GA+^OWbD(lb^G&jDrtwHUF zp_upDQ?a}RPK{%41!O)q;te8hDFi@8;%Ra_G$zVpJ@pp_OqkpT_NTIS8@DH~*j{^m zglWGWWg$5-w`FW5?tJfA(SX3DL$_jc33_#Cn-BM`e-pygTars3(Xe%T@d2Mb;zB!7svklf+xc!`f}s~-OU@PkPJPUH806F^ z`}iZ#f(1>YbRHns#7fO3v`4b$@l)fRQvM=#l`+oG84>Nso3vL!m3fmtlLOi(IV{0V z1B@y?rPIjLRBJWROCe1{e(b-9lYcZYjH8o~RTDC4LgJ*=dJ;`bJoJ>24N3A5A1cN% z*|j^_eJ0s+J(<2P7260NFWhdZUj{Ry6H+E+|?=`XHDzQ-}Jo-6U}gNTHyE zqZzhL@JHbu6C}-<+%Ggc z?VrF;&p@@Ck;jgdJ!cHa!XX^0uKD)-zBHRKP^iuN<$F*)%F^Z&@anyJKw4ycD!k9% zV*fq!DJOx9Jx2wjT_%zo8oTU%%gaUxBtWR$=OXaQB<=EW9Gj1U0YSkw3%9E1>=~g# zK};hZCtJX}!^}ja43se@tRyaE3g$>`4GtXb_73x4YJ~0E z#fU_Oqn}A}VsKpZ4%l+TfvGGaV7_2`)84K#)wil!60h3l7*(8MKXrL06%@ z_04)T;l~%?s|FsN?XG5Q=&CMumH z=lC=t>1OQXwn^8ViF%hWiQHyWR-$lK7AIBA(gx<8SE@}Vx$ zWUmE9I8`f2ikg>tR^sQYHV`fMSzHu|yZI|lPV6jGUOPD%Q&yH+IP;$y7(c0wc;TCc z2|)BH^*rCO~-q;LvA3%SHd?0W9jz`X3JTm12Hu_n`e5onhShLI=sb`5cnRGng#r65T_=&hAW=r#(~ zV+TW0cx+Fna!n8c@P3!48CJBXJ;aFu|G-!kl!%B0x}VZ&De%H22iDEpZz<}Fe_SFW zK`YIvYMzg6T`Fl^xzzgd|8ksE|NkE+Ur6|g{6mWTw|o5mv)CB_UW(M){U3V#hu{9W z#~&j)dFct3HP;N?Ug5Vd;-8@BH%{?Er=XQ2{QEq0)@Emv< zCyU@4&)?E~@$$l$vC6B9la2>ob@B_ppBh!!YkzS}b2C%JQWwQ~Ye@2MX0bJPkG7pMzc*-r7968O+@G}v zAwa%pj-T+|Pqm|8M@WUt^Zkd0DNfcu1nKc7c<(6x)#LY!=fI8rei-}sv1Zcmf$OnR zG_NS6$FEz?R-*n_J^p5|Up;=$85rsDf3>nyj7NI>HtJ|V|D9T|h1H^`AetZ?|;obQ5{@$T~ zzsEnU|1jWeV!NBe`OXUon{YMU@1XhT+45VF#x_Zr>(RJ7E!VUe1z<9(o;xeDtSOsF zE|m#98@rBN%&LWf{bDlDqtlFJQ!LU?KbzKu&l{ z$ox-i3~$jt@QpiFIJ4L)b$P%xo8+WSlfxx55jB|eO2dkwr_AF3D%@`>pvv`x07)AO zSg9kkcLeNDWAE5C(0i(T73tVBsdUB$Ukn7GQRxPF7}=~rNYVlTJxsNA^4kjpZg?2O zQ=Jg2R#Sr7y`;AQj3xO9a6-tqQJ#Vr=m0$T_p?+)1I6V|M~T+^zhAsT;ti#Hpw*e# z7U!8SV#ugZXexFq9TdKuw`tob8>I|i;SHXvhtz%bBi>IEqAMYbQK}9N7mCmP(K~B2dn(1nk@t?z6FRDGG@S$WXX$b@^wnYC#cNt{$B=acE2SFtUr5f8;G6+e1{mz1I z)Mi&^nIj{HLe|$uMhe`hIcVp40@v0{YC=iu%{({5vhhzS%$Fo-6Tbbd-)Vcasr-Eq(PUtT;pFI4NeL!RO6gkoWD0;fD8HefifcdS$8A zo?|_?{2%k>`bLnqQpHC7?_vNX8hRSv>J27uInHTxVb}2!Vz{^S*U&qCdmsMJA+m6X zmrJ1iltaRF*TEsVP>&bpt6%O7{P@sXSoU)N-tzqWO5-)>e9k&0fPC63Q3g{VkhftQ zOx>%OmtF+6pzG8wf4_Q`y}#p9(x+4Nn2L4X%~#hlcIZ5l*z);?@DE4;+qAGY=tHXX zdKdpiX9=^Abo`{QHLTSl`;^7fYWwj%!Yr}Ha|=tO==#U5aK}44V(>ssKXFzund&W_ z;ir)(d>5eZsEmARSAYVZGp@WpYyEx2P0DQT>ebL_R(!g*hsw3v!y5;Q#~-!_>1jyM z_^tD93*oG&*e)}jiOJyp^hpJORh+32_vTvSf%{V1arcCYAC3p-`am{#gztdREYJa> z5pys$8cyyMnnDA1l{k(WMuobj8ubWz9(*Z(LqQK3R*(+ji91uIBkrSczEuBuLu&#aZUjDlb7=umlXbLF zOM4t5eeK=GzFyD|1o*BlM< zy^LyIw{^It7Q&zG{T@uZnGFk%Kc(|5y8XUa$VJg9b7P5^^}#uLM%YI#-Dv*c*X`-| z#_c8}J+kZ5y$v8gK}O|_oJ2C3>Ti3}Im5=A7V?SSTqM^zvoG<(rjvE9w?Ej!QFg<1 z$qPq7(Xj&(^O@4~x-}m*@s1q`%y-f=NFxzln@E{{eXc@us5Khq19X+iFcOdVY=;r< z1?LAD5loi*cD~LJ2T5KaUnLMUoDB74Bjkkr(e|>*4*t%>z)B56y3Is@a1#y+2Twj#c?LF`8l61QsBL_z{jP)FQy=%xFD#fAb7Um zpo>TxH82+&@YQaM44uOTtw*6G$n@wbP$7j?qj!c*2EJhY=K_KAV85b$nu|=^g2A)B z(5LAl;zZuGZ+hM`xuD0n*i`!Ttb5t4Fp&-d7>G=@6hO;t5NB+UuDStFT(pGg z4*G(-h1fbRrh>;hPKVkA3&Y3T1L12a=(q1T86t>BHn7Dnds6-Q#`e4cQ<#rz**J%M zY*o=YpduBznl4UQ-34sWc7J<*{H`fHA`k1D!V;e)4#B6M-#|7{FlQx;JeTLLj}Nap z#lgf#I>X0|i4z1=8rj9vEBNt%cvOFB&LVQ*u$h{q@a#yb50XP(lxUR!riEye; zIJLXR3)}9+CE{!nxz!UCO9X^z))<kQ}TN>(O{GzoC{4 z%o$*}ALpyfwq+Ize-UmFM7Pf2xaYPGey)3!lLf8j#LB~DL0mD+jMkRqCD#J93T_5d zNwYp_!?ljHzMRJlmrt(GB1qB*H2%;niZt7^H&Elw4HoG!T(r|i&jLRR)9u?`NnbWS zNp$SG;d&2ce|-ryyw+IJ$R94~WSm_5`s1b=LB~xl13amF+FN+5&>_B8l#^BW| zz19Is^&~zfR()|fmsflQtIpuPB)Jq3l+4O_e#2VqFsMwk-KHgZ-VdXtU0t=Y(?(~c z?p|2l=LI*lL2sZkFG%Sk8f>3m16MlTs&=9TIcboa)IGs-UOje2V@UT4IEQU~Aq_4y zcDw|^#XvaMtiki91om3R*#^kgt#g2RVaU<8Zlv?67Z^ER6Mj>|;%L{~@m!o2?p9;h z_;?4}hIxRqyO$Z9a#`}5tZiy>_am0r7Nz7IOg345}Am;wkhC7mkX)2!yjU(C>+qen8>jHxsFLUZ& zJY(ZAb^k(s2E-e+Mdv8r1GMwi(^sLjUAy*V3816_f0Sp>afnUwC?H-CIk;~mJh#emjJbJ~GLeC=xUt_nS!#4h^V1*JTfqK>& zd68GifZtwZ$&U=3%>h+~Pi~oxlB4ybZM+{2UvIOi#ccFhYh?`&j^nk*;<8J{ca9C8 zdMUFKoPyi@7^r65HF1xz27_f z@Zsp=Z=*Z<(?t$s_Gr0g_>NHK4`wL3TrJg2?Pz+D>8j0nTV(Bezt}|ymK&%Dg*iM@NI5pE^hI47}%3*c-7-n|@aVKN{uM#Zi1 z25CI!=PsG}iQn7%6eYw;QbiIjPf#T8Zry!Xqub-IX8c{Pvb)+>?&>_ctNZ;fRbtX$ z_oR`>q;dSDN!g^?l}U?7lUCm+X%bVmyQl0urX1s^%wChO5m_V*c<#BA>F**uTgg812@ve}X=v!#z_%fHW7O5CsBegAqN5M_Q} zFYJE(?%JmB{{T8wKuR+2{z=1JdccQ=pGQnfU8c`xfD&|TIPA>zY_eVkmuYy-ja)@_ zh!N0Ud$W+Tf27p(LfzMoi7AE z8tG_qI&C(P!L5SegU|9OmwMdnY2du{^vJLLOZ1rbSnp2_^Vs@%1j${-)epJSmpTb29km;-19%AKsHH=+SKGS=kr#rIUKxPnNwa(&QVL z+;)B(s7n00WXP*CE5Nr`^msHsukIItpry3T6y=qA+I+Ns%{m)pr5wZ79}@Pj*$5jF z*=G-4mwUBzfj6n5#AM|h8+)2Ri|h3TUfp+jcg>_*4@w(12eQGvqLWsqQ%K$~$IW)E zu=n%oUe>;F zKQH#+6x>@gR~i#>B0e?5>*4}-7Kg5U^2<8Z{IQ%FB0ey~-+Is9pANsgy=!stdR5ALAj<|La(5~5o8Gs{inF0& z?jOGW_;y|3`^3QdfbbxEwO+8sPvq(2L7_Bi$%#YEg@K2kYm#>Y&3BFlu%K0JPttf5i~-B2)$U4ESqHYV|9Yf;aUc}gNMR!Q0b z*qpI5yh(kZsrbTSBW6vgllQ?PMi|?Ojb0M$ar&P{E0j7=F}82mgo=E zLjcvk&2T%?F!vz>U)nW116mliM;{2{bN6f>;YxUXVg3!ac!1)kmX+C5`Xsbqi+ZpZ z&&pW-QievU*x*|3sNMW_0D(K{pYRkk$Bim?rrMTF7jr61+vIMVZ9KFfr#b*QH+p%h zLILOK4YpOr*r5$A>)|s41?Qx6wJ9FeQinn3ZmH;GO<~Tov^cLJOIJagDt$3uc8$T$ zjCzH+pY%i0q`>u=lha~?_(XD;g>6>OJ9ZpIa&Qq@kv!X(X%Z16A+J=5-bOg;OT3*b zZZwEpOv^T0o?%K{@5wu6kuWy>J)-3#9q;sK!=!I$w7SD4dv;;vI~AY-`~+B!bA{u> zO=g~X8N`-R*7hqbs^YXnBcjE_1jt30e~ZAbHd9nYIL=w?;MFXVB}H`k%_j+)3? zCfa)|+#zEpz^QR$@8S4vzDW87 z+LKtqs@0K}c(%S$T?Li6{x!k!UH%~>>nG_OitNsH885up3oi#4O4Z4<2=e`)n|E?C zUEG!(;>#g7__6CM)~wuboAUF${-}0rWFB48tf9xzVyvSJrX&%sd<&4t(M$d6&T#;I z3~YF}{7<%@kF3@=A{&QJoxFu=kF5;8Tj%nFt*j!p@s7Lk1t`V=b4f4CG18XI=B@_;4 zaM|l)mu?KusTr7XyLE$LM04qP>8j*G5P$QDE<@JkG|tp##W`2@Bt9o14AoYd%pMlh zzX#$jx8|LV>RCJvPdD2@E6$}_I0zTKrjl2!=iUK49vqu~jrY95adUw$f3)spg_2=uzOS3Zy-wQX~ev-DPDFZ;Z86YkY~mE`%K-34C7 zaoJlQZ4bZL2>4y&&FPrT*^GJeUHy3k3FPs{LWOfa+1;wIVR}67zRKe6OF8TcPeWwu z3z2!0>-*5m)68Q1sxhRXoe?J;EGn zcEhG_BW29hC&MOxu?%Y<>6}grRFrM~9O-+a@wdJ=Y~N8 zh=gVbO;!@4}Mk7P>f>+oSI?O(#G%A9NR zA$=iw{zUCPh-MnZ1It*}7J()!{KYc*`)g4RFMZA-FvbOa{c?-5DzceE=RQIAH7E=K z9*nWvi&1?b%@NN093GJN;IsYZj@anG{O8@jGEdgp2u5e~ZWpSO71yrhjDj72Hl0c>0pqkV&I z4)x7hAGwAOMw?^LVKPvhf4n9I^1+eT_LyjN692kPqlgltkz+7o7ruJ^vR7PSWl2!Y zSyPaJc+~JXy~|Lf+fdLGj9;#3oaa!~hbV&a2bZ6Lm)GyvsNn-vugOTa!Cd@_A9CVD zP9Sh`h(EwMM?-E`lT>4uH=i}+Z*>W{=M~Zx)P5sOV3w|rNbj6WFFYIBKnb*+MOw7M zqc_5?o!l-Gl~2Yen%H~Yee$5n+kA#eick{Lpa!MOg>2_Sa9HS64#bQ?_lwG?l#_Iv zEAI0VD%;}y+Q{woedH71T=5aP8=pK>!XmsG`#_AAP0TNcE$+E)+}W`-n~Hq5isStt zFTEQ!gYhQ9@ycBN0r?-HMQd=RuyeLxq1u>!m>+pdTrohdE`sjRB9~m5+2BeK>wT(&3DPa%N_e6JEx90n~?@ zaXym)G-g|wvrg%2Dn1;S5kWzj*@Jef$98{obI*=p`C>4)gcNmRM(7aKd@pZv2%?<^ z2}3*hh2(p#GA_PIO`@@BREGW`-&0ate94OcVYht1Gv(e=>DXKVdEJpiCtr(Lp>=PdvJEVmZiyb7#UQ17-HGZ7M zmOGYrP2u->O-g~zHEfLA(7Xl9O}+-cji`6qq`k9>P^=S?v|*TV+{O9@a$qHbc6VSYq_V zQjhEQQsZ&QWyh#_pUv9fXyagJb)3C_?wvHaYhS}xuR12U>u1BudKxKN!-+6~ zdcvFY7du}Z2{lJQamz~)_XmrOgXzbSE+!331p-&O)Y&*Lq1co8HXDY?Y1=xD-r1JZ zhq9~)dC~u#%>}C#y(r0^d$#{W!#}MmIU#5xr}qBYkyiVCyG|1tuzSkYplUbP7N7~L z3qYBjOM72dsQW`y{lUVNCSd?HtJ-Y$pMVp-tnjzPUG=aV8c}UI2?Aj@PE&Pp!7p{lZs6D z;IQyO06|G@kkU4AGxWm-_#6YFN=^CutO8Hh8XpEmqZ#?<+Xut=BoDEU(aoRQi~E9O zTZeP%E>^U%6w-&5hE6^6rK`JC_d@1S>EP`5i*T-7i&ifc-xr(n&)E~(Lg-pd2raTW zum}~5qvi>BKus|B&($G}{zynrC!onkKZ#-wQ55cE9>fLGTGO8wpT!A#(uezW8d8+>oBI^(4Cp^(?f?`LYCl_P>d}PC1bC34- z?eCuMTLaITM!Inq(Z4>OKOqng5v-5~(Z%#(>!Er^V9T&}{w8SBtG@g6yh*J0{M9e& zjNH;QOKzVl`~$tG(~@aA(oYUAl{x#=ZzC;tQ6mWcJ5a>57oyYaYL@GEy?3{u!iMn5 z={JbWe^8u~a#9DaH0!%F(!_~@-V1-z*vS+90@fOh+vM!ORq)a_xZlCJB38P{s&I&s z+#_4pW4HUCQGL{m9y(i7>bqTU-|xIADYS46)HDptQvwnuzEUrV*Bu{?*lDTZY1JHm z`_%P)PY>fThUPhaf56YwlwW0QJ9c48)pT4V$H`r#?=qil6Ld8czutX@ch=I}(P-K! zA;3o;Bh9A#T0A>J+~_wlnCu{q7>}QznobaX8f4AyJK>3dCILjPLsNWP)+MAAa~MIm6UBls)$}Z*hi;Ub!OB zq@hertzqu{*OH$}ua|a5Kb!@96ds>vi)e3RSVCKUY8eG+sIRl%e)@KkGyk_oa#8ui z(avSqy*EXZQJ+_IarUD7 zt<2{>&DNFirzr z0RvVLjZ$svW{4qr-QX-81W+`A5@;FIyLz8>i2}!|X9FJ>OJG4!^3BMlJo`Rb zJD@V>_3nB6>GQ{PRD%LyeK#?P;k{WzJFr)8cus{Z1kwAWDks1ylpXoK9hE&W@gGxm z3oAny*gWZ#0&x@H+?J?o*o7m7Ty~x%?=UnO`NY_gy08}p~_4i)3zp?VV+c&VleATV- zPw&4b`&H$p42|-B)2KDDyta42ulJ&P3oRmPcc~>_YJ;u&Bd_HKst9E3!u7lR`?_Y? z$IrUrSN2>u=S$8Cwh#=X`KbM-my^B)BO0N0Co{yEQ2gqy2?&d5InJqa~`diy#B@i!8j;Voe|jhW6+# zm&DbR`O@l$fRp2@M#-=jW)kz2-OKFBZJAepc|G{0czf>g(jN(zA=Sh&B!yGLafPTx6J_3!=CL%8Uh&H5S;=h!p zb|)GRq?u$AW00Q02@H_RBS@O~MYdo&G^+dSzKY#h98S8Lzk zHjr<>@_WK$U;H@lqpuMRxqH!ODTa1wb}r0ux$^a^uaaKpxjddI+?w^2xb zl|rZHb(sr4btBEXe|R3I^G93EULIkaobhtvN2QG*Ybz*6zpj1KBIg1iqZ*T)ZBkBXep);Fp1JS8Y(B3 z4C8DODBkb$$=wgt0wgNtRdB{nfb0MHl!GlXAe{xZ7zGoFs)}bOQcwF8OzVF4Y^2KR zvZU+(GUG977VR~?AV1*bH)0S+{haiS^FyDR(o1TtP^#9CTnH-mi_lFWfq==>*YxC5 zxwEQl8rRh)`~idj;(z{=&!pV%+r+VX_1Co6T57|T?W_&2)bU5gm7>gcjQXnw6}m1e zb~;_>O*W4rEYMl}(kwVo7>q)se)bsw-xh|(0e;U zg!VrcGLMl0RRv~Tlt>#eW}tfI-pA`feUZNtsyesv^(pplmN8k_n{)+7O{}2jMjusm z!bapBK`JMX$LLk*hib>-{pqH%cPi4fGryW93aGtB6AgdW5r^1rovbK{v@8ZSiE^=e zR4}8_*ZFNfJ?Zc&xIL(Tqo{e?kY9fdW;+rE0~6>J#}=}YnLiDr4fcV%woeP4MVQZ4 zjz{WHM8&wjkaP=u&?{#B3@yE6$?eYwfUo<>)_A6go5uAlM~Bt;zZi_(@wX9 zC7@T`B}-0F4NU11oJnxli(>y~8Y^^crBW`_b4}A}IC4H4gi6D}^_+V1O`KpmGNnXr zEJdB^1ShI8kzg4k82j5jRgEy}R(yvwFoP0-|qhHb83%H0Ywez)z#U#t&g%7cNH zn8s0#j3M9CAQL+6FCx}-ZhsE-RLJTu^U}SO$g*pCUob#$w@d%gm9uHL$$#Rw1BS`a zUtA-F?^Utx4bAA<(|mCr0Ye3=7^P!oB=Exs%oI$$f9?P}%cq(WbiC;F(8jhF<54Th zQzdW%Z(aC}T2Cc`m^&F$uxn4c{_}WlJ%75C-1t$>Z4!}xOQWwZ@rjAy5E}KhB31bT zh1rEK5&HL$e*IuJvd0;S&DF`DaUN##JiHe42{`#=-Uk zj?-BQtD~2W-N(x6fA``whe+ANo!d&CL-IA{ssWyqyTRFl2CeL zz7)=S57xCplh+n|JAD1(a%83+g7NFuu4Me;_AQ&}zIDPi$H0ZZ0f8N0b$-hVw#PMj zZ=#H3%p$-2l-Zqp1hoO_qU(My?%i+iT>IOb_eGMKXd(rJg`_9#3i+%b>2~+Or zY_4BH92Db=Q^Z(=l(O~FBdzo=`m=hXLw`3be-v)S-agw)?{85S@IX8bes|GruPmrh zvzl_#sq?yQP)J_oYOK$jyyZ6{_i9w|2WzMIsJHVI%(Wwj>`7(CPWC^a!!q7#9?XK< zWd`LHkNo3Dxg8(gOosD_$M|)1dgJ8|%vy>B4F-AgDTh*{Ikys2q*U9KL1s$Maw#m&x~De3`F^^2}@(?d#N+aVtJu%;T$|ttc_hXu8wiP|WQz&m6J&t!>|X>a2+Ec-sq<(X$Z(*a|uLmIw~)sz z3}Sy#`eLweZl0|$Cg(4AN*cEgJUn=P^Ix!PwN(b8T!~=gU!lu#@g46^9XX74%F&gJ z{%w!WflCq$qgtu=t3KTAvY_W4!8SYC^a^^OK2+ zD>p8F&bu#*Qw8E=aL$i-1oc@eRJWeTco&@uLdM~VW8ER|&$9RT?xJ>lMMC@Gz+Z{dee7;AObrFGBAApH5b**7}DQ}sC)%iWfhR0_uBW(Ie!$WHS0Ha?(UY&$TS zdZ;&Wka41@9O?Q_3H`FQ{=OIiD9Y~!3F9JOUE17>@8_(y-0oJotk?{08lo+C(`mAV zwA$Z!eH@%_&-tkGBD3Kz=~r0mfOnl7vFe?@`vpoh7=`9;mFiMZE+N;<2E<* zbZ0L``{3Yf?9|^+<-kJKf{brp;xre8_z;a!f4|vb9e2M@!H%q2 zAVs5qA!YyRl0egYpV#aXx%>M`+tpfrQ?;WRsg(!n!V^v8w6=I}L}D5^?F4k%Bj9{q z9i0WA19YzG<6~C!c?!=Hs6yF=qK;orbI*4y60*vrIO8xz`xZ%u3hH}uh&m>pQsEWxfnAXl39ZSrV+`|>ugO>M1MbYs${UWH&9w-GHS7=+bVeGMI<2#?HWj?VYi zMTo<*5D8ZU-z=_~^PLR%+C4uTTWDd*Hxt;=yWKb9y(2y?mAe={GBzS!6eIf@os3Tq z>k0=6;1Vl>LCh!7uSbwIF{5+BV?Us^ZEA3=Yr)dm=m7LR%BG#kw~=c&VcD7M{`2I; zPjX|fYL?}g$7=&w)=b=3aF-GoV?=@~gXqLzdn}eUN@IvDtK!~-`zKM1xv!TzM+Q&H z!xJrhwmQ|r#%ui}YaaRQcBv14Ut(#%EipYD{!`C0Zra5HhCKwBH{&Aq;unI)_Y24Q zVUze?WOzGtVc05&-ZbUcD9|BpPFMB!6|3V4a?CEBvh$?8R2^s^oIM!xo@bTEn&*}D zbFxN#(Erm6!$i8!? zi2CzP`Ep}Ah6J=!UOPyLBES_vf@~7C)!-3EIF%!7_4R3sh?1ZQ_`UWRkrN_4Rng?o zyqO+r>p7vWlf?9-QOTN9v49~JZKN&v`uWJyOM%(oW>DG?NXUqUQj5OT1m_*KGmo&f zyguWlRk%P&h-iwx?+xP%1{Ur-{D>a%n-G1q!#YrHshDoRyI=1r)fV{tL$i_rzg{ZW z~&Nj-1L?0$8wuH#~1*n)ixrr1IP&nL_g5N{d@tbG<@ zFiV3$KjMP|lcuZ)Bj15~PFhjH@7E9eOP7`M7CZX3?J~G?t+_EEeU9SDlXyOZxtb@= zy_e@Cwqxjx5-O?lfjd^p60PNz)ke0EjykQmcxxu#*h`{+}lj-}`j5uG`ECeE4Tr1f3EVth7XJFl?b!ElEM*DtF$;uk(RYZS$8O(pM89X;Js7@yZ`uy4GE$vzE44vx+5PqH{x)x!Q?e#|4Bf zV%o1PeAQw+x@@xM{P`>6Bdg_qgyrLVSC2=DkRhTS2cJsB(w`?wrytIxjFbrPc*Ak? zrN7E6%#BP|vGGo`5CIIR;jbEYgp^u6=Y7hbsKikO>HP@lIV-QS>7v5Xs{*1PG&rK7 zfd`bsg9b~47{S6~-Sh?By9`z&UwEKG*dxc|eb!^y-UHB*?DMXAewWkllagwtk7x8h z)D5p^d^T`HU{=*G5kVXPWC*CF?-4~3weY00h@3xJ9!%YlWu{&LZcuA6ER2Z*WwOeZ95D(qepJOX#!ZV-NND9$f8&MkUg zB70r8a^2Z28Y}GJrbZP+3Y2GYeeX!*6;J)qYO+jXCRAEzewAWUSskiGA94YvsRL5D!c0{B@L`}uR zJCZ1KeypRM*wZUWo$d84w#BBNOo$1g7&rB81vBp==e^=WD>-B{XYK*NG5@Ggd( zX13j!OWWLpoxYTgW``BoY_Q0X(DDdBhRuVf`ZJsWw#BZ0`TM!&%dUhQ<~e?M{Jm<= zKS!UU_`B`UKinN>TsTXswE zuDq}F_*+rkHyz@fwYu;Ynjh)V%_VO#kXCRt@Yys#c?E0?yX140AyVMtIGES zQNM39$o}Ufjv-he;`^hlk7oMcf8)Q4JGWjspOPVeJ6Za;-KYPDZEx-PJJ@g+WVqL( zvIo1m0}b*o^V&n)-hx-{-Ok>lliQ^I=wCj#hkA-O+{;a0@TdK`$HcgC!O)-CabH)( zmxX_iHU5s&tvl?mzjL(R;jFrI(7n(5bd^WUpAY`y@6nw#)DOXr%K{sILXH9320xnJ zeux=fk-YUIC+>%2&eG1{59yCTWR|_8eg;fw#d~tZdE#i~RS(YO4G$C@50q{kC#*y34qpR>^0{gMM*s+J|@wK30wtb}b^<%HL_Ij)Po;ml6n#&8* zqD?o?ZzuE|B?;i7wK%|F7$9T?Y5_p%n_%_e=$jD07!#dk#r^iH(eDG~am&xJH$THZ z(jJdo#h1_k#5i;{$wyVsj2Hx1#S|i-dP7JJDiS#aoE4v+1scVeAt1$jM22wyXeZJ- zSbwH?A2o4MTvvb59YGks8Xlmw7xITC_<- zafBW8|0)tEWsZj^vgpCEARre20FW>M2#zN(0mNE3z|aoB!~uXvD#S%G<%TtU597m< zP*$W4IEk?xXktu!Cimw#W7hE^k^%Gk#YQ-7`e`8n$c6txBS6S=`leF|FiWJRgcgy5 z>Gp_7d_;OYk!}cyq7sp8zs~4pBR-8KWWoVd`x7{BN%h4kgVXOq1Sj%-$cYw9J^!Bx zy>NgCe8{0b(a!9$3~|-{MSl`r#G$qDTI9Q72m=-PI(E|K7&-g#H0?Do+E%62`TI<8Yj|XLccM#n0Nt1c0M5R`F`@@WdxFu-Y(Vhd)<3P&lOG#XPj8=H`gi*K=RwsJECyApwh|*yiuO-HF$Du$ zOjrsQL?a25M1k%1_CWOZXp%8Av*&&%5}}BTy(1CYx}~00X)jV+=7_5|4p#qd1hUtbV2a*D?rc0<`w0R-p3Gc2M-=47C#&t;-rviwdleCo$IsuIOWG37Fwr z=zg2j)2`pYrJ8zZFG@ELOvV^sfK34+p92dnMgSU9s_PHKlo^TMhL*vBM06QkAOTvM z$alNYBbG1ElgX%o&hCD!-0O$G#?1k%4Pa8vCy7mBrXI64)WY%0@9M_UH-D4A$oEzHJ#bz{P3Z{UvtT-$A}<3W*3;=kUaz z7EJU5F@J{e10~9W&@vRmIj>4mfT$C0$*j+T<8>v$z`~aBTr^IQ4NbPvOhGl~MvY8c z0mjhMi)>gBQul5D0S`H;S)e}lE1;u6`A7>pMh~$7AxS9pUW?>xkm%y5Dasy z<`S>Mk|#t~8M5qR_-HwyXL|G=q4^kIdQV&M$cIuUz)1v9y7N*sEd`}Rg$Sr28%#x` z(2gAaEcHW;x&RIy5*FQ8h9#?RuFxhpd0b2yqhJ&mq}nyZ2}0E2^jTrSEIb4QAlquup|JYNdv%0 zPXdHH*F?{qVu{lU1Y;>gZZ=6cz=A_D$mk${7(>zMb9^lY&{+h)h!O$~1Gy$95IccH z+ry2-SuPw`0%f-(%L1ILX#>Xr4OA?G15HH55v<`wL$vAy)CH`#9U`4dqk;v~$fsG+ zgU^VSP;V2F-NTO6;FW1xxA8zp|`N=W0XxxKQe-)Hl5OwJN@~gGcjVa?fhP&;3eE+cIE4taq!uMaFWp&`7=V&q( zY6_HllX&5h6$oVq?O^c%qy4ME4=hSlxC!sL*_A-=`P5pw{!(n;OD)Ftx0Ul3?Hg3| zf`p&0cXTy8M7|8*odT;V-2j;&JpYgw>HEuYhbVQpAkdrr5E!!a67nBOvGdDij3_{txQ*YlJD2BwhPiA*3RVr%r3wU}W zMBbBG4qsgm%2KiRXG%y?5G0Av1&$OnTqy=!K?BJhGkgPxl8a1Bmi%7*d`H#SBL7Y> zOyg&+=nNSNGi)wwXHW9DAK$hQdnB(ICR8(O~doEC=mC=|SD3Ei#Cy9pM+|4j(?ITa~y*8hWPx5r9A6c@$8rF{f_uHEy zPlr5d7n0piuOy*WTWfM_m@7mO1ikgLd`|3Mvgb=rsE?H0+eW0zi7cFC2di zHrl73MY5>S*Aizk$Oj^D5oG<;7V?cL8V zaKV^Bft|XcCqPtJlBiwpp&4TJdJM{F5R_elEGB446r)&(D9kM0C=o9l#cY;|8X`uz z#~P`#0Cpg2HSQE~w}k7(cq6i27Lm4u<$F8H95_QVdB$w2kz)Mx>3sFc0P*;az7vUH znTDBgAGglaukGRoMluc5@V`qjT$QC<-_ZCp7@or!e_CY4lY=fH`si5WrL!UzXQ1K~ zAb$=f`WCN-Kd6~WR^|^(qdKR}UeAICfB>(4_dXdshxaltxB@AG5${0lq~mF{#tc-qLaC7iBU_g0f#csKI>8cZy~I31Vr=_x7*i zov2c@LJFeg3bNPC+SwH^2`S;rl_K?}Ey|VMgjC-1TW3*3;$mpch>Z99-8`>p@q*Ng zg*3iEcR)lKvCOpEq2L}j{%~>J{EU(;vwVGjUgFuC)S6gWFiS==41f3#Us1F@!Be1I zsO#-oqOv?_T#ZMIUu8Um665d)gA`-(acocY`25vdPIN6e zl&crY?hF3J3UB9S9(mS(eu;FmI14b5p8Un@9~ubvGVgq3+gOD;KKzJkVh=!M zb+wn>K6_*}YWH=s`q8Bt&xU;8h}fWqv&Om}yAebSXC9u__{fLA#kj2piI4qtYw}E% zJw}#9ow*GFqHRpSzGuI?!@|vN{qWHz$f3caB{u^bFZ=?Ij>2r*VwmR@V~g# zdwJihx68OZ_c>oUS2dro;S`*nM@qH7gflHzc`O!(Xc0Zlh=Kn;K?`d&u1kG{y$?M+ zLpb6F3ge`@ztow!Qa}K}i~vCa&^g%KZkwH!AW44cqZUHU?XVx{M@44Mkp7a7t_tl-k%@H*^^3GX#b?{65 z`>2@B!cS0X-1(=AW%mZh39bM{6cWEy#|9wuEt7izjuPUlZ_*#|3q1OTay~IU!qfDb z=A!3M`;@KGT3j}+7cZS6;6KJ{2fpV9*gD88IJ+{B$Slq@EH23`eQ8*FFT<=vqV_WY zt{{OE8zp=2Z$x~B7FA}l3h&)3Vb;Uq-HSmC*!MTA*RE(VrEpjPjFM-7oofM@g~f5T z%$n8Gh4TZ>oG3UbaB`(_XG!wIu*5_2yta&3?H}s}jjLUQIr{w)XuF4kJzfCho$RE2CuX&>6mLJ3N;PuPv3nsRCU;vA2#%Hj zh~o5m5}pt>B|TLDr;=O3P%hZW3Uw^3*V{f@CGk3yad2H9azvaiiQiS!j)nl4eKL*l zp=vbOq(MltMW`!OmQ6owA^$z{&EFr-^*?za31VJ1LF&2-`nM0|M3cJiK+jrhl~b^W zIW0;7X57ny#sx~I&sR5np-?HIPy2Z~FIvnWW73+EXjv#^Bn7uGPNP|8p|7-W?3)@) zL@u!PE-Bg8@n0^)La~%&PC3g!gTpIN9=5{a!1N{6R!2kriJM4Z4L7YTgSHj{=non0 zDVusL9rfV2N&s53cUHppb|RJCnE9(da1V+0nsoRoHyG*)^)QOB%W%CAB@tQ2rP(;Z zE)qI!hQ}uj)jZ5Nh+Qvig%21%1IddDVaA%z02A7UYR?>%{U~$E=4>C5xi?(3GE-*USsOObH-fVdB7bnLl<>l4d%SmujH z?&(`a%X4_xKXG8*N3+<8-?+zkviWtu{Sq;C^X-K;=p%W-k_&>3TUQHdb0lO3mup~w zI5pxhetS5^J8dAeV%3a(&c6O*(ZA{|b4dm~x!3IUHN&9(tTEhiG~aN72EuIC%I`c4S>u&%V)-eOo;z z=$9)WO%V1yowiOqv2>LRp33ZIsoXktG|thY(T~*GtkDH-sXrm z6~!EqZnz57=l_Ohi{#XeD2mp&uMBGx&T7O>jD8BEMk6~4iq>J)E#*mj$T|)B?W!B4 z&e2?Pwd?v26{|xVPGa!uXU8Z2WS!2|e)lpEjr0q_5>ruN7`5Tt7=Q6Xk<0ZR&~JJR z!Oc4>{>hg0-#6{fdcm8dKMhVhi!a-kUs2770#Fio+6bcAzl>jC1x)DP<3#lZ=6lq; zvdeWpj35jy?NwjQl;-FA<9D=5AF8|tDphwK96c^ zHJSB4UF7pQ2%#E?gvaEW6mQ;8SDSti(L_&TDJ(a1uN#%noUPId7uOXpES-P-7kZ=D zv`=f1@q0%N@q_8L$1_^XV}@*8+Yiy_nL=v;UP$*?YxPyU^9ivK<)MFGNo4%1OBb^0 zc*%?+02e+3c6tC$X933cJ*8TZ^$>t|0)FI`tyldsCj{b^h@4WrP*+`17NA)UKfbfd z%F%mf)Vm7-sz_q%b=`XfQ0d`)ayP1*MNSDEAacHr#iPK|FLhDcM`KV>g^YlAlq9y= zD(ybjP5YbsUY?@Chrn#xD;&t>m3zHk3GfN@(YfBo;`BATp> zBLGC`FbpMP;yFa<>4m`nATt+8_b^Cem-m`(PrqiE%C8g0qW(jWiL8-ER8zMi#WC@# zh36V&c$pWd-uW`!@#u!-V{H-*t45}`b-7`>sC}(9*Z{=?*rgFx`r_%hGy(w%`V5Gn zHSLLGcm*nhlRc$0tF3zUV(EcmaIjSNtt+pB_P>01m2>;*>jxm0>5}tpW+GM!_qTTS zKf)UlgX2O|kKT30M`Dj3p61@YG4@y|o=q!1&?iw;wl^0^N%Z+>D(2FieEHzNPi=QL zX1WT3zL&)SoYk67uYV%muy1SS+mRn==NN~sCUgJUf7Wk! zLw4_I@?s=)QgAHB!pvf{SZKmv_#qucie4ZlO^A+29u{pLv3VzB*w-rvK~zO^whaiQ17B9i{yd+cBAfGV!!THgrl_=9kGDQqmd*lg0@J1ennr z;(?Y;hX9oUEGz&f!gNxmQ~c?BtGa4z*N8cWJJG&jy1JMwab06L2bn^RinwcsT6*Aoj4TS2BtubFIrq)&-&v$D~J;1(0z!M9H%a}M=8*i zq4M)h6PaJy)pi@bYXInRSYZMibfZ&QOeMj#FOV>LOXFI(e z5Z^U@X~|z`2-xI*(mWjr?B5p-UhE9=lD!Uo9?ki{Pe9d} zUaBJ}D7Wn`qu=}C|A1Pc${d20x`NZ^c1cR#i<9|&f+|MbeAuRlFaqgw^z zlVkw3ZwW5wC0gaEX8?j#_a`0u$LLC3r_zXT`(uyab=0;KpOKy&0R?mQ;Tj!8XWf1X zw!V>e00PDfV!;_9DR6o!h|BK$pxCG<@b>`~E)#=u1WG_|PGBcHDvh4-Dno7)xI_9} z|81s^_|&H>h@I#KILnajkQGLf5kH-OieO+a>k`?92ou+3jy}hCb&Ch?)|(ZRhI#zv3B^fOnMQ-AoG>^{9F&yF|uJ&oxZkk)d^p zjRqE=AO&qMka9BwIS9q(n<7t{s)a>ZBq$LIt1&c9J0{8@bZtt4#VB1**x{y`@$H~}~k-2#I<)(DD5QCa$Ax*-_SwI=7CJhJSu^OLH znlxp~jWt*)N4l#S=F;!d0qnC?@8&;@@yI|0W4EnhJ3XGb#nFK8UKpcc%K*UwH^Dc5 znG6IvfFdQ=++&QbVxhmy(^FWKpczZ=7pmA$EmQF(5;_Q~p-tZV%t}LbQ3GG^3z?u; zhg4O>RssV@BdS z0F}ZxU(*%e^5jg^zY0w7Epwb+%j#=&yX<-8hN@hkdUWGRy@8nValy6vc*=TRlb{^y zpc#@)VL)_yDKSb205hZs$cqG!b%<8m-~)u|U%>;#W@%ZuUHOO0b(nesxf4*91TMZs zQ>Rne{VSZPQ=OOufhYt{8bCSEfE4 zDaFW2Hz?l=dMldtHUSF&ajC!?wG%4@ZbaGnx8`#!TomvY*Xvv}ObpYe%6&_@6|haa z*f!YbrMWfF9>BaVCTqm?w(ZFIawPL|J9+60_1HP^SNB!K`hL2c4_F8JwREPTQvSXp2K#MbBX&nd8UKgclz!X9koKnhMGETtM2~ zXnYv_mH64Q3t=c9`o%Eu!Vg?RN(VoeEv0o0nf)r&f zqSvgF4~5Tiw;aprWF>dI&7FJyc)LgYPvf0)#T*`NJALMdm2Csgq6VJR(aZL?Mn7A{ z?Hsl54|viVYWG#{Lo}V_DZs_U=NX~p7dDudAG8oOQ*1sIO<4=D4inN! zV2(>p=k2W9?6G8zo6>S4%hr-FCckmxdd`Jj?H@UJTT#Ykzvqxrk^hPfTF25w#rpcM z4{bp~_pe#4Oga$eZ7V1^Ab+()iF$5Z0b{H@vkJ-RTDIB5pSaWDw|wdM!m2Aro%*&k z4i94m@+f?=078SN@Xag=^ixcnr?qI^9&Ym6I)XjVRL5+^sV6JxQ;*=&7$DfdtM_K$0p!Zf7tv1?7%Y_FX(WoaDJa`<{?AKA9i=X zV06I>zZ9)`6Q;gGGQ_j`5MY7iuj~4?bi5v!jNIp{hTBo?n5*gH9acqA>t0e=W>z?> zGt*E7@`}Gkx%45%-xDLltm6#gJEPf4IEo0IWN|d69$i?kR{TS{e#Y1x4_RuXr+Wbp zeY`sfwM^hNE7mn7s{-m5 z{-j1>mg@^3bCi`yF2AYf+A=jp&({SOb^@^M9pHYwDtzS=%o5KE&?HD+5k>B@wJs$y zMPi4^uK5t@>qYtS5*W3+1yB;Z`w1rV3^PnXO3ok>W#m-N0-h~I5!P5E2_Sg}ZfP#& zY@sF~LKvZkEz$xGgMcUv9#ZEY2(-(JGUpQy(6GQQykuH~y6tH|xsJmNNxTN+3lzSR z*0Ju4fr=PM)*P%qW{pJQBfxxLO!Ym6i**{bGttii(an!5JXdS<{OyHcKm(`$8ER*E8YedIg znHA2+oR035E@D?cqJ-AQAI9_X9#uIRjYmY~nARD(62Nj6NogIFP$zTLS1Ut+SYN_+ z`57A?cI-p{VSIoxVg`FA3f~volP8sF`BVM)Da~=DB}Vt+WEpz;Sq(rsdTYk%@D0(R zm+(tHu$Y@-Avbk)4es$*$({Hj5&O~f$uq4lQS#xJYH(bLS`_ z?a~OMk-)Z2z$$BV2Wj&)Y74GQSubcySXPUtosicDhhd^2H#G|fC1o$%r+t)9IdXjE zl;SdMabIXoMoCQZd6B?zZ}=loIKP+9MN4Uho*f71WzWGYflNI!_IMrMqb|-3i8J_* z6j2VD!-RWK!qJbH3m6+Qfe7)sFR(*3PO4RUO(T+)CTtc`7|TMIN>_{_R%RqEyMg{G zq;o?05c4x-gKT<1^H1KEM$?ND*aYJP3S?<+3Fh9eTiy3Br+V$leoVyBp=yA>8*BP) z#58dRdXDX3)ixHR!*uXwO=Un3(6dfwIz+Q@jx|3RYy|Hx@{tJQazId# zQds39R%e`#zY4Srcq@uUkjq%FyAsbo7#> z)3>IU2Ibkw;H#{)PF7qOA(p1^!6c?;65A#TtLn@h;>_3VEV$_`qUs_M;v&=RBERXP zsCq#q8FDel+TD+Kv5-eOaOUE@W-q~LuNqbFrV#J8 zX79(F-W{qwT_HYw%|0(TeO{~jz76r6X!d=-={u`>>2t`XrRGcDHZQHJ`fY^xCG0f& z?QQyjYW~Pjf2J0Hwk?0GS^#%w0AEXh;8uW$TA)N|piE1k{8pf%+GUl{%jzwcwHPdz zTF~jxAcK}5ldT|gwP35zV7r!Jr>$UTwGg+^kc%xLzFQ#yYN5fQp^Qq9h^jy6HE1TrT>drmai{)>uo_OH-rt)v)bWM+e&bx9g zhu=R8`T6nvovoS=PyeNyPVU@5>-|qXRI&eEPB%T!_F&=F|Fo}e=jY=8mHs>$`pY!H zW&O8uy7Jlo@A~tkFrB|l1A+)0o{Mt<2L=8w^yjF}=ks^`|0<^o8oju1H*Ef|a=Oi> zg#t24c99mtrf!=&m%Oz4F?FBq z%3Q=5)1B$8^ZB9kx$kOp7ijT^cNdFqU)o(NFRR^Mu5S7MAHKRvzrM9D)c*SZXzTm0 zA9VDQ-z%NGe!o|H&$K+l!kW^qb;v05DXr>l{FmHEm5I z37&nR6tRQZ{x4r0ewy(*XYyK!#J~|fjw}D(d0sdbfseiM(|YA7!fqA59E2!TR|ki zfp?4KcELW2s1J65P46QH5wOy782!m^jgLsxa5`5$*u+jQlX{*a0I%_4dKZf*{F&My7o-J8%}yyvrap9WC1W%*-~ z3f?q4wSrw2ji=w^=BJTm83z>JYycHR7|!4jsa*Ii%c@cTGLFYJNj$a#vF?Se?&}b@ zW+?g+>NCQ5Xn4n$38)hQy!uZ!!*)PO-(E6^PJIJ2Tp^$|sV^$dk>Nj<$w<*VX8_N$ zw;zi4qS)=t4%pIfmS)o3O_V6T`+w#@fN0^hmn{xBzPJjTt2h0N+nfX8$2d?j-hj~o!ai61NQI~+MREmf>FH&iHH5Fs#^dbb z2$5qRyz2dv6imy0iBK59BjPHoE-4fr&vhtPe&#)8iZlCQz3YX?*WOBT{%nak?kXDb zaOg}CjRi)b+&q4v&d??oU)XqC=TBE%#7;7N?29Cz7czZ=IGlWasPYE3p+7*CgfDg{ zvKtO50LPp~L-pZK$ zsgIli>mz~mF+KwyczWk-#Ea5b@>=%;i@Yb#^Kgkp8kZ4t`~&7XHL`x>`u4nkaNZ|; z=GKM%ECtU;c2pkmrBCq=n1$4GnDLV=eEb0T?8Di$x5nXp>;VfR7iK8BS#*{RTaaZ& zAI{48x-CsfTjpS30)<}W5w_haKEAl3qTPW~r{6y{y*O-h#Bl5YQ@2s!)COS*51SOY z@@~h{2#{6~5f}=&=Sq&MIL-+p605C!`Gs%1+EXR_%o93gUOwNFI#9`k)RCPH+pp%6 z6h3Ptnve?x+dMhr7~vht^eki*Pr=}%we;`rTp4yGy$+oxquDFMSGHTKm@kHX(ZBqY zqDlUQ${`^1h8Eu6tJv%w;~e7?-I_bTzccidlbI?UadLyUJzE&Lp?ykR?m>G2x7y8p zl;+cjNz(27&jp-cmVk{_X_ucdXP#bU1=2Lcxd9fOZkQ4_R%oyg9{{1hVFNLRO!MYw zYwFb_>$)ChkOviY07ID!u!R>|F?Bd0MJ`QuSTojE*4&{)OJ~JfY$X727h)+IVtq+x zc>@6N{RMAHK$0{1&2vHFyh00&_SaBm+~f$gZJo~mumA{=LZAaA1>SmFPD14LYfzE~ zo|L|xUkF;^V?zV=)&0$_x23Mk1v!jM1iK20OOhDkx^zXOU@8Wu05StcTsUi7xyM)V zoWP8)djj8%E9g?{w~UPq&F0IFLCBhc&aE8MTk*=nwq7(V2q~V)tDiu-PF<7; z9P+_nnZH^K?Me9ppEJb=RbnPIrb`ETGbw``$<{vL(pxF`lY z?{5KL1%I5@dazF60b$-qIOpbJPzu7~Qvl%ND=UDZS$NQSj%N{j2@mz*IB+y8u56+L z&Bs~=svC#AJuUXSlNm+TXt(&5Y+SAt!)a$i9{~l2drDU$L959%Oq_C_8vuX0xk#u& zilbJpizJ`IP=(T4m}XK&Njf6S<+7f!R7FNC#iS!FRL$zLCs(wDb66A+5$JEVf{V;N z4V?`#>~`a*9>enBL1vP{A1il`A*2VN**O)E7cyg6g5*9k3gh+Esi!pw>Gpj*_SsNw zFerP4(-VQh(_jN(JPdh4k0j(!f6Zzplj}ZpuQ_|F5Oaf=>!5Qb2_%;19K11>dpZhS z9fcSm&T+H=LIFfdaaiFJG=}_m%uMg0?_6{?;2+9n0$r=d53ZMIbBTbf7ywIkFGU^} zRJewuM06V9TG|dy%5b{1-u2uE;dhwuE;9KZ+L+3EuSEliq?w3sOX7N6@JZeREsI#T z`-Xv@1*$q)%w6%!y#;D8PWtA2PMZAYB{^VH!wOg@21oz_{fdf@ZiJ124`YCXl%v;b|ib*q59X3A;K| zqMA;I&thN%;UqHhn^Y-FKxC2>hv`>*lAt{d5M0mrb)bNDY?4_9 z!W?b05?NUyl)JBt42O{X($FtH=`+tYD`CdY5~n4|V0~j;LT4(6Vk&x;l7EZ1$Eag1 zgxelH!&3so6A&x9kc^l8345upOu+6l*@$qctq~hsp5^q`mliG*UkuI+SMA+0UF!50 z5u;w!fW&U!l75Y_)DuQaI&WK7`PhT|4fnVe5%CDP2z2k2EWXkXs#8UX=VB>KP_!PV z+O8IW`O0dGn}u9olNF9OV?t0d%%44Yv=Ihwa2_COM;4#lUBO94{AHpnWr z_UKRUUo_zK_kR&wguWvrtWYiR+Lj1_yd-x%8!BqnehzF9WZ~okKvq1&!sNrG2*d6V z70V|JRqt{@Z?9)IdamR=SPMXgQ!(6bnBy#*4~Rmcx?#cowzu>#et5viEJ5&Kd6;B{ zpfkW3i@djF@GQ1&>9uht!S|_avY?#l-fo=$)-sN{=A0gMAiVa3NONjHE>mHdjyL3( zNp#eM8YNH-HA+_b(^oP_}Cjh@|!e!>AnES@9?kf!_7$XAK=vCW)?={6f~ zQq3mF35Q-o=s>+uR*cJ|FFXe04ier5?xi4J&$%L#)YfUYAZZt2NIJCdP&=H&Ar0kS zH4^@u$RR`{xCK8!!qR3RVk?<^gT6f31zn}?CvG|jM_1-5m=*jwE;5tZCZlbUcWW=!<+l}dVAR3XI#a&_O8vztKJUO!Gh!`u z5SwxyTXxl5YmnNZqpvy&Y1=T<022jIX98#SF6Bk0xTle~K+ZW@@FjW@PUJQi+yh@& zGB9QZs(0aR(vXEe_@az{u+TKU7#58q zmD#6ogcG2akkUPgZn0IbbW(k#h%c{wkCHY5Nqb6G22uO6LVjfM7NM7u!K8hKl4vdP z*9LvZKtFs_Bo-5rjI$6bSUm&;wW(U!w?x(n>V2wWGZ~!dm zw?R=7)HH528Q#xq4%!40Tf01f#w%xh@ z2(M5SA}$G@brUkOkZB(9m?ai4uWad&ZT83-g)it4H9-R zdp{sFb#)Y{4THXo&MB4;q5!1)*k|*%!ipG|eM!&yuZ_D&ggY%=56Rl&$xF9iYG($~?U zwmeH~`z@{q8{^v3iY~2eSgUzk9%ClhQ8 ztxSV7IzS=G^L?n{vOM?T1~)bZAu=^w=ox!sjE@SZh8POcU%qm<4d;7uYRPYm(v1Ey z=B)+Awni_doq+(j)^AWs@Iw$m51^q}7lgzf zXp|5xkbqvid~@csW%O5v?U#ITHm(y7p$GjFQYv6PqhE<&p{sB@?iTSW_qn6mrHI0} zvJ^1DiRa!8M4u-mdA=p{u|;Rh1woqcOLePT5m?KK^E`OF(|PtP)7Wd(oKhiXBN;}& z-EJN+h0w81BL0!l`c%1s&P@Y!^syW7 zuBsrAP@4)kT!%fw1X|nv@r$bg#mNTQh!N@gX^*uX*NG6jX+X~4gb)dqDr+W zYlrvO6oh{&Wt{w}eEz5E^`FNIeri1ZsrljOiT$4h;dPyp>$>OH^{%fI3)T&vt{Z++czeN__jyky=bACJS`gTIWcGA=Bln>jfM;fdC zY>Q%{|Dl{x+V#JdXgIU~r<}4c?*E)qntoEcD>t_E?qS%^<@YaI>i*x%DO;UcROib- z1#*97NHpjXz#LVVkyA1x8vo~<(uGey$MY|VhEMa-f0{9VR zjHtOwCv*SZi2C2zjECFJRt!)pVP;E zt-g*`Y+>bjyWX{_PA>GFZhxG|wK0whmo&}zKQODUwh6U#>1Mm;%?9=XRO|zye6Z>d zmRXqp^Ff(=$QUl4epZW@_w4E^tcvS-JdX@tY%*#8kz`@CysG&&#XN(GS>*>3E~_-1 zy{FeTCR1m;IgyzoIEh_mkAY3TuJsAwgx%IV#d?G;UpW-Mwf{2vStLWEF%!dEEA$~w zYI=${No|mKCRP9N&RmBGyZYyBkJ_F2ywLAEf8~@K*;Y3%X&9EkX`4&c*AaD-!7Y*1 z)P^x3i;?DqLG1T9d9dMo-x~Yx6)vVTzgG|N-Tb}AEOUMQ$H0%}YcBWo&&#ckderT0 zPKEy1+nR|#@@ISQw%?zf#j?6TyI)&={Q0%gbL77?qDowViD5d~C;9QSJ`fD}twV|N z22=ADv3i`oOswQyh&>^ClN!8VxrtI(gb2)Y390R?{@ zqEk1JMnA}}i_!gA_#ZhX(O47^0LjAAtBGbQMOr-fq=)hD0Ofp1=aJM`Lm|H7qZ+gWQGj@>D=b42V^YOHz*m_?W{( zxAA8(dntJ|gp}&T#vRW(P=z% z0w8clhq;GSfhblCC(w8_fti4ZLYO<*@C35H0stThx=6r`!VZx4K~aEy7dI|-GL3L1 z+@-UiF&aF{sYHqD1rf~B+Du$SW`Hs6HcF*e`Xs^lK*HJMd@JQBSsKVf^T+ezBox7V z@Id{GA{i?((%LXB=ZSJj&J>x7H$y4_G=2UWK(QoexQJ2Xt|jYbsP3P}9E8u%y&;1* z7Y-T0NVmTB6HwW?!?vayu!F5+WU3d)Vtf`aw6_@Na>Y8%lU5`0nyhTFX5IG8sz&G| zV71ym_GEXXjvQ=+-drwjMs7+Nf2O0RnaQ`i(~E!^0unc55#mcL5t<>R4j;5g^q+ZP zEJ3tCSOp!(9%V$nhdk{J-@b^;Dv@tWK;w+;8~0N~@MR`nJe*{yEs;Ec&^8%{ld~*7 zN5A(~N#50y5Y0Iwjf5qFY#bbLK3%1Dru*7>v`dVDfT~!mY~jgQzu~DN!*2!NKCIaK13SA6({htM#^1B903YNS6Z4XyhZU-eMjz z6lT0*T64P`tK3f+ok}&VAwcfQUir>TR>dklGQpo;SvZ+UOFFz**!8h*k$_>e5@hRg zADtmWQ!W?}7d}mHe7*J~CO)5B-F-&Y$k9xg2xJfwGYDrYBa9qcka7l4UyG$MJOxe#L7Xy=vLZq}lI6F@E)?n~USX;g_YClSV}(fbSy5 zsmlir&2ow?lF?MXal_C=#9iwIJZddb51_MWZ0nZ#)=0=dA|SO~6I2pvBu{J1Q3g_* z8_V8H^S9#Pjtn+8cd4PLVy?WKw!3ST;E2h8#JFL6dNK`Qs(TO|m>`B_(m`^d z=kHJW18u$frh(=%Eprz88Z!MhgKJqC`l!Pa?lUTOM#W?5 zti}Kfxr1#p;@du27NDf*xWd^`04o=5=wO%)GV0_LyN_qmQNIfdI0I~WNdR1^E|y7# zehjgSRFZ^TXx9V^-PZK^ACoR~r(rVd$@m69f#ku}VH{2I;Ao}rjxZiD2*!4iJO}KN zMATsym}GX8Y-`k^@u1H% zL(GmbY>g3b0Fd{ijkkpZtRY8t{R?mar7Js$2I5cvV;@`A%p7`qM5jehjtkzmDU*Y+ zJksS6${WiPh43_ko+9IcHNay5sSyPF-3tuC;InDaR|MQ`JAP9HjKly8M#0@Z;n#j4 z`m8i#JjJk)FqmTyawcJ0+Y=Vd5H=@rlqUYhS|0$;UzJQkz$~4C2)JT=IR>A@g{&lD zzQ$!y0*VTCzJ@NeVC{kwNLGl~!B;7uvlL{#5^SS( z6J`a|`DhArHoe;v6{DI0H;<1Hv6jSJ^R0lTAy&^jLk_H12z5o=XflMSh4yELYFRjf zOtG3GR2U^P$1;L$1!^^b6&q*0Z(sQevur7GjK!rWYda|aJ*U)Y%g~%q7eMj}DHu|@ z?H8>e#hk0jU6%G;4pM0Q!c52J1x}Mb%k1F5lwk1T>3CX~wSYgk8IvyEcTT<+G{1=Z z8VVsKEl{&CNYZ#XCbDw#+T*S;w+Wv6uJ%)CxZY*xsEVO88eSz05vkzxM%1|(-DHru zEM;cW1EIuS*$NSdh7!VO;X*UlwRNG`iHwZ^x7psDUm|EWD1q3EezlFafiQ6^D2@1- zn+UJwLipNeUd|zgnD8d;im(Vhh?fM*;quPBeP^Qsl&l9?Wb(G}+a<^54NT-cc$PZI zCw#Hg%#Qc&aNE@t6{}GhVFlpm@z>e!m=0>~e>6@V0vrIK3zz>j4Z}jhOqb`c& z*Aj<)ELAJb!B~Z~;A+6#Uc8VEab7fiAp@PgK$UfNr1ElU6qr#rBn@;g#jNm6h$4)svOAyOs6)RSg{ikFtDk99 zciLBXhgbLJR`<784@_1M?p6=+*9>dajM&$VhS!Ye)=ak7Oik8I@7B!l*M8KfowKi< z53gO!tzB-f{W@9ueYbXnziv&VZr#3aGrVp)w{Ew+?)N0)gjfe0tVaiw?(_fqEcf3F z5uMq^47o4?MP13bqh3?J_wV)G#GgtMFlZ?5%aA@>>DbrspJzGs71X~75s4YHPW}HO zL~N>jTlEhi;#eK&d6J+}^S>}B{}dv=|Np@(M>{P%=RXt0x|!9%#KvGwd?8~7b5iX~ z{wH%%G@_Fr4(qvj1yVNunDqE=@5f|??!O5UJwM$z#+c<&|0YCaFem?*Df>?b4e_BUzh7D}RH3Oi71a4xSjHJGu#YMM_0DxY6@B(9&)AkHwiofMmsorxp zh+zao`;ahGYa$gk8~Lg0)}-(vACB`%MWZ1*Hc;1Z#)v^Y1e zUAnL+%YIoPDfi!*lhnOa|HhmQzCH8r%*oe(ndQdatG+c)g*<#)KOM(tfMo~~zqc)x zR()^(+H54=`n{W_`sCW^i-V6g=c|4^`Mvq&$5Y_NJ8e3+07~%Pdkc^SVSiC7q7(iM zN@e@+lnSCl?_Vetg^#BhHbFSsp*Q$wR%PIKSGGTf*}hL8c_S7&D$L~Nd2He9ky{rN zcp8U@ej!1_#tzLvZ|oGY^L!p$mdYO5zYr?cM))fzK9ZO*6(=b}vFQ`P=^5BBZ170M z_@qza#{$=61cG!(*9>G6f3&alwwn%PCr=EU=$J9QsNbtTMyl10cgL`dsGJ*s#90sb zQ$KCbQ;pckBUh~+?JOcp{_IR$&ZyPUuZZu8Nvc_JL$D(%>UT$-UdeZTCwJsM`zF-B zn9fo9)KU$=*gUrQN>{s{#^KI;#QYUb@JRE|aTesUb>4{kv3kMh3--1NirL6^bF}Uc%;A`_yJ7Ex`~1aHABcmskMV6RX&Qtk%+u0ibUlqTpeM=dgr&RL==7~ zkK7Tlu_iwMqpTfMT6iAVcRB_wGC*hjug;M^LVKjrW=bq=i9XDGp*ERc1S3c((mIiO<%hu zrzjz7Gl4a4Sj!X&kT~RF@WOs_Evt2)TtE;D%PHRy`ehlmHc+)X6BUgDKj03hb|ONGeG_`@rG;-es$`_`K~Ogo69QE5oo zM;UPoTnT-xO#1-O6lVd`suYXM<{8fU%Xm3JSNm$18HKSn3twH((F!EP2{nb{(L=hY zbRNBKqv5a6-s>H==t;|6FP1i`Ftq6(&WfAo0HiC7JPhCDPOg_8ds$%`$`B&%u9p$m zD$U{zM~Vg|`JNL|O4R<5Vh!#Jcm>8JJ2$1$UWE@h7O&CJZdDVwQFV^Z+op%vx*@5l z+Ec5_{$>AYWAlc99&!W#6vo=Sn`}P3kOS8H$L<>YhmuR?oX|$&&-gd%6HKaIcwdZn zYi!=9-l%q!GMebO4>^{`2+W&bgDp;~=TsD;RE0NT84+1drGmXoX7uJa?VC;YH)?!5 zjNVP|a}2|zTE)FbNA2G!d60Oa-Y(bY4FbLNmSLvDfwx~w&1-D64c({>Dl>Zj6t9hb z`#uY)jEC4=w;s;0)rIvK$>{`1GS7WZWtPPEl&^q*cGwY%dW8fzOy{HAa^3Kfd(nzX zoWQ;ck*S`AtjOHSEGtbWGB*BE`mQOQco<*^NWxhN&j2%!)n|;Hig$hnyDy00(jieu zAc~U#-$>FNk&bF2yl?1e#PIZ9q28t{fFmTX zAJd~;3)}+fAe-ilk%SqY&T1iYz;forx%mL3<`BqYX4k`APq?9&P7#D3+aEX|38XTK z>dU}sgMOpbTN~Frggs_peB(#8gS;>7hut26?*te|rYxo^*uRdwG;|Yg%;134hqDJ8 zOVwU34Y`tsRX%!@sXu$4J}^G~afEskWOV9O@Aea#m5bGtzA$Ur<4<*O-1)`&*$Pg0 zeVaWnQ!1iI@5mfHv~j(TZ)cH(Kz{xF@y5+Jc|HdSw3qw}sl&TK5lTB_ALVN?|hEsM>1_b{=ytcpnhZhwEbx3|tZ6UZiI| z{6abNg0G+d7)8M7F_v4J26G00&~L1tn3-I=6%s--L9=-abf`P~zPEqx$#3BGs;&zP z@#@-|l2DGAuCE%7571lxez%SdVEab&(wB!|7zF$}olI~f_#-0_tm@L*yHN^h@_0%b z3HR(a$8c912?kt#5yPeo5n?SV^pm(b-bg8`JcNU5d+I@~+ClTUY`me`u4#2WBt_Fj zCjtZ!Lml+`sFONG+tyyL&mt(ClQRlvxI}RZ$m$%VS?HB<8H~NOWaXMpnGz^h#dWtTfHN1?@eI~Plni3xO8gV>{gIE z(X=0b#F?KeXFjgV{LmsfjWF2KN&WI37e?xqz!Ue;E~w>&d*ZwMpMec^*Qi^UJD289 zUPl+#{bB!$qS+4lofzfiTzCD{$^z6;e_a9V>gEm`)h9Qkd)1VYOO;%iY{itwu=pq&6VHV39B+qB-(uh1;F@u>fV}@b> zg=Qhkqog7CdB@LGE8?;EAlvwmu=ud-`0&>F=Ah7PI7zY1c-<&iNgQfLB0+EXY64E2 zag{y0Uj~KWh8Qpjb2pB4l$?yg1s014(ZU$q0J|halZKoWAiUXM+z21>D!edAd{(N^ zlfjJy)nb5gk0dUeME3hGW3k{(BE;ZE)Up$uUW320IKHV|^vwdTtVIs`E1Ft^{CKy) zxNzlBkKt`Mz#W9}(Sox+9abJm3s?&t&w>zF*51H??ttT^?x9&w-nREpnBq4H@cg{r zVf_@l)wo>nhJ1YD?lIwvQXkNcin>C@*@(QkSK*g_Z|;s&d^+Z2Npq2U+0;cYGHi6ATxfIH%_%&@;e z5#doT1}NeHD8la}H3^W_P%zJIyuA!x&Ppa{Atp(I`-=MQr-g7Ffr+p1{Ix6c>1x@^ zN}$G&bDV(~OG~!gaCWM?0P5IvAv*XGaVsrRB!kZto|A)b$k~^U$lnpk>+>v9&lM_i z%*wf0enn)F7X|=#o{#6U4QC0{U@gQuf<=z^%kK#4paW^iPx?ffaD2OJdGU&2fdq8# zl1P*1al_E?xBw8C$P2iiQ5|yQVJWX&BJ}>^-5I|8kNfKRb9VXjjKf-w#|kx;g(xJ5g~6-F5iMw8GRs=`~fHJib{?#k4_iwXmV>Ydd10^9bRZv<1JR$>?dT~&2oP^OTWE$nM0rWH* z!q>aPW=TEv+zEf9Cs?iXkY-upKxw9)J5?rsY6IZibxUgH5TJS+OLCqX_1|hu1nQkY zG-L1L#@X(G#x39kkK^YskEY6iG=45t1;_PPr&rQ$xE+B1qgSP#Ye9%&SDbg~ocE_T zH(^wfM@MezBrXVmS&;ocdJ(x_9PHQ#7Q8Bq_lDTaZY!*S>iyVgsNoryiM-#S*HSLk zk$1>j;N|{q00F8Mzh9+tN8pzi$N8)VQP34w@j0Ll1&Ze$D)SB<^-t1kWcyMdQ7Xc9 zl}ofvSZey`!a+~>tmc#c+6->Ocd78HEKgSj3@2I5B%(-afMi+}P3*Z(nt?=WGrt_< zn{&dG{(!qG=+w$x%4&=)qk*v_Px)X2w)fufl3)QkyY5}-VQroKk^9B{fEi%0 z5wM{LXl(6u4V=L;w_^h7y4<6bG~Z{V-1X{E60y-uFL2yE?Q$gdsUp@9PlMBvpWQVVkxXg?=s+q9=SEqz>LLD9K-q)=6ewAsJte?x z(Uxw1oP!=>a7gf?7ZlIjk%sGf-EosOjcz;DHJEYdT#8^*@?B@gZpK=WdtUbgOZ4F+ zpt!1gK(WLBH{Ulo&Pv|4%bJ3xQBST29Jw*sLl)?b`fYEo**nrfYBRj5vY*$bv3bE~ zx1*z}`p3DY#q46lg4fBx7D{Ky5x9J>FGq7oWW-L~F`sYa91tu#XCz+Z76v&q5u%vje8f z3SWXjT{=zbMHfuO88&ntAcGf^xv!ytKvI&5`8_4`BnM{T*#vZ9y$VN0lx)Am)q{Vo z=IcyA=eh&lUUcWCJrFYMl`eFEKTqUYsSR%Sx;B747UEXK%8@j7PN@QV)qCM%aeZJ+ zpiRn?QwiBUIsOU*)CzI_E{mMd5v4j+=3=2Nlw)^@gOJ zIKaibi!G5CEZ+#Gx%1Hh%{|TzH;_pl@^nyUEroH{_iD*=^#5-8!1?;RHrmeiZ3m_O zoZ#r%Gj#7GFz?VPf52#3VTY#^$Mx3!SV+WJ*xj-4$79#tk45f{kp;)2 zw8mqc#^WN!6Yh>DJswYaKc2cbP8FO;*P6KHG?5iCk$ra}*H@>rWg=}=IbV?PuHa;` z(`0GHWcl66%Eyz{?g(2KT0h1m6#9y&rLUKN|6V{OP~dp{#M{ZVUr&S`o+ z!iaUIW5I-L`SG;Q>*?>lSP=ZzJtb+zp3)i!VDu&5ZUh9rFYrG#SQW%g3a-T{aVShz*AaE(45aZhy08Z39;K za%ZBaWrALeS0}c|joZibV4bGwY-0uE z{=Zbkow291lbLP{Qz*N8ZIdZ8J?vv!SwRd>`x_y!Lpc(Pa}aVbe` z5UZa6UD9wNpU26{79@R7l-9Yfdn`U#$lOqbU({<~!&%_6?y=>XI9Wp|AEnN)kC(^%Qc|uww0-gMQG`Xq{X7a_YP4soHZ_JlTIfcT66(g#&Fj8~nS>#8#jDyWehgLhe zYrEizZ9eluzx2mPam$}cI`KpYPULD&YSjGEp zCSJ(c+aM4C>deGH_mo;}^`~oEtgmqHZ$6(Uzvx;fsW0NTXT5_1$C(n;BD1tUO{)}Z zOHpUGKfA`Z-(kB0|DAm3jxF z;EJELHMe!+FqFf;`%W{}KnVnWf+dbTZxrJ|;KKWu)au=_KL{HYWeFRYKN zn3R6TPIz1zLq4Tiib{d^OJQ8pEk|!;-qenj58X*?ZnMBw&Xp(_d}5r?2`MRw-3qrW zo=^^H-vr3+&fOgY=>`wvUZqI7O!^}PEPvkNd@ZJYDqD}f4ggfd!fnIb9Iov#msMWO z5f4`khR?e)89$QLwZ`mY!zO5 zFcyNql?S9k0XD2B;a{HOs;J zix+ep9}b_*2eR@JcGb>eSI7H#inHtwVO$S3oVciJEg9KVo#?O5GoLtGBOA7Ct8mr6 zfmyrB#rc~xYH~7TKTWl{N#cvI&7F7C;isF8cdE6cWE?-Fa<%H)eK{&|hx(D<=3c2_ z^5p^}r*5BF7UP=QkPOk0Z{aQYi*F4=pBhcyb!~aHsNxqsR%LasHRy3xX4JKt4Y5nl z#;Wc-u8Z7y@!`+z)>DAJp8Sn-8ax;#HlS4>rP%P~=6q-elv*DnWjsrZX?}(qtdCP0 zm}S4Z{Tx4flPLuc9hW}R$&yt}_#5s5>%wNavKX#01tlElmN89`qRq0%x`I9EtYS8w z852s-fnJpLeS!u+7Lw-c`)#Gf&JMaE<=RkTIAU5AD<@-QE0S$K$J*-1DFUe$h9Wu> z`+jqbH|*@c^iO?|w_v=W@or}@Z16$;*1*DvUpueJ?2RZTFTc7U|1~l6*ZsfAH!p`@ljDP` zu{V5ueEn{rXV}$RdFMbszjX|?uV9WNa~qwf#_HB!i9sz^kBrI;{3*(ZRh%;+gj0+k@++ z$M=@ZZnlq@C~A@()56!5~cMm!~l80Z;){D<^+d+HYm2l92UR1pqNdQ&13< zDQ1y?_ps@B|H>3%ow|!B($rbG=%GN&BT+_C&%i+!BxTM~RCrsx`vH4Ciz6PMzCcH5 z(l4_Z&oG{pJH2u%mtQ!{tnm>ehUAYhCQ1RIj2E+XWF`>M6@n1~_!B0bAT~=zCC?17 za=n&v$D6!S`1A3qd;>`Fq3vux0T2nMRAwLgTKa<4sr-E)S~+j+SKF2SpNb7vSAHGd z#$5UH^X02Qn-BN*Rzi2vKAp^Z2?t;Y%Lyo#LH`ZEY4|}Z$ciR6#0M}WH_Vhs7zn~` zFR_*ReOb8vsU>nyiULYQA8fE(7+`q}+C^ixd9HCo*92xj;gxHA@jR<~(ElRuJfoUg z)O9^)dMGjzdQa#eXi&N=4Mm!$0V$z~p%+^~n$(0EKr|p-(13JQic$pBfGCKfU_tDl zAczf66j9_(*IH-qz0TSD+;h)3zwY^y{}~xGV}9TFzR#lv06NibNCHxyhTQ0~*?^LW z^hTNTm}-P=pVJ8{P!xI|yqwM!NQyxYIYFPAtHe(JD@@Py18*e-Zve6tha~L!hYD_?* zb8v_ej+Sc_xfv*;9#Ydqo?Mb=)1Wv&?0hsaf|=DEq*TukYpo^bQea#T_8<>nKO`hm zpumo-2V{;uk(~}w07RlXbcjPBapP|V$;-p!92U!b#78xkEk_2W8OBRrQWOYa zQ{d5O99c@!5e0IZskggMn(V~+V>y

Ii6W0Hr09^=**46u;AA$FMos*k*L?6!~t$&vU+@k9toKk4K-09>*1uiTB0tXEUy`nR*O5&L1)5rpyAxCb|#k2mQFg5 z4FIUsKuCpVJ;vi|IK-mM@#Qv9el&q#dtCaZ5YU7JNEzsI^m-m*@9X2T^BB>bBc%Db zp6Nt&$7oE>ai?O!#_1yhglI_$3SdS`(GWs-g2dRNUe`Q9C8YOZBBeL=w|PzFx-A z*YI>|3-B%Iw4DV^^39~<0TWV%Nr|2b1;zLpnr>XVbJx+|Xy9+d;B;l>wvaUbG$=v? zb+oDsl`9bho_owjx8*7y86Sd$oM}ykZ>N<1W2@lD)d!ZVnKCtDCN<&iHIXqj(Iqu8 zoi%ZfYZ8`g)Eu#h`O_>r`JEgT2`V02Sc_OCW2LAiUIKvMH$r9%k^D7!q&Awe5Sr5o zWwb{|1}3Iz$%xLz(P!fVa7LtU zxvQljtda6W-Q4i}-qmtrsaX*Aa~L@w1iFYb%W+;ou?DholCZi3-mQ_K&H>_OJTO>H zoRKLKb-U2*ZLG*YZ$c0-Bekwtw|)+4y%-8s8fW3CDD}6*cBxh^u+4dG+eJ`WH7G^3 zsbsA~opy7XA~gje*xt%M8y^fst|i{`b&nS$3bnV}yBxUvroEkz)6W6DGl{ua-b4MkOjl@_YAPfD!duyX zBZ;OHhfbArwG-Mr$^panSfDVGf1-P^tJ}sqbLY+OgLeTW8&xcD$rDjBDySyKj67xt z21a!}THT~f@rjq*BK!_Q$CH?Z7F69(DxYOW@-U3E5{fb9LX6@jW zjY_rXc}zaFHZKqhunqt`v@&c_I%6m?4qD5cKr|O19WJ>N9ZBhl=3aZ`}DDq~^- zAQWp53B^ep8v4D-jfUxmw_rh;CQ!>0%6Jol@osuBUA|%>#@9MLh6M`)LEWgs*w8q` zuk7AT76BiZ7k9Ix^k!%G&F-f+FLx`xjE0L}Y-CRAUAxBRK=yG@vD+r>m+p`g%qN(R zz0#g0z&U%RRJ^?5i0UoKnS{I<#h#N&l`HBqp9mXr2X(Q?soKIVQAel{CeZ?8(**7) z9`enJJ}XU7scwSRboidA!0Tf2G<27sV-@GlzR(O&0xYD&*U%B#$ypDF zCJxF074i^htTpzKfH9;gkcT^XwxxEzoC$!`&xW+s>(I>M#ueFCS1`yfwxZ<8NKX7u%%GIu(|!=M zVgJ*?k*rK=%V5T(!4)~=aP7#7TrzYDp^MDe{j7if(1X>kp{Kj$E)*6{{Ms2kpDBC( zIQ7}=d(kjbB%58Exf}{7ra4caYfrGe2Y}fS(fihCEap?1o3pR5RRTXDW?2$_BX=Y7Wl2@ zFRQixc?3|hfV|y>+L6=$zs9k~**LXYIF4n|F^pdW$FTx_k7IHF9>+@4c*#*IfLCi8 z)zSC2XtmA!-{M&Rv09_*cgPc7t$9Yifmds3ny-ue3W}Ap0;(S|)I)x+*0dB@m4?rz z2mEsc(9vj&nR8t8HFFDqn@lxT38_197#EI_7F~fUqmY&Zt*WpHN@9*WRd8m* z{)IJ`y@Ql~?N7J#9`5@zWHenmS^6WC_vxt5Ql51|=YfD^E45lyFLjfB{XN2lz`2c% zy1-nLAXGNoE9}uuMF=RrLXm-WJkr%$TWm}hA0KPYQ@*mV|Gm`Hu!m(*&mv(2P`T!d zRr-6XX}`pm=lVK1ud2mG#qu>hI`ab6=4=z&cW&N8jfM?1T5PRQ+L7ddQ|6;U83FwYUw z^>I}T5*s3i+Nfw};ZJFt70UI`G|e#w>N?tl1O&4@g?!B~?AX9Z7gc0+E^)S0fsarr1|1N#3x@cWch!9;sAOx4mKK zzK|R5*)#u`hO}Q^k5vFz?@TkcNHT^92scpkYdaD!dL`+`8P}R`M~n=GC2I3}bbiIL z&b{?58yOB)y&lU3Jl2$sZEVj+|)3RHg&?p}S(UVkJUBaSj&&kM+jbm~w zft!;!caNTnn^ zdpMkANwslr6#&3WXA+6kARf&GrGzZ8W+QMQNlCv}YZ@Ug6^z*t1LB-)5OAM{0dheR zqc((O6CZ6q?27yBOqLu504ab)DRm~5DQg3IO!jeN3Nlkw8*A54p5xwkq4L2#^W}Qr z(W=!XLYh(MD=)~p{Y~7Yc|Rv@pCDnV)pLgLG-wj>CZ8OFt1M_aY8AS~}GO6j%>Z?$i=3Gy z^alV}zOy|WH;WGrrc$q3Z+c=DUc3#s&#zLbYoW62Azf>|!)o6?vi1o(pkz}#`j^Da zy8#wqoPjp539?_m0Pc=qp-4w-1(clAspA8p$N6T((!}gkIdiFJY1dQ$R{Bo+B&XY3 zo2f)y?m985-KB;L<|j>5CNw7{7Yx?cw62BD6#&R%2|5W8L*(6)CzKS&wQQMj<$emL zWQZ4TySd5r(Si%wbIMFi((-#e5Jm6*TVKfW`s_)>*Py(i$Vu0-MoVueAh>HGUw`NA@-=j{up-pE)UoU@O`N$IK z9>?xn>XrRD2OIx}2zyR@Jj*08IdO6?=c2FQ)Y#qJVQK70=6dHT$&LqE83J74n{RP) zfJXWo*E`FjT|XC_j$L{exbyqtCqKV*+_{vRb`sJaCWFqQCS<>`yJ~NLu9v0gnuj+9 zu?IlRDgC!p8EEBnv^WrY?JbqR2068Bav3wfxH^waes*__3n~6N3r*L0gg7`3igUlm zY3^t5Omw%99N%ZXj`TA-d=&vdkLrs6937g>XJ#w{KOVZKq6uZn^ml>uMJzC;pD;TT zC{e5QxrHq^##R_$OG_mw86~OElj5UxJ&6DhN$e4~VgJx~6uQokWJbw@A@Xd7cF%rY(Hmd+)uOZ|q&OUIm81^krdv6efr=* zRq@U0@xUrGebfe0ZE}Uf5n8FB!kn&gU9JtmO$~A*9g6ChivO{wtDWkBB(u6zS?8SH z@y22rqsA_(EP#_iY|3DZyTPEjPtL4$QodHfVyO0l1K$dm(uHBhg{f&tPyIu?7a5nT z;85DGsj1|zQ=sGV!o^hfIvX)kmBZv>a6+&rb`*+N)t`$hinT4=Jc34)Bb-TC+tnBy%Pp+Uu)=dtej_(>^(IbegDK<%19;;bwM zL1dEEiS1;(m>DjUhcAHyu71t+Ee~S_l)AA4By)0o$S&V)%G?|>SBwZ_cnR0l-zz)( z{xVk(sbWhIWr1%GLngfAyL3Teelc<)cjl4UCIdqJ6ev%jL$=~%p5s%0L~enXYT>Dn zkz}9Wt30-KynE%~XCjaIAF4G2dR8YLB4ofX=TE7mPnP-ISTFgdN~e%c`B zv{A`vlg`tok56y@0|8`GX=$gFiUU5oR7y>x9G{U~szuU99Vp}OQpS}}aBk3Cpt|)SP5{sw)-n{}~BhyipS{d`-u9R+7UiK2jp>N~tT5Q5mcYIu=uxq01??lMXNB zo%-)qYc7AXAE=j5Xg}ja*nj(fu3CfG)P(YA!o)V=PBaO0H3>awTJyaLl5HlwJ$s_0 z>3?d-`&ayg|2;z7Q_3^IQgfWl(V9KvEF??L`oWL*CSOmD}dj=umC`;Jn&7cEg<4 z9jm6JeP=pmQ-Zw>GRJPOB@6=U^l=TgLjtK zI>jq$-ycv1xLTGfJd&=!`X;Vu^13j(%v`|SI@?uPc-ylBH!{k7 z7Dv7QjRN~{!DpyYLVT-*LAJpO|8?H4&J2Bc5+Th-nrV^lUnfM}T;1;5y#LT*L&xxf zDpHsxdmjmyeLw3f8r~S*_$sdp6>a~+4leS1@)$B%V!h1>Y1KjsZ}9ZVNK3zNC?y=Hezk6{(D@sozOTYihB zkiM?H#oqbxV789*c9+YA=qvFFT1CGVw7>0odzn6WsLFC_{-#Ib&mSi)Y}xB$bae*c zVghux2`s&R5q8V9V3mvx8{5Sjl#3QqqeB3pd+@!Ak?QBrxn$W9h2XaFO;DSCirSx? zSD66Tx;*y@9~+C*eG_R`Y;WPHfvXD3bLrH7;Jn({R}c#a`qWJR%1`*5^ZO~giIjEa zycrId6QnGB@ID3Eytu{b5(fa8%RF<5v867;eb&({Z+mXd!9(7%t`~+=EbKF9edN|1 zf7X%@Sv_oEE9^r)`fo#?qoGjupZtV{<2<1%4Qty$$C8D-TKg(3*BgT_oeTL*NB+W3 z_)F);Udzgdq`+|34ZOCME!Ts|_V}Z7%)@Q3HJ7ZH-3*X$Yy35`oPeZc7Jxt$ zvt$D^3TF-Ehz7z%04aJM)$1`}%%_5fMRA0r1u!ygSH;ao zEbKxs`=}NblmGy$^#B;@4)-}YA((ZHB*CToh!6Gy7`+q+ib^)=8;XVLgP)Y3@do4w z%Xw`jyUm4h#<$gmZb$CEy2SL`@>QRFW zF%R|yMQnO9e7&FzZ~NHirio{Gwu|-#u9=`GtdmxCCF${{OoN%+O~lC--C(H*i(bzC{+jaeOzzkmso!iqKCJNx6ybjTC&}EytC>`#iO7;o7 zNG@$9$s~bj;iM$6aJ=fkMfMdH?Fpyf&XC0;$AnG3G`)9eQ{$Nrpkycn@e6rM;Wt5m zKi8nOubhu$`)$2n$kiJ7jO|#NOPXPDHG=#xCTm)_#Tz*6A5jB72=>mLGu1eNkNE1p zA$2fwPocs$C5QcQ6Jx5mUah3ES8oBpKu;zJY!aPxCC^Z?K~x)n@l{EsXd1f%3Jfj)@IVoQY=!Vd##a#Z8RsmTnjtfO z(!D|qOI~drFTTy74(ZTGjhxM~>mQJD^x`O(m+85F z+#~acViT;UEku98_rN28Ix1b*v0U|F-rvolS^^`kF_Eh25R%Roy>&UcF)`{{`@bu zkf%oM$lr0L%1Msyk>Z~q2+|u>_rF1b4ywr#MpEJx7(~u4ibN!ZhLB-|ysPy8*-yX> z5M0Ea5urX3049vFU&Gm-7)m!~IRuiByk4XQJ^6UK4+B6LSBa@neG$#*JvhLboI>Ytia41aoFlcq zHmjsv*#jg|nrjX{qcYF2peUoHBcl|jc{M$wOoK#sPAR8nR!3)I3AiGvPc4pgX2$jG zn4(EKqnWO#iS`DVAZ0wH6{mP@G;48Umn74RKcHyhbmZGa+5lZ~uokD1mX5dC{)7be z>uHA5@W<7l!}{B;spv=s#+n4VQxK6Xjl2%W0axgG#CG`VD1VOL?pxhZOf!RcI7cT1p-Mx% z;ruz|DH-Rg7)uO2loWdewOXgE8cR%};xJ&Qo;5^bg#g@8)m0$FAvAsGSg1n8x-XST z65y!C+xOHdO(#RF3GMN{FcJxZGF;!wQ}J|tC@3m{Chl_gb)IDo#rxV0nm?#l1d4Ed zL#n*q>p@HH@v=;YZJk*6QUN^Vg}W6-9xjYXXP2SfSrMKSecR`1k`nTF$l>T$wt9qK z6g{o)X@1Q;xh^TA*ae~Ma&W6BVxlnmji?b0wlHA)lpr5W)-nH`8vxg1TRAdP;(eUN zne<}JyrVZ&@3whnF<#674HU8Rpn0U%IAlf<-vX7Czl5|{=vGbfJSu@r!{;*v^2fsz zuo9-%efuAY%i9v#ttDWt;|;emFNfGiMuf0c8;M^eN9LjDH^il&GEp`t%FM;GQSUUx z-v*by%Rfoib=k25eRXyh=K)uO#3gv-fPC=jeb835bm@_V;v9IPSo~Lu0m>JQk z9>lXFs{S1EI;;1^$mw#}9}1I9C%i^DqG9eH@14Mrht+5^mVdqIcWJRVPH?9KDNaEZ z-F1Mm$DLz0YEYqI&+$|^LoYj7Tj+hNprp>B7n{#3VAt1ibx-l!r2_&ZPycuM3H2#y zw>l+0Eu9JIiM;zi!B6;?L*AxlF^^`6*ybX3xri+E7g*l^b67sw_kUwp{>th(#mTuB zER;lH4;~F)^bSJWGvmn;KOH?l`jm-t9!_`Qma$(wD`~r4||#V)){DHX?WO6 z^H)9U24D1c?QqAlii{J2Ul+$-D^H_JR=}`4^PzGzAe7HeE0sWyYGj#T-l$s>9gEaY zN)k<~P9D0>RxbnQzD=Lz?$Gl#+pC~Al^1e7wET2VmzMqxSiow} z@llfdC@~fQX}m|s@ZH>1$XZ+1X2pJ=?k;gzOy4!RtOzS_)6%i|0gsHA4<&Fp)P+IU ziL2UP8nX9$vDy#qoo~fYXwz(EAHUmpeG7JXqnN@s<SsUSwKshK8J2py55~%d zlJr}AIOS!+`T!%HssSJPEY)hEHtHsAZLYBXS>Ck=g80xElEBQqXTpXZ!@YR*3#&9o z%lH?=z2hppx%Tb4!#pE+yH7Nl`%fqHY3%F?(% zv#{xob)(kZJ8vXk2=)2{?=Vbhv(N?@N%(t$s!_}I3Feobu(kyG{qr`o-OAE*V`Aa( zyN|2hPnHxL>eCfA(ZG0wJ&!R~fIvsuSZO;XA=Ra%RBdR{VzD8bEy%#~mSX0NZAvW!38rSB!HmfNJFWs~FzD*`+#ueB6~ zYI!&*3kQEGHXIz;68yss^Ff13M&)S#_UhG7)?9xx%8|Q#^R(-l44Y-mg|$caRjR}i zZ`isM)$`$DFEIDU_Lv0|$1(HQn{DliW}5P9!*6Krx?y+hNK1Yb>c(1M+ik}^8w)zl z;E0F*D}aSx!ybIm3vEeK##IXMeo{?JG=!vKyKFBMsC?s1Qm(y^JV0lg^cQn?Qk13K zc)g|{ZB}phq>2JlPio|D7;_hz$3qd$%4VYEd>xW0|1Z zHUs{TW&IB0Vd~`eJ%XtB}GiG)?B%9A5xzNl&loDXf zfaA~<91hxsf>sC0K>;&u9}qw&F%V=+%6so*S&t+fTo1290B88gf~78`siFufZ5`N+vd7FLT13VQNUPg8-Y{+rK) zoLJq62^L0ymZ~KdMf$A^K&_*^5U4D?^6otgzC-8(PJBe{(~p)gxZ&H;hrJ@udb5GI z4B@CEvgBN&+05hJANO&tN_mH7eXn|$Jn-=9#@o$Dqi(%YxJTh_J|GaSa|`^8V4O4j z!uLd*KKv@+*DEs&V71P0WjvzK#XLKB$JGA$5~gTyA-)k?qzy?M_94Ul)*qFuU~u-? ztX^Ku-jJKWFW?-BmH==S%=~CHiE%#W)y<7S2=#7~oEgT{CSx$klq;eabU`|rMdf#a zYfkf<(sc&VMoiFNwy$SR+b_5Qx+E0T0|>oocx>YIFv$bzA?ww?;hUk~u|;Of-wCynL99d}w%5t^*zLG2}r z#^=6pSubiZ%o3~C*uU6a0GKo<*@ts+fLO1}ivxyXLJnM$QdQ{ZsA1fW`8;a(gz^sw zPR|=IFd3F2k}a{stk@(bq~S^;k#LwD+fdPgl^0Y25F@u^;+P)qHgUBv81o=vqeM}Ip;C5zGAA}|N;sT^YOfxe`26GD z1vS~;TThCqVpx_0cf8TWOM4lmf|dFaM^dfrZQa!Jy2|6QIz2(3=|0YGY}6-Tkiv;A z+4~m`^FyMpgj@o-c(#x^=^TdtU8o|x7s(Tp4(>{}c|06=f-(P?)M<_bSut5Mz%c{d zB>wJ0yj-+WZWMO|0GD>=9+7BGW@|p2Ih=|@0Qee?3YP}h+E2ch7tk~x^@>gMlfw*d zefN@3!AikbqNK*CFB&&J6S4eF>CpD&?UPSF-^bR>UR!UoiasNOsMnuC2D)-EcFg!A zyo;o|b2mz-GA;nF6^|(@C>j7Cx zj>jqF;8iK02RBHE8mmvntZM>2cqj!Z2~STP)RG1*mQA_hOOrlq!_ryDqKFv zQ*BIo{rTjAyUENEAcF~;krC2{?#4FK&iA+OzJOv>rYJl}u^UL)v6Qk)BX!4;L%_Vp zF8*PO34xyhOspYfLc<-T0b$G(H%Ej3bw6B4l}ZOmbDjhcX~PUhhcX)SLras=9D2R4 z2K*jm2K6d0E6RS{k^OWm`}tD#xYW^?Mn@;!KK03u&LaFsL;Hj?lGs==vzZ^6(V?9Y348XWrE z9xi}aRI&}+_)YQ9>g#y9} zM}m$R;&eV&-rGlHI8TnWXWci*Xf*G*T24W9UJ4mJ9PW)aLu_&Nd}A#J8$GPC{^H|l zq4>ixG@mi6obrbd;=1={8fXk)1bhqXCem!#W^6TRQi2#3RJ2%*<9<_XH!LF1znmMgR{U^DA2^M+8@wAmVFfMQ_?zRn0HF~M0pAk^uc z41cXq1P-m6YXE5}hmf1RPLE1{MsBnLvt zfjA2qsK^3rI~BU5vH@B#V&cTF`=yCuCaD-p;O@>;s7WQgzUZ++4^wjhOlT?1sx045 z*@B?cTFtOKnPVGT~OfhGCPMt_&nT)thV$Juh)V}|1c{NU(QeEcP6=b?{@W&*lM#|%B;Z~3~g71 z`rO;xMv4*aB$u^>kniGMhtYI_cE-q=RGBtdjvz(jV#|@o@Zux-pfJ}xPEca*8~DYJ z@U%5inwq~GteekBP=3;}k6cjt{UT4cvtm&iby-Gfz6teeZ0N?P_Uo z0}Bs!m<5{}cVXB`0*26njO>=WE+mMkTJ-F+lkHjC{kaN&{Uyr7P3?rJk6T&vi=7<* z5(5T8>iS-U!)6iEnRBb&;E*7SNZH*d*_A@V&!wS=ZaX+t2uVpUS94LL zpf`fpl-Lp)vi9K>5kkh$6HqwJQLS6nxv59TR1Q^$^X#Z>k-6GS;MQhb?FJismby&$ z$y(P`^~?6P680gQPg!;M*+1>u@uLqs&8OWWx&X*mHzY~C)96swk$!KE$u&hY{fQ}1 z0y<|v_Q`cA*c6%*ivpM30@6`=4AcH_&;H1`{^-(v{@sltO=qd>#=O_wC*Be(9<=Bi z4#apuqO-%OEcM{#nSQ-cZcu+Jg|17U?K(@KI z2kW~B&paJG_hYb0?q-YW%?qA4+x{^u|KlcK?pCkqtv=6N*W+#tJar!d+6!Yq31t_#^r9mG`&6PdHZ$T?U~Zsv)#AfJ-z+m$L%?} zI}4_FK6~Ez5_e~*^v-hkogYu{{QPkTkRL|;HjLUmjENt{l?@AA8Wwssyk=z>k{==d zHX^orL?V7fs%(Vb13YLL(H$94SRulU1>|2`0T@67==^_S1*GjG|7*VF|DUXYQ~eo8 z#*RebhknZS1SX`%kYfrJjVA?Z;{X{T&Vi92<|6etLCR-I7H>+QnMgLPo%V)KUJ%F5En$HPf6?z3-dD-WQsr>d&!>$h%ppFLIE06R?^%$jch z)oJ>7SHPc6(|^L3eEYtA{NM8>|G0Jk%k{@x&*kQ(k?bw#L)cyj8<8vwTp)7=f%_!* z9A1h8)`*ErhT6Ns-EJ6h9oj@Be1f$D>wk6S$rhFf0i)A%2tm#Jp2vH2ag#`49CD=P zrj3{W!iWbzx;|pm%GJB?WUUtQfW9R%V$^eOTf{?W9Wc_~W4&h0|bVDD>;<>;B_+-Ahm02NlT^1r<+>izm9*mjQxU+SN!?SxOfY9 zd8S=t*XM0HA2+97@4tT8VeU?2;*M`0*Y6QsJU_hhL-G_E#nkVU9jA%eP`?O)(L$v= zQL;q}dAbuUFYx&;icQb09O_2VcZ`@L0TO8$O$;rrqTA-^-Xy$Ps;{@VAl|CCWq_Fm zG?cp?;9OP6OiAA?ms+DapCL|0iq!-WG#%$NaiK~Q?a`1< z*nF1YH-uEb23IGD`>$L9e+HVD=Z~?3DoI#dn|Y1$#Nv(YL4bix6~9Zq<@@B>@5S$z zIggQ4glaH!4ICGpS&~wdRWf)P$_0*kSxxrxwDK#Dxbb>y7;V^+r zBKmAYrYPUgBuKUV=Yi&bxOEQ>rA=srx_hCF}3xU(Wj*Us9%(vwhP}%u)AqJaSImixL0`2OcnO#Q{kO zM@+{9Yn)o$iBi>gp-Msm+fM!$aOvFA3<`M zdE2Hp*V7;%;US~(Hml%wQ$ln4wYxrDCJ>qrU=R*w=3*pBh;DXXst4xC3j!)LBvHYU zGXk}lupI$Fl~rj0Fhg!+HFH$8y)}tCEA!}W-e-j50F|lPMHhsV-O}8>Xj6t~27SCy z95`@j3lqeVKq0TK16j9XKw;o(mp}(U>$2d}clCZqN!-UU{K9Anm3QgVrQ5qiD?s7C zuXO*dHlD9y{*4vT6KM_zgk;3%m3r=Z63af#1=Tf^~ER=Aw|& z7=BFG>;qx#h%2%h4XK;th{DI|%^6cb);DvcOdk&&E@~r0u{P>)*wK$~2HATSUi~cK zw_v`p;x{?ISXQGWZE%k%6EI`2gWjNZj(QxN10~0zE~|kbP&Oy%0N{OtebIl79~Y?z z@K-VV=jL~c7Y=q_;$t>pSg$BGxw5zPTG~_JQ)zQK8|SEKXNV)Jd|7L}g{r_i_6-LM+iA#+S7)ES0pmAcHahEq|FH;7IjOx|8&|Ith?S|!bk#!1O!)sCgF2Ij*jLKY(2x`IgC@=CAYgJ3%Y-TQP z7thr2n7a@t#zwQXsYFz?@qrTlr<31*OjAWVhtqE#Qll@g6}IV<4fj&GoKPhoMbQ=t z8v5)J%0M1pX~2$}aMv_3UOFFhR=xUsZFla_H$?Dn&?*>d)U+MNLsOl^ds$ro(wxm1{!KA3j9aa}dCP z$Tnx+juQBlZ4Q4K6Y;P{;9c9D__K{?Vr^~|eY$i^B;c^@51UIKVE+|9%FgRYTuvM8 zG!5SURbj=z*$gZ_mr&MW2iQWDAU?-p)wjhi{=HyzCEg(PMh<{@xijDU0RJ6zlEoGj zizB5)WbS?T!cFw`DKdoxny^rmxx`)9VqZr|y-D}#QT5ub>Kf+nd1vu}4BwS+?e#n@ zLK5=c4tg#|_`US^S8?6Fz9Mu~&4-@vJc0&>&>+O}+?d9~YbZW5I}fmpurF{k9|Cny;N9T3D#Kuh#?6fDRqpy8Br^nB@$r%_OtS0SgM$9ie={ zISn?7iUYqA&+-*+!fMWU+QndNVTPI)gPY`E?F?Hw=P?8|HD?OT&-OGTdpb2~1V|iq z7lk>&Og9+F2!nN)K2RERge*B9oHihJ2}t;5K;ULrv;dUxc(L*@UUX({QD%Kd=9#ho zYoJ*|9SbZN9uZ%_BvWw6p11)cMJY<0O20q<>yb~*hb8#V9f8^J$ly?fxAge#2Lsuk z=Jlk95wC2H&Xr?1SPzrRqhB3T=Qs+2Bq*E~QfefT+!X%Y8XM$<0pMUX13PXW1i&~7 zCHDna4xNpvyq3riLu!xPzU-ykdH}YMrn=87%{&Be8y$PkX1&4X&XPlIYxl}h5z4l? zFWEjD26Ep{

l*L4RD+xX#vmlOO}h?S5BAKXQ?S$^W@39|DaXAoj={V2ecTuWI)1)x zIld;={KK~oIv}~2aS&mFw}u6_Wc1r<^{d`&=>m3*9nk9Xxxd%P%X(!%=QnSSq+ct4 zV2xKls&Jnfi@yd*a~|ZI$f+i}{T@;Pmk%Ma23A!MSTu353J%8oulsMGw=n}cu@E;^ z_$G?KCZx}7p&#kOTQd$OkXx>O1RC16t(2HXUA6Mrud>NGTD)jViHfQoo)| z-Ffhl1+<_b;B|nUkU0LlW}61aW}9W9p=&6vF+EG&S5(S(WDZw*R3&dZ;g&W3_(s*P z&1cr^va=1}^8kxO)r4`|s&{X*4$>*w@UGfc>zvb8gYjtpmA4vKgKJqkp6_ekY8^aQ zeyuy=N_fl0I`+OjoqKlNJn%nP?U?T$Vy>qQHT>x|hj|_T^WV>Hi=W~W?o^lr)_B!r zC*2jR4mwF7jkDn`2LJw4!h{6h|A=uBw~p^ieR`F7r{-37T*BcwaE|=ei60p_f6Ju@ zk{5$mBaeWne+ES-$QhcYJM@<}>5*pF=j8-^4#A#|1n;e=y#kUJBui7v9L%j{$X*4dAnRpOG2R<;allY1AE(YPunHADUV z3YrMts}8;6(`f=i>Lr63G_zP-bz-c116)&w;XbXA`i>MRPHaJKG0ECV#g3r9unw!o-WrN(GbP)Cqe!wfFXp2C_$) z*-UK4gEHMBQ?Z1HH0rhIA&iR24TT2FM)q0S^6eANZJcFJKIThS>qr1{Q$(pINV|aP?MDV*+ zbNarN)?`7(PUeM5pRs5C$HhiJA*7@ralLT;aBkA6z;sEBc;n67#PTftEp3E^L(fE2 z_^jMSw85{Pl^<`wXb2K*?8c|#+oZYq1f5RBFhNH8Ig2Z0$xKA}mT5nUhqO+C;5Vf- zs&9IcmS~_KHAxc@C|fM+5(lT}eA7Z#)UEV(*c}#}uo;%k8MwxZH46+%JClC~kJ+3h zWCSe(2-5SNy+6~_rbU`>4_-Wd+&+6`TDV@m`%h(7i%H?W!g9?i840zYL6xrqQ>TJx zn6RNs#8O4LCUM8xCLNxEOajZa4m2BFD%*x-k$OQsDAM)v*E?nj-mAI6P1?SC_r#(# z&|-SwktTIyaxqg2zjoUAGZ~&5HP8$9C9>wsjDHnQ4o1`jjxIMEYSs=I41x+i7<3sAG?xWd(4G-0T3&m@dKd z(j|B#v5{cK>BHwSFiBeR(A)H3Eu$s)U+aX(_dx+BDJtPx3xLA`FeN#s*l*1Y?nckl zRCRrc+ho7~v6Mk#wg)Dur|&3b0dQz}fFhfxV6^x6dl{Kdn1F z*}pc9KCZ`-Xg(1@N%~o+IGq{HQ_g0G7z&t~(U)6W+h4@nm@ra{6&n7gBL`D;iQu$rgA`b`YJV{yIEX2JB_RnE3W78<%8&BKj0mFrNl_@qe* z)Ji31uS7=Qv?mS_ou9xglOw>IE*;gtjzG{eR+*Cg7+ygc_Px@Fl8k}im-0rjp#*qH zDF-((xy2#!2p^RlPnrk`aB@9T8eq5PC>bnv?oS|~o{OczHH*w$@%G_b{xM0|2K8L2 z$QJ7q>whv*J&la{CoRI@#L*!_VbImpMo!2&rNF9|0x|!}!G^Lvq@JP_IF;9QCWlN~ zceIwS8J849TJv3%T($JVX}h=$T(^ZOy+^wbgqVdCD0iIzfidK7EjQfQds?Ps;?RQY={4U;2Z;r;F9 zKsAYcdo0~czf^J5c@p3TOCUO84%AL8#ph6Y8XcVe^+W&`#d@vN!+{YQT$)kH^jD8s znf9wblmm#bE@kusrzt`!uh)bD5Zs?o%^O6BEZJ zLqF}f&=@*TgFqaFMr0p;6P#ex&VZVqmkI(oOwBWl{`Dh$KeFXV>@sU*hEkg7uoAg$ zg*hBAl9wH(PS=PPu!<BDC*E*lSCZ{E&CZTIMc zXr_R;meRi9Z1Ove-v^!;^vVui!$PoWwF4G%YpnW-)Ez6I@}j+z1J(i42*cw`t-f=8 zracV5i-XjTmH0vT@jhfgq1p2UMIRQvMd;p|HMYy%G^vOxG<{4}FOu*z-Z32QJpq{U zGAH#81IT(>^J>e~F}LSVMLR|k)W<(^+`c=hWs4h)ep(N7>WgCY=lI4&%#R0lwG)Tt z2Joj?ewNK7=N(Gi+=a_-=3Jn+fl^`yb_J6_2}G{I@f?|qVmA;H7ybK|q_(=LZE?);2n_wwBa>OwtO zw8a^L_RA>+*h0$1s9KRBUwZCXMyWmACcgc5{_2VaqvX*GW<0_0D-{ua^}pBCCvSf` zSP@#2fvUzj^9SydW$5R$3Z|H^HRwQ#dktt)HVgmqJP^Jsr)Si!ezR5mQ0t=fWxdz= z#)GnV7c&1mWE{R~bmH5i+E=vKS&n_uJB%;ae;jIMMFzf|3`qtI*yd@BP?prsHSh3h)clf-LJxGU7P|<4@;4sOHXtE}J8kR=I zWszY%5@@v)Dq{^)i*Ik_pgjRdyh0elm_1 z^@)!q=zj9Ym6lELP#H8@2JNuB8$?#~z()EgxSd-tP2}D#*1;TKOb!>}c?Fpyxy}0Y zgOTz>@!-dQ4$HjEA9pIe@?CFrm>=wjK=v&jGQN65L>&<+!0g~?xbA^N-mw`f8d zq!|#Im~MY~O`qC%;QIbPl8i>|>HGbh`Zo`WQh7P6Wm@@U_P?GNVR2v@f?Gx;b5%OGQFn}mf$-x#>9I=Gz^&7Qqavs z&>DiTZJ)DUobQ}Y`H`_y_~AzFIWoA=_e~-d7dEZ_d0cytgLVfDe{&$Een)?ULRaEJ z@EVY|B@_KyrrklsLBGJ}Wt0O7^;jCtpdF#lHQYa^hSfwG(X{`{B6c#+0n_T)Al;d1 zb$9aqJcb5#ufr3W^8g2?5~cEF&PkUvy%*G)6l(g9wErs918A5|1*u;F!^T6UOdT{g z|IoB&Rb|mcKcU4py^I^#c-XuGD0j9w^2sUpkkI4nE}k; zR}xKwF>NC*ENql;NVaZ+jF8PGy`o~CtA?ibW01F#LVI~0W1LCg00FUF@0-)4zhv>u zBSQ2v?%kt$X}!S&)%{|r8;*%^1~liLv4=p~m*&+x>or%vj|q7oQtveGyiB`uPHpES zjjIf;byqCjIT`)4NM3kgbXd*!M5ytvte~PC5nF+lnm$85d?m)U9nUGVG|`kWI{$kE zZ)3K%0mwldYAclpXX-td>8U2EgBgOL5o@^5N`oxy`>@p#4Xt`SPu4c^FRE1XjP1M` z6Hj){P7bhR`Z|55>AKI)_&{JIFrboAv0F_e^ToZ(hNeHpi{0YGC5D@%Z0n1as&`h0sG{TWAXv4I& zyna(@y-&+DNq`_e95CF;#FG1{o(RpANd+m*L|$Xx!E#Cg(h(qd>Ko1n7W3i}weSnhQVkKn&>5cAasWsvoQ)Fzv6H-? z6V5^dn$l_gNsu9hhV*1+ddGW=sUDf&<Bp?Jx?g6 z>5WZmclGIZ14OKeKGZ}NSMa)y(8%FJa~SZEZzNWISaQ8VHI#&Zq%(#vOlDqe2DTps zNP|>Fp$tHCQ*PE1n@t$IwDr5blhA;^cwc0ttDcmJDW2B-x_S?Zi^x%8EYMGjJ2F0e z&!|+}u#LK5<-ka(Ii~IJ_kxkln+`W2&i`wAol`K9NtpPAo&)KGan%@rP5@KaAbV3} z8z!U=tHpR#Or6qETnm#R_HW&cqr}#5)bNmx9Xvi zThd5j8Ur36$*2Z&C#JPRP4u8Z+9O@vll&`PCP8EdslPq-2$V#oBElqz%(;uuK7C6n z+_rz`;nh?uljPtR45kvMXa@^+k*Y^MzygojT`3(B=*J=Up-1{HOiWYaTJ}fy`9{e~ zby02#h!nuUb^^M#7JBA)3=;v}P6o;R3MYaIW%x`akLu*S(Xa#st&;zEX= zltS_ggJ0AelZU5`@VV);l;8D6BeK=8eXG6UuyO^)o2n;ycH z=YY1=?t-!a(s?Ru#O-u9Q*b=6B<=$|F-@nF8Fl|`;lYiB!D;<&8X{1p=Gd= z<|PPE(T177#w6|VA?+}jKX%|p-9FvgyM4&QXX>72iKPl;DF@#1epS}5u5}-in)K}d zX>^a(MxvRR^Hj_s28N@+y`sW)zD1lTcTWot8B|lnfypnZa zA%;?B~!$>cjmC+}9T=IitfdDwDXEELVY$kYsV3ulz%46HX76u=MZsKYE6P`$g9ce+%DPTF&){?Vd zH2lInGn=#q;S5=?mpxpIbbBTdxB31WNoPS%@6|e@!{u0k& zVaBe9fqO2&&2iohNgSnr?OVw2uY140_4j?>Z*;$6^ky%*+k3pv`@=7vM;GJU9*#hZ zLGLlVZ@59q!+-yB$MDRX?{VObXQj_~n1=2rhyKm@;d$m;IDTRDl17~5_I}4jLgvqX z#*e!PQCBNrQz0$hn=B{akUt}^2b=HcRAiKS|9NuTO5BUAK4iP-W793Pk7t;i`uz8r z38HJJZOX?E1V(9b!_hhd@DRD$!oS##mO_a?%GInVaA%}QEz2OSfWb*=gP*`W__$Y* z2D36`F8UH_Wr#oOV|1y*qiP^wTEi*5V|w7imGQx18^zCGKklD-*cf!e^B{W7rNN|w{>RNE8FgLYl3KA&)M^Cp?X65!oQNhDtMXazH$TCG?^Hf zy@q{oG4)07mArlBk5AFwzcOre`#3#FJ5X*I!+xuGdyV4-!-RsbhSIfHYfeY+-Sw!4 zdH3F}=ga?lE|0wK?eOBu^339kn}^lb_x}F*_5F+6YRB&!CEE08T@=eSw9i5PReq~! z*aoMRs{8BK|2ey|2^&s!Dx^rm`XCxXT22GxNcN;$8jJ$P~7RQCN%Kf-fA_+O0E z7tmqGB?iN9FE@*9+0!E9djnmc{v@Yk+idZ&^EcaU4iP z*dY0bcwoiXe`&r-%}y%4S3nK6Yxvjsxt-}S`R?PjBQ717giOol$k{SCKHE36J(rt_Gq`fZ+uw=U zIjF_B_uE>j_-#LOHG1`Kzm2~@fp{9Xe?S0+jsI5ddoKB%qO4 z3(<2|auEcO_D}j4WOHG^);<5N?7O5m7Y5jsV%De_pO#E#*12XY0ro{M{6o zyXAvh8#n`MZySucNcW0^O0$%3>m8nAHykd!%-~N~py$IZwS(5uP1ulPNcg0+?M1$R zA8W{9QI5hL;qpnpWrzR*mc8g}FSR@GR5t3P``v<~!Y?b*n(FS(iJguVop&*NbkXp$ zc-?Acgj-(~e;D?lXs&0I`cZcWbMWPpi)mK>lMuT%p7-1L#n*@QS=GON=esBEvxc2* zbaN z;*j|urP%*uj(Yxxki6NJ9#tKmEG78**lmy;J?m@umb_hE^m*I*5iU}#uh2H{5-$BL z#30^!&y(n)YY7i`+x(KeG56`CIg6QmF`*xkM^`)7?0+fIeiii7`SGL(37CU1*n4Rd z61gtGx#k%S-*EAgd~n}YH!tm`*f&Q1(@I_Y(!lQeo+QJxN-LL}9{2OyXZ605UE2nI zcBMSlJRXa?C@o(wKWzxSI1F)5(rF-0G*vg_3R`UQ>?v7z=M@^q_1CY zti_)W2y5pwe$E79>x0}XKdyCFc5(B;N2~tbc+7LD(MXI8 zHW*Qd}5Gw9%@bv!RAt-Z*$H&+bmE~`=!@eM>tSd zc4>}7!oO(&=Mk$Hxai~oh~8H!-0k$gDPf>F@?~=SwT(0^XR2p#aa3ZZ3{$HaD*Eez;)?r0$~WtJWnsVb1|_G*+GZ zZn_F~(y6bt#)6McBtyH^Cvs(vxR?$yB4B?h&Yg5(A}8=+;K$aLX5{<1%!mlMD}{C% z^I>-4GZ{Af^WQzuac`uD3Szp0rT^XG%tj;}KDn!YYQXRK})$o)VlXtO421Vn)l*-qoF z$^X1uEZ-=6bct(An6G;|2iWG+mjpAw5G!#X%2iUw+C$TAVe=j6OZ@d(zPfu-fWj=r ztBiXxm;(hkvyH%0)RLi=NWKnL6I^hI0Wn#?;#mqFP9?Q`Tu0OHV1YGRd+sfV52PlZ z<~@;FLJcDO;GkZ>J|}+GYJuxaq46}U6@#t|+&L!S^`!pe)?%^% zSmr2sYtB*^ETVGoVRA^Ab)%-^$kp++N@Oa18rDD7rxsgZ8c;2nc8mIV&`kkMq@Dbb znhBtyS&+wfWl)PQ06$lnU494TGz@G)ppDA{OBL!5YI&HCWBlq}J%e`SUP8QrM=)3q zEqlt-aV7I{QR@~?O=dHbNbi-74?0mPM@0834&mz7|5*&Yox5T1<@dXX|9-uC`_HF} z!#}T{`SaBOa8{CE?EfOu>EGf$Oz4DZtYA+OboPVbNi^3g27)Mu_(<^aNgUmgj8F4E z`UFUw9KM>GS-b`LhJh7Q@K+`9^&E5s!9XQEOexT+&in!gGt9tD(veIt_~;U(k%J0T zAgIfTCJxF@iD;3+)+>=tg}B#b#9FGrLJn_|qelDnMGEvbB_di0Pm>EWmGCAhavK>D zrbLKj_)e8l@fGesfKU{$CMoaC52U#QF|5Q<$s%(ldYH`hBSI?X!DTXhlM?<$iB6Ef zS{O*GT(Fn1?@X&8SPltZh6gsmx~IXJ3iKfgtdt0^lk%8Rf?5tbnj^Z(V7E}f6D(Z+ z5A+ye1)wh@Pq#u3QNh$@WIH8)QHd^CKqs)WDH7Nl8S1bSL6^g$IYlu_T)Yze8lj&@ zR7;~4wkRR4Vu&L}P$4Tj#X+BON7~7XPP?Nkf6|6?hCAXUfqc4saw8 zh*sj#6yQxFRZkaPB?IqOl*iEVF;o=+v(!kDPKjvTF2*{o5mss4Az?BNoHDdRAteW_GUaIy5%~N#|(l zHJCsa;wDAhuxYg)5-YtN2C|b@Ma_s?gZRSID&AThz9B-t)=irZgI-&KYs+*aboI=X z#oMI#E(!KF12;=SI!YmyQuHhfUB!TVT~OjW z8MqjFAy0yxl)@gcaI<9OgbY_kg?dOJOeL;01zSeQE4u+3qt;$v;L=z)9tVGnA%^Wr zHdmnrIrvc)?zT(?_rP_@akp8x*9>HZ1fxm893I{2!~pZ8_zD?3X*VvDfq6qmmW{%V zWO`n5l;8$z352Sk@}^`pZZgQV?Z|E=W>Som)?r^tut$qfDmKYzE^56L`I=nwRE85O zkwX;V1`GE_inIek!WpF2>NN!u!$H4cATud= z83%WjjxVE}w4@-~S@<+1@&*N5K2kA#7Pu-qkwC!@(niSW?I40zv+bO_-C*XKFPDa7U$#7<5~gh zyS5`c>DZ@q?5wQbMFx(R;xt(}AqBH)`NS*>H>gi?B-Aa+kue;c0cZsZdnb&O<19Js zXmTBufV;o@*i{xfMvjY?f&FCAj0JbARcB&U7AUE{8NIVph8k8Pp)%D<##6EO_zOBU)qp*@X`eJO>us)NZTcp(VYO#!c$;bPK$@qub<4*lP|zVMV7F-#q@sBa#l)ryrttp#IX1B+=m`;n197wI2#H-V~=C zg5Y5ox{~=@6$w%xA|>Xft$Zg5P$xm(RUOwP>~A%(^Ve*Pi+k-Z0^9o4{-diY2w<;K z3-B7XHCv&E3f#vR8s9i-sd96lXH-9r%PnVD)O6>N`z7ItEa+aPcKjCrLxx%@(8skd zL(=-9w_QFA_?o>z90WG8e<7nK*fcTrB&9h)VrN6n1#aSJSjaY6v9luAk%fNBzzC%{ zCsN%E8975eAN31t$KVNNs4c;eUV6dHui$7oE^!R?l6B)Sxo%W3z>^P7F+fk1%~v_N zE-Ki8eP$r~yq6t*Mv5y?w#JFimC=!16nwNY#hnU?E^SEz;kv}w_hh8yBr@VDcn=x> zRE~>d;HaEyqb!sofn+PeK4qbr; zf)Hhr1sS}Hpmv$OQZp=rpDV(}^$flyL(SwUdOq?gXT(f?Y?~53NrpJGvZ)N*k_;7p z5xb3*tx3Rn|Auu-S}u_Bzf!O-Sf~ri)-)wL(H5Cuha4C~P21rkmHHMeY2L|mrzk*| z47W{OX-PP}trRo*8}pKJe3XUcDRJFWm|4)^meirjalrWaO~jR(zbe5!?{7MJpn85) z+Q=NfNZ`+6;9s_S?Rp5uwURH<;n`A3K7$T1TW7r$T}NG=HiwW>9i>vZic8!`UA^jq z8}=wg1vS1wK~@~^UAM{91cd*hSbdj@Us?<4r@DNTV&1XTPCW+R%3U@?@IU2nJ+SO) z#7bY=C9Q8V?VYXR(e>f58dM7vPDq0qP;r@6Pjts8N{;mDp9KGS-&eH+QPni-DX?4| zl&6G;fgoPg(!&%uRS8d!fwxg%>tzOaAr#=1&QZreD7~hP$kU)!u^i-4Y@lCg+ynvfuDCw}hgp#^~B(kC|X91!3|R zGI8uxrZQ3UPHEb&`*s=6##1K8Yazah83qy>O@YTKCCE*4mF+ig{krM+Q=at>@dJck z3%Z!Z*?dWk{uQ=k?#bHD)yNyO*rdm6WdmN%rI?{v#3Q<+3I%^jiYWoDlUHHxf#&N7 zL6n(C`(6QrS=d6vKG(ZB=4hl*C@V4~xgno}r+%uaqpI_frkKF%6-(9`}t{B$qjL}bj3%JYUT_}h! zI`~RG#8aj}%-w&+X_wa1#Itacy-JQ|WLXtJEG2N(@5B#7`pKQ|d+OZ8BIuS_d$O&i!#$F&3ZbYix%b#|jy^bZV` zh12s!8k9Pbi`_NgRmZ@c1rRqz@{hkMgBpWnPxT!#_aAse`t}#Pp2LoqXFs<#yx9v` zd&chZ$InkH&-=H0{gyR{!}SmhkKC0a>8E3p#4G;mE7g|i@Qn}Qwa4*BGwXWHuul@` zkI0C7AWXle_i!Vi(>6b7hPD3U+_9IuGVo~M>E8D@)jmtq{!sDybklt0hB-3sz7VP} z#-GdC_(Q5j;VnR|Ws*Ftz_$y1lHd!)mv%a#FH;cn`*jk?YTGs(Jrnw0w)(q6>Ux$0 zUd4mN^%jO6bV8a)&$VLDfBsn#6T{$>lMbI0-L0Qp=`cU43jF{C!Aap{_+}}6#UVOR z2=PlZc&^+L!qQl=Q(REq% z@y&~;pW?#Uq&+Iwp?G@aW!TZOFM=J-3+B;9UX20suqO~P%K(qh;{qyB%+{z&k zM2kfQV_cL}C}eT7aa!zyAykk|I*WH60r9bBi>#!9P;WAaquXKKc>2)aV5Ohdwy-RJ zotT^@f7mFB%){^LSQ^H=1Tn=Mbc(2adKkhlH3Lq)nP&jm~0cn<-mWL0Ho?S$#1vj821VpD#RLtRrFjSess&1Vp+F ziBE|-)~29r#rXJxBtcC)yIN?JGdW%0M$heoS~s!5nqh~QKUZk6IsGD%glt++<5jo^ zo7Ti&7Wf<400op-Bv<0Nc1uKw1w&aK9x~6EF3S$RF%3T<+t(+ub>3GKv^z8Ey=ll_ zqFbr4U*2NDs=O3#u^~q~A3>BX0C3$Na?mk1^Z%-Zy3KX7>XAWBmkWv$Cjs64y&e|F z?YCNUi;bfUG56vQ6B`N*iJjG9qOfa63WY^cg@qJ_Gu!EGRYczI^Cw)JTkn{jNLzc? zrLnu+_T*A>YGy|f7G+M3FI6!xqf$l5;m4UMBj}zN=S?TSFRnhiwcX~HDYQE;v)Aba zjlV+hkxRVBy$0;y#!4(@-h`86;=KkM;3LbeExt|{(-4Z}J&`I;hq>%w1-BkC! z2tC)~?H35X(n=v>(=OudiS_3dB2rjDVV}r;m>Eb&8SYEQ#5L1|5X~?~3~8Bz1u51E_%zBZ5-STADrq2ndL(oXeZZ@|CQ+ZL zm6=JiaOAETlB|}Pkj5+vE#;8X6d=nSCx9#CAZ{zkmTAQ1lu`-1sp-{LP zD>ThY15KopkeyEw9pTbpi%vy(hNOWo8YChrj(~mrl(-@GpiP?7ki9jZB(CjutIjIQ zAU+`cbF$yAx4y(^`Lb<9R`lvqKSNSHaeHi(U=7RJt`8yc-sQ8&Zha9@O=wGiCFsOK zu(tJolGUeI-fkayRGCKRWTTr`*$HWt(y4bHw_Uy4VlcXo<#K zGu<0VxH(;Ha(@T1A%J}9?L13uAANS+2L<8{{=Y3^(O1d!6AwPJ&H|btJcM@86g5;? z=1xq|dAZ#07NA6jksbA31`V$YQt~1vi7UV1X|RYs4P`KTM6?k zW6}eu;3Thj%$vf2H7R2_->729Yc}60V-&t}qBmYAld{TTK9C>T)ekzk9AK3~78}vY z*UTvOfJn^OX__V>rUKFrW=(eX9@VrO=~JVKqmlUo#5l>*grUmPch|HvDo%3T&HpLR zOaqY7ieVjS)`qM?K5i-nO6W3y6KgpZ+O2)i=KAMvGa5_XvGrJ@9ItO!n%F^>^^&OcSNs^_q z%XF9l!eb=+1W7H=F45e|W0dQetu0pS{c1vtY&_p~pe1 zKSUQ3NR`2DUvY3#*)oVb5wLA` z0{iTo)n=_3)Jj$Wv}#|%tZc??o*F;suvK?bA#iWumITbTsT+-OTR4;g$J7191PWA& zx>yQxZ6E{`(U3;COn=Qq>fvh^LLbP1{B*c)6TQj^k$p9{ zB*UeF^y>`>L$5DY_gYk^(uYl>WXBqBMJf4KzvIu_T!We?j`_f|b6CG;Z5(@tD{n7p z{H0*x6HgP{$xyMb5SmjZ_4Tg4ov$o7 z{F7_6(oyE35L$qCpM;nbc2fQCmREZTpzj6h9e715je4Ak#um@q45LD5#;iQZ8=ap5r^*6YX)HUv_d~VA&^`&lUY>19E z_soA>44JEnV4@X74T2uA_OdP!D9;59-GLJW)Gl22-dI$42c*r5x5psbHtNls2h$fiVp>ul_M$ zC>t}R7DsAr)L2HhmX7u2Y;3jTn$YhK=BwPH5QZG4Wma-AsI`%-yxS_< zNN!q7CLs0Px#}`bbMrV+sjagNw0m9AlyP+3xjHh?oQr0X9srhbUyYZ<-Pnki1~(gE zZkun?0fBYcca4|t4cZ0QuMBQnBjzo)m>6MBoVzU>3#o5NKb)9N}BHJ zLF)XtfMm4%`D*)v+uV0lo|+p)FIS!kBNdR**PHIA-{2C&#jR3qa-XUO0f>ykvm0&Q z`+@7k67fn?i3a6vfL;kH2-CIT5b={MqHv2?VFr?-qJ_s|1yBmAH&ki|8kPi=-8Cqz z##nRfD8O||(G7H%_7s=8uEcpm*!9|~A~LT?Qheh`NVq-MM`#xN!NFd7m$50lZUJzg z0o?aIX{~*d_=X$K1-L=s*QMy=L`;BT$v3~EqnwhY&su>VNYNx$hoZ+y(xR7@gswxz zoLUvQT|1arSVJf_a7RidI($Nr)+8WaK5CuIHIhyAoRrb8Ow@^oyHQ@SQ&Gj~mhhJW zQ|(Tfej}(q!=w@*y|!Qn@eWQ14j{wx2!c&gMEoR=V(py{Do7GTm_*?QqF~F4iu5@G zjRKWNu*+A`+h*FK4oK(*iI7@I(u(40OF>#q>&%c~6T^r6lK@j*u%W9UHl^Sn0{<5o zaS&7x5jB!8hO8QT_^ITP=G%gG?4Vm6H)W^KD> z7~2mMdlYSOzs@0}tL5?GUIU?trE>faCZ(k-0V_un>x|CI=a~iCaPp4FQ2QQ@AE_ zt&6p=(p;!#(b*r3#lvV4wtb2nEKF-59PnJ}oy=F0kB9lFLPumM{_AE60zoW8O9_p4(xVR{kf z;Wa>afupg&P2mVMo=*`LfDq!n)((K?f*z``B4zf=2il+Edx!LF#G;I^`( za(`u%YI-wA5bUTaToTxx4N?0S{*N5&(ge0ts3@s0CP74F!PBGQnNgw$5P~^*++QgQ zac?uhfc@zLvI6Yiqzd;uAQK^0D-_<-lITZwqb~h>%QlKf>ncbhh_*JVz|28Xi-HIa zOm$&W`zhy+Yoq;}#Or1YGLMtjjed1yVpnmZ6BFIcBJ6^5Tb={5E8 z0mx`Xu%;GTgEqQEJro99ZsVLAdZ3?Y$C zYa-c#iEyEtwCYD6G!m&ECKEU<^G%fyGN{fCRA(a-rLdv@-4&|W@W0+EyfpJkCLgKO`Oc$^=$CTN#NEkBehw5JL~<-GM0u)hy1td_T)1*^U% zpbd&LYx%}2O}jR$7l~wC)Gz9Owy;RONSCTZ%YoU_Az>Wo>WhWOZ0}$*P(4NiT&bhu`dc-a0e@2qG>$~0tP7bt2Er@D%39js_ zj(FRllcFjI(C&{<*9w04zS}?qt2U%e2Dgh1I0pUCIBJ)MGMQz>*NuWk5&?V4+w=Q{ zh6~(%mj01M2xI&Up6)%Jcvx@PurzQL& z7TU|fEeh_`i0WP>SauYgrDCo-2$Q7gEG5L8>TJFM@h1TOg;4(>K3S?}8O1ZavQBSB z*t5atldUz67KBI-D%g$ebvHpA>MHouRd6th-wtcH)1HSc75w8aaF;>?IZ567g!B<1 zU2)Q*oe=8^){}8UX#|0r`$XeJ&gXRC-T2&CvhG1)vcor;Y5}ZJ; zUf%@`&*zT)=b7>-+?IUCZNxTyRe|#qIEN)Xc)sg;45D!DHG5T2PS~Bsu-IWsO{xX0 z{1gRk;0Gu+?~qcuh|80$%OjW3bU;Rschp7 z`iRUd>0n!bpu|1FS>RSE+BVR!ealjBC%Sx9b^@6ks({ByFB-A{^0LUp4ZcGm(t0ZV zn14nyN{~t6Y)2LZvbjYhV24te(FM)17NsJ&!Gj2x1%4#-D7DyJO#-QVB8Js$Pgy0`azzpwY}dR~0+84TLz zDhV|hEg%=*{y|i_L*x4MqjGcOoL~;*reW$Rn<$~NpcX#!KmEODIwp2)g+2qXwCg7q z(8&-Uu^AD^grjn2rinY!P?vnx{fd5pUZvQr&;NIxY;6C!z72H&vt~2pQoHFd#0vN) z+~BDLI~Ulcg5PbYIGIbF%u0}I%@EmHLHHpEJQq`b6A2A32zP-~t3}pzo-l4fW~+>B zfY5SbCytAzem^}v&Unp`YG(Z{Pg}yp5SB(IP#PWoHqtHbrfZW7bH5_TNr@g zIEEz|no$ApSjWOxF57i73?H^BJQ8-|j;&m5)QRA+3Ri4|L*<^Nh;63=eKT2w%V~Mv zoZ+##`43;8FA0V|ED*D1)?2nhV*WHPCj(you9<2?`_vIl{pZA7ShP|#>-DenR@WP6 z(qd=E(yNr>b)GFLY6Kq+&745+TCLO4;13dK!uano@;n|x_AWxq&>}4-s`V~N(b&pP zOKL`|@N#RB^48!_BTc!C|@$I*%Vpm(jTV! zad%U7Uz52-nQ~vVi-SrT26eVe5nPoPxt1)kdG@l(=kjc~ZafQqukU6|M(d zy<&LI)pU)q(+Z_>$%$_n4qhAYuRI^~Z9M*JW*_sRHnq>eH@2c8Kc*(5OdDB5bGCgZ zG_@^ye>?O-$TFKbvD(<{F$kd%E}C|+qU^`!(MPpQPb}DF*2QZLjhYDWm7;jfV90d_ zOu5>88oaR=M)Jt>pB(NufckF!Pjsb!p@jX+)UEsix13|q^*0~C{l6{#mHu8%iT~~C z{O8QlOMB-3`u5-JPY&iZPT|jQpSJ56c74@sOYdyH79UhY>kRByUGDa26e@IhH;Uwu z^J}GDr}>*8CY141&kYaq9;ZDfcJa1$IS*zhquJdQVTt8J`w^n!xr~ug+Dk+0T_3kL zuW05AnQf_mvdXKJR+%BiQC-@F670BvDPjJ{I~c_@)e3d!g1j@u;+Orl;XxxA8W=Gq z!2;!BVY^|(&wuz}FFVT`T0*;vjtLLQ2O)}MMi59WKFEF+$=;5a97STxwDURi*JF>u z{hrycMl+<%3MnSM(YDj~oFVJJ|I5LCf=42+4~p5jK+7TeMtSx4Ub4y}ct~0grBr@E zSMRs6i@P3eC82cft4wYa!HC}F(*2M-t+2(XNAkqg7rQ2Y-u162R!ecAf8~)@9lWL` zezbgah1FK_AH1M_C@2-Q-B7PC( z-<$WTP1YTBVlXr1+K;CvwoK3oi3|UZT`8K~%Qh}%>JcMFPpW2`IR!@Xhc3^y$n5p% zKzVW*2|Mn%@6LIYe&uD$i;Q1(HoK=EUS#9B6#yR`+RksMY(Y8Yp>h z8U#*GPRrDhwg6T8nRerfAH;>fCp&P0J9-#-xsY);V@q4rU22nD*I~9XYEo*pux%og z?tRNE?Cs9U>3hUTcc0MlI={d7DB`!Y2}(XNSumOS+Z}G?-^K`~C;nz3NOSUr9I4BH z4^5A=G6bDwu_|<}-Gno4Kps0I{>In#&P`B&Z7#8d@jhca=oPpP7wR)&m+7LqW*^HaO${%8H z#un%$@Ynib(nTum6Y?*KNLtGOfaA;}Vql47GAcz4WLVYK1H4)Pjr!aK*X(vlUDKg4%E8Op=TWS9D5$jKs zdkdjVg~Td_wmZj*V|!4s-F`{8l52LDJyj+br^L%^sb_AvAL^LAw?H!K{a?6axkit8 znmvS_m$E)ROs;$Omh6kSS7Oi5NJ9S|q|a&0qc;ZEy%_ejxdB-YGu5vVA-(6Dw~AQK za!5>);<{A@=Ga^{nu_~xFfz{o*>8(*hRPuL;wh+cr2*jpwrGQR?a{wi5Ob#Y5#xa%3;Qof``vN?W@$pL zp(*F3S(_&4AAR?ki}XjI^Eb7GQu+c@vbd6*0iX($Vt+RNgdWQ(+yB}`5JLU= zz>0RI3Qce!wPPPr2Z6dLcqbyf&TUq^4gGW1Mif9oCZi zq5mGox5OxU#_q1M?p_Z#u|PVZT{o}io=Z8sx%y4R`pEQwzUrsVj7azNV`)NP$?o4@KgnLX*RK0l4wtZqMm6D_a4G?nU;xDGb3A$rf$ykS!8 zSIOp$(W@hOIGg7`O8oMXh5NUUO;s2qj5_w#0l(J%L0VPpU{Lf?;81%}UfBv@RxwCRK!OMTUT5HlmaguqbfZ)2F-SbRA;0dYdz8 z@fdLiANJ^PgvrJ16-Q8f8qC`2tS)lH206kM=J2EMv}L$>85;Xo`Id%{?YuxpV#O$x zTT$-Qnt;posjV$aL}FPQ3xP(s$o#hk`oA-RP2cyvL$8DmvQ1;$>a5(lyZu_GjCW4V zt0`v_N8P%KwjbUvl@16tmd8=u*9`P-ZfU+Ul#FgJJCJ99J^i5%Lt~|HEGjI$g2vo8 zFZp%&#aqiOyYM;b`|l6@QP@3y-znR&?hJO5TQKo*=7?!Kqa-fZ-*x z>p~|u7R{2@Eh*W!;!3H<%Cd<6K)4{;5ZyoU@Wh^)l0ymuu=)1KPkYlJ9o@QS%bq0F zjC^r99SSsUc*_CuXV)3v@d{^Cx$1-U7aD>~<6s#NF&+*T=%qr4(G-qpETfxm5rX%x z327RIWC~r5^lMfYWL0Y6RMNTL4B(0t8M4KGH7xm9mLww5>f}-rnkg-|)N_z^+um7+ zSyUx8PCK9#kRu9ri3og|dMKnK0XrInXcq*Vo2Yl1@`2@N>XfMbo$V&sMg=w2yD=_m zCO$#&98A+ABP+xh{shcP#x~z#cvo~TKx!o_K0h~CV;lGoHj5!fdr&M$lv^+}zU?gN zhY;#iL%wah;Z(Oo!nq(!3D4&2J~j>OdbkMg*;YTRj+^NC*8s7dkwH$HJce*MFl4&9J4#(`O96p4^ibefK7&OGT6=hJX(O+IZwV;4SgkFhMm?JPq0k~2be=~=oF4KI@p!P#wuSa z^YWR8*$(QC4F2;*i#4d@N02pAkpElo80KHYvK9x=i_&`Z>S!ims9foSURZ!Ac)mer z8D)I!>j~i`QcW*eIH;qtNCdLl41hgp)oxw8#I;rOw3pg8U)1*SM9@Uo?H{lODhS*g zwy^jpY3Go6W1-rJw>ws3?xx+-b`--pMBqVv%XKqUS+|`x)XzybCr^3+B%GXJR5>iL zg5<~3x%NZJqtMPtwQC&g|D7u7*$olYflgQ60~^M$nMuT{|F@r9^Q4~MTAy6Z{~#x~ zY9?9}tQMK&NqxMb9&tKn3e>MxYeIqf3ULw{#I23(T5e13moQaoJHF1kXxKGFv`oeV z0V#N;%qvLZ`gpCK6YQ3g-P|Od>jX>T-gopQaJd+8VAzrv`4|wd>V;D6$zHusni?C7aSE$A>LpMh>`c(+~+{&>nRr|^zKfIQoJDa#7eoo!R*X_-x zH{42Ge^$*j=z{7Xs3{Re1PjQO`q{6s7>~!NNnKI~JffgBYOQUq&O;<+=+`+!LEXNr zbHGF0YSy{B1t*qjozxuaD2UHNl02XRYKct>)D7+c-)UHvuo9gM3X{PeZm<9uVBF5~ z7}L=PbslxF1@;9Mi?qt}!JPo=R;{GOe`_A=Qb!gb?4|yoR%W8B$bOGwvg7a7yw?9nczp>2^|5i>|@6Z^hqRA49TLxU6= zxbv**M7Oa%Yk;K`*1`eoyr_`2CHT4t`)cUn9b|35d=R}}1!rt_#dYm+AR zi<0`KNc_shF1fmE3*LHwYHym(R-{||>VrL*nrgWQt^G;z_L=4WYtyWz@q_FCYVGQJ?4no$^Eq@H z+AsGaoqHCW34^0K0p1+CN@Ld`ot>b4m8G-GUbFZuPJYA-a$JBWiF zRij%+d??VDAdVPrLJaXB$H5}9hV3ZOr78fEEn#xWAQyP1L2}W$F?eFhrGrAu+}=wo z%{Fd0Ldi8Fh3jlbfy+hghBr11Mr#GlY>TwuK)lw}E!bHJ=0QO;G+uUW z-b&_)> zI}d`^tF7eb*2ztG-j7pqL{@H4(%6!`vjEj8_-}#)^aLqRQuj8omF2}Z<=l6hAr9VS zcIB|QQf#g#tQr?r0TXYwo|SKqYQ)-wF6KTZQ2X=W7#&4}z zF@&L4n>hu0SS@{5J?c`YaBTx(+9yKzTKMlNU*}j^uVls(T3^=&r8WeI0=;gQ6 zfQ}8Ep;NRzfNqYr_Lh}|X)d2_pxm1Pu@HJu0-Jg>zggq;L2`5f?wu$*6=Y8;kkaVLI ztw*!OrgL555iPA*Ya8O=R;T6nusx!3JesvmfYNal#7zy|%hT8wb37(Awy_%9sJAIC z9Mf#C)DE@1A~?|gg?+oK(ZXN}oR~=~g>Ful`YPwFe=@o0Ri*=}(E1Y$9K~keuIaN9 z2v^?U)_kJt)VLLeO=3CvXFtnzUlKrpP*?z(A`0wp$hxrIV-r)efdzNsIg#Y}FGU`D zHRP%q;$wvKeu$g6rdF_K9TpMl_S5wMvH1x`2%!Am@9k7`d)45CU}PJBDrQBjHaT*b zMXF?>WFox(zH59IrcPb4O^quDka4RA|5R`gts}+2qGAAv?!+iqBn7K@2Eg#tBr7ha zO^sHF_D1Hm-|rwQ)GOY%?!ByrE7ZU21Mo_dr2{3)njgcXfXFxgd)KOZCcnemv^G%y zHP?Hn*B@7|o(cV^Mtd7!@YiEH)skd2r0n0ti0R^+KTg_^7YYEBJ^&Zh8d_$8i}T-` zI6f$~Qk@UYQ=BdLhHEV^xhB$y^yzl@R1*c7*dpY2?3EbC>TcZuo4bNyB9zPYnaB>x~^ zBw8dt{Q2&a4|e1!?YB^SGB>ipc>wm{i|NZat z-P#I}l> zGN)*8T>5R(y+7{U)4nL&GodjqAEJqvqIPrQxPLwYf+J5vby+Nb&Z>QE5(tqUr+en` zcb3`Z6Rg}L`a6g89mKVY4BprTLx!>PN*ZMtajG!p{tLoJ%aZSvn7KS@?q607o=XQN zd|_1Bwdb3GeewQ~&jPH~LMQ&l)k*DV(w378)LwQSIQNrb;DlnkyTnuRyk&x_IlcRB z+~d`8NsJJ=F)7lZD)WtUFrL#qHvF)91h?=8cmDOuXYz?Y^J+_5tL$ot#`GDUaBvcu zin%*yk3#uq@gkh@yz;eJaeoN0boSODSxqkqSK-eaR0KT>!&bNl$|{U6_K~a{=kEa> z+pxn7dy^9)ue-`+X8u{K2bWW8aAg7fTDOu`c(EBXwio?S5b4;>+&Qig3@4Qm9eR5d zUY2|Eetdra?Al(Ny?g%r`tkj{&FMndr0}64TkmjS-yCI}LW8VgB^h~{WGl4T*&&ib zyic=2N1We~q_Hg$K|`F5kTdt0gnm)n#U5orJ1ByvvJUfgvSsb?beSz8_xF!?HhX2i zjXG^hf{eTD5AzOoIf%zm;d>unwkw@C?r&e=b~XF%VScN<4sE9{o{<(ayC}hOQuH*7 zuK#m#MCE#+d6DG_qmq5s%$F)ZFb63D>JDKeX~3` z{vi|{t9KqPS>3E3KH(KUk$hxflwt_sqYnt(zc813hCsn@){xxm#@?Rr&B@IvU6cwL zHd=aaT6dUHr!OzbN)^~40k6P?_S>wXUuF%8G zIn8m>#J>Jb5vFsInMd`Qj`Twrdo%=JFw(hy43ge2B=YQG z=1bb(fkLAaBRL(6rd_vM%pyfFjTi9Jh9w9mwnR#6Y*DH=%Hra@$ZLFrh5*$Izfs({``YZMAMFS z%EY8mTXUK`*lPF-VxB?(wVDWCAj@9$&mOa8inmF%Z(SX_vx*Q}Av1TV5*t_7z@Mhc z+@q_C7eyJUYbFpLDmE-r3ERIkqa9t#=%lAXsCMK<%sje0G8<-U?{uuSTp$`89xf}P zv9}76?!O4HOSyO99rGkcw4=x__3)OZVw|r@ z@(fi{;e<(`!6>XZDKDMc(Fd0iql@{9WW!sZcB6zHStC9bWG|1Wm-EX_M{q7{s^|>J z{Y}Heq|dXRBXR&)v^?1=&IE4aNiR+RJ-qK|g~&tRo3gf88Q|pvvmTlke)+ycH|P(+ zwQygjn+%)YH8}Xu^aPrTc6KSl3xA%apjO7^zvSzD4?e^|a-ZGw_#w7z5%14b4Vk}G zN{Hd{*T1Vw9#@%ttxGmM(%+5EojZT+zfN%aO20Hrx)WJiA%cfB*ino5(tvi2+>23# zKI0TzP$ZHiQE#FnLAW%+D+82Hw_C+SO{@9)!oPsINj(MIv{6Q)&@Zf;k$+p&^^#_v zduH}Aaz~Jv24-KQrv9o}6xg}!Kwbm;+=^B$Pa6A7KXBFNZ~r0&e%T#Q5yV(>|IuFx zaUTPsiYhMAQ3i%cxgt7|4@i?p0y#=(fFIHqE`&Co+k4vTjq*NiL*$FPWyMg=fg3E0 zXQ*VuTVL}NFDjTKgln0@0t})f(w9vss{^WgAdWs(?W*V8$S^Ys$6}U$ zs9)>l{G=d`U4w-*sOs|9&0z5P)oe{%EdxBJ&;s6W?OAsq;&i9A=KrhEZN6jq2`CiR} zlE+Lg%ul#5icp(U&q@3DN$dBq~^6k&5kj&*#-V*{Z>bnCAH z^-3hn$Fr#ClvSJgk5a=>MM`;xflv#eYgq)4 zCM^nc`OC-doZ%otYETJ=qyzx1FhbXT0*h6QZY9Cj7U?mE9|xrNvk=xXh`T}mEDz-2;n4ZkAc)7+R$tuL~KGu zi)Npr;ri3vv?A!%NmPF(ZgiRbRb!_iFGqqV)^HG(U_eCE_{}0@f2I?x7UjgnfoJ-B z(QM2Jsoro>Sq7W6+{=9Hf*@{oj5~bQMGmiolf-$8fvq^IBu)a5xxaeVA1(Ms+B4mlBO16detV?|J(E!L&fzKe8frvtdd1) zp1?M($9EAhpt~z$Q^KmO)kEwU1EC9I#upP`7>GYM?T#wj{UySp#ek#n;WR!Ty#A&S zOgVJ((LU4m(VGFqHZJS{( z>Z`_g;i*bgEDI#%4!(L%k2fU68Bid{OWx`oo8)F({n@(O(P6`??l*9b0e-3j$peJB zNp2n5IUaY9BSTPW61S9QM9O1+4B)wdV^=eRES(8QL@O6l&+vkVImsg%_)2)pu-r;I zFII^dRg?VzWUOI+?yx+`j@}JLrev>r>WzqEA^2)|aq_{a7-YkHy2m=KwZJAo3r|w> z?cc+r`6!3QuH1tja~2=Ozl9Hc*_Eo~rP89dD^aiZMK1xC43*o(C{uFQAwlNXV-7t> zH^)EedCplkf6w)sMKzt065QeDbIRLULGCk-}<#ZxIji>tRvU z0wX2gVt_??1TkX@jAR0fQwKRmW>~m#KK8oW#8^x$H*Bjn?6~2M2D{MjsnAIJY_N7! z3Bl+Kt^R^GE66IdZKi2KpH;8Fsn~z)4O2r_+A6Et^x0Da+lfUM6N`*~oHLqnB)&Dk zZhyqRHC%G&A=ZVAbOPXa9){*aWClnUo$X`BRi-5G&yiR+zX_xv!qZl{#G1{uNAQ#> zAtOJve5V89csSDXbuez@;hxgwX2c@f`C%urSyL^9U|rZIb-L%-6s073Ima>?u+5JNop&jCEp6j` zzWruXmv}zLVP;$U_Blw#}bb+F5M}{|fS3&X#?woYRuTdKNBPnfRC= zR+SkYdM$H34NQdU9S4B$EuK=X1DWzet?OH7^Tj##_XFO$H*typ^a_D-JKs2mZOYW(%;*Vo1;*WgbnE}qtY%e$4~GY$#Kb5% zsB2)fD#Rtxi>8g+>+1P;y0;Y>u)hrr;j-LF@vHc`v(;?8Y*8a)CA%bNX~?qhFEjKZ zvKQsc`UTE(%D7=c7oXV4hdgaZckuCV`NRw}mc~G)X-qo}0D})<&?x>ruZt^6mJ>Jl zg~N{UO`a;DziG4h4>{}k&vQjsg)*Q~oi3(X{^h%@Q5tpA-3F5_&-43QO*eWw*f#h^ z*%@OzrjTuy5&roZflugdB6RCyj9j#|tbLwa) zxhd?k`T0WwTj8T;tq+M-+{-@ob6cwqKFP7s$$nRp!OTNUsN?Sl4++6jp37-0hW&F( z-$mNv+uOPmqq)`53eaVa5#o^K6 z5skBtOs60s&0A%Avxb_QDi(IBi5+~%0v1{}LyKyxi867DZl@SqvzD0A%)_Ehj>*zW z>@Sh2Ek8y}%ER+C)#NC!GH$;-R;A*F*|RV=1j4;eLTW@9zx4G>ej+A_`|@8f&w zjiJnjA!9tGs#aMLBXz9Ezj0`BNoQ9{(kev>n;a-0@`eZrL)7E0)&~W+R5sYWK&aMy z%4S<|#Rz2ksbM-1AqSAD8=$e2c=W_@3Yim>P~nATCJ zZU``A2cfTU)Z%f=KnS`t4bB^)W>=9nrr}%vGr?tC2!im9zbCM_Z=2!A#X-K*kR$kgrPp<5;! z?PVLNrBu_l&KuYAEAW~-mxeOyah4tI{D@Ff(hiCq__I_j~wMBq;bGCr$`pO6T7S3i>{CsRY8gQP^ z&Tj8Nb%XOZlyaUH+J?nOt@yQv;Db`+ZOyGJ zO+K7%fiFh1vdIw%Kk|l5!_?$Ky2WiVl6M%^unQiDbeb1so~qF$XiS5mEbv358=I+( zRewdP$Uv5Pf*4V&HdASCH72Z@*Jeb)jNKE!O@>o=VgwvQ=?77659qHg)D~J#3)`Zg zl)8tN0aC*QH>n=(g;63@#Go1DWcMQV$LCc>;XI3&ybrOxfI|}866B%{e=}S^p=R)( z607K8%6B&)9*1y>x?$4{fw~8x(Tb=Jz?#2tXRr}*` z%f-rB9pYK9lva45Rg1tXn!QiNhl1Ar!6fRd&VwCFUEK@H%D>cbeuyXe@txOwhrjl3 zmi_KIO)?XZ^)`QoMEyGKbFJmyk;K1+nW#9gh8>1oxrRgLtN(V{(Bw3BOv>T|a}Xpm zo>r*T6_V{DD#sM`a?7-WT}@|ujxv(F$JZObxy|=q z^*l5G%DD^NMhSAOcR}$oX3lUw{j*p~wp)5svh3#@xe@aM?YS2x_-^5hwPvbnd{Ljx z{lkutr=FO59J*c39O*t8d9Cr~O_x7qIC7Qr^&Jt){Si0C#F(&W$>=nD&U0VhiyLbP zT0TDVUp-=J3e|pmNV4)z6#HMf|GNC*AKIMyK{SO~ z`}=w-{@I00N%?$B&G3s80ax$cVs>Ot7-Jr>u8?S)(CY!M2 zj5_S@o7wKG>2DlU(kjkI^_U(zfg$lJh*IBo{m>>M zP+#(rkGZ|{W)i)h#m&WST0_YqQY9%XJAL2yB*BPoX+sZu+$b>*X3So+X`}6wCCVPx z*J+&{ewEh`+WEoawqkw1TR>&W-Mt(w!HS=Jj2_rjg>V?p$Sh(mY|{|PFH2zUzPEXw zBmB-42kZO_vagN!RQh+_FSDyNK&T6|VA{YJ#S_6q&$LX;JV|+9xZeSvsSdw3E^TLYE<0dpk93#b=YN1{tU+Mu*{g3>od-X#9iwvir(7) z@X*qQ%ZwvD8Z%bJ#za2%x(AE4n1omq_Lof=CFW(C+86c;+M&2QMuE#Ox89`>Qct#% z7XEP?CoQ-E|GYAu2&{m}* zRAdZoXI5r_QPZUOJ`CBTRWGruD4uvj3}SV3ncVquF5m08Ao!*8Q}m-w%7MB`C~>YH zC}t)as_~B3-Vt>;dvA^lnV$^ZIeh(qGH=F9!ml3dznd``(Z7~DC3k-jG}Y4XU!wb!#jCp4>)T+Lu?DOu*6Pve-dgfk3+dj#6{U-SswGFsl?JX?>83P3s&VSD*|pBQ z9y=%ZuZ15`$=A8%8KtaVLCFso*M#{#(pfc%IJZG5%C?+s+}tlk<#J^tZW1CIokDZI z3^?>IOOO{oqnjV|l(Z{N24><4tQtefp5<)nw7Sr@P3h(&x1WPcKJN5hV!XrOc3qAN zW-sKF@bl~_Rh@9I)#XEHd1sT($97YqRiaB2`a0LSk`==u6K4AmEG(^X!I#Oor=CbH zgZdUNm>Md{`#o;|t8S5hHvPb^Ua3v$k9(^XzTH{JKMSHi;2!_27NbL0FjGDY@i$3g zp)5tL+Q`O*>m}xfzSCeuk{G3gP)9*IkRc{!tD$DaqJZhgY)pg#YHd&>ob>=EoV9FL zEB}m}|Kp@^wFI{5@#(;RHpl1_ldYXg8ncexbnzlyh`Xm8k>Bej4R9|&b!+VSb`#VEL~v2C5sQqG640wGWvU=+(G!(GVYGJrU76FT#@ zBqu7#{4)jK6lfsqehjl3twSvsP+ppoO%wRg-v#)!sdj>+SLnJf*Ii9TD^lE2R(VCZ ztjZ|#(vQPPtko_TYxeeWj)&he51c%#BfhFzd%X{Z;O8a6vPjbroWzRQa9$L~izc@${r&+MGbF*-XC(BpG<;WT^0 zdP|i*Yyjz(rU_lIzDfD=;o-eq&6(@@gR8IBKWRP=X-EM3+^)FnZ`r(UN8-u5GsE4M z#dmJ6P-TAoVBJ3P?BWqNDJ}j(!oB(x^Z8lYiLGZY?luu@bim*y_A8KpRtDZNdci z15=%~z7K{7^JrTSUtqBvIYaW4ehuJy8)m^W$hk6G%2!qDKlMSMZ>*VF-LvK?K$;d( z0;a_%f%ROY6g}8lN!`X&Uc{uG$Sr-FUEP^(ShGarhPiBOJXY=@+{I6@^jX-&_9T|F)#j(XHPjIEm5 z#LbJ+pP~@^HUjzZ*NY z{fflR2%iP6{P(oa#St6n)YP$7FK#@ffA5=no4#!qp({kK%*}UW02$jToDUsPkfs>u zXIY4g4D1y?c*-xnqQG2KZ|-BDU$Ka1ROlXn2x?n1#|(sHDmWQb@s(({0x9NVHjv>V zEQFH*p2`QSIdC@Lh$@ETGiBiwvIw-4+%F@y$|BXU{X$ZY3V(Kj|I8TrUPXEj;8Y6Y z4>jsp4BS}(coiDwI7axq6Y!N=X%mPX06(8iuye>}3nD|$C0%b%a^!o(8%6mPWcziP z%x9o(egST!07z9foCVkbNSYAE=L1es^mhKfMM4x!gf3O$-T~1mWd+rpf?ZY7A8NKA zQll(s$UQ3bC;QZI_OLAstaJkQZ$A8h0lP)9fBppOm}(P?w9a6*O*kOWIFI*R}%Jmax5TZ!_ks<~ct<`2O0S2eqQB+VuLj2i+GR{Ds;( zcg0@j^Fs^XZ^Fkx5DH*z%ep<85Ge!WMN2*Z44Fhjo}l5Lt1uh6$W08GGXw3QMm=Ss zH>uDo7??dO9{L#F$V|i3He7ymf3`O~XcM>vq+W^97(62rK5jR2mCpgp3U>_p202rGvn3V`x zXNah?z%P7}Z?kT1lJDG`ne7#$QzMZ{+e z0Wc<|xB-BTzl!*}BRkJm96x{j#`%2gIjPGzjN)8w(K(2r zc08Cz~ zoXS!FNer~WA=Qf(-zvg=(4)V8fo@b2kZR;0Ko|xH5;FL#MSx0h1>_iekogtuSP}tY zs6j8g+Is@`=L&t00lCdbmvC*WXhaDgpK_%t5wQGQgoE0m?*fDaeT3vEkXb#nXDs{& zF1nITk}x1QRG1Pn0S|4m=iqI-k?snZw-Wz(68kM4?Pvl#6WX-$PoGmG^&l^*fQ1Wb zL91(dFRmv1y2?*?U4I-fUFSKrttE)%8LOr&)We3STDl|&TVolWQ;9k0YeRu+*%vZ< zY_HAaop9emZQZpi930AXzNj&m?(GO6U6>$bQ}6>quNyyS*_fSJR8@E$9>qMv%u$`V ziAi$%20@Zf3RFM@9|9L$q$!w>v5*wT$?b}hGyt-lcJg4_#qAS0^K0wnFK)V5H7?V^ zjxn%YJ@$|a`6VTR&hiCQo8I{gRT?Dy2BBS#zAMB4F9?+rlw=jxo=?TkLv@q))aGE+ z+)GDAL@bsi2zELL;PFt4G47?V34ez*q4?^iqkPLj#!4zk`*JV600d`lf! z6(&si8VUG3*Ca>x?wZ7e^x-y3h4T5M3Mm!@w+@~u-$$YJeGw> znm|U3BgTdiOMaJI(~UZt;Bmd}kvwpT>R8R|NX_d=<8`c>$cpaoSleTjGjL~7JtEJ0GK@Oo(Gb>;quurg-T zv7|d2;czlQlfv0)+0=8pc7ga$(v!N}(k z-fGw~`Farhd>d8zGVQ@aaE7fKxh&%Wi;G^P0)L2*&xJX1OTP@Zdhrkua`l7v_#_T3 zi>_3AhM~cKeV92i;??^err7vd4RPk{G@+A`l%vP`XI^M3$Ao!xIj2S~nq=NR9&u`y z>EiDvoWQ830#(I>IUTzBKxm464OaM%DpHc>X6~)}=vkM} z$$gqjeD+;V1>_mdwDhj;>jMC*0|4gcicN^l^>=(TR=c}7C_;T{u&$#}rieRp?#Z8P zE^z@Xave&5X&2?&^$vVk#ERv4Z?zY+>qRR!J#{Z>n0ndpXhrR}oek?@pI*M2yY}_B z-LI!Fx{j=bTk`utX~=LI@(q?aTj?(3!MQXfWCSq);LZZLi>$@4$=9f(?pY-i`DOfo zlAt9+DG4uV*2A_7hV4szW}Iorl$UPrxuo}c;ztGXvyzByf!6~=zKz(CbqutTSoC{< zLH92F-MZfjo1%(XAihwl!j|VXlm{V64AjzR*LSp@Sp5C?duX#87@e+R%xrgmcW0Mz3WVtIH5$)G20iT5Ow4+9+cbr15~k=6V@KJ|LKQ0h%Z}yO1Jfw+56e8R1z*$EFY5>JxxIJ@UV13rhQ zOZkkGGAX_+;@s|>9DYv<<3@jc&u@=?%H2JD2GWTJ$1#wb6%c}O+v}7@H0f0KsqK~q zRGu2xAAmL&zQ{WT0`!x$dwgkl`Q}Jp5Et3Uz!-oFs~FfmJ$69UcfuNWM!i|f zB2Fuap+ZC%hRA>Zxu^PH3!bif@DUTZ7E;p?$MjEwKP(1Kz?8jyuQ> zcPQ2RhZS4hNOq)KpdolNjc-u4le|k=T@#tupAXG0)(+aoq?m25-mj9y6#v$xF5 zmK6u)egF33mwD_Mw>q@MI`nw#`z}7a^(3*MolwVt!1%n)`Tq*D-Vd?5Uw9%Xid9{_kIf zA08U6oKPYvCFB~YWqv{hD+&4#ghjc}(c{&C!IVgcrFP|uq$mm2s@w$IIEsMtAh!rh zg&~ksA^?LUrqcRJ@vHk0sBo_MeS40iAJeew=k`nC*5$!p&NQ6*a-oGocN1gWY+>gR zP4Eu)B`(*-E-#t?H*!Iw+Z~&>v8Bu6p1k<3<4sB7=X}wKzkM6_!k&;9;ycE| z=EdSD-}OP6EiYuWP=s4s!-a@p3%P;MNJU-qquX?2`StBDHm6iUf05d%yioJFo3}d= z%L2ai5+ZJWuaH$ceDC{OXt~wQcMSXM!`=>Z*et>J;2#;OtJ-kaybVMoZFR$Q-*$FV znY^8eK$%!H^sO|Zz@$>x+!p{zMRfziSc4IugN#jpc9y9V0IY-_bAE$KGX0R0sH9%6 zvk4p6_s;H{ZtqpTbiXX(>^~m%N&7-Nh02!3E~_->J@0NPFO=LJ_%c%Ji@tuLJjnKX z^8UqMkJ+6DYkCQvm4Xz#oFDym$34dat`cp|s;^Wf@EtZ7=f5zvLEDtMO8Q36Ho(P^ zdQVgmtjWn6spl?r`K6tWnbt;MD(}cOi2oqISheho(>(K>r%_?mlSzcEwl5F1eCOYk zTIns^Idx`}#o?-~`r*mZ^e@K2x1YNi)wS?-#$ZJ(*D%5A=j zXSAN}FLpZSgn7S(@!we6*}yb(`PKF3c1+zY*Cb8evHQDV{HAx{uP;qu_eL(aQ;xg- zxN!RKUBB)}7%x3=U4KLIy!?tsCOtfbBd8H=^CRl@=;V&gwWK(ZYwC9eiEv*^3|ATG zwKX0!$nBF_A``J8K3qLT#pd-vtn{&p;x`Qvd0j?So$o|-fC%Fv8WEIA3u@78 zfoH%0k>%XhetY4~ujW{~TCCrof;=f4BOj@-E)a1E?1b?ZNg@oR);2j_%SaXzl+#7) znF37UkKt>paQ&5-m}sPAwC!!&U8K86Lx=#ydR0u6uSkrCcHm<#M`Qe<#%*YRYCbNi zw(}7ali5q&?+ZaWhI5FyzLCZyAqUR~*b+}2l+GA#LA$EO--IHm>4fU=z0SAay7eO0 z9+oRN;@-}WTinZA-3!&jXq+}}Mwo_Yp#vDlF|Brp%aL0SKdqU!D)+h6qHh7pgbkx@ zynD|~C&D}qXz*BDu{7_?WvSt)=G*E)!JoIJMT81+?ivqor_Sn>Il*dRvpjTJ2|PcCH1Kdw1f z!M%}Mp;*^2d?F|ONnKpr`9IR7l-=>ymRKxX82sVRv}lB4^TC>m#~Ly7+<@w~PFg4c zgLU%@T~pn%*CMGlmDT6nlmfsmUTe6cPsFqzCZg`f0SV1|^j8>Ktw;^`0$Dg;J=-z> zA!mXLN&tVGGixR5{RY4tE7=CoiNWO0b^NhWyGxGgdH?KRtP?QNbJ7NF+|x$nvM$l7 zOMM|87X3IPxCLRsd`qwu6?@B=NWWIGNv;a6pQ}1*?(=5xdH~_srrT-v1lZmG9PTu! zLa{`raN$BIHx1RA^MaPGrNZBTzjoBpMPvQ#B|JA`J}Pb;i5pxcp%3b6m~a2rP*7|% zn}h!C5{d0Rv4rl-H9o53da&IjX5&7X-&;9&JrQnxBQ&6?;9w*8aF+nd(G{1)fmd~V z=2fVvJq#puHG8>fJ%Cy4$|0wV9+)@OB7KBSxJcexgWfNwLo*#_FPLJzK^4j%K3Ke} zO}gkfU#}d?xg9MM6VJOtf$l5x==35_C4jx5p6f)SYZdW7|3%waEI4xVnIyG^k5upw zgl@m}o+WDMG~4eE&o}>L_3xoRTi%tjj6Q{_O-x-FDzEWg<$yWY z^lC6|_2US+InV!j?(Mv6V0xN?uzwHTF6=r(MKz5B)5f`1A_e@jHzRJLUP%mdmhmBQ}_i!J#+G!*EK z-)7{6xD*WFE(n59>LmEr9+3J52xZN6HQ`;L>Tjih6P4H~kE*Jpl{0SBiJG#Nkud$b zKCMBh7)S3-q$k<^BF{R=&Jl(w7yGoPynY;=F*51TkU71b#;%MUrX|m5UR|4(hBb^( zSkqUGazA7AW;BLb{7r-bUfIgAopc35!ixQ@uvCrEz?m=Jp+c!ymHNw?{2)8qY`9r3 zA32nN+XtV$M^M7YAI(ROu4SPeg(u8*xBm6y;U9$?Uy57^qHH&U%Z%G}l!c5AACu38 z4#|>9g+NXxLN^@()_)rULnwdxaIp|VvM#^FBTQJ9F$g!@qV|7wZ+X$!K?^+yLGxud zY8&8ROl1!2TkXH*9kROxW#@ut*`wQ|Rx>UuX)+pnW1QB?2=G zOP_&S!q920$m@GyraXV`;x4KkcDawVxehF==rGPOcNbWtD!$BG?-lxx|ky~4T>Gt_I9M}beRTJjS zgNr04z(F6~!K#?+5N)?T-q~gkMP=PpOTF<=k;rQXAIOl^6ZU4f11U-{R}ERIsI(ac zhta6VL$Bc%a&^eGR}63_2)ZnghLUwnyd)Wad=c%o=%)PL^%2$Pg)@ zA6y~~%Y=9_Q0}cprZ=K<+GO4{idBsYaj@J?aGI`yX9|!e_JynXQloS+TZl<$RCqHL zzwd>6iO^|`!jt@@ybW8RRSsMt{7EU8e6e4zAy&T z%9-Jheo1jcd6qzC#ys1k6GgEV^X-u-(|1vd2*Qn8*|`0_6# zJs*{;lsM?nL40Wr51l>(&jV2$Y(%~2~JFHmF*O47p7*;KXpIIy)q z=B-A1sUxz3p)*CEHiPQyT$-6L%MXyP)8|?RKltg!y~Kf6yO&K5dig$YNxSI}+rVr#xUhKkHoUC)@2X9MtbaN&Zb zoJ<`+$2uVUxIbC{7gn^9>D zadyL!gc)?Mk9_4IJbh4dtU!jN%CdB56ZL%TxFV(q(_se7W)!Z!|2U=*}aDw$Po2IU+o!gm_(8xO~fh~0TFoP>`&E2JNt%k0!LwhHbMFH2|6K^@TCZ^)O8lV0D` z4c(oc4{wHw>X2c4-1g5$`=Ahd6nqlA(|hC#gDFhOjWS@6nWtEU8tNCS32; zh^FTwq75-vks_Hd%^XK3%)rwi^tniE*4Vyvd=Bje$}<~LdaYt3taNM9l7w(YPJsMR zhOE^9`Nw6YxlrsfqsYB2=kntj$~b33%)Nm{>u$?erbv^0Iwb86Z!_qM~M=Br{-Z^N}%5h3gq&ONQj7K60B6Dw|pe z-d=3{I*tQrjpM_gpFaz;kMo>V5b1>(RN2;W&AA#8mtW|acYg`^n5C59pUP?ZaI-;p zZo?AJOpi;&4epGb3!pPfVEO{&T1MgTN%XU!!BAmgtJxEO7ey$a|I8U)k#y>);hW0$ z&m(aEb5plZBWf1I5*g6y*c>`Ts2Fc8ODRf86e{9fQL(<{bGN0-nKHIo$_|%*Hh8%q z^lb!d4bv}r$rnt4P)0~BE*Ul2&Vg?Ed{I7twSZ>)9KQFSA$A6^w#QlPPWTGV)t)r> z@$!&dqzUUHG}H+9ZEzFXOk+J;}*ELG~*;@dNJzs{1J_Q6aA zIt$$y3uPpeD)R=oaS?59fW+Hg=8!LT;2|Jn+?y(KU?W`s_(`&qu9SEy+qHbe8qunz zzoZT`b7F@+m?K-}!bqLJ6Tul2vu0p@1CkT%uvF>Eyt9(JvJZg(yx=Fyt2;GlqqOyp z`1pfH7Y4#5A2yi?b5TOSV3}h>L)mJHH(zSd3UgsdY57tJW<7iiUbhj!q)IMXd|379 zq&{=Pg=%|cP<+7&dFojDKTb#{fAZdINzKLdqf;;|_VXOkx)mm=%t83810Rn+NDq3D z8l;3L{AORd-oR4F?hkE$NmoU$c=!6l$*J^@_Zlr576Q4GbyG0RkM|d*PHTCo zuZeBx;mwABJ zGzXyE6etl2*fRiDwA`8rh@I%&EC8=L0ORuzjoE7fpLsk0MTG_SNr~n_PtVX+6Ss;O!HIE!rL`o+F4;9IJKkp4VhHd~Uw zcqDdvzn^aP&+oP8&g@xs*dp+zIPd3{yhkUQu~$;Hm)62ljDk+O)y<3k)l6p-yvAjL z-SE7h?C`xOH%m?#^G^qEgBdl7$+||f_y#j(gW{2x)hHGmK4!6dQ?7t-_zmyL>9}A*^QW=}nGXmt2EQ8ZU@8y&{2s7i2+l zIqdqcZ%t|#MJe?ax${=r$K!v{^To@4 zeUu6FbjpZ+xT@fU{g&PHW>5SJBOl*%Su8y<&r>D2_y=(~rx8Fq0MS?0XMIe0bTa1h zr?NYGv!|-g92S4(zhBEI`-)J36>m}oQHiZ7@eKKjK7|)Zwo$=7*@ZQhXba}X4Ns?! z2W}*Lzg)6oV=>n3^?w3HqlkJ&%(_;ze@3!bFplZYrm#em_&G$-MC*gNRejD$ zI3Jb|&KiUnG5`ZM4beE%bJ=AN?<9sPrGKuYum!Tv>jish`f&of8}K~!Wp%~D10Ns4 zQAbx#n3GnmA+it`;$_>uVum@+{(pb1TE_rx?g8IlYE+#zR>Q0+5ROdG_%G=v@Ml(? zJ=H?yyYWvO_{|J9tzJq2@Za8gOu&Cf`_-0q0gS@LhKyJVYJX>qJ@ z-uwS@FIU`5xd97b@ZEXCNv9cD5cSVq7Tj%S>n88-=1N;Vx?@V^=9p(<%C83TC0n;X zn2QQ-G(Efd@UC?uV)KSMNY8d*N@nZ`GZ?JC9bcV4*EHHwX6BpMOs(5kSZv^B8x^bU zkO$j`@H^GwjwEt9e%s*8XGG{;bN}3N-eQ~HFjL>8PN7@JD5(;kA*;2jtS6Q0uRQy$ zyF-3QW^FhUUL*}87YAr(f$O8_5{uQVdn-6Gtow~gcPd@demK8qPJMPc9Mm#r9hc-`{t`6I=SG z??l*s*NmSYsednt{Qm&#;KlWiFJ}Dmni{(L`~4NDxynknP0esqG0Th4TZqoe>0vPp zzP^MS4=Q|Q6#GT7mO^ANjk=BdTnr2s&C#%ZrLFjlcd&at-^LaAJ z_ONg)*M4uS9@3|2xUM|#_qRIJ@`XQVtSc7&42lA1xk8)Du++v*`!rd_T`QhI#lhIh zLZt3P>EaGUE4c=Wflf^KlLL57aagc;8tX2^TvJEgUcWHZ38#4+(=9AxhOL zlAjcW&eB=_+mx-K`_CD)Xe=HI>M+Qw0h%Qj>-fRj;*A ztE%$KjW$>ZIk8!dpakpKAs$QGpklcNaoJpa>fvdvX+NLbCbS!o!v_G*x!Z?h`ML!qOhqYp~z5r(nE zY#uqF;X04uxOENE;I(4kJyVxpLhx;;g|sfh!r&`%{JPt~iiE{Zw>%y%^`Cs2u=Q2- zN?Le4DL(Z;oNb|5xQLMXq?W}&S{xQgFcy1G)p)+lxcR$95H9O`k#_k$-R5=cX9eG0 zvoybxff<|Y4?*C4^p3*p5}G>oUe->l%?%~OPF6B|(@}GKWmr(PnEjyJPvN!z zzJ;-7;U5hKJt!`+w!#aL#sn1uzddX)8@u

sT0r>7(Z_3M;^v73t+LShBy(C0e*$ z30o|3wbHXNF00w3romj9Aoa^o%rgI(&Xx_Y-=F*YPiC;mA)CsWFPboXT{lfz756Av z!u)LiRqoa(E_NvBFp)Cj2)VVW*Z{cUQ>c-tJ-alt_k^)ETjqXVqsTtrK~2|%vP2ap zL))OB96!jd>NAF(Fh;pJC~;jRz%tuLOpY=&OVN*{^z>S@rz(}Fj~JhsyMb_*Iv3`R z)R0mVModR}Xi|U`H>J0h`jm$@-BnAB3K%h&V#~-o8WD`D2=o{Wm;tr6a~ z)d*Fs=EdWw9X|nSp+i=8Pz77n-a-{?&%dwgK@$lM}(puL`Cb8v1w43^p|4gcq`Jn&!q`{P`~%|sNV>$BwMg}{~?AXtc6;()C6vN zQ3-dwm|eWGO=BqMb@|*_UXTqsS=ZQtu+E=@q4D{+!=(iM!S0X7oaPuKu3B zhUcjHJ66H<74>o1nd#|z)SdgRn#Er*(-SKp~T=qpkut{3e=k^BA%Cm zW40@O|0HMS`Yx=XfkG^Hp&EP0T55i{C(Z!WV&QPugs3nEfMK}QB18f$5!2QszQ}sf zC#3d!Qxd!LTA;ZG+W-25`EWLsEuuxqU|5eN!*i;xMKheo_j6W+Pf6ETS}`$;1khqq zd@!mZ`J{0t03XT^VzqvjXEoNEtqCt8`c2Q_*CYf{FAaA2v^18v0K=pqhM1|MQ8+at zhR%H0)ufy9%mk^v{zRzzYqrdEoKF}8Q69EDVq_y=^b#s1LVMbm59ATnFGBhZ?S7x|HZ~aw4<;du*3ffgq@BT>!94uA z88)f8Q{vVzV=7^X`c?ag&C&q0xzB2qf#Zke`)>>+C5{j1i5OiO&3MzDp655Xe2iaN z`?RIS(;&e-&6dr176%@rxAD*`pY3?swaDx8{tFW+3tkRhYu}0=N1Hy+^$P!^3u8}B zo4cE7XnZC(Y`_FQfg(<(umeu!nNwAO&+Dmm6N^MAd<5mhGfR%~VICG?!2%yPo_4Kc zf#2|L7;4D0oX=6Ib}gIo2ecn{hYvg(ekJ~kuU?xU(AoAT#6G`l)FO&yVD)xY6xgA! zWy~N{e6@7W()X-aufKo2mDp>sG+su`Z&ZW?gIC>o-Pm?F1-D?dD&#G8X}h}Yb=j!l z_zaVJnSJN|35mH}E%Q7!4UHir;|B*r-I0ll;{Y9awI$F}ZU|(V_KZ(?XQrKe-l>LWy zUth;KQjU1~*YsBdgA-;)%5x>lYD+BJSXJ|<5q>Sg(x2LY4c5}bSd8CAzTioWT@f3n z6&7#xXrjqmyXKpGF3PNd-(oG+FdN;(ACg9u+PChfJ^v71ot>*0(Cr!}NU93q7+nO>bT# zGE6Tmt)j~~Udj%aA+9k4t*>HIeyAvaR9Bi5k;~Wgel9ATkp_q~8_Z!-GB}nYUega2 z_Z3oW)Oyg3dxBy2h46pPAaNVqJt)>*HBHR!9xDkestJ?XEE`veG#qe8YgyMJ7E&0# z-C2zotA&*mwLIsH14Y+pqI@;^Hmqp(jA=q#&GaCQL4hlPBTrAx-@dE6SUT|B3wRXF79I%h+XZabfLtZ4>x5X z*!f~I5x*2ka&2Ai2`zD-M_4t9-TD3QizK98bJ951y#`K&1iMHvbzE!3gV_qz2E7tD z#~|+)68G@E;UgpT?0bw1&VoqsTNv!=97oIX(sS%g-tk$4PtaI1)UXF|OzejKdJxaU zvpwqk%V3-&Zhbyr+88vr*@7h04&EP~-^k(RXpIs&oclme*A#c1)+|6v2el_XA35-) z4i3jzZ6c>tHvU++O?-!Su#GAI6|nCaMJM5{gKRz6k{n4$JJlv#GY=4ZmT>Sz9H%xB z6yx5QX}hU11o!qf?y~CHdFJ_Iv5~WQ^MP2yiYlXN&694iQE=78yDw5lU~U41Emdnn zgxpLeti1r{orrT& ztYHPeL(E|Q{;klTQmegzC)RnsaCT-{kc8kKM z8!-RM!a9F<$!r>mrteJEkdrftibQ4e7O6kxFWWj>YhD$!Xrd$A>U80UQio$n$ZrX# zdU~Z&bfyo7V}e8-R;cZ@Fqu7zc38AfW_6wSlFVMHL6s zrIn({stB?g#Ek*a*KymO*a&}-#@ zJ#JQwYgB_m;DGDkvuX7~lg(tAD5*@n<;gf<+`i0Kc4*goO2vD^EP&J5m$^Hl<_7Gm z;hXomr&dQf5R}N)W;N9LrApe23pluseD+Y6L(o|@VO&&Jrf%o~IBF5O8LU45;*@Gq z!e*Qr`0GCRh{@&}wBtkm`+Z*`PgMffYM}6{sNw~Pjoe(l>;0Bu2W`EYlV`2EtR{>B z+fW}!GId13=7UjZ%0kapx2x|!oL|v#rxdUx@6^rqv@<(ToxT6|ydlS7jGNwWLh+G$ z#d7>S7Mo6s*$H9>gegx9*%XN_oi(mA9Q8VJlUvmMbcHPs#wvnS`pyY6o$q+9xnTIN zSv*qsRFQK+EjIxHb@jAJgAfAv=?Ck~#ng$yTRSz|eA=c+(p)w^{sa>rwL6r|07w2(fj|I2s-KX}h86`k^swNc z;>q~@mt&x4vZgz+zgn|UWL*^}^Wm}!5M?FjU%%+;z4g%Ha08mHc3QD`&tVW#1!BjL zoMwP1>Wpsa3?BkwAu%N$N$v!Bf{&z$&i1NKN;7hC_bXyIF$h4t4-E-%mPL=NDQ2bN z0Vr~}jN4j5AIKz(AwvSr;Nq7M27!j>;F*FD@}Qd3-ARrOiE);Zu*{EtzzF-0d#nH2!Z@YqP13rh54N(FW5Zc7BjUMUZVX#MvTzBefopQno0_ zbxdM8(8w;4csIa1O-%KOh}+RH$T(grNWZhl&7kAOorsr_lNt71ibdblM(r$yu8Lu` zB7a@YwN(!=SWdD-cTqsbJE}V0B0P60anMTg1{7H{DCViAadC$D-t(|du`#-w1*d$} z4Qt$%-Fj1fhg18uGwkV9?asNGmx;9^J_q~a25ZY$?JBW)OJrGo0VZlyc_9)}_(;*c z+Rfod#{I1#^t32#1>m$o6_Y#5#*Ktx2;)=V@OPfKz#T7#rd7ebwE&kFixN$ zojKbFa;xy~RVR?PZDJhp(!{a(H3OH(JkYKU7Cs1Ky7Ak;Z$6mw{w zeB zcpTeCQP^BPh;9DFh<$E44tFGKEN8Xz+r*q9k?)<06^@-qKD1mYQm*5A@H7+yXznV) zOkX6cp#$meWpWm_8D!)WDo)AfZ^=4@#Xn}(W3OFZv!A)v!$9EYcK);4U5#+A61Puj zT}2(PYOSlY)Jv^pLIAO|lzm>~UIKT9bYo|@Gd9S$V&i$YD8~W#g4hlhoyIaBVT%L_ zp-qCI>)HocP?}dJ#IAXEzH%t%-)?S{pUNS)egc zX(87b8~KUCmpFY(TA)-y$JpT(t^6U}*5@{{P2<*}p#*51(>Wf&L9V~V@cXS!40vfd zVB0En;k7!2F96Shb}9+yrVBQdL-lkb}a*I=> zn6N6vZcJ++fMryxZGhF*jUDrw{=3QkN zIgwLo=7#FQX-anNlhU!3| z3k|1SIAIp%-0W9+XN7MsjGD`p+!sSCJr#>@?F+{I?RjhewrUftu?yp*5NQ?kebTkK{V#2R-XG8Kr7nsBo52YMU(fs1gA@*xGV0 z4I*)KOm^Xi3#rRafBa@TF%WEJMZ$p#({pOK2_`p}2o!)%MjOlFpZ_EW8SyE>eFgs1H|P@ zJiG6qyso+mL6utlHUlQk>h~@A?c=G1$YXB-=Uo`pmAS#aAc$3>KX0*#ZMTxC>aYel z*0M@B-S2rdJEJaXyyph`=qiL=5$!Er>(@5wH^X%YI_z8|O_id@N4Z8Yu}|MB_qLud znFzlE1UNhLBf{7t;iFG!Oc$xUh3&Ud$Eb~bel4`iIl41%&k>ijH6yi2b;OtS4NrRv ztu}{;mly}+cNVdN6p=@~v)>L}-@j?u@jx-!(636cyl&z4gyMZ85zv^fB3A5Po%+Oa z$pP?;)z-5I9Yfj@_F12fFm_8qU$`E9d#{miN}DPprrLFdOGf4^_d7)q7Xf(lBf|it zFtMYMX1Aiv6BV#~?$3YwXBjyu_YS&kdYZoKOM4W72sTQ`AD9Q%PMN_FZ^=d0_S~1^ zWIpuPw@A(82G7}kJNksmMHGtQ$TT>GIK)C|Jh9XZlZ^Ln82F(es*K9!tFCW;dT!F- z&d$}|*rAIwU#l29EQvg{{kTt}I@~^($}ET%%5vXZzcs(!K??)fTJk61=zN2L9P6c? zSc`Z*dHa-aq2=zMwdq$#z7u^Nl;12n5!TPXKUm*dP)D+LFJ|qhMtE@0rnySsNZ9Ma zw}edF={NgmuETGus7ZX-{^Uvx%G^u%+}7Bu#UYfMhQA(s2-oG-Kn<#baSw6VxxGD{ z-1QuOFw-^rox!TkTG)}$$nHd|NHhbsKfzXg``}iS>-9%gwuGNDwa-+Gi*UQ#l1nlM z8CT}0f?ccLRj))2E0B6EYK7dA0Uz0ywXUCuX0)}2F2=S#Pm)CC9s#EFnuofuTJzUsLIZ?<|6wm6~lIvShZ z`F!N?!u1*yRP6siYitTQ|je1xlL0D2A)Cl?8)ulti>8enpYIwi(5 zU+JJ>=`(5(MTB4(OcSST_qrwcj$qwE#)j#C%h)4X8qc|9*B)!ArQla*43bK5?<*6b z1n+dP$4t$#>`ygL3%%XRVdCqLqUL|f(k)^zffviiWhMo-(({&A&s;k8lNuKAIhd5+ zom^!_Kh#OlPpQv75!TYUF@^K=y`pqwtL6>dI6U8GaRQaT{YYlZaB$65Bs33A?~UD% z&%xS*r!qaP5?{>>0{e1{Vv0J@M{Vc2{kqH@A@r*@WYEu?e-dRjN;I4OLfaLZfWn?@Ss3DC<Bb^9wv=6%K&L$~vT(g(FL!OYUx3pfS?;cynisDHG0V7C% zhayv4_a6#=ZyZwtuRgt0-zlo@?PC>h>DkCDbAl)Jwt9P*S1s6+DY30Rp8bcSwqD$S zbTW67e=X0eyXO9m?=_niRf@5HrcZmE^VLplykqWfCiX(as}UtSESqW&h`+$G!1kfX zg2S;CtQx})vcxthJVxEL@Ed)o`Su>(wLE(~Sa*12@SRr}oAjZk&gUtpB3!%|MCw%g z!hNO?65X6(&ZhrHiHu1y2kccVjy! z$EXT#2x-_&wIb%RQ8&xf7h~r7B&=pY=3pQpSyO{IKL0K;Dj6m%?9(t>Kq}ZPc=$=qd1N8m2g@Ev?wm!IvfP)eD zYAB}~9XRQ*mO+%3@u%XIn*eqxOUFqUgQ$r=B2rfO6lDNJxmDz0m+?9X6MpE2H=bSH zF$tsa8|8tsK#RZH#&!#c@+5L@#Rw)X_b?HL4Z6$ccXlwmLUd+2K4zaGTB5Hj z^sypiOin!IWF`B+k!t?&clBY%i-e^+yBAn2HwC<}H%Va@FHkg*h9<6iiE#dXT>ct% zW>(fWTtdZYp0k9M{D+8X>G5T2UU+YReBY5b4cunIP2Y*aY~O0i-`_p-^2t}n_>RLX zuBNKsqwCU$eg!(ihdM|A;M`8&BTTyi^a8<0a;{3MH?G6@hXPp*_0^xZ^7 zXK4trQ#tz0>bKEGW278FU#SB|{CPgaP*ybwK1u=BS)u9A8SSmRy||LxhrlbFuDM7oN85;t}stop{3Q9owiaV{m> zhh4#*^#1*RdHD`ul<)Tt(c+JZpLWdm5&yWlO^auk{q^e8v43y<`}>nPFlEk0sk^_g zc*`~afkSFvD}y>~!Ep=#4`aXruMtpCBh1l*l3}WJ0oQ!TwAh0B&TqgQZcG=!UWmc` z_W#QA%~$~s-gNoSyCtpXfavA>?*zOPgWID=$;{dZ>!b}#(a&k=FXyG+YIT2eor)Uq zSoThc<>xH|{VQBDb#HSIjAE4!2P7;8lcoO+7F6*Gxqn%3JAMd~0r|nhCJv!VqO~(i zZ4EAVoc)Mlenbnn!>&^!W2HLm6vn?q=i~Z`UAA^?60?|$J}^DPF4pB%tWB1To~I7$ zJxH?R4yQ}j+7iDCBszE$X44ereq)D_hq>T{{pW$wCkwMnG>6^_>`w-Z)`8kq>RtT9 zq$KEa_2Tq8?(l4dE%yAYALNbWB&z}6?K`689D-}#%MiJq}D7`*hb^1jEe4_;=&bB_h1Djwk7%?Hd%8=R-%b)TqumA=R7 zU_l+U9;q)GruSi(+kDnE=Qk`~8*n zWtSbYtSH+?9QIzeQ+=Utfm5$uo~~T%n4RQw>$1}%$?5K8=lfr5bC&nyWuYTr^oxM; zUM8xBW4eb4;iI@Q751r$C`+Vus<2}^yh;R32wh_y8Xr|dC@m^83-*U>%39z)@5=Xz zuKT@jXVUc+*w&dJh}bet^CBj10Vk>C!od1ZUaRj9l!;E}c36fXghUbI?FJ%z>`7&Z zx7Q}m5el4{_^Wr+*A|m+(O4gane+Vf_D^q}M~M#62rUq#ZuxR4KUx~Fdc$e6LZT4i zg$1#H>ioI^qK%992r$4$_$I|*`>Z{S5X5f2t=obH%c*u6#|yJ+iWL)%=8)U>TzGIf z@b}k1m{GxYTt;?A65Uz>rp_# z9Z&ZR&Wbu=z*0}O=r^4Y=LUIW9f2=sB6ZJi_EIo6s3CHaY+Lvf4j_u(v6gR9(Nk*; zn3Nk#3VE7JkC^lO-Q|Jr%p*?+wgV@Hli)cm@JU@)mK9AW-NY@7DY zHm(BY$%J=FV9|WNjiCL1`$0F)7|*RSzE@)cAA;NFqYl)X^K02l=A-ghMrxK(4UC&O z9CuYi$YYuF6OB^0>gB6@qUVQXWuaDprdqY}Y8IN`9A6suZ}K3e=#RQOj&5kC9@+vwwhN$^n+5a61mJ{C|I71MUD5{JHook;MpKXC^*UjrfLuCp^mEvtTP@lfQ5>@YJU*ilB9b!Y!}( zM4pPA8&qo(7GYe7a4z-C9kyttCBKPGzJ@8FC!#L`I9ZN;+Gk}emAHGv@nFuJAXJ?g*W>WMQtCw|uV69<00 zVCi23=vMq4SAXoZTd?ZpioA?mOI|JfAfU4 z#VZ#qzVj{j%lxy-3{T}**rp!VvJNk&e^2`L3~&*?s#F}DiP)$^ShQH~cg)O1pvtUY z@c8_9)o1||aU|Ejrym;(aU~)`RAK(ahU};1tM4)yKN2kiyn@EJofB;P%TW~k=tHpU z6I*T0p^e#uwcKH$$iDcXzO}^u$QQ?IqwQfR!lgmOyEEJSeM+AU(n-y8n=dS%hr2mB2(6sdo-vE5EdSS83L&_uJfOI7WGnC%X&+$hH0T2K`-3{ca{gaK}q{ z#UpADk!X|fYQESzA~4>2$(!omR>x` z$ke*3_ge!~C*|3Q#gu87fcZRLi5^lTQb8m`P5SAO_~w+~BIewU{W9;;Y*a{pACp$&RDSfHdDZ$zx(>lZ+JI=^>Wbr!ucJ0WR;CRqLWV>S&$ajA*FROG>lv*t0dz!Xaf0^R zvxpB7DvSau6j!yZQDN9HY$U&VJ7~>uz*mH0tLMm8UnJ>lHvnm72y!yz05gkx`t%~v&$e$~ zyJmn=roRld_`os$0^4!owB@NyFUe~bn0n6H%{u~Z|LH&F(_BGxmI_%iY}lB%Bq0$u zz$Cr^34W1i5ul%th_}!fPU8*zShNiyJoz`}g$nyeM>4q8k;6opuq;A{NqxhHKNF1T z_b3~ONePnI#KeI$fIg3-@q_6Nf<^;6OziK=gTn?p_?RR$s*7p#n%}paLn`4BLLoqw z)%Hh(=V=(WP)KOl5dEt14`9enM6Tl)d8n|wVOmWTxiU@eC&MdFuoR9S%Wb)j?%m-?Vma^~r+BEsA;9VyW zwk-V_UGeh|kFJT#;crca8iq)`1U*b%BGS)HCQ>a;s)kKk#T3Ub#30kcuatz%iyD(Jv;WzF#^;Ak(ZfhS zlXyOn%;p%o)>iBqruF`9_UI@oXPCwYUccG>$IY;3{MGBiw<#kxo!Ybn0FJMm$J;YQ zyHX!vXul5qc@-8F!Ijf+5i*8bU1%xZKXVrAUf;dXX31fL&G2J?@1C2zo^aRwRPP~= zv=>$HEC0FfpJ(=bJ70%2#!|~fZhW8tW>7oj%mha@g_tlRk-;=1TDgbb7|Y&*m01V# z4_Bf%Kg#N?nG+STM0J^YYxwetH$B!%Pp#c?k*J;qPz-ihHy4y)QFttcY(BRWRP@Fg zc$8qTC!I359LYgD+wY+-x9{9W75D8J!^&Ff{`xi!?}k=MlJj4~q)D7;YbMt^i2y?x z*OzL45Dj}?E;{J)`}FQ69ke(DmL!r)2P1V$ ztgVIG`%dP)0D{QO`9g5i|6e52I1a6D(6~4DZ2`yPJ;h`hycdEhG_wT7|_P!HGRncRLK->V+sh6Pt>@@Q|v?y++~5 z9v$wl&o>bbFsy#Xf`ablp|q7g*1fI;RsCHil;Y)bMq2lB`8LMBda9lqv+3hvhyqA& zGL73OiEzG!e4P6r;@!hVH!8A&&8Q3zyxJ`14$>-MTf5ECjNxt}G&DdXkt*oafbbic zsqAWsNz#wk`wpAGkKQ|wTJj|2FwL??2-n|Xma7H01tNph>GHI&<=Ie11_3KUX=%e3 zbAmM&m{+#@c%fv_plcK{}15zz4N(MtJZnz zWa(fX)H-16q=?TXB*{{dO4b4SAomWfQfU!FJ{BP%i!dbj)W{8nUH7*8e!ZWs#}n8nUS`8os<_RGM|WQs&}`7d0w97t+>=l<_HuC6&%uuD zb9d&?Sib(z+KUHqp=rKzEOvSN5;nc6--s@+BCzKNUJ&1<1}o~+GGg(T&vTuJlg?Gj zyjH;-6q~c$$iR<7aiu<{pOk3&L#CgjOnT}b)%J`?R*v(5^&KA1+MIdB<_zNQ_LACtgfXY-ql!-&AuZ#EbRxg6>3k~m;<>gN2o`B&k9XQ)jhAu|7 zPJ9CNep-Uc zb*Qm})dQBV;iX!s6Oe;UcEy^EaEm3p7>h!^BC=3|cktOmT~`{;@x(0c%cSKu;yU+f zA{=7HNV>?J!G%--9_1bOwCepWeAqO|ug~-qd=Ae-t?)P(ZWk|;-v9E-U!=LUW?Teq zb1hE67+|zqR5OilKs$0}whz^EIgyoO$3t1&&@hKEt2mj~l-qnY6jbA6o-PEt9E{ep zes=qN*jj-zMRGhH2J$B$v%fz__{Oyard$eNLpS${y{t8f;-WCLA;QR@mast|75r_o zpSEROwq_df@U*Oz)5k^gLfknhlUT0IwN@3HD$|m4_{9z|pPUcqOkNp|S(R2{Qztse z-A091tb`P85SYN<(d@Q2)O9KyqljN@U-2(Cz7VN@HOd?^BnKA~IvkOOdh2l!K2z9X zqWN(rLuVjm7Rqco*`smbN`*9mj^)FDxjU$tBUx1 zr0G|ajsDY#bz6pIZ|mk1T;uzEou5iwu`rjv_~)&vtxL|E$De<4ZBo;>zB%td#|D?k z6QZ>Z3yn~uwXaULyh3ODM2ut931}{!&h~10lx;u{dbK*!^b!Xhl-Gh|gb8e~3`AOc z`tB@tVPT&n$bsO)kL;Q@oWFiI<*Z0|YQ>*C$9;_ghb=5AJ`_MHh4X}QvOcZal_3nB z!>r`Ximah2n1Qq|X87JL`&X+rGIxMHek)eLfPg_p%Nb&Mm)-{*l^|u#6hr7bktn;~ z5_5OG{8Cy)Vth@5Sw~2TUn#r2o)@-}tvq+P0_PLi621{R6gNS-yhfe+5^&jl6%xa$ zw3{P%6pRUEYJqe?;u^d9=Ae-bl@E-H?uX`o~O0{;!HuNlXK)%vLUV~X>mka)} zZ&hL4xdPH~ywn_4VV~U0q#O=LTN(T@?wXeBRJF|E1s@**pP(iggDrtpEPAbkhDl^K z9#i$YA*Tj^V2R`tj7@f}t~xo01hSF+R@J@Q&2>`SRwUv)(Bd~&C`Eiy%$pdkd?Zva zL485CSw53TM5U$?`{qvLfd>|H(WmE^-umpfV&`fY-Fn+_T|C2gf_w1I(LT|A)dp>K zD*S4??99oT0bdib#WNd&&)-kGn#6ziDBh|;)HHfy*Wy{XkQZ57l)QWD@8Faaa^jySz|vRxMT>huI$%7lzYR7BLokSPmICBeJiu#7_pS@{WB&OdDWkdEi{`)a<&CSdIF_sj zY|RA;0lKv#h09SD0w0d*C3v=z0sI}uM z@RJjN9h4AX#jXwxucxFC1VkPEFQ10lcLJE_s9)MrD?R}F8?WyY6X|G&j3LY=w=j!% z{ez%%o4DB8d$lVjQbYD;;AJzvE}r+~ve{7x|H9huXK-P0$_?Q6@V5Ka*Rxkw?JNSu zw)rYib;q{-dA)7H`XB@u&GUs`eNS~~;nGE@L`3lm&-@n+y}O8sIflzqqhqFL`=>3w ztB|@kN*}-GY;@(H*ll`6YMQK~xB3#&h1fhbZV3yoIg6o6JgVbxMGz)SkCSn!SuETZ zJuW!jY|$i)LGdwaIzWIie{kZZJ&Eq%GHl?++jmVylz5&97m|6Q#TZ8@fi#gA!GqJAQ0c2 zhAH9Wyf#J%h6qTJ1%_@{k%B26Dwvmx*o*)riuuNu$>NIUfw;xrfjRfRjt@m#>$lAY zQIcGng&%<^p>HrAcM^#F_o#2W%leoWU;`cL8lerbOn$0pyC9R>^($8pyw<;7X|Dq3 za!FZqR5_QJ&P`2qp6PKO?V=|(tH3;`z)>T$656p%yfuW6brsI{5}}q%@-c}@a*7c> zpd#C-(QmZqf={S}Ec`UMC_w4#4dY%z)H6cDC=};mu{vIe2~eVo=~NdzT6G+4j6kW4 zc!ebn`zF{;PZ;H5n_=28mz5%n?YMxhRT6=(e=if#9*RlHmQ;lr+bD{=#KqYx#kz{o z?f^ExNEj7j0nAro~Ay{7dcmSj= zz?Rd|`&a?5>sJ?>QxODl5GZSZL^vx89W>&dx#SmIawXRVF>VL+#JzNrhX7`YFL;@Y zJ4k0&4To&wVh8oqW-f}SL`j9TGYGY+rsjMiKSJ(Djnn}c*Qckxq_cASPL!6B)`|D` z2?>K%2;u7L%ta083H~bbVG^-Uh1`X>DIoAd2M!@fv&F|h2nmfUiZej`sH7~TBY%gu z%t(ExJ~^n~y5-oecPv7&3c+D+kc#-Ib4J3TkPtR0q>Zr% z8ZHgtV1-?%gLD%Z#*IVN<6OsnF3wzss#Q{M{v;#DYc}1aPmSI6nb3&PzDC^kKB5H~ zBaB3y76&flk{`lEzObp%ND4hcUY$prvYAvVY*}U`KZHmNjnqeaLO1KAyQmX{k5!VM(J8PsV|vABon=`4@`3`Je3pgNdG7Qnv%h!wl|;`r=@W$k zF^(d96PV07Vw2?0m_&)zq%f?}c8XGa2X}31K2tcYfWx^WXTLNs1mkeJ7rUJA&AmD$;2^No^plgwf!$i$6T|=JWb3 z*7jSi?T@CTKE5d?dPe+GQ4awGDhtppT5i6|b_Lx!R}~Wj+WI*IGw3VQjM!)aZfgW{ z8OAS1j6+I$WNN%vh>PU{CpQxuRx!%!eP$~grqG!k?@H-v?g|m+&Ea;Un?-GWzKo4o zP#;+;0#?xR_0{(#R^n|h*yKXCpXM_1F)=3Um`Jr|PqaGRw%TJLNhL9rQB*I5~8VLh>G=fM!;-bV(=!XBAjy*YXB%oRf z(Hj0E$ucO9DSV*T<(NXF>ylrsLo`tL>I+Qc)uue#;GU6+_v_U@l zxQKe!KeNw#{!>Jo77;prpf5ZN+W6Kvd@(zbkNR~TY@}1?eImURBR|B~TYAdc&~KY? zAH<>l^lHAIc!%_?PfxJrJIydsi;cMZ250IgLW%*!gTVpei{o6{ULj%RKU}f$$xBtp zOA$dKVmDOw30-v>CFL56b_Swl>#5FM{0r8|-N}WN?w3dr3c>d|f%W_Z--v%GrdmM@ zy~M<{-=y43!oM2or~1>|)a)NK$OSh8G)B@(eV@0EdR9#nKPM1A?U3?kOq)qQqXz#C zy|eYh>y4<3-z)n6yNNbAeP{H`9mR(`#W}HamBd$klW(jy-}ol4xWu{Kv3<>N4%~h- zc`DX!?WLXe=KmQfezMEc;mhsm_u>o6A|(u)N5BFlzJ)z)BcFi*tQ`T--1{p8D*R?O z;i!efWCTds1+qtu+@X;LB)fc-TbQ}W6yLka67Sq2U&S{9To74v~Rj7i__J#KuaVc|TAhD#y@~ZX_Nr{i+ z;&R#RkJnr~++vZ&B_0K)_v=guTQ1dX-59Axt{+UEnh>f#=Kh$_3pXlMWTvv)&xjo` zl9vfXFT=PhBhJ}~y9Q9gE6zHLiI)HjlKJtzJIrMLHO0``XT&MF*jgh>cplpapK}%w zE^)D8XK&ei1U(XyR7c3mfX}b19ry;MsTP&L@?^miwa>rL_X5Oej`Qoo|MljhD}R%+ zMHD1NmsU<%bC@iBaw`lX-g|`HHKVqyii7E+eK2q42fU{WHPwiUde>a*T(RJGPbwF? z_NFs;TW_#xw9EKu*(6L{p(6KjaSB{~FZXn<^4S_xQ!lsW5kN^bqAvqP-l4C;bf8c9 zWEn*67JsdUQSpYCew&F4b`bl-#MW8Z50%7a5HV!(Yq1{nCI!7rL=71w_o=YArxFxg z9QO>ColSToq99}Q7i#JXC1twF=lL&KQt^M&o)b1rbE)N{N9LTo_2c!AS$8D=01PTU zy0C#0r)O17-?F_`;(O$lg+u7}h??krLswaHeEN|ox9$8le>r=pN!mXWQ{%p<71O4X2%g;>i-Z___jTrGi(0?WWQ7gn=&}Co%`^r1s-WveBZd6yMQ=`KOYJzxZZ<@r|`BgDHAfK&ZI)c zwVmi7G8`-FSm-i}H9BnvU(6txI-$^(b@XzS7luK%WODN`o#})$p=W})_T~`Y+A>t_ zhYPC=g+6UDkOl}&T$7m^+z_GD^!1W6iFCHpUz`xu2iA)}kI%inbEp?09-Fp8vo%Q4 zy!y;N$4h`|@Xh0Ytq7MBZ2aT({1@^HyXU;~!v&l*yoa>Ww4 zS+XbvV_77U$Q_GVDe~Dh^+O6f(ZCRv6fLU9*oO_U6-WV#L29`nBSmhWG?|^EvrJ~C zM6+WG>*cm0h+SeA;es?hr9&y?_&tT}*{o<7DyGL}49z9Y5s6D|y_woB_O{O45|j1O z_i*L~{+L~k$zmQishy`nxXq<6@%;&Q{j(PIeX5481J%fKpAeHEv`n! zNdD7j`&1!tpnFP2J#}iFhL5%{@~oG$6Ey<7&o&pZbV-H#NGyG=It6b(a|?(zn?InH z(+F*Qw$Fk}1vs0}4>qnS`t|ku3J7gkD3X!`CPeb@lcPf<;TcYt43n_Go{_-v%}~S~ zGsRh^xSd#O>eH+|LhuMEYCrbS4C*hXpzJ(BH}M!VItT=Coe`irWLJ#NFU5?@;bn;KMqlN6-)parM zjW4bmR(pT)>BUV*1vtYLnZr#0hiRy$tOBMa9~JR~`1dIh6YchLQFH*`k=7I8W|qX_ z+eZtUY6_;95B6faGPOrGaEqe6TQP^2F33wE2dZ*i~`64vdUwEgz~&BC}oD|C;}?+fD#C1!LZ~^-`t8f;;V!S#c>lA?^4J>r>KkdR{FV=&tHZqi z``!p~-p_iI;4wCH2;wJLa#45eQ5e=(`2(8d$|H{V^rs)GYxhX6gbb!o$Vdp!4J=;{ zqtfP%f!O(Kxz836<+16Q>4uFZ<0_c8Lxbj-_~9Q8q=2c*bg6%{tbHrYDfH4Qi7@@2 z5W5uGKJ;MTKY1nnk*CGT{=LB|f6ucSuj!((CrqIdd87=Z?4Z9!d0z$yTWDM|5{Jh~ z$nzmSxT$ec;KRxZJ(Ln=*Sz=mZk#=j_szZ~ZFS zRAD9Y2V~|+&~llugLoe=vuXozfoc}zU+mlU{~nNN#8L#%xOi?qF%V9H_wDqcz(yrU2nc2-UPQI>oC z2FyKKXXuGyFPmW)mokRIMK@4b(Y$1C!aCXC5Ro<^AWv*>*x7*TVGzzLt1e3}eY%K# zFbtPfZW;MC=Xd+&MQ3+~yvnWG`a9KTt1p%&W6q6JS8RZFWPE>=ZJeRcw?b;CHY&VR z7C-^xhY44DBCWSW7_Mv+F;XL)>gz+=EO)WJrJoYiJs!)uZhc#iv6k8lO;+-(G8o9xtjrS(@&5sHNlmg>#ek`_JP1Bu~rl_2|#{ zW4y%}zGUTD5_sx){o`#QZQ*&4+%Oli10tEs7~`T4$#ln2ifrVEQb(sblq$_}TAdk;TeosRb`3=hg4(tew6#KuqH zT>kK}i$bONUE)Zlce5f;&RSk2!cVo?vE3(|ZIwA8VJB&q&pi*DOj`}QMfqT-7aTTE z?dh^*jFY_lrS{0~M|(0Imp)-<-Yg1tzCE;cEBp5z4C%)+i!*JF=7(%DA&tOy?)w#5h)?7<~5(M>F+hj&`} ztwqQGJHe5?YHBHS{h>uaG3|LdW!sNiho-U3m)3Zk(DA*`eq7@zOTCTEtka0)v7SdP ziu6%#i9?kE6KA<-Ki{n4*jjnEx@5gbo@A5?GK$TWe#AQXpX#!VvwmBTxShFNwpEXJ z9-y9CLpoQuzq09~bH;Y${`Hu!(Rt$7B%XC%&7z=0Qh%|`PmkthpwAzGw)skZCdf3V z>=EB#gohen$*@caL9=Pm<(>Pe&I6E%5WEkdL*R-tW7F@Q2)xFEOw=--0eWVD3j1uI z)B=0L%1`}35ek9#fJDeYfM-%H2s`TX05`SGT?s7&kYNeHwEH{mAo-YDh?ueCj@o8S z?C`$yc&|WywUl~aEfY=PHbhrZ>}-l`J$^Pqj9R%bOA|W=8Gr0`R6$E>i_Mgv*>;JQ zQML{NKzfQ-7!-3wB})*LQzL&xmN1!;S^Sc@BH4PlIEx7)q^7%Z#&k&X^RYCqw%E&n z$u7jOG>XZzI%%5x>QaO-<>R9PDQ1(zA-da(hhJgrUavuHQrt3FVals<9K&R56qITS zO(S1X3+4R3Uzy8Q5uslN#SWifZYDE+jl?p4u47e2cndkuH)iemButOstV3bIL`dc#Fpdf0HOB^Qv zoGp8>$u(GnDNLnXrE}!dEu0u@i(Sga=O>gD7*Q!2sdaQLDRka_f1=A6bf|?$x!Jkq zEqk|;NIKTM{8a7l2GbniRUkn&B zZ=}9gR>JOf|9X}W*Hm2PR$gkr)4uHxXknT+b-4;YI=iFN>lC1@#YeisqVedLF!-~5wiC>Evc48=$vVP?acH_#Y6ivx21RxyYcnu8Oi7Lg zCn%hgUMQa=Lx*iej&mf7pFcq%?-Lg9UYH1;atJ8@GHao1 zfe^c>ws>)EvA_Vnm@}{1{_%tCd213EsQ2I6K*0GK4~#RbPO$+R_u$ht`>p)%43E?m z?stD=wAJw{o}HTFCq#KA$S5MI18{!9FThuMp=KrZ=>nQB52M&G!#7gzl^yQ`D;ltr z@MYy8bTVCyj*h31SqEE|o`752Z}&7g!vPPN2Tb@UdNS^qiz>b8;E*VBarpFzXzJu> zeQQ6{wyVYdq-J}ImqU|J4%h0vz8{E}%bmZ|AN8;v53C(myt|T?+_r0pEI|C1Z;9 z2zfi8SbY_j8XXrk19WBISPK`M0tmq@E$YMy==kLvd0K{ia_^}_?t1J-o_qxdvpfUy z)711?lY_+sp{z{(@GVn_FV_X9;>lDK3c6HL`0Zv?|!rX(W+!%iq!%TW+HI9E%N zAR1>~bR(y5@l*qd&Qxu^wYTVW3-n;GpLfFa?I9t zPxa|Y4W56~!zlF?qJ3B+uBC)&Mk#;sh{ss!tfI8&9ceNDq|Iqg<8Z-UTW{T1TXkRz zUzi|iFRQ%8=eXIStKyQh)sL|Tz`1sNWW<4FTT0{OgHR&M0)`q6${^JF@+bDr{7U?U zG>CA(p$B?ZI^{+$aBqx*o`9OKPS42S@mg;;nX&6aPfy)brY((Q_k<_SnrrK!X4|;;DcUD^w{kHPkXN2vPT(#*Op&=uTgw~%R;Y|&HGkn zIoiqO5N3p-sHLZDZdqNsDRC`Cgyuvqp2SQFvbb`@ZkeS=1xzRcRT5>9jFK;zwhwja z9muMcB5vsRhh7|CmA+}O6?X=Uzr>!?9$5N33_!8Qz(ang@{eXrRb6&xO577Gg|fqIteKI!3k;CwV~ln0*L?=JSBn7luBj5j@dGc`oCJ#90zflQ^a4($6my-`#5 zo=~iOd*CX+eANfUUns9gySs{a~e;RgWW;WT~Iy6U#nqS$dhxl>WM8?xT@jCL;)B(@>Wni*$il?VQkeofe@8cN={!RqF4GV0Tw z4~54+yot&wKK=c*+rOKtHoiKRGmE7VN1yY5NBHe`Zh3TxUsj3BXBjVfUCFk>(yGFd zX6g5Kc;aE63NG6U$&ZzytFFny;fjrk=X+!9u9Z!1Y(X~?$@i9)3qtO|Ly2rUN_gN$ z&;*%XSlOilZRpb3J?=vU=z+?;Hvw=~Nko4*&HuR*cygx*Omqe{H*-}7_kd+m7=_*; zj=FtLa9(ZPZ&H)qnn8kz8}WUq8IoS4k!TFMX3`_9AE9%0Ec5XbF3x6{(pkMB5qx_RpO!E>E-8Z-}*CJ5fCo zzh461UH`d7GL?nm1Ye#t0E$ZvzdM4m*GQ%jl_5)6X-kxI%6Jg;5rxy5W7ZDzq#Qvo z3@@`M11Zjw-L@e`4eI)++dJ(1R^F`Dc3^i@`Ofc-K9T2oV~_U=U4?tT+pWp{0qcfu zo-lW-^6-gEazD)0?wl&z;WRH1ORRE@sgJkrJU++tc=R4mLEhKQhsR^8J)KtF{)d-8 zJpTB~gY5ea1z-21XFh6v;B-9s-{D&)H%@!eUR1T%2fXv*+O|J5bMI4yJ}IQq@p zvhKyq-geDkMBp*y1<$%?v zlnQ&_YmWDKe3n3_(a@*RZOwdn<_nDcJ0xCB*=}tqtN@3`Xim{-zb&fmd8;%Rd?qF3V*BbQn`$dN)KoLM>#n{p3*_+6Z&;C8^?`ddqd@&9kh^)+-ghW zs1m_URlZX1Dx)$CF-28U%DU&mXn&UsK?E_o<{pupG7h0>K@Gy_phPtkGi7Qc!YFfl z#E~XmUxZjn2n&p)9sJ#|qb(XxMS7>*5@&qjN0PlV`gN9< z8b9i2DN`dxsmWjHcV|oe`%sLC=m15kWY^??;WXa0xybGHIt)}6Z@@_EEu7-pItpZx#n*%LO4 zI=yx9FxGJ`S6jkdWNg8i<<;bNvC;?6-*-AUw(_rlvlXs$r(8)x-3a}zJVNr^S93Pn zbX))Oi_bQ`Tog%?Stt@#@=y*FDQ`y3{>3BLWbaf-o-BS`}&^CyeA)jdEQN#dz<$uk&FLlI=h9e6&-5UIk!p~@J;BMLZ$jsB*he}yJJqhTwu@Q7mgglLF})^? zni9p`>0Xm+FOBZzsXrF8cc9SjkHh@CTc`p~hfQj9R48cyA)WJ*dX6CT&OjPJV^i$L zm>7H^eG+X0<y=JFsr`WaMF{4O78%a?IS?y(OzHf&LYXw>#+4jcp9@6wphk5W+&HEESWlHpI%2!GDw4L zUXm|QbUPzB>e_69^(9UOYd2eNlk7BSzTNd;QVJnkzca;I-OX!m>7BLThcb)x$}<_1 z2WFSeb8oQ>w|%Qu8a)r29ppqhKiPE%lg^3kpG#@0HrYgRS|sF1xqEy{7f*Vonl*_P zeyuH()gyjWA;-rNzf3H>(kq@#@EGeShKz*H3o@{R+eqXG;`laygFZ+oG- z9SHw`z?te9-~3I2FCqc}vh*|L*+bX>11<5&N6ldXCKr%7v$zWHks-84DVlJZH0xPs z38mViO2G%f$DyJ;AqtuI0tu->{SBOmM_0l}32NZ?^l7;doh#*>G`R?J zcAWOMWL8G!piR)lrn~Q-?r@@`@P9a97Bd1HD-uvL)swD%Js@#@eFa;s!q~U$a@6=p zO@-lfy&4-x(o)d{FHJl%h6tD0i12~3%^ySsXXptVxw#}4Yl%m)k0dK8%v!@Y1~SH_ zvk8T^!#(UNBuOQalW%`~pxagh%Kdg4EKahtCWT6w*B0lx%X}<8N?f@JNQvD$5f=1i zqIhkE1iRBl5X6&|FKjz(J8Wp7AA`#6+)`~9B+vHk)GF4-YUzws9l;miXiFW-)h&7y z^E;~|<+2nVRQrgg`A9;x+{@e5QDxU4n!x~L#Wi_>zaLkwOL}ZYaKKYFLpSYuRG2fy zV(7YPWq9m_sV5}CtqMhj7reYqpIjU@b*ToM?QeZMu06sRsUPyn9k#8bvuSRsin)ei zn|QY`0j!zO1&fut_ddQwm{emheQFh2>CX z!PqU^OHgrOAB(bnWTn+<{<3-1VY_2S{B1K@N`eCxU<&QR9kS6S0Z|CY;raE%&*vMT zed!MDV6D203cNYPoUdLDI$n(ckDP6O244S4gl+>TJ3+1U{;Q`4)6WLZ5T=|+EVG7C(oCni9>mh z7G6@ofE3F=GhOWmP1^tVn-S5_b|$FGejBV0jVL6HZ%ClsxLSlKFo9e*Dewf%$E`J> zqe|aghu=Budz)-^#fB5^wnq=TRG^54t-X{F@iYO#N*tl544sE|gsHVQXW?#-=IVEU zE(~ESIoBJiKFnJ1$$u};qp*P^bkOJq3)Uv zeXLxhdP#o9)Y^4_Bo%~SVg_xIzx|#;u(uqh9>a&RPvugn&>RvI6&T8N6Lnb4&=Gnl z6wxH?-YH`xb-0VrA50JZyb6;wru2ywzDePM4QBF7D-hZ#FjO}u8w?S35Ri&iafkaU zv|9y0se!z*caf$`YqltHV*mG7+a(Z5X0x%B{AutsItF?;o;$7<)E7UO!%J6%U#SpDys!a$spd z&3z|W=Ub!mZPj{vcKEjHIG!EeH!GL0z{{0k0psygGGqabGXKJkP`NCyCd_ScS^LLj zZkbN;|2>U=Y`=)A3>`u9LZO$+s&)O{X)O=&TR?q1fd2wBJrO|!BBf2jpdE~Xfr7TW z+X6TP0!f~5^0Noz`wvYA1SRpb8|7lF+@O5i`SgcN}`o)s2svtacpT7ly zM~zWvV>f_-*bTCoNMA2@a7vLAda2ch^^g()S9|!ju~NIFG@KSgkBITjkXUMTCL??b z4A-7#*>XBO)Sz3o0F{RdoMG+OCh*nBSZ&hjVjV+-tXyf`lhAHzMC607GQ!!RI@?gG zr5I&OTsl!N^{vxcF~Yso5=&U*>=N#)o|H__)g2wxF+9r`TxQa5N_`2)x_G*z=BXU;BRuAh4dc$8UbtjN+p-`Q(e;8Y(o6i5ohuL8n z;p(P@*e;F~Ifkl{veiJH^}QuKwB!Lk2|zOB9SnLpdrZYHt@a`42>kyss@^U#pGvKB zg_cqG*yJmcTX_;=YFQNzG%DL>hRDuR0ecbZiBiN zH5zFl>S|?Ac5OJVHAAMk69VgaiS19&u?KWa0^>um(x0Gb1#0RTYDOCR;(8Ph>1o3p z=0a#*v~22xWO??=ik!pOVirZraWUu#E5~GXC78vVKaP2M&kI_uhfFK97PS(yQi)li z#EdI2_2lDJFup))pAFjy|H_gRR#>lDR|nuJ{Ora-QwUf!fUKFG$cZj>R%&l-4Ri3H zU6if3_v1Pnf`91e-zYvI7DpNDVAL02Jfr8oHr#zL*i;^t-rHRi5naS;au)WW3QF&> zuTRUoqxx2|rQu+X5r-cf23sY;ytI^_=!$`{N|IgVEBg(L_?R!HxClO$l03I(@}@~0 zy!j1;c&yaAh=Xc?oDflY0w5AFlsY)3?a`Ydly|IvSOJjR0Ad@Ftc107owPxKSOd@o z5C;)Bzn>pw;J2QI32iW;2BxORyTED>VdJf08I&C z`B|5S0aGCR${vVj%px~hT|LVuxACuh^Em&fsd?&T=WSgUX%K3FJ+9@9-~PnE(Ck5^ zXnViCqxmxqh*P5FLxYLs+ejJD-=1zU9TT!{C39`#3b2eMEQ5zVZ(Y2ckz;V{a%x3+ zHllnG!cQ&%M6gq1*sG>6?~yQ%SZRgyLq*i07j;vco)hwa$Yy%dNUe*ubV}^?5IBPC zF4Nj*1U9vT56DqYsesOvVC;Z|(d&wu`I~>Qe6t0)71zEJ->%yJ5Y1ngNj$Qy6aW6E zfXXlVP&#O;ekqfe=8o6(t;ekbmP2-g&B`5rY9HDwwV7L>LLfTl%k0mkr4Onl;>Nmc zPZ(g~6?&6_`e&%l?tU*ALxAi`C*P+0mgNU6shp~QBXxSdw4th}3D-ImCmESL4m@}c zMIv?A1!`ROyGyMx_ipoJ3^3JSzVr{jd4u@O+2@~9-cdduy*KP}!6||^J0gNUCt{@O zkpJn~ZAhlKB{F)>!2*i zz=(BpO?J#U&`9Z{Ogls*tiIL*gq7at{%1RRu20;BvOs}(jQGZZjO;lD#siv!gOt;h z((;J5-m5qfDY~yA;xsMo^hpi*-ERKlWT^9DjN2n(i~))mK~C4Q!Ux{rOgb&*Zojo- zZ&(dKN>y&VJC6PtZh6%*-aSu-a z{>;awx^0Xl$Maw!1;EOi!ULA%vxR9jIYBQ$&bg!A)2z^vs5DPhDf!1Tq6{H6C&5RBr8Co|LdvW=TdHF5nVd3HhsGKQ({xg zCuYDcjS^Z9CE7(Ec!^JlcxUqWLd_G17%FGI=8LifQwrb{HPA^)p9u_k_cVBG!p=5E z5Nd#HTOug6e0(EJ9X!b>0j>q4lUn)s1^_`?sTr^{r{j1-XId&>(+LH-=94475gPyw z*^`*fHxG}%Jp&k}0y5M|Y2f=#0o)qFq(c{|!1!M^4K$Z=+|%iY4@Ptj^9ft3t=b?> zD`cYvEJn%#e-NS@TvuNMxq!?g7Q{^dHf0k2LflAGLyluQ=6c9dHHnNt!p_yWgr_OP z>;k_20LkK%IS((aITSE|14Mu1>z!X%@>=d4_<4HZ=h9t;Wd|n8judVW^fM_$-nSa& z;P&k|CMxa~Rz97myvH*mDA1GCxMjO%^`JqaUDl!#&xD{&mx?(7iEz-uiga_Bc9 z{NQ0z-j3kyd%g~=$%?fj#QzoRG2gB(`r|8w(ItAzO^5;86)+xtEdcG2lh7L6_bss9 zfO}@r{JV>w)E^d3t^eNM^jG8o#j!l(S}2jnMwh6aS8UY|e2mIo>s(k{IY23Xo z7x=+a3x83AY|kJ6rK#kcf4)d-k%nUMZaHNDivoK^7x}h?NmOu~mRyGsG$?=NcGzY} z?082#+O#Le0SggYwNy48RHj?{76&P2!*P1R;@;I$mA_DtKBls0$Fp(FK3O^ zM){RIAvtpqzVt8b7#q^nrZo}iRtKU&^gA8Av_yZOBR6%HtrE*dEt7I(#@b&d6I#z$ z2`thP{ZCVC1iAbB+x=qNX;Q-dd1b0e-9O z`0`&UnY+bJ4^MN6pIGzDgYM>)UcKPkaobH3FVID?5O2pWo|W0m?VllL2HKO`9tcaL z?TSX`{u!A&(@f5v;;_DP8ZQ4$$5e6Ds7N7cmDp0k++uYOhUT3($-mwbbRC5Ehd~BZ zmSB=uv*v4|0?6Mn{(O(ZPBOx92|2Up_JhSo57WM_Jc9s8pA0)to`Q_VsN7J#3FS`K zQQGEC{Ms1+p~i9z04#S|ttdSdBC>Z3DJm*>~t zJ6h3IWgpVK^eM_~pJwjMij-gVDBSM63l~JXhoy@1>#8n@o%=pK2oQ{UzlR#xPwY~w zx*ywomMuHtHC|wiUiB`ip217_z4TG(t>C1-hkLTp4qqpqN+h+QPn;Bb$B&6qY<)Vq z_T)8RDA0W?Rh+F4tH=p@{qD)#*|X%r11L1tcEg1lcfXOK$LD>v>FfVf+^9X9Hu}7? zwxy%Wt3Xh148b`A# z?pwaHWAFP5>tx9{4FdE5OS8%B_IX^l*6J3+TsGKSohtWjFP^_qCaOWFt3Oh$at2CY z9f*n&ckMPUWR9Qjp{)@Rklc>UQ=`J>6z@!}ENr zX&K${@%5o?zpc%0a&Lv2-|~Nulz+?ThdUnSoKc7bMViGORk4YZbhE&lobWP_W`eZL zdX<=kCgPBFXJ?uOhD;o4zn}>Y^kI<3OAvwR9=;1Bgi;78f`XXNr5-q*L}5O2prFi# zQEMT0?&G4BlcB4&LKP-6=_@HKW{nM@ox=p3r6xk2yn<(Cw7^7s&~yNd58{X?Az}Nz z4G8&-7FYtWaQ!{JC0z$Oj|0v-cy>V}3m61L0Ypi>R1zET_1WGRNX)dP4sap}>ZKNU zS;c~;QhtTNzp#)^V`q-FAO2kk676hON}AG=W1{Hk$t{Y?oVcG7One&Aus^Iqn|^S~ z{5L5_?Ri6rT`Pk3v98Tds70LBfg^&t!;nUTXL5n1`=Y$xtl9%aOnqCv_VSNm9W!|h zw6z(46_sl{V_sPal4=FsYO-L;zJ)6HhWAIRmLr-^^aa&7hIM~VZxtyAi< z#HJ%Pg#(c4fPHe$Eg(I+e#k7VeM|u)arYT4`ly|wJ5NLKr8&K8*eB9ZdNbb)5-K&J8ge1Wn|6zgmhW_myJt@>hN|{wukIZztkRmk5 zn2l*+3FD>sa(a}9ug2B(IlUyPHEwS^!_9Yh?+U@ll36`pDorZ39CRx zinfj%Z+* zyRPf?Jlr2e#NZeK;i-ZL$)FZzqhITafL`-MmH6N`w)rYIgexNZq}}h=>SmfYm$e(h1Fv$tM43u$@ie-TJjq=$^TwbOcIFjq*hR=mLB z;lmlP6DX5G{%$;_zWz`G}DXnt22t;XTPe{+aevJTI zxFGsHKa?FUNS+SO4M6^JEql$m>$UT%K% z_qz|NU}ITIQVl83)cCW?2f3A6mfXkG?j(0R9lLfQImlFZWM}Wrx@%=K!TqA3oQ+Tm zS|N6xboXue$D?^swZ`8y+FO64)W20$WRbuL2qjlfBEiIaW~+1P0&R?^mCp(`fXW+f zDkBZ3aT=m_QIFQT0Xz=_C^$0&t#%FKrdbA zn7V$OKkn*lw3?&~wi-avQxD;j#$?S@Z98KDZOd*MOs`kQ#oKZtt$-QbdBhBg0cdzf z0d_ws9k%r9g4yk%a-_u&zlIT*YTt>+_L7Q*#>9C`ht4dK3Qzv4BxL1v;7rydY&<)V(Zyd4R=yO_f@oKfM?2L1Qs1t5 zq^$@85r$ehGN#}S&Q9DxV5{bgtWG}462r88S8hu_ZGwuPUtWI?fZP0LXYc*P)Bg*= zHH1@Yci;1fouqBdubOC|`3_330)5I?4IM3k5x8`e-EZo6^qPK3v{aNr;f%VIUTI;k zAr{J*IQ8rYIMphV;aBM+QEM?VL<-&Kz`T}d^_)^mQrD|y;~t!SuV!)H@KzfHT{yd( zf@QuhH$!UMF1nK3RLC74xroi|8~Q@(v&$!zexpvF?bHE13*#{c{@vd$av=lpXFY@> ziMsqZM)t4fNWtu43bQb_i{=K?eYf%WuMvt#3`XZ>pmmhL2YU)Zv5O~7u0d&OsA4kY z3A)ocR~z7bzu^GI)Toe9XRh$uUqjV=##Oa1<|(whI9#bf| z@K^>R?v3(YCgznzEYQI351))K>oKZV_T$LU^xtrVNS~ji+5n#Z3IxR04GIkacftAbi=;dAJGad$0=tKFkIyu#j?wJ>I8fy-3 zRfED>|B`lb%?0TcKFLKLGz<*YDX>rl3rQte^ zd#jZ{_EkjXGq#YJ(K!o{*Nh{@B1|a)(FY(>heA@7N6FVijR5$P0dLW*=Q}y%H%os1 z^he^!nN4`Px;F&RPluc=1E65BYRc&LLQ!VF;myx+eYTPzTX>!v?o9P@rb@_AlVgkm zHp4D-<79)<#EfJz-9URd3+-WyBuP=u*+?rHDo@TbGJ`4^rbOIj^wb>f#CeB5`kjj^5rWY))JS|k)K(J2DT|)fd+#Bx4>MTvr+YI za}Hzj>%jjY$8-h^NypdAap$P`4{s22hf-2&(LGXpCOCHrxO6hi;s2uGbbP5CxlgV( z32gIJ(%8z?v!yAihf(00IUv^AA9`VlPD1UHB6d;nu_WwOIpF#lfmONgSU1^B#Y-7i zXFtPBL!nl zCKmh0YPp3S!eYuQ)OjY{h#gidGSB+lm7Dx6HW^>Wj*00p`zIN5P+IQYp&s)V#!!+D ziK0qHoAQE=ETP#ky&_t_lGZPcKyuBrOORK3zA=(FGvq`xHAF{gdAH|KzB#&$X*`+L zPTCMycO+t1__zHr+Zj|s|Krs9UbevDcWo z_EPoD+!wo)Na1qF5(X|;iVUcXy}{5OP!ew1zz=D|!sNr_nwDYm73-Bjehr}7rlH-O zk|u`Jt2F62P4*liCLVQBNsp(hIj$o{F-QZnB+DuS7og;Tu%7&JJ1c1ufL=P!)bp1k zr3{~ra1Sn5AJ4?)K+yTSFdr1iXf8Z=N-a0hJdYhiBWVA!)zx~ae@u$de~nnfbq|JU zgRCN#q4%1nxe_o*09KNemAW z$aUEd+_YVX@;;1h1~~Ni$Bk3Ey{yy#>ZT`G9P&JQHF|2A_8Do4$gk-@?x9E+RS3k#0|EVL|n< z3LI?Mc{`rL`XAV*-5Srq{@A+zp?2exMqwVuNOcC@Hcjtt+kNiCo+UfHDhY9E~Sp zr_8V&+O^cwm2U`*Rg_*HoRy-5=fRg^r_|3&kOT2934Hw)KzrX)?c4E`W+j};hs7`n z(I5iMU4@N@8!>e)q@+fsUauUX^3l7#6{kSX913D9-f19zhtwcNK4roq@s_zS5)D%C5D2ajS9dLhs&BxJr)oBsjT z9#1i zv26yjc&t5B*Gj3rG7;O%1%ruTXEPHRk<|gwJYQYRF`ybR3N2Y}k_B+QZ%yms%4y8Zg~g6R69ll3Jp;Q4*KRxJuJ8;sv|7=L9BUXkJ@#h=;n zq^Asgn-q)ff#tI?k8}6CgVu{YUxXMaNDkGJHXcZZ1oc?DmW2_NfUlg`E6@M2oA(M` z7M2L@{Gi-;01>J_MT#lu?-li)6yZbE@CH?zj?Ek>6PbU!`Kv)qJ%VOU zpmsSmel?h)IA1q(kqCBRB980t-d}QJp#n0%COzD)u}Fn#@oDKwsL3zgUAji5i2|DZugSyfWhMe&eCfAhu$Zv zEzdj-=&r5;p1f*tcfISreBz1MpC^}qkpROdccla=8;&5T`o^Cz! zbo<0p_f-h-ue)I$yYD9%UvIqfgRNoZpy{;X(s3%xg^RM4$HXM#@zSr=kDm8)VOkfX zI?;$!D!4#qsrgdfr7XD9>N|@{L^DGCXJ7}VTb}-a8;x2X_lp_VLI@d%)W(j4kB3!} z=v3vV*WIjhShorRZI8B+W_&W*c$#KB{s_DPMI>t%=bc&h zc7t#Q1MdXE?yAOH@J^6B`>uBA9+4nhY0sm99q@R{ixh)kUQ){Hq$Q&c(vXK9mZ?|J zaqw2m)m9%J=$bq07zMHf9i4R?=Q`4))cNe$%rUNhUOO;aayw_os)$|W)vMRDpf#KN8y;qpJ`W-Lbc$NF5h!MGA_f)>D zL*g;Db#v{uU9s19{Z{vuW|(%u@eqp5eU*Fd_A4DaMoe5YRntPQ-@K^aMp)&t|HHak z#bC!){RAjE34U6JxW1R@l8aiY)bH&$-W$CzSH1}D*kwOuFs8g<`M_nKyzMGPLt&KO+5s%JP7!4NZC5)!y3^(n0lx;P zv<(b&8&7@S#-@Ca#nnqMI9_}FSESaj{u$kJb=Zjy|Gw#eX}sjM@9!_n$NPI*KfUQYye#fv+a9l~|5Hq> zZhw2H|I}7LEJ<amaw}L8th%1lK*I7EZLd&WA#lBvO9B@R^ z<>{YFo$8uZ0%BO(<29z=tThXDddcVCnC>6rmvbxXKk>0nBYFZX>~npPQ}l1?p!w!` z{u^>rnWEUK9X(|!oxl63cwhRG87zqGHL_N)B8$To5FA*Xc&w)i=#tdSrYtO+JmIqkh<_*Vr8JEre^}dEIn%Z zppIS+6mAhM%OhCwt==4@Za(XTuyBx}@s>sJKEnv@Kw8kThJ*AjyyNtxkL|y|zyEj- zK-sF~aNTrO2inq>#6;4nNj_FJLb#f4joJO4gs3n_zcs$&!x}jYPH5ZYAg6w6WM1Rv z0o$7kp9ksp$FHwn^(kWHf!kc;6W4#ruLT%hkRK`}Z``BajUw7gJ5eS7s6^^(c{AF2 z&gn#l) zed$&BN4NtZ#e}f=6jm18RKdi>QU%07t2jF<4;Js{qrn!#A2cz)1Oq+>(*W08MZyrLpc}GPU$41 zGa8f7-dx-IBlvU~%;xtLyrlB%f9G!sJoP{FU|K@^bfy6E*B&pp?F#TBqaIO(KP@rOT5O&UF_Lb37SN`D0xs7V*dnj!W^FO&fXYt3yxR zcbp|=Gdgrx+?z(W?BzGFjlVu9JAnevz|I^3)=26KC9&}>{e$stD(=++0KTggmqv^S z7&*zyet7FcY%YK`VsM`)yL(GF5}N;bhDcrPME$-6z@$KR?JZcE84CZ;LbY)<#V{!T z7iEM;+}SvIG57@R$lRi-;ggbyo$1Ft2-8v^=~iF-JXbOlT2fIM05J$q^ol%qUl! zz<9xhd20Q#tie>l^>^}BH`XuP8IV_f=PwALv6*VscVNB8)LR^jGc$J3BUbAV--(v9 z&k%7h)@SUDqg!PWEyypm#^k~0!O9jYND2LN;0Wl*IGXCfvZj5E1oKfodCD@UBMJI1 zxIOkckb_%n6ZO<1o@>0Imo6(ykn{xUEsq>}tz-J+#M}A);H^WUuX6bSYn=cTyOBn8 z9!8HYCm&QHJQPZ}w-o-?;>4isUVG;KhYzC=pL$*}J+;GZ zlEXE!f@$>PnCNsipG0znO7dVN4>F%9j6m9Uc56970=8u^k=6>J`Ol?wj4;;9Jp{rULETV`$Ca$V0BW@NT*t#&gFm64uD`W)45|CEl2Px9_m-;6eP z`FLh+!Tlbo+TD5c5Rn!h>UMYS-FK0Xem%YV*Wdt?r>9gFU23-Dcq{OzMH8XX*Vr^3 z6Bj*JvUKBeIs)#`c@WX*bknhD&$2CjFsh6WymUM77~#Ww%_v1bD8Utumy`j>^~ws5yj8c7}d>w4Kg*BuT(FSzhd>{l`#oX3OCm@OT5n+^rt#0nKmqQqv=5ocIL5hx6jkgHVa z3ksxz*nvSJW~q?#Dr~e2F+)e%D*2%*WW6G*^)tbM!FN!hBwTEIm`|Y+8!bg%QK3Q2 zY(|BQ29rWa!jLt>Gc4#nF5gs)6Y+i0J>S3wHwk*$&Ut>V4fscI*WKkh6rU5 zKbaT#7K1w}xL3d`ASK+IV}FH?EKtF+RH!i(AzjWpE{AS(6Z$Pi+smO9a$-Flku#5C zDUfNZ;vE2-I08*vMB2*GXWUR{xR^wau|+X9T7h0rg4ciu2L;lMjLcEN_97-6Gg>M#a}C%k?)rxHl_)k5!yA%OeT`m+jEd>LS%Q<1?h#K`Hi@ zH2xM9e?f-7!-6jhMbv<}ow)Kc3v21PlyCI2(jg)rBF6oasafnfWOd?@&8PrV3%K9Q=e7(Mh`c}TcPQn*J_Y%Tf4!b0VM{|zo)3_UD|?W3dB$wn8SI+)6^ z3kr1Ym~B6Y@QQ_QaDo^t66$2cb}9ZI7x!L{c?0~<)?DCV_fJC|`Gn|s(0(JBatWK| z$SF2n=MestdTZsWbXgmkrPx*f=|I>AgMxp{6308zyX0;Ur)c8v?Fh+i=V_$Y4wQGFL8a0|Rc- z?1w%j!`_kMU&@I8$w(BNkHe4`?<4^$!YpKH-O44*1v;kU#0ib-9!@HoRxa@X-9J4I zSI0W}qXc)HWBXD;SoRJFN`zObXq5Mk6}ck!K7upIVy;BAEMn`F7w&-uoeVKSB|cN( zDi_hF95V+xy8Ss}SM~MNAc#qav`a0<7_gV@fL;X}Oct!8L$4^Y8!2ne=%>sWi1t0A zP&RtS0bHmY?kh*G#x;-8Z+_rlUz(!jVtl`}`GIC+g%rO|0kivzSpBjJ358teVl`D} zy(-)@25drk!Rs*^;ZA$L^^XZ2rRyidkN$cO}W5rHaZRq ze-bubY79%Gzu+B(Y#@hT{C036%Jj9$RA25%Hf z5v!Lq#a)7Vs$dQ(LYxZM4qA4c@5+Zl03(Iie(lKC?KJW1G>hr9 zDCjgf4ZY?P{ktiRb+qi~A*j^Pa=9mLxn~#T%VryujbRcD{vUjU5<;NEjX0JzDhH0uj$17Y^Vzd0(z(7ydset^NfpQ>6O$e2q2>Sl8ZadvNI(y1Dwt!$`J2m zgnM+TWDvQ(0NqV(br@_eQr!ooTO)~s11NMW2rritUxS_?od_OPUb6dMs<7POI8eqd z3Idv>Em?lhVKM)kIi=*`N3du-q~eW<9+q%;>ZL4QDzR!DEyInm+L~^UqU`;jJ$%zUF0m-Jjh-f+FzX#An7Q&KxY|_Jqb&Bn=bnUpyh%m*HdP(%NSQc_SFqa!Uw`<>A-r2eQ_PK(|xqW}5;?etcdYsym-mc$HV?K^g|a_O?b^A}OWy3JjH~t|r3Y+k zKkBd%@h-q=`f5Uq(?OW2Z?=~TMLGWV>*Vur*=h*`p@rJ&w>Fu$_NKSBf!{QUc>DVUmt@`xFAh3TUSFwNofU@J|u%_h2k-M-2#Y>G4gtTYNf9A+&2J>g~_$AT1(i@Sc-JaWS zY<8t8pN;yv6ujl$TY_aM+v24#3lzKQQPk)SSUdyl-M|GTdq!D*Ui6di0qKiEmqa0iBB^N{P!$pDr$Al`#n==HPx3LU*>yCM>H@pc%GSXHe%bauYo6+ zk!Sr8l!%3>>&Xw!`kjjSH@YQb;+Xbw7_X4H^WUeVtd!yNCWn#CVa78dINKUSx)=g| z+=%xe>e$?0`d7Qe&?RT6{&fOU%gA;_s^OG~Ii%%rOfFV8^*>+|4VDhQXL=6~xHPby z51S$@>~2jq_o?^74;pIh2&?*MrbjJZuK!3ska<@rVG8@pf-`n4Uwh5(xW1uc zzgQ98C(JeQ%&As7rf8AuZg;kIfXhb*4LmY||7s6!vWSNir@o#_f*CA6F~KW2^?bBJ zeP0#Au0dH*WEd=mYwJYSpD)rmreuP|=sKoeW^lLq|$@F2~ ztvF{i&0A+>cCt_}=mqj-u%+;^s0|; zNqc>v%1_AiCR*u4dz(1E*yN*~(=EPG8aUX>SFMP?WCTlwK}ApK_3kP8A!d)}M<0ju}S9N*f$$MeU+mq(09Y{#jB z=}&JITD$c8C;`VebyMPZZA#J0+NGYN7v5}beq3*WiaM6uyeUcV>+$TAL&-v3^6@Wc zPAt9pEu1RSQx0%ZzU;u9C!2c0Fw$bgE~kb*7&=Qv55Mu!)bh=&;$Mny+y1<`AQ(9 zc1QY_JapD20E$wzigHpv;9ibFN$ol<-qirgOWCpFNIYRPDF-ebhf<8SCLC=vVe z-k{IA@oDu_<>))=_AQ^v{aPOC^XGfbyLnh@(lmG*CtKIi`I%^M-EP2C|IR0*j#fJS z)grV)>z>(w5UYx{Q(XvTVL+i1+K z7^zYdrTW&uS9w87&Hw)xojPxbtufu#{nyi~%%=K+Rs#L4b{oVytGN@tom1%Y{TVi@ zF$_Pw9pN@GQE`d~ zljBxu@Pc~ZUQ9ZwnQw}WRr#wQt32p3#3CDN!Q8J0F11sBDX#49*&YjK$B z3%=&?%!Aj$T3Chp`HVGoQ5%s2T%uF$cWk;Wp3+YeIvK?m=cGgQ%ejSiGTH&xSvf+y zr^l^q82#W~HvFkXuTRlYVy%Ck^d?nE8{ziyr?yh+q5?7r$ic`4NXk`up?)m;K9K~W z)JIL5w?N?8swqU=la0$tc0jy(FOUk+_sO;La_=^te)@cG4j5OIgHFH=r}k3n!8(hq z15_G2jQ_XhJf8zU{-zsDUn}`_n~U;tgLpMX6kD_3Xg!rS&iXTA@#F-9xK^ZPZwDqb zHLA1T@cs%;e0hK~l;Yf4=%8PPNMFiit_{Sden^seI2bzb!S!T&o8L|}`Z0Dt{e1n` z=uVOlFGMA$7LjW!aZy1gx`FoR@W($f!9^T(i_}Z4eK&C@N~>yPKEy?du7$hLXX)N| zN;^5)s8L;7g||=?8V8B_#A=|yljRq43~|&Z$lEBA)N8hqygI5nQ6n5!*HY`~b7JL% z%hQSRsNKU@aD>u2zbChL#ocY~-@{=H!)^`aHM9{tn;r<|+n4(Hx+%fgj)$hGqrJ**(_ZNUWn6k%E*H^^Djlh8Z{1L3_rVqw z`j^&~?t#S~-H<oD-s+1=rwUAzon-MC)B@{#AS>OpsR{5t zxkiZ%3sS15b<5t?mY1k&1*2uHNV72xVV8`VA(22Igc9(<&L(=dfzH;O(z5NZPQmJ} zhw!`THJw_8(mNL%PZyxhSUr%wt7ks;t+t2Vck?&B)n7g$vivsQMqV3XGW0B7{%!x? zu@AfNd#J9+>q>(+n6Ft=a_)*;XhV-z1(AFx4STcXGZU+csiXFLtOESRq)YEcup_9-GUr2SToJ_Fg+Zs1^dz zHkPoEp_^vDo$}xJ`RKW>;Jvq@fAaT{Jm`|74l0bSs@A<%=_I}ZI{*nbn$+TXx@3lq%nVk*(?#6>ZjIV1{y{A<7srL* zC0wgcF1}H&DTZjf@r;yQwLLubF$yV(H(-S)k|B6DPjd`H1t$!wglbFIs*U>yh4d74%a|~<32Z+*SCfq`o36qbMQ{^ zSKkt>(*Y;xChJvV61o&^WNPXsR`DCg&>|)J@nOFe%U6vogW;mBN!Y55R!%%C*d_e~ z%NWje)B`pQ=Uhks+C}WusP>fH-mSg|W;IO+#ejJO7mdbuFf^{5f@pGi@0LRz$cegW z0|R=%4{3R)SPoC;=>mLfnVEAHfl};6Asy3QsBnIM2(jcCFh~z@oPvz@l`ng2`c|oy z)5g=05O#Rp$Nr>fGh|kQ$NuK=Xwq``br4NfpWU7t<~*Jb{g~#Wx1N}o>wM?WCH!CZ znjPsUj3iKMl=v^qgG}d5DJ~#}%aYbIkCkcYf(zgaHHU@{{bvdle67%7_ZtBBtbW~I zeVXSm!ZhpXYdn0&$JaNw`i=z_(#hg2i|?)ogB&8435H4KedueN$5xdE28SJL@Zceu z11bM?->M$;#Q4FBdFy!myVHa1UkC5OhvZs8_hR^+a8HTVPXGw0gH~Un> zq^dnPg9PQl);+d8hJjExJd&hcM+!_h^GNgnwP_7qHe?HMJBTj#D=xI=wmN=gXef9Z zQhpG)#4794K?mrLm1mA{K?H6}MzG^_1yC!L;3S(BM3X@$a3M5>t!WAG&!rW1Bt94( z86Ydv$mJ0wgck~auoXmu3r~*Xzx!HoatNX+XXZeJSoLX3Fa8pJ9g1I{Bp$wM7sBYw#v z{yRqkL}7&ruphGQssg*NCoHI^H0Z&|`k9dpi0}=F(T(P#AuC2h{YJyWN5hjxBX*8P zZV7iN=E3KewQ->ieZtk-1tH69TkmM>^(jgsscW_scEv+((0H_BiPZFr^*k8nesz=d zU;qcw^jWCEZ zd(wZB&gOCc5x8<9kN*^9S@C96YW9^6jOIypivq(uftS26n+;1YE(}ocm>h%-6XE{v zJ;QRc%_1y61HOwRYRVSTB@U5`urx!M9mt}BZgnN|?_$j+vLJ1T$e8pzc$o5xAs6yrlfBAjyxz5Ss^(Q7JELQBZLPv4YJDkUaC6hlh`$q_p2n2Vw)*-k`I9?x~L(3;xKKujoh9=@~W3&7WKpZHCT zginlanRvW&;+be-?C8Yvnu!-TCSLYTjE_!?+i@S4b4lzF%`xuO<F~*! zYbM{_n0((exiC68yMhM-iEl6HrUgN2SR%hD!85I6>!#HPvWxtq z4q|MdUbiE=pR1jFH%lb{5)!ylARG(+y3P7uM}W4VbX)*a8k0xhb%a_y!p> zj}%afq7%td13^~ntEAS#4EE)}2xwZXu#tvLRkAJq=K)GNk4QBoQXooKdr}68yD-SuC*yJMu)^C3>Dtg?}^H*?Dk+ z%TyA{FjAjat5+02FU)F%Gp&l&<-u~T3I|HTcL~pxfp?BGJMshcFpZBoXa~lx2JY4zh!RkQt#G1AApZ`u~f_r^FAS2A|$DfyJQFa`A3LN zGT)ph%Evm!DB;`PYBB*x>Y@lliX#;UX!eOnQ>CMon%eBE8&q6E=F=0-1Lg}uB|s!~^C-G=z=RiX1POLA zD{DbexqJhKLCia(&#zZMHHBkq3qjNvB6RD%R%zJ(E;IU!x>$5<-OU6m_L`DLL?IuL*CzSf=OG}? zZbOEoli)FKh?pgEQRqBij^X*Ekv8D&Q^=Z%*gD--p~+uSu!Q@JzwO*UVe=$k^9jTR z@G9#-#7XQSiDz_sk(n=`2`bTcg~9O;NE@;PO;(l|Jp1l%_nigqNlp{z`OpXAaThU6 zl_^k|ef;e5@yo6zmngxvSiys&k3R}OE*|^%vo`B{MAp~dkH1|$I*E^|h*{fy`Z-F% z(;E*=5w`BMpM*!M5L;Eq-6~X(3VmD!M&)5|s&I32(U<>c5idMHz+}9dWFF#aqq0>n z9f>@Nj7mv>jo%h-j}i?vJP(~ORCc~vw+OP%yo+DvwV(5Mjupm%D##>%@Yg$U0Qpv< zC}XKr_`8M|r+RdC7`ieapF$_}t z!08Nb>dU{MFh;zjJ_B_Rc$>e=%6G_tMV_&O7aQ28%NFE~AwdCog$wtk20Xz^n2;*D z@N|a{`-%FzFe49f$sNI7W11|pEhb9T^8`a1kuhrucNPo$z&S|PA?rL*W^s0ddPRVQ z>lIa$nS*jG0yaVU?otp$FU%&PTY{+q0UuF=*VH zRJ(inyGccHYc3?o%QLG#Z5jBMQ2#~t6tP<=47JLB+VI?)^sikMv}_pvZmH$N-g|dg zLEN4Tn1{Cf?l%JFd`Z!oA)D4_!|NFCg{C%E!^OtgqN2sEg?z!yWsXq-8){xxBma{{ zDG_*uL;V!%{;ah8dC2wW;hQS_)o|y{PfS`5d`;FQOJ2B>LplMzD_Q^_;XAT?DHYT0&O|-)Np^UP7d> z)!X)n>{xwu6MJN5`0jZDvU7Zi2%;}X3ZEqD0ei0)!d#+=D*(QoEMJG4`HS;k`+gp% zfx9f`+ej;1NzfOq-Fh6zme2qBnbaBQy{O)hZ^zjy+wiMpDV--70YAAP~vumoNJKj#1ZX)eBEJK{M}gAshcXuPOg=@{`2wG-bV^3m6h?@HGgjx zl12|`?fUWSqwhbjR{iV3+t`Qt2Poe2qPddN1H*KhBzNa+n^)1gi#2G+E`~5+{_!wT z&Ajp&tXFIjaL9IBPIZZsX5{tsw|-?36Q`{MF^f)xg%vAze_nX|#Zn>lF4C||`)c*L zI`Ftt#z2!dRBEy6WO4krG`yY@yPga2=?&Mm2}xQK4JX(>CofN^cbf_?jB1VUc$hbw z*ndFFBBXB()1{|GC+bh9YEZZFh2Hk5oW&-1VS?_a#8yeANq6+6Uv5HHh0wKO-1=t_<6^U_pVH|$KR>=*075B zXD7~YsKa~fzUMB29TwC6am0>{WZ0ghewiSWep=HY}@uY-tcxk;o#(JY4*<4ymN1MqG*x-e#>QKLJ z;>Y6f>u}BWPP8gi_ zDFgprJb`Q6(z7+fP$zA3)$WIK0p3zoL$0p$|8*`Q_M&LMc(3>Fm$f%KYWNA?wjC7^ z+^1y}&>pR|j)GdBb&=9$5(pPSJ|Z9vAa2u|DRp4?QQghGUt4E?CM`b%gbGqzVbW$(*ElU?;ow&d;_NDLB1=v z=we5(TRFp_IIXV2d&?-?}X#* ziS6y~bKV)_hmka2F-8lc8umwoUCuCh_9FkxijvD$|I)e+rMT=Jl)X84eaw2G-9y!Z z^D4k++}rY@&9UrI#p<8a7s_2Pq{{<5YN~VrL({s;!?0A&6iL_@|!dPZyHxE2*nXD;)&hosW;DTsL1RfmnXpOT#Bx`J5TbveYKQ z-kQh?{e0QM=-)IFjLe{FTr2kXG*Q<^yY4ta)qI;~1^hA+R>8MImExhzp=XS9@|*xoZe-Etb{t)G7~H>MVADLx}|@H z(su?ve~}j84Cv>G4;Gl2nQk&MH`%a+-=4Qo?}fOZ2{M@Bph9$<+v998w9Zc)D)*M@ zcFl{9UMVoQO~kCzWI)QRPZyJIpaWaHtFSKHs=DW`hT=62TkkR>!%RpTXTo~I9u9S6 z<;q~&-r+a8wbm}*%@)MWEG%;(O@}9>9Niv!*k`53R*|H(F4BDVgntvnb6w5ZEfe<0 znIl@~%tS|x<=k`btrqIynmXg(4AkRs1)jrz8z~uSgN~yseqIz9FIt||YG8TZyk)R9 zr}=`BAI1C?`ml&Tjja)40<-kgb0(;61Mqck)h(j-~^$C|Z2 zC&)2J&1^s`D!gnLOhX8u?3U>IUO(Tizijo*)pfCaxHe5&%{kZI!|I`$0rq0|*8n@u z;*m}F^NlZ0*1|LbwLN!>`CD6*$ge@f9H*vZIYzT~qFWClr*2U)YznKUldPO8zH8rd z`noH0#Ytkca;RC{)1Y;7Ftd6OUw3?KqwycxR3FL}om&|^wOi1%&{NT;VoPpZ3Aer* z@j`qSd84Jpe3r$8ikQVyh5M8c$yuKU$LR!}LP^&MbiZ;6~n>Ys)PDhl|TR^g|b>_v)Sya&9~&eyiQrcdYM4OHWF!9{LwVW5rKcg zaMXBwCiQ~t3^OD|c(LvC;UHD-vz%LlvHQ>&S<7Y}yXZId>%Fy|rbKJ=Z2uoc=N{JL z|NrsbJD=NXowg2JC!Jg8BeqUDVN?pq)=6hclEin1N@wdJrLc-5$|4D2ha^cBAt5VC z2sy_m`tA4sc3r!+`?~MFpRecZ@yHK+401{Ma>%vjwI*kgXKBz?IQO;5j~)qjy(xvq zJ3%z87X_9w5nrc|joqUqSM%>eQhSZa8jBE1vjYPDsu)t6LS`7%RA3kiC4;}RVDf3bLz1-bPk2pYSrR69P`Ps#cMH?a2Bj7fxg zMgjRO)BS`{`cIvOj*|a9n3lEcKsDe0EsWa%hNmtLs7DfTK1%_3@^Oa&$93@!4eaVf zA0)N6tiM)PI}FFIavyR&`W){|g;gu1FBc`C$GG2`b2+!Q6+BG*B3S#m1a67ulsikf zi9<>_uCuaiXH>J^fX**WBE4{r(n$AK?|>`zOVM@$L-(n~-&i#sqp~6TuO+Hzp7?gB zR}5w@@-}6Xi^+=OQ*J5Yw&H(9%OoWmdTr6q70WBh%#&KWoAVvSU9fnQSUr^>$kkt5 zvU72(y^hXpS8^9DT_huHFIux=V4-Mdh=lyK*WXxuxgdOxNaLDBq9(S7Q)}eCMV}i{k5F&{^eSU|$fN7Yn`G`=9BPDNJG`|D)$P z*rkmQju_^HlZ)WE3BTI$6V$VeY!mIOK{Gwx%mInZ1}q?o!P^@BV@I)qRr z*NTD=^Ffr5V$87U(!(XT&+2f+WGCqHw>)@rl0knWGS|%-ha}k zJZU@q%I5v{<-bOB|G@Nc3AK%HNSB(-Y`AL@j%frt#hrjy$}O_wu7vFlCJ;Db?J}C= z?T+NzlE8F5{=;oDRBC}vq?}>`SrG-X6-!kiB%(y{+G0R!4(z1#er)PvoFjU@_O(Tn z@yl%jw=6j=)yFgX(c*^JS~~pG;f0mXGB*<64hg0^f$3t%3KHM8My@>~K`jCk2LLCw z3QWp#?v|*T2t1wmj1sv{MyzqKp9%{{V?$JgN!Nub>r}awkYhjg+PF+&D3-e*`JOs6 z$S8qB2(z8Vam^A?`+ZzVJ{v9NT1(zuQ8E=G+V#{V#T?@2Fg5!_g7oz<7IMjK2%(p2 z7S?tHjD;)R)8o=0HN)b^Ix9Uk_2Bg8$LcuDchn}w&g_< zph;hGAg3@k9S9nEmiP(OeFI3nDO0_S5VGSC>zL{TI5&bZZ9wKl31vx|_)|hilxCs9 zt|Txav6T$soh1Nx`U*;!;2HpEwn^3c_2ZJyXn~|^iBi3M0M3|HLrSgPnk`o~pX@g+ zDoiXHHf4>S_KD(IE~tP#U^i?2aKgPGc!gVv+$0qPz??%TZHMK(;ON?!_wP+OqZm{}nFBdf~NjI@@ zdIKW9V4$KN;jjR~3v8yE)?$I6e{f!m=ELq7d}Ik~sd{utW9tM1Ejo2J@@zyu+$->% zn(F@ANG5p!4+E;5I7fDGvCy31VkFggud{fe27b=(x-N-#Q=%3UP&o-t^b8abMJ zpiKM4X>FzX<>|TQvV;`hD5mBDk1p}HFe$6}X@0f#!%zW8%{-xDal^{rh_f>iP9iMb zvc@o9y0fmtWwXUuDu92%74{Q&PI$d{YQxxv zTLx=u2JXRfHRN88oR19Mn2;oVXJ{r?|IxH;!Ph!+G+f-PMa}1L$*TVZR(m~T=y(~m zM8Dg)_y{L96=*(5>D%bPEgX{ws70QAu-N|4wj+G_G<<uT>nb;8T#e6+=Yx$}f zIdy^Og5_Vnc+a**s+f@KIa`FBzdv@;aJ}3iyPZiT{6|Y)IqQM87-#LPtpe z(d|+Gd;UQef!6o)Gt*qli}5>RWaf!Xlr=Bs69c)#&>4L0th*M?V!nCL)uJ+6H%ZlU z0Lyt0vD*&M_Fkc9$N0#&8_iC1)3uH#d2Kc{YeQrZ)E~h!qC7gZC47*CPfuicf{qru z_^zCnuT1o{VDNkxQiiq6Hc@Uq4|dCexT|DDAwHzbAD<_u=vw=j74h`u`OAhyW4)hj zu#neR9T;X~Yq4>B<-tMZu*@ThA1;x=qU3JAa_^fb49y{tF%Z{AaPUO|bv~-GLhgc< zp>*zJRsGc>>4s)7CQ1VrDe&y)_3FxyPTuw*T-DHY_dgJdA$N0{HrA0ty};_L^<3y( z&SD=Lcj$cE!_k|?HW>nk#2M0@Ohw_gMS?x8yJ#6cPDK<&7uV88q(R|3oBQ;wlvzc2 zdztvCyv_e+woF@waM`6>K+l0#vobDsrg=!@nx_~Z zD#W%>PPP_!Aq9@#H=}lZ(9B7pNMuGCj(WGnD}TKjdM7kEFl;^?cs;s+)hu^TWRAkV zm@dgIy!f^{Tv92-HcPI@_A$?fAZ_(28F7&v1%&exI$6`MARw}PLW|6GV9StfnfFn- zOA%!65iXn|H`Tf5y`JH-x|_;SYUlaTYDzjf$QT`OTa%Z})vv5{?)+4hMl$==L1DPXcrmnmXt*2oT>$_D1)r<(!+s(<7vR=-2xy=&O9lz7?w5eFB@12+*Wy`eCI!#IL5>_J}Qx#)PW#wJ}Yaa8`5JoEnYaisA^|mU~<9LUEqTDtt#q+_OW|_CyjLbnupPamu`g!}S3U6W- zLnXGmi#z=k0ITVuL-sUhvK_ zXE?4NARbQL$jn@@yl1U9W#)z2wU=5$AiVgEU`^|-zXhm#CQEg|u?Azhr#sDhgom_j zV)7lk1%^n8?Xb^0IVJV@H>Wa}(suC5D^hAVpuPwghVg16&gq0PCt9<6+WD3lSC9RT zpB(8q202pSAsrlMyaYW3{#^=pDjZn}$7X?6m{RGSN1=Lpl=G1PcV{#7UY_o zZq=2{PoI$-!n@xJ-dtI_du5F`Xx@8eFAK6?S{nvf3nA8hi9U;_mz#Ba2HNVry&=bW zC%fmZyx@N4(!MZcIFt_ZkMhmHbtdLZ<~5IR>Q=$D8MQr<&d=9y`Jm%f-20*99nEo| zwaAw7rF3i%CnA#nQu6a6!{FfKwF66yRgy;X$|Kj3h7HRL8^cHY7>aUfO_y8)!BXx#;E|Bu|J;T5@S+BgTTuQ z;5+9d>x40WrP}rhW4)EJYYrPS3rX%(ae>t<)_(0(H@N8>U#m$9J+uBuNil7ALio9eu7tL%^_ebq2r*5sVMKY$%PCm1vq>9_)>LTO zumftOf~%Jx8-N-axW;RZ;9$PAC*yyf0%fuewIvc zaH82JD3u&z-%`rbw%45n2K3*6r$$t-41+@+qa7l6C?CKzLRid#f@P?B0Ig7u&&yW^ zj1x{11Fc8g%qnAvxH#E4qZ`o@=<&FmaR833xjIYKin8|?=(D8IqBZ`bF(vDU zEM{;K-HTJih>1l`)88#Di2mm891e||ReYw>Cabaq8d1}vJmeB9EYEkarvaMIXBlrQ z_369bl)K+c>KEwb&P_egwO)c8@#|h}f%zD45Jy~xhfSalO4AB zm-G7A&e_GLYWYOYPh6PUZ$Le)r>?ot=2!!*aGU2S6BDsqf%{Rua&ukFeM9kY{|fCs zQ^MBO2XlPNabW@GKDbzRB2B}LHE=9ACvsFNAg+s?D%gRDaK(GsiLh@M0woSXy}yrzp0_x)kZH?_)!$n6C0;Al)&g-f!JjIF zM3qZhiRm@ZjC50b7JfH)*ZlSurc~+P&`3G23pCg-lin+j>@=w7Q^L@?g5#mHIWrC1 zBk3mJ=m!UBFqaWdRQ;OT2h>-(eOx1$Nq=2aQ(+q+78)mHWM0YcwAW)GXzmFDBm(IR&=>|8Xyv}b0 z87KqFTGEg94rup`;vPKvsChx99i?Un^hhDdtIB?z{;qjj!YZR&XUZ^oHVY_lgSJi7;5ry@jZ;8S(ZzW&juBwEYD8W%xIu@0= z7`}^FnwH0-7$>fy9m_7U>-EvqaJy|`w#;BgA!RzwA#nZmylXod>?9ZS@h>Gj98(of zn6MzOSUT8-Ee9zQ^KI7cLWPy7EXf%>YA;iej#Z~Pahd37h2YUCGxAoh6!&nGp$e)_ zP~`NZ7L1#}-mj{?+FUcR3SG_rRzAi1AbvAU5RvS|rUQ8iwf88H-tJ~*Xj zS4n#BYr-DSCTA{4phJBNTfvs-QN#fl9WgWBM2Wh7?SoKVZU6=KmqS91R#7`P+M4wce zszxdrco>=r(WX)djQtl%y_dXC-X+}ezrf2U^-7=x0mt8V@=&4*_7R8Y18%)iII|4W zKDq#*OiRNc=Ua4)6Pal8S8&@le}w1UIs8EhpGayU+}7#G6dK>#YFpb?zURDO=04-j zG4s0UNP*sx1aUvT_R{em^E;T7Eu$5+-KU*DCT%$P%%z5A{&;LQg+tl;EW4l~VpM`{ zmq2i*M957^_14CGG&5hB8>%DFDg;4o$~e&fE&8anEeKSL<0ly7eA*_*0z;EHxaYzM zHdkEW`h6J`{dWS;jHXUL7Betg*iyqZ*m|Qb_Pv1tkuDVUQ}&mOd+o4 zA)xP$9x-f)x7q2QSGo4&pYbap%l_6drMJWVLH)>%Ss%(4 z&m+%1)jv2ekdW5FKaC!Q2J3TKz?HZ+`Y%K@2SWAsLsZ$U+izIi-LhD-tQ$8!6<%L< zj0{N4R>=6_X!wC2AJVZ7LVk<~!ghh{lPxjO%lUAfUMEb^0t*b>W)K(mN%dOk`G%w- zN8E2!(J;#3b3a4$>IgIU`;fX$BgoNiaQFwgN{H@qgwb*!X4I}C3n3MT*!8t}ud+d- zhANxbHL@Gex32Zri}aBEWEy48-?E*6H+6=@To{h$sWmFizB*L)I3x_W)=uH}F3M>J zyS$ct9~|siylp>X!ib2!;-@S|T{|%MD!P9w>GyYh-O|kG&b&7|9QS*xzh>4yc%d4F z1~Ov^{HeaaN0j>Cdp$1-HR`C)6=HyyskFHf2Awgz6@c#ZYvQjz{yu!i^0?GgE5u=k zR(GcAc)SRDTXgvNeEj;4aI|$nl{Z%;?jjpWHXx@NEA0uO+$eYUHRI|3l)L z-iendavxvO|Kx-MNDdqFbwZ5b`&KM{)Hq&w`t^xlH-7yMz^>MSn{WZL(zJqf@)lFjG*{XI#s>(DeOzY7dv0l))zbEmDe- zNtxiN%j_V|!b?kRqVM5P)Wd2a4=z8v09{LOc%tTRHigb%lZ1?apX}iA8So_5J@GoT zOs0XBl+tXc?ZUmtjroAjP|xJ3-mb32(^E1v;XJ)s8gNw2pcc^b&VY0*{71ilyZPyZ zLkiUD6I4pae%|qSh)rCiLN~VJkO7~Q#kiLXxGACErfE+4DXU@1a}H9_Lk zP_-Q0b`co7;gSR9{tO#un}X{mknKL`Htm`+x2N10`OnQt!}AM8x*_i7`356~nWaeY zDV>IG_Ky+8i&NdqV&JI^PiTzhf3`b=Mm*o!cYUpV5>W9rd6)45{=GUTc%yRmPo+^` z0rl?}qi*O-Wb+K(L3=&%{nt^=P}?_zOhb!{Z;n-L&mPtGtJ3Cmp|{ZBLJ_iEq(9Mw ztg-*?k#fI#m)VYo6!{mkU74z&`b#PX4QFCKK$jA@mJ7`elML+yo=1?#-COeF-~C5y zDptmY8VR695~z{NH6}uPaFEAZAYN>A^Kz3$Bo!KsyTDeWvP7_G2|P#yRsn8ZK&zkJ z_jFLv`gTFQlz+Y1v^X{#e+qU`>4g6Z&y{FrF);>Bx~(8jCkagbwR@D(F0J6cKPnr~W&i!hsl75U)?xDjsb_5au#4Vq-< z&mdIw0fMQ4?UXkuOlwo()<}ukLfjTQ2Z?1SaV4RVN;MBavmHx+1)}(;4o;tq?2flA z_QQ-xG!4cGTv~M=DZo>@J`<#hyR;8V!jln{fho0ahW0EMhGlB@NWvYYK0BDW0ETuH z2fV~3M^a%=7`fRO+<$b#cV@sJ@=O6|{j3z-tCv_Q50_+)8#MNKT>=L$u}LvhK!(@< z0!DZD`oE zk7nRrF!eg6dnTzTL{f5RQ&!#M&AVt@0uNCPI02qYQWgM-W+#nv^`n_B*Em-dfX;{} zdE*gE)zs#ea6-*2F<&zxam{LTY@e2$>`K!G6f%)T-YI-H`OtO!xAJsn5&sDKHvm7bmzmFs1p)LeL}8 zt^)K2nkcy+omm_$Fo+E0r9a_lu4_`UZns|H;YQli(Nn|{8mM!*iI56trh*V$Wm@AN z)o0ZjS86-WsrU0Vq5)}ffvDk3giE`b6% zRRFnLYv(Q=?tLQIJO+|p6n&MW@|KnM1ITL}G?rHWX>M2fRQd<_Niq}CXbr4%+|%+skaxI;*u&K80f@Gi@7zF|Imy`U zEN~VTF`1%Y#i39|I@botL01UeDfMeSz8ddrqEdS#!Dw2W5-EzFD%P(f^NK94%V#K#wKfp#dosR<(LcC+&LK#En`R>wX4f-!p#KD4%}6apGp}XZY>#25ytqg9n1Xe) z@m%)NclQW48P{i1FavCiKZ7vIh5OEXW^(IcoR;iVWV8}D@nN8qfkE?buBt~1!~4a6 z2Axeb;6YTp-x7)4y_}Q#KbKwR=RS73k0L(a04I+bK^yfA-lRGLJZrev)c}(u^OZNCDKXcCpHg1gg z=kWaeozc`~5u%md-Y}dK!hX`|vt7@dy2S=DX1_W^1UpDtnIXxsG;ZI;MrN{4hkLXa zvu|dt?T4Rd57eDRJ%7LCZUwrQ`&Wd64`IAUpd}Ja0(-mp^@}$DU9|VS2yf()d7tLu_@<3A z78C0eB)99BzlMsT9R!IFvfX1|UuWX3?WVeHv~@A^?%UhB5A)xxGq$-;*BlV4c}|Ug zb6Wl^iB+%o3qq??HP}sPC<9an(sH1IB_X-ad2;tY`AV*So_T zKdx&qn@uMsunAgCDp?{|eHxx4At%sWEFHD!(!1g*?H~rCj*AErA=)Kys3Uon0qbN# zygJZfx0Clp;m%8IoL(Dc+ZjBr?6CK?TY5flJI{FRy06p4+0^v6Th`Gyc*)Dg_gFiq zk?5#86`<=O|Hp4$y_47t=&^xspR6&)pFa@D^VUSPZy&l5(35b;r}9_+wgxXTDDS5X zmK0DiaeqYKBb(0KINZ-12~_98z&3mW;q3%nQsR-c!%RZx1d^}vDC?G){PYhI@)s(>C2kj&?p%Gsmdw{yO|1Q%7rxcvBhsq3m)I1r1x$0;T+r|TX%wo;PCX=Q|m9& z^s}OMCZxJKtL86L>ns%hUDCh=h4{+4iDG}zXDZG?SmJ%G^k+YfzXj(_l6xo&*%Cy{!JS%ITM=Y_i zCEdH-8KNz#zM5`VrV~(uz(fI4CmYZ^Up;ZJ6W7Nfn=y4H0J#41^GD3N-BOAfPp?}_ zX{~;j0!2^!eR+;C86OOZVSL!j#4d_{-ZZ!^KRB;~bAbhxO>58$A`=u&UhS^83eU z_NiE`(?LYsR?kFaR~yMat=gopH*GADmET`#Y#rKK-sqAtv9N2TFJ$+sl>Tnw5W)mp z8V*IafvrN*&d+R{)Oup+2YtT!&~m6Vq9o@yTs0AQ-sjv}rTF zCPRfLty6J9O>0!7&K)nsK6q7>0>OKRwA2eZ{>&7ZpAvQw98}B zl(fr3Qq-%)+=H0(-sy^Sr2lP8sxOY|80?Bhn6AfcoT5|dTZ((ga2VO2aVJor=6TRQIoTp*+_k!JKl^#wm5@hir3;mT7S$O)K5bT& zgwu~wdK7jK`D*KOrV5RhJDd)0yK3@dAbfR&P$xW0Dp#+5AkNp0NFCYt_Qe12xpU2j z*ZtW8xvhKhdHaQt+}@1;t_)D?NtH5cUX*0xB;YwLD0I=o=Pk(8)_au}KMx9h9jIk; zXbs%`|% zAAY_%{J(t{?wn#`Yxc)C)Xv$$tE(`vIT^Jg&7C}KstAJH>vj3I?>;?^K@$gia@ml1&h0EKPN13IaQ~~3v{ToC@)G5yKUXduu+?D*1i?cg0wB*KiCTO z>Ylqz#RT%&9mQ4MtN;@HDPt!sCi?< zcypPNz~eVMWbG*wgl(W ztW$4LzW4;+ShK-h>N{&>l!?efm+sMuEUw&S5_E^!-GtBJhEl$^MS5md-ia^c>wQQ? zxZh<~#4|3SHR;RDl|Of>MOw!akw{?d(_5c;#d`jU^KE_+3AXiN3@qt201qGRM>a7@ zXC(sjQdW>bFT=ia1AEJiq9UX%9&XY0JSM?IU=${WvP9b)BTn&G5R98V2x)$M)puH1){IQIp3V4Ygzg{Pmetekr+acqgKrwwjILMu zpqH^Q%G$6Nt+FCNy8vd%mN7m_u49YO6fxQ#?k0RlzD<4jB{F=WNi&TLbIK&0gbR|HAdQ~WP{Qfb=)(wT= zQt5FA_Mk~v*E&0Ex$Z&whpl#HQ?PZ_rh@T;+ATCJziO14U~(pKa0;8z?M=~kFO0ow zUlf0SH(8l@$n!KuJ%=^iKT|hgE|JEhF=`w2e-Eld#btgM>kw%Qe_$y~-s$^nb?EH& zBU`~+*ADgcM168Nk)9IoehPyY^dG-I69ZY>tBva-zzmX`X1CB=$iq~bMwocn^X}Nl zUGEbEzL`Aks#_Xbg^NDcd$52`wkd$B&adj@-&OpH^iCj{m+{H{{=IFX7 z$*=Dmq!;V8GG$R=)PV(^e9P=FlpWSGH6;P!?kH`j?r!SS{dD;PVue2rWNIYV={I82 zrc*buXr+mhFDArA*l5Jl84%5Y>GpvzVq=~WB``E&uEGCd(v<(2423LJMi-;qqA1ks z9^GR8oHg{VHS;cF4#B0c%B(`oxz@hnWBBWyf3*G7fu1mgsvDLyBKe5!uGT=*Mz;cAK*5x8U=dts} z(Oy%iQv{e=Hs}dcXsm5+knd>waD2m=u9x-;0|{2maq;rg zTkE>n+8k1SMxj?!TZvT|yZ-?t0LgSqXN;saWbM5UKlDhd=5is>vWx+s3A{j&hxGzP zIF(c+m*28GRI+9XNBO+C*pzk;bfNFfS@5jEx)8hz-9-&v<4O_n2#Gmh1KVxxn=F`uS{VmVSYt;I1B2?g`RYDC+hH;jCtw-JWV%u?INB| zFT6Tp^-%<$)=R2?>ht+hP6!EtYvx-h!EUM!>@TQoj-QzrzCTW|cg)l&p0d3eh`uQ3 zzCvBz0C(+ObMuJSlS7avD{_xzBzYdqw^f20WmKbPL13j>M4OonKv|gx_FUW=J*{EE zrkIJ$;^%DdpZZ@?TOsE=xx3ko%!1Z07~fujZC}`$`qo}EpPRlTE$bla)7jk>K4MpaFwezcOBOFG0V zT~5{ZX7dsjfo4f4Xl)Mm6z_ItS-P`J)_l|T_Ld!koSqfm0em8W8JyM(*Fhz7d!d9d2`&T-|s>{R}Qj^{% zKpmw>@1UdnBp{@+rakuPQcqy+*<)I_kIn)IFZtLDK)Htk8!kU9CDwrbL=D&PHe9nP zsR(sW%h(+E7AIEVCxjR=3tcM296y3e1L0*#M29k~o~>R_*PECk#Is;AEO^WU#T!a$ z3*2`u>BLEsqyKiP^3Qs3u%aL`$@p`C-&YIz_j>ZrB=Vw#8*DfI`@X|{I+lNu8n7D7 zmng$qXYD0mLs(?>I|)HWJ*#m>O)54!%&wml!wnDz-_~IA{P52~%kb;Wj2E6$yD zEY0!6L|yaScg^XKj?LOrLHS4edNY5vS^hwZFyBs|9M|=1FOBLC{_P&xXz%A{d5Y1l zo7fxTji&UIPC?Mj(3pme@$>wlbzP60%I$%gKR#7H6jJA*Tjmj5{=WTW zuI@$4Q(MEL#aZD_ra=}D&sM1{I)o5W&f)WaioYkFU5BPr`}hTe&PTA|@`+Qw+S(*0 zr@eQ3m2M_QP!XqDuxK&ns>r<^*=S@;x`%?bh-0RtyE=O?KU|a37S=ru%>Ky89D%6M zw5k0kx^U)n?S(zZtpA(=?s@R8Z6FDt7cU{5TXqQOs2RV|xps6i?EF__`1XgPSMNgJ zXog!%bH&|S+>3q%?>i0>zyU&|(b9p=B!9USth`u5 zG!JvWd}RoNa|`uiU24kgsba3tJ=b6lx+J!T)H6(z8o&V{jOcE=LuhCoUYt&@_KKl7xx{cxG*kf7W!iBbg*3|OL#Y}5!E7*J1_Mg zyZ*n%{l3x-@NXiuNg<>|czv5kr<1$&{s=;f1mZ#sk09_c4mD59?ms(!|9RQ{IR6v& zq6~HF2rdI4Qb$Y`fT=Kp%m8$RfDRRSk^+8{2beMd6P2P+2p}>*x?&YQ82H-=fU0h( z6Ts?1;0Xmx6lVP1f78YuFctwO><2^wSjE}>fz={0fZx}FFV-Vp`hXQ&0KvVXPX!DX zsCwG~n1Fi?QZlz`p=kOqAOr(~%xiWHG1X@ROX4H&R)=t#ytOaV_m zjF#AB{2K*gv>-G($_o@_X^p*_K{}4Z+`lUyJP(YY-CQq*#x`P#J!REY>{vMb9WglT z1rX_l9^@x>C}HF84%pMt?aBjVFpQr9E!m^5E!oqPfdxBZ}VPWE9>3=yk`R5&bZUU-rpsd)Ni%ApC*l_5`WwX5uHPC zeMAXi*lW^Xsr5jKG=%<_LGjD}g*)QYqD-;$<9Tl_e z^pzT#Ko$#CqCntTh+-D1Qiw#e5Zl)sSwpfWOX1wJQkgW^^ zUW8nZCP0hXDBc39Qh_)@KxT!`2YsE;s=;ERb6`k$YCsl3(=H}dVC!DO?l^2 zu9%*Gf&(FHSqNw4NBqL*el~i~!iOCaSZxNpKNPxUxJHD;TtLR!00|7#$BHLED<-uSpcpnPNHMCegulms z%F2LG8hpLA4uJ(B4iKP|Bd`*}JedV1euf+nza?dW-ju!dRe+Z9VuY3$!K9Dj*v}xx zpDh{hx$bQLF*CvCCPpmk*6M@HkeK0jU=mT4PG)DDAT(0IPhin6N}eZe_@BXJ_=BtP z(=6bBr_ens5ZS3OviyF$I0F802g;(pj3(5FfhjSHI(zz0tqSGl zaC??w+i)>7PmEz(s=hDX2R5NMJ|5V&-mj*VdEFUeI|4C22&=q+UhMc~>@e-fxLQ=J z#eD@QgVx-x&F(!8&b!rd6^xmzwG9USW{KhJ)^7?mtbcIq{J1{YON==!0=WI*CNKKa z6t6dIpA>Ukhey!|4@37PZgL9uKFz*vOlGym zO2_V0RVDt|RWeG_M$}fMk5f5t?NCQAr@9TOU=xp4->6$-jzUc%k6)+JWMODC<<8X8kdprD6|qDy<`7^QsiC> zH|tyXGwyax6}i=G^z6*pb*C3<-sM%125Sm1rg|)O&d|3>^U6e6lETa6_^LUU5{yHh zqw<(BpE`}zJ=Jzkfq4jn!rBlXsM~g-MC^* zXd=YVe#TsO7!#}HRBc>T;Y1D3DdqWA{+mr;?wv(U{Hlq>*s2h?YD^g@tcxS*X>T@$ zt@fWXF3`C?(}G+@uaTFMO1!>?(CuDy-7)-M>LsN4Id0Wqhq9T6_grGljWpaRdZ*Xe zKcC_G+Gh`+Lb~i2K2^TWz?r#R5t!4f$k$kLmEZ3$;alZn=TPs9T_u#*-|_P&wxG3} zlvAT#h-ahsSdR8b9$+ek&IPJNb=3&t+;|2d+%@FleJkG|&0}`jNyde`Uf*Sdy0wcA zYfSug{VMQJ2J;WuLT-4o)c>-*!%Uzb9oJ+(-}7r*&g&z4qjNu8{uQ0~?XmWDgPM>_ zNSykdq;%JZ(L;J^T2sshW_yvj(MJ8MoR|`;p2e85hWt7sxCu~TyyX;&TXoljQ=kp= z`dNoMf>#z@T%XK%aOy`?^Xt>=`E0JO9bW7U^-$k;w`Ns{f&pAU7OY#dp3w!Kt?}GV ztz3UTg9+|b{}LyFfbqV|==Gqc(}kD-A>;6>X_?4w#_P+e!@fC0ruxjBsGkqBG(XSt zh<ac)BOkQXdzy9?41R(<$ihSq2nrJEEo`Yz_WiWA;ZPd$u zt@`MQ=y&E@?CDH&NQMN`DpEa1*?@f*LyZ%_>pLdB=B?mCf`ohvBomnclEPgSP(v(G z=)_(I8>9;P?lGbQk9=C#@+l5Ij_;_qMks**MGyZHyE8MTk`w{31 z_Mgzy{N$X>(ae}16v>31DB=%wt~o??T7hJ|<0CVTP*#zW#BWo<>2(POJC+wk@U_>U z<)q)ymZfr0ud!gg3?VP*#jvN5&1nf*GR-*5ELrvQ7H(g+!n#I04-Y z;{mqbDAkr-YVP=P6HrS&iY+m_K5wd@9f5e|OvN=@De}^vAl4UwFm6abaupGFw1kS& z8VoYLCN@NvgYkIe$j7;d!CR2#!~;k^#+y(d{gsPxR7xG5yF-qSHUXh81zQx}-M`q? zM^B2#R_(K0wrwzo$->zcVr3U2OWJ%=DgEPZd}J=3eUQ>-Sn%l#73V7g|9*aM+pV@1 zJ!m$cx>;uw9&5y8raXxqcy2FRg;q>h2+5_5z zkB^_-N#E41Xg{CeUb^|o%}w1k+dd|9QY^+VYF#{@_Ei7r;&Z*P+_SRVX&Loo8v|s- z8rj;k%*vGKe*O{H9-U6#vwLjtf3Q?`%!0RO3FuV3wQ*o${y2GffAsg(h#Mc`ckX}r zU-aTY#LaJ~?Q-ueh>IgDFj{rVp=43R-zQSUfRqmg+e5YSI`D2j zh9srnlDQ0$!D5gTnnCRWP3k29QkWi_=L?k~#?QB|-Mdi`kTrGQqSn`>GaIxLIslYr z1ebH75HKfGn`#y}icBvy_XRLDp}sL5cVP7%FjLC1NDNM9I}#h40DdTFUsyoIe}P6M8ra9t zpNM+N)t#B=wn}Ixgip%+H&TIsz3UPZo_zPq4m<>L<4U!DFpb_5wAI~2YEcTD)`>NT zHvW>riHo1N&neF%6>Iru4Q|GVw9u z$PWoypFf}dnYE+T?$y6+p?qz6=KiheS;np}XR_0;y!@M<6Rdsx@YpBKUW~mxgXTM9 zv-7~;zdN~zC?)vT=K=FDz-6xzL=nd?XPK~gb0L?fP-}~A)G|Q#eyo|+Z3D&W5%dSy zYr(?GUK>*ePs#%As}+O{8Y_;}D6Romv0j9wEf1N|Hxv5!`QU$oukgfy>CkfSur51T zErXX0yS4~a7z1j3dcs)R)qYnt|L{5AX_H^Q>JDO_dZTE{@QPlC{qY}1?fPa+)W8w7 zuenaO=R*k5S5nFBrLb?v(U+wSYy zcD?WS`}KOh9*P!omN{(_qQ6%jlG&1td8l#lT_W$o=>b~6*cP%HT2{xUjzrA0gw=T`x-}8C@ z^48zGJk-Xbd3(Q}c#!ue_u=73XZL=)u5zNM9Zkg8snueB{)%@% z%o#x0Egi(!6k75Ra$->u^AW!l)1F4MrFun zUH2@(-yb00&st?AK3)o-A{eldPQvi8J5dk|P!&RTF6yLHwWQlW;=;2t`#Mo|5&7&47 za_|<83*GZ@zj~U$^gsJ%?D89l^xs$LQ6h+;!c?kd|NL23pF`I5%jYAnpGSTcvWq~q za-kAUMja6)Gj4DjkpZ@zL7W?#73V8i`>WlaK4rbE@zrwJ&Cz4lZ#z8$COl^6U>zj7%+nt3U8gV+#EUuo38ReUGAXXZ`_Jbq2_gn+sz2?ITY{)RVbRIv zk9T^67<-2a_V!=@;+@)cDyfXId7^7qm%egM&$c0N_dLel5OJr)Z2}kJ%0iBg!!cX1xS*hJ5x<3=DR94o@$8irLl&sJ<1Ws{3lMMt+r&-KEGW z<24IHz8F6HyS_@~do0hZX2|!1yHa&Z#oOax~}-wLp$J2U{~STVk>I zBzS-EswbN|bGrPRhx{%~_+6ayyY$De1?S(I*AI1BD#l}()reJ_L`)wdHb`-J7P4YR zo_R3cMpQfn#^Uzs(S2|I@t5M*G6XxwlZbM~UyBwK(+5vh3WER=M_a^P5DqSu(?6@~ z&kmlLVBfEy98ZD2wG?U%pZZl~deK+Z(Zokcp&AQaqYpyIbcjh5E(arscOAUA{i;;| z$+>`+e*)yV^;2DUF8{egX%xixFY^ss3>amgPL3dMH;f9ccc-8Nd_cX90ola*`MLF< z{@j0W!A=`BQwWK+ZXPP!<;$0lQmYYx$?$ZdM*47%7ah5Ap`gvG{QgAXKWb51jflxb z0DF9gN$`=%(&teyl_f9ijPL~?K9+-3g@jrXtf3J8RDv|*>RNHGIF4P;qOMof4N|iX zQpew&{&Pi1BK{Law0>`uuv;O}fzPt7$Dfn8^%yNo1nGSY((haSIfQuNE{x@aWYJ-E zw%UtjO5aFDX0ivS2I!xQsB{{7I}x>O44KU>_&4|Per&~1NZ?vJXT+F@9)rh@0yw39 z`pjioBiw&XNZYpDq&VUnj<0?U#Bi$ejoz+(@MN-wulW$juFI19S*dYrF2z)$W8 z>yJK1<*x4S7TXUOShOfML9i#mHo*bh{4HF4r;YP>1)FWrJ35e#40w=_lsIN=nmQCp zTt-D77Dmv}nNWTb7m+|K4E8D9!bN4L2X1l-t-e7yTC<5y*${uvyTDQ`lLD28Ea{cf zZY6@1yA;E@bxA#}J|O%IJ|r{1hn`buG>EvGQnfQXjJ==V(VVY!Vj!IE>Di17mI_0F z=f$2kNDGj?7`>f>mj@ohls)2xKU%$I^v%77 zd-|?9s-SLuQ`}R(Jx}-a!Gneo!8}w~Gb(st+{1CTJ448&<O$T0Z55;-Rq<BYN%kaWNgV1jm zrUtBC?5e?`X93Aww9%!gBfVP(9O(!$|StY+{=E0EHWdh_}*m@$|qw z=kf}oijeL!q({gNvvj_V_iBx5zTwiwHPxuhv3w#IkzF*ZeqcGq_2jEO)xd6wfZ2g$ zQ3^tQkd8EQ*`8{rmME6<6K83Z?nPa_i~aJX*AJbdeKhZy9C*D|y~gz8JslWc;6pQ$yz9a`rl8EhA~} ztzYEr9+E$)*<(-Tx{P>nnl6xKoz4~|K;C)2dZS3V+_hN{ay^tHV3|4;Y_p@hNYQY(Z zZC^^?-TNT<`*GdX-~Bmn`^N{9Q))geKi~Fi)pU;Lwm(zSTlcB^c6!@*MqiY_GkDF) z7`>g{mC$K=YgDld=v)`@eFMH4%>E`|azZe>MpR0Y5L0IW?}yb9k?$du@X?*E%i#Ic=Fx>(2}e=4Z!)MtOOR~&o8LwN6F_#AfoXT9xT{?&6wr-;n}YUyT<=5?)f88-3OBjN|I zjXgx}$P$I>xCs4Q^|AJb1UcsyOE`&8tTwpl-1T@XV}4QOTwB^}`9RJ2^9-kZK%ZSY zY6VW_D_s}*LDDXRtxWgQ!(ktM!fs7}xc|fUG!VD;^T3A*?3aj+epbuH?v5i;0>*LM zpEZ3)q4A^JPaXc$zq5Z%ugsQuOMN@Ix#57UNjI}05l;~XQ{;j_vDUeQ$GZi#!Mny0k=~n(mUtv)$N_&4lE8uB6?ZOQ5&*H}d%E?9H z+6Cd!!@{+VgZ!LL0$%oM)7M{Z9=Q1sPTIHr6~O%|-Ek>^i<}SV0hJ0b;ed!n54=0o zie*62Y`z!rfD(;}>Ua$mwB4o${vBaumqBg}<+AHDNMqdHCb(A|pyDGu@Sy|tjFn2} zA1>W4`R8`?Tv6g#;D$lBn*4b3a$nVlk~frVHKo9{mYp@{p)Vmd$S5dv#dVYfpjVcr zDZBq2u|$pO<7tW%JE7ZU8F()3D1Lf8cim|5RtQeqRlXf?kRK~?0g8@;4g+WVk3gbN zz_Gj6?(Nx1E((ae3PfB5KD*+7Z`z`|31L?)avl)<*f1bHmmfZpKe_q_=7|Us`YW04 z8BmlTB?;1-0V#>_OdhzMgU)m**g2qh$`ot?(5{Lo{{+uYT=;zvwhPLK`W`2_>~9D;x{sFCn z*Cj$`3$U6dC@+QiQ;Oe`{oFV($K&TDZ;ySE{*#WuHPYepRY1gq@I%60NPZ})r+{ce z<=T6_D?8(sO|4O$mdLdHvaRUBy+r>$H$TTCN}HnLLcf#uN0T~k3y$ky3Byxfg$IyU zCE8CouY<}@qO|rVGZN1cJPP$Dth8nfgY@-}bY|5$9tzV{b^AeYQa^M*P+)9?5AaPO z5>~UdeIRv_zwS{(t4#|$KiTco1eRjXzm^5V@A?M&zRFzPYE9`m_IvSD&oZj>IlJ>` z%tM!*0p%8WAy%1c-F9%j~+B6?CsCk9$p zdVTGSs|^-N{0KW8MT49piQk8a@x7i%1*6@w^aU)DOqgiu3Y{Ub$U z2J8s$voEc)Z zG!u?@6q#FV`lxvsC-@mAko0`SPf=$dsunj?w2Z$2(cC76{vN2$vZgpM+8d6gm+;}0 zlELQs!$cVaUNSuOwxMk}$d_~~w<4ar6fQoq^`SS%_uOM|dvjI1EzcKU9sHhQ!pvdB z>9>uJ%Om%En@zxQ*xfybhXykEk!8<#9#%u*Xsv`}IHOJ0L(LKQY?qHEKExU%_R@s7 z@zFzrHjm~mW8Ej`f-x?ytqg_?O{*pQ9pb1j{ItfaIs8o3w#$ntr6T#njviYN2ZtMp zmt{DevhMIlrHSd^P^NO`5YY{&zB;-4>x-)|_rdi#=H*XREGM2Qu9{0gck zuM4H|&4NVF^36j13^MRwsT?xrdQMj=ksE2gcxa&_nS9FUVZOOjNU+ej#K(Z8-@paX zs@Pvw5^nE(uc6j@Gx7s`1)n48LE)(q@vXxHFAL%6K6AOJmRn%-yajWA1dOEVBgC)| z-}w725G<`$yVOQTx>Zl_(^Oy|C#y`|a#(wzbbt&qaSt@-g;gww&gP}tp=bC?+O)wV z@>rzi9Zzt#lqt0$A|km{e94T*QvX@NC4~q#o!Cms87V|bnV_3pt#8eAm)|0YUB>iQ zdbWTohZNI^iIvT`BOa?=fQ<(Ao?qBZvki0^EL)NfOFu)txs<;r_j9STqZnqqSZufE zE=+F$LOHtgF@bbr)nSg$ed3g|3j?m2DOD7R82Ho$m`aHh?y9I>A}V?`*7OTWe_HVh z$+P|)TcM#NTKO!SPwf&5OcsFErK5;tZA#RDS+yC`R1DX5JL<2;kfBx$z%+JpPRf`L z#~#+0I-O6tx2<22uFyvcNdLL?Io-#q*9Dn&*(ur3r?o!i6t3ZxUyDfeAWRay-Pl!x z^u!pg|5s(1%Cs|af}Jp3I&&AI-U}D4s$^18E;a_Yj>yo;&qMS{(0X(t5?e9N`e~KU z$EVA{HDZ=wv-r>&PrkXPoTZ-`olj?Hs4|NfCr8h&`|bo`En;h7i9vAWoS_najDZ*~ zZtxprg2~;9#5_sSnk>FK#s#k1B380F79H~F^826Lv-jkf`hfq$Dz_xHi+~2=8u6kT-dQv`l#8a%~R^Jx6 z$q+B%UabS^3R01MI2pf6YLxT9Of(9pF?s4ZXjWZ%}LLd}Rmkk5|JS4bv1Hb+M#ynbg#qW=K~2v=J=yNw~f0p>e%9#QVT3@X!HVLqDn|BM$7DJeqO zs>I6(f~}QhnASdY;}_6$ny)5L=IIVd(?MaZr(!EcM0D1XcNL2-lnKMjAq4+Q=9!oa5V1@P-ctc}<+1pw z_+6Wy`+aE7n>kEV!D5*}w*F$>jMdZ5yPMZv#xIg4+!bHjn*hGxfR3Lqt;y;kJ4Tw>Ht%Y_aNb|pct z1uAC-L=KuVR~`83nbxm8A1q$KdSPIWK#bh2*w<}_m&#$PMU2QVu(_xv25f}^s1TW* zQ_A@ZBMsa|lAQQm8~~1eh=u#`U}m?ah>wr_B@QjtXAj+g>(IWU9HAdten2>4@NW5F zMD}X1Z??gv>(IMUQ1GYs_^xuO@>}%fGe7PRuA5(VRD<+}o*)TXUavo(_j^&@?48NO zNCTw`_$u+WYySpvwXO^3w|?FB$9_2-hC6!QUOaO4a3JRWi?=W5LFT2K3pcJqk5)2v zt)0r)v%8F;Wv?n=#?~D)D-G+T+ze`TMDZ-zfSmk1sj$jk$cC4(5TwOq~VpfzQ>77g^eE(_1t=#Up$#nx_^c z039CNe`5p#83Dj;MOYt3jok~xg>aJ`DLBeE%+VcN-lbcmx*3)NT^j|}sf?x&g{VUI zw_1fN6~J%?Q#Vddw;r4~I5~OYWSGyX=(*zY{LM$r2ULC)hdI8~xfoSB7$v!IQh+$t zw5xC0`ot-pmsa`3V*cb` zyH@z1QHql@tw&*r5&aflD(FS9`}G34ocX`c48-CgeX)m|=l$XwnSD+VeSuL@%U!j^ zyoc|`Nnx%^LbCjkp%vUE7N%A|W=IrR;Xp(rZ)NVQm4a7&aXi5il2jyfRg2INMdY_W zEF->H)eVx%LP*to9h|QIgoN<^)tXKtm1WZt?{uY@$4nAeU^vP!mP@}{7jcF~CN7ZL zP~glKDbWw;pbLUFF~8*qYCRDR*N`R%kT8TizQAnjh8k-D=7<1^l+Pl zsU&*XR7huVPs7v3_rb_yOl69x?=U9p%}~u^d8~ z2+<+R06*krOp*fGyFr`&m)awp!>sZs@Xq>T#6LSWXOvS<@n zMRi&9OvzdIVmKFA<^Z?dCo#KVwDdbS>5T4X@dh5#q)oNY6Lw-mK%w{hX4bv)jo$Du zw!{2Qu#HK;mnoCU*GB(h{WPNk>&(*eaYr@YOn5~H#{;@`@BF`<@LzK#-5?r0ATyN0 zNF*5@co?023g=R2S}!oddsyM%M)fcQcP6DJ+PYU@&=h9T0JnGmqW+qo0$hL$PRb%4tLUU$7F|dXR8EB)g`ml6-h^r%^s~wI(E*y`Us!m7&5*K zp!P~}$ohpmn5NZ}-rgo$z|oL}gC=y4Rm4CHFt5fz%EsN77GN}~#u>*z!;Z(_IVH$p zf!0928UoZER#m2+VH@i0`<~D^ZXhhO_+8|A_MdXgjfAGl$>%$h%`k~($)IMjr!kwgM}OjJQbNd4{}GckKF|ZJo-qxl8QM+4DD-CoT8R zZM!*ddCQx3s~s&1r%6#(efX4}Ce7W)*7bpNJ>HV?V5?kOQ?#d)zQokQb(igj!SiUV zLT9VuXOA758>~yYb1vmhdy+>${c#$|^kjr&^M61B7;k*j{ujqqBb5ULFiCj?hmX!P z2w4Jj5iA*D}R4( zXX^O53v5(puZG5F-NMAq*u39$v}Pu`P_2 zR-wA8^zms3@n%f@b7d)D4$~rJ0fZrjW*4Y|2|MMyyN4rNm_~&W!^LX;r;iEyN2dJht7S8-w@}`eXJq1 zr!mbZJS=(JK+)WM2O)nr{zvYoAA;>mCEJt6O&`AL^RPG(t+XjJo8N-lbfHo=$lz$D z6NKh4P(;4kYpqifuL{bu_Ki@T-Ln>3pv?z3l>brhu+~$1!ws5Y@Y0Wa1*y8f%o@n#ZOa!KeoTor%Pk;Du z5>n=cVcUQ#rz*TBb^ZwSh82brF{X0EFbh(gZA#zr$Y#QZ2&@#6$CC+0+jrksH&%2} znR~IGpxL2rx7 z%`Ie$lPDiZnJxNsZ@bd#@QZdQ&>{%Uovcd%;-Vm3b4(}wP9XhGyRX!f))jtxR8%AT6D?#g@pi1TRo}4hoc`0EG$W4?PQo2b)0-H7& zast9vGBiXoq?JIsl0l##oId35nyX?~LilQi@(h6ENR5kR>$XXa6w2;r3?JYF6INQGo;R#wVJ!sVhzIv7B21>~f2N6`LuK9nF zwgW+K`nvS)Hr!_TfY#X0FChCxWDY}{t4Y4N5{~0vdmTblc!A^qJVL6h^!#tSi~#BG zx|NDl!bVbUPYhI{8W{@W$Jf7}%8mXcH{i{gAEUm2G7o5@Z$e}-{yw>**?Fvv30g%|%xY4rnInG3o;Aw#!x)fmjmE zqDY2ye~P7a)7hX-i-$uV^Zfx}rM%lEB-f@(N|JONv1LXb-N~m|u9R+_j&7Yl(D?^o zj5y122-K!x?fNLegbQnyZC555a{znAG+)9sQcTPXrhty^_rEi7R9=`WRzZX?mfnEMRu zlFTYaroSjvkglm^0?iu0SOTm2A*DJBR!LyQA(@qkPms)$I6WucxtewXrb7Y@i78oS z_b!=lne&IzAyB;6XsBCZ50eCJZYH zYjXEIkNNSuhcJ?{@{=v(1^Ic@$Tpl{=ATyARj4$FWryU9NNbT7i64^J>mf&;@s`yO zmwL4fdO-i94Tw~XVZf}6Uvo~)8PXa$h~%(n%eE@IE;o@AmtLJ#-?;GsCR?Ue1g*2z z_A%`B_^(>N(8%*;W6E6chiQAD`<}R%T}Dn9Y;D;s(=e zU$v#;uBwhrCTdlcJ;zea`YVrXq+&bQv(n|Z(trs!=E1D}oQ63ai>!_c&~mV;#x5;o zx;FPTtDo(}8td4d{qfl4)U(YuWc|ymdzw@`UPMblmZ43YV0gPI^~4QT z8^m!kn7w`LiN`ZdB8Spj-%QA?pSLA4!^+NF%FOS-roCZk{HnKUO0TW1N2`6x{*F!R zj)ZZi^-r|5qGvnPw#JP@9qCLDCvoY^$%tRhvd34~t%_}w+J1O0F`wXQX{#Unbb7nd zWahTmGLzElYc*5#BO7ZjtbC+@<7dJ7=PSw%I`@iOWAE3f+r|#K{MDBNNUB&0Q&e+g z2#pA_32dQ%XWM4s9m`k9)FI~EtZ)cj4z&%Uf9 zJ-5v$z!=&pVvAO@tct*yqIxw;!=J_hPL`^Cw!b2iscC6kTu(r{my0w_Y=#+p*O!$d zvLmy&PR%M&wH6iVDd{1ZP{)jluzq7%k8nEGwH4ZxIc;kC?%(=R1rz#$}HRvb67TsRG^Qy_D%9latlcC6*oOQ;OC+&zCD%h!$fsonv_xHR>ay~^Q=fL-q3?k#bHm&~|Oh?O>?Yjr5s_-Wn#6JSZa0Re0x;u{_+7&dZt=wMQ@=!bXxBy z#nVly7&>o+QM(tsu{Ub*IaW=&*Q*iON1#eny$6M>Hcc$%dK&#=5^QrT^l!dK+6~EJ zIF6^j6;Ij9r(6AZH_Q_FY+==SN9|#W!2A~t>D%kCmfgZI`30cSm2%k6_bi%mhS};} zFy4_w;Ib!=zh;;Prdcu3E=~gkM=AVzu)u^wEVhyQs+~Irq19T=BDu?avQts7_K!Ek zHWTL}2Lv95hvn-wxBwnE6f^Db$1XYUX~iB+1XKq+VQL(I7=8@WBDI6ciqkQh8wUh)EI%#Y<`>h{g2o=-c+K_o-11qS+tRCLm;vyLrAKrcLuD4B>vx<~KcRMg ztlym?v|!g^E>wGJQM~OjtcA7KN9kJk%fI#6Y7$L8)!(%AZ zej=X6HXzS;^f;B=K`pwo+-;x>s|etJ7BNQs(oBI>iCITlQH)NN!d5>f7hu+LmL7^1BWwOFpi!%&)sa!WT*idc}s2sEU# z9}}|%Qr8_%0bLxg5wdKVaF&FR%d$Pu6#DI)L)-cghm;soCH|=d&I83ijlXG^jHKXz zxl#^09zNQwvRrf_-}MgGKYx|C$c)OFg~v2{=PD*2gf7o^7T2)^A6SEhSYSSeqt@r$fw_O9FOBw^3d)b zcasKQ2=^`5o?Xp>?-IVn?218~Z9Xf7 z`TXI|A1ZoN7_~0O(+#|9n&B;QiA+e$Q52f}LN@vgTAO_ts$?3Cxz^F_tjc?fMd3`OWkzpD+eHq;s3{rvaML4tJkg6{Bc z72M^efKVye$uUJbUR(H4!T7iu_=Bq%k76BwPjSEh+-+eMaxR&j4KA4956N5@)5IWH4O!@Nr zUmu^R@h;T(nO;t|Uc8t`N=$(uJ2i2{K%cZ@!4O<(m~TUM}KS{PIBWRg8)ODCtLJ3+vO9Wb|GL;bMrK z8$^XOSi}QO^V9s3#CjGD{cC>{n}^&;L)2KHiaw$0-7bqZiei> zEFkISNW+n)nq>G~aZ|7q-X%ul&Z9g>nsx#x77w1+b4_~&5k8IIX8Um|b?q@DWX%WV z0BCIp5tYeMda&U5eg4yta;@X#OxSke$*s^dHz72LYl(6{js-NFHtU}L?gOT{N=V1y>njRsSo2~wIA!t4z`^2m9w0UXCe zsR_XX3|vh-2y%c9J+x)~aFievxkVp2%w96;CPj+a1N|!o2rVF+_s6qe-=7zAaXV+e z?|!%%{Nf6@h13A82Dbp2S&wTekp)m_RwDo z`KTiRr!y>8dTmH4HU#ZWv4I;rjcEaR)22T08nM+~wP==Yv?C4a2BCAH6K>LzY1U73 zB(o6;!kiSPWQXon&_IFt9NNbe$=VtV%Us$rYk~DL?-gzr!%pifZp0SX2sN2HpasK@ zq(^pYj~r7Vhe!7vg8_`Yx?LP2BV3L;cHtTOKYM@3DEK{2W5(uYD!NOq{<~pqXp3Uz zQklI2T}eQXS19EG=$(*5F%5_K&lRXg_DZq2b!MVR$aqMpSB`e)xx}Skh?HY?enmM8 zTv|CFZAMTbwhGiBIv8?D<&jR@nY}p8zbMDBB)IzhE~gfhe;Tp!JdnqR5%;ahaSks3 z*=lVPqnA&wZ7Xp=j%txB6%00pMD=>)y{N{Z&o#Z;{{<0pMY_*2yiidj6zE;yA_QzJ2vERnehk7LYJ#aY9?+ZkONt=bs~ z&sqV?Qb9kIqQ=|2RT#)2DF_TBoEfm+klGyyFZxS>gY z*Y&_4rb7R0ruVn9>r1VOy_r#M_HfK>Bq!K&s3OGw%41v8XbTC>-T;|akM~5`teA-n zmR!l=!y9Qh_6FoLIkkOCW7uOhjfNu?Vu~bY|0G&I5^gpR-F#uKO&Yol;?8EG(`c4% zwfIQJGP*>935O;~XpHoLqTr6sqJ?Ecm>dS$);g_(=i>eV%5G^pawm)u>Q*;2h2-UupgfNU9~oL*ceO^$tqUn6iw~g3Nh03q0VeuO{D8xP)kJGEN8}NN zDn8|R^kYQOFtVRP4&|e6)~WkQDH^Xd`axJbb9r_zQ_E&b!?Of0uG2|87rS*zClge{ zs48X2v|T`rjwq)HJ|^$G4kii~GNrSZ@047k(=kPYqNtsG15`}Gb=jFGQ>xyyeR@nS zQwec08k-5Axqy0m6tx|X|BnUF;*#U1@DY5c`f9{`A}W%pjPL?FuIL$Q`7MfnIX5ZYQXbXra~3Ftvqr(reK^yjZ&^>`lHihpB}F$TtnN+g-$m zaxgcUB|4za9X>u626r>iBkj_>Sew!>GhnOlZ=KS9YpSO`g@~3TM;XoSaGfzgDHE(( z=X})2aL<8g3};FQ0%2LT%L@FnOPmA;MQM=EGCqdZ+&)_KIaJ%od*J&{ybH?4nrgSPEK;_D>h|W{JC5{N0?nO|$ zbKScMgS-mnvH`<`*bZKcOqN6P(+X;C@->}kmx9Cn6jO$lZ4|6-O2eB`dRV5}!6c@g z-C<#om;Ou}Go_INPW_5OcpIb=j;kvrA#Cx4~IdW1$O$3zMppJ~6 zWEXz2HxH3HrP?l`Vm6mvt0lVgP~G_ChwnRZcgP$WB9qqslA)znOS~upIPb25t1>%e zZ<4R=m}sE9o$eUzP#qvBc}vuDC@3~91(KXSl9o28)$1{#b#D_3#C_^=?uiHw zMTE;mWMB%o&$#z^K=EsDjU*rI@4_;es!Id#hXC5@GWd{O|j?(k|EGx5+W_^nBz46EQlrLQIhrd=3T$#A;G&P=+ zjr9y8Lyok^lIPvf?hN9jjxGc#xYUH=K@QRBXKs#cq(LZ7Kj@+>+H zv`{{?yo~qtF2y~PJ>Ci+xP0tcf%E*Hv6d*!>cZE`k;D+lI+t-1Z$OQWqQ?GHV@Y#c zrbsO^VoD4mgoj$s!1wcQI?t*OpH@xo*q6tAv3(u6d5e~&!NvI6iI+T5%d{ghM9VAU z<5Rs(pNJ=9Q+};l->tjYJJ5+KtxsS7>AuloN;EM5M&+^SnHh0Q>Z8hrW>!rU0RXojzZ7aQwj zIc9+xK5WjJI-L&C8ay{VNfa5xZE)FgeRSrYk@J6&jPYRH_>pzn{pJSBV|vZERoOF-L;Kl;bT5`&#Y{(R935JYaQP(=+bH)&-TYs-Mu3oA`jg& zaUL$oPg3piG)ietbnJYRgfXQtvbL+7a;VRCU!&;~i!``4}zR@0VK- zml-&2Wu%Sq?B0%B(8BdHitJu_9!wp??Wfn{6x^$W{qF8(QtIq@>*v>*N9VUbxOwCEkA+uv!ydfyDG5dg(&sRwh4X5rx|)u_I(>o< zk&kxl>|i2R>@}C6%%*7t2wnQFXhiDzXIqbZJSjKP+=Bz-%W>63uMfDjo6kr@n#nV@ zMW*Kzw{w1ouvh{180F{4~ z$5LKd&+|~Gh!+GXlP>AG#urn+1Wndm3ow*z4Fg2lwkWuq)?$ez)~zxecE0muI;*X( zf(XM+4GwoxLt1Fd7YH{mFL>K`u%qU&c6sEU_EnyxA62wpw5TdyYftyUT32tjLK;yl zQ#&nsEqe$Cu>kynarIpoPJWLgxVChp#ah|+4s@P2M7)_-M~_Kd-{?Vu(QtAEWA?N#_uA6b z4!4W465g7r<%HuGRz(W-H@>_0d%o+(B(uIaIGn%lNb)4V;ZtpY(pkGPTOr1wH+?*$ z;i$96;^*%4J&WehRj2Q7_$y8>ec&euzGL>CWvPS%s-Jef3@};SH(C1rZ_f9v51!}z zIz(RE(FN*%Kc{)JiDH=x@7kIZDM1ptfV}S>_`bJ4ZYkeCxVNiV0{cv6YSc)P(+0e! z-ag%G#}-7PzqR)+I{#=y( zwP#Z9EPP^q5pE)mKs%BJ7U8W3PH*&ad$iX}jgpK*hp6wyJzY0#YAvzhP%kC^Z`BHm zk{$gYAjER>jJ~tsd}+sy(|SJ!ZhL_bvK-U4YGeW+NM+p3}Kg}R5HdqG>wX)2~(z?u5Bzz z9uVzP1(xbtWZ+A=1s3BA9>$$tPk1f%(BAq6qOF5)0VERT+fjbs3!99CbrW(NlO4)zgtN8nWJNFDVdauMZA=rL!AtxV|GhE_~`;_zPC{y!t z&~kx+=$&#%W54Y%gkllv8loD_6}hzmibB$Sfe2U81WTRUqDW`tOow+KLkn^MJ!1LR z%DnMzjNeAlbM>vZ`;sm5#;*4$)!PyM7A6R@!J>P@_j zL-o{V^%S1k0_5c?8v#*?F>1KR`TrHNUmNQD9PkN!ySdNX`D+?qmBH)Pbk67@7Rhc9 z1)mPSA>Pj#tD?#WknRoTrT=nIlV*wO{HM5QKtD#1T59 zu9bO-XoHRGubd0Jmu$4+TD~^tsZLQpf9)Rwq|4~Gl^$02nbK~oVoK7sZKNbF5w2y3^(ow{#iyx_8f$n1^Fa?bIf+I!z;r^9dW z{Pgn$<@?OK)x{nKb)(HsJ$g(V#Yn9&4BE2aS~>!u-6c%9r_W)`5nH7divVV7lOT9= zz~_?9f2JvcwR=M8k*Qk&xCaG>5&r; zK_7&^%Uw~g;zi(e?x?ZwA&a)6Ks940=^QV~hv|1DcE5h=tAE+-Uy zeJSIjPdcpcgrww}8~>`K6dFn@&n(*zq4Bo|!q(8>XDULEtC@Xg7VBo%R6l;^LA1+H zw%HMOt9-PoUZ6;Vc;e3ka7Ug!g`+%Ky)NX`%7pnR<=jg5F+P5te1qCz?@lXYzVC^< zL5jFk_4;ndTteXQ@$0#-hRe1kc%-KuTIIvaJHu%c?)y63^>4Dw@px)7`*`yZf4@>DkXD2DHa;B$(omB@9kz^4X zdvKEbNPjMEM`AS0EZ7iE2Nfy#1bfJ`0!1K#8j>tEh5x}}*m%dNsSOV`LPmIWn{pQ+ zEh0Gi!?2Wy=(0CW6qu5h4AmfT!!&R~qKH^xvRjNkB`9Z0fFm5_RMjqb7y5Ctpp%s_ zce!usmtF1u6Zuq&{5nK-EwLk``XQusAFt3dP^qCg`P}OK@Q(b5vHZxTd>*ABIwwC5 z%3B)M$1t!?9P|+dWJ`+WbKuU6z_0%qsqrve9ytCKnKk@>Jl%Ud(|!0q@XyZYnK_?l zjhxb)4@n!N5gDNoHKKG-OLQZ3e|Er}YL21O9FtU2DwS%6s8miVI@}|bRQJ8kI{NPS z`#v7uzxT)Xct3V}U)Sq;UU|V9k;@MwV4ww0K>rLZHv&-l0BWlYy_E+kkfFIej0+E$`&g2}L3J-O zP=C*%Rz^Tts{huAUKOLjeg!U`gsIaYT~c&9$&;W$oV9_1Tv*c_tdN1z2R)fG^x4cJ z@Nq$*I)A?kVhlp`Rez_>VVD|8ONKtc!~U0f@b!c!$9nfs9Z0eiV=Kjo0K}48VyKrC z9wTMH62IFQC^{d?f00J~E+rY2lD$fGV@mb2N)2mDjjxnyXC;S-{XJ6(4{%{Eyuxr! zS)2k^x*6+6DlAiBPVf+Q0JcnxiP!8J0TE>i&Dmk7Dxiu2)i7ntClPg0t8_H>go65J z0aM1n`EtqwgUUJEFj$3mHoiLYT(t>wwv5S1znmtG!b3pM0J z-q=7}NazzXc$^G4z`&KsfI=yf0Mfn=idL~#*vip03YZ2m?3%C$Op$iR9KDovG)^S# zbP3q>dKcanX=-##>2<6x=Gd(mWcEXrF%Qy7L6oUr%r}2mkZSZPh?0Ek(qY621?~W; zGW|gbY*#o)R?JVv;5i-!bKaVZ@s`*ugP? zDK9FM)x`5E`CfG=zGKpC^8erdhYy*RR*GZc42&-a6Tr9j0gwC}RCQn&agGXMYD_p4 zW;#aZJ&CZo0_e&P5O^36z}Bgc|M-p(a8RBadT@K?tM3?nDUyFB=f6Ra&www@sQs_1 z_NISK4M|f5M-`DE=L?QT#x_T1H_z1{&FG}*l0w(bAyVmiiQX+qu`OG&TXMi-W6=;U z4{KozkK;l17{gQNfOG{cC=KFgg!Uz&E$pCi>iljAf&d~4hEe)F#8wJIL)LAjK)EDD zQdR*$2EWg?(lo@l@>2y;N&YI1*)*zoL!g|JOxQ(L~fKqljZ2#yyk`4b3eSLv4#E> zV}*o9PWG4m50I(1{*oJ0J*vKdteK_$ezfqvtp8n2(*O$?x$y96+W2ak27X*I(?Qm} ztAkO8KY0@<9Notq5e6CIm#G`6_H`nvb>acnqaDjmgQmE2W<$r;hQ?)NnjsxL_~`;; z1_<2ISzWCeJ2+@Px)eHfB47rR`0XGQw4PWENr~v(Pl8)h1KwvJE=aUpSQPVo`0StA zmr{;iGI(^(N?Pz>7`1YX_YDur8F5;SyT_3J+Jn-|>1%TIA}(hX$#=d&ZSfTN&RCuM zV(V=2qUQw1D>rh1NvG5nK}&bch2V{uiOIOL|4v#9UaZhl|EB9`6U>mO6zzY|!*v$k7zi8gc@Fd(UI zXrcn3N&nVw_m&m~Xe;tERKTN|gN}X>JUy$!-UV%)UwpuuL{ps85u?{w> z4Yo6Hv!+WmOX#v^HXFZ$*v(n`cI4mK`SjK+lZ|2M;&xe{K!Nid25#hEE>~|RokxDH zB-Y5V7O!?-t8mX%h`)z!{#g^L0$4=~)T|u+UWWbo@-PZXtWgZ60zGP1wCO%xIZ2Vb z23mD0@AtO?{v51s4k%KbHCF&-yoz{L$yT1|&EjL!#AC$!NyOitr~f>X>@vg@NTFuZ zzgy^sKy;h;8%)vgmDJPdC=gc4kz9J3C*o>~yApRQB$*?rj zJIl$uvf*+!^|3k%bSnt+fZjc^$io!Y94VW}%z0OrD#{MXYlxJ?(Z4aiDvZ%og*d26 z<7M7UK~$08nkXYQ7)Rw`%3?8=aRWJ?jbSr2ncVWqVN@xA4JKiT4EUdKR)52U!8uDJ z+U~!5I+@edRC)fUj})Ups%z6$9%ij`kK((3foJm9EjVB^Ik;XD5^e^o8OCxHFtbZY z(J*%Z6KrVhlPJZLm$RsVepnkFWBBap{R3j-RL^}sMq~gwo?mGwhrsTxKZvk&DB(5( zMAa}-#URqJqi1|aUD~vIf962>iJSZdF=i}$zkB618 z$^ycev>w``;@I#T**y0|xEh|S1S*FSP-6^MGxKJP;m))iHa<)$EO*(CDNQXuL4Q;T zo{*8yaU{5agQ;YcQPs59HjqTA=8TS&4d?uI98KDeb(cX*6!0A-Ckg=UiOKTd;fY|m zLw5tplL8TeFcUgD`Rye4P)u+vWFycVHH;MvBexVyT?A20jJP2V;i3ZH#KB#pU~6R? zZuaASGAx`p*eMwyilViEBPs#nm}*n|?Xms7SdnyWJ#S~J&(R0Z<_;Z{cAd2NRcimv zWE9H*7)qhF{8^0k&Y4c+7#(v4n9IX!sbtt6@rWtL*cHn2)hqwGE7R!SJXkWh zQMSjfuH5+iHVUFPxUhH%!KFakGSdkP*vMJQKB#0*Hgc<~c&QTDLYMgR{!N#n1u|f( z!m2TQMa6})BLgr3U3l#HOYFH7r-E#Yh7;7uuo}+llkcG^4D7j;o41|Cq;A9&t2SH& zkueNx6Cd_7@%l`Rxb*JW+ z=wV2t9T|M%MTYJig)nBIt7D;64W9O+zyYZBGH8a=sQlo6Gx7ZX1DiTm-vz+Yuu6ZC z^HHh^nzju@v`GpMuDY<54B?Y|F*dV-=her~t(N`XTF!xE-O(?KeB5Q2J`DsP74fO$Vcd9U#9g%)tKMno!Yod8X zVgWfYdUZ|NfC&}#^V;RR;KgH{sNc{npU*2Yn)A~rHDx|T6Aagxqd2z*w{Pn-LRq;Z|-Bt zmJSQ*#rf82(X@mQ4S6I3RHE2u-K&sVx76o-HS1olty`HD&E}NXV+gi|lI|30V6kb+ zuxd|X;JRfIoD;r1g-Zr>e7IYOz>!;8n(AOg(_quGBXsV@2uX}cJW$r0HrvOx%-1@s zyXN;Fgeh0eQ|1yZ0*`S&B;G19Ta{-T^D*g8<+4qOhF)Nw+XuK(QY6gjT%3W&PL3u) zyxl47ms()9;?jvn9bYD@?&Z5%Ji55Mx8?eVzxYqDlvu2;i~FAT>fYX)j=kB)Z4Pxm zTs=wk%;OKklW;LG=fVZH>mGlVN89CYKKoWza*gH2+m zTPK9)Z&ONlh7_JM&EzMXI#)-9mKgCVv7uf|O1&M> zeb|6G&lis!T^}n1K{O1lF!g{GUa@hHiYjr@EfAM&71_MMPqK*(4?OVg<>gI=0&*}- z$6IBCsH`Ys=9x-Vmigxr<(B!Tg|2DH0;_}E+cz#1*Ebth?@S9VU2T0OsXQ#uE7|2q zNc{zz$~E-9u9LFd&1u&yudT=bdgb-nIs5DPt+IUUt0|3#1C8fapM1*@1n+8YEHkE^ zswX?xVG^}WS(URoYjR}$Z<6e#*8zY2r%q7jn;+$lAssR@&gN84MVRj?R>7FFj3Of1 zJ*N0n{z|@{@hBeE)q=iLos`G4j_C^&Cua(!^tu%8jOs6+GPEh$a<;%UaV{dy{zq(s z#4wXrmrosv@Y?_W^6MM>|GODhoO~qV7Q3@%d7IH$zu)kR1K*zHFCO^*;^f~4f4&`9 zJox+5>rIQA$n#pJ0|RHlQfjWVkXO_ZghtRLdh!P$b|VOsriG5xh(Uu}AnV{t-vcQ; zGv$^-m|gvj_yxGO=F$|vPE1Re3egO10qjpIr2*q-Wh!L`#o3eU*en90%T50(NmnqZ zgkxS8*u>2*?k!`pbgel8{9FRkI-=e@k$3e`#z@hocR}yAL{tPM&7>cc_Vy&opn9r$ z{Y-_wTU&S$cf3KrmZWjdq*!m~M&sKXuv+5!l8{cQ>GPCc$8LF1a+AnZ#KA7myn=$G zN6U_|iWdsi&PCvkRjp3PgGV2k%v6k4oOHF~=ZWs9+RG}>iIW|Yz1GB%S9|P`9%8on z=R0bKEcI1F*sg#c-*+lkviu<;Q;`cBr;y_h_|7DlkJQg)*&gK1FHEeyW-@;0N*(r)4o>hmlG-k94-LiP;uqzI zGfg=tJ?BnHk&4Myc!n27e@=HbenHvgAtHqcQQIR0ctcBUC`ozvAT7Y`ziMnK9%g6z zbg#$;{fDiq<0rSoUJ5D>rVwi6ioady^eUgi z@cXv+qb^>JI_o^3)%6+Lq#3b>xw8H6iNiUA*|kM13fx=`z+R0}Fs_QTpE`EL|CbHC zd+de=W&S7{Nr-*=P;OBZHXrdwu(?f-nuRFX*a+rs686bUU%riBvf?qZf&w)|_iXhb zK^$YpJ5PQ&Vwl_@aCd;}vq`hKvr_1Ylu#2`4AK*)B6k2bp zStcz`=&cn{(?<4yYj;O+TqJPnQU9)e7q7*KZU@%VH1U+o4|oPILF<5AjEUG9HHoL5 zPPM7n3C}h4>V({gS$RL_+SN^e9ABS?gbYHEiQ2iXikzbUK?GF+{$ZzEkqsXU7;o3+ z?^IFD4536CounfMsJMjoz@(4Tnu|#a-7DcJ$t=_WD1tAy7QkCu$pyi@jMn}=hc=vy zt&yz8>#3FG=zO|KNN!Wpu-N*QAubTTUMGbDCw7r>e&{!w8@t|6@5m)?3O|!ZF8p80 zm3ZePlS5nYZ~W`#eh4B{s28t*Xjdq5$K@WJGo)KN28+`KerE%rr0qW&WWtdjrpu>^qW3F^oWpM3x&Fhmx?ri=vuRAb{NnVaLk1kfB;;5n8!*jZA<9gKrsewU9Q_`IXfW zS`$+O`^>|jB(IpLuHp9nXYUXK?!fE7Z$+8iQ`jcMCFmkZ^m!r7H4;I%b@ZFGjt6VE zv9%3p8x8gwPS8og+(WI-RO+oYa@)ahB`TPN94Ydh&x!-0sa*QTF(eh z35s5mM)fU6-iLLmvsvUfDFG{DZ{QbqC(WE}d)$9yhn*I87JBm9V6I1G{Xc6A;=O7n zI`{83Vg!Y2ZjTDx#OOkm5N#uPkQ!h~ zF60Z~K5|L0jc|S-xN52XG(d*qV$J1!kKXb;yu0skpEQ6MfZc+Q3;YddTJ+3xWfF?3 z>eicEIj?p@EA9@kVDJC@l3MCJ>95Dz`%uX9QDIF*%a$WCo9lXDOMd1)dj9qDz=2*T zhLE5;jVGv}1~v-N`+~JcYPHw{dEhCtqUV(;WwrOQ71%V|O*1+8eF@4^iyyMY%s$^S z?TO{y)mwz7`>pfcM=d`EL@rLv{kLjui-D8myH?_xI>(Y{GV6;cV;a1fDyTWH9X4mY zMgol;JZ8hM?{PUA_V}m`_oyoe7!r6VpCVGF0Itg=Q)O7IvBLtK!#+ZN43fI!V_w$7qurL{KKI{tSE>YV!+?_^ z{DExQ^B$Ou2I<@bDcS=mh$%FcL-eX4b`+rrf2F-`S6C74sf(sK+$-AAHw(+mS0X z5zoK4uno*zob{(IykNa(UA}Ps+;hO5t*uE~QvO^3*$b;22L+I0GUT8o{%WmmJA6Av z=u0t;JEnm78HDjDG%0|P!3|~*3`xDO=P~1K48f)c=T{XxS8tZaFls<(4Fc%>wZV#j z=p8^1!;&*6a^XYx9p2Oh-NTPzxIqJI(txRp(y0v$kd%dRMNhN*d`P);&^a7jGRqXv zDdMwe*g@00?P!t1aG5Sw9N!A1fw|GL>#h}p1x@TV+q(=jn3zKE%1?OMu-pq@5iak2 zYzTj2oXbq4B^c%=vvFKfXS5-lJLtN~1is3oi9PPWd|hsYRJ0k)jo`w|p5!iWGek7J z?Q4u|{wb>Xt$?mmS@F&To*cl6D~p@%$(J97aRj_JK~|!rx2)1vA&e}5o-c-X=xQdi z^*o)bCfBeRbDhmeQWzgteAf!-04uLKLr{0oS}E-} zln;jNO0T5>H_o?H*m@?P9PZAXUO(2p?^&K(rdn7#boW8t;iQqH1vvm^&d91~IVWAVD^6@Y%;Dp_JT&u11r4LI(;Wf-P7& zR~;~nG@|4?laTyYVaen@TGXhOUirV!k~|v$PIh?kBM9rb&}iT6Z>hU59r3*S+_Lz! zU%ehURhESJUG1V`#y&7j=z>382Gu~p7a2g7H3+2Tgsw8oTOfB3z^m6?o8iFsJNaG@ zG!b>IG&3BR0ON9}m8k`JgP`Sf5!U4RTI`v{ye=P8CRY39cmZ{!TC>kB9_lo9+|3zc zbvlpBLq=6LZXbp}S1xJSXqXhS10SLXLNzBIPr8zxX>N^};OR}=;`Wl0(Y09>D=o*8 zlcU$)8J$zRa(bb$U5DTbFxU9vZ_e>cc87iW0DM6!Zu6~tp2IC_NB%Gj2Nd8e?enEl z6o!PQoE~hV;z6c;8sL%wsIP+mc>;)D(iTksnIatbl2+M_tc`k{{xfp3RiPmRYSD?N z`orw_g-aQ*z~Ln)=L*MO9A8R-=8u%wsYOPuLS|;2#B`!Ec`{*H^wHKDdE45LO_Q}3 zCy(||9(y=>{N-fbm&p?kCl}{*r|MJhH(vqBh7@g2Sl8`}P{Gyrk89h@#kY*sbZ)3j zY2$>HR;Hb=y!Zsxx(>Rj2g0uvUv@Frd|Q@mdw)k1JSUc^t-gBpEwn3FFQ%s3ZmvgE zDbIbmA$s`Ha-HTcfLS%fNOJugx<>jP=eTY1ZhzdYvH1pn(cB%ckYJ28|WZU$#s z<5CpYwW;ekLL?ob4IT|%5YO|3S3AUqnoP}_j7fN*!Bap_4N^Rx8*>}ZjxbS44OqT_ zxVc~qvaIL*lg}&9EZ*#woT_a*oPGJxIzw~x$t7VaogbSfYBi< z6*Ri{c}}^>+a{B@PakHePrBRNMme`P7mcQT(1Hy?ahM(q+Bsi8Mi0y_oHd>F}2 zE4l&-``uJtEt}t^jpi6V!d)S`HLHBTzF38vMP1?%GQBNcL2**W=6X@?)jL@BHKHcU zp90^_!Gy2s~3j901l@ZycHR@+t|C zgI9LgWLrX3FzME>k`E?qa;_CW_A81AHPoQ4o@I?(3Bsg*$;$JMW9`URUL#iRe|SUQ zHZCka3PGvN50G6cPj3o93%spgr`>8=u~u%x7Omt!UFfhCnAyy#*I9oyM+`}Z%D` zMQ`Ob;pe-(GUwNgf!qIMzAmOfH}3&dU*P1%*QZ+M+Z^L@TiQ__U*F-O3IT%>@A&E2uQ1<(5qGwzC=h& zg0&BQo$K3IdecoZATR!5+rY8(Pty2&PONm0@%QAF!$}J zJhz2YAq&3zYH?ld**GcK)bf7H*C>4g(DE#$XqHi`1vat<wg)SRJhhd;hTZ2 z(?kRhlyY}fp)W?iec-3(5cfhFGj`E4)c~1Nb?^(v!nD+LSqYj8w_<~f*S5HGyZ~?X zKrml`luAeIK?vutTI#Oe?r#2cjOJ_6k5n6tj8`j2PIKUD(Ld!I8+EI(ZHk>yW=QM3 z&Nk(SITf#r=0MwjL0S40d$!|N4QtBDbthib%VRtcm<}7~&VZb>{%KNA)6Bq5ihBK+tHe_vmxzO}yJ% z2LeUt!T~taJt&}=sQ3`M{>#Ju?Z1n}kIxuyO{8ecsb{~#gQZaADLA5C98hJ-VZ+Ju zqA&>*<+-t|^r&uZ{p))@>C+#L=}U)hyJ<;wo3fAI(+;#)IL1&Z(rco14?(qTX1=qI z{~fr=XZ5$*;k^VNh*kIO`}WB!!Rb&nMCxWfzJl!d8D~!K5`V`!e84RWFZ}y8&ic0D z+SLowOb(!H3ZisRBilHG>|!xtJ|Ygo$C;v9aqe=hoXnB2Fsz^xAc;n zj`|LoZm$p2mWi~zWv4n!V~6F`vguBo*f>zOD6cw9;I7zwB;!8>g8x(m^9FE=fE}OL ztyBq$eB(83>52o@bnEYxNSZvZ6^pJ=vz;zYU9ItLr1M&0Nt9 zhA?O$BvppXz5MgqRvq}R53p@uOSJG^JX|}|e)|4`a$rw{#^sS8+88|Gj~ouzVsoqQ zFhvR`djqjG8`dAP4skpg>O1`+^lTcHk7W*Rg8F*TX_iSty<3x_ z-C?1=Z_Jxs=AQ>@+Mc(e4xV0m!n|?S;HBQDHC(d}z73A;18jbM)5A$JlE4tzzAIx6 z=Gyb~j`~4Y@u0q3cxFm2RikjT1&daOqdEgWzYP3LdO5ho+gY>(QO3lFt# zuW@A$HM!S#Q(Uz--@^M`M3=U`x)ggRwj;a0t$CZFZRnm;J~j1;L0988wrqnP2|8-J zJ8deo(5WD<(D3;k)}e&&&aZ}QJ@)?l?z_v}aKq|y$J8IL^W$ynFYJ2%!)@ndpR;}J zJpPSU4|kXgW?~y zW*8X9NU4Pc_b!qMUjwcyq>IpFh3=`~5|M{b3MbdYxCywgXV!Pg>PUR{cdP1zLNDu@ zrsG0FSR8%|~e` zahQk~%wPyocadR3YC6-;89F*)*$uxu3vr8^PN&zoST_OqW^D20gPOUtl^+UW4&gJP8mvA|4TiG2Q z&!@SoH`%FyA`khyhFRKk@I@$U$`jV_{INJu>HM4$UQ+|X`Ote1COLHFx%zD;yRKRW z@R02Of~Ea>8*)0*$748zi)y(v?bbtPfVY$f*Ti;dL2 zN1zcWHR>?5ARL~5851EFt{ZvsoHl#nH-0UWE`^{+5^I(+h^Ull0X}V!F1j$J@t6l8 zr6HsmqX}zgjpTxlkoB4r^7r}vvLuOY`YgA%>?3R*I~NN*X}@r`U~SG!nrk%V(02tn z+_26{GoC+R0OCBWZ$qdFxkwvG%BFJG*Yld~ITD#xOG=}y1Fz8j2e@BTpVcy!u5$fI zB}K?VJ-hG%yFw6dJj{U&ed|E#5_CVVVSUx*6?h-?)8>MW2pfhl`W^$CO@ZFYlv&`) z&R4Vy9gVI{gqjaAV9q&*!+g*p6EzP-?<^)hNHpqf1zc9r$O=cD5GwgX^(`N3=Yga? zH``om6k2*fW^-?wclc&qg|eZE0`=qqL@Z;2fd=$kq;|5Pe6&y#2FgWN>;wxblPen4 zZWcr9$Om{!^kv9GqY5!DLM_mOGEufUp+~dj04A8nM)3vY__-G7+?7D>xX~?fvJ}G1 zq$|oMk|T>_k@|wf;dSSmtON9s@&+TS{Yud6(z!idrSS29(8$Ln${odzLV znjuxcuHiH%HPn7dZ*Y_Kg;Q$}*hMzh)+9gw*G7*nFrAl)vGV-djlZ||x9U*d`LLi` zrjq@|X}Th5a`H*#VCWs=MUTWoR2&71dv!v46(Fvsp(ueZ{PQuWwK)hz~D0HN7RT(UDgVLZ{05Jm~G z<10jW)l8GAImU`^ZQgj1`dJexUXjsX6ftGDEW_p^cl=`X$d$~{coc2L3s}@rhC4$ynA-A$&T+V+ZFxPiFAOm z)phT(z44cw;br60-`jbGv)>gu6R#lb;%6%za+KNJRu=8rqm^L`AhC`E{ocOby=8v` z+Gu#@YbN9-e4_MV+xbHnQ%%lH`&o9p+I-5FnID|#7f$8IG(%@w@qp@(po5P`0oAs`)ZOAO}8ECXn_~-mZs!X+MWcy)1^^f4na&XC^cCwS^|kCJ1u} zh`+{r@fDfhzOQlrFKIfedO54>#8m~N#KLE~z8}BS9KEN`F+Nbc6$FSBE%_+!eZ-by zwP=irc$@Slo`T#WOR3(7q>n=&e(Wn7-<8N*-`qw}Hdy%RdUS-UzX(=eWFd}~!!>1@r^KF1GUTMs$wCIe8AqC;3i=-DSDe71N z@w3I?{Et zZ0DVJV=-Ohi4oXiQkk85XBV*V;*b}{x3%>=ggZG6@j=*ob14#Z~& zP~!uvOdwdrVx}LFQ>NofO80X^gOXTCIwS6-!5NA8pyZM9zDC<*1lhKa;-Dl~gNEuJ zDxG202I8Lv*yT)c>LHej7e2mBO09x2>!+v7v`k=T zb8C}znbr!SK?TIY0jiY=^J<4AB>CCwYg%0uciM6>ATC#N@cMJRy4mBL`~xWfj9mq5YWOFN#hT`9bETn@1nPSugpuui9TMquXqF6hK%0U+~Gr`>{5>a<3rc(@K-w{g{ z8LoW@Ud%s}MjqKq)>r9z<}FztqNG+cplXPPkACR0{_PKQH})wnb?3h9Q5Z{M4k`Zj z(q7sS=-{MW(Na~?7Z5ME+NfeLJ_>WA-PMF2#HQJfRUW0;|oTlWBExU7@ z1lJ4tWKCQ1qLxMhC+IcJ4mB{I5r=~PO~=CGKvu=Tu>f$VANCXn*f-a6y)+>7z8Pm0 zp1P&q94=^#EP=gaYI79u5JvRiqIGLZO||W$QTiw%g|j~Twe5kI=VffY%pQuvpm!Uv zWL%jyncFx$C=N9=M$b@Fdhwc`9~$QAz{Khjjp=JIaSRVVMlboSjL+dJpCzQWLp(VU zPX`gbvzO8ebwGnIc%`$0ADY)9UOTt0-ZZj$cI%e8y(z^=E@NPvIVCCXj!}+}_Za9s z`D63MxYTC8r+kb{9!qCljNfo6_2_8MhB4JpS7=FI96?8R6wMK?o^7RuY$&w@sdPbP zUSo#)wr9MP5%e{k6sCQM(pdM{MNRwC2lAp%vLT&YlJi)z*21&9h%W8b8(NB|n^s3W zE>YyhOZ={+_$}YL$W4_9d@_3-(IR)s9Hpt3QvHT92+W1I)|=03#mueawdT3ErKRA{ zy)-v_7x&#ThIEWc1X-VRl(gGZU(loDJ0C2iDes4FH%4oH2svJA$!t2PT&nh?_B|kE z$7k1oG$W()F`zF(`7LC-u2>v%&u9%*{EyeE4s%?EHR2zJAY>2G?9XxhV@1B3`AjM4 zswvUfN0vG?ZL(2-e+LpNGkFR2$`boo8RUgk(@TVnS0@v%22CiH*oq!KK9RhjYbD%R zPqn-Gbw>>+Dw5vTNPH(9sn3rt)iMmDaTzqOox$gg9fIO`%qA*nlW~;LqDR~MKp2ff zJ}+1#&xdZJ#6?=jj~-+Ub^LLV z&`zKKSjd>$q@7#Yq7q8(yS%miOF1Ea#YX)aQ4 zfk~@ntZ4-agQO+Mb;LL1B0(MTz4Ye9nP*kzsdT&x1_x`M6w(=MZkhHFchz;4!Ff7n z=}gV62P{)(DkRk69m6Z29TW8lBcvTLO0 zbsEznMv*Jk{*_(|Y#~vMCQiiA#l;j+@7FXG9{(Qtif035_Av6fSmazq81Q>jqD+-$~2B} z*tFCzQ(#DcyYPG%^8C!=pZ_9Xo_XIH1Z!8&xS%$?2kQyJr0Y%l%J+0O1j6$Di zg3Ee1*d#yOr>A4miJI?Gi~~fgz05FYxfbjGc3XyS+n% z?(dWpyytk0tjo>Ag!rw96T~dsbL{N3xJ!y{-Lqu*a$u7)u&y#Iy;UduBlNE{Ef5Yr z{E?qh>@Tmh{0$G;Vu0cS5h)S$`B%GIQQ>U^!W;v(&z&sY&E{7I))@BfPfz`zibT<3kJwZv(nbFyWoW37cZ5SBk$aUb&+{;NogS`~dn)_+=7d z+j{~w7VBH80vr?w^QRz2m$?G;Ux9|@Y=Khl_RSp?k3(G_#jh(c?(z zaeN2$Oz{sdN*5=dkAAf5&hY_Mx-;5A0o9z8s{;9Sx$P=B#yG|T*bGM(p72?>{k|B} zbd+kttPN#Zq?4gJ_%$@vX|kd8yFx_7%&N>AZ>I_x*n@0~*zb4o{TOqHk*TgE#K0|bdYT)Tu*+M>Q z9DqPWkov!4y!1Hk28rO@Et3_6Ns?AYp_)-ClS9KiSP-8&r2kyrkT>W*W#OBh@WBA zoxTYs>=;w4>wJ_IP`(||qCI}a##QOB%{+9nn8#ffV(6mo$0srDXZ_%5@aR6al1y;t0Igt^2`U~DhlAnz) zC=8*%7dPzLw}2c1Cq6(at|eM5=rVfAt7yMpSp!$}?itxA&C^R5F@7gr7oWpOA6RYM z91q+d?&&-Z`90jDS5ormGi3Q3zNPo@9kzm!e)WCmy{xzrgbmZ;cQGQp1kw5gAShFN zA?5d;K$;-5)KH@@JyX+j<3k%Bpb0IXvI1|1jFAqLpJrRNmw&WU>ZS>(3t11?Pn!OM zoO(TUW&`xKcPK4KcoC&c^a4k1{QS2?U4G&C2)NfBYS|UQq;W?(aN8zxp#M%V4SbHm z9&glZ=8cVq-0!n{%&5N&hL}zsja~Uc7VrjGt4sy^|6=aItCL?ypthdIw&R)0#@X3- z78yw0ENxwgPo}>fJ@4>;N@@kfqCFGdm1(Hn+Lg4>zuvI8=(Ud8YV9NgOM!SsLf9f0 zWrx3Ylc#5~pLYuA;UKhV>ZRiS;F(>-E`L!R-nx34Cm2L?dxy%^uj*=D%PbxFzN%?nTn;|TK1n!ulH*Giqu~7G#`i7`a(BZmU&`wa-~h? zwbMxDQn4z8t@!$D>n$PdW`H zm{Y^lsvfR=m9<|j`~9G$raO~d08my$#9iz-@PRsbj{3qVa&?Ku3c^;bVaT z#ZE_d#b5jD!>fxc{C97<`8Ncm?^DfB=*`z&8r@yJ=SBbjl|mP_)`+|0ilEmJf^#~0 zIyZgW*vasd(bsD;c04+lFi`b7cBmL<=rH^-!M4y!`^K^aCr$C77*F<9)KQ@Z)9BU~bd59_sDyOYQ4~>_JYVNE|F^VnOt5$Yw#Z zrq(9h8e@)(tWA5;c*@Ds+hsB_Q4_U<1v~H+x}K)3O?f}NIEoU(eLEPK zVAIz6Zg!3Yel?7CYR@W%2AgwbzD-3VI%>J3Pr&}6QVOU$W?FzTKu46>r?ZgoS``cvXw)1U->g#xrP$; zIrXuaZ7iXAf5>U=%V*uM9vxQCfsW))T|n~H=TjGE%BjXSDKaelW2X$uekg+yI0tN~ zMu~$=lqUBIK^?2hgyzSd7)+pPBCi=`$y?NkM~ETp1etE}Lkc4H1fw_FWT%X(AIR_0 zE7{(0AW^b(3#Ug++OpsdPhLlN%O%l^EydV74>g%MKX$!jn|_c?&zCBJMDhQdu}2Kd z&)lUSOC(i03K9NYn?#?KLDPA^6Bo`VL(V>)DRR2ceW9R~7dziIpI0ei(cGQ_2$9b0 zoaFABe0e0{P}apM*De4THm+Z58DcTwO==1FvyAwJdZYKZ=8NZJ65$ z#`G6g9LaC|Un943Xj0>Y|N6l#65lmIP>y}_9o~I`VPs8mT8MU}rGUgPSd6zeBT>o_ z68}YBBcfatjO`Ciw6HXn&B45|s= zgu{Kj8w}rBCywCeieg;tu+wNQl;%S;)FjEJP$L{P;6(*j5O81!-+Ie!z zA?YTNy;9a=yD7-i`a^IL_m*QJD7L4paV_(j@b9K$BbWJ^tl?Ap7l&KN67?)~))qe^ zPu!6&%T6$A<`{KoAf&7>7vn6|)br*M@U6u!9eq;zovWPCk(Txaw!lu*&{dpyh|(x| z&NAMiDCXWRQWU#-X9sKV)RiU%zKEfu73(d(@#9NJX!?uY0+XlzC_il8Ysx-AWB{z- zvcrP(fA`iu8JLQrq_&pDqDLnnfHBL}Qmx4S<4)3CpRP^52S%`2$8ZTpD6`9YNO?6i z^X4BUtkXx4P1bJF$6;ZF5)=fB-Z<^MkINQqQ<^8H&^OOG%;ysF7X^s(flYlUNSs8g^5P-PL;f$y`7C!0_A?uUNV%oV_&>Co2{M-R$ zUXe()l=|BSb|AS94fr=*F1mx^NP-%ozma>9bb$T;lpWPrM&W!XQ#|&;QdvMi0|InxCEeGaemJ3i)m$Onc?c0$9 z*%RSkzFb-}`krp>jG@!NB6or{d;i{_H(;J(I&jQ{bsI(xtxWVj-8mZOoRA4{8 z(L^~IumULv@OvT9Wh4Z;1%?$S9Q(7h$q?&OC>5DWStf~lZpG@~N9}Hs3H93TywFby z1EepY2{mHFW78$hk9h@q!|%R~-%U^%d_h7?=kI*EqoK3-OIhe#h0qfAQ0F z;!8g9jhy&iP5eOD`oh=xF4y|aA)X3}+)41&`Etr@*g18#JfqlY%Z5-`AJ53QLzh<%ET+p) zXFvSB16=5?M=N^JSu$8F9Wn^9X7dT%mImT_v$LUwjuhlR6>4?_nM8s9yPI^Wp!#fJBfu%u8s3Dn$ywHZ=MbLEr{i;YXM)nx#_uMlj zQ`hi+-jdrM|7d%6xC;xN3p_+P^U<#PuDkEc7k}jT*FW0#I6L&GIou`_VI%8^N|KfT zNk`eINCj+|qJJ#FRt=I4E!U@&8nuG0cjhrhJossbc{kJWm&~j^)%Xt2IGAZNn?R~c zMjlN3{?Yjh%}GCB8NH>Hbe@8Amg&m>hoW=wXZri&`0n>H_qn#Y&VBAg+1x@?bDv0a zm&ig=NxNY#)kH-}LoSJ$sEBGVm3s>nx~-xlmF~KI{r3A8K9BP`pU-)p*X#MLL;YiF z{$=8pI4Fip-H`}hJKheKyws>=YQ7<=!1^BcG95LDXnH0hgAfIy>J3p}Ovd2)V>N^n zygCtd5(xHYkqsz#`3UZSwMqfNAyUM(Vrt}OD)Fg$@xgdA7H%j;nU$&HIF-MRsM{Jq zK2;0ujL|&F)a(jYlK^$pW3=X&S|_R6?8}dRIFKvy2zv|H3;=sZ!`sGaY~z?EX5xIm z5{HSp*?sO#M97;!m>E;+M#{#keVWn^%p;1CEobf$Kv6(M7f9mXbm+kQoUhxd%$INc z5UhQ7$#iF@PocT(t04@s|4oas`Jr!{;^J-~{1h`p7DvAMmf8EA$nyKJVu4JCK|X|# zTEDKv1B`zvo3e}yFyqo1CMSe~X`v`^)36e%LMjtELctVMcsWdL25|;u48K;f*@38D zeK}%95>X=~oldZ>ZIJJ*5Frzp1EA+q@xDy>ZVon!0yQJi_7k9wDA+`Q%qp{BM25OT z(C!zx#fealL|FZ+n9{ZvD2JdVib4y()=I795dpS-3ENn%WYx?q7GXmkdfpV(KQe>a z?hSUmYPBjtjj(m1A41-g!rekJK@@ot6lR|s@Jocze~9jsA?4VZ1Cqc9C=#TG{0pEh zBp`#>As0p1IVMabQJlAly#DY{??YHGCFE+Y+9On}{|UtdOqC!YVr@$nELDVBCGc_p z$Tz9jK?!VC7EwZgX+82GI>x?0Y$_=+H;@dPSztL?aW0SSlkfJZ1L1~9%kJZT0YBmc z9TS2d`5{Rhnvs%Pdt)WSL}!tMZ_K~6+dcq*N{zLmi5Nm7$Ou!_@d(eO84eo#sa~;>Oxs{`ORifpZ7+GWia`F+D<{o0Yq{D0M@FsElkjn_T;2hX9jI;_c(=!5V93tC6r97C*P*?4eJ>SKVjKyRG#Dy>TcSDAE^(s zBZPNg>eu%~CYK~$WWa!^`MR_;iPt^=Z02ME%}IaFUgNT1_TGr=Hg&e~DaL37Q4J9T zo4XjdM`NG+HL!C!yK+kc$0;X&U(O$408yI{bMg(bBrY%8WnMAB2=*~<@P>~&UNea*Z*-z z2mam3Xu5ph^YuS~u7CXd*H<;HAvtV#9L%g4@M)hl&WU+E#p$O9>+>siq!Z6!h8+F) zgp~|=rB7!!M^zoDXeC<8aLVU&IvUEvMM`+83Lbde=VZ}XiUp(gBG)k2eoj~x{FP|qnaFDhBqrO+quJ_MY*8kG z??&P23E(U?>JcUerH(XoXo;0DN3W`-GFt?;dF_sEjycDa1{zmaj{&>M>z%=@DV?zx z{1pH;=;b~8uzcNL^9*MQo(;5T9!Cp+e|-uPDk1ti3pe~Kr_TBwoEgbF2KV78e)Hyp z5XM?!@D%-DK3i1|)M~{N!KS7=H?}_H?1_Uj%knJ;;snH&!O|p#1&2v!IG2C%X1}{Hi6culp=6 z>{v$G#vmVkcYYQGOH@+4BC9H_+fv9;{+R(Y6REw4!A4z<4rLVz^Wj%7t5Bu?HBvDQ zMcd%oEp6TE+`1F*D^!;|^?fhz$`mxl5a*)FUhqCdu!v@2TRq&@eA~BX;a5!a@0PX7 znmrh7Vz<`r7!nhRwGx%Bb+-bG62Aqymng5Euhs3Plxq^vX3QSL8<#%(zGT4s0u%7U z^kI(xMj^i-su2bmb4oFLz8NcF8`EKLE~`da&#E6q6;M2=w5x;zVM$+69@58>7~tjmnibfKuV-8K|G6G< zss^r)uJHJV>DH261dko)K5H&=6+QK#o~l1+ZcCB>%0ND@@44z)_w_eMQC~2+L{bT~ zN)?e(@^RJP-(rD^2e_!+6xfKYE;L5TmPpKzPzss25gF|6e$^CZ^`%s0V<0L+05>dC z^^F;i1^&u?Rb>uRWGZW9CX_;RmDD*9yO)2}<#r4=opybyX8#wiVhyKfFyQZC`gEMz zB}ol?tff!rz&SpAx_f7DLUj+yg8*!iK(cbdC>fyD_0rn|Jw?4kMb~?7x^nyzdT%eo zc8e~oWr((|s$%bUg*7@t9Vt-3LK5*ktn&_Zi4hu-e+vcEOKT6)Ll~ZhhS$j8SxhVC z?h7-QZ-p3xjxI)x+?fdVi6GA>{i`1Q3AzJ4Bt@R(nP%UKG)4a>Q%`Y0>x<6qa+}=I z=%}|LH0Tc7kPYJY)>_`2+VF3Rx?$S;(6ryp>41OJfg2u%9(ovY^WpZJ3T3(Vv;{V* zxj(ES^j2!=gPhVmT;BQgaLnBpVFF08fJxt1lvf;@L&;4V3TrXq;~F`F?csPlFKn@3 z$a`SP?+JveMbtYg6GFY9OYu1nd`#V1 zY3_?(XZ-?N@NR>a^d^yNb>%IJvQ za@J=`RH__V@CiAM$8PiICZ0?*kk=OwCQ*dWM@&uIm=?W$hTu+iliBt}S^X-(*bD8+ z{jo#8>uJ%gMb4k6NZ*jBy3ecrvrhp7@dS|Z{-vgkKokHd&Ra4dT)uGYy~+OfngpY( zdGCjBEsy`V{9xmUhj|}nZ+&?7--nkQKQ82be0S^PhyRv?m4R;#)weE_47P++^>PPG z$Ci|DPK}KrYA?hykuVPYq*%@W<^9~*g1@qfIVH1@T2&$YQIP1%faI__=qCF1*jmBJ znD6tkV#S;LzIx;bj-Difie<7(B31twr9}2436^-R4YLiXmpVEzPf;jNgDHG`Rr=p* z+2Lbl(bK1Hy*s<(d9dy82KP_xdcaE?jnJawDwI!6?!VD&ppYOZSA*~(z>T%P58VGf zJp6C=_P=Lq|6aQPw{ZBscenrRIrj%m0f?XfZMyv%sLv@-kPqZq#fg&yn-=x9BC^yA zqh@CRT|d7u%rf9Y?8D;FHmwemt??@?*zSsJ+4DY@%8fBTrK-Co1Hf;ao}I_dNi0t{ z9;t50nv`7iRRUvcx8-<*T?`$szk5W>VP}gEBA`@LDGbH4^}}-$s7+OIAbvSvF0=dP-S9bO;O_MluN^jXLjGZfKRI77@y9| z_Ba(;bKv7}(z(35*R;W38z{-O1*atg<^AUYqxK(EZT!nNOERDq336&cqwxWQP4GE^ zO>=GCQU8<+jWxw7EiIQuQZ8P)h1%76sX#>asOk))HuFyl*_3SMkoWrKD}-f2z2A8* zT(h<;pL9B&>g(G+2qOBCTWbSMClGcGX5r`U{M4^^Qu7@r;*WE;Ss^+Eu!iLF5}n7j z<~&S}P+$4#RKXzT>ceCYfBaUN(q^-q8Js6%qO*ghov?bsZ>^-w`9iH@52h|auDBPe zEAPsQ=dRT zLWT98^`DceN7ucJ_fS|@(rH($F=}BzGkz|q8`no#OkHY?Jr0Cj%7hhK3uEaq3b`lF;M@K1nyz}*n z_Chsiw0ph2alH?$=sPF@tGb;RLzYa3i1!w4)9)Wz`}zE^;>HB~Cs9do@P8wj(xuDy z^X_|UY|nSJp{eWvJ+}buHa;`ZF{HKyWrs{3lW6CzZkw4bkU-2>988o5$#&2R8vYP2 zX`xJHTyq+nr|jXB^(m;H;^7+Qkh$YjW)#`5YHScnRoO)}Zg3l-#B*+ZPXSENjo548n%EK>HABxZo{pOJG*ZeX(X4Q#WYU?aIWHun(@|< z++^qj)uQp#l*}`+XJnVn2!*tv7#MFzj?EMAu^HyDVYgXUEheGa>4PeVO6y0f37U0|dXMhCHg)#fa`Ps4 zRM4kcl~UE|B=@bwle2$2IQ-P+%{x%RkT+kpxUF#i^B@=L#1qa&O)vVK(U=sW_BMNs zkNFZAlNDxrFC11-qQTr`rr<0 zeYHchv|W+=GJ!TD_aKf0Rm`Fa&k&TXrR^dGvWqc} zy3auQTsfZKnvmdUXRR~rM5IhuExdjtZM3H=F)0uddv3bU5!9O2wrdCa$;?Rhwa&J- zwDgiEPnWW<_kL(gKa76*^v6=in~S8KS=VL)P>uNlP5l@%*Vz%kUK=m|?)cVSm5kWy zHq3z1xR_s2cS81=({fw)^^6XFX<_x8O8Yb>ZHf4AXj8hMTHB$Y-DeJf{z{wp+|whk1$EoYSv*Nt|z88Ut6{CsxZBK-GGldMsEKlm^z0 zMD4FMF@u>-1z<8mb2ZgmoqBo1Jsq2mX&5bxo7ti8t3B(N%E3T8tOESQe;Kqp+` zn-QR+!KKu<@pzuXYHeoFy!}b<570%;{o&o7a$Ll=0(1Q5k@CIz%}s*Gs)MH|CGD}w zak6zMJ~Nfe+1xd`t$ux!(=5ar?-hMaurR!(UoqG)rt|t0zL8)X#$ukM6OWHq-*%?h zbj7jR?$E2M)mjvf!PR+0zu9IHt7MBvQtLM@%)0M|$xY7I9($J`J{p6Z()(fPbq`M1 zz5nH|r7O9v=*04)`(L>~3D~J9;u|ODzSc_W2P&}H8|}KTqPI|hKio20?{x!O9Xf{4 zsTmapT_C$t-PPdjUqP4u-nU=Z4f`DlfEiK%)Kjc6HMehw>c0|B0NIQEoLP;27Jj>U zQU9bo#C+E7Y;>}B@6qOBs;^f{oi=}6F&)KVTan#-|Llel;o7Y+N}8s$_g_0~(&vy%a zrgSZyhV|mdwmi?!R-YLia;mp}RIE=ogVrcIuPb#zG6n%39T8m}Rb7GtCG!_eYa7g_ zqVs8`Ttyq<>9=E6 z|0Qq@7=S8?cDWE_dhi8+VL4;@i`^@{74^UzQ zT!+As&fMT|Kouy9dY%8Xowp$;pX$u_cFs5M%DTw~?2^GV2!LoYx`hsmB=Jm6apOsH zur6=606+`}7)wz|8Jy0}Ppm|4CvgKvT=|hbM8FLbWbhJA5H`pXA*fu4%w=!cdJ@DF zTV6L&X&_|xgrlm+2(iSiijK-1%oZ~sBXD%Cn0WR&IztBS7UjO_M5oET@~@V>bwWvI zV38b1J)y8oimL)Z_g#k>T-o17X5IBo?GeL_nL6dTwJmLx$QIlY9vuc`K;4)}LUHUW z$x+!`uX;H+j1D{a)2*f*BPPqgC?!j)C2~|-o|xFiEJ=_Zn>E0fFb%74#~c%m)bspb zR_?6_^Q_M%ub3b2!oEY*Q;It){{{!E9nhPC#N^?MG(4Mj5fAI@nkN# zE~rxOF|lZ;Nh0WA6VZ;0N|VBRa7Vk@kk7tGpMEX92(!$OIt(S!Nqe2W)0T2$cXxI26M?38h1xCnu%J9U?MpIUNR- zLF?&|441&V_M(phnR8;{^7FAWuR+UStYFvcJ^olB!jM)!P+;FSl#UcR)JP#&7elbXd3|&NfGL@ib6I~kzz!UC+p4Ecsn_` zZKsoMt$gSO2o<5K0BB|{%8iWRiR1U5s8wPglfHxNR)Jb@;9U}{wjpr6?0~ZaQo{~K zr=!}N*6KDHmU+0KblySboz8wSI+hMBm%`+eDrK|!erJ^o_Oa~i2y|_|DXy*rc|MJf zvLV+(-W@0ns;D<6xW0jkrF)B2vj!!O#_sOMZ#}R$j!4A7k=YWs|i67Coa#K^l(lnFrfj`6Xp{19|_8w z0L3>ew5*uE1GMfUW3>pFU6MjKVC#!X)EpZ!+YjIKMte@&+TViprbDaifYU8&*v(?} zEy2-%sVt}rE~hEZv28vnySGRcj8F=862NK)LTSaO_--4}Lr#{g!cZ=~DZVsYhaDUN zjIu31Wk7A4fo(Vkohj7w72cl{a`Yy}l%g<>f=;(6&_q}>Aher~>c`d25dgWe%kNsS z@8>T4z6XXZX()*fZ-I(eQ?_)IH^s7`ql5D6r_=AgSj9@({4+1PKWN?l*d76JIM<9- z0#N2<`tHEi_ov$d2iqIuCT$6P=rmIatzaHmbWY8poWjy0mmLb#u>9pLjlKTf3|;40xjp*R0(r=D{I%KDqZzLbb_oj>(sH$ zqPhk#Y@c(LV?tLyE>D`7XTG>D7rmiGb~sjyZX>|jq^PfnO}k`XDUr1hO^|CCv|n7D z;EKw9f23T9%MhV;s$IeDx{6W7C+XT?czcSy#JH9k+kkEAHCez*P2& zy)KsJERe2uZpxd#o(F%7DwiJimZE_866H`+v(EC^pGBim)S3-KgLl)s3e;}0<#%Jt zugI-if3Yx?Tg50z*erkBPH3-4@ssFcWEBi91J2<9x16ycF*;AyJ|X3U=!FUxN2TSu zZ*hEt461;kDCF7z37A|ubV+0>M?tEw`;4{L0IdlbgJ-g*aDe(A42abR5@Xy%+$lQn z-&KsM3~J^k2WlPzl9Qm6fg`c~FM2T1LWNJ0Fz;|cECB;#LA93Q-lqTv8OHED7FIDZ z!K~VVhJL5RKw{Vg`HDf%fK&B3pm<K?sUKfNb+3Wu$91=}{9mzbZ_chs$4n23z>sZ{*P!`lpyveptQxCMiCi|$_ zpe6(ERUZu93>fHIyy{m%ztz`H*ndn734O z+>_=N0zC>2v4@Psh`~-|aC;OafxWlZ4ot_vyhWf`v39j8_|%}M8$~HvvdPjI|I=-J zC~6#-HvYy!x?l`DcWVEK>b>EcNDrgpPB@L%y>_9C_dmCQN$tiT?~A3}0dEG}ZwhgX z6+=3rc6*Bv?v1ypx+ckcq4amRf7_e@wobRj>_LhEkvlIUTld^-0lkyJ(*rB#M5ABC z2#^RUmI7^rHqR*kGN%N7F0x4zD$MA^jF;hHzNs!5E5F#_pD;q=K>d`% zJtE?O{QVE#4qGCuukHtM?DTe%n}#hT*z$i1$Q;?ZK2dOFGMXHP5*M;=%c%5 zv*p4S;>C!Fi&}3XI`EUqWYih7!l+2U&SudVwx9?Hz&>X4mygQ3oy(ZG;tS4;OYToMUc>?PBu(E$pt+ zhvhLBb#Vs!tT0U7A|wv@a@B}1TxjvLy~6hLhcC))bYSkvJ7ypt+@vpo4iQ_zs}vlq zNSOV<7fq$Wx2nL~dhc#Vz{rBWx``dTSjTkf%ikaG=6!_TnESAt!;#mM&u2zx^{8yb5`W(0!LRDjj(3z1<~N#F{JL zzv0#QoRSNache!z{`sO+sX!qNWlvWe#ZhM zD)Mh1wTbqAG#~JS<%M0iw0$ie?=j&+oW#XKN8cYiO7nH_S^v~{iT8IjB&_|26!iT)ka2I&)fcyv zZk^?b2PVF#p>#jZU;80AMoV0mdH6o(P}eVA0e~*4`q%Jt_~TE*%H_WY`tY<>M-q2~ zQ)YU4Muqk7NPLm=%nuN5Frpb4l99o>{ljMU2bK2Qkd(BUPRVdw{d#08?DNudJh(q2 zx%}J1dTB(tRN=sTEb}AwiwxuX3}`(J2=Gw&Ii>I%XPPF%^xbk2&FM zZ@7rB8`vS?c;*nJW>#Vbi`1+WpU!-a8!9t$SGVKIQ+n#BQ{Oxt^e+G_DHsZH)PV(* z4ZdQFka_j}LoHm_?q{d_(w<(A*+jY$?vyI)&L2>Z&fUA`NvF!nO2(bdO3#!^*AhSW z3O>BByX5?qx^4Z++^Jp1w$eqCoX_(QE}xA4eJ$&0!@~WhPc=9HAk>yFKl*eFbnK^W zAbsOMP_Fg$FEY=g&Y$h2avQup-mu)PmtmMsTc0C^oLaMIz|`TVb`~n8XT<399f$ll zW>{vG4?cZv=YVEXD^X4%e8Bu^N5B^j*a-ogq# zL0g(_5U56t5aFkyS_v9XqeFYjEaH_C5NaW-9ASW0w|-&4l_BF&3ojN|8NEeDgzIGs z`?!i5BY;Ozv+@1DH&U*C4~xotxHmldVB7mky+4-Z6hQcyWk!5?Xm&)R+Qm}Pm_o7y z2ybk=#sM2vVz14%EXuBY+7>KzApLkngf6c&{t4Kg{bcXst}nRC58FSZD)-%ZbnWUV zr|-YN|9k;h=t-CSMmes^xHk>(F~1k{oq+J7hhl^^DJs5<<}o84NZ1x55@hx6DL|%8 zn#N((E}&w{vSq-gv-;VeVKv#dz$Cp;D@r#gz0uUSlGo+v9o)ShzrfQKqv_y5BC?~C1b|gHi@BqQ)I?UpQ?$LGc~`UF+-$aV!`C& z?ekW?XH5r(AKLpU(rMJH_mZ^aGH&hf@m1@%GY=2#dw%d->lFxzDFeJJv1aEWcYBJs z5FAMaP7>xsUk8~rOWY3bn?(R^GGgSg=7D`q&Yz$ByOsNGD*W)FABDVCYEg+SMwyg@ zk5`&nFC)Vg&nm@LWLp^M=B;q42RiFA+iLaZ2!)Q@ULHxvG4Okbhd@mpD3I{y^(FxK z^d~udkDW}7?}S;a7N(s$+fyNyu*sMa27&(=)10c@r2ZcTp}WF1(^&B_?xh?JV#jIC zo$->|Un%iReyOq7{_ufRqaUGWXAx`V34A+xUp~-O?bX)Nn_L;p^JR*JSttEnYcdGnPFHeZP5>udMJ>9@!oITkl<=E#c-fJ3n5>!W_?O_5@hw?NCT~v7*&q#VV_y`?9q|%eODyKL}vRlV!Sf zA9m~p@SLR6_NNbhz{pYTx`LR-6Sk8{FD^tpOA$dL2!rTsnX={(0A}m#k4Y7Q*UWlj z!W5jTO4A5l!H^7$W=Y`BSNQ94PqqA6NI(2<)coSaZpOB>`EYEmY*WF*Tsx@`q`Ey2 zm@}X_-^Dt?t?MLi)AcTitD>r1 z>wt7m&$!Ti(QUEI!p_ANBOm>Aj6wtWUxAZ_qZo*(QwAIL#NV~%P|?oN=lZ<-VeHGN z3fn|GG+pE2EnL5oYX=kUnmI9s=^!=j$P4?ZiZ4#?&!5119_F=eiCC}DvS&_}%xobCiZx!#UYKU4Q z@w{P&cvq_0bC*0Dwmp35VAmqi=J^MnN*APjKYi%mE~fUC@#5)}O^dmy@oT$bM;(vG z-af&#C8<}^q!h&SBB%VJ;uJ3d&PId=A_tmD^mv@SXmbQqv&(40_b3b5b>(71v0RMf;yubB1 zcE`G#f6lHHx#M5!9?t3U-1za>CbyRctnZR!0P@ThPBZ}g<2pbyJkIHlaDU{|WK;C_ zLdc`gqU}5T#M^(sF415#F$X(+l+>dL{J7`#K^c6<>VQe!=Oc%6=fOL!_uo$Za&|3u zaoyox51R76w|)A%HR;^y7;gh#|Jv7he;12pr=Z%rQjO_#YSUN!4@b@&I~jEQwnc;0 zNW}c%Y2xdIe?4D5Fa0~5b#Vy`VXs>$xjE}9@om|lLI;liMz4NGFN|(Pu2oY|trT=G z1v5s$KBXuuQxyMFa2TqRyo9Q%-lpFcH`ykcITviFY^i(`F9Yhini;(0*b*xKo#8lC zQdeEgdhl9bN8P^<-2O7)ZlL3CI@K14E-76_L5ey0q^ti97J1YbtC@oJFdadjhDH_b zsw8fffeI-KL|VK}sCGBA_o(|-O#18YWOxHmfdwt!YV)ADemgrN1;DC-Ms$$ril;jU z^dyp^Y~khU=H*56@{aQIQKhO>;IYkIKN(N85_cT!-rIHV4TDc5bIyGQ)tN#Wc&Nbz zWlUiHZy@ox7POcFve&#av8(@gZL$6ZE|u9)`;r%FUtF*z^zIe(k!Vh&>DmcbjqPry z#xHt!m~u-+YAVt@*7n|dLwpAkmrCIpmU3*f?wD6{^yTdiXUkJe?`Ox?6-sLhWWdO% zGF!-1RU9u24^4jsR7nQMBzfvh_N1G?^^HmuU=w5NSQ-XdkL0G7RA`k)^hvdg?dVPuLUM#cx&eH zk!ecpW{v{cLb3M}%ASLgSX4$0qr4gwa|bhe@HT>0KiRp!@C249oG4_e{rxiD2ybjBQ%3LI7%1BI;(W#CZuW-|+@4XLd?l^297 zuw4O%3P!JdYox7?UG@UCSMX?Z+$ssw8N~}6g7o&GyFf0boNF|}SUrLhi03ObgBXNz zh04wQ=C7q_@f$va12H5L9^ttEIBlgnj0Ba%BPR@pjFR&+1ARZzZah+vxVSkN>D*s` z2B_=|L^tzF=1c99+4}VS=_?l4mDXLT;oq%}V7FvV?Dr`k}P2REflc9Rw2D3n8rGN?2*vP?G zJpCKz#*1|sUEDB)%l)j{0~TkVTIADaprMsh=XRC#m+_v{Mx$1E_{eEe#b{VEbW5Ah zhbY>{H9*B%I`mfr-(#F_@|kCH0l;v6xTTbX>slAW=Y|Q9=OcJ>^;#HRYN2~Nscx|T z!11lRd{uF1sARKoa(?v?#NFX>yH37s*E!9ACcIn2$I@_S+|UZ&?o03ExC^CUJK1)N z7;_mkIvHfdU=x@oE)?Y$ZxB=sOrLJUb#W&m zGq5N73r}pqu7EZ=o2&va5&by|`o1Z3K?1cW6-R(6#~(F1aLk({Lzmd* zc>aMEaOL{ij;oq&y7`Wa0BdrQ+~I~0NpSQ?!q_c)ECw0D^Tx^Fru^p&|6V#Yc!7tN zV~F#i#?CDl_|W+fBNckSIS$NV@EfQT4zgtvcMu8a=?#SSCkF_e3b;`W$B%WC%=Xrxi zTE*6dilAt>rKFpXJZh8Rw`6KCiPuQCOj?k=>I#@Te;OOR62Dg$-e z%kWF_4EAf+j}K^~*Z8j2Sx;UW$zJ2KM-q~G*Vb-qmjAF@&&-5L3q0~fdzIriSb-UG zYBuY^#^)qWMnTxgi`1~#fZfn7kK(MmVqZ*qyAy){qt!Zk2j61YxW3^{ob`&ITW4Oz z%PQyb5|Zc^?(J?!wKw3cQC!VRK8-wD?OPNU8gnh=$@%!ujba~CRDjwonLaM8?gFR- z86DQjbzA`%76oKyzwL+s84mFsD;NA&PW9TjJe@-*)rQv3IpPndusR~z-b4mQrb+jD&5}5lD)hH z_&A;)Ce;J33U^Wf?e73-%^)lTlqR*93}Xz3MKUOCVfBOUvef(81&w2nq-0+9kcqn> z%}9;C#fsfx5j0rMXwA;_%plJ{B}WC zWBZKnH&=~uEr<;Qn6P9|Vn8(3SpNn}n$P;xIinQA`^}a;9LH!1!z-H3XB00Z0$q=H7E&}~OUf<1E3hI#GvlqWpSHOliSW_wI%H(qQm#nxQv3plQ zHuU2`k6|9v@1VK|_~wU*t`{B)le@NoEURFlfW7X*y68`-4EWxFsl8Z9`oM88XEENT zxlp?(+ntncME$|+k28J|T$!bsp1*=fa{9-hGO{*dt#ALXS8EX!7vj*$@cz%`{g<6L zY>V(S|M?m7$%E*$L8DV(YVJWSrAF)gGBQ*(UDv-WB?BMgzV4#Okz+Q*ubWa;Z;PcX z!K16D_L(A$Yo97SwXTIby8rHH>@t^OOcpUls{lng4IU3QCKO)y#Mb|D(*5yr7Zt=3 z76h*O0z-5BQ|PgU;v_NLqE0SxDYL#NNZJo0Do*ulFdZ&k%Lze@c! zvS8i!b2Xa(T{-{2VJP>24%9M@XW|GX$@6n8{FwDLT$4AV!QJ}scpIOcFjtCuR@&8_C~4Xt^eKP`W)JPUtGOES0^<4 zZ#QH_B7!I7%p2VEDLrajj6t;;;)27*k>(@fEn{6Wu7_1t^4iX zPSm*b6f6(ezng5_TCQ$a&qtz@PD_qH8!S?Wn~;*5#qklvD7);d@>EZM->}*x1UiuT zW}ed@=Yxxm`GR503Hg;4y#raC@i>Ij16#=Ep|Sj30C_a67nc_Hbt2dn*5a# zEVvNG3=91N|CVp>;1=caSA0zqLL36MV1uXhXmUp8$WYjL@+9_*mjAeEIhDQ9Iw9pFbrO*o=w#wvmriJ`jYCNmc|Z!BOpZ)X&hpwRg3a zP2SN@>GjbL#g_{2rj`Evd`I)w`75K=1Fc__jqcI*lvu+rSe2<&dj)|qRs*T=Ne$#7 z+aApE5^|d=5vSTi1EFhrqHO%l(_~efr@Koh_f}NRR24l;U>`{`&yac1l^D^$QT=*C z`xqgb(CKTHa5U(dVNX;=xmgcpZbZLIwbp+lB(XQgUi z*Ft#HcrdC&GFhO}=A{ds+}VVzZsTcKk!DOQf}o8h$0l>Mk8S$Tae>D;+C9@IJhXQz zvnaCn^F4!eyi!TivMLbw$jsNUP1?^Yp>vdmK`Ex9BRhs}rJJ+pglD$B!j0sXlhhInxu11UB zU*ITj{>i6mDg|WqGBuK1?&8fDG~_=hpmlPR%4J$FZTqhK3HlUE1ON*k8>DrqeCXH= znmO%QhHD0)c9Fa>f`;PyC>+XRY*5*EU)fpant$rGkwJOF9j!OR(kQ`uofhYdRi{@9 zc+$HVpO?)+^8spGi-!s7eSk}ruTWJ&PsDPaaP$|as7*jIT|B8`dQD%&yEj%{qg|lW z9EvbZL8fYF6K#GQk*h|cjP1_68%v6A<-C8j zMcbDFojg%%n`8s5g#|hw?lz$0_PrTCQN9!UrqT_b`r6tQ8MP9#@7*0QA6iW7 znKbi|&l7?1qmccncL*nqjT9#UrfY753Syh%@xV%HLGB`ZhIOTkIwQu^;|C2>9v3@w zda&qt@8DP6ByB7EkioA*T6M++LRgY&mdX$YpF-->9O3i7dLoQDF2|Tz%DZNgH^l&Z zg;sSaLkFtcWAc5!_)FN1NK?|ql!q5%9rlmgX_!tW_>a=kPsHk)N4z^hZtVoXjFYM8 zXi3=BFHFs;87Thj0|mV;V0B-%_mdF`++EIIl?gbGi_KV@>2!`X$|6qt{mi|)w9`|| zfGwoWEyT0XVEQz2dm=!cb^;iC#uBWWL+4LTh)~fperh5d&%E^-!kOBy6~9SCJUD_z z=A*YKzn^>5$nHRTuT}2c8w7cFS9H~eWOxttVuJf@9LQ4$^DNvn^_BDZn&|dLd7MjUCwPiFFr)& zbfn0@2F`s4XO~D17S0V9Ty0gZ5u06Yk~G?5Q1c|7lln_6_773FoUo~F+6HA~5vSQd z#CK}#5P&S=lxdvc>b_K}m0)H>!L?&_YcVYb4X7GRpW>K42JVMY~2tWr&aS z(&ooAl0B!^>^+2Lh*TJ$1W{HVB?Rpd5}?_(b!y9tn>-JYF?luNMB2;EaW@Wp4~l@d zh_F#xJhU;3WS1>mh`R*L?RTCt?6m=>trCGYd0UR|N_!vqdi`mS)2;DbxdiJ1dMK9F zCOKNN8BieySD?Nu zuZ?!~VY`lib);2ouE|tBG((0N?-U1&h2T!em_m>&(oW(87S2XvrGb zT51Hhnn_d4BSSTN+4E+{>>rfu{?OfZ7B`@yI`NA{! zz!HaKgZF6^ZpNwFBRji9h&iV3r6(VMTz~BB+xz^b;a|FaZS0T2DgxZu9|28Y2I;-S zd#?w4Dz)wOz&{t>vjw;bvcDa|tpM&3rhy8fd;;7}+Pg)yUpR`i=w_AmVf^z}_$|3N z=*=F8OX3n+7CtiImWMexXil{?rn>zVMTM0QNq(gIM&i$M-|&K*eRb*l7$i1ZY^6tg{Cr=|H6}fP!1K7L#WU z=v(LJq2A0MX?yyhjEOX3Ou8_>vDK#AndrQN6x!Jl`+%txiZ&V8Kg4NKrNW28JSrtM zI4WX=YCcGKs`*k$p9ma&7Vpg_7E$4Y>~)xaDCKShAKpDHx zxAxgqD!D}Aoc8l{&U-?#W(XBpE?E+N9O!KoyYO@9`pyA@1yD|NGvg4f;Zkf*w0_N7(wpPfRU{eVLF)rc1HH`6ZnfDJGQ{ECRC$*LVwml2jRF3mnA62yO zM+_o)z>pv(UV56dJvEPdtZ52)p^~l5cPQ&u=Fbdyx;A^r(?P^8_7*9Z3d+S{pfjmXKrL#$3Idn*&!#=o${8S}_FI+$&{@Xvc6MS} z4G07@E*&tk=Q}sRaF3q8LwgBzsili@dKS z9ZWf~MhcvpY}-7wC;m|M=}pGCKT^hkIR5bOB;_0PH@qZ-kSQ(3s3GD=z=2x&8<6wz zS?xrw#(A)^A=|06Un9FAbOqp42DXr|m-Dj=uDf%E>o=I zJ*`u@urUcR+0)9IM;3Zoo%h7hYjjGJkpd9$JU}IfH@E$bdO)*d=>r2?zhykfvAJL4 z8t0J_o5TmM%i)=^2ci~+Ng`bfXP%rn>2@CM{I_;J>y4$DqAn$&=^SEwpO;ScNWP9q z>wr-z*rap-!WvkI;h^W)I1JX3=2?G>$gbG-ofQU*6DmEx8D7ugDUpVKw&h?(>y`THB=(kv1 zurdrH%377;Y@2X{t$-nD(x{Vr&D(!|&|+HiuXxBJlaN!931-H!lLyC6!?JV=$N z!S+F3@<52l<^ISJfx>CO9YIYLNt#qKxHE}K+C=dE`cxZrls)@Vo2NM(s1mhvY_Vj; zAboqG~kg9HY{0dZwfT=)mwHPL!OBN-u zO?p9SZb2s(5dQz{!9$DM**_6s>od~H?JN`0fJ_|QB&i=mVjIV>4AeL0%7FLv0?mkY z+y)RlL>0lXO;XehsSa8(FwJ%Vika1kVHs-=$TRw-JwYfYM0$-?eDL5UFm_G}<-Akw zsno}L_ot!7p!}W4mmkk)G%!RA42|8RwdX zb@V)Wd@RB<<8)~)`#WSNH#BW<& zP>cE*l-w&11)>hFw}t_M-R|=maurQMqBsSKaw>jF-uKI(^YNELG2XjD?I64z?YV_> z&=jRA{y9deQ)GjQzbu$amc8cIi4!nw+4Xnksb8g8(or-iUeIv;gs4D(1-|yx0T27A z908#9j#}~lgLo7y;q_)Sq8@uM0ngkw5Ueop8R!>-U7Lu*Cnj1xz4MUZsMNq0@A81E zOn){ygLHw7DFBkG2-i(B2mp7b$|f4a=MuMm{J!;j;zHD|e-JN2eihJHNjRhPJdV|g>3r_^HdAl*z2>#fw%G5%z2?vF z3h)#siplfflk$2CS1i9D-uuicHMNhZo}0e1$D{gtX!JCWP6ZXHNbSCG51QQOfC8cq zHf~CI@m*>m5usqVUpxs^r&5ny-Ii{#wJdpS_Rnqk$p>Z3qO&ccKbl4jSjc@%j5>Bz zw#vfcfD?J+()70dkS=?tL=)aUYNKfF|V5F=Y z?QJfD)@w9*D$Vv2TW^nxEfAv9E|6zx2*szUyN)*UJ=uX59Poy4MX`QEKU(QaL^Cj* zCB{;*iXiF3&uvP}1P+FtEa{h@HigI|7mwh&H?NHarmfV?I~~<-Ry5rn3J|DQ!`ce3 zwEe!Kou9%L{ZgLk^hh$+ivv@m z)C32<|E%n?F0x&P2PYAh`^c>@rv`w?Ot-0Xu<=aC^5EXhB)iqcC)Ci7{r!ekO?Inw zl^5U&($ZiQ9DBe)WRw4y-L0+kvj4`RD9tDbTt=&|VZTXAdh_ZT(rROnwL?&6xkV7u zqLKE{y(uuu(H8Mk?y`gC67}NwzS|i=77-4*eAXT}n2{B&!xm=H3K&?yG^}VE$Jz3Z z5p7wW+#ScRd~II7)#H49?drL#gZfwDUTDE_y`V5O#!W|m zV+W9@pm0=Zco_!AfsZcrk@?4~)V4hNlbrv9^q9)Rx%qgd@hl@i{kn7u$-Z;PrVV)m z5{3>sl7L2M=u~|=X=?L`y2LEDx1k=DPlXeggY_N^Xb-)|#|3)dzNxI~_3W~J)DfO? z(r;?%IG+F2**UzZ_21sJ-Dz) zG9W1l>#bd}_lLnZ(IyPl?@bD*KmLGzlOzdjYK;N?aVfGu0e?b=>G0`7GAOvLKn8^3 z5u5saV9G1?*U8%|!OXQHVdOcw6q!27y7~{^V+uHyAP$-M>+nOz_)xQ8rKdg8FB|mG z^be&+`c#1!qB@mfUxhVV)J$~%W9b!oGb5MhS-zgQI6IL+a+yiyRj1=^Yi`#XT``AD zMV2uYOqy@KM}@`V-;xLYns(GDkB`ElceYARdR8L#-Srkz@vP$%gmJIQ7L}%|mEFI1 z&3w7HWO~B;1z*xGayhE(6z0{=ncm`rtDY}9Y2SxZVJ@*{7S`XK=T&|#VrO+1XAC`D z+8*%FrBA1RhvS3Vg3~jus5XcNp$Gji!y~U76uX_CPDVZDd&x`bUb{L~E-VN`pS6ri z`$SQxFO;BrS8uL4x@8n;7FHuRr>2}!Ru+cKEKe$(IQrw`^J_T}zrTNW?WFR_ zf2($8>fOy!)K>dtwg42fgZdCsLA*Yc;&G@Sqj8*`E33WvUDvAwGRve=o@bY77F!9@ zllF``=O+1$UC2E^3WyX#ke0VsNnN7&RH+_ZtYz0l1re|kH|J|a;-(qYD&K^c8fBio zaS!uFc=pZC);6P&#R`Y*w1+jS7Gdr>`*Rrt|6Vs3_7Fq`M9f8_OkpO0uzLtiQytX@ z7Fipg2la-GyK;k*33o+Niwr96&}NOl;F@!Rj*O;ZoLQEND5X#6W7Mm|d^+p9yglz9 zBEUHhY_yS@@bljy)ub!k8zxrL1`V9jgMu7#P4>tQp0e<5?$3AHz#Jl24_fWaweS;3 z=9%}pCi7_gVD(({x9Bd0YOG z7I{uesf&`(ni2IPO14Shmb(=On5;tTIWHIguc{uR<0{6^J@z z?sgoTaE^~G#1O4)-UFp)oteSX9hLdI)2Y+qhg2b|kZF>EC4(r0>xcJFz4V6S10$n8 zfYGh9nwzstTWvqf>O~<-lX3#=t4=pB^)Sub^MK`~qbCe@fVw6kk@b}CGfzRwBPV^TJ3xHc`J%I zckC2aG90HFdHQ6oaogzLUwMd6|TAzpy{xC1d&8VZ-wlQJ(%F;N_Zv9 z)z*vG4~yjCEu+%K7o*@gBS5|zhKy)m5^U}O8uwdp=<-iF7KkttuW@aFg0BM~@rpyL4uVjejVz+!(s*W_+n?i%TIk0^py1Mb@T8#dxJy^Ha zW2V8tHb>Nyykm79Eyppf+2*`$KxM2qlan!H3PRLwhNu92O#nhlEDb-T&( zsd==!RIPnW)K4i)Nkbb4oC$G8(|X;u?q&YIPa+x{Gw7{8a$k3Uw5?}fm7y4~MyK7= zJ1Zmycm&Q6%X-E&G9`zoC7+4q@Yc~>1xBA{D>+?SvJWOl5efBFMa~5{Yl`r|1W6T` zju{Px>d18(jFl~7P&G?SgR;|u$(UDNPe#&H%-m>PuGc2~^;sXj{u8CRW zHqZSUc4or(bs?);HM4#qchFjbAf5eO|4V67t)WtS_XbBj_FBZX9+)Uc$Wu+jZyioY zLsS@ooF43X5p>X_PEXziys_j9;otQdRLN6)o5Bv{+6%KVy6yGkj2+J3&v;BYU&X|Y z_~8!g1PA9ZdxRHGx7l(0<$086SAwrz%Ksdu>GiQ-$opZv!NpfW4LbuH1Qy<%$XC-5 zFMJ<8n&>KW`jFeq8*WgN>2Y7L`%Nq?_+Xx2+Juia4ZpNKj zwt9PR2Zq4?wP9#0s`2c>J}E2eO?R$fi!8*tYgn)Lt^TX8Djn7&w(FMDlDHpWr_oR+ zCNS+c5*N9Ar++I_Cz{=yP;_eVg~eY2rT2lE*1f}Tj@IDrm!m)CXk_mX#qM$*MqHQf zBUW*css9AQ=%nm}Q0edG!$Faz=bk_CQQV6c)MN$O-QCoJphBEGFtq~E zXpwnO+p1P91(R;rKjmbTP>|PxmmTBoTs@z@zOa%^9m++0#gVA6A7PWj-WDd6*1@y= zX>#K=(mxvAf)DOECpXcw)x4~s|G=)>a+4jJU6s)ju4DQGRlmwJB63=4hdzx~orFD- zTP(zf@--FxN>)27Ud8M`^j(d&e*#igOvLyLCMIa^#cZ3PdpI~Y@m$qQ zIqI+L&tJtJxh+4lQfhfa^w^i9RexsQJhJThwdKE)ListEjD+^7!R+9aaG6K{UwWz$ z3-Am>Jry$Vm@P8p0#XKK+vBqEPg!#RAquBeWY&k=wr=Y>dw5zSdyev>2__Z+=*jce zQ8sjTW@GxFj#<=!jvIU zjRKR8_OdzuCN1{mm+f#%9^7^mz70Y+&=D>?gvaQ=6#jRs^S4%;T$1*y{np#C_u7bD zex(W|>5e{qB>p#whmM9iBOKA`bj&sbovcwzK7=izW6OBhs!{AYNTil7(!djGp-gOc z&%5ZN*LavMpFwjnm_wFWqv})g*OR=b$zJc;^2NA#YI5GD4UfPC;U(Tw@5ih5LOz_w zATBb9D41AR|GUX$-88(oIDsJHLy##T$d3_}2}Cs?qE-P>FJ27(-#f|}bl4D)F(2(o z)widLcYq?L49P3@@EnGbpD}fH8E4=lal{aOxexNI!BsDA3(7;cF;Hob5Q|2r96o4R z@QzXN#f*$Jq2ZorE22VgCAVz~r$mYyL3=)C(& zg;EnfdL#xhj4UzKhq$FGlS-D@V95D*{QV7L&)4hG>HqA7Omq$zQuKvup9iM&72W4K zSHr|iV0+&hsWbyHO%(|Rw(iu*8XBvJ_4KAcZVMhWHVxSmm5{7_;3ro|C0Xegz3mE4y z64D!Vynl^8nuXppl6uGMcsw=RE@8f7hxslEg$Xe=aSa4QAihC{^)d*BE3z`2zl#Et zJr&O9E3*>BUHZ-<1dkjO3C^s5NT&E*VY}`tyz%g6FC>~Mcw&e&Ms5JoC>qdzKFF6Z z8PSRxJRk}B;*kPvDbuPjK*Sy?VcN&Z5!lu4!$RaedqN>i7Uf->3f1&rfCLrpM@1J? zMg2C9u4l{uH4zV7tf@qTgjCJugLg1?k)g4>Hy zLG^;J|BX{?{oEUh-CM@pw?9_;{xo2cEOV>BIW9r0&DZi2LsCG2$*qDL1X+J$TsY%h z3KRMqFP|!~G%e5`7S`c-s^FZ&KG#l+>YU7_^B^kW*1s`C3K>ihWSuuPzC+jP<-2t3 z5QOn%L_47W%s`t>QDl7KPf+iYq@RPopG%1!dR4cLK))Y`n&he9ZhvP8IL4bOnKE~p z&w<)=VC)Yt*>G39`L2@_yN*oAXPdt_q~gwui<>aP6z^SC6FW~#ys13AE3+h^rDQ3= zT=&dn3}w#$^W&p1^|_H1QG!NfIa}g0RdbV1TaDXhEZ^B=l7*!By@v@+G_@~ zAvO1E*N*ddPLWIxz8vbPy_ZjR$Wd_XtQ#)U-qE~)*tk)FRsNcjGXbf*7hpzD1dmC4h1#w_hraBqNtBv4R9p%LLPK?EEGf%oW0@y%~D%v z%F#0qdb-{{=HFKJXi>lX{%PZmmXL?n!zvqTh{#y48&^NS=uXT&3>SFGS;yi&DtY&I zuPh7|>Fs^g+w;9!^Q^}?@0-_u+zDy3lKLJudbnEC?6^>Q`>o@?D>4pAn7&(EfK~M- z--~UqTX*m}`^#q^-#)o>?dNH;+2adHt76tajm9~)wE?V1`Hero%#bl=62&nljq_Ow zvF4oPX~k@xEX6$;Drp)Q8eiwgmedegBqxEYv(}@ih0|7Yeon|A1(%29q*BV|iZQTQJEB-hM!cWBHs4F-j z$<)xWeOt#j1C2(v`QqIc);=JPKDFQN@c9EvHKM7kQDSa03MmOtZJv<#bx(~}#(Znk zq8<8uAW8}dA~@uGtA5ytY`oC?q4~nWiL==DyPH@7CcN#gx>w3;YdYBb%_gF)C+&hB z;7H_-7hlwD`P2z;`V`9^f&509ag!G%^^=kJ%e%&O19fOq2T%DGzb^eVQI%PL%1{~J zai1siShMF%;K~dpGZ{WS??hlE1YGJF90n-6a?WDCFDj^R_%y*2k#F#ra*v6Uy$_>n zZIsMP?vsV=5^sAIk{)kJlwduQ0pHh&=oAaD7Y9mrpTA2bSo%3;>!>@f_$taQK2%q| zGY2&i-)AH4T=P!nJyDc;$?GR!#l|jbs7}$q3V@&E^hg15p9=jRFP#LA8+^Gp7je-` zS>)namI7ou=$L0$H)j@iF9NyO;M6B7Fd|YE!LTbR^#;y^afAG0Cgb+A2r_U^GNd|nMO{F zdoKT?S71_0=H&_pj?(z|uDE`CJ1K<7kt_V8U(q$wRKYdXMwNpyB0977Kshmvvt8$% z9tM8pwU`7HM{alEeCWI;b;8bp7?U_lJL?1OT)Klx5U^;5jdf?u?_|DAP;u&hdhzJ+ zD0yGNtZSn`GA)?3hnl++Cwz6qA@e~4Zp>py?8qi!d70+pw#X0mbd}}?^x-ln4&u1; z1L^Jb9C8nvbkB;XTfUMT<+$KYx^vg!`pW6JB(=IHq$U>{0{a&%dTn^#%GSb>wJS7e z#}oA3!2lZBmva9L;&r+qaU1ci{8rrP zxoP_wcHfa@m~?(&=$-Sts@+xN9JU^)bcXG5zK(D@UnG)3Q1uLD-#LuW2{(D3a^d## zgnY#M3*y=xgt}jmNND+-2Pd@ZfK~c|y)Z4>1>@82DkOk+o?14~njR&0en0cYPRsh8 z_4XrAzMoxt(6DtyN4UM7n^^tFap=2^$*2>Cnc8)5JJuUuiel8^y5u2zB&GKZ=Civ; z3Zs)jX;;9gql`J)u8N?q>=45bKi{WXs!fOo1WKI@7PV2}28>@m3=dNA;l-J)g*wVT z0RVHL9aoe5SxqZ(*eCnRl?#T0O>`vHuR(XB+4%?A<4&`G%QUa{c@K1*?N}e&icuS!e_}w)K<{eSc0%^=U@enTrgMGEucwPt zDL+*ok}x*iEIi<6q3%`^?KlXWI=MAtGp%(s?S-GZcQ*pHIccJqY%Fr_;Lj_#dDy+! z%7Pdnz!b?jt+0EVDbSThNEfY5PXct2Pgo7qO%0BPifYs~8jpOPJR$bgK0*&Qo#4pCb2Z{k&%;YF&Scwejzz06k3acLtb+pt@$xJvpV9mF3P+#G=Q*hdka;gKgz~vP#m84v=A*t)X992TlavAqM>%gl#EY|B z9|$+}lffDYq6p&) zb>$&lp69XODxPPDaM~NhC|yUnx6}q+hR?f5SGC9B{C6qu`J|510UK?Mz&plU)|z>XoA|MU zc9H$@D^9A_F?mZaQ4`VEdiTG+$GHp(bZoJ=IPCl2lz!QZR8P$7!4uG*gm6WGluf0J zJ#tj96CXcg>29aHl5@Lm#wiiUGENASfD7b$n0F163r>YEzP^bO7JP9Sk6tOg@luPF z&9NXos$`M*o<+#UzP7^>=C{R7FBd)t1GL~sZv3}!KFg{(8b8uxZO?8HFKJwX>Fo?bTqVAV#NB({Zi&nc` zrI5_Jd27K@@iQ51?d~(b)MTFsm6|OUEcjTMEuthXV~$;7i?PZXv0d-pEMisFjUB%} zvB(@Bi}`)c)1}L&R8zk^sp)?8jSRF3pz{z02qgK^z>IR5aJisM%z#`;4j;wZ-lc$< z9vSigJ&Q_#F|hz3-&o#{^DBprNQQ0LsidI^o_z4QKcGWj{tt|2dN7%erY_NoF;BCY ziQ~+I1Qsx)V9WP;w+k8tfM){Kt2tj_6!Q!KD9fNhDN)JkBz#3wQU#w+htAAFr+F-k zKDS93!ruugdUpB(OSJ4x!1Dgxh!xhd7Je82$|#T#z|aeI1NfoN95#MlbWqbTupMcx zO>h7*?%TUE8s&$XBHG&K$^mSEf+VkDEHS`UEhvzIgRh{Je-J0h7%(2oDLp0$2EL7VjI+;oOZQHv4)_WZ-p_$swV$M82-bkk z9sn>{hTm{GCHl?sf{YvoeOfM*ith7~6{z>M!;88l6?mq`Jn-WfC>ICXF~ssmLCd*Q zlL6{Z{ht>4oaM3pI(#fp<`C} zVKQBz-elfpHwkBdQi2b^$0<-+FR<$4kONNMW{3s0pCDHh>T>1%puGSY6JrH^=`J+e zU39GgY!{k9I+P*{+2i}36;Wl28)3TobxixzV%Jm>-*-p4Op4ojF`Yb_=ME5lqSi| zqDe=2S=xFTlPkG}RGzWBd|Ls}q92y;!_6$_WUVU%3h-AUxfp>LNZ4)2EHw1NFat2N zqugMhg28SmhL@(s70VZ(lA_|%4?tzkahQ3VO#c7|SY-h#J3>H50Dub_Y6GyqGN8O% zE*V+@0G$0Pa4-}%3rQFWz!!8#)eWv5dI|ul)s11CQZUUGD$;?3zeGS`9~Pv5kwY}y zeS~$2*ooZ`owDh>4PYUG+?^=Rc_=kx@2L{W|~} zuONmlgWISupk3_CJA9<}No`}ix+^hXz073LCZkih^d_WUQ5JWR7w;0$M+Q352&0}_duLAhxo*y7< z23&C&VX&NQsgi2|H7b;VhCKN8-vnC$c#w~@5R!REIHzUDK*KnO1H}F8lw0Ipuy?2) zczWR)ETj@E;~j?qAT&5u1@{qgjRcNNL$-`Fn9yBD1q~F2ugP5Di%EiED#N(Fg%ny0 zjy2lMWjAV=rL7@s`PKT@F`Z?~fuTG`jc6XdE*U_%=t6=X5ri=eH_=S!gIDa4NUKL0 z0lvDU1;IWo=#B&Mj$CWX1%rhq`LW8AZ!E=Ob?kWXIe^`ii%*Muj@eB%sS^i z!L!yf?mwY76mW`BSqQ&mA&hT4vJa}J6E$=pzHFpxyRTEIv&u0d9dLOW=`r_Io9lD& zwTAhY`xzjNvv*YTopr%|uIQ^c0tz@;F(kGFYBuUa4Ser3G_JU?2NNP_BEfKl-S8?` z$cq$$UUN55VQzyVT_Lz+BJDr;#h{L=DJ&4qKtwR>f~QRE2YjGYqEE2E;R})h7@(Su zD`Q~Z|3c!h1WPHgZOicMK=rNb5^?U(eG>6yJ#GgjW)+RS4i(AOw4&m%J}tWs+hUoQ z<(_7E??xUwXcY|jCaO3Y^mFO!+8*`H}f!C^TG!UGA z7m+so@p*GqHFU_;20hT!jqKQI!Gr(QlUUIsSn^tHkA=&!;CB2z3tGG_)p#w3SZhnP zrz1eqCJNN1Fn-%e27P_=!~RL6hJuFsT=7-E>ea!&8nx!K3 zDIjzodMMQcvNG>bpanW7kdc*7>DTVV%gCK6T58W;5gnm}XK|E-TWb-e!jV{QRzwjha{LHhj74#<+Wtm-d8-ZN#PzZp;no7e0K7{LbBj(ns&j)`JFHOC)+Lr{=n4RL;U#S1fBb$3|rEf3sY2yRPiKM!xP+ z_+$($V3N9-Di5U|C6i#meAlDB_1CK+;=l*hC5aT|`(LO);W82{O4x?F5j0Yt$w#)h z{>Kf?b{K`@vc_gUK%)pR%UYKtg2=_W`!zuIjRW23L9PB3Q{>x?LH@fEnjnGdiVYjK?x5+ zYiH*E9POr86XMX6XYCoef8AgU77mhBX zVK`9nL1y46FY6dG{yL%t+%kG=3#$iS5dPH*($Iig3KR`{;JwEox3dxFj!6b0-iA}- z=@>-&i`Rcbfw3wmO##PaE<}5xq=X?a-~~&ScYOLWX_RHE;{yrcu8#^IEZPdGW(M4; zjIvXBhBk(4$M^#6m@EUy)Jh1R3Xl5y4p%sfoEN!qpwhXy-2VhdYU@I#dajAU=XZ^= zqhQj3*0}n9;!5)(s-PnJR{mLUpX1hzV1cn8{Z89VY`+0?JLc7u({=Ifmt-l`4fysP ze4uMDQ!pYi5s3WMjo3o}f{O=9abX7S@KD}+QP}x59w?az{}S@q`N(I1=S$bO_uk)o z5-(VS*UT$~xW0KQx$8kLu|q6|Qqf2O4?N;#4xxa2DY36#-@ra{4F>w?uYTXGN*w(R zFhKzNg6y46ILtoa3UvyhqLa+qTUId839+nYQ064`!V`W`i7;!8&?k$^f0Zixw6ei^ z1;h!KWZE^w0Z}rf``@TqTAlxGk*j}UMi&hN$tT&3Qpzb}>HHxqf!oc?I=zf`pmgBJ zUhY`NylKB3)PXfRA#$Zce_a2+~AGjr3e9R$KDJ0`6nTBgOdr^SPU=-efLxm z1v{`p*U#$SkpAd*9PQ+4Nqy?<>rEo8=C*99xJ=^cH)My%^oLdS*yqIdsz~#@$@Dq- zG=#HY?p|PB&VhTu_w+3`>01h7?9VcxW&jcgD$fy2et;AKsKXopjX||#P*=K7gs?}0 z3g(q_tAwPb$6P6mIG7PH81w<1t7Dw_F!glkC2PR)do1^`TXy}qWaCr$p%)Q8u>cRN z72FBHsB=^{(7TC>3LdEd5valr2`yDX@+s!Eyp`6=Ubf+Xze4rGwv+P5(S|r|MZP_U4Jd|Bwm+%X4S95t2yn zKi8G#FJd;Y%SeBl#JR+|FM z>Rh49^T&7xk%Hjm!RQ=qs)ERyVBx>~7r+L{sE+TRzeI(LJI38U=juMEhCqmHcA}L$ z+wH%yb@r28f`%XCAG@1`>9Tay7C4+i(5;0{UL$X1eQ_1Xz0$8UrUW5$-&V>US?q98 z-oJ-_LFp*K&sMdu`R1bWcVxNNP40L979RchP%DdGgw55sxe(nR7CXNEp20o!F3$pX zhTCZh!lqHph)*%~K4a*yo$USr!N|>8?KM$=Vw|keql&W;D z_7>HLcvl5`6^(jZRi-hZ4lsB}f6g~3w_x4d)Ed9Oz46~|;mmN^Sd#*>4BGvV8YN~SRXt1iR_!bMC(15q%th<3TEKk8&pay=qm;VGTbp}TLT}$P z3T0VoFY$)ARr>IQ+-a90Py8%uxc#rlD{`yiuHZo%_3L3-T>cQiMv^@o zfNuClM|)+Um~C4hPTjnDBsAV3BY~+hTyKet7_m;6UN|g$Jz=g*{HJ5Oaf-5thZRr! zDn0FIx=P68GfQo9jsL#5lDk_APqnCPkfa>A1Uw8Cw$esM18yjkuPjmoah&Xvy{)md z`g2m9^}`+jJEW2R7I5B#_a5M5$qPUS`%cgK%+J1bayP>Wckp@Sd?n?p#n<)nNS$J; zGu`LxPd^4i!mT}No@2b!$^t7gD7NR#;DYa=8i(_{vMeD-zXu>$1rE7gJ5BGcK^Q@< zmXkh4iYax_(HA~U{Km}Ii5OSI&3TmCW%rcJgm zfiKvsiN}jU;q|{dM9L%3HssoF_vh&{ zA*DXC$j{V06h&4NluKdB03pk4Q(_X?v^-qid(<761AsG%Zum$BTuNj=ru9w!?WM!I z8z1gjxJz+it~LWp`$QB-LNXa4N(}nKagDUS%A8@RAQMib|UQ5eBf+!W``3@zO z$<6@b2ZBQa|H9C?aYd&n;8H-+4UXXE!uV`yMk-~zBE0yHr%PCJory;pffl2t{aSj^ zJhk$rqOMC8wk6^${J?i=WdQUN$#}5sC<2wtc=IU;1yJtXJtuW@se!-LU*FNP$2no~ z%~3~aXp8z|{)1L_`Qf*&BRa-uU$NMB2bUntjIs9+P}%Z50EL z4=&uIw}zL3!!Ig(5zTJz**3!T*AkDw#r=$|xto=Iy3SQW4OgYkHsBuOiJ~Y0fe-yO z;#{T4i&4kkv5{<8fNcVn#kp?8ra0RHywK#b7c{Q1ucU4z=u7C-%C}V z^`El}U5mq4AbescoesU+cX4!^eRM+yj0ZWz)+qRajvc&wX$}#MNNoce1 zoEyLT@uVf<`sV8iL`2iAfvBFs(XFg0!)+;Wc{PqC-GY_Enq6vDjAC)rSVXeShdAmD zICiYFl<3M5{ZJUATbqx8J<^3W!)bsv%cVUlkF!Pk!8VC@V|nH_07Gi;zrH+hQ+Khd z_9-#TtxnVd_Rz$Xl>#KdnRHhjUds8G0Bli@GX(&`^Kk5k+Da@DqwkREosyv(m+7)> z)tU+i=AaYu4Uw zomddqVb|{xRUZ*$9z)N{TNW1vk~#QKoP;$kgYwLzIy;~{D^neF;I~!*q;cSK`H9{5 zB(g!la(pq0dSdo=53u^8$9O*MJKdh!E` z@>1&asoDS!xo^o0==Nk;4Lj6wb#*bZjP$80?3%qh5a(3B?98SD?m9}B1|J?{Ig~G5 z;gNw0MY6&m-vJYNtE1|pCb!E45V~;mHc#8@OM*8*c9T@+M!RO6)P2B%vI`V26?QZr zz#D+vSrk->UPjk9aUSOJGc)Xf1NW0YX6Gl)6asr%jT;33r)%8{s5LKFA0O>;saW#j z1u&6R*044E6@uwNqO+sugnH$w)xsG~*%$OgI`IsmZ6HL$Xz z^xY9Hyd{eF`#yF#_#WU|uffPEEXx2pPZ*$!NtZr^HEuWTsp>3Q_FQ0zg~~z#ck<7MUyx+&c@tO;II_vFsDqe zk-Z9m$iWeJ$=1q<1ly7VYIt;3g4ooqJA6fot-;5(w`=ExAxJepcbJ2J4XJ2quZC2< z23JoEtF~rYI3&IpHp#}=gpHLuJy-hens2J#mOpwkV4WjqJW1UUTLz zM|?U!?EENiY4^#8yX#6|{5!jA{IOymCR5i99e$7v?E@M=bLtMM{Ac~_zf_f4MgMbe zrdv)-*CU^U!yT8!$eY_S^=|S=hDTAH<=IW$`l&+weJ^gldC>=T4lM=pAcu0MiGf?4 z;ZV9^3UE}FoBdvCdJYKl9Tn8S9JvzYQ}E(CouVnv$!yWdg2TzG>BBc)J~0n24q%^% zhpX{3o|bS657Xa_oR+P)J)gLfJ=$Eb#*~VCHS;4_So|K7;`(&gsCiYmR9!gkcpjA*n<1#JF010p>$6$}!5xr+_4ugkrxm>@1GisIu6#HW;$ z0pRg^2+wt59l5(mhh0Wyt5UZ7spoFL--TXdna8E)Gsv$}%yy^FiHappK!A`M-9y~@S`a*!2MvfX`N3l`X7F^41=(zx{)h@k z$;vzGDZAraJ}z}vwcxRaMY!;0y6|AQ6>pghr>d3&h_M=jugZ#6>@#Z(g~v{@tEN$M zo7c5@*z0~JqPnbAy9I~0FEm58_CTVbE|;7lHupp1N~5uFN2s) zCqyPwPXmmdR@J(%1dG~wHP&Q}xX)PQN{5i#R-7g-OYH5Te^tm)iJLdE&!ui*wzB83 zqv$*mZnWI0y(cYQ&*$Sr19RfM0{-ZM$fGj___uFQlyVsz#8Owx5jZGA z?@GNTV`I4U9Si$=;HhRqb@?^zI+#|;~wB z6W%xOFvc4-ucIQ_5O?$BX>(n^Xt6J&%CkGg1RxHw#tE6+FXVgv^lA^SOgWRf5wb$ z-Zv?6DiJ`gW9&2hj&En?S|hpIx3Dfzn_ZmPEfQL53bKECJ%e{*RaU$GpSbQmVKgp@ zE!JbHbbFc|+|+3>RhWisD;VH+4JQ7zPbnS!858a{8``vw9RQrJNT2@4Q4^S(Oi>Lc zO)>w)85P1LD7LMiIVmWvb^Vs<^h+$)K34lpLc>aV08m{2Nt_Q0y;GlPIL}^-L)Kn? zFfVHm8ud)mOiF0=l8aJlCyNcyfNrMr#|#-th8{Vx91_UA`&Iz#=gr;BUju$kaGSw& zA;DFB-2nU2ioH4~OA!C+Rm0wjXnH^NwM0AHpc`h*yEthKY}mneICGDG{${_8dl{Ba z)S+huFsDLP6B3)@%~&`I_Gh)D1K7%*L#GAoFnssLt7qWoKJG}yfhh#Aj$n%Xtxh}~ zkZ|JMUW?U$eDT$P97m$0*mkT+x<@{v>CkA7=_1ZLTLv7@E-A2 zl`bw|HEYfMepsAKH1Kz0acvvE7BUWhq}cNB{9zXdESIcr5 z^(bpD_21N`sPLn_wTRr_3&u?6hF^K)FA3WJ0F4oBhB#KT@xa+qiFFprJ^tfKH}BVL zu#W*_`B4@Y<>8lQ@b<1!p`62V6i}+v?96g}fk3SFA3-`r z$t)SFwa2!!e*p$SdHt#j*EeyrP@{cAtmMyZd2xXZF+n1({4vX3pIA zb^orF3WUB+z} z($}7x56ruI_tTa(>1WEy%BTh#db7=^=f@p^BEdZ-{>5P7wS((&k}aDZ0C?W2#0`7z zNz-sbFe!VAZmIrfXEFcqHRd5M_u0Z0buhBC+*3TW8qym+MOon=+;PpQR$|_wWQqEQ_E+N!y zcrtCX0-RM$zd2Wp!`(6WlMU!V3pa&77o4Du?|1~;?<&aDuJkmleY_tKcgI9~_vout zTCA8iQ!NNFp`q4;tFLJrwuIO)M)!Phv#aZKrf&8A>%VmCHQ31&5h+hq^zf*?Yfzbc zFMjFq+1S%daCp7BeiJDwn!gvc4yZHI7Vz|2PlUaXJ##7{`=!=hfKg=KkP4&d^+&pj z&s}K0{ys}x@Y^pKMSU>Ez0y95c6(;G7nE|=ANM!StC$_i3lNyMU%F#>BXLJ6Mr7=n z9|7C%p{1T)Oqx)Mq4xrbX*fM(Pja;Plzn%8yhiPZ!dTP}SCfIYyMOQ~*%*f_u7#d& zr?lQc#AdgYw?s|J8o5AOrVUV5Ag!TG5b8N^vyKDQSi@}69EDrlgL;SE=>#ctvb?kE z-!t0+@RH;GHq7WdENP^_#F#_W3V?!&affSrYL`){u4cRs(@|P;^#3HvXK(y>{R|8Q2m_afWGW7#0RKrCSIU!oazKiZ37U zJ8p`SHs}V81}6Sk3{U;D2xXn;R7V$G)T~1Jc$R+>8v#p`Q%hg-%+|L4UAyP({O`AC zN1gxM`1L{d=%0U;Cm$Umt~!jijKG2KQ1VcC`0hRNK>^hU~Cj1Ov>;bWT>CoS-NYu{9Pzfdtn@i-|eKO z`T$)!A{2+bD;D8zR$e|i;a7fWp!sWtwGB2$-@v9;W;3xJwD*+To!^2VjMudr+Hv8L0b0H!@Qy-iI%pV%M)$7<8d^Z%Eed6*VW%SL11!0eFIUedpN7cJ z1j0^Eb`JCS=9h!Uf4o5HvW)W|?P*Rj{o5^@BCp@FRO-;&vQWYxbZ;+@ zY!6MCRBMxLy?y4lM*b8nI#t3n?Uqn~2F_7uRXmEhlGhx;8A1G2SYzz=$N|er)pL}5 zgE>}8G!teNxn5wG+sq?Y%*YC!&Yk<&sO794h(0AHuR>G+YzQGTe*>X_xi-RpKu5^B zQaSY2{k!f-3ZpObUO(p_L_fbwE#QGgnK+bFJp0kEr56W(Uvjs$F4~*A%H^ zcuSmr+2%_@NwhYe$y6@|HS7SvG)Vzw4EaPrpTqQ!d#W<7 zYZYv>EuNb_lQ+k7SAV%mMUr}os@>@GQY>wT$LF0#6T0jk=(8w$zUyD0_)jH(V~*X~<(^P9}$y#z4KD&_gGmbi6AcoO5@}r<=VZ zUN3U`P$SdXLah(3h(?Z-9kZ{YG8taq_h;AM;JIE3n%R3%79PZs3AeeSalyG}E0M4a`eDVP6* znwL=dCg~jHDF#xO{vM3@R*!TRG%55TSRRB&#J%6fwPpoRD@$pLFU2>W8G`Jh`Us9* zXh%CluoGsvgwmlu0sl^LlzrNdMHoVAHf9P_hyD{otD>l5bRiGVqfmY80x{{t3qQXf zLm{3(9!0M6*ne4B;AVDw5m{S~$4BUd-jxZZKnW|9WZxkQCQz_bqnZiV@TPF|lc6eH zruG1yE{?}$R#G6CXJb#r)(g{iKR!v;@}km1{K)Rt*4;>zFzJNAW|Fa+cW6``d-u^i zb!nQH#WGcPMd&ITfB9|Fq2gq58-;RkuvhfJIuq_$2?rdiCIr4sG`DfdEah&8>RW@2(?W_u95GID3&%x zo>m|AUq!esv5ZQ{HrJ0~N_PMCJSo->agXqX84~tSKXRiJf~qTbSx=T*dD;J_sgYCw ziga++MtOi=2+lYEbBvbr;NOd!4OsN&z?spSqbdJu{c58Y>WyR2r!7ra!YF%D5eZNSBpFYV8_RA!?8P_n1mG`$& z>?=#f<4ap)%5kA1?!#v>!$9%J=F9(TQIkD8zTtw3w6>9Tyxeu_xo6c*!i@~!Zf&Qe zmVm&QVyFMykS76DKOdKQ3Kz3$@wxcu{%9JPQrf8bB%Xp<0zCcU-^ylBcC+^W)T~Q9 zrMgTGipVd3)CDTNsblQ%T88TW6)Eyqo4CxHB~*XSg9Kt3RR}fw%OWies!?>^)iBy_?$y`N^=ae_5B zX#2B{TE-UagsY{u(w0j?%0#wv&>w$g*miGSiD+{_;n8K?3|&mpxnXNc-N-k%X{blo zL08RKxckCP=-)R6=u%fg1WkKa#v{FgoH%bGpZ=VcNI;t=>hWi>ESup3A0TW_j}wN@ zy$pw+9^MQ^rLCZKED<`s%d+~Xu@n4|%wtM5j}*kZ+7T4av9=uJc(3O*bf6a17QH8V zN$DLx%pI1oDnaoGQ9f?vVgTQ^twA_$P`MmprOZ3cE#`2gBrp$Y10n-9y9FbIMvfDV>5&rvz~jn*i1(^gGv8(P}q&N|8TRlqQBuOp8{?W?jgU6%g8FZ4#?$^cho>CwCLQKTzG>E@@v`qO0H0UWzclV#dKv*KU6xP8)BzEY)R+Fpogq7 zVRuH}Dbgt48rwap+XY+y+0w0@rb0UxHhf8QSP{Le^ANn#-Dm~ww}S`sa58H3zv$+( zFM5iFOEtQcX$V*u(b`Pe(et7HCa?`=%<{KmD9+7Id z$kWv5w#*82-bf@}xy{Y@DLqF%sJ`YM2dFlyw+K&jNg!b)y5WF8*ad9T9<6-adn8Ztub4}(7F3lY?d2;g7 zlTRleHJFU=VU0*K&+$M~(K0oV@-&yLwy^Jo3vH(B5;dNMi~*iqH<<(gB=IbAJYhfZ z390>2+`fO*izRlTA!39C>tQiu5)pXWbG5;hvB7#9HH?g5!2uS$>=W{*2~r(cNDv~_ zOI`)VmraCW zm2~P_6a<)JE5NC+da8~wdLaz10Z1ANX-nrkG}LJ?-y3~0oI;CMtaB0a(x0<4p^{Z1 zK;wAO*seKOsB|b$PlbhY4bneRYd8o37uM#1o8mwd(GLd8e~6OmR?1a$jlcb8=$L0QKbGFApsK-j0nofJcuntHLpATy!5- z&e+^N2dZy3te4KFIwiT%H$J+SUB)|eOGp;k^$?(lBJ=94)E`;gbpDJx-J+38uD(l$RX7)cC29(>iEan;kL)W?u}tnhcDZQ z(Cn{#jVprUX&XTJ{_&yjolg6P5At6f|FDYxn`hw{Cxs-E=32CL#TrO!_XO z=>A;@&cKRZ#G$Ucn81r^RhwP!B^s?#iE-WT&jHHj3)IJH^a;vNPPZ%Z^7E)}FEy^G zd^@eog?igcXHnYR6=xMPVQ@CcCvVv4S-M-%=J|E%+V#2Zw};d6uP|(B-T}Vw@gzWv zD+{m?3IbTDC|u{Dci+4=<*chy4=n>QR-VLpa}c)hJcZTZr1Wsh*%HM8%B&31bsgqxNm`O6&!{FmW9Be>}wDZFkH*KGf_qv9PP>#bY zLn#?=s~uObZKwUH`}u>)f+{?4QAkYEQD7m29BMUS)SQ%iC4X_}6w4Q`rtO;5B~*+X zPWo~UQT^?#`ZsDO6p!i)Yffb+>6ZZ_HSO@eT$v&Lm;1KCza~tJ?&kTgKIhpT?b}@$ zlXju2tP?}NkrD4goQ`3~wLH&esdn0WZ}C!$+1yZPQ+E&LUn7Okt~85)+6brGX%W?( z@KyZ>)W2h}zb>3ri6Z#xY(_;xRsMNep6(qE744!FhSk>`-efsqUF`r&K>w5hX|WCp zC*J?FFosTc-J{C2uIDs`U=7iONl*3V|7DN%&^{#=W=V6@ve-s7?#ED83Z(&#UzaW( z&Nqhvr1eUwfZE4&d5*bzYX$Um7&fNl4R_E!DGVJ`fZuNQDGvE+u(6Q@Qx{hKkgp1X zZ+mf=(vCo6`btS}s(bE(sosUDXO&#L^N+OXkm6tJ)LS|{fAx%J&B)U;8JopjUzU*v zgKLGmrvh*M_@}z*IZeIYo4D6&DBJtUvO_x~q;`OmaL0tNdg^M<_IgP|7%C;+<}%Eg z`0V6U6R_>8(^MUN_g@4c4RLFxPW|8-hVDcD+K*UY4;i8OJs*@Mc>2YR$!kZ>I9m^e zaMjU?YW$JgmQ%Hp9|!UtN`W^i=W=Eq|DiGV&y3wP8EJU__y~PT@b~G>mvOX$&o^If z9GTfjiuT~9+OjUDaI?2_pTTY|9uOk?C<0w4<9!tP`c2n#3L;aYqwpwb;25gg3c&ft+`+C^q zw=+$l#rj(+{J*UN@X7{N%#u=G{o~C=+EFx?wom|o=_bcgJqgzh?Bhkc7Rr*`tL-YH z+)9-#VrTm*w1yNks09l4l`)=GdVc2u`z!Z&pE8RaO^k=g94k1XN*fG?kD}DVKqRcxwHV%unSf|AjL0?x?rN-FFEp>w?B^N>_!a)T^6kZcyYg(do+04LMn&oQZ%K#(Yl`@*W~8gg{*%n#8Tbh;nQw zqCiomO_mHnv|r&&PK+CGeQ#bxq)4L!(ZWeiA0-bo^iFcZ4P#|l1j;O981K2{D+4Ui z{YH5H3Us%vORUb}e9Bc{=L+Ku!9J3V-t>j$RwYAH7d;`S$Qbwz2<6-o<@EDpmg?4e zr6J3#p-ZtfRH8}i%FI18jFIbv#n?*xg!Ln${6xOblS-|CCVDwZ*WnLb8v*YsJ*lso z5Wx3>TecS5do)~LSdgk8IPIpgf7Y+!dvc>ge$L7R&PjDTx5=iEgN9-L0+dM)c_}tz z>(e5!m;a9a4N5WVg2Xcdx}Z1c%-yS$eYIcPc4~%i^9B%HKkfDoUx4=Ho2iuy;?D z@bL;2GsTZ$07C?(_=*GL;JYjBKP7`U`MV@PW&SpW70_ip^Fz;*Pln3COC(X_Ano_H z{g*TIJ78OA|NcHO)UJX&t~a1YYxI%%H+*d*+Au%mlaK!XJU7!L5#~-coe^K}+ZP6T z0EFk_Zsg^vzOSdIC@{d!$N9y#$B~6a&>rQ(m3@z*Wew5_686dgPE#zKAM?d#FEc~k zrn$+$l#q?SePIJ&W;GqZ^78kGPFq=7a)bGAx_YJDd!3IT;Qn9FQp~e%JO~lpT5Z=@V?@s#Y!m9k~NLA1jumhZ(qtW4Sbgmcpj8I`ECX#T=k(tc_0!jDVx^y$B@d`0G2s=1wtJXnZlxM5VJf0ZQl}0yTy~p zk^qdum-Nt|%Pz*#h@xbY_0G142v)m%lcjb8bl!ytcR6J$gq+0Tsmyf$Jo*&%;@)LW zgu;v!TjJbytBSYZkdyS!t=6XZRU_Mf*~&9#B)5mc7#W5}wzW<5m-OW;OL?U9OL7ry zkTb5=8Ba*-{=^GTESR{mY+5 z@oqd;Gjo#xHWkWUg=+NBp?|CD!yhTv;*38BTd_A#h4D>FAFKsUa*hu+5?Y0R+y$4p z3?|0;a%ei9s)v}lfHk!tD0@Qn6yoE;_#+#F_!{WbhBT4soUPvE5&1)Ri1vF>b2@qxPn04f(gw-q$_6v z-C^;%#ba&Jy9zwyqmwwxe2-~a7dh0UU z@lRqHttrUjNrv{}$|T9s2>*vVn?_qc-j^!V~~AHMcArKt?qc zd_~o-0w`l<&1Kk1^u`3Gitekmb^seBR!XI_Yj-qpy^1J9z)!f0Z#1Mfs>QlSfsTvO;dS}H z-wu7}Lf_F|R~#_xOGN#=V;_QX7!?kv{rur&h%XXmHU+DrSm<2`UX)7>pTNJfcQqyj zYPeA`oxkimIhT#{iQE@^6^!p1k=cwi-=-7ozs}3c7gHh%4+$IT8pb^3e1$Ef5tlAk zs}rhu&=aJ6DB;s-ubMR1r47LHKvA#gy-;pU8?n96;X8MWAo8f~+rUWHh{l2`&=%Yq z)BDNACyp)Wa~JaPL=|E%jfJp6KF3TaxcHo_HFp%i9=<7gw~>3(>E1d7W1>#Ok;mu6&&kNA%kIgRhz4ig~a<1UYm{zAq z21q6$+xK=i>cj#-hBRA!@HY_(c@l^8iNz1INWb?a^!^h?d}En;#o|lidoRv)`lX=Y zp&dLVcY>W!YXN2;;L(a2^(5p#FX$Nxx;~0>B~uIryNOE`)sSJ+#=I zJs?WH-n4HCLe?Zn?P}7%CL3C^CA&wUw}_O=$|ksMe8B<(jcAcM>+hh^U^Gr?VJtB2 zGo=YdSimX_%6jp12AODu1*GC24na;?p4#Sn7f}yUx~@x#GMC0w6dg!L!9bk`iWI4- zY}eqqFf!b?1vFTLs^E=Qc-mgZ@&;6h20zV zJWzKJ6ptWN+DH!iT7AhX8^;jKNh*%SLH!~4;G(0CP+g0Rq8XDSD8hIt)G`B=n1E~` zN+ojSMV*_ZI>&ydkWz_AIh~w7F1jo>|8ENE*Ip8Ybp$z0j%Au{h0=ciL)za702D2Y zRPCvu|GI{;j&h24zII`V?lb9A-G%E3s9^rVZ;e{`xK)tbcOQW7IBxg8k&X4#v(P%_Y zYb4hA{ukqEOOuDGCQrIdUVJf`w={j7YWl9rG*XB7(b8XbU%geVsF-D-+5JQZJt> z#RZoCJfSs@oGmv*T#q6!t^Zzdbv@?_p%8-ob^j$>ZZMK<&oQhN7jRGMqyjO6F(rRj zY;DsBuPKqMC!%fA)0SB3s$ZLE=|+`bY#hW5s!_6%`++b3$%{oDGAAFRAk@Y1SfaF` z%cI9iw;<3KZKaD$Kpmiv&&hwt?UJeRLu89lOtJU1^=-CI-k08%6&2v-11%8?t|?x= z_v4N}U-vc8rNBzILwXoHiWoRWOVn{Q4%*LJk0y6;@B4lJA3o?T=lL5c25b%raLo&_ z4hqQs=zp`dd23Igqhi4J6aE1Q{aukk-VcL9z6H50280I%Ia>$EJq+0MF!-QikVaFW z#tG7Y>!j~v+Qe@*{(L&Z-2YoEv>oQq3DB;_M3CEeJF|mQ+X7OS8PSkvX$;LY~;>IUW6(M8x6-B6*=qL zxoa^Y3yM1AXs!*}UsC-5AkLd3bxDC6OUwiaALl;52SNk+I1t$%jawvg9iI&+?;8Yb7l!rr*7V zyV^}h+i@BJM7UQ9(qE`pYXi>|A1-gsxHz1BKP1$<^Qd87&Qa+cHS!L5m;Hi_3t_$Z z#puHu6Z;5JH4*l_iVkfj z$5=F_i6TMc8uGDT@sy5Px z|M~lm7Gx-qkJyWRkIWh;t&idFS9#w$#ai2QFpjTytWkkst795MDxyeB>m?wdN)0wz zNOq}X6gQ5!-*IqHSfom7V`St!0id{qyW~T}3FCvf+ZGnjPwq7!8yvBtqeM|x>})2# z=AP+ulD^QyQple8fqxi&5(Lx_Vp(R-Ct!r4q<#X zc_y^953SZ|v+@Pf%$gf9suO#_8EUdr#VMnO!+UG%^vDH(xK?%u309rH9iw9~ zXYxa)UTdLrddCsM6XUvb)r&id>L1j^iIMIr4gdZ+3;AubgD6$N^x3vh0dr^!Z$*i^ zYV`(@&v!H`pND?QGTO2P4574S5Q$*7v1U{}r%%s}-`t~(Iu_a#;J!u(G~EnIIlhDF zV&e3j^O_X`>e!KDh{f{X<;?QSr!0`>OI3bhyUpP@ zDYM)CeO6n*In2_>t!Wk{i5WU=oCOi1rdR}m2kRhJ%~q+e?=K{)sh*twz_=IFvPANTZ_smH|l=hOE}b^lJ7(1oNM7jnuE_hXO(j zwn=BvVUH@49bhXxD|EXeluAvrMsQ4m`Bk%pL&)p zlZm)HX`e7Hbsc%*#^Uu&(3?XK{=4-jXIuh&1+<+n%JysOc6?_3ysqEGqpd|E^~8e% zjrm^>n}7e4sqhaZ)Dt2@S^MwVt?i>*1EQ3>*+QuZW0~ifG891JxYi4K@#*X20k-;D zH>AOAz{v7%CQ)j>#cR-yjNM*u{?c)D+u#Uw5VzxjlwIxU5a%|#V~V9do}x9LH(+GP zg~$nU1~t}u|By<0YqFjjB|081iWn!g-Ic-_gG5A3_>JwH8=`?5%>#xBPqTG<7)pwR z8qssJ5k|>}C*-x73iY5A1)-?LbKL*0wxDQaSC-)qAoOScDHQKZI&SMKpBJlrIFcH8FnDYN01#>t)_Ww)4 zJWI*@e<_%8_s%hzz0P>`v_F(6m<|Vj2L4aM94gW9?(KL|v-6+!o%eb#{ZGMs>SH8P zFmGgjegER#wJWb~vtUx1K7E4u|0$Sn_C<9rj`6g-8xsA?goZ(;dM3@u_&rUet)-gV z!jdY;nvU_y!t2&v_N~+eyE|I{Q!u4M#_!*__W70YI2rTF68e8Dm~W?=OLyu@6wD8E zL1B}VH*fs-bfeXBW3|SGA7`d~@96G-Zrz-NDqD|-)DfxhMfeb`EqQm-5%yxgo|xsH z#eOM=Cey{a((g{~Mu6^w`RJ=A@pUZhF$;a)dml2R=K|4!$?@60L&Dhb?9}Mn8>a0$c94t5?3rJ>cm^$!ae?9K>o(l}=hTnm1P3XN zYr)Y1O*du}T$`@b^Z>T|TQNn|+#CzEW>!l9OMp4Om102VIl!|5Jp5Me-{d!={KA8z z50Gc?x;!eeDz?q@pZ)0D+Mu&1R8?q;F^>62j-w8Bl`d*STeb9V0v!%hTYs;l>FKzP zO0*t$c^#u4yKQE&lYK$i^qTv9ENj4 z1ybo~8;SRzLUG%*ZME7BKcjo@#`jGpKn3vU08s=7%AJS1-JJp9(9^taX+K>bR3FHG zXVi1NYLn%_tk1x+iZwAcsu$Gh-7g~Q^_d)9Mu`>_$UXM7bMHn0~6Livkq1uw6a(GJn7qr>i0AOcWP&GkvPR}dei~wQXWs_>8q!n zp$z^I$=yPr$A^jx4Wo*yhxcbn%Ol=;&B7J}D*DL<~X>%2T+t6%owA2gn@psT%gxG-+;6=k4J?toP@adTpURek12 zZMBeiMNKRN;UU-x?d6%n*f#XSt%CJVt(d@Kn+_^(bApzt6zx+g!1LAnUeZ$0X|v3VhKsT#J%G)+wz-APaY z?#j{Sflh`|VA@%*d^!C2JFvtM3w#R=q<->~Wv43upT+tfTiX4KPp`K;uNA$~{&JkX z4ht}ID{==_-34L&RtRSxtxyK$v2*BhKwTY?#(E@miBYpe11Q>R2eC(T{w#)M2HhdE{gpTQXtmQ(>j z0nx@0+yjVFUBe$j1SHEVV)4tP7M}C zeFpo+4vRifc6Czo2`shUT6fK`3nKTwka5PbE}wYeQ)MybZs_Ef@XQ;$nD}4!m|O1= zu zg)D|}ly}C{9K*E#g#&h9Qm%O{8j7%!>t!bQ_ZC_mP<>>Wa9*k@ep}r2>1N*^m!F9| zZQ1Ly7UPg}ewW^dJqsIUlSPP^Mc|IoZ;ymB->FK*D^Y4{WQ(5>)J)^Ime=l=jBWi) zO(ua;lfFdBYn4r};9ad1M~x!Hg0ah-f_25FDbplTfvd@ETb-RGQ3I3_dA_T2z%Q#t z>Es;c5J3D`$iqnQV(tf))PN2hPnq0*!`L~|0%GyniSt`{?tQTONrJ_&lK<@#YPh{e zO`ewSe34tj!nN}oHTgDU3wt=LpN}olM~5PzFzMN)UY&kgwj!srAg)#xua3Ty=ZbVh zbERQ-xVP8r5NxiasVzFNsLr&?;4lAO5+P4%(4?%85*G`KON9T;vGCb}CKgmB?-v+wM*le6C&*Bkh6c ze(LRtO`AtBJRncw6DvInCS3MbMnmfF|2e3XYh@-`o95geKd^7<*8l{mjg(8umW}y? zUNhcUJ{Z9}^8v1SC*V#MBpKJ<9J9LpZ>DG4XLSXFNG4@Dce>)!5#PE)#IrxZMM>0y zkAOBxy(^Tzo_~Z4$u)?~+Ar@Tq8&9A!83H_KgD>Sfhwg?kTD<%V5Oh4b%?M5m&X*& zvskD#>_ReLOBfdEfdhZY*P!HQdv~U-B0ECx-iN}>h5Kx2Hf+34Wpw0z2nP@x`Pakt z_Sd69Y*u(O29a_A0Hb6`xvj5vjIN@Ci{$Ub85>w2y<=JMMyasmScmWEyI_`w4!1%( z={hqVI*-+fgU2unz3p~U2zWDzWl4e7dq`xVd_p5Ex)5YvlcNYB6?(9)jdVE^*6yY; zC}njQdn{*DN)ad14%-x%OWl!#N70uLi3Hf)Xn^gub#+YPS|R8v#?x4^<8ku*t1$i` zOPzEC-C3fK*AI5LJ)`fLAx;wUITEN$%Z>w30PDO`dPNbmF%>osiFk4rc#d{mlCAJ;*0LWo~Lul1NsE@7nR`*#^>5B8H#87i+ip-^; zJoyStjX9#j8U+cJcLrdm^_BkXJ&teFZTLx5)hQI2gN;+z^vrBY7$as?@*_c?WZI>V zL3}KvUMI&QIuWl|VP;G~o}Gs7+z9}1!^i0GK>6bv%Sw;=kncY&5A?}3Q`rBoS=Ytb zMxn*}ql)y!N(39SSqNLGQTT2bx^4}5EDrxt2rdw}qf-uq|2Uw!hJ!+OLn{DDTlDKU zX?q}HbF5;$AwBn>_)oz~E*OQiWKc1y0syh1)Iv=a&cWcA)gMQn3lm>cU`iFzoT*fV zsK)Atk{$|hIk)T4c`f=?Jl(axI=bwV;87!jR8aU@MFJ%wj~ajw z6mXqU22H7U_r#q0QTyeBa$XSHQicD4T6WkIBLuO)(+Z|Ja$PqA>CmWrC_uX6>|u=5 zWj^;Vy;9++(liAz@|v{?tMS(SI3TF|;F*0l6ihRhRSIj0v_M>6MaRWTmlN|X4K;qE z07xNA1Y)t->8)Ad7EoqePxEe4gc*3k>#q9G3>3Yl2{1QaP?0{yD={$yH?6kp3fqw) z5h{g=(9VW_L3#!qc_9?s>6N=XOlcGo-f!YaFb#1U*>kho;b}acSv8GSCX?Eqw|?!G7gwbTox7 z^9#hBRPb#BK>(Nnf;*l%$53Fz=;VXlPry&7CCUfB3+zZ@IEQCTh zDXcb@0eJRZ2iR2BBhU$WmvTNuq0Q})Exiu{Cdb$(!OwD(r z?--1F4#BSZmX(v53I9?c;TIvBST(_h+Q_GxxiU3K*%u1uHEQv_=a6J?2pq z1i7jor){3e*2kj>z1!+S7&oG^stxDk&!b44Hyq;41m#kVTjy30w|LPM;xbt2*?$!;utp!FK+O!A|g?4*Uqi$ zc6%`4?;Km9o#*J48Aa;z1RarT9p^em&|q8MEb^nu=> z-NX?nb*PZpPNMgZjfpCj&cUZKrBl#PzlQ?nx4zewdcqpO=!3G-O4?FN`pFzg+r=xP z#aJI!+bhX75quWcc^wO=)r0QhGdk<&*HfH12Kq;Fa@0n>qPYt=O$HzUEvlb3wv2Yi zV9KBN;GMuC;I!skvz%kTGwn2jEoE~4TB*7c`Mv$Vh|ROala5H>7?At&?JaZlyYIY_ zuM@UCi3RU~0~aEcl9)PiaUlMecuN~Xuv6{E?T2>&t+jE{d_C!=`C3n7%c7AwjzJ`*_1di z^_()*y|&`z`D)}mJ2wZ+&>u(O;V=lqcf)wb=A)*edXHgIYqc%{p#@`mz?x zo@dnOnrI4n(kC~ghu62~P2H?9!s^0~bU&#%&osO7c&f8Wy(%X`^|Dpd5R9FrASkqM zjCblxwh?%s{!KDZd2;jQ;X_slr!Ii>0N?iX)?X?O;-?Rx7C=S&1#Ai`gYiJJReIeE z(G)9d0fW{S*tAvDej=o43-RnmaU*>CA?VPa-Ut?#gMV@~7KyiVEf5hC^5>tu(CBJ| z#KEuLOZYtjYV6c-5m1Lql#i~X(S%E1_WPr=&+asVC(22$lOIS!Ab-l^^3FGposoYN zB6hDr0_Fg&a~epVL*VEAzn25a1Lk;aJ*x&j-$L-!x;WJ&B7;!gG-|ELMG8pR0^Yf= zKDg&a3Zx4jIb|??ziw*bU>9J%AC%5}47Herr9h=tA=+7wAEm%t^A1bA)F#{A3~SJU z`J}%H#-D+9H^XX7Zs@YI(q1pZ8kw)xI_&Whk`xv|M4|RB?N|dGw?1&s5NT-kjTZI< z9*Z3+g}K6DH5+4Zz?2MVg;2L1Uvx{}lm&Zlk=4-rEc2M+J1Iaj7u=VPE=m?+){2PW z-DdZ}>PvX!+$f$ZX$XMTTEI?KLE{?U`Om+_Gz#w8Ewf7>T`>eb_=4VB@*9tF7~7Ry zDT~O+_P0jh8JY3%%L)%wKZdc&=oC98wZaqZTg9CcQxc&|Qo!D>K%}7HoA9Q!iwNpW`EiXT#sMAk z%=8ebgsc4d2R&aYidjW(J}tej3tZch71kiKK=}H!A(zx zg_$--%okvc^uP>9Xy)x-Fnp$NveAQWa2-iu8Rc*97RT>yy_T!)P)D$5W6j+`{1nd4 z2SC-y9d#An1<$sFNii@x;cbd6pey)-n1|Rg4%DN{KY!k#yZUdp77V~QaiswSPLo!{ zn0G0_X>8>Z{1#{>iYB{S>|l%T$Nnz`Q`=pE2(bFUP77UVhkTCxp9*G)2{s``XN}_) zgpz74>P#-9Sv#A%(GW}c`}s+`2szPUfRRbS-Tl*R$$N(^K55HY6}2;{QKR6?xya-a zktVulD#s!Z1(f^zPr(fNyzAEg6wETvk2#qCaZ)u8CMpK<1FF;h_}u6oWsl$?EOyk2ak2CL&jrZNsH+sQh0F=1BRb!oDvu zD(FLaHdS+{18rxGQNv&m7%sYwI%q%}IjE)vG|Q((LxgF+ImYHGFdkJGiUp)KxWSCz ziI14GhSH(}&gf4h>n{N4I+Ke8dmT`lxaKYxz4}k=JarMeOiMcZ4qv1X_cQyhoxqhZ zg+s*G?34^qtd&RXqB{Hj(Y=-pnM;I6G$($z+_#{8<^35mL`7c; zy+9$XEu9pi_^g{xNKMnv*WjccY*dfXFN%;&4S)cIoSi-VL%ZoexWtrX5jRn5rj4p` z0HH)uPHpZDD}o=e3Cfdox0_#90wM#?oiy}4-8wnS$jAmHP~9ciGZ!aV&LjA36AcaQ5c^ zQ2z1%?=_2=%NShtow2WFtl45P7;9sTHVxTH_K<28%h<aEi1JKyj5oL|ll=XP%APnc_7uh(_Gp3mp~{wTGdKl^k2bSO%+guBE--&tJ(;KJ_* zJ_Mqvo?i;ixEWC3Vo5AjQGedIN0wGD*xqG`3Igh*elkmJG+@ZhUvicn3IND-@hvA^ zIpFyl%Wj)bdN9D7Vk72j(z7C_f>0pSfRIs@uaj8d&6G0_lc3q~agsTHg3ed4p}Fn4 zf;4j>LD=OYRi{R6%U?OJolu^G_f*btq%sqQqv5MR5sXa-3dXzbjl1+zGBvzEkSB?m zvH&8gYQfi|HhtjDRKa;n?;EnxW+Nh~w2wq#~eCYdh`Msfs z*PMWg1C|>+KE9>;TgzARqv1-XAOh%4Fj$C=KofVH;DUn$SBjI0hwi2tpEadDIz>gg z_*ag8H!KVM$;EOAg@=Ou^J=Lp=C8VuA#PJl#^k8dpUnc>USBu5_zauBXGD8&2oW_N zh~d!!WtRTq0%|;fgBEGugb3G0(TOV-Mkj~1rDt_{D8lxDR;u*MKn_V3pdQE&F{|p-1gp1x8XED9oELcv5bi~hKdVZJ3|MLaT+3r*R<%o z=9QO-)4s{IhYPJ^*Zo)BaqT#Fe3o}#fcS1cnz$2{6EtDPd=o#?e1cZvrc-otarS{i zR+{L7POUxl2*H4vfT>-IA4UkD7aU9A)65vNc5K zbe+|mwVqr69m#oY89&g#KSg+bIbJG>Yiha?`5fK$Mk;CnB|W}`y%g5L zou0OxdhkyAvx>`@{KqGX8-&rs0NE-B_J;5nDetWOo?^GqTHLhcE!_`82d7;Ro2d1I zXKUlK$;XYJ;c4mn%wPgQ{1vg=0*_2O9}2=abOzOuwi`VRcJ z@;wws?wXvel7z~1BcI{t*l!Hhei$%fKi%cLu9ARmObG7x`0pImM^AK$0#|$y&Gi~3 zB2Mu~Y@9YRO}({S1*(rV^Cu08RZA?$6Jsl7B%%*bqS7K^<><XdCP^K-1BC`Q;yl^Ls3qyx3ojOwGRP;^y4o>=8gX(OTBHuqfU<~9(ivli zUWr|r88}Ya>yL?AqXHlM7a~#oTFZhdKodC z=Z!@AX#kHp=()q=YSOiLdrGQ?ZkpS9D24$_0PVZYx*pl{{Lt8Pw-p{Bc>!^U5n_ z?4{D}VcmODB_EL$8n$NxfByJ#`}JK9Pb<|LDkQ#%`>JeO{`=eRxRX0zD6)Fj7@l{k zTNjYLBLDIp(nZ(L9mV!!R<&FaH9#R|3+No0>reg?k*wcry250-Tbl)ss5RcKBa_Mj zhpw3HWITDOQ7wb!=PDyfQlUNlLY>yST9`&*5xg|to+WA*`$qVk0YzDD5lQKpxB0q< z#bicl(RZwr(grn3Y-CDmG^;La5^S_*2KT7s11p2NNZb2M8A3Z5S3E%6WICDez7f`R zxAZ;AYN;qjS+EgN9e2184apr}u7C|alx^JR!`G}y`i3K--roA@Do z9L)K*s03t#nd@{I8Zr_#b1uBAuhj2?w6ncBu=aB(X9L#Y1bRs_nlZx%kFxXNfaIUr zTu-L+4y_X}?lUv|-M__wto2WGxL}rkd|@~s{+@F@SZmIl;b@$QxBpDT-PwT68!%s+ zRq#%>r6_!P4Sn#Gs$${EP)o7{{A+n!)Wpq2yx%R9)ky| zf%1WdSE|SC&mu>uqN6mI(r(3325~gaYcxG@l-r*hiWy}hYum^257_CXSUDHtDtPD~%tc{w^yo8588nmoJW83~aBKqNjnyWk@RC z-!414)WVvOh2NJp3){0Jn3viUCVTmIG-&L}G^Nqvb(kV9%-fT2>roS9>zuSC#+5o| zcrs0P=>fjgCKE#F;lZvU$9GWK!dB^36>~pRlkT_W7A-^cQ5dWpX5t7_GiP?2gPl0| z@aWASZ^UKEB5JMW>9}&4wh@~*Wv$Gr8#+vRz_j0jd5hZRI#9)e>l#3BM9qwHv@{FdW=iW302>@MZj#r+39J^JWv>LdTGN?Dvs zTIl0ELNh@`6~JdaYl16{=D9jMUzns@s@zi4XUa9vhlr2A%H}_>lV*~M)*RH~T(CI} z3<}kocJ!)Y- zyO0_%APu8B%$o2#$_ZPVRP`rw#mHVW@L%y@5Eb>6dxO>igF3+@w#>WXOjM6a;Sv%@ z%C7gV=PDyLH;@7qa9^@*ALW7IwFCT20Obq*$%RSaDl*tNo>6r!f+O-c<|PY|)}Alt z%P(`NRKZtAE-Cxc5Y~Ts;7}N!yovK}jg)j-cd>+qB380^ds4*ik61zRt#BGmL<455 zVUkNKLrIw^t9sqRxyUBLEow_2rHRRHDBG`y!KR9bM4{htD$ZiOG9*3^r2}skNShW_ zEO%^S562>>bl8PYCdn;p@`+8tvwq02pE6Ss4f~wNgftXoW`}%My;lxD^W!wU=7I;&57H^cj}-OuSs41)yd zJDE{8^E@FhOJ?IyXuDJ=#Huf3%1f5XKvHrn=ekPiut8eCtVG^XF*%Au?GCM{sYD&g z%Xuf^GKZTh$GdFI(-^EImTSB&Os?G9sj4cUi1nH%{^ zuFQsXmTU2R-C6H$>j%#*s=N<9X#W7xO^VALZPG)_RR*q!ZUA}S-~&gPJZHlC8}q*l zDvj;ey0KFJ$%k52=O8=`_U>U1;(+T}pTHQ2N>ip@At1q|3E*M!ZLUXNd3Th8g4`Y% z`N|*J8sH0w$v*Nn`zWI=Yu_kM6og3-jtH}0PkDg8r!Rvp@z{nU_H0~iw)^2k6@B2<($`$rDO%;DJZ2~L<|8{-1$b6IZN5mY5w>vp)CKHiGVMK`B8L* zC{X>=bH)CjoOi$#uO3IOQPhTv#n%Gzc}+EVP8@0Pq8-L=LFKSx%ef&DcQf z)k}XHM!o3vPO}rqVx{GkrP0YA0QF`zB@EDbU(o~{Xl7ha9L1SbGlBGaV~{*6cR>J- zW`*Nd;6M|CYfUv{zsoa;5Cj08StbdfN^5+egUGi(!!Mr=2Ut`v6yV)r=i_P_gm*bi zKy?1YJ7f!JUZg4S*Mms=F9n2NC7#^fTe7iO7RH6FUbmUZv`^S=P6u(KhUjC`PEP%0)ajg12!M)pnBac976k82^tg!2?0JP%+0oZ3!J;HN?jpjH03_fFP6l z(=Eo!l8V)c33rPQS`5Jwt_efnqVXkZb;paoZ^HW5m)fZw6(7=(ehmC;Nl$|ByQ1dy)wt3x@AL3;l?crhjQr`LD7^WIt1Ai54l8 zc08I>z|0Pn`?@zXt0q4zo&Cw{%a_WgVt7vs-ey>Qi6&RElqHE#s(8kXKEMYs*_zOU&vDPD}qMF4bakg)Q$C{W1(;uKT zk)QC%u}hC%`zB}>Kfjz|iqm{Yagi2CEZJ_hw-UOrlh5|umH_C!$G(3L%dI=8cd>#e zYnd6$&a$#w-79%Z$*29PMw)OxGx{&H)r8;pbl^J_P*O%s@iB~3Zx`yOZ3D4PlS&E6 ztt<*mX0o5ONIh-IRgeD1iP(xby_1=_v&$^s$!grmzQMeDYX><_`Pf!ti_xLc}M`SWKEB+-zju$ETPx2RF8IaR>PC@2)E@km3DSGke(g9g zImXNfiy!DD#sf46z+r}xpnA)|CzFW#u}cRxl*P3 z;y!KuGzd*kMdt5)6w_&Kn(CGLeO7&Z;GvY*%pncO6ABqcaMKljj?Lk|Yncb0;mjj) zCE=war#}5L-QJKMX1?)l$R)g=HX0OX*0$LlaH>!veoa*VIp5HB)Jy5K`JbJy>rZc- z+O<5FT_!O2GrzD5e$*Qd?BUaFm!J%;-o`Qb&315ULQWejxDznR1DxGrF1aR3*I71CvlPk4`N`LUE92)ip#+6H5Z>S@A~a6Pz5H+#*nqi(=b{qypK z`DFF#jY$>Z^vQp`!1c&4xic6m8!ZTdTH)@-I#TIlKI}A)szn&x7Uiia;%@Jl#Gj* zG@0w({Wc$=E1g89jS%XV25t}zSm;60q?KshL0;`Xe4}1>+u8+xK$d~22riqmR>Sw{ zJ&-#SsVrzfmc2h9;BUsds?gG>|8RGY$O8m`w^Cs|Ga8-J5HF_bt(UzH#eZK`=m`uHA3)R!KDk5~%z_h>?QCwTiVj^Pmi#mQeDZVD zo}2J*tFr_{)lM3cEIp%ajp0#b9ks)Fv97y*o27k4n1+$r!elAB^U0GC4Y~3C+`pIW zcKVZ_hft@;y?kN#ncr}!dhO0#S0fcqSE(T@Rta+Op2j1R=7u@tr3&FHjY0~Zy$YNW zEmG5#8$zJjgnwFBaG`o^Jk4X&AKEA^&SFK#>ys2Ze6AT@^0$JIJ=&g~5tAs3R#s{C ze@0)w7(2zvDBYql4V9|XMHPuAI%6U;i9@Oa<8}h30#0znEEtS{jC#-fkmS?ONXyMS zQv0e;KZ!+}-RsC7GsEkNrix8%DYn%hB&yYgg$yY|$e+hoqc(;ctz-PllbsbLJfN?A z^)LlPCOXhYrGX>}h#HP&0~GpY*))gAmz;tN9WcJGQw7zVQm%>9R8$(f`0aZF$_Zba zHZzR-XY0q4NQdoWfo7^eG_R`@plZlpS1ODhR~GCjAD!T0D4z4`J;qiQt+63=car#A zNnfrDM_22Qiacn2Eim>bc_g01PkHgEWaebmn&`nOoj{CwRN8*Y4gwNJ$vz++rFF?% z-O}`ax@@YaR;{Ot$}b>WbdMfNpJg43x6?{qy;)Nt9HIh;jpQ?_e3*(RrCxR#v1$Mz z6RPsLqL?l@L2>;Wpg}TTpDcA7DS-+(8r&poMDAnFz5LErQX^MsN!G#YPnDe+T9;(H zR{&WJH9N{Qj5m~{+rK>u#QhS|NW@hfFm(HZu~l!5%}{$i;mCs#QU9rPLb}KTl&^5l z@u%)OH`&~I*EV`z6iX>kQp44I8B(blHA7SY&mNJz0;_Lg!_Ux~k%x&iKArETIrUUj zYYJ=s1W&x3cv{P`j7l41 zbcOX_aU~Qli>=}F&UV8?n4Q_WPf=1yP_l>2m~16sPNsnxK$~Sultecg-0TbH0gR$H zZirq8P5re5NNS}ePDO%YLN@br!rKOSPJ#?{)kVHtm-@f_3ov128g^N=an~(ISk*I@ z`aU_WoZouU#^OQ)sxx+YL52zM=%m`7%g`aFFg?ngAlCQR%A-@8nTJsQ%Wi?KU&A~P zlx?!0qxQz-iUUF8A*C#_hnGOGs{#(PLp1Y{S%go(re~ z(;nk#h+29>OR8n6IdZUYekym3Od`y|MA1DFnMEh02J}bOGANfF+i)tzi#NT`Ug3(Ow=xoh3hyysKQ@u8PLrHp!> zzA}$*x%28%26*T7p3g<8{5StwBViM>FED2UE-H-;-witZff`2?MMylwCIp7q`gw)$-+{2;dT=B1Cu-JJoE{;dovi)E1;JHrP3U-HjetSIaL9P_l)?hB=-?{*b2i2N!ro~A!`qmPA+ z80W|yl2q8~0kHuUY1+}()7Cs58`Cdbc+sOpviQL?7I61#gDW#QWfBoqpt9JxE6h}( zw!Sr2N7se?yQ?n))j`9!bKB)wzX5RO z``is-!#H}J=(r-AnBzV*;>_vCZoZl zN#t4ef~&SY-Q~}oHYLi`G2~Q5W@6I6%st>^y9m^ANW8=fQJQ2GrL%BcwCMsil>;~7 zp!){qPg1Jm*+=X+;Nu6MkEJ^e5co{eVnby*Kkjk_HmKG|U4rrcH@{E>wWOi4*AGls zv5)nhd+ zop#fIYo?7daF~F4XxU3rDSoBKYt!H1C^mKSl?_%=A<+?qJP01WGJ<83w*5ZG5Wxy6 zZ~Stg%TXI-k!G2ameP>s)c~y#d(8_}%*d4n=CaE3fR`+<5ZS6dpOhvo6dWfN>}4-F zk_2?4T>gn+_Fx|C=@0dbow%!V!Z&yD)3Z!e$)GSRVA6%&o=VgVy=1WH0*lJnx0orx zl(!?C@Mcc!yMDr!#n2TPGPlgUK)b)`zdPIra75jR;EJC?QJPn}vVDa(K`TuwbV#Lb zh_k2G3s5%K2en%PfI3QOT9hjqGFD2Hvrh|BMVirvzvZRv1E~1O6V?Jl{U3?2Nkvzz z)J1EccEam{t%<4~>0n6bedm4^(;b?G7t!%B5fx_pNt1X;J`FFO)_f>Ec0t7^GCz3r za%`l)UTI>iN~Vo;n$4$~qwj^tZvy-h(_(YIDAKECTU0F_hG7}eAvWvzz@XkHUAN0- zP*26FY4}qZ7i6s>cB?v7?dCS5QEZdeVgqwswTS*}b^c~~QqWv=YLMe75jBuz7CiJv zHr)ZAxz~+^WvzwV=OF^ecxnGvIq}f0x(b?F6Mb*fbG#zMQe$dCAe7Sjd)@r%v z^8sPafhw!2Rd&p30W#NtK2U70q6<(($nG|+9HA?km(4PbCqh&NkjfM9FiT+{Bq8?q z<}$pU8Yg(QUCIPluwQ`7R1mPCM@C2k)Hb-nKb5KyY* zR5l{X7HIODJ;^KnJvVtVQ!OId7y8ZwYXnxzTF|(agG;3jp(j!DJzNS$kpymEdG5l z;ScxE31{0dC4)AvgB!zY#ZFucCcL~cUuPh;b*!Pa$BR&Yb#t0#t0vq0th4puFWH9o zyoJK(N79r>sKuu5I+JCSN|c~U@sqwoRa0u$LZEBY4Mzz74?MB||0kYU@&5%+G+dK6 z+4Budn~%lyH2B^Oe>HyV|KN#QC&L=9&fW}t`agK0#nVZ;^Z$(}UVMrL^xzM-OHaq@!wQ3l#fhGq>rdFWIiFI3I^R8Q@@(DY?$eBf!{O$eUc%sn3 zQT}3ME}qEXQ*i6+=HiKSzuX@8_58Pf%X~9Kep-r)C*F+6JQR56$LFP-h}~If+KFr$ z3BbZ5r-(a0w%#h|-(A?lcqQGym&-nGHS}(^utXksI~KA;6G-r3Np32V$TUHlrhzob zp7bVNEd1bQhk6(u5eYxJvBX4=iw|b0e3BT*2Jn+g2>ex$lMPcE2_P9ZG`-C?nXahK z=a&{$DG0b`y;4Y0OJ+&DkvhbRaI$|Vra%@R$}ADrOqyZMTMJc}`DSRU*__PHsyiRt z@Y7S^j9&6wreemaw+kWGj(^V+cUa}%W#Xu;}7 z)PN@X6c4(-c>O>vz;;!T^L7`8*A7!BYeK%vL056@yjiJ z!(Qtv)iUm|_g#0$w?B>W$!f62&#YYeuAf4w%uIM=EA73e{gmyesJ%6Cm4Cc-AUV;2 znEIIHIcW$!iC-SpP^#lq2L7-v^b|C+>AiYG`1@nTpI2Gqp^kl6BS1%)m7q|npZ%y_ zG(N5oxq4L3_8AnY<<=MA{dLM=x9Z>+RP#s2r7&@yp*8BJtdLNl+O7O)%b-W!UbqAy zhC~G)df5sZ9t(0epm0ejYwr?|_?Pj!CFz8?Mo~wngCe_~f+mvgh`3k!L2a;kq|lVy zXxhHVp073ZtlL~xwu;?NrY8H`EyG`X77%Wk{Cp3Aq)D+ zsPY><9JMH_&pV~@aU%)M2d6j?}pq zTG70;@@KL^;ilDkJb*i9 z>JJw|(vd3c8%ktf_)QR`s+zDAH_j{(P$BtD_ek6tOKMwR>H1Djvpu}>0-?WsFc6oI z{`dPbR%Gx7EnWlb%_(mQL||J-?U)<3GNzMn4jBfqwzobhMdsM=1=#kqCcSvsDQ^j>0J_Y?mwe+nd7t-h zOle!~xU)#=Iy~!vjr6q23hsfl;ZB((ZcDlBrY!I$26B@BT2#^Z*yB8k+vS^BjKli*Le$KP5Hz1(h$4%c*_ zG8DRkO1?tatH^Tbqn;1wu~+Wu;*DgnuV}b7+fvAnXugbE-nl{L&RAY%KOEE(Wg2zi zSi%dq1TFrnWIi}UsBNi^BMb7Ors=I@Hj=9;1SPd z@ife|CXxS$e@#;paEQ)Y5_7*rJ1+9@P|4w1p>)YieI>X#JCcE`wIfl?AI?9|P`!n$ z)a3EQAztjx8@I!asJh(&%$L8qu0-zKpOsYt0Ud9Cn`qd0`g&QwF9?s!MO?xov zIQyTL(s&zkO69iLH>UV+Bt4M1;aBvdZ^QLQ%8Q4K-+TA%TbZ1GO_{>Pihj7e^XRkP zXwCR`A|;eGbAzfLJ3=c-s-a+p5Pf3s|;kM^Yl`B8v()lrDnyUl|Sz3N~OP@~mE)n9UW9PZWRY7*L^s#z2>tI7gzfCS-(wEQ10 z9Ig1nnFJ*7%ZyO0r1jsR@WeIeFfJ_~Shns?8yzgP5M4uvd&_(gR%ay^NdG{CI zVrv4`0MHgJGx4rx`kG8^RClTjaBdQIi{TMg_@@GA!5rxG3DCNccX2KbyVct>Yt}B% zr=$=tXCN|&peg)`2(mPAnwBj-<4lx#4nAe>>zH8Z^wF)P^a0|(=*uc668(2+X-+AV zd8JilxQ}k6eY0eNYB)z+1ZX6TW22GZw$?{=oCL#cu3^>cXesSnFtV+AUh@#{yr0u4 zcRs3-bKhQRImc}7kztdhIHMUBu+NthLfcNl6;QQ`l1RmS5Uc9|<<5i4$gj8AaKK63 z_9_3@9QumITW7s(Bd>q1CVX|{@w6~U%&Q}Rt!*SK%Chu>G1LHVwv=Ph?@-HgoUV-k z+=S^0eQGeGAOyh#GY`fddY zx8JQOnX>Rd90}=5T7M4zdYnRQ`(3v}K|i(oK*-%AEDiOHK?fW1OBMQZiM4r3v$c`;J-19)n@ceS)D4 z?q)yxI6VoN?ojbbsQVt5k7g}tt` zPd|1*Mcbo}?n80oH|X4)a@>g;i4+^E(25!~(#5l|yDrQ+$fI|fnxc1LF9|A75{D!) zA<;3o7-kbcv-foRajB&WYy zluS}e*hz+eNq+Yu>t03fzdAmA#W~0~6K;*Fd5|#fn|E_NiHDZ???nzkg#%l#=aTt1 zJMH^4xY2}3%gXuhD};YWQ<97LSX-&PxAVhluo)Ea1%NHzioceg`Y1LRVDlx-o=YVa zgcQQL1ng~4Q0t!;*Q5*x%}E`Ds&q3`52O< z&{LEjCy?Zjhk!BQj=Yj%d1!0Y{@peJ?tVyTt{9FeM$ro4yo{RLnU={V@o{Jh0EmZW z0-6P+EO8S8vO%)6Qm@c?EETC&+#{Ly2wn2NgI{!A;B7oVNsUh;Npyt5?~ayEO^iL* zBNao1bK9YJEq#m3ARGQWx zP=?TRgQGD$QYZo<8kLu61W8L_2A048pcGDnUjczQ2<_aw_edZdcLGt|BxSP&@7NJ} znt-^~Q+eS_@}zIE`FbgG0Om7W*axC0?4nCS(b|eJ4Oifb_+wr` z6uNwDrWDbh6|n-2GEWCm&@SkF1dYAZ6R&8DgiBl8Awu(-5Q}}Z+Rr3?hp#PHU}HQ~$#7e8ozT>odm9DSLTP?qE}-6kQoHXk zEfln`3F^Squ7DZYN*{{lG(sOZ=BT^|l&CPLS&JYfq>00*A)~a-}i#(alr7 z4G0?i@K$oT8RRh8&=wAT+u{$u*$kiJt-iWfzzEt5yLvqxUfpej?+#9!yV@L{Up-&w zy8?!rUHPb9c=UFQUo<@7Ck!>2$EA1?FgRT3`o%$m(W_z-ZD7N;fepJN(7> z)Dz=*bj=&ij@30gMLa^lirID47nl?d5~LuZC6Gx~FW=&K@8r*zYphP!W=q7Zi6e{yfKLKBA+6>3G?{?Wlp>1hUvETW=%Dnc8e&s$D>%3X1G84_+;nf z#!gfr+MdvXtSP>t37y6<94<&hS2FbR2){DnkcLAKf)R<*B9!{{xZhTDV@-PwmN=V3 z_CV_tshZpZ83984&Jcu$8%E!}Hd9yo+aSoeHfgl!u4KyDh>jYcBA$Wx!00aU4T_r- zo!bJDUgl`uxij-nYREUU2gj(HteFl?N7ck@>_%T3O1=Xh=oRztL$w3v=D53-_dkx{ zZ;InH^Lu4N*j_f@S0`xi?*^c)!MCZ8?@J#~3{v0x4&RsF?Tegz*b$}}qlCMH(k}2R zcEha^z!qS}3%B@HgM{%W^g!Kwz_zLwiq?-w9nAK>rx%KG2}7TsF30Ni@%VH2XmI*Z zVD0dA2XgsSDi)-1G-QXEuqwDv#$pZ>-xlEb65_IQd|w6tg627zbhJm1KI@7`%rLTM z*wp<9c1^@*!jPqe=+PV+6}o$3@@{J)I{1Q6zV>xDof_ zJv?=>K0#$8C-A5VZ77P;1kySoU|8o4G;#(#xt?`f2Z~9(#8vy3x7i=)9Y0!I+}%>{ zp^;~glYH?NGR+kl*Mjsx)Y`9s&lAw%(R~Z)ClD}>VNAtJByOOs2EbXC;0zKteQ+`a zVPJ|})a2b5Z%yk>7YMg?LG{p7K2W2?f*kO*dH*qw`BcL4a2^|=FA`8<4ZT-{3McNd z?sQ4vEbr{PK&Yh#;X)X26n!2BR41WFK4fJ(NuFg4GYb*xUB?1y9;hCZ5yyimlM}pC zZGAg1K28^G0uuWR5snQqYQ{0NnKU8aneW2@;gY<&cj&P+^b|^c$>)u+ko_f*2lF!| z+I8HqF|;0hCbu7A!d&X)biF8!V|{ZyXPoxvKsPE^C`~r;pTBQ zC5VBsg;vO{XR`Cy!XX%3@Z?nZ2jTv^k2tUTOfL0XhA+%ql9=feI!zs89hu5Lc0YeN zj(>OyS?ojDTubuM|^-xf744qo?>{x;9?E0xvF{L>#F#;_2A} zjoEih+>cz(5Q$_RmQCliy|CzP&Az?AIRe#UHIr>z01uxJ-{(B5Qh48~`E|4AlzvO`lf1V4=vN91gh*l}8g}sC z!Kjj-vxO%i+Y>Q;J!hSxph%@@p#g;Q-qqq`QHVF*`yj;L=%|i7Xw7qFBphLL?$inH zM8lHazO7m9eoMXM? zhv~nd^71ze*Di%!$DOzdOg?=4Tu~40<9#aVIpQ@3l_@WDDmo}u?LF^+$&D>k1%45T zruC||9>$|ze-buet)3DPH4y;1o!=_LI9xUxO?`=t0b_Keb+JJ37=IO|9f;=byWd{Xp0QA??MXjmm zpRuD?;$FcDgwZWf^P~8Y95DMN=V_JX$#>A$mg_-2pn{B*b%qG|!#D7cC1?y^aUq%G z33WaYf%+AxFN7e(G*bAVo)I!s5PG$RnlDM~yTapcc=#=quhx#o1X@#_`n-ExwENB@ z?e>>^LT^xnM|E;ftK2sbQ?V#T(Bq|$g(fs?Cq!#VQhc+c#Do-fgy^9ekw8+#Dd>^li;NSp@2U>E)8^Ym32(~6$pThOD!Pu?wod$vWtLnc@Lf<)C@KX?cahQ z;l6Yl{-P z1b=t?a|cV&zWbpsCxLx3Z{Rfc-Q$uA2?^(JtpPQ*?0j(`cBKurG?F8X2Q2UPjb38H!H+?&T9#z}%iDQ|aN5=pvfkUNb z3PwxgCJ%o0yXM5NMhrtlKWC($u*vloT^-2If-O~8|5p=`m3?}%d%U|PuPpQ7uXM?t zFIXx4_&?p&w^|-gn#;Z}@i!dymek#~wA6Xz^CN2U?%871uSa&Gmnj9J1xe@$527F% zXyXfj5A|s(csW$R3SWMa>RkRQ-zatH#ge9vrPb7*z~O}+pBW3kmNP#tC}(H20`3mfg73RBoM2g3+UPM z9U$u2iTMP!+esWx)3cX)*b&kFRxLnVNkCqIxkeZ8rQBb^^~TsM7ZCLwRm%fA9Mvxe z3Ky>7#)SaU6?)SMk6JIHaFvZTaM639a?{1&3GwLwS>-V0I#brsz|C~M?xvgh=b`^d zMDlFWeO(ydU8(o0N@pu@S<7(O-A*E?)BVjXeMu2sjlhZGH_bk=vU8KDDCYH6Os+X9 zA%3dH$&QQ6Fu3+lW;Ov1XasoQI@lIE8rp1~lNw61RQ`G&d!%ray-y@kqo!duBdF^T zriIyr3B6R`)v{j$jwr-_Zu+VSy6xboBp6-^LHOYdN19(Pox0U!$X-?yi#l=J?@T5G zo_*%WaCWYFez&qH5m_C2Oq7tjF`t?Ak$D_7M|t3%rQXoJjMv+EepMb93#fYR`Tj94 z%a@vUJJ8zRG^o@kfAocHvY05~3frObR(-{ktakPmYDfX0&rCyWGSx1$7ja zKJgn3C40-N6wr&zaas1!#Ls{d*{wJn?|emCoMkT zFOa*MPwlxXW%+4phv)W^+{nr3Lk`_hYUQDP(*4P#TiI7Ln^-NRkzqL?33XoP-Rn#% zZDlMKpbLt(eR$D2lCN+DLODDXRGJ34IxRq*Dw93}vta&tvv2L8lX4d_Xxe#&xKy_fpl}MyWy@ZV+R)|f-WK%2Gl2a*A?preqjYj3hgBdrGWBnsIV>aJ}w=^Fe^Z5(iD@l%ZSO zA~Zm%HupclZ+``~RzqEa%$}N5dMPc@7hYjhr7pa0koDgPBl`rKXX6VTfM_ar2wk0C zpVjDog8zMol$taJ(PT6He(1SfVU<(hvFFG)v65&SkgLg6@4;~VvF68pPq@4Uj_zam z=03RsAy|k@7M|Licmec*=%}P&8FA&v zFlQ_Hkp#t#`glVpG!;RRsyNg5$dy=f5|(E(a_4x6{J`G*W=DKJ8{v9+GL?R;o}w#c zF*V@SA}84p+T)3B|dru2AzGn)P4Qq->E8 za5#w;v&S$!$yEjGkDHU}lnvCsqfvNzvgDt=U3=3gzkw)1!ebGUV)&jp)5%2#je+zoSk5$D>G&PV(= zALdbhp)}I{6ccwvGeKo;Cg2Mn`jTN!>>mnJs)0Gm`4#Thn0`~C*nzlIQ*d^tR)MP$ z^DRr}Cs7kMU+$lhR2tmO)Dcl_a82xbGOb!?r_!tO&cW(}k;}|qN-Rs`v1XMkAu2im zam@6K^1?XkHXINEmWBis2In)I4!qp`=On8}SKMV1v8w-;(7@0ot=a`j|I=4Y7e_o@ z$Yotom#X9TcmyU++HwuzxGW|wBaiJeRiUp6{krH^!-usAPfxZ63GAJyl+yC46N<4JL`Ws<^gS^aBV2T)cf1JmoqCM!j+|CV*epgp18A1_}2 zJJ_@J_uIW)y`L9%chQ6r@;yL>0~gJC-oorQ;P4Dxntq$JH$s`CT|99UgQMQiT!Pu3 z;P97Rlp2L$B6B38!Dq_FbD@a#rRK^dj@XQ)6x*tegcC2ZZXGC)>Ku?E=KkOe$gK>> zZx1LS2XRLUzX$|HL!16&{!6Sjo1ZjEi$V2moYk2^SlXag=b-k`pbi<p8TEJ(wNS zt1Ei{g+baT4Lk}^BgiOqnftrOt;Io81SWehlY%H`fwEd@>XWoRv-E3k&EzTkaXI&| zv+0_WL-G~yJ$MapBKslthHuX5uV9WTHjOIhD1LYd>GUVkqokWu9hemK+Hz>V`1}X^PObi;~!TOkM*xb*@cNf(etMnldG^ z8jOyIDcG%Lj4UwplL7igw&FLl6?Q-wjX@dYFu9~qlFf-4$}ULK(qn^f&w%J6PKbGq zC4-r`l5LHAkm4c|vm(35+J9!n;pm`4L-b$=;X&qB?>WQK!@nH90(2$1uDW97(Tz4n z3F(sKXqIpKZYD@;BiXM2d(K@PE$Ay3A!cQ#f#RbLs#JsaQD*c!KmR7J0J6%aAY7LE zuThc5H0Y+X0uXYn+K{g(7b`^)SDYQaNa@UFu^KyMEplK|p|reqlMZH|Hr<|SA|*$v z4LoFasR|S()Z}jGo!uU5pUK7~fj5t0iiWcJ-ohqAou_gf^iz1RhQhvt*I>>5i zLe)LnhTL+|r2dKFBlQ&8S}mB#g6V6GXD`uAy&&PEEqo8HO4xJsJ)LA8`p$g`m&D&_geAt~kOPxf#Iv~NVdjsqv zW^R`{^)izz^kZqKk7P?!fzo!o5**n7qV2w-nvB1N&p)XoA;1%QH}sD5UJ`mY^p2rO zQ9wYYSQBbOGxQ>25JXhKpn!;|p$ZlZh>D;X5D`1rh?U9zoH;Y^dS@=?X4cA0?sAc< z{o9}YW#yxiKNR!6($Bd`nu4V@Zp9%H&MvCHf94QgygVH|#2(C}97PHKEpya#_~2L` zG!MO>i!ucp%o&Xl0N|Kb;7f)$)}OEU^4tFX4PjD^dTfI;v+`s z%xVV=FqOV;I=*W+jkaUHe#WLEwf7cs(~d@=EQ`&#At*_W(u&TyH2ho<+YA_R!=w@1 zPd_}BC#uAQ94nz|p%{0JOBB}6MwZYZ!0i>FT4R|#0x=ab*;DaxbW0#5yc^}Ik z8+SwN83cxzdN=a)?q>^W-^4T$?xa>5yo{@O%Ensx(Wfg=zd^l(7q^Ai0U=FcJJ6lR zg+1&<9V|epl7a0ZYWVDvl}Vq7#~9epvRSYcRNM8wbeCNR>O=wRknKw zh0ezdU9T6qPir-NUtql!3KLztV!C+Md9gQev2V{}|400xIPufxQ0b<1^Z^R314!2s zyk3C1*@Zd%fFiW9h($dgtkK76LWCH;(n`;>UWH$K!NyDiqE~4s07$lqt`bnD8E2{=(n< zN5@c=;~4jB+UjGB^ZJWw&T}=(yw8Um)h44Z@!%u|?Td5GPYEiLVs-f3%PZ?I^eIdF z>(I-TsJ0k#w;P=Q00g*^foyUYxdx&>1GBg%$esLKGC#^ZKMM*{2IOauUD^BE#a zXo3qH53NoFMsF4iB~pav0oDf!uALTxrj~x7>_9%frAEEsEjjLt{)7PJk6#nQM*yg0 zH7!Yz?B%~#pI0-Nmw3yj7ilq}5qKf0C@)%LW=1=T=wbS5+XM*+rbU}(#+s+SvZ#G! z+5XC^|CRMb?0JP1ZE>}N2eH^`gxud(tecB2H&=*u;SiVA?!Z;&ZV9JDt8TTc?rS$4 z+v6@t#L>A+&YG`0r^D92{jWT65x?#n&>!{&0fb4r1=TJD*8YblJ~~K&F(?ZCtKq3( zXu`dKXRmg4yY5d}M7ser-g8KMG5PzR4%;UQQRh|;_RvaEGlNL`ak5);7&K$7lY*tu zV7n=SECc4c4mzn;PEArfK?kC3U|vn}rvdWX%-5HA0l>h;kkkd4TM=D-ba^J`nRSCw zhir_ZN^DR9!|7$g@vv7$tV3r6nZ%FowfPgZ7&XhjI6*4)+5d?XiXLDBRvLn+MYDN~j35Cw|{ zuLqdsPsNgxI}@5iM;^q8*%c4TakeZW=Yx`%-c-vz`-Js(XVjK@%-&yhdEXmkAV!JI zT!^JO=6Tbk0*@_=lBtA9%n8JzspiwIDL|-WFXcC_zpc*2XR&`mO)+R+>ubn(RC2RK z)Q@8yrrJN;?f+0V3n-*ecw+DF`P>I7&wLb1L@6)W-570QNWNLh!zG71)5XYa^Mamt zQAo<;u42cfXmKQPuWxl*y_vSPCq*YN8q+`qNbus2kK9`h-;dF($eZ2PNJ+FOhI0c#Brf-qGE2!!AXky`8UK^bK%;lpT%%d z=)~Bj`TbGhd0yrF1>98@B?USC?|M=3B8241y!}qdaGP`r`BSm*adX=a)a*p@L?I2u zpAsg%5?T9n)rNuzS)*I**T@Zhr!M@5N$+f5py};nZ3NqKVU``~Hgs}Z7+ju^*u?@G z%}ShD(90HiuaNDCx_Cp<7d0u^z~f@I6DYOa;=1)q{roJ%Z4CYm#y^|(_T#1olqe;# zVZHo?#?9T9&wj4G8x%z4vuL?!M#M*juZV*Hj+I|j4_99QfPVIZHV~thjpDk{H7R*7 zQa{l$&$_cdStf|1PtcGX+>0*D{}hEq?9#+`V?4K(QJRtq$5mO)Uj^#KB=CkBpJH?q z7?Su6{rGRL+K5ZUFH5wSolHucj{&g%&=sdI=PM^V!LJbl?n5xZd2Pyh2R9Ng_zVG* zcb#wgo6%_W!$J|!Yk>r^zb76hi)Ck$cRv!!j?gX#X4Za~mVHk*&l0@;=0M#XGI*=! zdAG6?A#rck9j9;Ayze=8wvImCI`(Gk_}1150Ukw)N7dlvn)C8pdHKP-f&^Y+f@E-J z_BQkz#aKF()xkZ*&8=o_6c2D|=IlAW<>A`aKtQ7h}-TVv}xtJ7gp3P^LHO<9+)9$=KT( zk!aTEBIZ#VKJD(7-K<39xvd=5E`xY{K{R(E2K{vKq};sux8nKiV$I*@5}%?Nz_#!S zTG^dnc$I>^^|Y|;-{PAPl^yne0I+hBwzs1&ghD&G^WQQn>Ukd=$19tyL+#pSU_*e> zCt=>e<QknrGNpz$gNMWyZ#Oq5+a}5^=9S`Ry0A`}IZ%vz!%{x_Z&bEGltCnvuUD+2@!$e2bK z3W^xRU%1t93;V^ZmJlo=caeJRj?Ww^CT)0INTwRf;Xn+RCo47lyOVz!t=*3>jbJ;F z_PdJ6K|kv%v2-a+(ZqieA>wUg!p^a7*(fGeK;%%i69;VRUZYBz7z_}UT2iUyd9iJN zC48PZd*1(Y>fc|^B%7c|$pD_=q+fj&Sod?qOL_u(Nh9SXTjKW+QFK6cho|ZmfI2t( zdE1@>!C2sT*#TT=R%DJteiq+?(!ESo9f}C63e`IRu=czXRqR-0%MlwU(alt$F*D$uDY-;KZc;E}MF!}-&tVc|pQJ^2UUpt>B{pl}IWiL3Gs{KqhOKNicvW)Kz%sER=Bf#OEQHE@YzgE3jOWd5{f-9j>EhIYHhj z?md5TQ2P?35N!1+6mlAI5|`Fsw26&}K)awdBuxjkvH7RnrJ@Uv&P&nkYD!yrLeiy~ z!1UAdGymaEPaJ}#@myrzMABKY7Q{eeRqORp&l~DM{B)=hG5}d(5dv{~! zZE?g}*EQo5W=OjX1er*G}enF4jwu7#o-##e#`JTP~-)Ier z-{SW7_qXkL9sYVb$Yya2RZ;5sNDPeBRB^fl+A7%9R|#BaJ(Tg)&%q zihuAZN6isjB`aUuMhWBJF(Pq=RiJ-V2^*_9Dl^L}G#gS9KF~3$@P$=m_eTlL(;QP0 z?V-8M;YGrT;Ff|f0kSIZ{DfTHXj)N}bxB$BYT^~66oNupJ#q&!qriymcqnYF;l6lo z%z+k2qp@kgLyAKb>E$#4j2xm6LSH5sT-M9;HPRW^MB2qa?wG}jF$ zdi`qUbDv5zc{V|n4LF8I96zJlI{V%VA5mz z@rG`Vn8O<|>5!^MXj8l8l*{lDh~DYhg9)oK_=g!IRVUUvHSE5Io<8#K>Y0CISo@FC zoX)AQXA~kr5TXl`3olkl5~UOel?BNnD7U%11Z&$`l?%v<=Sd_AvAte-o&p3z@~vp@ z-WM5pN~Px@r`$YzFJ1;Yz3nD}T0wpr6J;h3J*+=!lCtV&I)W!UC@rGb)}Ki)B304(SukExDlF8E?DKYXAdi*KQ}*+&*;%Jwkf| zemRQ>m@tfG^elQ zBtW$IUkT2Tbxy-~s%g){+M>45!0@?E->-P`_K6M#Zo|@pk`B{HMO6z0g{#*@=%NTsiFRk)w zlhLy$oul$Z_i7F0#qD`Yc9`7(s~hw+)2r7X#ExD#^-A}R<)iDwSpOT*0oaX}%lGxV*Nu2?0F!x` zIom!>*8g!7hq;%RC4(N35y!y=BRx`2s7k;IA-P(B!h4-bWXujZ$3PCXrv1 z@|%>NRj8ZwdZRFa#j<0yTT1UvXhM`nP_+*0CA)$PP*fU*y#S^`^G*C}atTCjar!j@ zVX22HYUvM_9=(}Id6RtLAz{QWaL81n@Yt#K)LTNM*9G*!+^@g!(LWX{WECZM0--DL z=z(!#eaF(P-4#!Ml}%XR-8`Oav$`#Reaip1L-nPh*ZP;Q4)4}KP=5W}IfycEFd_Av z_(tFx#zo6L$mxs{X85|xmZj-=9ovONa&Om<3_NPpKlHDF`@;YB;GfR&?_KA2y^YvD z{Bub7N2yB4iE^>u^9Q_Z?hQJ-^|PZ zuSqVGbBeZlQt=*-djBiQ_21^@tS_WD|7&08v;Wh)==rEkE?htTKj!7;g}DDoa`7%T zjqsCPQTGS_pXQ~bewwM1xegBU%}cH~s*~ai1D+z>TlFzV{$pMaSeF8X{!jmHULy29 zm!gYxcK?@o;k0_5NoAS+mw8E8jQ@{$87LL&^!zd z1T-IVv$yF#KL-2ZHY5_cj!|s_l-w#}I@$ki&y!O}MS?V=P_5t182djPa-(xZ)Do6y zs)PLYxmtV2O7Um*i{7iLZZodUR` zrKB`9mpcmQ$_ZTnn5eUX3V3Kk30p5CEX^rJHArl3)St3)w_=ur3jY zdzM9Ks%p5GuwMxf&&R)emn7x1ZT60KRX;H5(&b#$*lxd1SJnv&__l|3xnKBwsEI3Y z$X8DM#Y_`_VZ}QxMfPv0U6mQ0YCca?c1nosw7ARAz9?Su(V@Ee(xVl5a$LC!9`ITO$GpF2MsQPkx()uIuRg-PA?>j)(F$d zr90iHy^OsbWUG@irUXs{fJ!55VFP!|$6rthL&CU^;i0&?aEq0Z=#suQl_q zhJ=PzjM3QMsrTj%qIWsA-+!S6?Bp#jE!k#rXt@G_MJHW7@GnE zuDKawue^89oFJ`@!C!A{ehI%?cYZo_t8F6WPlcmcGD%P3Ky zlSyq7(K_6H4jcvfNmmr}5fim}*5Ejff2Jw4)*-jLhes?UBk8A26N}mtQL3`xj{eFn z9Spy;IN_J9mxS#l_NemSIH8Z)lM>(dh^dS3!iyYqGoF9|2T*VYfLUZYronKN?omC# zJ1bpxRnX`4NMVBb{&iWX?bp3}SlV~c@l)kaE9E@LJP zcjj#1P6h-hX5`8Yi2$TuxsC)&P&6p=OSTO9;*r;IG|yr z@M_!GZ0wcNi~D!gP`Pw^>47s4uM%aPc0+I{3^3YgCO`*kwMtu9<@FXYaC$DawT$pPYmxc%eBq%oSBtn%##CRAmQZV@) z22|=k9|{CZUWG2gwSj+Y409H63aSJFQ{Pq9r}ufdtI#k<&8`{c)TAVM(;t!n*uaA> zB{SYRqHwXk0zeipA9x?URqTO5tMV@y5*q^2ptnaW?3A}s%~@g@L8I}nU?Qf&e)O?yY52R*Sn4(xS^|(^Krfkr zBdcJ~I2Z36+$=#&{1})lL%|1T#2P%>`lrf11z+|BiL_X}gZw1CSWsMBdlh^t;pTbH zGwS5UgR~n63MhQ#vH3Sbt<|$g$6P_m4pQF`PhpQRDkiTL!bN5%(9n~OP~MX2Wf=Xv zV+ISRIB$9zENA6wcr9bXc_Y%(tU~kq%fd%^qj6kW?z2|j`p`2ZJH_URiWf4 z--{wmyZ(Xi5~; zM53RRuR5r`n*}RqIRbt*%QPbNugNcw57Zp2l9Qi5lnG(cBF|4YFq87cW<&*yI%DuI zpylL&B~`gwO*&Kj4tc4NtRCJK?6^6dvJtf8Dk9&?$vmHVngj z+Yitr#fr{bHM_;~H&ri~kxDOCNV)ynBn<5B)7p(23tB~}4nT5Gkf5+jsEvvXZ+1tt zl#smiKg3R|V=8aJ6h3gD!-;zn8p}cWCAh~T9OY89mO+N|vW z@^bO2b$@!T>X0*bIr|2iE3lK7x2;2SlUg=M|1u4&2|RpUG7?}*v`ji{GHfyc1_TSM zp!z%h{IQQb`Wd&3c|-Pwx5SHWl6tDZmj?XJKf%4Oa7$eB!DT^y*C}V~=-JoSQ*SWC zl(-*7*`w8&&}hN)96vF<@Z30fK4`y4bdtZ6;!qLw<){Oq!tigrgl@gWF!y*10Prb7 z3+Y5-AxZo(iWx5`L=C_76h|l&ECPh!Zs2)!F(+qdhB+V33J#HD54tS_yf%cD@^QgX*GY&Y3v(vUr-_2~mNpG!T(=jI5C%5t{9QFN62kkPVLPkSS5h(U%Ja z;oDl^rL-#4Fhr2WM@7gR76K|#M~r`_nO@M>$pNbYtb9j_%SIWT3endB)6?Jp(=*Nh zBA-_6I>RtstEuy?+zlWV-M~A+#nANZ&G|!c-;+?^QXmagxB<-PMX)JC;Rb?>cpSr2 z%26HEsJF0_l_! zj_X;ObhV5&anU_uj4M%>gBp#h!1puI3suH2$)G+fO-#>$$jU5ffu)nw&ARfQr-$B#fNG5mpyW|GD=*EYVtW)| zO^d6Ts^Hggc;~^j&}iil&~xDI;-j;Z3CGGAB`HZ@f&fzDC&HCe`9Gw{`{+~-I|^+%%zW6Aawz&_OSjWL7*rdjILK>Yj)&ngV#|& z<|Q!nNcVwoaBmna)}VKMIXJ!sx`6iWb2_6=hMuk$Gh#r^z>xRL&;jMsd&0pZjn&!? zd-sw^q7MZ9Al8n>so+Xd){ zZJz(A1@1>d?r)hUgx)pFv^{sah zXrqQPfQ`)3Bpkj|;a2+4VVIgF!=&|wsK3oPpPu=4ny1B%8&{aPww_i!8hxZuO8C!c zYoa894yHJj1T2CsX(+P6(5D`6Rg#o0_uBuQqRDLD;uVk$#>J5J_ZFf@m-d1#1_DE+*nlFi zc^`l`0H>~x%{-p6ZfTkDQfRdSX9r4HlU0Wq?NHzWG#b#rn`8_rm{A^3eUDf}x)zV( z*DeT_YC+#g!TEtFkZ}#}Tlt*EeDpyPP;WdzCC?9egU@hCy@yaL%*9LqVFu>P<18t6 zY-eC6@Hf87i+?#%hN`&s==UUo3f)1uW}pLJ{R5!)f*S05FK3{iY!Z{UM~zXN<4|>& zopDh9_^1&z4c^nF8GT7T4eFqWdmlaN`mxEF3%MP~Q8+E}Pri5C3nq^rA#*D)4Jwmj zw6qT(u;cUceHinM|hH&A3LEx8|yuxF*=z9V!!>CQbUk}vMJ896R+D&#m zumC#pp!*cWT_Wd8sF>#j-;5U$IbER0DXl7XumHRVaEka7jNDKSm@l^QCyGE8ER7V` zW^r7IK=X@vCgiR_^n=^hoRi+*Fr_2MCIb03UKu`Fqx4 zzM9~)>GO*>aW!ypP4d$r=-#`GvAOSv>)v2L5P9Q3*6=nYvd8tf)h6oI zW;KASTz@sLu{!C_IURE?Jj7xXX4fTZr6#I}zhu_pPpE+{Brm1lo@rm1`=JH9a|)_% zF!+3JoKy+5XVDFT-7dyp402A`a1s>_GXO%x?xY-)#;GX&C)nf+JQkqBq<=m6frgp$ z+p=$7qM{eHeQ@oOyUl&LGs_DVhS1DCsJ+}H&t0Hu29KZ+v`G}GW{~hS7IbVT%PSvU zY?I~dMQb0hXJi=~O_r_<6-A|r8FG*7f|A;NuZy$v0r#fm=!UFdr~xN8auG^7zx!5g z^cBk~s99T?TQgAW4XF7n`Xp)P1hYtT+gG^E;EXtKtz8=F&qCdJ0HT@&PsjJ~uHQAONS26lQ6F1a>qdHjPgre|-fgZyN9WCL~pkMcqS$3nqyvVHGf@QdW;T?o{5ElD7 z!$&p>W<;V-EBC-E_rpf6tqD|^biOy%0F7bo8wMPxIzCv70sAPAd!qFSy1CD^7J4?= zBDqSXdnf24lKR>VJg~Nsw?n~|41k;(IAazhJS~q77Ap^SeU&ChO^cHE)%M@Q41Ytl zKpnPWyK^MSS%a{Z-A5jZq+UKlN43C2)L}*UK(7NP_8YL%Lro8~OrDDz=U1aDPb4nb zn*fHfNI+3LZjuWjEISmKg#p`G~RdYoUAdxQSby}lO$7`~8@J`ba}!=0X| z{kop@y_>tV+aCiD$LR%}PkH2b^xcp3h`~euSCZ>Mb4Yekp@X>iZ3YzpDt1qlDcBdv zhkl8>TchW%dN}lJ{Ir3+rp;Ln3J`YstQ*k@Iwd^mio9K@5dI^1p>I3orMmklu&V&6 z$Uvsi&bD%Z4^0!NBYtMAJveQjFfih&wf?xP=qQ1^H9`_Jj1brn^(Xtw>qyDydHt%K zANM|sn|B**PFj8Z`0{@C#=qnL{_gt0D=ozbXtM2L(cwZC1^oI!i>!F%t5$1v{bz!p zOyjzPkh!V|TD=~i(3M5cLIKrUuEF>nESH=2Sz5MD8N>t2c_RUFT`(a(N=vt}-#Ygq zHBI%3+p~)lWha$7lXo-{8<+x=Ebz=>L)w*CP=$oga~IAFST9t(`CsNGLKx@d5c(CR z>24Lyw0d=y{q_fuTPMG0PSN0yl;mv{AZ_4nH3M)o@pIQW7jW+9 zQp7r`S>6{lE8w`7an@4D_MI%iIdw0fAYgzJ5WKrU!j~BMUI>8N?c)dwPV&z}FKb^k zc+wP4Qqqv5aFnspb$j}ssVNckRnHE-51E1Bo-AQ zXV(QD7=1H~%6W4vX`~_(_I6^9@G(R4?4$)0?)6q^3N9xtchxjIJ-nV=w4+d{H1wGX z+QW$pgX9aO{z>leY560uQqh5jTsF)gO~M}_p(Far9Tq%HVX9kBQ8g)k5>dfP;aAAg zBttK2^WXgvbASIuQ{ax*V_!0a8#YKl0FS)QIw{(k-4j~&Lq|5*!jL6>8xzf^DAm-$ z794ANP*ZiO&^lFh;W*Dk^BOYARI`A*4qGztpA;^hcglanU0>Q)vft|cnnaeg+#5lF zGM{_OfY=DM;{Z4HhXsl2$n+W4J7|Qs_E9obz-K+X1+aT1M-e&9`O${7jJ%&Tdop)f z>A_e|zS0%*8>_N`I*og>Ue{gLF;NNIUZ)D!Nmu^306|HH6gwaY#fB?#M<19%2#q~CmL09$--)C155|E4Oq>EecMW^z=)2vgK+_`oT}lp?0{z}6dxr6*b78Oex_6n zV2gk(-)OT5IhFNpuqT#ZO<~>;U)!(ZKqiV52Rf-sZko@ZoxDsU!|`j;h@w}($2QlB z#686&$Ul>(J|Tfo(;iDD799owOSKqdBC(tXuS{~DMdM64whcmZG9oy97dpIL0)sDU zKx)?YOeJr$rpy6=DgOXl!#W&T3lXy%Q1-Z6A2t#b!*I%+jYfJ!x+Q{*53=Y~R z8I%7-D~>F##D*JXRgSB6)By8E_Wzcrrq>{P@0dEFr= z^hGAU9s8$eKXn^6h3o%H6$|iGib2tFgzL6d_ub_$QCA%PKq!$u{$^6F2Cs#6pC|Yh z)K*(U!^O7`s*bL~J7MlpI=Q)sj>;xKIkb`1mFc4k337lm^_lF&1~qod**#a(9c91W zEe@bUlr5%!DY&nBDIGjKg_k2{ZA z2?_YH9jbV75Nlh9Xe`6G7~7*vo}4B)&I%vnx3t95--YgW)Snm-M4J3|6c$zwnQ%z% z!r+RxO;0lFx1%4bI?1E$YaQo(4&#l?2{P!(c7(I(liqt)1QDK=C>2o@s~M_CmcdYt zf6FrqiliAjC-hbRkvIYNHO0+yOA2hh_1@VNH0hI3^sv+Hi0m9K;A`iNGX~+6=gvA^<;)m-xFbNKj(#w{$#zs0V3(|L1kVSu^ z_iNiN`U3}lc#eWy4KMLIsx{w5IM^Ae@`q^& z81JInan|E$kS#U*Tg_a2Fwsv=^PYZBO2DGAFdD`N@4RX(bsfnaH%e9dEazGT!T0-Z z$=cZA65~k}j$|`a0^r`sGj;OMZ+kfN;O?+s+&gQ-dusyaag!p+cx3WPD(4n5>yYpv z)G$%xvdWa2WBt$$g>|yPecemf!dNUX9XQ|n#HARu%`0Gs;Z4F>>?+u~?dX@wCLryj zTfog!s?@nBQ#}oX@4PGQKalSV-QgwsgkCxcTB~9oT2zpTuNZYrmSI&hP|q)9#;K!@ z&+GHjcz4tqB2gx-xf>zrAH3gu}(X>CZ>{?Q_)Fd@f z)zOZO-pQU=l$NS)Ksm{eGbX8$ESb71{4y3~`{gr86IJFQM7C&Bk7Gp_ZqqNPL28Dn zbK%to4C&>nN}AcZrJbmfM=k{fnU~SxmIvxGFPRju%?lMI^Vmm^mFKg37%0wV&6Bz zQRH{djSir8gO>7#Mx#KgTV%vErwiwA6-+u5yFtG7UURmYE*PN7;UAvlLA-d>{B_*F zQnWX;R2)S`=I1*nwu*xf^XM8bkka~7DEY~0k#l}`EKt?(2fxR5F+f^h8lAd6tMqoZ zY7%mB&Tpq_v8^Fw+r&!xx2#k*skqI6DlT0&&^c=zNq>-EW9aN@^Zk)MVvZm&M^u}0 zFr9OB4v3O=xIy$IfpvfP`r5Qk*_JrdVDVG98GxMc3hNxx|f=zf|l`wxLv1K zRzSo!07;EbC8)@JcdwmCiDu^t?m=g_5E_T<Pjb;yIr9aq;l>Wras)k?z2mp4$eBZ-%!05&eAnrkRyA$h*3Z0pD3A=J z=w_e!Ja|%z3GMkvD(JZ1F+P`HVcf`=vA9e9?N3wgrOGABc%j7jlXk5FtUMdypaPYj zpQBO)W~1d zOrMgb8_?@bI!&P}Q2Z;>)T3UPws9woY#)=41{L$}58@+H5VU0oY#T^~S>hvmoL-zI zJzIGoXmCL=jZEYHLIrLV7KFg%9G2c8#O+D6K{zFowsbO4-~$3kU@dK)tG2yFyP~@L z1{b*K{c;hAtYnt|I9D=N{qk4e%irTK|2%&A_w~zv-(PMcxPT-VqRxeyabYf8co5g2 z<{2WBD^SQq)pF78TueV#aDt0{!WCNM3a1Xd_|657V?RnPi)La)&6dT3mL=ksB{P?$ z3YVpu#}_5&!l+8Q<3X}WK!_C8$XPB}kFG*dv8?C zlU!5GAK7Ty=^!aVEtFSfbR2UTg@S}$T&c8xU^^(=SZ*}1K@ru2V3-szkY=)k!m@!- zV=6vX2&)VcU8e|H5RTmx+&H#uXOL%%iYOrE%g&-bnRx~5Tz*GN6QJm)!PG1$R*d}L zs%^!ZFi#%s*F5ZMO1WeY|;3T}R?W%vxOs#N7v79z}~ueZ9enEtDL=*8=Dc3X%a7 z9Y-f0e^X1N2(8CuO-EMnqg#yFHv>tP6JyE&bYTYn$`-@`4IxOPAO4C3P!MHR>ewh# zzLp}KNCr681=8>2mH9r(>`$h}#ck81bttDwSeraFDIpav;LvD^3AkWj5=AI76-FOI}d#3%alP(t;4 zCz0qkLd(*=C|~JZVs@@5Y2UrV%i`0y1%zZk8Y-ljJfldD>`2D?APO{ZapFHFoJ*2W z%!Tavs3jb;ElLJNLsnk=+pBGs;&D~~rezBV~XFGy{16XL1(8U0@Y%}w5D#gOni8WJZA zefNWXwyVTG&#@*#bRlPl7?-LDEVh!W4b!Bu(mh=dBV1#4%kI}bEh8q$p1v+kYh$vF z^s2VS5~*s%kj9pwVy<@`x9!kR)ZN!#u8#N+O^S6wpnj%-Yrc?$W&hucD67i{F3VMk z5pcNMjKhvzr-2Ib0mz1Tr9&|LX9Exj0Q8Gi%GB$cyXj94($i52zyK02y%WW_=?vNB zvHvF74|&713ctk%DVwz+TBM_}9gM_o}K|+Uq$6#2<$Atuh3(A#xot&+g5%()bxfh?6c?b44T?c6bukv+iwn3pDZZk@~g*Bz^i`Zg_pJ z5|~}6PgSZ1xIT1KAR5rj+fq|FbSz;Ld3&ykdN5%fUtwq-q@|p|!!|>N&-_G9ygB8{ zO?~>ac`IjBb){hPT>&?TLE)Vd@OgcjS1k=mD4?SP_XX&uw+Y<)7lcOh&fLy?!$A4I z6-Hk^PeW=JY&yG-l`P!OVzac36D4t#p0!s~y7^+??}h|2fq z$d^rgEf{jRavc^0LgGK&bY>s8xvTt_=AXLtJi48O9Vy|?E@6XoNW&RHfwVVggNcTu zgZC544kw^j%#IaiUr9cXMgyz+wgzW3{@$a!X(S~TQ1b9Ruk9~OF;)0BnT}4rw}MRq zmYJT((*Sz@aE}Nb<#t3R(=y}wmW1%nT6|=lc+~RileUT9YDkn{Oj^*}yc-F0Lj8vv z0eW8<+{0}hPuv#sTbkSY30JMzsza-$t*54{C`Pup_aLm%>UiIe0cly z%{@D7Gpu+zB+*$nl3|qc?wi(J$A2feF66`b6%`t|veyAE3b^sYpt=jad!JrOdHz9x3w{~*bxjN;trB`#qwy^?OkuNjZ=EI+BR5cLBt z`$my2GN)au^iyP;l5$HBF76+HB}o8Uz*u(3Z_`iD2NTv7K8E9;zO33WxHI+7z?k2p zrvQ{Y{5oT{D#M9yUaWrHI)wc6;L~4g-p0zEggM}}&986oo?hMm`M3s79)98Wf0A7P z{_L{tU=t&69siGcp(3K3oP-Sr$Y45}9{-;tm&NiCV{xZ^f{@>UQjx-8o)S%|*g~1E z_TT1ZK)FP3kf&T~c-KPZzmr^+?*>#(+Wz9HFo+mS)e2|XoVI*o5qy>hnlh%`osR&?FUfl|9l~BMGo!R~}gX*6p3~uwL zHcY{k!xS9%0B^xgpVudfQ+{8(448N@Zv6=RbG8+7K-$n*oJ3;uOZW#65u!)2Y#FG~ z(N6VksT+Tc?i=2duZIh$Wa?^VGdJOis!0~c9PR_c&ib>cma6{58@PQ0FM)b5@ zMwWya?Ct2&qrsly|LRW6MaN1c?UFM|Geagsb43SC=(=Xl?{w>e=oH7*N35N!h19n-39HIe)186Pc)TxKTA_V1P4)tbu^fxF$cl+M^ zGj#&TPOau?>2A;&>kvTLf`(F#Mo^R2@DE@VRk(w|#!ZB{P-nhVB4qd)KWTBcWBi{( zq7)j~r(U`4*k>aOvy@Qv7D`_x)@BfZG$KBtV>n=)!!TAIfrzW3c#8A2GByyvdK8j~ zj8nozVZpu%${X=n0Rfwn_;|dV&~=V_o=HOCTgOQ$$c7z|ys1&kaDz=3F`R5p9#4#x zO!4}9wXU8__lk>ofORmVCf>(8QC0}DB!ip_@pudg0!XrC+d0D!Aq%#m%oR43w^uh| z)OW|{4)+F4I$RA)L`#TT-toPknw=#6gc6fGz99_!^B0OSOHv^gm%>^J27 z3$u^W;!?_o{Q7urL8#hTOS0hC(#neH%KLuyVmcd;Z~##P#%_a z`m2n8OxeYxJb!tg)h?q2IKx>HRQ8OLF(KDu+A8v8q6!JRnJc~8L;Lv835n60O6m1n zdhQi-)Au?QkbGyn_0DBbv1jM8ukV$e^w$P{{oP+B8H!WnNV3&?NQZ>5%`jf@u;uVY z2hmJtfnZm5Mr7U?Jh$a`Hbi+&MhEbUM%K|*5ZhxH;A+**%l`*q@BP(O`1Wh=^aKLz z&^rkoL51Rgc2th_*-tA3Dr(GfVNdq>=8wszWBL zrFE{#$Z7)95fyVs#qCV1;K(aPvu%$3JCb zr$-`J40;>8k&1gR+!A4!eBpaSsL{LhrRkl;m-|m~RDk_gYn3e0&dq9w^%lIbYNwYx zo-_BQZfzqZ7gygU4$*Va5`A&S%V2EEX}Y0mZKpH()!O;(T5!So;VlfYN3)xPz>U&gA-M|Xpu+*yN7cRumfofIrVG~vH?9$G zj)8#icRhL0Q-u}|=qeHD*P>_k4^^7Ece^`&u=VUP3LNepdtI;MjSjrIdao0)qnLB5 zUJMg%N7*S)EjcQ1(y%$_nE%Irpv2RytHUBEXB3b1MoR$}I zKG{E+ZWaAVa6LiiPnt3H_08vhHy!HJst5kud2;q~V(HTgaV#9EZkOu7u>xcN7pI?2|r6bb@TGGy9an*l0l{i0%_o zmT`!yl-}FDJE&VB%*Q$r)>VKPu zF6eT1x}6V6E+|ddm~^U~Am85Kvp)kV03zRd|9x9?D*vEL6Nx-jhF4vpHja~cUa&cF ze~sEy^=>|&E~$F#@?{9X&7leOiS<<?~b8UZ~q~5Waq2{{5BD_tm ztkdoK;Zk+a+-L0Dmq*VM14pWyS{j~QFphmcGu)y!rec}SC+B>palFp4RP*r2ovV{q zD0R*ko$vlH7}hOnZ?2q6>;H{m-5B5lIx1=Z7lyT8x`uiLc?!la|6l4M@H+ngh++M= zdPv^&KN!}3)I(3&@2SYNBql%X)FJQ zVU-N~z2~Wi=I2;Wd>{XVVHM3Gfz7Se$?NwHr}8kY%{QY)hk`m!ujzhXpFg9ZU(|NZ ziPyjbXiX}3=LU$UllkRWU!G~I(PL!@9t?Jq3t0YqI8#;|5fCU4;^mg@vtNlN5x{Cx z+@}!oE!|_$w(bcTdb6?21d8)ez#4vE^~~E(D1OGon7nyI(H!C($k5{fP+oa83j@f> zh6lTnjy_LE*?80y71u%dW_LJ* zOZ0}mUi@)uyFRR~to}Pv-oA{!I%~e+V*Mk>U}M^&Lqi4n6OxkZZhNX|J)!`%CrzQq zkKC^Wbp2erE-$vzJmlpe^0^R`5p6eIC@hr{y`+@@-NGP=65l<%w!{{+BWHD_3|7B&uNcY58A`IL~RxK(0c4MbI6G z`gYo+U^*oF>+=ONtV)r;Q|2k8GVGZId+2wW1k?r5`vznsLTLB>+yG#o*7j4ac`seHy`dtb%OdC z_(4H^sG9RAsAzW(RAyqzVwZ0U>I{%zs`?*THi9KBnp}ex0M9>rNc4@k%)v7^Q=)9J zHL!Vj0dJw7>iHGQFXHD0Vss+c$Ga^b61kxASAj0{s}=(|U|Rnu#rI)n^|LQJ8>EwO z#4@>Qf@Yhy9{dO%W(WWrv!5@sWs#B2f-5oUmSR|?SrID6ncfON$Wkt7U!WY^M0sT_ z+R1lkXwKm+1KWuNE z^oyYZ!}hHLT7I4EJI6uOYxS_}Ep_rgj7yY1ZxzuyhGL;kL)JVDi@EGLEj&DA`)fSS zxU1UPpEW4oU*ruV_wdOK4_~IefiGx4g+lB~Bn6kP$~S_NhwKUaS8U7jx@z`zEslJ( zZLTn4T-J(S)1AXCCv`OCXs5p%T>?PM-sK@YbB!&EyTX%{G&ma$KRy=Ugueaivc3E_ zmW#HUAXFDB)s$0qXu`vL)mBZ|(WKJva;*1B0?c?g3B39io&b-2E`KI?$2nwJL<~kq zH!c9^Zd_0G@g*fI2qi1(Nq`t!w?`7G2{Po$RP`kx0_e2eA2G|wtC4T4WpX9eEAMDu zM-OQF;V98is-Qxfx+~C@o(KU@#uRlx)MlbTNMm<5x1Xe53_@9+x{;+C4)!CvYoK)D z8k(l{9v1)QrRAj5O2muRA+Hbw3}~li?urY@zJY;b--t5#)Jc2s?=vF3som~66KUEL zoa-}u2*A3S-yx$Ed&IbLi>7G7py1RV7j(0P_w$ z_8>gNsW~fTGH_zz(lhg!U)MZs7JV+eEhZfkL5uO#WPaNTCzohL#stj|6;~~NKh5I% z*dfdRl2WyZ-gEaV=^)!mW}Bl@o^o@4_idk6WiNd4>0?B}?xy+k!?7to%W=b>_j3eo zC2FW^*E?Lm-4tACX{B)3;HY>F(&ix)W3SHS1NP94UpjCwo77p%lDig+VhRYztR9kZ zbo_P|rvj7eA|ge7FcKmZM;tBM7HQQ$aqW-N_Uk^p1I2Ry;Bt9Ym_kJUaONJ3rtB|E zxxb-!3D)W@7ydojNlkn0T=me{WFVhMG~!=mVzAD}fvwY!uJ_M(C2yTNn*J3p%Uj)_ zuQb0TPP?z#as0OTGhLRkaqZC0lZYeNrMc;SUOSHubwh+`w7uoeq{fbzAdNqfSf2$m zo&ca)F2As6`jXVHSc|yeF$i5v0sipM@v9ja>nwRKHa`EO4qEg^@d74@Q&lKP7l@gE z9(9tS&_(xv&@z$?dwRUFcWq6*SrfyiCRE3v)1M9<$dwO*YKjkK_&&Ug@cT6-${4_w zqJVkA1*2d@uLS-eSYv;1I!$o3@vb>bDSuM1piLin=`Sk^tnWpVf7q2F>Gs$@cw6~g z@bJURq%p?GyV<+D@QV|kFgEx`_T)_nkaYltA2fk4hCMiX*GQ`huadHDH}K39$OypB zz!Uc*&e7U`MM*AT7ZS zM%mp*=>v-V$!_JcLsF=}Gwmm=wLybVrlP07_%m;a?-_ls7Gi`_l5d~#Z=N%jOf^U{ z7FhBIzRu#K+7|2)M|$_k!mmLY8Kgjqmkb{t{1NqaT<7M`{o6laK~}f_lyzr)^GMBE z3l85^WjeMiEf#wM$=d{&vUKn-@NdMKZ_80|%A>iA*f4YQf%oXgw~iu?Y`5~zc~*0g z#`}jlUtWqhcCJamQ=C;HJAgBO>&@%X1sDMYWNSjaDW~v(iGN5GA-YZEBm6?fRmg{9 zsr-c^i!dl~PzNO5@w8e(kT(s=bJHkL0lBvH>je0xAN!we3RK=Z z!tHDUo=RqvI)%zUC=VDB`7z$QrpC)bx1wT(XoT#^9 zm`N7pHLItE7~nqNOC<$jzZ?*bOV9eU1P?O=3#m!o`pDo$uuhGF!2!G%?j)FLXrt*1 z0Fhu2VW;~jz((kADkg+v2UrJxc#)X4nt_1Oqk(kdbeO*nm_&t-gyJ3z9@n%sGv(&m zu%Lgkal9<-_dpmd2R;RD|19I2t%{ZnD` z)#SsslF$Lbwj|D28G_;#Lf6C>mSbRxp*$hTu3%JbS0=A_KV>SD*#?57Na1GGAQ@aW zV#)f7>m;D!X@~dk_x~-1%QQar9u53z1hZ+8>Xc%k;sj)Kv7B$|VTfDs4uTF<_o|`t z0RT3hh*?}df%eE3XF%iWet1gpnlVm4NpDG|z%U7Kgmx2(XHE08Y~|Sm24XfIHP}|d z@4=T$1qT!Hd+@ODFxPNiBht~l2Z2_{?~5Flg6XkT%gYozUrMcqfgY;#?J1(piy|S0 zA3r4?&49)dRon3V)BC~qn}MGKtgO9-&1kU7pNdD}Kwz9mTm`J46siI0{0x9?WQqy& zSw-GEYvi%tcMUD_7F4|#&QpXiNjRfQTsFH@zE|m7mjG~A?cz(3IwI-}7b(o!eZH|0 zxO2YASNQ&YaN03ZI=W(@5(L4Bx*>4r*+700sHA9pdf_;%R4WF=_X5QpfLC zhlGMbK(#`9omqD|3gR4^9YQ#$sbL7bNUCPX<$4;$O5ZOI0x$AKL+v$rPYz%bY4^Wp zKVEV%YNnbWlnsA-5*h#*g#&|IY^*7GPwJ!s0LcgkB@TkS4}ylTz!UANT|wU4vBdIe zTpV(*5f$ch4>a9`{w~csA}wVah7{PrWqO}$Fy01`L@4FhMUAPjM+s2=u6lGgTk0Bk ze(vg(7n)#yJILHTg$GmM zxC)eRECjf*F(NYhD}yfpzH=X}NJfVTUllAqCCGquywZJoO%&D@`9V{Xat%DOT3h|& zCQ|nnI-u^m#x=CZ1yl`Z@}TWOZ{f><*ft`E9RL@-03zA9_z4wMC-6?rEvC;E2Ydyz z8BmO{&a!9AGD4DDZpiMeODnLUYmMo|9H^biTYhia^ z<=+C-IfcK%yqI`j)Yd8epEoYp-xwc0>_DP`0EQeP&A;ae8A1x5XhK6^P02V37m`UA zOl8wwme3-*81FVJdEb}w?L}Dd?`#ir1x)P*OqYfpy1OS?vS<_e-Alx1!LsNS5mpa5 z`3)y<8&4p@D?tH0eeinhB{XEO2*f(@Ypi*++*we7kKCT#elL!27lq>!J%1Oud0&K| zf!qR8T^@8Kzzv;mq(z(5nu%i!!EsiAxGqY$OEX>uXLe7Ng?_+@4zJDy#V}Aq)623a z!?!i%-|l#eOmlHFKL8CYF9cn0NIB5@XZQgh;Za8o658Ahoe~}uNHwR5>GFP{I?n-)zd=E;ktCUQW{`~BisE70;40uZ&6#6 znk00qK%=(P(auObo%zPAm6Bjrki88&Ltb*mkG-k+|BP(WiU`!rVyEW4lu*0N8gbebEn0jR5!D=SmBR zgofAao*Wn1e%v{dF@n9xQ?iYl+(kenWo9Q#x*_a7i27f};++JrLzW_jnM5q2kPwK= z@a>l9VSoya9PQOUO;-5bS^F6jj;KL*KeX?9l)yo`Y}QWa%6-IxM9Q#(t9=4DsfKnL za~PCz1^KDrhtfwM>M9^QZzNg$p1*3!=t( z0rjXc9cr*HLGeXTp7}fN=8Fq}O^Evz!>9rGF`mxgG;8*ySo8}a^2-DODlVRR@BIyc z)IHh_G24V+I&Qt$f%8tDKD*Ma&6ho03{Cy}DnaRm2BE1P(m1aM9$c{O_-mQ4@LFvA zE>8EgaoBV?!>SbtbDARB1G%2RudW@W6Wt)wG?Hne83>|0^8L0EsCEA>9#13RHMI43y%E!GvdjTu? zLY5AZVoxQEL(jfRMg-iHph0vLEseZE5if86fXlhzj-=o$wLu*=BvxBmE1Eao@%sFr zPXnLra})R2W}mN^0;pc`JD_J07m>dk0Z=BBwpIk2VT-SobQhq%ixn=(u7+)eNLaWD z5#1i6c^MXD4ed%C0ol$*cCU<}8Ldju(19DW=WZ%o7+VX8?h$!eE88^Kv=uC z;@YO~?iCu~0JgT7*Cz+uv?fCv{UQj(D}V37Sw~%82m(fp&>)HCW5+-|@xvu=@m?*^ znmVX4E+BJ#^O*pU)g`C`S&ez;X4~sXG?^+8N1}=E^_`jv?k)L7pG9p!3H~BF3m?Q# zz|)9sJ2K+Rj-PPYg8gN?y;pXFcB2O{TOoI3S~K^G$0vbHVPFdt&@`IhcAuyzh+OIXz8L^Va(F_=xhNd0Ku_=t*TRG#IJ+K15PhoK6N`o zaokyA{3}~W!T%%3aiVR^oDyQDWfW8%1g z&w{`wzu6w!hwK&yqJUKhl{!)8o=W+DtA|cP54YhNvMm;YeLj2(xNZ@bEB?nXoDIc3 zJpK0{Le^)K+LIZYroP=x52!j3Jha`Ny-+EVzq?L3=06zLMT;}Y4=>!pE|?^WrW7k8 z!mD1iL8g1Y+41j8e!TTBmO>4zka@YFR`|o=?MM%b9DcXNi)^SOiHbk=d6PIYdBxb^ecf zD6}KLGflfmCm-@7Jsc?!R;TMo$X32RG)D8&$^P7__aF68#vbS1Uj($%5AB!s&b#j| z-*(YCQG0s?ISv8N>l`|^yw~7GP^|r~m+K8r%IwwAB}G2esO$R=F2Mn>Ww<_ttk8!B z_Fl3H-pTMSgG6elZ+M|AiG{B^bygcLqy8c`*}r z@SFYt-%tSoyY!>RyWM9lB_G}IZdGsK6OfIFd?ZupE*t}+Bh*qhz9*np( zJK~Y%uO5CVP5Obt+|Q z=TT7{oE<(7O|8prbRdS5@1_r3UXWE6U(0To+g!!SHc)Kpb^8M9vaQPp%ucwS-aV9Y z_0NPDUHsz7DgAZh|>2&Vyx zCpNR>nhaO(geq8Hh0K|h z$jydxiWMqiddBk9hkH*oGSa1`UUrY(S9_H5MWD8m5Ijg!ceP)KscNQqnLkSXop*+j zIVXk0C#Dii%a3PKh4CB`NsaUTuV@=-;;yRL6B5nMP_qpP{YO)mSLUhAL@?k#mbLU0H|t1}EBO+VkTc88w%RN4stZ9s3mIoR z*ebdkI@EfGImm9f92LE6Y*MNk2+hCp#4+sGncR=Y-->z%%9de$^fM&B-cr*(HU;lqDpmlltGFkPg!4utK?8)bX(Hq=H~hk` z!~k~H?G^IFFiNK3vl^kyFk2PV@mKk`@FMImdxLh5!uUI`Bhw8!7N+}38tN|+bNK9C z+V@pNsnqPw4CkqbJkL)(YcTqd=h&a_dFi{Ca-`2?_e@i-TJe*$nU1P9sd#u=t6vUNx4{%e#)oY&^iK6tW7XWwyLCF_V_5M2=<+|-DUSa+#0ec@w4 zYvTXOvUtE-vbn~nshg5d2oI&p8n3hX&v)OEm2_!0Y^|z_i`)rPG4mZcFm?NEe`JWk z1K+WMXFkp88xCp1<>r}FyHUEwL-((MJEIr#)5(@Hk>QaX&p^7p)v;>iR4H~e%eenUX(`5J^kicI{PTlk4J0I zMCb1RLn>4lA0spE!RW6TlQtqccfa}a7E>u@{`a&F-wt`HoQ>+m6lY!@f?rgUu@y%& zBLG#donpdIy}(Mebv(^2SR;Zzb~?@6>h^&&Q3l?#(*GIN(E!+ZF`7_uQGh3^Hy&ug z8&lnGTGl>ICq|$M%4pVJB0O(A=uV)noFEhb^zm09E3qQyKJnq%!VK)O1r_xAFBdW( z+Rg5H%h%WXS-dE*?^>QYniflk$u9uL=D^1WgW9#C%^KtO0Vn?D7uF{46|a6hxC=`; z?kKhV{I0L-@@>Wq77slj#IUdc=QK-m?*+Yr?}o+8B*B6^P+6cd%SaVMkIa5OyE6J+ zdQV9q84Qy8H1Ol+*u`Q$t@_tLwXp)re6$_R-3NqgK8{it?Mk`&_(fca5zrPXoNhI< z^yB(=zd>hoVZzKC1ys_Ion=hP*_mZEhoq7HoiP>nX5Q*#Cp`|fj6MHiX2obQY3yWY z?4=(w@2pVC+)T^3T8Y_J2Z!W|^3J#hquDk0?Br(>Q;f_YUga5Y?Wa%rmhMFj)?55V z?!1ZnbP~S-A15K3E}aA@f1xTv0Fr%3^6rVQ4YTY5NXoy4mY*sYmS8YXmbsI;s4ku(W-k zfDZu3)q@$xsv2Qnll0cg8U<+Wq~U8(u5x^PzK=h8EyBAB1QeS~)MYb%z>DF)7?)m# zmI4|$09h71FU_@v^q)yoKCpvHlcnRm9i6@kD5kxIE&LuFgnVgS-9(Odg47#95z3_#-1aH^1)C|S&gTsBQd@{;lNn}Td|Cc7O}HzRbI z-QgW?>X0G5?yTwV>k%DI54xXJK9G(iF1hd#v>0P%=xc|pv(zDDBG#H(oq-~~d-Qwt zYY=z^ql{kTvR;$=Uei0hW_`Wp&w4GEdo92ATEY8BqJ3oLK5P9x8{0lx zuRgn=KKr;n2Ofr1*5_2;=gh;fv_M4ne=sb!ueN7TF^srrlGG-5uU;D|15dC1{XzX{ z##ea#9zM#(&r16b-m$CPm7%dfENi=dNVGk*Mej&cx57e}m2Xam$bd|VVYugcS(&r> zj>wN3(S-AToCkFC&%5SdRvlMH?^dq3;&FkW%4ontqP7I7Xrgcqvw_NBPFMRkkz024 zSXd97OUxH&R_~lHI^HA^H?IB6hm}#O9J1G5=KKxwVr>a^yHW-udzYh*BGQ_bE0qZS zI6SbEZCiUNF++ws-Ng2kCD$O z!+=Dne&di@qW-xV6RA~(Jg0H*FWf7lc(;iRJ7}aKZsbbFNMqT^)n}OOdS_BJ9Tog3FAEBUf7zVpB$`Y~6U_w8`fbRUxjZ-=9t6e?I#?zC4NK*#Vr}K>xQz#|Jax=qm6Y>IP zG3;kN|CU($p@$3 z)~{8{+?NsXK>jje*Ta1$$)tyI6Ro{`2I~{rZzlE>+}GQW;i)H}d!>!_5rzgIq>K+6 zn_QkOZ}BYaO0Vqjq>oOPg2R?i?pYaNT+zcMF|QL!UImRqw%;bz-rA)NDLeGvvpdY} z%{_mC;OYFg&C(2QJ>=weT5$J%^$_rR$pcwW74$xQ=CMYEjm7>_r=AbGA$>5YUm!pHVmj?{x(@~R1Py}&+F?xmf3TG_ z>~7|iA2(yu{&)0&kmKN@El;kaqj4O))!r_MW+dkWaRy9T?3l!U<|CNriqk#^*^YF{ zao?JW{6;#%0*&z*6`1x0z*|CxnPMsjGQplqgBLrMd#2Nw03VZ%X3_b!$(pl(aJ|yU zrs)~=@rnft=k13j4{z~pyvQOVj_pVHd!hN6Of1@`;<*;C&BB=ZuwrxXH~uu$=Pzqb z_ZD*wq^+i{D3Q`xz8Um~+H_dFD@KdMt=%t@ix533z?jp=jOURSw9rB3uG00L*IV4P z+B`7Rok$vR>c(hk|0~5|U*9!4c9pIp>X|OtA)@Z1l;PHDt6IqP$rvJMidp=}KExg4 zSNCYCBlD5Env`DM-`{vfh56k!hnG6Uw9)yu51n6_Mz{HlK5v{}=B9BEPO99tq&)f) zG@BP|@vP+abickahpx|=&8+JjnLWI7;>#sz6?Dmh`Ry=zQ(gP=hn!~5=?Oc`J~8aV zgV&k#xp}b?gmKS#+W6Tvd&wF9Dw=iLCjCP!qvvGK(~J9hyI%Kax&fqSry%y9>)AT{5Y-A>cm6LHQ z`F7OeY$J@{_+T2Eo5q6ftX&8wpat|KQqn;yfEtiK^i;2KiLeGdx$HMy02GVmD4r&h z{Cz9f-s!}7IZK{y<;`d#48e646V)Lj>Dtql*$)Fvih;X&Xhl&>lKI%+E@t$N9IPf| z?%e+JY4fp7`lFU3f3FYT*oDRrt!z7kBG0)ky9Nsxdt4xz&D-VNfIa0Ln(dfg)Tn<; z_}T8=^p;DSc@>-^fIq;ET~UZ>32t497+8s%S~y%9B^YdBh zk{NrA-^ItjOUQbcSn)2Y;azg;yHf-2Ql{RWUU`@L{oNVffhoSq2%)&Egf%9=OpnsQ z?+=SRx|+2BbBzq!sm*Q6iC4cfekaf#txFBf6Tjv}YcU)uH8RMFatSL^RgoVmzn8e0 z)wsKCKtnz$ys|L-eCyhUfwiiswTmlj-|5{2h+|JatQG#6^AdhvqkXl`{(bSj_m@95 zHpIU#NPFKXo^w_Fa&1F-h4y6H+xIuWzrTfy;2_^~RM&6+w|dB)bT?$ZH9q35We#WH z*fql(PMJet;~`Gz;KP;m&hP7wKCXjAhzQuzQ|R4gztMMKqd#P$OSNYpYh$QlWB8Io zI)0<8Vf~!Xxx~A-M7hVLOx7M(l&Wxr>E;WmO$e&o9^6%T1m~#LC0=o8} z{$;dV3Ss+7U?(TOD7n-tZ6Q7CLdJ|XlRJibv$uJ!`^rQa?3%89!SoexDYW zL3)%=`P8)iDT{*oCr<-_Y_c(}7(7wV^*d2%oH1lvPdcG&fJW5xmv3*BZ#PYuC_T|d zFCW0*9yu#gLM}2lTbV+c^vpnBAd8*bvP*Eq_EB6R>-WFB&(oXrn;UxsHmi)I>)EC* zbLzs`AGCEpD?QS)tURHT-59wyTJ7B>Wt}{%5pSM~(a^c_LX(;N(_we$CDl(kz1CAj z=-qQ5M2+bE#US*HVZs-qPkCC|UrgMm^7NVf(^U%%u>rYLS2ux@xmf2t2p}wtyui?- zWZ;=oB(=-0%`E)^V0Xw@w`=)nw6ruf{MyAh_kF&+AK2a4Qq3_iodWs!GR~o7LX3NO zTbW6-_!hf(V%AtqXERN6GmS`9|N13OMG}@?^2NKl-22bB8TLtF^Q7)3RF@P_4UN~7 z&G0$#-F?r8uq)q>-TNLfuoV$nAF0rX5VDPu=nHu9Jvy|GjXW0P@FULq$H~wiDTVYG z$g0re330ynl0uae@BLW8paH^9I06m;fEEDYdAP?<$p0F7gva8g)Cb``|KE|vYktH3 z9eKQ|rTG6u9wB~}BNwk%sLnn}{PKQw)cbu;C;fj$9$9*V z|Fd~MI8=*||NiZ_qm_CQbC2);SLAV57U91mk3}jy8QJguEAnWeult|o`SrPiX6A8* z-M`QBZXIpW+#ZCg)tFy>wZxM;mrw0M?I#O$fwn|F@YT2fYMy^*YBRL`g%^2re^uN6 z>pzjlYWGK-e}8X(S)YIU=+Vv&fK*?g!^OiE80ZG?!)aKES&oKl^`*at2+EnZmf>&94box}KzzX3+p`ARsFli~itv?lVGUPT&PTSc ztz4iDXuPY6n+kt-F>&SUyGtqG*WOjPg#)YX4Dn;DHB8lOtF`%t?^o+sD{l|hw;aD8 zDp(eBY+RqgQF+p?5q9 zbYN5}KXmhKWpXiu-mxB|k2dmb91&3l@@uRg!uB(c1qeHILF-+tjQYbo|@V z&zc8`C+-BJtuiSs_f3vmby1Ic{5yv08~*$Fgj>6?^RAo5P@tC*dnfZM?=GG$uC@Sl ziOZ<;KB@Imcp3Zju;<-Yk_fttB&6L2bg4**?M#HdwnHj$p92~DoJWBa+z zR2_Nt9>m?-Uu6%KG7@D!mqhnqN@VJ7$lT1Wbgbzt$;LhqsIif(QAoVIE1uY7A{9iF zKV{3E<@DY)b2>eK=fQ8aZITtL^xIUw(JhU)z#mx);6~!(yI-dDq#wUdf2a6&s`AXt z8v%!h?((kO5BE3kn@kmmva z0k_uSS#frUJP3$<1_40v`cQRq!j~Oz50a2V!UuC}gm1)=)3geNM_|Cp!T5(N2XT8X z^VuRcWY+7$TX{b1>2ieta6=59Ie)#D6o(ox{KdrT0}$YjG3)v;Cm$+hBW7i+V{|YW zyC=O|!Br26?$DBe69PaDa(~fjUTv&T;76p>urx+6Id-|0bf9=Jt?47LB+*g%4Gm5- z)-)@(6;(ylc2Fo#$?ny8(g24p!UhOb4plS3q;`KtN#30n0-zWU9-UyF9SUOo=6jJ# zr4=91uB(w-p}Bm)1_d{GQTN<4VF%lP3N1`L*RgF3{>CgOQ<*TM7grxsj042lS#z>O zo83ZVix36lT5=(K$2I=f7t44bUt%YrjS_TJ3|$}(l@fP`yJh6>~<(eYNDn;w+PhKA2;HnpauJtkl5l^sIm19|&NJ(VzqhKa+-w&`afJU&T*{v^@^zbaAojgj%Occ z`SuHJqnsNa`Zig@U@-j<@lI>5WA0QQvb#zaRpOFk8}o3!;8wU>m_bIPZd+~rhHXAQ z?fLMJM;F3poG?p#-c6*7=gmG!s~oigWlz?{`|PHxZB+W9$HWkseIs8JSx)=n)_i}kMcev4h^so#iYMCI1{1ohrH1gxmRaAt?8zDJLc)1C zBU~ORM*U{=l_}6Z7iIh?kp)hu9cU%riYMJ6C|n6W|L5B1DzBCWTW=~300o34uRO=3 z9rwmqKGlCjlpcCywD0AdZRDga#s%JoN+KOGVG0Z``5N)#yGBw~4V8F)=$a}xPzJOw zMfFWUAs`0cNeVqdS3B^s|}r)B8FP(J~b z@}FaA(~t+aVbcBQchblA|8`Q`?8WE07OP({RK#~SlP!0vg@&((0ByTn*k3+=VYUqo zSfU|VPGpcw2Dbb#y;>l~B^!3kmw0tIKz!R2Q@q^jwaUO|_-*#fzE+goVR!d+FNA_v zX@b0%){rA?m+WHzl`JxZX=G2A*@b%~xLlP()gj zXCeTY{P~$cNnwTD+9s457&!!7J5hNO2AH;ydBxDWHzwb`MN9o6TMCR*^e^CJtSTa? z95SzL!7Qq13`e4)&zV7S3ERKyy!>$6iihUQUE}XYEkqG)VZa%5O6+EG!sYn{MNQ^s z*y9d=>CNqd+-w5?zscyB*F>2ll2;(4+YL=}!2XF2U)gRuQ0w&CpqqvD=bVp6gqCj? zHg1f*7(LNYy*5JZX7r;K^@^(NKeeBDEccP>EGpYm_5?-R87I^}t&J$a7A6>yZLvsO zR`e`s*W@dS0D;_@)=^}1kv;ljRMWEMZy#J-`F`J+B0!r zxLy}cTPtQL84H`n^U^&r3nA)r5P>UHfmdEerfmvG-o+^pl0*p6QqyWMPKM7!I<6T| zr=}%+HrClhzEc8=0yFLRWP${T%l-Zi32G*rW-^0XzTVn$sKhup;g@ZATY!r&TpGp876)_9)(R$ghtzj z9{_6>lF#|%S~k=1VHC9kJV zEPdMIwf2f^&R9zfq3Re2&v$EH_YT6D=95cvHA4eO0ld-i3}sxJuF}OT!|6{3I5Eu zv??VC2UcrKwqtF%mD#mB-9`XKQ2)N=zW7q<0QlMdnwIZ&d9w}CfE(`xn9A{=buGJgQNye80AnXH3f2(l(274UE&8Z`f&lr#xizbG%G zQE?pZw;dD`ZlEKy5cDkQEFB|qF9RxaHYF(odc)Z3U|?A+#4HxfXWVzKYzQ}?gRRdb z`acV_(;+*;=N@E0b74nRw;>lzzzW4wn1+NE2_jVr*|Wg3sKKTYL5_yl3<KQ(6ZTjVMrnLwh zQvKf-N@HO(A^1qO{`Y# z(lFywU$wU{q@ikTkBT=R7{SO~p~a&J{JlaWVz2! zXm|JlB<1p?X>G}s>IdyNiiho#5+fz}ZZ2s!geC_P>jnQ&)m7+cR`}#&yi-1tz)iN$ z?**a1n?jj;_?#tg%}1j`g2Qv1!M|Lg%q3UglE06@RCKi$rW@o>iJ zHw*Ji=`BE&vzzl^dCu?jU>?l?_vUlOM$-V8DsWEGOuUfhTaqPoac8mWs|J`U-4YFh zoIn7-7o-qB1>UFQRKe=65V-j%2{j^2kIM`1GAkD4C0OZFjH}yZScDDD<+ZpP8>-2H zAb&{`jltajO}PZ-{Q7Qev2D#3@-Iq3=ZnAzy5VWQT_f!J$U|xx^gD|LJspbPB1%G7ECLzt^H>M>p|TGgZpN=n16SpEAlL+NeCSpD}Oxx&i(sOln#q| z+==N%4zT&#t=mg@BX$H%iR-RIZ;ABK(qdh?`P!U!!5AikBk}?+yCe?Ye~|YE0-S|> z2!L`!J2XsSKD)r_uF^v+{$t<+RQJWPLj}h*!I@2TQjQ$+zLZ)<~tGf6)y09}{f`7U| z*=}L;Zc)E(@sw`Ks&46yZrPb`f;#dj5hQGMixBQI63#1E^=NkVXwCF!|LGyh_U?I1 zmLT?;CUzQD^_q6{n$PrF{^=#j_F0?v*>~T4Y7KUYJQU+;$hE{vH_;b`VF!@Fo)%aL zOzzw}tqJEoduULey13;^pbi6a5Chx8fss}MNrs^6?92>8-z4&B zQPJ&ql#D*VD68{E6QL8l0_(o}nsWc#BIyMYDe;?cfQ2p7yKwvmUt<@P4Sh2F2j58o zttgfeM*I+B=P*a`I*reQJCGH?4`-Z)GA`qq5j*?fIkIDz+mV@FrEOev>@^%KU&2Nc zOy&ocdg2E<9{uScv^tN?cvwza!!mi@J_Vo|vBSz^jL3%m_7gcsM0gPqEovZ(`atL} zUSqQvT2rG9wDYb&Bz8(AQ}%++RT34>U`QRpirTm9B0i@Wri$0IJODRe&^ntRFSVs( z0rpVW#U*5LoKR*+y2eZB(+&Ni87SR|sKG=(12*~T?{P#9?AT1-!S0c4bI@%U7-7C| zW)FG}#2v?@*vCM1*`lvAcaH;t^*;Focj|9}Ec^L`LwrII^UNncl^0)D&Azum>h%f+1)g4#cW&A3-!eu1?LN!5UjA;0~MDisE=}y95 za(nMUCSA-yJ_Pxj3e~O>*H2qxb^hvHjarY}153n%HI^{W;Cful6acP40}QuaHy+Pz zjQ!i-%72*9R-kIG;Yf3nscIp(5!x!~tu>rG$*z|R5y+&(*eezQ~n%5Xkw?O1)$Kl0@| z^rd0-7t=>y%;&#Y?tCE?srJZ!wLS9H{>)cLtCHI{F&X%Erz1+nbl8J`UsYms|6P#W zcdO3p6W&8^xBCL5vHsm5cYLoun7Fwf_(}0O>$_sDW`quS9^}7E5eR$w9kWlxO$SUm z@k8h{Jd6U?`2R?m$Lo@m4N+Yt7TdWB(r>iExGu#1;Osr4nhF6KTVQ_;Rt5MbWBVe4s|Y+3)ee$D4Qg`#VV)O69#h?BNXkhp zj-5TcWKi3WO$qz<5A%GkLhz5z4UBNFk(%J2DIcEo9NmA*k%?GYymMyD-^k>ap#_sPwes7@26bNeJf;RKH&-p8Bhm`*rdF(IO1KrMxD8PVBJmIhl zY*@m&Nf+>l8Et=<|B_ZOAtToUf8bS07DOKF+b>-att_ku!F*0uo)S@%4s&s#+kqF? zI1Eb`TGU1Ar{xFeBB7JQaiUdTaQ+*49Ir^z7=yY&NgBnLUBuC{ta^Z7$cky_UT)SA z96*7Y!aF^dj+L0L`Wt^EkEH%7m5_7|%!az2#1A+M4r!y{n^feN#2+U?fwDhHLFCcX z7Lh0Ft{clOal$k+h{A?01|$=N(mkRlD@}s#0>{s}=JS7!;zLmR_L$yen(V)G)yhB8c!x)#~s3>&8hfmqdJSvipS1kd`sEkF6?+cheWh zCS{&asIY9S`#cy>FV(cM)N`d;CPF{wRo6R+5to>WP4d^&#%&2|dD{WmBO9s$P`G<; zyl%L;@8(BAY@~GaEH08NvbMnLO(LKr2p}Ct=1d+#{l&AYgHm5#IechA#;wZ`{?Qi5U zZT|Qcn}drLe7c8=-s7}zmdn+w+?^oMcJmWj{J>0-rHh(_}(yVD-t%+A*Tbw)VMeBk>SJI5?b5w)63k-PoD z+!p?Fo^I}_Aeoi5?#7ru)H(P=W0K{O_43E)E9pUhQvUYAy3l+olpIyOUz0yKf2y*} z1EA1D9F;xF%biU{o3UcM>^GgAwk_xOZ+fhmO^M{n*|ez~@5CtEKOvV~A1mJ9Php9m zE(>Q#(1`&$3$h|gu4NKF#HpEa`D}&@(8MGjk#LCI$rs7S!SB9B9{+mgEkk;f}cKBw_tkw+5w;kq^^CFeFjUN~IZa33D*1aYAef4%D1fU+6kB@WOvuiaO!DR8V z`v7`dmg@FfdgHwT>M%_k$1Ct6!XmI@-RhPrg6s@l%owiP#fDm|BT{mR3g zaS6huy;9pd^ESOqaH%@EC^~)PUUuu{c$wh0Oq6NBg?%Z)*ROKorf1?E|PzOx&LsHJR86M zACu6XZF843{{zg4N9Zs-ZWz){%Z>JwYe)anMRM%P!T;(asU70}7Z=G>?ULu*OyPUG zB0E>-1ul{k7rSqKdd>4(V{Pl{`o|>ni@QDlnuJ#Lyw&~vFPIDc$0YRs2u5@c8>;2N<+z2ImDd5V6HsoWuC_0NoWC>ds#pp))06-{(?F4S50T5 zd*3h3AKxp9T3|c=1#>QH=NC#mOy4Y&dO2$@miYw;z+B+&^NZ!rlDUf&)Ev$K1arF& z+qdRzm)xgh9(*dv&|(0a{OZkuM#j?lXA&96{CW|2>q(|4Q>{x`G~e`XOsJW))|>jW zfVkLH`9m7K+@!}4ITgym)lA z>yZ|!I1Jv>b$3vs{MJ{K=v}R7M~oduYUh1XL=`vcGAyUApmD&>O1y4Vt*Jn}HC`BK zeSRxxNLVJ!*9-ID5$od7J^;*bSsMPl)vk#OIEWJNtj%}-f+&MG0JgRcFldwSzE!u3 z0&)qM61{z2@Dd&xtz0b~nNYIa$PLA|O|QkEv0=}HgvrA^y>^lep^2{Q(lm65^{h1#_X zK4}B3-;O;uNRUfJ*>95mbDom_v(-B7b?5DC?|~(J{?whd5Kv~b4v{T8p6dDR6XKcP zk)F}yX&9QQn$ z2L{qmCS*G4pw>j~9x|clO)^iiCY&g~K2n%WwOAnf;dV#= z)vd6QmN3QxFPbXm@x$XgmG%)Y$c@U$L);DJYT0KZ8_eG*W&M17Om=I;lMb%A&bANl z8Qd-hks?|ad&mA$>sQ8&jc^-6?$rr<`W(?h`^Gx2FmUK|OWHFxa#F4Efsl{H_)X6@XMTY| zUwvuw^{%EE$LPDwgdHPcr5r5tq4jzXiMc$5aI^8Uo+slH%N+wM*MPZXm4>Q+e%0H6#lR*C(HDdwk>jeP zr)k=iIW_Mt9z{^3*8mnIJ~CRETt^T2ir?hurfxoJC)zZWIfz|2|G>m!uJskm04p2} zUumTr0_c}(!bs=RSz%%D%yWg|qDNyg;V;K4MNK2OL8L|#7$-sWM7z(^Hbkb#0RUEL znu)skfiTQRG6eWIYLpwLjSmARzQQF{&`PEr5tT9b0Jt5e@4@aYLx3X*)6_mDX&5OO z@qswlK+$l+d47IVqlvR8`DJHkgDwn6)-V9_vGfO`S%tz?wAeEi^FE^Hw__CY`s5PA zaKEl?NMvfbXb-uAqQny7u5C}N#1o;v<1|pOw|+XLLq>0oxj_Ot0(N=H7^ z@L({lap z3#pI!IcT&RmhOABiWIn+RVrrJ;+6aJ8QEgD!@@-{Y=02(SlVaGvdG5_BRG6ZXJ)cP z0?KjMQxcMuQYq}Si%EO(Of&IPZ+5BE0qMvr@$Yn@xPtk|Ya$~epVA!4G-GRR2-l zb*od3Jl zT~TvpI~sCE{%Vaa^7f%Ih$z7+_L6eeLqH?Qf0x%r0s1|1e`!;i{y3FM|aUQM&sLF09Q|s5tS%F+LD?s|kpO@+=IeyR@G!%X#Msh= zD6$V-&@GptL8nI)iXFgdey*rJOK388*#LQzo$gD_5cJZusQE(7e38D)RPsI#GhpkI zoF)$ng}_az8CPP6JuD_}H~dtL{EzL0*q1Ds+QhqQ84pbH@QTcQgF}ntqJX;1)`7T^ zQ9= zI5gs$?4w56l_w6^d%@i2H4z8p$P}pdhJ~{Aw_^wCpdzPav^LNpR>`={$N*6W5aC+R zg5EF)1CMoviIi3P@+&0f&C8~1X^Irskpu88RJg)+N3p8lR%UWH1aAIV;w&2A5kW-G ziAU`RB@L3#xPZJEDaBZEF<&tDyM!ub5ABV7N?V#X;Q)5Z32!0wWIF>O@3ELnhpj^Q zpO>JJP4;t;LBzuh8F_b(>sTMHDVLWD6X=dh&1Y z7pTG*2)+cKt{j1G%%RjNg=S&c(O7wE!%6A(!jR%!mm|L@|D=n#EQKHjbt_EvUg z9c*+y8HcN}tvxeD2G=#fF^V{a2Rpn2rl$7R=xfQ^*F-u^0XBSxW*Ry#TEO*6HB#g{)0Q) zCo8!-u(D_vyd5Ong8?p+&3+o3(U!dElHhray8lioIQ{lQa_te_0X^9`=wmm<=1dm< zi3E{?d_U0gn=iH+c;-i6?WZ`26fd_^DP}*kz=>w*Uq3Ddg`+wi>U{GeROg*r_ZB_M zZxM38G(`lL-V)Armg6Upl-u$%E6BinjPyGREhQXwhFR0A&V7C0YBXhzCQbR$3ieQ#bZ22FpW$F}!KEOr1JG!ccjJr7I}M=4-& zKSla>sP780((V?<1lDT>>ajb&m!Ur&4g{OkqfxKL{@eAj;i=BCUMaVw2I z^N6jQpvjAH@`gGR;^Zy0rx)s*H4*)7X z_E@{4D@Y?FM9|JbX6eN(zP?2m`oK@nn${oMj#d)}1e2(SUR3)52Ec&GAig!(AeR@g?veD_k&Is>bZhf3dFtywcX=lFFqSpe zH^zqxTY6!0A>+xt9(_Yx=6TlxpytIlV{@zMy&QzB4(Q*ee=b*~i3-hN3-9NRGis4J zY1gtop8uiY{oxE8{#`tB}<-WT#BjoQwFnB`Rms$m9U}(#ePYrH|LmCG$aCMQXPu^4~URmlcsV4U+Q-B;=aieESJ)M)O#T)9_J+!0Uce<)=rE2(_ z@J$!-hXouFVG=664T%oZTFJQr(?Tr}A27uq0@O$Qwwmy1xR~GjjOn-2nuRcSuC$a*oX8_skSNn>qG-hAscNWb@;);K$`h9t)^kbF`5-b(NuUfrQQwm|Vyb@U}Ux=29Tz=JRr;FeE zI<4mQpKhP0Q>{SK;=KeYXsEaF>3u|LbEA&YOD;lyAdeP9uYa`TEl}cXN!fEm3oHxh73}=1 zS@mB2^Ny>q+;6iy7_zKjfG*%n1w4mL_b5qn7tLK?Lffe#Hn`Y>kg2`Pn3CsD{wVyu zh%4s3U!8kKAVHztf_2RgbC5moIT%1i*ahOA%YS&gO+nQLzY+M6kAqx0{ZznLZymvH z*t}P6r=~T1tf~dx-2w0Y0lR-cL)&he6~!+otfH9kZ~InX)xtlwu5KhiZhu(am|Ow8 zUWyPQGWu&;y=yuz*0|r7^b|iC{snXQ2tgsA%>OHxQ~Ydi``PiR?5&-jUCw-V>;3HE zsT{-m%wH{^7<%Is`epy>d*~#}n~fGY{9qqGh)oLEA*o$qasDER0szc&zzsxWNf6Y^ zq5jig^resT$K@0#YqI3}`**V8bFWd}-=qw_Et7<*Dd>k>tosuL0Iof1Ux9i~lxj_}AvvWgu@Q?NG7Q55GxoBiz;(SD%*)+66R-46rT?3BnV9yl;Pd zSr2o9^HkDKShQyL1LLTV4PUGeA!3Kx1;P(gA+kJ(8s`U!fym=OQvtpUp0VFiKBcQf1ihF~uJjKSC6U>jAdX%%gLcJ)Z%@@0;4F_d*~* z0?7dhYy#xq{5dKnOGIoRk;Q=L;AQR22WM&r`p_s%KQ7^an1uf8BH4W84_wx7$*ayt z+oh9J3ZbL%N_3rnfVq0$L6@8VyMWfgyu5?@l@7&fi&ZmRE z#68+9@^yCR2Q~ijzg#3{fp}TbCo_VdbsmU4xSLH|sdHtDpq;-QIS`SQb>-vmqe{E^ zeSg6m%JZRM(*tO_XZ_L3;ZT`tl_9ycW-kmV(DCYID>es<$UlO)Xq|VpcG;)$uHS)d zhmiK8Ax|;AREl#XYUc}ctYyaRZ~H*AbD<;o3p#-5V1covj-ZidDc7v*hz$LQi$v#* zIG{B*2Hk{P%R>JU^#Mj&cUiN_d+I4HX~mexzb+E2m;|69BPN_%?x=yr)cC#;Jd0RX zxlD$&%c!hIQ>=BBlD9ZXFRpD|2w>}sm6+BJ8hLL125&iz8?zqu1lr&n2DC2hZIP&Uj50Z0)awQh&3d-+G7$u@m*itQj#3+l=CcjEKk5p9aX z_fXwkA%vJr-6~aSm0vtKO?9s;r70`HUkMWO6{y?>OIw7dT+2kRy$^{+sdZ8_eV_QN z59_0zlWH-%N2*1ezW!d8Fd=M3^XBaYkt`SP^z;1fVeZ;#e@qKKP$RqK0-vj(Ix zy5Yv|llzA)qEDy3x)FWm=wC3GtJW2B_PEU*czwn0uGq#iIhJwf8ymVd;x1eow%l{^ z`m3%zmwJ&_@$DmOH{(0*Ia}?$I=%bm-s>*}lhFT1FgGB!4etK>D>-SF-=j$J73eEzOm;-Th{!24$2?h zQ#^JqZF^uCHfl*mrJkDOSHKY2-|3+6m6!Wz&zx9xn%RrFSP9e{YJ_vAxW7h|h(rAo zLq{c};stvZbPO6>K`&9g>j)@6R&N zn>;04m5(lhD&|=cxfm7u-Q3Ks`pYWg2hMqhyN)*D=E}5P>)a@@Qh|kVsSyAWXN8~k z(Sqkpt=uKX-tcIiP1M*F`)F6$m`7Z|Ct}OSmEERSZ*1KswXggcTz%r!jdG=&sZ*~V zqb+;FnY)^&PJhgbwqCUGJoIR)=G$Pjjo5q<`R&x14R{P?zY@&9|8iOaF2=s`5iCn1 zD|0=r(Oxyk*caenGARp=Ci%ve&tlFhIz7Pz&_Q+jgLm&9m`;0)+e*XW7i4CyC|5a9FE4$Zt{99SgVyqqhPe1>e1`3qw{Livlks(SD zv~9$|ud}Xwd?8?B(MsL_WMZMMQ*Z$jJL`VtA584QH1%Ih%<1xmsOPO;qY_KLm7$*B z34i_ksYxQHETOWu78&B5+inTUYF+2xV(zh1FDR4nzf3GV%2iPbSh4q+q@69IJO>>` zOhi(a=5lQe?BH(m!74>|{b-48#^dzAOswXLU?~}F@-uoun<})s?==-(xbqwx#&#Tb z9%MPqG?kfZOT`ADb#EYjyA=Nk$Z1C{R_ z-($J>gpKTJ4;A~i%HDk{-83NE_s%KvV-~2dv4XPN^RjWh$z{S;y&IGc_qwfplsD(r z9v%<_s>9#DY2?H`xJUVw75DahQ$zFH=9X)3-(F}FFtK+n@2Wr;;LfWKG=odNWVUj* zozTXsA`1wc^!RNKVx933%N@MLMl3KTg@1q5wJ7Hzbw4(8;u=54s!9}?CF6y~FLRj` zon=fpmOSd^RhH4?#iaP>UAUBJ)M*M6GoPRdoDjcOV1Vs%+W?pP<*B}y9vU0iP4BjPH_|@sU7usAx30e|H2bhV&)%Z< zeW7gozVD0fv1IdCr&3#e5jDAbmLBqHx@7*@#?~KOG-JFTylvASq782z+-K#(IlOmN z)RbHlW#9YaPn2?Fry+2o?6=Z)m5b<5mA8*{d2wo)=KGKMQesv|MBhPapTF>T+A7mF_5_h)OmKC{*07K8KuG@ zQuXLd0L8+YE5bYCA8QCJDx3Jz4rQlcSET#vwz_s^h_4?p zlQ6pCoBXI+bPyu)p!3!T2Rt!M~Jr>vH-~eB?n?bra8{^vK zc?J9M@h)6p@Q=j83(dq`GwjkGDtwd?0l%TK=EP(R7ieiB)%1!BaOP897Rz&u%&>7U zfGAOhcGB+!HyRU!RQ94YXP>^-*Hj+=;OxlGbD5wmx)qWV1!vd z(vq)YHxYF*Uw$eOyC*K-wV^JMBzfkVaTzA?z@_Z^Wa3)Oi(M%9V%HDF#3L;W1c@fD z{zDU`4ds?dqnE70>Jnlk0YlN&5q^9zWz#DRdlNKz``N^hbvM*0?{P|)qfk2_?2icXwGf9?*(+9>qNk+&XW9rXw!r%c*Cpxb&9FEq z9drXSs|!u~lZ2TNg2Or*;H%51Q9@M@e|J#-10}S$vRzY>hi0;9$L?9N??Cw*V20K z`_I3x?*C#HzwtFrRla>@)$kw@g>uO1rDcWKhc_8}^`V{@7zB6MP8x6Uo#BeN%(nBz zfg4^rz_klpixycxadZ{eU=6;()bIXL&0Iq>y~+>Y5xp(tqG5;=+751S!oq>}t;Arn}=m1sekQ4|DGrdH#IC;hc);&^BS(&H5Y5MK};QQRo!8QLsluIuI1jZaS-indADvw|92=20&_ zgC$|o8m`0ZI}neUEy287zmgryPwvhH0VvE41(<7tCp>ln-pUX&=%n}6h@elo8s%4$ z+^^Gx9H~gVRHN%hta6Vo_=6^70eX8k!%LC7}W)JRqCS}S8Cjr!ajSr=jZ~c9-6qu+Y+4N^y)!HH=w(=Q@! zCbtxaYDhr~MQ#74l7Q>WwQvR!onazjsP>Iyc*pD95*9&iFcn@bT$+`)xdVDc+8LWb zlWsr4g+qvK@x=tA4u`B#7Zo7J9+&DVh;IZBL=$lc7zD~9?}MSW_CF|qMeJ3aleJiJ z7KIgBhwW`$E$E0Syf7nUp98wb1iqRU%ow1l1%2N=%m4Z8Ia?!p=*chpxkEJK3k6+k0Q7R3AjH%<)iHD&KXi&7L_(9!wNI8utC^RC=Bo-eN2x7l& zIlw<4u&VXg6+^>-a~j|U(^5ur(S8Ep=4_rWdu;$}aSLMvS#b+6?0(?EhslTN z2cUG2q>=p%lBLLn@UI=oEH4o*h8#re>YNitqX~D7VJ3rRdt=218-&x<1l14F4gg>P z;VCF%egzVO3`>NLz@dbLVA7T&3kixa*M{URyqYs+xKzQ|1Q#Ml_83_e zS@tpkxGemt5BSzxAs=jX0X5i3LX&BJX4SKh6mV7OML5=?BTHH{TTBS=_Tb!oQeyb+^qqpKttMJZ94MIbR^-=r^hK#`&>;jGRFJL~ zh$jhTs5(twhXy4&gWu+4#aEhQ%cKdi_yv1N)JWqc@1}(>5WG-?&k}k*r+8;oy@#w^ zo&-#jr*A5OE5zs<*Po^skaXM56G%>GWMvhy5~2!cO0^lxZ|=bD9DiJO%dbH;F2^Vb z9T-qqc~!<|=(OxAa()RUCLcTJfa84DzMIsFN@zwJAT&;ZTcV)L`To*#9)ZR+wh*`D zR4)Vr)>{Yje%T5OgSt~BG+-AGhXJB_=oIQjBWHm6_T+-eMF5}+6Kl)c*#w5a04Xm$ z21j8);%%HQ9n(tlZ2~VnM*!LmxQ`u#Ch!D6ZWh|Gl1^-BK$EhmdAXS4Gn2*G>1^>S z$zY^`Fe1V3)*|?*9{WcnBZJ}PE({C{ytcGsW{0JtCW?ZGEalxk_=Cl$s zgfQ0Ux<-HN&znnhpopB+l9J&rP< zhrSz%)R7h%NzaUI|F$$h1^T0Y4F|RZ_dk^ylSwpSByB>{eHR$2owyB;Y|_qX^s*YS z9)b38jyWLXH)1?lpwQu63Q30qPIpm+cVEsdG6Xa-$F_?Jy24b3pxiGVIU3@IL(w6L z6Js02*!}`=m`m!b0gH4vnSITEq|)JWj=a`h`3GupxwW_d(r*eGEF2hb~^eFSvD9m<%NH z5BzN>^WxQMlR04ycPAmbw4Dgj`E`5fY=>T;6l{tJhP>7;0}m6GnHbTO}N@t@MSTuw^Qa$X4o z*~{F!eo#wdxO7;TWUYcB2vu8QHoM@j*C|}VBOK+KQ+=1Ns?WyT5)+PFm9F&g z)X4*vLshU+-VEX!;L62o^+J?0yysZ#% zjG(ehUIa|pT7hOx69-r4P^++CyXU_JT}I&MBye_X+wa0~u%cAHn~Khtk}@_6ibB zFjVM+j(vtbF+vzA!9H&V4;lIRa=HYIFJq1Y(7x$|dh(Gw7GaEM^{x%I7o?PyJ-*LX zULANLTzpK{Zt2vM#V0p$iwxleB#%_ z9lIK(4u`||2S}r5lEPq9RbcDntZJ=_A=L@ac%rrR0lx|*lSxX}Fy*IQQi7T36q0oK z{rF_Be=eviN>KkT?w0i-Ac4Fe{!u1OM9UI<_wM8E+Ftz1UacN9+@Ko`HgQRzUFF+U*gz%*x;sVhS)PW zt)$O02IHcAxfQ|E);3__cT3Y|{0@D=GD3kbq({B@d5ofb$6XK~*AbtfZR?d112JPQMLRcIn_N&VW%LO_e0<4@AN5JIt0}0iN8Kf>@JJ>;R47 zu#cbe8;h%}Uwq?3^1}0+@6X;ju+jd@fCn851s_KIPR>Ek57ptHy-sDol<$97UbBrV z#fsT(a&!H&VHX{4|NIN1CKeDbaR+)$C?mYQ7$ zA50@Kl!+U^RFDKCFCWOW9Y6k2RzoRfL}>t2QD+q2C4ICb*1twcLxx`cN0*n1S;v-`A8K7`U*l8kPVCANTl!#aui4>U!nlLs;zp!Ew5ooCRwJIQ&;|%i3u0X zbG)44bosnrb0|Qov^#9WrNphtcVfBurASAgB|y*W4{3uaU!Q%+y(s+v&UMRGo9XcL z_5AV>;dD(j}l2Gq}nWeLGiKE7TfX!52^90l31m{VNYD_>Ojo^}FBw}wGC}3jO z&RNySv4Sj6mJ)R6rzEj+5`HeV0ZiG`LM-{4l3RCWjwZbg0;~y->Yj&J)=q=_yvRXE zzAa9xY*9D~2hxAY$Lu)%z?>1dS7>l4pyd)FNpEfDq+U+Okn_BG|o z_>EGeL%029V$Gg2ld&n8@4s;NIF^tQ+U*b`_T)`c6PS9+K08|;!sT}EKKVnYUMlU1 z1hBK^)yA2SN4-BQd4sLV*O?@UB+B7}-cia2z3lU+t-Fcz4J zsTBbTg{PDLmem}V_jL+ZD~*yFX6I>@hb;_4>2`ODXm_r1@H49W8o%Z$j#~C#5R}z^ z_H~ecXGDKQBmZEON*4jL;rg?Cbd;d1wpHqS<_ZwF)A!%XY63sMXbNv5Q_;iK>=(8D zI9a;2suR+M(MByqgL1pAauJOmy#j&3l1=`nESk_Ya*(l@Ml6;b!o$g2W@hp`$g?&z}NZ0%b z5Cz`7cELs9=U0UxgTg8OT9-590T88!X5RF?cK-zL_GIMUa6n%K7x;|oAeOZ57V5gB-?ZU5i>+}1Q`OTOga2e=DN`q3z@yEFEVd=? zd%gWOQz`E5j%_K|Ivhk|UHDMxn&)U?!B&7Ib{~bL&?#VI3&(t@L{GZZ1J1K}G!oyy ziB=Gl)%!|g2WtDJ9JaCWlvxsZ)Hu{49s4rGb~-B6%bWmI!F z1Sl^N`1uzruoZQ;S)=wRoKA{(q3k;%9S3sEo#K4_4YP|y;Ci-HB{v^4&@{d^rx9W= z)p?e9jk2=mE_Qp6B1O`_o5eww@ z#`*6dI?2F~UC7=W5Bn5YGLuknd1&vxbl7qO3)ZMEyA)O2V4_a_M_Zq5p< z`N!}F2NdtFWww*2yQW3*`l>C#?^igaE9YEVyE{u2sV`B#lhB%isQ4L5I1U^SZ5X`* zi&Tvly>c5Ox{DtCr@A;qaHs6#qj5rRT`gmnnYY`6GV*y<&FD+F57vVXeNO4@l^!NL zf~UenQ)dPgkqIm(>u`L<%%HmSs?5~=kwagLmFE%na%`36C8j(55J>Jwq2v(LuW}ey zyM2F4X8%D8Rir7WO(cASrd`oFLyYsE7A=#DR1BIK-u`?$N+>_%cKRL7}8aB2@y;=&}$19@L7I(=b&cS*w@8r*B;(`B&OGDAPS@%BX*!E zx~1*M{7==Pysxq@3j2)5DY{x7E*L#6%FN%<881xIhE~^Z{`lpAaT-k1(E^|sI9m&1 zEChRF^^#i~!43cTJeM?8P*0(7KjB!TuP`<+jnK4ATN95&ly_dehy^Na%$6}0y& zW(aVikgRXKyF5M*rhEO3LtfXUHN09}R+6gI(tnM?+iv++1^ zfYE8E(QV@k03iU~aUHEgX4w$Yo&canqaR~A1fd-Ta<#`R5YINiV%El$Yi|e#kOWr8 zOO_`Yji3)wt~g4YI~4L@HaemPa5|F6!bc9i7iKzjqrKV&nF8fB90*il6*QwQ+T<1? zfTVGeo?z`uW6)R5M#tRo$w~C)bZG~PJlUE4V$Q&O7kjGTW*<4H<4cZAbNX=>U1Vtx zO+dR2ip6F*&tDimwgh0%4A6@UrrGDMTd2e70(-F-k?}~j#C!_CEYX!)&`BO#k+l8< z6%jgigs;r4T<1ooZ$S;RG95=5NuvcZ1G#0RdG(|DS4KAq21g4Yj21179{W6c96rXD z7%Ns8D={7`bsQ`68#@s>R-QCgku_FXHda+XR()mcJjP#bTbky|_oWvozlpv{aHse|hV+ zAbjTLjA};~OFRaGuwY1=Go-D@bC+wbWNkjS#J~twbV-a|C}frIfqY~#q|uO)Pva;2 zazZz;cDqkho~j?gK*G~KN|Meq*d(#h8@Ernq`pD#B$`z?xH3HQl0BM%0geTM5mF1B zIEgk_VmQm-72MsBWoo{T81<6dLQrViDV9bYdgIB$M2eOb6PTF8x|$H6x2=`u9Pehj zWiw)$UK_i7%5|bu1>#q zMde0_PI-E^s#q)}~fuMRF z5sgvIX@z}oy7^)I5IBHh8U48F47kvbQ|tg1&~*jvS~#%1f2+vFnltkdI(+iP3PeVv zH%bmIoz{;>0E!$$Io@`8mdSp+~Q7SBx%@|5> z{+UuBDBi_d)nN7k-KOY%!WA$4Umqfmkv3d+n1v_y9ph~&W_ddvx#7@_o{AheLC?%3 zZe?}SrN8)fSkc`GXx(&{+(nq8S5~GM-MA%FZ(KX2v#_7+Dh=TC*7`~)ugHFvB$IOp;=2%dGyP?({Og3lNS&T zmo+CTv&?vKf@()qoCM+~UZu7YxMv6A?$H99p30@GpX_(S#Y0T5p!eZ|X!~Ls2Y6C1 zkZgX`Vf$rw+Vli1;xW~Ld^J&oMkk|($kqsqn?d<8nNtD|@KZ-1FFD}h?`r3ZUb8it z+F8Mk`b?d~s$&`{J3Aa7zMs0f2A8G->;xyf)ya5|@pR#&z@?fa*wzZA8xn@5$}E_Z zc}jtKs^~?6Gss`pT&RQ~t9OzpW6Y4kXDLHemPp!RR=rtCD4@@|CRi!X#3q&Xms6Bg zKA;*-zPYYznm5u?e`Y*DGUlJ%k$N8f(E_>5{t!M_x@IoLZYW3+dJayLBleJh`8 zm>N^;$yJAUQxR?-B;mf%ZjgzD*GeQ4CTmWHmU-}Q<1%$$j`5r#NS*!Rw)*DCta;v^ z$=iAJC+|Zjd#M!OX`Rm%@4q&`|JLvReWv^Sr}xX7?^jq!Aj-=8)^jx|6dzJGw>`}dV- z=Z_ApPrgTgpJ=rn#OA!F4Ba$EkkcHT;|Y`>XI+75a@Hef>Z;|RTo0`2>*Olnybqa! z4(ytq!Z^R+isYZ|^`7kIQ%ZN@dbA8iT1JmH|v-^n%GHkoQ<|JDhxDwAHTBtO|$oDPVsxcL?x*+OlsHI$RGzA^) zNo!uXqi~wa^h~3lk(uuK^us6SHmuC>?Aj>BE^?mgc6RZ2wR7b|4u4OV%Ex9xXfCox z`qGqm32lE8&}+1epCGaHC`XDpIiAgO^?!Q&g?t)`!7rn^u6S~KkooHt=sLY+Hz~I^ z$oKkbq2b2QJOIvCfX!;r3Qjiff+SA%`(E`uKIhe_1G^)bpqUgO=Jrv)liTn}uk5pV zW!eBH=^|kt zAS#dgvgv1f{9kS5qHP!s)OxDKk0t*$zc_KUc(jSfl~iRAqG;!MV+n>Tn5PiqslaLF zZJ#fMrTD5BB*NEtbV7_cjl_Vd)Uha4&-iE)r>hue-xQNgr+7P`R2`rm$)OiQMtXQ$ z{qzC3?V*4-cQ6>Q6)z)-qcQ#f-0_sqF>egrFO}SNDdFRjJ@lI#GHx}nmPk2QOFrg0 zi0Z7OYtmq?RX;uj^0l1fO1&xh-J>^&)?b2-6Ahp*0f+g5YYE?yLrgR(3w6r-o_@}V zH^aOMC%uuCOUwQ7?(>iR_gg? zg;nyBl2Qz$Hq^8?_SG#nG_*HDFal~9E@~!k=;Uwc-npm|x1l$i3o#?b#kv=Kd`P(@dQ<7`GDDY~u z;p5Pw>LGaN_M_wcNLtsb8<_^B(@cMaXOpPZf}|(g`ku}a05hCQ()UA>p;l|@v$Fw1 zqs26c&5g~h)vwpkkX`YMf~JE~yaL|VXwwx$*>^oepM zUm(*N_QXGNpXQ%<762~fr{H{`UTvJu*|EVW4*&b9n2YD5o(t6{GIo(ox=Revx7Uui#sL1c5b15GX`J2DJv@0(w- zJb*xa0jp|2NwEhpmn`qZ#q@=pG!KEXSH&N(qtcdtPlioBuvN;;M~gEqH4hR_as|eR z2)FLn{#+;W zrr`r+!+(ZHP&Q#eM9ISLt)EG;ABLGL)*-7&&sDCB%rlWmCIAM z_l90wQJfJNez&-Xhjw`m?#;>lo!9<*QfBX?)72XWesirmpMK$=CjWh&y7J|IB^mgy z+5rlX1!`bFS+_9z00b>+RnO>-NAnzX9jY(w{r{>R@TM{TRXd=#yN?uE{~xsjp)>-{ z*%Xy2B%1}?TROrJR`H$!S{s}G6ChP^6nE!ALhxV4y2K4_4qn4<%{EcI88rd_B~@{f z!cwopD-p8`y+gdH8`H%K7L0tYEB^_Qict}Ez6?or;Ho0QxqJ|pVY8`)Al_ljkJWpR z{!6MtKM9!Gd)eT#@cOB%I!A>y$%66cr#j?_`Tb|F@*BTUvwT`G@bJO8e*n^`&Rn>~ zeglM5(IuG#$@xvxl0O^)cwmDf)~36(E>^L*?mhaC+JX6Jj1L57!^c`98uQWwbS0lw zd{7(Z@SkHzRjNEAtrQ#J)I}^WoVz;W#Ju~qv5Z}!NDJWwmA#!MRXG)rC%|hbm;mRo zsxlL`y0b@nC3-DI6{D%~Z>fs4Lk7lJ=z4s3gEJU;>>sI$YvhduW%vIsRr#;l!5!=U zv47PLURR1mF3I2KxQaYTDA_}YCrHGf--hxTHr1O7#>=pzD&7vJrni7vXbLvO{`Wh@ zw;ob<8gX5-U#hG0QV75ebOIHt5xcKyS6V$YHKZBxnjT->y!G{4Vlv0XL7))|cIiHO zrj@7(5dRFC1j#7;Xll+<1uGFdrop~09OXwOBv#vhv@Q&2rAXaH`LogTbqKGh{tny-t3X3A9>4x;N|TRG#l#S50vN4A;E=y`y|v0{Rjl`WcH|` zUg=L>p^*g=g8M)Syx|@d*K`vYj~VKdWg`ei;-86Ska}ul%mR;%mGR%zG;M{DkDq*7 zCOEfHs+NaMgHowNqtgQVin9;|_RJkPwO4fpdra4)M>43d*%O<<5xV`}STA(Yq(wgS za_t*Y$1LUYNhVr>mqz5U9#)sQo+;9km9rg|OhKy%)`gf8Br#;7<9d!)yYw}$zI>e} zDA3JJRQ7NNzn8A(opz9!aj(|4pI^^E`$A^M3o~N(IGDp!Lxz~IE9JS2ODY}ee-k(~ z7N|UYsQK-njP9ZkLvnhfcgxb3v&9vGYS$Ix&^i9&h>Nvs*0Sq0K zK_d^J;&58>Gkkq~v>(Th%M^kQTnVWs&-M8eJ?K?mx7w;ZzKedXauI~~Vm)Gim}GcN z4s@SDYN1!+dH`~avG!3U(aiz_?F~lW=5gIyGQKVk>VsrhQf)rwU>Hm=y4Gl2Po+q> z-Q5HD62cIcougIwnQW2&IN8w1pr_KUEY8~?T*?N6L`xhUB1arKY6D9cV{e$&b8upXOS`hhTR!t;6#t$75yPd zE7qvWasgF2vni9_5Px7d|K$e>qUK{&`a`#;To_p^s*#7_JT}42%8`-J-59SfQ4uAQ zWn5m$$+!@dJtO<_yTDx8LVS~nK%{?jdrv++29FVCpCEQDepycB-MqKCsYSAU`20UDnKPZ!dEf?KY;*b(znddspjE1QJ3x_V&K^wHTX+J zs+Yn%nz#fNk9yh79ln|%!BN_|bpEnL^?6ptBbaafO{;O_z-D9HvlV!Cw}qK9SU;n* ze*MX(H!pJ2#@G_FDtu~>yBUIaTYfXWz8#MNIH}#X2^^>YkRbylzvoAXf88vW8Gt-J zMLjZ=%B@UG;r0TUmI(k$WWDxKMego^#Ql0{+CISzYxa6n08q>&U{aodXfR9i_uS*% z58=rxr*GkH&L}$Zg`MJs&9(pl^mh`NOg13QUggYU7t@I2XqA;g0qW4sjCXLwrt(S%5Zt97b>;Fe2&z1u+Z{=QEk@o|05=OaKvySQJ!Ky%*HoW{sI z66~#XEqxE7cdHoN@$>Bk;}|41m3|vmB*o5Bj?o2EjwPJdk^#?2#fPDIxYlBM)*$S}NXymOXlJks zt?Py7Vx73>sX|+ZWd4%QiH_4yo;C{R8e$q4-w^Nu3?e(=^EV2_dxV|;6d|dd0j0z` zY@Qppk`K%U%|1q5YelhVIe~PDS#Jgcg8Vypi6ayWBZ9S7*okf8r>%_0p8!1MDl#h_ zDiPK#nT}op-J`rX=2CgEs@Y4#`CNMb8tNkwPKcbVjkEhI09*wb&_+%0 zK$j01lD@l71I?vPc^c3Ntm;@FOpXDuj=p|$o{pzL1-^jX#B69NYUsE>$G8qc7ppi7 zf?hc;J3J?DX9!79QTAqscdoNbw);o{TBT`@%Eh!0n9@(eaOe z_A4h}sL)MjJXN-1k&YiGOc+=F}UT$8#Wiw)rhOrn-Gf-xLg+mT(#%h-?88> zJ>u;b?*Tv-s=;2t&?{bEsY1o;Z33X3nQ4v-o*Yl8H+fmD0i(oogtAO62u?^Srkl=| zmA%o%h?>i-qcUJ?MUGn79%~SGDGUXcaE78x@?3<68Tc51sqCQ%J_Pm8@P?RWa-JTOQP+b$q7ex=dn2Hq@#%^np4U^-%g=+2= z-c`q1pK8T&3>T!dRK(aJUq;<&kEzuezne3IMLV0JofC(I@43(2K|(AuZl+Exn@m|- zcRb`xJM&$w@%SHX69P+^f*t5e((m_yRkb#Jeefd;cC(u+LqYcdpi}X&sXjnZ`7)LO zSf2e2(OanItq2sv0z6iE2V4|LcI|hh;2~x(l+QzJc|X@Bouk#@(gRSjx=?{Bm|E5P zg1!Cm-I}!kxJ4Sa0Lmb+*diwzxBYKm2ANh2e;9JP`pyfev>j9*fa$M7_l`eec*93y z>ayQBzCLbq-~{XvfCdi|Z{#L;5N#wkL!7B2(2~-U1X7D@~-A)*}qk zZtkk(s#bAM*99E3s7q0?(^SLGOu7R+W)1|N1Ef~-xW=u+DrqcN4{C>pRX%B!;A#!) z!!J}PNtWJnzI!Ds53yF`sSCcLQ;-slr()%9Bq`iL4jB3fzGg3qiG4zteKgia`!xzq zXP-T4!U1}4a+-?|>{nvr0|t}&07*tR5(^|5Bdyf0T*UW9H6)z0N1tLjFf?&VUC1B- z;cuUZj^(%vsaLPu$=N^xC_8hIG3-3Xy$22&VqsPdW_Mh9ItSF?rROEGU|s1W5;!-Y zh#3a#lMoWccG9~fOem0#24M8ym0E#E9lVAXU?vf?k9s*--ojQ|$fE%o(1fhkplM@g z<2QJo@ISW+KI%iSLD=6IdH}Td#$qVrkr0CG8rNMx} zl(iZcv*z`|{4kn7*~P{0XJ|j5hOn!jVmu1#S_;mDAxqo2?Gr~EN@0kXqxYT$m?l8+ zvp2rVV{^UVbi88_eMURwyDUI!O~sv^U9tiG1bI5fU?Fp z;jBkcB7k9n3d*3N8vvDf1*ZToGNii(WU~Vh%$J9bf=~vibO_9M24KKPU1`va>mw`# zfUSOnuf2knLd|C(R;7_Xn>H31{_WoLJPl@znmTI404R1EHm>iHaUUJ(DfJ~o{3T#J z%i8}=(&pmBxd3;57?(kU1p(wReI+0ZbGkCw?g|o_P${8L#Qpj+?v-WUlWL)ZpQ7!h z0X(wUen8(Id9Cz;B?5j?b%Or)3&Qi09|VAMeSO|P?BYeNv-oBv<>-w_Nj~Ep{%QT{%67@h z@5d{*|F|G>s${SA$kR;{>=b2m2($L%}; zxB*k`-T5!%;SHR`*NP16dKp5S48vQ4t5D!0$5$tir!nBC9)&ln1qP}7Qu!Di>#WL`n25$;PJ}4>qlVRX8UJIZ?o!^Oh{F{VT(h6ZsOi6e^NEIn=R$w=0LLmZ0T|if9mzb`ic#f)6 zB4?U_(EnTQKoQtRYT3t(ShWMD(1jQC2;Sz6qx&)%uB0WD#!VcSEDy)Q6~z$!8pn@nA02*HU}EKo zvrT zi<*ssVa|?+C_3%R5}6@g-M8Hz%8YXFwIcF~UOWe(WRY<29vdGxQ;Mp$coU#8mk{qn zcqz`QeWq~%q@Cg3L~P$bH;-XSRk$s5JQD?cSp?;x-Y5KdGU=CRn#zFA$0jHpMi`*skNG)bc&oE^M4Jd%=XCTlggv|IVhHE4NZt({!b+At0-hKUy4HkIC2eC; zGo*`@gRDk@0FG8Ai(?&_K{3Kz0E~^~6cEO7kUks9S@X68OS*~?18}VZ>s$`Av9W+&bTMh*B4r=q5s@V_bf5aLtD9hgi6Fc>CYgn%{Pe`T zu`E6;tE8Tl#6Fr+$5du0sw0aD0kQ$o=Lt0oVq2Q65+I2IAxMV^AlBxKDf}k@$N&uP z00x}xk^q8dYYuoLg}3G%BFU-^@&F80${xbQ!)At44+3m*q`~9P9_DN6qdchV#=r!b zpN*UXPI@`$}4)PM+#KHGdq;dSa2_!B&U7>a%6#yX!2zfwm9-k)jI$m^d=pO5ycECsQ4oeKmQMf!1#So5Rag@oUW-E`_RSsX7;vTE(qSxWpyEL6) zUFLnC@gkYmB$!@3<-=2M=^}PxG$3dXaGAkw?jBfN9R^dBn=be3KR50$A&tDNi~D-| zFuM();F)N~fG5g3ZDVq1EtW9#;Llbz%*V9r6=k;+x*?p~`YqFTv7Mt!7T)a>O(EoJ z+r+@biumVMEUAiAXz$7YAyvtnto4%-wjXbwnyt>gcj08w={dbuJ;S+mQHUb9wf0w! zzU1DIYrc5~qCee=$*WI3d(#u!G5tV3uOXA~=DxRt{_8sHyvF?g!n3L!ud4&{9^8s3 z^fT6;T1>UP!##z~4D*v=z{u zoz(F*dCw9r5~_T$qJt=nmKFe_yFr%_m|)SY-AlxUuDVbRKr_WFZ6AxCJYDYvFdoU` zCu2T|D4*i!69&-6v5Ora+@4Ab_0Hdy)8)zeHJxsz7>$#IDO%nloRrh`pQ6efDS+%J zkYJt@37X&Y*%lWF{?j2e#7obTpC)~B@7YuAJLd(fw`FBPD7U z!Zl|LW`mRnF36k9!VLx*+E7M0>G^a3VQ8a*Dr!{FYoy-n6#1A zCKp3jEv)n+M}F(;7y{iKAVEn*azNfGT*)7Xf|CJET8WWRreFroNRX7*jRtMD@$t@9 za3#JhnzET>CU5yCVMGr+OZG}|2%*g+unTu2rXSY}FGpKKpT!5Q;xF;e$*rTw{c=7} zBOewbUd%!~#LeI;-Lq1D1-Y#%eXGzf27tl%HbuGza$NcmdYBM#S5EpV-RZQLV%G+R z09g(3-#c8-Odg5bzba1&@#aHZXDOb=rAtvMl9eU&!S46LoM839jh&cW!FNzI-7aV) z^;p@IF$6`rWYTDLCBdHoIpJn?toT-oN-n8eCZyil1Zd}K;(jJbFy5%T-cE^TbZeJq zjRnZ=3$@4FJ=r`ba)lMpG-=QCkn=sr{)}}x*H(>V0()5W_e-}D3PgdCTf4d>xT44u zr1}PUkdr{U@taNOIQkt#7n{&6nA0s(-YwkJEz;L5I?*k*&@KM6`vANL&)Xv*-6N^d zBW2bjeWFLkr$;utM=qg^)>wYXmpz!Sxx#YfUuF9-H); z_1!i1F>Ch%EMv_&w@YkxOW0_AM<)7?F7zGy*=H+Cv*qo#m+p7a=s#}Of8s>{NrV2x zB{P6U!tSyIW&J5J20hzif`8cEa{AqW_MeF@@PQ0?N)Pm|QoW?*!k9>2Va(|p+4dmX z)6C+aH9!H$XPs$*uC#A9Xg?A;UZ?jf4)1*m?G7iqP9tvW@VkX0Z;+uknMlAn$!!SX z?4KAvoBz?85zj;hxzNn*k`sxF!O?>OW9%2`@o_seV~}=%^-E&X>&=Tf1Y%MQ(ECXn zmWNi6s&+JQWAve2G`-ep7mA6fA7U3lhX^Jd(o4Dg9lXh~N}?H2SmmW0c4hU!EIhSP z5tE~lqP9!Z?h~M|TILc)63B_(03eHIi(Vh16d-TL3YWlB|4Ojm${DGh7`eAFQulL2 za4z259~IzrPPS`LFhlwXgOJgkGcdGJs2MHx$7A@WKPMlNQraoD zOm2+2{je<%mS2>L*MXU%q3r&8Psb|wK$>j`bjJ1I1zZZx>a~%Hr*C>rL2_XTx^w=l z=*BTBy)`0P!LY`-2evO?{YYwjsFyP}z{QcQao3b0CE z5oN|&i&sHWkm6?eC*G8pZk?~UpLbH%IyKqEnzuyJS>?^%O-zUQXS_%4PaGfT6GPvs zGD~ZFkRSGJ)at2GHCeP`T-Z(YSpZ2q_jVKfg@nut$qEq~JViv)p~rJTX0l>9{6#Yc z{a?HX6gU9X!FK+iyoX(BOA;t$Q)Jap)}JP*9{6^s;r3uA-ZWLzy0LsXn{d45U%W@g z%dSWNgZCiCvz>e$_&0FP`&es(cc%eRe&y}tsGw?~^zrv&ZU01c^i$gm!;j1tl43*0Lb`nNEQM-{@n*Gkx0 zne9#6zyAo`Rix!zlg^6h7@k;Ic5`?setK3Ic=7Suhv!c!3udn&lFhKmZi&N!Z_a); zmmU1M$cpHsqFjB{JtD>=D>xTi6GS7IB!aKzHcpBL`fShrE23kQ2@owpHYYA-rfWR& z_r9j{zREkpV0pi$(F7CqKb--SoX{U0izTtoe7tU*miM+|Bl8C?S=s7I zN*Y^m{Cr+|?2$2n716O77ldduRa6+2>e@*ZB^|6WVWAAkB)SfCIRExP!my*p`|~5& z7HCg6>rr3euGMb_y4X9BmzU}gy4O?0?AcDp0hw&ySi-QY3$}Hz(s`SvY2Ul|Ea!mw z)CQP!8;kd7ISZ%MJZ)za0yJEfJ62OGp#J+B`pkoONsTs1^8?>jo;Y>e;r%vo|Ygeefm_2cKu?-A6%4(JtNbJF?#BD&*L z)Q{%SP+<UmVxCGzj@0Po7U{?qCP8JIl=|2Db23q>h z`m|qMw(>C&G)XK<@KB4w!nq57cT^y-l#Yz!>3{#MKJbD6gl3IbZLclbDw6?Gt$N4v zMA8Tnr}aVpXdF6$KZGm={tf*^hK;|04B`!c$*_2ja;u%`2qSji)%g2ic&BYyu;QMH zK;069^qHg$wuhYHgN};T$$;yLR9w2G)e5PSUFiq}cpOs-?q9@lxB;_C0I`e&HmQf6 z#S4h*CzD(>`VQjkQ`C4~Jp&j}wpb26qoy*!;1@*UJZn51c1nAS1O+@`z+1uF0Sr*l zgQGlFqw|IunkD@x^Tn)U_%MjFK0A^5`6jN*GD?`Znx6<10RUwIZ@Evr)NRb`qhUe%Y+z{;?y`DxgpqXK7x zoR!~v8W9I(VQR1WjA&<{#k~KX)Xwa0XA<_+DR?gaEe^snm(n!5w`$2gg3`uKQp}`A zjzamd@}IbMh?U;YGT?X__Eeijdd!Kl-3F2}RL@qQW90L&Bk0*fBQNajp@Lm##J%tN zM*!x73Y}|?%51{vuJDi68oAf8^IZ=Ua6W0L$EqDpSBy)Q5qZ&)Fe=g{sWNz-E0iFL zS@a-R#5CI#@Y0NvhwG}j%Dv|=i`!?`KTy81d5_E{51iL^yzcAZE41B(im@iu^laWw zc9>Bgz>V-L01A2>j+px0o__<640 zR?}WXZyCBV)sCbkc%%NzOPhGT_o0DScW z=`&aRnjT%N3;5hM;$bHx_(5m>d4_-T+_4k*P}=bTEjzj?7?q6-7$gnJzuQXn^W*%J z6oHsW54oqgg{qx9!|8>3xRsrt#EU+JR7(yS>wSbS;p!OC_)xvZ0i0(9$Z|%#QC(QW z$Eqs>;y?;)^tR~ilB3Or^Go>60(F8%P-Met&}OKK%3pq_fy?0tuZ{!9fe_`%_Jbh$ z=XM|IeEJaU%@^&WE!bUk;asxFiE4{g{Hrj9jto#Pk;@0Tf$P~shEZqA00dqKt|6he zfWLW4WrBVoGPnTaUuV1D!*;{eroya!1KI_g?v#Zes{f=P!pm{!&;y28_Gd3+{;C|A z?j7*pl#zJn0ab9I`QNE$w+4-Gg0ZT0VE*loRUVx&!ag{^M@-`z{CJN zLW|yA`$X%rZCt*6ct`vld3Lg8>-A~&FD)bs53&+N1aNrU()ljzUdj5{V`!GRnzkeO zC?E{~!4TSh`Q0}j8bfl}w+?YZZzU=7Z01G2bCo|7)gR@4KD=k{oid07Ks)I?SS&kB>#d>y`J%Wy*fHN z76LsXh+dj%i6`cLi+*ME2!T6tEmWx#QQK=0`wpx<(AOpz82{k5P<-dhfjgQ-=W^Um z%o_lb-0a|-dE^#_gQL&K#ScAnj}}io66la|i<51U?P=1ZqfZc+3PKKW_7u#!2S0swj(5&{JQi2l#>o>qy0+dRCM;CxiHHyLkQ z04~a5qnJrB`zz-N)R$AZ){|J4u}dT$9MFtZUA#!#K86g1Kq3EQjI3CL7 zpa`>PEo8K(CK7-~pi^SE`QZT6B|k)+5YIUm>cLE8(4zXF&?@y5*YN}|0yw$oefjf6 zomZ)J0vt|E)-R3p0FY6PWcOC{(4K=G(`1BdigGJZqyrv8A>)S9WCxu9e44HVJj9Q7 zdkfHO0hd3LFBM$oR1FM2o;KB*LGXmb8Q0SLQ`sO$|7mX@9dNxhA%l#rg+kvYp$CRC zpcvfVdeU(L97u$PEYgsr5w~>c=1!T$_DNz5>5Q`pDC3OX3S#Q=go4aZDljs3fWX?7zhMucd(Y0 z)m8yc4i&am7fN(PL{|Z$dgS?f3Xf+&>rM^^1&vztK3h*sv&1%GJg?THmUFUH{lMU1 z2*SCDQ5_LQMmy+Y9bdwl_xp9>_Ln~ju;ml3{kWbvGkn^piq8UoDqRAzDG?DV;Q7}j zwmavWOiRv3(>XC%xm8GZ^{ttE-4OLV7yBy9;iVCbSFDsD(8|6kvvA(uHXJxGXgd7}^yEa&p-i?S-E!6Oc&X^57 zzX^EL)yND%ftXSR8$p;ZJ$p#g4wUn_GhK7!3R(d94SzURj2juw@P!!?x= zRUeOuND6wUfl%^8?*#5!J81yfAgx>ZwGj3zsr72kZDa#HxIT;lsilh?ZPdZsz!!1z zG`Wys{Zyo06>`WO;MaROw$^WgZ_#$; zo7z$1FqhQ_og%WQM!>jlf-^SYw?KZS5Ev1l3@gZv9v0E&d-Uq^q1XDNZ};CkDr}dT zQ+VvsF8}G=Y@$>YPt;aEJwIjS3ESURFb1Z zyuJrs3RP!DiyG95aP*2AsA%opPw0^q-DP0bij=-Xu)9v90Ud%8$bireGtoYt-~N40 zk8F1P>_qz=((O+(T4fFT@1|gM{Gj*J`l-6??zKin3D@{t1cR8CF0Z@8;Iu{3oLGMlJEG=n&OlD4|oUh|a;vs3z`@WozKk7l;T$dUcus zea082JPUP&4`p`_7rh-W*&Swxj+7aU1RYGQ3>pzWGE&nyQu}tKZg-?!bhOc6w8?d} zK@{TDfJij}8(ZqV$Q@5Qf_tNQWsVSz107DCFuhf%3_~t@9j*xjY&~H0yv-#qLwbXF zqtgdh_0c1gr>tU_F_49T)|6QUlmri-}ivWkk<{vl%qf_bP}`dd#XiY zvcwm}U>OPgOY?Ujmcw>Xwk{%ST%o(|OwfhpNRLpom(Uc8c|VB$iacE1Jh76hQ`+ zH$;>ZSjPW+hm|FP1x28l-3w$W?DZD(P&$u3iNHqy4eY}+ZektSc5?%bub@BXHdS7O8AiXSQHWR{10409Q<0RSK4LGMFI$*ZqDPEctQwD=GY$yHr2 z1Ym8KQFI87{zJk8+Vd<9n)US7V^AyO`yu0ZlAah!J#O?pud^L!LkfgK`h@X6G>uUJ zfP&ehTp8$3loedo%I{?%HY0HN4sg_%9c7O}jRQjaxJojPKWu0f7>`bx~Vv*y_C98V2r(IW&j4j>l-<+AzkVNu4+=Za|WWf@3j4 zXds0IzUIO{@Z)RN2hF$vtqYins1;4sRcXqGjSsg@oUK5d4JC|JIhu_)h|)uQ=nI>?}kY|6Rx)+Inb=bi_UU7OwyqqF^w_$%JsO zP9Brch)wPf$j>_5?a z`(dwoV{dj}ci!l4_VK@;pXe;z`kV6L?{^iQ<^8|WJp1cs_P65pw{PwLezL#&;UC^( z_8(!`zj==&PO<+c3@fnz_>u7ER>v%{@0yrVlIYHNui=039+wDbpB5X&A;o5-{Ko%@=x`Q>2Tt8{d-AtK zcq?dz717Dhy>j~3`S*|VlUBuCw?pQ2^vA;OU3bDh*JWxai@W^}Pkdf|X0XJqHR1;= zqGS71Y&UxSlf9ah) zb#VUtM1$pl3m?}kC6bRQSxIJ^HL6Qx`!o&@=7s;mdz3fYDBSN;JFN6@q4BWF6S(>j z)j{b8N7SF2sUOvR<@4aE_J@D*9_0^?>971NqO^OyI96jyd)G*Zk?^T`UpX$P^0~aWseb4Os?+IBYkk;1{*6{T{ zKdRlcFFX|9)o6yWVwM-)JvN%)OZA7$p0h1P;=jjl^|r4h@`ik52y671Fszrdw(WLR-gJ-&}L^Ak$|h- zVW^v-45RYdP+f3heJixy`H`dcnExeefxuGqyE{gN1f1FnegI>$M1p=m zu;nM*P{UusQ+~+^0RG%?XCsPQ7fAw9y>D=N&4j^U&h`E1hpIi7BezZi zFaG9MbLGhKv@>vT!G2nWVC`IjouId{lp0L4B@6!|%vR#iVG4?3arc{v$C$eotKiR?uQG8U1zT$$!ZQ4u(ag=i@7)dhWh{i z|L-%8*)Yt*zGN9ob{YFv(pW-KMha1kow6rOwi)|wl**c+gs5n-WNDC4szF7mXNXd% z=V(Ez?>t}c*Z1>&f8X!(J)h4n-*diyf^!_l<9@kau9s7_s6h3drn~ppvCA&l25KJY z-tBhg+UcvAf!cw2uygvglV`)IxY%yTIVaB9+o&K?)-wiN&PMe!txo*xXSUelscL@VA=6NtP^9*PVwjVY21*G!uJkS$ z4P&ey#xoDg2FRd^qvD_~lOc=c!y)Fj#R#9wxEm}Z*KF<3ivYejNTQpHw%Q=UA@7b7 zr##fHRZE33$x$-GmxGgj!KJ5>yb~GIMf z?PJDAO6cGG)V%JKf)&(wY|$GwuZEWT|h_IFyM5w6^W z!Y2P}mI&deYZcD3(Jn}EQOjDlH=elnCO0{7ohI~JV@S?hlwl=%cCKh6OZTRzsT1BN zQswxt=GQ@YpBJYyN>vV-q<$<6JmAlqlNvD-;-o`oD*CK1j0&u(4?4+J1Q6Gcj5$Tb z@ZFRN)O3G#&;4%9nFl6;IwhLK|6+(EfHJrWasMYV{NEVjJYv|Z9@KFEEXn`B8R9vP zsgu1*H~uRz6fdRxCo$Z84fmhK@OsG9k?kE$|00I>YW~v@@4WhNV%XI-{~w7Va@+n4 z3z`3(7-HEJ$p1%T$hGB@0GchLVs&$y%*NgO?`OM?eemW-=TDCwJZrU2IqKo3*Q2Mj z(lib{ao=$)SN9)cc)a)9m46KJpEEX)x!|VZLSOIqFUv>&Y{8AOm|wZC@7Ml4Av8en z0nA1pHw-T^G#KbWkG@Hy5>Tp5M7K2^kEbX=GvL|QWS$|uTd-@lD&MyZ#r=KwVw}@fZ*&d0bD_M&CnIWph zDk>xG9J?(V5`l~^t7&^WD6T}x;iK~0E(rDP!a5Q>GRC$+9tPO-Zq zGR$P!DMd2lAFkHKEslJ;jgm}$zT*|Y7*@JQhDQt=^UiXRc2fMS!&0tsC0e-EWe0-7 zSJH@ugj?zAm_*z`SQ^OcaVaG%?JwimjDd5?S18wXLH7ICk4_u%h@n?Sru7&_`#PTT zP?lhuVQgcsbJMGZTyHoOY%IuzTzQ80!GM`yl=NbF)3@o6#-anHy2tI;o=1(OJb8vR z(xxWO-@Cm2m;LajRpVqb_KHVjrs$s;+GRemEwzsn7vrs%%Ss!IcO|w_7knoKfpqkE zv%)iNXY23F7pgK#DDf71ncIq`N;Q{}a;`sCF8g_(dFxqH^Il5b))C3GTH@VE?W&KJ zxT9)UU9_%bF4#?i#m29EZR(M~zY&ZG1=|FReUE)bj?ocoi)Wo-5^&hYxrszX{Q0>g z>H}{L$RKR~-Y>qF45$`CJ>|EE-s*?u^J%S0q5h}Nz2}ZlE)eG#u!Ss8ky4dzj-=Ox zplg;d+%hfnO@`hbfb4UP$Hq$NX#8+knS^?}c77)5SLF|sNPdG+q)VTc3qF3s=)0hb zq}_d*)uu$3sl1F{xN6wBEyi!Rugk6Gd7nD;MSWoVXXd=X?(-605HY;%oOUFV4}-7~ z#y^q^2vGW3FC*tRbV$1>yn9YcfG`Pdi)(f|I{vyhnGDlVL&D9P^;VV*Bi0XFLV5i~ z0fLgAjoCiW(;^PQXoRURhQgaBUr;SLT|myZw#On~U@0^G3rsa;mD3VyAu8wVR@*|q z76of<3=&xEJt4}e*NlI5(Y$)M;w|F&6iVl4deitBC^S>9={Pd)^g9L0>juNfJNh!c z*7*Fp} z1(Z;#+L5mpNJz}f*mnNneJ2AK6&HW7gL9N+#iXum$=$LT?F23eH&BX7-lVJB?UpF@ zv>Oeu^2X7bt9nh;B_TtFeKr6UEp+Ycmiu?P40JD6F-{q0+DF@;ucCb^92CzQVj=GwP5UA?I)s=XEbnN>M0|-ujA4 z)gAD3GZ*N2YLaW;8^mzgp)8l{Kv>XUFP(>=TdhY*zmVa@kxZ~*ckR+s3-?VpF3cVE zHsq|#v!3GpXU-hD92NNmt!Ocqm3P4Hx+nHldtRI(jV2;Bc#%|Qd#r0_>v+)3fsuBWHXj%+_enV*)^ zf90;c4Yccu)Il(@oyU)QcyZiP$DTA?L_C38eZIl;U%y;>swX=AwMeh)Lan$Nwy{6UMCzF^v_W98r z3jV4mo8(|uI*2*+Ot~9ksPz2@#%Sl9)E@^bd~en*Z-_!!=ZxzA)Rx**QvEne9CQlq zdNCmMRo21W#)ZGv?9LTIQ=L$QeNS#b{mu#U4V2xFr>8yTjxp)Y+Jb(QWL4zu z8shHEZ|}$T3G7|%3As+}^P(>!)tLp70U{Ap>rP#z0Ob|0t>-qcblnrwe{y=|L;uPz zed{Y6z@*cU9^SL--fQFZ(>WKPqFuTOee{WEfC9D%$1v3Nqw`l}Bh0vo-dFCIHu9@H zrGNNFF~oxqf7F{NTcLhskt}^}$~ys#se?;jFm8@1hm=%valZh_jSpBDK9@T#5R>Dt zbzuqQGX&m$#vT$xVZp}w?1c64q8IUkf~JX96mC~g+C88wWp4LZ>+5XdV9K<0=Bumm z=^{<+9R*h%|8kB&UBn!Hr(tLN=38Z{snJVC7%&j|y++_h%-3eZAM1KlY(CdgaraIf zs(1%8Rd)=w?4xFg@RU^B3lwiG8mRZ2Op* zi$homb*Bkiy^u#;Ug@=t$&LGZe$(-D+X>ByG{>E3^1i&7%l04kFdG|}YES>8cHHM= zvPQHHk(#2bNXIhhYpdX-B!ftXr6olbD2(F}LQV3hM4ev%AXnPM_k&>+>{ivGt1Ow` zjEzuV4dQQ#wWnqT(9&h*E#1$+nRko?xD0Yv=2iys^V=k}2kg&I-esR9t(W3do~2|J z>6Q?RTuqm#%f!_oVFpg1DJvvFxM$kZuL;J`=;HIq3T+5j@mSncyi9ra39>K&1O($i zqU2E;U9-z`u(5TGMB9`EK&;3?pe zPkQ8wDrVxW@}&@nF9%G{8Vc8i`PMnQ(Eu$4z1pNmc6 zv<4*`XZ;4Z0~aS4oxu=?Cdox?DG6;+07qj*r_K3c?L@M}QY_Yx22jjoj~k)6Ani$4 zF@(tGLy$3Z$(P8v$msCHTp$QxIPq9(I|o4c=MnSXXdUm>=c>3|AQyV$kcZCWJX=h_T-$(}<@56=SxXUG?U8-7u`*U2r>e@1j+Wy-W3yiJpMsNvV-4G{f0xlUhS* z$ai4WEG}0yeW`?*xe~sBK9pB=3`OKtF7oX(U}DmmRBm1s_@YAA5u~#fXkq@F z?_m9#25K||{lwa%7xZiBrGS>b1;^Uq%VQrvzkw$mMBd94cIL})L)Ys-b=jHtnP4Bg1>BNDg2Y&VV34*ixg;D*0{Sa;cLXeO*Mn!JyxIi1PM)O0v<#4?eFa4du0YzD(nJ?g`kBEp=>gFF#y zdfk@NWX3b$I<7v^vk59?<(QfAZYhk~u+V&M(^!e1i`vaa+|93`Qc6PE4Ew&@o#T%4 z*$KaBEIGg1x{2QiCZ&pU(vP1n{n(V4Gj~Gz7MwDpCux=cH9ojpI=V)LeNtK&mP2jto-m(d1m85o{T0vp11NJ3Fe-0~lO%ySZXfl%gWCScCQmQ=Z5}@@%Jd52u98-Cw9Y8Q>HiEaKC1xqN zZq=i_i9O{Lm~2c><$g>cN94?^Hvd3p*L_M5i}$R9@}}JysOklz7T%?X#T;+Y0vu}Y ztu}A*)`NstjaUY<&P&CdMXuWPy8gI8!zc$%cT~w000u;hW}}4HM>QT`z&bxQLtiLj zz25{`BdB-ItP5m5Hjj(y_v2~0TxdgUD~gS9pTit`184F9hi@k`>UpLNM2ceX8$`%P zA;SSkVk_d?Q4-Y1vR$xv!*!`&1$PXJR|SA(z#voL1PwMIK@v`3oaSAH*`bfO8qyB{D)vbR z?AoiV5QVg(-|;$B)OHP9uZ#zjUZijDVYhz38an!`rPo}TSv9hP!=ik9P2OoZM%}Hg zM;=)jA#LXMq7eH0b;J3+rTSSTr=M@zBR;m+>}U=2=jvWW%}9&PQ))hcowf53yOM&{5$53DwacweZc z!*lOx$Srg&F@c@S9KnGV;ohDRQQs|o9Fd+XQ9t+)h~l6HcRqdb$U+!1-V#&wo+Ea6 zLLy~Cs%Ao_Z^C8jnCHmE?NI!7*g%;+PTXVqTOZbCBTucGBL|R%6j?*c1GP=TQ=dLe z8r4jhg=-u3O$nYu`8DvHFJ+S!-0E4xdRhFt#j*e&IWN6iz@ zz9)xXKJh+0@opAgvM37p{lxjsGn&pj>=1HUERu^Pw{`Kf*r9#!ey>h%Qj74O z;1nG(b0&nTM;o&t<2Hz04eg+@kqj+cN(Y&Qa>4f0$_3T^7Tqq#I|q|Ci5l3|i%SMa zx?hSqg~Lyo2@AhwD)+yzSCj+vsqv2v54XSk%`v3=7j|ZhqkuIh{pV@4pa{DU-umY`sxINmZ&6`Q;)Blv_+ePBypabw?VqxJ`)=8PJ7sWi3N>o^V{m4=2pF~4~Mn_XrfwV(&LdT zEy0Wnk?4!_%8(uj(tsDOy_Id{rHWrJp}s8Ls(Xs@edFi7HQ?Nv+>SS4-oZR*=qvFy zL->uX;$tD-w=sJaN^69-&M6pRUW2Ia$FdK{EtZ2fBOWG3F9YW5duLu7V8F8#1@nkk zjBSuw|67552n9xh9Hm`@`#@t(VIB{}=zM`JgaIkxlOvq|NA%EN%O+GL_oeXWMM#I0 z0NN%?xEP*!zLf^;-i!Qv`JK?k@po?3WpC^3cse|%DEHb z49hO=EnXM?UX;!1u5IC7B&-)0$E;#PXwZlK116=<_Oy44)PMat@Kx3qB69{G z7bb)$yfJ2vlc=xAyw@hqd&{~HmRP<4Tl!ip21+P_ON9WL`s`k~cj_E=sOH2(6l_kNMNP{{I-v{9vHTJGL~k+QJtC7E zebhAg?Cg)&H$9KiIgSZ}tDN;`r&IcCeSDd!x&ZpS9$&)2%@A+$@qVllx9yE&b#GV? z!rKsjJxbeWz~;W$?CaL9`7NsY6Ro&1=kw=H+8-V+e1H4T%Bw#-T*y_}{JdlH>;F%Q zVW*9aVB+sTXju;~jU{J{8)y0sWecSsWHH_DEX;_6mS|b^SMI`n14-q*vL~XklS$@G zbr&QhN2J0iKvmX@M+{XrO#-AstXY{b5Gqtb5Rr5YAW@g`9am9=5<~($YzhHhifGER zi45{jfjiR zDthg9TO#kQD(%wmr7Bs5(eowJHOJnavNc0BXNn&SxVB3z{ykCv4a%(=1QApsoUT&G zlPXx(lsWpDzULmEeI?B5g&GDT!8Sg3Wj{uW}AjqD+m$3&yiFDx+!_##bePUaK zgX65mJCes*L z)qfe{U3Q{(9eIYh!Z{72T(yf`3(Siuif#oaZ@T>Re|#kel$xyB_V2d0GhND4Yp431 z_Q~#^Gx5LJ9h7o)%P6`k{!MpqZ5qZbq%KGGR>=91e;ML&B0d*uvu{xv&+`&P?`JM{ zm>s?R_uz@6S8qqO9Bms>P10_^Z)YAJ_#~(&yzOC}c|`Zyi#-uNf8RBa>|1}+6M1_R zV-YogRqKr!BG_9*4@*W~&DbuTV-Yi=+*rLjrZw`5d*9&gA?^cnY~SCHY}Dlbo^Z5J ziD0@0AO1-59jrV4Y3ar>wuq+41K@&)M6l3C^86 zHh*57zMU4oy6yu;&=iCO(+g!tL$+j5(8ipD_*fchE7^+Qjgu~UhlcrIi6NBl|98ZY zY^Q%_HRG#+KfLF)y8S9asc2r*`H~^?jspeRi72J)rbv^rLLtE}W%(~5Ob&0TFRm4| zPDq<0mLN4oR@DpI`Em_+t-L30(Y5c|X=?uo=Hsq$#TQzF-r_wTca5L6mt=))25kM$ z#E?AzlMgvv&Li$eQ)H=`Es zG_bcWaGbo7 z{1^k<+_?`qcRZE6_BzD!DM5Ksx0D_lUalhKGd>80-r7mtN98f_VN59TzB$&EiMT#pRJ!?5NJ*|heY9r1&{RxP z1@q-$Cw_TPB!gg~ax|ponoerJG&NCClR9wMUjOi91M*di`cw0Nn0 z)Jv%WZR){Ku09G=IwCW(#=#;l&#@kE2mu{gd8O@h;gE=qRiQv8?1>vXc~nkV1Bd$D zS;H_!k%Br+xL<`<2cOkNn6KA*`liDW+Q-^0&s#E{tt{G*!^L}kWJM{B^0%~Sm=l_Ay>d1U9-~T_A*1+cfL#6e){V?nQ zR$A`~9&CtssTF^9`DIezm45?jkKl_#xdh0=FmF}qZq~mh%=K+l&O9=k9q%>>2DQRw z5GlOUIJnXEy!Yi>MjxiH_z!vOM8&@O2T-q(A-d;_oxR(jw$`rI*TZ>QJIskzOs+=?f&22UJW@O5E3HKVuOxTh(hLe>jg?Nh;=vgbQAd+qEm0i{F6m>YAq#ox zm@}{3w~O7$a9@{271(`l2zgyZu74sQbSS!M5R1GiC6Y6^wOl!{kFRX8)XA>njtZbe zi;FtJVuyqeAlc^~%EK#8m+tx3gn9l~KX=-he*ksIuBY3g?rOZ<7V-3-33L4ekIp5p zX;8NVo;J(M6gm=8mn(lMq`q+5`;hZYOU=*=WqXf=HWa>Tes{6jc5&hYk$ulEwe~LD6UX;sv|8P6Nwj=ubNdY-5!)9; zPQ|F5)@ABlx7qhM_7!pYO=fWy3KdmpJV0%7@Tg9=Q?x(TFszFX-QwO&I@x{qUQd}3 zTEiy2@7LOW;l6J_%=ar}YKYtcoDGWG&Zl;I=%k>%?CRjv-C;aH{nIvjSo&v~^$2mc zXLUzwcJI^{-SXBLs-4(;;BjT2o|ru=fd2P5`R`cYc)e5AUmj7;-_(Az9UK02!eCw7 zVA9E?rfu?yna;PzN?J87kM;*&{?BQ%}om5tH*S}M(+EN_}->c20zNKwIHPIbF_p0 zcFnXZo2L<4c_q!D+k7Wrb&kj(%)DyPs}yc#;}37QWfSWY(t@cEZ0hhPgM$+1j%Je& zRSRmI8IngvSP+G@2b5CwbsyLP#or3 zx68z+?OE|}{~QZxAnB+`%1$+*UAt=3^=VbNq)l*cV|#_JW}f|8U$u>e2jlhmNSCu} z?#(Bul>*L^fKEo$7uY*dBwo@Qwl%-qt$eGw43K6Bv2742WC*4|tDs#QEj4vQ6sXS* zD#U4=_1-qVN3Gn3u$P#Tj+@lQh~^4*L9ON|*eF#hgWrksK%z+$D6&+&S`+sa#4;`A zrGf(z=$m^-#~P}XDh9-Z=8&Lkj`g`!b-Ryr>4D=y9**kPrc2$Clrmfgcv02|q7;Aa}=_Vo3^p--VL~QWz(GW8?a-9xWN-!0tdv3j1DBJ}=6& zn;-b$QMkAZ%~KJ#+ERa=-;ZLP-mx+7T61Y7oj0p34x)-&L7miH93N(zuv^Bmf%YTW zQK{4S(%ZDyPsazYm^|>6&uZWVEMH_h#rQvOL;!)ue@!IK+F9Hk1 zFFo0Ob2a6;dW*a1araM8#GBUI38`$Gs$-M^B#)S(E!a56 z4S*#BgtEmPLQM+tY38S=CTqIAFXE=qH@wqs+#5_qKXFadeA1YI=F$=_TMI{`qoowf z6+Gy0Aq@0qe1!lB2+Ft7(I^W3BiGKHdxDV6>huvkP5O}U;Zu99tY53oKICu37Uz$z zd7IW4%h>2S022X$NEdeNJuD^#(9zs$h(Z!ZhCl}dFkrGVL2&i3-c%5@oRQ5cG+S7G z-zWKSB=nTi^Rzig!8rnbc)fl4M75iIOVrN19b6z?OYSO61?P8g86S5)#}UgB1PLxe z83loLj-7mYn0K0Z*+ZMuD%aItbJS-~u4G=Zw@6nkiA%OoxG|bx@wHXRp%p2iK>m{Y z`#uB9p+o9KAb7G5h$Va%IL6D^-FTK|@mLB;OaLmX?fzZ-P8j`}0l^3sw9&xE{IR{c zc&pZcJKM#~lq?%yB}myVQ*_`@2L0_tFO{We zJuaJUgb-y#I&GedV6T;bq^Bc7ej|>xt(GfVeJjvqf$+JbV-tIS3{tKJP|s@~5d27p zLHWa81UA65t|QU_H1H&G>QvF;d#4cSAvrddyvZQbfk-i(!ni%RWH&N^yLT?(Y5U5G zvMds9DA7j8&gFDet&cPic5Hf%7c&pvJUcXeiB$LdQZa4O@7>nBpOG?_bD}77q3Ck< zUknri$(s_hqhT@JB!9OQq!c!Q6GHJz(lQ1(<1{I5?3s07%|)ow0=-5M3M8yG2@%5* zq7P~=s->!sQ_-ugN?pDQ*{Pooc>kCaWU~FXa}j)Phi|&436A)T*+JDoSZkh|3P1pp zj)B3>bsyp!&X5A_iBGcTKnLFh0yr!;N7i*y}Wu8ZGiWo7M)UZk~$R znxIgJbZ`H>|0kUw9ptOEq2atl_`wwVi<=730%wmO)3}RB2u@>!qg!GG>VJ1oT0Nq!v0J{{uH5kDnZNW#DoZ> z$AsF*@D-e7-@Nm6^@5P{>{AFINmWf`9bs&zdrOz6!yCeS8$rnKKy8dyZ4BWt2|)pw z)=>$PGl8==fhPT!Nj!4)K&a42W{8`=R4{;}a6Umay^g>Na#B)G*du!=*cjN+kv_1u zEC3--L&V8Rx_U`1i2i?2{rXrk^4G7#xhk5R;F=LLiDc zE1i!&S{=rwJRB@_R&# z{~Ui>TMmK-;y57y23~g&{@lFiHgv5zD#iqnv&l^=wa2(+MdbHq7j5)3bhDgJ zHUYKY!QNd^GzoKR+2@N?@u4o@?{?gdf{~>%sxjc>1}KKHI}=dUvve=FPz73=r-#29 zjWygT@QqC{zp1H}t5Y0Uy~{P{XB7T9=V%ErMS$e`qmi+>oNFBwscQyc8W3e2b2A1+ zZUW3j^p9l1RNSFmHAEO2au?x4skDmF}QB#{_44@x>%j??3B{=6Ji)kpE@96B{!?+)@-;JUTskE5&z_=(> zaxlpI5g5P%*6t7=J&f0VVN(33q(c!2xMLKM>QGk}7Y21?&Y9A_1Y<26LS;6<6MM`t zqPo`cMimu{;v0>e_P7lWpC~A)NVp(N!uopnUpEP|ql9{F#HzPd;7u;tk&wpk8^Gx4 zTh#M8BNc|mX;`~7v1NoU1sh8Tj-i=w6n3X3WWWMKtoTK8rpDSi5y`4;7=(mbov0^6 zDjqqqhWLSPUyH9it=?!4kVFn-%@TCZE|gH+J$d5VwpGGUj*u7|Axc8lo6@G$QJbND zftzaxr_n5WY*mT)Gu>7+!9Jr_N{OX$QffxcG7 zXRB4Ts4bczV3DPyC@1JelXV6+l)|CD%2=7f;a2?fnKi&`7DwhP)bkP$}A2 znU|XdNJ!t^(8+F}1j%zy6mNW^!973g`z}9xW7^NGlFdMr2aI;(hcXlV?75M@<15u@ zs2%#fzFMg3>m6}48d;5oiAwQl%j65fZGS2>)?jsi*leFzK+aL=qm2a5&AAF`7#K0J z2omqFQ>AlG794eafsAw|qLiurPrn7mQ!qyP6$U}IReXpGvmrj5<}W$%o@zj_4H2&v z{rY?CLKo0&i`U6U9`%Cc8i6@6H-LokiNnoqMLj3i&7yOktJOI+F}|qLWGOZ3q+9)F z2wkh=%`cUf@R!nlu+71_L5{VDM>3%lCw{QeZsz zu;WI&MlV{>9_VPs8?{`I)a(&`dkvYGgmv>@Y61LIq``)=cM$gU#Zz7;bwijDnXa^S zhpazLmam@05dD`h(UeeNinXF4kn#PLO>%tY(aZpD{FmvQQf!~!l0eIo zRt%7j>@Xk4{0!p4JX&iUW})2&?}@Urk~)EbgCCUbm(W=Q9YF=H09+g5eVL#8Iy#z@ zcFU~JAR+eb(|EcEBg8ROY&O)Iela+xHG^3A7VE)~eIPzh`_Xn(iUycmoC57G8f3o2 zXId?%UG1*-O$eIy^c&m_ZujJ@=7)*o+!KURiBt$;-w0>klrpJ06Q9uNRCDNHUcg%H z6b=;Aut*|^4^GqMrD}THPOi}xaM?m3IFa~h8FGer?)BqNp(0we?JN9C2d?3jAE*=w zr(Ps{Yb&=KMWBhGOf@M+EeXNQJGhx0IEzlvz@tVk)}jD_+wLEH?&FR@lrG;m+%{yz zL>NhcPE&-to&Sd|gEP|1q|T6+>H{=@{QMp9Yy%O=y{M!euB43$AdL|yEEyc1+98Hy zWrvf%xi2PJ$h$@F*@fRu_HC`1#xhF3b0GJ%CJlVFENN=8`HJU%wY_s9X8JptDI21$RJNci%afW%ibsYUI#bCuM0q z55wgm&DqfIIWW7NV+Z_?3V?5|em-aJ36QX~khJG~e8(t^J2f46Y&0sAmP*( zO3qd5oN>7YeuVE&62ElLrE1wH1=^@M_B|uxu_4U!gLcp?QQ*DVmHH$azVU`63~*7v z>GvpsglIRVE0e$vJ51|#I>wGMoq#LDBB@o_#5qJ{HDYjD>4P+O*BHAc@3!1wRva^O z%#LN)6{}a-QLAyI{UFPz19-wh2}_z^3`#6Hbm9RB=`N6+QrAtE^QB1C|6 zo4lEL3Q*&{-2Ih_xazsv5ItokrviUA5Fa1!x+M>=GeztZv33}goPUU0CiMKYKQ;Pu z*N`O(Y-t11wD<&*pv8@7e~|Lih?Tu99$G75Mx`umG?8Dnh$Rw z9HFNIAnj@AiT)Rsr}$>Vu*Knth4w(3mMHKxZEi37OlSQGEU@g1tPTRvv|0CT=^+NR17tcM*c^AOBW&Q%{dVW5}9?YPTI)5Fe@WrHsG?C5U92LN1 zOS13u#Va0SfJdiuh^XR^{Pn>(I%t3%BP1ODNO#iz6@`b&>DSg{(?Sx@Y&zANUP@CV zjeR83s<$;@C9pYMuu*;^La5~2#>@uq6)C(M+1^{t#|nV4o8N%)90+oH^z&)#&#a2g ztmx$RH(GB_EjU5`@)?Ju!7-4l^b5J9P5X{!6^8&Kz4sUp8cZnMU=cW{-m2GrZqXOq zVNqioTC}Yx$(buW?d+J{?-&Trb@f}CUA2k>({qz1dmW{w~cVJY!C}xOOab zy*v*S7iPp$vLEJ{JdE;R8$I+cuvfbZS`OoT7^Mwg{NjKC(aS*n>j%8|A|kGWoc4C>t${bISc$%C51S*B)3wSH0>4M2tRv60MxS_oE20Rs0ZH}>%k{I+I&kaegaK;!w3RF9u00)F#&OR089QE2^)&l{M<&^*)= z^DP#=UyaoIY^MJC{d*Hj;srK-U_tVrupgZeq&%mqjKlGSD2eg`pua*Q z4xUx@AkvwbnajLh(-sOHEB{ka@%E<^Dx9-8D+c1w_7H~h$|&xn4V64tNYuvpwaH(hQWzLj(}i3tegmNG zi4o_q)yv8r_alS zPKqIP`p)uCZ4k=#Twgq$-Qk~$$0JEZWo032MZ>e+p1f}p(8bXmDr7oZJa$v6fE2{< ztY(k|U2#bB%mlEBvM0%oA0ZJpNF4Y_e5{WP-+X-_Bg3%FV-CgShiT^a ztnGeV?Ta@Spjtu_061dvIs<&VMioySop`IB#&xl;t^4(&E9SoLh{dr7CU2`RBfse_ z-I9^Xg@K}cwdDRq*kwy5GvfX;I#xDmLP&XUp|s*49bJqU!;|HZbHokg10A0QI!3X- zxT@p1Dy!&CIUBd+-Qd#ojE)|>@O*vBl3JHeQtbW^bcVfMMY%Y6ox7Fb>@gQaZ77zc zD>q^IE~x&lTtC_?`_o$aIf6d6lpz`&GBWt*u_?xw!yshx05y)4_UpX-Gix^5@WKtz zX#P!neK(|{p9zb}F4z{0-FK8ZpMLAkJlvS?)VeqJIskKUkEsjru)e`8KQVE zyajB0gtjxsS3q|41I5%u>q+GDPRz|`16dF9hJ-`7jG{xUPzQn` zXMO6bu+ALFtYE)`(RU&2Fj9m|-^-$^#{=9w;H_dKTNX-BkW&@V!KU<4*DdDczm-du*pm5Q z!A2m+Q#=UzU&Qt(!^IeoTdOFG$TPpAC`1F5lCH(@lLkpBK^?s zYtxm-uUid7?X-OFQj%pl-ufsjBDTT&u!G!Ah2ZLph>+0pXW6Bf2_9OQ8Gb%7x(d)& z%-CUme!Kf#w%LiM473bYNo*eWROerqo@=~skjfUS-mZM4G6d#4zKE0_4HUj9C7MYA z9tye8IoZ4>}UlJEa8!aAeO;|I_d81`G8-tf-Z*qxvi_dAD?;jxFL}6`t-=Ze>1f;F; z##v?~xIIUk`_EvFFa1_cl%KOIlc82gz8tr}A}(KAq4V2!)tg`aot~BQcE|E}#D%cq zcRt?85zc=xPE;Osyp38Iw8=aoRB38e<2fNT`VImDUQ(XXy`g*KpHCUyeQRN8Aldiz zluuUPk$Rsp#gxP*gb^zPm%xG2WMX$FW&p4k{oG^tUP0sPRuzemdFE3g#gna6-Z&iiNz(_f$Ce1; zRuW4UBj+>@h92HGlHA=TXW2cn2)>1Grc1tk*!vK5W03MXW|z&ZXo#If8-9NqVtl8J~-|r|_LLekhY00XQ`L?fmy8A}I#qlN9t8@~$%5 zHbx1BHLq4C-_47!4oKOVRQzH~_5;jx>+MDUd+gXS) zJ2o>yh>iOv99#BKh9$R&cpooiQyTWAs-)3nkEK3RGeR<2AxIiMCi=G@b?Ew577fvH z{n)@)my%?U%1^JbX&b|jYLgd{4ie9MD7)_7dA5CKXFvkQ<%^Qb0`vQsK& zN3TrxcNg6y(zjk?vfeYheq5QWKl3p$k0wJOvo0#MuK%Odq2QnUijn!^Jj$L{L_$KZ z`~@SX3VYiMW#)l1AKF$**_@2TRg^B78jlgB#iMgQ^7I3|@bk~nspRayCagO#r(?_Q z|ClguCFdtcp+}_TZ;dj){HRlqRwnAsFgVw{p+7p>g#A$ARcdL{ z4!?Q_k8cQU4(9eNPVwH96cqUC6)y<}iU>ZpK{((r7pAsH_vDtR-`a9SJMOxGNuGv9 zufXW6w!-&ZpVfxHz?o?)L{3-NEGL^5k`qZmgj4vFW3DLwGhx27d#EwZqdbaS{p>Xz zKTwD_&Be|Z+rDl+D@Df;PlZhszY8&*TE5ve(A{NfJTTjuh(K_nMDY{n3W$&cj06dl zX8Op%8Tsd<4Tttsj{Tr3N1@7z=PL*Ls52CYgj<^JDgv`wF_n_6=r+++N&StYXH>>8 zN&G}&b84w(QGS)EV#a~xi&s|#7*L*mO57Tk4Fl9jN0rGO$ zg5D;%u88Te{m0R>fQSf9#4A|oD7Y|;%Asz(j#n&(?u^-ydsUiw_**zxA*;)J35FxM zJesvm_@VS(DJ7GI9qXnDF06K%ygC#t?(AC__tDd9~PrEKKYc{p5(Vsw_>@7BJ6T*am?qptebdmB_Y z-q)I%)2oUq?j^|$k{P%1o@KE?7PLW1%EtDDbBh3W!)CLSmg59Gbp-dayp8F1|+ z;tUUM;m8lfj+|8BYxa$44WI3`_+Enr88#kSPc(6nE$2dxm_;c{Dn}_cI2vkXD)1cQ z+op(P`Bk%0N@y#F9)*z&ZRx*&@Zph-^xKi8HR!0UBx*K|f{tQhGZ6H@QO<|d5pn>? z^6XaiN18YH<*hzU?YiIF+FR0Op&%^pgQUNLt9$Du2ku|Z+DP9VOpt$$J9E|}owu`f zTd(kxzNx!jq3E;1A4m~11mlw#JGc}D3V zck=Mk6K^@@PS5h7QFWPw!Wpvhh7h;^bmRZXz^^pnTc zKPy{oZJqq&VORbd)~;T zc@lstR19Ic!^iM~^UT7d>!whrw$5)a z@yjaf7Rtb&%mV;$>!Y?&%b12_!psA4$$WwkI1%=Ips-ZO&nkU^Kj$o;DLe&5Za9|A z*vFQ+e6g!fc=B@`{fAd2cC{=&Ly`f0K4VZCwtA*lBwwms;P_Od?!r+6N`~jX^D!0^ zvS}@ADOVo2VX~aNDi2q=TflZMQ!^HS$-7@yy=*VDgH_5~Woaq*CgN-u@{u9?XzVELe8~4iX zYjTroW>s@?+t1b~ zB+81D`S_~-9YM~Gv>W;ZZvwJ+vySJ0$zbqb`Q1ATPUI^Bm8wDK3(LkIKf{+teyefY ztbgCv-zENzQO(JW*nSQ9?&={3`!lz=0*<#5pqKUfoPb@hN{(b0n>&?HyO#F%s?6|z z0T^U$LXpwT>Bft57Fl_wz-|*U;-)n$>7M|G5zyKJ?ZHeNlM`?&r~m>ili_Q76px+8 zQ1<(2tmAii06^Umx;MI1xeH?cLgp`IM~}WK-S)1Lj7#Rg?zek0ht54a{zc``UdV)goU83t7RtEd>vdT zRtS*gZ;ECCF2*XO9;4#w6e7&^2cS>@xV!7!kjLJ%rkoHmKz6FmA1G+NWVMb+**i3c zUT_&2Ydx^ZGV%=9J@xe+vc{3)XZ}me`}3lF#al_rD?A%t0E+QzcgfO~!8TLZBPYoi z6NXLf{VAJ^dt4-fJO;UO+P!?bN9mHn_;ndfF>){)k|#0XP$ttv;h?_4K`o~A>M3-x z)*N#`kq2f0N^-{wwnbFUvlf@xdkq>E{|tnE9?wbPx$v{(=5_%s_?!N?GFlT-GQoPi@{K8`qvq5*Tu7$Y;t-b(QC z=kanLxcB%vX%gI@>w4B{@z~)~QZ8s;DbNQ1Gc>fuO3pA6V#t^Sf0MqJ{6+ul%Gr^( zIhklX7geG=^YSS^g!;=2aci4+wy?GL?q~WMS%w25DPbrmBFZ}@wk-x zCUeppgMeD)ZnD*B8) z&9k~X@awpwKj1l64Hyw@Ib@uwSJE*ojNGG(^*MfIi#JWbWTo2=Bz_INX7rC z-I!W1G*Oof_9Pc5V3m>%9z3|aTE~iF_qmvqC6c-HXaG}Xy{mHcdO>&7csHpbCC)`d zOD7XL`ysc4whZ-Z|7p#1h{OVa~LftR8xP6H0 zctL-1+~_=A>W_9T^2qT9>p^4+&(&?6)lXi9_M@dvMg42{98LlvKo z$r5k)2y;P+7R*2T!Nl=bA$x%EKuDTzqqih zJy=X}^!PLNP;(2HWQEx-3hD*QHy6<5Dg92zG-!5JT+vrOv??5h(Gq`wXIjf)(oCV* zUbvQAL014z4B{~O0$URv1mvKZ*2Na&xe<9OE&$%UZRuH!k}StBqzFU-(t6304L5-1 zGk!$@*v8I#6XG?$UX~Y3$-v*lX=@Ql>p-S-xJkvaSb*~bkyB>O{GsD2!blS476{30 z-!Pf>_rCnR82F3|9Y(Az54e9hSfFB!GJuO_H-4GBcXGr2Pk*de7RJu`v}%k|ZykQB zYg@4a0CN6gg+DdVd^(Tr*qmGvxFn|KR0OrETE)+Sh39CqcoUObhBEkoJABZ*AdHOi zPY3yEC6Qmo&J+xJ3Z2@Zd}4QkJI9ZUnC6pmYoIP%NX-JFz_3P`jKDdjF|)&WN1(P! zbfPQD5%muo{10i4>THXUAS$=jLTI-iY`*gCa_E--w*T;o)#jOv#(C~Y(J9{^*{yRj zF!g6x;@b32xJbf7L9fu71skj7HA!0iq)42W-XX;EH-zmeCEs@Wqtf^S|MY);JbzB& z0AD^-C1OXVW`&q3W6?HI4#=vNy(E3^C7zJq+HDSiA(9yrHOJcf9DxmJyPedI!bC8k_LI?uQI1K$#;PJQVB97Qo$8U7%N(|9P9t607Vag{Bq zI`k_UhQf7CY?HyQQv22Zj*%zN?D>_+JQX)BKOIyP+Ba>G^RAZCEJ+!0Ji46^u?p6B zUD8_{6a5Bz(dIo*s@pK097yx&utJet$kWN@%TFmpIIyLdF^UBSdFJC@uA40;{C1vs zvjsi`f9m<}eD_Ou=x`9*Et0@!yPo_d_v>yz((L2NnPa71Z)=w*h+jC6abzjaBKy$Z zv4UO@M~Ybm&82Pvz=1CdQ`^j|lq8ECsnUQ>QN^$KgR~@BEUqa~Q3P}3cxVH0P}~wa z_|b%SHDK=E3&uAobZ+^%2#2Eot(02;w>%41Chn{|V*6#t@Rlv}2S$F^R0yV~j}ZKX zIUq$(IYT@4`8e|BtX`%EAmd1e4ajdzM58dDjF6MQdj#Lgj>K4gd5K;7xqnoInr)cU z0IT~{Mcd!#tE~zKF!0*m&PXKno`bP(XouVk4v8S&#>$Gp_0KGr6*Z8t}48c3X23k9_YV+$&pKM|a?9rw_) zCON&igCSZwK^2Ti4rabD^q5weItN~+5-OB}nwao5fxw~q1ENf27HxY#08YnbA@j7P zk2bcb43JSq5%zNS`uDs_I!f=KzKxyF)WEwq(9MCM$^eSu+6BZ>z}u}3pG~kjz!YOX z2!@{Y#9OXrAq^N5d$sX#{f2M|%S*K>moOX0$3 zmKo9Jch}qGxlEci$;mcU2)bQmp)hlI4br8g9u$n7wNG%VFIa~uhRpFqNY5b98i9zo z+7v#Ud&&rOKlE}1k}K{7q^6I9!^k{hi$Q2H?{&buP%03BsxC72*i6+4)TS9I>+N#* z<70~9MKg%*rkswnyL8=;CaBvgxiTP>k=?O&r6nfaFhE{#I(@D-&a!<7PM*Qwg?nK5 zWL%`u&oc9{M~>u=`R`J#i={1O3GZG*g^WSI?)4S0E$>BbAAB?L@4{vUZFRmYC0d&vnouE-$Nq(4$A7T7qb-FzRWvE-B| zYuSILdnDaBA+F*|^F+3)`2x7u2?*??R#HMu`_2yHm2QPDANr?%6py%}V5WkEb81ej z{+xfYdB)ZA_@C;cw3QyUD|6^ULuzePu5rFk^Q>aV`HimLlh)r$H1chXJ?EZ9Y>OCB z)TtagC;1!B!Irjg!25NFe?o9U@v|#;Vmwh?|Kybt<68+={on5tZG9a=)Q-CBcfR4x zE|Vn%oV}o`d(?sac<6)*0QD(u^{-o8%EDr_lvk(kMx*-HWnC4cOd`OeaH9pLLaOzx zeI*j@FWBn%jFc2mg-gm`e`y$7ml;WUg$upRGh*cXS)X*~ulU%bdO>sO%-);Iine|c z_!v%Y59tTtB1w#QjKBuY^DflQzte*|z1aou5Q7zTGug&i6iIKx!4|acW(a8)0hdds z9(7Dd1HL!C+&v%?DInKVhD*5hPyhv7bPyU_<-l@E-5D7 z%1l*Ry<-0E%l^P1UJ!)mlSa%1$vUg8DQVaq4}fn~B?hg|Wb9cnE8PL-S!kL}9SS}7 z^9~l@kE9*R5y2}dxI1@{EN^xCF&lSxvt8Qhm)MtIh$w$qtcz(@{d@%bCL6DHDhtKQno_Xhx5+HJi zJSBaJV&bs}RfWe$y=sfD=6rnCM`V`QbSjCdkFYm(LU~p(P*oz*9BUK%Y@CJbwQohA zBfNh^Khvoa;x6$LNBs=sB@U)zhBJ3V<)4JMXgZ~2`?NV7=|OafTqDG8t#7dVe6!R3 zWL@Xycrw=@X6Cl8 zTHiIMpzPi^*~@K0wGl1#$sl$C)`A;Ujljq}CG?zsb|dV#=eHdH)w|P$5WZ+@Pery@ zDDp<}L#3{f=D!o67De)_#BE{9sM$?S?c1W`$$X)CA!s}p%6F7 zKQH52${8M%!v&n_$hwo!%f`GL3O+N`Z+pTsxp1-RK3piRG7TcQgH`OY*XJ3Yp(0A= zn!Sm%z>ew~O?B;9vG3>%N*bgv2ZNJ3XXw8uEZurm_`2Hj_HJ{82%-~^cQS3kISrBm zo}+Qk`Pzf|g%R60RVN*8O1zvz<1z~7FEf#Gm3@WO4esUDX=vw#%5oy zQuoZPR-R+6e9W-v60H2xzWgVI*-rtMUT-OxV6pr$fJk;);EA;ds<^Mo?P{DI!_!pTcy>E2Ao=m}rWxHJebqlaF5*4&RN z>{Y6&3|9uiT0#2?ofK*s=-d3c~kX z)dC7%HeI~}VFw|c2#_8w#;q(Ivvb$GBa$BSIK8|UQG8Du5J8WL`lnUSpSZfc_#PxP z4J_9)aK!T^Fos_HsgnkK%V2wtS-vZkMaZc1OGA54d!5Ir5v!6)uoVz)_&gSX&b)kg zW>&u_=9Q&1d*jM^;aC%i{enS?Oe7jG$p!%Jz0eG?+*I*hy?50t`u#%d zKZ7>iyQEn70TqNL!mva4V#h3}%nhXSp6OtocX$|Hc{(!&FtCe|EN4gx&%V|%jg-U` z7C^B#`HM>tR~j!~r)cY=J$)Y{uzo;%_3QP zuTpcb20d|R9m z5yQ%8JQYH9Mze;au@MY=tB+5UqM5X4?BYjMD1@edoHjEW+o}Uhx1dUai7zd$jE%0^ z8I2jlFo!=r`_zIqZ<&_upRZkOnY8>U4*&FYoAK*lXlzF`Hnin!e)PO<4C=YjyUOUt zMVBVj&hL2fX|(eEu}_~)xje`_{{ADu=t?lK91LL9K95BLFExx%bYm<%W-45?+yP+e zEi(0&rdglH!WmzUW3bXpOy?!E$;U4q(QjZ9?%*@B^wW!A1~y^+Gs5~G8Xw1%_CF!) zpVdIT(KUWa$$WV|`mt*N*e(D|F8DpU{>!%gSliFYiuFu-%yJ3z*Esr{feAMDGb%!~ zyzMhX-0~*%^Dm{=d7qfI3MZ6By(Am3eorlh(d!Y5j!ary&62G{wSZog{d#{3Fab| zicXo(b~R$>7aK^0%fiz@9l8J>03a7vCr4zoKe<;O zzD&|?fs6P$RZKj$Ps0jQKFDNFtuRjasqpyvqf8_aJ6jIYX-xd^H{_pqRZgEuEGW5o zcvL%~f`!L?*H{uszBEWHhW^48ofRgYBcS9$VdzT;>9s`lZwyT0uFLW8;%_SB z=IVfVEafzTo)b$a7t%}M>#_NIOR$4q1=M5~K5AKd6s80Ts7?Z6!Zm#a zOD1Zg(JHWhg-IFZV{!qb3O;Q3pw22pP3xo5dcRsilHZXPFr~B~sb690G*Q6mzJQI8 zPEUgNTR>@4fHsG)_}-*f*Yvs2GKz^G6(H5F!MOs7BQurSr=r${;R;~mpybT(*jTJN zAV0ow=M*2)X{BHe9i4>qlh;_(Idf2fPfF|4<1%&Fy+Mxodc(jP9+CN*K^^VY!*rsD zfrCdyDw(Sq5`5<~AGr$U`LOU#qU9Y>zAH?bD@r$HFpn}K0)CdBU6u`9%{~OkMjce# z56G`VddULC3KkLHO^yAbH_q4Z?>fGzo0`yxF#%9kfaC$`CxAw5CV7-eWW$V>AOs^h z`yf*jpM+Xzjo*3Bh=>MkVN0xoZDtI}QE>PmAMVRabA=g>3NTKB)C^Y2fp-0IQR)$v zOz4l~AAG&EzWUaUG%*9dn401$z$7p!?7rm3e5q2K;EfC&F4QJOQ^uAekz-shva}=jZ=e9&=%+Hy_k# zOUynBNhJeP(hOw;taHysQ~>0G?yEl}KrZqr=718d&*)hqe1)m(D;UVImQ1>IXn@Xe z&#Bfw8f4MXCWhuBKY$0F-goUf{06)NCNEKqHbE3BY<=m$!24xcw6!mGh0qDVYPZjT zkFrmeK$Yi?0?B$k$mbm}s^HlEUwRO0?l+WlJN>dD;BXWoZ(zz)tX3So@nX{rjEIk} zI&?lvgdFY0&{!FddwYLFI;*0(+k9lPX!&&ChYZ&J%NEKx5S%V}efE%yFCft^J2qLX zlP#4N1(;+&O$rYw4tA0Yc69_+{Sa}HyBq( zJd&?zDk>pR)wr0IA-;whlRb(PWI1NIq??3B2=DsHI45{ic94hi>pl6@H=zz+AM0s$ zvVBE7ehJ1WkopKmZSX$n$(FS;c|#~w++|^03IM{jzHP0$d$Sccl}ByAy!&qSnYi-k zo!9oy4E%kQ=pu3ET%Mn}adQ9eTSq{&l5It-#D4w1)Cj<_AH?pVH+POYfG24s*AwLB zF^+I-xB+sk%Bf!k8A#E2e<1aW9KD>VFPbG6)=#8IlHEgVSp!b|w4U+jIUZC)i^?Qy z^c^3{opmVdgi&;Ty^|d!E{>z;r0IG>Ep*gG-L=%%ZUF&{S$7m;tmKC57RDYEs0wWp z+sQg@xh z=jyX_BOpW;-HVm^icM?Jb|RWG8_4vvyjs3Z?(}UfIVE{5%!jBbp1d>c)Nv+tU#yce z+T)_u@eP8VMsVpy*W2bRuy@*B3`-8S=w35WFDKve^nzhOVng^vt;t}Ykz3QN@6o`n z>7bF#KNlZA+ycsUnyg0{jW^>gi^&->mbpAHtgUM&ze%;p7Yq>_XukuI`FZSpy(Y#+*U+y=&W53(6UP6BS@Ke4BWZ42}X5c<&ZoNT`B`cx{ag>V?I3J{psn4)?U<&e8awZ8$%fyuk?|d-v~JaskV=2$TM{}e~fqO z;=yw*$TgX_?t8C$eq&YV=tNiJHv_kJ{G>25@$Gj}Cef_OHQM2ht8Hr^=wzPRXJ5?w zbbEaMxsjYL=g`Vkf$`~Pbr%TCR_~W+@2&a9_BjRtpI`iV#h2Ta%s?+^EYAE+0E)a6 z3I!!h>Y5OO8Pm7-gE%MBa=wg-5R!HMjtM@FQYF-ZGA6NV@onRGg@|t!8!!HC89)0t zeaEd|H!^R_A9?;a_UB3EzyBSJJ92b4&*hwQCRmi1*;~m=l|1x*vd1(af`1g)%ET0B zsIQ38Od84a5nuVJ(;0*tAL*0JLy#&YX+Hv!I#CU%XvM$_7*a^KfSg~P(J4zRM-V&` z567#$<=j=?8aNaUVQZ_ht29$bcb6PNcf|xw!XrEY7DYLjB%>1>=ql$s^ z&JSryPJsxReBQ;Li)6DJ5mI$D=S|iz@KCP1=KE2=p@IohIbGgg!JZ zmf-c$Z9NR>VKT)fAWx;_-f;|)--M#un8n87m^sq(+t$tzPZ8;-EQ+%C~ z;;`LXJdBQ7F`|<})^>?6)$_+f;M+a?O$wY;%J5Vm^Ig}DSNb*>Pvqv=lm2E_G!0a3=A-oxBp5guY{mvOx|L&2pOFlave-`TA zXt*Li>-;-15M0OYl`U_}Lf#KNlEVR}9VCkijX_%Lwhwufcl5CrKl_q1YMeVd&U{-OeW?2ig zRqq*lY8ogqaL?E4+dUJr`@*17(@e|><>&dbQM`4!6*}3cFMD21ytN^tmF(d{g+jF$wyjMmE%1f+(dx z1frOc@VrKZXgUXDGw;E-d--S0)YcUKy1-K$VRV<8fVc%*pw4$UO*%s$C1%JP;{z|? zrke5*`@Gi;o_>ux1$w5qzz%KT7do}oVb)&Y;Quu;#sXqnaB4dyl~2hbT{s{9D_jH= zyOoCR%3unaA{crvL*i5YA3;cmckP(!q{`5@I|!%pY9%tplMkWJ1-t!K0hFwmzh9Rc zvMwSiGggs*V2^n6c?fuYObFef9n*G)Q7x09UAgYujizyCzMohbt`@2OX;WPwLh0>##oz1j>ZR4%XZw{84;erV4Nk z++sg^$72sAil^hPmruFQz}i#=ee~U8k2Mj^!hI>s1P+31Btq*h-T%~?X|HMCntA27 z@V!hITe6D$|bV7;t8)FrFW0QF&PLM*V|+yzGI1&*^;<7LAP zv~V~RAYG)eMkiY(^L=RIlN2$0O-{eKpP(k*K?kM6@y==-a3Bj|A_Qq5!dZ?POZHWR zZGcz=!E4xoK4KbUlJ)SVNeD{2ca`1?qln;<4CHU2oa!iSZM}R1pIrZDKM_)5a0ni? z1UI8&gF{5)*9tfH01jk51}K#bZft}BN(DG0P8J3HE)W8E5uuWu#TIIn3blwrITXd# z1M(Vf{Y#gn8@K;8Uw&hDM`m`%A1F9=H~ zA&*pE-1uFzO0Ah6YeUrwa1mjt*(L-68?@8HtR?lAd9+Gh&wTsI!=j*ekpjrpdk}g& zK($d&sTWp>fZt%?2+U0=7~G8kTNT4M&*;Rrq6*lcK`)UUBBx5mP?+eiA&iyV#0nsg zumO9FBJ($1-aAxofuS8(tFK!tw^U??>f5gheJ$=&cyCW^*T=*%Eb8Yz(E+IiH)j2( zcTYd9#vj8`g^0!+%iRhMs9xk@+3}+FI8?jYFS3luLy(l!XCSXXv%&6(q2W@N&lerv ztqw6%k=?S6kEI9!puz>Q-b-)BzBG6*9`H5MGkUD2HBuO7g{&TK0Bd;`u_9^wyt*FJ zOqNWKLoq)*uB+`!t7Z za52_FVO*LJ2504fp|@eOfYdJ_(M4y=?uVdxowwb1nW~twtHHamlZ71Fq6qgE+xf=~VLXGkpwh0Nu zj5~H=a`|GQNe@XC%0>!U7MK zW$zoTsT?YT+f)jI)3h#k=G zGRuIze*Y`q{GTKSb_)8u_rzZ9<8Fk!Q--}ghbLCfC7=ewwWGqHChiDN0&52iXUlhQ z58J!;^V{ZUtk=n|vnBecbenj$YR~ob#mf9J3T6l*B26qkPL+qx;xqQfi|+SOkhYid zqZp?!%5id*39k&?iFz>7<=;Gegh9;)1LB?k}Hoi-!d4r+!g!5AX zNxg@DSF#ZV4hVbje%kE9m{}}7FMU3Vu0{`6yqnkSqQ%_GB zcEa{ZHRP_sLSS%o+tl8kKI6t=!(`sgei%9?C+ctT2J~%swFq9pGyF3jpRsjlF4J#^ z5TStqoP$J;#Q7h{QWaRg+N)m1i0M1&8I^SX`j6D(R(WMs z=SL5kJmnew6G^>1NPq4^A6Qr~-K)41Y9h^4z6k;xNx3DKTcsYoB9;l5ktav06{CQc z07g29{!cs=-kb4}RM+gBVsjg@RSvO}VrMIoNe2AI%g64Jt4A7?HFf2eie)2eP7`7o z1h%X^$3V<5C>6oTUJnO;+%wwIpbCXcVKkJYNV)N697Mh(zWxx`fI>NTu< zXBY*NN`uO71;cs-xUL|nqW48v)|Fq9mAykZSbH*~Sl|dSp2S3~jXVIGN~$Wx!Kbol zHxL`#Vp~t%46AY6xZb9lFg_xb?e~&^}p zd$@!XklO^jkM)i)<4$nI-Fr#rB{>XrPqe|95e7AQ=Oedsbo{UC_~0NH{vA`hbN$AY z0OHV*)wkQ;8KrIj0$=HArA9kwoV$xU7Ym$2G`0k27v%l(iM18+5734CjSlU%sQ!vt zzc^JusJxT_CUafuCayQ|%6-VlnZ7&7Kf|CC@Z_bV`>`a$wbgIw?8WD!54PxL#i;4Q zLK90?*^nF7VSql9f@(j^m)gTzJ^`ud+gkR2VWXb z*f%v}?f+`rH>zed2fX!AJ(@ATucducX>1rJ818GC?^|8yVwknq|2s(6fvJ2ayOuXk z6q&N#go{>!QuVnsxx~v9c>%OzyIGFd>5;;?qjEVJi?p z;&Q4heAfRO7=zHWn;OzBeIx8+zN67%GR9X7to{4CKZz}GiI2YSnA*0d)KX@5tST3H+y7~0gptxE{NW+zs7A&t6#Za)T!B4E#XN&)s4yo#*;m%f5;&W? z_Osu^VJ9&Ax7?8~cmyMYUkBbDB5Ij6-X_36DHvZiNg4hdk~)0wcT^GK{dy^QG`=sB z6)*d}zKDV94%*Xv80f>ieU|$ScaiTMe~<2*NAD0l zxl0+k8oW0O8oJz*@e`6`V7(hzS=uuSk+V7k5NK&9_$sgc^L(kzBn)RM@oO)wW4S~e zKe$&5X8=k?FwG3L%G_o~zC#$^vq5Gg%Af|t3fA&&(?iw5fI`+}quX<*KcEq!j7PR77YR;9%;iCqn)!5hZS@NT>V*ZvL>=V8F z9pcx2`JirL$JZYb5mW)YNFerVu|pX&;Vwix$L1LHo^dnLqiV@eA=*-`_Vpo2ah@U& zzHxuNa%NP|cE%!AQ$FR&Mq+EnRjq4_|NcDEG?|A#09!Qe18g47ZG4s?wJT(m(2I+2 z-|VrUGOXhd^yQqh<6d7~mBeclvJ>cw*2Oil>h%2YG_JY501K?M1XjCx;gUSVF>_3C zUePh*0D<|^8XhU7WW)bOYw|fK5gLh#+eIpOyfx*xzt~>Bj?6qME?vhUnNz}a2&9XS zlfgY08LDydsOa{1iHw#@@@R%OrV3?2d-Tq`*cpztZAV<#JL7hyJT~0dihQSpLbpS> z*j!#JKpHDrI=O*lcs5SaZpY06>&x>Gsx}?^CvDRi0Ss+DZC7Y><^4qS&KrkiHeFqO z(z);1&B9IBKD{V6Esh-}Cof@iZMK>i_S$Clq1>^*b$2&7!;G4FM1F&qw7p!V?_ZIe%JUZ8UZJF!xOoHSM0qq z&RSorN|ZS}-o-6KfYqRGBqxfP6=zb`zsvDMsU$SL5Dy^fRS!IE{C-0u%CTc&eEOI(bHBowC|HmuZ}@`Q=yM(31awWL7?)}FD@fYRYG zV8Dkg;hXdwm(J+`iYCP%T(t)QA$~+BpF^txVu>Mp<-+k)^+bdS84eTjQMxW|=Th?w z@}GFC5J_q^Xz${gRE>o5OvHy%=RpB_u$zxnscPGme&XWTPHe%>*&>$50Bit2V$-mb})r6b`3f-r})m3Lu<0B?AGwfpi~)U}s~rDD2f zi(F&6PruM(>GNrfUXaAWGm)RYf&Iu8%Ta%1iB~ND=D(Z!E}{=viO>qq0!P(u+M087 zdfiWPb|VRH@0o}VE+T|ZeixaEr52xxfFC8s0bweuH}*JkU*!8C<*kad&vJEKda+?k zs;3a?T*8J-YC-HPl;Wa1yNA1cl#epbye3A93qxO?&nRhldCG6k)pOnR152zuMrzyV z_vl2pCp`&2TbT4Ta+5O%V{OO#dX%ojWy8JI9MH-Krg(WU7fvEdN6KIS;8$DP!(KR*&_um_(>8ooF8*4X%6T^v5V+~j4Jj+K7w zfV7Gg51g?Z)aYXOki&nexU72I-TMANwySa@A`V0`5n8CbXy5qmmkH8to$Yppx z=6kU66)b{qDN~W!YbAv*R=B;KD z)P!iMVgN2{f>d}9KjWO-N7$GE=op-|#f;SuWTB#W-Xx^+=q&VCfv>lXgxs~#n@5>u zAna<@e7KCb(Dxboba_OxQx?BW0Y_>N&NE)4X7cTtGG9@9rPR!Mk#9G>`ui#OuI>A{ zV`+=8HFWTNwwr0;zYk~Sl0l3!0wz@^J`HOZI_dk?9x35+bkyEL2lIfm;|um*=#K!r zWtJ>eZFV+t)R{gG$u@ETwa_LIi8sdV^b&!fSEl&S=#jvRdZL^Ni4LumQ))vfRS#}- zbP|vmVPvA%^WrcWN?RhBpMX>Tame zwtJXA*?A$cC93SK-EDjI)kVE6fAjX8>9;?#BTQ_4Enb=Z9bWY_ch4n_r^gEBLaN)H zQNg|7hzffYFdhf3j?O+DrZCO`y?Yoq6Z^BQm6G-scQ@)aoj^qG<)ad6cV`;R_*etqj%&2ABraK{jH3d4SUYP!B@{&IUD7W`D>auwhST3F;`vu3i+7P8 zhix9kcMKe_pNK3PxKkV>S0F|hCihBf6b^~8f%ob6&D7;5H<_Be8gAYbrOdhXv*Ha6 z2yyQ}lj4hVD&|Y?4(B8di_U!?Z~B^8Z?%uLJ7a&rYqbx_chjnt!u#v#$Chw|B;7cy zWdTiY_XA7y^5L{sSf0((M+4y(>VCR$1cgh<_X9q4oV@jiuDK62sEYqmklP%5U#;8K zxpA^&Uq-l@PsN>WmoA@aZw@p0kn%9?)8(_C+TqR2l&!fgrj^=Rp{Cv4+q=DdE0=fL zZF0RHnXK__Eq$%vo!h?D$EnXt&uyaYWQFKbFFz=_$1tOfWFovPPpMAgT3*?w3{2E{ zd~+<_bjAA+sz-cgc)uBXZv>hw`l8eTif>k{St{U-SOmiZR+=SNBY)9-b^z>gMT7Bp(XZyGO*3m z#;5FjV*K|Q5z=U>CEi`QURszx{ryt+gZ(jIalBsQsR#yQ-WNUjYcl`Pj(m*yByh-U ze!Xr8)V{QKMqtVHlC{m9LeBbu-<(9!rQH7P=e}l*ANI)`kjm6{$YoH)`ahpNyZ7bL+oAm^=Qoh|~adu`x|P4?i;p=yh#a z3N}cMh1yq>6l%urfrm&(sJ31?wf;0wXH6 znukjivZdMRP9d-ta6GCFljUHQMEIULEV~VqWuP(bT1ulh1u9;rpK-R>BmJwf%qZGE z6M38=rM|)}#UnJb@XbVI85t%MfjWz3Jv2{~dJQni{Fg*50)gAy2H<9~ULa1$VcZJ= z_2%K7JkT72YaDeQdy9>CViL(ISYIrE3Ck3cmR5sEwOw|0jROo^5yv|_k( zaXJy)^uy2I!uR`>wJZnS#--u?(zXc|ym(d>8Aw^4AH)L#+muTH%%L_fFLIWO78oYN z9~j>rE1!kZa8ynF#stB+-4*1mO2BM!8%c$H`-^x9XdgcpWLkD z7fpAd1w7(QoCd0U+z#Zi^3`|Es+BeP8)P83@;@LD(Rv-2+6scc|l2t)y z`4`9OpFH4f`76ONBTJF>nv6j2c*^%b5awVgF^J~x|0l0j^%%K;s?eIz^e6aV3#QAr znGsGTJZtyYgY6vg(nJarOV00q)2{BEqi9AkheGL!9Q{ldMZH74rw<^6Fn^5!6tZ_| zoI^f^V65eT2dRGLvR0b&$zJ`c+fR(v2hnrl1BxFh1_i75*V1cBz~5T*huy&{_Ig=sB6s<$z5;lA3T-6<3f`JO8ZtW)M8QzN z)=aQE#ZdjJv5taXX&jJm$ECp!w@!rzb_x;q7OZ<>p$-KbYZHAmS<$D< zz5Q}}I&>r(o}RbFEqPs+NM_}8)P~;@zg*)K&tZ=)?cVH%&=6vLwXC`yqos9hV{A+b zWR<G$P;HIu~BzW8(*Sc8Bk4*HXC|rxH9X-+VPV%xGaJtenHs*>om{L`ZFc!60mpxr1$zB1N=x#p zaRlP{g|gy{I6UU{TL-UVnrwIeKObzmh*6#kXOBv1KUiI0&cv8!LPixW#2pLy;8|UT4OUu}p;z9q4q1ay~~-%M^RQ3_DVZb@;0I zx&AWWuq)$`D$zvma7qAIUPEIP1V+JQ`*z8^1&uoV(-pZR%O`((`2>!3rRq~)X3FX= zano9-TPL)ZY7hbB{~3GFpr*n$Tz93BkWdnOm4qTy4823>RXT_iX)2(gD4+$ie9?ALV^Wlz#kCrM zoE6I23m@^l2ys92CUriU=c=+&ba5<5e7ZdSv(4jm)$gBWb1*8Yg%##fbQ$_hVVo?d zu8HihBURvb>z@Jt2lzhlp&BhKSuwr&UiriF2LDW#8j|#PqjL}A= z1&h1V`>9RXpDr&g!BQuaW+$v#1Mjbn+ITQa1n>mKoP@SIg5^m_4J|!eddTcGh<~pe zgB=>@n2GBjkP(~VFByHBF(WK4@-?fvuhKs2i-R`;u8ptBfUr(VcHWH^$OWWNDy@`A z^E`u;7LIGPf^s^xU_=p4gd)LMi?bs`0gmivJaw|r>8VWisWod^M^GoiQj*`kjM*ev zWziMP?nF2Q$+p6Uak`vTxC(7Z;Ml9c6R*zPp9#ACDxWmyZ6Vu=(0b@B8S(rq=Yo{jLR;8qNZ5kNG1;5rkG@J4 zJa-c3`aAvXGFWI&?EQWddTZg=RmJCw&h|N&f9yS)hB%ygbRuhL#rEwpkt4%z0f|gD zC#);|lq@Jfn87H*{E6J{kXJNWm{?qDGnk3IvGC>Xq?Hj`Z>kj|%nE0EK)>U{?2$gp?6~sTZYaFpg9OnhLbM6DAo{*p{@xS2 zD&j{+Au*+|NslBaN00v*y%stut+aYJY#>T(S(9r}acTPN(^aC~@lms`KeK~CfCL|b z>HY!+I6g5Noqm+aFE|0b3lV1r;KmeS>3YuiW9-h1wlcc1VqGS? z`RyD6H9+w+n&!RNqMQFh%1i9HO1ylgzT6p?zMpQpNpdma&x2b)H|d9vy{r2o&EGyx z0Ha?8u4f8Ms6!rTn8 zO1xOvs63~^Uy51x80ANbmk+4N|GI5?0RRRbE|HoAE*aQoIdMerDrgW8dQD=t<`;Sv zJWySpc1~btTji{(Z~5ml;)UvGEy6{JN4viN`4s7G2C#y24#D^poEd^!+Fm`Jf+HuO z0cm?BrvOP}3jFxRwKp@XmK2=%9qCiEYvY+1#|LNTX4h@=RnAUToqGQMM6piP$F;fV z9~{aswCJr>R^%yLRN9fJ;RMrUF3g7O7K8{+f(YY7*JJp}NhlFbE262iNdihx+KMh@ zVv>M_D~QE;$)-%CiTpwD`;C|;A$SxxrtsYZi9DR&(Q|$SLyUNwX0ZolWhg0ySNtNq zSa>67y38%uLj`+UR=JeYI2` z>r~fKlL|vgz8R;ix^y1%ATy6E)37ccTauM`IR4PuS#l@py!3$N`14CVLSk}A=j4-u zn`tz;UPA-qAse5+2{>7OjG&sT$_$0Pag0Ycu-V4YAlXOzgWC~mFTzc^^uF$yqD}u; zlWdgeC$dEJ>&vs`6xiQoh$ZP!c^nk>Ndi0z*+V)G(japlm-E!Y966D?GkUtx2hvD~ zGztM^8*^rO)XFs{fy>qmTMp&+4#y%~%+MqOOw1oBpNJGL3pb?@E(e~%^UX-1KIGKd zXYI8|I2iu^`o)0&;pZbFl&IBO5_cwNvy}DO<67e zHaHhdxGStW4LBN@H)&Q~fWN%zb+PZ;cdzi{HUO%jipJzXb%z7}YQ(@$C1o=z6|O8& zN8-^nLsZ=rsmUJbz1623^(Jzm5(ZD2-7sMiHYk#4c^cZ78)bz6DNIdKrBdX$(4bxs zaJ>}LPlZBkGgsQfu5<2G_|2y(RfSiES~f(O6i2)&urG=ISnxsb+MNSN`pu6U=Mc>@ zx|`ueSAT`nRp$MYW!DX60!_Zi9R&|_MxAQ;`5K^(57FNiAtcb51~|%vnXBgNc%- zO&M)fXOD$#_Eu^WoLo-Lq}^cFsZIJpj#v@1Br%B&9tubx`Yt2}nr0R~0B^S;L+t!3 zq^+Oxno)?URaMeInt~K0f7-yErvWkOI5>yMqiTRjIaz+*H4dN1Bh3{08p4G7>y+;M z9d16pC4#3yhTj=oy6%{8)V2JkXL>o>EtUTim1ix+l|$FD(^`Y*GCY$RA&p5<<4d>u zD$QT9nBBlen{cBF4){^w9**>fTaFVO z0FldMqk+3g4X?!7zB)N(WsA{aN`A)3xD8YKBrI8&jy{QuA8cU~#J9~rs7Mb7i6c?O zt?BYhM<`>?nG>${N$%~H_a)s=#CpD{VGaI%sMjKdeoj|9RKeJtM*{&Ia^p7uiT*-n z@f+fU7V|KBu{##L{;*Nly>Rk#FNnS)CV7v>GTvnDa-7ueYzjLj99_y@`q`L08jG)r zTQBJqdiiDGN}8{0SnS*1r(d3?g5x8+f4NdwA0SN00r!GO4KQTOWva-MZN57m_;S42 zy>X#W2yjmAe)^RwNl-E4E#DPNiy!lGh&7GPP)- zMl*7=^KhEMSzxR@i1a&4 zD7i1X6yYJls6+`??M9daLMys7OCy8W>{$K&DYWcKr;+f<#|9g zqkZped?^vD5yr9*61tnv9JH3gPqw0P-r~T^51K=0rftG}mDz?xk7ni7x3fidRt-5O z37mYXjp)+0%NglCB%bh;wfdCwOwPG!T1zx?QH3ODQhH3Dc!lm5%gD}1(=PJ6+zR!(&xYsVtRtrDhz(5>5stVy|?aB}cwk({bYylxBdS?ybZ%5gqZXC?EG zdX@8a)WtXL_KgtkX)@n5v9UnPWdm%EfC4mVWDjDCn!tR1SA=Guw*^_&lja1t{25#m z0o)>UHS z-rJH{1&#_KG-NilR14&Q{2UhZGuzPhOa)&UI12oPD*c33sb(gt^(bIujpx&pNj&m< z2^Iw@R@6k1x~%%2x(+lzCZmWm#+WW_nfbNtik)S){fYBJ~xQO+P2w#Mmb-Ue@hIy=7j?nx9q@_Ze$s{$T0s%U}5jwb- zm3>l&lp$!yk8$Y>z^fY-_DQ@gFsQCn314hQT?+vOlx$mfOgjGPU_DN}cD=ov$x`wv!*FVQZQ?1xVs(2W@4x_jLn#$o z{C(S~cSZ@8N$l8sx_krmp)lnL61?4A)bjKGGMJG1Caonry8}<^pw_zvREv0tIEdYU zeW>K{Mc;wFCFQ|5qj?$-3}$@`T^C|Y?@uD(wi2KEQ-&K@@O1?2Rm8I=t{CWWpH6&Z zQ?_`$v?Ya`)3$g(`$*qh;Xq0S;%^#i&;Ac|SiV<9!1lyTGY2&1%5em~r zvKbF(+c}wFIOs&NSMllcwm58jIwOU6Y?IiHpj#%iL4G2$=O9N|rBDHYVGdC*l6POq zxy6t2g;DSvYR=uE0-BJ-Jas-6bz)JzSDB*tmdR=J^R{ld0B?TgYV;(5+Nc{mnZ73_ zA1=M;NL={Y;blwWag?_BtkL(b(ZM5u&C$%901nCF+GcXg?3o)D-j%_kA%`+1+~RU( z={?8pyV}Z_b0SDrhd5K5F+lKL!OH^g>PAKDLDn8e9lBE-03IBU$46CD(J`x>c{CwI z_NHs56)j$=#}PKueSaX{X}>$zIUdIVe`q)Xn_(cCX7Xt-AXz%IJ+2`o?i?Jbr@K|{2Z zy01`;*7~S#AjfjqARXbe*UkOo1t!B^xepYZSH2RDP){lGxWhEPB3uz^E!fg}rwXsg zK79v86^!-ggHaF?0H7!|c~?<4@zeiT&21eF1?h}erJt&KwlyL(@0@`bA48h%9 z%JVaA_@O3*aU_FT4y|X%v@cF~cw-{)qi;Dfx;01tj+}Xk4-sZ?&=7A*5W_Q`&mA4s z-A-S)fXqMTz2($)TaMIlxof#VV0;?M-_0?*KEVicUK~G)OhtEfccQ~HMx!&(2o%{7ye3WMx=;plvW_wQEA8J26tWJH%H%lVP3da^L9CDL<}NPf8Vg!6 zr(UwUp;x|YFklzo{+{$d(#l-7ZUj0I|EhqmD~MrC|NF22*^lf;#E~cyXXY3b2DI`J zoS7kZn+PzQRRsq{`kkYcne$L{2C(QV_KrQHX5H(yY9j0UYrq6O?!mo!Cyu0~e<5dc zT9MfZ87L~iB*cqlkaAWR5-8@9VF2#%3ZR{@VXTWnI}aFW=bhUJ^uUsf?czOFt$lAH z{DktRgTkD0qNZ2+WJI=2US1Q0^V|Velebi_-;~YK?rWwQ;3&YSEBe7PO`uy;eG0jl z3NZ6Q%`0FJxl@%_075R{a_8AkXloUdq?dz|c}q0FBWv+x47{jy+OtY+0DoO-r8{LU zE+EoAs05!Q!i?9Lznxc=<0rz!oznf*D#5)C>PZ{ceZy5%QE!tqLN^n%0rJe=1i62? z6WV|DSDgr_)m`QSM9Jx{zH@?a4|hl`znFG`F*C8K8fqPHW6nAe-f*@{fyHRhmH-Wy zP{I)kphlyb?HWW^q%9q8K$JE$*1kv?>5_H78Kn1DDx(XYxx_>8WE&><@<)jI*!x33 zdWRl=b0z*}Jz1HVxHxu)4Nq=&fhup@j!WX#KX&&^O1w&kUVJeZFK*L$`bq6a>S_d+ z4U^lNn)sJ?-ev>BZUwQSbN%(}_>g}mt$ny>fOGMUm3bYQ-ES$vJ!tf1=siNliFKKn zz%0R3K0%7MyA_|OUzXcL8=G+AFegcLK^KHVLaSa_s?&3b`Y!*l3lf!Ll@v-Nc$B?S?UNM(ay4C=N-}}6tx1y z6`fKTfvED%f{{Bt?7OiB^={&NN>&iQ>a=7p?$oc)_w*e95TYS7UgtK{(GPa-UBuOa z+op%*viD-N$JAib`MJ*ifFw0n=hr1;o;@><`pYlJuBi(C?Ic=Lj$WPMvt0gQ6%MRM zYcB;)*g1t*96%`$*!&3J;lG4|^ENUqU~;I@n)ziv?(cW3(pRbE+t;7m{`<-hU9+c4 zX4@l;PTuz2y!T8WA}bnkN*&@_@I9tS@aCK#tJ-wJ%bP8eD^T{4n~%i@W_(8-`9=X( z9}>#%K~Z-6ftui$qIOah(ija}YACQde#Y2pZ?s8N}feE#Tnmab9DK`j89JG z3e3IJRgqA8l_=*SRLq&MapZifn&+QgO;y0uUzMQ*e?g~&OLw|-zruCXzQ7C-wYN(2BbYjpvJePl8Q zhZtmGRaWsij+{g~D(4C~Ix&+{#c{|*1l?>TMNA@IUATojk*DlC0L4m;aENIG%y5uj z5?x3o0L-ZnDK}GLaaZz0L!|uk8v8Pn+X_(%FB{yOEnZCfE53ek`f)tx6MlLshaW8M zMB~+C3lD+^!G3dBl|AlXs6IbdyQv(f`)%u0b6|5J!&qGM+{@mJ$~X0|ch23mFlxSO@caA6 zWxYE9ot(fm*3)`bwDii&=HGqayWENA*Iycw)-~Y1cAN5VsAO&vq4IcEP`NR*DI~|l z)XSQU0OJTgE9iNUSZj=siK))D@T%`#CjHITrk=SzOo?Zce-n&NIvihjzwqy2qOj)! z>uzUjbIF3LEL&A!F_}1)XPphO!h&+)0D)o4A$F$P7kpp93E`!|%(_81C47%1RB2~; z*}oK!CZCu+RaIvRh!0Ix6{yxiw!|eicxjeyBQMS9#Y&p+qLr*|Wa- zUO-{Jt7P3!eN9=sNJCvETZ1us2-5XveIv{4-`ITaqzOCx;T}&BW)s@@pzrg1W3#;u z9-TYTo3Pb9Dp}OjI(9V^;d0EI*3|yo+3Q%72S9`ZNRM}^9kt>I_q$iKeiy*jvjmiT zw_6u3n$9S%@A96#vhpBkYrd%Y(aS5F3elTPSeo@%DHqT z>MDL%FtAuY&e92QY~6Y;lxBg;_P){_Cx@eOmdL*&kGr4x(>kek!3KrFw1DZdS*~D$ zG+<}bHf_pVqJ-g;Bcu}gf!Wz6b5rq-7gR~46CZGBw({B7$4aH+wJ-T^9sg&8W9U4L zuxRJ}g|??__m71TOco-Z`)J(|?g{Byiv9AoYxx%BNH>$rd%AliS*o=AUAo#*_v&5K zBRy-`E~k6e?**3jyf2Da>iJMcKGM5UnSHuMLT9d2suk4in>0yTi?{c~q0?p^!*+@-k`&iUyC5?AHA{P4#z`I5HS z2NC;fLkn5d*FjKAcq4jxwQ zgtEF{u>yS?!^h*Du0|lGgy+;0k!Pr(#==r=>W&}*cIk7+=McUeUxk5{6m#$EQpp|x z0y-;}mN3su8|O%zUY<(k+$I5P!)mr>^{m^_dAKL4Mux5YAfk)oYzEVMl~zx) z5cH#x?!z_BFndFVl2ru=^J!8sxc+sg9Rns{qEJ{Vnw=!0GP+S+ zm>(g-_mUz4<&=v|vCze7`h0@Av_}|!3QOoSdoSmOT(NV!G|%OSG)YY@A)zTY zu5hAyObs?9@X#N@9Oes^_q&GD_6l$`A5arty9Q9n5D}VwuHR-OhJ*-uB25~tv1v~& z2@Ae?GM;a&8j6!6sj&y1;>ii?vRk1*qZL6j?}u6GKZGDVVl`INOj=mzju|wIB;Qew z6IBP9U$I&El*VS2CQoA11p}J}OevR5f?2Gdh*ounCEZ}=Ip9*3*BvSOdRRI7x1!u% z0vvyN{`NJLj^ClAHUoJYPZr%_!cDaYcuMh!ilHm0K zJKjp|VTIEw>0UeU1P8T8R7+KEUkF_lUDY1dT~fIlyR#|*(HS#2qMDf=x+W#1Gj4NQ zHT$q=XHC{rXTrI(wHt}f7HR^GI|6ivIy+fq9Q}#jW^4YF{wn2X#L07~XMvKY_ZqU+ zx#6X1CEMN)pl@`Z#Vmap&ZmDclCa3d2&o63O%5VR&Fd!Ht5=q_ZCIH0YTdn~ULB^k zX%kqees4;>)+n2J;#$ller*?vH3XkYrS8kRb7Bxf@$(Fg3|#B6H1_jh+g_`^ugJgG z8u}QYDMMR4Nky&z`&Nlp>$aN zT3Fv0%&mR6CWKIpblqnI5^x+IYbN}hD}%;n&Kn{4ewl15OWR@{&eTTH%P2qac;di5 zIhf4-Iw@5GD!G@06$4OE`edNJ4cOE?I(d zn(sDB`iaZIb=%qVS?6p2T$<5L>e6+FY#N&L^6=yFC3?vo*|xyxmGbpa+h<@dtZ(q~PX~Eb ze%C6r^i9gw*~X;p zB9>3Vf_BDa_2nCf9U_6s;GQbv#Uf>}OB?~^0ilE^!$RNLhYm!UBtdlXZX^;&p$m7D z`ZvpUK!9LPxxY413rc@%ES7QLZ#yZ*xDJ}VO%hapC&4w+e(bjMQ%l`$U=|5!o*(f050^se*t2?sYh7jY~GV=2*M( z)y3UaMh;=4$+Nowb;Ykbv7GF0CAoLwHHB7H&P{;$2^tpApdN}Ag{&D_q@FgxEl$i; zx~p=^4{^ejdA+jk#%R)>JLF&mR}-i|v6`J4VDPGP`|>#HX<%)=Z*$J7A@~ddxklhQ zV=S^}Y%(Lw1io7i*d(X5Csfo-OCn;62`2{p21#aH80{t>$Tw zcEr}=cw6nWG6ESXZqr^jQ)!j0;4{%)|Gd_*(x$|wqv2(vN89UrAN^=Vl? z0wQ7G-+g&z;I5+YRR4j`o8%JPGW&-yuO!m}rIx9OeLp^#2<9Gw93J%_d{G##^nLc| z;qR2K^nAp9DVl;FUz7 zE0#|QuMuaSifWyadzT_@81)n;Q&aaYO~*$Stug|j!RhL+f>*7jC;%O8N@K|%br$8; zC}sj7YnfJ^XH2u~G&k3>9kbMvU<>9U>$$?E#PvLHi=U>EK1uTL^Uvgkye|l@sefM> z+PV3@D11czLviG*kPju%@9RI5-uNEk0$2Gdzd?-(A#9YV+|dZE$k5!{sHC`G^Q+2n zPs=IKJJ+yTQ+#!6vzD5quvJ%;cYdqBuBKtDp{a9gtC2Qxs4L57`{MkC+}8IE+YkD` zZ*4c9HNh#-hAebXwTvBY+-aTE+}>%M?o~M1{-WY~}d4?h>fMsD|Qq>Y=7Z#EfECw1QViO`89ui zX2h2%{(a7-KpZo9?#F7Uxew|qgTO`&yJmN$Q9QyZFyhcv15m%Af`(d&VuuPfl~|$Y z>@_gcc#`CspB&jsyF#;Ke>jO!z+~Jd6du@%pyb6?s~IQXIzxxTFyT-HK&3Mt-rB<% zZw9g7j53ds;OjC@eAajSSa-69iIs2kO$w;6>-3*5S~Gq_I5{C=JEjr62Kl=91m?RbJyY{Kg%6Vh}!?F@u4 z4-du?K^)S633J)y=8u8fFu!Z>q{i3}bxg?G{RzniO>d;w{7m`k(7=f=2u?N=K=jd> zi&px=TvqUh&Sug{U?_b@GJpsW2-r5g@-e&k;dn6+_$naw#D)UifX!fe^WTC8y3t%v zVmwrMmCg2w9`NTx1RISE8lxpj8!Abh&KScAUoim-oXI+h8Ni0+>so4t3S$le%}3-c zzK2{)QN}ES4eDvnjnCxr)z9<6u9%?X*T8&CDO06!nL9{!Ex!_2@ldB))Jr# zA>v7puYi<>{+eA3{1C(tCPfkUlL>#zyRH^)7wPLTAi;jNRK6Efnn;ECN19H(D{lpV zWw1-b^_dcVzRCwC#>P8LL={e5fiI($U^bC`H$L*D)pnIDfvN+h-6hVp4+=*9a*k(z zP-zWXdHF6FEv3%{1?|)un=9y@17q*Z@}*$(f~=}NdGjzU=WLXN-Ev_w`~V@*OeUOy)s{TtYv}JcZ$F&rQ(0e!__4&mEIlj%6 zsc5^C31FV9l=pt)0Gr-qE*1qS1eD!#C2dIZ<)FvBDv?AfkG#5e=!T7^G`jWTtAJiK z!lO*Y12`lahdXHOD3$!0hxZ1+Zr%?ISx=6yU#dfDV!^;w`tVW>q66qA+rU(P^u)4d zzL;4l16aoo_M!Z9qEF{PxzL3cEfYUK$~H#UGxx z^nEtnf@4+aM1$$%D|ROAf}$Y`CCWNw13&IZdZ9Y(k8mH)S&gj!^D9VOPgC##!XnNb zxjt(Xm1d|*PKv!ZD`_SYxCr_{v+-ud>f5qh2q zyvz&ZAWm=T3Nq>xVYl;x8TQi8eEmrtgFX_kjuF}91=6K#_Rl>|3Yh9S+7-PTvz&D1 zs&WwC>m&g!O`v-Eg-M8cZP>lbYu-oDdGU;)+I1A?o_x?Jo}2>d4< zZ1G23wr`lH{q6&T0g-vSeEVb}ZpWC7NsLEa zyUdB|~- z_VYz^Ehk6R!$tRx{Gy*0Fr&o@lM$IH7vCT6uW#IdkUoWJ9B1r~$UZxS$6ynbV%9$b zcoPU>uWNVY)hFmmFVdby;_Z)1gcy_D7gWiCAUYbn0$zb15u1kSu?g^6y1JZn1E?sF zWt=5o_4x z`$Ny5W?g|BL*7^Mmn5PU{Ge)78F)B2+mWk>;s;sLydp-G<9;!PUTo!&#@}VvFXXN zo6E63$Z-_Tb=JvsJ(cTzJ=dck*Rv z14T{%fIk3bN!42gSi4xgd`VDJD~KNr0^>lUj#g+KsOve+A3eC(ntt^F=Lylq9qh5HOWD1w5 zN{Q~3iG!%%84y1PjAMeJg=k?cRXj8F=nN#F2OU+#riEsk>OkC}myK0`WGEn^X%M>z zAJ=*G`R^EWT6T%NEEZW|s!}0ugIE4l0p_g?vqZ~aE6p)5fEETehS!7#3IIU+UL|YX zxmS;nq$0L*WR(lUrBf>nT0kYEtYs2li)5vbTX9VToQ_}_W~`tG0jD6Vu7Jiy^aCMEyMu>6aJbOdKd~INFh4@~>qxnY2ug3OYjjRmr(HM09wZ@`}rcPaStqrAR2a+{`u*U(Jc<3TV|LsK3_OEG(we4w(L8u|WDCO!n&HR++IuM3b02?Y;O`F(4e?tNj)?xj!t4MXw)YE?_pv6Qaxz)pjn;< zQVXE5W!3_IV6-T2COMnKSf@pkcl|mYl>H5S9Mov;<)f)_e69391^)uf_97tkd^EMrG4*a@D7MH|x} zG#@0RjH~hp@CZ?i69tiet%(ch0{qyc!r8!>ay+IAx?h+zFQl}M$#ks3Zh^|v(RoA| z#<)Zfb3fR&hhv{T1O?>E6ND*Ez#cnf20kf*VMiM$f%~+a*p2BuQH_<$j1CUVy6Ads z7{D`dfhQ9EkZner9q1|xXREPBHCm&GpP+z4$4*2G8@Q#_tbsS^cTXsz4}$BA#e!pq z5UmAtR1qSa3dByAm@;71dmUI(0b6-*t|B_iu`A6HjwGP;rvV%m1kOO412q5^Y~abL zu;B}$0$h!c{BT4MPjvle51Ise^^5n*6AXD9d|VHWv}GtMvYiwGVVJ-_6p%)siH7$! z$)k0Z&_q2x(Mg6ksCz^hbR-PB)oG%#DxL~^llr@wgt4XEMZ@EsR^pT) zIH^w?Q|x5dVpQIv!{|5jA6beTNHo6hC5RD64KrE;22{Wf9~B49b;MganW3lG(IL$B7n`xq3#w;1 zfszLM$$DDkMI0v$By(eQG-UXsU2V>h`*WMMBBVYZ>ga<85d6xTh#xg@5k!bZQwv`e zOv!*sF>ti;iBL40Hq>RPK%zfla4BB*+8Ha|nRv7#b^~aWTH$G#Q^~CDiWr`>m+Eo> z3)0ISjZ5l7T3E%D=L)kC8%>b_qzZ++1My#(Xl%a*fz;tXvE z>4jI@GK??lD8QNc-q=?fdx_`RR0X1)wefgGO6>*=#{uuM?u>2(WTl*U)(uvR)jf-^b8ZU z@b%VXiC1aG3ngfF-C29`k*)8NlQf%Qv{i zChi$&Ca4@9d8EYi+xb@)r6P+}D!+x!cN~UYh>P?3adGM4cWzn}Dh2*O$jbihVs_n6^wN~5XkD+RIDx=bEc52Ve)J|x;KGSwWYdJy9Ugtwqo4wwr zAvFhsA8Tz6Mu$*!M`O55yQ3+$x%#1#x!~D$CrgP$b!ThY>UL+_;3Va^c1?(M`20oW|v)kQCwpU9=Dy+Jq?CZq9MLM<9W<_tBUf_;*Qo!PAo8DKy+ z<*fUpLt*0gr)MgwzgtNlZK^!O%IzQkhAoQ#2DpH0<+^;@RM2I$D}G+rUW*1$xx&wm zkzZ>PIx0DXYSm-XtCRh%~1x`gY0&vyGKOC)Irq{`NG2c#b#(GI+=^}ajs zt`VEgnM}*0J!i5VEOgH1o;=rc_MUH&&bfl1nx1n-mqv7gO0K={2`anArn|vN;O`9{ zJU8|_xcc6?-jLd|B;E7%wKcuF=Np?xbT8cRdf$7Y`LS|{Ic+p44c;=&(r2_iKi3!5 zwVb4PvFDa|?8UxMrxi&gA!ZS%|By{ToB@~Z4V)W19|_)IPS(eHEmpVOjq`>#AX zKB^z_RO>^3#4{tfLFA03?8C_C4weQ{FHZ(NjC$>xY;bihsP^I2g-fFb*WOMHYvzzLhEejH`TkuPo&8_77FqpC2ELzPSHBJ}&}whOz2mh!@kALHylxB^e5d z3x)W<6A&pD0crSu5)fMXVDkSv0U6pj`~QQ0xcX(*{2u}$FFF2y2#EW7M(ckGNay{9 zuJF}~|4l%)-ahGSUVi*v0@6)e8BF0-JU#he0wQHwYS;6>3CMND|4Bgpws7#x*0BhP z!Mxh`Yg*tF`<QkA?JSyi16tDBp^TbR#^n(@uR=LSp;PH+2j8Z5H?n+rkSvl*){0VI%Yhw zp3Wj57Qtu^gw1~l$ho?eB(bX-E6LcT{}7P8;CHEV{~;hsog44c@gs7p8SeXp)!W*- z?#6fYzi+JGC9ui=F9Pz=hqU&;2#AIJdXB3*i-35Xt7j3AtDEch{QgToraFfRrEVVY z3q6%r-WLG$@%R5FAo*98>SgZ*?QVW3BeE&5YH?_YyzkR>^{~{oCHpLy<5Ey0FGFEfW6b|vHun35S;%@s3_Y1onC;pND2XAlw z5B2}=|39A3nK3iQ@|>~nGxohf$yUusLaIR|p&^BmhBg&7_PvI(Q)A7RhE#|eOF|pk zka`X6D$yz_pJ(s)d7tzCobx@Ob1t9d`-^|T%rMvI^?JL1xSaB}+~kT#{gpKMk+8dg z{qjuR^fpZWyKsNlmBE9w+IN5SRkgY*>{w{ZS%QaSL}Ay_Cm{5YU%p>HH~{Gfbbx&` z_PW#khefypX-V-A9%c%A8PbZtOuV6&-n~V}Lt+#IjAv$OfLB~AX@VN z4?AKNXA>C-N414_Fi5u&uB}noD|n-NTvj+^5x|N2G9Ag{0*s`Pc~$;t z=O;zTZU%)D*I!V-zuW20>X1=lniH_(nSH9JLsF|+l8`>g@)J&3HesK1ls{S#bu7lF zA1BhdbJ)r2seSjff9~QlSTj~2WH5HnP~BdhwL~I?PSa8ZkJ(L-xcG|zBp-wAWn+;u z>tYq&K6P5jYfE`Jm?TnWJYCdoYJOD0(OK3*Lux7=lHUw+HB%YbH;)lphM!jEz zASwiGZ4ORBtL>aL1L9((86eHUpn_(bxGMQlz3%bipw3=47x%s{Zb`qk{<2n6Bbc4F zlBT36_K8{Sn{hgSSKvk#uNCy&PFqOFC{50+_MRW6Zqrh|E%7N)di+CPA67`VbBdQq zBgX-{&aD9_inH#%txcPpbT1rU^GOmb2RMoLK0heCBQN@x+MctKj9iwGB11WdJSPih z5^Y~Zmh7*9uv4Ck-O^DOvNIXoY9|;;JA7uPwhLd&y>m3rjWCft%}HS75RgE1y;vkPV#pq)_^3M*a(dUeQ8{5^Eo*f`phxBPn1me#<3zyOt2`zsZ zUTHYEOaKq9VP4~GK5~tdnX#;R^YSO2vF*(=tCqrweF7K1osXhu2YS{)NSbegrXs#{ zSD-&9_Woj8P2C1Um{YgGU0*`au`(T#&^^1`gf_6C?#!`z_AtJn$OrC2R!W7-(;x}gqw2rm`Y0IfQ#Xcv4vFQ zO5U_Q5FA)TFWYtF*3$-l#GJj0O4CSl26vbCEBDBb!Y4Cg@z(@8gcWN^+|MU2_J$l@ z0uBl=aWAMhA1YP)Y$_U?@5-eJL-zR8DL+l7TAPSBgiGzZ#a?26*k&vrZ0NTC>!$tE zMcM4kT~;Tl4{Bg;vxR&H^=?K9wy#q5#INwE$^qXv-ht-V%eshmt#4#rq%V0Y`h3ue z6DR$CnaSr$EZZ+2;8jBubx@9wrSm~=-Kl-Xz?xU+qDo%|Lf8p9oD9tC@=p8)6S)iG+U@X`HM?U-PuM}HsrVTN)73?6ht?0( z>(AWJ6DJ?khbah*sH=OTi%4>}zFxu7N*Ky)WM{JNIt?VQ@-by(`7HyP3173Y53EOG zhExJ*X~r*p3IZVkM@iSdM^x)3sE_pM6;y8Iz^C=vW93H_lq4W%qZEC~o4JwO z1>5&qoJwqMpvK>lXT5d#xb6mYC{ZqN%iB0vHDDm)D&0KzqDCe7FI$aueFi3isg5Om zA6KTtujI!`dlzr_DrVgIFdU~M7eNn6_SYZkfcgr-M{c`F_%wOGA9x9Nw@>Gh*6{-K+& z=yO7il7j*TWBZl&4y}>Fs$Nx)k#y>fjohjOz;0!Hi)q5hcQsHxcy$r~m%^`Qw4>Dd z-;wUGgf8_;yahb*`ltmbE+O}?4XG+CJXi8qZF~F{o?ijmS>h=BcU+4saE|XQJGS1; zWBUxq>5V!YjGfuM`aBz1;L(5cxUVX>{^sF+%=Nuq$OIBZ=#$nb0HTwV;fS=+o7f)B zrKb}SRjs{nqx2L2^CD@}lvsE+PK^-n)n#snarO*ge8a$!-{^{rV@6SC7qk-&Os;>T zcf?U&PW7TczEj#-D>2?3_|ujUSpXvn#+fQb=(l2|b@3l&2bs4u2jMWe* za02eI(z$Mxam_uWx6i0AKclTF<93SC-8VAdzGtXtLMCR2Je@$H5n(b>sxv)}kChI< zp@O+4V`saftPR)^$YR42Cwzw?3LBx!q|*diln5XRGCubKIqpf6>*MJsO)4M@7LGzc zDd`3YN0K!nFlKrgsnyy(UB+shENUYZ@dc4&!{|Dd%3(yI;Dlz@!6YjJ{fg;3r_3vw zn9{y%y3#50RIQaP#E(sc7aQ^Bn~5kGB{J|iJc2xfi1PInM4-)HYN@Z~A_k7Lq8}X~ z-!wm^GX#CHWPG(kBvBy&W$<){G9TJ@82RFuZLOKLjhM{-VX`tP-1!4hZiU{C6lyaNWiF)bjNHyH1Oh0g z0BVnd)PzNsYqENXAVx8_{Bx05K;AV2#Buvl8V6ceQ#iNZ)RXF(r ziv`62&Uv)ayhql>Jq1PZ1TV^I=M!SytQYd66$-LM-lrDd9JN;md9Qv@R*R5oLRO+) zvceD>`9WSX7_Xf5(dAEczPs^f5}a#oG%EU~B!$x1_3IFtO4^OBG_`rM!jfQoo%CsDl629Z%F zf8RnW5eE;)PC0M@yIO6(5Asob$Cqyi`b=!Uh^UF2PvhcTJ2So6=Lv2^H)`EyYvisE za&b9wfYXq61UV`Wtoli~9(F&0TL z1Kchwhy!sJa?KH+Eh3ICww*_qL_aoECB#xhkd6(qcHXjVK&E*xM~aM_b8gx*l>DU^ z^chwhPC-5!UUHuRszpes3l>9zW*!%<8O3E5)>$Et+Y@A`0R3&lx&kdv5{RLfO41uJ zX7vQOBJ<9A*CK_@HYXKopg@&`SV&z^_k&m@-dHC|+c7Ivtix|w z*_j-Ze`05?%*Xj83m(Rtjggv{x8`B&cVBj$F|gXQGYRfY+LhYjHJrPgmT~Eg(En35>Q*Ol;LV(lV7L<=x~`zwrD@lt z?c1g6+O<@)M)F`+USzxRLKj`N+uW{usc*MsbhlM;w@rJu-FWxPg>HswkG)-wgKv*x zbdOVUk4t-x>v+!wOO}d|GSW<4?A(29 zLBs4x-}b!!|(bt;;xk083g+dY@y&%S@^vf0}TrU z0tu~PDpaa^YeQ4{4!Q12+~in_Bl_>xD1In$HWXRyf~SG^Ra`M#w@Oli#Sab&yh4iDVV~)a2kl4E|!) zNkSRNb_x|(aMJD}lKT)T0+JPI$qB9>**;8F)6}>+Y}BtUIz%tR#Q+`M*JDKMCkla+)mj2N9 z=|lft57}yuP!~1G@6pbfM9u-qQU4B0#Md|4x9`w>7`L|AzqGX}k0{0`$j${X>A> zJ^PyjD~u=oabRbk_nrFVz_xyVJy`z7fo=Qx4kbW;{mp?Db*C?CoIUKdJPhl>(>Qsk z<0rpg{8g0nu`Gr8xx?}UC;>X2dr|*$uk@l^h$vRE0|3&J7j#S<;;2t!VmJH~0V-u| z_ZIXdYv)=$CF)jHYwlYGF8>Pw`s2W6TD_`%{_hEplWt8#gsCa&z-|i#|Be9Z0MF?E z!ht=9ZhS7)1jnZh^mACUV|pN2>Td*SS76x*$24u}?EfPIB)|LpKRdAhN`OXo)_u4< ze(>FgE21Q$>6RC{yBm^z71uRvU97k|eRa<-40q+sqjdR|-(KyOhvvUMdH8op^|yTV zLsU`~Ug(rqg-WXWFqhN)$AR7Y$>sDcW7A*$a*J17Xn7V?vmamcvFlBg_-x1VF~e1Sz^+pn<{8lnDON?jCQ_+zE6ewwf(2#9Mj*%nG9l?pCH zwk0eQwVbX zYv|?Ex}PaMnv#I~!`O|#Z~n$vif)%a=L0JWFft z?jg<3YDy9*!m#tw0D7K6M%MD6jN3rM!MRV$yEAk>ora-uQ7CaKjU$3Egb8OyZ=M!I zD7D0B;-YNGl{yo4B58sF7Bg6k{4hyiN-Bijvw?XSGkLU4-N7oQJI-lV+n!hUGfZsF zZb>t3^C0KjqQ`53vt~6HCe@ux84%SRduT_6m*UY$M-bgfX0r%N4T@_I;5a&@7T?bg z-o)}9E}Sf#2fx*YtMj>%u$cw?fIE58Wq!4P@2S&AkWe1qnH*>K$2sLY@`JKZJ)YDu zyj5v0KkSfG>-+L@Azt>OS^!mbyx(9)jR}Iy1bN+l>K|rsfuEYv$G3XRkpdI&cKno^ zt{Ri|kGf(-^pkKZrjMt1=SztjZQuKyZ=>Fb1HK8(x47T*#t&nDhrNLVOEzyZa;gZGo{1%>7&#YSGN z!Quwl{is{Xdi#3Vc07{0vBSV5&!^238%|wVYHzl8c``oXbgg{6gML`yOc#^G z-mSfEvGtSnqrSW6C;4|)`+8Cpb(~E5^$?n(2+PPZ>YnCq+>~HXEui8K;UJ+AK4l#H)Hj<>Na8M-LaPH{1u#X|ur*oec zHifOry(p)Xcq4!oYxQ8-qBcgy+s1lro|2vZ)gZ$+;eK0(d|NaXx34KCf0}z>HFsj$ zPJIl(8k>WjwWelKte#i+Z6>Xn9O)|kW4o2bW5*)e;2INE`L4c}7hHm*x=e^PiF;~t zxk6_?f2w)Qc*2Gkb%6n$)~m;L)}AiAgp*to_HkWc{j-bpl8}LKgAq?!#vycR!*Gg* z@m5jc>8jPMJ54N9vfLYV#LQY6BsnBN)z|O8Ze8KyHT2X|cK=O4SYrePX%nv^7th)} zeG~W%vvWdp67x{jUOHnie)+zaooChRoL58XOD`zZ!kxxD@spP^(QJrY;_ZLgEqJ0L zo~mKRwD~T<-5;LVbn3vK()+GN_Lr#I!t+Z@tazbu{1nWc-9euEZiD@~a95*ADE*OL zbDYG+$_59`PVWzQV>u%9%X@t7`O|N`jN z)gr8l6?F4PQXHotvCo2knjt|$6!wol7bnBN1zj%;?F);*Anv5vv4mG8!k4D_Ez)9> zT%Hm{5fcH(kewIdJ@>k8LbH93y4+}zrlkKJ#>KNz++@u6YlgaGQ2ENQ-L8LhKpYc zHlt7SU`LL-1Ri``gZ$=l!y>~yW}|fQQR&OY?p(%pZ?|~rh2&tt0?%}PcWf}l$p>0b z2*4`oBQH^xA6hYp0n@`ve+|abTZ~Pbw-HK@VLPQ?1Mm|);m2{B9yVKImEdP@+36@p zE4NOI-w$|D|CLx{eZ<2lF?`rcx|}|IMb@(08#j~?l&^Q@l-#rjz;MB8^ef_Hj9gjp zUPV1`UBsMc;Th`(m%<79h%R-H>T(1H4l)0Z0OjYW7Ph1okEEWNOXVx3m06`#c&AlG zr4i-`CsNYxz}P4PP`sHoPzKX^@MSB+NjJT%CB1zl{n}i*P%)z`O7U^x4s`jT+ewGU z%eYB_eILs$@5^9KW(+$SKk&}%ip(4#7>~7NUK`G|Wrl8@5qp+TQ{mvSOzcrQ*^7>( z0{(0dJJCO#IGK9Q5R2(rf+)G$#Rm=RkIz-OkXKSu+ODq=x7xY zNC}oniGb7=ScjjFFSXTSY1>`IQD5iT3_)$>b}Gne)HKxNS7#O&wODLydN8 zNI}-8jQUWch98B^l%ggBqvkC|g2 z%PHARr4qjo@=!t6ur)Fin%9$BQmu4Sj#WtLEWj-?PY?DNKR;YjbGT$g>5RtVGn1_) z8rH=P{RJ-yO0cvuC82q9#F9G&XGPY?`hv6FhtG_J=6xuDABOS`OEE~JGZ6BZ^D*W% zWb4B@8fIARCye`H8F_IpafA;Tkgq}kzLTdw0KNhXiYO&P3DTkF%f)6-?90M6p2U=5 zWf%|{f%aJ=k|Lfw1J)kgCm)Kav$MLD3X}y$&{iApZPjNAXk6%bF0xV&YIKGb7_jeU zh*emO>&&8v_}ETI*bVM*MqfA%q3Fsx4?1ufVYfjBpbX4d^(x5N4we!p{NacU?1cX@ z8}iTy*@A;v&dFI;K=EGuR*-3h(RuFQN7xoDL{b?fFCi8WCr z81Z8?!c3B`8+P6hhGXl+$@L~?xrwdF7k#8^tjT|3-{iOQmEvI32H7ys>^1}>k0Mgm z7%aobRkw)^o-3b4u ztgCa&(Vt}OO{DVZS>f9%qSwS_FP>{0BRU>30qh%Sh>^Q4~`4W@0$i-ZeF?k&DX5rH3M zAWsKn$P$1&eqHk=IJ6FqII0)+8NYD`Yg>wQWCpKd;Ib6j-Zh@XwqneB|P z)wDs}eC_hUqe*2Va*l8+J3{jF~j;L!-gHh#!rV$e+|>s?whZ;zx1WweajDO zO5o~a@pAP5$oJs=(pa22>4C!sEh`cwmVSQL@Z>7L2OCys?MFYW1=nO7mu>p>fD-_3 z@PR5N$a{Cg$1)!N*90ij$)@=6zD`c)!2gl}NyevJ{of=&-4bW}BxO)*;-Bhg9hCfh z{g32_HIWl9t@6K7KPNdI`(M@1C05)2L;d`3Ze2D>aa-Awy&9D!3f6g|V zY>%raE#yde{zBa!@5jBjwWe>9h^-V9pG)?`>Y?rgPY?r;^G1a0w+p zCgpA6@AgzjAMSj7p4vYcOy$3<@o{{}}r6{*qDiMSQc!`S3jNE+pZ%_SSb`N8=>|K-u*fqC>%k8zE z?`iQ!BvpKOvS;t%k(2BM7GST%530oS3jSXc(Nc7Z5{WEoe$9C@VFgb8>@$8HB~FK! zVi|*3#4a-(f8?A-$X^tzZ_D_W3s*i?e{nNkm6+21Zk7KT> zO_&#-Y?b{@QfaXY@bh{@rqOv+5~q|=q1Uax0f$4Qe!?PwdufSP9Cg`DDWxM2TvB63 z;mNTK3a?#@VZR%QCMZ|(WwDAcq^K$J5?(iNm~U7ERNhm`IC#Yb)1InCFIUaWc1(K1 zIT5u${Gvz!gD>4uU+o*X>*LLP{Z%sU`1qu19QtHwke(G4y?v@7F1D80#FZfkVQUtE zB!Ylywcnz(G~AXv3b8|`ecej9~_h%8z!{_bJO)N29=H{yf@8HzQ0zN zr<84b<^^V{tl#Y5mdo2+gMhs-<+&Am5vU*eth0Bw?uv7k*9Joqc1wKmed0=qCDb?3 zT2=I)W$>Mch@dX~f5_#_&hOpISi;P`Og4k?4Z~Qs%&N8Z zmrSw4kG0f}9i8q;&m&H2^+ECs$4ujkyUn-!g<LhH=28zn=+j$I zpMeO*vIg!Zn>Q}0af=(4h*zfb-E6{=&5k|Qf0!Hdq@3Z-*0a8N&I-++SbphKClJ;0V}dtBGVO| zPOnepv0rU?RXQ_Cs|({9>d=b$fGFobmXuwFzm~RF3yJ-K=QM*+Z2{oDm06bRM4FbN zdt?ORjg>g!7k18b>$bH7MNrze zMn5hBkzeu(ccfR`;Cy2yy0Y$8_lx$cU7N~}I18l?W`GYVt1iUd zyjay!zj{LKUfJW}U`Gk4GSk@B$wsz-x&$V;dkTKY5V zH~eK!}Y{kc31yIM(8N%#Qb;q!QXsCmk?N zG7gZ|Qvl(M-cD6-1LMQ@*m-|lW(h(*q_Hck4z0(i9eh5Mcxt)BP>2#!&tHmqPsgWs zXY0X}sUN1`fG&GKF7gFe4dXW}EFz8^R9=L)R18J@fr0zrQ)4^P7sd zsrVzuI@ex3QzD@(^L8f`Rne~^?sBfh@xkYV2@rSJ*~J?lw49{Ds}0|O5NK;q+(Qok znd8nVd^+vbc$sMa!sGrEf}Xb!wm%Mw-X_jw-n-k^2LWY{2%|SAy!+`#ton-;PfyQX zG_r5lQzY#$vq|q0Tm1_r52CIaaQ=0`xc^e^jo{$cQ|G-n+dimYI4ZK#uo@#}-#N8< zwwi==Er#!KiN*Alei%5ramA6D`H?Hn2tH0j=4)Kzmue^b8CFt8-d2fuv)69Lp& z$ovh<%{P(Pe0k+A+A-d-PvoPy32PoMm4EXs*oYxkb}FouwQqY>7e)5pgF=#ZIk`Tgr&@ghHZ|O@Uy;vd#P49fNAh0h1Grh2r^_e^QO2VjE^uh-CLDGkVifA#+#n7nRUOH zme;vN&+>ve3-<8>Y_5QcKM0L9&)3_-h3P_ zSblV!6H-bIG`^qmDasxaE_<_m#U%xe*$Hvwxp+Gsa%>r|@00&_i1)Au+7qw2wI$2Z zUED%1>n}JtU=|u*114`m&w8?&ULR9;M&jfxs6UMHbZ6xot^pHkw=d3sMm;S5N}{8{ zCeuk0L-sNw8c&FvwW2m{gSM^X+1ScRvGS~xu)t%>>3g3%*=APTsL_92vWRFV{j0q7 zi-m^KCeasHdWXvGxfn*}M!Z?=;z3+RF325mx78nAw#Qn|cHiEp&?Tsmf8i85We12H z#C{Otqk~-~NRLf5kzdX*<0N=8UCbFSaDdt-xq>r43iwKeW!8liTMDZV7giS(*0vVb zj~1fXN1#;HWL<<}pUa1fD627kkKpZzMeY`O4?5Brno#kkh+)C(EhrvnExtWkeD_E3 zpi;?j%@P$Jq{b;p(_FWSvd7sh+;2#(Bb7F}I2v-_KvoGI4Jp%DO@+`yVMZ80&DR=t zmR-V4d-+z*suDt-kZ?<#&xg;Jk%=Ln&Vn{2HxA-5=;US3$Bijr2;d+F(F5C7D+~RyOSxLN^F3p z1OSPe5T0$Xj9^^pRWf7<%$!j*!)zyj?J&lgkyO2zY|F-2b1{mj!NE8OLm7C~gScOC z)C=ckL7QJB%8&g(|F46rJS!;^P_|2rSVV~??VPC@=G(dGco9B*fUeAfU;iK%??P;l zvf?sGi3L{4cAlo;55Db zw0#{M6m1#-ubZmV9D+3U<0!};Nnw>F2T=HsGQAR03g98YY13~rL=mkfLs+ilRxDOp z5RrIZnc48T1`<})h#s7OQ47gYp(b(E0|UAh2A|R{NIVfp{S+W7jg)t~)AYt}a%DG^ zFaMLG3&M!DWMM9J?UAOo5u%umgzOSXFdME{HQ@s6!_$zVZ;cpQ)5Aq;B+dNn!c>za zS)ei3B(_`gp+OC?vk7K4C~<1UXzO$Xo8gF>Sp%f?AYyatqT#w`4D%xAMXmEsnL;fj z)3I7P3r15>14=awLQxz>;S**FL`> zQ4&^(k9L5bwY=TmD z$ts%{ETx?@peIRB9>mO+7?jfV*f5O)TP~vK%Jn-k&w>3^WZBFvk{hPSrydt^4e;^W z5T0g*P#9&{0BENZ;>AINxixcJuZq*+MEfsD(r{35DIvBjZ4htjLSD%yd@3r(LFIlx z{mVS%jSG_B)_4j!PirhC^C8+Gs6LA1aQKwYHU+aP#TnN$F8M4KL2ncmlFn+7#4*ry zFvF)rREd)bmH|W;L1zrV?JDycwzTKcJfo3B(f1*fYg=<~AqNm*o2(EY0rXu+-Qu8~ z(}ShK4*YH(SHz&YiEPu2BD`1*K$F1zTuc_@iZS!L`nZCb9fH2o{up4KCR{{M8b?fu zg?Hd|ty+ZeX~J#_gnwhWMoHKulSSxK#$|>f=={3__lh$XpsHHn`|EIkcs81Qivwv_ zq|_Mp1u}jjpjLb{914rFZ3i>$azmHaF#B^1#XQ;|Not%QZ$Lbv@`@`$5kM%Jm*4|$ zIubL(mlSnlB1+S4Q>#hsoc*^byxYcRx0>tab@x{;7z$KkTb47gQe*GpIUwS6Gj<*9 z^Q61L7LnvZqvK8FnMx(}ol>noYhAhF38FSwmt`dLk+>m3yKiY$MH)2pqWA7T@}9}t zh^ETDy=@Ix^fgt|@@NaJcN9_-?N*!_(hInFTNQ4S-ScdnEYy5XN*hsHj7CJ(j-++u zc{5#UYs8GBi-|aA9C7Z@z_~Rm7@ZL2sLTDH*1f|?gBvFXRhdJJrMLDntEr#Gf}9R5 zV-c74w!E^(6j;mn#>wvEx2q^%A7z*nF_r>`+VWYC$9xIrS#gK?NQ-E(820VaNFps+ z###)#8VYb2${TjX%QB!~eI#wY$zv`_xlSfoM8eXfRzZ&+kXJ9ff}|L*tZ?W)jD9q_ z)E3@13OIUQ2kS9&F7lm>3k){VapAUiy&^Ho*_f7JGE!K5bso(gdH|ax$Q&(={-CpT z7}gVD;I|4sYZ2j!LIoEYivjFAOL;5SJuWjI=SDDO;T|rgBgb8yI8Ky)G(w8PnldLq zZrX4*?ct=K%+Uq(e;)n;dbx-Ui(Wian%y-dA%9y%DU7Ovjg`U#oc-u0E5|`!+tA1M z^XAaqwQ*8jmdIapcxSR`1Km6G10m{t_5)Y%*O)ej8jZlBH*8Qc?B6C=wvqWbQ?%Vxl_wWdB<=fN# zZ*z~m&7TgzgNXtuqmh!qD;`xxpS?Y2-a?G1oN}G&rgX1snCc3=*&t=2%bsf7VB}|l z*!#Y@^xIIS{av5=)V1G+Vyf@k;rBhq{-u7t{p|hS-|s&WKQw)6JZt))ek$_OnGa*v zK8!#6@a*>ok^1!H%IO#W)34AQZ)c{bOjmbYo6eoQHNC+g%@4wHD(6){^6a5`V%3AR zj~Nt*svkEq{V~350uv#IUDQ`V)=m}8oM>8`%NI(W)K_3Zf|UqWqD$t2o=IR87J8H7 ze#6i#T+3YZ)ab{MyLWQj^&f^)R>f#yD&RGX{*x*iG|lT2`5@g^zt0+xpN-8V9?oFx zq_tLFr*u;h^x9=1{mY7NGFyaSOx?d2%zlaDqW8MKvNZIiU;aN5^| zZ8}NE=RC6K((Y+z{57}s(;RP=w(+VT{+d5>&;BU9{sTSwc;@f*^Q!rZZSz&f=c~`o z*Iu8m|7*TsabBSDvuV}O=50SOAOG2M_GjDmpY4DBytepLsIkzsYN2P_Lhtc~zOxGh zA5{|L-Z;56U4H~A2RGf>D}eX>!pBwxUtbts{Oi}V#a|+g-;=9;FI%jAu~Ee^=J(X~ z-|zqWJ-zsQMq}~Qs>Ltc7QY=|oIATX|Np*zHoQYPR`q{cKPRbf`Fs7`TfF7-&buXl ztDnDw3|Fo{>sWGRhs4A4e%F(p9uRvsg4WM}_5M0_5UrnM7RA*6)Xz6EHU8Akk+1Ho ze-6>Rf9#)nsCNa?R}<{eWrmU5WJ!jXZ; zK_Q;bfJV)wx$0nUV=|-=Bw*q-66p3sw0^cHE$N}JmR$Zquv&T*Hp}e0y>_F649O7U zA{&Al*P!*YnWIv0MWdt2-X62H|3B2voBpTzS#G_A%fHpn3hSw{8`tVw+T^iu%`#8V z%{wl6Zr+x-tnq1J+l?SE%x^xuK@e~xT9sX`qmo}%vGBU{>L15G*>3}pS88Ew6|CGre9 zGx~o`vHV+P`{sV#-)2Vtv&a@Jk1CdgKas73<)4{RNBymMGbdEBYz^h2k!{n?E&qsY z6^A5H#d30+a>G9&+y7j#v=_TUakXsq&Sw2Zc6%7!wwo<0aMF|6OED@>~TFqxX#kZ{y!L9sjfMdE3!Q5gPWo`uOj{|TgOE%GTo|8y!u+Pj9;X>Iub&NZ znd^S4@Bhdou5QaTvDp2PfThPo%reDX!y*S=w>$JQ^s61>$;o^+xa3%G&y!w%NR4vK zfGMCWJy-tYOG^ClC0V!5KjtiIbD2S^keGD-jq~5#Amc?u*twasKbD~gI4KO3_vfQF zl3uhA4yCU><{>5}$xe8IYW%Xd9vDgr+cXeh{p!P5026WQSZ_0aGCEuiN3Wm$03IA; z!~=|kEEhSx>e9vc!(yz1qqv#|vSdX27u%V>mFA3T{bnh~Wz``%0<~U0{qfUn($<01 z%?eUrL`n$(L#lSX4u*Dqa}0AWgN^TesTN(5q$&xe#Hii! zQ&;Muqd(Hlr1wpTQ#!K=w7Ax-ikJhJGLo^PNSVV=FzQqrSi+cVWS0NjGQ=o&MNlGT zBKPa2NJxC$F5h_U=iS4KqM_Kl$Vp z^D}DG46~XyWL~FckjIxOCxsItoFS?Y)0y!9h{DzZ+Ka-lrL!a`E9@L=~&%JU0{r|1aO5< zZU3;-FW`vxE9*GQx~Cy@-`UM^-~fFUpRuF$!ToDHyUwFA_;$~o30jCH|E!wHTf-{v zYm0#gFP8Qts!@r<&w9Nsr`uxJmJE9Ayc}36;23F_>5jIIZKB$Xa`o0S@|3=iTD;tY zL(Q(<`(se9%k*JuO|5(9c1vOhU>y01;|BHUi0QX&elH;DY!10|?HKN(E37AwC*K@aO=-x6+xhj635XIdgIN&wpv;L7Bh{GBAEBB(?nL+)o*Y4uwA7Qk<2p4bp zHtr3~8yIAbTiwET2Ia@@YW^cr2Kzns^~rhl#>zTa> zR~>I`mcneT41WJc|0ud3t3tkDAGq0dvY~bdJ!*52bDZ`Ds>qb!^CWvZ=@)zC!?C-n z)64eeNJblmOEzkKvL+h8)>IgHSfl$Hg!ipbHMJh;49GQ}O3=D_8(uV6?%X&z#kUkD z0M;eb{mggvQZKL?tWKgOCoX$YihH0SHUnZ4Vq1hS`X@jISu;W3W6e$U+$0_CoPAZH z1gp)=yB_|#fE9I{BR2uEVsOO=cc}ha(-z6!(te&}DH}@PCHCz6=*MH5sd-z!fmaO& z+zxdt@!)nzKR8jGv=4WK#BP4zm$x_R3wPQgrLdMr$6bBHz}x08naI>i&~xJ$1*a4a zFGR=PBxx%suZdt9EH_)0rd(2#hboqXAtjT(MsBCRmyte2$uTB7rN0@12T^9U`X3mL zJ|X;D{inelPwIwb@%K0LO!r3!hi;=6NFt#J=a*mi#Sk7ZemwCge)y;wt{@~V_|8e> zSoETc7X6jyaCnFR)f3Y~tWf{iy(%mJHH5rVQ4|mN>*WU?i2=^C=yU*Pgvb5RA>X#Y~d?k!m?Ld24lhfvnBMC*;tOGi1j zg}>PBp(lQOF;?9IG&SM1y6nY9F+$_$ioO(;h+=i-CiEnjPzYFv>eeU3(@%b&u8 z2=nDzvTRXKOF(v@oHk$twifsQg#j-m8-y&P(VQ?XZ9LUf|WyaH5$e-0p1iGkC-Ymks z%1ST!+X&^QPwA44glKBUz+A?lVx}5|-HUF?Q8V+Kg1VA3bGo4897P~X8Xu9-Fh7w$ ztobVc#8k_P_ai5!=T5ws^v5(x8O%z~MClwy2kZdw;A8^MdQDoS#w?1Y&_8WEuY1!j zHKALIsD{W>?Bq$jAWDJN8*fC(Ia^tfg&l&_MUX5J zD6_LjZbs%rATbJAEfRtCmTYBSw(bls*A2qcvovb5aTAc_OqNn;7L9jG4ebU2So@fV zcgxm|2*N@b8`R32!Dwzy27@phfl;9G&SEf@oFKVum~DWl#OFxRA`8BY`OLtYYjK*d z%`OH~syE7XX|eF$UE1ZQ6fWHkq9xI|NjyP(do9&44LF zV3}IbYsFBdStxOUe;$4I$i*nHd&UGgI4OK2`J!0*uwM9O0OlvuJIFZ@f5*{%`fbHQOtx{(f*hZ)E- zVOJl1NTcG|B@>X%MbpTwmlG*A*bQ6JUA}I4j z_D-#NGK#pd4}zH@!Vn(AMAur0XV_?D8G8mBP%Rcf^hO!J3+ft@VtLh=AzTixJeLg- zSpYClo-e*r9CSI?b~f^HowY}*38%y08&NB-oiS#lN2)uU@^e5saSgiIm;)w)nX}BJSGcW-7L$iCBPHViz6qCXvL`j zFD}4$C{lDzwDgJSi^21quw_-k48NysXF0; zY)-erH$t0@($$3JxY^U2Y>QDBwx{J1-t6MiqYC?K$!4wD@$ty&(93d%i`8Q<$7!vM zODjsFaSG8D-F48Zqt)j7 z$^uKPTs!NenQi4M1?ou7t~#<~%_(bV1JTKq1rTha>j=EHSV0}d+Kp`ru} z6`x3o;p2>KbdFQeheXX?=@ki6RlqX8>g`q)hFou)N-o<%bH?;HVwvB6uA@JH{5N7L zKTvEjaB=5AY4ku@{y=%hK;@qi%MJ3!bqw>i4{kHaYD-f`cD8OG2f2S6*~-he1&Yar zbP3np>aSERkh}di#L`6t@(K-}3akYJJP4=i{n_0adTxsW!CTu?<6=d2`2L z657;O8KiU9Fso@XU-e+eU22%u&kmK-^8bif8g`cozgPJnJES$4FJ7gh2;Y_Z1F=+C znVZt7^hDW&!c+Zw#L}W$Xh;P-v#f0R)IZrx@Mh=aIgTkD^az}*IK>>*hXo*w5Kfm0 zXtG_Wz6I>V-xCl$rA|I!LwrD(EL%@hM{7yB&iecLUEH@i7n-PCA0`AadQhb60oFYz z5FNl2-ewVdhIisj5xBuzecwtrf&akAs}n%pHg*aNm*K=7gR-|3W^^R4u_afqA*~Ps zz$aGK3o%o|sM4UyRfQ(+R^PhQUSn2xQ%Q9x$mo%_8V}|4YRv54Xpq64<14%DrL-&N$wjJ4y2 zp1vdHnSEtb3AYV~dT&_r5xXchhL11g3wXjpTKqjbvPHjU5vvueQ}P9h&OOsQF_Ehl zQ!rpi;R!9&sc`Oyc`Ci%0E-cUO&*gUoe4s);usYd8{1K`yeuW1JVoGbiLfY96ZGfQ?jz#2hhp`0>KrK-cZR?!A=Lnl z=;DMscBIOkjaM(nr|>Y8!gsRDj0)nVon8dfr|`f@_&j&!Q~Hej1c+IZG$jIsbi{!_ z^ZL$=={Eugxcn}?ygBd#T=Wz|ZZJQ^bIo91u{wZPBcLzd@b=!14)NqR@Cou1?Ma$i zoRO-LdT-j4WZ8r&x^lt^mf8I=nssV=*_^a8>@MZ_CzJD^%&vX1c=pL^`4dfP-e%3b z-R^n&$ZcI z+uv3eF7BH{4((sFcYi%|{AVECX z5KA9T?maKA!TU0}{GF%tV|a7&C(9pZ&Ob&n#758m5QIoD@aMbeFZtl-|Ku+EpU4OQ zd4B0%+(rL|eDJ>j)A3C^$nz(_zFXTj91&E1>!uN{fmf~0MWbaXHjSfaZh)0U zpSM-p9*2>6xZ0Rs`6Ug>pj!15b9OrbhxiM=340&{ygN6~qQSLP9)#^V5qrV#7JNNt zLGLp%-sc|01CYqMI3Z(vk1cLqW9Ng_pYGc+J08R$jJ&;Ww5G=KTV9D+*>&prl&%(^ zdh1!)`FFSC5WV2wmN8a?qm5lO54A=_oO0JeYE>`IrtA;BAdUN5FSy?K2YpCQhB8Zf zqNo;2BeWbvtBD*u+Bgza5zn+f%!HE!@mGQmZ$w20&EH3zUVgk%4YfDq3t#KaZTMmQ z-6Q%gFAc;2nUuHRHg`I_KN@cR0>wTwn)$_S9fELe4S&r;b$-|?oliSbEiX>y(x8yp zAXn|m!ncnwyB@nfZ@wFlOvAaBe0y{Cu56MGy65R?=O?1bciAwAA3awRmd-;x^k)3n zET=01bilX3E@^xE0iC|}$0$cS)bcjJ1vdKjbfMNAxaRV8s{L8OPn)$cYeuLp?x&AY zeGw88@GxGc!#hOC%oh1bQMM%zX5;=0)1a;=dkYOIF`0yQ zeKyI-wFwlvJ|f6%mwrT7h7gRk^sud5F(VjE&HRqe#IsLduZjqGO>UI_f1ys}VBE6%niFHGXI~*KjmA#TMilE@` z7KrrB!AzFM_jtKPld-k#H5s44`*4bZ4-~AGeYHQdBZv13SVbu1!xlF3f~{*=Ff%Sa zNajv#UFs@ivz;f8m!4!g#@^D;&NNh4M;EU%w?RIT_v}Rg>%og8QPGOB3$#uED^9LI z`>MT!Hp#h;gOHT<4ryX31K;;Ob|C-` zIUlp9b)PDbaVY`9@q%ycRDiya<&EO2Hbl$?jcN4Prf$Xih+^yFR(&BbO*u@+TX3qi zTV_+7fSnZPD{2igYZT^hDkg|sLR5Y1?T1h)zs{2f-R;;KRoUq|>VQq=33|`16uk!? zCIt+hOELB2Z^o28e7btorIm(dsse4PA&;^}jfE2A%98s}e%wMaV1q7)eQ+ldRm8H< zfNR7=>MAqu-C7F!3~}D^%p1<+`;W96?7lsqw|GmmB?suqJ9p~S>vC_Pfu;cl7D#51 zRiVV42`}$C3dd(j7x?S(*53-;=S<%3p1e-#afQn_aex}Wma>y109uKKrKDY#(tFEJ zKKC*$|Elwr8~yj{m$BEYS8r9PDqnFkYCEG#(&4d8=L2h_N3s;1* zcYp5YXgySSrs*7A9dEX^%}q6*0TNAS3C#&-_jjx|nI`uUtN=PNe&yKi%R1@;)2V$n z5sgq$InDJOU)^~$%91y}a`O>KA^Y>Q{Hi0 zML1s?SVid;{rs|;%3G~7DekZxQ!j81YqYOxO3hlB&x)!ZF|SsN7CQx81Y_> zTc-z4f^EI*X?;7v@4c35EPfMNh?0D6(BgveyX|DJSE<&$CrUPOLK~?Kwq_}pm}G#{ zJ^Yw>sEK1%_0e>-)Fy}T@75vC57#63M2Qzc0Z$J**5HtXVvlaYq=F<}uM0yHtR(_# z@MzrGn~k#1%O&ns)5y5=dGl~MV*Ij{ziv) zjY*WX#R>{JQ4(;)#9iZ(Jvq_yosuDd#6`0k5lc=YjkKLXkN1sdN}gDIZMBzpx)a%Y zZy$~>M0dR&j+$$5BJKy`BuAHwKO4nLntiLOrp5N7WtjDw;WhBy|hGCL_>a_%{=e@yeX z^4do%I)rI`Kg@hG&5=sMLeIH2HKIW113^!yrl5Tn>2+TC6!}@xk#rM^p>nc}&X$Z- zxDD>@1X~4wuAlIzRV^M@o1?Adrv@JRK9KiJo^xcKCa{mmJM`{{!?lwGD|=^|1Y#E# zN;#Yw=XjE(J2PiDOx;E!L@*0yo}(t#O`orC{&pzcj zA!X#qt}oay-}sA`U)E|r*TM0Y%HF-L!jIu*GS8QwLJ~X(np|LV2fXy?3+{6hWqBbp zdn*h5aCmELyWmWrY-|qW`)tOw@2@v6e|xO#L`TZ2@~zk#6~jl zIZS~Trr;=3c##Q9vqVi;;_fWTNS1UCOSXk2Kgv>EWRay~RZL>*>tz8B-jNoIRmLW% z!z*)Eh$7G-06e+yheIz;I})a-XbSz-qLkqPcO2_7v8`BdSZEi$^NWVW!yFHzur8fr~#oD4l$X2>$g4@RcSUJl~QF0e8q z7ULYJkptSglMYKJ%5n{m-FTowoNXjXqQilUiAc}IXxTmb7#?70rXcq}Hpp*hIk0p9vrG>1aS01!JLWJ-oEX{KUBQ^mslg&5ZR zb4aFr$!Kd3m6^N>sr*oq6-X8`h^CJXemD&GX`0{|DaiCz*#N|mO{B;$qLk~O0>j;L zV|c*KAx)5){L1~;aQsFjN`ej6b|-2q9>$YEQ-@&O1j?TQ3s92utf^EM1#>D2&tDTEs?0p5WT^Er}&o42;VR_7^7s3i-6Hb0YHeGhTPgPUTMl+ z=?D3c!2{$plon+SXD@T`BF+SIR~DuSSTKUkwBUn09CFXYc43GUr-(!82$;x$fTB+c z%%XG>;!R|o&hmpf98ouzkOGrTxEX>I&`T9I+KaF`Dn)`sAX2j}*29R}(49+kcmwa> z4m+~XqPk9P`6?&j53@{TN?|iaI7LD^3(AZ)C_*1&2mr`X!V9AW3fP+d63Ff9KPxZ+ zuybKyCVYN7+{nZ2QANq{v4X8|py??r^{8u#)QViu4ajhsbBZQ|4wMG7*2CE!qy7Fw@Ya^F$=&1fza#fm1_H4W{Hu*MTk$un=!AG_=>W zEDK?C^Znq@1mIIjVa(jg0e4V>3A$Y-k!TtE)+i}P8e0=g>q|T4z(JS8B!QEtI@zGe zQ$hozNfTJ44GxWjZ>&y|qT4D^kS}1)-nw&+nbd`(94*p$Jtjvpv-rzc0g81p-kqcn z;wvX>B7@BEIaylHsPGoB*88GIoA`WKDx?hAJ%Vjy1M3f!`kIN0_CunVQxUm<77U#^ zL!H90?9Ie9C@1$#Bzwt{NFJg-W~4nWyTY|eP2s+x%Y5YjVG6+Te{M=zO-IqS#YWvx z!Yg1yZMfW-y3?`fNnLQL7rvTkRQADBN7}Bs7>g!RQRA?5AQZd8x$Eia6yeWPqGBP}!FWozf1(I8!AcsQZgl zNo3%tqkPLD2)VVd_k&!?us-=>lJcdjZd`OoyxK=JZ9vM5r`EIu^W5WjFc}8hu`-k3 zHTUY^`eeV9+I{u1vh)%`1VA>g6W>uMd9+SCuTHkTPX2M7;!+)1u3p8wUTsIc#?gAs zyn5~SdfmtMdQ0^bxdsFChE+QnjF*o#nB+B>wKrHiZm?Qvpvg7bm^a$(XtY1t=#baw z*xtC|apR_?M!H;+i+PjljwZLGP40P39_>v#AIq~IHKA>`#gRTI$l#IYfcEB~ z$IaX8!3wXU{Yy$wXCR{am9NyI$j3^eY~Pb@SAIC7)Pa`x9W9ARTau58Pthx{Oah1d zj_--AYVc0kZ5~5`AuafFikwpL5uMqVR*sJI1(~)P=hlnuigAMqaYx!DGn)sfEoU6z ziorH9W$^G(`Q1m_8!Hr#G6UO}+E*UD%r)=m&%}@W!#9aQ3N4q#!_lIYqM}M%27wLQ zaHh0{A^v34As{C2WR&p*;bp$xY*%vkSMk(D@<>HmkNLIv9oIe| zy|yT))s}bd$&jUOGq@Ka74-<>;NbjnEU^w~GuF|R`OT*rV@ z*F!IY09+tjsjw%`S7}^_799;ouiwtRZuT$agWr4T z@;6*8Zn*Be;TCn0#OdlJ=(Z#fh9Y%2MT zARrDWg*o*JQSr#}JA`veE5}zcP2$Q}I>xIDKS#L!Ccn?r$(e(Hm4i>E;c9{guthl0 zR5-s?f@X^R7w^DYBVF9nh2&cV5){5(@`^6$JbW8tO;8Ae_nSI#W(h0`95sg1)4C1N z-FMCn6h)my72TP7Ct4jS;WGw^!XWp}B{}ElPx5yINbyo$)`|hXn4-Hsb)_{-nsNWx z^!%6#eRen;tXbf^?He6x6%V>+a8=Um>OKFVdsfFJX$trEQt#UxyYEnN-|_1G4TyZO zpl*Dfiv5p<8>{;^Z`52m`oQDr|3mrUMvdI||B??@4L_v5z##I$WCdGYd=h%YsCFjG zSqQKY{Ok1m{o3t9V}HLI|Id#$n*06@n9Y@(^`~OQ|E8nOfC^v}4=^A7e|xmS?+iqa zHeQ~x|Lthw_U{~R=z@*$w9R^2>KSy`F*RV@rr*VgT<(B) zpw{xIqfL3mu^;cID?FFyzrC%E`X&DB(QuNo8Zg$80`J(j|D{enyl=+{!m$BW&HO{Z zIkukQ7NnV7?cFV~!=)8EMqz_FcWU*v{RH^c>z|-#*QFq9pbE6H(7xV99Uqi#l%FRe z4eCB8O<~g)WS;QKK2Gh{f8f|s{@~bZLtW>8acuL7=nvMA62h_RZ~o1(DI*-4iEh|k z2f06UY>mG;Hsojn4`^A_DKgJ~b8Pd02**Y{Q8f}&qsAOYlz&iC@WYK;03sTmy^q?p zOop+5yb2F{NUCrcWu(8VaiT@`gzGPk4gI|RbA!H%rfuLV;B^d*JDL49APHklZaOqI zX4P%#CeCHHRj;y<02%CpN4V)`>Bydhk9lcfpT0iN4aHLl2;`{*3&SG1Gs6h zf%4N6z{XSk1VvihcT=i|oIC_{Bvw(G!DOv$Ss{aM)gmE*38c&k35heb_~^k@3Fkda zBhuAa?*kgA%u)BI$|_|yfB+Op6Z1!*l1|deu}6y(I%^%QCIxW0JCb3I+Upt2nH|pz zlSzuRz=CO(+mirqb?4#6Qwp<3^~D|J(JK0;F=4JpDGt}B)?zskCwAh{DGG9^?rqiD z0NSq*Ob>}4BlH|cQ=j8xUsWX&iq66^=XC(4Kmz&R*-8~InK*3A8dVO4WPny$_l6+j z!BZF(7iuZ(jiqIf{d|xbwRaOzqdxtsMm>Wxqu=D-+uEv|yyo#?CMKVgH9qM^vo%3+ z{7Lz!zd~@z`vLd8s>}W55%y_;aHZO}GqWpA9p9nvzIAKeKhhWrZe#)>Yc5>sG!J-jPERut9hs||*r3--B?W9KiI$NL)q z*_GtoCf&&I0>V9?3PgqyXr%qKTD3dN?wR9O z19=d$=W0cz6~GdoOoP%lCU5UIY7|2jwVAv6wt^u^hXi^W4lyr#Z(abRQkrv15=yOk zZDz@p-2u?tC6csEi|Mij_w9mq-L0=tik| zw}UTFJ=hkTHmp4Nor}$&56uYp_}3)lSkpt$s*!GOrIU|#gXMMYNbU3*~&UW-2{VH-%IgicM3?icL zwQSl-hM3P;wnlou23itg;R07hS|NCACNTR%_<>YXPxaPfQ3d>t)5Z^oG5ki=pZAG? zX-%9w<0{G&uznQ+3qlNurIL76<9s5pVX{LP9cLA{Q%A5z44`QkSa+tv>*y-tH4=DN zuOc^=9(oxQ_A=~p>Xg0tk?hHw)Z}o`sK^2u>med4-Lk?tyjkqwlpR>jf`9U62v%y0lCw~w{_pGID?B_sf;M(Rr!y7duR7<-&T$jv3Iy~PT|2<6j?kkW@WQ& z<_Ul7^;X8s8f}bd^D2A~AhId3Va;h!z$AX>m17QC==uqIw3&1f{tENc*IhtMI~gN) zKH%ZX@*7XKUx&j{6sGbP7J85WsS|O&I>*+<`DNyXzCm|wiwC0;a+G}&gFEG{?%mz= zApy0FWga*i)295AUjYqFZV9M{c`n-+^bR9+OpBMAX7{?3le0CTdP+2{CgWNvwa9`&6RzQjhjKzQ84y?yp5TcA9!mNf9qR?JYw-tgP~0CCii=7&Q)G z4)1rwI+l4#b>VN?*zuWfmHdS(_nzC8F&xJ^((tkG*{TiOoL>euJiw=5fhaz*@D5*n zMampdw{3Qvc_?SeiNrW>qm$?c>U*mx1Wmy7i2?3>VvPCcLvi6K!9~!LOx2`>1k8mQ z(lk(B2)BX~nqrQK2X7>89>wm>^`VEy3oK%ZmJYDy!cp}ylzJbeJqy0?m3mG)M(vaP zdCEyMQk(lztOGYQp`l@2FzC2G6cR7C-tkh&5LhmxuCobdQii1)u`AAreGIy zU2-C2o$LA6l4cypoNu8}2a<|?hfir2DXP!V#G?Iddjm%FIt;9@S!CkrAA;rQb)_#^TD1PG8C2@Pc zDT?az+%=T6B{ofZ%g=-HwtnajJt9De$jzx#vse@+Zu{;`bI}VZ8(Mr-NdnqB-Z291 z&(R-fQSCQ|?P*Z_s5soXp{mKuQC;7uc28*zxPlx1BvNh9!6Z+X%M;XAXbAd64I-B* z>5R21-i#s0Hs>Vfg4-j0#&@31Pez(Ej%_)-(U)}ceYoY1ZAh{st$$R9_%#E5qrE32 zoXE#WX~9eE%txB=@*-PlyQ=B+6P|U(RXJHJTh+X_cy}$kp5lKr4xCG{x_rt775EDY zq)0Zi9| z1?bFt9LWyRpv#gAB#QF$$G~(#&Zvxv#xnA2j?caI1rOHe%Fs-dCkvp7!VDRd1{p>w z%Dl_@qgrAV4nzro_AZ`NnJ{x)cOKA&B@H>kb;xHS43$dAsm;*kq0HHk(Loa+ zZr>CrO3PK`0rPGH2-58bhC5L~GBWGe+A^Y@PkLB@xO6#JXnZZ zfhUz>L#v=ULTX64BN+^%g^LuS(K>L+9sx=E<(6-f$SxVk6LsO$ykCKm=755f9P|Vs z;~bm`V=&G*4C`W10KAqRk5We2Jc3J7VUuNEjUf?m2LNqz_(Vv#3a{Zq6ex9qq+L-U zQ6V!HW$E75pyO45+;cajRzh<{*sdbt5b#l}1T%#5I#=DCN)qK%xH&dukAVdNFmm~2 z1j0hI%|z?w^-Gf1v_UB*GW)NSqBc965IsyZ8598SUarXeR)`(~WXRyPD40bAgeeyQ zpiq4&C#HdPdTBL+wB0@jOYv8WhqNNs#m`zTC!8b&2gRebPX`|rRhb4q<%-Vwr+y`r zLdsW!l-qLJVFhHEUE540wLjECs^G13Fa4F2@XOQiB^}t1Q{-=!y{@a&m;nVHDY|dY ziE8Tz*xqJTSL{n|ky##UQP1oUbxz#40!3h-RTpKF$n(QakoUasK06>P| zyZgal~?Vog+nRd+{;tGdZOo_`vRkT zBlCNYbo54#_s0CaFEBa3FLk-2FYUkk0{?xO4e2<;y(K?bqo10AjyrIsu zwp(<6)JBUNl`5SsZ?3nwpdRbq`Q;0=AW87={0K6cm*-7Q@mFgxx?my|uM-|<;(^}Y{ zo4;n|1K!YOf+b9ORAgU%Wv7Ay{Xv7uZ0+8Y3U33-A?Jp`V1?5>0O>|N3av;FeE4i4 zJ*w*A(@Zd{y*0*iv`+p({GW;ufj=IkKaoeG5&!QLBZNqM%!@1LDz?t$t$7bBa=>jX zOD?=Eyt5LHt9YQCm5;E~ci$9@TZ{`Xd)(a2 zCgN1P)v)e+b5;L%1TV&D8k~CnM7Swj9%i5ws@C2>}P$btB~s zDg3fjr2b5Q2<(TY%x^>16COh`YH|%Kg)pfQ?lPWtNb#KQ|6^d#sC=A3!P3r9z?T(fxYy)xd{mWE1f&<{#%@Sat z%8wTzLnT{@#fd^y>k}J?WRVfMG;{1q;J*j6B{vpMrFKrGJ)KJbImK3dleI~cV({i5 z>;4%%$TzB-*!BG+xhb?SMgo9)w>?gcQ^ljHO^CfKWz2>zUOKz@fa~=IBrBj zhT~%1e2n&0d+*wrcbzloJ~?RC_{$kl4es=(m=BAEAHH>dNL~B(vEtv;SO57cb^HH; zRVtiH({wuXw^gd`gmNtesQs}@{WNy)-&v)K@9qQWb~gm|Exdt$8UFa6(pO0OHO-%m zLRP6cJ1_*T6-fFuao?D=!Nm~kRLV`0bApC_NcbZ**AG4!%SY0$hclDuCux%Y7d@{l zT>h8o*RMmO4%z-1`@Bmpzd9Gx{N`0&h~w6^5>7q-uL}sIl-GsPpa0n*Purs){ePZ* z{T2SWc$Ep(-};;W@pt-l19IVO9zB$|-Rf!L(zZ2dmd;EoONcqsc9ihjhRB`ihzPBH zhnj!&_RLjz{CrpaH*DpWH7^8$C_Bf)cDP)FsDc34F&#;9f1w>Tj6?lVeVwHUG~A)Y z^@tt)1!$Q>BW9ore+9JE&Zhkaw1A%3-+)&BE$u%5E#o~HDgtOB{a0bRi!=Ai5I}3# zW6ZkA(WVgrw04NRppN+L{u7|Z?EMXB?R}`=GO8v6d?YO@F8?C5DA5R^#W!z$lDzZ> zp@ln{vaT>2FhB95nFc&3rqE;@W}-HqHjMxB`r=(Q#TH~cw{=ObNSM2i`9Y*j9IJ_$ zMKZ5U*Za*6ubST6>J?)1VSW<~4E_bs;>>K(hS%tWy~Kl&)*p={+U6(pM7jODrB!&~ z79kOfFB9n>Ves~zO+)<_m*PKsMHTT)fcXo%gWuy;gV z9`iw|%-Ig$BEL{LREkG$WFIhmDD&+D9~P;DTrcp74SU=9ef{KsR$*UF9JP+;8FbH) z6ZMOBeefkI13x->wOM~bxt7HZl7_lM+!fp9(Ri4aYDY=X8uI#q9_|4Z=iDbKeJCjt zHl$12EUVV{NnjBWvv($o&oOl>x~rvnl?Lon27f&cqS*Oc93=pZYcoM zc>1bo6CvCSAlhWsEUkdQJ1E*g?L%_a>5cJ%`_vpBeROAcjybEI8dp@$JAKWZrjjCJ zDra-c&n}xOCpqkv8awXq0zz4_@U7M`(vWZqKtR`-F@^@%9taDa)5C3wD2~%Hr{(Z!5xnxq|>h(KfxX~Y` zt!*$_#_WPyfkm8n)r$f^o}#j_%U)m0W91Kg7lgdA4%&bffqCnOuyV6_>`GI6Hlq@S zXr~}g94gVo;S71_`@ky!hYjG`TjX_%vD5TK&^XmVg5O>qI|soZFZ3D;C7Zw=DP?hoz6FcGr0LI60K&qJ zd*Tzr281v>E32a`78=G=hg5>*wXL=D?&Y^h0_>0*+QQ!G$@0TpBhz`lL>s1l(8Kd6 zXYyTPkou7nUyX8BP~*ul*0HT4*t-~}{Txs6i$QhdW=RUppraEEiJDcx%fJFDA0*TY zaQ$|g8li9vVOy676vn>1SKkvw+eOS_N`a$DPIzO)_vMd*HIM(<_@MpSccqRwq;MXn4sJtyUNwNYzA^;?7}C=4SdCvdybJ^vez0!k90F^14ji- ztE?IQo6;P=K6*HEqcTr}jS-MiR(#w|Vgf9JyfDTG9`^928-~lhLC?KE%V4csZIfg( zAUlF-2H8a0Pql5dwPkW>gV;q-RnI{B4iWuPISwKq;`2?1?LL^p4^Sp|s{0OIvc9>; z%zUX)n#hQ{;SH_I{qE=-?ysrXKJjUvTzygG#EqIIOoXHB(DMkV*5itb5uu#3+lPG5 z$fz(7Gr@%-ZW%L<==xx5bF5Bh$rUH(TPhxSambQ>!k`AnW1sCjVCf4*%J z--DsmL{)xk_@F+g%8jQfibTz6N&>&Ek*khme>S=(Zj}C|vhG;$5&a&#;4Z*+;qpu~ zuk-U`WhqnaVBb1#-C!kp;MSi;NU=i>5Xq=me!5FJG%zpbPD1aAuoxOj1tPEKUAyD` zNsB$@^)6xUu2j+s`~q&k=-vo6=Db@BJH(r7zt-M91>gJL1V1$}KHk5chtkk#(9{_)0vI`ENJHgQxk{178hDOA{p6s9qW6I)auzI6Vn zBH{W8ydlo;`Vu17j1n=#>E;lrUk)Q8G9jj#0WD-D54*ZgApo$DT?=*iirWD0s3H83 zONVDA1rR@UF6{tSYEQx?z?z0ujW~Sxw?k5HF=mUqLOl`*N;bxqS>lwB)L{vvt?uQ$ zu_Y_quyY3MhoQ08`e(6H)aBYpfDs2Up$K;c#2^`I4=XY0o4QgU<-iJBJU|JOwvC~l zC4MYTSwXQ#9fdOPL#cisQA%p6mU=o;;n86@X@xk$4KBuQci!XFMmw^y#q&bWF(Tg^ z0_|_bNm+6*A%{=g%S>=*ITuMsBt*E~Pfq$-oZNgd8Jb858$zuHpq1p4_vg~^bvrgp z;Pb*G>MrV4_wAJ48;zs7UO#1gz2U@Ej{2V2)KjnYqogI$YeVx^r^<(*QcK+D1^ZC{JXDuHzmG7f(XRCANq0~n8&MFb`s)#fK|6cZ?4m0Fc^jQ&CdV2Ug;GoOkc zjLbPUBxWh@3o9*iA??~M6u6mkSp&^YcVSWG$?J>>fYDcQXb-xC0h{N7duLA_S4j^j zItlQy2Oajlr@*>er$fVl`8ZqmZIapyG}6hDzTj41F9Z#V{N!eRr|D(AJ{=?~>>z2b z;3sKpYQfkZjI*X7$XM1xk0m+1Od$#}qbxz3orIetlyaGn!j(d8cs($MqkwYF*{pc9W>-?I> zmC5f$0B0>t(96?&qe>kztLrr6TD z*ek18`&%(Z_JV=gg;gFGGD3wYRAJ-P6$fT<0Si#&R}y=a^aoJb9$%ysyJ|?Q0J-7I zazMIcA)Zv?Vpc*PGKJ>zUCzPI0tGL(m$-QpGCW|HZzZT9jxcMLn;kryvMNNj6d?;` zco%^XkOUNLlP$r6CA$YMdOiY`d57#DoX04Kte{>*R>hQM05C=>APiKa7L0XF*ZT&u z7g5L$M*#V-BCiaxPDwonx6ecR6hy9xE^(AO`3>SYiYk4?=G2;Qp`o+@Llk(}oR)Gu z+*tkfX>BqHkShVWgv23<*4jvsIXEgPUTXvJ5ozQl1zx;@wF-`Bikz@y_#oP=s^0^Y zrc{eFWb`PNY6hTMEU0gT!q3`5FTfvB0J7O7k-jEt^D8#G8^*TqmP7|`Y%NcGb>$T~!WTcfjd%8i3o%*02~ zagw|uA#O1$6AyXC$q+>s9B~`kaYBr>m%_2gy%Xxf05EFgh+irhlS#w*GMWg^gwtdg zF(ZmoH(%N(a|Y=w(^78rH6l%v%n*2A1$=Zz6Jp5(xHxNC6Sl67-IYdFZoO*SqWBAN zY$Y+usI1mP4qAX)dC4A5GEWh0hphlg{toyc1%BEFBY~C;PB421%nE@^VGMc#!muzM zj4OCnD~g3F4e_(411GjXB}8B_@Jd6wyj{EM+0?va=33A76#g5AfTHAXkEE*#knia2`50mrVesL=`r97>>miHFfo-o zU=n~E+yUFMyAMLZ8>EIv1e(lYw?Kg`pb4VZ5_FNjpcbeOcYF`{(i~Q&feB9VjiolD zeAu6HU6@xYc}v!&@;VT*ilB^9ABvZ7g1s44a=iG@m(9^6@Usl^r3c0h00P`@Y-Tq! zxBB`yr$ggwvCdu45KyB7KTWN1tpL@TWe~OO#n)Ek0cGQ9&;LbU^@yK zSF78kd&zQ6*(eL8k=KZ$LR!o_gMBbHuznTlxSA8(Cl8(arffkmSns43cIl2vCWQK7 za6tg7afH9$DtvAsmK7i=_~t{nagR{yA?X6v!x?Fc7UDuVv#2n>fW&R7 zM81H>EVg-thx%N!_)D_RwAwQUp5H#0-sLh(ZZl9a@cbgejD(u}`F< zA4z57FR$TTHKt(@KVnZ%UNjfCITos@kTRpM7}|o#IF|2%2V7dPYbF6=8}HOft>x*9 zO+U1d`s=?)zux&V&Qo|YZ29E=t|ueMo{SbedGuZ#$M1W*{No8<;pya$aZ(6)KN^%} zgU>9U1{*+-T}om;SaSO*Lj`ob38=x(=1(e$0z>YhgF>|1OD7c-DCm*z;-7900<_1_ zj6(Z3A6A?YwVDw3oRCZ}l&RHKCiA5_)q5Ys{CqN@Vl}DeIjIpdsaZIw-8rfIbW-o< zBt`MLfz@+lk7^wA{4iKzvR}=P|HOR1s_W|fb^OoajJ#R!us`D2 zr^HTqsIIu3XA#ootpcs(LCQEtoAX+As4UHu9BHHRH#TZX+l4IKo7gAB*XZ~z&mG2sCkW=I%_WsaO~(H%>>`a*eV zwhnW+1sH0L-;5!Opl|A)qaKhJ5f_V6)k?CUi-25EcW_s7fMfjy0 zx!~Tnn;Rb8u8dYX7~pznT5LdhPWDf$)SbIY^lu~k%u0sFN_J%^3D??G$7H zx2@*^adzE30Wx~`;z8zBEnX>${iP~HsgNH&O$0b>d?EQGK)Ld9;=M}OA>)wj3d`pX zWH3S>=7hB4mP0?t7zjR~4c1$NDt+(oWbn||K-jJ%zV z0cZjb^q&KDAeR=40oj^f^a-0pAqA^=Y3E71REd?IJvq)7?3{r@LAC4~H|(?2Hx}CE zy1aBevvOBwyv&wY8_pR8Yi9%G>l+I#kNxcUI!6$ZQA~LuEe%b%lx{4rN|4<;?OMLI z3ei7Gl%`4>dcPaZ%;pPL?Y&*NHqY(7M|1F#&IEI3Ev7Uz>_wT5ZQ{e0V?Takv)=Q&mt%hZ__6#;|ArrGLCUjZ7U@m67d*u;rW@;r;ocWFhY~YJ#{~ zAHP>YXR&Tw0UlM~uVlnD=vUi)vEDITZIm0w>htJ{6Q68jtOuku%LavH0j_94cXp_V zh%n9I7Ex1LjJY-hprHtQnqF~2pQV#yrLQ;E({1%-(Mb4JjRrP* zs*gO7jvn2Rx;YU;ON~9Vb;`|+ST3=JZbgXacz{!Jcf79!4+$o;@aAj$_r7c%{^rhxIfyG^MBI$#W49;L;C|^U=VTGWeY!2rb z>88o^Cdo~H#R*CyCO(<>1~`+Mo9#{ap5C^vb?@2TiKhERWL5Rjcp$ z<5)Alq9lzrzY7`mX8t8-_qF+7I-h73aQRYc+j2lf%}ukwsw=PB0&A{e&4cQCHQIw3 z?%JCNH$B|f9(?6lqWS*T*QM?I+dteiKXCQStM&uemJ{&;ZNQ3g%T9rH-#c1`H+O`7 zd=+MabapOvgbnKVT7=(T{kp@%0IB26N1Ly>dhp)nb(Rqiw)tL-c(^;s^3d4xJ)F;D z2lRvEvi6|KMQ{l2r=djbiq6RA8SAW~UY_;sjCy@O$?C|POP4y2yshcAI{N;~>&~Me zuHn{1&mj$+=udaotvR;v(D&N0FVB+J#C&~y=~~Rvhu$^Ee|&j;?fCLCjsajyxbJAy zG2So(#JgY99}^*oG#%1COl)OGc!{ffyo4iKY!hdblU{t95V;{`r(CZ`{<|&v3ZUx$$Bxgiewvzt zpx9qB>I6xUp@L@i|M8k)_*cj0{ICunp7%#aUDlWTr;Iw1Fao|G`JGW8T|fJ(3*rp4 z{K}}yC8)qy2{q%3zccDin*6iOWgPuR``1rX_ja$U^tih8PaL1-5?$8~fM1T!aEZD; zOW zyYHus7fgEgx39)$r_h2O=&?7q%K%*MQI0OpxVfcct14`=D)yGi>a~c<^ZwEBJ9|Uv zHNrHh;Q67RAI`8a5T7=GZ*2jYElA%M+_Z?{+%frFCj<06HmFkuThw5mfF z@>xGt`W6SdxOE9XeTx&H<>1$iRwQN4`Wb4D5?GSZShf&W=hk-NWcYe<9Ux(JFqh!# z04u#jIx9Kc^kw;daWD$N>n~31*Wj*R80+)WoroV`w{LYBYstzCYH+CGclc$ClXD= z9}w?Dk-zlP2KcyWvd@7R?ib|W(a27;3u<1fYnA88na1a=i_zYQLy&Q*mLxkJvnu^% z(MRKb--pCGvvJ$HOM^I#nZL@)(vLnG*-&C76~7Edeyz*-WX6Kea8}F8hk*;WuUh?h zhQitUVZ%M5svxs3ct+jp>%gni+P$}NCM5m0182=XJy;Ven}Q0v|HO1|I3s3pPr-EM ziZ$Q6mNO2uiLHB@bBX51I~#-I7cPEJy5|06^NN=)`duK+W{dzFH=Zw+zCERnp}@+* z++eZ-4YU$qf@B6+-V(4CKz{O8^g*Fa{H<-Kn={krLy`>f4q67ogmKqWAep&V6AP3| zY$c0b$ZYpBu|IRt0Pud^FPbxvBPKRgkaKVAesTTdv>($+b8T%(##FBW@d8B$7jAhFLGLt6K%PS8rk;9N+DHrR{2)-l4-K zPu{;OZ-07KBJ%otYJ&lj2B2jTsGtRsoR*BtU_04Xe?g#nHZyXVl+G zbkHi6WPKnZVv+0t{- zjGDT(WKtro{D$5u@wBsH{nD@fZW`YdPdCjH%!yX*wW@P*i~oLFVb2SZ1BhjzlyWOe zTB48GwK9{6+R5L?@5H*zU@iFIOV22%=Rp`&jlm}Zi~(rk<7vZTmNrgm`8KLG49l$q zg@A`-g;^Rj68%co@L{K5T^81nHX$h3fBQ^77p(mL(%fkq`N&U$GfF65)!i>}6#SS_ zOf4jLk)vvaWx9p46_lJ$lO>kQY4v;JWCs%i%*#p+tMiZ!0(ThjqhZu)S>Gm`AEJr? z!XlBWy@z}i)x~^eLH5C}rd^c?WzuB1&xHD-9$;j`v777>0J{1bltNRAoqgxqyS+>3 zGPk&@ij4=_dD12=Hdz1`UdN6Sm;vUx<%g&&8l#8@e+@E{G?qj1rkv zt0)(>lj)5Vl#u;FMvu-lc$MFQ@w4ZxtS$v)I^!#ecgX;WS5B2b%# z=)VT-tv!GOm=*=DM$E_YDI)M3U;Z#Z&kLP_PsQIy`?dXIa%?WnJKVNGH&L@sy^sP# z+_MlE`B-ei0XZ|aITz}pCZxo05KSsL&8Qxn0BVQ)(B9vE4m+WcEq(3sxjk0B`jFIW zg*-tSQdaQrC)#@Bt?E+)YVdbgi+vxfNn z-)od7J^Vt;JI(9yuQ8(B542z=#GOvKY=8sgr(b4 zevf-2n*)6^gtTc03WpxsN(^|bpe7V0BYM)wJ#rhYnqEz>Tu=}QN?%?(Bt}G-Es{!_ zFq)3ql~$oLkq9Lg;@(YA8RpxuXr^C6@Kro^mokmaba|^n{c6R77D-bKf+hvmxr(9o z@uhLIw?!#?bicrpamJlghD~0DHolr$V**awdY)r|zY#B~4lM!-xO6f`h32yYk z&L)43os~9vCuWdJm9jCvIpH_6z-p1H>vjq7_A#_)Q zIo#;`ybU!8TDY#d)+%BVb7xCWo_TGMGw+_WkdU+Z7vr<1FM4HN6~=s?C7t`!q58%B zTxQg{b$8XD9p@Mm=YB7$0OCxP2NRRX#Fa7$olM?o=15*_EIrzp480A)WCSI_(e7L8 zSa_Tu9TMGpFE+L641b*{1{1Dk9q|PX9DSO${520*bs)V6BvOuS2!o%wgC~@JC_c4H zBlOWw+R@uP@`FgJrnUva=Ds$ziV}?UJ=5OQ&H~?51FW9{=XlH8>V-PE{_*n@Hd$F|sB(ApNf z{tP@Y4WQE&swc1rfzbp8f4aiHJQjArBt1h0?9O<*2Nb ze&iKJx&B(sk?m^6RP+vZ$aXT)v@8ir05n%G7kt7LcciR5AyxSCF1zEaOQYOpE`Ij4 z?6yAfeixKv2qoF_?6rbom^E1{v9?Z#B5vfi^t;5aK`-UzGUK`P-T3^@qA=Wg9!3@9 zsz5#*@L4MZHFwxL(hEsMs0bqL7E6#s??>oD%G9Aeb>bo0Du7(Ej`ns>ylms_v3~}P ztvS?60O(8gS%KoYyIF;Ay&eqKCf*m`N!>N2-Z*p&vF>qV#Bht`bB#pQh#JkM(Z1U)RSfQsGCj>@veig02?3CFWJ z<>b8U&BMqGj?e|lb?h<_?{*Bzt@;I?=UQFxIR&i_!uvodmsxYY%Uf^zb)dhgD-n|i z#N;u{v&j+3?C>cGVlNj9JbDJ)m_GQ%Lss^FQR{GYtlL2yv4VxCX`Kt;>4mf(fl7R< z#|eE$9>oDUmkz{q$ZqZm=VJsKbmi|+OPe_)z7lv4b2kWM7S5*~l;qa@U9RDQUXb)u z>(NtCpmBTLvG#=X?MH95Cv71<6+yn)cTgla;;>bq)Ofzw^Y-Uv5yGpb>-#)*XGR4C zALdxq@kU;@xR{5iYCd&ZMu+Sp;FU}XN|N^=ay`2czMU1PWr{dR0WWA;rA0KQ;_6k| zLJlA|LcD8zEU>7f^_H{<5K&!5bY`^N4wI!RlPY!}tUuQMaxJ(w77_gP8bB#gq9}6O zA|8%N1_#z5nv=hB578EXLJwS8U9Eebk4TXgC!!u4p%fk#xm%MCvu{xFBdmiFs^h)OS|6Hn6>%aE(*qx>~J)&l=TF|~1S$8Cz z`R*`aRIg+?&j2YEJ4%73+_0K%GS|c0R}dBY+#=^*~uPdK$Z++cG8I;FN@ZrYEh2xWK`K1qpc z19jMk_9Py9(iUhD)f1^74L!EW#Xh^u|13S2UT z=Qp_&#LC@Nj!Vk^eDQa-Ac&37*E5iSSF}7g8B%;Ol4##z zV9={R2iE?&=stG^t9{-4172?rq_O9AjtbiP>|_ipEv4a(0*o65qLEdoJ3LsUJ;Kjb zZu4$T2>Ev7d?$QHftkC4)^^Z@cleG6LXwXCca5Nyc%V#@s6Ggo>vxCf7f`#s%G(8d z_aVR;FIQe+TydbjcN$^*polxfX*-nka?qlmHsUS#V6etNw;Q9aSQ{R+zAIL|DG1{m zEY4{hRc=s%rVTbmsC~iVRbBx;@DuUc&eHUbq(jRq!(Bc9o7a?{moHwv^n2$nBmMqm zP9Jhkb2go*G#@cr<}|zfa`xlq?5gxDR-OyIO#HT4_o?F5&z@HsFJJxMd=&~_-^R-c z`s=)V$4JrIo)g*3;r;y&*OcRPVi)Eldgr8O=VT7(M*aL3*OUuIq>P=%*G+U}-ng5^ zeUErBfGX%}-TZoVpRV zS6Y78DY55&isbipo{CUi0I4Ymw*C(|`x3N5FnTwBt$%+1>e21naPojrHDWRgfH!n-a{ta906S#JB6wOG%={C)vK%f!~rTB;Ni7j z?IUdsU$c9UV6It6Zc!Y-!&g;$pNiB5Y-jgwXt5iOwI92ywY~a!A4ZxN;5*2RGV90S zeBbkO8p|g;w34Y*KsE`ke46NvI`&IV@xq*ea^5h0HL`k)+bh-fF;k*A2#7^n2Cz|R zA{_-IpB$U(jd8m7rB2```<}Wg@!C^(mbez|ouN0>-*=KCDq^crB{m9;T0>Lwe& zm<&-kY-oOnXa2@K{>0z@9BThx+=0f6$%gKyB`w(tvSu6|@e0XmSfVrar$k5b#m{B- zR?7_NcDy3vZ<9{%re)0P0}{>hA%L58f>{Kt&x;5j=2jpRcQd7~RG&aj>e^;sd+j= z1HLDu)i_9DOm=;WTPK zcPLLshScJo;hiPB)$fMtsdU7zH5f~5gz z93asBsYuL20u>dAdV=5O-4Xr_h7}+^F`r9_Axhhdr=dgY`K4ptSyO-tlWg_53NmG>n8XQ0xJ42S?6KJIN7RXPUT+W2)U~+mDV^BRKq%LN=Zs#++LMBZX@uZFZrz z_2|g>@e54Vd2NONIkMbWSi8bc4(#y&rK{HOdzomO9rqCv4A~YIQ(ITE5IAG`wr69W7~o}jCA0j5w?A)gY$&Ptp;tv z8KJ8BNAG{XAKguN9};@whcs?1vG3v21kyd{yiu1f`WgEr>?*VGIKvX$sgGw{krr<`!c^dLtOfzY=6@a7t9ndrNHb0=KJBM#eHFl^wS7wRu_CN#^z3EH0{t8#lzEz968ovli}H~6PoB@z_fKZlpeQ$AJbivw z!m(_D-H5-qgk@GGc~_-d`*;yVw~N;H+2}qY$lo5`tx+WZi*1Jed-Hy8c7i9^a7d?@ zfy{0oc%v_Rr`VrA!jrmWhT$+$vtsxUpN}>RtT?P0;v0bWU<-rLkp}l^;d~p-_)PD) zk8b(oH-a{|d0M7ZGwb*Ug;Lo)q!~5iie$jRZD}4&HkkWeNmW(UiX> z9H#W$JXdjO2B4TDarCB^C3Df~3le7Gjj4j+9F#g)%*=7@QLCx}Mi0x7MWrGu-Y*33 zVeQHu4TqNPitFh#fLpG=Q)>6`c`UKBlt}gk_#uu>tXZack5+kU*kEUsjl}^S`uicL z_0^Zc&s(t61mT;>k5iUXM21G=U%2y)9UO1zx3e&Z zegB;mk2!0t_)1g;+1cTV3a*D5wdSh%?xwHvkI|Ls-^{#_|*m?4$QgW%nS}&8wi_2Z%AoYV#@2q!lX1`OjWXw^IujRR?5B- zO_k4RE3&cfXA`_ry8n=->5VYhghP9raU?HVN*jPpI0z=7o(|w(KH6$#3hp?jDlviqsVtW&(;nH#E5ZLMEr!kM9xGxs~rj82_- z_?O@2MkHEOj^sx^JMvnFKl1F9nC6T-@yXQL{~`PO+i$ZfcJ7nGIXL+GmT+!8SXq*0 zCw>o-Ts;RYL0oscA5&^d6lk*pl7Ls*EKqut85g}BcGqAHa|IH&lRSt@W1t)Z;tPSq zJ(vS6OnHwy<-|PI(meIfJdNo*$#HP@5^gsc(!m2U5IUDjhhpduk#^3HeHH);E;@tJ z=}cZjq&*$r8w23@!^8u!jsoCr9!WfJJy@y6uMjy0{+a^u9*{VNDX5m0))d(px#Gh4;-p$EK*W&>zL&_GS3kRi-ikh(chUNBK=W(5GfPI8C`` zcwWbB=T(@`Nk?i@&PYWfRBI{_+&OSI8=A>h?Hno{E@c+l=GjxM;rip~Fn}JydO1U_RQ1B>i`yN+#?Ep7bu^3M%2p}3J68FJhIaZZ70LU>|Uutm95I%;E@hpQJ z)S(~($%l%fk6nV<3wj>d0Ci#!jVLHoWkrz4qY)So-sd}Wn>tj=i3W+}Svp(X5 zF}RMz!%u{X)K#eQ{P_p_0tr6&w?MHJhG9<}aS4oES>*n=>9`Vq2@`c*k#i)xl%kg?Zigjnzh;r~dORS0ORm z!Z`7I|1Etx&HJRlT<4L#Q;E4UxuBdz|IR4*@3~b~N`*weso9_`!tU4JP~z3d9rm~r z;&(&56UH7fJtW0GT)oqxZE9veU{gM@yL%uqyU{*e*+B?&{W0JZrC4VODKT!ko>9`@ zUCE0V6zdxFTgl0z+zpvH8rZGW=-C(2phSFu-unFReiB037LwGscWUV}E&E>5j*>V2 z-N{lzsXK=Lh`g7cG^ADv9^i%#W$jR?o~ci6!V246J{zu}$N=S-J3@bw=UV&j-dA3(#vLue}xQ z#St}$u-s;JWmKV%g{#?k_(dbf5&)iRKpmc!QylSO-j6g|dN;Fb!*=HzDxV)uC`I?R z-JSq267~ErSYWjvlK1S+g!^Xku_K2GxsShSltqX$KPFwm&6z|CfjgvS zt@A+7h6!}@B*3{Z3bN$3KpG}8`_w1h&O#zoeD(c0G!bTlpbnZmmAcr-<5X*vEqi0- zDL*lX*Y_GvZtfx8$8i<14MtG41RTS{Ps#q%b-fqpbu{(d4hXL|_c zU10xX5@;%jcmR=LW=b79yg^z+dPY8ZP;p1mc*qTkeaotvEaC;FUi|Kf3Q}A0^Z&@c z_=K&ynY`quh|-BZX(^q2Jb_&4zQfdqiZ5P%a9#Rl{2f543DlPWV=G>~=JpL^t8llE z5@RW|!pkq`&G1g-XQ)VHMAfs!3b`T{OyVM@0JCd*WaK%zm6}9%&i!J~S3gXogpO^0 zq6uBJCGm5B1H2VTEh&!|kXyFjfiBONjZD5JlMB=EtVYuPEVTKQvI{@NZw4w~V7-i< zlRhrRm3sLHAMmn^$l@idJ502vp>=wRh~C$8bF+DzY7zGE^-v;l^v$}{*uxiSC&s*$ z16kdRy{A`BJo|;yL-MTm+h+lj?ha(wCI3%F^8b0iO&0gxkO0kXx$vCSr9lu`2fCb% zSJW!yIUC9IqH^bs@`h=OSvOPm$C6+tQ!bI?+uMGO0z=mX7s5ODjdKvqtwB6@Hh<(2 zX-lnI(AG1MBptN2yOa+r&XNZ1et3C`cJ=rN&Nioc-A!Si(5r-$#+b3I`r`L}c4L9_ zkmsq!lZ4B$G<*za)?OSXdtkwxT|kWx%xVgk+E&^KFbDNL;IP}1i z9omn=e9<0zU;@okzTBEGyCH|4k8*N|$sAykzZqHe#Ah7){Thsc;ruub@f>;QP_VQ$ zWhPJ##M119c!--Ho&c1qytylDJ_s_mOHi?M9KP$^AElhI^}#q0`?4<`zP4=Sgi!W= zb4c6tWzTuZm$}sUe_*wjqCbAond^(leU3K!O7iU&xc$}p)z<^uuQb_jemlPf9Q+n| z;#+X#x6s?)!e7C1n|~pa-`c&h_PsE-EA@mJug`i`<@%}H>##*W=TBzSkG#M9Hoosa z6>Sy!jR&wHUrPVANd8mFou*eJ8a5DzLQtte?f}|u{2}~kH^21MuOMxLi2A>Y$bN2LL}2 zrGn)X!aA~CTab$x&*xM7@@1!x8si5*{HsaKCu3RiPnyJUta7AHj-$k#=WYIJlX!NZ z)a9MSpG{(vgzKW?#a(A*c9pp<{f|xJeed0_`Sct|OS-MNxBPpPSXb}nNy+^my}M#R zDD&d}zh0jIYM%R_L%hoU_ak1vJW&Un0g7)|>wkE8O7yS2n0;`o{m8|=C;s0&cPM{L zrJ4Y6`|a2zJFW?Sc1Hr>y64ryo?A;oyJ`Wh>g%5FAD{E9s9=+24_kfT(@T|mZ})Eg zlRP)Y_Rm%$4$gDaw*K8}MEqCsTxyi%0l3R(TY~xbF5};MuIqse&;MnYF{C(Y1%ETW zJfW-Z!ZBd1^j#$bqaIv(oIiB2~94Cq}V`Tw=Ak*)ov3vxoXb${WIOdB#91ym_O{GyS;at zDDJ-j%9`2ljW=Vrfh2lATY{(h`hCP-+=vZ3fY5fIoOVz4{XV*x`r^nK640PrhY^qr zod)BZWQ#|hAua+Ik1jul!~rQ^YfBV;2NR@G0S3|X#!;kMG|m+<>AHD~pwIKxVqBD` zutM7${rthVS%Mx{{+oGBn&Q9&R+F{eO!af40jR-~-bzgu)irx9UA2lcqE_j@i3rR~&|GTU zDC5^BK#G4H2oNLc*dSsyTNe;ty>tO4t{|oEgityX2+}z?$*$R{i{VrB*r{7@zBA&u zv&IeC@eeW~j~sz>j}Bh@2soxr>53cR{tY)3F@UT4RR&TF@``s6z4z)40XUY4meD|> zvbcLcE;aSd-M^#-IEO0p0spN>;NOsm0@7 zf(;<$K@{(`JQ|ZU-wf13cDt*?!+32`^5pJ}@ICntwx#lD>o>JH@t=hf*`fx4cXR$j zMdW@l&t3nQC`wF47|{?JlKtY%)?8u!6b+}N1v}V?0<3V32@qyp`_|z%@!p{#9@t96 zCiN^eNW<}{mj!CyOZQGerN;oa~Oouq$@@Q_X6GLJrt_TWm$?Q>*y02&ct zkpNX{2*U3EE$BYsALPuR*%B`@&m-&p(qjA3^n!6t$}Rg^s)McW!LsV}l3(4FCFREp zNS}g`W@x~>3Odm>dEV+)oddDuWcrv8DQ@a5k-d7-SkblGc$X3%88TW*25PE+P^ph} z)V7$Iuy`>GXQyeia^hL~pA3kaGChiv9KVanWh#y~(fDxhkv@0y9*~B;$&ccVtleT} zz_e+%io90Pq~dW^o!PDKdNSf`80r!sdmm~a`5=HK;EV+`)#JSOofg@P8nS2)G z5N2KUZCSQ}!^a}`xVN+3OEZEq2nJvtTy8r5?M1*#FpL@efjYEmX`LrWzxS3weQX0r zbX>pn(0q%yTQecWzMmXtBmH!Nk(yRjordCEOqd&KnElq)ix?l=^~i40^e9PbU9qVp z$!>0zpx9I)R!wA6F~_xplzZ~&H|LkL*f8(36Ss@PKjA^NXli$;z3v^f`>{6;bz1Tx zJ=4D*RJb`gc)R|(!s4w{v-Kq;b^eo*MrC@K%68>XJ5D`hyihhK8wi!+wgAiqp8aE! zMEr9~z;+7SGuJg~7caa*qcf#4zAe|#)Xb0%#pWfq z>@QO&#XT=P6$R5fq?B(E-P#z16%3?P(TM)X>(Ns$KC|u#53K9dzBP#rSe*BF&HH^@Emm65$3;l3c=4x z6{zJr2>(3-SD%p+*7&|({W}cMEmo2`^GIPq&%s(_P)G2&k%L`k!<4(U%+Nb zW+FgFg<3dV~djgjL`iA ziCQgL*1oC2qdbZy%q>#CqX8ZI!4Hn9uRj_1uL311DCBmi^LwB^Ocj{(*3Ht4xEyDG z!)kUrv~)4pB0=+zg&B4(N!S_s$r0FOr|;>|TuIwSc062zjK$@qc!+7?(*kkL0`3MG zMR|b4UjeQvN-*4J2X-83PRra$%S3jN497B$Pi2M%E7Z$D>Xc+&qAo%k`Kk??4a~xF zn~`cXq#7mp{w1B^K!~Y-NWCc=5t+>=w{y(}YS4x*iDlI!occ#!c~cfSGX^?9BlSb4 zZ*9v$I|X;FYbutI{2Vbo!CKu0XYMAP@xLfJ^bdLNgu&TK_p?tE&Q6t_o#{CHB3My+ z^{h07cz^P2WvU{gFPeYt?3;B+axCZA%^W>q4*c?vhQQD3%8RNHiHd;0b7(p6svPu5 z3?Y~cimpOm6V4s+1Nr1YEm2|(9RuSl`PgWZ(^f>T>ahU{9eAsi%Op%I=Tae&rUPhS z!kfpi9tWy{719uiES?u39}7?Ib2)e!t|250Watv}w+$<2H{s-2NPwD;XoffIC{zlP zG?phk23=r~On>Cto5L{0T!0!1_ay-u9-x8BZTjfGLf&Q^FKob3iz{S7ZXqPNq$j;v z@Ocs4stU!{DPr+}FdZN^fmkvq%>;C(;kyP3sdz2~iq#bdrD+ASut1%%o1q34lmb}t zIkZ_mywQyEAnK}t#dtu@5w_xh=R2d3W=z+_VwXG+PL`dmnXeLZ0DxJ72ilj2lFaiG zRrc>|%eHmmk{p$lSl|MzlD91!%qzcds4+TS-uDTHLu{EatmtvBc-pxIhC_6=RJ=&s z0>dF%xugrP4Y$mDTxgEEu=qoLIfO(-0XjD>?1?N#_MIn1o_}RiDNW0{TMGW}Jddif z7jLpAvcPZCpbQ86ok*16n8Hc=iaHtA_=8C42d7aNsqC}?PJICa3L}vQXe`DYjnD5p}7U^PL)cYaf|DC=9}P3 zej>zO5IKPt_c?y(s2b#?LGX@VvN7yaq1^@-=~moz`>Q&U|#$MW?w4 z)S7N_iK-40IT;hjD_3W^ObX%@#xRiXjPt0uLWFNUz{2i^KQ$T@Zv@qP5*wEblL3J4 zSm0Ctr)nKmImJR(F)8)z8DbC(JVsAB1)uKfioa16Ts{gk+_ z?KL$J`?Q{zM=R8vhUV%UBI@$Jib%(}5Q?8s@54sR({dYkLuL%L*%!R+%sKWhPx4oq(Te$P{1Jct#x&{<<> zYZ)D(R&0F6VO+ASYQA4rU078ms$J#_GSwN1U00#5)eDZ1?Um=n%e;geDVQTPs7I98GSUELh83uqwI{uF>{PE;o?tSRB9hAx8 zS^g!r;`LXTn?^#c5EF5Li5`1%M2>r!q{TYjeT=Ba%tMajfmNi%>NVcT6by*W>0pab zuwj+~Kt`Ti%rYE{r*OhW%=Rd1K!#%ogj3JUx7g#9^0{rO_u9#>tNrB2>{rS=FHHFe zEJgL>`v1;z?OzNy{N?4*(kpcCR)f_%rBQ?KNouf~r*LBMzz#K<)ZN@|cLO$51C#EC zcHa$uarf}XUAol0s54tO4DRJjY!%_$jN?@eIb912w#3vyIJV*?_b2srAG4Pb=W=eH zP8rH>P|n#Hx-`f7FeR3&F&r2*Tw<>bE6e>RhA;3c%dy+5yp`&_{+X{FM!Y7Cbd-;D zb&tTZ^4^URw$y03MkXr8e<1#{47SAVfWfH`6=y4Ik0+%$lXr;uPcJ@aXHeC z!$hZY=p|V6{K^8?n?;z*m1cMRN(3*vBP-yp0O%8IojJRxc=uaAus#gsy zr7(o@XkUcrR>M5RI5wiJQ6LxR<|wiiFRBMKP+9i?X7S8u``zqn5){C{{vH~0ZML3X9+M=Lnr{k68O|(g zJe%m6iGTULck?-0`o(w8=lw4wek~z>iFX2tz_ka&?mZV}Y%BeSCGL4tku)KjPgNa; zNSN%S&1JD9X_JFJVuhNZ5(Fwy&flJ?zqa{=FA_wBl=Ct3fBi7A@hFSJGZ)IHl185A zmQDc>7({E7=Zjr8oGq!kjv2=Wh7n`NIFKfE^{6jGdkUu=Osac^(~_7ggW&2h!4wLD zUveLbcy&nOAruR}M)yUFK%f=}4C$ULaKiIDzLp-xYB)ggA-OOcdaK7xoLLhfNU2ASbLh^B(LsJd%xe{|HsPVY6Fs))&M?_SEA+mO|uZ!=>3$@mQEQ z>!%WHcMWQ4w71-R8|qum2cGjwMC6`+uDDudlb0{fSU}2663cU9j*De*e=cBsTLFBm zmkCjf4s4p|U-lt(BrleO4MD7DM>_NNCld{3Ws46#xGsnuzfW|`Sz0j5FNCg{H5Fwi z64kCPe_kv4ySyyo@E(==DCGBI_i^$U=@p5VR|CEKUMH_`b64)qt~~s`^6!Y(r^i1` zUHCB5`{Bjx2bk~5k%9THALkEzTsZ!5@xsUD-j6G@A3y&7xGM96%v6L4-hdhHFDKo{J38N0`tQED;9h>uWB9reOCMvd4i+&u@6sX^|)Vy5^TQgcWL zLtF99@Au2)Rvw2gd1B?+h4Z_4<~^~td!ZX$4e(7;F{fxmq9)7dgBuO6a2RoALr@-C zcI#^dpc-RSSX?-XPHDk6e>-xn?CFK&cHhFID|r8xP>oSD*6jMk$2TT$EtvcXE4S{w z#yPQBltP~W?9ieec{ymU_#n>;*7t`n_+xVx^7BB%u2fyRCbaDXw9sKa+WTWm3drC1 zgGS78J*z0}S$-_NRGe0D`S$s`=QXcQzg?S~z^zryBtw0-^?AB-^v?Yps@%B$4|(py z&dte#n@>+{!m{$2+nX=AuQq47n;hBSuXp~QKlpp$#P7w*-^;guTf{4^$ck%h{66Wl z_~{_`+X?P^CHLoT?#3%F08%+H8RGv+o?9^t{70U9pCF+NB!u~W_%qL)9X!APj|08` zr(}q?5wGt4=g1H>+xG#U8ztHnzhE-Nt&Cf=KgkeI`<#ORYh;K!xE_GYEAS6wh=x%C zk%Q^lR^mat6lsaV&xirZlSu1((x*q(tY2PJT_g}sq9&{riv!@B{M*oNyVcU1qjqn( zzT-ZsxoN(|ZtHE7j=lCh#T)iIk1Tce=sgR#@!+}8|G&UQ_9oq@ zDy9o=`D?|Wnh~^G0@8-xjFjkv&Dy)|Gfr3qZocm8yt(wa)&&Xkn7sK@vi6PqwcjF$et-(;p@)Ziv_O?6+wF6FxFL}87k z`TTpaz}o^>w-C6=d{M}v$UAP@J^#QzUGb~EE01{!Gm#ViT=6Swr3_RuitfE*rNb-! zsx0ODV2>5Pc6h~aWa&{|;1;@cxg@ZDsiyoNlkfTyIT!w3@rPRd{=&WU;_6N3P65;3 zllAZOf3IKKYux!!J)GHt7`wXjd%ECC)99y!mF88)J9~GI=!Zp|z2`jgNVjptWu=w# zaJ^yYua0e*rcW}i9zOl%HF8+0<9^r2?kzdS=cEHh1>ZM(`DXX}#zwjSfap^7`#<{R zzjf`U1e~dQ(2ld_^}GI^YMvq8nJ{vFKq_czi}Cu*8m?Fr9#`#v0Yyj17z@*vy z%%@SzPZt5jOfe8oc=x4C+l)J=ar3yk%bOu7>v>*$mogHT$Rf;4zDzDnZ)8bZiOu1} zRcrmDc5>4-zco0!M8w7Yp7+NQtfYK1rFB)0IgZgXKg3K1y_5F2{&NS{+)B!d*%xc_ zWa7ikDYJJ!_clNJ-SGWQtJ8S_#W<-blz6n5ldl=!v(B~l4S*@Iv-rJLybF2ea?bRZ*i{F^S5yR#!B2oSva;>!;f=u2A6=*3TQAz*mHmM-*4+7P zMduOuxJHycB|3@9kVcj>2&SLr4{WS01}*G0j&?nKk7&(${mJkb^IFc1$@y)=@`t~i zfNS6G0N6`LNwBD*%N^2y&Aqag%YURK5YJQR^`J_*(@`0BAiYw-V}(=X@k zixm-3%@~~hzD_wwWp~h)G zmo%SqmSt%-U8{8Oz?y<=6Rw}Uu!`2xNCEuW-m-ABthf<@Mv@r-iiQ#jc!)a;umNBd zv^8a%6lhXJIZ}{3fV@C%hxOv5*!@telX@*jCEgV&K#W*t=|-_TcuQvHmU2ee!6u|S zK*PcQ*^umjZ*0iyI2i#xuAG37DFKai?ly+2#l-7U(mSh8803*zWnc%C3qG zRVnKqFL~(RzI@N*i`+SSj32)WhmD}H0JIGiueyF-E47)hO;JcLrHTg(_3t{9%sPT32Exl74frdi1vf2`lo_ z>?S14-J5965zhBGe@8u)$ZO4h#LvcIo|}s80s=IF4a*d1DY;SOfvS?8YDIXt+=(6q ziSetR5|ZnacYgn%2tq)L^Dh|#523n(?k;?Gro^>tXUEp5KLer2#F}` zp)Y>ndoaB(+MKU(@%&dXR5K|NI^$R>2!CjO#G;T)o4l%;s>QcN77hffFCDK6EAzi{ zixj@?%JJNnnMR+g`1j+ge52i|m?8>BdA-XzNc6%o|O&k(f6KHPia zg!q1&9b~$1C52@kdEn>i84THx%eD^7JZ8tFBP+!6a^k;Wh_aEF_X72cXvO8AoMo%8HzFbGXXPE5CV*w^u*Sq z>T-R50&RmS_hN7nGDQrSGQ(Fae1NcK2d=893bAxS)ZFk=& zjkFev^86t$vIZ)tR$&t9Y`G7NEJrGbUzHV9@3iW*jUksWKnB1Ch_^&rApAjK6KdexyiKD99)k)e9Y*MZH_OfLT4ZlV+^#57;2|h4cN>0pe@x;oOC~+ z)zkvsh$>5wq5cBIfTHG)B6Z^SyPx?) zUXrLYVlIvor6yM~2B|42Xgd6}03b+SMN2SKkVvYTnIRdKV#?<4=MGSTbXtUp$Tmi) z6cPleX$GUPF^_h2(3_A=YtXInhN0%X44P0l3)pT-#jqlV3=I4Lbq4VCW8!G?$mbHx zdBD)GRUlJD9jo7zLXCo8b=$@kM~jN`=-7s1!ARNFu?)H2*+CwH9ORFH$X5(p&GrR;|?{&CITEo zudRX22J{HtGw)RP`Y-l_yo^OoJ0N=Fu*1A1MbS!q40%K3Km|whg^=15gNI!#tgayN ziON6gDDdQt(>=i19PkHekp)5)T;XIp;8>@U_x!VPWozI;oA(}l(2I_{0udzQaR57% z%=Sl851zQ=@b0d2szqWBE4mSjiG;Aa`;+%7y2h=d7h@4(O*B-jq0`M&pwJMPp?i>R zZtloGSiI-J_7v8D`;S$7JqUH2hU=pc%*WC?g)BDHX($R}XU1Nx(1{<)sOV@hv`8xQB%KgRN70mB(gJKWxC0rwp%7AG&PM7F6`2E=tMpa^a8-y z$Fu+%u>1rLFuli$^mO0{4+{}Nj@1x4G1G8e zkl-T}JPfy6nBf%57!Mtr0_zyFT^L=Kb&0}WfZ{A7O3e#4#6YJUPz;^z7FWKWVN&_} zR{3Ti!U>)9b*25f`i0HmCZq}#w=qzF#ZOSMXag5Z_-Ibhea|H)xapHNtp(81_ znO}ekhZlNj&EXL#;O2OC}N%ML(o7iQa20NaE)3Sjdg-U13fkc=^-9Y`q( z4PfBz#oEh`<$DJLQD?uxV}s?3jAq>B&;o7Kh*DtpoyO+KET+E|d>B$Bji_Ytq}ZL@<39 zz3q^tDl@I*295jH5}}K+8{2uBiT72*1g@Uvwwk@WcW9~|Frj<1zn-yTX_)Fj!qdv4 zcz{B!a3$(LNfU5!1W02bk&~LPdlqSd{4EL~R*^UeIHw#2y2ejhM>ks`5s_!J)tu!| z+6ZtQe*W;E%-rknB?Dr)tzUEtzswU)N&klBjeHv|8*@&%R8LmO)za1;K3Hsit_ftL z?8g8pOV6+0yrQY6W?hbl8DdnMcs@Zs;qNZqQ_wSCMbqd6@@nvY?oSXQ7bZmo5fmWb z2oR*~wT4_@Cg6(hxPYqxEp7H0U#g{=jyO#oBGXSv-qTwb0zC4)41!RfYk5AnvZ?@= zK2H1*q`^;R)XdXeO)<$g+)(CFC8iiOTf*HICS)<(_r%zocyl4l7O6|Ovar+&wXQv? zv#;L@nM%jKrW5M*FvoV6+_XeoJsJ5fQ9BD2-O%Q3v7KtoDdj3AW5}qh0ODxuUZ?c^ zonKAs0u2XsEllDAy4Z(P?;P)tAT)9a#gDDs6~bPsp67l&2qZX2S{n*L0G1k4MaM$y zU#+NgBUo&tDROD?vutgu6 z$vh*~WQU|+{T*$fL_<{ok!z4Ms}P&X;K?@td8i<86Ud?N6-8or+RV5&i{!$vNmlmP z*f}ffd?<-?nE-G5GLE5WaKy!MUV_SJ;cG=H$t-XtkI~{*E#5iL&2$J z9y5$Z=A_I0Z#OUgG>u&c6v()8Mueq``HDL~r7+-|H6}NRrF~gP?#}T)^7OQ(({p3O zwa~CBwpDP(Bzs*Q>R?cd>ED)$Pg`Bkj>SBA`-0cNmxgQOsvU)I% z&A$#9>74H+T5O+B#XDnxNRDNT$ZbFgB{!m%uNpQzl@F0|GtWE$H58dnqfB-lt*+Kr z>Vo;r_lw(*QPdIGU%B0~YyloK=6UKKNyyjY1P(ZfBzwi%JLt zoYP(MgKYphDvRPh5EH4pn&n^U0?{J*Il%Je!fsu+o`AjnOrE|mg6&uRG+;0Od{g5g zR+S@R@;h*l+Fp2PXkN6y=UZ~UUVms8&15W1%yF=s96Xn=>-)>AuD#hMMz;^zvH0sw z(T=U*+xbokg=L`bXu3uUGVQEZ6Euo+72fBYivkVZJ-dubEA;CA%yD6TKRwb1$+W z9aL$uM{xJK(C#MGi5Mi;VZ96YwUGQiXlN&fCbL#j#TcN!QdrYs50s6di4c~D!7IVO z=7;X5E~Ls24y2~pIG}(84`-?Nh(xgy)#dw*-b5cPYfApoG_>VBL&*Sl%$xtGewtEvBrKlQ8*8`v5_vv%pw~%T29Y;$tQOnb1Fs=F@Po2$|#Y-M}=2`#zPzM#5#rj4r=0$+WqdPQ<4x60#X752t8D3ViH0}42T#I zB@_Vx6%Y^=brX6KLlF^CLsL*xMBs-F6S|6uf`~mJA}T5(HZ0uSxifd(Ki@wylgVT@ zyE*6koacNV{=TZELI}Oud%vNqlILv>YTf?GI$gRke6M5d>gy6Z4tOW%Tf1j4EiBZ+ zeIPp6`$cRtV=tM*y3@;gnYC^Q0s)hhyC`s?zR6YC2cAA7G#q5E}^_oD1TvO zX#ey^xBPWwmGZKIr_BiP`AX=r!CAJ^Rq2(3sV`YypGW_*4=yCjdCr5Z*7eMEnU~kK zL>jKldv{0-TJo^pMgnH7R~>RSOWaNH5T4ncBrApS4`Vuk?1#I3_l_+AtW9NyDsSs2 zJ!U@QJ?RpG-wKk6K}LT?Pll@UYyqw4=;G@;cf8)nn;&l5hMCKdJ0zQ5rUL1*H96^- zGw$Bd@Va$WH=FF(M$-hQ`-?N~5j?586>?AhvVtUDu3VGRz8jFlYYzKr&(s(% z96q1v;Q3G6|Cn$&7z+sJ6|eHJt71S!@ndZr&L#Udc|li;f=4L-CFhN-FP%QPDS^B1 zT-3c9g_?Pk15Xx%x!nuSI1PAXRUd;40d zH}Y?hW$Mmd*bH{;LX@5R--6HVRo<8Wuo0Bh= z0*CU51U|@T=FCcT z@hWQMpDgt2wdFb`FlCn#d<#XRFab%k(n`iw(6QBOU3y*dDqlb>?C%q z+)z?4;~sw<)?58-M$O zr{&FHv-9q1|4;dDxa6^NXP=d)*6tRCjv9;Gg;3ED_hX%Nl6OpzQl~6T0Ha8*ttG^D zeRg|W@>5WIy6m?Yo)hh(Q0XN=Nv@>=<+bVb^liDd*@iqk;&(}FuM$yHqq#@pY7-w{ z?P|@_&8r!uaa6kY@s_j86zEez{i&djo%A(7dGI3&14MdOIxs+#Hl?@ZxI#k^ReuP0 zO>D(mLD}vLUj}u6KU0^2H|^}V+qil6n~sg)2Xm57Ir_08@QA$$^jeF<#Ay{~NnErt zb9i4#RyjbNa($$dLi-Psx`}~p>f3HQ;>MVe^F_4SH0vfK{`N4RS8f6X&Yu8D{--(a z6av#lt1sCw)%8QZZoGbW0)!|O{G>{o*M(9nucWSKw(T?Wjb@^Xl1i1czV}QkT)yUCWUP zxUR$c3Cd4P>@*e;62mO-I$aLtjDl@vIaK_$8N=|xja~#`_!U@8r_LR&x;7M`a=peu zS3`Cr16q)w9}z028-lJ7{3!s^IWF`A@~!Laq$@vYC~KX;fXl66g1w%Uz>PisEB600 zk-v`!()+uu`~~6wXD=%67Ktfh66r)7N&x|BIvUM5B>7KS&1FdQIU19D;a8NOdR-1B zM4DKMrVXsOEWI{_FEK%je4Pu!k8&r`V$~e|s<#X*aSDr4GV|^kt92Z5?(rJ}pqciq zOmj!Dk<@i^))4|c#bTVQxw3KC1L%`zP+`u?kA;lH|HC5+T0@KHgvI6 zJ4bTtrabA$GSQh#bNpGKp;y>e6p^YJ@7Z-bz9y3NcEXcNBrB7Wn}qGPQbR&M0&7O1 z5QtzxUJ`q^$8M#MJOBX-*C)*pI|_)>9fV_mz@Jr`hkS$O0U-I`caI!OA5iksD_H1h zP-re&4EK^^hyr7k2??N-S<|Tf5I~Jl2r*RvQiFfP%7vO>Bo?ob>Y6G)oXa_d+)8tI z^a<>_r}J_)DomS>S=(_78+Em$E-~eZ0}MiEe~rv`W(jVh0pCI4+Qf?1am|Ph@LL-CH7fkg~%ox2`J|k72->K54M58R4}c{Cf0u zh~X*M4JQ~+CYda3be1azhLDp7^#Ta}8jl?gonUDFp3e*Sueus&KUPb~iDMf)RX>=m z4;*MA2YR(zREuCh0U^dZ0B6n@7n{c|`6SR+sEDiB;Q(>PckyMdCV0>noYh1Vl58zI zTBuWn8xx^){IGN2tx&We{0F! zP+E(dNt|p$czAjJzwf}~vAc!~&l;6K@5Yp7@=VdViXZ|L0H?vMlX5}Uy`35gSgF0o zoeC{69j1HF0|;p>S|*s9o5QZD$4R<(27FbpdU$;@fAt~53;Hbr`P8I!+KaKmMLvo| z;V^f0&%>7FNpLm-?}>JApO%4&aWdaOv3lgDEJN{g&d$uVH);om>-Db`+*^O$7jR52 zrXAiqBG5>++oJcyIe@LEPDic!=s?~6(a*wCtqp^+r2r&aq>@gX%giB}1e`xoJH1MG zzZMVYJ0#xD5mMrwdb_ctTY+NPqF6pcEsOsSN`~*}rnfhKe0+1d9zy^GvBx9NUtOJdFgmGE3E)jA z6gyjlvQL6Yev#oJ9u(73;k|cbi^Z`9V_jWbj52BCl|YW8{;d;hJNv<96|Y&nWLnlr z)d0+z42si+Lx==nk1r-qup^Q74AXPS?hq(FjGtFQS+8;$-g*J!L1$5VqXC@jy%b_n zpH}CY;X(VYc3c-I`45M1U{0UDI@X?d-DP{7+KXAw-7mryYjaTfV~+C1n=~67(fghh zM5Y7^cYJh1I8(=gpOHvp-B{qBgM@0)kspz3h_&%n1Vl-~9?D10Q&c0mzQ+U|BM{~J z(ISaVkr?Lz+^ii2Zyg*Z-_{^ulI`O4qC{h0Tbe+;-el7coEneQx*1_6WpMZ9k5B&@ z(5H16Z=bxdX$$PFEw0nPa{=R;-MuwL_r>@B2KRqT_(nK5xBObpYXhjqz6}nO)r&{AgGtrmQtzJY?a%rGb=uLoHiEu8<6ij_fCA z8M;w^&{GG^IHCq(zaj_ zjIt_l9Kl2Mi^E?!Dx`$yp#1eo*tKQ zRQdy`?qbo!{T$SXcZwdh;QCFlerx$HC7rnUsxwJuEm!11hDZt}JxbSO-9XX=a zi6zLE3REkM9-`>pIz(_hn>0zQC*yK!&o6v&^SNUErwAdQU45Vm6DrEt(|V4ZEC~!6 z%84F|t3P(~4vJ3}-&=oZ?=Qx(unYT_LoaC>dPCPBW@#{mj`K;xtv*=$l{H4cuC`t( zIATILw%~AemNZyve*HJBHbL?lIf^pwR7W6wlhyyD*SY-^8|iCwRQ0~lIQDI*vNTHm z&*f`TRsu&c<^8M^>Py!*O4b~Z^%;JZT<6C=;*p zl&F<*=;A%cBOjDl3eP{da>(JQ;2Q`083I>}?N*FPoItRim){k4#7&t0%(${Q@FY6I zMoz=gnt^psR5=c0E!!l)GoeLH4meY5X5n`(IJK>2zN5Id=*7GPBbpo}&f83v|1pFC zxc1i;?|nwzm!+Qo4j9MzEQkUmMV>5tqBrGSc=1-ri>~vETv$P@y@}Obx$UMBws|H1 z+frI)#n&&Nvykv%UE6%CICbhK_AHUkB^;5LwVsjfD+WgQ=I+kG zWQy~s+aHEBJ__wnxBQBUkArDL6j0nzA1~(@iVs)rc8WjrC=NN}pnQ>i$`Xru(2l2& zYXU>e792+2PT&h2h=ucJx|w<{mk8HikABO*zQxM@>D4rT?RAc#y!9R5fQzu?3Dyk5 z4;)J>^aFHT&q%rO+e=1zd-_}EOMWQ@WTeQgPq^K&U}vQQDWAA*)zw6q&JOCxTK0ys zQaP5_rFq%yk4nBx96n!K{ROjUUgbnQFu6(JHVh9bw3h#bmji0vat=Qi1JCEntRfJW zx`-xHLH6vE?OB|DN0Udb>u>vr6lOu2v)19Sfhq$trN)+=2*tn0uN%;_Y{gG)=?E*V zK-mGvqlptI;g6S8WJ2OE`lgSZLq!vZ%ehYuY%bTjezUrfO}EuY8uzgZO- zzL#i}1#_kx)_-%%zS>*G8ooK6WEibTO39Z4qk{A_6YeZ z7uW0NSL{}v$EsYVARGf4P!qO=zpAZhyd8fpY#71oR$VVWCoZDB$R0s`vkv1G@W~mk zXqA!HzvXX?TnOH99^NpG)c_g>f9c%XMn{Z5q&MJI8g(|J#1TgA@e1#K!`;k}6q6Aq zRa2X1wszO8@PD3X&#hW=m zS|Y2qZ_3iwLT;rqit|J^?bDCZN35+ID)dx)qVeu@5<>-n%(G{1Qmz zz8lP)3phI!MudNJ1&TwIA5E=YyGk&|NG1;v*K-X(jDO?GuYLxFc;zO-^_|WmZbSK> zu*wjl+bZDLfqhQat#L*F;N`uI@k1N#)OxMUG8benfP%%#=VzNzJn;6F_@R zk=rEPvj;#-f;<&q3WQ5&FmJ>HS7|!vVf1&*Bd_$(Q z92N#AU`1LH6bB6T3_hbLHKxpeYAhqbj=z}LM^!|VV+cGEQ8I(sKa%@xs>tI0F>)1X zg8{YzfU4KmxTER3C)R0X;j!(7Yczo;PvwqmC|M@gM1gLybhRa%@{=Jssx=^GcGqVJ z^@T-`Ch{$=6zE+GYnk-iyRQb|$xk%le$OiAHm#z-j?T$?Zhv8GA|mG*Vihgxz_#{f zOTmDpNewhVCC}G!*kg{mQ~~Y2GWccv?PfV=a^+HTPVaY2Cb>4$|GPRF^aB)Rq=sW> zero9OZk z_?$Yw4yTscaSdrJ2;E096O1JmWI2wYHj)wM2(K#&S5KDysy_4Q_G6`xfIRI&({>HY z?6Ii5d^1xufo{^iIWB*1dR>tQW><-9Hy4U3^`fugm&}WBmL_i}yE03b|jkrm-OH1#2N9YHBWJuAX zL{6jX)Po0*v-C>l2>V8U<~V;!hr$=PYL<5XS^DqbL*bEhB5S{6Whsb7M7z3hlSCpR z3W){)hEx|+ATLY@h7clp%Al$>}3h zdE|NK5Jp4CU!;kUvJVr0z4wd@l%Ya>-PrNsEWrRmV6#r)<5L^407pU~tCEgn3315m z=*>Lke!ps+Vj`E0$kEDO?Jr7-?#m}ayWZaoc+AmRvwW~{rS*=vpH|aDWk%~S{Bg*A zGhDrD*QdE(HnSsjp5+$Xmu%mUo!xkO$HyhRxrr0MK`{p1r-s;wBk!39P+BeG7id#;w}H#&e! z7m12o-ZrhTbNUU4s@DAdslT#V@fHOU1N>CdFL8X|rGI$!(ocOMQ_hiET6qHtJBgVT z&Cu@sNRs07tqqkayFgVK+LJGZGaS`9n`z6MAzYH;##+(y6r&SJ5{CAu;Q=NbW|9;& z$r(NSznITU0HY=mgv?t^X9I)REzVue_;aRp$scOP>dj($cn zP>083yRm>D5{_~1k*ZtMYmn~xEVjYMNgsK_00h@b{AFkWnU;X=!P26Se+|6sRY-Pit zxc;Ds6r*{=NKK-OksUT*9L3W7kFQj?+jC+PO9qOG%JoGT`ooUn?oySnA+=K2VJu|j zNP|ujr}3a|!ES6il3Ey;V^zx-Sey3l20)CuZp8qi=#Qm16`o8D*Can8Zq#8c02|4~ zq#VVRC@@ou9UFhd^NWrG#Nx?I+u8o<qIG4~nuvCSV3;h{kOVWYUWFalK@vnG3qJJU86>rk)jTtvMEbN=2V85i+N<5JURCNh$)-RUrr|lNl*v zQ0Z}Ogf~D3(o34mT5z7LIAE`mwl%+)EWsaR@pli8o=!i81U~M=z1_=k0ECmoeGuTm z5uEuRfTetPB*$9C%k1nRM)#6YzIa;qqaN&=EhXjvlzbDV21_me37jTSaE*%aW5D_P zn&5tUK4X7F3i6exk4k$ty0YLaAZuEx-?t$;@Zzd=bH9Qc5}G<)a02*w_gL%`@6I^@ zQb6*MWCt$cGb6V}7Dr{`z#yb36bWg9lZ0BGe}*XT(q+!DNjETgQR3&t#N=rn?-RR4im2!8=-&hli-)) z3ALIzUWj3)u5(8@S9`>*`%4P`6SiM#g zx1bFgIq}O0xurPrUh=eEULIB#aGf*!tC^g4_@}uu7c9_fS=IULNrV3vAEBHzhcepZ ziAuk`i2yJVU%b|a*or`cfRep!>dodaD4dsE&s{6&nRO;Vt=11x>@+kd4NPzKCH;CJ z?6aNOYFc7dr+j|a-Nwo0kMxXFiPDzIp94T%Yh?OZpzwO87WoQ6L)GCg?;N#xT#2I2$)`(iVL0${x1jHQ??mqaY;5f*g`CIH z^P7^tv$c-)fuyC@==U|xX1DLU_UvWJ@`W{v4@&mO)nj_hu&Qni@i{eY!)S*d-D>Rh z`Ktzw;YmYE2>3(=kPNE8`572P<(oLZ?zU>X^x{^>HEHgsuJ3JG57hE@4@!c1nC}o6 z;HW+7nPK?zQzu4j^LWoQ)a$s{ z*&cFx%3#ytA*jCn*4kd(-krP8*3>xk^!x|%*E#XOX3j=+nZ&Bk_d4z}1@G7nV-m_3W7nZR@sFSu@b9Rp)WRO_QbdQzmf)U@``& zrU`ko#tXIkN4OD5(C{BYnCkeZbU9q$$zQ(AnSK z;9jPbWD;lu3+0mf6-2kMQTtyg+39zobYWcBUb0rb$zH!KXqs(6^6}mmo_6rg=2NeAoJAAknnPlcG zNrFqYKynM@GVNykrdO`Bc4fD&<^lAYcDK!d*mszxStI4 zQno;_E;x!?sg@jQPT9Z@rB+ z1M*vb4Q8HnwD4So9(NYJc6P0|vX1im`C!$7*D0C+XA$;z;Ymm&0f`Usi!j@M8lM=5 z=SIiP!yY>tJiga?9-w-qlN5@n!0^!Bp&@VkK80bi_f=2tlhl*+T!rj9xokb(dqckV z$P0ZkZ4fwgoqA!cVP6wNu1f6H!|)!@_tow%&aU%2-LUZyHmZxd0slrJL+o=QTET3q zS9;^d0|wmpe(Ko zhW|6*^*qw^8(49DfcuHXGdvw>F>~)HAIHfhdwE27pjBK3xO)epZ+noXUeO+gQ3sX{ z<8E(_5#*|6#6+`aV&eJR+6H1$41t!IxPjA&=+kNn1p)1+6H{jrKN;?f(NU&=vbKO^ zCL!eytWY_ZJyUX=$a!E||7MW(iNb8TGX78Kx5gs^ivag?u=SS zlNue&E97g;(TeXGRmL>4yv67wzHzhw5d@{eH z2cL)+qrDhtTNpFnteycQ#Y|!}P#Ysg+X6rXjA#H27WuVM6v7s$-XgB@7og^h)i?sk z3yJ2yXFM1vk@3;Jur`s2m^MZS!N_5ThAqsUZ$_swM5^FX9|lf_({EyE2%E7S80`h0 zR5hs$7Nb1SbkS+-rhXiCC&=k+WRlpFJCEI>59%15A8Hg&r>$w%Y3~>K4G3k83PQ)z+?B|S|8Y8gpZ){^~NOXbEXo* zb9%HMbs9@86|}73lQ=yJUXpGPNe^@u!C_G{WG`VvG>eL4sZbL2Mg#;Zt1Vc78s3JU z1)J^X)VT~Q6;kCwc%qqVjil=&XvqZ!dJ-{g29YB`%t^W+U}zk)Ol2BWv9!iuy%A=+ zJs|O!8zY%%RkU0W22fmv4wa=wlYPkCxcymzN(<)sSyYhh@MSMWFUeBST>~P1-M}7<{BHLnlK( zfGug-Ak|DrISzQ~BY1Pb^7jFjGLQLe2|!mc5XfcFa*;{pf;93D1o<=e2S}?D z5Hv3s9@bJlm)%@1WS?yHC%dhRxIz zS`2FVh(&OE2aL{V=;bFFNAa;$K^vo0+P^JDN#&~ZTI-?^U9v_pMwp;;c|_~Sp@K*O*_8f^diXl z06K^*Jm3H9S^SxPr`jIS-vqWg?P>^3Ky$?4aQlaU?KY2Xox&4veeKmT;&mGtUe|Vb z7p3|*GrSP-K4)x?Rsy)^ufaqH&oCNW+iym(~wqU$5f8MWqZR|4$BS(x+#4xaC=PnzHr=#JjcmSB*hUNjd+0UqK zfO}M|7L}X%XlHexnOwswaG3#3t;s*|En!FRnIEcNYQf&|k zTwlhebdx3ss6M&4<>-HV-g+VF7xWxtwHJoQm^un++*QbpD|hHPhy#7$X|ED=7|`kg zU=CYq5SJ zi+bXft6*)e03kFXkk6*=1h~p3z;OE33I>+8YO9%P^n`Jg-?=JR^znu7dkBuDmzO;* zg~CQOrrO+x8zus~$4tZ=IK8(WW7?)i*=2MzL5JFc6@GjaoOF7exx$o%D>nWbt~<&HqveW4?aDC`%p(_87sfGajrdAHj;SFDRGvQ(O4g_g1gqOVtux)p1Whr1(+&zYY0!S>>jU4Td|a z+|5e6_u1thV*fpa`2L#QyJ~-9Q^o&%Hy^3LHhSjGh?6A)BN^ViaC|{l-cnD>y$9z3 zHLkfqD)ZgGMS#Hw__A>R z`a}N8RoR#-{)7kf`6$!g6i|J>N^^uMpY#qr##CBNK(LoHpgS3Nb^bnZMvw06o>lvM z_n_;8qJQr`{CT(hXO?i|p3VNdo&zKLH{M=65GDFIt9;{A@4xp)4}9ExV06um`HP}W zzOXHnfSPVbvc(oZn(tbgw&sd2em4$0ywk6|!)ISA(eM1FEHm$GsSW;iPCMbZzJSPw z;kDe(Ib*9fCeh|H{IU-E+=*|v&>WQ~{%O*2vSg=Qk}CrMM)*7oAC1yB>k>xv3UC;w z3J0ZHra;Nqy0|Jycc55@8L5IRjYgFj1)L7LQnuCisAa@Jg=2Zl+T*K|XU49S$F4iI zhL2w1R1p`DPxbN=GA3CCB!D_B9AUb-HR9;0Sf!rjZI2ZJ>qN1TNx=atsY22Gm>c4J z&^ezbQEeYeaiw+DMC&T{hMO9*>2|V}UnM;km&_L;J2pmHy(>~&MDN?8K%FgnaZN39 zutH~b{9K$;Lmyw$cTLcKE4!Z21|5@O+HZ^^x zFcXDITXM)3Gj=?Booe>&OA^H`O{_%~DIQ+cf^=Zx*-fn{nRz!>=y`DtP73}wF=^4* za}okU@e4R6h0yQw1$>2pr+3V+Scs)J-VPj3BHFRGH6UURR2y~JTDIn{BH@|O3TBqY>(ZeW2Iv~5y=HjEg>xW8}GC7Dsb zG~h9Gngn#ON}`mp8-`MRow{Aza6YYc$$f7sj_T)BA)GF!nOy=(DEF{blDioPxrWqf zZBA9Qi&T2FA!K{U27b(9z<9{E^N+?iCEra8R#X{kAM%MOHkHw+N|Oqj-+d^gb$Va; zs`4h1^(6Dvmx4&^Geudd2AWNM0zLC1J<592*>B3;8KuYywo5aUG{>gYW}{t%6l^HF z2?_g{Jh35exhm?dpxG`Di3MJ+zmO_vYa~6&aps~1^m>wZCm(GaM>yZF*NXSp==+B} zUFvP99=tigKjh7kkR4CngjfP%C^WN`?X8sgaVo+hCFwKZ+Y-kpu(?SXh3p&?Wp&?43_`1S2_hazXK>j*Z7~-g>0Z}vz!j~U44RaJ}L)GP?53VL+INvyi-5%n#jC#=PIcAB(Hp8^)L=Y3(hF z1~)qQ7I%gE!e8CTYX*j8As!%J2)le?fg4$;u$nMmQ3x}-d&GNJG$54##wP6v7=fLR zRC`SUGyoPxlaaNO7)ps8Jcc)Mht!JhXV^3Z#?zdnr&+#N9!awyq*9dre?N{xaKEX~X%`dM)aQV(+ntAG+d-P?HM94g!YV zh0;UY8^Tsxkb0C6*^q-R$Xt9aAZCaVoA<~8CP{!?G0HmBn7PSiQ8i1&&pOC-9!{Ev5G{gD;9C@9-=T?jIV|S_dD1V59TO(lzUxY{4&TG2c@|@Bh z+(zrkvOMBEA@zI)+JXT#a^MqWF#tRd@pPDnK_wA@(By(=!+^Z`cU&}H23brRJdyia zg2u!Aje*JtjEree(WZUX0l*)-ec$m)uQ)qUIoZZ*$b9EEJs!IJ=*>Rwvoqx5rzn>V z%{CV#)TpmNcCX^JUE{5Tf@y?>$~&(@PM{W*j$KZK!6UN*pwOK&$v6lNOBw?iV+3r*>w;K^hUR6!dZR+X};lw?4z>{ z0K-mNyy@4hS3tRP%Ei3`RinoCIpHzPO|3ccl9LssTIg z+p8TP=eies;fh|CvD}@{MBeh+s25CW52E;fzpT42@1&%E+Zp}q=+06_u+$M-4kE~ z!UyI3|S&@#Zl*5>-q9S=TLB|{pKcfP@x7W z?-&zvW2BIFm&hdoSH$p}@0qV@D8Du1U2GGJSV^v#RNU>r7Dg5N(RdIp!#|Zyw7G_* zLK6YmkW=SLxxS?%95A}&Thz%lcZ^(-FMv!F(a5*4WCF7b4tIVJ$dV1K7bD)9f`}?~ zjU@gOvN^JQA*q()vTIB5(rE3DsHNdyu8VtF+3dV#^mYp9(TIB0H84iq*NorQ!@Ao# z^3sO>2$Sd|L2D9?-2Kijr)NAYM|3V2$=C4Jg0YW|Ko3xD_iv@{vs-#_pZqOSIcc(R z_n+5yj{9SN7UIQFaO`SHvrLfkITbe^yC!Th{>sNL==J!h_ziBN@(u}iZu?1IY(d86 zBs3n|Gg>j<63?FsYwQn3`ia!a;jgBI_N`O82bE86DnUBQz`k9jneW!!Jhq}b$Tl!`&Wv>Ta-+1mX<-!YtVK&W*PCXuU6}|k7MRSYC{!1*<)kH5x=WnDbHpd z$K5tY;A4q$Ms9O;NMhf+ri)cio0L@NL0uwWk22T*bZd%Jy<*o*opA~Fgfhfw@pEMIuY2JoxTM4 zsZ1&i)E_VtBamkg{A<}qoIjyQG^|{=>OzFvCAxfqS&Y*VIKy(;ySBHdhcfm0B}r~H zzbR|)d48AvALt?!Xq2xBk809f916^?*5^<~=C(s%=n!G0nCi!vpf_z{VV@Bj49?OW zR7(vt0$O7PwytgtFQtUN0C0eTZBJ5md~nI>bV;kcz=?u#k^-vY6VXlk%(6|Wh~mYl zpSKH4g#zTj_IwAVUWU+h(e2#TGradxD>hSJ`H8GqVsx&QKVN6E*vkY8)F-!%0SI=w zapUs!d}{Z3dj;R(Ah#-M-OFSyGx0#uym_H%W0Z=vuSMrUpjyva6qOVKnk> z!(0h5cBH|JZlDy%JNI5pQsK|_^nDtTGhXz^WlV0TMx@f1N>V8x5aCrOciAfk$X%4v z5Ls0%6tAVA+g9jH@+&USOnXgrSNF zG1ArB+C8=}9(-@(nKpL4LT~?7pnGrP+N;2UPZ)D40O$e38X~lC&KHpS4!yn2QU(H( zP+6WP9XSc+V?Ymi>6n;)7_tDhjKV;?_LLT zECy<18o7Gh^iZ9f4}jl5Q(QeONc4I((zAN{?$4i#?*CGQ!^_zoY)<$nCoOGbl+P(^ z591mEW~a!arVdqu^*$42(jHK}6uEi|0mxwR%b)UJ{OJR0pmOqS{;=1}lbBF9%FiVM zH)Pw3tC5tN$QK-C6F=UIm(9ijavQgAa3A|p7>wGou5ZhYAuXk$`ize7J!uy7l;dVY zNu32JDj>G_T~nQ#bfNbIy5I!q_B6m7BA?xWi{#V9Dr+y5eCid{K*^d6k-e8iWXTB{ z1$zG)`1Bf}n$ObNZdC7QL1(p=J&PC~x=G*cgw5_tZ;fLs-FeCmF%(oFZ2I7#QBPSo z$dftL%#^3%P<1-Gk?2SnPlJMPxLY3y=>F|U(4~7-@XnV|y=f8a-t#CfFgQQ+fi#J| zlRh__?Kjh~_PhyQYZOVRd_o)eEx%{`Elekd$kek7BtOY#m0Dl7UFY#{cB0mw{ns}` z>Nyr4UBHc*TT?osp7 zL(!YRumDW_JC9*K-A{3o9(NP?|D`yIHahvO(vJvd^9V^I#CwBvPV!wADoL|q$V)zn zb4MlpQ(NHu2qF9}&UZ8K^JWJH#9QGauRlhND6GO5yi3usvfuXp;C_8|QV%)1P7^sr@Tyx0Ps(kBRt6iYSAc?k z?pCw>T`f}2J;m~wW=g}VX#iageKxJKg5)~b{Co_Hvb246Z?_&bV+fTwk$2CFK3_4A zH#}t=*}9XBnY*`hPmJfbfxh(FKG5u4YK0KDM;!PpV1vD&;P>NlZ)bp6iD^%!=avBv%7o-O@Z*>=nHzfHRIga zh{hR+-VJ3fR|vA-WAnra7jDxV&HQS4!PCmP${Jcxt5x{tZ!yk}B;(kMEQC@n&x${_ zB1z^rtySs-flg4Vt12O(j-1$kWUE@`-z&kPYav0J!kcrZ15FPi^Vgjd6pE)J?Q>mf zdJwt51SRXR%QTexdDDxm=auA>7Fj`6tB$dua`uX&(MOVbA=yQ?6=w5_@xfj%)O|brT{F!q2>lL=k zth%jXS64-f5fvn$q0^`?k4guDTq%0~n4!W#>XVRQl{QMj-nQgy;~2xl^Y_k7{DgK( zEyxs7sz(j$vKIi8NOkz8LcgQ|=$`%Vr{Aqu>71F$)ck&BRb4=5cfb;3C#CM@Ly?t) zN>a7O&P3{VX9bsT3SWQv;-MbOS1Uc`9@%h*vW2m2XWi+QpSAaBq`io{WPDut7fi6g znC9Z~(>m9Hs47a%*#N{BrI0Yiq-T zpE4+cnTlLPkW&$3$lZ6-UCzQ(@l&kx%dM%{_BcSA_#+|BXJQ*P90M?NY(g#){kB!b zijBH}1Y3rXke5>XXIe*tI1GPs1?-6_X zgE;>E8-q2iAX}8EFTWNck=x<9_M1asW$bR^z?xM5%puP~#=bp4=cF291u7VxB1|1w zyl|C)d??O5U2Rb{691{)yHI?g_s@kN{|&qEAA3Qor2-&{MYwh*M_fSJ@kJo2bB>#R z2w1Ha)#a#|XA3Cz&-D=9@Uq`^b@WA=$ydz9 z{y$3ItDkk8Na^Z*s0Y|RU|DMPnLs$Eh5l=j_tSZrnLQ=uedM{XtW#1bTQ%~qtU7#% zB;+*}+HPAtAfP^CQGhI0@|1H5F7DE-6tr{Su_3nq*p`jd*3SJ?#;!0_u*(`Wc-4S6 zjG$r!tKAl=d3a%Wb#+hV43&XTf=`6uT<2*~tDQ~;eZOxz+#(fWk^a@5cUkXgGgP3T zN(nu)|LKO&r}~49|A(~q3~Mq9*fifHq|)BdLMQYpU7Cmq9TWitr5k$3fJjp$p?4B` z5e-NODN;qz&=F9*7vVFw+sz*^F(y29p{p8cj~rULG8!qO9FjWS|r*AYkTx+3uU9B3LYJUu{}_*d!6A z=k9{2J{UHW!Lj?RxNXuThY41UL^1^IzhNZ%4kLAIQ>edp&UZ_piU~dhN@D$r{#r z03p!}4d^%our%EcydpXZJ(o!)Ne=-o!lRc=E#MI+pROIx1jd{j5Y;Ag?o(Dd_zeOW z+Be93WxO(H@~}*L!qs`6>7bh<)Fx>-umc=zwRmloXNM(>%Nb_6w|%- zqIf*U$a`Vv!@`{e?qm1hlxrHl1KIPWrr(U9BdcQQ?5l52 z8H_%IeE|U!BT2?c%~A$2YD!=JTIge0wCu%2-?PR@S%*e3R^tdoU=xzfcwOjq<%chP zO;#u|ItZgDT6(Urk%$S=854+Bk*k$+3VZipBPKA2rhC_mlwybAI8!o{h#n0*NJUPXk!8`GALyW1 zdFrp@cFCX?|bY6`m`ODc-wdnaOyT%sunU*%aAG)7_Yc zOv~NdsA2``WmzXt&{QI0v*XYAYcEtSh?jy_pSGbW6ly8_Y1$W^!bQ zYo|fpvIWtSWb+=;ZE~97hbry_r&4wr0aC0kA*N&xJN=9hUj$M+bhMIeE$RHnYv2M# z5X`lmhwxmDr)W_E);5wV?`~NkGgfM*c<_WOPua|XrF#q6S{hTjI!6SLVN&SMndg_WkJSpQ58<02Dy zD+ouzygInufU7t|ZK>m@Iu9zlHjQQYzzkK&Dz6k#O84ksGAF=bD{eH!KLX))Y(o(j zvNwfP!YNkJlPN`;L-M8VLZW(n>}e`?>{4qGYbPe8j+|sxBA8yr9EA0FQ$8wKqTw=7 znQJsCUUsmcBGDEy;~K~*C24-Tl&@CzC`p(pgtlupMqgAn<5O6nfVXxcq&Aa;ACrvO zcNk^M>}Mnl?Hz2p^4SC@L|u+mogm)gW9M;5gv)tO7MKsUTxY-z)!8|u*VK;~0TnmXbBn3s_Aq@VSTW|K68PV!iKSQzH&@VcK? zJDqu894QOoAY~}kK~9R9G6F^emf0$=JoHnVQR0;OHPhv_USwJ*dP3gij5w1T%ydDRdhavkVAPOvL^Xy?jjNL?9;_gZc5UK+lp+}Sa#QOn9vOk^T&Ta_1-_=B!4I0fe9qd zrKm>MvQ`*p60OhVMGQ-nnftFQKe2+jq+n65sn85G5pB%ax>~w?%<;j49EYP7TW&3E zmR7THkFF2dy5^ECy9AW>IuvE%q{;RpFVvD;%j5Lk>vS_mobXent9JveXJ1jW0}jlj z75~;l6lb2N6ed#L{VN}B4wlY1^Vacz@>VhoEJAzc20QU3RBxGz?DRn_b0|}5d~yl;&ydK)BO_; zZ6>OrlJpA!?YFKYl2N1bvQ|*)3;V?8G|I6Ue(pYgZYNm|1qzQ~@_~KwnW5z4eMz>c z6b*%x)0QcY0V$puN#YEobEgzmUQEAK%r1uiXn^do7}@%bXsceS%O%nx6RG%8e#<_} znI}r;QE6W3X)nT4E={DxZ>IhIt|C6ehx3;$mKU3oOeG6aWaTwP7#H$N@i~@aV$4+K z34Q~q4Awtw7%ELLJS`TL>9L!3!!olrAk%Qfp8*jnqF=-t^OIH}T)=^2MU@a~BQi%& zs2n22!ziv&rKj`H zqr{>Hqd$5^#$sjaEpy)n=Yvd;^R9ABY?C z2~d)-r)XGxLUH7vgB}}jeTN@sFKEiRBG1g%8Vz?yDn<#FCRvrHWZ+I~3GgJt1tCaP zGA(>iH>wP4`i)=gIr2*tGJ{^0`k?6QR@rrQxz}L0a3fZLf{gp{>d{R;9!Un1ny>iPg1pgAw1Vq9nn5uh`gS^z~iE>+3HoM)?c) za1y04I5!L2%4SCI&m1oe>91A{c+deOF1%211^P0U!MV-ybX7&#S75EH_=BnhgmrOE zRU(sBaA7a|_R`cC!jW>u&H71z~`QAmQnKf2THRHZE$G2;2F}19Evb}Y!V^D2+1aSE)e_m{@`*!U) zVZp;dows$J?<7u~bYnKKE_kvo6eFPN3q6kk*a1KuA0C!j9~)E`9akT>U7x@T!YVZ+ zSvRBvHKb)WWHdEoO*Z6gH{@X&=}L_S){R9$jmV<9TV>dM8a9)O%+T_`#4!q}EQwfKtowe9Uz^R^_aS zSC#U}WXnTqH*G0XpTK4z&qGI7TV7<|eARSwVe;nE_RZ-@*~VWt*Q{GTOir+F58YVt zCJ12R()t@qf2d)|Cn%W^U)gku2Lt+Z&l8H5AK+0gZz9a9r5> zNWt|D8bUGS?{^0^ySpR^%z$t^byD#0P{g5m!KkJSn~IVDP*I!ucs>GD@irgE)h*lw z7g&Nd$MxoY!Jn)bJP8#@ymj~E5!|6TZO^KRwKZB-M6_ThWfE`k%+%v+lLtXfAF$I3h37%tK0#_LdT!CJ7 z5%4mAaRLJY5KQzDVkQOtyF*Gn2(GpW=a_*W(Pv6e4|{s%2hi`6vGA+gb{Ch!52#q~ zySLabR=5$mJvH!Q>ORNxpvtsq+=JneY5t5RO(B8BLExWmTx^HTi%qfn z&C|TEa=LrPG-%N9TMs8=r{B1x=*00ojJU4(99~E+!#xqmoE3V5#F@Sj92^8>O4Mel z%9D%Ziiudgq4C4zf^N&L#CUF@(VyY0bWs@oQeQXBG#l#pu|L=xe;Kya3OAS_Hbwlug{a%@Ck{( zVy`6;LMz37gN&=?44*+{ec)58kBL%DSs|4Yq8KiohG<0#T$8SFCmfXfcihiXhn;JA zb}q;NG*zJM3$7Ur#C?eL?>Ns;c6Pi+leH9WleX|hyRT>$#mkfU9|wrnb{&VZoXh z^9p&y?w)7(tRRFib+dlx=;EXK&a~aW_s0b)L>gwqmR?|B^&&Xlvc=G*rGHPZ^V2dn*9um3h4WNYWSL zB{VN;zyyc9zD^tEi$x^z9`}+P%p!T{r=DDWFy)!!c1?!5dc*Wl1IH<-ZKvu86i7^x zXsFZRhXGjQY9rI9fSp!($Ls?hF}Sq07O$p%&c<$?ApDfjC1$=(HRSOV#R77^f>r+O zBxgAygy5wJyHFu|CdpNM}#0-j>MvQ`{;Av6X!jE zfNZtD8cw`Q!oIpmBtzA9!wj;UA%IzgL|}DbPv$FRt)!4AG<}ePRSCcIoj+Xpw8fmdy!6s=EYCz zubyt$GKeW$vM$dy?Q5)xG(Ru~j~go_6`!nidA{w~;@lnfcK&&@qdo^P0)Q*;ox1{` zxB4#3eRS<}D2cfZWk4z5;k8e17hZfm$E3o!qi(0}c#dT7tNAUy-1VNI%i7ktz53!i zU3U2VyTw;uS(h-gJURFIZ-LJm9ozht=J$eMcKAN7b6@x#x_JBI=Q@SdALo|`Q@Cxn zDt?BqKPW<$^e^sT*qk-fwbh#t;n{lCeSYIpOo`5irO`b3b1~vKbtC38OZ^X=vv%{~9z^1JjvI4mJ+tc* zhOhWN0xlOcJ4X1(9)>kb%sz^wG}+z!qK!11DR#W4-lFz>;wZ1g_Ji9#YoxPn;a{F0eCK{6Az|evNNgGOn$+ zC8YmR#^smr?&v!|@8GfjF5`-Wk6w%YzU6OX_(yT`zstBbtFv{sH*e6)m9}aMUFzNc z7c#Ex#)i88D&yL2ZXY{Pdf(DD7xeyS-@B&wt#`j~zi(qAls~kO2n2r!LCi*dxb@=i zQ*Pj|;cu1BXNen+2?q+zA>E5n??Y>TxlPUVyeU?$P=^Xp?0VkyurEN7Xb9oRr#bco zG{DNAAffR<+W^qpL%9cJOU}T4a;;l4Ig-piSwevwfGB#Rr46f~-LmV*Z4%6SGMjDR zohWHM&K%jfrmpcogm$o%UoF5w zBr=U)@$v-ui9_B(hr?<4Z;{X47T`mV-P8USiEk_V5XRt@JD&;LqDn~|UgK#K5Q)t! zmP6ngh04%dKcFQMj&uRhi_ZtI+Rd@=k$y6CQQDKDK$j#Doopf>VT?}z2`2K|0^<_t zVcy5zexznY1v#n+sT0u!pW^I<&b4AWZERsoqsZJHgP02{12ooGq9aw9U52Jk+&1t6 z4I{VPe_sq2^klBG-=>=jSxfPaBS8XrW=kA*02(TW*}tl|Rh8g8Hsh`_i4%bF2SzJz1A7QOn{g5aw28B|BbA&ifs`?A zbey`pda$r57X+Zi?<60Vl)#*IDgtPO$tu~NcJuPX!cbX2y{n2VT8aYuu#=|S0lRzf z51Duf*iF|gdx@G$9g!dNqG-d0zjpH|95r~P)r7I|7h3v>8Y$d^33G!l zbho?0GL<$QIJ^CXHaYJ1U%xs#|dan5E+Pw8xj4P<%Y2poNTNM?OkSN!><}W`j-P8fkRFO?97G?2p>T+QyU2Dq;Ag*9pM@pgWxk?8mce2c`i_LmzFlu}1fv)g z=!qKoAh6_&Ds?}~e)&VIJ%Y~5!GlN{W_McV@?=@K3G@UA$ zd{$?$*Jzj1VqtHq9*a9i1`tVK}3S_+aa&zG?yR;ilQZhJzA_c8-vM+_K(0O9%(4(G^*>Wp3H$5OQ=Zll-L6^=IsJ;n~jb}dH zX&EYrG7gBx(+tv?-A0;+PF+S(M#2dALKp#|iKkMNnK0W^mR=A$YN9#=@?0!Eg8sgm z!+}7R0SIw_4GP&!d+;K9A(28nGD$uJ7)!f;>D6%$QFjWP(X+PGF%F5~^jYaYAKS7w zK{!=`ig$`>PYivVL3J?3ci}%J2b(3cABV`{bSC_D+!_#{zsnTzPlQ11mUi#e-;fgYf?VVjBa%X*P?{8h+Qm41L?l=b$rIw|Or(zV!Cd_kBdVf8=uJE*J z@{GVqF;NixkEB0EZiEG1P@yR#3j$6~9W2O)R8^=xVDI5ap?N|;Gq8p$gVaH~&F}*v zormF67$BuysaF5Il^)Jg&NBj-s>1EIMwT$)_5ka%lt=7=ObA;A0;r*)3jHi8BFs0O zg2K~`+ljcV4({KB7M`#BP2+T+EDDlTfn{dWusZ zGA%U2Xg_>LjJlXOM*u*=5AX$kBuun`f4>{N_WH$I+BTxuTCPqD3TYndXOPp6m@i(E z)<#R=gOg3H*eVOtp_nh8RLdc$t^>;t1-}V2RqjPNXQ`@z2m_fXtq6hZhZA|iSG9gJ zru->~0t2Zqi4sxv3_X)1v3!3;CxAWYs0K`m;5V5GaB*%%U-0IlSUE8uSwQ#0ONAeX z5nB&3I4=es51zNNphQ@s*u?G*T-?3)Lh^8H*u@S2`K_^H^tBPCujCMfJA^dmonTLA z=l{pW4vSOZ@wA$^UmSEyuMxj0a0HA5svb~eC_&Y^3RWMl$JbGW08*Te<*AfNXoLF&)xWPmonVx0A}VgiGS?pm2F6aZ-~ov+;aYNgBH_^%*_g z9oP{Ptk)hqG9w0E(LK@*(*LrLnN3E8Kw)uRA+>2U+Oxc1e{8tx~HJ{ zbk;PudyXR#!#H9p2{~K>G5jeoks1=Ps}rLDvw4}!QI!l2Kgmu{qx2;M%;b-S{2JP2H3$0QJLP7PRq4Y z*V8kdiI?P`WS$964+xj;+RV(C%)(<~azILK1IV(x;blR41#oF44L&Pohk~io>_2L! z1E9V0%85-r=ybZ8g{7rC$v?svn#Dk(U$fQZw6azg2x4KvUr8vFSj zuyqGTz~}L#gEw~&K@5&k0LYuc2$u;2EvNFepHc&1p`fMw*}%wZ4j6=k-4j)EfCpcY zIgz`Z-yFbAJcx4!`xpWP$rya8x(Yree4PcVTygCurATPHpnTsl7fYgM!T|H^IA9v= zx5yOuF1x8SxU?+LKg^j{LpYQg6BvOaq=Q11;2HpI`Ey_-*#SlgK;bH(B>3MJ=%io< z*Z^%p$dzZos6e@+JFwI0pf|w*5l;Uq4SKTn-}Swa;q+WI?uQR2)RU&oq$iC4Df;rN zH0Z10!kimvMtcZX8uUXnsM`*cWR#kqo5s?4}757(>S7-w6=Ikd10U=Gc zEV_*Y>6*AkdWN3fjDo;IU{-H{as(bch!u77bP3D2iku~JDuU(CJO~tExLm9rk=hr7 zb!v}PisBI{PmE4=HdXiG{Uy!AfV9c8C<0J$1_b+gctGgWA64f09x~t!#F^Zl?=r$< z$j|P$NMo4xb~T$u{K=ls?EGY-c`%-F(d?JP2Sv0j5|AF}eOjOOgnr3tp3izYLT)@F zzliscORW))%s@94Nkl43)p|_wvU<|Z8^EV6DZjY7BgC+>-qMF=(b8Y)$S%B(9o;hs znE;Rln?2>;ByxC^lPnAbr);a8%tcjdu* zzp$q$wVbr(d|w173Bh{Uw2Z@2#^9ziO)UF%q(yDJHShCLA1D@T`#lhsnyAR5xWtdTv2c?OL z=U@=>lfw<1khVx+XYf7v<2l4VC}?@_+(Us7F>0_Olx&J83sFk-t8PFC+x}vB#b|LY zNWR&3XC(NU+Pk|PczT&vi^;g zSuQ4i>69E4lEW8stajN>VVB-Qo)!9g!tc1zfIl=}DRCqnqz zz1p^c=Wly(yG`tLKpfMn`ox9X91Wv;&A#fzd0uA6di^i}6W{kLdUe9>VU=A?TApYr zN^kCQDXs-DKAJ5kR3UkJAkN6b;2u2V$PN)(1-& zRtG9h1;Yk?^p0R(*G0jokSi&-Z%;|y3V`Z@cd^)z*|#?*qC5tBZa=srPf-%oju}{7 z7{NxOAE%x zP*}=G4o0_%P5^!M-Y&ajI{VFrU)UNKknV&8m7>!tm_lCR(%2p(5h521+5`=XuhvV3 zN3hKzZ@FM4X#@BcJf~IWWDwZL&Qn>}&!^t?pnpiA82xQjtnQXi6#RJM9 zhVC7SC*L_d!4|Hl`0{p)p@fwR$l)KJFcx9m9^lkZ2I-e4o5+|nCny$DeEGpQA`|WD zBI7p1H4Di90daDksxPc6t=%jZ5T5I-we zISc$P6&{d@K?83H1!6~~&Ml`Z7h(6bpGZU5Joe#GdI5L1$O}pW^Z-&$HD!Cw?^5#| z>0+RGns8F_IX^@h)aA#f0D!{`^w>-ph3^~|7|)W*iJgUx7r-8^8D1>B{I#}6sZx5v zRdHGISVe=U=SPJ$^|By+ND~0~paH3+=h}%SQdV6>Gc>55!pmisn$H?*p5?1X-zqqiL=@MiB8s}%Jk9n^G|SVV>{iQ*o8 zh5h&j`xyaw^b|VWK5=%X_Kk#aL6mpaF3__ zA%lm+bmn7ff7~cdd-Htht;fH&B=L7%tzGAizEemH5hukcXZnh%y9bM`h+@y3414!$ zx9P3Ye7Oy%8C`81HHxaD+-dgdu-W)K7?IU}GT}hJ@3eVljx}~+Y18$@<{wG)@o2<= zJ~%r`t}?{3Oz8)+eMAb}#2p-{tvwowt%>oYcQ0I1l^~sEvUM;9RX{3v8M4O#AUy8;U8Hlqm&xC? zK2bh2^&b8C&*9wOnS?#3>w7Nu_uSs>c^vGKB))rnwtQR{ z{MsPErV28vn$}$j{ygk{*e|WM&c#anoIb{5TX_Ss-T~EcfBN?9!IAHZ9gqxP=*49S zrRd%I5??|nXm|_4WruuV9wxJVE%^-cjdq}7!_R^D5J9_Jg5XNL-Oa5!!a zHxG{=B#Y@4i0`9a;b*e}ySV`=LKCk=3mXw_G_y43kItAu(%XLnH1BwdbNAg}Qj!5- zTg{z${8G#b6r=?_1M)|CLTz@Y53chF&=BI_Uq6jE^@bDI+W+!B_66Gi{y7A{4q#Xo zsYS~#OV`1RBuISanji5m>ofs6AWT9coKxJi)NaK%l~c?pS&%i+pUHp7W2Dr6%{*7^ z=oL1hQ|p%bvNqRD_1lR_N#ZC!OQB9LF*s7#k}$y|Z^8+XZ^<}ONvJZj9C5R9hpkg} zHkC#x!j3^txBzRK0(~baoy)nt_`?+{f3W6=y$t z+>8JF56+>Zeu`5_xa%XD5QZGf5#vr3b^hWrS#;>!*j48XgFGIcen8HdPl%Zco9pJ4 zE_*?9H{I{2in)FdneRRbeKS_+`XlW1K>Pth-0dfMbu>r9;+orj#Jh);$I`^ze?@LT zzjTjF!eO8$DX=H#6w)?uvJHuA(syk+{I!rhhO+~+UUMX);g)bQPX+y$mfx#BWx%y#^a7JY}$52q->X+3AdT{ zfxQ{dx69r_B1QX@m3*y3FG}^M_Guf5Nk$?@d$UoVS4XznA<_KsVMoWazTJ*z&!rqb z|-g#y^&b}qSJMc>uY;lg4;%QTtj=`_PCzE57%`I zAD8WQyYSdd*ZtxP-(L6VHz~Rvu^Y9$9+y6k{*Y4p^0s#%{x>}4t{GIW^vE&H7wO6b zc0Z>(ZhT>StM8c*`ATIO#B^4Q#x=~<9R0cD-n5GTK1RO9yW>8EXZ^Swi?2V?dslkS z$l9-rJ(J>BN!40;T$z9{2&hVv>kqh*XKwK5R=%HbcWp(gL1+Dqx_(#<1^6GifHcqu z`~Lrh3yf^~{%>#r2NJ#R|1}qw>TP>-p8{k5uUsIVSJ`8_uVZbT_TRX`RH;_*>*?E_ z8;|u$DB?E#U0Y8ZPB(iz{I6VK>YB}+o{tNC|H%c^3tuz;gA3g4+g+RZ4=!-|LM9(T z)BX=Gu=ZxIGx*J;fjd7w|0fr)y?1y2>*mwu|36&7dc-6RpSpP#E>#?`nxRnFu$rmT zv$>k3zJ1XwTYD~Gjl~5T)^ZKMZ?5GL5Q_he3s}lEvbcawV?hAa3RhX+z;%11$j;dL zKe>Qxj>{EAzg(^Cz;|TwnD! zw)btDT6(tslM4hrJ^B@B=RS7p9p)9wv$mGn%2Z8-0Bmf*A*4LMZ-X7vVckKNX@4+G z)j&(q3{qQV;X}`fJ*_9AH0?+z1~A0a3>WLBo_5N=f&jc10Cfscl5RdroCR{Zq+nu{i-29MPWQj)YKP zu*w~6PL3*?Ch!bsC(~%W*M)_qxSs(41&`My`U3bdbef3Ir%8CXmJj>u8-6U)qoK_w zVW5`2-41r^ql z;nZ_u?Gs}LXMBKmk@Srxe&a@($pCi)i3nZ3O=VjSgh2+y{!Cb=PqQp=R3;AN2O@O7 z*Y*06 zP%B&_C$6bp%t(Coe98wYxvbczJMAZ)jNqPdyMNW{VGnx5r`~RUp-FKnrJagTU-y$9 zR-_%md+{O$sd^&LLnWL(9Fb1)a_36Msdf>*V8Mp^G2q~csVFq}m*_juM3&waf-iyW zNh7R(YV*^ys-oBelHGA@3Z#PL9+#45Ywv@@%(B0;Jo6g%3|EL$74Z;3k8XVO2~ z7kMef04f^B>{M{CX)NPDRQ_t1XxUJC6%wL4s56K^8$j=TCnk8=(%Xr57|DO`vK z(q5LB{26@p=G2Lz1rBzls|#{4mQD4F*l`XOT+$QldeSqor|rq@Eg`-=Z3G~pOb%?xqctW&BNPzh4hfN&6rQrQ1IS1u|&N-*u27=0ZG&bj$=sR8r zg}9C}w9J6d%LZA=6CGr@;B83mp|snw>J6MeQ4u*G(v@}Gs3fo3Zjd$s^ZI%IBU={{ zRjI07{sz;26rZQpbq*{KLfD^K#BM12)IGyOx*aFKmq;6F<%#2Ecwf z?@y7qI!nh-ywj}MpAI587ibuQ%hY+TnTYQq@39u09#fmq?66%bf$JoX;(9h0w_)x*v47j3lO*d`;>ql5SKZi3M?k>=Is7)kq>1m|)%& zyEVjqdEu~#M3>-*I@m8#2Qf1wV1KB7OmS*X=Lw*&xxJ=wh>|MoV^$v4Re}fZ^RHz4 z_6a(8YWLYnO)bq6$k$=uWc?#}<$VG|hnuwrh?ijI`oC$n$rf{=hi z_lkpg<*}JFNNz|xz@)HMMZrBG$@K}s#&K+tF@RlUNfdb1AO85=h2RYc4>@ij4SYJ5 zkevpKGa!=qL_Q};k?0V_U_9Gy)K;p2a4EPDh4oDg6q$kCcmdgcccEt`M(rm~&i{}g z{<7FgaMD>(^O)o-l4L3%CPz#h#-^Nli35M|$<1CFsY-F3;1^M++Rzg^B~!gi`HzrN zf1JW1EP3W`K@dZq%Dcz%0G+ywR`?h=xo#4;qSYQUiohtgfdssnW4pa!C~ z0TCphH?D%5U(?s_!}&U;8q8i&CmwT)f&paMA({#ME>WKh^Nn!B+RL4Z5m2STbU%%#i&DH^XE$iq`*M(wzh~_z8 ze9%yOuC-c?V>_U&I(Ul&I?%v+7+|G{dx;0LXjXu;O}}NjaXyT3HV1`; z>1!iT)96aHQm7|Pp9GcLA$B-{GO?`r6am8-*l99Uea7qg2(bRb5ef-6(YW-r>ZC3i zcFfLKhgPB*moASZT*c4W~j`Tx9LRv1SceYGYv}PbqW|me6pGJ284NhEGmC zZRfV6V0)6`VEGTU)Ij}p1ADn|FR$aD1hQGnLmGHzk^(=ai9C*F&^kgq6d}wB5mw0k zv?O#st%{sT75ydG_p@rr0=cVDEf-gT-<#%3dt$D{dNCu^fRY__5@_?PvMT42}a7_q8DLj)NRKnZ&T$NMw2UUas>x~d^72p65%cxSM&(i*o| zV!&t;sWxZ|@5pFTYN%>ziXUv+9BUe*H?`064W5ZZJA<-K;GfuL

Cl0OgE}(?zv7 z=7&sJ%T76i0lh7jUKjy#)6Bf|H9VR}9;>MxDKBICPOZgZvmn_D(a{m8*RnB#kpL zy7;qrOIW(8_vW@7>sJ}}c~Yh)uI*QU+n@Qif4|xe!W{-O>wspwvjN!jBara3Sx~Y? z5`=7`>^r3-e;3{zY!sV%!|;$jyYwimkR?L2SaJg zNA9h=-h0QI=&ZQ6edpeXg?pcV-`f$n|3xHVGTrd2t7OjuPD3>CfP5c!isN5}L`Vj< z4>$&;b37oUpGT@GkL2XPw{Y2E*)ZYN#U+=lY|fvKolUjs`3Y46#9)oEVV^^`vFGd0 z4nVFBok0vJW#ggpvWG;6Pn(5jFb3cnjg`&Vk0_v-UA*-@|9N#L{R|Yl95Q_-M2s{t zSA9X`57x{l#yME**fhT^112RJIcE%6m`h~qfDAic=aFnPyCYJaI;40NjUfeAe~;o- zgm?*d53vLMUs+xg+}ci{ayMZjZlTeq0KP zi&%)2t-ABmP4r7#pzIEd2c&&|FeF-Pz+pG@=j_Nqi|D-ID6|T7Bm_$h0U>{9hV5q& z#OYgxpnmi0Cr=1@xd>TR-kUnbk40%HJ(*g8=qH{3-cZGR@Rtcv;kWB3k{?;0LU}0X zg~{z}T4UH1fQyv8IsNq5Sx{}i5W4d0-h4yxSZr~_vnm6lfW<7w(5}E=F05p^gdI3N-Ez zn2*0$#SYv!j;-c+*I=ay1zR(lD&{w(8Kd^9jY2n`A1*X^{E5<(JzBm@YI8nJc zIj}grwD{=nA}h@P@^NMb=EWewjp>4B&5lMo%M4ia*)O55P&v*?huGo zCz5Aizgym5tH}B)0y(1C>x^=p7Su>~l#UJ9D$vR2!E<+d!qXmB+}=rd1$8)p(ri%1 zV^ydM;AO*I-D~l9z>Y}*l z*tMFaPmu0@s9G%emfQP_#bWJQSrVM|^MzpJw)cJqC3Xdj?8Ut96Q7SNn~&+5k9#$r z@MoSTyO3zKknFLLny`@GUAB-1Xr_SU~A3 z@#c*WwA|bZkHu>Vi#277*Si*Pyjr~VXR%)PW8+DmalMc6xMYA3bmqjz&Q~A1{(NM~ zF7+5K^?5AyCoBz?Ej{d78hN$!=+6>c_S1yXrzakto+W&mD*H6u^=anSCnhzra_Q3> zqt9F2+utR8zDX4jeR{L~9sd!)cIor}+0V!i@GlDoMgBy6*}Ns8YV+~upD%#iGHmbi z&rCK#4hMq&J*l3G-+v|5Bjo*`O!dnDlTSR!oG{@H#*vutz6W#7H}2T&$B+{9^&ZDIQg?p|UbE|laXy+5#N*Z;@1t`Q z>X=`sL2y9Q7ib^x+i{IglY-tIBn2?g0NS^nh25?YMroUuZ(^Zm@Q7O%44MeNQ&)1g zY}vhtPBnHf{QZoLVDkQGIMw13H_Q93WcmdS?h5ZY6T058`nGh~mo|$W&q{p4TTVgo zAB-&f@Y1*3Dv9kY&b^TUup<3ND6(>RpLOC6iIw3RCpD(!m`j=oWjmd5Nege20ZjMnnb3Ma#X ztdg@5{PGHzNr0THI5_MWu?z<;vJfe2Rv7Cy&tCnSlwfaI5gu$(;JiJ_1WzmCsHF^Y ze=AM^q6EN;Oa!y*lYwo07-K6*tUm_d^XW5jw=3(RO=z-WR8lIX$$WE5H<3<|Tu}hI zrpa?a;=BwZWq-D}Nn#{)U#2oZ>!%~ozYM-zfqU8Uy)}jb`?#lUlK7mF8-0UjGOri} zn7AwzMYvCw2Kgd&lPL!W`;9dF1Rf-Eo-`ATlf*|-60*IC*ooUX@v-AdcNBnUg@cwb zPAd45D;>}U-r@)X2b(HYBvc_j(yfb&QdQgL_dx>WQv@@z^Cl+b;SrY!45TLi0pGaW zbrVk%WOl2cwHQgntnxk}%}Ifj2fmvVi7G(1qWY}0tFcxXK<;^d-PuB@U;HAarNqVbT{e9_wNu!44V1%NqZru?oP(_(_Rt8El<6C#J04dm z+?c|099kVuCP$Dz72bon44)&bRqGpc!>l*#n35vdW|s>gzU4>Rf8DD%aJ}cCPCE`F zFtSR`_pHw=birWF=x2lDs2VA}#vj<8k7@X90(^dBQ z=w%;ZTZsR#4I|XW^iJ)!f;JRjOWzs^2aW41OlF?u^!GQrrcpp%Oe3%nPrD1y z5E6|pj8}io`0s)io%C1S^l(5?b4s1*!yw`M=$&XJ&NX6etzM8)UvV;prhvj&Nn$Q; z8w3BzQ+sxvD6Vz?aLwIdkU>1}Zb@9Ws&0o-ZhAgP(I=lw$cBu%>GdiBP2@4;X}(lm z)}(o!B}dOo9Z=Hh>b3o>0DPtwIyCvJ`lJ?X`d)>&vWh}1X_12n4agt(2^W5 zG5Cwhv68_I!%x?F>tk$9qjuN0@zXw^>%+%0c3(+_z{GS?NB``g8k?%ZuI5CYg8 zj1T&Bf{7rp2hry~5rcP^5QrH1Av;bYzi=*0VTkqp;7c&*c)(L+?PXWH6Q6nS-4NI- zH7F6p{%qw;BOF4qlo!vb@*ai({!qH=!U0~OuwqIHN4*8s)A_;+U;E_2jJ?h9YHSd2 zX8;`;S5Kr1%}sB!ctMebv~&^Wy2LF?^T3Hap+J=9bhpLEL!Z+i>Pa^r8fXjkHTwGe z30=?di(YUPSBhTews13)BLDqFcqLj1hghMSwgP}^pS2*+N~w{MM{dXXJ`Gf9H{mSb zxq0W>+p_P8VyMP54|Y*tizjLAIvm;sWmDMbGd&X$`#8Olz8HVX9HGyqL*bsw@D&Qe z<@4IZrkCXR0`#}W=RmA4D^zw$t`|80@|#Kl3n&Wq;Ng?$rX53g)%dr6anaH!IL8Ph z9mN7%;N0^hJIz1K*!9s%H(@9v4D!jn&D}eCK=JiX%SQKKViqvq$1C$L|2G>LU&7j` za;~zz@wY;j;ZMT~-7QmZrO-?_H=^Z27j>5hBoE2`l5)8_D_HTvSIG1mOrwJmr1KdS z3~ce!gYPDVAXXBPV3-se_=PyDuzD6g4xZOKiL{N8Vx0`QbVz~$3KYgEv0+mK&_eUx zrDjkrU5Y+Hi&}{X>SN(vv0p+HRccho;z{Y6NxK46w4;)45MhcT^yb_oy>cIYl@mzY zMAL>nzoYZ3axJ64L(;-$~$-oE{J; z!y6^4y`18059>W*eYi$i#EI?{<)Tp!_f$$2m~}_y!e95Mx#8eK7vUTv7r=$T)=J)5 zk*?W#kj@a#$Qu-Uqmxk(mGS3JdI~+Y&|D_=G)#!(VL*U$kC|02q#+wpP%G)aE7Ar8 z?u%0|o6B%1#w-3XeL#o@x}*rzandmwIHo7X@5V3jB~a)Q4<1X>7zTDkNsQ`C!XPy?mS_`)c< zN^lhL6`8{`&JQe~N3ZZEGNX^L@B=p4j}~O!vT|&%@qSBz8UY53E^vv#2M`3(n4S%V zqPOcAz2oq`WTfEuUJOy*-V+ndy<$YkgU{w6Y|rljJp4evaZfwcRt8C($#|6n#S}ua zEVu?c$AEQ0%O<oV@j1v)8;#)ZqVT<4Dlg4&wk}JjEdN{P=tE};sb<0GkVhxjqY>Tu_7nN|H}Zg;j0~l|L*QD{8B~IggXH zfn6_oIulcEomU-mofJ1+eTt|0 z!Adplp|HOtG_QwSa<1976(&!jz>exe?%SXDp4u&p-Qul1k|8?;^v6lYQUwOGz5=&a;yF(MQYAYVtWXt^(!4R79_ zS)u-TT93xW5UJI0TkR)p(2K?T{_-l&91>@SiH88fHlR{Tt(Zocw3Ms~4{jz9`k@Lj zYjGO9r?zhm%PwW&t}yNpHR2Ie-aHypM~cAV0krCF!Mq}cys#@~kfA{n43C`Sxoz{2 zkbE855gRL$d-uq3x$j$UzXN1Qn-Uha90lQT)s7<&mv`4}VuYN(sdz4_3)+h2fDkwJI2 z?trqC>R&n)g7iqCaX^Gp-?4ICr2Ag%i{rN*Mjyuj+v-EV?r-R<-g9oabEq7Xi3X-c zgT6_D`i=?LQ2-7|dKNAH`{RA&ER4B)iblb5$32}ATH&7Hp{Kyo3t9i=W+1Y&)1qKX z6Mlu!1E0k@)yJo|<6hX;LNn3@%zGIs(7JaoIy4Z6L*^}C5%t7I*u>NoNgJ_mbI0ai zUE9a&f<-MMC-&{6<5`k6eb~?hwd<#bR>}cFhY^IOFQ1N}A)7coC0W5_vEYLFSoApe zCv5iW2;wK`@~m_`oIC3vEiJ`L_%H_wZ~&g=j*{4T;aoa~-sRMhD6++%CtJ&09tb&J zN|U4|YsC@hu0w^TL&cp#r87hA4neUuAi+3X>eA4I*@m!5*!j1`Uivq9>DkO`@Kof@ zZ^s|@QL*Z1+>cCLMG$l=c({XJ52rUhF@WUxMn2&XPM&$_@pxXb%VOhbzwD90ai9wp zCa(#JdfuV~qmWmG1s`z8YP3J}`qbngJaj;s7&-cV_?@Bj4zZw!Z{0{LOpzSp^5Wp< zUyp8=2Xiq=jq7w|IpFe>8r1t)66e<-D9hsw! zC0m8Y5`xexTDG)4NsUMR_oM=O0bO$Oq62nJ46)T*DY8}Gt9nmLU|CDd5iL;yy|aWe zLQqEJ2RftD`!9iL)+7G9)(-_^`(DZfI^#y?#t*%eeeC*l265l%fUL{CryjqbddfWW z-t)}Y{h43W-4*d zRI>Y2YW!6C<*CejQ`s-43eBSg%%kd*IxTGzowl8nbkuenWJ@@uJr?capA4z8hO(`% zo#)4YG=Q`iHAh09qUa|hY_yfOLzjmhH$4V=7r}j`n*j=j`KpjV0WMB?T73cvx8A{h z^!@hmi4(B{Pv!Nl=6V=LIzNmeRx}arGtxvZ-JQ_0RVpHHgMIA|d7vL4HAYdnFQ;$f zxcp<=b5V2*wBimaZ)-w=+$Lq@S<5TMZsgl@qWeBVbP5{t>+p@y*D~}SM4&CW`z#b% z8J*1`q(d_36R9m@4h=z5#ZXq<(Dd8eV!VJ1p%*WJR~Z()stwgS&>g1UB)Ys|hK}8F zo{mtNCUe97vbXwOZw+6)HTv_GBKywR=$)y@JF|p$=4J0JyWUy9dUx>8I~&>ec1G_H zd%Sl@c<)s9-o;2+yYYQ?ccI5Cu`e=nz8-Ua33CBub3t8m!LQ~{{+SDrorm9@4Z9^) z7$dK2HyrWrrg}dAVX9a9O62%J?`7G=ibrxhyB4pNNq!*PKA9;Ee1acgoh%T ze-^9NMU)soOV`IDFIf1a|3B5cRo&;l#E*mi4Na#E{O_*po&V3R>_syEb!A_!M#NNU zy!i)Bx543)H3SH?f75i#vFkx-L0OtZk;&gQ-SP6@sKjAn$k&g5({!J5wZFXP(sYwM z{FvvqWu^VSviC{=tabmQ=^~o1-ujECi+v)@0V!K62mhk!wCWBAx*hZUxw7#0%HC&n zbN%bb*JJnZZ*2i66%Gv{8o;4r{`Xe)|3cHrS5kTQpj0a(MfkWY`{9VcR`%L|fqGT@c%*6B~-nNr;7&F7;8yi|2Hf9f1&C22UIgtw=LFG z76kp*SN08qN_9((BibL;Y#R1#zZv)Ym)57dU!Auz_Wr>L?`Y-@7fxRLNg1$dd3!C( zl?=ntpq9n{7tOkS{ZOW(0S7WF20LAsB&oT7RU>5R?y1TYFbAzv84<^Yu>tW6fs)cIW(jr|ylW?AoY5bT+ZflK&)sQMq;@8GpG{M-v8kKqWO@EEf6SA{CiBk9r zq)AAs)apj$N`=ujg8Oj;_sOpPdjTbea4z(23boZ zVm|}P{54~UafjCR-guzPBqrU<48pvm>wlmp$^xF0y^GwNvep5B@f^EJaP1ZidN%}{ zIg$*2c7n*sf&;SR-2xN7J^*B`^Zs+|Stz;|hE$*nX&0=V6Tx|PZ0<8Sx535Yn3B>z(sA5p_~b>O*T2`z&C{K5 z@OG&|+(YjCTVypCM+HCpia;dOSecBG%Kc`{p@TumLa+uF($L~z@?a>zPzXU?IP%Z| zk4PmV0A)!p#ztG?#iY(EbwQXu3C27I4Zc@Td#-!VE3fdTTLteS;Eo^w6%88FcL`xf zOC>mBWuLEO76AK zz%9I2YG|33lq}*iKm+&?nJ_&7C0u;){5yKkd9`$&nt9EgM$9-~xXMEts9E7!4r#Z_ z9JUDyK%T-#K_-3lAd7k~a~O~hze<^5;Qe?Ix!VA**91>{sBEI@jj{W1e>$EAunBr( zoqoV%VmI?y=22b_<+0>8e7vkF=CBL~EkBKm(%bEbWzq(8X$Oj@4iLj!0aU`~(~!XW zo0WZ+c{d^wZ@8q0zDnGF``1%48OFL|&&BQ7RgOnjf=iE3UA@vC=oS;sG;lVjha|TP zoxPl0jPFMK#(x7#R_!e+efC8QD&5YeK0~MeQVh#of_S( z;#{XBAPq2(D~>OGH4O!(B8aZ_#J$49uCAekbNp4R(g2XQ3zK|S72IK>%jA8ced&&1 z(Pt``g`E*lL}mOuS={=Nu@8d~*!6S@B|AA$T$ts0;9CZtFF+H+Aj}s>?Ui^E-LI@C zwe4@9pMc#^cJhUF`K_z?>kfJDA^L~~uB!;W8xrb~N8SU{y9JbVpx1|657bXRAR#8o zD&C2yXcW>f21z(iV}f>+|baSaIRdv4qQNL!~!Pxlhy`(;43#3HPbGc-MtJKX+{Fe#TdmqWABfS4ma| zI6UJm^MZB^Z%-B|mx zoF>ls^vI8$cE%Pk@Vl0XxN1B=f$C{+q_-(3Uau+U^gKQ^)VD4)bZS>=?FdE#mBhChIA#4g0 z56GB5B7)3Q@g}$t(h*#};yyNgZQb_Q;>X8;!=nVkO)>K?*rReUzjSHcKZ|{X^!@dA zQkjP@{ny#zFL9ftUX&-d|J-T39lxqp@wJRQ9RAU2G#81Z5>x=^c35(h0BAns5F;V2-V zO*C>mQM4S?#NhmQC*|R>00$fv!`yU46C)DfR9K@Tt^^eeTZu7?Qkk8M<}!<1@F4?A zkj#yPb@Ligcy|-9>jRJ?g_}^&oiR!ue&F&MxQYE}gx6WbESMmccG?&%%EYxQLry@7 z5cLd27up>X@pfNo!j`$x1R9Wbism^S?KBX{=LxAsWynHN7tsJT2%&Uihm>Jx8jU_5 zmCL0A35hwnN;m?j2<*dCJoY*Gs!q{D0(@IBz~&R~15z^IN}|m!xGn>(3PsD1V`Tzh zP$AfUDSdQ2jS6}@f6pYBgZqrnRTM(@HN=^9p@n^vsdc;)Gfh|{orFKX7bHEfJ-^L1 z4OX7Iny#=kCA1HdL+XxC4anIX6g4Eomq!UlK!^?}nIDDtNrKQRvcQ%~TrLL4T}U#* z!T2e;?{XQ6E2y&+{kT%!O47&+%(qz;)B5 zw=g(ei3>ap7X*msByAJ*oQ1l~D1XTeJYiZbP*W~k$3|x(08)kE6XAa;5cIg$>?jli zHcT%hTYgA{OBN<8K+2q>eTQM_TDhI;i2-zvg(Etl68RV~Kg0METH}(~E+`V4@1_CI zfO`{Ag@SF;lFo%~VTI|@+cVn=?@kn+*W1pJC~D9wGRW19Y7;B6D7xuYB&`AG5HD#s zUQ(sy$LU?tKowra0%zKeY7yXd5+z5$LM6b{-uZxGt+E&mdz=YoRFD+>AR-5}hxmWL z0Xbf9<@!B92uLEpmFnq;a@aN+C_#oR5kMsfE>nNmcNPYC=8tcAa@#4)2~QtcPpc|n z#H2D*gaHa5B$IMB`pv#^uKa+2z6Ej1R*V{l=jUNe&9cwP2BwC_gPr9GBBQug1Hcn= zYZ)DoA*zS*wTH>IRKgY6QQsDnhsaPr2LkK)F+_m}+-DC<=sf`{u!mR-(Ni`j``&rv z4FWgkBX?7Eg$G0DO##XRHIOp^Fu7paS4~>W z18sKc;5q5hi5L^^%!+QnlUsofGiwX>h<=s$aHcmDE?1D^LZS1vLutQ?Fihex89`@i7U3pSBd;y9_&G zX?^t~P*8sr-jKStJX)nO(0l{l=m$SPeY8Xm8YzN~1XyWvj!tBX?w2SV>_Nw|WkxRn z@)hu`hCN3@;C6W)*Hxjq4AGy8P^_w20t!fIMja>S&;y`F6{yw=Z?aHTid7D0=eR@l z${Oj$=1|u1?R|_Abcdo?k+76!y@-_(vmKHO0VSAKWo->4*G4}oRw--yx-vF`Bh;Y? zDSVWM7d1NK;JI7=NHh@}=!o4DBqV8d$F-6Bnn**|4HOk^_ETPiw`qT97JN3n&tJi6 zxJh#(>TV&OSPypVLQUHg?5*w^=jx4XK=KqYa#KE>l6#c5nUV`94%Q)Xab~eMRU4aw zd4|zSBF3YnAlSLd%QEEBnmUp(?*$jj2olgmYyd+e?PXW; zWPp9={J|$5h1%*mW?u+P*uZwMSvvGYN;G6#2=a?JDuqO64$z4PIwn}5lY02*>%zb< z7R44OY2AGww_BW1tyUUu`6ds)aqfO@&$eGeHkF|8urOJzmt7dOdnr*ppo>-BYcL}u zzfeuVHBw8vpUf9*4oh2h_8HLWiY)rUINX}mees41CVD-9O`_Tjh-lUSF!X^_wvf6s zp2+EdH*}r&r6{x9FEt+b=Q!l0q8_J(37} zv^dDH!(L%Xj%+)N$n}Ab4_-7>b|70`x|E5vO}x^na`;jraXa)b1*FG548()Md=hnh z!)xOM&85Tbox`0o!-uH@T{EOeL+I;AFvud}ogx?+*DVI_8xFwTRRMP}JG)2Zag+#| z5U}H0_TC#f94*SB3bAt-x-($;HhcJKC+SS@4KA>^r{qzBd{hJP*m*njRt)a8_1GbA z@RJ4frFJY7cDJS&+GGBxjE^mm=f4~5$8=|YtBVp~XS~Q_6T_O#uGyHSg2Evndplla zd7R(+{>cw8B{p50t*Oi&6+S_j?8M14hhX&c@LAyD7S9zr1$K28HuER6rV6=JXoBVa z+xZokwB+67q2*|3YCCQZKM>=JEh9WOks%rWj6iCPnR0+1YBy;PJLu zxG(yG=K*=%DqL4JwC@Hk|I%1sJYmETcXbKRj$)mDsf;E!#U4-&A;(56KWh3pDK$}U zUY^Ee=WqkK^22HQ5W{rQN|tx?Gx0DdLlm zZt3)`-_!N~O4HpVXr|Y;ol~0e zw~L=lsyjU(sWg|u;Ppki--;V;gpW#{7{_W1$IHVJm8joO;a0SQ6nmsT`BiB&N-qd> zqcu`wwgoTq!$4*i0KD`p4bDpYfd+VQsP1xrPy~TsX63HqJX@KK{M0MCv{(`5L`oyp zOgt7~U|#Hj-l{=XCm?qSd7c-b+=9Y*3Em@bk>woMl?rFB?g4@oKhD@$^PcMxlVJn4 zQh4+US^rM4&38wI*|1leId@vdVH%}e;*^zt8J1g3;`H+7`V%n(8CEB*ySjfAx~gv} zK1GY%+5v6_rwD7riqtOv^=L8q$>vX>2L|{Dc&gHIl?$FmEPx}@h>YbJJAR^*Cw4d! zx_Ik(`i^SZ^_0`PF-12M`H87q97oZRc=Od%#6s(V%Mu69L0bcmRl?cTsmGBA2zJcY zcnS>n{9`IV`tm?~JQ*(Y>G6#cjII>sf^^dHK;(K$N34U9V)sIFP7C`l$4mJ42slGuh2(_XXf$Fy<^fV?un1Kyj~9W!Q2(2qhERR{I6~sR`Ogx&ptfr@kq@aCkcU9o4}ZsCF8Ti9UbU1 zcNT6>mThge;L0&2Cm|m9Zz6ebx#lwWk~YgdP_-=1;J|l@ibbxVEX1Y;-H^H?>w^T{ z-Ky+i$XTK+yRrXL&d&H06?I(7`VZ+h>FUgpy@Q?8b-2DCWyW>u1n;;2i*EpP1FK;v z$=OhInk)Fi4L+~y1w2I1BiwlINP0DIuEmP6Hm=?##6xj^QLMD6^p{BOlV>Y0{g7Ds zen*hl9U1>*GCJcU?!+M?SMe2g2vQIE_0=g&6o_#+fa^U;9KAouvqd;#FpU;H4}F<= zWlNcg*uFLt3GlP4#_FISy0LRz=R*#i7hCC8Z~RSuJ*^_Y(EFO}C8cowvz7glIOy9g zt^rKhXe{@e7wmBFN|vynvo79!;#FUf{rthQJ@J1KdN*7OF93GHzpm^T4_`kb7nHf% zCiTcI_j?IQDTgJe#$%&hBY8-mHsAkcSBjM5XSeoLKlfp0e zr~L;u=jNgGcTfO+<)172qWVm6E$^i%Tr`JowCbNL`+_{Hxj|dIRKBqr|BtThAAF>6 zt?Pw$OrD-a!mtYRI=-B5*PvYz53ACS$%mTIJV36xs5znrM%fc~RH@xbQvPy7BZ*tx z1AsIltUE>PkvFZJm$T-%m18uF;BZ&LD&e_%6&ajFy!Mo*AYEl}6~?d9N`PUN8fY+k zxdZNJ-p<$z!Uk;WOV5cvU18F1UjWiG+O>fHu!QgrzA?9}gaL zQU_{!Ve}g*yI+XP*bMT}Q}5NGtYj;$GQF`CNWcPEt|ZturCi#FwEITYQZ)(`15`0R zlLSj)^JMo#d60%zr)(f-9!Q?#;V3!T20`?u${^ox|FMOc?4{(^w*rDwcbF&?&jwjv zI)FpV<<|!QM-lxy$4;VyoDb%ldPYV7WECP2Z@B;jbT92HfA4nh2Im-H{0M+2YDY=f z>qdMhY#l7Utz;YcM4z>`Q0A^qOsfCZCmeLM!OY-O&e6g8Ws+!ggU=PZ^7 zAenS+Yy_P)iuplG@`(93>GLP%Q_Fl;?3erKy>Tl8%J+XY@QA3uzU|YzAOGWZ+TMhX z`Re-#Kfes@J^TB|{cLb+1MTTI^8H%b2Q?bn)Y=ki<&N>#birg#grY8$$AQh=$$6r7 zw^9Ypu>05dpl3|fO%bn7vTs6%lBrT)x$>tBFJ{wE9@X3oEU*Hc5 zxQa23d&6Jdjo9^&&5MkF3q8g>5Kjd_Jz*2sZ-oQmpF?vHR5=-E@gxLhf{|wGD=*S! zZl*nv%kyDE!9v`^B9oDqAAXeb-_+my-?Aj@m5aM2{?mqF6i}f_lfUq{4dLr^+jqwB z!6y@U{%-w%l3TvKIEI>QwR_+4mkmMgGn$pUI?ujpiC{``Z3u;zQAS)F zLMZXC{^oBRg8V3p+ushJz00r}ucJZf8j zi6LLmLV3E~F|;_udnCZIm&>U!S@~e)=})nYQEml<%bz z-=7Cm-~2uu-16!Bi;#gGKW4%wPyBcpHGlKRtGFLqpMJciq1D$p$zmthXVaB$t-s0E z`Mmy?v0r`T-9^Wf8}ADR^?L=he=R3bNS=8cleY{L4?KY@YQ;SM0rNaZ$>G~Yr#!rI zuo>H|6Mx{d;};AIE5u;;@GBl3jUDe2Z0Z#NmKncRjE;i<7PjxgEs8AVP&hB*6LkK& z>mN$D>xk4^`~Fk)3T(_2W^K>9iT?peXZdJgn8!KBMe9#My8YgZS|Jmzeh~aE&NPMu zCQ_W1_bNSLS*#|}-LIkW*k%?|JLKSL$<|7)99Z2|D}z_pNl}#9vjYqtiZL&&{0Xv> z5YZm4y40kw&XXbl2Vp@P?D=V`rlNGGdwmN4lEt1JlSb3~%??kR{QAXEQSzZGBfL%9 zreGOsCYSeL!vH=Q)6@e?xv&-adt%mJq=q_g@uYW^Vq``pU_*5?v*{{Gd4~>i^I;g* z?9U5T_G|d~cJPl%lH4+tp*c+5DDX7ZlW(*=RQixl7zLPMe3NrbFW$X%cj#8O4`0#Y z!=w&Pq)MFnMd`LnK6HS&SJBx8{~ z(GRSzX zJv!6=_40Cdwc)(QSj_YVLnj*x!e@!C?O1c#6@Y(%%T0lF$u%Y>#Z~6o_l)Gvsyv8p zVYT=CMsgY1UO0e+XM5NALVeP(RPW#O$1GmbT~?$j{0@_y1aS7 zN#`r6Omm+%-2zdZw&*U=>W-U0kX4v_<+KHDHEz4o(8E_(>NyuD1CGX0kECyuWn`#R zE8>rPC!S69Y?0pVm8t<~s)Txya5C?sDHJJ3n^G&uI%yK6x?6s$lXme!34<@Bjq8C;qNvfI)~v2wm*l8M=M^6= zE?n9g)pUBbDv5_n^m(GMY?m|PWEbf3CLg1rSn%g&Ab;UEz5?j~LMNl5I^NMQIzuG`U#dqOf@gGVfy^=Lsl4Gr1~dH~V9Kb8^@7yObwxjKpH? zcEoryRe0@AK(4?Pj0V=K{$9e6$G90MuS#f|;#I=THkn8`4|( zcUNRosA0E{pZYOaq5?y#dXNq_uV}NbMieH)YZj;Vt}l zlGUJe5ODY~!Jl#0_)&=6$+YUHD#UL2C(DVo-Ad>@S#z}8a+060s5V6o!|M@}B+8gV zC^O_v=1;HHSJKdJ=`RU?Y!W3}X>WYAj++{d2Lp#I78Ps5s1s~PYD^EG>^EAsMjs0B zgp2GDH&w@!K!g!*!mUE@5wb?sV}(i)AHp8$!3@zw=jVAlZNgq?#vI2jCl41OX(CID z(Bh|VlV5OvEROHME`27vT&}=l69wpl9)#Dd2ig;wU5*SI>+~I9OPUd8>$LOTI;khc z;2n;+4%5j#3N^E zD6R*WK>y2w%hZ1pf_{MpV*Et6>saCIJrKEjcB0S7O~Chtn87qq)HKMI03rMgha8~f z{KT(*c$ptznt8skWDnE|EM`BnjclyTl-jQZ8JR=&Yj6`nqK-MocuNH(^3`C zuOFX^fRKXcfzL+L`NssIv!meQJ@J*Bj3i*e@Ml!^f@D%UB)B@D#-9Y5loSdfml ziG%=D^yPFFDVmF^XM*->$W>kZ2Qz4!Xjsb;NJdQIdTS=p3wA=(ZJPrKIKZ@&6z&FO zZJ*5=K><`2aMVnpTP0ft=fDG!4pu~nD?;a=8t!b&9$Clr_(2K?$cJ7 zDmC*$ue zU~>Y!68c(H=w=i{);LVj#?Zv(BpjEkN=(Ps%1bRD6@Q-VznUeVp=_iWq8P2bThUF` zSy}%3QEaQC)>Php+y&WLH~y{q=v~eV+O_Etq%Q%>A z1OY5bz5Ig;Vrjx^TM?nJoXh5-%NB~t7Td~}o|k>zC|j1evZ{Aw&H2jr=qu|*S2o+O z{Ca-n&&Cx%k_ppiB3ziL80IaDFn}4Q;m!E);ZVCX@vJiw83Ec)fJYvjMTi&oRfUik z<(QswVOyIf=gR~h?#Be#v{1%1boOu!ofNbs#c$(DVAV4~JP^ECe`sQm;H(2Z3V`OF zE*sk9RHP!!f-YgHyhP2)iHrhFx2*v6vdo*x$qZyZ+c6Ka%Y{-N3wcRS@Se5fLcxWBCOZXR}!@o~rx+t?8Qcn>F*#!KQw{os*Xt+lUF4Wok!CFJ%(Ks{*>vz|*N(0T=^O9<|5vIzR0A zIqehI9})^fuRDriZf#!2n{vhJ5sl4t1?LuDhg>ZH z2q&Wh>g$DKmkMVXoP-{E>kdn@*i zZpj_}jyr}g?il^NLy>ASHsC6fo4AT(^O7dZjwb6DO$UEA*+|{BGq`)$^{zwgU8j<} zE-&)fNB}_H)+qG7V1zN8k%NM8Fi?c4rQxKjdcf)u9i)i4j z4m4jZ5~k{mCc~`NvFMfiTMufTX2CT}NI>5XT^|_m zEwg9nzA(MTY1STvCV6+*Ti$i`HYkKfB+?~WA{Hze!yc|uSShYYrL<>TXOG%UkNU43 zvUIPeVec-tUhTME-O^tD&R)ZrUZY>V6zM)=!#-2DJ`-1Io1nfk-EfN=ePKk3^-^E# zc%Ply1BbW=PNfed@MW-Wz{4=hMY`YHu;16M-%q+1$LROJAu2)eNW_qk9sS<8fiSm$ zGjRh^r2{dY193A03BLwt(u0YHgUN1#sd0nprGuID&cW=N!SlZc8PY>}hC>&vtq$$h zZFkhUaMQ?;wHM4SPRGM$q~C2M^z_KUk~1qJx#o|b zJC^&8&mdNxy|Cx~K3DgpD|FP>MgW*%ePJoh@^YCy(!Bs&A}5RBKsU9VQQ`eI3~~8T@rrcmBrLM}|L^zK&7QJJ#5mUp-9( z44B*5B-5h?S;QHD(o1RG^;?bC;YFSGv&Y*m@J&AJBEx{43lvz_PJ*@i)F@1i&3CNv zT(Ag`%}>#?=kraRDf+{86p`ic5!l;d`Mo-+JKdPi^;EFx~;Q#_S1uXZ97AvSEwNzCDlLGoG{50PEIleHKI_8}*k0FO0lc;Si zacN0)mX`FQS4Y=aImGKvdm8*0+wgoToUw~Ka{K*59aQ{V-EBZ=*uAXVK4nR7d~;qo zyhmAhuqWqxRm|Ncr;K+~Q=Xjl(TN3N3%{zj=QKsyo8H-89%M zySbc3;j4hQ(#-qhC0EkTtt;@C2K$usS2Ap}D}<}fA8d13$#fd25N#QJpdPc5<;izd ze89Y4vv?&t;GegfjIDW2W?z-A^}eS!y>dQkoQp zOVDN}YX*bUD=Cs8d3@%0Ado@=RP>;ON_Y)TO}>t8+?{v;Q~s*7xhe?h0B#%@N%uWf z(*|@-2-}%7#XP32mxslZ@>@)E@rcG2I?1~*oU2Q(~M1CuG?8 zV2+~CoX9dxkCzLi?c?nk%Wq%1raM}DF!G^2d5$0OAz*O}dF`px)x6(v=_q|qE9}S< z(o*mTV@<-5NnZkd_g!q4XA~TmVIna;7_RF(3DkUt+)>}{7{MNGE@g&e9|J#y$M+W+ zBj5yKAnsHWr#25wS2UwmKCpXOj5f;vN*w#n0XHAKMB3cK9GZ0YPU!-pSXaC zz7_q{Dp$Yp2O;J_P}F047=M605vLo7eYP8VJ>gp^sRF7!{>dE5w1s^+f*~oyaHpBR z+%FA*riz{}bTWm2J69QUefYx3ZWcl_y_?T?2^#6<^aXX?z}Lm1_Hk8!IO0j0REz0X zAyLY*>#80H7%-_C@tX-3-l^<}c_UT|pzoQKx%f^|#D@!rfvxUzCr&1v2@?Wr=q7IE zsNKQ*Kn|egHt*`nRTH%V>4+3{kOl-RY{{=GV90>E8P3VLpG@~pRRZ`k(&0d|m4eB5 z2mYWX2jC~)NLu*8u1d*L z+!B7`v~eQs3@=ii$PXojKL7fm`IIS72Im$LB)?2tW|k>Dzxi_V?GXP|7@USw0kYL` z6)#f3CE3n*rx#uix&B!#9P6CZIki!L+Jo}!j>mheFuJ|N`q!F6_ZDAp!=TRiZvxlh zVy2X7EgSLgNd16l<&Dr8xqy#dM<0FI?`x5_t8k@z|H0%7W54DMwl>%~U2D~celNOi zZBC7KeQz22{W*5)Cr9x9*80GqKdU8MzZMSN-<%x#^Sxv1_j1ntU-L(0S7DxQ=&-nX zDMA$D!|TrsQ*cR$ixfgq9IHN(#WxWv(*CpUD~Gcpy^yv(0?cJcNTUU4K#7!hfpW^X0h99q@MIbJ7%FEhots#BzJdp+Yu78 zftBr-4QC;P(LU@*VE%3tvL-6C#ZrKEX0AIBP4{4-V;?9(&w8C4r($0<*p^SGz(Oq* zjwBlvrgDvp!BeRx*Hf1#Xd$iAVd74w3#Btd+#^+_EuElsG@#m=#wxck5KB%RlscgZ zyFKrnHYf#dIY1YaFU{s7^x8z zT*tHQ3Egu~7HA_O&|Mn*kj=SzBF`)ecw&Mytv@$YC>d3Mu3ZT-tUo^FaQ+&oGa_{E zvu@6sQ_lCOob|$-&DNY>Q#pUua{vhjOpk$ZW}u=Om?8#G8-wpTLtujeN#x@7a{oW> z-ovTMeedFZ(gOr|2oOR~kR~9~q*@X{2t}GGRRu&Tg3_BUA(T**(5n~_1S>_9P}HD^ zfQqPWq*wx?Vh2U3%6-ti&)KKF^}KiP-2Whx$xOcMx7PYB36E?-e0G0_qy09REXD3< zzNE`7?IlaQ9W)mxBx0wQT2lpUjLH#jfuYnvg??*Y4@rD2sIz<-gK~#S^Kvd$!ICXE z;3rzj53^T32uP}ewHkdI#XhVV71fG*`_FbOWW?tZ*SASEz6jFTEHCJ;~% zD@Tq`oKfJ(s%p0Dmy-Lf^s_B?PYRw}{oRiu?;&b{FkEEubtK{BNYk{~c%Q zk5$=Wf!1%mM8RulGor94;B>ye+v>M0J0#B1qOl*{r3rwR`$8S>;Aie{(g_dy(426X zzlJ;E=k>8=^7Ofnt?z#+6U|TU@jWC9+{`Q4-$d4Qb3R?Sc}nS*gXaTN9oQ9R(tC_I zb#ucTU`3h8Jyt}GLC>UwSnr2TKN29n^uMZ1ETuwc9?;Y-%&hpOGmo6C*L)ptbqoFa zn|r{8uY=y!p<$0dZ-n#YDD*9#RQA?fFs$f0fAu2{<;#H#%yxh$stN$jqYpkVZ(s`> z0zB2{FJmGYlm}SqTx|@Z{~PUP8Jr@T!JI>&%ANJmz?f^Fwqg11z)wMsu>)Hs34Q!n zZ=?5=%~VeVk%vvlWEf9kE9Zv~F3eE~;cdhtHBgMXoN$^>6F?DM%_XsgO(r;INhYA~ z;TA0pyzs3q-_8m9c-hz#_)UCbgI8f*@hmSc>CtL)bNALG-q4yiF zc$o?qK*l)h2wua|`#d9qF_cImE@D-Yl{iKfzz`eh+PRZ$mTdqBdT)|WyX(MPvmKR< zuoYOh?i+;GspQ9cWBB){;l$qHD1D+FfFrXJBlWZ=c-oa^p5F0$-=}EQ^>-vVQ_NL^ zwwTDp6XO3RWzsr*EDTa6uW7eUe^(~6-M2UX^HteFK_O%XQ2YEIYQQ+i!W_7k7g2k{ z@TW3)RK74%gM5%k8PdTktcL;V8A2T{=#6<+oo5_2^x(?e9;Nzl&T`+-x1Tc2ecr)G zZ)u_mnqL788+B_VuOJj#tC7!UhEX@pFa#&Elrfx}ltZuujXs)PJ`-2iXzFh%whm z+tQU0XErDzD3U(Llvl9g}0 z3chUP{Z%fOR1EMoi{oMb8kbHa$_wZ)0s3w@Wa4l&0n1=EAC9TnPz<}ivz|Hlf#mQ1 z_0Cm$03lt(uUJ*8O;Cr?nF~oL0gh#Wyq--u9&>GdI8_|ROI$|xorA|ScuuzNaS0^U zT|M!C&r|q^U z055G5EZ`E|pkPFLC?6h*G&w=(4^La4@dA{Y2={av6I^a^f@@C#Mxp~uMb0qU3*en7 zG-7wWOb{|((|rLo{#JqZNox}z51_@GK6Fh~Do3-ShZ~Q?c0Mu^BAH{y6Q%hiv??2h z`;2auaL*!{4N`@G!vuvHA3>c-*z#FT={G$Tlnz^IUL6Avl|4vdTNNZP(h&!beR_V- z%y2%hhAB|9Ibrl!p5juN!w4&Glf_iur&`WbR;DO$?AF@KcvTD|uN^nD?9kHd*7v!f zZRw@ig|jN|6M;p`wXY2C&*y4i_@WpM92%R5zn|(bQz?6ujXfgLm!$xUPJs6&0DzQS zy~n9AD!e*LFS6js3`05g>iBz#nk=7@5&L~JIglz)KO!z%^!@#VaI+9!yF_Na{KvTa zZO>-=Vy{frf70opZz6wqHj9&*VmUq<6~9jQ(0{hs{Al~c32th>R$^DKn)AfbFT-~a zDrBTCw@+F-E<7y#F;jcHdwi=S`QoLG=7-&<-UT==jy$g_UtPgeYW49OWu_Lbf^DRV z0CzL}p3WlRiiRgkhy37_-4)i?!brkE8=Qo2HwvQJp1nII=wDV^_+vTDl60_avKA?$ z-ahwORA=jx?JC@WqtQ6IT$>me;%(veqe({(ecu%D^@kK4ZcInI)6sEsY!O|MOUDh- zMds)rk%2d6NVqcyaSUP+Lx#(c8)7KTF-XKjzsjBP2mT`C36-hQHwqQ+Y!g#Ajz19v zs~mvcM*$iXcQV}t!sS4~>2+8Ip!>+Wp&jT7Cna@x$W~fF{Gd@EMq}`jVaDADm@i2gJ=CKJ-$c*u zjP5bdPqRmE1j?zJg9He3B!=yZ%X}2;t$;dqyTN^zg&9)p@BmF#5Da?!+J2NKr*91g zfB`2idw9l@M%)wB38;g_>vnkR3io3wb*@M@eJ}XxYgX5^{W}`F zotlUhSi6?XZhgQO`I9ms7H7+}WXla_E6it;q;r%^a+E!CRO55hi*qzuac8o^X9JaOm>fu{D!1 zn@qrhYDvK$@P#X8Oaj&$Wh@p3I~l!SI4lEdJrMyfA_*qlkFj*h)ANW{bqA|mS=$=+ z3c+lkxcuEXyFe@u%|4FRjciU%i5kwmw3z_GJ=(B>g;C&v0`LGgmk^ePdEmD<+$Q0r z4+Muoz64(cCILE**}TlHtE1a$32FTveM8`}G;qNmUaFo;?mrkrPDhYkii>iowS-Cu z2he0I#-qfuVGF83=||F$u?bh{`otUaQqbG36%8m*ODBbC|5^bE}z2d!Z#`4GzgvWE2+J@fZ#ST0wPc$(@PkL+Lkjuky) zzs(u7&voyaYN~$7n_t{qNYDK38kR=Np0cRF=0E=@Ygihk%eaZGP4KUgzt*tS&NU7u zjGVplN~XlL^&8~0IKG9yug}e%rcY6!V@kXh4%J?;4NptHWU-n7tQso0}sfJqfi@a4) zYq&7n$C$r$ zT0B#|tstjGW#X#Jf5&P0XL`mu&$1$mj;kVJY`V>5KC{!#B9)l_Y2{F1-`#z}zrCI) zfUSa|vr8=vhCw?kUJiT=E~aBrEe%mPPwICFNz~SBcr$e6hx&(b<8V=|Wv(ogz6Urk zrxXBy-(*1qr$ju!D{}BF)Z4*__p5|}N8(iWC_(gQ0Q&BgY3T;+E$LO0MP4qdKx-!= zpjQ{gSI}3pNY9wF!l>C$r8gb~BtkqP~y1vFzQ2OL%h$ANoCFPuUbPxFrbAIcf#9*4R zZ2;v)<-#S}YPLL1aP~LjGZge%9^HEUaY|=?G)>uwqsOffOSyL028pDv{g`m-%2nlr zL-{sXonct{wb#N&{URhrWqJmqgZtcbhs#(DiXdGmV`M_Igf? zE*pNSiV98V(J&i<6kpY_4(pqC$ZmYX{kFDPk*+?62Zc$IHYozs+d_B0i6|E!qV-~x z-Z#F3```sRbi3jZaGxKrjNotRK_6L~V1z`5$n@Vlw3lBxrzA=~v{!o$Eqv|AH=}ci zGj;Fxk`Qwxky>6`U?-iW_5B4q@lxAZ#X){3Kz%%0B6Px>%iaNSVvR~2dQdtIXyK?J zi@W+X?0TK#K!A?8vUE=;7EJWJK|-G0!Vt7HLx|%H(AEkW0!jp73n!n%wUb(XPy^I) zy(PXlriUR3^@&`Sgul+ifl5Z2RCkA@uM<|tTNiZgJWvG0AvGFfb(vgq;oV`kRzdZ7 zx21}c0YOEYRywScuz?gJiq6^`F_xUmC3g)(9vV^uck4{x0W8lDR66dLd6QI(pkEh+ z;Hk#m)J_c(T+=Ot`P|$gv{MV%g#;g$ zz5LP1L!eF@nCC2}tWkc7Q0`?2ne)7XBGT>?>pH-@Qr97C{p0R8B)~yu`|61J4cFd% z5G@Hn+_=uah7yq$eYggcC0owjYq@0T2yz*fm&pPWeELJy{1CQ6moLGCx0nC<}%WOqdF2-}dE* zS-Wa7=1g2Od zdWCUGDq#oZ$n*%~R3SZvoLEZ2oJ(CIhp%?VQ29Wyp#WjoCpBeA!F~{s z^@&y%gNxO}Ui}7B@JVa!0J4V&lJ&4?sdRA{bi{PZ=|A*LJrVCBmGNEIjvXi_#n~>; zr#E#gJbp>vGbv_F+u|FD)(I4=M|n06Wqc0btw2uQdMk5Hr41n>`5{+nhfCPj>c@P zba-6y6fx^ccJOc%K;$^jaK)rK&O=DRFyF025^fg=SLlbyhQWjLq1vtucfb>!ruZ!n zO!aj^Riv-_PxQ=uE=4-e+$7J^BhM;6k5-&#+mdHLoaZo~=Omr)Vv-*o5iCe2-KOQr zPi48TRxGfDz0lu>Y{*9XhQOUuA+>nOSblB}Bt#s49O#Y*(oqe^KZph3#~A20uy!5C zUxnc1SwAHXWOZ<`OTL|tXsUMx_ySMA z2^9B$IUdK0Z-aRgplGUm9}O&Cjml30&zR)wU}F&l*b@Y-P(ZL4hle|h=ko*jS6e>MnR^(zz9mP0?Vz_t54p4;1ECp|P?t?e%BDFe z4S{rj*y*rD1Jk?@mLSv{cb+=6(i7vEaQIKhIA?VLQt-&d!o7lYPByN0(XYNF3gnVdVLVz=w`iMkQ+ zRMFOh5LId>+lg8z_`tY~i@Bn_bCqO32H)&kJWPe>*<}N3h=M_+@{<#+xcKwJ6+VJa zVG!x^Llu&V1?X%^b`Xe208ctO?*J2lsiPJN&gnLoG(gZjj5E0aCY)v>D}2(C9B*gD z(pgYE7_2aHJP}`yuK@Og2oXDu*rKFvYMqoBn8yLoc7Az0)Ke?40IVREf`|FQ_4&2I z(+%RwzJ<`MLloF(R+7DTANbqqttKeIAzd3)Y}=X105GHp{DI@Y1tvZ zaG6{FFRE>}8y18!y}C3mA0Qj`Sg~)-*mYNBN2*>q#_;NhI~O9`9AVZR<<$%UJK{>4 z6WW>&jW!=yY^KX{6V13uUfh&}TvjPJy^WhW%00fwW&h;nI>iv@ty{vye2ToJW-D7t z@3fqhZLKtGt@3Jp2D>1}ZgmfCJwMudaj~^twvE#ZG-`N*i&qEymC*b)iE*=Q zmd;_X7R4tuK_*}LM(#CAgV4y-wW(3aEfg66cYhUYNATg^n9LPG&% zJgm3A;CUVrb^%!?uFD3*ygLYoI*9An%@=nlH+0Bp;T7z8e=EG#LNnCw{wFikcd`GK z8S17pk81w!W~l!py#M(O^?zU_{)6xqZLz?8hGwW=*ZN*voShO&Vf|jb+yf!c_7q$VkLWiW>gQ8EU~{m*0)V|EzfV>OY>Lc3l1i z&P;cyJZ@zxSCz8@&dd>HygA*vhWE30say^JZgIA@_V0~E^xohL+*fDcUEBuM9_x7M zl;3NQ*U{(B@A_-)@y_dW&A91S>ia5S0_E;J=Tu|^;7xtD%f^FvXfe#^Hs z-6^TH0BzT4rts?a3w|P&lgn##gaS|QaCvs5W>OQ-pP;{>1Q%9kfL{nZ`De`MgPD|m zU@Fnw3mgyzD70(Uby`tM{jUN-*CZ5H)LmP9bS-ei6wu&09GJK=DrY@vIP%=(DGy)Z*b><`#=QN;AUQ}gUZ;ej9XlQnf4 zujbX&oj)^m^V5&U>D!x@7r#DFI9mVx{U-?BisJwn8V@crMaSCz9&wyvfSDYm8m&Xn zb1IQ|mxDIy?hr|sVv=wbSZmr1e92Ujx_yP9+mO6g{Zz6}W(Dq#h$GTLDWX_BEOM{K^H~)hNX5LOQXzi;ia3sY$3YhnG?%@xf4sOn&VaE2M(O(uge_>A+5naCHMyr0_PjDaBlz&a;5FI#>V`*s67_j z-(+up=%TubPQA2$iYd>(K<-}b5Q?d1c1cfQ)&RUZA0MWkU{!z-y`#S5O}?DLqhbit zv05{Rks0-9qbxQ+Az=JmL@&LlGphSz49{?4^`o+v$}AIDn1aIjNKEI5ygO_2vX(TD zU)Iy)ziVhn?g!R^bC9fVeygfK*|u5~9$aftVQ$T!@d16R{{dyw2gOesl|E!sP}+1D z;IvOgwuk^|Q{d0TqE;U>8>PPUvu8cfGz~ig3rHKg7|rHD~K$ z)RVTswP&VsS#NRQlBO^j(xd1hnPB-pVLs`-la{b+mrodoOhY2+|4c z5b~toB|HHR7#b6VT%oz3PR+930SdPMZGQVx-U%6ElANd0qf`$cWm~A(sHHQQ#hnsI z_#uFLMmhm1?;ohes_xYl0+z^9LwAxjJ$a8 zJ&)$?A=Ij`?$b%f3q%;Zc zziupM(i=AiW`1TWR*f4}M~!g{)VsqM^^*!n#~^T08RDTmPf@%jm+bVL+KYNENAgK~ z5jZSLy1->Gz-v(VHg2K}wv(t5%v8naa-1nqvVO>OasHz^(Z<9y_Bm> z?1U{}{gB9oA?5EHWZ+5Bjs~6&aYWq#+>NC4-&p(f9=MTU-(g=&ZA0LP2UMjf{v`q~ z0*X+4H6iXY^SxK@Ui=->L&ENCAwPz`&m~*hiCR>m6MMJ*WVMl;zKdb#J6y$Rir>z3 zqqnYQwI<(qny5}b z7Cl*tJikN=w)R%V`<$v`sK3inJOdk8)-a&*LL!udcr}=w7gxO$stUf9ymHPl=&P&x zvf+KZtyJ9j{TgMMh#6zTu9 z;W0K}$EYo1a9#N2w(lRp>W&Y+=&Q7FNCl&IIpg{Pzy(Z{j(2pHwxJ4c;mZTRVcSzT zu4a>U#;4LZiHWSIBjnbP6$@uAC64a}758o2eDg>9q-NawgHzr2PoH#pv-NpJ|D_*a z>$9%DUojF#e|+QKzxpxu{^GO6AG5sIcf>7pzVKfMux}atIBZH;YSetbDOGtRkh8or zn@9ItdKLTi%PRL*CtVjuXGNF4-8?CiFEr6WoeqcAYT)mg*VidLK78J2O`e${|JB4= zVcE4HM`R|1q!AVckPbsnfGRwf<<|-!mWNLj(gFG|bj1!tPW2J6`pumK{5bbub%J?1N@ML%GjU*usXfE zTl{34^eQWmKuH2X?75+I;|DMmCss)|Ea>$vE?2yU1#@glDI(KVRlvxt`#Xr@<$-jS z&9H`-(k9XS2+>N0b9yptSYM6w9m4i})b{L`UJBzdU0$5d?$}cuUe26ARAZ75Y{UN9 zUHK$$DqvmkO>s*7piis507oNk#~vDcNehp zjF*R2NzM-D4`d^1XVU%R3j&J^f?Engh70!37lcU{Mwk>vc@)OP7seGA9?D@SoRPWW zUvT)1Oac!f%RAPJO<|eHj3j{%(xcmx^W^o=8gu>ah#?=*?HszQ;+Pi33q3V3SWUKslbrN5~af z1r1`drv!FTGE{sG7-Dy{rya(QBJ4P9nsF*tW7uuxwOCZvKdj zJ|AvOK_0$YQ92^C&{+*Q#h-dB({{>O))cWz1Dq^6drG$ksf)0j3TpI}p%tGyLp=w8 zr`lU(^uZE2!%dxp4lRn9+JCtw**OY9G`h#^Abqc-z?v z#bf8jN6sNCvR`{%ykv?9QSZjf^GG<(Rz`^dQi3jZ`L5;)j)Wcy3J>s)IRC;;6>Sk#DGT)ieAzRW{s)` z8`Vo2HTJC*(1B+28cmxU^~^3AK*h^5Q1Nn6My&pli5XGa36?F8IyiiZK1R3vkBgUW zm%T?X?_9j>BYVZ~=U~m=gIC^JY!37y1h-w;Id*b?n`G!~%$xoz;cb#FPR+5Sl6*kq z4JGX0o#q%>t}~2_@Z~0Hnp>UI-PzAQKFXE)!p$n>?(l`{+Wj1?X=||vC@wRTC|_)$ zinUgH{oCeNC;uzz)zv5a|8Q>gKP%`#*r1i!hrf@(s+cqISN}o1I{vR>u;tVAu@t$F z+o-={uzxM+h3@DW&(QgowlQG^8x#X|^JqH76S-#Ei=0CAP@qYQ9G14z^J5zqf zVE@)O?ppo&e`_26li3HE8OIg%dhTE|e!y{48(Q;y{lv7zN;eBi~xeR=2pBXG2ltaA)=)&K=Y34wgQ~sy_g?jzx z1--w-U>OQU>>CfAtdFfS1AO%1>s($4S`G^I($_rpshKe!y7Y|n>5(=Y!Ui3!xM6rs zH%^wxMZQ^#IkWS2XtN$rzZ@2OE^+B;uuQkttX-Pwlsd39 z-K|!)^!cvQr=>6b)@#4d47eTm{&gsz?)$eVv7f%r@>AFTnEOM${#bb5{OQNy)a|Sq zq94xn`jS&C?FmW>x|V(%l1_RBtf*IZfbb;mk%+N!q^`~u1(1eR0TVF=>Y-9^=!i9c zs8{mnGaV5znLt6fG{VN%nk_ZAMQD}N9a;O@e4M`zLYAA>?h=atinjO&b(G$>x#=|Pz4Qfv{xzomCPTl29V4Ogy; z5SKeILe7;HeoZU<@nEH(_kv}}QavDWUm_in29=kjItngyPs4)=mI$RJ}tQ zqYAHHi9)JpYd7)PiuEcf0Fj|s0!wPrt=Q!uK@nc~H`0YUQY5*$5N#7)|&_Uv) zklJ!6p=^L|Vx5%1EE|`ME>3Qfh@mr_IEdsBx|0ZLnSoH&+5Ezirgvx>rCg4ZyjY|* zWXf>_xD8P8ilJ+whl;3}B60M)Max-)kopg~_-@FKp;Pa8B<*sHDxsR!UuNJKYc>?! z5TMsucZPjL8_iMQgiw+hosFdRScH%O{Iv8GJ=s{j+G@0Nz-pQyipb0tvCQq&AV!fW z=glYN5^d@PI`{27R;ErJL^JZDg>SZ6Z3!|+mV4irzzlh0WCeCzK0R3(v&UHg`59jF z>T4Z!(SJ)h)@t3gEg}c-THipSA^f!OYT?lLG3C8^C|kqzd$?L@8>>9Tw{ZYukV^oy zlP=h0(=dPtb*iMW^+T|iPf2z!8_Rl$EXVVY5^FH3Y)k*Ki%~UpPv3gZwhrC97}I>`>BofGHokCO+-vm5Gsd)4O2eR-w%sQh~MR-&E`73%&$&* zq(2~#s}|}Ac6+S}DMv-l-6V-Lu&nLJ@uhQ}>JAO*Zg-y3PQP`PCH;P`=~JohW1d)XTE^#jM4|o zW?(7+L^~LuBJ%-Ws3bngQr&Mk*XzhJp;jBvbB-^L8lIxAZ>ZRUt*RmnI9Yg(v!guK zC5r(1o=rn2JDf6zX`u+raTNx8{WFgc$eU1=jso`ej~48;0XY!)x$`oKRv;h)Ofj|M zbd#iwziPC^vC)tFSLUDl(#%cqB*4;Q&opStC}pX}mLSczVv?!$cp>ZPOy-d8Lv zpUP~Wql}1BdBIvc*z!WkVnaJwS9UN_j41rWv1|9dHq-Y*O~t3Uo^k1C_j*N!VwN7q+89HgOk%RB2LOxYzq) zBQ^=${&>8B@>)24uJPG&fn~{>`Ypy&2aOJ>vXolEylve)D=aYCN`fN}7EqW;%(??dnE1Q0`!Ow8%5r-m~d z4u%F-d>i4wL|xsZM|ZziLxD;(cM9VBfF-#wQFuL`$xCkz~zejVJ$TdsUMzoEzsgE}c# zAeHlCL)8K)gI|VJX1_=b;ahZ7A6hG^N27#PKareA&fHlKZVqc(NQ*OC1JL*Poodlq z7uK|FF}VSJ8+(NOY~vlZxe)eOS<5BB=P0!b0M^@G6BU_6Sn$I>aEq475Ld!;Fb)HR zW3nw|eGcq*c0{{_3wgluDSDP0mFNT?=pu*=M4xqq39~@(amedJsgqKP%I=A(af#|h zi5lEQt)WEixkPAdRnM4d;Le1$R*j38rd;OwA?C(8CWV+}Zk%N4o@6z&V<0>!pd!FF zPIA}d72DXwIN8-bd3#*4dr`6{H`$vQEzqCr-m&jhqZ=8MvNtXz@J|K3Fk&j?7Du_K z#>D+ez0Rf5iL69pR+2mG=GIL~ds*pRR;n&GQ)iClM-^e$;-7K0hQQ3ax-+x3(GFFbr>VG^Uop1lA zM`Q$aMB4p4BF+E)h+HN5|K<@n@RuVJDoXu2BEQ=H!x8DV(vgCW$bprP6m&%X-jVv_ zh&;A(M85g`i2T`+;(q%k`%nNL|L*_hi0pW!0ClO{_VXFS_P@GR9}eJ#JmtUQJb$t$ zUk}&}o%a;t;Y=j*)(uzrg{~O@C4p8wzp^L$CPnNYUP$DZlx#p0!KER$ zg2goLBWCBCq9iuCK05=s6#(-UCsli4vZ`?Z!kgNfiwkf6T}NbHjnqzD-nDtBi}yF? zWK2!}SekkK=}YRj*L9mLWw8UxX!)V%S>_-d_J;*hds#P+$v{CNxgknUlUNms0`Lg# z96|&Y)Rf2i0->Kxh)+n7hBO9G!rYkgo|7!hU$ToX*vyQtgXBUs-F2Dvh_kbaql z<4Q8&0{}yg0^gS@_5-bVJ1>euU$x*TCv}6aCvrQ>%EQ;vPlqYlx`pl2F(PC)#Uu`~ z)ApV#Ar>OKD<}Ao=muXZ4M5m0IFe+rFs0iOOnJ+jpkj`N&{?kaqlv_b1Tur7?t=}k z2fVyBJXJuvfLPB3^3%Cn>pX`m+~ktPW2nh(O@mg%Xavv$tt4xUZ3%zkE6W{9MBUdD za`oZw3qv}I9??lY9?}u+s!k&y8awE1z@Y- z9E!erlFkWwa6@#bj;$YBHB`@us)os7D&Uk)qAG4kl43z~J+V+Ub<)$aRejSO^~g5e zWK^pG^1-3wf}`y;(WP z4yxT+<9W$euTJn{v+`61*rth=?Hi4{R$WrII$VQ0n1bCtW59bLJ$` z_0FK9592oSjFv@UM}-$|EDT+Bk=i%Hw)CD9YYx*%5@jXt5bW$hld0;@PmPyM5PL9r zzy=tfE+thD`);8ROg#ovSk}wknAP?6jZ+As5?CLFq@dvk*|3vp^@^1`fT@!uD7($>fQ^68`;y8kforJFe=FsMLBD?Mpk&< zO$;v3dDi0?+cb({z*<8qerf-1BZ5*(M&8R?w+5t3D|em$aXLr>0E|Dk+$1!Tthar; zf8RcW6fpNj`l)^D50dPv;+R@20HQPx(Au|#?p0BS(Mj+1gs)z^CoPb}(w_tFOz*u{ z^y0~Ttj*;M@!w;v?RoT^A^wghVRNx#H8ZSky5pQs7PnK)VLIJwX`FbU+hx=@ef;3k z3zBF{x3$CPoYJLVl!xEDR61ELcLT~*MBldzuaYyohp=E=CnUViaMtTj)g~JoT_&Ze znEDoVBWyKKtaUK!R?;HfsgXJj3w=UIUn^!D5Pb4B$~g>a5XQhck=}p;F&I9V5vK56 zBXGID9OKXPXRCUn9>T#CATR zZxOG8L4$*hz907{H$iYbljzNX;qN5HlkgSVEENgrfFl45in|#DTD<*P1M~r3Xzp9u zFF7%)t4F1yMJu{Ksgx(y{Oh74q|LF zuLdQj+=OAin=mo)*|7Fk^ncZ*QZoM6M5whPmrvESHTGO77*kI1+rT2Yei#ILL=GkIoJ;m0ruZ4B_`Cm$BXUUp%}xJk$O6FN6?<;| z*v-GGso1wP{;H|`nwkA;P36CHDxR`inVDU|l>fP=BI;ow_%kiz{wpmL^Ov+t)_*T8 zvxWhsWt9FlEwjyevz^Xh;ES#LPip^F?cPNBn8VN7{r@s8Q?cUazJzpt(?q0VXTGQ%eI zC;~+l9f$60&yX_Y{!GgpH=;K4yM8nOnU;x;l*mH>x60pr-2MU%-26AEW&U_?jBTR+ z2?%B>b)jEK%KOzVQ-tsCnd=6bt3XhYx){~si%q(N?ZGKKn6LL<}Rdc!~yN3{`kU<{zQTI@MZc<%K9bw*kr?^$zncppRu{8lX9QRFwj|VaS3r@ zUxA(hcPi)6aW%JKXWhF#EqXwe{Gb#vbZdhB4xvuQ%M)1}Zmx7oT0Ne252R7Lu&y!h z@z0(OuZl)&A|Ktv*69}j`VS9_#>gIRpPA`9ab9ttbl+jznx^dUZN?y(O}J~e{QZh9 z@A%c{uX8g*WIwcxG6{LNuZId5O@=Q2Sek{>GDa^jX92F(5wPF$`&=32M>u7ta6O~l zkA&>_nkDF2pD6yX(=xwm_kT{y{4*e!?kX1&O{y~NZ-HRCdJHz4aFHm#b}B{4G7yk5 z+nTI7_3D8BP%*lzwwOBCk=gQqA~58x*7@MU7W~|AltUCDz|}7!)McSUW_L#5EmkRkoI-Gzu4D3s?Tf!e?ux?dY^Y@5u#Z#|N(+Vehe65z z2=cq$4&g)9*39=D_azh9I)R9C`6d#^xEuEVN+Lq4Nz+4(wG*Kk1_)bHNU+u|m~ZpT zJw@zeA=lu6Mv^z~$$fu&68l}=9OKfTlBiO#nl!qO90)ZL%#G*0MUEb^=2_Omfs-H$ zJINOS;`rHZJ%O4P4^#C!krMC@xVVrHj8T~0XU`dj*>QlWrDtp| zuVG(cBPQ(1hf4-#p>ww5&%#MT(mWnoS?46)eO4FdOCNKqQod` zzBmCda%Z9=3{LiJ=tOG(JP~uK+ruLvWx}X9Lm#+85+5lR+Mzsuxxl4(WY|HWyCF(L2H~R>%b#$xX<~s~@rr{=BrF|0dNDU_#-Gpl{1ccpE z-Z_PFtECE8$#$=rh%Yz*^FcBLQ*PS|0`m4%&;&5-2x=UW%`dzL50(cKV#UHGPLZ<0 zyr|l`pm*)Z)U;ZQ%|*s+ZHb8n1sh~yPQ&qSW$^vtVmjImF#4{E;~mP{w2wo2LbDOL z3&KHFl+L(;oG4Bg(!3L#QWb+sSq9e(rD!#7X748{*cc{~hy%N~3rQeErwGf`O*M|c*8S6 zCt3WionPqJhtF&0nG3`8JJ+^iMQ?ESl%kIxJ}gdaxahs9=}EEkAwD9Y3Vdjb?UX<~ zq}rK#CCd_(EAbEBJ;62xcjyi7d4{0R4o*qf5UYjm$#<)1oE^}7V2<=we@iiVvJbwF zbCNQ)j_QvC?idE1@LmtNr6#&Cj9ZGO-TgTkhZTvDZFUS}WkAL$RZi~9=t8lw<3^jb z?}EyYseJQl@<>~Ci7j&a;zSZ5CtvQCs(;Km43sz}2 z<&o1Y#WUlCwfGevm|;s9=`7A*KO--@ zO}f2HNSuRq@Q$^8-xPLjrFK8t?A`i_et+jF#J_lNj3w6Rw^K7JG;bTYitljplTcO!1 zfG|8|w_nwIfDcgF@(x$@?;3)QZXlY5w_v08Mn^8Wf{!8+Ul=BiHt2tO0Na-bTbyt_ z-~8A2Mi+xMYr7qPQ%h2PV7F)q*T%>Y`xWr@G&~ltW+kaOCl`l1FK^!p^zYhElgHA) zYBg|VHu)iphDQSopOlBXPD=GD1e9yYB!2mubVMhu&>&T3%zw7?U^ye?!R|-|nU!EH zxA~>Nbu~TNT?~blDPKNq**AN12Nnn#BEQo^Xp_8kzSy5~PH-n3L07U+4T&_PlpKB# z0SFEwkt(~RbJl_B^_F#kiWgYXftP7|M8(TQu{kLd+N{l0jA9#BtSZdN;c?Q;^g$J0 zL@_ZaBTlXg+AV#Qxn6u9K*GEe*Q|*ZQ((tJJwaDanhEomz>8z|1LaCUAq)L5;86@* zch75Md6Dkj({pl>0s2i{I^*vD4Img)yT399$dasxfuS;IpcH`PBXbtHSY}EMbcxB) zTCH|FDMV)|r`p%XNG12w7_4L29YfVgF!YeY^NfV)u*f9Xw;p9-bsUmFSS153rdUCi%+qdDjgTd7b%M@vv`}X`AcCBM_RsG;mVl zW({cb2o{>=vaf1;unIH-YUCUTQz6-R|K?><3#&_Ij9%-#8R-+0(5`hdLpV%3I%=AC^iq;{Ec<)q~tpGK4EgI ztN`YU$Gc+s0o61R!^=aEt+FICeW)0be&9Y5AJ7lXOVd2(FB7hiZ(bUZQ}CP_b8mbXoi%FH|?UD~u)@n6;M ze*wXu+I`6>)7De#M^0^AI7N}EGB>TV^sKTiK)^ zUR;(+3)0_Jzzy*OS4vghi>ED9@UhgqpaLnuOMx zLnAdu7Ha4+wTY&+NuISS3ALxDT#_zPrm<34NO^R| z7OE`hoUKZbSg9sjxfM(DYI?KxxnG1Nak*9YDzv08bq|7&9*sPwG+rQoN%m(M+}^SL>0 zX*wkc6#G3oyW`H43!}|pFFe~LZe{EMVm_4Q|3!nH&%P+7%le|BdiVFKsBb1g&M)P8g<1A^o1uAdbc$0O8%Mo z5Ho#Yul*#5#gRMe{a}Y=1eQ5|3_=C0I-qg(a|+`LnZ+m0?I2rec6_Lv$gwvZmRg5A z?%b6Ud{@_6_JEd=mE=j26;yx&CfWbC+!q>CX3)r5+KTUXOR**CXXa!0k#1X<8!C2> zcd<{woo(TpRR?INl%isOPDT0UWoX_C(tTNSg0~4;=P?pLz5i(qNi7o91i9D8R0;fYi(E^Nqc7qDfotBhXQe zS(}!oc7KE#3x`f@dW)l{nRbNuT9Q9q^!p&Ee!kMtY~-%9==C3hD^pQf-|lZ*c&~Y1 z%>QmUw%tF|H%V-6?uBFb(&y1>2+Ay1bVvKOc&a?kVw|RG#Q~#?jTaG=F2fb{S`v@#Xtr2XlVptQ45 zNa~0tX8F>mCo5A?cG}N(TgydKLPJ&AoGFIbE{Vji{FSLF>+f@q`uft;uBER!=Jp*W z_?CEhe&xB|>D5wZsP%XZ?(?NpR<+-65sKg6x%{?$cE3q0n=ib0xnuOlE#fRu{^F;* zMxrsVeso6~55y2ZUtCqqp5~40!d7H_Y%_y0ANpdjN`Xeh@mdmM=FHefu1cgORZU~D%j{asVM~d&bnx`qGFXwId@LqzK8}yYkpPe6 z(=V2&aJk3%1(sw05jKsno^OJfjn^67c!NFEnhV*O0<{Zo>9LuE3RsjB+n5})F%5Sa-Lz=X60?eAV|-=`WH%;p~>YsoaNUlE5k}ByC|sn z;y8ZVfrD?gf}6V)#U}c0w);7{{@^mtH@A<#?IkLDq!bw?AKj>nP$W6&SIs>w78~6l z@EgoAT2@OkL#crDps0Qcq#>ccQ%|jp4fs~~`ofuks-7HG4!iba3~5kZ402_BEYjOR zpAEbzI8FrD8fU0@+TIbLRgMB{Q2M-%-I;1Is6W_8d1gNlhbS*H!l*mayw=IKjj7*T zoZmHDy-vJ`xLMNVerZ6KLgK;b5CH|&vg2)z?BRI4>Zb&EJ@w{^>Y}^@{o4T#8}MHYL-!n}%g(FMnevVDd>IaS+o z<&;T|P{ey5aZD;*U!`yM-S(F*mxaZfAfsRQWSJR}u2$X?-gS63d+qG2hKHxxNsm&D zKYNs3NTRgBe64Rhk+Qgojf#juQR)*8?p(RXt*QQP)6w4qRh@+D+-*>9Zt@4i(S>l@`;YAxvEo+TO{SU5?l$HoIrGBXe$I={ z-14^MBb6Uz&P)zI;%mvg}kDQ0r4I9>T0sPqHhOtQi-Dc>ye({?5K-I~)9fjY)jp-Gohpz8Vd5r;QTzrcA>K4=>d3 zd(}`~5b+rjQ~8hoM)W>jBlq_c&On6&sS0IrAC!KWk#ItHe`o2%kL^jxJT;FwdR4}1 zY#ZP8x@dSO9$MP&~)#BZQQ1#u3sLvSQV@VrFt9jHqrim zJmFlB_qdjre^l`X@+^q2|oLFMH+UJh0zjpN~Mn zdvXdWxi-7K(mfnK0gz8j^47T23KDmt-#qW_!A}EBGy?c&j#UoBd%cmaWoGW>gKHn9 zy9FKUPCiBHw|h;>KFk6`8NePJ`*%NWD+GJYkx_w{QiB_!&^kMxdcY&$jxw4iYjo^& zmbCuSOzc!Zfh9t7nmC zUnJb)%ec%bOf4(irRiW!6DnyO!W}mUUoBFY-*J)!R)_}@e*og|oEwYe{B^3-nN>l5 zV}6^WcUmwFy>PMm09Z*WVkO3xAf&ZA;-*oJIp>O0d9?*EO>X$9*ZNShEP?B&b@a}ZO zJ5@>-cA1GeONLwh3P8oB1~rB5Rz|nrECsb0iW@qQz&<=^f7*tPBg3STVQl=?!lg7c zE*hFE+!>fsIXh{pdiWh8BShoo55jAip_otZX})w46QYL6r~{o&=;&6o?@NuGrWUE^e!BfZgh6&J|d%i##SnC%djhTJ(_N_8v0`pbgrb~&Oih8xA`yn z{_l*U@$x;(b=8997#|h1wt~gU)C+>B&_ClCU9QuS9*$vHwsUkE`C9fxQEIeZtkodX zG7*d#--y9b6YjY`EbLnV`<;XhiZ-U#hCYd5G9=Ps!M>vs>86eE$-nT_j__BAl?bHT zYu&sMEwRzrC4e11A+C>N-J)C4<^eB?jgk`qH&elFEbNssEQw22|Lrv#?$a_ZoeGnJ z>+U3~pf3u{FBGBbW*VRU7VQpfy|S$$e;f(_c_HF=kbg|-->z)PzM`IME7`Tf4V z`;Z5hk$oiW7aaO0)eKY`d*MyNz5$l(I^1fn!iC1i6!lBef8ZU|yGjF6bnL=~-`Xu% zw)PdsLi=ZJf2=w`-(j{P(fLBuozv!72!o&il^mPKqVU$O@}!Tc)A>a>xGR~dHC?CA7tICM@(jJMM*XFG1f{$94srvk3A2=jPA)h5EO z+vyh1k>H*YZgk#7WIq3WFh(3Df^9E{0jpcBNYp|Ib?CV)^q8dot+k_k#c}^`n~a~p zkkUQE*De15tV~AlOw|N-;=c$eRzk;iUctI6dtN2?=2L5RTZ1l?4-&qD$i z4~fLbET_jI^+$K(>nE6+&f6zz%bqqsI!@1bVv7U_D^~l^1?(3wc8SFdgo0xL(3T~n zr)12&tD}XUO1>D{x#ruXgr0nQ`$}G3%u#63wFiqZa0^bFv5^#^pkvPgX$BNqS1*`E zdJ53=S8zZANf1J5^g>39wWAPK7UOlrd$*Eqq&e{TFl{3IYi*A)P8Z>Iy4AfKKwc+f z=fuf-|KuRwBKZIu$Gqc2^dVJs2fS?!(B)Q(M)uk_D9z+wLvR1S<3ZB;DQCgOS;cQi z&a%5a5{#3~cv5F_BoG#Wl#zf)FtCL*2ql7l6`eMnboY?B*diiqNVsA$;-m;JO9yw~ zQ2ds>Uw5_k=xwW^r7m%|cc)5&ZF^2a=#! z(aGn7iaC+bQ@-ilxD@*ILxEEBbT7QZ{_(3~D7>2Ck$Ft2Q8a6m4>tWifMX)6$x>PX zGKB#mh^Jz3(z-VQIVQ%D;OSj*Tq3vY83QHtX$!zgoMd4g8{F%ZlV1yA*KnAOE7I?U z7>Q6iMS#!}AWFZx6JH}qjCuZs@BbiO^uA_qldI`^+2SL$=$c9?|GU&S>rT#xmiE#e z4~~WV1;F8gT%5p%x`aGqveS8Np+E$cCV`Pm@GdBj8o3iC0$pSVEsFzdEe?MyJQZcrNg&Gx0Ik@@gF83058 zmToS%_yk1;7D&fm1KfY5gaCjJ0#lMd?P0NnaA;3<4^jGAQFGgEp=TGr#$BQ;?)fT}M=dAGVgUa5s7xxTbgN%ivT#ZqPC74xe==FbR21e!lQYlo1Bb5II7Gm?YN^o+8-g z6Cd8zLF7!8!e3!ui@?VK5Do{B=ty(h_NA>I-fkm|KcAFYGgd-CS}>+%)K~TqdH2-) zGi}aA8ZEU?wwtw`oy(77q}mwDIS3$da7RYX18TJR%TeZh;t%hzlgNkpvzzi~7uVc3 z=f`D8%4`!7#B^_tHGIL7O0 z$z7rtq|=tMu}{0{xgB$v>2Q4mfqL@u<$GO+Cm>)CMP~BG=9FU_jdUQ%y&X{^AGkUD z^|Y+mr_4C=CQmu&jbEkJe=i0rg5Cz4b4>pS&G}m3O9T!=-7ACNZEf&B>y)7q@;>-N zNcz7IZ?~Ms+cV+_q-FL17_Ey=xKaEVkF?JhQ;x*k#^tC(=mZd6i3i%q#6)xE;Qea* zta$;gg8?evX!pJ}b7Va2p*+C^R#NcjL7Uy)&V%aKHByJr|D9>kW?A z23bdF^`AnbrRCw!cOFo1;0^%A<40Z<^3Ml&paDu+Od?UG>!ei%NU%GsCd)SJ80Xh;zr`#BK&`%q^*PQmmL~4R#K&&M7!Meg-%FVIR_L__DuXTpn1NQ0Fc1i!O(|zUNz*I_Y7RGJ+T%LH{EEB+ zo;?ieP^Z*onh+&XM&LI%S8ipGEy39L-hf95Q-9f!)`;ct?}0A?SLx2c^ZoHGRY4qCSq*4>g6{B*ZZD|k}w zW=#5jq)xcW`@S-@3R3o!VVR-ziX!Dz0=r2_F_K)OO;A(v;`}(vKqK>T)o?B1D(P(o z74>e)V03lQ`GZ-Tuf^3Cc-Y0)Us=2Cc;b#3#|4SwlGdGUzNX{I+PxI28Qc?x(v}BA zwOdqvYbTx>Ctn7%!c+;Gnz2`#OX7I3Nb! zlJYD6g4FvZw(Yjv0e zghtB!cV8dy7WN03Dg1#lB8T2slJ*Vtn@dc7{q8Nj?6ku9j2qroZE4}7fr^#&B!zDZ z8sSXDDr|^9RxXcx^S*r>7)>UzVCPVhkB^Q#%e{=9Ujy>A^Hu>ZFpm${+k1Ko z4mz?YYu*SrkrtK9E1KhX_!}E{rsOp+`fm79`j5L$?Ia(;qZvK(X>7v@$<`n(`EiNK zCeFB$I-?L+s6PtV^eUv&t#buA2V%tcB7TJ8%_<5gLn)ducSbpgA-K{7%-`o42J1Gnn{YC^RoxA63V$Va)f#LRk7ZhgiW@yh! zkfGH660P@Wz(un%M+yTp7T%XX&g4{8Q;~YfPjcRTWBaN1k@zA$$ZuLz-g2vR#Rn{C zn88!m$+u#A^*@+Yyy+jXAp?p@l$odVoYmZHd^m>6_ryP}jCaxE{O#GC)O$7P z+>fb7=Npe5^){d95&Ns&P37X%#X17FkGOn^@0lMimCjeQwGLk6QXhstd`sn+7jvL4 zOH_JLTa9pGa!OXeOzYuVLGUKo(&3v-4rnP?J7$%iBav5v_sN(h0mEue%fPN{LrBnS z=~1suvWnHH%FMY_>rFR>==5c-hJN3HGS;>5`$>Vy3VO~Wf`N+!MfASyR98Qv>s)cCJu|U2_TojU z2A&G(%**hkSB*}iBU{L&1=`F+sQSia;&{!eGxI}l4$Hi09!yN?a!W@nr?d~ae|w)X zdYUflexcgHAfcHc=NEGItET>|$r{-7`7*lQUaR*jW4~dyZC$g>?q_~Zd0Ud37PDzn z0G!pb*O9r-QJR&!ow)7v1)m3^Ltz|g;E+@QlGAgkyBITfKjaH%UGND?=zrUy<`Bqb` z8&`XPjN`Gi?!Mctar(KZGjM|0cI^3wU0d#Szdu}%*24jEa-MRAlTW7>!2!+} zIRpR!fv%m(dZOmXvVKu!d;9fq7$&<(ts_TUWvW&Bwd%`+sH}iIxH~(uEjLVCyQZd! z_D?QS94jZp%zm7-oG zCcxZ)jH^-zSH;WbQG}OEUA4HCQ0#pa`MTllNEYXg=7d|@+%Ca$?i_n zFS=p@{;J%ntkV8DKKE464N5si(elFNv-4T9U{^Wh{~@c zOY9djb!V`?ia|hTtjDsezKny;(xiI;# zjEz~gI1KgZ!%gp)I|aX4#|J(Ah_|Y*5xh7WeaT++^C;WF`g&CV24}NFnM=qmZk{{U zm_Yd4;chqSVqBHqI8S!|16&poN>f+?!px&|M9BWmXur{0&@pj$Sqbv=rSYqM5vZqx zmL8_^P_y3gc^L@fG>F3PrB~d`h0s9qUt~9vr+th|ZWDX^wnl*X2Vl)5cW!CQ$Ym?- zxGGKsqcHqRYf#Ao`$9dZV2>*@T<2_GPVp`Mrge@=Uf;OOj)n4}v91ukd-)bXEWlke z)K47AdJ5?&k{|mpcz?+V+rO6CSvU+T7m2CJzoh1DAQ!Pnl+f6qFaYvlgLs0ZrQA;b z)tQX9@+!~!eBDB&ldok4o*HxuUACSM;u~|!R>N7!IkHBS>gC@i+}v;^$Xc3NK+GR5tI)I&F1Mr(pCne23P8eK5MqAE^HKb zWaL!%T)~Z#76YYJ59N?4_t>clVIZ&y_gpOpNL)IJH8)L(Wpxv_lqh2m3sV%f%;_Z__(--D~I;2;?Qi{WpRL89=;u@KE}1 zDlzs6p+4}$2%_hgTpTK+VyReKU;Uq00f)?N{e3xLdHVJx#k+NXWIw<%0hzv*; zxjtP|Vt+TUW3;W9tsxMX+Vcw?Rc{?4T#VgqA(&&m5@Ls#L&_VVd=@*+EdRdLvr|YZ ztBj!94cciKY}+Z6{aO8y$Q#F?=R-z#bZX55y)*vy=ayXgM_AAlacja2wM66RfTE`)HYDVtB%adrv+_;VZ$Sunj$_PV*izfiW z1JQ_5i*#O*9dsXSm_aZ|Gn3U(sO}`^LzcnjWRy7p1sSu&EO-7|E=4~I%dUbBN=_+P zU49ge{=7egXU=hF@`40dfOGNrk*Y>%c*tGpb;k%dHHq2gXztf6m3tZM<6hx5XPvQQ zx2hL%+slDW7V9?~P8;E>jIg{(AtQKPDX7RX#pksp$3qM|EP(xGO>0bh_hae#^##J4jf|~lt#rB#@Q>UU{vDdK5zjHfy)rWb&Ih2DLvOW z(9s07&B|PF6<}hew`191+@6hSGO6Dhdv^PozihyZk6%|g;5!_LPth?M6`^f_Id2uT zLVP2IvTHXA_P9_Hvu`2_&WPUguI!Wk#h$&_6T^>#*@>Xs%ZoBOUV!l;$3euJgg{J@ z90$TMu|2A17_f2rR!X!~qe&9J4BI4tjXi zJaQ((MPUya9(_7{)yx?1@2b#nwDC(5rKfKB`i^!3;5pct`;(WE^)`P*=9a11^ zfqimMT;%nTl2hl-G`I$Bc2fB4muGfG5BU~=Fs3^{UoFK_TQ@}5{{&f#qyx8ael~h? zHsFs)=S;U;#|r1-YZ=-)<-c9Tt8ujY!xA-Mv*0ocLKaV^vOQym#{XQf*&O z$#~|KGpseamAodCq?K}89Qe`wXc&$)Ujeb9e^elRbE~d6l$J zc%SrXI{n;mbvL33uR=D6Px$$2+e*pzXC?s8HOxSh3<<^OQocmr&^#bwdPo+0_Vze^&zTfejg zTMJ;cX>gcSMu=bx!rHent}T?xAC6Wxr(hKJ>)<3TP#B8Kr>W%d|*pTZb8w1!l5HlwGU#oDd<-g^jvmcIXMo;sY1EL;qA- zHDO)a#^9-*TQ5?zH(d^n7xWxGcI-h#DZj)u42Y4+eQ=yLu6hzBwu?4IE6B zLE{(@62PI61eZX`xr;~NV_QTyB_JHfN{?&S1Fla+O>R{Vtc5&M+!nzi?QBdNLm&Y# zLe?m5nbgmdRx&@ZxU4zIm(|_c8n>b~oTp-QWNC5bmD|au@D1&oB?g0`8|o&5BnHdF zHzR+MhgoM`8B~@gq<;ib3Scy^LEZ%DxnYiGc2x}8C|L~Z-?;UDn(csSHsQ5# zd3haVs<#KGWNEg?Q77qjmVg%;!O@p77M#FjR?cIVDNhxy@H~k zpKHJV>|LXLc||&Hap=>U?YG5;jX~`P|JwandV0lh4Iw^GDc6%qqk`V$Ynyx0r2|#7 z+IQFDh#As}ix?eT0Cr`eTL#VYr?J4&IMTe=aVUZ25g$zifpzo*Po^L-c@xS&)SSFD z(vwA-fuP2z0}v~jW%0HTr&d5fNFmz=tD8oOj)F>{!}v{^R#_k%wdnD7ec1Oth$TI< zFI)r3?#JiPg20?=M`5`(j>yPVjrTLZqm{Z?n2BFcnq_;%-g;e#P_&{P8F5^bKTWKf z9ktaxoA@+E_gu>RtGegYoq``E$EFKZLv2evf$aE|V}lW%5)Kl{pF+SvdOu(s5+y%2 zydK)*sjO^C)DqyM8*IdgqruWjQ2k3WtcEQCv5#V~V^K3++Ex*mj7tOY-M9v;1wVDt~0p$#m+gc`tl479ei-GCB*JF9fqoeR?F=Jf|tzbts=yA^>z z+uy6rh0y(uFb2Uy7VdWR@r*k;xeS!z_@@lRG1Q@gZ8V@9{S;6Q0V3 zU7L_LzrIx6rkc2Gg{3B~H_n38&#cS<5p`YI!=q|xl=*DKo0M0l?C+~N|CVSMXcM6f z&tU(yjj)F#9TY2CBBQi}J&{HFp`PEqvp~i*-x5mULUL-HJ_x5z0PXn1m~gv%fQ8%g zp+-ablIeJDowM0c9cXcrl_H==+^QvVkYj!Te|==5k8FMxSfb6qt;&rOjhNuyk5AzK zA>hH0@}bbSo<6DFJ&||J*GKBE-#)+;M?rPoh*+TU`uJV;8_X|q&fHq9#>lVJ=$Pdm zsjVW8V(-Q)e~V3De5E?a;;9KsY|WE5Ssq#;(s#PRYY7?qs(gLh1z0It<3Hn;+rfjZSgA0HWEM>Z#k%x+b?i-dUw5BTvQ5UMX|M{}<&WRUw z4_!3K`QC;k=Dj6Wtg$kP6jN#@mcGqH%D%Y`Q5Efaz8QpyS*XEq!$O}Ai!Ogv#zF`q zR5->P)31+USP({3Qw4qATRV%&dUZCNJ;a_|f@mzSdgu}RTIB8aJ6fkwhu&zLH8L}{ zGgfzeK#pszkB@m}n(ot3_Q)8)Q(cKaL|Y2zodAm75Ue=54FHrrD&(Z=#k9J#lql4WL6k#bY7f^=NbDk>muGV?i3XjwjQ5!W5?!;a_)%M z`Bc4C@K%??>qB1BCytU)j!KLzHbxxTi+V#kKLl`#@+g^5fJMbqSaRLf3R3{W;Zq?N z^Sf3kh{6F0RmEs`kGLG|+OBKVNuPfd3%>%RC>uBis z9u6Ux$%2hB@Gp9@oB-xbxA~ux?iU+GhgsdX>wu&${XW2fyLQziqYO z#8AlOQDiy3Ji*YO7fMiQ>enFHa!| zpxziP5jWP8;-t~OIxYdx;`_ecffhEIHC<2|Cc72wlUcMY;7PqDAebMoGAxVF(966C zKegLu%+APS;u;>Yt{Svmav48K9`6A9BRaL^QIlR^KOc1+@ksvO!pt}ro z2ijcBN}Rd7W!0q)7B>{$u2XRKWb8r3?6|n;1|RI8DATH^TKXbpdrFS3iaE|+zhq8K z*k-m;HM$73D5v2$j7-C^KIEQ}+sD+KdXSw$Ij~eu-`BREH@>RbmHCG`@t8##s=|u1 zAMW}GOJ{5M)ENx71P={tnygzY@b8mdhIm zn~Xib<`@N1%~e6Z3(zAP+qWeQb_;>MZ(1B9oyfqYnSE5ZdA9Pu3iwk#$UDh;SM02E zW&eVQ%!!Tj>C;~oat9a?i)8@Mp=Xke<{%>y&wklY6wyD9YWrk6d7^vH{R3Ji77a|VL_Fv~BBtD8^7>@(Qi^>;QYC%PqkUf{GL>2< z+L>qWx5_|)ftMo>4VI@d#_KffH}UzIEy_FCcygbk*R-qceeE0KjOS`V6Ll?JlaQ(T zvU#BW`QQK%q{WB%)4Y)3kH&GM-D+E!NiK|J5C6R3avfK_lIdcKOEXg)grq_rvK20Z zq4FMskMd7>VJBGZcF9m6e{#5l;Q#kUG?D#2c{qG3LkgU$dC9AIp-AK3odQsOY8y3O}j@5w?rDbN3p1Sm%Q!>ZWEgZVxA9}lh`OS4ZqAnEP;PlzkC%|LNL*` zuzppSa@%pXPcu)tu&Oe#LQpK>C(Y3QkOM;`=yYN(`T6*^?!qevs*IFjI%(pH1e!X@ zz(mi9&Ys5q3d=30q2W;;1$CU3FQ0fbyjb6}fvL5pP&C!8bArFPeru zdgT9nwLrbQMwQ?9tL{ObpZ4S|{U<=h#<-X)a-8S{=P52x9`L;{cKil0-&r<4NJWQD zX;ZWV-qZ!`D>=5vEgqzO8&MCLo>?h}=Sz4epfCh6mq*N?G{^zskie4iB`>71e1`oa z@u6`LAa+A%xce{P0SeJ{UPcFHvN+HEe#Wefrov`*-&bb$p6tk&zJvj~VXUd!@6G~n zBar*nI`^G1hHvP`XT?EN0Z{;8y8xM6$~{aGIO}buuw3mKm446? zn_(%podE8)Hj+y0u%(`3h}tRQfTp|X3v%kFN!8uag@L7U%l#% zItI8%sR<}*^6)Vd>#(>nqps0UpKYv+n(PUQq+^y?R3n-=MKccG#KOd#8;K-W@qKz> zA;Fnvqp0z%(mrcDiD|TH$>5QB=tiL?WJJEl0k%ctranaly0L{Tn~27zPK`W-j59Vw zr0f~3d|;^Z-r^4 zrvM0KPxqctUd0m8kFi@>IHK#B9x1=y1Fnw2 zbAVwC^s)%E>jhz-2^GGh z&(Yt7aqr&sj(O)&5FG7tX6bI*djnuc)UB8)d1@b4-f(zN>##L%VHM&ef%tzP8TNZn ze}r|);jVXvN0%(M{%NewICb#*h`&5eE``)pG}PIIArPptE-YM0WW3HB;_^uN>LRfz zIBRJbyoeDQJyz0NfEcg<;uc~a`&1gcE}5^=KS?12FRL(|~U>3y~v3U5C@yjn4ow~WsZjZHvyltY4c7`$_4AWl9@MS1P zk|&VkLl8e!NJ)9;rGU}ijN+1#pt$uXarB+ONRSMM6(f1dA>@WFx%+G!PIpj2OtAv8 zPj*BVF-C>Oh(SaaNJq#C@TQoZOQVUGn_z8LMe zZw&^<7YvcX9!;e~;AGkzibB95UGE1kREh_Ig76fv3NWQ$#3n$eWR0lkCKg9**b#?K zu2GmI9gLIz3~HjP81?Tu`*GHxU6~J(k8u%{SRZNh_OS%ablGOHj)T@8)E&XIMka2mdQ;QO}E>HFF-dpkEDGVedI)oIbiX~AW(WX309b}rGq`rEm@ z8$)Yb58nAcT%iZ#WMdyVd9BW}my~_C`wiW?8KS8x<+}>oX*qeI2I|M)03;B0q(e5D zEz76j_G%0P`$!)+^;%XvN+!1yQul;1NB! z%)BNLKq?}L!Plxly_cA{F|p1Pr2pMBNR+wbMoW*)CC>xR&a+&TB?zS(?XP)I)i6PgH};R+ z(CdA>ejlLD7vW?Mev=ZzN+ie&Rve=Z?n|CnwJy@~bS`GI^)U2Zz<#_(of91(dWG$^c+`a zu=ypU0whPm6%nxd=ct#*gQKd3b{o4;{F-C?xUyALJee&WvrY~14LhNGwaE0U!jXr1 zM43wE3uUW0HTv&v^^rsK-(K&Q3V3RPP{ayoQ)un$8xQhAmdzA$!NwzAaY4RvY2 zX%W&8cE4`b)0_d?>D3V9lX#4}eh&;C?Jugm~g@+x^K` zAktR27ZnCjVS0ZbPu6;u57MLn-`!MvLNg=`z=Q$#jR6U3j#vqRtvZWHh@aEGdDqnG z)gdEvuUKk?B`pTf(<~Y0H+SE4C-nHFyWHSRiYDv*e@dxQ(r)7mC^vMK8ZZL9h5-IG zC*a%@(0ezb9sj6JEOT(vhk}3ZKb=@EDs?i0HCLUM4>|oMo^(wHfV!QpY;JvZc0N}E z0=%5Rh2HwU%lXINTR#pt|2%f<=Sk<)tXr!E&c9CI`gPvfEgAB=-TBX}pE`O_kj;i9 z=KAN!t-q(6zxkfr82F))08pm^@&@bD9ERUU3!~4uWMT2CY)YY)d$xkv9-`h#jYok7 zEmPjMD8{>3H?Sf2YEi83Y163T65HZE{%36b)s3_pxTBdmLqy&Po^?9kwBWH$PH}ut zgzS8TQkg@AWMQZbWzyz1ePr)Fp0QI2@s}v7r!lZ` z+l|V^{ZHEc?~{^W=S&!e9E3EU4tI+uR@=jXY--x&R_(n|V1JaY9*Ubg%ngmg6* z^9{vzhWxY`7lWjN$7wLo_@SG>)GY-(xq$IQ5a^!|;{#Y4I&cv0Z8R|`M@u93uZA6% z7*dML3mh)B69^$P&~+U)PsVzL#0C9S9rx6*8liGgmOW-%b+Zuwf=)J?*skv0k+r2jttwcj0HV#{FU|r4Co0N z-s-A)-E0G2g22oX)A6meOWGEK-pCwn;T2eBJR#_Ia;X2F0JKBY< zT^tj`hh9oUhjg3&D>|Jw0_&wnes-D9y{fdUjX;?Q7ZFxU|m`PtRow{4?bA z)_d^pu77oXF)B;^Ji4-k*qwUZ>gw$sYb&Fs8Z#(8Au{@9V1cm48B6ebAx(!-tvLpK zp)LrKL*i9$qT<%0nnA}UY^W@Yt^eJWwP(X{G5xdQpF0bxO(g*ab1X-69q0$QcwY46 zMqYWdmaH3J$~)PGQc;j$oG^!aRSQH+Nzkx&uJX9fx(ppKP{`!V0^$rd1H{)7Z?H-M zH=tayC7s|UuNQ~_^uU_lVCrU$5NrSz%c^!m0a+RXCIJ4m0NX##FS4**&XR$g8gdpHFOoMh`zkQLA^ zfR5PWFeod{6ss6gHLz|%uqt2tIqhw&V_Q+_#e_|r2ZXMeBZZ`M%bIY!7AIp$SZ3cu zr6uDBNk~~B^;Ixr!6iE*nUe*r2*%=Ea;X~@U7uyK5@cwzqeN0T3k5L2?{LdEimF~) zzO}sv&iWr??-kWlAL!ez^pH?iLPx-a-o#L)n}l9OniK^M9i&JH5j6B7U;q(B!BC}% zbdaL-B1jVz6g40qAS&1p%g5#0d!KXmz4x3k&KP;iOPbDgka5apzw zD2xNX-8KR4tS5MJCSp5^T(-cu=ZYgi;x?wZE z*Y-U84zSKNR>IQ4 z>O9pxIL#E=x7O#~3kd&kW=Y85fnNF1(AEzwJL!`zSMu)1e)kjQ?@KBFlh=@>w&jYu zlqsU*R<$wNNq1&^R z0xNM@VPe>Q^Vex6$0VQUJ?5eX!GJ{;O1puAAvM8(KP-gyJcV6OEP=n9{9vN>sOC`u zM3Wz+inaGBUX48k?v^XZ8RyIVuT0W#VnAlSf;iD&(`Eav;y;OA8aX{op zkf!DzSDdzeYB0x6s&%*Hh8xGd0~733HY`i-2Y;R7C;1rH+wO&zKbDnd#<9`1X=p!# zQDr)X;Y!c`y-_eWQUe2*wh!zDYIik=ePVOlP+T4)cC`A|^P*g3xP z+Q@UZMU6-ZosZQqCe#K6#55TvpsbQoPuTygFbc3q{YQmyiFiREK_0V=B6yTKUIqYA z^l_rrfa8Tj?Dv$>Q1;xg0Re%f!Affvg_E^>{GT)oWs*rbeir42s@uL7a~d*?_Ww4w zrU3U%m=r%?D}p$-J;XnF$tqhx9NVkk zixA7wL)0pGkjS<;6@gi4DFii`6 zd8a%Z4VQ8J6n1aqPim~m0BG2-nW90)z^w-xAa3^nZSe9J^a-CZak-(hVq2`jZBU z);AFn)qIY#V!#h0mM`P*dt>+iITCJF3A5-+;#7=_MK8s3Ls&4+S@>>k`G6n~1%(X@ z{!#7ycgMw+4GS;D?tGZh4|F=YQTv@c%<3|sgIt+ZCA#$ycWN%)W;%dN0eQR1ijyShtU-x6u`D<#hxnRhV{eLHeh}G&FkMss&X}TOk-+?T_YatZBMXE$^Z&^!%7t&R7u@5mYi z9qQZ35=tUlS|XgN>K?Gu%B$PZDr0`URCK;}LlHfz&q+d2^IOJYhdHQ`>5EG(W z(L(oz~S?&5FO3+b^eN*{pJL ze?4F;rHG-*=cpY&x{IOz@u@^_$nk!omX$(n zW+g6&WdH;YAsV+*n1Lsh=l}=y*CwT|XYaJ+8n~!R2^_U2v3Oj?j-wL^U$B40FRfFSq>OqWvNG6A!=5L zynE0ReEpXUWVrb;rA0y*aXX99d7ZPDEA{;PRdqCWt9qoVan~$EivE~PN~e4oAa1Ex z|CTd_t^+31f9MUo5T@a&rUYRYAjASZ>RN<)AsS()yq6(w;f^vjPk`hT0#kOxS{)c( zd=W(u`N};4Cvq#9?w1c9uc<1SMSZ5J-48Q}CM=^epS8U4kJk}1!Ii=tGbF@&V_CiU zO#rgI#kXe$eV)e%A`f?bJ|jJjAX74dzM|`_t63&LpL5AlmUkI4=<{SEg#2{wX+8Ly zXEtZQ<^9cfERRRlMEaLVKWQuM>ca{(+U~Ejgc`}- zFrqVd!`sl@(%j}#7?1mM(g`6TwUe2!{;8O=w#??cK`URYjnr*)yf@PD^vk-F#x=%% zih%)*_xItdelLGKOkWB6CnAWgJ&0pB2zM-)H!@hTJ^1rVN#TjWeLr6Q<;YIM9btzP zmzpG=)x*Vlx%k~)SUeWa&VjH9=w)fBMDH1u7mj(=oKYt5h|fg!hVcC`yhuMjhBoyr zR490q8qn^h;zRhgj>q+L&nidlJcH`VeTtt#{pyWEL8J0snBLqzG12Dtz9m||jnj1- z!(S>rk$vgt91?L&|8RWK%NZ@-nhKpwKdWmoh-b&EQ#UKCBecH{Nts=~gTc=EBy96# zi@8FGRB!jIZioAk4>PXBZmP1yV~Y7$02>9KrcE7`|(c@|>--#ZLj3EKN-N=kb&pe+L zSgHsB>k66s-x46q*NYvNU%ktRBeOo(L31Y7GLY9kv^f6NU?3KV6_JEV0+JTR;10X6 zk+a%hot-wPixtD);Lb_2(_PSi6MqXA|XKC(BYJBR+sGAb)<%IIt~b zwJrR4MP#R=>DqIXVZ^EDh^(!PRjQTJ1&?pNFoRBf?_VcC--JuRSM#MP>JowydeiXD zUORG-t|+hAWp9`;lT*r$29|QBvg|kwVG2p|=3}tJ6;olvE(xe0Tc%F}{Woqf+cAH) zs<-A%pK1|G1NwnxC+IBsCUQFQmH3qaF7ZivieffC2B6)N-Ty_v`;=fSO^ZbzSO*l= ziH%_tC~%%Wp36=JD)EI!fXL(2B4}~P7XxFL< zbAbEAp`uZ+wstWcN}}{df&sHqq#tH*y}V$~u%VZG>-3cHvQMnZu}7o$azYNYAGLBS+w4Z@9edSzbaApDLZg*1-MAu?1gsZ5YF#zFfS1LtIV-&_;tYa#H+ex z<5Rll+0Rf9h$mw;XeFlf);#ItCK=*$3gMeqX>V5M8`ahIJp5;L$E9?#5M57bP;xN& zTCIFwa;2lfF%#dqZ1!s-TIhF2{OKd=^h?I{%Xar4`O~kYGoThTpxHg3`)7cnGiVqyxNq7$c;e5Xwa(C~ zm?5X`A(uZxt~$e>F~h#y!vTMWgLOv2V@57^kLX(yuP=;LGf?r)qfXnGQx`{f8%FcG z$BO=pmFPUKhK(YyiaFhC}twzn9Hl16T$U5;YqO#d{5fz zpS;$YT#cFB=$`!eXL3hp>U+%8UiZ}BKT{ChX+-QaThBDd-)Wrg3~%g=V9$)m-x;Fr ztYqx0Y|reGzq3lZPt{_dwg)$8^o;5JeQK?6%TRYnAdv8fAVTe#JFdWQSMLEQZTws%2`PyiQ`B;%53-b6?-G#i^g_}JK+(kX54}ULs%D=1- zX{+ja`Bjea|H@kZ>&g7}zxQOmRQ|v4WZu`vu%5LVpd!f<<^r6hq*a}(tEnT^8<>zS@B zUO>y;C0VAjYB^mf_&>8&?)uU^-%<}<(}9w?+|dwnvTRAD6}uzsbP;+bT$ZF1H}Kv|fJQKKi;I{IzD9I75ea;K@ubpCK1qmTFRlUx-Xjttpc+dy*bb$Rph3IG8-VXe*VCd>1GB>M1(b^ zi(e3v|JcIp*EcGHzFuGh@YWwbw&%tZKNMY4)vgdRy&PKb`}-EX^3q5hYDgUlk9jypq8*clXfSrQ-v_&9+WPn)fsk!>~V zv|O9iAlLEa__{BT`(7`kige#wP8XM-rb9Uh%m%4(on7|DBB-WK`aKykO{EJ~vGsM< zA~GUXq;}D1t=VXM;oCFEfl4JxHD*-*InALnoJtL%k?FjN2W?dU_Ky*^wLUS4<##(5 zzQ2lkf8@nPQ_a47^&2{B@`k)5ENFC5MoRMMvdUu}a5}?S@qt4k*WAuZf%h9;fz9)u z_TC$4a?Xyg%%5k>sIF*{iXG50Kt*n-P zPriD)l|@e8_rwC+;Al3%gv$Gbe6)UgsOej~wsH*d5)kFYb;Gt_$ZayNNCmpwmd{{I zok%8!-NNjP%xaG>^no$`WXhsfib##V|Jdl8Zbfe%B~@ES~uptq84dL|*&byM_++kJ1vG|KMjpucBM;ulu%sv!y9i|-Yl$j>Qi_i0Wc0(-Sg6xb13Z5J zc-Urt4Cku_ZGKXYro_`?H1F(>(mium&9DN5!Fw?XkQ~`&;LG-8JxK_M@}2Z|gex$= zuT&4X`F<&vT`DtjFuQY^W=DvO5|zM6gJ!h47}(5BTm%w`40&p6CY)C6Xf_A9w&Z(S zR2mR=tgpD$T{j~6Vyhk7^15599RFGxeom~a50vA^JwX5@FVx{D9Kp!FgkxwUTr?h@ z40N2ge=k(jyfkM2Dkt?`NH#XjYwI55kO^*8319q!B^+E)>sG<-n3!?zI?yXZ<(ap< zAQd5=>0IY^H54uc_7cv0+-y!2WOo_mCRSe6-?v;&o(TNW+Ac_^)S+yEegE_L3WX!& zUFqs@K{|{&?Ifogg3{iyCfrTB7ZRuPly`KZ6`ZJiY(^I&v3K<-8aE0!-hi{j2Ta2GRzdXO9G6 z!|iU1+}d3%a^xtl?c0*~#YTaT`CUV?dA+=b7us6!-9Zt}9|(dxt%-ue8Vtas ziK>u%FX8m>*OwZ@9CjinT})oYTuE?6#X1bD$r3TX1q0}*H8FHuTFi++5+(in)P;sf z+3l>KEa8cBTHL3Te%84u4;dzF&iN1`)JC%{TQ@U4Oru5ivBo5p+|G?$Pkc$$PjaA; z--XbRuJ4M&DbxaE69E?54v!9OUJZQfsdK|fAmM?_o2*+pTiGiPcKu(<%*rwj- z3{LsmMb*C_T(eWZ`)j#;z4?n^{8H9X*!tVqu(v)I zO{HvW0wK;(e}0}sH&Dc!n(`mT^BPcKl=D(0fsBSQbRXn!zA0bc70v>DkvC<`{W2VP z{#8hXBn7!{gzJU{R}X}8$q0B2<9-f!aHHvKPcg0eO8N&(zA=tLM`Ns|81K%)i2yv? zr{*b?7$tz6$BoTJN{@OzQ}HljSh$mp{jS9Qeh=f<%97hrf4&ce{b`9Pg-V6pF^ z``8{N-LNpscXhad^B@6F-2DM^Z0-I)0sz1+MDdZ|$-)ubkOJx-RWSCML!+v};+*Ag z7+xta9K95bB;t@X|86&DEXPWtAIqB}(q7YHG5*Yk1Rz zqp4u?D0nCc5D0=|gHpbrFD#L)k$uucWAO0wH9lOT?20Es^(g5D#!$fjr+RXFzh#P% z;n5bu7acg9ZvqsDGT)ENe)fX_YXpcR(p*7lL~F|KTGT+(kzAVmS}t}`D)~_v+5NdK z)HPca7bD_?tG}D8mF$7V`SL;7pSe@yZb%D-$~p5LC@b0BS}`S6mX=;xysO!Mk+=m< zoKtmPdU!rpFly`@!(0418^qNnpW3N^f=ewlCo<7(R5Nwhwrv<}@WB@l!05Dmr#xj- z6TCwj$QNcwQL%e98?g87WckK*-EfP{1>2o+s${reYb*lnP1PlJfVOf+5o)#_U8tE(+3Yh0yI8V(k2xo|6u+i1Js9ow0|q$q4( zF()yD&D9eVcfHf}^h{*oLzQEGHp$DHNG@7BZybb+L=|#{3%tDJcjFEp4g>emn4l(1 zI=aD2s154&q1(sY=Y6#_a{2lWzCAUT7$toE+$HMKUV$Q{tCGyLW1N$+xSEsk`mr^% zI}uV)APEm;a2@M($Dn}s7iF?<8m}){J4Kkb<&`25lEV5%z(f;YYP9ONI$4s5BeR8HRuOM*5t1^1V#pv%9ywI#jOQtsD0n5I$1bHc~D*>E{{tIIVmWD{c&6KxjUe zkAGC@g=yqcOllES(YUEBfc&Cpy!a8te37`U1rg&snbPrd|I zzQ(GjNK(?;3@g07RXRAceUL#x4-#b7bL3*2&Z}bqRa&gaW-DsuS|orp_3~nw;_e&8 zag{}|?QoQbIHlh*cQmOZW>?jc*0clyZE#HmSaGor>P?+&6 z+o1ZAA(U8ks6xpV3i=(8IbRYikpp+jnizx|5EGp1#8Aje zZ>7wj;7n8NT(2PLetHXcgdO->fOOr50@Ad>L>*jCNSFr=aL{yF*wnJA8DXkIPQ~Ck zkRu|EK&Aq`|3yF7cCe-Y;2D3giGc17mA=L1pL6=YC-qUGu$yUr9W)#A+7D;>2SPcO zv1yBOCuiGW%nw1JsszQ*>Ff*mqfQDSr#s5}(s%CY}++o+jEw%~K#uAk@Ek@j=mQU*@J;<{OuI7Z6E^~4WMS7L3WO51GTFV*j4YR6E12Zt!@Prt@+Wk@gd^GARZSoRp#%?WFK1LT{LQ!fhJl1JkCG?Ow5KE|>Fao_; z$PblJx!$MFVd&6?t|N`~JA6+~iyjCxw(&RWrU1_^oxxBVlC5Oa@x(Jon8b(~{=l*3 zmkG_EfA(Qb+vEI;-lgm7~Sd<)s6da|2(LJDtmXS2T zANPc4N1kv0!uTkRC!GLLG&T5lgvdSc3<lRYsiurA0iCch92!r z$f;Uj=2)ct#lu^no;eJ1}hotmEn!?eaR>Y-2yEB$`9L>+o z0>VdhaZs~27BOk(u)vpgcup|in9FKb|C4{r(^G>Q%vh)ItU_#$l<@=~&DozlxZ0;+ zT*LK5pJqB2tL1bbtCb1&0M(YChz3ys8q$Ha=sLp@eO4BJN*sE5jmx!>FIb)DB5(*7 zvaIZkq?g!Ps4E7l`A#okb`tLCg1UrdC=p2^953Uf1Qg#te-`IviR;rD=3hE%X(xN2y5WbXq- zOE5q6lcU?9(e^r=@``7P$G!ABSTzcboHXH)krGC^c zOyX$-cxJcRDUYel40Pi=?%w(KBM0<0w{8Oww)Dd^0lcidON-<5Z`h^VWOGpFka4SL zIiirn>xMjb)wk{=X05{vd* zF7XQe{q3?A2%=2mRZT0K#xEuaFvDt;4zge+#&7_^A!<-yRnlhzY_gvguwFJu=RIX$sEHC6~!YZLP))R%qJ*rax#?JOgON_PXLZK z4I}Yl0(RHS%g@_b)SS9^cBt^w2m5-Lp38_s_6p-DtSCNLtp`!B*1RWKVH%l?bU6lPt1Vs8Vq<=EC`{}hfb}_5JfhH~ua2Nxm6t5huVQ=3 z!L#+0gF_O7-VRq-w@naDjr<`^eO%iPiDSXr|;c6$y(>D?^bs1 zpRc_?tmSvFeXY~){v)Kef8&T$mw)q=VxU|S-Orc5OAZzq@hO__2#y2)KbcE-vkeNnX1G@t@$E}MKvou zn9`8#ji?XzNA$!O+v7z64ik-nM0S#o-leZo#>Zp7zwmw(yZbif_~pI#cOPB;{dwg0 zmA||1A6?nsN6`+*YBH2>nvOD{L3umKNcHJBu0$GKQiJk8J((R8PA&6&_RC+-pbRzo zH5)S%r45KV$fXpXw&|p!iLUIP8u~)dr<0Ejx^jkh=!^cCPB{*D1Culi#Q0`XjSbxJ zc^w8)>N9C46Ww@>6D5H#AbjT*l``Lq7dDx>DmX(gaP(%pNIMaIDCnBQX@GvHmrOh6 z6E`ZA14|fXnsBE<`r$te_3Ys=j-R|jQ^PuIk|UnLd>^MG9%eNAgpji3E+MIDYGyy1 zlRxMog-Agp*`3V2lfmMB-K=YMBP6a|)dWo?#K{-V<{>2{KS^xMcjL-cvSKP^ooqoA z&k8iMS<>5|shrTlLIDgq7T^Ei)oM-}6X=!ZoYlr<^@B(E$w?}CQOWTIViymHMZ`V> zq&e%~GA}pC=uM#n2Z<41X-MP636N;M!CWz(5s|jIt4F4lim5Rt{#H&WxaW9al4&qr zfMJ-_@s(iL08!l6oEcsv-$Z0r8TkYB%*tNGKRTmW87-U9a3$JtD-Vi4(<;L(5#_or zM&(h#8EygqLejVSXD^Cx%}znfFv*3{as{I#WZ{! z9-4XZJDZ?gZra1ldCD_T5WjOXoeludMu=Un*hd7GtC|9YGK6WJ+jwCd67+!K$)W(~ zv^f`x6{+)z?6Ws(26)&vd!7(KpfBU_H1fqqb3owU_XU#SVC#KE;N0ay&dbUH9Ycnn zX0mQMuPysOc#;(Ou=vpHii1er+)!XdYnRKXh!wb9Nn?&OWIA@IO77=l=Qe;?X|hVCY?^!s3|kJvd`$3wz%apU8JpkU_>OHcY}C z=H>AM=O`E~9UpWG${y4}dE@7bcNl^@eW6QAV1d9J^F#U8bo^Nz_la+D!^e>0ke64% zhj!4BPaVrpQ}5#yyEDp7BZHV`4z9T(OqAxISj-b#Bxhr*as(a10+Lf3~HDv3v0 z!-X+D>uIzFZUFsNdb@L3#;W&nzGqmaTEN4gmj#!P6>L<#z6-&0PtKMasVQ?&;|D5V zKD+<6tO^>-t;*3YGLoh*XDfx zBrTJ!aq63j*31ch<*)dQSDve<84Cvz4g&{k<;c!wJ%JJJT?tXTsk{yB0P)@T>BW_J z28WnqLW9wBl67%vnZoM+UDNyN;*-r?15yyZ&jQ4zK^NG%AmnKplTi5q7=TO%%(SV8 z-Pga+&#S2JrRNE&>F%JIkz9d--WJF)7r0CegPJAW>4&8A#9RV*oq?8vqc4gcJFvX9 z1YGm&?Fi62i?tG~M^)>K@XVmDK6Tr8`5n$DdJk7?4u6A$M6LwouhepV5}O&u0x<+X zN!ns)UO?l!(j)PBQrA}SK>Rf<{>6b75Rd5~_bN3x7_PsDb-i+F6X%b=^yaU>5UQ(2 zyaA%;ZR+%CA(Qt9K7ysj0$eXF-Z@0@Y|<|F>#TjCTU!O8;+xXDUqvO#F`@@v<`#=I z{C=n7bn@x${+r!LsLR_)$77cH-~JroKZ6nI&R)FJzGi0p@bs=o9J+u7eXWnaw>93$ znaDR_%uhKZNt#+UKK|g4eWI9HDgRf$A8&Ell`lEm;_j7+0LnkSewX>N_33rK#Fii~ zKYg^41Bh-nC!iDcsvw3|Itl1zh=u%Z^P(4xBGU=ITS7{BG=$x!`-SgAYkTRMB5l6xAC;%+i7N%?hjWfwj^OJ%7b@S1GcEVv6{nzJb9%jU9@# zegnATJ$baiPqMLryrfCuewo3OoL-9<`Gl{c+pcPsF}0>VLpG{Iwg!f^gdsZ#d4Kgl%oo-DF7RO*&# z-9*1xYn=W#hhv()@Ddj~VJw1ycyae#1N-9tpeeJ!${2kb)3_&~^psMTe7%?|C$ay$ zSz0OW$nG}qqE9!&LU(Or@1x9>>H%quAo!|(L~@}hQALD}Wl^XyFyQ`V-+N)S$KcjL z$TfPd==$CSE9{0URs5*J?e~6M@2c;=|7Ngu;K`hu{J1jt>D%OI_|!Jf)Q-f|7uBh+ z22tb7v~ZtBB~7FArr9c{F|E_sp=tJK(;TbQoZqLp5Hr6_>7XR>nUctA9|eDEhSzh3 zFMQ@-PiEeXV8x73>&&5{8R2I$BC9i^-)9aZW(mBrM9En(wOMh)S&37#lAg0t;j_|7 zvod+JfTYm)%~|;&8&SzTg;g7>c#2}c;R{tz(vYaU8haP%l;gb)$_x|mwqV_KI{N638wY#|}`ta}XpC_NU&maA_ ztJ*eqjt=MZVa1`Ps#x*t>gzP>Z)={V1RneKH;H^+RZGdj5$j7Sgk+iJ)PK9GMzG=o zUPPg7efcVBSms@Z>T{oW|8`a1W$FA_e|L?HT(HJb`FzVAg@pg*MbtM|a;=PHSFhVG zYn;n-^r~Jx;6?uJswT^>6?okEmlvt5UMuu(+gQ65^wRJ)*?f9IfFpPz*(B%HXb?O?n6J+k#dx#Wq=N|5A}O_X6Mtpk(Y|^^9csS6Z@skEaBRO;;7{?T9c_ z+fPvf)b*+N#p^Yo!0R&y_pJVZ_#})qV1`eus?(NV@2=*tahghH)j>^r5Eq_=9t2W! zrdtWQ9*Nx%84%622I=9Sa|lxjYl`!$Csv!#2V2v^wP94FqDKDX^ZZ;4-B8LgZp%m# zJo{=t{~ss~XroyKBp&`L@Hy6ZI%mm5I+06nY%Mw0BAC<*1bxAsi`fPMRjX_FK8cEi zjEueAy->g%7Yct5kl3;zWIw2r=nOzgM%*S7bV0PB4}iTkPvjhj^?vv>($|fy=MEHS zkqHMB$<}fZ?-|-Kr!opKu@tYT52Cb8^gHQ{^AceOBJ9$&xAVk;*_O`D?z4aC7ZOrZ zu63mR(lPG+))()G&JY!3-32ex6KN3z17jKygNo^f^sLcka>&8{V!br6Pr!*}Gt!mx zvz{paZcc!-G^CY0gd=M^mnue~Z>1gl`L&+sc|@y!L|nZ6g7@=`6-#I+4>g zMMr9ow?IKafx3jLSF7`(!2m%opB&zxBRN%n9*e9zYl{-8PoayWhlG_-=J@hVi9S!c zNLjvGUIqS;GJ(&m7j1J#m~!@i&=NmK#=Sz462%5r2BVCSUI(xCX@r$l_OZCyixOFr z?9%pL>Kc;^v$rBu_<)I|V>UMuZ!TxNxA{b1oT6uk-hSt#h(Yf6)I(V3+y>StmTVf@ zJXC98Ts$suntD;|x{Pg?v;bBbyqC$I^pDoUBY|1;6+!wbZYAoW9t04i^R1lxfXQ;x z0Ml6G**fnE72g4*LZKCi%I(8|$!VNJOxYc>LABMzcnT2pDFCKR_y%}sTC0DrJVYFr zc$|%O;rw2s1epi8s7eVCng{OPo%UigkRf%RSHXRB6B&ZObUB>esDsD;{rTK9&U&6& z)_aGzXdIM=g(9bAT~OFOi#lkvru^-PMo9LDQg8&7wx}h&s#hjwCw?T%Ko>o}aHGzR z*D~nP(%N^M8OV-@ZObMlYx?okm|jLvW&nkogx5%BQ82nV+agF)GmziET78qD;H@YBR{xg z)b(nl-O2;c@eh|PcBeD^#0*Lfw&OY#_8@d%0}1!_VH2z4LEbI*-B77{1xDScsd9LJ z_{0A(rt4@99f0|I26MQ?wm7nW)M+r$^?vKEwO7Z}=g|&jiR>-fEqyW(!}^~Ucvd`V*AdZAyxN1= z!_SUF$-Qan@3e@W<~+RnrWMC|;0IBd;QE_X7)*c#T9Kjd1*qunp`r;dxYJ zYVZFNGmlJ5$m5Sk8&5aCmDzWshhU*pbi)nCFH4QJ!CKGL*cH&4q;CQ|*IT!CYq!WM zeGc-iUQw&dgYugE@ULi)6;EXMxT*vYn6`ad1otJarc9cHp8?i^DKR6}ir}_#pHqn<`V(?XUc{qQ<@3@) zIOktz?<{mD+~}oLQ_R>$dam?ha@8pNyMy1!hQ+wFKg?8zKRu3TFcGQTZuN^^2n~nLtOWMv0>1@Yk zS^4j}k(5=A-qzP6m#JBWdAq>W=fC;1EnC8Av6;r9_4zn`ck@G4M}E7)xqn6>zJ?l| ziYKe+ZNMV`s4Bk@v(f(=kML1+CwY31kR1-*RVaW!ishkLXbWf`WEbRL;Cdp#Dq7;( z5d(-LIPa#g3RMOw;y88^9DH!V4Xu9|7A^$}Ic0L8QFwBmaWLU%+<*a7pCs@??R&&A z*o^w^c3ZA}QWB<-?$H3OMra8t$qF@7F3Kpvw;|8-@jTzpL$g&H!t|eps}T~E{`T8F zNxsNEV^nh&CqtLUcBCy!90gQVH0_SAygT9S?viJy>u+K^;TGw3PjNPcNDHkiNH_-?xj5e3~v$5^_OZ=8%%^x38xFddiG| zX}r69;xX{0iAEDXUEJMzI@j1DO6$p*>-!GsLMyJU)M}E7{6)&#G131NMuFkd@!2ZS zZ0tuBxj`g%^w}gOl;0b~BRXH!XTI@4Qa0 z;oj_*hP-jh5mt&+xM?N}V_Q>JJNC}_D^=;tkXn#5*mFwjnL7XnQN5|S!yUNVgJ%#K z@NEOv_RrkRro(eI-8-ZBZ*%r+C8#w0TvT5$tTBhH5qi@Nu8@EZ+yfZ^8&?DU3oDP= zbXd^%iu{aOd(w3{(GNd!a=knlO*whGJ|&T1WCzX3rvn6XYA+ zPvknnm!h-sz>9X*xMwcJIDoC|U~8T;Jexh&2>iw3GN`=i(tlHHM{&_nqiq!($dD}_ z1Ks&=x~stWnEuUspdbsUZmTyLf2*Gw4#fdK*-3F1{tZyDc0FF@4rT*vUKHpcQ1{}geo^h1WE=g5LRwwF;N+| z@f=EYbRS&H^<274X+wOh6h)gypAFs$w7Drle{p=WJwen0Re}H%JxI;<=$>a;rC71d z5=P!C-~$26Wr9qh-DZazxY2c2*Z>s4ES8`9O$$0J2y;9NWZx)X77Mq>KtU^?KutOB zU}(82(y$P(R7uJltGp=2lq_+MC!lMn+TqoA*meMSGw!nea19%|Xl^Bf-{#%^FX(}S>s_LC8@8lVFfI#`jpPn4K{UcQ zS=6#F3Ee~7I-Z?k#G_QO#rzeH0J_N$z)&WtjLz;GceeeiC@Uz_n1-^3^VzmFUcY7j zwY2KcL7Pw;e97=f?#DqSZt<#+U{A1zaYB4#pb-wrsz&yR#N9!t8)26$m#^|F(H?Ff zVec=AcFXf>4?}o1@!wQYS`{rv48d?_XowZ^Yy;%47U*ZC?vM>Ln11vojz|L@(Hapq z<6F=Wh}ItNUb(Hl$3qx}?P>!WU?C83kfGW%hd!uCdfy_B=(>T9Hv|gQ&8Db5g=ZLh zFYhTo?!VfAie@1L2@VFc&D&Z$6Ig)H0^IZ*SX4rtp@UKVHK$$Slv?o3m!aifu3wu0 zIgkRKX#>9ul5sF4`dM{CCwUucA0tvs1%w&0f`da=kQ(FdM{uQvK69LvTp19A_*53^ zwjXR2z9kZh1;StP3b-GW$dk3Z3c6-I2&hCpY{div0jAB6AuNz@gQSpk+!{GD|A^G> z(xH^J)7ICX*nm$ozu^~Wl| z+R6yf$Ay`f<*bl_(+8h%_7al4)FbQ?WK2OaB?v901y-?5+V|DOOn}@mxZ6~li0Nts z0bCm&es^2^=S>}CHiZB>+CU&+4X!GqsaTV^LbKUpm;4CpUodP#WJd)&xNuCCr{=CL zl2mET^yYM}=PjA$T#{?w;L#>ahv_`Vo)8(>gP4jZAmgNw(|5IqlU(~V)&5=hk4m$~ zecdVq2Y`H6kum#%=!gY}-L<;!3%B54qerp>*+HI)oTr{joO!ZyOSm|j8?w`p{|{&H z{ngat?^&Pp&`(0|3B4P7hlJk5(2D}0Ns%g5L`|rn8W0c*3J8b@2nd3W-feVHMCr{2 zioG!LbH8`)y>n+~&GY;Ltd+$t$vJz!_p8M;8Y+@E8K;UM@4#Fiigp-)(G~!X*Zs&b zUTWQ7K?O{&3HIyo%;GqDX!)3Axf3_J)onM%GHiAvWhh0{SiG38fy}C;G}pR}-r;r^ z|J*PGQ})6^p$-rVNs9F?3fl7|_levi)3%XMz{!PKfPsQn0B1$`tl3dlMP-*ygx}Q$ zop2zPfufcJpC9vzcaLC{z#ss~{`DeE4fT;bOI#n!QA2uBU%>DHc_Yy+8j8OIAQ+b; zcAoaXlQCB~Cb^%9ZapXeX{GE08Rp|42O|OlZ#aM^I3jOi-b-ep8$>n%s@kRnCIA+! zq1f>K9uv2Tf|}#5b&0+XTpnYFWpY>06-`vE+->qM+Dr;GJPao_@gW;!U*)AY^!H4Z zEycufnov+ka*q9wF%lpIaV(o6UIR@p4n%+jDGkuE*BrjLU>2Ovv;*?59zZEmQ;gU#wS zbr9ys2@txwzW*Ey$X^Q+8-N#h2X-=d79PkMjLs{9Dq|ZCVoJwUH>GGxw9}jP{VSW< zotwF@HuL{%GTtLHjIa)DTPEqlC4b^duVBty*}C#)t6Xfm(rCNNd%NcJcI}nzy3XzT zSKEz$wwuJ>v>3f<^?t)#5$(A0=3eKU2e00A{&~|a_O{pPZT~C0_hPT(;kS&mx1+Dj zbGlJa#NJI9y_@oWH*@+O$2=f|dx{02bMFmB#~`nb-miMUUqAhR^UC|}&i8Y)K!6f2 zQviGG&1XF!yd?HsucwO;1q%p=$%E@?hY4si4B7>%F-;-dhfiXX!ecws_dF5ofHAd~ zgXSHZzvl8_N2qI8w#{6mTSvLKuK&+5)^1c8Gd9_ z{lJqA0G#9xhp#GOn_hE_-6BOw=9Q1mQ_-{F7qg{z*fE^p4y^4r=I{E3?#E|m*@C@i5c~FK7HN}BM0MOd`>M8L-tsEL|1nN=;0m3&V3E>7#AqsX; zG(W84;<9zLubD1b?yH;zym~QZ~}mh5{BuEESY3*h#IB+ zKlmadCm0kS;0WbE?WzhnZ;~s`^TfhKMxU6lS(W8KZffdv`VU`3M?IG8Zh0LFkXYjf zLJ<{bZGaWsRV_A( zxBAs=l}{EfQkDPis$SMBt%GB+j^k1y*utBswK(p-zKDi3jK}Fmm?h$=$XR=1<|#Ru zgpzJ0n{t_J>^qqA2k!N;Nzrk`7P8gO)~Mjvkv<#kwbtRDh_@Qf4(%^hVeE@(=c;ei zm=vH{Oy(%g9zljp8D>x2t(1y`ml?Pn_JcH6-!;25K5+q4xf$Q{fip&i*lquY^v5Rh zPmbOin0a89lsD~N_s!F89OX`Xv8)qNQ2d5AuYR%e z8WPxCoRQK2h3FHaegb#bUycRNLac4?0ZM1Wk$RhD8EMvP?&%hKTUS6b(-+a5+zZJ( z%DA_`UH879Wq`s3J>j8IkDO=bPYG)>(tmn|s4C31e^~qLc)4L%HuZkQ{q#axXr)8a z2mG-hLkJ-7UdEuBk708^YJisC-Fo#t12Q)h6WH(pA|bWc@D~Qvg{c8Z z4Y1gKAe7*6VU;08hBSdY2V5nd$eyjWax9rBx^5Pz;Bwc-_0B}`t+YU;KwVqU*EV+S`%&+&N-<^pBihQSgdM(U@JR$yVmeeaG%z02pM} z2aZj{WeXLee^-~zw4Ca>BRRv-gb zZMA-Xyo%y=s8gdVq)n;1J~Ih6Gu~6a;2eAro#lDGM1H(CdJ-SF5^SZ}s+GKbs7khN zj3QA3DpgKZvtG>J{`1B0qF8VdvCmYgR5kbF7iW`06gVC|LAa{&rskc=qM6Wb8L`Fk z8wZs`?*ykz6_Azd=2`#|dXh^cD_u!{Gt?asAlqD0Y`iUh&12eA9NReE5SjjF&^aR= zKRDeuzXcukYZ|}*#YIPAvBC$TSoWM_rfF~sxEuxt*!w>;on6b@_s8pdjJnRWoIfSz zqk7-tv6(NuW+eq-H|jB=X8}bB9DOfAo}0MCcObj1>{y`w;TJPAciIQSBjWBKe)VOh zy$cZ$m9BqenQyjZ$UNeB@%j$#?OylJ%b>65Hnm zHYjcnmf~o?pDKFySH(U2;G#fU$~k;DaYr(N^&p~KxZsV+QCL*rd#~87;dF(w1pw|C ziVU{~-Ubs20;FUrsI|jOz3;Xqdy;ett;Twx*5PF$kbN@#QNW%=P!w51Ueyqw zui?fk&Bdc#O2qHmUV=xD<*K(3KA)~aipAxjcfK=9@%?FWE>?$KU#x{SaGZp1^|&m0 z2p>w;#YZ94O@1kHXJb~~oom!TZBrm#hG}e03mgL6<41GGNUYm-dmXEj)yBQ%=XEb! zGp)p?@bAkc(nf}>r6|l#n&im!K587G$c!u_%`+TQ7#o3qZ+CwLv z#&yPA`TBCh7?m`ZZWLR|zp!a(nKV({8C#>huyrUiX{y>NuFh>?+ifUmrmZvXpIued z$+-ce_^J~Sz+UR)i|NiU$vE?NR?F1~9u;)kWR^BKmJ|cf}sI_*l??aIz*OM(eKH+M^P6|5pzLh#URorhnn? zo~g@Zm9p*DTq`pM;QuK9K74ZfdBGMqNSM$-HKg{o`uD@{i)0@}Ny8gmlDx@)zztMeHE{!rjGG&_Zr0P51lC zS&Lufzi{{7z_UzX@6(}7Cft>9ko257l=1uWU%0E%=4Y%t_!sWxw{nqUfUzv1xQK>- zo-SX=Y5~`RDMJ(>GI1zdIgX5njax|;{)M~5_&uFW(VIFK7{!N6LS%A(!EZ}RF*=sf z0EsU^x*%vKWFzf+R0v%(LPu>xApkceQI^0LT1)%Lv%0E~skI%PX=k&?i~;CY#MaY2 zRgL|8_g`MmK=athR6NF46D`5mo6S?M_YX_j6+%WX-JIL)L4gLx-gT^gxx;!pj!J|9 z8uY{O@9$(B%`Am-oE%HpUB7w2Cv)y3 z!kSYJS*Ie)Eyonc1b~3V-C?QJwsOT>lb`0TFvu@2cIlzF;@2AI#y^aXYGu zY-)FtY$r!mk|SN5Y2IEvQ}wC*aoe3+y@R-8=m;x`+_j2F_{A2zYk zK78IhCt@S&IPvJ?R|_lMXd8)|$gYZ(d(f;$6o6Xy$x4`xpNQ{*dOzm$5uSNZu5L*w zFV{onF5W*50eF%_Tx<12X(CtymL!5(KooJm)J+2`2H}N8dy|Z`!P8S8QVIPoPanji zWTYRTVBtoy@>TVwb`Ua%B2RbsSC6Bgu)rgLF$9ybru`{cg0L~1!0U52^!xFl^GVoe ztkCXaT5dKapqRHohf%~K#Zxpk@CQBd;N|CBoIL9_kq@y0imd$@dsbdR4#GaV!0Ac5 z=v%yQHLRDnd(60UcJs(MDO$8NsKPVBB+bW#Pg{ zUV7^K)go4sxjJ=ra3_zR;emI+rj&wA#8V14BcVIAdlGCG0%euu8>h}zSW$GQL8QyYvk`I6?GOI$D%k@ zA4)n$;==FMnwdZj-G@*ec2BMnDH|5FRqFse4GtL?on08F;b6F7BJ-Ka`gcP?pVXy` zSK^ESGY1^)EnU=p2@Q{b)^O@cSVS)b2(LAjID4v4)AI1WIOMf!4D$t|76Gh`fJa{4 zz9QNRaelJ@Vn!1VhAn6aD$?pJd9|eJtmY$yu5*z3_JfVb$U0!|vV-$joUmUigxzg# z=gbW#fGB#j@DXlm_qP76D2pR&JHnK|XZkrYQM;hXJ}sU>xkY?Azwko{dDi%NUsErS z43PV@3!v9cb#4quMp14_I&dd-mRtVRn;0g2Q?1Y#6GSh_6FG6pnDo4j<3YIL9 zA(A9M0y^{Kw~;i`^;r%fh~vui@L$IDOR6|nG2;XA9dA0Y9psd zC8^h%)A8p$rJJ8_U;TAo`B=oWbNdI;A8KWcQd`-8G9*z)G38YxyIEh?(|C7q)8`d7 z?QEUV0aD$)wNx{GNee4?ofO)U@cY7wJ~7)wE$ch>P~yS9i<-duBa8rvdh3k{tG)M| zXpgO4wEt$$eg3D#|N+6~1w*Be|g%k9V8!}nRu zxrj#!h@vLeB4_Vfo3UdLs?}Y5S;$-VP#ffI|B1619EOc5f2zz`6_2j^U}4V@LVuK9 z4u4KDJm8ncCE&~AU>jtT5{o_}{QC|5`;eNk+L*)hr;$bI^h*==;2!qJNw{tgDy@7s zdS79Lh4hT?pk>d}6WmG4p`3{!@4^(}EAJ#xCror+8p4dz*b~Ij0_)n$^jsQCta%Uf zXHsbYS~pS)wBj@YZggp1*S}EN+xB4_}2%43s*R@0YBJk$RxeV}@ai%iqFxGxznra8Qp| ztwuI-5$0X;`gOEpadBULRs}0}Qk%kFEI!*OdG}z?hIH_X1d<^$3F=54DGg8n2QmR@ z#abvpIK$RsV$c#mUy1yI;y=@tAkplS!tIZ&(7Cmz&FGG}&u!y%JCIgP{SpKRJD6sM zj&c+&N)^IE#}eZsM@@p(d0EH!S;Z5Av}8^odQPFogIF+8EK6~)3bvRrV@ryeT5Wg+ z7-dz8jpq)5%p_Hr>h=I}V~M z%vt~;i@hpKH3--}?`EB5(W)N&Y{OL&rFg{I?eU}`#flCPprMHgP$YocaWB|_!tAx2^MvmhUqdV%x1w5D=>3dZ9>ZphWT3y5MGTt zM9)7V6Q5R@<`Rr8`s5SO&01p)a&J%%PMPV)!Fd9~Azu4$vS1gMl@79AOGNXYr?Qcw zpOkpwQyHCnvI0Ab*?*6CPyHomP4=?Ml8mG_BDZEoL!nC5=Pwu{S;!8e9@`Z2{(A+E- zi;6P~Tb2oev(;%uG@=s@XF}o76V@wn4xhBgGoVPqIq}q!JnNb-w}t&Dw4N8xK5un$=WG0ymeqFItJ^3$Mt#TV|g2x!$=fe~cyD zR7>tls82}9Ywiptjr_ikE)>Q~+ugXFtf{;Pay}Ex?to!MisQdHnno61nB9`9??`*& zqWGu7cTz4Kx#Pl0qgd`hM2K!1TcD!}%sBIkg}Gd3DOhj;a~+{gcMhBNh+?^ws0&NajDPO3t^^p$9l3)qXWkGb@6x ziUOkicd~eWD@lHpT+L*K(8D$;05TR5JyGuI;&IqTqdP4|4H2=K?j2EG@>JcV?dw$m zh&_^3R4EC3abSNnY>5$%3hrw7NpVic>3{(P? zaFvT7odCcIw{FFO5z_J%i^#7fVQ7co^16(+;k=3{6a!b!k%+oE3NCzv9N%ulR{Klu zQQ^_KA{E9<1NQNZ!oA+>H+ZesmeE4r4*0FBQ~-pbf`;%E~rUwMq*Gc&(#hHyRPjRs?KBWKWbl^YChX8#fiVJlzOYa8WRuHn+vTOHv*R?H<{TVs#pk!j*UJhJw(?fxNLsOKELl zssU13$gpMf?ZGB=PyMIE#HM?|oE27a@$B;*X7pOm?*{1Zf#HgB&HoID6M=8nmAm{< zxgOwJt*!$Tp7#3HEUQN@qnX0U?ZZ99v^1F`*kvgElz#F1EbuNR{Hk#7yG^j-GbDqR z0j1p!t9tOj#1C45!W<^?O&5LoJYbY;?QDm+E3LAwsA54b^&!H1R&p%L{pS)e*?CvLUU8n@Q zWY1#@ddzmFy(Nh>0c_0QLoVHdm~hGnRWOQjIR})!OeWx^m5`Mn<8Y1|=pI)8m|OOt zg-uzQ@fVv^N7Eru+A&r;Oh*Rv*iG!^C>GpUSVAULKGgyzTlwt8BT^NIp+D_wHdZd` z&h)Pl3jj`C_ZSVBgj4(S;e&0!E!NI5EM@fQ4730s~K zB#N8xf`D6;@>k-K8v((lzz6`9vlA`3FKYT39RKkWOZx~hxZPsY1F3y+l?{^Uy9?zf zPgk?$^dbBQ=6$=+N$ADj%F^hBF7_c2fGr4LmSkAwYQv4 zm7L`6CABnm0Jn%9_=WY-E_PJl-MtQ#rEtI2Vm_gPAvoql>`Wl`gv3Mc;gdX+yG#WK zLE`|bo7mvHT?QjQe|uzen|pDv+TO+2#o=e8N$q8{Clmp(i{gUP-4J>$1xSkmYGV6X6pI zSmqnC*nQlF4Gj|Fe>bLiLv;)qzPKU%@ziBT+6&>hv7_Cq+iPs&KwK0b0VTm+u;EC9 z={F)=?YD$l2Gp)BxO8ZMzy{~imZ}PfqAt`J@u_yd0>(A~Dy+T}zfsZ~m2zgOQloP? zhi@0Oq4zd?c{Awu@y{lyRY*1ntl7> zJJFQ;SAPM2z5pVW&KobNNTL>qgU3eTl%rsTsH~ko5}8dn#}glHoE94Gz<`~p{MBcN zA#s)Phm?0Ye1WT2<#zuMKK--29||*xceyA4*XeSoDr6%A(TM_3tSa4RzESPgT-XW_F2|Curwl}tw5-RTfoHE@D~ zdB~9;btd_HQ5q6(b;O3lKxpc*y2mWQ5uf*G&LrnP4?!-TmGE#u5*PR#HqM^SH~OR) zl{C)gyL5@`^y&^Gn%axmIYupqZyJ9gxh1Z#7BGgMMJ1sRs}s z53hn~0)QX@P$Ix3I?mOAdCBj7pcbqZduu?287%&Ag2N6lw@3ELNd!jL5iWol1kLqX zgY|q4I|VJ51=YHLFCF-EX7&$2PFgs-4#&e5_y5Q?ZMcbb0ubUNF$KXfDo|@;&c&?U9 zxchH0fVb`~flscOUvhotd5776O&4~1f8^f(guADH|2bI4u|w%i=McBJ?7k%dTu|}e zt#toa4B)M7npuutKLsi3xfeW9eZNjm==omgOoLZf#(%)wvcvxlcaMCFTKaVb5>q%bm@$A^4f217yX~uv502e~t3Pgh_3au8I1Tp7i1Y_=E6e01IZ1LX?*+s3 z&(?o>diH&PjHI5&1P-QuA*BK#05mP_X9(NX2452ahL-nr+aryWzqv4QCpmKklJ)kj`+AHX2MVlfU3$;xN_L|pDggh(DVnaR6DX(QCc$mUm zj2C=SXTuVMGeIjkNCv181p)jy3Kt2ia0QZQEFO-a+DtULHXFtT~+DLs?W9j|#!L@aU%C3^4ANgbmZ@25O8 z1I#A35&+^WY4TIPEPz;@gwurpxv%r11;V^n^0k=?;QqQ? zMdh25VesVjtJPI(Lf+-b{F=x=Klaa9e}Wf6*1{K0zuOfDcC|&AKb|M#u_w4{dG#Coo;-ITc>&oWd77QIwX|E$XAr49clx zz@i~IFWpBkV`(Mr{drtUG+Xa=B%1`icOyyH?)h+G>5#}lq(}(2Ogb(J=mz);bPqNJ z;6eoUt*FG7@7)(m$Dmxf62LdhgU1z+=hn<*kG@(5#M#sMlead#dE7$HV^jFzQX-w9jwq{yYvv|3fn+|Qx($W5GKgQc7U!OV9E-BA-&Zv40& zqS4ypsyIrlpt-#53zjjO4z;=j4QHuUXW_3gOY<7`;n9qmDEd+)y{!Tt+v&#w3nJqim6(kb|5{-LTwG3MnFlr@6`7 zl_s`w^s$RGfGW#rWC(D`x5e(>m+4z))^fObAf{i&&1yvvVSbt)SyG}nfy*%SeF+gZ zfX+NU%N|g&N+D;#78`4J3`{|^Uv@pK8TMQpi=u#V<=vwtMsc`Mae*WZKkMx}WlT+) zR3L+D*wgk?9*c#&pyK#=q-DAJ{B#4_U%$%KOH}JQn(ypDi|uYiJnz0|vNMxggsZZ; zT}7sv3Gm8=xKqVVLt_l2p&7KbGC$q%1ARI#fqd&&ioYdK;n0im&jc`PkqmYH6! zV!E=^OX069rYg;POOEIOCR}e_xN6VK>S1&>luQ2;0cbeqR>GD0)avikcVL3c0dU@W*^@fQ*ORJqYCvL6I}DA?jM;jRs51%5G)HQl+T{)Xd6HEfQV>y1LH!{ zF2Q`8tTYy>FZtkX)h=1BO5{LW?yCF|L7p;>!VTM0)al!5LcN6@1&1m;q{QafuX;?} zBy)P=Qq|SuBzYEydIRHL%rSSq;<3`z8bE^=5CU$SEKz~j2qHZF(If960MXOvdeouZo^J=gFlhuzxMof)NOG4iW zNv+6VKg5rv^_b16fTwWVQal7};@4zcc2ot*>b3%YA17pQat(UhEo3Cw3?-X(O3EY6vMm0f;v<&v&Cl>HwYg?%03FlhtTBx zS2M1nl%y-0URd!KqE7$+cTx-^3MuVFedcH^?l9QACkk*j+LV^eDJP^UvD7o zYlfE6MZZ5mtg!aICa1P0QL`Pm=;y`9`}IW59!r*&YgKtBtWLQX3>&J zA~dpqei6HP6|XBx@em8|j37TrgZ-7hsKuVVbfO_`(ZniDj-?!cv>4d-*Rm&~Awt^r zVRHAlnK1zK3(cZAW2u6;9;dMCEFn6-2>lrb!V)v!uP2Z@clWTJ?44{hM>ntU%D~}e zahWY{b{)Y;;r|>17!0Wz3~e1e);}0FH5k4+7_m1P3Ae1Dqdw51;#!)cq@>g(%jr6n zu^LhW3Z?W!&4e_m6FjC#?2>~lVluj_$!1kt+;kUszw4f*<_o}32+f8YPSLPR!CYC= z6?`LUp0RfcJ3O#oJPfcW;yx;{P+A+cReP?NU(@!G3G{ow?Qc-^y=Xvqhrl3LE?e)RSxP-!--d)JEQ4!>3e zu#`&aKZnuEsrEE+l-g};W)KN{l*(*0wQ_#B)>6yPVhtd~z`@*7Wk3KPosue_V@Lzi z+M|q9%DZzIY5-c%oSyQikVvzFFWbV&V9ghj=I#3Y3|&1pQMOq7Ph zx2EL?G0YigMIcd@f1(R2Nl%ZpTO4kfAGInfPcM+93*LmZt;N)#td&jv8~pbh zk^P)bZ-7940<#9{y8f+kz7o8V3hxWZWIM<@z8~Su)Wf- zqkX$OzDjR?@mLSA-)Q9wOv%FixR>*Yp4WS`f~T~z9EO?`Z_*cf%q^BnM?YF2eo4ze zU@9~%#ey0gI5bIrLbQm5(>8a^L135KBiZoZOcL`X4*vBph z;rV=<#KOZBo`0h1tQ)r|JnsKn3_!kmLZOWr1DH^no={$!Q29J@05M76om7>cRC8gI z1E_i$lN;q8{hCiMc7!--pK|(F3}9f=VA^Sac*NPJ+7K~C=nVL_9_)^Ue zI(t0_pmo>I6+E*D=LV~$YzL<7rl$_BP1%2*I)s=e^G-WRPdjQ(JDE>AyG*+TPP@iU zyQNRN7f*XsPkXjaA0C)KGCl3JHtqd++6Upf`#qQPyTDi4Rpi1W|LTGOUOH(9DMfY_ zd5#FD&IC7LB5|njTC-yf1tAn@gjYcc42VX|9)HK86sGZv>=rlO66fU>(@-ElS5K^- zO=_DxIWU{-m7O&;i(Z;NeTs1gG4~Pu-@*p}2lwUwF>D~WDgD2O4QyI#|7+M_;r|pi z_)qT3f@k2r4`H~~nq{%6vxq5m+*<0Rb1Ql$#|!nSv9>`-52ACS)?*^y6_M0 z->|_`&5UC)&eMY;wz(uq3Xf}WMFd$S-aHaz?mnCTPuPHzhaVJpAzC%S3$>0B%lap5 zAnMX{B%aHtHa)G&5K1Lz{2jtD6DtxkF$8cH1a#f{A>uy+|kJ#S2UhX;-Qd?D$eFGyWwRiRga|olhs&Q~%L9t3MxnR4# zWBuOx1-Y>3w8n1aPwDfG#N#*1du48honzEPsa0|>ZN};zxgJxdSCE&71>~qv@7fnr zIz~GJl5ydr-)T4B-&=d`JEV|b1SPg>P;qeP5QeR{Y$E`SpvJZpceVf`h<>DT zeM=cQJ;i)@r3k9_paefD?Txt>pM;KE$u3NZSX>5LC&-qfMWO*rbo|gUs3FcSpdYeH zbc;~_GAA?O079BNEtx|YG0vKRce`>zDOt()>jG5GB98RcWMA#;YpPR`YCVnLTSw3` zmZMuFz8`ak=q{|Hn@4uepTqb_J$*^^IrRQ6!$73u`#eGrN?e6TfBU{|mAZTLQi_7g z82*@?0tl(!u-90pbm$%+QD2Srux)QeBtM}5j1G)txzQMEme=gv?o>|hcg&^NFMeLQ zB&>1j^Wx!OiUN$iH)P}eD&aprIL^`Dl2Win;E%VnK3*BwTg%y^a)f6F%P)HuTHjg{ zQ!Ye$TYh`}lXaL#`>e>1GB9Z%Y}`kBf<8S_>53`7AR)O2T_rsH)uytO?IObt8{ID@ zvV^utgQftuzJ^l%z5_+JNs`esED0SlR(8wjjc9Y^{&!1|^so^py)vwTTaq!zV`P#8 zN+k7`WO*~7e28dnjxz{gwi?b0T`J_hW;KXssv!uEN@7YW8(t+#fA8g(i(B_KXr6jN5<}*<1m;6cmmgXs|(PfI#3Yl5u zIwJTJa0ok~MjPQ^O-pSXl@MV6j?fLT#!2_nMRAzN-!Y#q?e?5A>U03nK=~zTbia~1 z8t{_q&(Pu-HuzO=FmGmLJ7c6VZM;%Op)+R?O}h*dD3+FvXbGFjs|Bn*7B(3g@hrjen*5x;e!&^;36 zvif=GcgmRkc|Ek8h9utXn$s-n6^KBUhaRGv^_ft%lESl703dDqV`Qdt+rk^AVbx_O zl&e);cg~VtNcsW+PP32QV!Y$h?3_`us;A)MUTmAN6%zXcIq_R{*Ug2r85}Q2aRmq8 zh2tuEZ`H)4$4!{u;au)~wSV_RAPN(1{vLd6-x0!IN^Xd8)eH*>>!-TfF zTtYZ(1};dk9JLO?L6Vt-qTCSp3xX}2u&W}yG^%SEKG)nTrT z=^>cl0SksTxbghkaEvaF^74jXf=qwv`C zyG2jGlG-uC``RkzimWI<3#_~`bsC`u`@N#sosB>y63b96y}VIlV^}FzIkQ<|>hxne zSWroy#nEg2?vHp>^T4{v_9{ilw{QnaHOV8xfka7hd`4SK*YfyLqscPRbl9Cs?Oi%S zmh(Y6VGg}j|9;f}`Jxz`zVs7@XPzfs5hwlf?IK!R)(v-hK9k;eFfxDVvlPfCA*27m zn&EtKzVS0Z>G6R1)tR4*Qsdz^j&>}z=jQvOr9PUMP||MQ{oaRY?n6!G?c}FQog#Rc zcinsQG!qs2WO)BqHw&4vnil07?{)t(>1`8wW`u|o>w2`u6HyqZYg-~x|B;B5Wys~M z+MVDYzKoENSBASr=nRuM;Vr3riv}AB9t2xC)yDXi@tX+JOwNJRdXlZb@U~we-y(1f z2f}p@tQ=%!rI&PK^IG!{z)Zo87G2PUp&wY)jh+=dn!UB@>L=?Z*7~t260IUom}vxGdTR1& zc=IzqyXTcG+xJR|?xq5*h$!4R+ioa&gG%KOw#NN>({x~7D`oCcwL-0V@-k#BF@Hy6 zXY&+(A1}J}R8R68yT6VQ@cu0(zw=7CUX#%gJ|ZpKDs)SZ0CX#+m>0frXW(Z1tF8r# zk{rJJIe*NID;PQ@M56NghWv;R32*hVpn4wA0s{yKZ@OW)0H|A`fv^?Gg_GaZ*48lx zbpRmjJT;yMt%w1Uph;f$VSs9p?V_2<@HSdAX)5=B+Ul`xip0V71>9p*1HkDFCin)| zt6aNU(pU>vEGU2lMa#${-ul{Ux1p4XXe%~+jAgK?h{4k=(K7yWU}$=BJfHdzKl?=9lp_L1Gk1XOkKS+yiwy&bU()<>+XKF@>JE2s zyE~?f0w690rO_9efSh{gm zjZt}hvT{3VIz+xGN-#)|Qs-RCK}O4%X(25Mhlc0@P^n}#GTjD+rIR%|`Ewo)+4;+W zan)?Fb>lwSWPUt@3s1}l0xgJEdsF$6Gr5yNL1GYOB@gXQn;i@jo?9~vylO7Hz2{UKFB9>N)b&woHx{#CmdV=e$WAit zDJ}}$I#8Jq@*8Wn(_#YSW2Yn>rmx7{wPNs)@}UsuC5vN6%#d)+*!x8#i6sUZ!@er5 z#?CQ^Y8lSO(@KYCBU2om)3qI5TVXoVz@!^TFT=DN*OZs6O21B@5^p9|L=l;b0B(*( zPDS>CC2SAf+zYc3g#=8gRv2cILW7V&(eb8PyNXb$l_5@FYp^ZTVJL_NX<$bZV9qd$}@2o)T1?rGkcZ;%b@w1jNhmYedtt|HK-a>p{ibuh(?cGb3Gmm7D`+` z^1>~lJRDhGh;uME^EB7X@I#)rHQlex@s5M%Sq4N?p}nZ8w0ji+&&?49C(ndB^)+AB zT5=GpRt{#ByDbAA2m$?Aozn*$Tw>t)RJ0-?NZuTzH`T!^e1>DI{}ehq@mw$4K19)u zIXQy8NvRCnMn_O@`XEe5ajZ*dMK&j|j;0IWH^6r%s+D-Pig~Z~WZU=&ayPb~ZL6y> zrritXs&?jB1xSO4({uAOp zd2Z7KJgE>hWYf&v%=McPsq@GPNwy4FR7U7w%NCV>t0C>`z){@`#>YVHjs?&TBqpJg zLXNT0ET|o3nWH|R9FOgGv^i)fqz_*2aK-+X2IVOF4*H;s8-{f5B2-ElB7#;QnlMmC>u|J=O4UFf=EkOpJfA>5PExQ@WfL;E3zbg_!vEI<=y3nLJ|Q^)Ch zoOlV$HuEyuzY#lp{*=klyFaGQPYQ*vee#)4xH)>*LP!r{^N1OzAR2E z0gDSYZKOEm&KMfVq;mc!Z~Jh}AWNo2+`+~E zBG^L^F+oFW5;6YOr^!iRxl|}u6#7QX&C(n@i4B{vcHq1XS?ECz$7&A`22fT^F+2e` zIZ>v_rh7xLh_m82bC_XEuVd4;M3FaUjP8}02~PbycecL|AqD3ddnmo6&lVGur4J5g z7Kq_XAjd!v^8mqMEiH34Iq2P6#$)_Va)VJ8{BAv#nJrmf{$HT3t zMc-RrA+}#1p$bs$WY|S^r-8d;j_O>@Oo&JWzdyAPzLd;fFwC;l562^2_CEoKb$E@* zXQayHzcVJ3mvSDO0!F#qj}_X5E9i(N09k>!@}N&&S>r2(`|Z%U>SmXDbiezLsU$cj zJ_#OAe5|{Kmd`4)+6830vk33N1DYUP6g1=sk9w1ur>KH|;td5%H($3${BQ2>JlM|K z7IzFx@!DwuVfMoEqldg+~9-x9jq42W=1k!za8(;#XGL0I=SsKc;X0pUi<92W-8 zgmVCRk8Lo{3%Z$BT@8ttqWtbrb{&!d`VY!-c6T zBkP8C(J@*$a0~!c4lX1!!x)61vTF!~(iJ4Zw4dV>iuJ91SCHirVLa5C> zLGAdeZW#EG!WCIC-i)8M|Ql+%ymvUR91VNsvjV1DpJw;FT+bu%(>Su%{nqK>7UV`b>|Qyjt`}hVl!N zZKeYkkVZDGvsS#WyEjp6$78VABufA+Ub$~S;Zw(r)xZFirZ-X074^{kFMdJR0$Tmb z;Bf*H5|z32E|@thAu#qZfT}M^e5z6a7>=>Sm)!qE$$GlIp{Q~`&wNM67ENgd)doIo zjaS+51{03Hw)AfaPP1^2SwGNBNjxt5M%nK8Kdp^Fjj}rt$#C*1WKK&*p124C0>YsB zTN+_`VhK7Z%z(M7|1;cv<=^~9`orDK33S&)t|UdD8+i3UD7*7;sN=rx|KHii*uFFN z5@TONW8XDn-y6GR8N2K|Z5sO$8nTndR*15d6dFrel8{QW7NS&Cq}4s0=Xu@Necsn~ zAHVB&9Q|E?()a!PJRjvJ;cMbD`jqFnx=9#PI)VXl!o#s`a6tl$hrz{~`9<4jQ9if@ ze+&x;6bG7yRft-*#lCX4BD46HEW!bc7T{^fj^`S>gewp^@dc)5;%X z$SSSg!DVEtI79(70_Q`oxCAIKrR}NKRyb8X|8kTQI7I|8v^QaaeX8q{!j1iUa!4;a ze7;KD9FP1|v6t|`d9*vhI}?mjK|mqsQve!61~8s#@NoYT@8=&!qu2KO**%fwN}wMe z*?;lJx59YV8mBwTNH_9#X5Pbx;Q#X!3KsrW|Dvp74V1F~3rL?^LA4@>&wDh@_pBM_ zW-x52900KbMNh{{f%_D1IBE+byQH$^4qAM+HP!v|AKRC|5XOHE8`KyEva!o)L~g+V zD3rxi15c0`)C8>2_S>EYeR)#G#>@_`<#^%|#R}&Zn}3E4{>%17FNL@TG2@0EN`2=- zqvqvvX@X3!KP+ z02%Tan|NLXd+KR)qwOsk)pwxI>WcAYmz{rXU##Ofj6`6e`;crEhUZtJ7@VDk&G@E9 z#r8`iu#|x?)Oamtnc^D(h5|4YyXsOPiKZ3=dH(12CG2!n6A1#tu{ocN1gPJkY@%Sm z{beeG3lKM@(;?=vKotu?8eb0}4$v9<{Nkob7>;@>2{k!D_>b+2ifjs(y@m*q2W<;M z@&g$pB)=^fkj!<=vi@)mX_yuZ%<^@IS%^qn}0r zBAa5-KYkwM4KBoI^rTrK)Y|udngZ?vY zFui}%3~*MlF%eExu{EoDU6X8fPF{L4~)umJO^!fA$h3l_72IWa~4kcPVjNSVAQc{7cbQPRU z2uXa!MmE;;NOt$rU_uxR@7;x-=bUoQszBgL*75p!u<}PQ(Lc**?z!1EN!sn066;g>=jFh`EEhUkRw5!x7BiJ~H= z-?D8p6P+PIrnKoNxc-I2y(748fG92)eiY*v?)j`**jSvzNZJhBPXxB$djx&O4H0~)MXV~b}}UB{aR3DOY)(VrxkC-?Kmd7tYghb z5CFfC_NwNw)6bt)c8`)SWk(!K$X61GZ0jS^6*+*-cCO!s(){~dY0g$8*09q7M+OL> zoWyjs>7=B7F!Otjuf52jRJ5sP9CzN@DvEFi0)%cQADW??vdX;WbSI8W+H7D;)*-B+ z^zjS3(e}1tEB5h&Vv+ezMJ#9gI05pwOdka%h3;E9tM$xoCyxnX$l5oRIoybSCVk>B zgb|2s$z?(qzNW_~?>gSb7&eEb2Dz5vU|bAJy{+4@o14!Io{?ua^W>cEOP1-Rn}E@E%_NDh6AhKeM0>09!Avt=9Mi-7cV zjI3(6c0HQ-Jxi%o?-OzwWW%aF_#;h9*VDn0LldGR)Co$Y&%WA-lci*U1pY)~CKA`= z@9MXV^e`^skMx-S0MI9`Uo?!Lts3CYgzCv;Opv`lMmJ`9H7_?{~u-6}Zn1wwF$nsU&0mM7}e_{j7PwvQsGwNO8bUF!h>TuL&@Jy)a#}1uYQrBl;t^IjEE4=i3t~Iyhx;6~XcXmbHcA#mdw}>(|KvRGiUToX-e9yr2EvDdjAo!x821D2qgU>;)H0mCJ6Ttba)y^&^~~}&(`C23|C)t_Rq5k0?BllY z<6%>K!zn75CRBS#a zUEa9dFHo!x19$?;k3_YyQbbe3`!Megu?FjV=k=pA+PDHUa6sKcCUrsJ-oeuy`$xX= z@Bs)YG)31Ax*;QsxLze?hi0Y24>#&41{$cZ@CXH{ByPdwqzz+FqLCOeKeJXMx1p=e zk<>d9sZ2SP-Y1GfAH6OlfiHt+8D8#7GH+2dBhpPxuO!as4Rd9D*{CFLC7R+Dfpyrv zP4Rf^WqQ&exr1j(v6v;03YOHAlKCpm6f2a}A%_7KsPP;`$WN0hwDKVIxKI+mz`YA) zu@OM#c12RXV8{ruvZ{oGQdBR~ce3MhaGz0%DKR>FC@y6vzF_E7?a=9tp)=71L2%hA z3pAHBZ_r4Q_GnSmph@!KL(gHATHb&LI;lXqa`8Jq%S?Y#_ML4=_5Rk>U~+v=Vn&K7 z^@yEmN;NaVJl82Mism1?n+KK@z}3JBywg-uiR7|;^I(ZKRjp-8?AB0VXu#Uq;P)->uWR$I5t z5yYJl;Zw}!S{BP@;aMZ>2N_DGSKe7JW-pgK!Qr)_Vy#) zziw}3LHD9EuG>+2;9@O?W2UEy%}uND&fN#z!R)Ag$y5@#rFwj&e?*5Dt~8QHgVttS zPIVLlJ|gL+V%^-6g0S4q}1>|!@q5viTVCEC{4NC>;ll@u^?3VJHI61B6Zo4J<(j_Vn3qRXd zKT=msQb!-dgfPxstrgEu&fsTHz4LK{*@{%_xqufDwMj^}$PyXmu2aLsvq(n&|AsJ_ z+ZS)Kq2Y+bGs8uEXNq>Cc=JWXqGc`{e6GlUNiEGRLsGl;m7jGcXlAf9Pw7F5aWk@4 zf^6!Uz#Sn`YYWgAZQUv{O+Lkss)t21P+8IUwP@OEjl7&&0Nz$8s_P(IeT5z#ihxS! z(k{Qsw$sVHqQx*xqD@|{?=jlDtimsBSN`BjKyPxuvlKc)M3!K_1<{^X+t^4pWui=i z=z;gsX5XLo@ZUQXbesFG76%sc&=L(3&G2T|V^*_|X=E5~!B75jAbOgcw_`ZTW~jXZ zPLknCRrE2?DajNbcFs}iN7peRHBsYnkZJ(~o~^}%w1Y+!Y#fuf9J1)iXH%Vy9)H+J z=}8JG9(ZlfUV0_K^|rEkMgav#kkL-kpt6{ZX|tKOYg_YrfA&LBXc_NP`djOGR% z<{tRYJ&c(fN_AB<8<@+U^BJXL>Zt~8yz5PKp|9u05%Uu~^OF+uQ>yb%jpnBv=AZe_ zKaZJzkvcz9IRCP4e)iV=NES7BNq`1OFRq95(}?Y7v31TyNX<038`E4 zb+=P`_EtjT#{u+FQ`Fl+cbn1F_m3Cspr~-u^uz1!_E6O3ArAu1Bgu5}i|=Cc-rU#n z!o8fu&zC&Dhj`d2B@Xl~{$5@Dv$MGG`>G7F^bWfO>Aeh9TeANj`zo_ax)r9a)ekQ4 zD+kUEx7G|@#2aJ@nzhxAT#~kHbRB7{dsNI!@ceha3dsBKGo)Kx|1V$V^#AFr_!Zub z|MG7BQRmGkqUR*czgqmuS5d1srkAN*_?NFz%i=z0R=QDP*I7^3c~$e|?q3%ctT$uKr_&^nF)wZu+mUa_9y>Fz~j1AIrX! zQ}mJPt8{j+gs&-iKOf6ezLuT0^EbhBC5k0t6LwPZ;i+H$m?4F#7z+T?>L#JydvU3} z$w0Ve62D)4Raz)f)Fsu0zbch?B_!Z=ru6I1QGUVNzX=}e&Qanj+K`z2*H;OQ1%OPk zI=# zq1l=)W#JEH{B1pMcnzVT?3!;Y&+cwKk(dEO?MEnF_zxnkKw}*H!-w_uYrW`d`GZMaoh2i&;MOz?d2|A>Jnp4QnsyhRt(Vg49ak96u|uzk_=yAQi1 zN;}H#6x{0WLz{g4Krn8s7$TG|_xXfXXcj5XDZ5E2FN)Us`4J&3W)TbAkpofS5OaoP zHYpb@s16I)&(z@y={Tk`L_$uSQV9S0l>F*z<0FMvc>wXvc8|8bmtQmF7XEa0D3+){v7&JB^RJ!5!mU~LH+WS{Qh$Rf zhj&*v#}okLJAOEMpiSF(QyBvm&;(p z9oRY&$L6#y%8l55Y3i5(Zk%gQCE9cT-p53u1!M<#R8^KY6HwFgT03KOO^&Im~0Gz>0 z=MgNkzo8IW#R{xfn|SrV;9E1*RMHs|H4q?25B6`GfHd5UqtKiXT1dCE#8t4`6sN8ArM%sYACP1L%qzAlP?M>+^7Xq`o)^U9 z`0GUa%$_U|lU#tt`nq4$BtFk~b=)T6Ofeb44eTL0Sd0Kwsg`UejM zpDV@y@pEQpSFgHgeXXfDHBEGcn40`rH_6Et!m)Q*2S1Mp+vLj713)v{Y_wJ%bx735f7XNyc?2uzPM=(kR9qPXrio9H_?^F~d)d(jZ zBt`a()t5a}+RTyy{+M33rrhFrclIC&cs88KMi+nklW}m3GSU8{kU(3Xyaln(32!q@W{C24g%84xylY!+ zPDuxrn*9Cm6<^!O_z(hpYP^Ndq=azP8u2@a7-KR`?70nZcUawU&6cK}8NcqtjUXzl zmFi26VzVT$4v0_fPaeyDyBE@$YzG0;g?8R`Wj?5~ah%l>8^!{W@BvX4sBBK~)|I8l zpWLlgX&biOw@eOY2ukri_|5_6hhy1?=OiAd@QZZBDRdH>9^g0n%E#E4ktz4qYFK}lbdY}TT~bGAXGfL*c(ApNE+s)Dnx=|Vai zFE^K==%%@7PI8r(Bc_BcN~3QPO`&416uaDhCY;xqU34?`wf*z2{wzDE zBqa%&Sxel0*3IftGymEPWAN-p@oVOKlQOgo>rPs~<#1bfrgoaMLfUaj^sRc;i-`o) zCp5n-O{vivSzfoBkgX0zf{I4lLZXw<2t(#4hzZkjE!iKg(V7S)`yyQJ2tPI_pDn=-^sGI-NK(Pt1-@QVe;u+_ywt#!ag(pg4{4 zl^YK5rm#_#{L)l)kEbyXK%`oVo^&SUO#}*xD?GX#Ew=FFgx#YP)6S`g<)C?)N=tlM zESe+J4-M%c;!l>t(1s2HtqrB`Bl8SMMEcIp(z#*B`QQT%C!EzWMmh%Qm*` zmG@RDbMp|+VwSJJQzS$N+J!>L^>4KD3>hz9=iz&>H|roSBY3Gx^XLa-kP29z`AIA} zoIi?PnaSztBnG0{#&VbSnt3wb^C+bu53j&LG~eTjb0D-MfMXC|z8DDr2PgF8Y?1Hx z&A3sS4%1s_Wl#X(cf%jtshx)cv894fV&P*_wa@VehPPCjXx21Oz+^&fMgr~9eu}Vl z&TAV1E~)HFQC^~O>VwhI#<6`q1{(IHrWE;t0T<$%)8+=CJPw7Q@Y(k9@#v2zjTOT| zlx9@D&?O#mP$fkpFdanr;c@8{1L?S6u1@1Wg$~2ttnI%-nO_ynXUTzVK3V!&7@ zMAf`WuU3+dlz4D%Q4iY~+{N2V!cC_f!h3C%^_{iP8ahAvrh2j+QMC%1)o*`l#m8hMF4&nt)1*`GAV~(>Ta}I9Sz^!d7(# z2~qL)Ce`?*e=pQ*Oor^gmNb^c>E8;dnqZ-k6Vz2QtkUgcQuGwQ7=HF82^csd@(4%@ z$|T&w#R+@zOCmZED*Avkran{cR(gOP$d1OXy-j~RsBkUS0cE4D0y7$2Q~K@Yjhu87 zXa$rtw0)lD45Hnw2ci!0MDXwhPsEsW8LAYtlc-ZCe8Qo&l2P8D5n}P@5sA!VPc9_Z zo0X(Iz@K|L70McZMzYoV1_kBuSz3n24dJBRQRDkbm2#aY4oNzv_8No?gOJ)B==Z#} zj^t(98&X3mKHZ7orj%18m88D;a2hcN@{bQ3&pixU|Q0xeQR@V2Ql6rW0%%UDnLvTCVB-)wT%!_n&7{4c+=$#!0upDp+h}$Y#K_D%?>#CUY z7qr%YN6tbf%y6_imXT8}e%acO)YIU?x=nCSfeO>)C*Fd;UM4=~3B25b0Y>XSNXqUN z)DEqK9#O)9cR}Qm5)z+z`&rzo8HnExOpBn{-gzl|di2zCfB171>$!|L_H9|+$kb5V zLh*+e4^pvN-pWz2?w1ZYWGv;0w_>abViI)?H`Bp>CFCa+@v_?hCj)^_l#5R z#C3C%oR^?S8)nI|OUL@Qj#TmEE*7&mPAQ?P$_i8b%F5IZn7}#n)Xb8gu)34O$3e#f zM(=GSM=-V&K<;oWMpxBxzM;%I&U*(6RLuY!+W-OvyomvW8_upgGdTV|eEGFYyh+hU zmYE4nGqk!!$R?Q90xe6cL{6G<_BHcBpd2Tf;C(f(zP1Y7#;_HK&Ad)p4d+}aY?14r zw#kM`!j(9Q$W#o#ftn{kJJ~Ah zgU0qKe|?gRq~Fd1`g@XU;8*TgMTUx0BO6kKZQkyY{dR`&+V@;tH*|48LVi!Kvw zI1O5HZHJZ~)Ngu^T|EiMlhFZU3C1la9NuaOQ&8S*fG`~@9M1fsbpDaX)AAmUa?QJ3 zmwFK~tNV`S48yvV@Au@5Ghy4e1bo3wf95}f?wV;UGXQr*RFZ=Ho+^XOuZ(`hwRgCb z{Vu<@b|(D~|6SH?KyyHE`d%+ULn0N$r2xl+WndKbg7;_R*#?apQDXCj_cB@HV4G1T z>CpU)9t5d}6S(vAy3Kv98&=a|(itc30xb9_xYXSaB@3)E2fIx>#uzu(HF&i z;=$zyC)KpE@?MAO$hh@#knK7)E-!$sjW;mc-y;w!t%D6Uue+@Tl(u(q+5}NW!0`Pg z+Yy~(p$44l7!X&?q=_gq?v1lFa{V_=ByRcL& zOc@IkG6CnVP4Emv2^}BdQbeM1r26gwvty9$p+}+1WBl`zqfBOYX;N`N`AMIhf?P8w zD0>qY!Kdzhxal4cW`W)I{}ZZn8#!QQRW&aJcCmF+9ZrHfA=a+fn z3Q8WLHhb{_lh?~Zl@>)^Jn~cs^7J_nJ6DvKWRUdX1-ycACz+sD<1Jt_!DfkN`wTuU zKUoywIpzv_d~QNuCU92B{BBTh9<+5Ftkms8*-Y25I|xu7J!y=%a~7p}`o$jWX=t9N zpq93C^Dw6BOqt`u=*dYJyzi5WS9}8yWAcQi707{~WUE45+;0Y3vmxiNf%kazdV_fQ z*#X6gNni;DO@vKfJ|ekAQi_{HG9_mwY8>7FLiC7Q#{}g@KdEq zJ%Jy^XRqX7`58|our$9(m`lqf>W>1|`|w^!K`ED!x)QM8ox|RWqEABA0a$tG@>Uyg z+Uvrv3@<1Z;ynTLCL_G55Z#G(5gQCZM)ACUJ-voFDb~*IiBxx1*KGles1U2)*aA9c z+-fBr8P)bMwl-l+?wFb35$#} z?o7+DpB`~Jn2Ynn5zVt88*UaLBmIc$2lhqarHYMk&svV|x6rSnob**qNKb}3)|Ue( zOf5kX0IgzVDaXc+vZ1%vQ?ow2`riD(?bwDftyustns@-vJF0Va`x3di6Trp=Mv^*M z)CmYs-l1Ccy;>lo386ig_aC`j&T(+{>#d)lp`#p|cX-NQ~23NWo>Dbe* zU|hmi>;113?pgZ@2|f|zB4o$;%8twZ9Z@^z0miye1VjRlJA{vP^*H8!3?e`|b#MZB z6@m>~+$~c7AcV(7aRR=_z#w4=9}RL~2|Td%4TjzG_t4{~-n8M^hPD!TTOqimJ>1sb z9{w$IlB;c_ZwYr@I{P8a8iM>rjx-G1 zjn5{MM@VTgf}0KAUNv6-nc!*L$KqA6cjN#Tc1Nk;2|9&_L$2RB$U1Z&nns2IY4htJ7Kg6pNZl=ltD-vH$E~a%RI3LlPhvhjD84UPBr*Kr zQZN84al2-ycqFs0h@xF1OuwcH>q!hFPycLY25Jg9Xj?WEZEaS82^TUPIu?%rBV`ze<5=IXtVyJ^Tz z$CI+#?tRihu|KJ~>sUJ*HV_e=!77YC+8r?@oURi&B6Y3%U%ra^+wQ0*M^U=bh{>Xn zWTZ5gF7q9>e^1N{k96JGm;Tp&n<5B}y5Agmq)oGkKb&3TmQ5}zU0+Ny=^cKpYSsIl zs9H}Ce|zm837#RnGaowN_MZ84AGQDJN59m01GozR71{1b{`b#)TTDNi@cr$RUu-`< znY2Jq2gpm*Mt+6|z%$rgz679#xG2oeGg=5Wnqf@*a6}{H5X!N|@Cq%(CIG9$8au&E z@K}~{a!(>66DLv*>MyZ4+|lQ~J&}4O#gnbZ0LsSAsjM_8a$Xddva>po{%bNBmG#X) z6cdnPWGEWXkEVW=n9MwuB3c&CXC$ltHW*&&#dFKF9A9A(c6`o@KWHEorel=tFKC8V z(`PiB;!^`syp55OhE1D(um=Vnf;)Fi^hU2j&MY|z|4s0y4Rec9VGl7~rp9VYM@Lu= zT8pw!fA>u0o$F>jwjOV09XoaD3fz}DLo&Dhk)g}7eA!H#HhLqVfvo3M^VR&M%s0Uy zag3O0=;=314w4=MFIbiP-GRkaD8ct-hLP6P@*El+egIE8PCE{&VWRR(_6q=j>vhRR zXJZ(4CIgoH78%4l1?#T2z~gLC!WF)8AXJRl#x?fC41O#_y=7+~_G^fnu;{gfNnO}USj;x|Guj2GMXXL zWmlRMK*+NQ5UCdgdm_y&ckg{bJX&Ss{MlhWr+(je-_>Fy2Q&<*Jyos|iV~`^7-XIl9 zgo``C4-ui5oH_{LOw$jjV@y59*}y_sWy1`UZq2h5;)hsr)lOI#LVKxri@G;NSE_x= zrsU0g=awVxwwK}j29LlK*AdcNTq}}!iinMVKOGzvkQQm>(MxR00O96#%Ks9pHPC3XQPEUw@2-FKxcgLR3&zleb{4rk8rED>Mw`q

    vs*aB+-^*bW-xG~`Nwxp*=4j|)6u>e;oH;A|D)`MXe0_DafIx;;zDu{@ zw2tcHdTsp3r*U2zs$S~;J?!KE_Embr)70mdIn(0@CG`G3d=-b@$fC}<)g$Sr#(bH+ zinaho^`fhPM6cTU5C3mp<%cN_+_~WkG)C3_-@Zy)@%*O0$zNY3_IBqy(^ok&x2hL+ z_r?6jxS=x(JH2te-~J=PvnOeta zeA)a~UW$h<{qGq#ue(cLbw7)0dtGQ-5&<*3tTF?_x;QI)0>Cd{l-Fo^EZxkRrfL#mclCF zs>jb=LCx1EAq?E!KTg0O4J*$)>qAko-EJayAYCG0IhEhsn$2pFYivXDAsW%Err4+GloyXU$MY(&OSJ7oB8`9gVrlgAlh^F^peo(Enp4oOS(>i#Xc>>;a%442@Bi*F3 znI#JU$J+=%%CgD5OnNA|wut$B`O9Msi`C%j2=rH@Jc+l=5`{_grW{EkY6~@Kss6#P z8k*-hgd5Zf*?Fcw(j`ARgvs7{L22hspH|`I_MZv3_IQ#{TbMgqIdDk+n~};;>xa4c zxAj+uaE|>wzS|}RZo5Q>w;_9}Wbxi_3kivRyQ3)GtwfMbIP}!qItH$K#{!3^-7QYP zA@b&2UPOn!M%InHsX9Q~$MHBAa5v`q3+u0Z6fk;lKFI!K*9XQT+rtfGI?zQD4BzVK zuR(n39$Dx3Gja5Z(|N^@z*y_bEf;@IqRjJjVP(ubt4{{AO(6E?hv=&&-{s9A&erF_ zm$n&DXv2~HKWLcsL%x@bnP=6!Nz%70{^tZ1{LYLur*6gLrxqezo*?oSvF??q> zO%tG1ojtHIRH0(pZ+!WqD<12~;uK$NFtg0TJOLX-l4yp_a&azN{j3_*`n*2~Cb2E$ zM*F#79R|rk6~y;(7Ne#49S7qD2M_I*m>OyKfPgpGa2>uCW8x#qts-Yyoz17}@5!0s zVELvXm!{1e1KD2+HzMdmsFZb4ejhU5Z8S6ulR)ASsH!}GIxf7k@#Y{R5dbz@YV8%x z@VRt2AxUJ23>ULrc~$e|&$pw%ShBdqXD$(wjS4a^+lA9V>~9DPC;+bJd_P3d@Zqha zLuQ=fK2$!LIDrbXP$KgF!3;4439Os@Xl|c#DmF`<_U5Dvhc_WfcngbbCP5Rr$0P%h z1W>8sLyjK|U_N0nOX+4gk02pT+v<%%?nY_2!vP6`D(G0GoXrZE=W98+pC?iHm}8c@ zq>aidYmbO1?5cK9h)%r3bVzdGIRSptGGn&!lUUmDvzH7sK#88_ky0_e3UA{CwhXGJ zbvacTJ}9T~h&-B3p_rS^2*utfMdq>0Y4NtCkh;K{f@lc?cbe9@v5i_0mWK_|qtm10 z!yLNW844@to8*MPjLY^Jcy(y+lbmJFgF%hX_qnCAF@u?>%izYz&oG1{Wf7hx0l-xa zXTV-t`~Bc`_ie9q@?{6STS|=>?*V(KrX)5CiHr@Tz9vBbBL0gQ_+!`nc=y*}9^6P1 zQTn7^>e7viT^94uGE_bfV;T=_ZVH?iHIz)m@$iMA~N*-FTFD0v#B-lH8u&dkhxjX_u~%WY~N5Vz?{ zCh*7q%sapjhvpI@=0b^Jcp>FQoo1nj+j5FUkHt(C^?`kZ3#hzyBPWW9mZkuzG0X8{ zcm~6})#_74ho);Y`NoOl(@Uv3yYoUL#2!=vm;8I^To*ksA!mX`JMi&wpZHtEb@Lbb z6iTQVUc=S&%w|5^!WFexa+pKm1mWRG`Q3ffg0CIZ#%$tri8=dn4wa8Z2r^wlR~b_! z(?`~qI-ASti)(+v<4|_+oJ1Od0Z0;@N~k(>_K5Ai?URS*l6WUY8s;VjZmT3M0l>7L zmeWG?c9Ec0W7JqDQQwoBzBrk0ytjn9yzwrn<%>A~dg2-zC8ctwbKRP??8bwILNOhp z=NHG#3WG?Q8v5m{QQUDWZlzM__Q%OCqh~`#fcSj5rB+bm^%nZ#vVovGQ-MgqO@TQ1 z4bg0sU!f;XVC^-I%p?PwK2f^pSAqA89SZ*&J^kco6W}(nu)KI7#n9APnTBe| z%Ybp5xCsNqEaBoHaHR2s$u%w+?;>2Rm?0IGh;S6g4aYC*n~kobV<%Xy6FsK$6H8H= z>q$vh-?-{-Nvcqx?XYC?8D?$)UAL&sCWc_`g#^_&RS-80E303p@)*;pvUvYb2paFoT( zhY%#ujZmc^*pgJ@9QJ6{P-)OeKmvQMKh5Qi7ZB~B#;rQycLKhQj-aN?B|=pgmaV48 zInlT(xIqS5R(r;8Se$CZmHxuio%vR|YFRULDqA`)`;qhU3vaRM;khSZKwL|*Wwql+ zQiDrL8tq~c%c=bQm=v&hU7EH9$ZHnO7D!zy!0Do` z(?3J}VFhAE($}_%j(Ga%n-r_~=U==n7fL8Tv7t<^k+8kWMS1O%;$5j4=q(BJZlxv2JqDfzjIqFXU1t?{b zlgb4nxtvPHjSa>bOHQL?amIJ-qkP{-wn*ROrKoLcKI5ikNiL4w`51z}Xv!{Wa6EzCh2pd&q4FoDM zTQ~c)j(=J6;deZeqN6gQ%v0?OR$zxvVu4`p$pUQ_)tm{wBeiT{$&XdCO` zeeI_bC~~X59tEu1fv4YIhgV(aBv~NI;#K;k_UhNS>H-QfAyTv&PV5zgA|daz^vF{w z`S!!pT3GxSNJoEKu1d|gmZLNg2vfSm)d@hQaM`lw*}RcA@JLp&5=c+OE20Lz9ebPQ zSz`ineQD+qQMA7c(V;*TTLBbV+-&cr05Vshqk(^0Qo*1Esn{%*=mr-p0k1n**WW;G zpXcAM=e`aWL{;)dT)Lir3BHVUT|%A)Oog=_pY9*W32#-iZ$o%9@_0qUPp5!Le8kBm zGAwpEwiyoJ-I zKK*mYz7beMW%I|vuI%3Gvx{iN0A6QsQY{c>60C)ck{9h9Lc!rw2z*Q1F1B;)0KBh^ zrGKl9dM4Uv2x82rlc|Cpcy#&_k);{Xi=iMd9*#Xh7Uw_1L^A-LAl#HJ*wl&s+=0HZ z)a9M$eC33;AmJ8rvJu~kK0`-^f=%c=7puvW0MmvbgAv;IioD@wW#C?Ww@53q1RUoL z>AdU*gF@JW7K7n~>ZzyUfv=b)hM?Ob+jKu0^s6%(CR_*B?Zv%Dx~-P~RnF$PyCK z#26}V-uA-gR`nTUAkWLN=V1N6N>kXpf#B2d^Rr;Dg@86gU0db8WVWgh0lO&ME)sDb zPSUM*ZBPmHyPvZJ@(ak%#3it635rN$2aH3 zKmHou5`6Mm=gC*sC%b2#>{UGZ(f#Dt+!HrT;Xh+}B7_Opp$Tj)q$zl!#%Jtc3q%Nn z;v)ut@DSli2+Jho0Bw?wGG;Rg5&AvJ+dQ!&8h$360Z^a-@d`jzJkSbZalLk>2Qh<4=0;YuJr{3E^0Lm2|`ji4YAaWTi*o+k*D~VGc z2w|rL!b3zRAly0A4DU(VoGBG{oJ9CDFl5rB85CllJUID`BoF$sKmTR-T+$pH)q~~1 zhYR2#HX+zhD=^XOg|zP#C>A2;IT<<+*jdfg@;!@Qnh_Ug;rE18PH>&0fcXGMkHP|v zfCy2i@(<}0kzs{I9EQlsTpWutd2ad?G!G3InM9DTNHYIIBI~#@Xs$B*?CFpI_NAC7 zL>&JVw1R6j!r>xw&IC|41er(#-NM0hWT@PSSGSXAlykV#9)rC5cnJH%JlyjNE*v%PpJu*_e%e4uw(aACPnRU~+6`3Y=F%jO{=9OfDflL>!; z#tuMRVG0VbJ)chKu=C9Sf_2Kj(dvDpv+zdm&l{r9ioV_otajS6@3mpBs&Oy3CV3pX z4V``tk)f^FyRSMXtU6b&y14V|Zo%vT+=(qz*w*U#w$;ryP&)-slldElWrzq3I(u@> z27(d|Km6b@Y<6=+6W=p%9kdTem;`r!-b5vkmu9zFZtp9>f7m>jv(`7mK~xN>u}cXMoEbNtU{hTMW&;*1cuFp*0L zI`^SC`Ppo!X5zw!MlSf0-p3Vd(7^R$M0*W70$7#*us*JG5QM(82GN(NkiR~ri$Me! zANCeL{rU3=5Z;0w-GX~;Nld*%-XvakW72~f&*v9djwsRbU>*h2%DZiK=_UWZstq`= z-m`55dxc+A!RmdMJpWnxz62i`Dv~oN6Q*=s9@?}2`?C@ZrA+>;a$cEv1x80LKovjf z2!GWVV$naM#3MHQ{`l8RxVMBVc&)F~<=xo8UHYRk0tQLq4?{G%c(_a=Y4Poz`sJ0pa-@VFr=^0M8vu9m+UQ&LtA^V z7A006@38}u@9$45$^U>(&i}B!(!%}?e#F{(9tx( zwWk#qDvLr(^X(0O{4dhpJRZu2@7q6TA7eYm zz8m|_*w<=iY-35bknCGXB1@8LFm`DOp~aenL}aauHQ7Q!+K{3hA*J%1zTfNm-P?6P zzx#QffBorY&N1`;9LMo@g~bI~iZVqZ4yA0RnUiIJiY@9ShBadS_wOAHc$aN2f(ZkJ z3R2sq0hf9LQZ$T^0Q^;9VdcJ6G6m?7C2rv)2M{a*vtf5x516Q%@{ZdBH2hH^^)gnr zqVPl@QOLQ~ccq`8e?DN$Y3jJs zTA^Xx^bZq--1R2=HRRo06UBKp2b+EWzZ0Z($GEp2p-igw63x6on;ucY^(O055>fho%E2IYrHWE&>c$`+x z(3JxO?zecJ+d=7h#bab!y%IUi^dJ*OK&y9(c(R^Pnp|b8Plj5*p6_|xcdfn`_M!Ft zvdv}N{4O3a)A!GF4ruegRkb9H%%snH5S^_hrJHOF{>Nfn1AM~GJsU8n$`n3zg1 zINHHm^H>&mRhwau8A#>^3^>Xv^ytcVz3m55?{%z}!;fTn)&&ntsNof}2XOTETq^Qi zceGJtPP(QWL>M;>GP{fp8A(iWcQ;1STepxr0CgW015m*GC+~fzFFBghO0#c>k}}}4 zd41`14Gbxmpnz=RH)hz<7yReo9}Abn)DkQSU7vd*eVC;QHI?wIwV7vg79&{WsM#GqR!FgLrXq~ZmPP!LTMvshh8cX1ZxGd}E(o)Tl zLu`yz6Iq?z3D}3{x}K?`(|EdbuMgkdR#VmJ@eEJMMA4^brjc()e5>gzBw-(a<9&u^ zFx^+=t)98T)Ogm(UdTiNO~9Mu7tSI5{$qs&nt&&=FVOv@W%Mm9ohEWF_4>(bxBZ6+ zIR9@G#pAaq$l;QAo9?gduOPc`cp|@r?qU#jiV{|T;*#h+IHhiG(39^;_;D@BM4_O{ zT@wCpCWv5N}i+l^pB|d zzGI5Tbl^glcE_PQXEvICFgj~z)y-7zJ2Vc}EEzZ$&}M)|V2pD1{_pKAnA$VLfOlQ$ zRy>zp(~x|DC00`wDYGa0MVIFiL9+sU*y}uX^N?U5@G^}ndU-yDYwrRYxB!eH01B;Y zAzhhki<|*z%6%iUS}ADETWk{`t+~1U=E9X*a2DwZAP5?VG|-O}&3FoT`M@B4X+LVv z+dP*tnQ_W*zxQu1K_A&G@YpCph!3nxbCAngNu^K%suh;5L>A?yNkRFH010&8p`~IP z+7kL|T5<743B(7=19jMSpTZ0?#rIc2^)wzSy4gVE&>_ALsV1CZ&^UDBY`95!MP+q$ zHbp1ByS!#sQ=S=Z?V|vQ-#gV?dv8<7JFRANIhCZf75u3IIXj+4x(EO;oP1pTr>4o! zBLk#Dx&{VExTnBq0k#}Iw=RBphpTMeyItAzw)taSaE;$#3>Fw8(7}!eHD4c;p{(AK zv=)cHGLeQ;A!HC+!EsWk!gi(SM48nm5-3pOfdY?YzPntiQ|*BfN)f5Vhw~^wn(`YV zwrq+mzx+geNd%K?%if>XM)a0y8%OJ`dWUY4ri+e2nsQNCGJZez zjx=&222;239H>8VpYS@98NlX8X@Wfg02I5w!bRe*xN>yhYGN*Ou6Fl&(W=dDrA|g zvR~_Z!mux-2dt6u8!z}nB3~npz5cybN){7n^~<$kY%R8Us=lUosO{@Dzo+nvv^IQu z=YgNokBvV-?$bL2@0+&R3SQKYON*H#v?FRIzWPp{k{dqL7TLoay^_DUUMUB-aV8KP zCnaY5lvt7zxY}1{NS2u7e4Y>D5}DrgFHD2@xO4*Fq$v?=uLXRnPBJ4FTI>vji3$ph z?%k0dGl$+;pd2A#mxkrTskcmXfC{xMqaYKZ{o-)iKkn1Jyd$718MNBSD zj95`e;0ofAR>iUz3lWbW9DdHb!_P$(33X=Z!IhiLA36Cv^wCB#85)PWSidmRMXfCa zFn4Ot$&BYQheuTBb@~l0>S=8QNgN8x*cV|co)qgxiut_5!R_zD+6}2S1M+0ivv&xe zBrh&FEhKZge!FsA0)TNyW+$qDxY|Za#arh|a@-4y5pL*F5K-T;j{NyVmn$0!6>JB* zdY>?il&|2gIWY?QG^H9uuz~|%mf@doW!2$*H(H;`0s{6aEKOxi6n}=!+_)4s4|S6` zXg?YfL@BUfx?&r88uC$Jechnb_>~4;-eD9`?9S)~wkN*6 zTM!>uKiK?JTOIjg;)c;Xi-78{5b-E0gPm}Q|Fw3T@zSbX^`N}jvpa=c4yhov9-A{W zDQ&m7Df7yTMLr!V)&UQ73Wk3sA%7gc`r>K*le8G18+)$c30D*EN8J#+PlhNrk_s^#TohtJ65VHY~8i+((& z>YLQNt(ps8v+^;H)+AT-`M71n;HHk!au3*FYRn{ju`cJzbtkLK1$BU+@A&FQrHX4)d)$ z6pm>G0zts0Z#$Pa<|Bk>NCbT>Z0MeQk)gKYOu0=tsiL*VVd-;a6#5IU$B>b_J%+th zWliB(Lc~+O2n0R4{?}$iyw?IJutQ8llgw5|ysGa2^?m2|8<7MA&hIRggkWNc z5;q8tLp--0JWP;~cVQwGQ`p^_+*JP9n(OzMWP~{eO^M$8R6pkbCFyJQyzqlBQHJ(M z5(;h;Uj1aUTpQg?n)4~9=vo9HsLHTy^7#_FS(9enKlv6C5bX#3Q%?G?;AJ70Zdps+&X$GeW`+@AQUAa>%7c#MH~rNxz}EL~(`%jjadRfZKcrp? z=24tyn(VNBq}Mm%E~0&{qQGG}kR{QnBZr1=089yxog6R^(CRfle>8=}R* zGnab|Jbmrb^$!1t246`gn>GQT0`PzMasAq0X_zCb;UHIx!+QsJ{Y$3rjdfI70X}XZ zr6e8E<;rena$6ou)5~b80_P~_#Y;T^+lW6HDytdkJ{8otqkpnhsZi50>6;=hDhbsU zD-bVyA;JCD#Up+_x>;4{8u+w&E1ysIegWy9^W_*9vp`7HLXLRdU%3ZM6r7 zFVUn?aOBuoGcTlC&iOyBem(;+m;BW8r@=h!1fdP>Nolfepe@&yM`%UFWo!Z`2t@A? zOvbunIIHkIO=O85N0ye9G4ttIJR1rHq>LR9y^Cx1JA}JS(R`MbZi2plP}w9hht7YJ zawM4@ZzVr>kjxSY1c8qyz(l%jG*cfS$y=@Eoz+z==To zad?jJBe#!8IQ$gI*W?sEMrn5l{J25acG5$sM}O^8<*WygSisuP<}dlUP2n@}IK?3G zP{36ueAk%Wt@1)YDdlYxOCgZN;S{2KF!ODSLej~I%Zb5aWW?A)#C5?_!_7`UQ~Hb& z3*o!CWF$?#O71w_@T+MoGQ0pq)^zWMvH9ngr5)(f_x896p4YcNxf6yxo~D9;vEFU6 z-f_^X^l^7&IiAo43CEQVM5J<)i;nwH+o!H-NFNpn$7Gcl?n}+F5-jLzb;~f_k6b<1 z+wAzw@oed%^A}ve%^#qt&mPYeSOm%GSDFoZ3$&);#T|{=bTT!Q!B1s+&Qxtg|J9A_ zd1nz^qCZMSKOD<53pR`jWs|UB4|kCZQa`0pJbMVAw;_AjwwyaUk;faE#mxVmtAd!v znqQ{~O=+8b(`NIabfGo93eMVptu#AmhM#V9k^tCZ zDz2)Q>oBorC7ovlVtO6aCB`YPEi#ur)GjsQ__%QyZTOjB@Ij?rhPGYjxb{;8kTwgj z;1%gOI~}b+i+6QPNZ7E`k#j-#xBR-L3G^O#gh1ETSbY$%0y$`)aW%ft_1cZ}dUNTF z1sIyiG`Z%ApG&~@I64n492F(Y%06jOAt&4I;Hd2icm8PA2@qkYe}H?9FYHKBBTVgG zUGO&ArKs_EwFc?))s45-CGVSBj#ATkz18=>!Jcyk&okJN@fV}RkQ?csZwB{)01;zo zH)Oplp;c$9pDwhTqSxZc(wKXYoUFZWQL`d{<59E5y8rkj*9j|pq7}ER(~;)8E>LV9 z@v+5h9RODfF{OGX+4#e(01N=Atu~WCL8b-w%~?v%ohXI3t*88uEDSF8ZL+{vD_g0a zz7==zOz=chRV6Dl_9ds(A7Y6|3*b8lpcy9vCa?k%v287D;|}*ig7r29I$-+g4h<~; z+ND0yh0VrVwTXD{6?uij;L)9>b{u}cJW#G}7b(v?mGKsWXYPM4XAf(NR4cP#S(Vpj zU{GU#??;l<57{aKoFC9~NF6;XuZ#ci;8rdM2m^S7Gf-r7;u2PCtkXFhV6C@d&tz_E z0`ERR9(`C-HCR`zH|_#TrD6RD56o7tmWEC2i!?1p9?(wX=m@zUL3#(W}ht*@dU3w=SIFVsp zeBqdrOmt}&wps@ibOAYuIR`~}`=4Jp8po#=2J`wQw^h>3*2VJS2xxH+9B|@25TTb< z(u4MP1)eolORu3F`3V$TfzHD$ z60CfRVenUWU@j5r&GV@f!>(k?=R4=~s`nfC)TMLpk6*qEpQrg{!#o&hC|cjK(&PQl z>O4opP^5kH+Nr|45MR++Fu`k&9~7Riua&aLTnAV)?qUX%`E-~%lge@%iFlAebk*+{ zV8}J55T~B;39iUXO(^f?=ZUAhC77S%WDSwG>6hA~y#_y9`Q6k7p0$lw8uCX$)%g<4 z`+K~1*#Px=gp4k@;ymUtLBiSnIucSC?`Az^KPgW z96M&VhtK-uq*spIQC%A}qf4$UDIpamP%`8NO9oa3y}C5^5zXNZ(T}aCJaT$Z(gxVF ziCJI=LLESbfgLfPXFd{|ho`-|?;IVhp2)|4;=-LAt7nkxPmQ7WVPIOumLjyfAln)A z!Z2b9lf`b9i>u0$ZDtou&aG_2geTGJ?^~TLL`bN}g%wdFu)|B$@4aWC*1T-qtjj{= z*-Vgg1@_^hVPdetn#)mlB4xL2N8=5ho4$V-Mf>B>`$c8W zpN5~1eTG=o0_$hItGaO^;83tgn+AvkwA9vS&E}5;;1Lq+KovWn$9QG0VPjb|f?HM* z0nd0NXRxa_!~i(+vGl3m!i#y39mlZRD=Tf`(VEW~#tfRL#!@;P*YC z0!0(aguU1=%gQu)Yu@+*0t;8hWzNcIZO=ivYP}FZV)Wp5e*i75Ie@Ow(!^}Mm4;uG zGtU&?t<=}Ylf`6H2rAcvW^LZQ#+D|P`XCSNIUfw=9&G`UFcigB*oq0$tes>k$ zI)C*YJKoGp$Lz@fY??gX_&aP@PQ4R{f;S*B^+?vSnUkt+DF9l2&fjnZCan#7Lq|RD zV6v)Tf(7BVdY-riAJ2(1Yz;^4acwhz68&UPr-RxHbn6S<>KK3-Z0euG`BP z?QNS?Ku4;eA+a{O{)4jVo%A>DNIjdXoWBb9j5gMJ|Gq$Iu!alAKSGuw|9C?p?t#HC z&Nt%dSYO{*$JAElp{@wG!Wjta!NUoN-8i6ylcak7>l!gEja)A zmL{5&7IJI&AvznK`rzv^Q-SGFfUqf>t_esm8p1}vgWaFSnNJU$SK4|74WQ^yFMGk? z)c|p_OLaBY(UWh-7l0?Gr}zUD(!05im)Ne)C#LFI?B<{gf*{&(K^&mR_H9b~_@sa$ zO9T?`5F^I%l^6eJD+RQ=5yD}ItF8x;b1RnOl*M|3q5Eb5AN+5>(F}6QK6R#n*IR@2 zI{4z&6sqA78Xxa{&gQr~zN*DW^xOf)czD;J{8Gsn7WM@?r7kegDE-x=BGUbn7;+ee=3_4(Bndlz zachtI{HpJ=vzlEzyFd}cmAjn8rDHWEVwJz>@gK&a&^CPXFdKjS?C@CFJhkwMvA{4W zNeuWmKJe~NyqRqv12)kpWbu4=912_LJ1>3-nu~__T5d*@XZjLkPy@F-A6|3cj{efG zG~&3Ta9s3&3lLX5i2>B`*}$AYYR7im&y8I^aNqT%cuUD2^(L|hUP$38F7|SF5jtb3 z1L+6iNLZ!cvK93dR<&M+hN_=|FJS{rU~piAx=Tx60o3w%B>PWLQikh&HzX3%tK#fj z4)iW%gT^6q@pH(W>u`WkLMY%{8@gRqF@cxFu;CJ@Nz#FL9uaQ$YFMeX^b+Y$URWy2 zAUJW}wHI3dsVP^_Xqwm$jYEw#hDvd3HviO=YuS=9e{0IMcI-^~{ddP9(NR|F?l@$n zP`i+BrTezY;XsmbFX#S!e{0G&+PNM4{|g`Z*EnRKx32Bto#OA1*w`)YG%654BPR<6 zP<32`ZuHqER|bT^Xlgfi$DxMPd;o83n17D=gIzxGNC)I)*PsM)051+f( zA`BXb*w>4cGXf=0elTbp(tf>_*d&+p>JHe z+Vwunc|ve!_G*XW`S&F)q001&c%2-G50u?5sUI>E4zyrv7kbn9Bw5&ZHQ}sbXvfFv zYlKQ#-F9f_PFC}ACgyuHvioF_L=w-nGmx9{dX_=(QO+Cp)>z;AeuP_3jRCV+(KDqo z!j6Df3P_cQp>H?3KRYq)+4+qXDC=58>ASJ`R+`(AQNSs0%-*d%7u5#@F83;!#k{?A zL$ff-Nk55Pn0n+v?8j#&eyKcu8h>KHc76>{7aJ7~WZm*BgU4-5KO~|#V+7>UmqP}; z11>*%C~mA;_DlFd!8z~*C(w)kPMzsDhBpoQjt8HdC;BD5jhR~eGhpIRHGk6gg=dNT|b``|Jwr8klMCbE1- zBrIVx`?cgtSb9H!AoY~%a;xcl3{z9`5tIF+ef*fqqOaiCLdC>@sm?^dSF&#=LJO3; z>SdZ4V%bOyrc<{b{Rc3k>3f0 z7KfWua!c_4Qd9n<==qMFAa&{l!*Q?|Nq`k1?W6afcy-j5vkSPFc_NX|j~?)rzSPb^ zi$@m#2%dr)b~$Ja;8KF9%REBrjDp9ncX6eKW!Y6e;fdFoJZujDzW^e&S$Y!A(O1=? zOzdruCYFnfPDzO}QK=ksj(TK}9tQdMDebF#8NIMp#T31oMpA$?s( ztV?7VucY5y)iqTdn=^$~T2c-9EP@@MJDNyZKCQMyk!aFg88y+oz8}^Z&V5BhWzrEd z1PeX0zun2|hrPT>AT962Bd2y9oT4lDAX~v2FW^-|Am2Lb#oJe08fm7;L3Bg$DY*3G zK9&K?;Et)V;h~_B^LH+7JWYY;GWguM8jJ7e+6P90*Qq%YC8oD72M^|B0V_+y`|e-| z!^0{vD%Ld7bPVM^es(k3>atNfa&YnR!l=b9<7dX#0k?xB&-)@MqQl=kW0 zlc~h9{hy+zJ6@ySJqly>Sj(Tjr=grlwvF}JTw_6Wt_GfdYv}oNYWl(VytJdR65d~% zx>kGpYR;jqRI=$sF?adEN1Ke#3Nu{{@2l>$&|THuneI~-#<|iz^Qoj1Rt({7lBqR6 zOXek&pQ7RE7bX(=#`><$&QAFpH1fSRP|&X{mW5d->=W7L14AJj6G>zauHPk^fIaEH zC@_i|JXeKLTuU%n&-wW=Iij%`f9t_8h-wPOY^f7e^ zh`936-cNt}kQ%L)BWC4}qUq`nf=lzaDFd&!g|&eMQSz#tO=P8f)^>ft5h%^)sP z2AR7)V8Z1S0Iaj_4SS(-BMpK(9K9rDDO7TS^80gm2Y3gWn%YOdELnJr5L%FL&vopm zQ^pA5p3C7~RFw<|3?NkXq!IMTGD*gtak0B5L>hL#8c#~LNj-AfU5&r?GofiE-XC*^ zS(Hn4DOu^IJCuDsR&%sRAv@PnxzzL97L9aOEWaHOcZqK4@NlOh&vU8I?~wGq!=GEH zVuu|NzUVNY-?d1dPZQbmt#dVR+1xyKBJV+DrS8l32U21u5&p`) zDkJ?ppQ)JW*yUSR_ovUwOmG_~Fc8aRWJfj-DoM-%9f2v2BO74$uNk}yeI9FJLP$1Z zSjxlmqf)kuo*FTX5Ttyxg*+uc5t$m-{XG75V`f#bd#>~!f(Xi#usNLqgNd!}_b9>2 z-%cH`M)DY1A%J=UYQk!MwRrjtI+_*e9MhMWk{NL;o}{7g?TBvf=Xk=3z7u|oovxJ} z(N)LW`0KUq4-5FXozM?`Fe(>i^+`y!CdgE7 z;BXgP!Njp?ks6t7lT7wSCdWFH6WImwbm2qxo{%DoZ)0JWSs?RTW z$tEgZE4nX))ChReCAQurj-<#gbP;+R-pn$f8{{D=ij=XGkXyGLy<0xFTcM&`v8h|B zw_AC#TV=6Zb-h~+*+b;%QJ3z~(CX1N>CtlR(e~@v(TVKQrT6IN_UKm_zZL9m9;4yL z3?^u#_IiUiN|n_^#$@TV2A3k=QiJT7o3C5j3^Ma%(*Rm~1}+f08>hF;DbHbloq?@h z2CQBPXA|p9X`G7strw_u)ywScRZTgUk*F|5{jgrwA8jSXCUUBzoOi=Yxjw++)%LqR1A$fS^hz(~<}e7Op|=L; zw&|;D8AvddVTe8dV!(7YheJSBtt;aRmDR51LKYFGV8Eh<%e(;vv@9eOhYz2x-bkUL!{@&+&}TOOGySjlMA%U346M>o@u?a&(D4x|}=uzGC!4)9A+#2~zIC^28zQ?=`F`I6AEBr`iG@yLQPR!CF+bd3G&*r(PW z4w=iGD7yyyIR0+lf4tXFgYGpx{!5rQ1(dS<-}sz|vHrV0XWzjq{}tx_Pxl(-mj4aR z`@g@}U=_3ehtJu=Xk7fwUoh{lr|SQ>*Lb3_^tc4N*LYdb^d9m#`)<~@@4~#Rce3_( zG=F~Xu`|ExbN>38`8UkFy6ba>?lpE{-g2vAoBQn>A9wFH&fXLM{`K#y{DXVDFmH|L z;|KS*J3o7!OkLfDc~!ONUOyJEsh*Komz&$Y*MJ_^I$FjFY&y%=&T^Q^&(oo-{4UH} zHJ>c9d#^!AmS0Gf{tM=<+`ZRmUM@Rht1R&*(+Vp~Co%3pFmLpkdKyV z?UH8&sZDAv@Lz)AhJt%D!rfr@t@lnPQ_;2%OL@g2)7 zwmp{e0_L>UkBt@_th7czFDFgvq8^2X*bab}Wcuc;Qqy94V2WtZthY+@6pqJQz71JE zq$uy@s#ckpK<;mSyLsB@YV%Z(GBAxpW~jC!-wcwngveE-O9|@9FyPAE*FIr0gE3K{ zSHiZVkZlr2eAO>JD8M=Wv+tHb%M0(CaIK6tihwno*-+EUg_HS;zL+5@@Ah+r zZ)BCPx$aD!Hgl zi2&xB%pI5Nj3QW_-6P0r=*Gd==LJ5gj_n0jp4fdGN_l)wYV;(<_TFLErdqsL z-0BMa9c!eKIqrhOpWg#*WZQvR&h^iv3$xDSFZiW#Y!q?$>NWF(_)fIYLykKLU<=#L zys6!LfS`Z^PLPwid2aJ^ut^*bjY>VZew@G>(WiKVtX5D-znnJmCMp>5%hcP#m8)a{lj!N_4fr$uX+6q;L zSh?z4ErB70nl1zmYaEP1y1V|)i zRSE|(8%xMvHrS;@*Yb0-CCOQV1_FC~eGuxTTHHjR>fjwhg{zCcUg}W5URj9Qbm^*1 zHMYZ1MOaMc$tT1+NZ(#Cs!Wy68-d z@~It$Qt3yIN1D`kQx>*ek&@ZDOeZPL)qNsoagtdB6{32wjQ8v|gzw89WZe&!=+WH_ z*5`-bS?hvopOr2mS&CkxyK578)Jnvpcz%f383DDq<$7;f6|LpT+{p>0EKx~H6D{Tu z&1w=9su*@K?WT-sbA+Rr!&m`It6roUHXaul7xS}_g zlgqx`VV;1|2M0J@>zyA=RGv}-Q*Bwg^xx_x z5d%`h;+#oz0c&TS)OXKHe@WhUT`h^q!M+J>P%l(M7(8RIgsP+ zo-;geY537ei87uprK-&D^HRc?N@U36p%5*TNPck8;qZ@}DAkQA1#}LF&3O_tG5!f@ z0XmX8+RJgR(HO@qVqf}>-5g!0bO@6WpV%tEm0EC_!&amKW$Q&apn>fZDxnGaA>D(X zJWCK}yM5elywr~fmzHdO)27iI!DCmu(P|;>3M+>|EsFtfiu zIC>Ze3`2>s8C$=z^`zx1SuQaTB*y{p#naFzvPOH=o#$L6^zO!p zQetRxBFCJ0NE8-J7scdfDvS_ux<6ZF*rRAPo4sdY;MCCMtt&Etr)M=2feosH!~K0oC$8Df;jxA$m29QYnkycDVv$rnURI%4iPa7> ztovktJu-?+y7sPKydvg>Q^$gEPK^9bOUdNd#Ft;$XvX~);$6$%knY4O)EpLFVLL2X zZ@5O3K6sgMUgPJ2bLVDK)gKAAT8%g9s2NoqHIF~;g-b)5FkY<5oA?_2TQGpiBLHk+ z1QRXHAOC!}&kw+*^-M&l-t8Brr`x3vrDvK9{enFBox5-BY{T_#6cnA{rT5Vev{$>9qb6daOPXZ+BNwo6`f7Jf)h$-`ScS4qDD2)4apJDo<@OK z(idIB3JTf_O)~X8CsY8!XdoxU95au*9^mpcN9F2@>GfvqBl*FXzn}W4L4r4&GtxS? zQ3<}GXh(I+TA3ya&&2U0!V68*Lyv$vCqcakYCo5nca&zeKeDuY@8rAi$!-|F1ze9t ziZfw8{c*_oGcWu=-EP?Wbm9gkk`s?Bt%pbXL>NvQX3>b}rT3hTR=U8Y7)d?0O#$1d zK*Ef#TMFpBpq>&YBcBA0Xpd*#U^%6uV~&9xl92<8N?GrUpm(X)_SB zqzl%e@aI~c0AhOBTlGhX0OP9E4fDhrThr)14=+B8@*4vJKaLx6q?&>~To(NrX&)&r8Rj%N6PK3L&x?W>m^bOZiu=WgValOgxuEM81m{W~e`eEV6R*rL5d+yu@=V&gKm zj)4*v#io;Vo+ZL)aB(kSJ1^qlGQ+5l%69i4JP@N)!nU`O`T$8fbO@9O9fnWJ5I|gS zS7+7_UFgjx?Wu9Oy+ z@(!GsU}PhSDbkr|+hUd_6S1W#0&S{=3?m;C`?tNPxV@2!#u2cMV>Nmz%zy*YE2d8= z2OFLhzS}&;JphUXsYH7LoWANYPcKySCekVDC8xlOoETwSe65bAi@$ZdMe;enf~N_# z?PmH2d_f~3OjH+i+o6Hvg#y8RJbGGP+~HKs*tIK(sZaIujBi?@=X2rVSTm9=VJn66 zNVe#a;xWNfK%YRCpiGhdPO2rAhlpn>*I#>BJV;0u7qW6eukj04lrcIVNUynt_pPIQH>T<|rG6CQ3T9UEHG zWC_kG59vccQINj~y7<9RAgo#vnMG1WGhrkbFlqx<+lV_81afcLeMz%@Z;aS}dYA!l zlG|e#G}c=W3&*(e`!vvYcT5r-(?43^C+*8uZyZh4a^;vUOHaxPiVc4(!}>!GoYDpL zDeN;lbI{Y=+HWq9)AribR3MTW0qfi|29zE3(^79usK{p#e2TC0B?C&Rhi3+X!=Z7)TKYXwO(1u8V;v&9Ss6*y}+e= zFfKPn<_^26957Fq5J<$;MDOV@vkq4Ogl^yjtnd9y`7;Y%31cCwphU`DbWg~X@5qp| z#^Sx^&JGLQsd;!?*gF#qI}~Ay^9_RoKOy5Y>{B)PsGda)6CR(K^-4}V;U^$pAIbW@ zk#fYsurPpirIu~A>Rv4TDjMKEn#Ax29;P&8+{K~m0SrJLyFs>&DMNc($PeBvG~0Xh zGCrZ_CQIq9ML&GK;yHK&T=8K9w3f;v>f%m^^F+kC1_AWb-k}EgJ(G9BTx;Vhj$W{r zfo?iZ&=~f@ZLny}qA|c@jAnEkOKR4?{k?|6TRrVN%$M1Q9rxXLLaKi%5KVJOl$xEc z$HdYgv^6#Hxp&R7vWO7AZ=hWW)}&wo9wmX-!|p|2hd;Q)yD!XdVCSe}!!xDOA+Tn$ zN#G&)D;OQzM2=c94m^Er{^Oy2aO&fa2K2HH(baZ#Z}mPsm8IBo#u0EI;x4p|D827i z>in%nZV#H}HUrGhXgIBe=cGLlBp(+;un^{8kAu+2c((d_?CCjP&9G+nE3yzEJVpfh z1CiGa@ZUe?cqDh>?XvaJGQwe~;7F!V1tt{09L6J9;ntA$C}K?~-4wX;p$+nfUUN+p z)WKNEX@jRgLdiWYyBiq1Uo=fxkpbJM(U1XHMQ`)!j}=oz+se}zjJ8JP z&Vs+T`;itP^&?FC1m#c{6JYcs$>QggWlk_)dzuf3Hvr6vrcPb-W$SdC+8X6=KxQB4 z-2o_$A)IOWvm4y8{)jnNq#9$;fr7F0a&YcGU`{~R8{L7@=<+l;M+WG9^aii`u^78eUhkkiiENGbd`Sk%OSUd=PvX%xibc zc^?yVaKH2~$L=)OV&1OYxq$RdHh>a>|5ZW?%tjcFwTg*OtFGOc{RP}~z;le@Np2nR zaNvv)n8wDZNoWUXWL2*jl{Mfj1WS00V_+WC8W~RVC?r&-gs~yIIIqpm9#iM|I{Zut zUJR^UVe_^~?^Ayr$9?-V=PSg_vA<~VrdyJ}wt=b1NB1ypvBM5EvU179;k!rp3`!7& zVZ9H3OCB>#pV)E3Bf?+`rR1-Ng`ST%1IBwd>`kMGHK_bYw8<>hgux}zNdFt){aYiv zQegW*v=0I8yz)wXH4E;24-V_zIKK}`Xv)9LmEaIr*@54=g@k)>odz&mSLa$AIY+>_ z(=YMJdd1P45fIkB^Bb>u<~b_-9=&#cft$lRi3_m;bhE(DeVf-Py^aV65KQ+V+MH^g zQQmoYqYBS68a5Mvp_D<^*B9SzOmsw?kE;R*mf4)W2+oKUk=%n19!wk z)Ifsn7+ePMi5?aF5C$^M7X;OxajU&7T9(d3sD58zz>(zXTF+)a3avD3WRO)aM{8zwlFw!mqQbKK*07BKz#Mb zOWtr|7+ig2{H_@9OW~&gZE&f99m-Jm5k4Scgh47RZy8pp9U_`A{7kku=qbE~KZ z*kcy2fwQ2P?Gl&`gK%OP6pCcP+TX%jK7V7GU;P;lTQ~#y?ggd3a*;c~xjo*fAj21x zIS_UnfR{Ty1WW+F0Ja5ML_fX9d}5t2u6mgJZ4k(Zag{8vGuPqd?;Nmopc!V<2@_hm zBID_XZukaGsCz2ceyc;7_z$i`xb|BavV8&L_4x6xd{LZ0dNC*v29xuIr(W2ClSkMZ z)&<63Ld>7i%y1E1yoDM8+y@c~2=H7pbl;&+@2o%oXYc9vXC(!?m#cmrJ zzW%BBH{5B1I~?Ewci`kdtl8fKNFR5z^2s3l{{ZIAOOF$|(g2gZDlf?EZ|%2YU36L0 z<=^f#{+X4J&h52NNT6pcJ}q#;kO*{MVwBa@Bg6pNdP^WQLU|CK}E0swxXpiBxf2v#35^m&HM z##};JhNfeAib^F7_U^Qs;7^amUo%kE`wQmXz1M)GuQV79i$1eA1R%*$SOm)Du4FOl zn9Ck8N6(o#8VQ3I*5Z>dh5vl>`DJH{xaXg^`Ms=Vxwec@megOcPqznzd)3YVf_c-7pvxC!lQ}q`7rL%)A#=$u$3lJiBPju1H&kN4f(zNb*I3NyQM#wM zVgRqn^-5O#D=UBgFrAb5zUFF)Wo&!?%F1h5JysS}m#|3CliEok{dKRQ z|LLQh#qPbv)+mt+P#tW9?ltzI?y7v{L8|R$<#|omRe?1o=xV*|b2bIzSvUqsMAu!I z*W)`^s*-1lO!LfvayYI2Ql@|Np(9`2HV*~exV~x4+Df`J%XM)ay4T=tFG;lP{Je5O z7ZNz*R0bfJS5zsa3K1ifXQmVzR-)!2ZDJ|b?5HFyv@>)yD+aRE}&=^=FJY7f_%>B zvQm$fq{s>dmS*hwoQ>1FkODeWF_Kl<$@4ow0{Q(0M`a%Rr_oI(V_+Bn9PL73QB-s_d}S0hs7KKJ=rv?3u(ue?H((RYzEl%)x$wm(GX&f*#1{Z0q(y zUnWpv2KN3BK6$&XPo;=UZ23q1Fc0k)0^kqIpXiBC7xb=DAyVH z?Xmg3GaJ+Y=5xN$`NyHH`5!Q^=!H#B07c~iICf!P3m6`Pd1FoD*&&!$VU5HB!MwQA zIn-Y;FJnjMS%TOfBRxts?S{d$gg1`ARS}@ip)Wajvmvlbz`*{02lM*#fAa=kI)j-k zY4;(RcTFK1f_blTm+F~LfuwN( zKx+5Q#3eOJiYm-2&6AJYyqJhB&TO-0-~wFu?ADj z4QE0Zi#jA~=Yn^~`DK}n1F@g3!$`A`nLSBiq$nc(b0iaqu_NPoB`>Zq>nYMe&`=R# zyu|EN6*>(NLrEs3(gCWViJ(i(pejF2QjJ!E6wM`BPmXoLE1`GOs^F%E=1h#AeyUtO z%{eiqB-H0tO-s%+L(aPb-5V+Bg|JdpcI+<98L-%qUX%v80%^%CtMQU_8DZu1cxCn( z5+>I`%xs{~OO1!J8O08@Vi z(Y2rRbeQ2SxCPJ(e|v1=M0NbQ*>wAKUug8*4)-s+_Zqi8MyNH%D{1#4o!tlAx@tz} zbO;95gB1{SAbr)5wC9!G*Vrd*{I{g72%FZ_{p@hB-;!Fc7zM|QKQ#;lzh0>+oTe%D zi7}ujPC#I-lsNOy55#KI%UOy;Vto%6kPwu(3 zj;4Kx*b)cr$THqzLp*A;;}?=6D`fTrSvt>7TTsbWgDTrP;|F zW>M7#?*}`z{7rqWEVN3Qs zR|4jIr1?G{>v1DX#0p}mfBYz+vcQCCdRmE0F z=alMUoL(jB0DlR5n=KE|e2MBj{p$P9tM8qdvnxsa;uiQ{Z#^_WyO!4( z_fB_b^I+B0Zw>>AU6wluP2~?Z%w5iWKKXk4HRjwFl$95eVG`I#J0}J@&u+H7{{1!O z+^@I$&fPSlEv(CVq7`l9!=Iq;Z{055fs`K7Oi1mAFkvG9T~;2O%Y>TpxF#lR?|-@1 zknZC8|FZJAox0xS(eN&QEfMV;a(kgz;!0vlO7#?|_h^O`YB?Gs9R6eH zSPI(3H~(*T@!sYC$u92bm0fB3|GtawdJO)ST({l%dlw&WYg~G)dx-{l4F1~1cRdDw zORlf|wTrj@Q}MvuCe8XFfA~&zbX#7mx=x|Lgm^ zuEEa{tg5S&t(Htm0|2P-(V_HY9E}wYm#jmY%qy1jO^=e>k-D{H)i?+saf2_C_X+Eu z@UFeCdyK0-*t0aE*Z>!{BegeBQfuh1<}^Cq^}IUQfnaKH2cAz|8SO03tIg`_pYRQB zMf_f^BP{a6kN2X_Sl^L@Ns?G~gVyiTHD088){?EOjJNXz7`+V}AYM6~W*#tTPOX3H zL72G70Z2#y5VAxz?HTkTM`RU$yeZOIGAtNtpAGChSMj1$kl3O|shgmiNMucH; z+WzVLyG?`kO2D0k01gT!v;9loAe1{swi5~%#Q8M+?uQZL*0h_3LymR^%mIu|sF2Ur zFA|Wixjlx2tpA;YI|yweU-Ad8j6Y@VwiW>3pk9YUYu+yH76^7ae3>25p=n+z1$Q8E zx>{=6_6u1;rl7yC2?40IV?SyA1!iw2;c_zH$Qr_q++pY=j0xcWydlo-5?SXHnfa*R zUc>HZwua;+Uy%~>9QWq0uT0TUP4oM2cTu%^sPYYD{wF-Y&^^j7hU~(lj~C_mE#wm( z{*V=lQ|%@et-+zYPvt`RceIv3w@#!b7KVwk)}E+)lwvm@)5C^E!`x$e-sw7ynlzp7{VD^@TD6RYD4A`!uTxQ&CuGjAsRXvzCv zlBlv1Z4i1nUkztE*P`5!Ne#=-1|(>gOiz-TTr&ElX{A|i%T}hxD;<$?`fK$rN!x+= zjRM3Q^PQ!7)sll`VZ`V?kCcH+>-^j6GZm6Piw z%cWFSE)#%X-e2S9L_zW!KPZF65df-O?wFbjF&enQ{iDaM53v$d-f8)Lpb%Si!6k4f z|D8EO_xrJeiZHBsKdz;wQmji(51TW5juf`^ z67lzgt9b4L+TP`Hj0uo)8V-qPed~c)Xp+ykCRFfxr>smmtZH@PcF5P8-Ce4E@-}lZ zZVp6$qj`a9Wt)vJkA@K#4tY8&ol2ziA-ivzqU3o}!UdQLH7w1O(DNhpy5H9*e^vPo zOCS{s)RHJz?e7|*nU@&kWA4-M=*flKEVstc&HQ+%2nC@~pY?9`k&o};@x0?(TX{#4J(7r=U zu|zd}^9nYv{24MVxx3*xZ2HOL4004PTB20J7}D>$roj+b-fUPn$=bmi^+phHHz-X} zL{wXz>_H#KwI14S=QKE6|L@fH8aC5DY<2cztSg|p1IvY+v56O(Bq6iDa?0m zL}KE2ud5)urGYRcRMsX+|Kdsnedf{o#_f&BPYlH1q+Ixu&v!8c;bA8U zkt*j#hG;`-`!ec-En%Nq3`-$r^Se(%2>Hds9ROVuMJSD^vQ*BBZ;^i zt9{j8(>IHx)nRcQN@Es3l3rMoc+)xUUGHmn>ETE1ZlAAb-y=q%bU)sS*8_?j^D65V zl}~wb1PpuR_us{rNw!2V%-@9T%$xLnSU{)71A{qTunr;I{+SaR1r>>Ga)I*9l!x0< zshsaGPzmV}81Nj*+!zv1d|#tI3#zh%?~Jg|%?1D2=iqL$f}JvR4US*<600b7@!Lyp zyyAgc1sfmP`|X8^@%6F`o?DtKTk0l}HIw(T{;g|qarN)Vesw67PWHXre&(=WhPukg z=Kujleu=n$=P>PHO3-o|_&V+IK9QLBX(UD<=AeS1L#xY~p+r5_n$by7C!)D7+6_$S zB*1Yf8p**b-Tns*WA_bE=u9lp0XCwoFDCnACo!K5K^uP*b|FNe|BNi4ueuhB2~SYo z@JJrEbL`T!QcUG?*;)8VYSW}|{^p8Mu{VV}o8ZlN(B^mCl&s6~nSJ2}&XEs0WfQJY5JUTn; zVmzY@@<5Bm?K5Dm(MbT=tasv845(m}e9FdnzD-j+!f4J25p0n&VjgB~xZ7>#prgC3_JLUo=t|C+lb{2iME-@A3|Ov!O-EE_Ax?$r z=uZnoQW>yP_Xs-L3yLx6JU1*6ojB{zzu!#vytc)Lz)#jGmrH71?m5-zI3ZdZMlKu) z$>3{NGl(K9TbxN~g`V65?;N<8Heh6J8ac>^K|1XA6O5}MAd ztK#+$3t^pFmGb_U2;CARy|ZeXCc(D2^(5FjZ`|h4a5zncgtA{d7eLJEY4MFw0}Gn; zq^b-eI&*+;moMR&bltQ3xRhhaz~0wLWO(RwhPEA0l;RHp$dgDCa%gMH!G0Jl-#9n1 zQ*E-`=DZP3{Ro_B?RxDyguwAr;rLal;#!F4qXs&Z4M+o*;$MK_^;yqHz$ab7qKn1F zE{@g)sEmyq@#ga=bCtsje11(p+)far0YvZ$T23&L=GXBV!doQ>=Cff;sBB11km( zS$@uU10-;g_8o_p!l}KwF4`HO&W58G>kr{z3Q7%d-jiBKL)1XyyH*?slu1B>I7{f$ z7{Hrd56v}+33Xs5v8Lpa}~# z-<{SYsslLlV1gRh{M$FMdy8@jr49IftLhE{Cq)l!PYw_wMbso$68Kt#N>3uuKm=JO z+6Ysyus@1Zd&n2Im(mKQG)vH~?HVWLemQqQ4ZJzi`r9z{yfEMio^)30@LXwpB+fiN zmXHMi1x@HIayzq1W5zKqC4}?=~$X>z?7$)SavYy^h zdw6Q@cOxs}0$L{2Cg>sFXT9aiW!MlOz@wwpSYlj0%8Pzl0MZ@*9kK_=+6^~2b_H}z zJBQ4T^WV}gyQ@KD&>$ktJ3owp8=sDV{f0fEV5#jj)K3FsDbgYxG?5Z}O1k-b^58Qp zWYMly2j&QKE@?k_E$a@%>(j9l>?TZeX*9hS?u`63t_r1JQua-Y9DtOT_Yyc%bt>{0 z7kO-fg9tC_H4HFZ-SM3S9`NkXadFI6bs%Jb)4kxegS5}1hM~PkaPiW6^lc1GMHWaG zg+SJ-Z}Mp?W1U+L#Bu<#ATrmKLQuOEoh!yX5;>J6`U5O6!Tn_GhBA9RxSpWv5R`(P z8NqGi;&`Y0g3cMj)GmzN9ps{VskA644XeTen=oJ~{SKt8OU(Bu{~CT5mmjvZC=@w5 z^2~o2&K#yO1%1>2bK?39-Ki@NDb4pv>QARgG7r)yJjt&pROha)>3O_qIb=QV zL54if`5a&p56W=%?RCrG`LlV#Tj(TkbRJLwa61J6hj@sC0Dxyf4%S1&*%0r&Adec# zmO;!8sUCR$FyJaE+cNENVHzq2Ik5d9FPXXxoY^}Az?cx9qoCC;(EAWn6uf_A*KF{i z8EdG!68I3{KEmK09_oYa695AGxMJqKFWARMS3oK7G1hrD<>;(U3&dN%{cJXvvHfwz zUTEfToDBB?J6lzmbT8reV}M%6Xot}6P9OV?6DL2u+y@z-c-$zU#>te%I8^l9POsmRxTRtj4Gx*Enz)9rPGRrJSzqqP!NUmh)87TjAy* za6kZmCHtXX1DJUT%Hes1uY$dYURdHEnK(oGjxIYqTXy`jOf3%O*8&B>g-kBO5%*GB z9{F1nJd`6QEjdjW07Mzf0PTUtGdZn9F?sLlJ@28x-ttLn!$H1J_icMUer?_i?2BnI z4LHj8F&;cmgvJu<;*0e!Y|&R1{GU!@QOt&wQvb)teP6M><&;3kE;F&6-fsvx5Zu*A zhWFkO^H;E1tGTUD0V)h2FH{uk*F0M--S=|4;M;@OAYJjw`^YJ6If}lAmi2ty>*8Pl z9k!h@iJ2VM;pX+4DOeqvv(<(LyY!5ky`T1eKa=o&w)p+r&G+-iW7FpwW?LI%p5$8gm5rxe_^q+6IPjcFh-$hQmg_=XXvcDH^eP_%5 z_#zCysrBQ3>M>~Z`Pp&iXP1+O;hz=Z{+|nXS4q6`_bo{)t$CXrKV-N-s}@d01C(oe z^VAty6#uLEd4LG(h8*_}tQnHLGAK)H(@_8*o(hfGuHcz52{j+l%Yd!bi-#i9S z`_BCL&hefS@87Xs{*8 z&IYHE5QY{}MEOnGs8#YL*DO8NMfM=Uj~{4J{io!*RqmCbrrh2nO4U8~V2h@% z&?o-u%m3Sw>%UwaX?&zK?O!^_J;9YFsm3AIl@&c(A+?P>E?(cs>l`=ULYjo}JO;gC zt@o{as{~Fw0J``;P2@M}q6X+mo!PYwJul;4WV7c@N618Yl6~*m$`^^M9D*YDEHl-B zaO9j81juJwX|jkBDF$6+HddZR!y}OTH#YlY53P{ME?F(|S|Yh^M5`kOSKRyRVUavJH#pOR0$^c;8Xamw4h5|fmemcX`zEG!AnUwr+i){L-nP0q-n zuVIQja6CPWIZO8u@?n>? zLC0kF@&A?N`oj7-7Gr`O)v{b|@t>7k|BqapC%GOB)Qal1_x>_<@fQ3rDP^aFpV)(7 zKY-!F5DHQA!|w5F0pq*r@gbH2lJYqThB*x%=IY z(H#%2eoPKBeYw+#?V3~Uh5Zkm)cR*JEu=VcE{|+HJ$eh?iIB66B2UO!?;T6}lPNFNr84wJRqZ)uJxCY%?8zR#r z)`w8h7iwyc#!CgH$rQC*&Y<*wdNnv2!92Bv2CMt`u_g7YR^Gj)_+3HEfo`Dk%embsnaLgPKvyr{ zK3ZXeJirCnu5oBJ0W-r`jJ$zcDr zN5vBQS}=CKMmdaSFw&4bWp@`?S^7R`e#UwIU58;~Vec{1`n8(dX_Sq1SbXU_^Y7sN zxs8P_tFDhI^QrK@h5+fa&`?5Bnk024SB%m zq7jKi@2Nd-`_=iZ^WVev2LKj=5l2|U{O3~0k>fI3g6^!)UHo#^O;0)lw$i zWk1gATgBo&CIYkGt@IeM3$g%ayFZ>~+gLYgh8_Cji5Oi?>1(*Vx^L8e1jR20>eN-A zjalZ~ntf?_ppNY>(7N;k#G`aX@JY@#u%}~s)`H9Hxd$(mDa1U=uq`_mk-E?3<_}kv zHsw>kt6Fk9W${*2u)TLb-CY`^qarV6i53DAae}-HsTh1gm)Dqjl@a(bSPBsPOcA@}3Ya?K7r z+bGqNBN*#8^VzL@D64r}M8f*P8G_4j`1XC5&`_wt#5w*>Lb}DeBCnMRlqFue?oj?F zGX&9iSnpvKxyA|8zTzg$iO2&7j{9U(^iQp!5 z%8%&bmc3#Dkeqi?=84hVVr@(8sqA-qQcvzYFib$1|#EK>&1H-4=LVqg1T# znY9j0P*LKx#tcvU(#X~qm)m;!00W=e|5ZmRTw~JBWHJ`46irU=+CCDcpa}*_6`ozQ z%5V~Oz|gKcr83`pz0L_TEJ?YTmQp|h#r)vUyuS?zd=Krgo>5OLy?+?a^fw=rrl!%s zJLC&CTKf%k5WTfA3a4jljB89qqPc>1?V2eDV!Ztp6sjetlWH&DPjhcOTyOML@in%& zroVY`3(h(4vFhdNoXsr=`p-ycmddNBmv>`@utO4xGn3Bi_C7Dl`%!{Dx|u8Q(EQVQ zKJ;2Of9JtSF|9&tot{i8d1>mQPC0+02TS?UYO={s2A`N(bCU5}xr!Ng^9v?Zy=Jk; z3pQ4r5hpq{6_#Vf?jjTum0#I?X^GMId^}1Y8H}$l0AB4)A74GiO1v4H0;)c!Q#-~;!U4R)`(BObP#*B%NbljwOc zBqFa>3=stBP+RY1sQF|=smS31sMjv0C zPORGSm{oV*vs?d}vDOzXHim;TOF5BDlz<5l)wv}Si*^djU`|!+_V$#f0mx}@utRi6 zaK%S{bzTmA_}k2ZbaazR?R+V9r}?{LmK~*iX}G>|LNx1k{?&=nlUJi_gz&GsHJWVs z%#$tjJ;8yw{U>vbmZVz6xs!+2@2ki6_PAzS4xif>B=YRdH|X%4&j*{6TUS?anT&in zD9Ju~UB>f**c$WB6|;2pu9tO{dutQFMfzT9h;wy1IPITmD#8`Di4Z?C-unC3*8u*% z1u`J0WDb2oC4EabFxGKTS3gcKBA!yv83Uxt90@>ka1QTvKug)`_rnQL4EUBA^NA70 z*1CwYIJO3;(zh44+F>Tuv~&#>L^aCu&x|P2e+*MNI;SzE)&NP<(H|wcVIl3hKg8Mq zAfDi39>?N>77sA*3J2|e1!65+Z{v5VE}TX;yQq>3UREICi?)(qBBVKq>_H`q;RCl) zp%PWLKl~D}seo9{L0i>iKR+=VDUhzr1S&)l>F=uku&dFfk7oJ2MP;v&S&yz5T4 z`j&Hl=BzB|;B`Y(ISHvkP0isX|LBS$4`r&5VCHnzj};q*sC18|bAlQ1n`qn<6{cwS zF`izSXZn2b8RE~*mHvLZZX_*d9X8;a=S_*zd=n!u8>2cZvHf%2u0-07EgGoXEul+- z8DJDWNdT5u0G-T$F6L$9U}ldqNo)B=@@U=zpen84QZ6iNrNB55T9tz4_XYaIbBvpX zo(qd=GWgs_6_&q&Cg1UGts?puz|9ui5p_XN2O0X^aNDRj?Y0YjM6%WH~48$JX2?m3^E`6uA z9-!y!cj8&K^;qt^h{*C_WW}k=F^CJVjc|dqE4Mxa(UCZrd;k@dL}ZiqU}_kV=pSJ$Ly(uLg!&={ zLKIo561=;bnS-Stl;Go{$#A*SHzTDVK0|hqKokiOxP%n3E3-|6UbYc08akt*zSD}! zf`yl9NhwY@xnEQj|3fDIy@%l{3N&4_Skh4(6}xO@@(loZH!!^!*U4pq587kWY|E=M z9AN#2J^1!b*ycjz02sLf%F^)ha8ss1c?vk_Vnwi2JCnXyjhvk)0jH2+7H$P}=Rem&O%cZmj# zAH_CY@M|EN*CCjY(N$2nsR5uhz8j<1vFg7YtLicuWpQW(4k6;qJ6CgVm}`v9M^_M` z658ni8CAhW01FsC4JBS(Q6C3~O5>)2K|I?C(T{~X!^E+QU>10RijtKU#!I!JO3}Q` zBEq~CwKa)wCO5+ufmkYP=~T-ud`nKOur#Aua-jhrLQq5y545fsgL~#$*3==Qv^uiA z9_BQ-jnHmWtyoS^Eq)eGMV+}^G+$i&hc(H*AX#;UCq)}R#g#aKDeS0YN29pK6ZsWJDV3-<}#@AoO z3pc*1?bB(g0X#)`fNnRZYt`h|rsu6Mr*D0`a_dL$tzTD&4?RVepWM>^bjvaq22lrh zfNnA@D0H49_=^J)`thdy%9F6&B!o;e;>;RSBCbz_Us;R8fy&(ymMiuZg{n1q%N8k? zX~5J07^(gO0xj zsf3|GbB>Fb>VB^w_o5+>8$(|6L*BoJXlHL7AlwPpxf2j~=Sb0=kQ;Zx=I=`|c3Hyl$m9D8FpZhko7*D!-Hl4v@T>@|`aH(!#MPoHL#_HzB8h(v65yo3g$J@Nd zJL1N>ipG0xjNh0azxivNLzuWR+6bNO7VhtXW_4@hpmM}&b}q#2N(0RIPR)Fq6BcJj z0%f=zFD4;V{J?bBSW*n6Z4P3g0jhIv!kZz=3&3`4jUstsV1n?PAHV^va5;n^4%%*V z|H&ehO~n8JuYiZLV>cJtqr_-@)l$8Ge#w~9c)wzdJ8=@$e^=<}HpMzHtp>b6zsq~` zmpUyogq?6Fa&=FGio`Lr9CS>xRiA~9B!XjG{4&}{5ndqNor@|4(bvw7+i8GPkAcqG znrf-!u~=|#Z`<2BK!9=oq3>O%?OoKnwQV;bZa?L?MW8er5NxU)l}dJ#Zt*zu@ZREt z?GuRS)k#$DblC41y3C^!yBQw1(f>a{NAvElZT!RL7EilP>Hqn`pgc59OUlUlTk>YTxebQE)Y*Fg+dwt zuvVIP@W-7WxhkztKM_Rj0k(*(Bc3QTQa5%IDyxIZr9XbX$gOc`5+h;?kmSQQ}zkMnthp6AR@YMO??A?WS?S^*(iz3^`7rhoA zhA&F|qm#Pr&mwW#lDyfHqW6+=!jfw7lKRah&1Xwmf0jtwUg(&;(DQy_knqB&_4M(cZU0_Cbss^fEQ^D8%HS=NIq3VsAWf^A_ zv>CmPG3g?A9~oX7MX#UQ1xAtKf(z4_MM%E@AVGvka#2RW%YbL#xvStF^&9Tmb7EWJ zNIjG1P;<fc3E5#pHZ~hBHGW)ps&(q4{ zk3VjH{PiC@smL>Hlx;=m=i(9FYmv>9g0k!Q-RmMg>tbitB}&$%ZmkoZuWyr;d;Dkp zsBf+8C%Mm>pHxdessAfN^4`6n=d;1%N4!Yte?UmPH!XcOt?hjpFDHGWa!!9csecjD@#^Q#zCa-VTHpIW zx4Cr%{3o6q+o~T_{$E(Fn>PQKZEis?{!=zLt@;1C&25zyYV%K&b+}&5waKD`l#Z;e!{?TK~A3A0K~8^?Kgnnrdqw!g>nMCyZC$!};s*MwTZ#00DXn2OgCH}W| zq*8#LMfNG9tCNbq)gNsr86&jw}1L0OQ0CiZP8S0!@uQAs{No~e9)7Qtu zR*|VKP|>1{{v2{1iPS@r=9i?Hu13^?PMc0On&R0dx#1FU+xACN$%#0h%N|@)>jOti zYvH)JcKzMUc^mCHXMG#%0Gsa!2_M?g&vO#^Ck+}qcNA@?Q+J=OhJaazq@Kh*->Piy z2bQ7a4u0%rRi6!Xt-r28ifLyZU9@Dwi9ewAOnozx;GoqXX3s4xIYDB9HaQUHf|yb~ zC>fA^``pW>J$qWn$4>Hhb^sz~+>3aHX(SLAs~GfdaEIXrS-^S+juIYACqtTvw65IJKC_;~8gXyzLx^$*Nq5$mhP=C_3F+nlOvZ zYsBL%BjuQICB2b>=My=nmFy)T!%ck2dX8uz@{~L!u}|zrlfiquTl*FqpBV$WM=V~F z7)I)tX2%Ey?mjCYHmlEa5YhH^-~WWnAtQeWJKs3(`<#Go*S{k$&uG`Sl1l{5Pr83 zSz&pt13n*-pR5419L>XKS<=;0@C+?5O4Q&@6>?z)OV6Nx2_sJ@VP`T4uc zT_#NU3+W2}3PqLb;rZC7^_D zG>j{Iy~P49Ax=pYxS0bY3lztkl_IigrNeDZnCQpV3NxXNt-HGf2O09WubOjrQb{9t z03`8Fk4~|4evb)G+S%xQwVk}#6e{Y-A(*L6I{Cjkmd(HDPB3d?oJuW2Wk`?k#Ym#Y z%qdwXYEWzHb`Ne4pe3klOEX^0nXccogYe%0Ng}ZW6-V@`PjoY9FW2y{{X+NDSMUEm zl~J#K7gwGRE9=V>~s(OzX(@Q792dMuHv%y6Uw!@fz!)&}R z8+3VY)~H`>F+Xg9B6o1r8;;O(Um`o2gJ2gQ^k6H;1(leHaNxMja;zeLE}i?fa#V3s z$2|ZQL>j%&s!(W^9*uyyCz99UZw2U1^!}&$nmfc#JVb0{+8mNBKCjTHln#ApfK+`$ zyYY>H-l-Gi4MAB8!qwn#GBr<1c>=>(dqWm67?^Td2EXfhU`_c8F$IxKl-wgo2%C|k z*(h3Tqo8>qZKy)hmp{N=)*1}Ym4030?=v+-h>U`_PJJ7b(oTjT7XqffxWNh4CEwhP z%;Z-GBK8z}OQYW0G522Hg7inBA=Hu4gWE$7o>>YM1Xv!LKdrK4SNg5D{WP8L7hpab zll++DwU>VI5>MvdVl_enm~VuDUeW2Z5CFFOXW%W?9bN02$_LivzD;8l4yukNFFOV5 z$TeAxTq_-{PT#mOMc_ z^)e^n)6`=!MO5p+(G#&=^Gm8$kL{R@&PxR^n7Ykk4My*d&#qOBz`Ptly{lBB2mGVO zYTEXs(Wn68bjqW|{%MD@``LiaoQBDF*Kq0O$7M*)sn5GuZPwC0=W;sl2%Q)=3Cpj; zn0NFMmTths!?V#_4xf9?9vZbRhMw_iv#9%R44(dac`zM~kSBxh5f!dPX@G-qT#JZP zxyy1t{q)X7t@p7zv*qtdu_+7DcV3S+iNKq`y!&v`fO_;w)}b_|s!liqAS^vbWJFI2 ze0ugKu;>k4cBJh$_Gkt>eih?SH#gSaKJSZ@P_|Ep1*Nn&r92^OyN#g8NB8=7_GO{M zMfzUc+qBaN_{0aXPI`l47{jyjSVk|%OJANjmDeYGyn`@ylY8C-x`iWrTdrSw@8>Xd z`BPVkO`{N0H{z!haL79SuBPOR@8)HP;G=F@H;!5;RqO(yS$K+9CN*hZl`Fiye=y>H zd=jVo2NIL8MG-UTq8U+EN8Zk=H^o>UFl_MMf9Iq`xzltVz z&=~MS5C{@aAes|2+P0_BPMU`{MDiIF+83vsmL_B+KyEM$i7%~)B z8~_07Vxfh02l)v=xSniSKK#&(*n@YpoSyECe zOkNSky+UEAP!Gj@)*tgQ?uv%3FB0aV(KrPcpB6WavrEGXbQ;}XEd{5?fT~hcZM#wt zzVOfDx*MBXwi}uq`KAx?0q!D(fqroOKC`xg!$~42>owrLCGPhCL{%hFaGexZn9Sbd zRr3~7jKqAPIA`r7JJ|?x;|=}Kk!n*ftX$m!j~&1TD;bBX;B1a)J}Gn0Mjt;(Psn`W znL|fy>g|-$1>Y>GpKGOT?6b(HTI}4=|5|Pk)S7a%WB>8j%82kxTyvVx1|)(d)c+t; zY8Z~y&O$UND|DS?M3@#%>m6MQxe>TGOo6(%k}9W7-Vv3Gymb2SwE#680r94gybdEUio&@tU)?7z2hX%QT-Z8d)PPsF zrU9z6xqBAS=}k~;KX`8%dYcihmKtVzFmK%e=tTj2)*44of^MJpj_nJRrK_Yw_>95L zsZ+|VDNmLTxgrs3`qf*NbP_brhs$DCY5&-pf{lGvqLur%`DSZvEgpLlM1FEG&n(52 zPp>F|bP=tM^iBgK4gSvmNzGa^QN>D+(WATx_Re^JPWr{*k^pun2}0%F6tYO$Z&sJk zJE3FB;A3jMK#Y3%XMt&|6Q6k`6vtLuJk~O8SIc#PykU2xh5d}O|4_X>?px@}CV=e0 zBZstiSse!0sKMZ}g0yJ$E)yg@8P?3~GeGvGS{$1?lh$M;%iDvJBUOmTPIi%2F}QaX z8XrGtZIoXNO%Ib;Qy8@Y4Gm1cb)EfNOxlRhmQvZ?e^w~`G+*#J(du$o%t=~Xv=HlB z{r3vd&RAw3m^gDixDuC$hAfv|l~bs+{ibD}R{?H0C#$Zd%C157&7C1|9h`ndY`p=0 zq(bxehqShqr5lH-=0^lDlpTKH9DA7Ne#izQ5)074H5VCe11TgDwvf-Q8L!Pq>f8Ch=BUn&7+XL;-ns(dVD`b z1<2!LT0A+4dvKT?ZwS&^$XEcCQC9Dss*}deKRc-OTq)zaJAA}}H(uf=SY|<5js*{M znx*#mNt_M^xJ}@sGKF;Y;T-sTi-$E>*USyUaw5MU4pv{@LYsm)2bUDF8;v{-2#aUV z#x2ZidB@@OVoDKxLx|9y$$Yfrd8aTU|?)VcYxqt{J zg5^zEUQN#H-_mQFx$P7`^;qG!L>l~#i;D(V`79i2XmAzhYeS&H&t~8~S}tY$Bg3ZA zh6;ZoYCu&;uvY@9E|Q=%ybwI=f%Bv(E`%JzvJS|H*8nWlKs`(p;D_xOvU@F}z`a_6 zRhD3f3Uj*lfPgj2ZCfplz^+9(*U3AhvKElBP2FzHcAyD1qz|5+>9uVE%mEbW()Df2 z+E2tDXU*yIsbVVkUr&p|)vf%^vh8eYj;+<1yP|kK%O8=RNLcIbwZ@(AIVkE}&3TQt zMicdB}kep$Ge%s zuc>(dPLA+ohsMDmm!x#j16SpOt|HY@Q@yxVB;YbGiv0u=)zt=AooW*b2s(aA{MznB ziUc@7AS(U0^*if!9Inl(NRb69^73q*dUX#T1Qvb1DyCh&Z5|9INyI$yNMH?FoQUDQ zv@y880t%5Z#ml?_{H{~D-=D=p39#*JCdW(_`SsDc7eP`e7`P>&hy<_gq2Cg~H8Pnn zcWPgdrcocc2GZsx8{8>N7srhB6tNf z!M*rcdXwnYUB5tq6BjGhnyE6?<3i3zfDQNFTEoe*kpOi97LFW^ntBftyiBM+W_Y2ZTlSfZvd9oEvCuXr$>B)O_eDc~WvxD5n&zLWR#% zJ-F?wq|Tm+kdZ=?T9j~OINZZGao1q|V+7|ta9_!<0AR)C=I=Fq!wH9nPm3?kO8AbL zo}PnR3;MA1cB8D2)Yd>#yqO070D#S>ArDaD3Yt%TwB7#22f&EHIB(NW6qTd{cv=ZS z1xAm~_rqa3z{l(5@18yjEfe@4^Ze7U=O{n^ zTU>3=H8d>>{HPCkYybSL^8;DP30Vq6_X})06*}br%CN_T7RG>vJ_-Pr0AL@b7fbmt z@iU!BT;xs;Y~k*rL_#s1purpVAZrFrJ6u-DpV%?g%pJ! z6^_~A{o>3bz+3#A=73jD0p=GWlDy*qA}Bx_!}ER|0)XQOh~NSMta(njg5q?@m1@~f zr@=jDAXv6d+Z!BZdqWr7DLLYjAaTg+6;gWu&siS&C_KVXzWiM} zbG2edxrwMvzNgF>y|_&rvUD#X;l*FW*xJj%vyiMD(8Tk#iy3aa+1v8u6)X+{W4>1S z^%l4I#<$@$c5%YQ^W7aS8gAi@TIo9!?%kt%drcSK>6fCPH?+7>KjaR+)s?{@d@(R4 zB3=y7$;91u1Uqs*yx)h3CxUSZKoICx)Aq<9gK>eK&yIl`THqnZM?Xaf`tLLT(yj8B zs<|(zjuYFsfK@RV>-bds{+cs<6>0ujWfHQK1DbA&LFCSbOg2l=#8>ONOmIV(asftsMChF{fu=uDd{Sz=mJ5*9jpF;k9`ly`3xm z3XS;!P(L&7r=I7rAp#<$Bw6srw~s485PALX34xqOQK=@#)J=_its}cR1LqsJMVG9U zmVl|pRzT+;6sI5M&tJ=xu2lF4FV6=X&|!u&sOwGe^ab7@?g3lh|Kx4jIti1pZK+nj z`p$tjjw=m+{As1TIA{>hoAgCdp~k+>(+0I2~3Rz9dhauT)%ne z_@9;!zh4f#*9eCcHX)^GN)W$3AzxTPA54x6RRUmgYzVLjWUJpqxW|G3AsGL{x6^=~$}zxBQP z^wjHJ66Zg7-~6}LdhWj1U!*Ps%33{HW_K##;9r~DzB_B2YqYc31}6$hxwk(ZnJV8~ zVtw_;%96BU!aLHDYwNF4O}7R#t&J=`AA8o9@@esf=eM<5;|l;4!X6X&yIS8dSHa%Y z=l<7L>se@iOjx%R zJrFQ?Q^fNhHn;1|))F#Qd0dj-6An!JJl`5`wGOv~V)%8;VHgUr#a5+6@ociN9izog zqp_$KuHL-dV!z|k02?l#^R2}}_r3@p4A3K@_ZmJ=*1c|kT_rl2d>j;(SGS*~B^htP zdG$R+D4VT-veMg{)G-_(C+!wZ(VJ3HlCVVTD-G%GlhZxIQ@HJRU57iGE45Dx?ac0rl@f|DnEgc;?Qr);$$WMX1zt?%(x z>!FQ92A=g{c}6-vhSPe+JvX>+;dp+iG{Z6{?-dYU)+-H zt=KzXA2T7DLoY@B>uUW?x0~C)uhz%6;5Cig_Ty#wY9vA%AupFgn^6L%{;t+djN)+CrMr`%x-4=(mOT+-OO}xe%}25t!2ED_whd z-``l6PiH;CGQFg!zlwoX1pM|}aOEHT*dZ_9T z(If7gqT$|gL)j-KGN0rXWaS}df5Llhk_7>LbK>V8bQZSmo}7NuAOHc$fTcO^;RYFI z8Kkg}1W)+UIs@S^>!)aQwqQ6Gxs-xtJeRX{Lw!3B*K-F^XQ?)7n$pP8l*Y-OnNhM? z3+8$p<)n99qG8zNH|han$yE)Q3egYuKd#oBGjdww1cooNFk%5&p)GzAs3ZtV5(8+! z{VC*=ETX8>+2fm8@&G+G5zY^ICZV@2cI~-kqa}Clrw>Iv2HgE=k`>=iF<+&!$OQ0A zTJm)-@Gywe!vmRXvX*3RTR>4KuVgtB8FK){QIh?A;DPF`Iz8edgV`vxXQfrkiAWZ$ zpk}b#HNdLE!n_f3*c4r}Hp9eH8PIM^Wf#JozC>C-9x>_6I~GhMm@mUawpNpr@TJKC z(GOHTVI|u{^K4UW`iWw*#aFae?m7fFoen8N6HhJfE;EIztLc(LWKEL%bg3)mnZ;k5TdGQgQU)X_j73m4W$KC|)Le>bEMFpghn$s~ z3r|9M0jY#lI2!E0l;;CDB0_+BwL?@0zHq6HXb%biW}hchZ4&~l;n9P|6$T}RrJGJA4I78kn#V+*L!d^6>#C2=OiZu2qg3(CG@I<-UI_i zf(RO=2#6SpbTITHY61ZQ0*2l!p%+0BqzIN!q}i|mf&~N=5EU$diZc1WJNM4LYt76* zNY+Z(XTSS>9@o~QmrVitLOfn}yLNQEY(AA5;<;dcw0r#JwYd8sUO&5!-d%rr{Tw2c zim-6&lNfJF-xum5-s3iCJbvRsYUs9~s)hTg>v(JNeH|Mk3PWfU2MD(F3tD`-pJvE^ zqP%^U@Tp+m)7XwSi)d$=L#Tm=9#>(|8dsjSs(p0?ksze$hKjW4k(2+9KR?-=%RgCX zDaM3tb^~vB0e$;5xLxg+TrEKY%b?FX=d}(Rzx959s#vR{8+*<|ppvB#`h;=b0a6nM zGY|Mk9!mu1A8|(xrDuo|&;zVQ0UH6p`HATIOIOU+F&tvIlm3y-0fy+ayG)7=Xr4#2 zUM2G_D0X?Aq0wQ2KFDXLriy2=iK+~#Rw!*eawbp%ziHDSNzY%+1eouH)ZoG zX~%GD>C4;x#+|Pool1+kxUf6GeB#yPxWTB)KW_(EZM=GN4jIisSO(fiPK~A8@@Q^% z0&PwHKWT3Ngv84Dm)pY%Uj+TBZ#a~_?DGH6+;0Dq0ED?e_XXVv@!FW0xQC2wNwp01 z5lsb$c6B_JDg;LlFBOiAyGL>?!-9`aPfZNQcC_CK3y+(geus?fx^EdCSv>vvqitOG z%RAw*ozri=rp4V}usoGGG5vO9Fz)WpJEzWWOuvg0@4xq4oaV+jf4+ye+v^q3N1wuj zv$IpF#yfxY@6Q)W$q5I{u)edAgG}H+sq9>G|V5=;mi{9&}!RcaIJi7>uu>&1$hk)#d*uB5b{s zk68PlSkm!X)~#>z|5ax>cHb~yJU(*O%hIvDEeN=H>+;SX{5;0U*^b#JzKnfM`>W?uZ6PEj-X4WzD4f-WzmFo|(s}qjv<{%~Gn!*PAM5L03 zR7CkBuc_8GeLE&?VA?-Q=#*X?)SK8^cxe2wsm&o{h``R%-#z=pl$ftJdZ=O}C zS2g{3PC5S~y7}{G8mfzA^ABP`7tt0&{v`=PR1P!`Nxr zTQVDO{yYw&y@{UN{=AV$f$ny^_4$5h;~lGRsGm0mgmw*NkpG3vrG^arn9U22-?@-; z>|e(R&Z)-<<2%mC|6aNuDWCVIzVq$XWrbJEzgN2ZzQnfP{J5(uHA_?|ue}>}rSWrT z`L3Pw$G%9M*n6P6n~Mkb-`(K9 zbmiY4gKO{1_D=Vm+LQI|#8*n!#>Q9gf7O33|JfpQ`9K0)VDfbP|FctGJ1~j}?fQGn`2$RiEG*xFc=oxP)zl?-ZwS>&keVXw)($;U z^6y4}?3>ke2+nEPMv63?UFlco@(`>2T|vZ~A2wGZy|A1C8xBb4Ds0&eSr#oesVCkr zm8+H&Jw2?c{Zd)f4dPm@Mqm@_m1VDSQHATh7cghna%!aIL@i!ob&fPB%+vQ-MbBrR zf|SLqriQG3Jk2?S!Chc)J-oiY*raDZYM*KI-U{GcNLt*h@MkhrdN^0W0_YcJp;MK= z;Ia~#RpP%V6;&f7M?B2cvPzc~u|r*CgToo=rGCzP>I<-ECj)ah57T##M&wWnl%-

    g$D;zN6UM+PO5F_J#<)}lV7F`X?ZGMh`pI2 zw>mRqw!+@FCvo(}s4e~)^$92feO9Ofoo>~5^TA5S_lmS&anWB9q|ATt^TkJ;O`4h5 zn3*}2bN7&zO$1AMpjYTBI!)j8u#k(=O-_SOAo1${=N5j?#eZ|^ch9p9&RPGc(>dT% zrS^N|T+?BN)%wMf)f<#^8qXAF(L-j$25eGGN?8sKLUSocNUs?Hk`6#z8bknYmK|&M zx0dsEC2)YcUtEO6KlDM)l=!YppUORHL4(FVda|1|giifap}LN}JHBIr(+R&22z$~bIDfth#U%?BRr~sG8%5--}M5IHImw^{)LWK z#L=2No{@@0Fr3mJKA*Kg`;E( z3GHJSi#_}-lb;HmX_*5R@LZJhDqsiT#o|n1(kmQ$a}wBtH6^9-JT>rD(Lyr7&}v9{ zgawFv?3R9B@g73FAVT&$xfDQ0>w6ZJ{oCCqM;yz#_|`QMI;iiYluA+yc-DZwkJ1tf zI-#rsAOuXgkUSNl`DA5KVDBqz45NTD%tBINn#?S(k_6&rzn+Z)A&zz0+G%uhTAvW! z6hg}?`jD7$9CUMS)J{B1dlSIaCmF;Ywg613%gXR>TvXt)3l29Uo3gvL>qEezPru61 zJIAA~VsoD-;o;IPw0_hF8q{LLy&Fp>CidH>VW1fh0<2|Uc)q14mfmNfHMCBJIVwkk zIR5&6{=u0PnXaO;U{SL3xQ(hg&zIXQSZz8jys{{;~|J`A@( z@h3Z9{VlZox%1wm(Kn3niw&m{uJ2?XM`x-0Nvwf=sLYMOK+W<7;aqe6c?<)%I3;Xh z^;6D6fbJse4anlTu+i=Si3#a8DxG`4C1=)xZ4G(i;VPAs6ruRp*4J|S#LlV6b36Xs z^=huQ76vi#V=pTlFWi3qcR=0q*T}_#pX;?-8zswC^;3PDJ6Pg-xMypdPQE-?ZU(_lp z1P`jtFm%2C0u>!tUmz|BM|uKN7)=dVem8ZOP!aPKTu+uDJ79OVH{k(;3*P_ zf|KL@7SIedgGV(DAqsxyFq)js3!)qrZ`!hqJ+E>P>A4&+9R_&`j|SIu#vj0PTzAG% z;QM?v*y&Sgr@?ge$y8WydXVG>pk{XNNzyfowVX!7mS49`!)d zVcIRQy|MZCIwQzzj}H=wUI@Qre0&_A!HgioXtO`dIdks`qM5}W}*HmJFt`$3{K=x1(2wD%+vVFaM*Y!p8iS;ux{sn8Gd zhgb#zyO7Jh_O-;7Z=q!)bSqj77(CyrR#$LzKuJahKk@m+p-7 zZs1SU0Ql-_I@La1v5R*#JCH&J99PEnJAXTTx?T0yAE)9YSdappMDmpzp%hMc7_Ne{ z#9SpcpFQrSYo>nMKweZ&gHF2Z-VE3=;KD)-Kau9{--3#41eCb0FB;nCFl ztP8Z`zPz^t)d|cX@$TVZF$asg@?;a3s?8xC&FG3v!csv6YF_(LA|nA!H93u2bPtiC zzqkn_uY%G6Ktt-0Wh$za;_z(a-fRK&4}k5pM~$%s5etP~0W?E33fcUV<7SSs4mj~nl~oe& z5xhYMXdb@Avmn>~!6NH#EXH5D<4zQYiy^z&ZD{W z&fjP-I5on@r6BcKR->w)WvqStM^RDY7Cl_jCR)_7a2 z9BP<%2pX_i$BlcNMCxq3Ddyz+L{<*h)OFvs5?avGIX+Yhs z`rw9T_vOu+M?;UYHxmRMav65W;;ASUB3Oa|*P;QYjvk8vshOxefYw1C>n+_!n|yG* zAg!Ey+($DuverDw`xR>)kpm<`-?`Xc*sJ(??9XkseVWEa;s$WxzUvRS2MStk0scw5 zWBq;kU~DR6#DNa%jHEoeQx#JyZ{DVg1m~JKbunRLW=L3W%KKEn4ZpzBl5i|;$y6a(+Tgq_T`S3gpHS^L|M2l{mja5 zcdXt3UUWAHS(xaL;z%qI{{~drl}+`qeWw9)n$Btbyt3iajb0Z zq{aty03k}4kCJic!j5&XP4_nvGjMAT^lTc40W#In&hB-6T^gV5_R%+1w&YZi&!3WK z0bh^;bc7NCRG@Te{>{DPp7I3+T8_bwNyb$fd+p<+m7E+n>K1_Igv@%THUvZD#49RA zAT}Q6OJi(tuvJ;4@f;iHN-R$udG1GjyoP;|#gZ>?p%6uZALmTUW{!Pn%J=W^I4%$Q z;PbRPx{?zXZhmz2miBO4KW;7&!Z8k3`j80TNB9uxpcZ6ArW7@zxSdPf}z4bKg(^-Xv907Vc4a-cErMyxZ;i!#NB3mz;MDi$^CtDzO4vgvOFyQ|x5mvy-)aRvUHZ%0fwL8+jN$iIhDca&s|#6>kiG1Pv89l-$; zr<&^`Uin=bl(|^%-1VR>ZcsdZZ*qe^PiOB1%0`w~7I3#a?QYuhJ zV5tp4C z|BtYBhwF-4>;Iw7`cK%}9rO9}--)jZ^u%vA);7^Y!T?%>_?mBPh9ReKi{Z3HLAgXy zzNPD3(b3u}O5AVOu#<0|9PXlUDl7tW=tn4EqySMVpw}XAdv9uEmOHIpIX!A_a7l!D zDHSg+x-$%wbx2?P6by~~HkZ5z$-cZCbmSv!2${Gmo=E&7OjZfViLe|L;@7`1LNtXv zdAIc|?(@5$EB^}-M*L6M+H_~Rlq9K-Q|uQeVCYnR^r%4}>nDCV>xMGnB1UP`Txrpe zv_e-w+ZAXF8Zd?0Qs~%m3mb!h@G8B|hla|Bj4t>$J*=q|t3skxEAeZqh5sZ(o0WwC8^dTmOE&a_&b^-DL|Ir8yz} z6*S*oZ4*_^(b**PKJ=rqz19vhJd01i1?gLTo${tCkg8`dx?(8TmRdM8a&0e|DhE%Y zf`IWbo?qC`qS-@CR_uoUOD;gaktSm!Vgz9NHQZ%P@$~(dgnpa26hg_)4lZys6;Nbu z(lz#cd5YRrFq^&qzYt-U&tHiG=;?CW3FkleBevU9++aQ=zmFfJ`c~1lr$6m9#;FXf zwkRG_t{U##UzOd#CDI)SACjW$O$IKi+9&e|*IU<@^xA2*jD`#77^L$Yh~`vt z%s8_U?B;O)Fs*EO#X59b!Eeib%=M5$xR5ei_#K z`b*p|IH2#=Cr;u3V3wkBe!`((QtK_Ribu-WTYKxfoKX4nk1?`npj|8F)-*uhW&}5~ z->j=Cv8A{|v%l%NQ**3XsZ;Sl$&$E;~siKwUqmXbB(Kc54of{tl*yKVFDVaQ| z14@?t@J3gcNrUGulfsM>cEBnfFEtMcP{u!ziUu|>`5PN1vWtU#tNNWs(ctQcomM_( zb`1{v?(z^ay0!mc?6dqUp69)OgBKj?Qw%>>xJs29Tom*E5Vga4_<`7Z%am-bvWg}j zPyj;~u=uR-!hEOj(K6cZn$C}f_lNH4H^Xf~fVx{BU`pAs_3DF*_O`c}&tm+J(ZE6G zZL<*=dQ9fzF9;!#QNGXfq~Q=Z0N)r~O)UHA__|t4uC@fV`^RAg%KGyw+fX2}TwV7p zo3{cc0I!WzONMWvV4Zs6X#N<@V~zf&mAMjUIzKtna0_!QU=@wLJPO;p%4g`rRbt}dNLSKn;atgrLgK# zhS>vbjGRB=+8lR3>lukGRiU(I;ZR5L*z<7m+HOqVVhW4{5NR*3{$M+~Ju&xuFEPx4!=;ty51&vJ+2b?ozt^y|B)WG-MDmh>+6xL#% zO3TJT7lax^<-4Y)ch4(z_2(-_?%VAnQoMQP+c%V1b+lYH<7Qj!NKuHIpK6cM!?x-X2-k=P|}a8-7oDDw(4!+&LO+`&}D$+ zNNGYT5f7z(AU2?0-@rjadcG4@{!V>bWh}$JFVpG`flz*~u=(tbNMjNgZVfW~g1-t5CX{=7bca->DXV`roj1C+GHNmAoImAH`qwY@#G|{4QoB z1fL@CxTafQD;1r%e_ehX>LJxmnm;_9rPUZZtET@xDMPrisX&~n;>o)nUXmY^y&S7c z=z3aEF-$-qOo`w*W|n@8bKA~W6^t^?(pG25p`LGcr|@oI*wIQ|xa@nObUIV)^$c>a zB@z9Rg3_8&eBHPj_2y7|;)|NQ5({tVT6QFhL1%5cEv9=9R|)KwZOz4aPQEaat}%ja z$D-2N4AsiJPO2VaCCtX!-IU~}g1p(!ByK~R;zBKCld=({*DxY8$ z6zV{cg#%kqLo+%_L+{KDr9#1Uz)7)&iY39qhBMtvmXZ>|uPsS$2qoQS$ z;9k>F*QW^EgKNo?upM66(r0VN{NxzVNM7m(x#uHZs7-GU8^_z&8mSz6Q&oEXp5Z~6 z-5g5cH@EAty9|`}OT+(UUO_n-Dd#9DNeLTrfkA1z%3&2M`MH7((&>rWyWAhpQnsiP z5X!2UG~o5ui1h+uH0p)47Qw<~?7>^bsofZBTAi?Y_N<1qCZB0P4to+*S)b7$;IR1> z8E_kxqcwE7zF=cA*FFJbm<))=ONb3~lw0+LmjoXls1A3hdwSms=SN^gga`Oa3*Q6B zG)0=7atedBN@PUc^6w%&_z0zF8L5;g8vopW?yetwy1TEzmq1Z-rR&q|VXoxJ0YR-# z=xv|B!H zYQ^7=zfelaw&a&2YGv}wBvgLjN$ro5nl_k`L2lx7rODS`C|8Ciu)EXY9<#r!BWJBvnCr0 zY((}9-MTu6ZtM?|nn0_Iql=MO8M`>8&w7dn6!|a|o+7*Z=8s43po7~tyH$?QNO}mA zxm&1zInr>cL9CFTmyhO4=I|6x^pkvf;ACn444>Lz&6C~j^;5}cYlu3ddMv12wEkcu zzexRTj`Ajqlgk%4%{lf-K7A&G*P|(0&G<-Uh-)D1=}d82%JnRgdxF%79zLo}pP4e2 z??JJn9&i;SdA|#0u&O&6M0$1=^Q@j7)l&9$D_?;_pHX=#l5HM!HJxqR6k*PHpFnq6 z6#V+2#D2{v-;IS@Wo6)CLBD}c8?72v9-)+_%t{GOz-}(y)*Z`=-~AZDrPC5G>9_+w zW&lMNTz|84GpRvS$>tSWdX)f6j^^t=2JnE=M~O(kVQAZg0<%s+e_py=LNiX7wgl=0 zbA!s6(iyXWD1jkDUS;gAPcc{&f0#!gM?iLNsb{nfh{n7ir#iP%cAe=$4aHwTY*x{} z36-|Cq%I3866m@trJ6+;&(Dpp18@I^p*NFFO_R;s^pw>#5%_Kv5%8RSL2khWy5mPHs%YdVJB5ETsXu zD1{+PYkS+3mtCdvGpb80=-w3q{P@jBuD1j)mmtT_zc_t=BI!QASbzHddR+3@fy!av z>s=xM^E%OufGXX zo&lcGxoj>m9QFX1$&fii*Lfu;9++Y|3Ae`~{U%e*C*jJb^v@+|`KPRjwY!^|CD_1r z_Y}G6(1B2QtimD;6-WCE%$CqBA zJ-RW!M~gOZY2WX{3(bHg_2c^k5%$B(V3*`mkgHG7K%QN5XPBB;BM-=+^ytPdCWDTr zrQ{#bAlRk((K~+VC3~XNW8JQ9+qUORZF>BG04dz`+`hLvj_f+eLS>mVtK2jLX6dgF z?1XKOq7wl<#isGqyWB-Bp$9223Sjq~Z}?I91{ZCwSVVkLa3`$af}1z601Q*I(rv&i zbB2#tg|7Q6*Mdb#dy*@nQY=fD`^Hi#wBa%@G8SK7v;gu5d>HPr>&JVtAFistB-#@B zB^y*FZU+rmpwps;(^F;T&rP0>8UdB;-irIre$c#pW-~1=vf%DtU=5c%QUZT=182N{ zFfay?wX2v!!vq!^cdar4?4S4v-~VlGRj8lEqVlPZSYmP;A9Jz`JshC&6B(?GLyFls zKk#9F#Jw=ESiJ6mXv(%RjtU-3(O-pCXUpU(X1ya`#7gyjqIdq3fluFP9Rx&_*;A&j z1i77;Ub9hWO85`FpNjToNW{*Q*URQ+(@<z0|O+Uw-VUi8)Up_$=x7#L%B9vT`3l z`fab59f~?}6e{o_I9b4FUGLIjx3cT3wYhst; z>jgJ(gX^J_4f^Tf-WS-Pq#I0I$c!-ITQE z%z)Lw=f`o|p@}%X!;P2Ll9g70+cLEnW`SDs$OB)-l?Lz9z;e#vEF;qRWJdX?y-XCE zKH&{BAfy;_mi*RXYHl#vAl?4hp1Y0G2cAphKB8xU4+@hPRcR@%!w}1gUgrg)^`y7M zfFw6dGhvf@+D8jUzz#NlAV8NK`*=ew#1g!j)P+(RDd@Q=GL<)II!MQ??(Dgr93+kQ zjb^T{O1NG$GU{ht&bX9*I9U(q7`s38Yv2X1JyI{6%<%?=N`Om|&@l1U>tn3zI-0tf z<>!+Xa4jQBI9_)rMPDNYUk_7R1jXak;3X-K=cN87@ScAQXx1%5#775QKm&Rzm6ozC zzsT@przfFzNqs|!)M9a#lJWkGgKYjAyFPtP`vU$#ovlw##Mv?evB&f7_B0+WXR3i? zEi$VN-N?0J152rreVX*RxrM#F-6=j%>9m>!u&F4O5n=zR_4Z#n}GqQEL zduxuJ_rcs2YJLFda)MMfK3}@b5XCbdOm~e<_x8AE+4)XK+&}nk>|KNv{3rpg45ZJU z@wb)}j>Xj*m13z;*w!3077iMe~#R zDQ^RSJnL6!3jXRBe>{xQNWm@7qo*`#w`$SBhc!?5_Fj(knBY&=rY1`d)8Slt%Vl1o z2R-fO_D^2M9TDWN@CobOevapTAJg{@1M(%%Y;N&FGnSNI9AES!p>Cs-&QBCbOQNE1 zG>L55sAqYo`p(QzrGnzt+_!A8vKubefg(T&Z-KXayEGnimQk%i0Zaqw0A3J2Ll54= zFo_cu=((z3uVJ_(=zI%9c5A@Wq2o5p34G~R4_|O)2LCXC;lyG9Yh^Qt9#z8*Y-4d< zct+=cNVpwv3z>^L(5*tVL$xw9V-H;wO)HjSfeGiBi4(t@)diY!M9+?)cEs(RtjK#X zmP<=KLin`~w-r| zWRQPZ5uzJuXA>{t{#@pLazu6(nE~jg`J8vd1nozNG^) zxa5hazkU{)+GRASn;x+U%w~fuT_B4{Cl2N?4ld6uO?O^U0M2gxJ`53WDA3PIgS3^! zHRWNp5;;#NDAF%SPPX_qz4E~{UBu7#e zHnssKD=UL|yp34nvK$GIq0_1900_j%Dt1Sq9Nc;RN3-9*xrgiZZ9i0sAA5P&x|K|v z1lvqrNWle6FS@nN!0Fpqg@YIfl+5zRrLS;^-ke|!!m$fX{+JJFZM>y6g%4W(0cM`$jsEJdPI#AXU|Zngk)T@S9(+r+ z_;{kGNaD8at2nz1^TA?qsW{$>8ejK%_EovXvZ*>xOOcx{%r?zaa}AX9rh~D5h+a8` z+E+V}sh99R?szFZB5*T8rP8|Sv$RhLa=^`}ERIO;gF9C&7Kb@!*eWA!02o@r-Y=%m zpCREa;l){JTMPHi_Y3F$)99Qpe(DI`$M(vc)@dEl>d|R?^etL=-@lcVW9Q-kx~n_l zbGr=G#Y*uBINBTM8j!ovI6O)EDy$N4S!GaULhwK0Aa&eD%Bbb`!CkMe zwh@;&{X&F+B!kChpKcpGvHS>y?fEw^n&rMPq`l88C#PL~*Q+rJ1&>SFq2gXkup=pm zqZvCg?~JDfG8sX&eAWYiSO>i?^{qDw9Z(TNo-R`)r3F;+ut%r?X|N^z9-m3;BvlIF z!ZlWwcGx7iHPfYQ7{oMTLr#lYKR!vAY;KPQ@swc@z?j5N!Yi6%2jGy~=NoY8B>riXW%ahY%65;3^I`H6>!aoX zT!RaWw9t{BLN}SVNWs~FFiacngoK0wiI88yf?Iq&%{q~CnRHKmS=o+V-_(K^tD@zcs1(QUaFo2e?{-_Qe=$jpNC%U9;ELekD zv~1k+26%U17B^Z?CY}AM@>s6ryw{eJRKLdH8U>2^MMQ9&=US9$X<d`qRM*u8zFD3dn<1qFAjaY5Qy5J2wCbh%0ndvr?nS25Br4ng&ho znBfv+rw2gjbN}1n@gKTr;?O=f;S)$Pc=AY0q$yv|qkt@e+4a>ylV}UOf#r!5c`B7} zc`V)PTP`-8n4#c_QL{B@e3~73)BVXTdie*Kv6!8fI~O?+fX3aitO?TBV5Wv;WoBK|q4olX*UXre0Md3KF(jWhOoWWe4&3B-Ei$3fdrIG4 zD9amDL(27A|7CicI0FhPJIWGYq=@QldrNLiDtUGWK4ouSzqb8J!|QwF#GP+3>QB5y zme)bd-o835A2XP&B)913uLU7CP~hz|+7CK#fN32foOi7{RuBll0pQKEJe+4iY>BAOY0DB-l<}lXf7-;{&9rFx>iltCHLFCJWOMA;L88V8>eU23T72ZU2;LW`9pPxSv8aNs)wpRMhU`aR}W_V47C zlY@pj0cq1o9)9$7L}Swae|JF4n3T*Ap503(e6G6P&5oM@K_Ot04C%<{+q`{7W-&`Ljg4xogZ&Es+ z4U{UH7Amk19S|Mcz6rj^n+yTvu85KRvZey|zOl}_o) z+UPCq1+UmgKe~^o(9&`4^)ZYs`M7iDp{YL((r0JTW~$`(!{{H%n%Ajymc$*$V>>2!* z`{B&i1uEkgD8!DgIpBKt@=qNO&-I6Na|M6wR6+uT695{&?0*Pw65KWzg~#N_ zL&~ch)JqV+e)+O?=lh+nXSXx>ykLMRjf6-$%D|ZB!9=-qJp;nlT^|Cxco;zH29EG; z`x8>62I$He=^(}r4_8_W0i{hDDEaHjBjxn(X`Q8y9uAg>T*R-+K0W$z-=S*3&>2W* zk%8JhL!X)BLOWS^W*-gaN;$t(O;5Mx55*-;oCW~-Nq~$#1?$_s^XKih)#g>_v^6*f zBd>Sw;P8om->UXt=PUmG#P0d`{rdLb^n?H88t(mBy8;N|K?x2hkB6yo zV7u^eV-DO3&pRT74&o6aY!hcZ(x1a~4({JnK%K>-)9|)2m(fKWzRR3{8P?+50dXc% zihG3|5Ar|83yxFC2^_%>9HB3qqTzQUL{R)SQ*s!Om8cMw_ttHmA$x8!Fr!ofB}FmY z3bFT?jRcbTK}8Aw3W-c;{V$0xkZb1&0MP)MN|Y>uq_xf?n-q6ko0Yh$DC<=W(FT5I zdpoRp!7nNT4;AfJ<$*vh(va7Je~YZHAo~&F^Ru^3auvLQ9gzbvd5TiW6?TO8JR?JN zG+iycQgN_C{cNRe46q*Ktv<+96;dKEdfRP!tJc0(NRxBynvJI_X^dCy6q1q3R0OEJ z3vePIld0ARA-237ncSW7%KHBJoxwyT^NsFV5+9@tZ1K)q29S1i2v7o~e2wy$dTPq1 zX;tuNO8X0V%PwHOhAVGVNv58FJc)>wD(y^V%kgbx#PWMGT8T^o3?m0jGMNxg-s;PH z*s3pLwZhJ`!g80&-dF`W66jEEtujE8b3VamNYr!?Rm~cZu4X7rdhboEwiB6Af5=1| zmRjYI@HCPFjkG&Q#bHo|Fj9$ivk`PoCQ}*e08wTJut{U8%=kI35+M!Z{t_FUGgr+X z5I#FFUsz2>SH2xladEAYEQQI@AXysoaHJ|Z+Ls*NYe)2xB>LH{&{Z=}iZ%I>sUX>n zizx7cv$(dABv%hruMetH`-m`JCQc#}wN5&q-^>2{KFg|pwjaPC zB5HS)T>;%@5aOdVA*neTkL_9q`Ui4LrC(8PQ1U^Du3GFlXMMRgWM1)wp=Dt*#4NO-k2LjL2H9PW`E9dBMsu2+k+tqanh1s_!)3xM@Y zmC@k=;k#f8h6{l8JULQ5p-6p+QYq3^lWY-K>DD5 zZoTdX=A&yQBlNdAL!v(6_PnHYEn`=pelQn-@dH!2d-OF@GnHX0o@7Jc)NqY-{(Z+` zz_HkRR?gx6GKW7NbmA@8hy*`@FRjTh5m;r!#U!h5&!#uFk&Ruvz z6o{sqD>c*(F7Ids0V-VUCKo^7x8pUW_OMR};3^C^wxm_*M?-`~l8ID*%Pwux_sJF) zZ8R{wj-K!~*AP>Ao5CqxYgoH8(FeQ56^kB_qG~ycS$AH(s@_fHcaR5Kv=8#A)J!5j zYg?;(JVa>f<08Y0JWs?%Gkek?aZl^mB&c-iYU?kCf|O1X1{4G6k0^{YTA{E}kWA6R z*y{}XHw}jC48=ALoz)pmYZ}hc87XQSStlt0+_V0Qb(cfi?O_^Ceu6Zn3UPk_KSkxU z^$)(RKvwhdFs^H!GFD&f$zWrYgg+b|CM**6)L%wn+s{`+wK-xuBO_3PXJbOBTgfF*#EE#O}7HTf2p zE&*=R!Xt-68u2ZwuAXBS^O(G6a)YNV2 zQGVA&kLo$jG$0>(M|kK-ekbWhl5o*Cq&7(KP#!i|Pp0mM%yqpToi}#e(~}*#A^Sv6 zZsLaAJ3aZ2Ynj(B%WvFJ*w(|NTJczY#gL0z5|Mlg`bxU`$|kMKd-PSvttyA~RnMKk zJ10}VR45(&_E~6-JWzM2K42w0U1a;jlbIaXJ+gueRLQ=8mFt;G0-J2F}63Z zn4?Lu794{Kt29sBN5g!qRc}_SREMf;tzbilxPX%?FSwJ9f%r|j3e-pQu~ukmX2x>u zQf6qj)^bf@#@7uGh~jPdm5hvtXgj)+mXcIaC4AA>`^&6zNE@^nu35~17Izu@SLyF* z-w=LJj^=7!fA9QJ@fh~Kkwm4OSKZf2yt%}CvskXq)flv^E){F+E!p9%VCpn^JA#1q4i% zka4^}r+8#?#A%Y+1%12WFa@ghI~$YNuAj+CKOOwO9<`vuNrv$$OPKK!^sRV(n!$Lm7(49FLI&z`N$9A{w1ew=-$OY$H-${UE8s7h4Wydqtbcy=Jl zWIknY*ZCk~%-F?KP7A5Nrhm_xvQA7G)Eb#)ZnD}=>DQT_?~D(xjdh%-pXnxk6b8jH zP3PZTmpI`4Zk1g(EAPBje$VXU(5;J4%q~sby7bQM^2b}3 zznWdyxOHXQjDzatV9hHeyDJpTE7iLzbSChM|51H2-?XEdtUK`L|d+N7C ziD})r!;-ejC+&#{ids=L9U`ue>kAl^`O4U+pS-MW?6Lmb=e?PT&&$mBfydU77k!(L z`Ck8%h`_DY%@sn?M2G|+D0F!T8~92u#&10~l=!ohxKF<}Y0g3C0wfhqhrh6vbmbzr zKI9kH5o+%xktafwYf)69fzLM4Zvzx!{Q(K@VKhctl=VHWup1jkMlV~BdH@GU{rQNC zu`|YGoj&>6UfaG{)_PX#InqEnZ}3$GUaOKRHja0r-g($4{jgRUgRx-5X&7B7Ao|`Z zXGv!p6_sRlw31EvkZZR-@K6URS!ABiLHo7tck3n3?*>*>4%(bN)w%V+DZj36H~8zO ziXBXM_Yd9WjktIq^fVJ5Z3--@Jl*&{9z{~}v;;!$2*v$Srzex`Y*ga=o(J?iL*+-D z$~Pxxyy=J~XN%fqAn4D zbZAbbNHk8)ww2~=60?I~mZn2@*`FY!<~GqvKYQSY6e*ftH^tQ=Ro=SPcE&fFD7njS zFikhr?NF|^@0*FXRQDr=MpV>Z%ux^Pn+ND}$J*08kKR5~WR|X%e*RdcUA^0r_VjHp zyV^6o(E|Dz-X|K}$4ZZNWL!Aea%o{OT|e`pV@JUHn&dyU0!-rbRg3(KlsYKse1RR?);E|k1u*-gp3M8 zgFY>d-L~r~2n+f4ap7L3QDJ!4*0=Sgsh+}X*S5D|Tx2E;tHNT!aaQDBq=+}G7fnbc z_hA*QSbdyoqvU>W-Bniq4icC30M0^XY=F<&%KEOr3GcDHLe7cSgCd?)V}oM8QKQ!P zB!X7Q?nzO(Qg-i&QW-bTi#4#hzth4Y>b`u@z|f9}pXT!S73xRTi%(TejF0T$1JQZ@ zHNfLh4J5c^sX1fNU={J)`{+a6x2q~`dfK0iAMN`xkg9I@{qs>4{*bUY%LI4Gc5J`M zg^95Pge2Q>i@mFq@q?r${>O*3C(<4tdG;TRH~)wke*9}O!>s!MK+I69lSqhW2xa|8 zF+)??*iG(pyiwQxP0V04c8DsNBsudU6$#0)*#+W_j1m_g8Eo{ITP%%HVA9|`>tGw>hxShz0i_LrDpc_9WL z{g;@*<7M1mVg{Aw<-ZqizFa51O43O_MoKpLy8P+}5v90DGZpldjk1&|Ure#mdb`LL zGbp}J`%BDV?^gaggDqxwo#_;o<+0ImWsUM_0Bj^n&UI5xReL$wphxSe@Iy> z2>trs7H?*`RlF_DyZT4W5Y4vWmt>q@DQAlrRw}BRS5_+P{t`1ZO`d;O-TLN_nBnWn zyILknd6g|@@LH`Ol6(5fXjtprY9q@``F+#S2b1@AEnzgxiHZaId(H$f+arlLF>Euu#A z0ev_#fCvC)26#wBL1)$1lH-~ad(p**0Q+(dulYK$xz2hKWZG=sa2yiP!f7sf^CHkx zYOGB0Lu*!-*7E9{HB zAk>*jFf*vRI?|XK|A8zKl8?jq0zeZ?Uh^Wm^+VqA=k0r9=YA0j`95o{0u*0;QVg8+ z>&xK5!xLX6A`7kG1GdTGEvPiE!KX_*WYqyE_KYv-EcrQcgAo(sqykr8n~)R{#X#ie%Cmv*7)^54w0rAZ$Q(X%uCq%G zQRcOH;)o-O$cV^ir%>Qn%$@BwMST`Y9|`cRB9o|SXfu6}y!M0{PHlhZr?_3w+a{QP z$S)$w+ZTVp!*Mm4W|W@CNI2R#f#Z|zNo=YKN!DSIW&=|sRSpFY9DJ2Jv6QMGswNX= zB8<7XtOo$rgg#}94U9|7`?vMSIX&jU3^}tRVX8Z1zbHevs{v0a-ICRjI9eIop zaRc*vym7pu21HCQn-v{m)bDVmOJ6=Xy`&E91JcN;J9G!6tkr>-l1j(=)uYIC9lAcg z58%^}MeuI4?d4tM$vjwO$#V~8ET>^UG+=?e+(y?ISA%mp8AAwOjc68K9;Wb08-4|? z9@rQyOggb!hz({_v51Tft5}(1>}5xtUqN{LQ&NEk?)&{Qo>?o*L$Ez1JfG>7X`-NW z#pRCfT4J_PkUVJ`LX%=YE1;j06^fIrn?y{L*JaF=V*H}AE7Fe0jCkx9WJKH&!F%m` zpJ#&4;^U_finRs!xvShBM1N-CcK~nD{L!)03iVqG>o-@Oawdo~O@uRd6O4Y29ov2E ziHtH4!NpGe(+Dm*F4Fo)$Lnd=*6OQ{^{tpT96x$};$g+n@8I5tR6BFRojR$@^F-nE zef@$_?sr%3Ti~`73a&rFr^(#r{!)=L!V@Ka_Lg_iP$0wuP~hpIu`u@XB)?l0uHdB7 zH;Fpsa7lUvs2uTfh(~Ca z9U>_Ekr4V1QLo`SnnVEUcZAB-15VQ#9C zD>x}A9U}fr-8|`Q(KE?c*d+1I_r|xl(z!iO;1fnY48Hd6pl-_K9VJ~)-zy7%u{GN* za2&Xra<6fi9Ubjc7y@{hu8~=lQXUsAxn2rHUc)V(_BwocgsD1Onw5dHdgDl7y8vF^ zzu0iddbiQ0^*QR?7X?vC&Ej+zASgR)d{T7?cYJI--1F#t9o@(nSe<7?R0h7VCLVv- zu_%592A<%5wzLs=(0+UI5T&NluD$o&>r*)+hjhVy>EKf-?>}Dfe}3uk96&M9mz{c0 zL)%h)mR5zkbkY6^!B$V=19$Zm0$v9&Lc2U@)76sywmY`|>9d_q4y?@U1Ql=1CFA9W17#^qYT#=Mq!sM3g z&A5h7XpfUJtKFP>hwu4+tP9LA@VsCw>}8mdk_mtQ+iFLX({jyHwBMU&+MQVS$R^#s zH+ppUAhgX~;h9pTHih(ft~;0i;@F~4QRNg0&6g@91o+ASOuZP>lI&^Kr_&*|DA54w zb4MiyeA?1FbeuMkV!vS|8VM^6k9lDIdQ#o;g@$ihB0gjH6$ba}7Wcfg}x- zkPJ}4uit%7LsTYA2nGgSJtC!gdgaTtGZC&xH4~kqr_3mzwkc{W^Q<%#3F44H;J~;B zdZY2OxbRMXor44Y8Z~JL`H1F1pLB&H19TQBa9qnHG?aX7NG%(Vk`+-}Jq2qi& z3|`-f2-kV+E~XHoUviN^M+-OF-}-Fo+7fl3Z^w64luN4VE=_>xe=uxNzp(#G#o{&D zqr6<_U|j;~XIj+_JKd_cvulNwM0VgbfffN`&}9Vu|RHCuoc-{_GD zcLwJ%dlZQYVgT?mD?ZGI5A01oH;;3{qt200dvQ13>p-hz$vwP6-~#e@*$qI12I|rf zCupb>N*@Dh9BnjI@gAw(8(Q=mTy4sbE+$#F(j^>n8ff{1&>Y z5)CO!Wiawg$_@f-$sAJ8hDGDOXR&Qlw$)I8!bofNNA|c&LHzOQO z=PAm7k7ZoURuG~=Z_OcL!1Sd@s+?zfz=_PflyojU#81rRQ-iS=R!VJY5f+LWEVLFS zi^~~{Wj87ku}a^wLS0}5^H8B8l>8k!y@mzISiCkAhlkjzS{yT*91$b32+z>vEhvvb zspVjtVdp%}L2E3)z&yqPMc7=jA1u)Vx*`Kv*5&Z9!+3lqb}UC^0gk1@#aJnOvPq73 zaPa<4oKLFgHWM%_=RIPEGnv_YLJ@lXJ>S+wRe}u4`+1eA( zxCp<14~!ZIakJI9K83$@mF~7Ocz!UTVgKs3!?OHE1eY7%0)^hoLXQUu1%D94b%mCv zU~+3FQs<>3Y5rG>BEo!%i#G}lnaJH7O3I!bU)}#Q=*}l;I4ItkxydMwQ0G8vbCl$! zN1OWd9< zOa4(t6D?2CD^GJMk616XS)gUCNN0%(Xb}?t7H9+jyz^jga79^8MMZl>l^*RV3x4wl z?x+*Sn}`H}+trpkb)71}qH+Oi&Hbt1ZXf@)cG-gga5npV!5!W_TglN2cdqkC_TF5( ziwqrfj0`=)vH-_sCg4yvz$}2a$Yfo2$ed)gw{&t$I9Q$3O!eZ z42f7$os0-m*GNzDvqNp5bAA{DL9NTviM|EC+sWetaFb!!_PW#KMZy%A0ATvv0=%YJ z@6b@cKmy$@p!37^p>&KR8T}fE0q{2w)EID~NOns|)l1?y5qh^R(ik*`#@oTSIoQ>7 zwU3>%Guk+%>oTo509Zn!cYO{>utU&OEr%tzEg_4_rt@O}H~!4V6*l@(_Pkz(8xP~1 zuQ&I)<3~zgq{Fm3GO^Zo+)m0K=z!Suo5$5#{15KD8q#8u(h|(MGxTZ8IoutJerwdp z*65Jd*xc6mj@HDdt;t)hG_kf6{kF7|Z5bhLS-EXF9c_6}+X}YY7-H?k`t2nr+e<^* z%W~T*I@+tAw%2U6*NJsB=yx=o>}U?@XwB_t@95}!+R?q$!4&K4)9)NO**O@}$!^^o z?&utS+WBy+Q?;nB8^LQ0VRd15B1S}gw_0kR!VX9Ca&I%c#+{2nYw&<_ce(x{ekhBe zdgpWo&ONRK#I>-t#Kn|h*H1tyUO45M@(}!)_a}NDEx z>KGaRI=ko7Qwishf<4Olq*EQ|#S#%FJpeh8hnRl)d&6T*1_IYRL5Hbf)6R(Zsd?Te z{G)g?u^s=jN!01?b%#Qi?ed|>PKj{~%ahr#>mrClKXY&p49WKg(_Eh&dRCM@nGJo- zWX3_5{hxB<@udX@5*0roT}wzMP_A-LqSYdwZymdzmYxD|P?<=6y^)8cYD5v{I3*Y1 z+Y8J$p$W)%BHD&B%B&I>r4=HmeQ32iPI2K!qVJp*e=tPqd3*|-P=N^Zcg`E!14;Lu zSBV`#nVOU{RN4IJthSJPvuMEl0!@{U8Xsa(=Mf*qIFF#5NB5t9 z#2VXMegf*5gLZSWVSj)`Zsc(k7h=dC8ElfEBGtIY**d*a`|*LI)a$2kqCO854oPZn zjX#g*R^LvN&~$vPlmA$+>#@PJ$A-Ti6D20tngmnF3A3;X^ZW_Rt_iDW6Ni6IkR_hj z?0aJC_~dxl6Z`xp4qZ=9J$rKc*Apj+Ntb<-u8xy#+;TClDFLTcOFr{mJzp4|mbNx3 z@cE>wRyIs17iQQt<(W4G_f6iK8Q&$*qKi#GraP513Y?xp*WQP#z2^(TLsw|n!NxS zZMQ$eSi{qOdUc#0Fi(vU$Iv{?TO2Sn=9$ogXApIM^xOGsr@bB#KQ|J60gZ%v7gvNF zAHO&S2QDOri_m}*ZR1XdQiPo{!irL_CQN~nvoWrzVrwaU;ggxY_W)X=c3UZ zrs9(SuZlN6-22S_k4_l1k`(U#v1nuX+V=G8)am8u z@a0&eg5`YzQgu3WWo`w4AmBgCPXCKc?SCpeb@suI{wLXKQ<-)2X^v*Sf5=Y%mZ>$K|7Y3h zzh!D#H?x}m$WH%brWQm8B&}NiH!?N(Xz9+@^;iEFnOfKzCG}?`g-8DPGPPhk(?rcl zOa@BpP1&n|%G9_A4=mEn<^E5Znh{Q(b_k$h-(;&87nNqY6u*6w>ofTFOs?Ogh4hZA zZ_5Aw&(!q3My@uD{>jvi{f579I&JX|GMaFEdfae@$avr4yi)@bf$yRLt;-jY_u(*M z+J}x)LHaB#(8~F-%kBa7V>kZ9h>e07M1cVaO7F+s{Zt|Z19$mUaH$Vae9jaNEUfVC z8d6<%OrCRw`VTOI;iMlRxo_~Yh!w3%p+$wC11ekH7&XMHGRtIG-qUR|7!uT$v%>hq zG8N*Ul0q&3%po)FUA$d@$Li+^Te}Nip4hurf0;ZL@czq`Q_QZbA-|I^T%B>dUHx^| zyXF1Yr#|;~eVg;2y728;;8OLs=b_)&veOroNckHEJw+0M(Z9ow(qs@b?BtI_>iGtT z(-4=LLNeYD@hYV!A@&}I>Wh}n*YMH-=$wn25(*Sp6R{-Z9Y*-T(8=J&WQ~C!uzfKt4P{z=p ziC@FzdkP>#^Ubf1-oBBE1xFD2Ml>8|VZ#t$>L(ffwC>?hOLWHe?$=6g>55PRt|5O4 zz(7^nIxdR)wM=Y3s#q6cwq|!#_%w0{y>U?l5dvZvUF6N)lk^du*v9Iu!w6K z{Fn*JNEnxnia5YH!?{h6Wxufx2@ctq%o9unl=OhA76ze`hxsbWglV5oa29W!AtgEinzL$lKTTpeQPH#+ zx;%<^>(yoTEE+e9fwyboVkH+1aqizBJPesf?M>yxAGa}vWX&by)h(ko>1scjlk!`S z&7uNX_3IjdJZa(Tn^GStDj50c&9mD&Sqfg>I<$k*9vtLNs`-)rA>>;kTA$Kud8B_Vdt=4VyybK1t-faIn;xw!k*0JBzj-Kw;Rl2j zcG~Z}8yT-|3LtceBp#pL)V#_XFq?UJ(NZ;@pD42rAnurJpX4Lh;8iKTSm{!7ISfzV z>KC9~&HC)n=%=0_+A%X2c zMxA?b0&#dA_nb#o5m>7>3spWfC;F{*=unMc=E&R|y>D%-qz{+f)*wBLZ|&1x9`IHj z#HlT7brRKM}SgIt4kB&$kiY#?yYqnb#&wkppd6on9= z)e~u>kQ7^9CQzrE`kf!UKWqLjKprqLpv6Yz5x8ASH!|8j$5BtsY~$%=rri9-oPfD8 z2Lc;K{DG$_)CL{oU|iq9v+?FS8=%_7c%CQyoXD#koYGznGl zd2Z3Q&`Q5)sVK3R!jD=9wI8l0hx~kn4@fV(F5-tt5?9jQroAPeR&C&6l`N{>Xd87u z{3+*bIoc=-G;dyu(O&L+p>>JQdHV2ZqN~3v!JIlCaZ&p0FcDdaB=Sf*evTq9aER|2d|zTg_g0sZJ!H<$KZe|G@3bSzsPl%x&-dKs#OEoG#$sShJKg~OPg*X-!pA0F ztg|~ON@G%9-!VZ`^I*WOBVETps=E}~7;h;otlRY%eH1~0J4wbaoZC(#pVix#t?zq> zZFmvERk&&9OIiM&`-&@#F*VyuM~DJ0OD0lE9|s?9uOR)X52O~qzqo<>@p!xVOJmRe z57)NiU+&rFAM5!|#2Wqn_GtU}7JIiQOaXN$2zv@Dkb=pgaI{jmrYSs|6iArLt3&0t zrwRsAg|n!ltyJ-8s^lgWFB~DQ6CrCKAr}~-kQJfS8lf^Bv3oN@RX9>zCsNZsQY(;s z_Zz9#8fh>cX}B3l6pk|1i4r*gLoIkq)_cUrL9&z!ayXFSbhgF!8fNoCy*BURG6{(c z$kv=QasDOfuQGjaAV#l|AeL2@1IY`*DJJ5hyEDIM)h(!h}KnY)6MJYjS z_aB`MzXAY}f*8ZKIHl;gNA;m$KG%g5V4>F?xEapel+$g?&TNwx&pdG0&ABhyq4ukr z$$b1MAwgpK44f(>Lc4xmfn5rf#Ctn>IUVMuaBi9^vvJPh(PrYFveVBFNWEB&eG{0x zoRz%Nnv4UJFbika6nwXD!KR0jI~SrnW5Zsc06~b|ER{I#5yVf1IeOfvA-I*rK;>rW zQxKL;u_~ouES+f0Y99Q~9OgP68piZ)wetWFxP!!LO7x0jat^mdiGLRr3xcRDw68go zj{ziuAbVDdJu_Z$yIfRc&8x2&y0sM5i~)Lty>x>_XJS3%>&~*%#HQ#l4Bh2}ecH_; zV8Y#DpC`o2K$|*68_K0O`i91#0e1)s65Jw>qYd$HDBt)iG};epB1-tYARc?s6T+W> z_QXY<77?=*$v{$5xJl_?FK4wp7|@nkQUnW>wsU=pt5kr3qqFWSWLMH%eC|U6P~~ey_66CdWL^8X(9Xi3runzI;!5yS;HsIz?YpmVI*0xr|8ify-rtDeV<@~TvQ16 zd>VWK27jE+OM#)+&fIPd-4_@FFG^HZqjQj)>576Hp139!5*%Z{<*#(8G>HuLhttah6v?{(_u|l&upAKYcu0fmgpO1 z$^optEn{bD8NuaQIpsO+<$1H^1wYCeq7}t@6(tT8rT@s(W-DrbRMd%9Ht1D0IaKm{ z$TnLF6{J_X!{R!BR5C@Y`t+&>9I6I`tA=u_hTE%d&fXqX610q#(UFdR(6pLstL~ID_>iNX|75*jNWJhom8-)wFxY>b_8R`HYK#8~ zL7|E}?JL~RNm3)b{ByO%AA-U>l{c^aKN1v?@&B5jc-nI2?$Ehbfqy3`_Lst8TM~bt z_M{w}JZxUwOO`PyFz`%y`8R^%dxM5MU>GCG9X#9g@V_G{{?F51!9gf`d;9Pof6Vpm(N z$a()0L9v+O^`ULKwDLpyYV$jGwZ)+F$Ij1_ULU(Q-&C@zExx|{*aM(d)|dz(Z+5kX zeAQYXm-gyfKXgE4eSqK2d;P93-`699;sLAc_wYwTjtt4Zy8FoRPqoFc80s<^

    IZ zjCwocH6G~X-T{Cei>se3e>FA5OR!rjKaI&=SRKc~xtTD4Q#I-Hg!r$scZim`vUiAP zpAtWE4cdgI8!2AcMUx2td>XrS*&Sj;-6+-a={SNk?HR~UzlFbl*v3P0*8rzzRKoa! zDT!EopEeLnBR~k?Y-GYhr0!`N4xp^TFj6Ha)Hr)}JJedsSTcl#RdJ>r&Q`|Fi^FUSf!VN}|VjU^*U`g0^6+Jd*if2zyV z#@>FUz}E{+#!HC^!z!ugk;6D5!ytm|5mi_gv&hlV%jNfo!WqO|-aV}W2s=|GO(i+R z)%Qi|)Ld3Xu%D9txK4}eNYK-Xi~B%7b)HNRnpoi3rn{s0g?ll00}QMk1sq^KJJfJaj(QUv`j5M3JHw zc>*YNXmxfR5KEz)xbJ}2d%rB03769zFehL^(A0bfaC4Li8v;qk^@h(OV2d08WSJV6 zBJBjYsY;yrz(8!*6V?& zw8shWM)POJ-yBl^Os6!PlH?Tqwn;a#GzvD(FOnvf54%L*`L_(r#dTZh;b7D01r>8? z5qFx`?x=95H5YWtCgr;5BJ6~L)uiOGyq_=-T{hvuhy4MA`_nw1-pt=6#A}mmmA1=O zro0dj9NEva1Khi_j6|F#M>Ku#Y$4ggA*8)+gwqE&ysUgbEhpoe z)zO-$_DBgJ4nrb-;7Ro+tZ;2M8I0G|#ycyy?AWiVuEW-=XDv=P=t4)H^Jms%GqGj| zcmR*9jlnka9=Dpc8n*K49(EW*=LvT1Y?Ly#f$Sp0jjNZxWD#*Msb{;> z_vYUmv~^K!+00QW;=sLtn`Y%Y1x6~VvlSe!XbSPWow4^V+5NK#Pp4LIwv+2gp^_>^ z-5k9z9s6XX2rZkkL`pw@U(Hg<<>}HjAwX@K`U3S*pI=!49%N9f2qU5Zlcam?o@zEO zs*$3~a6qL_?YgRy#p^X0Wm8F*93sVa=bl)&)X>ee3h&oQ9C5@ZXJUuBD$PKtb!56v z_1KRDH-xpowk5V8S86u2N#`B|d4X{`qC3YnyzIM*4nBg|UDg5ie=*V8rYu=GK zvjM;A{5qI0*-dh9pQ$d<`Jz;nSBIuKm^G~lSmAR3a~F_ePKR|KCg^trbaL`iP|Oa1 zOBjZETzzRL55qt69Sq>V_`x#B39l5}ij|i1RVx5c*yB_#TOV*&EjCEQ|KYE%Wt{A&WmJ ziT_%5E*mi(CSHk2b5=gMr@gDB=1Wb;uXj#6w(xfdUmJ2A5Ahi4k9bS-_Li}yy=%B1 zG$K;y?ynDlM~-1O46FOX7QvnNu_y)gz;5MA80gC^=6FHla&>~oqKWWRJV1|>>@pbC zNfMohp~=wUTl8u-p5G&U^mS;ka?5T@_)LILbs)xfc07Vs2 zu!oXkLgUGPfGQP^3zAWXn()x3MnswoHjF|+lY&g$ahoP+k_TkKrX46o@htQw_lVnz z>=6YiZVqwRq5UB*W43340-%BGDg>CybV#01NbXcvhif!u!Hcom^zQ$Q5p%&feEcy3GJ;3ox(~}tb~OP z)HQ~W5$hx~OCrD?5~U?#asE-u(8Iu3Zd?*iZ=&dW%%dT`x~m3%D}R-`2X&{ywE->V zfJFas*osH^p58M*ky;-ElR2D|2c>T;m&s=b-k3_c@xy-C&*>YFH`oxxE;dB*$cBcR z*`q-N6@eRjzCxygH*i62SVj4-OT0o9tQP||*r1^P71B~Q(}%zjG<-%oe%zj3;$k#L z!S2DMYao>HI;M=m?l9C>+P<%JUlkgx!@VSP>3&zbU&mAF!@=c_(-%o=h`^Z8uJVti zTDB>%x8_Ew&`F}FAPH&xT}f>oCe!C8>O@v_P*!YqR(xC5Gihuo0MPLesV-R8kDfRq zL}79sSA_~yBLNC6Gfv49!q`)gcFW;vU`|oFV4*w|YX^IFFIm1gr!r13+AkMg1dAw> zVNZVL`XWR z5)MY*R$%|qfZk;?FR%p{2)TSIFpp*EZFzwgA@op2O1fg9k8{Cm5!v;)!t(LL-$6=% zDC3qo0}(IyHHg8{&fuE;i=YrK;?*nScPRS#GEgw5NVL63e6~pPM-g7MSX!@G)`6{~ zE>_4XR%$O+nJwP^qgYk+rn=ruO^2IW!8dhsZtAt)G?=|<_~Rx~w8U7i#MGh0%t3HR zP>E%GiPdb$;q$wFHcK2_l58Aq9S^=`pL5Hh{g&7mx&X?q$Yh-2z?UgP9ICwbPB6H2 zs8Uh#C_U+mdx?Z12Lkzgg?;J)e3rTO0iQYE8 zr5S$>B*3_wpi>mwh8-+b58?&Tj6i9fI#{^-?OiLdPCOQXFmYtGA(J9(kCvuHNY0m` ztkFk>5sqtFhSC)(D`4qgi*sr7Op*HQf(n;wPDn>NK<(|t`&yy2GAIL|py&bVY)JDu zg^sKgJJK-XS(scA%soYj;vOn2jFF~L=4Q}yZP|+ERiZZV=fNlvguFt=`a`!0bxYo& zfR3m@u6fwYxIkV?ple17H|=6Z+C@+-C{+(ZS0HqxT|_$-uHL`-t}HPy7|OfnCsvm@ zk`>hdtsX(B{OoKI^(t{iq2cV05P5RFfnU9{Sfjdrqvpv*t?hTjC=;D`)3AV{MgpzD z;A8?rp-H=vAnc^TGgRAF9+E1GI2V|UQw=0g%7usx`}L)?H)8=tsr58ek%OTE27+Z6 zYo9y3Hq9vCQZ~B6Y27U5)-2%?bp;PiWJ9Q-?ES#?zwOsYu`QtV4QX;q{Co|3tP;Q@ zu>|CGWn?U8>zATjB%w}VEI3v^hMQJSJ18}H&xvLU73xDbv!LtlcXAUXcHaxD324_- zj}*>|2&kmaS)eVM%~e~{o1ZEU1wzqcJ7<0rcYJO~uD952bSMYI24DI$zuP$&(!n|2 zspO#JQn8cut`jp}HksQMeU>r%wCnj+*Zj6v_e=fm#gpA{Lb{i8yH`58SD$u&*y>&r z>)Fun`FyhHYe>&#ZqJX7o}W*9esA>v;!Mzhi8#eXg)%XDOpZ<_Z!qkZYx^!3h1Ai0 zyuR^PCDfnUP?gz`z7(L}k*xc!p4g!v($Q#P-*tSr5rANyuA)*|fP)yn0MTEv4y^+P zEo=(pT2g9x)ZRXTgJ6{zd1zRzce z0V0{TK0cAQvXGj+pjjZ~Q3(|~MfGt4t|Js{pGdn?t#JT{Hy4o30q~HqrL?<~2hnsg zmO77({nkh-LI;LIcCis1+X;eueOkDkTfMjdBaaF_4=8=Lf#y{qNxAlzlTWQ~$Zcil z5&>CAzK^gTMv<@_3~H%(b{Z4OfT}=hD>u~slCxKay?2Ldz@oz;gkiZ>-1&r&y$OM) zF)*d4d}vy9>^GnMDnb8w0IggN)*qypM_MKX(lde2+GPU``5=c!~RZCcow(e)*jD|JpKnkVf+BFOqz&>J*sa}pb9;-N)kG&`Ck(h zVUr&Dljpl8y`N29{59z#G3B>!%HMHHgOhsonLuFvll)+=~oueDU-#HEt_l=E!;#;53t#6mU4(*l%nm|G~b3_cPfS1k_Y7-3*&8%b%@~ z2zb#st2#DY^Paa(;_1KI;{SiFEVX8h@cxU-7_Kh-zgL$2+2R*l?r3iNmzOb5TaI@P z9pd=MWz4r?tB7k`9Dm>9C%HL{X04YD(g^Z@zl`BKl3U76TzXWnPk+R!{eN&7^IzsV zd$8v^zI~kk7nd=w{#Up7g9@+MTYL}pWz4_Gbw;m1aQ0=4X9nu9nc}%)1S@uB>7UCO zPYrMOWsEKf``_g{#_T@MLdx@jB}SCsd3LTN7ca@5sI;PR!@%HAW$E$rZ*Tpl%NV6A z2mY@vWBx_1<5v04moe;IXLs$dyvh%bzaiU4?Q5lXb{MTsc1(7Bee-S-#2PR@_Sns= zlSrHpu-1E&>I4ALX2M#(%&$~l5j@d*-PRQ^%~CpWYE{kbR|zMvW9KsxSpkAnd*Pf2 zifn%d!y`M_0uBzy%h*hBmM zDMWZ(57az7Z;UTi9)gQcwF1&A{Ol^Xx%uNb{j>*87xY2IDiO6UAPaoCJm1foMVG;V zz_+s^Z!7GYVexCnpYx62O0+v(b*)A76LBrKS0|ZJCE02UFeN2 zqv!Nia~eWJ9OypNoo|$P(AHvm7Gol0T#fNO!jk=g9(MyRqVPtmLkON?HGNqexKH6# z`*8qN4`pj8NeH2FdD>ptlK72OnNHMXU3@DG?n-h8JC|6~PsG1WgL?{dSXw~W4&eyY&n0(I3YK)8h;wKXN#LBt?gJ^N z7o>DZD8MHIS=T^-Kb75c>k3+CU_)m2M685fIUoI(O!SC<+N+c@y1xGho>*1k_t7Hl z>jVTBZdJ^>Ci~E?{p=ol|C<(TL-YU;|JS{Yobh&l=_Wk){pdIclc809=wgTr_-oI>ceRO3EH~33{SSEVzJkO7##Jf;lUa zVzRzSyW02SCWU|p;E0pvPR#BGSck{(y4%hDh7n0hlhwC-_?>PLn9JnP{ykX@x+hvT{S+C&BBd zr!S08u2L|?DXfa#TSaT;tKVrjlxt^=@kgC0pb5qlox16rhd? zEGSw1`0j9mZ4BYF!nu>zBW^^sJo7t5P18g^nz&lg*$yNHis`~Y#=f`(XZ(A`1K(Tv}$^ccW0rA(V&et7+3m zN*c@Kgr&L$MfVdy5sXDzIcj#A%uJ3_cLs()x^V^sL!Ar=@7g zroz69rLmWue>ef?R)ak#QSp{TZ?$dOKZAl?vU4LSog_TLXj^2V9{Vl+t!#IJm-hZg z%s3KP@K;Ro$K`Iqc2mFw)87qJYrTuBIAc4|6P+PBaOOhuA)c#v+D@YQn->JhzCxRE z>m5<$%7ht5H%O5xEd7uubfh-FxMwScmLp@`-n_1!tY-R5|Jb1b+hiYy`^Jng6MgC^ z34Brg@f@3V>7A;5wO-!zp66sj`S6Xy(5rPEuvb`bKYy~I#Ih4Qx1i%n>1l!b$2A{- z%`G!bZJ?;dA^euy$WHE;&xdb&I-7qRe!hQSH>X*yQ-S-@yVBEYLtBe*vpu^^=C9t- zS7Bz2hOd!yfQ^ZSinN~xKf--NT_Q0T=JP%l6J4zwA|Q7C!p5%*;~VrZ*VSZHj=n*s z1@%xVjNzt8V4Hq};-mh#fZ&^En6J=b29ldEBAG)+#4Kq6#re_)VmFOdA3~SB9Dn&W zT)mjO7em9v`(Fd_=kTf;ms#ppG=iFZuUF;|#o&+G z3tcnUG&`^t_!&cWP1zeUWpq{5^!aCGYcme=L31r0>$+mCn+b^%joStz&VfYKQ#VT$cc>#yG}!>d##D1(}@o^6Q^HuvviUs?2{(5 z#9bg^!TJP{E-dthXlm$&0h_x~YgFI-CRwQBoUH zV0+tOB2M7%*fa+Zy0NaZ2pKHl0|_)5dMpLuoJN{SYaaIp<}V!SPjf0y?@mF{nGjAP zqhkZ>p{UXX00ll77qLJo6OM+w;Jzp?Pi04+j8iPg-v`pp&TJb8rtBavjuz3TB1VRDQgpM^PGn~UWoKn)OAjRF=qlUIC*=nzCos|MMgG5U@!u*X&*W4~r`P?{ z7T-06tKCBB+8TXKZ(V&^5k8MC;34?w;{yz|3ygVT8@fuLPZSpU6>ff4{LxmJ z&(3w)6xq4XeO|bnYTR30+}rQ!s;Y4`bH?5c`W_OPz(DPx=xWm8T5FJQou?`b+_MI1 zvp@+V-+gS+xjqy?;Vxr=ku=Ur6kL`nXCnY)L>BuLbHQO;Vq@Hcl$)0$I6wGs6saPF zeYuIj@-f7GAsDv>hy1=Z_)%5p>>7jL8gWEVem4z_FZB@dg|lNjMT+hTJvm(&_zg^) zE-gI146^lMXTZ?Q@9yl1hB6=Rmcj4N)<3ig-4 zj=V}Y{4T}b=wI=xY}J!*Z?E(nuk0QcJRS=(6{*rLX5;x8VEuVs=(chZhQNTW4^{jk zRS*8)W#1!7;$gC$yv_pv{5}Bq03vH?^q^`@8<4=zRaj3Zs3Ms0H5$C2ydE#%ewMRh zt*UhOvsvE7<265mWj;>V!k)?rh-4vi<&KTRKF8N#^>=Z-t=kbIx9bGBq*w1T4hyb> z%TnquzSIFw$nBiZ605@qLaB-!JK-JICF-hqw<+*ik;b#eb$SO? z44yU;#hQ%un@mqOnT0f&=Qde(G+8}uI=t0H7Q17kf5-OZo#P>Q>~rrpblf@h^v>z6 zJ5FNFF8a-`C!5_unmuxx&v!I?KW+X=jk_q;;-}x@f3l_BruOPPLSSwS`z$7WtA!%g z8lm4R`|<*UP$6KQ#g5C^k+&Wp_W`b9GPs!+54(LHcN~+Vst@Ug@a}C({ju5D>s%lK zHJm?KC^VnE5*W*S65@%2^Q@&GlZIsHFT5OXfEyQvjNGZ@1aPc2kbvZ=zfSs|lPZQc zo!5lpYEQlUC!EO%o5TtDJHbkcw2p&>(T+O?+w)lD0@fbiji_%ET7XSWwf|V}a(H)( zvp1U$M{T0q`aK4SzU_8QK&C_GDKrcKVdIIAECbe<3mGyni3weBTsem)h@PuBpW6r* zG2@27jE?I-`3(+Ip%~CP!U^njD*3XWlfKoVV$t&Y1SG+xW31`$cYOe}+F+*ZtyGdU4O3M@Mk|!e85;`K=)LER8>FLH&4r8U} zPaEXuefJw~Kgv0CxB_zF8r&Mo1m>AMiGxU&9yq&8ytDN}CsfEx2k@O2S0(RSLV^Z3 zAha`NR1&k5{wuxqV{5hew!zSP5kR&&jL(A<#L_B*0s83BE9b5$PQaZ}1sC6cg~sG2 zH2|tu@aNquZ%Ld7EUf~%atcaThBz4axr=*FzZe1KGN1J(%esn(iIrr%I&qsg+3*5(whCM)BkYGnU z|DNky*e`4GKz9tL@Vyswen7NN-AU{F?f{KD)TF<=0gPnrI#Ki5A`LSG2<@}_V&5P= z+RGb15V@V#_|g&zoa2MAfE*dUq6{s22}I{YDVQalF5u&-*iej+>?M{A=O!Z`Yr%JbV80$8$iDkJ!XV?dJ3Tfsc=lz9C$%aB_l}I2H7=}q?fr}&m!31ZH6K>bLZRhn9qRpMeF?|NYlID`*+36KMzQ;->O4m?%r=-rEH6>x|ns~_kfhL?cuzDEE7w(4)bpU zQvWX$Gtr-szZ5ffCO7w~yGu7ApOyVm%m@`Wqc)O0v>YMQUO zooN6Ft5}41z|&Ig<4&F&5?kd2Km`OoEqzbp0zkpALMQ{IYK*7yf9saV6{L5Ou$S$6 zQFQ8D#oAsHvS*uVz%T(Fr_8=q{+expmw)<-W$`?^9Z8GAKBCDFmVR^ z5MVP0E-i~?A_3!+XCn#(Sl&WA#i_G@oEW?+4B&&GoV-l+|4shu6lq_?Jb?taWyVV+ z^aephTy$$!l1k)P1tA>{L@ZJXxk6nK@u35%{+o;+dS>o00sP;cLt9u|?O=Z>uh6|Z zyY-C@B#bCID+rJ{Kr|6|C=w%c8tEB0^Zw)Hx;do5zS9;fViHL&QCBxX&xb3_zgYy3 zoMLFczmzq6=|}aCru0)-11EQPhCV=DeP>1_WecxJ3z)6C8U!+CRPe9&d?^=X%sF(Ko{_DdPY7$^sl}#wCe2zODMTY{9e->NaD!D@e0PB&=N7d&M^{g7xvjZ$ zJ8Y&ocHD|}JtTa)E0c+D^{~~HZUR00rlIudL`02g1vfB*EU@7fO{a~`N}MO1GC=`6 z+np|ln#oN8Sd32T>iyGww?$H(s%%u~?g&3zUOc~8(UCcp)~D&@{3rw~r<7;7S!B9^ zl&HQX=;URL%VoEx=3STj9jp(dXXuh#O7No zOEs2@^%Bzj2N3n&GU#D@>@{YJsTNmuiO8%Cewpkw!-F1OQBMYxa+HCeyem1f(}!_5 z9l=}s-nnR#Lyn^zRMupVOGcT$LQBu+MDG;<8)utI zF5+9A_H5I!TBT%?Ps_wA$4&_Y@4JLIk^^^pGYrS!n|U{h0oD71$ot*BwYKE?po0>3 z&ePuZ?pEalamB;~0Gl|ND2eC}A#sre>mhj7=A z#xhuNPjE)iDlp+Z^t$S_u)6onX9)U1C)jR42Lny|`M_Btx&_C*Lbmo)u$e(Hz#fWv zw_)8LRNBkcK`#;@!1FnGgt0XC4vs32lSIAsCAf2~_;65Q^gET3ZFOtUTk8zs`w zvo9d+t@vxvJ5juEDdiXh#D$lcR!qoad%snQqi8hQsFGDKW)PW@O!d}H&ox6!K zXm;OJi?%(c^LT#9{ot1FjR&PvZ;-!}9t z1vINGs*>mru5-#F9;fa)DHJMpLtT^%+ohku6*Wbt*t&?fOewR1xz92LLYv4|*E69g zib?jx1+5;c1iyZP*tO4JZohyNnDZ;I75Q%cnN)#!CWGfD6>!{IKo=@B{7xEJ)vl2~ z=&yU*Z)I2B4tEXrZt6kDPbiHrz~zkR`|RYTX^PI`wQ`R>8w3^0kD(qot5?Z5h-%kh zf4TP_aCuO-Eq76h1-&nXA}Psl^Oj197;gh++laE6KlLMtV{H>*d?KRxlza<2mB~lG zk8}e(3)hHIE?*_d-29R^FQVa8llhLYpg^3gg7CKaO0gKHcig16v3GZpPcRH_sKAVJ z5O}nnz_5^+3AtZfwJ7a+6r=r|U?1)I=~AcTgS9Wl+l9}lFaQP?dSUjnugDH*%L6p} z*@3z5zA9)cEId~`ed0&q7mOx=6m(>O5g)!dC#e9JA3*1Ds;O)z=IYnA-Dl@SeO4rc zjJ|B-gYxBo!0YEXsK)VO@7MY%BOFX@d+h~QzIUz)Fr${TwfB=4$UoI#n!Fhza2>{0 zd6OaY27)Oypt+xWkm#$khXKK*7`P528x8WeL>CSNikxU!dq`mrRI`U&qX3bz7Lx|H zT?YLUVqlktGzX;GLMA!lx>#TfE84sXUf}?rg+Q=<#n=SemIJLBB~ZiSoNdKySh03u zal$l^92Dz55a;6(e>g1O*LLkMPYFGi$&N33fkT2S^chW9Re@f>0i*;00v0y7pXDW7 zuun*{z-+RI5?mk`2)&7oMXeIhu~;p*%;I+nQnZgrGtsnGhipb;a=#{WWRglvlFD6@ zE@{|!lNd5#N!gCf+Az%+QecBg@@1F51f&W+#>o|$$)t3fr1ZL^^o6Aij7sk2 z`Q2ivm<+^j=vpWJhvx$@5ds4Z?W67ukoCVtI~pL5cY8f^N&Q;k zRZ;Bx4liV-TMOC<2oxE7=nO@TLTevJFR?gw;lOD?Q5(T2fBUBp5ful(1j-(xOkpWf z;zfc4vZ!#T2pus~+%tuc_&rB-+7{AHB*<$)mjFfkqj}n}gChsZWE3L13LF985<}6x zvb1*yokf9;`$E!`qSq$`5RK&tqvh!K!imK4o*=-{H0DQJkr*e`OAt_{dZQc?#Yh+S z2?C>6izd>_9F_~89?c_iFSVgk@l!iYO&}tv;zhW^L5)(kKY_H?nF`5OLJ_U9vY%Wr zrc#M+j5XB&`*2nLB_)Xi5Ul!0qnwA!R;J}uysiQ{n$M*q`Rp$~HAxC<{h%aIboLd9 z1J$&AtG-qOdWK(;T!_!CuDQm{?vRZ^r(HynWAr$o*R^VIO!>Awx)?GFAxEMW7{$wP zYg-Iha$1lJw;bTJ-dJMn_^jER`e!|H<=+$`yS#+2C55M<`qPl579_P)jqezV!NW|*RF`u=Z0ngFrZO6Z&{ zphBc3Jgk-sGhMq~rp4T3Ex!^pHi9BTzVC@`5=!k->wtP; zFEqNV0YNAeaI2I*y-7C-dCyJ)xFc1}E=7SIsFG`U@6<(M1$SJn7S@KsYsAm;fyXrv z9cnnf>Q&Diye=4Y5e>U{Xc+u_+s~`98Oh>FHPEig*l@6dP!o!ynC=(6AjSdlK=Jl# z%|H^UMn#h`!s5#`LT?j>V$rNtCT&AU}S zy454PH43`5I=Xcxy7gANDe^sr<~>FpJ;o6|CIvla0Up-vJyC?3P4d#x#9k|pUh9Zn z+k#%Zj^6DPy*pQW?d5OQrgb__NUbwjYdBiJr{ku_#LfLHH$CP1yv_T3Jo*kt^!XO_ z`E~RKO!OUF>7&c{2b=eYc=U%x^oJGnpYG`YVnEn8!rqW3Of?X7=}9F$ll7~n0!|5I{s@OHt! zCkJ+aRIC0yIS`O6YpHqC@bAb$x$WfNL>hY^zYfTo{GXBotu-(HtK{Hk&;_mkWpdzb z1(O4fEP;PZ4ods~GjfpjR)8ml2uggFZD>Khbj&UK_i9zRXRco>tj{?1{{=bV2`=sW zi<~ykG~oAYRj87=_6HXY9X1aE$QXQRbt5pC;6!}#9zc}kU++{i3i1Gzf_L?{cj`lW zsYv?#+;y9K+m2Tm4nTw(r%Zz}06(wYQpgYpkXANJ&2QU~P`7dTw^--}Grr|_Ar zqzE9o6?G=SaF-CoKYDG=yNgY*{fpNngra#=iRiwmJrN*}WUy3bH{ls7`M;-QY&+Jv zdCEI*9~2jn?7O!$ucKg5agLuyw7fPz%ATHe`cHh$EE-wpXV)3q24Q_L(*FGl!yShP z0@vG!Pt={VIY3&S?wMq)v0CJzyo9Oa%m=a!j?Qc5!Yty~PJDWqdE8_9WxRCx$Fb~p z!o~o}7hnIR@W4;76_2EZzV$nif_Q-|;eC6?-QeB)G=4*RyjZioaJ+)`z|WJk1R0|k zs@CHDmJuK}*k)GXXs!8^!Oc+{fKw)$A#C}s;;^eio@d&r!)H3zO${6b;HroY=lJW_ z#X_AHGYt(t_ayg6&G0^}I8u~PK}z36IGsDHgiZr4;F5ZUIEBO}VLhkC;427HS#j{Tjv=#XdOqT?L5( zZ~&Idh({bfIAxNM{3%P$c)&m_eJ)i0 zB@eNav^_Oq=SkWMfLg)s*in^?Po>5ZToUg}AsA`>@&g!O(vD<$!2atVSY=h*sw6!# z!zx}b-{_ep1QmS1zA{5>*ibrXEvQIzYh6rq7?H`kgRgUe}6V zC*kxCNxbQ8_3rX^`*eZ_q+4k#HP6KO3c1Te-7-F*1TDSGYr@?%6G`)S33NVkT>h

    ne#5+vRrB)g`Sq?(jpGFv_p+<)6nN~ z9Cp~+nu)g%&85a016-ET``A*Ox6W=CkoEWiQiPzx(Jg>>=0n0+yB0rhG`C zUoIfn`WtZhwvlcf$4Y&!IyNwp$4yG?S{M*S-ZOlYh4gx7;j@7qv1)ihS!s`!-692& z99*K9lA`_3@1}IONB|aeVECBwIuZ6BwWAs_(u${D`nZ5(&yM>F*frN)=BfIKF8gke z9z+73)I%Ef@3*aVNpvAdZK!4E(5Ny!+0vyNI4MAkOw#=Tt$xuzeU?y9*9)@g#0XKNdxfT@OrcCqCWOoyJp^*Iaw#yBq&FgTR0qWyR5{RCD zTz+e+-HY@PFVgZ^m~&D4=Z@YHfq2u-+kz2dEQz{hkFCkMO~Nvmgs3Mfyc7MD>8zE# z>eizRp+}m0*0|50JU&yAI`r75(WnfA6`ZP5_7*qUu2t;S#gFGRHK5_TWmQ29LFWVE z*U&2grCEgY#5gC%MZf zNjD)|AtdqebopWsb%wA}5lvXGJ?@FxfHcANLWm${^<&FN7k$qk^c)-|yoc?kLWkv* zCf5bZ^ifz$5Z~}{jZIO)^=)e})-!Su5|NzuV@7fz$rp`*q;__=T81Xp=@OOIhXV>Y z5{x0HNa*1Bv4_@78LwIk+rHUzTm18#`*6KR*2t+KJnC4>mlU^wgIg41OOZloVl*So zzFZ^+5k9xekopLNokG6a^EH*k9Xg350rRWwDkJmz*z!lz!i}KrC5qlh;=Wz`zIiWF z7k{uFK9ytk2v9eFb2uSOyNmTPDQ`JB$5xi|iLgN0g=ce8nbT!68xT(fR<$7!JflW& zL1$#mNz@pDSBS`eQfM;|a8Ie0*ah{BW=y|lZs#2LK2O|oyTZ!;L7{yGQaYd+ZGfbw z3P3z6@6(S{ThhGdPw_{md2z4LQ~4tCW#KP{w*Xyo(^x}k)(f;FJw~37+F15-OKktA zdrDd$5=Ph%e<^M|6+lA37G4qHB*uQLP{Mteok@|*VH8A~GX-}-Q`1kbU5VVj&eHIV z`SM|pmm1^>T>P%ec3iCXglOmL*Zy5UKjyEl%VR5hF^DCJn`G zoQbgxi>({-!Zw~2bcnW<(UhS_8)IW}Q}AVA?554?#`))OnfnA5G3Lx}5JHhWkutaw8g! zmwanWUaC~ln@>e}os%l@7ZXQlay>vz6;l8(X5vEXZ$nW`!_Px-E^G-N_QQD?$ zNg>p2L5p4u4<zzG(^wn|lm3Q@jh+FBrpR97j>U*y1J>;k02r+#_vGN;h%~y_!>^wN2UF;DSe7BIWuY)D zy_k{*p)g_|oOocavIre9(a3mc3I{agC@65V5DSHcrtxs?Vmr$`Ivl>LMVRmb*JXyP zJ%k4UN?7qdSGmtPfIzu`g7Xec7>`{z=nKK^!-L@pCM0In+doAf>@y>5F;brK!uBN} zy$Wk@A&cyPNnCX8pf_&`NGZh2T!ppOc>=l6k8CK5UWRWhLbuDg@JbMASWF4aLJLx+ zXTh(K>)_==5~O8T-bDs8B`*k5;U6<|UlIc)2nbW+O|az?WRPG65h*MU**rN;EJZ9! zm>eTo87t@prJ5+1`Cg0|uZa9s!H}(t9*?wR5tK}zans5khe}|T>NS@L>q{~v+(7Z_ z%9{)2JFY?wY%J3giFCjvv0=4_T+~B?x^ZZpd`6Hv|`#6Wd-$7Q$RfFt1o zaHDS5xAiCa$X&M~T|gy+8&_Jb7$}$*=nJNE>rq1(oL8YBw{GmTT=?FL+wBNLnh=MR zu$tFUR|3*4sL#I<9Dy3tJNb^JI^lfTAH+t9nw(Cz#=f9NnQM*m|8sKCKU{BKQ>Z}U zKzWj>G8Ot7AVH%7ZCir$W!lNG_G~LL4r@V9F=XxQY=vAAjaWr?nd3qMHjQzT5wjob z3a1u?JueyB)yj}S;vmKf0ww0JAVADXDs;!J`Bg5&tW0n#sU`*q*xEI~)|HEP(3Y(Y zm+1!qPBmNxy6kzy)*Xp+hc~jzg$*vAnJE<|T(a6wcytQqi0;4FO8C})>{$HzB;o<$g6&@ttC1&0w;n5|v zqOvKtD|9GLHbQE{_&+BH&OtZyn6);+-PS=O-Sj75ly(a^~JVnsU;3r7u`sN*(Aq@mF%-Uv}AB z{vU0c`fz*z?qOqB0T3&1%jI;%V8yjO2Dl|X36P3i!G8<^?zZ{-iVytPAizJhY5ox( z_!|WH`$EnCBtGzu3pM{rd_dIIQt;!F^xg&M?i z&+iL0hc_bL_S{F7UK$_6AR15eP?goIS~WhQT)RO8>TdNrpT@b_cdkEjtOT%~Qrkv0 zYmEhAWB?P3_{PED&krsm$jM@;tB1`jQ-`u%9o>3Y5!H3^FV+&?fh)=6(peFN*GIV9 z?MqR*7V~>EMt&%u4Yg6u=F%uXy1@&Ojis^@D_4en>~UhryD)-wK*9|^N^429t(BB^Ty0h zK-BRt(dm;rUn;Ji9gynHOM}MtDy30`1s1DMOr|`~TvFSG35Qq^Jm^P~)MHG5!1EDf${x|C|4Z}l+klZlZ zPrLecmA_R_VqjymgV8J^Na<9A=-C^sU*0?WFh<&5 zZergzi+OKEytm=S;KGM5$A{)V2{}(o7*ZydJ(Yt#6(iP{ZU)TpX8~##L4w?dcH^pe z+VV%GlslP{st2E(anUgRO37LHEm~tcc7S2S-k>ulLb60j_j0?Ki~!QTZ6zWEG3};CjRI9}1&TiRzeyA?09Gu(4ECN9KgxbaO^_d%d9smI$7pa%ojgguU zorg0M^@Y=IVpC{P)1$JVeW!L2*zGWXXn-2MAdBoJU|N8K{nhO&r_HP-y zvf8RI!%v}XePw>OcRN7QW^ZsPqlL6?5Sf23^3+JhQq_~K;v=s9T(&Z8{};frI#xi0 zphQdI^roU1F7o17R0{Wgfsa#}*{lYQw_Y48rCN+6_Xtj(T2I-3uM7=nY)8h~7hxZB zfP+K~*5ZD=Cm*S%U^_9#9%j`FpL!}kTS}KDko8(zZ$*?*Z_M0}j#aJ^+A4eZe!ErT zN*TxPL)y=zyq&QofnI_iux=OxmAkdP3KxFV<0MKgrYIdR9fvam5ATlU?os{dUqu7_ z2XAZnAl3{>ngXQJt`RKiz;vO)&dNI%WEh7gw$&{Gy#Dj%`ir)=cj?XK=}KV!ZqJ} zMGo{0kl_2W&3GSV^PaNvN;>S9Zo&lIcYWaWD~5nktkQ~0lJNH4w{Lxf4o523ikj1{ z@$8F*v>;F`=QAzUWIUUdf)w0g zd`AkJO{RYIK2xXw81j$BwJ8e&^iu>WF`cLgp?d0SBCKWNd2MfI@b8D`T9_1Nh@XE% zP}>5o*lkNoOYk6>?;0?W3}%S7F~tCS&mg+#y#I-%x4VnFuoN;oyT`*!Z_zpXgkhtl z3~&nHtaIQ%M4EI+2kHI&Lc!?k3}huw_#%6Zy1gE%P`Wwmd@A)CkK3yAlKysGnts@t zYxW*zeemY5SpcdDwUOF8_d|dOJ8+=1eP+K6-J-S{(*Xhl5Zg$spiW<%O}aZqKIrK> z_^u>DyyNPeeU;(s;+W^D#W&W}Uj7Y+_adnrblLOV9BQo_A~4V29RB0qy{dzJ#2i=(6*Cn31T zx8qLKs#%1ypiJ*;{U34N2M)i~Q$!vLy#TH3l`^2v0nZ2%depjZ9hFD>(OswDLMY49 zv_SyanL(Mc3=C$91n?Ps%ypu1+fU7dPu3iIc+lL}2J$`#$atQ35ltAwNNwbx!8Or5 zhv@rHEWRm2FV>4cXo>>%uJg1%jWW=)9*jYD9bY#psY^#v03$OEdD;_*<|`gb)mgX+ z-9HQssu7Al#_n-Z8Ebab=It4q)?;xIaW}=S>2dgyGe{b8<9r;77JsNxMSxA~v;z8j ztY3DYxEU&;6rXUcIl)=ta-<_W0Tztb)JVB zsr2gLP!@*8KW-zu?tO-j%Uea$U^I|Ct31x`STP{~>kRG^8` zIdqp+tz+cOWivDJy#kfzoIV0d^Bb@(C=v_` z)S5C)DnI$K7;dr}>w!wTay+5Zb|e0%rL6{3k`Y@gsV$lrEBS=IJ6(4TGEFBl6*+Z& z4rAYHmAXy1R$)Yz&9_bu+(LO4%I#|f~6J&)^w&J4ijXeP|d zbZ4rkK(cctf^b1;5i*s@v@J#8)<8IEWS}NA(VY?G8g79E zvJW3c1ceI`vX5UvH1%g89kP)Nrv;`!&R3NB{IO%M*+I9I;;XXuC=1*b5Wlb$Is|X= zNeCdw0=c>HLQSr_rR7`ozxQyQON49xuxYxI_5)}shdkJ+*!+i0vr1t#8FSyXi_mLRW#=5I9II1nBzxw^WI2P!32E<^up9e545t;sEk0AN~k{J4$afi;`Wp z0X%pF9lF02f)N&50?ND9zzfXrWPm5yDJc z0Yda$g(P5i@i$IhX|W{DLFTsR?OaGa5BfA#Qf&beJRuC#A=9SxMky-G6G{YtBwlIf z3mkq5r%Wv?E(I>rsi-O3(Qqgojt_9kax5?y2`s$r>_UOeJ)yN`P~gGx>hvN6n1psH zg7eGlQyS_i*w@ z2!+pcD{2g|k-UmWQxyzBt)I&k34WTYt85P$=u)zurWPAKO+m_WD$~p~ceR(VVN~U6 zX~IIyII$8WvtmiPI_X7)f~S5-Qgu~z_0-$yG(#lsYK zxaXR<_-h&>-?@omjbdjsV4-GQaHEWn!7uv|iTm?4q_v)_awl8PUuDhgU+hDshDyK} z$e2xsYfP%E_6Q1ukmVx)&-yjm>IVSeFA^eNuEZY_BGReN`RczMM2ue!qFqnb|8Nj7 zqzMjZTIjHYha0+Q(q)q z8wz#*mFGFO4Z@y@g7Z9tGNf)A9X{7YXV3Or7Kr%sLQQ_f1rj7RU-u}jsbrfBa~@}z z*B&Z{?u|v8<|)X&YY!U&t-*C42LjdxgeQaJ;H1sS@o9ygG)!<#ag962{jNyv6F#nri4^v*dA&W z6xmEn;xVX3DZc;xhR(-|&)dZCc6OWYbo#ugJ!1FEucAOM6iiY7G*m5Iu>J|L%h#|= zB0&Aa>8^vpg~Zw}FR{+=@4DQ*{gbu3_c~%|d|qozX@FR z@A>N8W%e&a0GEQBZvSz7pkA&i;IHw4@qv<%TJr4aU-5y6zb@1W8g(G2E=YI{08kls zRZe_PTQ*7XM)U;u)Rn+iho0p_7{)~vLd}QU7m*W0HJ~eUyMx4F@XM``9OF3J3(-3Q zSdyUIrX4m_2gipL!*%*UYlA0m8;cky-NoII}Pm zTg#dQ0QHX2VSm_4G~@3t=IO6$-=N`FbQuo_bA~Vx@@-Eqe))b&esyEvIXqCC2fePY zk)_oCG=*;H+`hh0IO_UP(cqr-pB8FTz4U8k3vGpqCj}orXM!JSmlSj_38yugraT@q zC_6%JM@*IBnIqmm6p}rlc=Q2szg@-gSzJz2t@`$6WiNu*DHR<_bcrkM?2gS@fzr0+;6_4&{@|f z%~qMXH4ZP7{ajJF^W)K`nxUr-&yGgu8|jk9S2sRwNqNZMIQdlI7RlkrS|Pw`9u>E3 z^5p^wX@E!5TIW6}s=GgbnTDP}_k4~l2ymZ=F|t>56~F890WJ#pWDi&OWp(a(lIHgV&8risM+G_u_b>y^d z(X^rt*jF{Wwgi;qR^MNKW;9i?VtS%h@RjSahbF=`gPM;MwI=z?g`yon{M;9x$am=g z(48VKX_a!!4s9KwO->+k^$K0%&+k1@E2pPHW4 zBb50-t$lBveUJ>X_s@O*n^G32^x-#v4X`ukIXQruE;O9-qI+DtFR@O$UFwq;Lg{e7 zKpOa=v36tf*pWBQa=_LH?Y~tqIf6kC)9XJ{ls*}*ZvJF+;FEFGCzIk&W}TnRpMTo4 z`iZKvXt8cFCP)S_+iqFv|W_UDT`R~PM-K09vy>~!GsqF27cvCqj}Q*KJccio@& z{r1^w^ODbjrNdE6=alafxJ$3kEgf53qAPs~-uxwGGZ9b!a#B=gO))rCRWMle9~Jyv7375Gq~)5r=q(eH?#n&*nk|U)1J_RJjg~ zrvTr#U&fq~zX?atTG3ZM><0C4q)Eb2EK zSW5wM??ndr4-#bj-x&ckBw+n0ricV}+S)7yk9cG}HhNStK|66x6-oU>WfkZSg8QzV z9cnaYE_6M?5Q+^jp*ls)If-M1plb^j>DIfg%J~Ry5Vy+yy&^(6uV=~ zwRg(hIAOVL8XJu|3w-EtlwPFPO54<%y+SmS+o&7M0-$>i*pM%GoRB~*1Q=aE(O-ip zcAUFCyAL7?=}-n0T27>#m_r8vJcQJ>_O-wvpm(VnQ`8>9NN|8(nDc z6R@6BEYg@I2f5ysfQS%|K!yX)X0|}M;Q+MF0FtD`WyVn1F_d2HJYKmw`tm!vn1t;V zs!H=lsHg;ZUY@8%V}oh9W$EF=}%t8V5ahBdW-*TvTY9ES69&t6H;GoHCPn5255 zS7CtKbTV)#(HF%Nlt|a@_e$G0Q&TFJNn(GJOiMg^S7nJbXn-xBWr=S^!Yi?eXf_0d zX=A0%(_`1pI-C)FPi(N~bVwUdA27X}LzAe4gf|%mAMF`aXj^A#r8-PTY~M$tWHIAh zK4!3ECN;J+0W~`wWF^F^K{Tpi%7Q_Lxlr7iH6NL1_T301;nE#E-*%t%vHiRzWZ(NW zkj;!RA}85a2n5XhtcSwxr^w%@AC863O>*QXA`N0TzAy9y#VUDLy?twoWhe#AZ{C)9 zlB<`i$UZrDGHkULG%FD|V)2XODior{x}9Rv2jE3IOuH|8g9)C4I`nAcac_VcufGop zJ2aOUemli@!Kc}ZWx1M2i=IysJ_Vt+95%JjxLuoTTt4+)strn!y&urfTy^)ftMQ@m zX3`d`;ydYiP#n#w`1D!?D!?=&825SS4waa3EwOd`&MqLOcMKp?-Pn8e{7cr3&Fp!u zdY$Ol=u>&uwno;F;oFoPwUk-l_T;pBh3xbN#KH`9FGZgj!7KRUKL9Ro|JLW~q^^_b*1dPdWxRY-bQNqYrYQ8jQ%-MN zSc@IA&>`<$ZxVGzHpmck#`?6b>N*7xx}PU!T9CBqmfn$6Cbq^Glo`;s#1{~pNk}ru zg`1$c#Q1U3iqH)(G?zGD59?eaw-*kOP{A(-bvZeV+%D4bl=2r_e4x`LTi5|0z`Q(M z8<_}31>lg%-v>nARnzUsO&CC@v=8uAV?Y0vEf00ww(5Rw6-{M-2IE)JzKV|360C;_ zEGACcX?Fi4nn9c@FECB(82*STHz(?`Sd7g4JHl|cd#_X2l!y}7CFJop9V}!OjCqFv_;i3VtEd^P|f{5oWDF^WqtC)0~=7i=?OH{IcM9C(* zV|vjc>veWBxqLV~G}?NynZ))i^)k7lWO8 z<+tnf(@*u)-l2Da>9}{6f>m)Ls#b4f^`-VWC@!lj|CXgHVP?5vAAV)ah9k1!0dIQL zfat|Rkv%Bp6`KcF%tv#OlPlB;*Wz`9argb!oLTds#ra#b1fQhPishV&(#9FV`fZNZ zf}BP?(`YmK!GTTBJ4iof-B-VjKDeR~;yicVj$t2!iLsOPcksORZuA#Y>1fKB(RVhmFrPL7t zfJOo%MiVk##K(TsAX8Wguz-4$1wWPkN=eCQ;?oB-{^q*5&?XlW1{q@sWQ`<}ZBj`a zR9s0Ya}nPRAi)#J&0M508zJmHxBfwN99jY6u|tGAAcSl|N34sdBM? z^N1~$$)>BU0i^CcLLVMr9t1DvB)tt&tB?7s>c;*rsvApj_QBs(H!`s521q;n zSJjPVkg!aZdct6m1o?qo15j;c+M|ZJzy;B$j2mTa%?>C*N%EKxRmy^p_`R}U-WsJg z@QA5GGBIZ(>?#6tvA$v=0Dz}Q&}Mv6Zz;>tLAV9Ao}Z@1jDo#2XRhYTm%_tmY^4RJ zVOw4$PMydAi9k*xJU67tM8aZ!L#6nEe?B*49h`KZSU7B2_{gaOSoC7mv}oG3=yiC}Om5Na)uQ)fMRUtV^Tgthrp2(OXeqq-Yi==YDOwqW?bC%? z^vqRL4$6%qaGF!ylZW*q!4B$Q6W)IasO_Yg@R|?>5*y@5n#p&4F(q}O_0w3jLpf+I zu+LdcgbK=^Cdhj3Rc7Vrj+dmT#YsaXg~6DCFZm)vUU;}*ssgR8mUlHNU#KcW5J0vo zz`CK)m6XtsX_qQ*n+)0h%p@pi)H24v9WvUf3-t$_lJ4pmc_N2-qneO$wOrstGtVIYN_7O%pxneI3fuq@>5bGHxfopT;ghveOc)>P zVp%ym?#LYwyksVULo`;&x??s$&C*jXu0rxH2f=jvMl`KSjEtL1t64J5G2Q^JaVN-M zQwY{BmSv~}9BjojT{)ty5G_}HMXUZdhqf5^i`=VisoU(;zY)G506n^*6&1a0x$Wsf z0$?wUPUGg?QP@Fjf3kq`rM6GPm$JN!SOB=pYJVKmZmkJf@iJauuicwMDB9ba@Q^W? zSId&G-JL?LWgu^EK(=W6JU$%Q{riOXpxpK04c8yJUmrPheKi02__ga3|B8T`Gz_Y@ zf!nIv)-9B(QR^+LA(m^thG2c&VxE_J13xJT71mjInIV7&Fb@^q4Kyv*>>&6ePV&JE zaE#DIQYjDm(D+Mu^VA8>xE_XuH%D4)KYytZaR*T{hvCKb#qnP|)kVu)&KV3zJRw9C zN`|;cdE7)5?C}XTg62x@)LF-5m z-TjIi8KL>~*M8T@?>G%1pqSr>qg~v87gFT4UKech4yp+Ds5om5CGvs&-}?{v;dZz| z>70Jn>b6c;dLyy{+MFVFv=-X%2rdrx0-k7PK}-xW_atmKa)$^mMiLW}Ct>Lgor?*I zaNGt3#PsazD912b@NEMhlcV6e+4f|q4^tow%Z|Dg*W}SqHj`U?m#9AuTK~wzc4iUgML9 zI&|F33#Qoh z_RsG|oBjW+y7{#Q24~g&d#anF1qQqYHn)eCK#JFR!GgEI{*qM-+}HJM3+(^qjJ6F` z&7;~CjMC{(;UU82~_uVkM|op2VM#B*M;`U&CCK=(hKzj~;CGfoGC| z8hHZ%^WpV|;mw*Cgs2)202`otz0EA~hBJ4vTMK{5Yy^MX^PwYmjykA>I0-d+cxK+A zz|v;MT%RiD5K0h5ED7YPU4ct%{7C#;l-_SAZCcRRNk@g&!P|cisBd5xbc&^8Kagr` zWv$UnBt{9d^8B4_dgRW*$H3tM$Er&{)vFT&*Xe`e>kP2@KNU-a?H!B1vx14Spn*u zTW8rUZq)E*T#wh)jG5AlxcJ*7>W9?{(U9H+fm`Mq2Q{=CzFD42_Rz~g-P`o@i`p7d z!s6Bq(H7F-8bdtVSo3eeUn_nYuqTncj&wElu&|XNlFYG`sOZeva-T#RcutidL+IEB z=E>xV2e2vwxV(e($)XDl^5dC<_}HIvC*i&)&vKI7_#*fQf7o{-IMKOf&3K4Yz@A_OkYTYJfS=GSm3}v7_ z&MLNzp6t4tL*2v%S4$ki#>&PKqZ(|}Z$hY2OVpQCfVuXDfphBMO9GE`Gl9Dk)#Q(r zDQL@xbo%XlO0~B|_02wfh`ln)Hg7TbqphvTZNjX3v5I}a8Z#iBj9>J*jIDwi;zW^w z0AupT-pdx%hQ7M0wwlM^YDBr*Oh%F!&;SYR?r3l{efrQyiYfcZ&0V=ejv&A~c{`pI zor?_TKfB=xtg~3VcQSK)Vt`?#TguDFq%ml%OFIr280L!@Scr;?F@k>_CqWbok?^Yq%DMXIK#&SFsFd9-0dabCU3lNGJK2ljB^1yQjF0iI2#i(?{3 z2#$Vr@9Edl%1qR&6U5bQu_i;BwT${Et(O?7>i%;+$}(75mo<1tYlO*<@_uBi$p#tw z9+8CwN~-t!uql1}XHZHSFWtb(w2jzUDRk~ZBxlyuAug*0gB$Yz`Iv{RBE6TbQNTN+ zr{lYCk_%MiE>aI`vuOZFBvNKT;L@!PDN7@}J3eVz?meBB#phBg!{%a8Q~*)rS!XeD zfG6^0Co7DM-Ka6({aFmjy2&}^;&}QgW5;_PPsx%=W zUCG9SweS1(-shY> z&fRz1Gw#^`K*mU5j^usc-|u-^iZFOT0QJGSt-wkRiD~c-ct7~)>$r~`Kp#kw=}e0` zKX}CD%m;f1%=8u9t^vZ~Vx{>qDr@S{LB*v5!QfpH;q|k)S^q|`Pt#0^Fq|uvKwWW# zNeE9r#e;KBOQJqT32SQljjj}?+Sqn+(hh>;fJlyh(ThBzgyWR8Y^X%B@rUSC^gAj1 z=iapTYvV(D^Y;<&%r}P!4M?j{^qh2r=4W;k)va6x*sP@RwUA<=+@@jU(LyZ3L~?W6 z@#zL3^C`w_$V?^?Gq%&}yEe38s1EDTJXoV`G>XnKRq0W4x?@`NWE(DZ@>J|+e}4v2 z)_4CMY4gF2juv^Ga~tTSMZ_lR@wdJq00Jh*9F@7_4Dfm%6eO>Kl`ui+pZ@yg8uX8Zq#{Y6@ z*Dqz{ZMN}ev#QC&iniAGF3|0qtIg(+SOo`Q{A`=4@uR6hen0;xz}P29ch^W@V);Ye}c0}67_ zStcibA&HyzIkeu2?b>+;xn;q;@cAtWRtzGM1AR{yZY^B-_Tx9ESU(@Tb#YMPr+~e+ z|GCWV#p@P7KXP*WXG&DkOOV|8f;h<=hQBu0sFi%G7P~y_xOMr?$*L`ztbd%EJ-_^* z@8_4++{<%&wtjou7fe75G{5&keGxfRrD3`D3mnEvk*4n_A1byv9A{1L9;(zf1n!Dz z-1`34D(2GdA0PHuA)HvHD+}7FpS4rW2_S4h3`VNRTRA$vbqi%jL ztTn~6kMLpm2P7p(Z1z>4`alFg+*csZc%68DIyH3)gfmd;#56K5HKSpRBrTiF2Vtel zjxP|^5ybOi08(~`slqi=NSq5`24I^S_*4r@~E$@DO4pz$=6iqbX1k9~7k{9>{Xe*N{c@4-xaS5kxfdW0H7+!ge|y zNyK3zL3PFnY~E_ZL7D{BlOQsL&=^xxfC|#$0iSql@fB{4IJ0136GHYitxQc@~r(0@Pc<5=rn;SaCZ!*Qy%2GzAI5AT?%5b4?!69nV%P9cJYTjY0FX@U)-L zek8BxyUI?HO~}LD!vY*!-XnQ=ZYr7;9sC*+L5pSTKsgdD*m72XA|Bd@ zjb3g5VIy=EIcI-#+P!#41XvyHWNFzr8*p^&C=A1oYdl#Mnfpl#@&)ow;(srGRii4x zp~H7!z6yj|Qo6a4z)lR$O)P`56QGhuC8)N_TRrkhC=Qy4g4*&CAVEbArM*;jHWH+( zSd7BmXJM>ur)>1a9=B}OJXfA28xr0W?bGt|-pQwOV zOkykUWGkVsRrpD(Xd>y}$JQwQGV#sQ7~eM8lWp?&%+ z-?|v9%xJUiORwweRiAT=9)vgBp&{%##(O!L{0TvN2tv_(0MNl4Wa;9 zrd~V7^PQeI-BgIV%2DNBn)OCw00#idBBJQ@54~?5Jh`WXByw5xFeWACa@3!6i-$+ZZCGsQl>J$8}o}z`fWobg`t)IJ2l01pOK$iMtR4e z&y)LUxj!) zyF_h7GPrM18!5e1$Hj_;D?*I9eRG#OPBdDZ9I2!YxkyM_09uR+GZC~N#}Ek4nLPJ= zP(}oUbGo`_dDGo00rw3yukuLU3SY9H`b?;*-8L46!L}*t9y>bODfIbDM}k>ZGS6oa#=t2I1{(z{}XdZ zZ#VhoajUtVeUI5AxTAd3ya9W3S$5z($VbW1*b*u8xu1#c?ynR^iB8f(61r4`6qSt? zipntfI-Hm5={Y5w-+RSb46vb&ezWy!x9Goc(CW!)>ep)K-5!w>%e&R(M4~!m9ijrU zlT)HGnVPgMX-t;l5E;edWYn!YaH$WuF0<_XPn+N)TJa>~$-0|ax`Idtel_tG9q>C) z;J@pe27x%wvZ&{gGA;L9R7po15)CdAYCF44UVG)Xl^FsZR`7D7)EAQ4!SlT;nPts> zxOJma5IvxUPr*O$DhlEk2JX|kIEUW|@7hn{^QuIynz$VwcM0v!**&qwmd1*|bEfOg z6gU~1Y<9Sid`n!_^;BB2()o#WN%z;bF1;RJM1JV??8=8zqN3L}bcS;n@xL7f-g{|i$KekTld=y4K3*6N1Q8W0I5mxfW*5eXPh^x_I)0SYy2RrD-3MH z4Wqq&ZWZ3?@*;&-utGMPRrdX1AX;5#M)ebV#wC%R5TUY&(-LfuLiZVQ1qs&OhnUr| zeR{ou!3E1?H{$8LDI6J!Id4FeULCfATEELLpz-c!e;Z2aUHVjcr;X8rdt25MPOORT z;12tnrF4Ggz*DE}_T$?5=WcG--j93adE5}d*&NS+w@xDWFJT$Hc+^;H^w3vx%z8WA zMzyc)`1?jsQuTpITF_l51y`Nr2|xcWPSP->biZR$GQ`mIed6jEm-tqcDmjYa%yr7m z-X}G>v4elm4>~`3bV9h%#@FlYL$iL-3G{+zOD-=hS&>Ov3!|JS;#0jH6}R1SV4ELY zU}EFHzbIVse}?E3VOj!I)Q9$=`E?@#;Ra5<)@@Ia5VbKmRT{pnQJ+U0ZIWa>CaIYW zP#JR|%ZLk_3Ya2@b&&pUcan*qgkVX1&U@zj#_p=;;Tup;yU_3)Iy`d|uj(1DdE?wk z!qAiHEepL*U<38-zGpFMUoXQ`r{*>levJC!z#bRjLmT=pkX$(unmgdB^E=Bb6&e>( zLl&2Oue0Pa>s8MnmBN-Wj3mw^a{K4n-ij(b@FylEV^}C{egBej z-On$E5yT|M>eRWi{AA_l;%^0?KdqdF1S>1>7aziuiSlJ);+Y$3(1-yHZc&9BCsBbx zZs3H$C-J~q$Xx@1|5rs!$+de9Z=UuA1jwHcSQ_!kTBXT4-N~y{rxvp;T2f{)SwcL; zArI-O39YB-D{&A;iz!su)YSk$gW2k_nnw%}U=MOq3BIXj&kr2f{s>+Y>Zl5q8Frk+grFIw>J3$?@v& z;Q6P4`p>DeK{G=()4vAy6MOhq{meqP6qe&u+MQ_`1GGya#Uh$nj-zW%S8ivAUovT7uS~RHp$+LGI%L&V(!o(;EvPg7gggbF##Z z*Wrs*B*G>S&{j}_4|3IsFxNw70Fc#&;EOV9A&+N+(pZr@z78OK$KeX8SlBKO_iq6z z4E7*UOA3VkV1rT%H5(QFx+fQ*rV}LHBN0IaQ9ih)y3l=0-m4qReGR!&pmo}iIRDtx zbnY)~^mi>Nld&o^Iq+!piVTMeI!W*~7fdiK?j(b13AQ5qV_JmlY<+ z@Q=w?gCf<5!qCaiH}Y8k5MBnM#-M0U1&Vd@TDZIwiCEuSF)62r87mPc7m7||eG@91 z^LAlY+Di7y5w}qb;X`*mP}RapzzpOIfq5V0Dv)61+>)G$GlFT9)r8HHDM-iIAYeSO z@?gFk{nWyk9033>%4`)ZRUM|HU=%AW6_RBD^Ye$AORB2}DrvuiKt{|e;gZBiI1~c_ zG5iW4;%Pp)_*QALGzqU80X!P@0xvpbZ-mYbZVE_7mX-LVRjWRzQ?SD4* z@Y(qCvxj@n{sWWpPk_~|-iDl&#|vA`!U0ohj8 zsR`C@D8KrqbbctY&K#<_*ktwyRIfg)z^KnDKMl0v=;2a`MyS{ad+GIIH0(41qD7e1 z)YpflvRs52pd^XIpf@AHrj#Zd0@2^INebgk?Bo``F@p*zmFOUR7Na&MoU_UWVbm4* zBe&|nJJFI=U?_M7`w>q7%Q!k^d#3SUBcSgQ5R4i9F%DT08sVcYuN(@b)$WhPKsI#` zbr6i!>O|_PoX5ahopLxl!X?Pme5po7M&8h|z_uOU-vgGsJ$u~;fmoI<907zT>lR(0 zGQY+X&+sO4x*}_~2PaC0B>ZVA`fKW3H5J7sUh)Gw z;@3(`F`ATZD-wS<6{QArrzdu^Pj+X)`n@OJC%$!a6ngS4dI|%2iW7TE|G6Qh&}&g+ zw@16TKC!pjhSAX18#8&JB|w7DJ9=TSc#bCIL+kBOh-IGa>whApQGMyMLjRye|8PM6 zLP2|j!hcof{lB3g{1nJRYdTfZJ8U{lHnagAd1Gg%GyX4zf&kxPC`iLc?nNzooT0Y60?w z0L4h@Q6Fw;-ZTlrmAnVqQS#`8}5m@2SfCcyQoQBTIU@EmHT-A z!ph})t${enFVtzB#NoT^#f%0Y?)di0!V_B-BUKiK)~E5eUKQ%%DvQl6zIHn94q={; zKhX!3FYGs&ZF#5m`7I&{lgoS&{e!Y5U~a@=%q*#V#c+U*Q29X(Gb$ zDf-d04gjiIeg9&jy?3JxbWdo2EG4mpcVTMpQ?Z$i``2@3-b$bxUZBp2#4ddn6yy^?M*mUEmVGFNEO=B`cEc{eADd^g|teIq7g3O#{2BdfRV~#}R@C9j# zL)z1z^st;4{nGg?Hgf>@;=&hyIcwWu77S`OsM?*VHnu3u%SBZbLr4uXmZv*MB0(8g z(;)Gg+`et9H$_?kJC?0DpMT_ShIL`GF-6`kK(%F5(`HF?^E&(Z<{X@&-Dl2;x*(>guZmB4PW$hqA3;);#7>j|L7t6oyxmB6}%2xa^C&FM@ z1Uacq-@#zjzGc^S&nVaivV?))K~hJj4o{q&92(?BV&nFX+Fo~M1ta7h16-9mTx%gy zuNJv)T>Pyu>vR6WVuesT^=)g$8sRflE|)h8Po??Dyq7vlSgNzb1aS=RMP6X#!7s`+ z04mP5t-aISHpdx6@7R0>TZRHYlOV$+e$|heY!O$~W8TX7LNcY2tuV|_lK{le9Q6y_ z?_tCYuy?T1iz73_G2+c+(UqyKH-k6VyZv7|rWq^-=}TsAWWNL`DO;q|+Z@m5EjP__ z02{m0LSgUxjc%;74o+}<9X(7OO~bWB_N=IUDH1A!ArU4OkLK{oXWj636jo#hl*?-J4;8m4&0NTuYGV@+J?e~$k;$xTwxh!`GJpe zZ`Ee8PVRR4*4gbp-}#Q3ceP5Z+J(`n11E{_GU$2&X;Rv$)7YhWRSx3OVUoJ9#B{hu zHzEi_1#Xx^U5EwJ&24fb%NvNXH~MH3J3_jHao#9%H6%nGK%UMykQ{%PkM;2!2;BcB zS?w!QaS<5N-F^Z26t3v3K(fCiJj+XEY8`FyHnEu(Z`*yY{9B7b45AHEom&$2+Wznc*#gXUd zlC(cTmo zbPohf8?crFlmwUg73IznuzpLHZJ=XDWJWPSD=4LF{k2oG(GJebKbS@6$I4GI*a#u6t%c&AmkLd;AEPCpsRN?ucw zOej^uc7x)i6aySlBpynZJiLC9BH5Z^wV0y2i$$H)lYziZ|6%6cH_bbK_0SqLf6Sk) z?ZrH{y<0nlkEP50?iBgs(8_ibn@T@%XFcPe4z1iMk;7~)m`afT1*!8eI<~+CF}N7 z*hsvJ!|Xqp1W&#|CQO}GCc$4wf{6{s0}R&w$s?d2`IAS$Gy%p(x^iBIMd-l+e{BcMgVJOZNjDvtnJxLp?J5%4o>y7IPci>O#c-Va5}YeT-F zt2_c(zr^h$*raNG^A(OxlJ6YM2z0o&zo%98#aEzy~$R761<`S_+bR zV8N{7mds*vGDy~fG^*jhe5y)hG!aTZ2E!r8N|bF8nlz>cFe`elS z2FivLDn`pH#(OFz9#!00s(_&&|3{hk1c#fxe`VhN^fDiv!snL&=6`11apl$Clh`T< zzqY%a;I9btOd1x5Q9a@fqw4(B@IabaWDUyZ^uwC7uO6W@f%r^1 zdh27X+KMm2ISb0vvGAp0i>X*LqcOMq>|%HnA}Gpn1X#l;b<_kM9TBITAjgGtRJ2!DyQI@ynD1I#xY{A0N7Mhm=w^1Sf+)xb;U|`@MlL(@%Obu>Z1hgsi z{MDd1jC&2hEtamS|D2^5<%dNOadP@0qB_a<9$)CS$yOn?0@b)E9ilI-9v7e}4>i{| z5yf$UT`xFf-q!iCyi)x%lH4xj?j=ue|K)Mp8U=-JAID?P4Hz5H;7JpFiC0_cYj3Zq z^OCnHCPDkDOl%MDyGZB`%`)_ur=#1x3j<4TmhRT>-W(fT1$WW=+NozD|Mv*bj# zy(Hg&&WVo~r{AoPUsm2F)HPO98`jsgy|ZTDpNG~zM_$;>d${jk_ieI$*Ga&p3X4C6DS=LF1x#L^buBqE+TCFumE?HtO-r~QXgf=K}@kAuf5+by6cazbphxv~K7#lo+TTHTqL|yPUE>ID*Q)=G;41N{m zHlU_=gbxf5$XA8(a7M1!ka4u!yK`U?P!ku;@ax)cgB9fg*y<)^P?S<)G@iqP6)SjZ z6Jnr_(gI22%0KK|`;I(~ki@-+ppeXi?5;Ek@N8{HK*dR@nac{lndq!mwsa{kQq-*3>t zr0W$E5yZO|Xe;+j$`~PR_Km6zq*N8WDrJ+r4>I=Sn5<6QR>K$%V`_(X_p`o{n zN!2{_Rwr~!awT=J2@aDFH+M%kP|x>&efy5HddG*csNaejfuvq>S%3le)g38&=Q@4J zLQLy*ZUQd#1btljVrV5HU&-;i4zl}r%w8G*FeBI6I8p_0`P$83M0u|h4bfY4&7DKk zvgg`FuTv5`}#P{&rPypt@Xs$r&|@I-d{7geQse(^SYH` zicRpG-lE&F^=g->EF_)Vm9pXIoj$_;ZvcTFs0+;iEl<`!#-^M1qJ*X8tYgf3XT)0)wnoC8u- zIO4zRL}Onej#Ph~e~J_g%u46A+0HhKsdaory?^{;Sqgu-y;mzo)au*kfZzlhcIwf= zcV-VS^z~z?Hmzz=-6<_uVLxk?<+|*x(pzqk*sX!h6pB=Ej~TIbUV!aCpo*eai>~xJreht{ zB()WH3<4yas;GP1rvRMFnT285^DQiheVR&*OBSo(GsJZ1-mbpaOj+PzG53L&c8(mg zBqmbz&}q+jQ^>s7-EB6T{gMXsJRH+sdulmD={F}0yYKpBYe}abMON~5J>U>4v675$ z?6NaI!)n*Tef;1!w#6iy?3t8x*3!Ab($+NxFA?=RRN>S~f=(N(|ENGJn_cP&8Oq=XGnGYy*Y5WTU1jy4B%sC-WU+2oiuT=j3pg`sR!?(AJ*F>E(-4Pq0pHAx0#eq1kX|c`>Og$yLb@vn=eM}|s1Wn#+Q3%QJ`@M`P zwsWT3Pj?ANbSnrHS)OPPs)lVfhR`jtn*Uu!~up;6bAUSV^>`szCE_7@MhW&3_Oc+LxlMj7l#-gn`c5OUz$ zU|+H9FgGl>dtGc%`!DYg4~rsfUTwM+VBwK0z3#*N*J6vLop`h)^18hfOzun94!uL> zY&vK5+aCq?o#+FsfMI=L)b;QQy0^W@6R+?0T|?R23x2;Eq%cxy01{Y)iTQhB*5A#6sz(vZIt~*Ic(0Fs*b+_c?Yea=(`l z{m@o7C1X&_E_6qz@x6I^x870u{dR|PG-e(kA6R>@`&LYT7U}*EL^XidinJlnIq&7p z01^-v2ozy%*)#lT90Od$56*?k3_n5>lZk=4bLwT)B!f~L;ZRO8t70vN!rmav;3`WE zf4d|h(kTDU3@M^uht?5r?S8yJ7&ij&fiN$m6(3-gQW4_u$=JvHUva!|lPF;zAo??a z6%XfkDFZz>&Z)u6B+czB5~E|X{ajs+5X>0GDl4r{Lo&zctn(W(UTfQ^}{CIme)BM4uTQTxQBr5(5)oys5gh=U+ zIRHp}Sl7uCF(UPn4l=3twm|L3>h}uJH;mOf&g}S)4~VvJ)QNSmy$WagQc7Tf!tMC$ z7b;!C3Ybp}NlO`>N@PZcg&S%meq&zsKceP8KR0Z>{MP68zeLTS{QT;C*SuI-IsWOd zGX#%?A9d0L8GNCY#nIo7{@-7TZ9&}H&O!bHwO zA1)%jLxV6*sze$qC5k00t0mvfI(CP(W=fMJo1AEntmdn$Pe)L=%m)`CT`lBCOo}F3 z@$PF$wZCfa8}A-46L`Zl_t4_V^#a5O9zuzC;M0Z_+8_pC{@a?n#ZYR%-!*q`+Kzv! zxd&@$WH63N5`FeJsQ+1Wr-w?q?>p434%gg&jf#|nYwmE%oo9GtRLzWL^tC<%Sm7Yu zG}vexv=3=F+MRjm6}HYne-lqU)B&A66$2|pYU2;dwI9ta&1&k-YMJ`|=szk8b1m}# zz>1drI5MTpNoEfX$pnC+*6gr+42y>jY~A}PD0y&ET9iWr1aVU}IXBqS;xsV&()v>} z$M4Qc;{ZU39zU*+(3oOi$j6^JN&7;$Xa;6dKYLCKQsF?bXLUaq*V~|&#e_aN>yLj#&Hrxw`xS>KthW9mdWzx7|ABw9s>UXi#6Q}oL&{9} z%c^>98z{C_eo}B(9>fFUjM7}ZqNW)%+6@P~A>tcxV<&leGss-7 z1i~Iyfs+mNGT9n%VK`B~y6|LVLRJE6wKPwOLV(+)-FIO5InPRS2Et2v;d}!vANhN} zLCF{U3oia)TkZk4E)V7WU6-$PUJW+f9xcbL{E=+nl|3a_?*GeO^4=Lra{Q|-PdW9V zrfT0<3AQFtgvG&-!Fw{5%uI9<4-1g+9kTc()75YTdi-B1@;#402^XdBW5w#)aUu@^ zG6_7mkV7!b$4>*t9s-o*$mh+!Q^=`Dq$H^aeV$ z5L0Ld$??zL9%wq$2wXh8bu^p^haMz9$F(IW^)44b8LLD@V!BInMg6c=f@&G}2Jgd) zxNtC^dloa@K!ls|HuZbPnyXzPjz95aj}qU!7;eVn?a!g}&)@Go#e9>yDMDEwe}N?5 zyx4o8%d`CZ|14_$trb#e6SruCnW)l<|8dm(U#zOxZH!CncVQ!y$0U?iNC^t`yajoQ z^M0`UCpJ~?q$MHJCd(xB_3`sPbvE)R4`g(N?T&MNayDEOf=WQeHy1qo%ZNNy0keEV zTO2@N?YPf0oTBBG;U?E8@PQb5u1vKzTyVGJpBACVE`^_k-A#!ZU|0&c{V~?Anx$!m z2e@cUAa-QA9Y0`(nBFGN!92f*6-t@7d*6GxoKvk3zO)yxICa%rVomiq#5C}MAT4;* zhasLq=ix?$fC*Tn5{}?VK;xQ|9Fx~>n$(HWk40V^{-i<;RPr_V> z9CLr@slo;ACJ9Oer2NpZ=<)BZcOEeG?P?+Z2<%rC=B?p9WJs6Mcn`q@N9a>?cMKMQ z>+jtWtMzx`>I-Oh_&u8()r`Y3F^=hXXB%C>@?J5t8RZr^=841h7 zV%4g=A@d12SdUWvafq5DXKOiJOhj1h{THk1-)@xu5Q}>DWAxAP>zM<{@RsWYb!gw* z_1wwpQGZ!g8NXNLkM<87Rvi6%1Hx>(=vOAz8@+*2>+aw1YRg=$$a8OS zb)|Y}6C+7ds}=cHzZ(-1*A;I%fj5ysH}AD16wD%jvhdP0gY!_qH~79)2L!@^hv(*Lr22|GNu$H+ANyCwKL3HJ#+Y zxNY^lWm&A1XCmE9{Wd$4Yc)SA;kqtEOX8N+$Q+V;?zY3;bvrKIa^ZEXSoY~!zuh5} zyS64Z3Z-&_X#;?fsM_1zbyaHxfo}<(AE=j~cQjL%0gv%DClsTwDs-v-ZVaGonj>`T^vuY&ytR7c`%cV)E&Gv4bYMni5HWC8^p*tog_t#UtI#~p?P9i| z+X2b@aK}YKn0x!1V0mlrkJi3$i$2#o1e}9uGJ+7y1k#l-kbng#^MEn4C4m2Nz;0y! zy*qPR-#e*ZYen|nzl>O^&Rwgx`N(^#rOzE(H$DZB)LUk?uyZkvEpnZxB`e?}cGCmJ ztZ_qn3$Lm7H(s26F}V5s89!qcIH_j?^J8fwz?8-j#)2{2}F zrwK7hL!uS%8`hZ4Iy5yvB$*W zv@Ge2jag4W<1ekb!fYdK?;gNy^rZqA5=t+Lo+)?%ml!#Hs?32`G^sF z)Agf{%nL^bfI#G$kHU=P1g1-bdCqQ!uUKx>5{+3t=)LiSdu~MIQ0NKYr+8C}6GE5{ z!oEBhYrsUCilgEHK;;AH8nkOND}ywIjB-d(m1SjXppZCG5I}^9qj#4Mop-T!H0w1` zQD5t)bR(@XR0QMF~tZZeN1XXc4nzFC3qIiUzlfe-T1p#O!tS8!1 zacjSG$tMI%aVwH2RQ+_lUWTDh%N@TeIAu6ue=+t}{sDoSlohEhOHAcCL~??`awaQ= z9mImt^?@_M*O#McYE;xoBej>La4e2meNw-0nyC2538@S0Q>HM#>Bb_Q_?yuL(K{05zLL=vV_DwcxuEcM~3BI>>)It&9SV+?n^+&Dh`* zTTh$k#B8u6=(W_FYunD581&~Edv)9TUGUFpK3qBg+AwE`DkG+%D*(M9Ls4T(woKQ~ zqavs!1FG7kOouEu`0?2=LQ!YohS@zSw8Y67x;p@n>7dX7P80Zwl>7MpiwY2_*KD^J z+93iR&`f)HvHRiLBaDfRA3Utp6>RR_iz%WBt=u(&vF>&`c)vwueG8*t)Q?h|?A&%L z>V|iOyWGj%m8}>RNdPVQw?$7Gaiuh|$xAhK&<`#|DG~_=vQfh4srHwsgeH}1RE$1! zaNC^_1JZ}x$^y?v=f3Obn#3C`-wJcQ_cO2e5LHES{mpBN8VqLk4qX78)c^rOnvC~} z-fcfZuE{oCv0#e}*D#x@w!|LMMEBI-MDBif#NaS%oJ5E>4LNnz)F;=91mF4tQX4q!OG3vKF&%P2k5I-SL)JlR(U z;bu~h7GsHWfb0Sw|Jv$CElePkM1&&&bNXyG;HEq?Rg^eVM@e`|CQPR9@&C~#Waeou zlRb*I7U<_j+*g$`72%#2o4#Vd{0*#s1&HK~gE!Q_M&{fN5jqrV?>uN6x2wwc!}(eE z=Ni5ciCa0WiNRzHNu_d9*H%2z>~eo5q`0uc?HqA^vfn8|Od75)nCYB59-CS#^%xF9 zL~t?^xF?jYTB@x2L9~kLZlWyH;C*o$Tc5fVrOc-)wrinOo%F}ubIq~dZm(}hi6PM& zxWp5D_M;PS!@c#gviu0ct|zV~VllryuHCz5*G?kf5o21Ww}FXgUoKNSkii*xGVizq z6SQ#-X1bOHAFap>he}h>y0qN5Zp50tL9AK-WR@n1B>W|8#HbT`DbacOVUgjNEz0l% zKRhi2QQl4_row1w+;&J&^IhG;JJ{-xNiY~Le(pMQa& zBG0?8Z~zJBsj1uX_A$Y|w{=fVuAm5~Bwa5e#ZO1u1&z^B22<0q&CFqN4Gm}TSxEVP zwe315u@DT^tX!_hFpiHqPIpgLL)Co-(!ERq;^0yk(6lE)jOww)7(?RIyI;9R-jDPu z^c8(b(<1rNc}zVceUEFV+zvn%a!Yt%TSM|2jIk)*?TO+A#R^3FXkypJw;A0*%w$Mf zO9RHuw#uy7NyAru&iL2b56 z40vs7zRAQoW^Z1BMWN*OP80jF^tf81UEcRhTVK<%JxoeAImt52LSxr2MzNIkxFdOP z6Y1;Ua>Qm{7+RNVU0)Fw-kIt&sb&ZYEVdh&bgSxbIAnG_&B=l9B*qMiPIn0A7$S^; zLnPF<_6VPu5E9?256h}|K-Q)jVz`(JEvx;P~hADycuaR^ra)2cAnww&jY>gs^nef;*3$)+zoJ=JE={=rwrz1Op z4HrKfmvyesim|hSPy@(BFeJhw808h}grewcsG*EnW177qgm@=3P(U{cC%yp+7M$>( zF*PQkuf$>R#n?~9V})gWdUrE@G7yWlyYlWvl4ae@C7hXTocF!hIG%~NgsK$|piocP zvBWA@Xzp+09R!AH@)!ij%a6;zLK z9LW%KL$73B?5_G)4PO%>2o(y2s>t|Uea(miz+D<9902r_wH_Qw7sEK$g}Hw-@FG44 z(wkvC1`15Vwa}drG!6Q`PC$<9gsHO%I)vR8gQ}rm019YC0zeXi0A-onjXdsYX=LoW z{xez~1w?UR&JAF0h+Vnp>>#k~#F!Dg?3En#C3m~K#RAIIeZwYhL$9(JuV|_oKHzH_ zS#zJdb_tB%+h1b86N3q+iBj(xsT!BYM{Qe%Hd(*)5TgLHe5YawThkRJST;k;prh2I zakdZucM%4VpqxD|Fw8m?RfHj7HglX%{IsbN@G1(h(N5=$vN|2&mXlqJ@7nIuG%JW^ ziH_TYfb)*enSP6vwQA7r5&L|vED2e!JjtXtB^jc1A}hNL+Jh?(x9co(%XgwIbBqDG zPhb!m0rD;G4DTB>bhmk9YN+apWVjyx?9sFk572PCVF(KYa1d1L#3Q6P?Y+@iD5e>D zK+a6BbG@wUCQ{ubOs{W5G2a)>&Hj-sQL`l9!;3dSGu03f6pl-HFj8<(0w*JWZbD_lZUxP zC|47TtxvBy<0=OM8%biz)uQCOZFO~Lqw|Ht=(v=_7DcLNJJR#oO=u#H&UB8`&Q!x% zPcy?1R4m^r9hF52#TLu}rd(96<|g_35$w-RYtFLRoO%yC-~By7N*Et=Rm0gOJCa7E zBMy|H*f({>$a&Zr7c@aKNf#mlO^e(OV{kk!{`K&dn{Qk8MQ!^@6Fb0jiUi6&oDJRW zcwPl%onwaRCW-EAjoA3|Xg3lO69UMs7&p$E(NHff@-|s^??!RanBk6?<8}5OZxWm2 zLlk+glV2D=q_D{h)J}o@AS(S$$`Q7aE5HRa7!LbrxR4H0F=pc$xul-ZJsURp$O2#m z)p;L9bb%Typu{U$X!f*=E%FJpPtz%jH@ou4Nr)D7Q*Bq_T|ktBH6{TPG_xn2>rEs=dmWqsEQ{1>D0eq9 z+b|&buDuwRt)W%2b`g+FiAy!!m5;KOWP;-h#y5TRi8{7o6wpO2P)yoKM%P6G*=Y-a z8J~ee0KR~CT;E6R=!5?K&&8HGLgzVFyW?;?dbdgJDc~XP$&wu)u#iyo@~*Jxcom}EofFm*)ZfSj==H%s zq^@@C)kCO{Lr!7AyB;CL>{Q8DbW{$G*T0V?#p%JS5ek-rp#0Vncv&eYh2|fP4Sp2@?76XL+#bboU2*|b>9k-PSMo*Zy=)Iaur*qv zX=^k<;9zfm7o|#s-%Zj;IHV`%qi@pTIVQ|=#sH(Z+OHv z1HfjjON3vNj4?*v&NX`poT9m)s(}a*+$1L2!J|@HPh%NM_L;FTD+oZM(>>D8l?*v~ z%v5Hp`B`Lna#g+Rp4jds`0UPz3wdgr@NjHfVC|*5Zq{FXqz;{X3*Qg##nofdb3P3z zVJx!>U2U07<%OXBaJj{&oREc(g=L!8cVp!TNEixVt>tw{0BmHI^)bUeK3PW|(Ri_` z7wR{xl@7@ae#q@GM24W6!cYZ5m`F;@of5-KUJX#mdI?RJX~~lbD_XI7Mh(U;*>M!i zE}7w|Ye~bQ*&!14{hCkeCwv=atZfA$053v^f95I@v3vZQ2YOiW20%>G?%261SD&%J zxV@zwVZ#TLTGuwGZ5r69@f{N80MC*)dYXT-$Lukq1OqRfWBoq6ow`@HLoF5{Se}c& zaNo$w+AB+{h=WxRT#&crNILDj=UcB>(?BSMc)nw246`M$$3Gbx+zlS{%$baK>beOc z>aCvKyJ6vB>Go=KEPx+8ab+hy6Z$7@$ zpO1#P>U&G>9l01AC1ty$;#C`)tbOIF^|K<7>JBou5}INcR+9Ft_-AcT?~&N#f|$1Q z@X5;FeQf&PLuD$@uiUkv50^O@o(j3h0*C83S$lHrK3r1dPIwq2}(_#V-TITKh zn{#Iy4LPd&jy}2|iN(AKzowfRM^XzhM{cPrG&DXL6wE-RO+7O$ausI)p>M2IG`uKB z5Mdp*yRri{=_rbu&y!9-2ijB@?K=NpTiI#Lo}=p49fS{96Op>6)9-r=T2ToctQ7|v zD*#_581AgK5_9l%EUoEU+#G|pocwSTpcK8Z49Qrbr;T%QI=(g4t;`-2ZwNvpJK6JLmj! z&bhw-%s+F@HP>9%Yo6ER`M5tGw;O;Jfa57ZMiw4`P(j$eHWmm0zNC+*Xn>&)gwe@3 z@HbE&$4t`!!iOEU)I{SbTL4%9--kh;(`I39|sj+_BpOJ5 zPJ8yLp@j*?rG8~w?q%A*?Vpgyx6*jp@Y0LqWauFy?!d#x2rZvYk>&j9tJ}x6qpc`MIAzOjM&+p22*36mL?5rAoXNe zR17!Pi-NVsn`sF6?Q-^k^uoxKh^1ZdYZne^weysVsk z$f*R*h>H$u5%{Op0{SamwX1evxSWXZ_qUCHta0m{jr{rf>Dk){Y}Clk=!3@+XbBxa z3z@nyN*myd$HR1Q+2O$)dS|9m5%y$3Xg4>LT#eXRIWo`Pv;a6ZE01t3oE~>bjya>> z_(i#zn>^eEn2Emu=sSfw)d(Hy5mZx4B{wY5DTnYL?!@4sNDTJ!9SqkhI}{+~Zt4*% zwZwD1D6k6`Cm6CtauB|VuO4@7s2}4Eue2_gKD+WP>DRJs+h9acoMfP zDr`1fbLR2+*Nujp(M(jz;3@WF%TQ~4&%2}%O^JmEDtgo?5$hA=jK?mgCdlg%U|)S* z86Mz4rP}uP>CT^5wqIG8ME-c^`{>y1jn-v|$Hn7^w@2HfCwVlBzgNRSeC!5+fSk!A zDx5o1uUptAM88iUNmbO}-2*JZ7~vR0B?pYv39+&aeNYFmLh1>x1ptI5(cHN-z??&3ODp1?)S7 zH9a+by~uMX;H*$n%W<{P@uaI?5Wsh-yF6`v=IBOl5w(><3BND8;dXd-otZs~RC6mH zeu3$|pbvH(y<60kIdIA8-Ut>6$azPzC&98NxpX9R3h0v!Hj&4vkWutItrX635f6&3a_EPmpM+?X(XSZTg4E$$`&2n#mX;BQMB$~;W9d!4wcm1uASbyvD29CLNs<(C( z6V6D-AuUE8Yl1dkVC^VW{y-c=nZbkx{LDgm$Da;L%M3+s!US$fQL;ac7t}RI} zvo(oJe;XPn!q0m&zE50R*rLY$Ic^}RH0LIC;eIED#nnqqHDh2^MM+DVymy?>(kI)s zMCxdMR!Nxl$@UQOUOga?azIN4P`>F`<&N}Sx^U##>Cq*HTfbcUq|yiYQhViO@o^`z zHJIY7tV^!hn!Xr*`4bCt0#1iKEG~vgNS@5{NhmB!Mp-`O44(jk^nA8xpDnn>exlJd z8fF1kF!F*0OB7=pen7XS2mZM&y-D0I`;_W>bj5F@@-ueu>=kVCzxdZW< zvAH2vjMTiC{XMHU7>(>b0WzQ=671dYcrjf;x)ZG`AFXAMFo@N0Nytf50X=(@#&cbu zupaqg-sSD2V6N;zVKhQ54S0Rx-S+1$SyQ24dWxtR$IvDWIfm2c3Q4Yz(C!xbb6!LDnYBk|vk0Go zyjMaS*&TI+VJd$q_I^cjWlmTjf8TL4u8U)cs&EfU+iHXlt_RDkWIV6Bk&9p;-MNSu z(c(?eiIsfIq#NQ|J}0@0*Qw5fZ_cl(j9a4$ob7KA)W3Osd-*Cp^hwEOx&#;D02~MN1z-0BYq@J(z_$c`lbJAhe#{8(ERId=Jy!T2Ca~yg9XU|K+8! z>Bd5HIQU>YV7~2Zz`e6*q)17Zos563Q0tQT#l&Rg!V7E8*|T{{--*`=Ec2wBm0f_%a2$93P2I182F>c7Tmp2c)0 zqr;%?$U>h>r=7aH7m*fzevbc`Pd+>CeRT}WL>&!&>8BV>kC9ylou$jyj}akSLAc=( zAu!Mxg@|*47mFzt(74lu{G<8ay%xzbWwdw2B)fB$Ac-|8bj;T`c<7Njiu`d=vltbs z?_H+F?nnj;_&B@$2obq*Z{cpJb-&sJE$6uDHo+P?Xf9Qo3DweSacf-xB~&G`qz6VH z6AxH5ZWwE*HpF1$VbDYISRfrAE~eF&XASa+x-MGiio$wvaN46=&5ls~PF{0--D=u4 z6o`}+{9$ltLQzpSM;_tY2$IBoHf7a-D6>gf7s=w^ZEGT> zt}4;i8revhA~iH5doY)m(#?-gdK#9*4P%=oPyYP?Kx-G@1s-qcPwG?y@04`fo9Ir*!e8}9%kHj$Lj}z z1G`BCPBz|C(Bi#(^HkXUc4%+SBPYy2u^BW;{zIx`y>h_u81$jY zOGqt|7#*n$F=B>_6oo55Kop%Kot&mgiA69{NI_Yv_I&mFEeCKr$|ZY%n}QTKKnmhg zz-_52^8jfO7Jy4=YE?P!Gn5@-d5*K_)*vFBDbl@K_Id@U0SLVw5_7{GdB;?BdDaGN zVeqCge5RB0R+Bd<_g3j;H@W!f6s}l3(14$mNbivXKJak8vCYH$H(Tj_83ci$BdY5! zzTj(waT&7PLa4zs)T($Fp{bfhn;9!ea6K*;UddCJ4G#lj{kWgfvTN*7*CCYsUyA(< zYG8T7i0Pesu_J?-BikG@kz?@}rZO$31*#^{&#ZDVcphtxY>vQ;{5t{~<%0gAvLkrz z0em%r#TN}us$0oh$-%55RX(?(Zn=X2wEBv6>H!T6mK>(UyB?1X=nS=|&O<43D<`|l z)f4K(lIXPRh+pCSSX+R-e%?zCeC&(22c zkHPMl-qC(IvOoFi&wfT^c|vd)lpKgRuaA)!0ytbHt|cYK2F0Gd4-jvSabQ#aS(BnF z8zXVD{pHCx5gwCYreV~aj|6JFpU~6yX6?NL)$3`1tI-|@pcO7`tRw%k2Z) zEG~f{+y+E0g~h3Egp|BVQ*TjI(L{X?N>aI4C_(05aZNg*GaRaPBr>Ecz6BK!R9icS zw!hDns+U%SdC*LOdOaw8!b}!B14y>U*s+kIzf9w(0vasnBKW06IpQ{scYl^&{rnwG zMzqH9w?2X$k$SQ1NV*1rieo?w>?rJL^Guh3v`CjBAT&IkwA(BH?wJCJn3A8!mBj_P z_$TYH%iNgI*@#Z|8rFIe_>AHXzSHnnp-(Mo(Gcw?y-sYYF%v$i(-f*tTih4Y5-H@x zp;M-%o+A%~Dn!B!G7m;rG{mWTju#I*{F0@999uxM(?^hK4n@unwt0HUBn1}S8HG9JDobjbjEHON>1Iap6X%9I~@YACFAI(n6ssv0w0|xBkA_0mjOyCe6 zocm_><$3J~KX~6;(F!=()hq=>N$uK8)c-8Q`_RnhB6r5TQWq^t%nT{V9uQnKr`s@2jm4EO@NJmz(Ejei>ML~@d>>QMXsSdx=CBe97*cV+R zt~ngi#+yI-(+m2srkM}LvH;v;y1sh<3e}PkAA;@~7`caG&HnEDII7GG0B-|ZAmb5$ z2ZjRRUvq&i@LP6>t+%c`LX~zp5BFq`eGtYg9A%ms7^%RmJ10_a*8pkV#=BnaT#t&5DPpGn3_vu0+W7dz6S2Q)D(`1smdIk$!Blo z&x!Z5NYd40slm92I_baF?rL&x#iu~`2C4gR7F3-}vvN2|n}mjkd7PS0_~+B?!(|U_ zOw*dlT%(F2&WXsa2C=tp^}vgIyZL02zd)ZWgLwJ)M7f4>CCxA~*;Z>*4hwN;?0h0< zT|3lJe_twY(M1C%ghs}JRzXcFyRHilr~ zIUm2H-x{&uKr0g}aNs<9B7?QyxpQ7kR2~uwG>45%;0js;lH^3QCT5dh@tM5aIfhID z6ma5X(S`Bd=;Noc<|29i(juAjY5L9*E|#d8_Q&>88I|YKsj5wVHvujkpB6Arju*a# z#6Pvhh(?OoCU+MS9sRWwYZwZ4sM(u_&>xQKB3_1IfPGZKU6&9_HW~-nb?#9d(`Wlv zlAR@^#}U@Z$$lWIB{11WKeo{H+!14pIS0CiME|@nsE=BPl{fLX2&8f(V`Az8_ykQB zFf&TaitDT|B&=3W!F<&?*)Toku}#5-nyrkw`3p^nqYcG!y$OoS0$u`q-glZ^L6c!G zOiv5k3`ooCl1MY4+A!cA6htKD&K;qgD`P7y*?+^67aHMqnx2eP zP#(k0_XZCzCVUTiFN|xhptUt(4!cIrf8w+Vv`A5MkO-$Oh9QX^!@cRLq~fAJgO-*O zx{wsWO@5_`m6EYC9;}~w?k8oq8*Q!_t8(p~2{dJKCDqW$;GnjF3(Sn^d?)a$|RO^quuN@knw?(&yhIZm!CfVIe#bJ?@nU;hJeer2ipr3n+bs= zmxe0SSSg{B!Yh+rT#3IZr7x56^3PRqroX-reQYYuGBCz|`i!|(({i_$e8a={`p6(9 zeohc%b*0gm|DMWW{s5`;PH%~VHiqQ>$7);*K!+U!G2>J<076{?LO4McONB{1SOjfc z#|U!WD1*+&+pO0W10A??jUcy5OxaZS^PcJnvS5;H=?GTZ6h;Sh2 zLCFd3+ZW3rmrTD?R&qK?p;bpwB5=Az6$`e8o* z^!HP`a(mzI-Euf0mmnHAK*nv=Awl2XjrmdD6*lMhLGnqb{s%9tenB7oH7zv=I2wfq3tb`&;m$>*?zXzY1+R zqgxTz%M*AF{BK8pN4ycNC!jdz?$?Lww7Du`Dl+-06!Y?Av2pYmz+pI1}3APJr#JXf3U=FD~R$&r!HfN=wBi z@iYT+D@uxnSc(i&)nY-!Krni_5OkDe`7%Ra^*qO~uhJppm{H$@osS$hL2t={0%NXR zof_HKF&1nExtQfs4G_(c%$#L+Cj}B=V&=E>w_qa}8g7sRXrQ?%hBPKt15crV;)p^< z02#p@&&w4nCe^Gl7U09Zuo8aEWM1eo^_4rQpYF-*6( z1%To(0s|Q7JPU4a^p_ul_EdfXg-T|H9{=RPQ!asLE$5k{&GV5!1c;~p$kW@d0f^X( z0%y6C_wcL|SAbKW!3cWB{vGadYIb`t3g+&ziLsw}X1vsRZ!|8u`rM^~SpfBr01#Ymw9c@M63E&+%*K?5@ovi`n`! zm(T<=L4;!(H5z1dJp?L^(~BFt^7!O=3Wk^&A5HMV2NEN>G<+RT9=pYeK3SPI{sD4u z7E6`p^hy3kah0?DfkFQ4d-4VV0_jv+_tqWzyWZ4ZD!OL!nvlspKqf~&hzwIKyrbNv zSd?P$OR+fZ0#exI_auL^K>;w9m!g>d4Jh~e3w?dcLNEASkjpfNl4f^ORuJwyllCZx z5gjOC-XHfw-fxde9!SBzb;-D<9#rv}15pKi4C*h)ak_OPlJ(%B<5%{*5hAuZjsV4e z2RM&~eFyP;Ns;Qk1|RIL!U9!NlkkSD9#z3QP8b=qi^5ps0fy0qLl<;T2V&(m6`axY%2RJC@Gh)`i zf_PG7@t(lwh({lW6JP|2BHje|f#Allxnd z=W+ATktwgFV>|JeO0M&&SYYR!%+VCQsRMdUG~uZ^JbVyu@#NC1g@wtNaof4<{!h7} zs^&K>L@cOVDyazf0b|93-bT2MUUG#0xPG(ug>`!WH>m*j*CPCu?x>N}MbU_^KJn=H zjw9oNOF(3Nk&W?B_m@}Pw$lF?Zgz2*7=7zAdCV}`q7(XWz$s%omE zsVpkiV=)Z`m%Vqz4G4_>4zn)t{f&tXpP@#lgoXw5hGPQ*qtOTV&eZU6+M3`rttHTu zL8=rAFN&P))ymQ|T0V~p2apsWiVRl8;KtZ%@FW8jnT(XAw#~f3FJ^~})W*siNpU)s zcMEnNHygrEeKgq0SYEA?2?dy9RZuW#1cWw*n(+wW0HCGcU=Q@BtO`-G+fGw{ygCk+ zU16VvpXC&olAjx#^ee==F`<6WVmJ_0;vp{hI=v|qI8O| zQmPJ@5|eQmU{QviIqklazy%A^6Vtm=AueuEIU=8E!-KhfdA%Nv(Z+R%BtRL!fGIRR z(tylaGIqIPtH%h6=M7}^$P3z0;OqW}`5JpLej51~45UrYNi!i)i~Pq#P_mlgLw4nv zC28OB_aw`UOudN^nzgrpH=PObV++`IYH~_4hM<$t(!jczM-RAGM zUycjfdQxWmN6D^3Ui#K-k=T6LBXN`$Lg(wU-qT!DUj6$Cq9MWgoOKjp{8mO2JEN6U zeC>o)K(}5#ZggyKXtAXsk3aB$b$)t{z-x!rZV4EYC!)cvdUz@j*2OJZ&ODJ0t_fE1 zfqI7H6NTiveyidjF^UOClh?XFeExhlOmmDH{doFiaC2jR9Jg^{5O4UcA1-Q;hfg17 zX6h$*C7gO`YJ3r(>fI{#OYY%uNHv8Y7EdVQd;P{Xo$a}1a^GIQZxy+Cf&ZCuth*%h z3)s`#5D%Ym0Y^MMG*oLj(|Xop_z1|j zKq={1n=~vjTVV9$J;=dy(8*l$I^fau>xXq1oNz7syO{Bu7@fI!ufgkS(uRzRAP#)zyi3*aF&xHZTv-L)ozi|_E~ zg6t@I)gosgcqX*rh#7z+1I}uA@QS;y4liz$gTw@YW4;Q%WzU4cb<%IvL0d$<;F7M< z7;jvR*diH`4ab*gietsf<6Z-sI^~9{YqpMUllm)~j~%PmPQ5-1Q>J%uOcEPgn5;w% zJ1VCG3&cxm1@Y1F5K$ILxJC3GKqGJm@<0G15?l*^6d?bJ_J0n*mF&23%U53aK@Zt=!L0#+_aP3VpaEi@R^6oX zx3g5ZO+8-Fv6?ih8jmk`j|hsAz}6h0?k4sAQ@DA@ca|k_pf_mRS(}>Fz9?^^|H83m zE32{nv)XO_k#lO>_g}X!9eu7pdaY(VZ@Ycj_&~q!w%Yds{*D!M6N8D2nviaHsreJP z4JM0hwizcn)|{WW`F5~iRo6Pcc=Cn|t^~uXZ+EO;Ffp8YU9;2F=%FUg;({L?+i88> zv603X3fXV~^IXD%MZye$qjgmD${AG=Hp2>lzQ)k;#al3AxBTm$a}x%4}PbI zx9$GXOg-3NKCJ$0JR?fOEi@Uvkp63;vGYgG?PKfb)PGOE?%Zj9er)4f?e7oUoj*Gd zj%~)M@6Yo;-|aUs-pZ)m|E&FdZ}hhD_agN_tB%iqy?t)H(^&iG>$T^<=MIc_d+v6p zI(qCcnLPiNoBH=hqhwgjrs?lb>IZwTpa0!?Zt{1#_TbO<^Mk(!CL2TI015}vg0lp1 zV0i{u4F@^OfEeST<_xF}4(7~&dE(%6a{}dkSRV$W-&2vpGr?>yW)^5{Vm5s4tEhU(ue;oJL;bL|5FiNZxH5RQ_<#us2yr9`p|MDnFXOA9)!3A}y<=d7txY$6)K zgg-72=kq{?6u9B%y`}(Q*Nd}-$vGz_H78c~fyuLvCzr?ZjLb_cz}Ps7vY|d6p@oQV zAW7yUIV~DWrK=f)7tCSFKXyM349+Y*mCInSjM&keb=J0)lT%8}uvWR$#@P^p)MytjO*x0?L9qowDJ z<$cUceQe~mg5}GC)fBEBExTsC4E?*{ zzFTz8j3Dby<4$CZgv*6Qxg&I#1UGXC?cBSLyv}d{h{Yo^neKtUH&E_&4wR61Afmqy z-aF$(T3)q3_bv;#nGL|nOi&JUp~H7Lj^a)NAY-s&(&kVN{K@<-tpM+LL%ts^%c-3Y z5t~FcI8l0%%4-J(ihaas6w?UinxMJ3B3?b-7lKoKdtMfB#V3IQeum=B3oApdc(oTW z)m^5-$Z!^1)?H@4 z2T6#N#Kp&o1k9%Icl!^E1NKXKP(~S)6fl>DpZ^LAd)x;Cn0B1`q277?N3)?~_#+07 zU+~BgH+=Hv*iUkPSw6GE`@=^mALM92M7qLb3GtfT5652|*V|Zgg;&-^$<+&eah5pT z;91h3_QmOFWn+U|Ez!JuR6NdE_`9daB1r%if`r;z2 ziW!j&Uo1B;j)$=E8KQHugiF1lLbf(lw@2e5cKVk8cqaxhYx~Iqr85Kx3H!AGZ#&9J zc9DASmzkjT7k@KNQ_I~3{d(3GI+dwC^5%En=Dl31x+zz5r=ikg^RO4U>O{U*S*ffC zl;Dj%H<>*Tn`IG*m)}OIPIXGKPF|eKuAWXUy_tXcaB1}nTd&)xI@@18JF5EOZS{va z)w!kWxee8iJJlcms3P|duA+Jbz|f|}Z=qcxw5)fUZb7H!l%JJ)>nR9m`G zvvfsmIrN}rIZACMzGfv=Z8f`QHD7IQ=fu;}4bJlt$?zihrOE^v15P^!rz?y^@z{3e zu|Cu+2(G=4tehA3Jn|wB;e%i6DCTbSSUk0+Gq<`_ulgk-1#Skwtntuws@yuEC{P`k zB%pi(-ub9_k`#b-LL?afR4p1dDQo|>53ZB1Zcc$(N5cjc(m+fRyYBnl)H0iYINuP2 z?Yb>dve&O5-_9Mk19$&}tMUq@O0QSCD-t_wG+sqVcjo(p4pZGUx-7tT9Motx5>XgR zlna^PGDy6WZ^tuI;py7tZg<&T$KQh8a!AK3Rdx zDV8G>5R03F{Jh1XYaCS@aTGq!L646j6NuY^55V~RzCH^pAbjbJ*dsfp|N8g^WVAP) zgIS3KNxbjOgT^j(Z=5UF95(`yQZmz*DdEMN+v;>uisroMX_XjPt+Ovqo4YdO;4Md{`uePReqo$;`mO`VJy0*4%qqd2*jzy!6 zt@aU@#v^C7kNP$qy{fHyqfz&^w%$3UKy2erjEcUgq-1`hL9Mpo(?-MR+C~HS8jW6Q zAA8q$?4!2va-;F>3%Gx@xBh&1U%xE8_6Dy(gBBbgasrSk>yBIy#%xpkqCtgXE32eiw2k zJ?7+tJl$9in-d>SRK^Kka^@H-2>kT7EzpOWonIHc8q)PC_*CwaaXXwrEUf@i*r{WL2VY|X`8?BZf z@MB`&EXu~S&HlsxwD+dq|LHikO8KXAzq{m1=WT&l2(Y%3#8(e)(q=-o@^SQ5_-p78 z7~^v3Tc69HPrUtNH`c!m;B*Hs56a%Vv^AtyR<-p)<>~BW1GRywZ_hQ~UAi_b^Ra4s z)ad8>_A5L>_4}Ba@MSh*%p~^kOH19a-~YuJ`!VU1lymLPidM>xx9;a6uD@H3;@O$< z;mWm~UO@p&oL>*e4DGfqVJjYZZnprj>vJr`W&Y71-q|ld)j$ zM$RM_eZ9OG$am!px3=Ae{GxLoy|o8mGWPCc1<01zVSD_yoRqZn%ECT{-?Mmr7=Z~W6wwk@HYMwg~pqJ}KQN=4`7s2#n54Fp8m}0R`DXsC+sF8n#JNpy%(e zInx*Apa^*lWG@+jT&rNZvmClO4$Kq`_B!xXm_7AF_O8Y?DoSR;bb-s)DPF@VDDnOl z5$hJ+rxx)oiOgMu9msj8MgNxUSDYe@>h9Cg3P`z9m4ThXT3CB@;XGTw;$H>_j2)It zd4>SoA3X(L9VUd09YPq@QO!Bc(hlK^*%wBNDVULVXyw1@fihyBI6$;;)Dy(mbi@## ztXnwf+^m)9Elsd6&_KI&Z)LZPl&IYp8ut9Pb&ttis*zwh;w`$JGiY6^b#G|IA{>+o zP%das%f9q4^~c<*D?R#j=;f7&?FTHUMAe@AC20Eg!xif?gLgxtp=}w~ZfNA8xp17z zTr5o&$KY`Q4m9K1ZE=RX3dcUh44smfivV^BOYj$C@dn=u&?)6+3RdI4odBgjRerbB zA~MBD-(YKNcupOwiS*p>#fm5WZ$xayD24cN-42U6@u^}0*-9=3pH@7+Q&xj6CXb85WfS`uFNha`Ax(-;qZOHvm z^*$2{NYCG)x=JGjSu3H7iEj&_U?2cSL0Xkjxd95_biqZBo6#_;A_#D0MI)gLLtUwZ zpb{trs%Bs_;Hd}^^tT^iDzTS|9@BnzE#xt?Q z2M-HyxlXbdJ>F-)#c&Y0vFdBeN%Xf{N9B7{Q2rd<)6v+UEy59MA%|r@tlE^fy-h)f zHvVRO4R(=(|EUQZI5D@C`?G!JWNpN|;kli*pBw-?slP5>tYqG=Q+>pc4J5D;&n&nQ8#ycaBTXsh4lj8 zgWX<5oBFKB7HF;zDAygDC6b79e;ek~&PT^zvRnX!vc&wP%RSD-XU_ivAJy__A3x$a!wG{BtFnsw*WEvU`KTs=m7W3n2UsRTqX% zB&2@t8k@5Wi#QTX$A9-4=1U`bty127Bki|G>yWawCxDy0v8*$XKhcZ!8 z1P-gsf(h_FLuK7su=*_?XoiWyUqbVpa{M^;T_oz(1H{;D#*I-)(=ayU2UXr zQ1nI_SquU2x?DVF57`tJk`APB*Ha);p)uwd4#n{5c%l4F4g@GD|0o)_;tZC8F_`RJ z${%3ehFrUFD2I%_0k6-xrfiQ8V%_5Eg1MCmIo?AGO`+{wC|sBr?q-l2`IhE*B*(mq z6eaRD)@HL1n4`5kjL5 zR6xFf0OSDxLW+^<7+o<)er5N;x`Lhrw2ak5Qhi}x5>`84cCfx^;4aQIQOvTTcql{B z@$txi>Vy7$Vf+6UebC<>+X9;Ww_caukBoX2JmDCh3IEu zQQbroyZWJ6&B-xx0G#(N(Qe%H3$58N??T>Arr>kc8w3zV{=&?7G)H+{dgdTb_LJx}TJ{eMXKIhk9j_dn+$_I}RmWY)BK zXH?ZJe!QRdhxUbp>YQFydz~NBr?9f|`yY`nC()mo+qcZbXvtFA>-HUigl~xwTD#yv z)2n~1G<|MH7Wg=2{n?3wle4(BfX!(9GWDbHKhTq8fCru2MRh!yQyx{&%R6TJ#X4nd z=+Et6VsJeQXosg*!fHx!}zpI zFC6+IIG{R;@wnbzB=M77*!~*7{*7-CkY~@q0qpG*4Ouf30C2P6%86n$C|ZNQ1|x&t zn9`(WH~?sGB^^*?0%l4i2O%Fi-5OAkQUXky8`3!dJa24Wti&xchxrPD*J%td!H#7* zp{4v%=`r4@*KYm$pD0d@Xc4+CPC@SxCxGjTD`!$(nb8_Kw_^N_*S$0Z26YO;(Sk{C zYg9fJGYF<@)%r&!mHQF{1oo#upx$aRvG{ZmI@8#c98F!nRu0f9_z){Pmpl0p$O?H1 zk^Uy(()BXa?p3&~#@l*hvkK(20x)TnQ5*fn`tGet_hqYhZ8JY=!d_N-Hoc}6E*00x z>8*JpPE2)+?$psvR(T5#PxTw@)W4)E`5;ckW!f~`#cal$S0A1pjo4{q@KpPGKqtqS zD%?v?RtLBY&%ABhX_{+=U;6w#-sIpr0GOb=FA+YyjqzhV<(j4h>N4r`d^e=~uOkDs z3qg-0?#cVy%Hg>Z2;tYsk^&8P@jU!d^})EjHnPNWr(s!TEA)oc?91`+jxz-{4Np&Q zME;YzaQLIn_|s0`Hub3C;*Wo90^sW^wP0}~VOvNq?{CV zikxeR1aVjaF=#&~3<$dtP5ll7%pm;g^q9llc4-z2upmI6rln*iQ?U@41;zg4tjy%= zRSN=7OGqg$ra+Eh~{(+ z7@#bL=GuR2z+?Q~wS`Q_JyC#Q0g9Y#hpd4a0mFui13Liavq9POhoe^h@03qD>LT7$ zWLv?sPJ+2Lf^ov_sH$^$#U9%RBs)G@?d?cGm*=@tR=HH$w69rsTx?6^k04E8ZuH37Ta3`RJYR{QJV_7AIAggHrJKH>dR1op*_>IMZf9Ka zKaszGe*}12m@Q$nwe;(beoMW%{|U$2 zI%r|DmHuFVQSrdG^@YpmR`#>~&l-1IM|^FzbKmbT>Ah+ljnrY~{r)$2E*p^a9x-eF zFL>_g_fkXgg~&}a*%sx6vX4u%V0*kpAr5W-%%`j98=En9atnpblI5W@>r@+9CO25G z9^AjnVT1-OHt5@Ki?fI+-!~PnC5nCB>%eIMgq!G}RT$TV1eWyHzR}n-}0~jc2@)HEN3Ee=kkoT?q6TI_PN5IecliH>c!EZjs zR$%cZ<_@$-VTs!N#qIOyD>NS^tsja<@ms_Cg@h}wzNyJZqX1H@pfT@F_j|xEj@6h0 zHnk>d%T&<77x(46OVpP;AfTLk6AzUIoPI$l(0A8q5Ns<@Awh<)bj5gBS7Ll`svtaJ z_G+Lh^apwL?Rd8r1&+TKDM&)33Br>LiE}QK5Ne@Lj8i3$;%s)7doYG|*M55+2<0Z>LO}gkG zWte3|IDbp5x)O4MGJB4T>0f8}^{ec`>cr#&~tw7Yh zRVp0tAUhJkUk+hF9cUOQzvveG*b0|ejyh<@hm@Z>l zk_dN5Ds&ZV#|AAqP#{}L9g1RcF3E#>+CKM^N2ZcTca#607;|@X?*0nn%WR>_jnRb1 zK)N(Owon9I;n=%-T}AH{XBvppmCnln%r`}273qk*Gvh*@J0 zt;@kVMoSqaWz*w)?TnqW=xP=S;vj#cB05GxGY|-{(m+$_f}S_fHZ5pZAfOfrB%)!( zKmF}#@od*f00)qwd;N54l+?=2_dmn4>~3{q`45LjLDRC5FC=={L+k6uA;T7hVy zh}cX)_O}9@m58)KVY+>xJg10aZei*;Xl$rZL$pZCph(B9=x9WdUT%>=TanRBk@2r0 zyl64epxDfAE_1IRE#~NR0QGaVVq4H{+kDCmf zDO$yB)9F^OYF`u3M4uRFs~VZ98dY}b*sIdQR8Mg7Pr6k@|5Ib~|5uGk;j}FyRw!WQ zf4qrZ`(?UX(#DgxTH5IUVzrDBzxD}Rn4LQVRtO}oJua%SLc_W04wNrmfFLJ(5IVqS zS5>=nb|qSpU7W#zmYFa0Hh&uF4QvbSy0rqb9$!5neevt5n7^Nttf4C}x;S8IL0?-O zjvamt;kr{<&aFj1EXsLzfo_Tde;p$}+h}O|dV*{n5rZ!p0pSnvWzzpS{~?MkG(q@g zCE;1S-|F>u^>0qyPhv+5H^d(ddnTyv zOclH_-I=zlNZOgPQ0?A%Z&m^MIcu!Mb@W5na`lZfZvPy7{rQoCP}^n2ek={0r^WcN zCpfVMT7HoVYT@Q-wxhBdkPm6C;?7r{!yB^?Rj3BoCv2Qwc1y!hK+iUw@B$?d^5sBx zFP?`Y8}8-SIV&T55VlQAqjDP-emjkuXQJ7311R&v8;)n3@6+$Sc}XsgDK0aQJEKWDR(j zV3)IK$UU?fsYikWf+<7sfR97RoT`*7bjXbRpwg+m6geM;SQQf)dt?=r^aDOua3gZUdI@4>c+q8tW~XLH^G(9ZIC2&&A^)f)_e8kcEag_j zgJWfbVojHJ`_ymQDe2?DhLt)8)S^C4PlbnM^V|y-@z}#4V&EZ1*E-w7Cjl5!nT9u< z(AS{MBePTnk7ahN0V6nsp6Fn>Xkv*Zt@mc=zU!%}^AIW?0;uDZvYg^+(wwpnWC(f2 zo<9Xb>lysuI~CSXCtqC+V&%&Z;p{0IlO&~6itOv4Y0R(QQsV0E+Z?&4YJF@nXJ09? ztrDFQ^>6U!zf_oW9DWwXOla`r;J$=LBAE%8s7yI_yfnz?9YK1kyvk*v!9+qI*td`1 ziUC(Kz@6nH|Mkj^lV_M_t6C`cqs>-gu7J%?Etq1?_lDboq~+wM(`_s4fXY?D?_R7U zBr~+BE~WaC?}_&_2Qxd()cYz|ZVa>S!#huz)i!LgdL=9Pa#sJ#d(w!p6R}7<4u&Iv z`RMK!mqV($Qyo2QLFtuRW5* z`4Z#E#@9z1^M8&k8~@&WWoQLw{P>=rYX<@x$GRDg+CEU-HYuG8q+$gvf6Ij83GF>< z=*68F@hKdPXXp#BXI+eVa>zJ#L4$t2yT*B#F%WfFEz7QZ4OC3^d!FL91|TjMv!q6|L186%>s+T;a)%vdGL+V%hZ#S_&t9BOSO+{>t$#dwm^DDl$ zjZr1l*E*~`4}P)#Bs+>}9qY#z2$0R>9p!>4oa0r)j4AOOtujgwH6hZ6uWBV7+u~MH z2ZkA7^)NY1=O)R(XhHbZZolE*Z}hwEi~kleTr@TKA0vhb|3?~=mRB7cH(vdo`~CMP zlecp-!FGS)(82Cm7wSmbtNkUzgT1k<{LhMRKU#G>_%-#abLZ)+KO4fb=&bVI1H3Fb z@}E!rS+IJ5)Uugwc(0!fvp3pc4+&zD76BCgfTY9p25{nipA$sx_J?-dyZA481Q`r1 z09PKxtRzGoVtRuH#lntK>&hq)3@F4I?SRIJlF;0Np)a~%87#n;0=Z;CdA1B@;G+J! zNWv8WLdc*}0N^20;cS(J9Re~BOw4n9ashLcMz;+>%t+{b3haa)TJ!=Y9nAp=GUrhg zC*|B6zK8ZQ$J`-{D_WpW58iZTLmvSkeKRhNfrS1S_TKy->b`&ff6Zbx+iR?2AG=W5 zk}b`k$d*)y>Ku_R3Q0&cV;!=LC0i1aosbwyH6&ZgRLYtVMX4+;68XM#)_I=S^8UQ9 z_x1Vy@cDed*PnoKo8$R7j{9+t;i76$7-tR=CPLfH*`6tGTLlx-0eyqcoH27YVg`N^ zK7ucVoh}BsNzO4CfR6!-UNaN_XbcVT1uv z2!hM$;Ja!Vj}4miIZH?r+Bn@E<3W)eg9SLiM53U1VHkl;KTASN3?>Qe#JU4O2usRd zHv@W19$%A%c@pEbL@)*$n6$z+Zd3YuP0CUjlnN%!V zF9_U11a$^e4obs641jhvAQuiWQ95@;4HS+|5%4;XB3X?E-u)WG4`T(ri4IUp=5S&SYh9d-Gehf#9oyYEhl@wot`vHqg7dg8l z_jGgP2MH_vz^X8jr!W{k?sB?OL>@Sg;*X<+6w|YcV;hU(*8bT`EUU2udWPjJm*k3; zUezlta4anhDTUr(rC!3HZbp_h3LA`-UJnr-5h%N{EL;;(*4S9qJXChuk=Q2>a;cSj zE|>i=8#2( zjg_-QmG74;q4kmlz3U$xuYV4?zLa&nuE-54epng0zAMiLI3}RK6+Fk_S<|c9nZ$`H ztJ($Q8DsF+k5!q&c(4}L2I|$wylTQ**Fk0d!(fe!SWTK{jqGssE@$|?*c#R0noZwo z-hR5QCdRL!e`7Ox&kb#T@NZqZe?NZqpQ(tyx^(|XPeuHixXccGv;H>hezyH;8qRV1 zKe}{YZ!4IuO5gsNxV+9nsmxZj3H^$nb$$w0UXPzW<5KS=zPo8L#W3O;2z2V>L9R;M zphwe=9Y0)!F?rZ9``xueJfEUZZX)SU_;7yw?7A61O}@Qu#hIbMZq-rl-q~Ct%fL@f zZ~|PI{yr=WZ_o7vf&6rAzFlhD{rL`MG638o{w01kyKrBvLv^u7tG_(6L%SpH2brZH_cYv&ySvBjMPl@%BfwThrhA;S%h}lSDqp%o?S1w67@N4O0!3!`lpW_|9eS<`)py?8E=ZJKd~>7-(+{VY zkOGeUa_Q#dedF@QUz>HnD)JH%{PF89U4KxX{MnED1iAbpx1$yqbS*1%=RJ_io0t^r zMMaAOz)qn8q$of|YOp%Fy@|*}{AMVi3TEy`O%Y{MQFgl+dyQ-@#274D)32bTsB4PE zfoq#ieKptILrh0>xo-a3_?esDVkSGTP^)Oy124zLtbx!>LL2mr=eE~6WaZT*l)ABB z)*tb+n+7$PkJQK+yx!FtGPIbp)Kg^0xn+%mCUD{kM(>*9iLlMGqX4i~N!Iv?Qg|Dz z&+x)QxxH>cp#)|=Z{4Na+WjcuhfB8y$!M)$jJg+?R=40_>@X>h#~ccfOXqI>Bx^`( z``&4qg{}sNaTN^*Oux2LNkwGf3JL^t2U={$!U#MU$y=IRxX%$y#DGu5xN$PU%K=pL ziRTSfa<2#=ini__&sFsfC-sGN6g7UT@Qwf7r3*n{3yj1cUhM9_z5MAqmAjmRws1)A zlTsSG{N`dnN5r%U(O zw;}UE#UF1&?n>Wii;)S@FU(G>O8@lxBd_$nG_d0<1Bxu3zj6H1IPjn{u>St@_aR@J z#<;KlZT#%;^v4$dB!U^o=-}ap2U$cMfE7Ai(@9f)Of1;qgBG2uOVT32r5dfVT#sqM zNjo@@%Q_2#{2R~}QIUedB8~2Fkuq)%d(Is*CV^Nr7V#jH9-etJ%212KYf@D}KlB!M z*bENP%uFOgNmw8N2Al%P^1v9(xxGUGv0)+1eZ*0CB!gHx*P__CjK`de?kX1)HwJX^ z7E5FLCX~6@?ZX@vTyh|~frRC`pQG7Xvqp3Xd;fS)Rq!y3&n;8GMK(ajpc zCpK-Kka-gAIvJvq^F6@VXycm~jK;oO zx~IH2SMh5hrjM(*wN~S}@TLeVOn!iM1#fX=Ut(d$Z|$84+%?X>xhUY;tskC)k)jij z@UE`WID6i!7!_5083zU&SO%yjCTBE79el}3U3j$4SliW=z@u^!@A;sqa%t)(azOBJ zvd36yZ=!mJcY01CT_WH>e*tL|`)%lUw@yPLj8M;r570*)G@sMnnX_^^tmE^2BOYy| ztZn!hF$2x>->b=CzIc4-iiYqS@MPHF+(H_EY09R=ug1I^7oV`3f4Fp~A1>zna_Ou; zUKLyYed2Q6rGwsviH&_lzfW8`^fp2hm!B%ntiGl2HVt%Ge@^4xhmh(fg{}Gsny2_9 zytZF6d40Hx?zWsH*-6cpc;M!gVml_`aJ2A5&f+#q0gvw3;y!i-1B;;W3JGBpZRbFmdmuZ={6_X}g0ai0xZD-zQ3aHq@aGbJD`wUo4y%mjYg(f?ZXo7TjkOFSikt z$giu1Tg`gg4=u&}-DK_#{$Lj(wR+O|qtYSnwdLWp?@PURzJKXm`~Gch4S=?abf`!N zsDzA)$)MtxRIULk&k_|R(D-y{0uD5xppAWgG*@*WQM#bnQyOH^$>>1)mSGA(VM-Zc z%FHlT<{>OQY=6tH$r_3fI$S#_Tqh%3j~Q+-5N@~>P9j7Y=|q?~MC=TTFw2NAXGT~K zL|89H*bpLZbt3mUM3U}W9dwIyWJaD<#~fUWJXpPn;=wnnX67=0KY#%a+o0Ud3^%Z& zeCYxk=ED3Oq634XgEFGiHG=mOKxpUXKj^_f&YSPP-TZZN`bpVuy|-_D`!e_P{*~Q# zZm)h@T73JW_s$*YZ;nzLqauYo#%LIY;;}F;?diYKe*YJt2inenXmO}aC{2kYpbV<)Vn0074PK^;tt zmf7k92Gmv(uQ;AmtB9GbU}=zzS`bLk6=)+QwvpS#qbGNF5TjMs6Iy?w2fu4SP0uF} zy%!(Io{ziH{Vmj(eH(SKd68|>d&cCEd^lCBbCM^bwS_WJ9nf*wa$60X;-Jcq4czB5 zxV^wJ{>T7IBIy*FD1NqX0KQ#~jVChv1`UDfp1=gu?3pjOge}%KvI#%{c@Q}BO($A} zV+zlLCu}*ml<@T#1%$^6<4Qx}AdU+3}wwVn- zjv$fli3{)!d{73e+R#s(c;#@DZ8oIHaLWQ|T?R#!ZcdQv(@SwZXcwkTjDlG?u}l)J6G4RF#s$d5vi01!^~C8|+J zc4o9;vA}6VxlvxfB1Yu?Bx8Ox5@EwjOoY

    p%QOh;{ddjK!>$P7~S?2Vm>xZHR~ zk_3U}i>!C1B1)Xh9#D^LT)(1okSD}Xg~PhFd`}-3AsQ`{wR6QEIckF#$cGBsQCC89 z*bt$Zelvbg)45| zwcnSnwcc~fi&u7fAxMf-ku=edxp(l!7NBFP3ZaeD-a*M2LJtN##*DeTfSoGcKVS-A zK#8o!h5oZ zKA*`lV<#n-?klm0FWpyU{nv)QoH)@rR{k(g4)~BmGI?SwstWu4lM_fu(evKqrsJu)}I+ zZSgK$8Q`2+_`|=U5fwhNb?KiVKpIjF{RSsTHEV69iK{D}c+~ z*np<>)pHI11wC+M_#h7E!}$LOJvj1Jh0Mh@&Le+{C{U>uqfzdR_ha5AF00XXJ@iViQe>pZMZINkG7^4n4eiKm7UZ8<3;_TTyfU++_R zZe(;=zS6k#wa3HyM%JIcz>VzJmap}OMM`PKCh{m5*zHjfEdez;2dOnOJ%Wgo+ZNw| zo0t%_Ai=qbT`+NQ`t8yIqO?aqoGd`)q|_o5h;$rDCCS`A1R(-Z`8QHLrJ_TK_$5zr zfiE5v6wR69%M$S=Is>(h9h-oAIWRI-PpO4(J=nF*JOH_{vg3)0O9#V}zh`wAWN4Ei z=D~-z;F^T=mcYteE^jnUuJV;cOg85q3S$g+I1Jn%@%e##9=ZMRlUh-(+Zd-89pGrN z^R?()KdM>lnkZOrB(pk8D_GV|RKVPMUNIw*A3~JsX5HOz)i1ipalF^FfV}eVXgvQZ z1G%-elm51q3oomhr|t#o_C(7rW}=H;Z5?Hr>3x?7i?ovJ4}T@=7hyOP66yFV1S<0M>3P$uF^#F(BSG$cp!bh^wL#(VZSa z%1-#Cx5SzuJTeHn`oN{wiNv?p)U02zHL&};O_UZj*x-skH zEndT8Dw{(4!8?D(o;WSL0cf#PvfRvk~X!t{UoyG#8vM(WwTFbKX{6S?0p7ADT0!0GZ{tD1oTDcpvz}ctstd70y(ei zF^;|B3m)_U%`w0sW(0Ir6=i}486hY9P!4qPWD!^*1eeDMCp`;taIlpJf=5&nam5# z0~c;DU0@O7T6N;u9OBx8;vV)#cX|jy6**Eh0rv^99M2I5DT z;>QRH6FLc#4hhhh`E*9Y8)m}nz&d&`N8is8d3@d>@v{ST&PZHV5}K(>REF^!pGuS% zw?X3fz)Q^8K@41pfI@B@=T`N%kex?vMNC#1^Zf+=r*=8hL46 zZ%PhIs<9=2P=JLkZeKGWgtjtB4DdRf6kgtJ7*$qw{akJ<9H6k@Rx_}Etyma9LBcwB zS`1(icojyO5&+O@M}(g4HhO^*cyG?j2H-FjPwmD6&B=j{ZsG}~MkUhQ8e>TWaQA_AJSPjznW4&fU?40Zba$uXyNkW%f8w?F z(0$Xvy<$E4^6pbVrKl@lz_k~7a?qowLfc^lY0RjA>5Qb`Jl4N4`DVbdgc9K#cJ14Z zQEK;D`#LFB)~2ywXqN{+oZO;(n01b%iq;ZONZL+6-Sy@0&dxG8Adcw^H_dRrJ=J)c z0h?=#CLZZ<(!4?pCg&fU+&zPe_t8r+EmqMY+`4ge5sg$O>H~q|t+X1^`5XFa3pz+R z?vl&Bxml%9nuJ6E_y{z+ZirXmRV(AZcVQGOUjTU|HrctPC~4=enFi5ar@N zd95%~Zpff5mAtZ5aOKt{75(TkCOV>)#(V=)BEjy8=e8D)d~gpf8%M7}#n$%fpnTgh z32z9Uf>n))5y|6R*8;-c(~fU2V!ps)C@LvazJ6cc(q@g&fMb#?SA{=y85yP@ZRQuN z6ov%Mi$N~%1knURlR%9b9(|R;I4vFW3BOkij!c=$h$F2{>LqC zZm8U6;>S)2$bKYV;G|8O+eU@Ss20ShdM8)7y;44(gx}!8x`-4uq8g_mIb1Okyh#7H zeRfz!BxaN(Nowa{zkvm;#0cF+Q)R`S!%@{!W+u9Nk}JN%l)0&kZkeF8*-6Emk8)(m zISv{@+R0TeoJ3hlmKWd!64`DkQD%%c@{=&0*_ZGT_L?pL^zL^Oz&z%n!etArGh`dw zD!nlk!JQ{}U3cx=de%sF`_(kI%k5KdU%Hq_|U{P^IBo@9vEVRVvTU@o? zDf*t%l#Y;TXVmP}nBow|yb0_c1XW6J5Kohe>u@ldXd#l()6>$j& zz>-GzB<-g}Z`P>-&R=WWZ$wwYIX(`TkKhNG%ai*|Yp56CW97W`w}*T8Z8PGz9&5HS z2Ja?haO|jG?GCjtmkVJ3?(PqWozvG$g+Rb)O%&+}I`sdR!iPBP^GuK5;|TV&ep2h3 zEpqIvE94_$59Ki}4Onb}y`}~&?f4Fq2EgJ(`sci`bw@%uEI(O3;5MF`A%1gqmo+7V zHy01T$?3lLvQtxM2%miiKi!QS27U0-Q6S;&?vx`4{@^cqycs~q2EJ%xojAlM@p3a< zfAWXtU(TTk8(qn7hwMf8Yl7sArwk`{M6-Q>ZJi2xwSvdqWTzuggeqg@D0oWJqy5@9 zUYordK6nlnar{gEFubmwS|rrgDDF2PK?0)YaS*FBvk^E_g`jb}9^IIe5GQe@J#N&T zNC^^8)|^o8Sm3|L(K4^bZCe@UExgvifz5Hs;|mv|WbRY#tT|t|T-C;iw8&+(I?XX4pV*_Rss~+&G5~1&{Io?MXE86q@)Fbl;ShB&^>zH~Yint3Xi@ zuL5Q0=fc!5z($WSr(~E&6^xq*a_8;@7-}dy{1bXTjAD!dq(LM2xQ~Gn46YuI@Pi4D z`M{DvYbYOK7VcdWCPsugF(Y~RM4+WlEbQdpPmc^Xg1Kcxc`>8B2cnKIMfnn<{dJ-P ze%&`Awl;Ji`rJ}9HAq>OK)-0qA!bI;)WDqcrPBxK32RF~HSXS&@YDe%%*mK6W=!@# zOwLkFZiZ4n7#p>KI~gKhP=ph-KW z?}FIsi%_6Oa8_&R`Xb&h#VizK03k&yejOh}-BNIkKb($=tJi z2@_03NahCnCrk$^LNd2T1F?Ytf2wqpcaQrskHqoU3F3UP&3>?qDwHTgc5%;9UT4IW z8whC`4Q!|4Cv3Q+XXLx8 zc*=Zn-GX@8%w*>9bvQq9CiZ@Kon^gI6Uni%0d(J5gX@q_d`Fkhc7_!J;so(o=!dfHO*Hf z-Cs97;6OU9H8Bv%zLW^OW2XQ1IQ`t9JXIvaNh2d7Qyz-H*e7SicFAcEWH`4*plIm~ ztU~I6%)|bf8C~*O4VjLQGjn3(b49Z3G_neI$rlD^l{RFR4`x+<&8iZ)RHJ*T_Q0h& zY)oSCrN)L!&4ZV2f4#&K$!^unZaa|O9-Q5oncdxx-7}c|@M|_(Bi;qu7f<Mn8T{ouAqyu%z{uY>3#C9njWBT*GD_Xyx)We7gX1$EC$ zu+ws+FG$bj^6KSSn!(Vx2xK)Zg#+Jar@E^%0x2qi-Fs!Y6 z4|PzdXnJjCduehw*BA^>gz1`<03>+(G+0^#SOx)N)Z#mjfb=dS1gvxf3uU&{3Wp*% zq+!W}X_>|1`Alsv?C$FqtPZEm1jL(;`mL*#C%AfBkZ*P?7bi9noFJ*gN zQ-xTZA@TcOmm&VBawrs`UQtPaIp2hRcggQE7mo!1cOoc6{DB}<6`&qneJLuw#}~wA zVT9+e%{Pj3;;zB*7!f=YK3}MzQ}y+Y*sv1(I}V7Y7V*B4L0}P;x zOLD@tUC$<=tK&aBQ7FvN?7c;*Y#0Yf;HJ zcdAHGoGxSe^AQ?#&fmn}wN!Wx*B#`~J1$o5uU{YFR3CVzKIl??NK<|2aQ(S&^;9ut zm_9SYi5YcZ4nRU%wCLj(oZ=Hl)iyPBeh#Q`_e%9NoD z;;XDf-ujL9DquJ})YqmG3Wy;h1iyuVi;duws_T1IK!`T766Ki6D&o9^$<3_-s`3Fa zcm5bydZ8f%0E8{TdHrkV!-88_H+WiV;n2~X42{wjcohH{uW=yZOYSDi1_&%VYrYN^X_bRA&7iRuCSa}#=hv2U z22kPzbm`~az6l0E{j0t}ngjHiy@w)4e0PaqsbuaSYVBwOm!o0wz;!QmDTQ2RcSleJ zXx@+&k){BO5l=|s0CX(qAl?zU_9zeHn)r`}H=BVCC7oCD@<#1CQ?t9Wn!B<`x^h;! za>cu^8gv&N>@E!LF3#>QZSF1~>8@Pqt`fgrV{pIr;QhML`^@b7jm`I)56TG#UA!d@ z%@Oysj0i7l^xU%~v}O17jPyKQ>0y`4u*G0~-p!9f9}Hwa7;1hnGV(yQ1sI!s;IH1< zqA#_<;l@O^P|d}Mvm+1RuRNR+?_DtH{dlnVb7=2UcJFd?@5)H;_my5if(_rsMjm3L z&ayF=*|=M5rU8}9N04Wgy<7bb-z@=wjdw;V6v5}~%#i4FK3hA zV`0i~iVN1yCdGxN%Au>}P%GK>t~DZ}y!L&hF^?{$)|m6gvo|V-w_>!q#erI=qvno+ zQ@?hd(t0b|@vTO+eRbE2Zw|PXy*v5C@@qM+@_xS}rtd9t$7=ZdALR|dw~~E)cI*RG z-cSa$l6`*r;SPXSons+|z2{mmirJ40Uw}v$fFk71wF%gJCmWz8oafs)qCmV*UM#m?C05srQu6jd-m~Y9DK!E_QEx$xXGl>GavJl&aw}HJo*9^39NaE$% zmTjsGMmG>Na_@;iza?ATjbc^RhZIM)3ZKrUu+TtXRc7zu4@#emxpf!^%Dn5jT>(IA z8yikYU2|d&C*8#Dc^-Ho$ZQn3ZI0E2+UN^^%+D187jZmU_p#dz%k|FpGD{Gl|OTV~H;)HY`KuTp}_EKuXR7V5kB)51pL@-rO6cUdUf&jUxh(cmESW3h6Grv1#f6$>m{fDnb@5pe(IP`e zl9+}@ASUyP=v|#gqEIZ%vOq?-t8=H`LJ}jc zKu&R2mpN2`pV3pGu(hkpI%FXwmuu=uvvjxZx;2=6flxY!-(0Y8u`2GGs{5|{j^B%s zupu+F_pYM9ASMT`PSVowTL#fE=x+jI)GYZz+SNFz#)GCtx zy20uk5KehMhSskl<3#=2rJ5;deY&(2|D?rlk4@|xF2eTZy#Y7ArzE;(mqy4C?Y1P{ zEceh;aePql>}GOF#c@IYgD>9{6EXnQfm<@h3(5$>*cL{>78{PkMqxXO$2nd&dhvMA zF~rqC)W)C|&g1Mb9@SGtv`D-dK;_<7O92~#jCZK1UpN5dI%RSsYoOpFDw zqR-V$>u8TVi}48#dqc%yuEGPXko*-hVrkpYy-!Ma6n*fe~VgeR^ z=h>J%NaaI1br{TmB9=t^_mGLu2tKA#R4?s6zLkphS@KBh)^ zq%;lnY7tcFg8?5#x2RvcCBA_z)>Za>3o!YN3d)IQw)C-X2^#gFz`bx0!jdm&#R%Qn zP|7hwLdjSq#c;MwV1G-n(qy!n^SVxmK$*Xvhq0~0a#v(6u!30RAR zuSj}EJ3+-~K@^QVks$V%UO!ydxDQ5sUkDYSx!&oV6x*J474iekOgjgqWw0M?mO8@i z&yZ^mCl#H1{ZaoJkiY{_ABbT-XMf;+e=79ktzq{s4gK5)&PuIJ*mtwrci&z}|A`F! z8`j|R>%Cc@KTvhHR(XvrA|J~$U=RA-*jj${R~ABFEPIfiDvDn0j~3t3eTirQ7vx8b z_CTetBONduuoFUw03QV#v?OsW0Ql@3_rN@o6dMChRauG+_`&x;FGK+K#S)@A=Ivn8 zbeMQF4AYM`VFbmPTBiD;`%nA7{K4lwqCX&kKR)c?W%lDgx-&&_GVE z2ND)N{2G>L3i43SIIlhOrh0%6?Z6l|9ROqCv}0*(FYNrr*)*@W_GlsS1Y$hOBQKgm zJs5g|9vc8%(=m38NGy%sZ+emg=JR6V)bB`#zB_o^;iTlzAY>lwjuPl^4|6{X*WPjA zX}twRbx_lPP#r8wi0XjkXs3xKdhXPu9H^lXjv9~qoGye_0&kmm+MP;>-2>kmt*Z7q z;Ui=X1|_bSH!u@d1`@w7B?2N0xGn>EfPo7B)k-$V;Q3_@3LHoh!pfHi_y{)$89=?4 z!9vKsB&n}LlDf$X!O2RQ$;u@nSZJ|mF1eqXtf8Btbs$AMIOX^?A(&oF%HcekU@rCD zqmu@~f=0TjJA+frGE>bPQY{Blt-q$)h+MSQy}0kdMZ4gO4w)An8~z>{iX-oF!wNu2 z6;e>WA4G342wJW`h(|YFdGG6CZ@yi5*&(kjxNvI8z3=<*G$t1Ht zxh#^ITIOVm{wC?EWD6tDsf!M7!ACAS28z7oIvlm(RfcPt=c`PQ!je~6-gPstF8Q`^ zc%2>a%=7i-pjRcYb3#AQyuL#Hca;0z)vofrvdlttDi?se^~u87QOlV z(zoD8eCvI}w;xDQn+z{=2eAR*{oYgvP!?~+`XS~oQm zM;#DFzV+?AE4e%uP2#%xc@0!Dk$!reZnh3|bhatz&Byd)hLPHVdn>ai5GLi=TY;w$ zz(_6!uM_=^D?3~{t?2AKmu@bWoQ`JWA3%rR(7Y<1WIpuXEXP3d9_kvu87K5az%r?c zzm)sXQQS77oM|BiqYd%XwgHn=e_u1&te*@*%mH^WSI_EA$EmH%7T)9T;T9pb(gv9D zw>Y@M)p;7Pe%wVKlYBU^FYkiev2apE18VP|eZp=-ZHW)tAa3v{(6Jus({1wfPa%)4 z6#g0N``IVFczG`Fzg6y5#YVz^(DLGt$wdvYy5akExyETc`U|^3#t=N z^*kbO3UW}9oSQwRgbwjr9}moh@ep?*Qt#?U#e<2l#T=jz^CTlyG_R&9KSI*G0ogMYva2}_clrHcUL@)cy2GVJNYM5IDS zCk&-wH?^ik$+~gM-2v@?N6TvxiILkF5c-YH<4tAi{Q^4rjc$JGw7JrhQFKlah=`=4 zSof%W-o$#mj>;*K8~r^;0~S8;9h~5mW=bz~AJ#2(mG&39((72UuCc(hHY6Vx`;Y0ckWC#&4%t2(*-#Q_!Z=N5n_$|Go35qmIqpK^-!v$NPY@_Ta z4hnY4s1j+164QgI zny%-v;2vncm)eLr)h$X}jmvEqvb+V=!Jjuc8ji<=vzmxgm0w7XJ(0VqG7rxBlBmM) zXsNQPb{c_c3|dF8rF{h?v@vjQLOPPSZ2}T_$6<^yv-4le2}-n(;fdS(!!6*u9$jR@ zi^@D|Kp`4>R4ST-FrOBEuRgo3=E466=-@GV<9kSXX?6KUoAu|KORKXUyPJmkAAYWD zT7BpH+X485q`-ID+Y0@{|3ROy=?$)pm!Ljj$qnI4&C`BH36GrG#P+M5J<2%|sZl)Y zaq`TqS<~dO1}KU51NN7?dQfUTv+*Bvf$#s%=)zy_lmDv9>HDE_(zrC*)>Y0scGwS< z!;O3(ZG-)xa@L7eNad^(tCspkjoWpTD|mjW9MrnX;f(lZO4b2b?`|utYC>P%grv+Y!q8llPEQ`s=|5BsxE5{JCL=okSC#XR*s5hrp8TQp)r4Xb z?ofJMs2r~ilEPbcy79xT#!)2!iV44sx#-JOxN_Clp zB?M52i3k7ree#-;>8>C5$y*CX!^j%*eYZ<4R=PfsSpx4n4*gn9xM;ReVqtGz=(^-HXIfr5GPB{jr(=shop09E{`# zK@Z(?OuNY391CmkJ|S;AqsE92v$;B!{&H>&&?q=9^Ha`RGx?af#z9-$eo)89F$0e~rK(3ISN*!+c?& zlE2o3L8sjlWf)eADu?!E`7~*c)Ik41!a6Q!OA;t3kSv4J8iS%;z|irc2A6B^Nitw( zm|2UV??C?M78N^Ts!Sa<7b%fS!2-}?TtF3d!^HISFFGXVu_>A&ZUU>yl|l6W*m>%T zEHP1jAt0%ZpG09*bt?HVPA?`1Jt)?rdp-u$ z#tACmd&43oa>MmQ_4*9nqpbGu$;!A(DKvf$pfi0{UHaJlpOr=n`3&)7DT@P|`?QHn zIe!`@s~R?Slp1tBTjXc*K8v&FsD^R-8v3}-ty$Pn^yK!#sH(e*2_$G}=ep43( z_6`KD&U(G@ynm~%u5Ne9xX-1+;ZdG?W{1^#|4ZLSrmgE6`yadyZ2I)B0^PBNFsu}ntZUVXBr+fQ( zLeryeU=1_rr)fjuOa(f}cuq?oYcRZW8Orx}(8b>R9@-{Uz+>VI_8rK z@65$sou!S5jIZsuplImFXyTQ72aJ6q9p1=cgOPl3s*2Sk+{)oxcC3dTbo6JP>A+#IuROHwIX!o8j$kKzrY? zElS%E%y2_GzXJRG_Fvelf3lD0e{%T$m7)B9eGdQMFqGeveptN=&0O7H(>6}1epYJ# zD?IQ1_Il8}KXUW1GSx!^V>RnDS5426kL`x-IG;g=a$WC(J$P3p&-t;z1K{brY9^<$gw$@T%^1qW-#r9Klty2`Qq+kWjwVv7jE&PVLUBcZ*rjVXTHwYN-^ z?G6r^1@89@%sM}LD2EJH3|!v;7~cr&wD{D@(RjLp+;c%fW)Xf%ar0So^(DP+c?G-o zuYQVfJM?P^z^_+v7CvKzK)R^DNaa?@+U@Zk;9?_QK|=sBE9VyCVd%puX4_J0wgIyw z2Lw!bZOPb_fgE%|TCh%k|dOM*Q)QH@^o!COUEo8{o zem`VWx$sixR5ao7u_$#9vY2lxcuSAX=3{4sN7)~@l_HGsdKr4oXA^3!Ycpf!N`L~6hV;oP|-7380W^3XI~ewvOl zx=J&511Y-Eu59E6?1K4iwVv7FK4O0>lyjMnp&v_=UqBq8YbN`Q$${J&Yt`=bG3MR`m3D5 zR7833&z=#;P~QFIVE&b3A$O%h0IC!QmYa!JFjC%-#H|y6;0jhUQIy#etrQ?DIz4IP z8MY%}a16CojfNG4SBj5N>}rja!t_{=9a{@Ro?hB-xwjEaeMK)+KE+l&=~Z}nA=T1w zwFGJy*r$fSS$tSe*;a5%xIh7^kRzZI;jZ^oXwyv+KB$XBts2EW>0yWtrE~A2us}vG zQVl~x9R#THhd=EMyMR(SOhns9VcX&34ymh#@0b`D5 zi9R!<6O6vf$qaOS_rO82lT?>$5^K{^V;oCE2N6MnZ5v7#EWwkTWaPs>qW9LexLcHg zl4}upH;^qepO#qBzs=;zyH>Pv4>65_Szm4uf2Cu8=^5coc{<~0-)Mg8cv4N-b7{Z& zCi3#8p!0I0^Ph{GUs-)HEGzr(X0BG0toi#XT@;in=$S^88HU^gm{ra3rNy>)qn%Gg>Dz2ch6+xmD==vnhhbBJZUu5X zjfuki0KqM4n~F1T!D*Ll{^dyad?;+6^0rQJNuA$gm=z}55Snnyct870~C+n zYfWg|5}{g?k^s3avv3ps2qD8I6LP?%BuUK<{^Hq_(YuBjCl0%Ir3Ui!*^ES*Kv;52 zmC@C2Ro#5d0O_+(jYz~c@3K`#9YeZ_l#G=JXJ5-hDMJ>iV09NNhzRFfa)p+f;ab~G zhB!%6Fl}G&iO|PLPDUNgc;s;yv227ViIjNJY4>E6RtnFd`V{PA+n^7>)&P8UWZpjC zc(c}Iv|=tS1%-H*v=u10Y#!@Dgm(@D_h7kR(M3D)08tB2C4y2E6MWp7c4zjs<5^1L zCf)E|Z95De_z&2K0KL`$JHv>egUiC}EmGXpJ3tIgY2q1w3%ok~p(wX^2yy6{88opr zT?bE@$@808(mBUS*oq7m1-_9qVoyDCs7T$$bJ9qO6$pG>f*;0D%{OT;UG;rK3jpM?nGA(?Zp6NW@o-{px!ycWXKP75WDaZYx6#cTzq5a%yFkkUC2 ztiX7!yZh2-t?ZA*FH+O?_AWnb`u?dZ@z$*S?r%fGKhIMC&_VfM2sZb^J0;g?xBzM% zK)AJLwS0M(g*$azkfO6ueelG>`4`Dw>NL_kyB>4z%Y}%iaW!pnebVN<-9f{mt)a<^ zP=~yqFW~=shy2#l;HD0!L*75ZJz&q6#~#3+85jU{$OC|X7z(gR3qwhtV-}$c1HcVB zo{{~6Td1c6lET;XoKz1e&*@}#x{yuf$ctbKBlZxE?$cRsjCb+?uez-_#%t6^Z9@a8 zHW8S4<4y8Wwf$%w)-hy~mZx77$M|U)8*Rq~Bh1hiMPP`|8T6X(seSy%^3X!R2Rau_ z!1N`HzBKT3o!>&l`E7Qd&I6%mqacvLe?8Di^eJ>(FNX)WNQwCdp3(-z#w^@WfK4D6 zpK;bD&jP6O%r*%`wtwQ+C84E(Uxspn z2!;T|%$(A-rsy@K7!0NuVnvS3r5NK=jk@?%98$OXr7BNz&xfb#R&x%qp#f_C zQ4-IP4RUV@{}UGSzy|(GZSc3ji@sV1gk(`}!D(&{Y929ZM>6@<8Gz64Iee^|qC>ij zUwROhFC_EgfAXC97FVqQ@m|W?V9fOcgDw6YgN^zFgT3-U!(hqPZFIR!u%E85YTfk2 z1#YsmEaVDf1bMapnJcVNGMQ|N8?;Ta*|}jVb)Vf2SGZ&M)>O4oE@gQY5)VfwHS0Y#&R@J_-_Mo8fd`B4Df3a=Y;gI#JVe7 z--7GI$Q_&7-A$ZfE!@|hBB_&IykRD#YOh1n?gJSH3{I>?=o2Z9ae&pMr+A2urGHti z{IT^}PH1KJPYl+{-KU?jUIFi#?(=yagZ(_@ePP3?Vc#bod%OMmeV~=u*A-tzYjoGb zG+$89MBqed!pE1!x8cvBC*pP^X(ZPXG8M*aFuF8_l^}yi6jWS8$a2}FXT-}DVKkjD zn-D^VQ7I-scG1Hns0`-kWp+053yDfDJCRMvW?4^Tq=^5|2C&IUf zj37GgK{d5W*rJo=>q%OxBvjy?5N-+EZ(}S;R+E*R9e=iFI7j7Ov5~ppVhOeg3m(7d zA_NdKz`IWj?-5{J(HVEYeHRkMH6Ia@r_uz9iY0`Mj;klIN6?L11^Fg_6(%1PDc%lu)FDp%+nuf*^>7BBG*(A_AhW zgcgtzihv*zdM_dfDtd=rRY016N)xf(!HQVexu54>XZGy#Um^Vx!`|{5!vN@IM5~3nPBs({L@4KX$6~J> z9dl*?*-3+T^MtaRJA_`2R|aQouHLy`foEMvAK}*zTjEbJpN7N`S&Hxj1K|Z{h({t$ z%vAyj3WHBW%*MKeMI-->dikGu&j0aL_{;&EC;&pJw98@yE&!#DL-;&&G~EfRev18Z z7q?7ad(aW}$$YiJoli+0gm-)&&(l#U1Dq(|vEW4huwkW`374cSqayJhTcBwI!5sr0 z#n+G!0-=m1r2nG`#5)Uv#r-Wd2)>4v>~0Yv`(GQnK;?jrl{?{wpP`U&`Pk;3a`u=e2WH;n9q_jKtwbTaLT2cC&DP zGp@B%R*ji$#g%3z~`uN$^0s7W z-v)o;<|5YQ?bd9rm_+PZ3}1Bu9>5tflXayKmK(=Z_6lpd{h>s;l-fOiHS?VQ#&62E z9(?d9Y0Pf=9NA%f941d`yzuty_iFfqzd>B*B5MC;x9lGtYk%jm6s|PP;C~_D|6eS# z|KAAs3=IiN;eR0DV|V<1u=&x{>c8@wx|c|rUFR51lpo`Hk7fk)>FG3U(%uW0?L_;y z3$?QGe^=%4d2aGqFcaEO<#Axn&%*b;Z4gY3e9>BeVN3fMi6RGhg;rd_L#_Z+$X~~= z{N)BEfRU(7KkRHYl;3GH#@nGp;U+}sMG&_hqXS@nA<;SfkT@s&r6Wp`#viRCq`NLZ zUc$gi^ltZEsT+Wi{{?wBHo-?%i9By(PFu&-e!qxRq)9D7h%BN@72akx=06GVXa9rn zJ{FJlL!6*NPK;UbuXvvuESVbtwGQ7IbqQXQP%RbNZ67X#hrT;;z>Jr>BX+NQFSrx+|D z(h)z;^BjU4zmCWkfmxscH+stSt@s6F{1@caNs-HLXy9(})$#Gua6iZ)KCZo)k9{FZ zQ;yKRQlI)o%Elc^tWF&ow~$DTlt8DAl!ODkO8_1DB`Cqg6J>=@oz5pV@qz5T6pVH1 zH^1gJjXA-Vw%G}K)KFgHO(jFeGb|Oa@YA~^ z=VPC?G2RaNu!4P|w-|dPQ-90=ws(_d3BCs~fX|TcyBXjg$PYUQmdPHOkryOG1xfge z0C4WQSQHBQC(H{bTB=JRS^vRjAF|J-X#7L|**Oa|zk+uZ!}xr5L~?B1=Gj>%yjij+|HM|P0y)V}SyxXz%%4w|3jWP$M;ZLXX;;k;%Vnc4 z;W4cM@ONaGJqoBe9G;8D?oq?@d#kFHGrJ%tO7K6x_AGYVF-7Rq%s=3uzt!>N!E=0I z`_lH|B482Yj|Ln}WA_K+M?BIDmLPSemYW1gGr~>e66TvTK6w$?$Snpq;kk4M+RxA? z|7PC>#tG69>BQU}d{Z(vALe!=II{?=ctc1eHJOHJ#)NftK!Q$+l?CIYPZ$=XCC_sJ z6nG6~og!EQ(L8l&+7og#2x=6>={ga>-W0v<0ac-;1dq$hkL6zRgcLgAWiJ54L0_ob z*|?KBbkRF4Ai#03XLXyj4Mysq{Ci4E!H5u8_IPvs;yPnW`|e zstE6@$e60Ag8wDs%5w6yQ?Cy1f+d`)KBuU~8mO&~$*fM7smU^{$?>jvW_nQk71pHPVU&h7n!1j9A z{}%%O9~swH{n*xi0m+6vdJU5<;)M|nHjFc{CDa>Q!<>xxU0%bIi})fS{DzKr<<0-2 z@m-AATNnJsR%1P)jII?NTvGqt)%(6M6*OTu{!dr$Hy!gXZonZ~+U`T! zKV7{mxw#`_*LL6gr>nQn)a-VuwVH9hzT=;+UiMT)&?q77d->^?j~|#%T&jCd*#4pa z-#5&THN_I=-2K!&8QbOm!Po3YFM8ek%7L)mj-++KWJh9P> z4#bTFksqT`EBwT7%}gS@!w<#x11j2C+Q|HKwyS)VVG-GRAwI*VTI~3>f6jIurpSP# zB%jNQ@LjOWrvFO(=Is6v@#)1CN0T?hES2GZ62Ffpae(LJaYboYrk+FUCFDP%<;2O# z^uu!^js=0S;Qq4Af4X}3w(Cz6*(UxdX`d|Xei(1lK)t%Te_L~B$?qfAE8?n|_yHmw zZSt;(Yh|`*6;!&cknPy(HvlVh+C0@f<{+>JehO}(JLp807iTuckS-)R> zOCUJ5T0?AIsqEnOUnLbK9zA`M`1W#FqyDc+O@3Ez<#mRc1E;jMqS}TQe?@>S!|TCc z@Z5RJn?pu*hmO(WMQld(kU1hrT4AB9wFjRV2QCO;u*V`=Qp~oTOg@bo&QIfZ{|f0C z?wc+Jp}T&r{%Z8Im<;(cj=k$$XA!9G!&2T^1|-LunjeBpc%87s-|gxxdEam>ICg*f z%TxTb9Vp~=+A>M~BD#j%+n$j3+v4gs{@HFS(?5&k}qYo3EDc)TGb+dGO&A(Mnd&=v98+*?XR{_n;2L<#S8JkFDbH`wFXO z&R#rpv99c`+#l=Z`#U3J7sJ(*U!485vA3-zL;0w|N0Let3b#xwQ|2drZQI`LHxC6N zi7gM!ms57`jBCDiKQf@{&z7-JHBK|{?YvWN-Q-`NV8B}?!=JytD;!LJncpKN$k9E0 zEhSbx3K$tA8*Q8N7^*c>mdiX)JGRF<4eVWce?m{O`8~mOj{@AWT5bjn$EcONrqec9 zk*l@}e{R|SmVb?Pj3p7jlA)+Myo%@++k6kY6tlh8|Ho#( z#KPAe&4R|WYU4L|fArJT&p9PpLPylNSKw~Qji&@J2#fG9l%L;<`xl>toi>W{8_l-C z<$KEH;|yRe?}Y#*LFealaXQ=w>7tPoh6uGeg_EhyzL=`==vyYv>2lz?U%~y~*Q>fb z;+0N0;-8PHIJ;z?K}&88DwV8`vnoRmq;n4jW>E464$O(tWV3ARTuM8OqSM?B1ra-l zO9l#VO}Xu^svUN_5@}xqu1k)~?{0-4_Z%M*xlV`guqhGn|E8Yvidv{YAl+p2JU}o} zo#@n>RB`cniP&s}-Ojc36#qYHQGKN`jq0RNH)HBGhRBy-iUA6it3qdb{fy^A69t1356@I z*6x|E-TnNh&9GfT@OhycH{wxp$hx@SMZQ1Rqc$YyY1Li!P3ZY8L|AKE zJyy|9f(X`%1ee*ygJ1yfz~0>>K3)5!9If=3W;TPF-Y1_Fe;Mgj zd$MZpx$ZCFu*pRQ(?Hs~zn}v+aq{AbudGlt5!vCcp4>j4Hd%XUlSfr+k5=t zHL8CuNxPobD z5`y={*$+BhblG?N(&lulGDz9RU;ng|q__Og_eecHT>zPTKU&p1HD7QG`}v{?DcXh+JWKggt&m1pbhsCSb$?49rG4@|ZJk|R=Cdx_;x%49oemef zt}PywCP>U*P?tE+?)}PE>d{r03bX6<(We`(9$#;i{1uFohV3& zZMA+$Njqp8$lfGX*9KD(kMQob_*{M>H-~&1xAk$MeBT|5pbzgO|4Q6<3awlFX|-*^ z>Yv3iYFC6_5+ar|@}Tj3hTNnjrAjMS#zIesN=EkEIQM)^H#xnYBhYmG-AL&AY~`sB z)5H(93g3aKrs(H)LzUmI&TQLth@g2u|2LX23D(?uV&8S^w<~y$z1Ld$$)M|dn|ju23BciR5;gTI~Ug~I_RkSk(yT`aKg z;CaL@hsP&Sip;xp%6i>H-vRSrTiMqnNAoqewuYY%3}l(bdF>H;wy6xLnA3prBOUy! z21`N)F5^nadrnw(7h2;YagtLf)F%D?Z%$L{x7qR5DM5NxKRdgaYU>C^bj+7*^E(^12iwzDsFa1aPEj92+}zjHAUb^=xw0j+a?} zCmFP$fS&+PW93BdC(FNId0flWzXt&MNztg!=4=u!-X>PGBkppE2`mua0X?V@9)e60BC4F|JD)!%-Jx$#kuEzaD_ffszb#}***V+-W(M- zFoylW5!!!0P&N(=&sW>~`RcJT*c^cSx=o73Z<3AJ zFby(Z8vyk93+^#Tjj>dy2+Zjj+kL{}S&$mf`mB6lrq3s|vpzb2j5&A$V2K7gE~3+$ zcerm}8R#$>UPfO-oOSq~wY`+^7aFM5-vv-pe{Bp#K-k zV5BiLelf_Aj&|fX`vU+z-aCMDKJ~|y3*?Nv>&JDSGgd+~{u(rm#3Oc%p*{dW>;=5} zk0S9cv89><7=)2pDYRAtUCE9x^(dSQwlYINdCoVGbQBAZrE!XJbe~ZC)#6!;U}p~L z5C?K0I)HP~FqoR(kK6^IK`Lwx#9dZb5%Vr_F%zwK#yc035bhORJec@?T)2^qNjwR+ zLSTSFeTlq~doU7Bi>dxe!2(b}O)?`c+kRaeMuj(6-tN+y49(oM*!Ltdkpl|#R4nY$?xgi*pTC1{l_x97PY}}zeiF;G-)bA{jk-aH@UvYCx*BBO1%R!!Mc2c^o`kHX{ zd(CmK0Dz-YPv|2vKSO?M)b2G$5&`H1ZigeM9S*i@jhHuzRduZ2XiRCXT`sG&@p-wO z0{w$jBGEPRbaZbZYLS;jn!We25Z~mJSEE7w%Ef(W3*4pSevAp8p3#HRfrl7m2?_lj z137_Jh@^11w*edtF1L)n8WAD@0R0;G*5Y*20f0np#F0?}re{4o%BZ)Y(Ao#O(dbdN z8^~R#O;aB{^+Iq~`db@UkM9t7JM+4C>c)6+G2X*dCDo^FNuTzRWJ`r-Nw`^3b2txh z4QWh$sse{Y#lYJa7K6Osp1#Nf1b+dg4oE}bwg93= zM4amGOvD;)TGp-Xir7*-a_^yVp*k`rcr_bG$bx>YNss z84d4EMk@1=S36~v-dN26?AwLP-zmax*_eA2{w($2M1gkOf{I@(phkv13W4J|s8AQ= zhkF2#3xSJg63hCCW89v*?PKq`q||Ve*G=0qhT2}Oo!_E{X}+~BjEdJy$5YTpFl~QA zxiNM9Bs|~%Vm?tCSie-w1p#eKyb+K8eC>|Wc2_sNi!CJk*taC!)J8a*BfzB#f8~XK zU<;&;6}x|je8xbLH0~uqm3l_Cag!;ow z8^lrsVP?LPJMS3y{g9uqhr#I4p>z-afjNoWfov{ak3r!8hyd-zKr~9LfYLAB@B4_W z%tJiv(F3@U!PD?d#0NnQl#0FERR{s-sh(yj3s=FQlo8hl?Z-Qt zavM5I7K5(0w2K{CMQsZKsZ+xrq@IgW_&3rCApiFMhW>+2tR!G`QMD@U!(!7Z`ouF8 z*$+)SzXPp%fx<^ij-1i6m8G;7jdwXhTRg^T0VhiPTCi8%FP`($->bUvE}3Viz*tQT zS_#;!!5(ZJaHb%4y?7{%;?tqGExIa+V_GNP;>PAnw}3(Dpld_pWAh?3n)A{i!=ZgK zG==kA);B-z^sp%Ez$3`(t1o2g`vy->(f&Z-JV+p5@be&PIsV;a^}jyQDuYtcpYOJ- zhX9q`lYt<5`BkTmcO$i~|M^qPa{*jsBvK6+3jm9grTdK=@1HYyv1aLCN?8x!7@ZL8IF;~?$Hr^uf#`(s@K*6(OnOx4(Fa;3ez{?CnywOy^ z(#}quka-PRpV#D%Uz~KC`?Z#mGs?!F-==@Q&J3Aece(F>W9z_(+t8%P7;O30-_qMA zuV`&OSpx1~zT~J=?~ySZH`Gq}&e`Bm$0#rKXP;r?Za@13fzTg5xgU1QviMta_=}aA ziU)e3AR5yPIf#0(-cYQL2LbYnKro9rXs+9ITIy2SgGwQx^s6RVKvZYRL|1;GUoT(N zlWAU@zRj&E8A};>hKL}S@BX+D_kPhUj ztvo6PAgba@<|N7j=KO001no#Akew1sMDR4UMHC24l~Yzv?S(9%xs*iw-xP{2Q&~xA!)!F z7d{e52i347ijrM@OB{>CF#Yij!W-ECalYpKhZlW?o_`;GcrN0-aJb>M z;oqMow>yz|_*3BUHSJ^lu6Gswy1d2oxYhvz3~zX2|+M$PUDz*rtDVbi!E;SX@!11+%vhB_l%4-}+FeO&#K=IvHu@d)LU z5RvMV=bBc%NpnKRJINcM1TI00v$U^?H>4Hl5}~QWhj|l5oNF za>YM_P8cmm>fmC0{h&#yQYM#m7EY4X2azzq1S;tGF~7E5`F#{zjmOkbBb*sDG{~o( z#UcrxLGOgrud`(*RrOOhxj-|O?8L&kn=HkNac$sx?5w=vx6>`&k0CP6k7hpt`DRIn zVtRGWiQGXhf*b$=64uF2u>~G!S zDT7LLCu3%XvY8AQSO_%p=Oo-Zsv)f3Y5vsL@a0~Mqc@1RG}KDpRXD4*dltYD84tNB zFsP~ti-&!yAN(QyA7?RJQ>IuiUoQW+3=*jSC(C-08Oq;%AZY8Az96hl+ON zB1@1>cq|1km8|QFS0yXDkhz)Jip;%xL%N3wj`+pDhxDMsy@qkmjk0-|F0?~)DSp%# z5C+-aQy6cLL!pHbt<&c-nC{smeCoy44eRthG~z20N3-eiba?N8)yFOofXGx1iU;xz z+%`)NvD3cWm3HfpO1vI#5vZ`XKBVK1+DM2`!n1St*gz8NDJW=C$AqdB6lillvqSq< z-rk3d)Hfw>%tNpaI?N?>n|0~lF9plr4}CJy@;@!8ek$!|Y!Bny(D3CzprlOGMyF|U z5Qqd^gcCoPltTiBdLSx` zRS+#wbUNvInbCC_mP*qx!5U#J1hXR16`^`G6hjDk(`G2K;p<|dv~M{=%^YrPH5)o_ zT^5{V3jeUj{nj{2rKWT|Kj^S~zz8KodDN*CG*oa(HhWx>wtcPIZlU+&zVr7E-kcr} z{Yg#YKf3}C`-x^lqV}Etf`Tf$Yb!>}q=%BmSTbldzDhO@AA)2uKn7{6-rF|owMYD~ z^oTzj(q3zHm)zNR!loO}J6~QCb0KDi7>6drc8F!i*oUf;pH;+uiii)vEJ5PiCeTOi zU_Zg*=F^{sw>_2Cl@{P35W|)@<>hf<)Kr}H4=a}=fs(0+iwp;D-DKr zmYSLRAAQs2`?{@ax7LrFc2>NH=R^h&C=z&$O4dk)w~(3?<*as7WXcyY%8}KNOus=g zsH7G79n7+m2n!liYL=UlJaR%F+WO-%D2U^vyevpTH)ZW~axmD-RiOe9brJvr;-18; z6yW#wxfP06hQsyog77Ygu+tDJh6Zu3^1=ye z!N_gi;8O`oxzWz#M`sgr;$|U&4%|VMYqTtsJc?PT$LqZ3Ju8%-9X;U?Uf}qyLzKVG zq`8fk9}ov7O0-UzF!wo;XokPEx`bj_OqdKO>-8)eAkG%vtnK%(bHySO4qWvnf`}c4 z9DJ+bzWJ>kg|_ewUkk}XtqV~3AJu91A7=~A^ZIgpv$|r5ys) z*2Y5Q*5g*;1v3loglv@gfmS7nS3xVf%ZC=y6Y6Uw9|KAFmxM;@5Z!Illw-ivper6K z&AQr+j241JDM(|qqq0t>qHAekfTvlP$k~>&qV`2%e&;+jz7{;{`H)bhYrQCt#(|tH z?ISMFKBtE|4TjsL6snfc)+OD!{61ik&L-)+rjUcl+y)7lTlkbW5WBXsw}w9WEDD*A z@rV)!$7!opp3;;<>fJtVo5%jbX57Rqqc!xMvMFjsB0ski>q@wvMS^MZx?=z! z@XGnjjkth!Ehp9dy%U}+Jbv(SZfA;|v@KqS%+%GQLE&VZGgf~#_M2fHGY$C=&Q0-p zS}!`F`mM+P*tVYxWre5pdq#Ktb>+|Zm)o(oG|oA-*kR@Qg5+}|LW%^T&qMby1VC|J zS)7})u$cXGDZ_T1DH8?xAq|0fWjuH$EUuJ=*pvCvS@^CrFrf@64q`lMgljDGBf$?# zK&d+hyV~FBygQvyL5M@(@ltr0rXIA3-nvc_t?erRA(L)PxY^m0QL_k2nahb&i^Q^V zVN|133}<_#Tjz_-=)0VV4(x(-`WRK;Uth*hoGG>lY>QMg8nUs4(oK%Zu(5DB1jC2O zgSsX)tSD9|3=juOt_HJm=qCL22*gQNoF)4sc<0}2DVf*`x2JUJgo$T{nwKx2n6iY2Z zkSY@>l3rpC<0RFmTp?^V!#D?|#1?(WsO+#{2Cc>kQgY)s-h3v$9`CL2!s>AWhzKCq+%W}VByd~oM2pk$c4w2z zox8F(!XD_&qU)AQ!lJLqvr&cju5KTB-Q!(Y)E>&E7c>3 z21E1tSK`0&ffUn-m{_|Y1ATsCni(*mM{&CxlfA&zzyM=M}u;-peY zD;o0jajd1Y`V2Kqd@`G0Q{wnc0%IXFwaL8JZ0`P6Dl*5#3tM_4-vwPdKv_+9J(8kM zh3;^I?TV7f7Z(yY-Md{?qbAHl*NMQ7I3ca`!HrL1e(^QTYMIx;s#3J@x)*Ky?~Df@C0SeLnfgPItbI((D9!|0^>o}BE7(}fx-aXRZz5h}ERPFdJ^*r}*> zPosY+O4yohW=&uOD*_Uwj8u9DYq9@3tRPtyMju06iDK8VOn-lVEca?${t=$nIvzku zwod^uMU|KuCAeO}bAM7iHuUPx zVe%z!iB6ce>!O7ihtZ6~`+r+NSM|}-w{o3qas%R>^YzuQO_(_=0*=p^Qnkr9XnSSi z;o`H&28t#{Ak`ECehKkVtj;s?$}mgDC{nwgbAgGn%$@qhdT4i;)1<`t8lG+Z^JM## zs1!tpTs;Z6>jw+%K=S(+P+l3GH!1ooNk(ppxobAgUXWy&i6g{KXDV9$$fanfA!32; zv&o7}fU(M+zc|*6bJh$K68PXS!FfFQ*pA8x!q8PPp2`(nk#4fIh~L9TT=cU-oavGn zOu?Z`jfId-cuaeE3S~(WO0(so%te~PCEJwpYF9_szV!8n!*5G%`XmqU0OQnUM9mmt z9Ywd{Ao~algNIwwV6IBASJg=tr|^5n-Qv&BwcUXa^K{pbR^t znSD|y@zj|_z+Xy_UX7D+|LjuG!9%)je9+P)+6A{lCnPcPI!|KKp3%vwoRJ}0)ZaEugxX38`!4H{M)_Z~S zphG#EKN`iUwzcVy1SrAq7beVzVCDUfUXUc0sppB8xGX2pwDM=7VI>gQB=)iC(6DI# zPyEoQPac7X$8U(&^w{-Cj1Ix8LD;6U>xB8rlAkpTw(ZNVm~K^fwVBG8INUOFD-7hw z{(@HHbJ8A(vFe0ZMe1u68ht8R2>J?+o zBCy#xP{dAoo#9MLJiym$P_s;$ug`Sh8lTUlM2W|Fp%=zPiAwBiERw%>yiD7m8*&|7 z>oZlq+0}rpHJvZTfE~$kx_CG+3(YGK-(EPp-&6pTO39p*?f+!j`ZXG85_Q^qo}Tg( zd~TAgiz)VCR~({T{c*2ehz*EyhS(-d96jE+sLsU|i|)++A!_F`Ht)D1l`cTO{j z+Eq`1L}KE(+yO=-o8QmSDl!q~j{l?ja1I%4A-`UpVi&w&hTPQ{rr= zV%(Q&fbJp#iO;!zUdZnvxGj$szxcInp620bU6O-OD=cwFg~V+`U%6dp)NCSs0YJj* z-P=274`@iA%leqJC1=hnJ*7uUXq6IEQWKa%yTp{FG-NqtmG~QuW{#q@hFB)_c#{sL zo#RSxXqX(l5vF`*X%L4W1b2K^sCkMR35nbneiCWRa`)0~|LERVPml(sm+=gOH;wZC3ZH^dMb zXQY7)YAwpvZ00R13^N291h9X~_cA4)g43VXcU99_Qy4;LX37*tX2lZvo13wuE`CAG zA)+DOl-&M9>+TFeYT9%@&zj+=Z+8+?T&D`^p+%pYup;x5BC9RfU5taCn+e6K?%T)- zpQY_Ivi$YHe0( z<3Pex3c~!dY^x=!XXlPDb)4x+JN`2H0t4Q5Jt70dN`PESn|W=hcw)_4FU5SzpP(%( zPPIQJ1`C!yQ)!|d+lZE4e7g97rAS5#Kf%bM#}H;#s38cC(u z>@!KQAuu6c@HGH3l_`Wr6DA*AuUZ6tF9JU(kn?)kRC1i(p7AOYOnx1rxX#$#s!x}i zlb8hdAQ9!XIcBExZSG(aPJL~*B-Ec0M>;8E!GRz}(DBC{uqqT1Hx4DxZN&=?>>B6a zt$HB=i+oSF;~*)_4jEr|Go2cUuw7#@a1P8jpI4?cN zcoOkNci}MJ`ICSye@BrzYDnru9}~wDO`#Ayr4(HpMHEhkdg@y%JC1QSj(4N2)u6F# ztFiWPV!=|xTL(Adu)r5U?0^7VLQutdM_;BjGJlLB6b(R~fbazd>l~?fTmm9e(r0~G z9(f0Voc@{wJ(k3`tH5I!09Pt~K_tcHsoX6tYHm_&)FSc6>=XaADWt5XtxU8^mb2zv zmF&G{KU8wuTu#oPNqlaQWkaIz^E*kTuz@4nP~UPqp#%(#k3`NcO&s%tIP}2uL_p@b zuh!I=t6xF^uB{qh!G5!aWw0&@Wdu8xh*^-kp(OT37r+hWL6G>guUr)IE5JoLejU>Q zcEX<~yE@CApN1(psVgQFEr=9RLVrb{JdCrSd~=wD1iHhMHY3r+a929i&Ja%yI2zUm z$CzxkDnGHZl0jZ)AB>Ug5w`HUuigGU=BIYYQi?erRBF2R#8UMv;ho~yOa{{vId+%b zWNb}kA1NU*ozzPPA;38L(Pgv zcDUeIlRZ^89`oJ^nrhRTirZ|9+^4=vB^*k8-84U$L1Np35ak5I@&yys1ZKbE=+`cv zK>XM^N;j4Q1LiYN#v6@IAHb2)^@%CxCzDxKf5tKFcSS%BrHAU1%@Q9Ho zO4RcYX4LSk2PuN|?y9oz;Tl9aj2tI&l=PKL_|AO8fYq;!Cy06q+4*}ZAW_n=poI6fasp&oqu-V1A4qa>3E!u&%vr*qe zJN4>XI-MqXAzuV|u?vjWjXKFh9F{h5d_ARv0nvr2LiS+2#1s0=B>`VW%LXP1Pt1#DpA%{#ZH zrw|ATeihaz1}NLb!{B)47#d(w>&xx8MKIE>lzU>oCL}&pqjrDWAoPZa=%3oDY;?Qk z(V4K@g?{2$R>PS@a}eC;NPs{d0?a6Bn(vj*D&wsF+ff^DO+#7YDS^w?x7=}Yj#v254o-1Ay-uaO?w|ta=H)N9TU@2NI@u!>YZ8Mgb(w}C`Eb{HP-G$ja!`y2 zo4_;Ca=f{Tw47noLaWrfYSZA_)H1bmN zORAH`C-!lRizzEAvZAP`W*N6U9lNl_k9L?DXZjsY>eE<~Wef_Kie+ll!M-iJHA+p1Q2DF-d?#ICQ%;yT7chexuw z!K;wpI9Atz#m(Y*5 za7lw`5Y=z?5s@PP$4xahi+Y0HW?+gyxbTAMQ=&Y+=1AhJyFMK-9efuHVFie8)fS29 zCyCQUO*FD?hEe^bc+)|ceABh*X`+G8hTPX!)2LL*eE=X`-SPD1AH(XNZyB)*D?|dJ z(X%y7S8W+KIDxAM-oQlgiD$(^)UdE z0;>EeGT6)y$V?V4Dlnu)0WCes@uBS;aYe>~EN$*o1O%3{MsmbbG|A4H$**2`kykm+ z=2xKDL*u2loG{4F&|sALCkD>R(R+eoc1+NpfAc@GrFS_>P}oL$Bl%$GvI`Vt`jG+2 zv~VC@xbEgEdD8PE^1V_-jLwUWI#IyR2QCCydqg9$d{k3)ey2QMwW43UBt%w?rd?}9 zkdgYVR0~9F4*~i)^LJ#ta!rx&fglbvBlU}`P_!U|%mW=QQ%)FCnkf%C7LFU5T8Jf$ z@ZB^+$I&gY4&86{X~|FFyqH`_v&oCkjo%++_bc!^lB{Ati2tJ``#(M>O{>b}K)oM2 zKHE#hVMx$?k_$yS#m#RIU$^k_R@wP02D2}*0sn^gH{?m;HvoPWS{8CXnz@ThSfgka zX>rvH^;;`hZC^{}pm3Sv6zoEHJR1)RhHhpRa3fIWzjlN@Rqc@zFOM|O*HE2AJCc{J z=@s870_Kb6n?1UJI?GNgd}ob7$<4*O_f<|kIfhZlAf)heC(%c(>#ls9kaK+Ym)l16 zj19oOYNwEl-#eg1AHL{~8*H$MS38g9{};Uv{Wj`P9xSrdwB5Rc2d>i)e}UG3ljBj4VQ=?{(lHNa z+K0n!r1;80CvJiXlP5lQG?{#_C!s%MqdB1_vB`=ueEWbDAAWu8JPKJ45z1`Iyo319^f9PsR#dHiup6N8Ms)R3=lQhTPQ6z1AT!^z*qiI+mq%z)_H* zSp;GQDM$-@K!wW>)1e6d;>=vdeLm&yXN%GBzm5z#{Sy5e0lzGA72m-$Yld0DueC;P zms-A1wpuF-ad);9hki&sy!AtLY@siYw?}>9s#;o~Eqf431-u2h-W%8zc9(aXghJm_ zPl7ekq}%0{y|GT3W>yzbJOH=>ysVEe_;R#mm)+La85GEs8a-A)4Zu}XkbwXgQl^Nt zj`+$g9s?_SuQyXcB+%!=6T7!T_+*hLTFW&Yl-oVoV>K9OF;--CbjP8fibMX$v(>i5 zkS?dd=fht{p#%X`^`yu8)ljkuzxkzAitu?>ygc5QN)S>|WSadx@aqS1J|UssBI$^U zpmjV39^Xx1c7^!?NE80;lQE7TbKs=QjxuD)jQv6&Z?sDhAK%a63f$NRyZA4KbJ26w zrlfAjaRgSY;8ujw7aF*8!B!G7WceOu75wPXTIJb~s#azWRu(o66sAa&GGuc2GI7se z3)bQ?-2O}Gwi0fxdb)Bo%at?a&AqWF^+j1VM&Y>gWVL@(>Wpvop!cTzp)Vtu8sfJs z+>y=bLyEm3=q`d*xBNOob~I_9c#wJ^0*>yIqOG7>`%v|{1@Ke{LAX#Xn^^RiNbIrv zHTZ3#GJc}=6o zzU1B?tKLG z$mP!XsIM=ftrd`7l~XZAm!kTZFeq+pJ5*bVNz zUYdPU_19>DHX2$?X&Q({ix>W~Uuo_IA_la5;S)Ffs^Uj4TezE3`Yo*H0(qp(R*j}_ zwM}QA-rcmdiirC|fPDUqnX`}Il76XUm9Bd&IJsVY+a%B?%PA>pVvSm2Cl7BTbp0AC zh#cd7;$8J7bz_-~-xx?@u`!pZl)$ibk_WD-~W6AVPv4wRcdTpfem6MsDSz zUs^bZwK`pW-@h1(xnR=k1|&erw-1>o=lSYMA?VZ6r9c||QL9E}oA)rB&Ly?R@vphN z%fb2S#t$z(&eAh1Sv|!zzK0+0Y|u{IV`!(Vp-OMfO6Cko5h0^GnOml-^hf-UbQi?J z&-PxW!_bIz%`!Z-%X(^7YF1%#Rn((xWRYmil-cVLNXZNmE&?Ha&D;UIiJQOh;XGGw>22$777Q1D8pxKJEm=gI(AZUDEQC`W+?2SCNSq7K9G zp7(GfCH*)VI6`iRP#`KG|CbM-o`i@4*Yv$y)cvsgxfm%BaZm#)2q5yw?QZ`MckdO~ zRO2n$u9bu&^p((i=tb#WT0nXYML?wr2v`slrHTn1DTbngbPMp==)D*eX@V4yCP?pH zQBlyG_}}~Pea_kY+TvWJQ zRe>y2K(Z2%l0?RD6l?<-lSgEtP<|{?e#{Z;5)}b*CC^0*u(Xo5Jjkzx!WdanV*6;d z1ptnSEEGWS9e{dIVd^F_)MSIXL5)N1VkWu38Vof&1_m1^AxjOtFc z9#t8Ss=>3W=yTQR3k6Hwz@u;~C)I7AO-mx+kYDx<=9#A6k+`WlP!HRx51<$#LSSdG<;iuFp3^^S_oj~W}Q3ISD1U{$r{ zs22=K2CK$S3a<78@sqr)qI~hqho>ksYN9EMiyd@^)moW;Tc1f z&Z|t7TsHUZQgf84F(_mff>T%`3oq@cUHMUWg{l^ast;sU58|p15>me^S$|bNO=3ShuyCaD^w5PnP%T7-YD;6=Z5hS zK*0M(_*lrn5H)$cItWP%zl z?}0)cs&TjCS&oCEPT&RK(1Y4`ufzjh8rv?^xLw+CyIdo=z9IRQMoL#hihH#ffM?c@ zmj)zUvI2M^yfHgK6f~?Rvo)qm{&ZC*A{M#* z^}c3t{WLt=c-9F>_o7&RdFFZYYnFSBS^0iijOLjTyrDV~?x8PaTBDLlF}z3tRRFFL zQtqSc>|zGAKg0(~utg0(3dR=sQ#k|#2(Yw>=zKU}L2Y!3fdPgFX%RG5K{Rq|l8=ez zFf|Ydh>vZmo+PMpn!e6B8!f#X4OhX_`vEGbXx6MIG1J$QlwbGskQt@nj)f$c6h$x; zk3PPSbfC!p(9eWZcr=KxU=kvhVsf&x93F9MCk&1chKB}UK6?!@7>?jR^mfszGr5ku z1Q@wf==x3|y{Xrbo1x`r4;!!5A_s4%-TCh46yG?e<#6Z5Wnaqk``2C_Hrsztdwomm z4qxOc$)lVE6%8)!H|nbXJ6f6+M;(&id`&uAd|SG1X?G{Ibl=hLx!=-LsNGxI(p#?m zuD<2nEA76nmc9Y){;`(+8SVEgE$?@<2Y$2+P_+k9t%IyOLtL#xLOR2et;6yS~=D(3u`kL(A7S%S(syoNkHYcPzj|$E;iHB7fvl|*@O4Ype zU9t+NAo(L2C8<%mH;8#3jNwwvDj|5J#~&|;pI*U0=f$W4Gund`pPN8L1-6u=8|SV# zBUSKCg+Jx5?6-MQj4hDs&vYdpv>_BI-hm{4LjcYX@H@X2TpVAsP)3>(1)XUJZi@b> zSGyMSuBcDVXU8H_zD`p%C^&X67 zjfCL=NGh-sAA`aOri{?x#aSh>##tKa=ZuoM6wi+|q7Z`s#Ou^I3XJy~6yu%LItvg&jb}zv7uIu-f7bn+J5Sb44lN{RFfu3&? zFp`cgdqf0@88F?2c&ZTHVwQf|xLpc}WKm7W}Sf%e+TYf~y&P;m(mtH|+ z*w>YzQm0o1HzR)R%yr$@D~!5%_+xKn>{a2dThtpT4{azQ{qaHk1dJUGCuPu7O(@|M z!s~n~kdi>J*hhH7teF!1hE<=*)(~C^C8l9)Ep6X&v>%faF?ueQ{+7r8`H=CL3RMae z?he=->JlO`ZD=4Zq`nkE@l19-;yIV>L{R{xzm6gA`Ec*CO2aZNi5mtaR{^F7A}_6L zL$6r9xn8a^aml`g(Wq?EAjvxT!+Wj0yufNXRtAv)J&-x;6(d75)=D2^(KaSYjTAliM>h$H0ADui?PmP}TfAMkj zY*7EHG1suIk7Mp6X2)^QB-zn%uXHQN37?$HqZ7Wxsg9HW|GXHTyja=q_~~-v*661z z?aWS7K|Qi#Q`d&9oTjf&TppVanM-y09Jcmi>~q9kzthakpIc)yw?G!>SrR=}ZhSTd zW9>W_#}hC1dN;9(L#*_)RwPu~kG zPjHv5Mw7m0r|8FWwhJrKw^{qaWuz6*2@G;YKt1kw@yTfAaE)&NvY*yvuW9u78cv`b zOA_e4fni}CBHT|&vT7`o`IIhGAmz- zY(yAbEm`@yJ*)LtJrGp-z@A_lcF=o zKsrkx1pNqy+P={*ti%!ZA8wl|5MbC)U)cz)#C`>lyTJ5wSf+u;%*exgQUYYFV{GWT zfD+P7Hl!kPG|RY^RZaW2#wpayF$ZOz6xb#w= z^K8Z3M$*>lw@=l~b5v#<$p)k+yYA0(wR0OQrlqI&s4VadWgDx$Oi#TWyudfdZKC-; zJ?(nUg1}z3iOzQVotq9!>_^<)?G2{nxDInBrW{ivxs3GG;I>6kVIDIx>x_)MHH+ek zIc8P?8JYR}i<0_0=C)rHz(*=em#>zHq6#wZz6f4A=E-Am`h5m%VRlJ2D96HeJL7)q z{*pY2$I_D}GyAQ|vSNCUrH@=@PJi&SaxssUzjfw=k2TAxl{r?I12S``_m|b%d8~ud zGV^Y-!)Z2U>+3Hw^SAN_aZ@}tVONv+zxF*;FYz6aEV+hrlZw#=&s4G_vWn<_pJFig zC&bBR6*FI7Jt@p3`+N{R~KgPgnD_kN;Jg7|Zw*=B+NQJ;^@bBog!BKl0*Npy+7=|xic-i9EaIu_XaB#7rgY)8MWw*qC>MGApRt!5b z3e^6~7C&`kW2=64`1a+7#d~MA8&^x7{crhk`IOXuS7g3v1z5j#Mce{_SSDc6<0OS? zqxKC8Bcu0UIVSC5R;f>c%!F3oRCH79*xlQ|_DdDy2ug(EQW!igsbRcH>(E=|eH7$#Jz$G`NKnFDYEnvB@o_rnbFeXrhPkNjtWpFuRfAhwxLyrf@w7G<-vT4 z`u4#B*+lN;V%Dn;|9_7dzEcfYDKgm)TYY>#;MZDN>C0b)r!Tjg0`IoT9d6c)=}O*0 z$a)-ZxBU2TB8C?~hks4K!}4zt!+(a||Cfm2;>ra8Tq>n0O+4fJbT2Kn?5Hw)Io7ZL z+k8wE0i;EGdPyE!?8o2%kj0W>#1E%1omYeM=*Zr}3(g%yAdyQuP&FDtN#b#j3|z>n zRg}2nc-ny~+8dCW>_lCLlQ=Ri!I0yy-!2VRYlFMqD%r)%w0#Is{CxazM&dSAyCz2K zG=UDk$%H;qCm*Iuk(B+i@JvDVVgbuU0C>aXrNYv1I!KujUkqxPK9a`Iq1-Q7-O_yw z7uY2F`;Rao`3*WX>NXJkf#(di6-1PxX2I3!g+>M1`$8o#GOIIyVwX0Jm%f@v(+cqO zNte^{6GG0x@kl96`F&3cIq&fpB3QkL(0ehfiO&aE_cIUC#ALn5k57Pr0yd6bb z2)qvKybbqbN)b%>f#%9cMrva5L$>}hWA*}zj+^}5_r^a2QI(u-4@51{5&b@mwidY4hqZh;)2t=$S`=23sXX2N9s?oZXg)pej^#{N}ftzSdrw3^3~R%_;Ge+_59uPIUQU$c(* z^`VHRw#>w8-7fdnNSSr*Q>XrQ$L3!jE7EG8`&wm z&%@O!dXjQ95ld0Q2p|y5xdC*26{|9;Xa!5w4|R99RoXxZ6lXJJ;FNCA-^Uf|9Ax9b zl^RAoZB-G7#s(9j#fvOajM>qpVF9KB?3kkC^kVb5)Mfo>dRlksc_c3BrD@!XH2GG! zFI>U6vBW+XN^yLQgbBj{50@b5oykgmr@>pg*Oy}&PEWH`8VDE$#_ML!GaZY6nsG=L zl=GXNF`cPFu;9oX>K+x$9me&70SMz5U9hO(hcr)J+^g#e%Ba_pdPbJR)LJGIjSK z@3osgNDKcEsE>1*NlXGOg2TsJzugzc8o-87u}-lY>6BJqrQP!}R~F|wxuSd~t)tmI za9>Tfv_~__Bi~68-`1B#eY;q_7f>jC0MP#b>l?H1jQdiHxe~2(VnN}t9Z`q1jcr4W zN)ZRNAG)a`S_fMLR9{c#-@mzt&p58YR(WZKA9Oa6p@GOWPGmVCLfj;*28rF7#2NbE z4I#HEdC^O0*z!&7O3bA>IBu z-doBTx{eEG9t84G*RDC31OM_L21`QMX)kigXHKIpE|;>2lt8O$o@e&LIrJG_aZoTG z%AzTq=qiJDy29aeaMqAZH3Ufe2b*fet#iV#+OEH5!>^K%d_5#cI3p99v?#RJaO zdnr~@(5fS}iX^_Nv!6n<5owmf!4yAXd!`~^n{N=_2O5>SG#4)rSQ?_5aP985G#|&9 z@ZuO4sCqBq|1LlNzv?QJe6HfcI5$-@&Q>N#(DLK|#TG9fnx=Lmhl7I{YpxWi`7;yG zlSONf8=n5Z%a3b%Twc27u6fV9kvocT&(EK8jeJiIWV!nG9xjNEE{N_N{r#PV%o{oP ztvq2G|J;xId7sFW9c`vGGycDs<7I(=;9InG9~A)6{H7H}?J;OJ8JF&g;x`G9=!s<0 z%7<^0xs@+Wbyq&>x`R7;o8PSJaZjd{{Zp5osweO6D|q$hnN^qc=W1MApX#YD9Vo=d zFbJ5}lnp&H&6IKNRhi2uAv`kAH?MvA@tJe=h3QE<-m!9zH@5{W>Yh(jGtY#E#nip{ zR3Es|n{V;M^QGpQ_4Vm@_2o0Ki2jo>k41~wH;HUCyP$Jxra)zbKWJ zVTDn@N6|_QHCFm*&qW}H(zk(s?SgbYGQIin=h7|JPTOmFT#|sq$dGq-rt|rv0s)hU z=ekg5;-$}rJOO7#^~+LdJ@L0@rw1|kDq2sx>2BC#JZn*42Y2xIHQ!4ru-U|8X=p<@ zgA>eSzA#0tcS1NJ_}qDYvlFyYJdb%j5z4-?K94nxm65^LoHCOF$bhB|zi8#jU*G$*Wu1v1D0lU%;#rPgSJt@&^#}D_ZGMCC)y}HHa5!vqBA?7v7T5UWyt7uuv zVAzurd-u3<$sfOD*jafW1G3yPM#L9x_ZsD|gTWUV0p>i0npHDd#u4Qqg7SrZjQq42 z;R9kX$!x@>`X?R3wFbi;1CJY*zh{Rt7^+%WHS<^&o571xlzhitJb5dvpTP*+$f8OU z+btnH(+1yE{)qBahYPeDn^O>(777Qv!Dz97U)x78z%IWe~4a-$r?>%q!m#1Rier53Tb6nINdoSeK=$>uH1ci zLh%{v1G1S*6+8J& z7k)EIFe*RA6rD(59}?)UxV_I|sBNMUjjb+~er~jvjOlgZXKy%J3*xoU98Y{t>Fz{N zd#3ol&fk|Zs@=-*=ScQ@B*?~|p#GVJOY5HD+N{t>e!>E{O+6Ah{Mwl>YpDH@Es>$5 zy4!rc^bYJF7dp&U{n(Z?tDbH_AWEOid4xB;$22N5fTsTt_d2*qgF})v<37_t52V2d zXN<0n;eTxB{7LjN-qZ;nD|UhCmzSOGO@{GxP!Pgb_0hm?A3M6|0XzwmxwR(!TR<#* ztZ8=AMWfS9;X>||rPG=@$~u00j_;;vsrHhW-bVk|0@$S6FE@HBaA;(x9Yl%Ne;+px zePSiNM9WQ!OUWeWM2&XW*YP>2b0(U_Y-dc9BuY8$wUYHp zV_d(I7rcD$&#y7k_$&>UKDD~wd@4WSo^I}GaR9kc^M=Za;7k9_W*hR_8KBJ8(ivRR zZv&_1|C~<=p`01O9dlVYabL~$M4}F>fs1TfappjOz~yy%U|A56G09x+-^q=cht2Y3 zoLIQKiFev-`k@?t_vPiDBK}Plv4EZa9kXaO=Q(W0?UgM_)qM+(4|%oz?NSK_eYs>C z&V%+_iuuQG|75HlEI3b(kz9{^YIG8Ky8e#_@_Ber^PpRIc1Sa znx4^!n0CZZudgnBUJc%X!d4qRX(lD}f_!0eH2Fcav{}y^gL@I&_Ce`)ESIVs%-Ugl z@%qu1UX=*{6Q8=ddFyH9z$g?fBWA4tR9rd{D>Fh3)_w3%hDDQXY|bMgC{kVEq%@DY zDBAC=W=i`Jem1TmbRhA3?{~}6Mb+}gMqrla81XRrmGtv{QpuN``(JeD)5iHq;3$(4 zCgMrorY>V=5kQc@J^`B@fYS%-Uv0N`Y9d`J<@4B%4qJEQifa*RQ+yn9zEyw`aUI^C zoo2OlQIHJ>2=L$bz5IOEBk_!|#VH}b>#c1Z%}o1C zTyVwBkgY`HK+*6(mOnj-%8fA7(krjozB_+8F4Zcn#y<93cXIOmZzA3Jr?)t%5F1`~ z55^4r&-CrnN%Zeq^{n{-7Tq6jTrJ^+OgOV1>eX-akX>WzmU&IX`{_#c%-!@){1Ts} z`8wIV$px2>QZi|MaOUWlT&@EUsR4H15(z5)a9OzHa?V~#>zqjWmjyuT%`6&w`6SPD zgN5G-eT}01!bE;rE;8Gz&gz~1TI@+);4aLsmD?{`ua zb#aheS3c=tg#1u|#v8cpYkq6ocM>-)T7IHtrqJXD>C$h>8NqIn{84HhBjT&Vt;9E? zYgq0ppTknM+E>C}Z<>bG_m4=mhPm!t15%22J?4o}!!+c0iv+am)q{4_@XC8GYj;_D zKWi^1&N_3CD*b2;eHlTXQ196FWsj!5VT6G=759ptg15U`Sc!p)0q=#^!V%I6#OmCR zZ!0TDwld?_8IQ#tx&x62637MGox?$ScGrGNI`ZQLH^P~jEC@{exX#f-fMK#b&#+Grn9$M9=)Hy^+Oe(0uP5RAbz`h*5ldoJ{V z4yGmnS#btS6n$ZImgon@iLLRUExEw>yC1MfXT=IdS|EeUhlx@ufvevM; z3qvw;C34wbz2#>%L-n}j>*+Se!EeZoT^LIYf6P1}0oivzDi9EXV%JuOSkz+CiU~Zn z0gQxO5{aBraY-i)6i9Ipau>K%#%BHlBqu^oOz6**MI-c+_$z@(6J)>vrxFeh?80Eh zXDS**7QRD~*i^mZU{(#Jt(|mbk4V;S};NAu6jk)iK8mE|I(VCo!3U)Ak_2awbGgr~b-OC;dx7FKIfTG~n2lm|G z?s!o>VxJ%ZkOv!+O;%QbIo!>V$q|PF!#1SY3C@uAE@)H)!~)AY^rE}Ki--I{MTs}lQ_2=m$!3!L zfMh8O5U9~{tye2{ViTfB7v6=0{KHl_GlXrGo#%2C2Vs|?2iK~u*ZF}aCvy>)RQWJA z<3Tuoh38I82qqRi0RVUf7(XGM)ssxqzMm$+4RO$!qTrC8+^DN53e*WK&0uD8I*h}N z2o44skOSX%NkNcgY9r>rmqT%u3;+*kS7NjDTKHl3V1_ZGU8~brtK+9AfX`1NvFuC~ z8vg?&5@BD>Ahtm0ak|VbIrADGrXm zFB!}&$!eOAIRsM&;H_~FEe%rGDw6l=9wg>q`F<7i3Fm1)a9|{Y{0a}9lAyY5Hh9Hd zvq?|50%*}|=7C2hk_}Dtfg7`r31^;MR|Q0QFPllT@4wYp;tcUV<8rn>AtQ+$pTQ3h zL;UJ5T$wy~yot?3p@5aG1X08<1p(pa5V5h8;sX>>rPv)7is>&rptDU5=E%7%nx zx;n{rxlzkjs^tFdBvCVH$SDR0q-zIQiyt^764V$8j|i23XkZdeNOiC2X}0NoCQK=; z5@6c}pAw(lQvqRtH!3xO(9)39a7e@nKm^@biGL0QlSrok7>#a{0odI0i3d=xIY4{M zga`~^BLm&xFFIr(807^J7=Ts)mKgw2oV!p3!eAHF+|7T@t0zymp->e3N)?hJJiftG zaf2R^!NCdtz~W6R;Lm7Xz;eRr8%E(UrekIq`xS`d3NEe64DZm%$K`0o3h-S8|3-xp zP7J>mF9)`DzT3rAstwj3a7Hb88%y z=?Du|Q#F`~BNDk#2-;U(6dx(D)9fXq0Ec@}_S963EL&NBj79OQZy z;tB-oYQ)^0xw|%lSYmx>GltNRB~S^vIAgAyt)Kr!ij8PU%x$2_%u+rzq#ZVp`5H5{ z8neze-iv6=&TV|q+?e;NvEZ<==&XPn)YR%oXJgS+s)mjVY%2TI^zyK&g0HzstGQ-_ z*XwMv9MZ9&xw++2bK7Avg|Fo`Bm0;_%dc<9TM)mVM}B97P|P!kcejNFY#=gX1&DP3 zzLoS28s5P0LUo_0T5KnNomC5jt3%bya~7JkbIp$}glny17HpFac9N$ubdn$mI@uo^ zZMG-tkB+(hIeazAL4h5)AY3S&*C}Ww7lsy!yEg(1=(ioUu+lIpg?S(d=Qvj zf#d~bWnYt7JmG{!xG)|j4#0(rKsji;A^#M;OTSwvYAzbpQy~lCrwi%=iA>AyY!(+9P6jVeB+y=aRig2d5ITxtNy-1Y) zNPX9tGS!`S)J^8^$ zi~xXXEgW-7Z&6UQ&3Ikqaa^_KyZg4Z21Wux(Tb9XYwmk@+o7-Xxk-0kUqLY#!G}}Q zg5LG@NiNopT;hd2!HsJ{1(E%Ep6^h@0JfqZHq`$)k_W3`1s4HFE#EIizW>Mj{celN z7wv(|4g=qrj1Te#?qOarRt+5Gaf=gMxA_N=HwV%AgAA>MOw)rbzXu_KA#AF+ht?41 z%^~jmA>P&@{^=pX-$OWoVG*5SG1p;1mw9Z~yn+cqp0%AD#0* zp0Sdnr8&}Z{d3J9*_Ha>#em)1Kt0&N!3^w1K!EHhVhHrPh@I~nm6#j&_z6tTzxYV%uVeCniZ?Nn7smeBqGluO zVpAbO3S$NUkjUukvv98ubN~S*LhcbHOwb1*OI=3e1V)cA_o8(sQFE|TE2w4`UPyo< zHX(OeGZN!R(9XVf>yzag^e7jjON2^qA`v1JZPRo~coaY-qaBHpdn(YGXVY{;C_4|( zj)1z0qx0f(^jw<$8H8MOftFi8#&wgt-T{ITh*hYg3HijJewKC;DsVRE=FFG5KvdBu zhL;~NTR|S*W>M`^4bPi@lInPN>$q8_l`wOHg7YG}^I~rE5>fLrpd%a0s~Q0e+vj;H zIUF}p1Upz4hh9JifxHkH)d0qEFEGCD9j7&#=z)*Zp>sG|6SdJ$u+h}E(eint z?au~9aPzh9W{2BmXVhkQ!DesUX5Z({_kT7A1-FKEw?^EyMx(aI3$`ZPwx&LBeg3mG zE4V$cyS?bPy&SbY_pz3X2nygf>l)yzt?fF7%DFMd9r^d8eiwI+%k2y` z@9ZUyes2S5m-sw`;EA-+y7wFW{4W88=ss6A4oaM01xh2Z86n4!(+Wk6gFIL63|(x1 zSE7$jFPvd)C}#rL16xl-jsKzQ&@%{_k(_Kp9x$e;Zb&jP@2sub~aWL_fsMW7-a&y_#DFI|2;P9$_nr| z{6eOKPxPSLThODOm9b|lDvDOz1lS!}F4=Q1e&;>9bdbRYBAx9WWQ~is{6j~NKm2!J z088BrHRAWm+(4bf@6URF7Ty0W-}+hTd_mn|QtUjE#XW4~fupmXyNg4bb{@X#n#(CC4~nq7%izHS`vsda~^r(U?d zeQ;{S@uh2P6dj-ArgN1~e}Pf16*DoOzlqQolja8^SFeL61h3VoDNtb)ORV;3~U zn21#xve_6a8gV#zR~m7-$0{20_&%;Q=DX6NXd)1@SZN}33!!8xoFG5N*1#9i&Yl#uMojcrh*`~na4x@B;+2F zUSsER5ZC3+j%pjOR$-G|kt4C1xBl5uDh9TgR;ff=BcV8z;XFICgS?{L+x=nlg}${ZwGhwU9xdJbH#PQ(Iw=CEDjL?kx6RX$!^PyDwqn|DO|H10Lwa=XHHjSkGH2;g${XRT( zeRt#GF~B{gCf}m|<#coC*Y$pl74+?E5pYI9%Z7@%Hz!zy-TE3T7rMwi_SI~SRZH)( zl`l%Hm(Qm67oAKNv}#g$D_=s3_VhPh_iTLmKV$Wq+;lv`Eq|juEe#ZTO6oBhR@Ype zdH*-aDj?6@fS{hDMSGe<$~-!Ys0Y@6vAXI4x+Sfx_3+28R+{8j{MlFU_x^>||8BS- z|Ap1ZC*jDySp5l!@^{0cWJ2cquWSeL#=Ml(=k;6r%ig~F1j>wyw1 zh@McXZfe8&^HhV%ju#Dbo}c(1F(AyOax|RpV7P`aY*s#PcgALgXBEKN^2Ar@m;aH+b7x_^xy(b%EVQwuD98ASzF{@^TCmu%h9J26bzu(*O@ zpu7t3F3bOHUL-`yc|S04ZV@R$O;5 z23gc(yKegp+0b@AMwMMNFL@aS;V`pyKNjLr$nM%z{c^^UJMXKxsAbcVYgo%EE0)Jn zK4px1q?9*|>~(wN&v@?4*xW}nB$Yi(`^8^=t-$sB>a(0DcpUnwodRXCU{5&6WlTaW zAu*i%eyntdn)T`;8&HPFF6CI`vesOO2ni4cAcj(tad#=RTtHa@yy4{R_NGE<^mr1^ zp!)&BL`qz=fnL1#D+jQR*NYj~za^F;eD`||c6zAis$?X#df7u))K5PipXaDRgg-4bu zdTbo&)O3XC-U`zMad2+)^LkE=(dl`XOX=HCf>stIX8&R)v#%r6n=+4C z$3Kt>@qgrqMR3#4VS5z9pewsyveoQx0I^3qPAnZKi7!zx^L}UpQ|8uTG_J;e=_KtF zkpkHz8mc4h8tmp_4~}dOWS{P2(FIsGhlRI@0aYDc`|(HAjX20kuWu}l;Mc;h$}d*$>i#|96DmcFd;W$f5rk+BN8+c7x6bM{+LzW| z`f~YayOd~*wW&$6AJgb);(uTlz|vu8s7$09&yI2K*%!$fC32SAA8%hPsvKElvwOEr z*166mj7$9Ft7vg%g4|xhDog_}4WrS6TcvkDeiCAch6B{V+M3-OVXL*Dsc~g1rF8m( zd_RBjbcxG80LU@{q9cZ+$GbRF4)nX-9!cKb{^(6ayWjnH(|r|o1)QpD`r*ltf%&ji zp8a$EU86eGjUTP)!ruD9rH!vy(wV%*rLNP{yTr8&>C+k*k*JiMsiZ#K;tNSE&p9G% zAikAeQ3yyen`K}{GNr5X8StB@USHyBW)cPf1tJ-RLt|uWD{k|gwD({TYiH7L52nA0 zz{(qTNV`?02@UJj3lD z<(`msVdyM+gGsSqU3_>lC6|1dI5`Uv;gwcshF*tu`*QB+Gt$>`T8AziUy%z4HB#1d zrOmKhhT7&jXdZq~7x%NdQeJBNPuguExQT2(+_SFwm=b{mtguM6)is5@7S!?0<yA= z+x0WUM&kokTX^jB5NUj(Qry`X-1Dy`zOgZ+Y8Bd@>Oyq(OJ7CSdUHX@tTbX;)LJ7} zNiF5Q7TiMkXvyc=5Wh|l7$3$H&P3Q}eE=6(# zi^MY{l!(n*1vrE$i%rlTSwnQOG~l78yZq~AHUR`GEVN}6^}33V=&^_j3y4_gw2ys0 zb)U|x<)oksSum3FT?Xo2Hjxi65jFhQq`c3DNGzuu zt}}WFv%K9%UZE%Gz7LJ-->#u5q3nPd$OEuf!I!aO#bNk{J;|a^Jr`{NrkaPp?g&Mw zUFX{=vXbphya!2oBQNZNslHJ|YEYIhP$z-uOSolK%H(^>r|Bf~+fm3Xh*&!UaR+N5 zg&EBGsyDFqb|h9l>Mv)Zp9_fAN802C4^VhoUx29+Vv63#x^ zUWlBc3tSqI+#5+DHKb4=ObCBY1sB0s9BJx}*hqkFtHW$pd8BqhnZa0~0uZVQYeU6` zgqYip$W7dHfCa%=(HJf}B^4sbNc0+Dx5`rn*6H{~{Nk-kZ{DsAYbRVsD{^`q1fy(` zIshQ<40TgaK?lnTR;7%zcbU(KOeaB0!5QBi z;wRw~`0J~^Bq5%I1U^9nUTBO7Ilv3APP}oO3ni=5aRU()IP~qNXgh*QIF2$NyfhEA z*%@*v8Ok|9k*`xYJrQ0w50(qc!jgf#caK#ieJ`P<~j7RJOsoCk+$IO5~hq&~079WImtRaFrLF7}+ zL>H4%R>_hR?D|U?fp#n)(aU4@irF0L8ukJTcP{i=VCEnhRxEup5pz2(3M@LctnPYg znRH4K?q-k`HJ@pvuM&`GSQU*Mgwqx+83JaN{L#QZ`c5he41%)g^vO8DMKOn6aaO#W z4(^>J!E!FniKJg|3WZQ&kL@y#P~?&iK#8lc^JbWhE+<)O4C`*1bvoRTknL&5TBQVv zo#qTaslp1-pL9^o{R(>FxFi6qhd%ko_XEH98s5euu|4 zmjMJ{`Ei`22a3!f)r?%TVIqHX zfZv6UNQvI>i5DN$g9FkqLb z(BmotJSc|{l*|VJIu*sq=mMmEoN5sbA_wr13h7BgSL)b*Nf-Nnp%blm=u#Qh6rF6b z3v%v)GiDIMR~H0efGMW=9!B~$yW1DoaRq31qVTwkI8p&L!NVoaa4b#04ai_Z17vtr z;DjayGXb5rCT_WqXYtE4;Vx&-UL504^43*)NC9Ra%ez0stq8&GKA!Mmkgz=mxf3q9 zw1dgrm#+FkB@>Y%wmN4OOZC6OBLho)s9}KH9x!dMoGN*Y*(5B5_W4rBxcEaS!#Ol7 z;IK-BS#Oz%h~}C<22>F2&B0nW6rZ1vNZ}c5PWO~Q063;&D~nte;n)4qusPUc zUNHnNLlgwLgY(rY|LF`%qw{>WzNEwwofoUfQlR<#YDPZ4KHQ`tYPDXlH3!Q-7%K_o zMQB3OMT+cS$m%A@YX;9!73m1O@Not)Axb2I96D!?f$-|kV2o5T%vuA2a1m0Fwre=l zbbNOn%)Iu(P@u5b_xj~7@QUvPj&~64fvsBoRHPl@6^7XSnE4eWD;2TIk;>npxoG2Dh<)^V&DV-9(Yq%7+@m+7?+5uVYqQ1ObMt&rWi>M7XJR3 zD1&oQedr<-1XI9g_uh@b$h=l6hM6+}YA)nzf0*PfC{qDSc!-H=cNn^K7)N%P=5?62 zbXY!@U?1%u@V~Xwerqp*Jhh8)!@oV#^44YQt=rLC5B|8RPjzC8yGVVQ zP|I!(ghuXc5U3yC*d&}~ApSJWqpXz;i)LRkBImP`B z2%$S|`Hrg|9U1tpVd`Dm(K`x%-)rr@jy`TIq3sP8QQshc|FCwya5~dS zi`T7PBtnHwFSwsksfQlZgTZvqAIB~-y`SU9u3Tc%1K=*#;d&KtHS$X)@TuM|OsfL^ zVXZ&rQRf9qHhqpkCGx<}P3YQf3IIGkx}=S%7(6jL$nxSGjjVI14YBKZ(8&7E-63At za9V>+0XKNO4-yf0Eo}8hAYYAR7b{kQzOW0cz57zr1I|iKhsV;xWp`onfpFPDaP9Vc z>1op&G0bIyuoyDq6#^z(fw39@syRl6Rc^qFeK>}gJAsc2v5eb+48;lvjv!{|Et`bF z_v|3Er>vFEF5F$zRf-uy4I7)#8(?4P$hEVj{YO2}0 z8>Kkat7G;4_f$9g^l-n$i0kyz;OX&xv&q)!&(z=3vjU&zbv`e;eqO%$c{Ts@dh6$h z)f1b)Kko|6e9@WNcb)lubLJp_=2z>?(e%up-!p*VEKGM6;Wmqmnnf4PGPKPyeV%3c zGYbjMVRh%&-R3x>=C}*yc-!XqKhFua3CIw}X=k(lhSi@jjYz$mIQDs7?$5k};DVCw zLOvFKmp~5}24$=lL?6C_d4jlhI{D(h-r~-8me91-0u~2eKaNGs0=g_%UdmKDQ}-KB zG2;NpxGzW0W6s37eG)Yd9&(6S&Wx9lo7g%GCW6b6|ThJ1;@mE2{9 zDili*$`EpdRW507!-|LtL_B>kwFq$!0Gt6J*aM`!P-3Pmvx2D^a;wS( zq|3L4y7MuDL>H@{C{A$}d`n>aJn}0Q6=MVojekjK~!u4Oa21PZiu_1bZ5VE z&3*S15*G3SGk`BB%sxh#UcKs*vfM*McSzYCBRL}yO`Yc@%cWiTkyv#Q;x3-CGtXl4 zEy(U?ro1?F>d##2Ptm-^BE4Ua-G7zb`c+o=>*=ds&u4zUr2eW9I;_$=tZ_fAyLH%5 zc-Zvnuw~}3je1BCI(n^l)Zu>AdF!aV@Tm9IQQyqbd+O1k(C=Zr-=(8qVhh;*;-|La zk~ozN`t~hH}1gE#uRSM~3JtUv(oT!4Gn zZ%KxXlquz49+60H($@bL?Kxs+AtIrRVp)&Xl^rp6v(5#r(i7KgnDnmyQx>}apIANM zb1Pdo{%}xVY{s@S^ulk#H=5!Y6tl@5%gB0EmHeMrJ;Avv`dz$7`!QAK^aGC*aS1Z! z+1(5-w?_wNx(eN?G_2nIDAEtd56t%HC9M-?iAb?f)AmYkZv_!%PH(B#<4pe%?GeX5 zMPSVjAdysU51dqz%xqHW9boF8VkVJIyj1e$vH!s8o3ii%l}W!CUebSH^(QhUL%@{% zi`jp{>SEQF$^(YVR;pv()mG{=vC7t(E03$KwRSp`ZFGJtR@>-N5h?_Ilz0u{B&(4M z)z*m1r^eQVhSmQEcW>ei<>UYTU)SvRYh+(%kbN2Z8Z!tX4at^lktG!+N|qUfY#~X? zzGjP(eWz%VQ6f^7$WjVXlJdKHzdxVv_w)JP-}^rIeV_ZB`*(hSz&PWaIcKhUz8=rV z)8>FwNxhAQ(nGbw2Q}yG5C7X}&ws?~m(}eYy-Ob09X<0<-Tqj}`~!Q}NVJB7d)(dz zhvQfGYdCt{@M>`M&bzGPgmL6(ONxc8_=XO`tTxeLyCbwt~6D{}4yeFF6<3wY%U_Jgp8WE#t z73lFFqdlH!rjpH`*AAIzdtJ9b(LApsPJ{d0+RyW&m~9bc@jWL#@XzL4!sz%E#7VaJ z6kRpZ@h!P=qQ$o?FILCzPFZQoeZR`Pk91B}H-2b2dAAdz>tEL|+3J6P$VB(lgRv8> zry8eXbx$`hl(wF3{qjinO#Al_t!FxSF?s>rSgE#vUJg^ez=yovZEF*40eWXOh&S5K zDnGoZcTVA#&%o6n=`pS1I&&jjmvK+HyxcZyH1;ZbyQuzc-YhV4BKlQ@6@7t>s4nJkSTcpmX|4$5LsQ*+H>#FpubF*H==1OK zUVmDk(^J=9U8Se;Ov{z;i)G!}$tV3~>1z-1XXgCtqvW2{%K;?-!~70{sJ+gsFB!h^ zYI}usPnC*N>sgYggEYi3t{Kx5 z?c);j80Lp`Fx=E-k{jR>L`eYO`z{@t%@}K1rPTeFY8bs9k}?x1D(Vrp=r(Q25aN*5 zfedb6`WzY+IE}EpQ}9f|Md*`tnAS(cgWuar=Jb&wTm)wM0=jG|P>Pg}jO25B&CX zrwFT`0g#Pr1^`TAnmIvq>&PyTw6GUI;1d)$_G`He;!2|6>^<@^MXI_nuZIE=cg8TL z7ld$64h6Y$4&Xl<)ml-n0uo6xXIG^}n5~wzuca2Sw;q;HTv?5K%=A)r*CZr$D-4P^ zbAHaN7Zf8dxpt-Hzzq3w7xC+il;ulwv#z1J#}_WH6OIN&&uu4==I z-h1-mQx_LWz80O5Rv!3P&hKXZc$i0Yb~dmIDsiam#=42qxfuJ zYL0W25?vdSQ9BfZ@YaV@em^vPD!%4KUExOU)3&-Wp-MWxm`nCq+HGcv|_W{!k$xeG>E1e5^ER z{gjr1nax-Gu?|_UEadPba**S(c6hrqtRD64f%4;57UOYF4!cqEStJb6kQwajwdZ=;Idksj;jlQ95%LD*g09ww0Z|jvRb6^`)4E-H={sB*!|n8sV0D zk*hBLafq3_oz`9S@ZF$uY1$lT`2ddgypvv*o{cpGex{3WRMAcle~ERaQ@GE2A94{0 zOoKMED*hZHFWG(52>186R2dGdadfJ6Q0?)q>F0!jQd&xe=bM-lZQl@Z~doy|hh|%x-@6dj@$d5ZV8uCO_Sjo`5`o!In zRyc*Lk6&XY)zYYbE8<5l<>kX&@;@lNTm1Z?ufe$jDJO4;UU)Y5{0PyP8V?V~o@D6X z&&_QAqK_`zuQHJRkS#6!aN@7=08W%=cav|!cm4!dDPx>s1Cl4cE44M84)Dyve79{VXMyY&Zxq2Y7Ov zmd1&#hMn~?Jj9#o(1j3LrJHI#yNAv#D~%YW@8S9t!0QOx5?`d}J{{pU3Fsm}ds%zn zqRP8x4LY~%Yhh)&FA@z^vnn|M`s0Q`PPCy z@SESe$s4nJe4jAC?J7-NEon{gj^0s^>A_c`EUZnD`+9_D*bqZ20WJMFR$dYiGxS}) z?R$HKKm!+-kXUP^Q1gZLW2qc-t0gt08@rUyuC#luH(4uq&8|SNbL$3Z*-DTZb8%j- zk=_zZt^qTDE(*ZOPhaisH!-0h(oht+054IpKY#a`AB~ZS?u%E^JQ`Gm4O7u)aiQjE z5iE2GmH=8ydZYx!K}_a;98XrV%Hkp-AI6PSfapZYUFSoM(WhyT@gswdUIp zgfuM@Yi+tsHMQ%G_1%pZxkrLP2A69Vh+X3XRzcO(%kpKM8<~5NAPdggbi9b`?P~l| zAd1XTu$YMgNatM#!cl8n7WoL#Y01Muq9dA|fdtftf^guTUb%zZ9yj194FPMn6|=&a z-H8qGu7epTm=zCn=?JJMReBg;H@L^85_6nj#0$7V(zw{MgqJg{EtE>grcTBFDx?^wS085ihpRYdG$}^ekfZq~(58UCx z0HQ9AI=W^zOrviwgGN65oYf(mw=oEjZ+^wtyDeN^PN;N zp(PI4B~C3R&J!gr=A16n^R7Cjo=&AFo)Cmnt&|Et|A|s~5y`uP!Zr=E0f3)5KC=lt zpZy1+6bJxM>p)?CP;`RTQbuXu69Yj4=(Fp6g^viPWS47m=cYT|$qc=dm3=3><<9Mi zJGt9;@&zgibt;OTDoR5u%CjpfS}LlX(mdQ?9YsvrLt|JvSYil z%RJ;FZxuDDtS_``AiL^GOVzW9s^{BPPn6M!nNy5V`LGtS*L)A=)iq53&}1O?WkZk* zQo^Y^BfT`fg-f+o$=Ijn^LEXuz}H@s^X!b|{y|YN5g^5{{r1 z8Fz8FYMEPWS>M!_=%DwJYlW22v0WHj0C=%ni@1iw%0WA_c)Qi?2t_qzhwXM@n?tEO1cAf$=(nvt#W zFMX}2{<9w7aO;6n>jO~cf%7erzd7Xc^TAh}G5|tglp8#sD)OgRd$cwv6*UATlFsTj zf`=P}6O}I9YFxk981}P~CfF3E+Z1!ODfWM|9w69KsM}I}w59Y?OZlyqiq@8@f2{`` zZEd*J3V-vp{A)cxx2^AJ+oMZu1Gn0qSXBLCxJeNAbi-3QAulrso}YGD<@8Oc&hIW0 zaVx{_&NNoN0on4;iw^^wWT_Y3?TfaMFrlMd4xDz3C9bw3>BT%01cGvB+Cub;MXQf4 z#MuR4y3ss%5UB@UN(Dk0o$uku6P6Dq`vHGi;@O0660^&LVhyZ1L zf$eCy_F-!@iqd`WBZANJFNm9bU$6jiQL1x_*o~a&sY^^`C6;o!GwG9|xf4~(Grje1 z(3vEN9su!D5oVTn*)S1v`BrRx?|E5pN)9~gTqaRl%ozyS6!yL&W}KMpZN3Gb@V~N@ zfcN(=JDemG(gKEM!$*ueFD)LPY3q;J>8A+|MClEb9(^d>-4SCcbb41VLsAGYkZQ$B zMF@7~0T2k@9(cH>xjzXncXG z0!}#BA_Bo1dV}|sdw|t$fQCL8_7tEZORG>#NqA*v(JANF{qjAxlAtm@{0i&yj_$lU zXNVGj7t0@N3j}`_p8p}wzzrVt^BZ7#%V=QfWM>nG?-*Ri{*TlHe%+a@1cTDS<-|cd z<^H9ZYO}$z_=NJSde1I~c1k4mN9epdlT@CZVCBF4XwTrwO9beAD$>J}yQd0z)r$T0 zvlLT@;~{`&b09&WoGSpt=`ryHjG-x5&H&83z^JM)gPGU~v)6T&c;|dvsU?&^c!CVX z09~&|S(zPH`_R_N4!sdBVvmt+~*1AWerPh)xD%$ts5kZ;mk z@1Jk5^aj2iDk5)^$4_T?Ndo*}Q64n-Hf?yor|emn>>xlJK+H@oC-W_3m%-PJ|D8LA zOUtX_8T#-Of^VQgS!?Ug0+9ovLz1RQ!o-8tFs6S`y zGG`JoXO=r>-Z5wSZqDlW993lAMt|PcW!^4g-XVA1sbk*x-F!}kui>Y85B(3rcoENt z4`~#3A1khRT|Fmj_PBpWd#!#b(uoX;ScptRXrwHJy<3R*y+G5iNETXT#Y6u;RM)}2 zjQ`0%Y;WZFM_qRs^@wk4Kdi3fW1hoN+&p1*9m}>96yd3tf6(AJ z4F-Fc#_7yJu-d?El3IkfX|mRb#kYyLefcoh`%R<&9Gd|Hi7q39z>rq>Rb$dvek z%*ANR8(%C9e>ixl#QO+5hy_TmZq48Hv3tZ}7>84K#QQ#ykutnWF73X3;R(}YJPh`h zd8GKSE#${caF-f#^HeMr`p+MSBq{;2QDNed{>2iWZ{k#4G{vx({Kj2&x!hgY16y1p z|5)lyRl}24Wr&-*OUqUDvis*`Yj8oX)otI*GlYLroTwK&cuvY&1*(Zri_zAhpYAgr z&B0QRur7M$@QKP(2g(#LF_hoL3f}TTC|G~?ItM^9_W?3M-UnC`KDX6S+?AT=>|%4s z&4^k=>jp-iv_A((m8(KZJ#*@~agfuzliBo{0Eefr(_v{&?Y~Co}Bzwd9_%cUKG=Vni#{!y<7b5 zC_Yz6cVh(UC;L)1#WU(_FFHIB#TSKeQ-9?-WUprVE0!~r#Z z{$o*Yxv+i)MJZ&Vr~&yLOSO@FcN8hefc|s~cH>9bYL1bi*LB#t)5{z`z5A2HKClB4 zZBpB|rhb zxfd@nFPKb|W|IQi*jNX#Rln%6^uTB0r)Q_D;~uPTsFt6G&GNiH{ZrYa7_S zl-SjZoGBs&DO|$q>G{?Y6w-;7n5GpLONn@9(gE|K$rM6Jk+8%7Syg^E;7UnSiT9&E zQ!m!JuwKQgB1i!=qjD9-E0^~>QeE+e_I}x~^ z!_40soN=R_j=PqJ8?;y%`2a;tbl*nvztoez$w+ANI)C!`_*=2`{g-2qUMi^+R{4or z54x`fi%sIR)ElCC257~5OB`2(43WEgV_47mTqe0l)d@lp#{g;2@>H)SU`Z+wSXv}^ zDUXy!T=vS~i`SJh#1QklDonZ#aS>}fziV$+9(C*{W^vaio1n_K)|TN}xiaY&CsA%I zZ2XoQFXQ^U*)SN&Ld3$Mr$^~;#Pa`UO>`j&zPnZn- zuQ#in6%$Mp)x7wf=r4@VRT%V(+8BRzi?vMM{>SYzbAGHG2R&(xVNi*RC%1{;gIfIh z^3iWMZ}J`gz;Q0l)wr{na1L-Z?ud(@X8+lDfG1vq`GvO>Rr|WF#_RMZu6ln##}PsN zaMInJ_lrEYqLS1^8Ckw9LDmz5(M%k?EnfVK-~H{Unt=49y2)-a(O!on;|+{_Y%(t^ zH=vkS3y@Z8v3j@Cs^13pAQcv!J?o#mf98_prnda+Z9yG!H#7b&R%|xmO(v_B9jTu! zO8M%!FN6X4#XG9gFm1Ijfm@h4Hag%k|bpHb7Clc%GeZLp0R|bgp&Wk+F|Iscx=YbM9&#q#ed! zyZ3F1#U5bqCPgaT9gc?NhS_9*uUN7>GHjec0D5)}b(A1tfGE%N5ZTl-SIjeK90(lx z%^U)Tv~CX6>BkTbTcwj`QkGZjs;Rnj{siUl#a=_;w>@<11hhUMjH0uQ6Cf5K1c&$E z{eFa^air3SjT#)1v|%(B;}bwYJXOWcjs0PGPe*}%W5kai!nrO$PebUWSH}@)Ow|uu zk7hu9>+r56AUbV#wstSeS~PM-ZAwZSLqe!QG2N!o4G(nqys%Tzq65?32jcbuB&RrD zJoPM z7WY6$P%IWx5Qy}F&bgs}BSTnr13;kytgjoSm_=i$I~!$YS#5e5MWQ3^fHruperF2l97oOFfcT~_0Sr#SEsh052pR%Tw9v%VD?hpRJA2TP!`|UMYR$cSU7=|7 z+P=_%M0X9Wm?XH202=rbCNPns4l&#mk$Zf2LYMuscq)tAetsIjj)`&12p>XgQEky+ zHwhDRqGPwzSsd^NBYtmDQW~%oA}F!o_oEmYQ@qh`B)5;5PE2dyv1Tr9GV0P}(LH29 z@gg@*dE5~+AhHTkY|}Aye$r6%w=!;df?Uo`QIy;MAClY>JgheZVvR0da^<;6`vGfC zTv8w>%yft)m;uz@L@C?cUlPvu22g;}=kq{9An8tX^$$P`v|7o%cN>C09T=xW3GRh++ZkQDD;AmC_O%M)O5> z=wCo?oq({GHZ*7o31xH9CKMHF7V20vNG!onDybBY^@r8aaOuRd z%3YswW6k3qyvmKOV*|H?JCDT9Khct!zPh@Xo)mgDk3aSR5v410m$~k);e(8?vTCj- z)o_COO$$o$<+AJw7Y)UocdSkPnzcSJzIy@6(Mt63<%S3-S0Itatj_knIS}CT;zv4n zDzxr#*9im>U8OBwK_tVDvda}M0{ZJ- z3M^?zd_CvZ&37$a5f`;g-AuWBQ26Y6h2HvF&zO$~pq=bG*Wm{&44>n*EbG$`43X#9 zy6-yB;g15?JzlG%4H|uH5bFh}&Znbl8y#oLk!b+JJw_rHZ1)ZeJF2Rz3o0K44pnj{ z%0NgOFc;5>qctM`0%T*4Li(-S&~A?W334UnlZ<)FzL=X@B># zeR}tnxIlo^jIJ{b!!F6VBZux`HF-2!dhLX+JhJKd5q=&#a{IBU;4 z+a5{zgNa>OnaLi-ogR`TI2FHa| z1jr>=`ruTU%AE6a;<@LGRm#h4&pBT{|6D~{6&l)b9{LtG1j{nE+lF=~hkox20m5*O z%s?IcuY4K%{?7zrcsiBoItk)r3{s8>9oL0;08ZysP9lUD)f4!1s~4?2B&GmzG60D{ z*vLHcv<@^&9zoy{4lBcW0N^Ee2s2ud#5SI~+%Gy^OYWm`E29WJ_{I{lal^x5s;>eB zlco`?9betYWLFUR)R8}c>0f;5mNAycjd{gllxqe+3?lZuw^0u zlE?>hj^VRT3F$*jbSk!E@Zfpc_@kT`oVC}ocL&E;o_4TxbqJ8h*wa9cA2kem2REVX z*GXuo{e>Xmc_$mdPoCl>g0>S6p9M;-3O@g&JM|%FgfnmoY4x9AFCiKJWjnEfxInz@vu(&4UoE&16n+vt1kcm zAbHk*j)x9nSEFn9bvj1~rYVd^DNF){*{}9keZnl?%!dv9TbYBiJOn1G6i8VSPtN_& zH8a2E2}$_i5AG@~wiSR}UsHo?7E@3AA`=(VT$V`TqnYf&S-DHM-!0|-Udk6)F4SKx zc3CcsST4_9uIN~Q$I=l!FT;BM<6J)GNE5ehjw<;2#> zsoyba*>TKr$~k%EYtG8D+>C9@;MZ_)FL~;g)hE~pk~j@k9prWkhnA0G0sl^vHP(0< zFw2ERpm{zTxGntt#8E6;KDMasb88KXrTZ1VmRrdM?_E0?$qr<6%_4?BrwtygXP~h& z$n5q{yw=F8B0OTLlWYZtP}Yk`%6qgsT5JeU+>PYPU1h?~tRw3t5$<1+bsuyUp_BS> z(E1ez3yB$@VIgsN4bSOZoa|jZCp2X|)lr)a*$N=GKJzRqe89~B&O?K42Ae4N-o4cM zGn5Wi06%+dlLNo$!NLF5vSdocwYL$G(m_19?Ruh)6MCOUsjwoUzl;r40K-`sjvn-%`}G8opc z7dwBarLliH#5GOp`4YLuo(kDhe}6UT?#kQU>Es36qd?&Qk}qRlaKJx(8R~q{zY>oB z`=*8_&;O38!TkSiYJe@r|88n%{^0X(rUnJTq~l*q4L%DjxU>IhYFHus)6{TCm+POV zhV8qAg#R!#i2rv?4O;`e;{Px;kX4kD{+JprE{Y$|flUqV+s9OZF6fi@9|7`oLBuZc zEAcM@@>m}`t$q7DyhXBrLv#t@UhbUF9qRl~Q^Owta>FA^6syLfn{VE}KU*Xwm_KYH z_0JZ`1)dPByD2ij@Pg0m6=_3sAq55$_e;tA*&?x^a2EIp6qDbl==n8x7^c?SQLY;E z+#Dy?R*%wQ0kX_%0|Ooulb@BH@BDQ(^vhYw-U=RMrdzCUraq>cQ-b+ewnlN5e*>&* zILaJ^OG1JRA95~a4~R$vH{E+8Bt4l02f7-#SdU<8gE=LL2i_to$0rH@vOCMs(8%^6HOUd-Mv3`r+&1>Sv&)*Ehlp@$gw#M7`dvz z6ruWOwFB8LD9&dZi7}@V3ON1BQ&Rm<*qf4-D-G}?DMPkK3vr-wGV`S3$-Ht0h#PA=bDTKU64X2*S*!!Rb0f=FD-z!k|4=G&ebU`vyEi;-qS({D50^Eg;yQyr= zVI%21Q%W+isuXDknFeOWy;EYg6^Y<{e!i-5i*hpYb7(7l;ot%3kIcmum2<!j#x@iHP9$2bh7pbBigze_ah$W#IjbQLF&tezb5`tv+?lm$GF+D4=m;KN-hK z6yQt>IbVsXG{KsQJ@K1d0~C#iGd3$=7tUNv#oiL;1sq*BFoqrMEhNkLX-sPa`8jLl z32stNuUSGIBvkrjBm>2If9^7ip~U%S=z5kO?Xoz`3OEg#C(Sk|sCR3%DZn;-2_~}Z=@;*b0a3~%po&HJ?3H5tY@do{_KSld zj5$f+w8~9uw#1_qb7EEpEaV>&ulMcY=l|K$_^V`9>viB|;zajVCxQEBcbth+Vm^hI)rx8|jUHk3PKYmi>;^<%yA?KWR38w<8viv%_}&T1 zy;7@^<`n`Xrc7T@Vpsp$?fYk#*9P$dET*-Dt(psr1pV^- zTlK<*5oqf(8jvCnn+$!9iMGp>PUO7)RI_me8}-b*m~{ORY2=Y+keDZ{35;}x@%8+E zxKZ}v2hlj_@#C8ssEieG3c{{8hH~vGr=o`}#mgJq+HCkWkBOpc#Ydtt#ObPC_O@u$ z!^EnZ^Cl0aE_FOkEm>E@YShxnXQ3#iC^xuhnp+^6|cX(k?0 z1$pYY^C4r159tr8-~FuCR1X~-eLE7ByX|AobT-DreWZ2u@-x2ICjo}=TwHLIR|KB( zO^n)V5p&&{r}1OD&jz`Hv&mol@9CybMyVa>+mk0Of8}7bTQmW63+Lyz(DE7PMwv_5 z=!fGGNCHVhGh4|>MGuO@L<^|?iWQ&iosJ?8S0mW#Qf{2Z<`QSw#Up6v4ALiKY4j%K zl@(1DbG7)n3;om@X1cFM`pWi^`-0C5OQ&ws=xvaF!M=|#mtk%<2 zod#n2h@E3L^`!@*8k2;2aQi9)_b*<~?r2zG?|pfuX!uhqpOo>)t(5arHBY~5tQ@T6 zR+5V7^-f=f)1}>6YL!y^TuN>p8Xb^izJ7qy-MK>G)d786lIBN`GZnAnejaRSFn!^h zFrCdB&u8Y?fB0k)8ED27%mlEhumNEYiXAj?60dbUfZJ|wwmz6ON)-zK6mcKmAiN4x zjq-^ByqzsI23mP1EC6}!*G-25Hx%D4h8?{v`2|gJ1RFmk$h*DAfym~l4YpILBBAbG z(vMd0tb-CP#y3hp3-tE!Wu#GK%PUu% zG-T7vQxYuj5gB5vY@L}tSBi})a~66f5xHtnEIv|%82lrZ{%@P$ zp04xAwLm@P!*{tTk*{QlT97k3PW<(LFkcth6-uge4FNFnqd_^l4+AvML)18^Uozg# z6e(a6#OD^bZ-#1n-!tJQb2piZnI8Ij_yTCBnc0-E7muyrI(2KqzP8-4n-;bqX{(@u z4UURLD+8!$XZwK!-VhJTx~-q_)bR0@ok`;Hn!|P3m;2DKOs+?)L^x zXr&+=p{rQ|8H9*i>QJzoRP+ZiG$rX&Dokuft`Jf0d|ai0SfotKfY#v+6cY<{V(&r# zld`L40K#R#v&IJ6Lj(P#dEHCX1e-6X0@S(rSYQ`AL2I-Yh()kTL&vUTazTV={$nN zHqjh)fGib~S_ODsUq3paic4dXT1r0O7iMY4t`seNGZX5I!&8iIye!WshgfS(-RIAeu6m;kFT7_`Kc?iwZWsmL-8D)7yZgs3`0(L z0}SaFj_xQJcVdE4=-`eV>M8UP;~+HxNT5(Vt&rQ@7(pQooI^;H9U$v4Zelia?V77H zBDtsd0w<7H&m~GNdSq`W3Tq1LfRKI@UOM7feW1{4E-PKHz%9dWEgvR`lhom!bg7-; z(Y*V6^Nqr6cFp&=y6ux9p!Vh85bZ*qxfnNJ$2?zzpF4opXV!ATBUMw8FRv8JyOrB{ z7$Av%QN+{EhAn$UY3V?KM*#En{V)_vi;`|anFLgN0!0$amC}&zp%U&w9Yi`3C`+jD zFf2f<6GRg3zlSsgmD=f7@1dJFS2h(Mt zMuEbV+HlbV57F9Ow6zw35@NZw7xrpvU;!!F8haHGQ;X(b;*!2t^f?BS&H`^R@5z~f zesAB!T#|y>_d^9YSfD%7i_mdGsbE2V9jDySuDg!zg~6|C_@7EXK97>mgmv2B#O}D9 zP%HHPQFXv_1d3S2r_2o0av;}i!|S=_1(6C+n$k~cFuzPW(8JKqZY>_F*uKM~T@<<* zU5e(EJ;|d*Mj^VbP;crF8me$xaH;TzM5@*y@lMvEdc{2zVzwUP=m=QXBIBqLoE7TKBD| zuu)pf3K08hTVXXx*H0(~K(vjRJQB2;6le#Y*bDSs=Nisc-<`4Ae*+k+JkA$@pkDH6 zy9ZoczIr~sjkv(Cxdsby_HT#cCysUm26=pX+5ruBhBQHTkIu=X_BdVvQM4<=*V5U$ zyS6PXDCW?+3n&Z;_}Jnsklu+MR-IpipV6`4H^J3bDF526>swt}bGRQdFv)!pV;#r2 z3Y)dHwL-zSRCN2GOXu)s6l5bG)dS|IoLZ=fF{V%1x&h+FD;T?Pd= z`hn>JfYyd2JlytaFJ|4dTG@{&U`GU2rCM6BkdZ7N@V{DvDd3pzFy96oj-XDqaREbQ%A#IG@$ z@aw33uVaqAjtzeupY!^`OmsqW_z~L66+ScxL!`R?c{K`#5ZBDCr)_4G&D` zo+v&xQ5yco)KJkrp&7_lrEv1hDmGvnDYY|!>ltM(0Gn1I!NFni;Ws7YP%HdvCV!;+ z;GRAfk3Vj27#U|km$PBXw;lJXH-#_3*TS!q)AD}s+r8aA_LhnAb_?-tG)M2G&AaSi zSk~YJ%NqPg-+gZPf@KX6a3`!!#x(0=5RiaIfLY2?|b?GY>LYk)RwetjnU!{>)(g zSj${S?t=osJ(5jI-hgh4#z@NW>ITYoc?jSY{2-9J3o^eELLgSW#X(t(q9mnQ_To!^O7B1v2 zgmx^1xp1Q2Ezm?3+uWz3BB(Jgi$8aR7US6uC3Gy#jx45F9ZVHjx=}ouQFCZw9~2p} z^k@X&OkG0ME!}ppfMeaF)6~L<<=Kqo3af)~rrW=kC$O65+aviCo3ytulA6PQJkA zLQF_&uzzq>Z}t@uPZy=5mFRCD)(ww`Ll3Oh00wAvkTX|*iMM<0l~cAbX`y8pJdgv5 z>;gB5RH#I8-R>Y*B7jKMhD1)`FYJsW1HW>sIHK;ZsvG<#(rsbz2k9nQZeVS&`3E7p zyQ}}|~{sg+Se+!V$2&QlDjKBT1XKm+Gl|YaVz9Q@8vi3d%&F9Hcqj{TBi9huhXvlp~O^NbM7w|NOTA`L@H_Y_fnkmp?#` zGQlGGag(X^wG+>C{t_UoJ!D6_;#dPoo4qV2kKR94dGS9?4Xxf@gV#V?h8d;Flg?}R z(d2IdvVlG4>-_{C3q;;1KsJ4RILSKaZvpbUiC03o=bo9VE0a&pV1B#&4%^-g5djEq z^Boh#K1ro~G58}u?z*fvP^t2r)mD*=`CEYe=^2Gt2{tthnIqkhY^Uz88vQLm)<&>5 z?D?C z0U)1!{uy1|OcZllPQx+abdbgrliVsJdS5_1E3oHN%O`U1uTAn%Hfd=eJZ*34bQGt? zYc~$Mbknz}%S!R&r~}zfS^1sM7u^-Y55+PJ=ooMs&~kwHdC06tmVy$#o~XUQP&N|G z=0JSZUVw8=4o}?{la~F&Ucuv4w)7H7d%|kNzpJy!Sy`Zy5X=+L0~D^u5SDz_o+A^O z{I-1`JWZTgrgJeSRAuy;-sB%*FEpl?E$g!Y=1p2H96)|$%$X^Mi|*R@?ErE>)U$kr z&rwY*#T+%Fg+`=kEg|Vs4-F1|2F7s-^6nf)MZI(kJ1#3|N2TlT`O`-+`QRJn%6-*Q zdf4`mH#WWbsN4Q>gQy+$1s*L9i#Ie)R-8_I@8bBZP~g;Eds_sDD3TC;+O%JP$KuVa zPyTB|rUv1gW8R(N->2dXB7Q8Cbw>RB(r*y?>-$1y1QsYgHJvgs78B1ymUpW-x!F9=|_R{{Y1e-n& zo(E0)6@!NpT~WvR9%`AWWTt`M^2Y^^q~Bys`l#G*eO$<>5TQLfoD$M^9IgnP>VF%) z8j12Gpta2md0wQ(8GDLxH=CJgyhytm<0-LM`+&LKi}V|Po|5X#2dsi$T+2gwN$=M- zx5<2wQD*EVd!*UiuHnV?O3q%n`+OFT8fjh+jAs?>Kd?zmr(bDhm?(wcG(MARB)FgN z17}%xjOR9k1%2^^YKd<*7po2Hm`vXX_3v4O{#L42l+9?G54Ek%X1=_=VC=1vT(5Ax zAvI^kc}91JzYC5V{;zw!JN_}B3HvdsoBaMcpV|1?#0*Hu*BTqDf#);-_%XB=3g|C^ zExErv-{RQP6Q+NAzTa5}DO1{E+~vRWW9WK&iJK1K?);h0oa!-UVi~0c**{j@L8M$vLVX}M?G<; z#O?P53|SnZzF>Ai+TZuXO`j8*M%n%i+BYDt($V5uL8BK(<7UQTKgOX55+RR#C~2YAWeBtrszvKao{wjsH3Iv4hQfAKa{Yy8srDN2fZ1>kM_oQILBTJ2$FVTnD5 z)07Xq?{De9R=2h#m)gP`vLmN~q!Z%%C6FJ*`PZ$j*PlFyDzLu{&p50y$hgn#48w>PJs5|EQYf^kOd+PHcnmUCmfE8ov(;?&HePMJ}ArsBUgBr9C` zvt&Pz0{ob(St9@Vvt<8K6g>lwr?cbO$C(hD3V$!zFIP2w-u_tI4=>qUc3S*gX@^UKaxhN;ruOZJGW#KNkNi*?(&M z^84p%ztZl`#@LzNUt0@zcYp7E|I)6A$sgg6p6)~ltZGf*rop@RDF8GLrd;4dLF&=! z3aMly2?w%sN2{l?1Ei+u2r>YO56D|<6QXcm4|6QyJQ1kZghGc}LoB`vP7O0A0aCQk zh9AMWVkUf-l}w8R-J(R{Hiu-BRP#8QzyP{fVzTlMvc_Pf2l5fOq>(%^Ch!=}kPIfh z+Ylrs?fmG$J$EQqZ>Pl~ZWb~#97K_p(>S%)h3rcMdAEH14=Kk}rgZxHcl>7vu3DC- zw!7P^P&TIxrj3Z=YBc14$%UhjyV+6qP}){6_Teo&&a|mz^6$WsNGP5~e_RBSN{>kp zFl}&H$`uk(wmwYj;qZB!%P~MDprCoOzps?=q8pYtH-FJ;0Fsowf1XdP8^PldC!~T$ zqq07z9+Eo9s%1=PxzL5sss;Ew$hY3KO){}U#c`Hyw~;r=I!50C;Qy)a%%h?1|G)p4 z#Vpp(SjUzb2_ahxA(q=337VCF1po-LOHDS#xu-P^rFZxc6jll3Y5dFkP2Vc031z2djE9@n z2E?!YVX~i!W^zg`>77CU!(^{CY^++8;7h8eyk?=qs$e1h3>f^}yn#ZT4PYq@Bpooi zv1bs*lP+9CdISJ6s;{`K_HDntS+2ilJ$Y~|@1>heL&ZhEN3X}%zSpyOD*s`!?>$!O zo%U#KT5F|oaBn3(ulb%LCbh}d4k=X`_vTaJN;8}1u78iV3YNZdj>vizF#Krzd(%qm zV!~%e3h{0J<^+#IR;cg?MakC+1&E)QF*KM-3Jk4DL|>VwU06ook)KcpM?!ck2I3N zDMa#E);WNU{`!Yh)u5jbZOg~WHBB7_=Z^R7#CsKrD35u?Qn;DY!@XbHc!wNf4a^5W zerV^L>dKQbEWkt;rg2#~khyH9P}&$Wr;f;++xufE1Wg^McUuf}=n8+wj?^3GZxn>DR(8h-rgO7r@g#l-rSnPZ;=U$2jUTiDyS^7!+$ z_4T&^Ujqwmx)>_H!N!<1bcj4zjMUzk0FxRX%9$?3+HFkYpEh)BJXuN%+IUCcYwR_I z-odgqrtn)9?Iq?hI#Mm$J< zBrqs!prB;5AeR_n{1pbI7$E^^CMFd6fb2Ak7WzO4-Tk#)&<$_?IqCEIL$j-d^h3d0 z2tCT>CstO7h%*@16R&}zgqkY=Y20)NUM+Vw<56>OT`QPsT#p zD>xAj$8q47{P$RcJ9ClKglUpNjc!VK1OmpY0D#(J)b5W@h_7b*|~j1c{FN%~<> zcrX~MT^r$X7Nh`kjFc$JZn6kxRqq%1JYq`CZ%45evN`~sY!`pe7Lg3w?;iPz2~bBa zZ}tv8Q*bD1lo)VB4s-*;fx%!MYqYLIgotA_ZEHkwk2@@d8iq-Z0Et+`jthKl zQKzgyV{4qQwM=FMRcuf(bt*bWJvM2TP+Cmg(Hj}`EVj&@unQGe>mQf2{c=M?T+2vY z+iDyOAK#%F|Ij+V+dsZHJ-)voeqbd2$!h!{KH-^W!VBw!m;MPO=?S9^31cG(Ijx;m&=BifY+HyQa=Ue1vREk%7TZNL^ruqGRT zrQZ5&7IxDJ_zI<(tA z=0t?+Zg2MCH$)joTLvnSfoYO*-~hM>8EqL1P>jj1#T2wT zGhK0c(zbcBfqC+oc?wN=N~3woYk8_-`RZEvdu;Rf1?FpJ=4&x|~>uH}=&3iPxJ z3_k20J5gZdRbaFxpwn1z0CpZRfu3U&nDz@as@^%VCcp-G=cpVuoPuo9oihpo_Qs%# zR$=&|ym#+7AU=jCr|!iMh3;ztvWpC#z#{+5qCl~OnvF#q(?uFXMLuHxUA5@{FF1jt zDumu2Uyl9a1ag$XR-;-PzswB&+Jjn~zI_~dqZg9$dy1|sWowB4m+#2s4FH5q_Ts-n zDY~A(sW|$N)h{2V0;A(eTZkXK$F4zpkb{XKU5-ve?}PTBZOI{UJZJ^gqJ^Q-43wgq zorv7_%XcJ`>h9!!h2az>IiCaVLF2E~=+_MyAUa-i8ZW5;jA8N;NvOWp5_HfvpKc@@ z^E%0R-(10YPF=`%RJ4@Od&}B&PW0dg_nsaSouMkqXPbIX7D%L6wP$!*oI}e*1;c2# z3op+V*>8Q_JxGKvVF4LKpsFh;T-Y{EJyN#R{qzrjkWZE$8y*pgvl?~O#$4TBbSL|Y ztuUukAXJMkfKqfN#gOl)wER9NE~gvVV)6M@zV!HbbPt_81J$AfQwkofDtMmH!-j`f z=l^yViT2?B=;?9Pz|OP!snz*~dn2ym{P#w$d|cojk5v5BFqL}#Q{!wQ#0ey*^?qtz z>{f()M=yiMXy2!U*9AdPt_MQ5nA^ic4m=TaBmt$e9l z!f$@5hY+Q-+$#g6==$V~%9s0<>gSgqsrD#+8Q3%I`2~_;m4A7n^S|DMw)X0Ct3!9& zllu$6&X*2u_Ymakm>1-cKlUIWP4a81%5QpOzQY&%&Svu7L;(B7wifD-`5=JKx8Wie zS0|$7Dpx1tHJ*4J4AfF?G)gwR`1>9daN^dbPx}pWu0y_~g0zeOZV##(zWC=J)Uxtv z{WA-#^4A`;u{`h}>_KUd=zCY#QFjGklfU+$9ZS)=Lu$d2og>JF*0!hP^(qJRlm;%< z5!S@t9NPl8p^ri%7PJSQTYlbw1t54ycllKyI%ESvB!#e9A^Y{w;;JLH+uUK-BnoV} zE&^e!h{bSu6DH@$-VWiW#R%1SCbyeWr`YIXq~-vV*RQv8+uC9ji8~M6iZXgAEw&VG zWRl09)@$G!z}#^xK2NZyx0yFPAr^a{h86>8iWV{mU<44^O%LI9XT!yewhQ082g7;- zfWyOR>$hs+KX@GM4YCiAR=?XvDU=MCwrAMH3#sgkd@ z&4y|;wDXbN!-Ce16Lm1199(eaiKP&}OqonxgM2t(8Im@AK8$40gbK_2S|ER{#Q0?Y zvsCG>Eakm|CTESGXO4a?)O=iG>X+G>vApM~?q&%k%J@Z|*tcS%W2F{p{Vxi&zLiiC zN-c|we=D{9R%-pY)T+M!x5~h8Wez-L);-2AYcju;yB{mF9q#{^J!te>rT-s$P}|zK zyELA1hkx!tujS+)~LNhCB zBJ_~-;#kN$5f(V>6r8GU$+xJ-4`2+WKd=$T0D}uC4#OzG06urZ_S{`=u8%rTGn;@G zBr}3fmpqhE>~OQ`klEGi#)Xk2FX_}p7&)5pW??e5=ycUX65NZTDkeu~`8;MUm{cus_a@@cN|D{$0^Xw^? zvUl@>Hnm2kH7RKWQ?lZRI;AqIZ;0$Z!;L}q;)YnS@RU#<2@(P4{^_RVS$mGN;Vr10 zpVGMmBKE#UZPft`eM7h-r-oc%9@;!yh%JFrqBigWM&UWQ{1AS8c$|b64Z%& z3AKk6Z@VQMU4O6@9rA*RR;c967kXv~%)=T^?(3CSmWN?qv=GFtpL^|+_X^DpNmsbE zuU06}j^r8fRNx0PJ9!s)sIHL^YZRV+4rd?s0vKAbzhvV<_!x-^B3MRYsJmI`eS21v zZZAG0PhOfkZ0s-R{{ZkbG2RHqG@LOh|G3!jujpn%%KuGtGxI+~H;-6)B3xKM3cs%&~NEQn>N&0;x^DsO>Q$cQidHQQ4 zW0;)5tNmjnlk`H;ejmw%Lde^Gjbuc?EBKF*Y%=DJRj|AB7S8%%=G&CVA%m7&x0-3u5(gZTM6$16h}g#)3n8&Bk}<2N51aHi;s6b7VHlzlQ(~!r=HVsp6)HV$^BwR zmqSWvsj-X{x@iKWQrr^IJnOf20d zIs0^rY$-`+{3`YZQ=aZA8vrDDSZMe?5j4+Yc}0DyPS2K-BG5QOULk${bYV56dKybo zY(l<+@OV{AT{2N8E2qjiB0?KUpRqS<-ZN$zjAa3mQ&caU$Bv@fIV!RCaff|&VXpTL z!<7T@bBOg%s-;nZbG$x;LERRStqEc}+D8k>y}w!_=@ZP_18g{ZZhS+Jl0OZ8cm+e@ zf!OS6v|jv9$~U-8(&id(6NYxZKapJj16lI)=jKcWKeuYRfUjZPZGEE$^HC4rSKN3H zSe%|S9hL%UOezv@A)Tq-dvI-Ek~n#s)V8~a?cX%Y5}k?8lG;BB{#;6) zVbyWw?g~w$%^#DfJWMyNMjMU_U=-key{~EQ$A5}rXo5HQs{E`-PLDq(!2+WmRyYNq zi266^g54CC<(nl#Y{?e_-1)>w(5q@H&_29Cv)E0rc;L>tNp=Ycqg~HDdzN_Inl9k4 zpVm7+u!RhLNYOMENwmI2c9y3L$b896H%~%IwjX4jKJUQ8ghL|3$KIxg!w4Ox-eqTi zDz-0fb-tT5!e7Raem#bSZb^7C8{DVs8ArP4i-S z=VBot%QTx|WUCYKs?l!ulA|B=0KrELF*4>bsmyN0R=8)cXC5$8bm*)Ei z#K#)Tv9!CgCpEk)W{3Q_3LpzA23)k9tUPLeCpx*Y-J#Nee}_R>ya*5tV&+V2$JZtw zdL7|G?Onyv!~@L^I9DN32vML+S7{AgE$phu*bN)6@8Uw6Z}gnA2Dj6IHULxxe0$iu z&yf${Lkpy~A#C}a8t)iSrJgRKYvsdGXS}DVwPqQpPWf__V7#FJmGhnA{R+iBvc1=^ zdJm^{!?mwa2GQe4fcky4k4Tm$(~al_@Zw%%^(`D`1Dtch_dB3s;3ejXA<;s>2gzQ% z2i8*3&3a2(8f;(h(CLx7v;*(b?c*R+6DwH8A_%(n5|vG6)JK0jc~2|%744hIfofiq=3=>BenjZoO`qMR4m3uiWldjIF*0$w|YIN z9}hIcXRkY0B;AWPy?kJ|b53{UA^mhylpRV4euk0+xwv53#hD+zL=woW7hC~KWp_0) z<$8+_{X3k|dgWj=Oq1%^l;7HtNLeRsKzYO{z0CUWX7yX9-}*U!mRc%r?6?*CPVC&` zYvfY1K4wgYn9WAqMw4Lpr|g20_e%Gl(9-umGNG<&M+ory&IwZmT6q}{3J&hNz_ZL& z;L7P$zy0MC$1_?OBq@9PMq7{H1!(44LexCnv=3<1N~%m0Q@T8TU)%|u0w-a8Sfs7- zkJruu7$<_jD!_H;fy2koqCNwy_vd(^=ZbhK=??8?vS|pHi$M6b`Fd;2q4PyiXGWr~ z!f_^8sKrh|o<`%&hQd*c+a~?|lHhPp0tn?uYl;G3vsRWbFY(^Mf`!^jGl!h3hz4H+ zKURZNd%*i0o@dqJ89Rb(eBik&r=+TYXP2)_Va!MOS|P|9BWZ36U!@rJPTcJ-Fqvz* zn&6bd>F;vj3hwGbO|wI_ZkX!x;?tVi=wN5kX(?*ZJ4;;J36v|tfs1(h<%y6AYg0qE)HyvAc@a2e1c<5zLRF6;ZnwtYViCnckrE|DVzkvq*#hC!wypuAXf1nx;5I|MuM7j1&1)d zMX%69yzdF^lryN!JLjW{#)#th27_h#w6D7h76E|%76~K(*z*P&as&gvdwMqo&NCUv zgB=MdqT?l03g?hPhmXhZ{bmTl4hNEZe?18Q4kXeql}MZ6$QnkCV8{FOpWpA)5xy1w zFn0F~5G0|l)&PoCdQ$9dJ44{7tmzKsPVOa&N+X~IX?tLRz}I(}HA5jY4gku_bEu^R z+3a*4OydlR-n|IBapd&l$y>Xb$vP22P)%hY0UU%(@q_7=%WlwX4T%D#>@>T%-yn1+ zQaDEKv^l1raaW-YCM9KU@H_pXz8 z7+@hqL8>(Jo5X-$_vQ?T!=$KE!&rg*Emge%m>RA#C;cJptPunUf@`FK%i&?4w11`fj=^-0_!@k#|%c<$yj5FnQE8!&2mhWBFGbh2AmZwtFZwM|z873LghJ4yxuq z%Y&DX$Q2j=u2cjNI$FD~8)-b{K=}$lPrL>3azOs~0)XX$q6XD#z{W9m%J%_gVgObR zc0vnq8qI@9&Vy+xuL277(J;M54v)SN+NzB!$3FJ~`W;A&WxE9v@D7l#mAZRd^ zhVyuKNkNkboC4&_{qhWANubjxA}2q)VYJk@5Pp5S3^`Gz>j9S~fRIcOpq97%1Km6* zR`E=$;)QL+%fO0}%!<*bim}lOXCi9XM8%|5<&-t)Q{}h!FbFvf&?^N)$`?2R zamrmu227F)6QP5Wj7r)IK$HOcnu!yomGd}O{rq4hL;r#jE+Xs|D?8kt9+JxGU#)a>9gS7@&JT89Z{*QjgP?y;-gw-r>Y`6z!g zvo=EzuCrcC60g(Kt~2-@-Ml`Log7y8@1Awvqxrt)>-!hi?^CtKglK}+;`O)G>kX3;hqXWzhLt28e&sK8 zb1jr!K0b)ETSQ-~YA_CJ5O@ctDT1!rIO$R=A|2knqw!l_`Y&2aRXspQK%d?yGRH|m zUR+~2L`zW%vV~|VhmAR6=c>F3V51!>_jPmIdNWJBrQ>&Wvp`6Fx7~h--uy45n)Q-L zcCDH|ts~8?V}Fur#M>sd+otT=ri0pMv)Vp1x6Qw9`?TJ+DE?qs`@vVc2j7DptY$q} zYksit`oYij2Y>_%uERo}Vxj)`NHqkB4r!eZnNuCI!5#A19SSWSO8+3$IOG15?@<&x zyU8$=)c*rjS{fWWm zMqyoAV81QSA{ao1RLxd*;dQzpFbdr6PcVwT((hmt)vCqzZjpI7!=dw^U=(Xeytnm- zd5_*HGyyzJ>zbbE5gz!{yq94Dek#RnBb_!4-j;f*y*LY;(8ArKAdooZX9cM{@$J?Q zo$zD~nhX~s^$EfHe)B>hLhf?l9vzME1_*sT>{=ee-QH4|#|9`$>wcIm`GpgJXTj*@ zkMJ$9lNOux-LrqY02Ld$pV}Q8_P@}6Dtq`%^>FaND>lToj>NwiN!%QP zDh(+IUfn$XFU5wx6qJ7}HbDMKi$f13302}?k6*CR&do>ql2!bayDRaPW2dTG4uD-E zV}6_cP6H3WDZudbXV)r5|3IJIHW9KY2N!M8nC812ztAVWJX`GN$RS|egK0o{&A~($ zzaC>&Ai2zgA@GUdG2E{=+9e8tjK!S>QyCcHO)NnD4ar2N%#R9~BfNJBOOqb)IC5}= zyu>-4l4LzW=7NZ8!ny3XD6a{W<0E*;1PAUdni(t5_C|Pd41%6Gyb*4bzF)2`R1-E*fs+NM3nr!W4Trf!?@)}8r#u_3NiKKPSJ z{ErzQul`W`*~n|N(FwV;P^%$+96|}qLam0BwjD=w=PsJV+FE6i7yj#{n#5FCMt|$J z`3_ylAf5T{ar_*0UJu5*t89L+7YBzI2kXHjzAk-vvW-Ov9mJZcEE(Fiktg-45WLS6tH{|t}jUNQPxcvR3()$2bBk2YU1 z)c{xw;CbhLC_Ea*wdFq*mpt)HuEq;}NQ5}stNwa4z5L9u?$ldIuC~(Xd_`buex>yn zdW3l`Aoo{zbn$#mlG%f{&2{L}^zBor0!hm&BTTzr;ZcTP6dBFJ$v^ah!lQ>V5(B!r0N7x3SfuDVL^8+)m1JPHn#x1cgTve0js6Z$Y+HJ|;pLLXQx2(+CBST#cBP z3SH=~MS6aiEBY$wZ6p^}EoE9bfsjK2FcUy(Gr#wP5L?mFu19~*QwqN~7 zS*48Tj;6(KE^GO1p{@qIm#53_+U7`yGJ!>%q;uxAS2GC5KiiQjB2#K zI6(UNk?+1d<<4^vhxnyK+GLH^OO1O*=DxnL%(A@LqyFBB`r9e44Gzxhli?o2&RJZU zBW2cj*T?`S2W;fFGI6@5yzq_0pMTCU+^M$-^)8z?@P@@xrqf|4R?UCi{W%>L|;50yTDwG2!n@7 zavxULuA0GpXdrO=jTFk1fJ6m06Wl_$Acedy1@!E12h&yyCncS+5*V03k)~|8i`iK& zPEn!y-U8`s#Irxdqum>f4)1<7A%0apU+mu3n!Qa+Mo)9r3b8ES$_Vs1VJeFHU<@ z*GW?BABtB3Rj*25)U=JCy^81I&`Wnea?(S52QNQdDWT-B?r1unym_H!7v`8x|MT3n zuSF!DQc9GV_*3w|?a{PJ)CDA+P-y^ug-3O+o&_R~mFv}!X+SW5>w7MD$BBKUYjpN5 zhnnmiX95B+LIVahp79QA5oq^*R6YMf+*Gv@pyU9g+)gS(0STkvbjFxfE@? zxDc!MFl2<6RfkNzooh=);M0A&`8#O(r?{tTb7=@MQzKH$MhN;veedZm7IxbJIH2nQ zlVB|avQ+?4KcLLU)LXyG#6{t{=m5Z~))QvAghc#3vKGd~!FJSZTJM3b4n{m|KYk=bBU3f4wnVbPc9*6$PMG zRXz0iWCA>7i|!bfOq*{14d9C2s~1e(9sU^}g&s|f zl_{Z#?gXM3rhx@pyma-g8bWl0gg`z6&={y(-3I^?yZ{zcz{Z4Vw)1@IxqgWRm)i0_ zEW-<=JV(Bh*s6#4U4Mp0lNtxyOuuBl{zrK9OYZu{42iF4Fv|36v_ErJqC&4F*?x$; z>NsbT)bygr^joRj<_ExD^JUqq{)(W@j}CmzBR!_y3+?mg?*?~D1%5%q=Sk|yqy5Lk zYeJeX(PXYX2-2T!!|}+R`n+dJP3r1e=+`JzGvZ zWAv`^){h=DZnIoNnOXg?aC$jT21c?vU(9zMva4YHQ+Yf#e4u(l_J9BM6jI(51|1N;o#)8yw zX9OJ)`>Fm?hiUPaGX`^pXk{VL=*lC?KgD9Za)?im+r$4vj@`E)>9ZANAD2 z5B$fY=^pE_eIu4_eqmY-Va`i|I+`Ti)vy(Ta6QaH1MBb^pKv4p1I7*ErmNwa$zc@D z2ute-EB^@V^a$IAh*KjG_Nx&N_(&(sNN4LvSN}-&^hl3%D@=Xl#nnhEKFV7&%GWyT zihq=UdQ@OTRPadDwbdvZJ~~u0I@~%s(my&nJvz1_I({S?0{BJK@i8fyF*mJaQvGAn z(_=ClVh*|lWv|9C@UeNCv6?Pk1*djpJr7PJ$S45laj>mlpgg?b?qtnrM39OXG7p1Ne60 z&IP20HcH{EWcVGto))HKm@pi{T71z{t}&e>4+Bt9a7P$?B1MFW;W!7T6lQGVIMBFc zNMt0!OfJqKKCni^anQ992{(@usrRZbk;;*S-^T*66hna!4#QVjxIEbAVbH1sCp?$< z%+0$uM(W0jO~!t3xDgD!1ADz6yrz-!V}i=RCE(*qf2y4;!1La%AoV zM{n=+X2#DN3)t)wi)G5x$fRKNWE8Brtp6+FQQLyUfdxjH1;$MU|6Z7w*>A$s}<#>@X)`l->>mVm;I)k{Pw%%%U1m|vcCELcB6527J#i*8xNayW_B zl5B{4mw+sSy_W~$RGpHx`Yv6rN5jdm_UK{}LedQeAgJocLq)Z!<(>S%0HDw@6)G@g z7^{M`MWF}&U}+=QvD_C()MouueMH$ZKh_7=X zLIJGi1nMA2&>R*;=7QNIG_01Hi6OeRKu&u3c_PPcLIny}i6Ub;*_o4>Sy~8y!A?e) zW9N)h0b0e;Q8X{>2Eq~LJ5j+oRNfz$&7l_XwX^_D$l)HQKNAu0Wdl4^VBHAxbFCV9 z>K@k&LG7`jtiV|=M(sF-X z=(1|Hnrn4l*XsW3h0Z9e?w4Hcb)D&Y9Yy?}#oy&>>sFr&X?A6zyV>{7oEOa%ynj|( z%qi#}7rHoQni$Oce98kXbFTxn8s#xb~<%l$a(8#&34#(!@nxU1^AIZis)~ zkhtDJ7jI0_ZoFyNm>SfWp4FJy+?f5kF?YR@@vm|<4MkMxBO%DIc7j-1^+>Qr5e#GV zlzk~Ly9%QaT4z+1^HlI@Hq?F6(p#%AAFS6a>(y`*bWrLl71F<^2O2CCm#jX sSe}2fq`^l%xngbm)Y_(kyl1j-FxX!)mL$LofIkB2ol_a1b0txclY2<8i&Rq1b1&F!QCAicXy|8cZWv4-tRu= z+;^Yv=lya2+%;hI7^_#+s-9Kzsb@ZOR*0g!1o~Tow{UQ9=u(oR%5ZSV!f!gW zZY!KnMY8F)rM$^4SD2~nl(dYI{?;8GnLR}TVbx_AW&Wghh#PxbIeX+(t4SZUyWQ5$ z1xK5A&sM#B#|xN84hT@#S2(8z0+UBdLj}rT8@+;mg%y`#IxMC97JTijkgn?bBV!wK zYkpnm9tIB||@wDb)#$(WW3%F|7S-VT}JC;l|>9?=wrmBV% z^3C$0LG0-?z(% zaH!aS{lmkhg7DzrNa3VJzpA<|9<{oHa!eCAff|u|M0w5mG}ygZN$|+xAK;O?Yhq>T z86QHR2W7rh*6qH@l3@kKCxfWPCrxG@-G6)wNZ-Dv9Buby4m7%OlAqCQJb-R;2ea*h zpeNrH30EDTI_&q#$~+F-PaIATb$5AVC?ef!+3?Vi13C15Jh=~q`n@#nr@}Zr^J8$hV^}N;;76Ug;U;Rl9#bR zets70Z-v6ev%`>)BL#K}%0|mP=SuB4(~io&%c%298Ajk{4*#RN2R;b3 z9@hFmtswT9w=G_Lyce#kUR=<7;wPW7!3Inufkv@%Jq751plIv|W_kz6?QH&(Ucz&K9L} zANI1Ngl1g14-sEj^%yYFF_uQy|7Y@;g|H&T$z%F6*W$rDS%^&hFDiY+j#mMgf;HB2 zYak}U#$-`RXM_s3`h_?H^ zV8OdR^*WjTj>0Xrpv4;JHn|#cF#{EDRasc)QyC>>tMHy%N%gm^(8y`T2ZIWG^kUUfy4kvYJIw~1LNj9uFr`9L6LNA?S=GDsw})@EUntK}qz zhSR=r&)?Cn6)3&Q)_q*}m{?JwZdKY*lvYYNRF+N`5Sf*Y)GCa(^t1e)_ z&13F!*Nq*?=X6Zg23@gb61*B`lZW;h8+c#g=Ra*e-3l=a3Z8>~yvKA_AM;?7JugA* z?gRvG{OZEgX|b4Cg18KZ^tHNN?tBpu=~`LQgY{R!)pmZ}_sMJeiIDiS{KsQ;!v9$= zci3k|8lRw1rw>A~SCw9C6Zs?$m@sm`OqFdfDn&|U$K1kQQVJI)wz@RAHB_E>Nl@ zFH;kftLgf-h;2Odzu&#sy_rS~IlV8|cb$C0^>UJ^-MRxBGGX1#gbtMI)O(*^(C@^n zh-JsHK^z~dOov7VcjMYxo`24zJ8gK6894XpxsKciL)#4797mt~#WJ5B*T%=^+B_Dd zXg=Mp43#&yt~^u=0cQhz?z+bNe?7+e`T51k^Ao?gPWm2Z09D7p z7M@u4#G!q|4=WD>pZBhdNNQFwB&$i@KYZMOfW5aiF6QQTpSM#-xsEh=?H~(kLu~oK#p#Ed|s-oYflTvA*pADhw<(#RlL7DChzwkdnN%tw$TfUalXbKu_nFj13i4e87$I?DRxO ztf#)M>mLSLH81|!1}!H=BRSSHX=SQWKzorJE`^-u`?Z1k5{9y48NE8eIc1@Cp55ia z1n7=qBT=(UuF8J3&~xD%u$4!rq;>V36IU;ePban=>a)U?)R?gQK%)jP;UiwI{Y zh|oNW8dY8Myxvy;ZGw!c0uj9X!N^=i!WaQ1qf{ui(`CRtJ!w6`xuk8 zVvB_M(;FN$E^3F&xDH-u9G!+O{|Tk#TQd%Y60tUp^dR zQCrn`WUYT4+I$MmS1&c4+=l_+bgj@!&w#!66j$4Ix+LXAs4Nw&zx0lQ*+bc_61gOo5@#&TRm4uwbOoVQtMSe{mX4Wy~YV) zR9}YM_sc~Q4E+X&_43ld@xLuP6{@A}y6Qd$`ywMH<$ig$ZQf?A*$W1$bC5IZ9S!~R z8N0_3doJ6>X&ZI~A3kR0v&JyS#|Z^*z>LC6zrMiZS+803In$}vm~H(FSX1>;fbja^ z;OPbVF>kh1Cn^VL`u$&UIOek|&HTfl{uylWeBtp>A5$CLD%%=q(VgA^G|R(nG%~;0 z93$jm*0ADny_Q_p(cyz!Kkfrt+-G)r(nz8X_ z8;!D4C~OQ@DLw*YJhyT5<%{O0t+OTWlebnYP1jNO9vkT8LIXUvF;QOMSDK)EB;vEg zH_DLQt2{!Y%AMJTJ1&gngiucH(plr}VIIuej0UHh_Oii`&*NGp5;H=w`6}C0&V+xH zo&ONZBfr1U_q^}Pb`43W`C(Cp@k!yPYyJ<_ke3g$PE@!?c4?wca@lEGX+5af?DMSy zi@U?`i=~d~S>@&1;A@YSjNpHANx$_I&yz17-i{eu^IzBh)g{cn9JJ(NpDs2ic7ca( zHP`;SwUgn3tl0LAlGKX~9N8{?|C*n_p#cxg2Vu5^=j;n?ZTq2odKcA~?s)C-1csir zJ)#JGPYC$c-@(M&d6N3i7q2sgtJ2NPEggagiSdo}FVKE8YyIs&|L*o@8$VsbVBPW3 zl6$Ti0>Qs;|NYPo$N$aZt?~R!|3m-(=keq@=Km(~%;i`q85woW|1s&`p+IsyGtz(2 zY$N@y*9`wfhFgAO{cEfK_i%o?qf`8g!2TzwxFira#Q*mL|F6eu^y>fnfw}$sv5=cY zT;p;5wOGTzWj|NpWrcidYHDo7bH=I`M#BwuvXOmmM@}Jn&@^m$uNgrp!rXsM=W}K+ ztm$Ukoc;V6JLJoAy#C6>#5oPH*8oIOjK1=G>;s*2^?qtE+fS8oJ$2p-$@khD##Y~c z0ja7NKh8TFJVjOda6e3IEZ}kc$IySh!43I*nVyV6;12R~mRb+Gt?t+^_ukbad0Get&ivGywKy;0Va_NRp3869s9H~R$9*HcpBvm z^l@&R5_GsIqDd*b3&mc2>V3I?!nAKXkGUnT;9UnfMuY@=yWijX{5ZV<*zH4FuF&oI z*4r~097kvBpC1T?w8v;$CC7~Hy`VA=t)k5*7nkMc)FxCz^DUFje|Uf?z;Bcy#A*% z1)eV}8*&gs%j2Tj9M0q*Pxtr1y9=io>`vuE=K;5%#|eWG2EM(Zu|p7WZ`8A19K##J z)%NsU>#hO0yLNq^@)6JuJ9uGLQxL>rld)Rkv`*AVmDUG7#MLOn~N_;x#_c2M9uZQlPF>C z`ocL`3sDL_jr-Da^k}e*Kj7rj<*LBIcO^Cy=Xx^Fzv_T$AqJT~ZF8D!gQ#$?hh=&} zFJng=_dUHItAnSQTJOTM*GwnD4 z7}evh-Rgl5Q|r}L{_*DX@=5wR&m&+6z6V{_{R2gn1QErd7^~{QRub#tS4# z>c4er?z4OBO?tWAf!0Tks2^U3*hb6>dV*D~?>_E&?H#5iwq6(Srq@vJfE-6EB}j;V zq<{?!9>I|HVrq*06rwbVBD)v>1>cQ;q1evFmo%4zgW6zX{ID-PckN;dtR@3EO#Bt~ z?lZj-ed+&==-&Js2-aXiGb&za^ZVLLqAt^V)?Lt{(Eg-Ols)gRi|%>kT*f6{O96O4 zlx-DogI@a-#djabb=+LRrUt&G-v#9HLe27)Byi*)jJ=e z{PZ8lzbfQC7cb~Hvq z;KJV;>^%tBgLm z9=b=@l^Gx_DdDb+M^YNDHuwyUt&VPFe07mCQ}ocwUj2XUaBh+7S8Su)PbpbtaAPbN zlx;VsFDJfxA`ocjcGTVQ#89?~%C*UFzWTK0w8h3&$-VsjrI%wwgO+@Ujr&Z*L;4n# zFbn~JDPXC*tie6!dMk{i*=K4vuG~`AZh^BBT3;(s{<7UQ6NJ)cQLbt-VN|Y}zHl)_ zvdUQp%`GM3dOmZd5D0F$h$beS`X?g8cMINBMhPT=63)O%L?oAo}m8jfH~l^mw5&> zJDrL983$^j6L;uywL(a;;xtC26BmZ8%og>0fokq^qJa%#pNmfW zmB((A(tTaZ#9=0ZqiF?$$7katN|0k2_&6!^evJpx;8n30N(r3>Uw4%gJw1xG89?nd zUUm<8PoIaS?4K5muU~sLs~6t}%9KA%7JGtg_Xaxj&9D@*GX0w%z?s zVhZJ(TYgM;ZFvs6RvG1Ai+q7bG>aFHnB`QwKn$D~@}qPx^xo)s?M4`I9~v99IYVu_ z#5V3*4ZL@D1#eG8noE8E4qW~P99@nWNqQc%9)+MTmHDn#BtiumFHKtU*0{)q=L37B`BlaHc4Ux-Z`rK?b<`;l>HAY^^eGnd?~XZN`;&;Dm>Xv(Y<(yIV>KV5xpv@ z?S-mz>GJtg`?`!tl9baOM}(P2W>smu;uNc&c}%x{|@R{mh$VY5_akIU1UVGYpJ3Ej5P_hsYzedx$c`iymVO4u@?a`{A zuY>0K0Qhaph2Q)BiTiQMjX!d%skzy+?dc{hIl18!3^g-1U!U#hf$0ubwY+?MVH&@F z^=-nYCUXq-i%eKU3{pxBN6Z`-s!Y?<)3*WcKp@b{Dzw!83U!br05b_4uLW=UgJJF; z6}Utd$XnS=YF)OH11Gxm^1VyIsL^ZqQxS=e%faH=O67A}HCc=kXEVI64$8@#-MTRscl zih9KkF8VpKoC}j6LFjrO#@U|VT8W*X@*#GHhK2yZMTX~zR+WjAf&yl%jE!8hQX<+t z%#79s(8XY4kG)<(`%fe!naRnTEpF$lo~P+!yZZz|B1Cz3>9KA>+`bE%3C6MLG|qg! zP?6vQrpK-*m>O~J#!nD2SsGZ%c6W(Gua1U^sZp%PQI(5|(F)fzJtZ}QOjbhYR2XC6 zCnxM&G&vy2B;`$eJzC)_R~E=>(o-CZ6$84si2v~VdVz0zFTO{Jq5FFuBR*=OF@*!d zcho%oR3gV=mKm$-ro%Fs{HY3#>JZY8$~Qy{dDP|Tvs|2B^8wlANlPr?wohU>0kn$a$)?k zC@>&8LSb1A5yb&g5o0{>nu%zT*hA)|6!bcAg^^Tzjl-$>%(f7Wq!mkc@KuUP$kDC@ z3{_!F3hN>7HXM7Kqg+^4R`#0V6NYZ0+~9-hwvz^=!ww@4S~CXanW>4@U3dL zGUr2AM|9KF9d0U*6pNHq%{{f%S;u#x>vq~;)|Jc78Z178!mn)JNmjKmA0muE2GLoP z`V(Tp$unGiq96DLhc&*84LJN$+;WP}@*(j9%~J>g$=ch|(I&v0k%ZmW$`<1!HR<@# z-d`7Nt@_bsJ(qj@IV=6iPHM)MD*hN>5#62n@Ec&M&Lou{9;;;PD4oH(*Ak5y1Y$Vw zRqBd4W8Bb@0$PVPbx(W-*$x2gs$!N`R?>&IVft;x>Z<;(ZlP*wYHE=x9n24shI%%C zY!S_W(v+-a)=WX|(68#kUs!`0DYs zuFL$IQ3}q3-1#_y^@nG723)?owE#?^$FueI_2P2y!|!0?(4Oyws#Y#8>glDGnkB`> zsCTBCNe=#`rI?w@#WP#-MJGsr?#`vEDOTX8Wnn3SU^ZbiR?WW5wMb+L5=O2QgAsE( zrvb1*l8)>?h~_}J6Ip|}v8ew(=;P^-VUQz_74KVa70wUmizbFdq)v-ka0_L-X&JFx z9h&k~=SERxx@iP~{bC{LzU@VfnC;*X1Qe#zY*Cbj3qGb!fo%c@1=+-~%%#S`)>M-m2*!h&Vmi@t@JPyhUe`JdH2L_t)L%Hm9Z*a zA7ujBMB=@3TR1WF68~hC=eUZ?Rg%VuB{?;@7En@@nK_wEicl}TW7+);us!12aLQVW zUXGf-7?O`YxbVMCIY)I{Xh5E95c6`m_;3s};D}LtimYYDCfAY0fl_4a{KsA9&PYHx zy?V)foh_j;+JZ<7m&2%PrhTcpN`AQ2Ig!;F=8wqD{dbn8Q=JNfbf-xvLN2?O%}BmF+oi;z?QDJT+ke*rR4v%p+cSBM#~ZZc|1P39 zSDMVl6z8*99WZ&nhX*&laPIcW1tnSHB1d|=wf(iCk}zw^E3b{=VKnLnW|S~{RG%<- zfyf%z9#*Oj`>EtHS!`Hfqzk?xhj1#-AMOS<7D|js)|_cfUi&g69(%vVvpec~V7?h< z#F`?TtK3hN#r{Sga}F7vq@@J5-CJ?EOrLN6!EY>-woJy*IQekVK>W^iTrwTYhkIpj z>Ng4@u;gkiMmauCUf|Er5o#GfchhtPrkWvl#lA*fz3R-~z%@$QyLeYYs$WqAao-Z) z;3;_+k~2Qzbn{4_21NNOD|`?f{ON_1>XyWhM92?=C!H!_<6DS6MLyzY!d421R^6`U zT>JrH4Kf3IwJo*oLo0{I#F!wxva+)8)Kp*ZdcM)4r>EDj-&F-y$zpPpQzFufqpDRR z9tD8pd~oo+z>o}HQ*mJZBdq+^C>fzAKOpNK4#Xg7E7QZSBSiaV6qlZdE;{%+y-RH+ zT3V)XQ?5vFPrAU{wN83-&PZX(^(cPQ5-;~k#e_H=Idj6|L(RQv>PRTtG+CfI%7cTK zKL;(J@7N;Pi*E$La$a6U(y>4AXWKV5JVN&FA(^tvJ+z)k{Pj?bA`ACcTy(5rl=p#M z?jYxO9%%??FTGSpdXr73tC2!r8R1=oDh|yi%hKEtgI<%<#2;AB8c{_>MZ>_0!?=8{ z$S{864t^5Ou7ruNjILrHw=g4S-yxP98AxA*p`yixYhC%0tAsK*^4Sw7s!yfx!>e{c zpSeL|y2QMpIF?5;2gYHf)&*(w@y~{bg})L+&u(302yy4=!{(oWPEbE!LwTp^C`%EY zR_AmA+JYBrC^KPchK!elQ;N1Kn;G52rVK%WY~qKX1rszX71f(0P*N>xVa&|+qR&k~ zs__2kmut`^zyNN4e_xU^c4&JIB#xQL@O&9m6z-<%%5fu%h{`y_K0?cM!NSeJnP3If zsw6iqF?UIXrMGN2Q8}a?GEHgyw)PhbgUZ&6uDIO61yJmd zHV@`JfZoH`l2@_99YZdPfcL z{z65b$JE2a1A22z$Z6BC{*w^K^5_%ZM&Aj~ujdcF#hA{WY)5^5%flh9K4|<~Az18d zThMS`ftYN(K^!Pj^_rZX60=y9h8!R0(X}v;IO^I<^Khff*`c-*HYsp~mTktZMjIC| z-(My75LeM+fV)}EG-O6X1y9CUK6fbWIw_U^p2TXOtM%RqMU{<25T1#?F#$&a9^Y+k z?*w&qIuN9qr-%aA_{8{bi#o4O89^{#(!u9zj!x^W#6yb9c2`t0y{0AbpEbG&`nj}ko-b?OYTEx2UMM@n!?GPd#h+>?Xu9K;js+*gcN#{;h zN4AEFXQ#;KDSj56+-K)AQ|uvH^pR{V9G)Hs9ceGc6v}sKj3~EYY}W~fEYSF27}y#{ z*WS+n?TdTO{pe(Fbhvlcv8H)YbW+i#X5doIJl4^8*x1;3c;0ZZ4w$gU4Xov;W&6PD zQ}`7gsClYG&)k1W)>afDpf@v2jEKx4K76haI^25o#*Q;>#Dul#ib59H4@zhnDMoNM zC`B<=qS|pvQgNq;jHz{oWdLS=G0V0hQG04OmoZutrRXJpQB!!W;9U6ISbvoraunAn z&9K(jfk|Zp7U4rp+f!TL^!4u$CI70Y3d|?UG$EoE{Poed072=!6*OfnDdSc2ygvgz z+i9GZMGbss)X&E+$R_b2+21nU_`x;{RbVg}=DrgX6MD@qU)@Q8jCthSmhe%t;XktI znYTw(OZ`CVf(h?tW|3Uf%hs}oEzm!! z^u`XCz)2@)NP1H64k3i$rTX3hRsaiE`}h0tCL4Anw|$_Y`E`=w#AHM1pAHv{NDKs& zN_*9F@oIP%Zl{5Be)cm7+cfalZ%7*33ruG66$nh3#S^67Oj~~5w^Tpgu13!dGONjx zvirr_JnE*F;2n#g>5+a_m10~t6>d52q*B_A$2Llg4R*|)FvKCAEDToCfIpF9l>-lQ zWWHMJo2$NX;f>y+8%+E#zBFsak@~3<3EK|o`IG2KbW1$P^%cpP)*2`3=zADTOJ+iw z(6VJ{CTn;znewf+5I?AR8z*f)B@)<5tF3VM%l%q;_kz6_YeqAT(G z?(*M@Bbfvlw|i=slBq^`1i zcmR|e10RshbIK1aOi4+Bg|Qhya7Gdu8XA;ILzRPHi+)G{jvB1H)2#%VjSy?XtEnp! zr%bmhQXS3obk?_2eWn@Ky#J;~;+gyN8ldH>9YL?sUre(roy*F`rcypf3sw32p*<2_ zU%h-TKR@5PcF`XRbq%k;U|I;b=G;cQ^YTM#yuD%v#~|9rZ|<_ zwWv7_*x*iZlR;*;s@m1#HvGpp`Fzx%Z`5&0h$p_$gZEF;z~NC4G8LodIb9U|I{UZz zJ6$iv1HtZOMJ=3dzM10SPaJ>H&7Bu5Io_R#sV{&kh@OgxX z`-(DRPdU?T%DHD}W2Tnxi6@kDgNpIdyN&d-QQqnzo=M+POWIcwkUZjGkFoL~Hfzg{ zwG$Q0SQ)Md7bzd02FxLog*jrJkUdf+NUyVWVPQ+vn~$WIKO=a*PLa(7iad(AIl>XHTBi6!yB z>rs=K@Vcs8r06`(6sA3>GCR{-$+9IDW;cuD(LU#G*Be*Xpjl9ze_8ofQS{3${ip|~ zcBs;gjE;6xl{W#oME#X;Lc;=G}dd)96ABSp0?xo zRHbRF+Jyxz&B*0yY*>H@qwR46qD@Ur2pO*hB@{B>jdF?4WZTb!7(g^{k}vwP?His* zu(JemLo?d{3dXY<-@y|jk*{N+M4O|!twMWlEZSu++`C~>vDzyADFOdmI?dm9p|<^_;~m~BNKr1G;eg-JvLB>D=_lQ%Mhweje?YzE`?(@=*-qTFqoMOGs=-4uUXe`#j$ru6X7`0h7-@ z|4&hy{nx7g+zKzW1HTHjHKY-$2sqKnhf|7LSsVc;IW}tztx?9%A1oSPJR3rnl9E0y>UHr}VKK z*0N&w(>E*BaKd_EL>AB(E?~8PlY@b`r-b^aD4#$%PnlNIA3;&>NTsCTv6)Ux2}wne z45(=!WF91!7V5TZsfopzahot+Bp>9&-yi_Zy>l8@-pT9TDza-&`mP~%ZnR$HmQIhj^Cn z3fmqJ!tW$|RTRJ~cr&@_J#tCtjHOzksv*xqF^P93hVTPSNF_(bWjJ$xC5b^#`t=Hl zcbG|~7S;ALg-1aueJqQ&1?j;oOhIpB$Pns;4?jCR7w2qdmZx0k`yQoaJXhVq#l^+S z%If=ff6JGPd!T`V!EeR(Iw!YnCielE$$h6v&E-bNU5Y6FDx)ss$KqU>Bs10&B0d+z zkM*z^GB4*In1RDNg^pHjD@&)qmt7sAO_y+R&CC4>#l||9qM2WiWdH~JN0v}On`zc_ z_?SS^iCJDad~Nnp^=_(l_NARL_B#L0tzbmdGN6EtdHG634mEJ4qpLFPQWazH(aP6W zLne6Vv7zG0ffSt_Q^-p9gdI`vUT;3aG!dl&MS~6}8C9_ra|)lDTXbMrIK8snYL3#q z&WN0#aWT7KFviZJO5vThw{i-mm2$EolDE9GGP{5x1l{0{DvCv_q>TUbXP39$T#CaR%U~pX%a@V`o|4qocY8>)DeF2X^$FFXsw5zJ3@%wc zO&UK)H_s5h?~jry`X*8qPAdNZv%gN6y-i7{crUO2RAYM$&ahu{`RK2e9B<3HSq?u|mswDZUov}sf%!bh{SfAvyU)d|z#s^MgS z+Q8@IJKiI7c&Z^a4_Z}K!*7zP#ObHx&`VRRD-26d6#g*cO z=vA;?fY9$u_A_(5@$OG9nK1XZ5#==xpm%w7sbZJz3)>n)fRawk!?D>*fG@AS=M1y z>IX+hfstG1Za@>0SKrd5a}g|0-TPgP9w;a0=7M8VnA~$&MXjdEm%<8`4?xdIMUg+L zT!5Hk`Tb`-jDk3S%9XMdNPefr4|xM8-;-yKm1|ahhhaCYv=meDj`Wc(Z3L#*!9*xY zN@WII2?+`MgizUj6IOh~RMO*e!G^iE=WAHF32Wixt z1Sh3_R z#t`u&?@7Jayimn8(>LiIMhb&YgZD>`!{j%WAQuO0V;82x)9!9tCQgCBv~+53Xc(s$ak91k@Pd561vuBp)mGnZLg5+V(@1d`AcbS zQtGLrNgdJa6y;i+QHU^g#Wa+4VBL-w{8`_ZBcz8HQf8YW~!Gbf1 zYx`(4pek?(Nwtz$<(|xIjI|^DUHq`W)o#g6wXrt86;eMZku#xMP&7NeZx~yN;qVqa z&_wZRdPi2U@{~&FU4N;%9JN#ocUbgS00$o*9}f?VmFv?bbmFo(RxSBxd$a$Qr?PZ< zl+2&1xsQ^Tlv>p-6^-FYfd3t_INomlfnrgC4=Yz|#^mP*(_*h^#Q4N06vZy%BAe(iBVk$gU9%6P56}z- zFH^xxq4hxQ2Pkxc^^Y#20_>8N1zr~$1ZlW9Ic))WDiAN-&kASGZHZZci}mdT!He8fBpLbUDiRYko*yWnfaG8)HCTi7umvpAlzTMBipbo?7utVIgfrSB4PE zF}DsA(3ToO%pZIqpHO#O2sYJ42*#bQ_I1(3+`HFd%Z7=9b&dC8p&t=$j$waZcN4vT?w5ox#_oc!B|=Ex;7Y<{34 z5phJT6cqUi!(;GVMpybXMGB4=ZK1qG?EEEyKA=@aEQer}Sal!W*i0O-VMW`T?#1Y& zBQcZ~Wr%2|MCtMZOUjtg-~XaScz^3l;ag$^Qt2js7x=K_nI&WCo1G+-WX;-3zwhMX z=7!g#{D%*gFofl}m~g|6=&!D>gulXvCGK^g;b^Mbiei3Y@ctGI&}Q+ImQ5~YnEb=o z#?buw5A(sw=-^>AmNDbd-S27gSE*H%rmwuq@@`G%VVXk+fSw@YyS0g`vZBz}I|hr( zR|@cgNCj5Eyx|IPI-`1X!#N$$GCQWTDN6M^0g}^3L3+fh3gl*CVH0e%=Kc>V@k5O( zIP81Ln=X9mNZJ{d%&ij^!=t1AqV)?luzeTi+k4Cbo+w{JOe3Qe+oXzDYT}M{C>*FrFPPDhVJ~tnBbFQa_t%MXpM|vK!wpC=~l1X?T3qmMvstE48o0 zJl=r*0-twOWc5?tg)`Z*mD4))Yq=cVwCZ=srX8g+EmM9=P`HW+uUHLs?1+@n-SVwz z7;>HT+K{k4hk$?pFE1U}29H9<*oQ0`d*1Y)Uyu_OX&JJ>e(-u^5nt5&+R7Vb8Aa#Y zDP=j0B-R^j~Y{15azrgE!h%0(kfO_-(M@Esj7GG|tizR6X z0_?~QL*UR&d#UlY-N8I| zkxC}9WlxNW;M1p1goK3n`1i;5J~CsO#>U2<>kdv%Mz;Zz@e^|sXnD(m&?CpI2?-cz zz?Ms7R1_u#h9K;081o%W!}Qu8=d2cI?d$X>(^6^w_O2F?@qna=lIc!mn&Yg{E-(kOyXw(33DuYzLOYVx02~?i(x{G~W7pDVfJM+C=;<3G0 zRPt)BLrqEV^AeU5xDOlwq@Yi~snaes9ZD>P=}8U_XJF__Gwcs`8R=Kk>oz!$RV)?V zbZew{*I?R>WxS!wAMg-;2(+~FQLu6uU9MfHDX3I7RXKX~nn^g7kb`4S{ylYb?iPBP zUs02ya^S4Se8W2_0jmn~ZJBtoZ-`8m=3$BLe(Q4fe4-!=>QDeBZLQ;Tk^W-1vbs<6 z$_@h_rV??mlI8HS-XLy)6kQG%nJ_G#g-Pr%&MN%p_@BbR5+art?-i4IwfZ#?~4R-q9n z)T4kuX{9YYA58tm`Em#J_{g$@gu{+DG=+b!%x8@)9%hwo-qEi2bhSIJz?=%QM1kl|1%3LQB}PV z=)C~bt_xM)4vUb=_WZOzJB3AHtE;PCHw*cSpJ8(SXP&?!jCWS1toYG(u=wnFsUGHb z&k0G*V6b4Ou~WPG;9L@KyU~Q+D+IeU)<91D0Zi@C@;=H)_4*~5oOiWB=Wn}~*m;a0hbsX)7w;`ekRu7$A9dq$0oh2|9_3bz8 zBp&Q4uwkl_1q)94{Qqt3V)EO?{x@F~x;tcgyR^Ys%&D!^! z$QatrV#*mDoO-L3_%YoP?$uV+K?db5f2QZJR2)~wYrnS&T(!N-x@E;?zT5hECyj^3 zSqO4uK=zdIW7Q;-Lg~xvn(wy~f+H|-Han8HXvQicA_8{eq)X^&Ut#l{n~oip=$U@$ z#4Xn6q@T;hP;t}_Z4l5Cn--t2`dvc@QIrYTPC?1VR(2^5VfoQK zF(NP*j!@BX6O}XE@->2KKm)Z*AqJmNzy7ohw$VubjNe87jyg&zOg zP#$xM{fnN{ABD1|DYbMx!pC=8d)e99ZmT-5(h&`fB<=meCfcD=bz2@3``4IZ*X;>d z7>+>WDQqgY_zja%<{6Q6(CMUNY|AKJ9te*eUlw|0|$bIwdi<@gPLmqVII>DxOC3oZ1lgSYtCZw?2x zwzh6yi^z6~(}#QpR{JwEgY;HiGUhwc9*9M#Isi>|ANf1ofE%)|gf1bD2^iB>C5!ZU z7-$+oNAn&d?Od{$Rm;(gA=&1wO#k|Ixc7H#0~h2tdQO3CDdR)o4o_b%)SOE%c5)dJ z1&CN|OFRwK- zq&G*f6CW1ruo@g#y+;3Emn1uZUW?n0QuQpY@h^Tt0 zb}jH8Fm93{oeM)aMOX3JMAxm{wP5 zERnVT%~$$NED`>guvw!>HTgsqykSyUc9HujX0}khcpHGf_-BN^ER@dX_xpFAOWBg| zsLxV4tf^^e=1O%?zR^)``j)}6F|d@Cq9`psI``W;h;x6vnj~4Vy^KnLYD$CRn=BqV z2fguE?C)Ib?$xUfL`zd+A`=usps3dGa;E(`j+HmBD=Z79iS7^@IIL$s0s6_Z?p9za z^%)HV0e=1#r~OG$a=%n_HHA@z_ghmMjqi7!Ma;QoHznyf-=&XBJFH1hBT^FYoc9!w zN+Nem?`dOrt3`e=EKXqvQ!60LCL>BZX9&*iU>=!3hzg~RzDv}l(}_-*ONN#AYEfDN zI>K#0j)r3)YMw_sYcu42LHVQ{D5wTG`sL=;T7}|%LJSGgFi3-$?2Z~XTd(84t3Sc{8vw}Ym>j_x=qi-R>~h3#nSd8d|}Y?2;Z-m$4XC? zN3KIVFkQFKl&gJTQX?_4+bB@Fp!P$8JJHyt#Kw-|G^d6*2|)@UyXr%bs<#|us>9dH+|HE)nPGb zD{G8qqA#&2OUT1;yonQ3r0TD1`y)G}AE9>!-0J|~EvVtvtMoFnVtvd~a|7G0S=CJ* zTN3vXl*l0cIW?4V^u9{4*ix7idE`z^QTfu;sc(F&7~z-wz5VTYKErR5%tcAnGMgev z>BKkH-~EMSZRGWp)rs#C86YtoZ`!Cor5OH5gQc7`40RJEDG4Hw6_r#uGNp52`CFKZ z#ekcZk^(#BswwpPhGN0S#n3PdRx|W!2ev|&4~Mod7Hh3PGH9-W($dp|?22G@7Rl!@ zpW@|hvWDf6n_ZsNEK2&@+lBew{^FcbV^*X~kZ#mP4kK@XuF>`bh)xP?x}wJf$CG=L z>Q!@1z@KODBZj?>YKQL&gwRwgk(+D+6`tY0_JOvt~X>t81D^zGS6XHNjPicvmm*Ur(!0#PsXAt~f8**27L1*l?!FQWr+T^^jJC!Hpdo z#{erEJan(b-Z&OvAkq;wE=;jA#Hki&`Ew4;x^S1bYf082VqT%CZ4%ZV%+`wx8HZpC z&~K?G{Pwl?ugQMzJnHQ1Oys^5LqtThRA=kC_d6KoGe2{1igO&bi?b@m^|mX<1>WwX zJ$^ZIWPkq_g$nPs3kug3&|HEow>+Iqw5fH5${K>JqR&rtAT5YMusd;y15K5*s#Zfn zLfRAXBd4~hk+43uxMU@n6OOZIeY{BT-Xs5nD<_hz$^XbaKzwl;z0vjc+5cn98myL( zh=AbW^fZ`N_^u09O9{g=cJ{zbn2IyEu<&Np2&}i1B>a|AlBf`?oki-Yaf^;@*FPS2 z1HvkYjm9&bU8$ZBE2@a{n}HdmGI7-W#X_+i2rdXnE5{Bi|HTwt0_dQ#Pn0yYp|;kO zK=E0F`_vyhs6XKMqi5RTbF@jzo6R4~8L)&N6%y(n1e6wEIdBx#>kpcR1OmJk_z6sM z8ctYDk{Oq*3d6h?d|JxJznHs zWo0cdpf7PcfdTiy|DowDqq6L}u1$A$hop3OgLHREH%NCkA`;Ra(xG&Bceg0r-6{C( z`}xMpPlw|g=ymRMtu@y%=RO8&X*)MMqVd@`0@=_P&A)S^1H(zrIEu&lsJH#7;Sr`8 zrSaa0nwTli@&QS|LRZg@vS#B7JK_^BnUU3Z$(j}r+L1VHg&a|<9%60;Kf_)pA7i7i zE{l{`S37?EBtw5Ad@T-t4ap>L-R@>mdG`nVz^nDUwcC5X;(~S+c}4h9pdd4(FyJ7m zcEQOgcuQ7vz;U9=ib+gM>5|mE%l_^;n=c7&~d=yq14eCV-Dx^VU*@)Y|<-3Z*ZJ79y6qdXs{X*wkT z$!^G%PXx8XLTjI?9N~maFHny3`HZ9~;5Bhg?Tg%v#KF=25-n@Kt6i1Zhfhv)9bwq7bEoi?bOrw8^0v@ zI(64NRpHM!ng_6Rf4V3nJ)jZEOQAW7bL>P8nng7io9ce{F7N*yHYitrFE=!b^sS~X zmS3`5PyWEGBN3ibnrTc{_R~YZkz!1uuA3#dMQQ4%6_v2noX2fHa?I*=Mo-nNh_Jed z?0J7ioAt!!IMG+!usK~#CNV?~K4|FGC<#syL=$0%aJ1h+2sk7zxqW*dtOQq9!_=rX zL&fcd#NWV}OL`s^fuA8?oR5v#K`atrh*i4`bDX=m;C@;=oGM?u=GgveXDBv8qM*CG z+mHo6W-vM$(f=Rle1HCAvADFfjd!q}=Atqc#o51Dvf*MgrC6rn$z8k_{+OGL=j&|Fg&>QLDEb=c?Io^7u>@)eqjwD2jk|Z-$ZDfZ2392`# zUyU_b4jw7U!{H*d3py)@R4x`)vTdJWJO#K}4;7r@l8Nj}J&yvYpcP8?6MUV02*M!X z(ptoXLoyADiHx*uWvzwPpG;j)Q_yOiqL7xHZLv<=4g@L6?$I92=sQd;fgiurhp{lZ4z-eVYsgWhwo5RzoP z$nFkZL(JoT9?YQU$dEoE4O*6)n%iX!9Tz9HrPZTRV% zKO&aiN@XsT|3_8-FCX(Bni=F#G0M--)$lIMR=qq3tN)|sJpm{Nh_UMG>cT>3i;Hwb zX&L0**OR;F(^DqyQ-HdyIxL;>EICh!f7WG4*}n1ysxNI)2u0JXLmcS38*=_20H<&8u=0GuUEnBJ8#eRjQtT zM5~WT*q2$~E!(k+b*D#&B;KP76r_(L7|}Jo8=T;26Mn}FQ-v{5E{j_L6|*Wa%hi5b zkJyZ#4FgsU`-b5mrtnEPRf&<7s1kTBQDXYyZSkK3E(45jzvGhvZZ?bO(=$*uUIwsL zRB4DVwId`#7*qm2SZE6F)Q2EU;IoC% zNJUnqZ&`ncaAeWp_=OVU!DqRfoIJwLz?`sxe46OMiZ;?>@j&?(_Yv=6rPjPl&uCK$ zZp{#*Idmd}M=^PrgnRG(4<~3lU&3j&+2RGpCnk=Mev|poRUs822o{W5?3gcgRjD&N zMOYua3nNQstD>1r5LPG5%nSoQFpLa0rbXM9JXZmc4_nu0T9XS_8njI} z&!+(kU*qh&E1FbtZXAjeH!F~Pvj<|^UdwGEY{Q}ceQdPT;>b7!P2BM@Xuvl~P;o;O zAS1-kL>4a3jH=B=-|6B}Oe0;Xa}iDMxdQJp_>q*9jFvJ3rzk@aZXLX-;$ve& zT!TQ51xyaLx+tGHaqOtEqDMzZLDR&4P*PITtm7xcgfj!E_N=u3c`)35KsOYB z9ZA_yHL0)7Hh2Lcp8R-jnyYwjK5Rt-k5YG`>a z5RK)KFXBIv?S4c>*{oq;O9-?4GqZ@&-8NWJSwFE`_G$yYw|9Ki(~R(#S=iqCb$5TF z8+PRVhQ_6mX=_@UHU~)7;CQN*{yUKtt_?LuN2Bn?!nwRnTme^|f^ftlm+wuh)H#n- z%v%a}1lg0zwQnpF6N#&?fCSI3y6nX-7+dIRH>tX1`%7sh+TKdQ&0g-e>Mdj6<*T zpOi7*1zYF(SpCrU1I5F!>uGr=*H#Hxrg~Dd(S2uM}-cuB!~;!ZDF*WeIH%z2kNf z!M3|gAaFXldZRunUpX)%=rT3AAF12GM{T>eB&jmv$4WD% zi~&vI@{%o?BotC8!4S-TJ-SLNDqimHQiZc%nFx!FM~#I@(Uds4J1{T+1Tw7X0iZem z!#B9yE@R8f%mi(kb9$NuP>n&f(a71>EW%Bn5uR3q{G} zmI-r$igC~W zwys-|7;_gOnSwN=o51wFQEjB8d!!k_cwzPPA|i&z41+{6a|KgUiXv}0c)^eQ z3!_AM^3pp`LsLBSG5F^ zoardTbKFTo1;RPol%*nK%~UQ|(J*e7lCZx(jfDIpzVMm`Lk4^6lm^=#RRKXU%_`v- zW_{_r0}q&fr*Z^Aw$1K7yO;vL-R~!Gl@3#f5%!EqiA2ewIr3Uk=|+ zliE~$N)}L`MmUUHjdii94GwEC5b$95XSpeVZ(M3d}enx7>J}!{Ov+^ z;&O*J-Y1zsXn9g(*cm{?BA{7jlgTpJqAD1~sH<-{5o*-R(Nj*C#=Yv4%wg%KUoR(I zmo!X@)59A3$VOdlLZ9@;GyiL-k0hPoNgb zAs&n2XLfbK59j2-z9zf<1l<}p3z+ip{Xg?yM@to}%TZ&s0=MBfXyzQ(JNQ%N!5}Q& zdwqCl12(Lci@xBUn(YS61Pg-O(`7wir!u6{SBjiXLbkAG`gtuR-sa&h*M{!fo}l$} zsMB4?@x1Yb-ZV`FuJVd?-%)5JtDOcew^#2jqVs()*>2B|nJ1t@Tt5k^me#ey?7h8T z#QI#oejef(0$vO^lapVhML{J+DOHu&^UNBDkVCQZXqgXdfgn?D)Q^zPuyKbKfHmpW zT{~qfI2WXRl$X+)w@m3V(~LMqE^FdbHHfLB`mVxoxU-qvz4~MNz+SmrGe20O(ZgYW z$!=<~{{d?Ckoi)~lJe`s1gD=BcSi~O=hp5QGNqnO7;~9>chwO|c!)D*zEY~L3B`)5 zGMt9(M2VA%O*dO(N-!g~n^ zkenG+7f53U*B^&?CE_X#S%9A2k1llC172-nlVB6Dbyuujp2LA>qk?z=clT#=6Ro@W zSkwKTP7D*2d|)Z}e6k&Flk=7=Fs|wj$ao2)YFGwPgOHySqlY%opZt5S{-@tygPCAs z_bsR5wV;(Z#iOq_WR|~h-G9P6D{y^|`oleo#VpWBbnC5@YIXmvKXj!{AAr|c{=;e_ zjRIIzb7Y`sna;oCJJzPHUXt-?Ue%RPeB5#fZ?JR;3}YxqH#4o6|64;)I~ZpGY5&1v zGOZ8QSRwBcRg+X<6-T4K^;()eqoR6?`-NrVcTxamt4)0vI~t`$2&7`y@S9F?S$e~U zjtG^4l$J5SRWGd`gDortdaVczDA8a^w^nOD4DeWgt7(laokZ>20`$zGX9# z#}TqSjt7|_zFrxlf^Yd++w9Wr?$Sv7HLwIr{2usw24nD9jk`$9AX*fheu;Ca3itNm z2Wp7u>GAQH1xJFnX>XZtLTVLE3|ztt5c=xt>u)^QlxdSL2W#bFtI1i&;^+YuAq0$h zz)LhVOdceZBG3G>4d)k44`sqR%l}`^!mM;%JEWi{ZyROO-CmK_ZR(vp>~a<)n;T7L zk6d%Lz0)wK-9T_EP5COc_(FmmP|&Tfb0YMSC_v!-M(@O#?K;z1T+LCn_Bf}xh!%Hw z8(&0ya@Cm1r-NO$GE1(8_+&LI$OEjE?7p@>_&(P|s$EiZW0jiz_MI zXtg_Q%UEz78@aNP+OMO0-0ryxxM5Nl%+Jv{tmsWbF3{FQ=?y9ukB$7!?(UnrNp%?v zpTGvg^Q>`sZhH@c0xu+RG{GBG!9}~2Hmu+kK#QBA6nSE)@-lg>j~dIBI`1>nOcv-Z zD-Sh6Cv2RapZ{Dw0k5ND?I~p`o7Wx!6@ID(zVuOQJ>Lvwk?VzC{j@q%eE|bOQ`co1 zE@hFYT_BBeaJbGZ@&55#`!v-GG9$s$P^ckz0>gkPv--Iwjm#P*Y2FuUzN(8M$Ak`J zH8aQYn>xv^eFcpd`7hJpxwPABC|bd)^_k|unzfM*^TW&3MREt}kv?8JhIVKoQ|>ZV zrJx+`19~d#XB@T=@nN#Pjxx>EpF`J6<&8rjKcwzrwaKN#xC^h*7z$3Q?5^hN=;**o z0;KH;h@PO(gB|3;+8Wrmmkq2f4+Oj7RV?acb$0Y2GUwqaE2)fmXesfRS*P--WNxv( zYh^QTX3V>nXv#HVwzu6^#7!OB%((icsn2Mvn6=8Uc61^2K-RiA7AJW;sS|Jr)%Nk; zqpyws&V5JdOuKxD+zYbgbK12cc`NN7kBs_)YOCLA+z+jq0-51O%)#d~>p;37p_UAdSH z{C4~&{@9{k-e5VN3aX!0rM8EsC$NNPX-l$f!zK-u)2CumYyJX8f2Wgw`#4{I-DnrE=k{_RVa~rPxf<+ee z_iE#1{h{WW3o9BVyS?lx|If)T*&1bN3hima6xVx%N<~&76EdHX$HB;!9oj0t?9Rqq zvKKhT&sShszp9}k%$=j`v|6{fWZ=~K@9hQf(F+SWWV@jH$r5WCJE!Cn34NfL$-a4C zh7)#tv?)a{AP2{<#yRfFbd6ekkRy-%Le&2>w=ANOBDOD{QX;s8pzKApXcvyV_q6iU z`Egu1zDnf7{*bMRyzs&JT@oHPyN-v}?nNl7vF;K4lE?^l`&#`h!JO`d?s6$gaqAV2 zpT_2U**~Wl@JROUEUo;S~(4mzp=c4YTNPS)Zg65~CNcG`d$?=&fMd-JHlotLfRxe;vyc_Fo+nr` z3EBH%@?H3Pgz9`X_`ipDk*BF^FlUOcMB7@1BHY|7rMw}#J0iP++&z%-U7nqlvQ~Je zXG;GfZvd1<_Jz%9q4rU`8oNVJp0XVpHLG;-72h9c@zm*LLcIAg$NeIvn65Q;+QPXh z{ynF-WQe!r_~sm^ks z_;aj5{Y3A-O4+xJB!$Z%OT~4>Q8=Y5{pE?l#ea^Vgx5-eCn3(H3=Gi0no#jvjf*aP z3N;Vwe%*IJoL=YBx?m!;fz4ronImo7!`;0`BTA)O`6Ok5ACa`A2mVWBK@j*;_frsk zx$1Baj*dtBi#`ey~?#~i|$3JhKc-m)Dkc5 zd3BaK?}J2zIm->Ft2i+!&wAO9;G33aw!N6-Vzw9(ZNCU($d0+I6NOe7JPs2?6jap& zSPj4Fh<@Ya4l!Y4wkmNm*yJDHy)AVBFP2zG`LUYg2DI4jZXh2KvBU@Z0%(wW?91Tx z;bB?zlL9psWC@w?4dq}o&rR}j0uJ*4OR}_7KY}L({BdkWaZQW*J)GIsXrbHhpeePXqEgkJGw8 zsF&bLn9Sns_cl2uTcwVo`KyP*T&#P$sz!zDnH`pCXdE}Mqow53$aSYtf0Brx@lnIp zURio~i*PzE#loe$BH5Z9mzlU=C|{Y;FIk+)ZPWGbC)FVwK^bwvj#9w8V>QFb#;!SH z{Q@d-mg4OEGl3l%TL##8_3PZ4wLxvG##PL78HaZ950SqVGi>J%^&#^(`1xA{Uhcu0 z{z>H{P0}dX0Dw_3^Z|9o7R8L+ zDpLFQ*Ho?0i& z!h8Ib$_!-Ri5I3|%Q%vMBoYV?^*e$vTfzma?=zjXN;ye+RIN+#8r~s_G51@1ESONH zB$ZRZE(-iIrl%V&mh!0RH;yLw_-t0&;<`5m#3omU0}|PvAVWnYFRF$aSci&`Hjv%b zDGq?Cb@Kw{U+~vuAh+Kdgh|j4NQgyQa%2D$RUnd*DI^4*iaAC8?%|<7Yi9>S9cAhQ zl*1h5u!TzSlvr2*OV+ENUz0Sb?p&n_V|2H7IdxE_+x+-BVr5%@Q^PCX=F?oW=h0@G zFF`a7m>ty1VQ>k{H7lyCS+gc9@Q(x+YNcrY7M7MC6a()&z$sLMo;CQUd%Oo{3mMj+ zYxxW!^T~S`78Zm~aS^<)VvIXH&p@Plo!h|_z|-+YtaQHyFC?j;F6thB@58#gtOGo& zyXSwe5A1NAIW$93;;zNjr^;jh^4Z{!pJT9Pp9}+RAzL-(u)L)Eo}qsCOt|Ww7&hi< z_TW==aLfdi$?5A!Pc@M&qKw0$D)rrb#Jit)-)$x|D=`oiQIB}-`Xs-|X}2g}%{ zd+t&OAw(iIt-^}TVuX>0K8#7nsuR*haL&<%u)x|SVc&&tgqQ|PCzB$we=AQVnq3_} zPj{dRu^hA+N7x^jM%vQ)AEn&;{X-0ZA)%S$_s|K=i}&@8($(6B;rLE!T6&iuGhVgF zdbEOQjCJf&A{}Ki2oCjjsrL7Af?!yrT?ZPfjBrIN*Q9zplvAl@xDxI5M&&PeHO<1r z8Ls`?^rej|BW)5{EZozJr1YAyV3}>SF<5kxNoWizzH z0jn<1Ai+cKU<*i7AeZ`M%otoAfiCl#Y!8j;yLzK)plL|LAWz}O3th{C*%KJxxReg7*pl1m?_LD{5jsSN0Wi8J6sz2#tl8P74qY>iqO@7yMVBuU^~D> zKo5f!s8CJv%m8(08^vvZqxbXCP9gx!(($KjpBSyo9oJQ7B7@&5a{7;yctoUzYfY-b z9u!Md4U12i6E1+`1JF=w2J4cV;A+Gf|Kg)$PRDWLJEbe=$(QVXY;l!SWqSyfSP2T_ z5D&S9>mgg=eXUMnWSa7`7;HQV2WV|Z?OoH{Xl~u5m@fVpr}VmypQa84zt3AsEwWs* z?Vo&}SlFbWN~BYlH45?9f1aB08|=exwpP+^7i7dFm)piVMLRN86oz2^*w&y*uUWZh z!O`lnGh|k)Tdt{!M+VoRsZy-&+TGJDr_!BH8gT~wD8j&Bu&R$EpmyThgvMEnYj4VQ z*H;z!nMh|4A>DvP#C{jwf1Gr$W|s&d?{hNErw=l?lNCCe-qH70Ka?vu?CWassZrz)Cg98h*+MppgP{&ekno1BDQMAyg*c&=IMAT0??3UAlJQmY~bzi=p+%rF*k z$_lqV4oT+c=5(5FwoElS_z2zP9252q!$EK-n^wI`dH;mKs-;-UkzNradLnsYUS|Va zEA&M$=&De~7ENgde9vzjIrX`iOnP-i-QDCw?k)K~>{*TuLFmgfBZNg9^2(fR_fNXz zR;0%q^quQD`#&-0xl`oT$tMr~zGC<*HT#EnQS7IsRWv~*kLPn)3^*0lNgVgRE9V-G zc|zF<*!JaCA>YKXtfF_qQPLbqZdFX3!C}&Vk}G7F->ub(87oO=q=|uE?DMA+2!=nk z^k3up@I%|6#-tYzBB+vFNuxbkVYi4l#6Z7gX*6V+o|?M9z5Nd^l^{xskS=5w5kZTP z*@TE;NzF$NVKu5;1e!0{K>;qcD>pY6IMrB;I$El$(HXVGTSWx~kV3${BB0=ak2}r) zf3*o*<^a6!^YfhC+*(X{%hkr+&Rc!p#)y}*=H`vVi}yE=&Uy@l<a#3n%r_x1EZlofBT^jE|cdy-bL*;H~EjvTs{ z>xY!#?ueYf-+aR>BS7EH+*IER-?!HjTh`O!87#vn_2?foC{k9bcvj0YEvV8-ktrys zjxW7$#jU{guUJb{S)tD>Ct`cL-c=OcX57}uYj;90MHc$XT*H|oq(1kkuCDL!ZvIlu zqgr0r<{`3 zrCrcqXC$ozi|auF(Q>S|PHvLOeG?@#L0O5Qj0*{kGZnXVk*2~fk=^*V&%zBc#l6HB zNryl$kx9$L{hOD5kZ;Bpjhq61l=f3>tOUxa4+ai9{i)xoyc3M*{<1dWyZ4H8BwAaS zsxlFL%L&yh8MgKK-8BbkY)qkrvvZ_*QoY%)gJDbuQN2Yfx$ow~>%3J#71ot?({v~ZCO1R2ZH(di(j{&X zexXshs4I4O&*j$RCNSA=+5yvmmg2GV;TZ<9EUOTg?Nnq$F)^8UdmQMK1*&DsCm>)T zYqAeNL|>xCgpG610GM|mt?e!w`uLEBeFj0^A-5io49szpt&SYb?ej zO1S$7sY`u6aw?ePMU}4)RZx{9-$y2h8aLW40tUdK4E^C7vP1NLiv9-2^BPD}13NS^ zrS~6Ki^YV+bot^*MLveElA-jc9qBE=O#tpymq}Sg#oYS#DHH8=H{4<^0M$pxbmDSxr^yi$Cl0%8#YKCpA`qW)`D?10x-hiRDMh*Y(Iw-8p0 zqgB4EnSaLhg45`hb$K$>LpNgk>hTLMBQP2A0JIgzU5_OR zu)Y1kLjIvLl+p}m3yFZC2g?mbTH6BD8y2lmUxYiGMx0{V;07Q9+N7k*7n{(OZsWAR zd#Zq=s1q;ej|^CNB6|{PiM{j9LDIC9s$4=B*w(_F8dW&fU}3F;PWFeVaIRgZq*Bp3 z!6w3}AEIy%vIv3i%I)GzxsWq9sMs%Y;o145rF57*$SOh@=NoL=NRaG;u<~2>m)b8` z*r_i}5u+K zfsIAo&E$ia5R@>yf`BE8P=h)UxuvVlrCTH`KUscoo>|$J^(tKD98|fye!#P%%TazC zMv=Iv)qL(ewQgTcc`%iPjEsln81m0O7#wD(zBs-d$LiT^{vbb+|D%>XU2{b&5BN{#dKWVssS`;1UhhCX!*W_7XD zi4O}AjA5Dq_iSVJwh1(>Zzz2GLMe}B6CShg?En5yJX^`H403TcR8Lwu~IZyNn|V#LvP|YWEF4(*$7M^_%jqw@6yG$n=f5%Zf-z3M-CJ} z1=h~+6>$g(upldiT6IYpg?Ynu{vFn?-KgK_a0ODCj@-$Fydmfd^?z`XA2uVJWbCLb zR~blFWOKl6OKTQ>gp5cKci$Q?A+Yj%x&aOOf}UhN;F zp8$T#AM_^lb*1%@Q>3+;8R_t2*EC`+e+X_1Bb!BXig^ALh@se+$N(7=kcY^Hw}#xO zF)6XJs2BYV)y?w}OXKa{kEZXduR}2(JG!Cpn@Hl$(G!v7Yi)05bj!$@Y;cPVuw%dG zz>u}CekX|wmiVATzdR}YSm2;d_SaDJ6B-v{*rH_iJE0NPggg$P<7{c_BlrTdjf2lV zgvu<-ztLsgo(C}WZa9OXyd*@0>t|CR34Km#G1}y(LKw5l>-Ko2<7&dTx%YogO1`zy ziSn^A!v0m%WpeGCGA6Nevw=cCtl8+-&7p#7H9*cn634yD-FQ9s`cDJ8dwG?KC!@?V z6UZSWB{lW7M69qXdAn5*h?}XQo?q~W3v7uTX{^UuLPKo-nt`v$fIDOLt+e;_Yk$9_ z(TB6_wF>(r6_R>Pdd0wzMQTw!pw4OHdb7JZ^gm^|-)+rPmodg$#I7?saHMJz&LHaY zq>XNpSB6si?T7Dkr0^|E@Ue2d-DL`PV@C+f9YQ1)UX2waGS3xL)ve`=HJQtj8)!uA zA2zulP-+&r!7?El$Cc0pZn<_kJYFbax%ESsbLfwWx8xxy{7hFF$hU}VXSSD+9i6Bx zaKqE-%S54r2i|}$L7l-wfoiD8bOjh3rQB7&g(}k3iQdRp1ZP_7XIb*YLwvch=r?pX=Ikosdvv ziaEDc`TFkl_cE)LCo4N01$?p_+qW6~-L)&{&uffVK?xc3M&^+k+aiQ*N2STBsj0L{ zqhJbKQJHx*U8YY129}e@$H(=~|E_D8KiWi%>fbs)cLY_edCe-`GG+Al@85HCSa17> zhX_x>3JMDJ2bX_PW1mM=0u$ArmxErHMgQH1cKbhZ)VZLcp^159DwkSe83WTRf>HJI zQ)b-o4p_Mi4h~w?BN8oNUtf3nJ&0gKFs7NF7C)}%(he`sFR3Fk_BP|G7vmOveR?(r zt?Z)RM{sY=R(}*cJbVoiB&j1Cfp_Nf+#E=}sdM)bl7|9tCkebq+06-ooD{^E`2BsP0)2c~q_oi*m7rePyTU8(Rl>&Ht*$g*$n zd@mgtJPdb0CS!`ySAPG{*%_DP+;15^n`7YMQ<3V%j0@FqmDeA^E3?46A(Lu?!*-E) zLuIbu8ssRxxMhlC#XXdnotG!W23tYjL+&gv>=`q;o*nO9#=<`{$HQr7UN|TfsM2cO zP(3=_b0elehw~f{v*dlXZ^G8oGbW#x_ji}B3^y?BQKzPv&3R`Lk#5O^DVtY1g5dk) zpZlFFZ!V%<=G>$(6NvZ$%YQ3%YdKX3iD#c4a_KFE)fC`9{QmGV%I|-^8m@2-X-e!f zF^es^d&N7>-;O=Opm3h>8+znNjFjZAbXcAIODW$je)!7IX|+3c=edqiN&LAGw>X75 zq5Z!X7!HXw>FQByF+{?_CW!-?-%EF3Qz?8~f4#0E9)Z0#*nmr<6FEq~9w zO{+wI#Q-{mt6Oz~!4_#Ia)XZbP|wp^7^4_8o?9ksH%EODyTzXOo5a}K=C-{`_ z7V(`DIwvf+V@@f7_6XBr`_M&t_4c)jU6X$|d))h#ms|Ll#WVX-iQG*peUYX_M~I-F ztXF~JOn_)|31K<(A_lH+9Tf@|=7~E?NwrK>f{GgrsS9v3j?L{gH8qWm9{&D@)yo%u z+Ls-hK}eN&7}P70E?w8->@24GtXQQeKmY2=ikL0DUlmx+HaACMUxNfa&SN(U_*0DRtDzb2NbaZjKs)wqn%Gip!RLnZ&%#h))CNvJ; z!^<@D`&Wadq%z?Wbny^)0nXBU8VhM8GgzyH1HAp2RYTQ}pU0vcZ-aTBSRP{de$m}x zh4pT3ZbFFdbE4^Q5sGQ(i&fw+TdPn_vj@x_B`jp0*zsXpYHyQujva}`U?yQCBzC=% zl0Y8e7^DnSXT6?SO@ped_MYDeeL#QMbXIjjSNq9ttp}JH zwBGZ%>|7CiSMKVqSY&{+ktXHM3~L!A+)Xyb@@y#}9zkPOuQ}7@v4M?F2@agF7cAj+ zO;@SAaA>L9)1)NJRaT+?ONlv(vO&m8q@K!jf}-bi9=(WV#j5<7%m-7T zD8V@0_di4OJsqN5=LJ1Ap9TE7H$ZwW|b>f~-av6Lt&ML_f$XCt~u$%9abG>&W-Jn{mBc;^> zg|F@#J23s0_p>u}yo(j>hT+n3$A*nI-|+D8CT1!&E?AkEf~_KSkAb8?NrN#Y zc;`#HGdF9qaOTNu;B0G)*cv_$daxXcZ#+PTYik4X1_+C$&1(^IOD1eB9w*xJM>$^W zPxGR$8tKj;5W=?;h$YTYE&eT|E5f zBQMl)iOX;@EghB=a^fWEQ-O_hr(`ZR!M#xjm(5)cZ#nbv@;*GDRR3G+ekDG3B8VRy z;I^QR;TZK`(I|{toHevfC}a9M?^*U@I*p%(woQGF2JcuawI0jQMiU_ga_k-&cmD6`iz8gE+HvE8=$0oA6o7*xnF5Syg;tuqJpQ4|kD zx*IiXTLhN|g|j2;g!#BraQCiZok$6mJWg1dDAjAO=;@NJHVvN!2CBKr*rj^EroesY z4n;cy7Wh9GW@t?{HEbD*AOgS9emSy#3+Ph@9X(Kg7(HFA;&3(Csv@i^--9DE{NUR; zlbEkv=^+3z!?t2{d!sm`?db*?#dPxo-d*WVeCF~F_0pAuZ=vOhLN5O&vFaonkJ`>* zeh|IE0AIURf;%tmf-q*=k`8hB^3Jq%OwNSA)XV&e@N;YAJl*Zq|1A zx)xt4tTvwY#rG`t5iY#)OVQmEK`hjGN9n`bbrV7BZ#q4UDyy&pC3!@F0P}W}ZsjRw zZTUJg72(;&$0S;U23vd>CcHPn6aMsQygt}mWZDRpcnp)B9)o(-NFO&vmeG$ALM|g>I#o^gI%Z2d=AZP-YTlu%F4?3_xFJyjHUCk z4>?xa9594FK7_c}HeA1c{mRVA3D}Cjuc=s**8ZXG<>|S9aDaLTmw`N`XK!y`tZvJZ zL2=*QqzP|aPXlKCU>iDBSb zPBZd-A5~PO2&Lm)8PS_DC<$Hr^Ky^E8wqrg(=90}uMKNwVC7&`iL$YaGCmM&Jc{h4 zYprl&oG{hTm^qz=K<6N#g&IU9?COcz|o8l1zWQ`NA4615{?BK?moa9AdP z#H9ZUyjg*QxXq0wQ!guSUJUtulN$(=C9^j9^ch)M{kis=q)v^k78-Eud-~9JGpq+W`^sK&`-X9PyCWlr3V!9t(`H z2@mSa+TglRd=WNSv9|Qu&?U#$?q5|KrW`d;mg(FclpMCxH-U*)3 zHW^2O>!~C4(-MR->6?UhoRV}TKAoeJmoD>1I3mz^4?~*v(|Sox3|su~6Z>B@^|n4D zSxw#%JHay@;$hR1vEf+j?e2D7dw5e>sjhv2jFa78{jutG33*edUKb6^hFi_vAK!Ol z``*sEv`#K~6KiXU@I32&7?5dzR5WY}zHs&SZfR`f&QN^Y5q;YM*Po7on*)Fi9*Cj( zKk&Xokc$Qaz#ldnk7=+bgf&H;O$nUaGtYMV)XU7UFzAuzO9MAIHz22gU1691)AQX) z+1R@Ojgsc0!?0;7rYBz6KXC#f5s`Dxc64$PkdwZ)w)SxGzy7>XCf@aT{zgeSM!%8U z(n!SNo;rcVA;T$kKaXHXK|~LUbO_Skz?-YR{dnkK2`^~!(iGyLJ!h}(xKc%;OlAy< zKW7&glEKekoicz_6Dti}=xtl+itg46bsUzVZecja^X^TW<3yvd#%J69olNOWZ(DH4 zX)7~F!hsTt7sJFIzhXn9pwcCuvFYyiamW5(j6nd8ak_9Cwp!$??uh-kFj|4B-jujv z7psBH>S}$CBG!CICsESwtK1aqmxFvopV;3+66)C4E=_5DJpFdXofQd9WLvcw|7Z^X1Sf8{Nlw46QYQS&P4XKJMk$1l9rC}V*bn%m`I*(4k{Nb^vFSx z0Eq6Hr$X`E{XOc2#>qYE|z8j;3R?Ju|zMI>3$J(}ee$_retP)VKBN zma-*;6xR52|WS=1r8 zPb|dqjZ8CPse6oiQ{vBV*423T>xT1SSjY;at#)g<>&gOg3K+Z|y8pduSKgujyF?G` z1-A-;A^0zrzYuAg-*U{)@ zqo`S~iH45;jnf;f{XkHkRef~UE;yS6>`iN*ZlTiq%qSpj3;s;A758a-J3H5Ob*Obo8TfKlzJ^D_SX^{@ z{6QHDO|2g-DvF?so);+^g63WJ?bVvdLV56-gTIL<2MgN)T5E4XXkq?aLhMrY4+&T# z;zYx9m5||7+-KO{QGVG@irw+%syTF=nK2=PgW)@o2RcoU)n@2-6qLaoZV@tpz z(a^v}7BBjGJKww!*gk7hRaG@HIr+)aG1O@ZMfBYHy#N!93bwdD_+yaL(~ z$y_3K?2rD+Rq&krcQ88v4cA1mnPnC{q*d-b^=h7?9JMj}W*-#q&R{qIE;qOXDY}zK zFyc*hDM{lZOmCrPD^KiI^PjD(46LO0C8EB4S{7sMvS|9vF2Srz(EJKD^XR7jd-TBd zK}b&KQDo_(H|!S`=-V=Q^fpOBS^hpKIX@PJ6q$M01qgD3H?H|ED0KM!r6!fwJjg4bOKn`!-?^uxxqqk@zT)hCdor~P3HYiiBqX7E+D8@2N-KX!^3Hk> z1Ocvl@5GK;xZdnfI-jIv)b?1Eh(V$woQ7>V+x$uZB3|nG^|dQ#?i%%Tln;hti46=4 zs=MEOfsA7jSl!SY>7%hYx-@A%U1sMDF{{1WDc?}ZxY8j?Y&~A zHKy;hc1(P;JtoRUYmQVDAdr;4qFm5Zq18vT0zb5gm6Urmqtn3Q`Vzebu>leJtEQ6n z=2p*^-kg8GuvR=|LKGZDpo^}rlO@9dlgF&hiX0nR>c;-=wNEAAUoSoqs3ovwf4-ep zSzcO-11mQ)G*Ch(fmdhCfWQrJN6!BWqzgDdZ!Vx2qj{%?Dl`IB=W+k+TGTcY2_kRGVuG*CLuZtbnuIK2>~3E+{w`qbT1;lw+K@^{P~-lkTu@DNT{@( zU9`=H~QHVV{ZL&ir5#kWlyJ1Q#|w&hK)5(*^1G=!HfbGt&m* z73mHlKg<5{Y>zdgui`r^5`VGcqREcB^8S7CAUf~U_-Bz8Yxhwony|@FjLTjk7d?b* zU-X%KjD>`OE}8YQI*rJMmVLym46aBXT5GK;|8$l8@hhwpS@muvij!H?!RtuNruiP# zSPaO^W;$X8m)OXV2P`-?yG(;s1ohNz$EXWKWIyGQ<0Ic+-qMsN&gjux%e%Ug9u~(# z=Dr{A+tVYIx*lG?;T->75lW*_tMLkFwEnKDaG$?ty|KyvBt@oBL*-y|&2WgAWC^2# zi!=(G?(PO@DG`vAknV0px&16~`?R$+W<@V| zdn1&KVkO$&D2ijwb)=-o|5h~b=CxE3N5mMeU(J)QZMEc=vVi8~&5(1tHP7hv)1JkG z+feyj+suSwwdy?}IQfq$*kt{oQ=UtB@E5kG_Nx9B7WJsa^7`Cj`uj(nb_NT*nQ-i| z$!1&TyWp4#yGTEKY)q!aGPpLIw3AJSun1HgS4G}OW`6Rag@*XK)zy=mhx}Rt zE{SdIW)sa(hb^zHs#@*v@0hY}Js)Ogk(Vw~DSh(c?3ubI;5e)}_0)-X&xc_B%u+n7E7O<})$lsh2X2 zY3lJL*(q8@9M(~j4L1E59#*NF7qE7P#pWWo^o(lBOCSC87MLnbpuM!2DYB#+)1~ug}6!+u6W35HyG{u+|D`BwC=DVwIZ~+ocaWtaGa5zvs%C zxp_f+teC6Mn$HUoytBcQCyL9hpag$R#s54=JypwG@Nz0 z2T#g5P4gvQ-6?);LqTWr0sH*X1_HNyG_$x@S%s|z!#{q8PtX>tnmKfAF$@&60u%3Y zaFEP+otkGP=ii_Azg>g7;0tcxHfhx>{{tR80G>SWI6WgFu`Bg0tgcFd)G`btkK-i~ zQBeaE6Qn}?HFRq>fDJ7>dI*rc9{LaTuQ#YvD0BgKY}e+;DMjiw@F>onR#jFyI5_x% zj7#vB>Fn&tFK=`b0K18YM=0EB>m!(M4i67WWUs*j?~G{ykE#5PLvPzBbpti5*?rWh zD`>rBPzaPyzCTZaD0dFI7p3gMMAbEQBf8O=~D#@Kb zLh|6EaV8M$)Gp8BDkH0%mRRa**pMz!dRiW>9|TMFy_un)8X#QF}+nm3AOC zKUzdApPU(lz6ePbbNkUc_wiNcFFo;A3Aa3~JX0p&kb$*EmY09q z)`KE$ruq_(MxnguduM1ne*&EJ`U!`>ww2am6JG7KOuH&!uJsXMf(G56;3%lZa4F&_2!S<0y z1=60bPdeRH^@lsh?=fW1)3>8FLKCMrI;SKF!ZC4hC<}3Hd`^oCbgj)M;MH=LMpf(%?aapwZNwQ^Jt@nbw>D*TXI;qDhet<%tu(0$@4(2xymjha^x~4k zUY`KcllqpH#e*wAy@SshdK#aI6=a4WjE{It3?diMTOYa4CXs_5YDt-!=}8&&UaLP! zyEp7>uJ;!mk@{AY$V`(=hU7@2&&Ht9OPx)G9GYbjDuzg%arVz)4ENi+BE06f5*m@p zP7*mHAzaareF`j-kY+Y0C}PzQyWjhiz_O~;94JR(n%nZUMd_+d@|-1gUnpfKn1yoQ zqYe&|=e@k=G9#|4ii%F}()^e6?^skn^ge!%RelQJ!PagNAor??ZtB`;(KfevsH;;;O|IDjtil#$!jT)o{ zjN8uzdDWFt(TwHYnv`K@zIUoLnElwcx;spOlSJ3rNH>O&|EYX%oxB0Or_b5JUdE|kdc;bC8!c+>3i)4{^yz+kgxiMjA-r`g})zzA1 zB-dTR-2Un@E}PNJHOUk6wIR`VEC+)H;ot^^BEX1_PE3HRIIvHFvNrWnH*orE$nz$T z0L}^|_XUIRqic5pb=#c)n@?ju2FkeJfEZ~|J3gnTM^m|#GEVf6U_?|~-865}?a2H< zp6PxM_uJ=S&Iw&2w@fA=d!dua3GSHu8TAi&*oSy(sebD9w~=2aLcUpFcCrbg=MfPG z(CX;r*k{-${92xnUWCm9@Wnqh#X{WgYCeh;kxmbu zXjV>C_iBciG`=W>f#xWjp~B>22Gxlbf)GlIAK#|4JYP6G-G#H+wF$z0HbuN)u&aiC zz#Hu=w{_Fj$3`ff$qi;A6%NmUknj7n)2H* zXy^G9>I+Im)^>AzxAB$FlhLa&fU0p1b_=Lpa6wR z=OxTEVS*h9N@Gg}50lxQC<(^w>@3Zjf9@^${$Ixo_4Jzjo`6_n8eEH&hK&F;y0|^t ztgNgQTJ^a&UTy(*2JlVqPUHbF)Z=6Y=%Nn}4%Q&s)eT){)y>VQJ!`v{Hty~Xt0zKa zvA{CEfo^`p$ARAC(@k~$)elt@MGIGt>||5;ae=XbooW`< zmvd_eHP%Cdi$fE;YsZI4<5p2a@uv!X3~T4mZf!{Fm72(abq-zh=qH0ON1XH$Em4hG z+4;RTC5-2&kZ{(s!=6>OQZ48%ZFap$l@J*w`SKlkF2qCKgs4Y_i{$n0Uzq=9B_RDEi)BEZ47>(k z5ndBs3K4i;ozq~1(5{bIi@|~Q#m&+2$La}?nbZA*SAPw_w%|u+0W!#5|5bO!4 zsBC%X%p)ckhj;4kGb?_ zvp;>n#@c{`or8tF%c&5*W-#D|OcEA`L-G}Gd+$EzaW&28GVA2k2yhqSk;~YnQY4V+ zh>!+xdnDT8$*wf{JCl6afI;q239%R~rrjk)jj-3|`1l}#6FZ|#I)q2x@o8Z))`j=E zWa*+VIkcI1OOMK)fG(b=o_%kD18!XH&;eCw$#Q93_+-#6Q=zx=M#(07Q;con~Te(}M3O$}vC#P)r>J!@>g zsszJOaWP}HZ=!)Ck1ueX{XGDhBO9Atz}bNl4-iNI#qSMVcLtQi&&EbzqlZ!b&muke z12iQ!I;~2IiyMLW)BojpXJ;q9<8d39xIz1LTbslnWX0>C67chEslf05swys9jS1|v z*g%%)SHQ0H`RzCFl)%3bR%W?38(plXm7)658)XFFxuVMMA%UDn83gvUc4;$up;&$E zhqU!Ms6%1vt$}}uh^V3X-zHCnG`huEI9`of+^=&xQjeuL(_0Sx>&w&3quiUp^Gv`u zuqBLm=L5;h%Hj7V=@T(JT?>Fk@BxPaz@!hZ3@QPSjZ@3vo3+NxQutY%`~tJ^tzPS@ z>Fv?sMlRT=L8>Y{J3HVoZjP59&f@)JxRbobulpJ}N;A)zu8I+A0IIPy(lf&`dv!P%z) z(g?u%-s*kBwSkp~)OJ4#TcHaeZnck{TlQ~zASssC-c7wX*hVI&-*JCrG^-vX2J~IN zdl3Q&8^qvSt@;c9=3eAJP?1{)R_A!o0|QmKFYdOzTI`}CtcxPIekdnPQC8eWxDl3T zN_xp(A}S^8gIgtr^ZxCBrhI4pQCT-> z0=Gy`)~ZKLPc%Mh6y}R{#Vt(>Sy`4<;q878wb;WeFRJ|TiMiXo^8ow}T+_jjszCWmI* z^(%7k_IA?}9WD>VdO~if+=MC^li5=@kx8w$5DzP?YkLH%*iSTQd#T$)^_8(&jFa&Fd;43Q9>$1Q1st2}bnrT13OrqH`m?S)NHDNy1SN49r^j5%KrJ zh%q5LVtuDemwugpJNUv9jvCKXM#qUn7(WT6mz7CT?n)-C`f%v=2NRwHiNmKP_5>^5 zI|-|#aq+JM(QG{tVFVXURNcLJHOyi%>M@yF(a?31CdJ(%H4S<#mCTqvX9JziO>|}r z5!N;i%4S#-6fSgxQ=lYCS1AUXFAlzhwBL5GD)9dK>|fmj*1W$TDU1aOoE;sp1lix_ zfYIN*rLDFW6!IXz--1^S&_Q`mhc=*|v*YEV;|1Jz0Qx3Z`{Cqwk@e*F0=RVWd;-?) z<*Ld*wgl^z_{TC}uYQ$H2)J(XFLMFng6CYIEbylBTvzJ%%8mk)A1B&{A-dqFj^82G zW%09#n7S}cDSs=re~VLn8{?G2E6Lnc4U=zTPMLS)x`H%uc$c}lHfTwv$^Am2;=WU7 z7Jx^6Se*=3Lm655*k_|t#DXkKF>iHFE55zCX(8}isWw^Vk7k{SNq_nP;w8kC1nQL& ze?L@NKY5_vOQdK~T4xz)6Q!Y5zzlehU+zZ+p!M);V^b4Yp<~ps^6kKVHE%DoZDC!) z!r|SvV#$}8mq#6|pfn9YuaXWb3?#su#U(`EL8*mf)k68UnUAmDv|(wNoHu)AJ}#voyqzndWT#Wiemp!?u=6yHNvj|)H?mul|ZKUAfrf1(y7OxoUqxWh_A9KQ(`?go0GznizibQ8RZ>nWh6QZVEeQcD% zoBs^_R?pW?FYbJqk58*FzAAfQPwzxA%LTs1wYM~LQHL7S5%+4HJVPuMc$$*-#ZV@l z*0J63f}5VS@iA2rpGa!DqO!?y_FnFyymdFROf>*5gYmgzbzpPSRzNf-uIz_Q3-9>w znFV_dA@*N^a_d%}F%quM@z&Iq0WE}-L?$CBGL&8V8#qlT)Mt}?O>bR-ZjoMRr&dFx zbgE;VaX&m`v8p7Tl_(8~P@`gxr#QNYWbb|03m?_Jr#`}(8+T^w%nt9J=$%5EnLEo6 zszZq;nS>2lf4&P6`D-B{xdfxQvMhtcgXp z^UR>xzC76u7w=h{h`sQ-{Z3>_4jiNWNiN0n6O}{(dxf`<$(SSqPZRX*?BF z!8-#V2={ORpaSru0D>b?^{2ryfDq@vPmuw%f8O5F!2yy8p0F3NH%ftS5htHba)4?8 zw&&wdgUz!h@M4Nms^KUWPKlkg!kb=K0mY1MfB)tgcypf~Zt@iWq2boVD)ekE(w=DS zGfsG(X%ye=kFDqCUhY!wCoHAAbzGU*{u|b94ct*c>Eom1EoX(=<@Pg#cu=qt^u-O& zymLcykt*I))*Hlv5Gd;n<+dHXLMyneqOthxVMqs?$m<4OIaK9Ehvm*yF9m<-|G;f> zr&iufHIV&vH4(DIQc~@PpxoCwmJ8QF(LyRF|@|YPzl!2 zmIYox^WT=N4Er&=Fqj#SCFw0};L~ZV74IY8l`(e2GkZVNVxlHBN87&n?AoAW4jE6f zw>+vURw$$DRlc^4=@Xp7A{uFLi>zr}vEL z^W^^tG0mc&ht6|5(sr{*l;q#lqF4-|rhn9*mzhb$xxkxJM%muY=wA2a!jasi(e3y} zMMdTJbYSWa@-z%8)Akqy1qJ<{FY-D-9}KkTf2mEYQJOut$8WMSs-u{SlEo&7{pwlF8maYF@EgHQ zHQ{!6F>a($FmoX}5H;Kbh0c}N@{&bh1b~8)qB54dVtuRgH^0Xu(ysS_%hSwEia%f!uIGM!@rRoTP#i*xb})8)=bSLOWOY zRw^Tf0sn)`N3;RBa}9C*D{_s0?hMgEgUu3m_&HfFm?WcYSnc)vJ$icIJkv_muLHz9 zj$;%G*PT&x-*t5HAonu;foc%Z%`@#=e3T7T<}x1CUAI}`->Ybv29H^RXgH3kS8z|rpRa`N&_K?WgsGebi>s85l1%84|7T?aD7pk&|;OA*i& zVJp*78CczstbWVy2fx&><}2a0W`mdLuM^bb&zJauW$;Dc@tIof>6lJZ ztrQ!uRROl1HkB{ua4&V=l~^s>iG^{KM4CMEH^e|B@j-0V7eIZVMEh2&_r#u2>_^lk zXJBGiLa_<+%xco={?3us30RFDaP%oWF1xn+!un9boBVEH zdA*Al9xI*Xi>-Td0%@2HG*W?{SdM*&A2O(+-pxHJ?aEe^&^G?$5LH1U>@7z$QLO@5 z;8vk`x}+zvw&$EkC)_2XA>fYp`E25MXH~&=<>l+{KFdcZ%}N=o;Jg?Rikb8sWSqj9 z6^wKzg$A;JT{5hkeSVg-kAHZ2{@)ue@Yz?G0(eVJ0M$~!ZiY!gMa9L%wE~JLx3(<( z{a-*v=Cb2oqT=0%&xnQW9OHcABYT_O1#v=dDEhQ3M4X4k@=a@$%tdNw2Y)Dxx~Wb@ zB4~Z+y7yBycQXh_hO3;dsRhH<*~WVCHaDIBa4ya9*M0PLm&=&^5=}q)TAp@SUgw1GKJU!^&bgBAFj)627 z>_gQk0fpStaZvC_r35>?>DjK3em6?IJOTSyJ${nDGW{n_P)(oIaqZA^zOK>;z1gq8 zLfvuUWH(!~b6lq$0Qna`XxflF=DNq5q$gk<3U)ozZJA_?vddH)hXx7fo9%ak?oCu! zytn!ibSyimZql|9G=laPn*@^6loN>+|8Hq!cUq39%3u?n_$xo?!ff>`*R;K`>zU}P6!Qf)rb^$mYD zjc#kS%u%GYzn4$PiPYIbo@5rEy~BB`Ejsg^5#}F0o10Q8-2iW%5FT~ml~`rXri0r% zK4c*uIu60t-6|Tcs5J|Q#@)qwgGGWZ2p0t~YW>B`jv^ER&L^?-NYX%WxT!kyC?$}) zX%(m#f#eV}PwCf|inx?4fQ}*ItGn3!0*xY_DqX~RCjBM+;s-- zuEP2CPRuymMOD!G1QfyCl2ue|q7uiYp7VQCO>C5{!*^5)68gIL#)l|9TbU^}Z1`@; zaQj*;JLgrqh6@wkMdgV}^bC>=r8k$JL4K>2D_(<+{oDMSrHX+rohTlBhS(U|&YXuz z`9eU%f_Q)ysSA$a>fu^Of;O$fDc~I!-kGxf?+O}buc8Tc2723)!T)}u8y45h-`^jo zn1M6~EL?y?r3Td9#rAn1EO~pP-b45YE6HHG@P;+CTAOUk2Q;U8y{1llGKHQMLYR9!-m&pdX)?`J=`); z`j885ek|2r?-^ZG9~q1f$ZllWuh}qW-YyPqTRQ|YGkF^ZQ&bFX^Y)*9`&PMDPu~lL zsY9svfyBKa#CM7Iit3m*2KlWIXmogb@?E2a83b%eO&I*I?kZ|_bH-|#f@{EzLe`Kf9I$nD1;;tGaOG8R8skB2@1ZLpA7BB__`H-OOSq#)ihyJUwnoiXhQRZu%P+ zX<0Pe5yMN0p1t4m1$INlQk;s^?6uU#(%IXeB)_PBz(wKc#TvK7-L24&xo@n1cXa`Y zz^UxIewT&R0OU!TzB>5Z#}dWOZvLuugG_4)KvMx}6vI5e3NgQVb=t{`XY*kZLS#F; zx#aiiarrFH4t3VN4^O`u9@w7vK%o(b5mUAyv0L*-`D<&@i7lVwX;ns`^}owX_L8lb zw@SCF)vJy+kUD3D%H=UyAYmx+q%OQQdgVfXJKf}IR?$Rj+by?> zH7OgNJW+^7*7H#CBB;svE35v_UOiN?>AD-?EDi3l{)=5t(r^7LI}h&XR9~c~RsMu8 zs&D*%wLXOScvPjQ*HIof^#48e^T~bPxtvZtu!F}II!8_yUvQ>V^GncX_&@nbF=`sS zU>XTlc*JF2^g0w}4HfCVAX|fo6;S*)E`m9~>u69Hw)^L=U-uvag*Ko4Zze;8OE$J|@X^PNbf@l?ioA{I(tm+xZ5Y}142(6Ic zckKq&Nfm@V8B1mrD+gCrFU+ld(bahKIM~<2_ z-e9$%k(nBWHLN|{NkW!sWhHjo6XKzcV8Z{KqWnt5^CgZ)o3XTTv_P=E?>y|FH3eNn z=k3&~YUn)HHCA+VG_T25py3>nZ~190a=Q1qZaxwIRsTSf- zf>$E;6`mYY~o-6hb4_<*%TN?aUtVt4T5g5Hy&n0gU494zJ_TGRJH{TF?P+Keksc{6*MO;0

    1&7olw!|8zeftZwoV~={qYHH<aw(jWrp~Ueu6Ng+KLi$}6FNIPtB&~xBSt7;wGu-s`OEe% z5baMD8+}|K*tN1$EP$)Uw&IFfufCqBE2j}+d(o|Ma&}7;pQVZVkOBX&@SjbW35^aZNEPmX2noaPPA?X_EL!4V8H zHl5HMM`<95R>AVbX_|}hPG*IZ?*%ZC*M9voEzY(e4*JC31U^G_#S6QLSy^#C&Y3~D z%ZA=*6c6Y?n%xu^!PMjO3W;fiR6Xa_Cz0c3wubFnXZjLs+G>82`p4GAWf6+68)t#0 zHx+h?-)DRi9#H zr+k%|0d&>sFu&27(E*wEK+Gfc$-4DI&L^th$uTZ1#R)m<5~!bcv@MkJF z2Q7J(PmI*o73P&Og(q3mHkVGJG~CI4jByB6bQ$J&VWfLa$E)o+keSXVzsp(Fi;T-{ zDN@)gNAu>*d-WC|1w&cdaeUs%5vqbtyH7!N15LFzShH9^PC?6eNGGA{46 z>&R1*K1=UfU9!~c$(f&@KWE(vocn=`oN$wmFavc9V5HS&MhfI+m1?05#&;6lLB3Jf zS0y^xgE;&cd>LoOr!!!}jT;Z0^CVz}x95_gm_5KIuS%yfS1Z7T4tF%lq3VniOlAzG z-`Z`n#L-duVdX=hiOev5cM^eIa#T6xGt;<&Q`MkFLzW;ov*8Fuz!2$X3Zd_ zK_Lg?ujVUPdtGarMFEbr-0a#cYooLr8a zd_k=Me^X9Z)%-tAMp;D8q=fX>;Gf06kW}dvM#f~F3m{bOQ4Gk)iiJ{yEUaGY8~eQ+XvF9UO~#A0lSl zr(ST)k0|-*yP`B(o9ciC03VS`i4{WcUu3`CHmf4Q7v&^IV`XIx>0dcc_(QfFA5HEh z{o@ZH-~zPa7ahK=G48NQ0(4n#U=TWad8LD=%y+}w;7!miv|n2TMP$DJZ~Zd;M$ zf-%IbDe;w)h@^`0T@@7|Oqc+8a<*KD9~De)@byESA-IbxC+g$47U`m`LG%ladcCe+ z)JQyr3PyG;Vi+FAyBa5{gBH<3zfE>7Ew3Qo9Y8rhjA`hSNgWHlp;8K=-Gs4aTK9@1 z5-ZI0hj2r;@pW)QiGEO^QyKVS;9-fe%8 ztY@aSz;>i=L>Z#kLR@Yyd_Kq$O`&Z59mMkYM!>M0W2wDI8Z-Td6IzFG{@0^NvT=~kaSDVs;>lj0lnIXpfMRaDkV7tj5RB7n{ zrjp>FBYF`68W4ac{rV%IGY9wG4e;_nm&PKUod`@I`ys2pRhU$W#$&m*1je6pmGYZ} zNELnwN-TK>avjQ5n%qFo!qm@~mluF5D{(dV3RTTjt?C{gjgdTz*I?013&Oj2Eyt?W zU;*VmJgOh31=EnGMD$#D0SQ)As@hWPfV}X8FxJ2YTK^=0BdW!e5I9PDpC|?Y-D7_E<0=BR)>6J@Lc)P zU`idQbjED66VbE6u^lpI-I@by4|fft{>TM7S-#qSwreim_g8bgd#+R6RHq%!%&q&c za`Uc8muMQ6%nvBJ<&H3y!xJwFraZqiq>7FW@J_igPm%PcUBTC=sU>5QEuOL?IZTa= zr^j`!`587fPl3SbE+1&C{|~~kd+NG{Au1e{EP+IKYl)U3gxrl!NVGllJN!6wo0Z-> z9|cP3X1tG%j6|wl`whFELPYA=Z}M|AW_a|nt%sMFbuH3l>>=tOQybLueNjbuU5$p{ z_7w$lUk*NB zDN3pbW?j|~erLzYewujC z`++6g^%*;6&=2ii+pxMg42R&n*JvL;FzRdW^xn?STiBPEFrW|4@;0|NUOjw6*alIr z?6AIG_IjP``r(0TbncdXck%Qw;p;?F$Hp?#Vr2I`ogPEZY87^MNQNOUxoBy28nW!y z(M(z!t=d&OyT7M?@(sLenEw2;!m{N;WGp{*Gqb9A)805bo=8gXg&-{HCmP1dkZes_ z;Hc|*q-ZRIxxMDPNGpW^%0&AL)lB{_x%@6u4H?UE$d|m6S{5d7iniVg3=^Dx6nHs% zM_yi@Itwi2Zs^(j{TL({v?3%zKMA2&ZUP}!jEU**c*nt5dx3hfDa66l#*}nzG@5qm zfM$Hj@zi89oeUZnr5D6Fpm(9TaZgKl5g?whsLU=T3#`(P94sLBQnT>0 zlniamX0ZYdWTtGgL10aUXZB%*3en?2_mm;gsR;uqMm3ev@t|>0eqql}Y}C#AR#$hO z7WfjDcY>9Unq=nRXPqCWydw*Pv=Q44=nS7q$*^rW>8sYW8FjGtXs4iI`ckODJ`JQA;-1?nAfnp$k>h1{SRWyv3*18h<*w4i>>;&Jnf(V>J31N5P=TfM zgB19die#n67)>%xA}9_%yd}e8{2>dL_tAq+KS^(MJBRKKtH#rOqM|)i-9yBRlIN=; zQl8A#a~>NfVmR z3o{HXh+N@KzS(qG*B!NHIo2Fo2uzgOv%-Zt3eg51)mF*;YsrG6!&M>1AY z0f)%-#v}QOPH~hS?2&lok|E+1oAy>Vpwx`UV5^f9QJh2^4M$abt z&>k_J!ly+_=Q=x2Mn~bKSOtmAO(({(iKUtdK~?n9s%KiqwcI?$-F1=7KzB`BcbTxw z2Xr_4b1SX_=mg;c<<<9$(m2A5Q===NeRKVmUIr=-e>XAayN*Lr3(>&unZFUDMGMLT2D(4!yj!K!ah$70LU z$Zxsh=2t*b*}hy(zk0IrU8gcofn8fLgLjGL+?%p~&s{VYXI0iTzH`u9*GOAd%=F-> zu8y`Lg`n8|6QR@s+wN{nFGlB9rokChfx1ksH?Z>*1`(#QvD2`BfuvyXwNg5{j@1cx z??kG9Dm&f6&IUj;AL~% zYu(;~x``8{<4-wP6yO`lSn-JwvYFr=?#P`ez>n%xdi9RwrZ;BkIP{q%<7jRxrmikV2F~5qy@2{ z^sxK1DG3oJQvBWWJahcCzor!!`1nUf=>&wHNM8J;(h$obTtWz zDiD-4NrJIPjgrt%{Lni$80n$-X%ANw=jBzT8#=a!oev~#(x$-xKgEB>`dIi^-MYQ! zf1N>;mkbfV9s5K1EOQvJa%0jSo483`H6`(g@dH5pY|uLZ4qbg za1;kUy;d4@Y8;r!1Hr^Fz8v?A;SW!rSuPPsYau(jFmA3gB46e8>dKLin4?cIE2AkA zjXF;CX-4l$x6y;i9FKZ?RP8iBMg(lYUPNtZQ@VH)(AyWC>!ev& zt{1)n*H+wTg)P!ExWdE|8LC~2<5T;9b=X6oqD_NcQ>1K-Az?+g&TeAvD$jy7b3Sx- zqtp>HM#{W>UA|{rjLN|?wHC_%NmiL1q2g@soFVBYl5Gu)7uIAsQw`?lXa6BQiIpF% zRwN!=pX>%Zw{n==TPu`2YE_DV338OHt{1;AXkqxyU$H@RS&k$&*Wcd{j9HFOP6?Ao z;B!~?J6oVn_x${Pd09gEz>qy!`b#^ z+qP}nuF0J2$+m0KWSf)SWY=Wd-p{x9vHJz@(Tn?j*1E3qyj-;9fbu~!0thzR>}VSq zSP=QL7lef@O_t9d-lvg_K+PaCM~CLeQ3}h9To!CT_4s*W3aO44BQXI?cnaw|5TWIv zStrro`uy~-UEZtD`tyeWAE`Kfv{^-6@R2YEgmcDSJn=L&4OQdE{y~CI^R0>crVRU( z3U^ULu9pq{M#7M3;{5o@()bHJcZQT<)))DVgwwZQp--UX3x}bbxD4wuQZHWqCq6-mDcKUX**5fKYJfYyO#sfQBQ zn9Gqy3)sE0Vw4}WB6wNBZ5Vyem8m|6t6bQ+xVk1(xIWy`24|EmdO0TJ3S+-}ntSM^)Ag z*B;q~uHwVxYBrX7GMKf!c|qp!sOI%ua8!GJGh%K4m-3VN^gcxBPSLaUdb?`tS51%F z`(3s1l9&K&Koa$T%Zg++Xeb++1YcuatLkj3Up%o`Y{_Hh{DeRY9gbjCVZ-;lfd79j z&mW{bU^(fMX@k=QD9WPi6~Y$Vb{Cp-kyz63lGFy z9k8o;IOlH57Y&fx>eS0Q)lIsdinFB@2cAw+myx~gC%IwZ&eSlKnZ>!5K0(AMO(t=n zg8j=k7RI5wZvsm)W=E5zt=0YiEPx;envc1^L{Zi9Sr9uY=WK?mdAeme7giJ4hNdyh zLGyu269k%SfB5afk6zecWRafCH6QX!DAJQ&w>pov=zh2+2dS^-)b;-2{vUXgX z?a}HLnomN#t6!#KpQ-*P+b#2jW-OLM(A|~EuT^~wRoG>NhfzD0>0uS#0!b%E;U&V8 z2C9udUQqpHWa`PRSl0dI6bjZ+oP_3Ai?ZS>j!Z7kkTVk|6zY5GVpA&|9ZnQaZUw^m zv6T6p^Yf}rhk06I^yEUqB=TX;g=|ge+d{(P>b-?9)vM9~nDl=Kd>4 z&F%vZ)nSBBUVsm*S?L=Xjea~Zi=)=Cy@oHkqb#tbS9GG_=xQRn|HE@Z&Bij)P^DU> zU0h!3g1@?8TK^2-4gRPFcEDI`jBZ7;p~dMZTN*(@ck=b4%R=BVs~xf6;bfYWj(Ha* z^qaX5z+r(vJa7KNP%np8a5B_xp-GRz#ia}SaF8==*LML0uueeBX3&1xo1*o+XLJXQ zt8hj(l*HMBBHA0MfZec$R3{L%k$~z8ky7)+^4w@M9NqffbAy~F{bIaf^V)7t%^Alq zam!JYG+#R;$6NRr>ldAp&Pmmja=Sq?GiHLaRb1DTS~Fq5s%K_VLsyWEg_Z?Fz=;Da zG9dKO09D;E;?tC;hX)LH6}oHS-k#Y3*)i@oOk<*EHAIC50Vy>JhA_n6mp>f&vgUoz z#!lmEzs;$LbSA)1SrT01L$%O$E`o0G+YM~IJH7mVa7?R`lwicBM&?{@t-`q! zGiJNW;+HxUY37yRTdk#~!8^!2)tXaJuhO!6aWo_dW-_ARo*h8a5dbr7z>x6ud^aN` zg|#F<7Cdbl`&_zey{2lFnJmxFcT<{spP_-#Y+<@B7q-gYIYW8#O8nkQ%i;$!c`vPB z*BRDL2s`Y3wcY)Y4`(ps9x?<(^>g)Lb+4dRHjhT$?c%RzxMZ%xV<*lDd|ZNDAq= z&r~j+IYbKf=hp;xlJ1;K-+ zxqKEqP+BjaC2!sJ><83&_@pM&)-)L+TNOpt2A0l^NuqW_ZtHT@f{AKqPuuJ=rTkyZ zd6V{(-*IE1sA^tyHj;rcl$)FQ6$ZF_n}KhwN2h|Q9X7y?Z~JR7a7W>ofJ4ooSWhxS zephf1mswOGnJ?&Vi&I~-0`JYiJCGq(w3P3Gn%gA@ms-6E2E~!DxUg=j?ZyXTWXd>uCpL{H&Dm=ujvo?V?IGQ`T58 z9Crbvvn+=*QfcllOg=mkXk?uoE-tQP87&gK90ir$+6Byg=Hj{I^Ggt26|4r`2-;I8 zn|X(tOtEs)qIXSICJCSJnaDzvzkvhfc(>`#9iytw2;VZ|Ws#xO4vPXqf~!@f3NHe^ zLC8q&s>pSkSyh5t<%m<)%3=0^bL;5e!GQ%p7J7QyV5AO@>AS;ZM^7tH3?1n2ofYYWT_Nh+-O&C?+kys*%buV$VaizI=1{ex~jz%|JdF;vjhsg z(4cmsRZhKnE+R+28d0Am`RRbXyyMyzvK~ujm$Nt;1FS4N_o^mm)1b9_#uU^~eF=Cv zwo`M17r=L5FI3D2@s=2pJ!&=~&aHO>m7NmlS`viZ`=%A}pw;_+zyuxghbrIq_M|M| z|MTVO>t5;0JXzj)@<0~`730otte*B(Mz4!KX!Jhm&M>SQSYxqnx-4uSQLru4XN(N^ z5uO6Nm9P(D^UAjn=a=!5{@k|^HDtM=xt}2fU}8a~l_z$z^yGA*Ld^aVt=NluP#xY~ z4;`(o%O`Gm0zOL@9?en7C&U(|PK3?NQkN8tihKOcP|4De$v`|e=QAVZL#S=N#Ee-K zfD;Dh^od!R@t~yd&hxyQ%WFl47LTMT(uPyPH6yxO+4k@bq}Hh*o$+K?2CS%2IhwVU zht0G}KX0|rSJ_l1z>sLWB9$wp1R8q~Cu5||L%X0?FpoWIPepT~V9c0>mQHTM zSUHX49LrDbk>8Xspmxhf42iq zi_JMXjT&Mwhg4eB%UYT_ReVOe9Vo z1!B;p)+Ms;Zl=_!n)n}TnbcBRIVi>F_YU8uNL&dYQ+>Y(iq^t9rgT-pB~=MF(r7Z3 zQo$%sl2XD^iBcDe-duw`PDJYI^C|8A<>+VVL*ZWKPr-*4F9_TR zN?91%BZ?b`K<~(kBjQ4-5CgGEsK|Fq6w?DkZKUWhPy@>jF~s;2Z?n z0Vo~87=17}Is{X$@@I9+0NEU%)>5K^uBf_(b{9gW*{cpY$b3F~{4-q~*Gcm%B7ZbS z@lRb#_+_90BaDF?Y9qJ*M=dO~C^9bA4<6h`jYs0#n#z$v>sN-$t*1g&ITeljoQYPo zTCz|)3nW33oJKYO`D7(I=Q^{NS4sy=f_gU_{GM$I1rzRQ{#Yc9X8TTx@BB#$MJr)| zwJ{PDxLY}J?(bS>zH88Z&F_u@cKa`Y68|+X^f9klxp?&iT=II}F8OHRC5u3P(r;S33%C2l5F*GS)-^7{L$5BnT_Q>M9oVRoW&Bz zr{6GW`fsOfn^26@94ncsk+Os>)z4x~0-=1A3=^ph&dtFM{W)|9=Rx$0A3ZQtq<#*924rmxFRdZ zz1&Uo3JrpSNF3Mb)k3XX(TFYeHnb+A@?he%D+ifksJ6nEpRm%t3ab6?Fp78T$Q7Dr z$3ZNA2QPD5>{sX%OZJpoY8bdh@&Jg$&G5xyi_$Y|Ns0k2fXkJLTjW|VGptoRP_=Sl zX3%6RME}A2PamtYig!{Bh;eg*8M~e|I>;oWMZvz&I_zp5(DVh%Oc*qJWaI&ZzsbOr z!NXbZ$xBm^$jarjNutQLedpnxB6kuh_Et2{^$;eF--Y$WV8)%0lX7dh{7h1!gPPBH zAD?cblP`SAY;TNdEayyO?7mLpis5h18ymy`%_T`o5xtC!CWY7k=g>d3yFvQ4`ftAH z-|+GAk1G>gVR@7k*vMk9la_47^ll*Hb;+y>rO0#^>#AIhScqt$H^{|FRQ|A%Lh*|n zyx0X~k&ZJiw`+7HD6m3a0V0pGd1tp2azvmE1;d^XOa1}AM1o!pl)+T^gCmW*Z_sn7 zA-iDC58b1joU4jctD{gPZufq>$5lAZcPW}!{Hh@}4c4(s@crAx&=PsA(H=xEl)}q( zyg0DbZ(Ie}`pr=R87-<>v~WyE7XbS_x&HV?45v1Uk zc&}^pa3L+9Jpj>>Gy1U3^JSXkm^5I+4iJ5Te>Y_K)Y%`SzOCzD9HtYKD>Yh*l?Qd% z#jqo`F!=Y(7A6J5_EwWBr*A}PgUYrzjO$4J3dVw2Lt=W94*Q>mM$S z!S23b4boAxHmK=#({z=cThl(N<@3oWk|Mp6%Y{YhrUXHs>d{!{j4PDe7WU&>3b$xG zhVd~B8+X=?mVc#wYj_xhymnA*Td-{wdTSH{Cj%@EpMbgp;H3dsFAg!)hKJS$n=7Y; z^LEj^K7X6tp~$zUL0| z>1sPD`55;p4mX7v>1B+nn3v=*E5Vy_%`tj z+_=W)LFGx&T1RaPDk^{xtZa-Nt_vATA}g}xVElBZm>~upKfQ}vUE_`u3`9ZmH*@(d zBQv;U{Drf&3m_p$OnHBCVeoxzluOiZ%Xvcmfa~I?AzVq^nH5FdY#ZhrZ^U9sb9*Pp zBc@2f3d-&dY@B3Kb~YX_=&&~Gw=`!>;$g(IOaz!D!*))vV0^Bl)dwT1bzRVL?m#-; z{Fw{3NYJ1g09a4;ls-Y>qjtQcKH|C&Lw&*Y1F&KbBYQ#o{o#jx3;md06RgkwMPX}m zRav7WDILTRglvo?miA|=@ZWjtDi6v*xTlSrjAWkPilk^(D<#5INL{#zo+yu8u2|0Y zzO3(Vrrka^i-W5!k4Nqxi@)kL0avJJ+HW8Q4uH*MSlNhB_P#gkhWsg5v}K`@pGX$8 zh++_JQU_1Ofsq+}1VNSA;yNma3pwfON36fm1omVvT1z0yHr>etr5H=U`@i$Kvn?Vt zt4%zBUyz`;h}06A`Pa>#aC?J!$iUef{k32My99yQ>m!G{O`7vjH{O&NTPl;$RpnO0 zAhnpakDTq5;b>LIZeE7bX=5I23co*HtTg&K)$(rle>q4Gc=8Mw8Ri;vUdS3S7BnLy zr3l6f_Nu~#>0sZGExvUmhwHj{;2a`RqR=V1MV?Gw+HQCH(fg3(PaAkLBGmvljS=9) zcqF#UvM>(z}W5OC@?WHMQ(3Xgrbmj`lBLJgHj&VgwdsjR$E$7U&Z$W9{8_0FN9OOA@ONOhB#pqAib zY^)rDR3Rc&E=6+ZPw7RLhQ4fn^o>^lzLp!pNKyLP&Spx6`{B@-0;n<-(j2>ixL)-! zhO;rlO~=FWFJHj=&YZKDAzdwXd)1$lh=G2uFJhEZ2ptl%hkndeqLKyN%!MVw;?hkLn5d; z?}*kPNIU+zY(_@Lp96*OWOZocqrk%rf54}2yFQSHg-rw??_?m(RR-;WhP71KXlgJ$ zf~(On2o@2;|6)0SOl$rWe}Sv6QI|~hLK4TV@E^IL@N{q zIH-muWPzy$1(h6y5TuhM-=fSHqiu~ZE@Gkw=vdR(PoJkIPp=9c0TS$~{rFK@)nAIb zaKWaNuR1P$=Ajo9zej@2sZI|@$o7s+Vz`2YkT!-)Nvt&G^)KTic%sJ#QqrX}D{MIt z+H6AgWw12!EWvhXlk(cW0A`wLV0Ygw@Rjo;mw_eT#Mx?}-go=)F5?H;U9EY$PwxYk zsE|lY$ynmZZEw$8e3G%}kCu}xXNr)rd(mr~Y?Vi*F{Mo3ls?=RwM|wg(cHB)1qA;u zpWfK>C(ncjwQ*RXb=14ux~5df-o6#5`|_@kp2ZFYB1U&%9tsd#v-709_pi`=l^hJm z-?Wvq(%EN1C3+oUmYLZrmCduqu67Y#mpDOm>1NC0b6pa6u>8O>{|yl~U&RCYMj-X~ zU8*!yUECF%>Vba#ocyI_TINSgg^x8}APh)K)zKKBRySt_D5Mhyb2t0jpO39yw@hER z$Y0mUMt%>eiuyJn_H?sLFh`~RJuYCXU(@gf&3!x>kC(^~w}Y)@Nv>vLwGyD}I@h0$ zdomyUKQz%|i9#f<_!ik1WA&lP)C>CE_<8Vz2q3-o+5j4 z4qBfFOsN90gx>@c>4`9^9FopwLUsEjJ7w6@nnez`X1v!qWne}FF3VteV9rtTTkYSX&F!#*)NSDac)+iA8MsN;VYaDkcootSZU6%*eN0Mdqrz zKC^A#ZvkYY0Wj(<-E!av^fJQmkqoUw;?VgYt;$6wFSETq=_I^SQjz{Kjd2IkIE~7n zjrn;smXXkFH@-reAu;F_^YNLteCgQc1UFqQW@ET3@aQEE0z8!Ra>=4ZB)77%G8!<8 z$LvNx#)x;C8>u#gZ!YVbU!49n7B6F-h5=gzg}{rCv?DA3te02#MJxR8caB{uJ>~jNtC5ebC*JL2j#X%CP zMR#fOhE271tLdNjg&J-u>;5_YOzhnu;4Z|-^h-!`xzi0uG!G6H9oO_|$$(y9*NpSP z+;jAJo8-z7s}l9=HxX`^7+c_6D6=hwRprD`K$weNi0iT02Q*oKsWSX~w_AnG6Hud- z!i@~_CiP-2$~XFv*>DQijYax`z(G$(?9K`3UOq}!VhC6Hr~7Fud-=4rvX^=D9=5I$ zMAxsrBprSDuWo);Yo0aE2+AeC&Bw3X4nhm95MMtwP-uuzDB9C)5!~7ap%U*%gL!r z`>h3Rd<&XJCBRyPQ`1b@TcH$wgT5NLAPTc#z^*(3(+mg7duTLxCq}_ABPqs_AO%v5 zW>p&sP8apYg+IYl{3)c0jZO|`vIuR)ZVdaL7e9ma+R-L0)fE&8n}u;IRTlB2xYag7 zyJRVO0+?FPJe|=-3P&-dRd36Mg z!w&o?B{g<(pI#r%fHsL5XJ>=hD4J@+h=1p!ms9C)AvMm_HK+_3`bg3=dBxETKH*&e z=vE<9Y|RVOvTpyg)~XR$_?k$ekTU;t-RM&U=f(CW!~|(|oi`7CUv8og!nCj;A5oEW z^%>(J7+;#n?#$geDsLRoLDTRgse^cHZ@IXaJ0K6Eq0Y)J~# z4}PorzH`^0OTQ2n>LM+xVnt>Jh^cte18uPU{rm(7^gm;>&nEVd*=V_trmnyFYB zQi$Sd{a*OI6$+sUA?vqF*jlj>{tsIUNMUoc*A-ADyM@yS@7DDpr@m?5hE$!?@i{#; z=hX^5U__F@T{zPOYGOLO211BMBy|(tlT;n;HdSdF5tH4gSAv70b%s$LECL}jG%akx z&X6eErO$|ZaQ@(}Jj~9FiNP#*1QL{@r_6Z=%^7z3HjX1h&~KbhZ5~t{PGHKiHVY5{!U0v+ z$=}OnKecc=iLF&)C=}RY!k#K&@-e`05;Z15)ljhj^xZ24J4YG$wfGzFg$NfJP;iIN&L?Flx;zLHpVw*7=vAk83um-sTbZ#&~WH{b%Yamf3oqS;{KfiL!7IO}S_;gpFy5hDH}$&>2xdJHx&{ zN3AB+3;nzC(SG?jw+IRGs92AC*quH~WYwbWhrbXD8HtvV+^^&dYm2uJxL{4z=@blS zrzCk5$~gC2+e@A}D}gEp>FJI3Ui>%H=IhwDmz1h8WTi&t^zPZzuf?%-8|83fmtA`M zq(L_qf3+(`?@^n*q$1nZ?aF>M_~Jmt^yK*I1I*P_D??JUOk6BOw%1Tix{(803fnY1 zAtoBLxDJvi(3jqZO8K&4oy-x{puGJ5&jOI+#aUMUi-;bXDT%RKMF~pnwtC~^+^wq) zTma6_d!oFo5UM2=bxqZaIUmDNxufSC3qzq*`vKE)3TrIZd~$;@ti!71GdJ@KhHotE1=VjI4Pb6+a=7W^*oUv#Zw~ft|bsTMmM!jbeRa zKvOF~@II*;O6QD`9xuqphldp2MRHtr8&NC}J+!-6sTJ}^m;i+(7^oEk?L>T^eN^H? zkcSK@;n~V#G<$Hq9biK~f1-~32UuScoN-E7Z`&A6M|*cqTj2Fc)JHmIX=8@`{v@aK z`2PLuKdBS|E?YctLlKZCLQ^n1Fu9>)-D_(d@BGnF$GlG?hD||Rv4B)#i+^Z;ffaF8 zFlSGFH;U43%ymO&Wo6~@+|t?#{J7u7Df*Xen2-pQbxYH8A01XKYUjvtg@wjeD!vys z9ix&#OJzhFSmHQ0Y?*28RCMKu&xd|LpedscdT^aapo}I_tS?E}{$rzq^dc57;CfN5Ln`azI)X?EuN=l+Kc7VSn4 z@U-rpRAxU$F_{U=(OzMj+ z)Z_GYh+$Rm!+Z4xO0Fd1>}Q^}%8&wo8j8zl;cW8uU>Zy9hxkRBlkWEPLE-|CokI6! zCg;F?= zDxr-SnHBN`{l>|ob10`m_WPByVbx(VOAK@OA>*99O%>Vx!e0ZxNIm>x?Bd3MmsxgDlf%pu}A=8+5)k!*l%= zr^Xl$ay3CJ6Y6j_a)}jH@n*)8OjS!1H4S4TBajrUT)ZV0`^*W@@Czv`m&4`=Bm+?o zv2jL(m5^RDtRZt`AESYnSra$h$58`WPpfx@X|m7r{2uBa6PDDlelh2yc%eF6h1M=j zK>83_B|K=VIuf35Wq-B@^)mxT3vN4$g8Ct~&#&R70!2(EFS7zlD%(!`;EOW3Kb6=& zB}{}=;oD*=b}H1_QbK=%xbsrrIp!l{V0eX+9 znj{gUraPF^!*E*T5_vJQPS()0JqSZB0aT1jU$BmF4?5q$9U zIkp!3KBg4hp*XQYXeMTe__<=V7`yM^zw;CF#Tb`TkBCE_`S&UrgeN4M!^NJK@h`t9v)bzA&zTcWZ(6aFxYYCciZKcKM1`c^(Cqy&~59>c{#fID~Q(TQ@iq9d%kdb~uE4wg+MDIt<`c7K0=d`#`tM&m6( z7S0DUKf6kX zZF;~hRlw~SRlXZ9K@PfY^V)xoE36X=Z!nowE(hfB0id_Hy8RREPKl))qX-1T%DDq) zrJpj~7yhz+Gle$CelkGYB~(P`)GnY~_EuVhnfjsZq8z0t0ggeE23V^3+E7V&ApQhC zOcp6VJk4NZIXa>Z{qq6L>szHy)0#(l453YI>rM8_j|%Ni^T{2$Y6d9FmS3bGN^equ z>pb6CjH1VBOL5gqhH=MF%#>8sIz?|e@P7Gz(BfBa$D=^BOjyz@*V+BqdhL94w0l1@ zx%C-}^+sT>tTU())CWIXQlbqUd-H`**AC+WbZt9%cE5JOdtk5tM87v7g*3V{ysoK2 zKW_pDi~zYn4OKMgcU^bAP~rpluKA9&%}pRP0g&a&24uKWI}BVP?BP^R8u9O#ogk8U zR9rzJQ;q05Ab!U5N@~o~2}DX4L2|=!$KTVE~W676*IeNIBjxbu4nwWPu#XO_hY&@ zMNsTvSG6g_S<3a>Xbnk>0t^FwdG2yc1SaUw`iuUvk!?kBW(Fu-1?i*g#y{^L!W9lO zg9+L@POCsA301?FWLE53`oi_m(Gf7?Zq}_{wd0MJ&8z4QRcqZqxnZpX*VUBiy3NaO zG;O=tA4>-C+OtrQ7E6JD#aJ-EGiAYhaE!mt5h>d#dM2K@$(B7G9{x;Nx$u}$xcTht z>G6NLwW!t{AVr}s(nWl~J(OLn%K@-diFPwX;14#;IDMDpq8zG>m`dnGuyUrU=WWOu z+J2St`Mj^=yC@f#Ka>52#S%@c7O?dtV4cTpz!krl&;4fK`SIx9xa#|Ou4C)Cs%vFm zkgTnNnSwrSR(LC;aKLmD*XR65S%<^!U?!j@fV(@W--IiT`7X~d9ot7uplasH{W)n* zf^70o+V%r#OT0?8SSdAA)QQ-!K-W>S7{VK%OzEo{qw4PdHyjw$CT{`}VFs2#o2IJ~ zCr#R6Q(dX;7bq>rN`KrUR=`;PQW9}(*!~S9{+Z-!5(GeK#3e2)>qF*x!4}(rWi%kE z;tIIqim3u4auooc|NaZ99gq1qIWglPXa~{rZ$+7>;%QVaS}U-K&_l&S(FIM6K=ciY zB=poc%}pJr)JWwDLv~;wjGNEo1sR8nNtW=!=lMccGHnx!bYMWNIE$9lbP~MV|xnJJUH}_ zWAT{!%->j(be|6QMH%g)B}b?sJkJl{*vVDoE}WjR_Y?PSR&e80b*gjj#rFj4-+Yoc z_c=4G9WkAcI8Qajh97SaX_j=MMs~@i7M(SAwU{*#xHKOH1LWMNh!-vTmfnNThQhde3J0hT~Hg?EArN?p*`fYnFE%bZiUxhU9h`1#l#xaTr_)N zZlhqye-qP$BTue7<7W1c^J(I?DTe&!Q3`ZdsY=Y5${YPGJC{y=o*c(Ek`%-DQ7p>t zPwY!tO1U)5eF!6|$X2{i1l7?PbNyAUWvjc=Wp z`{h0FE&_(j7s0!vSpKNAA;SmS&P>0SoSx^(qzyC2h$1uWA9nN*;6P+nxcqJk zImci}irZf_#la2g6Mj~U47ka+cr%}VPPF^eIhB;7V+|V=nnfh> z@+cmC?w=?BXc#GFGJU9Xmo5ncfK?};1_daGKzR;Wm5hdilYoML-$l5m=Zlw8iW7(U zt@$g>H}T%(02e==RF^ftN{Tj~=XVy$&3#F|wbJ$4Anc2;2uqEQ5?3$kWbKRZ=d2Xb z$1ZlSF;_cIL%{H$95*^_){tk!m_GKXVU+J!k()RJbIW~a z8Y?;AnmjWE7VJ*Jve6Xlno~O#JffbMI#ZqSaz-l~6S4_N?CQ1Y;YjMH&OnU@&Fx7g zPFK}dn`Lc#byYN|L9l)b!7W=R8WzMzd2v&9&_m+=5uuq~LmtGX13A{hnB&y|T8=#ro|IRmzje~u6?os?1CH#~8#F?c z3F?|p1Vm(gR5iBtOg=o-1B5^(Vwi&}^tMkwuN=W$@4QzMbZeJ0)5^Z3N+b%LLU1P| z8EZIRGoT4hJIWi@ahP)0n-j=z^Bs!8=3ji%{Q?#|AC)RY4^8l`fymI`x8 zB?bvd!N1Tjca1*ax(d-|Khq|`kS#eH7m&<~hu91~GDf5MS&3@+F=8{l%+HOYFLJga zz8YYw%5(g|u%IfoG8lB!VA<&ev!r7$2G!AIAb7m6hJWu*cJ?NzI6D37pF>Vbq<#vH zyBhjkOIa*~r~cethwSQgv9~H6Gi4NMB7(T~D73FgL2_ zBaXv5jdZKi{7tA8IkOeyWGyyHJY?9{x3=4x4BY#hy6L-hS|!-F@J zl0&u@OFIbVXzA#JBK0Q-z`V>bP7c80CE;9a*wy2soe&-Wutp}6l7mQ9FQQ|=dgcv# zDfqxyBJV1b=K%fSDLaQ4J#;bC5n<6tFD*H0D)ma1Fmb^V*hJ5E558*OmuO^7|>NxIg@Khg7}CoN$tr|swrRD9#A)byi?ylMLg z+YeZOE?+&}`~!zTZ5R{C|3%^g=>151T>rf2e^YoY@s_L`%+sy$7|!=yE{(5(uy3pBSXO{ zD)~I&w112BgO0~^`to38Z111Pi!<+EEl1q6JN#VY1gsRdc>M9k$o*`+(8hN-WWeca z<4n7zSvdTwBVlQR|9cp$Dx8QaZxuQi7*q_XVrSs+P)4?I$mH$lZ)at%SGuw~Alp-LVDoFQ(|T_8Upvo!Icc{T&{w1yeE z5)rjST26hI7U4KG=;X-sz&1SEf7cDeq-smHCE3s>=$%1B54U!Ae*h1e|7^#5{*rdX z&9mS7Y>ZPg6(%@QwHs4wIh6z%WlvdFE{Zx4P{{&auzdWJ@j%P>*-aN_949nXlNCXF z9Ac6x!UM1R`N+A)IWNP&&#=AFA+(QT1dDH^;x#%iiYaH#nQHqEa7W_oK^(C%@p84y z$POg!z@x4@_&=2>$(z4CeE9y(TM5Z31f*j1Zan;OKNwG@5ekyqL#yCOV;W;m>~*i1 zU_4`*HA(jV%^Gt>Tn%}hX7uJnq)0J4T&v>HRT{N$-u(o!bU@6unAF^%PaZ-TkNjMX zk5N!0)~FqaRQqvYE=%lz&UzO1y}lRUszy^Y@c+`FWA^}0AxoapDBz^lA`a6chyC0gV*`@pGTh zlC{d@T|=6Kt5(Vzwe6pJaLrm5M%q+4Om+b+S7r$8xH-g~vgR;JBV`^dUvAMnQnJCt zB)Gt4{D<`;WMy zW-&%v!-H=woQmyeN`Lw5FrDFggC_I(NPOpuy3e;D!soK-4MYPE=d9icLGT~L@AoLg zCj5fB9u3ZhsG#75)@dC=SS0)lpr6K$OM`u@xGX~t@ z@Mgl0#bWu^V<`wq$XXslt2c$YBS_oUbV{5PH@|k_*(Op7u~>*iOuIxM|12+1ia5$p zAs(*XI}z>A4Red5IVr6oOJ!V(TP^!gJ2VmW>un&83-}#eFl~>Wq%2ixOqkfZdR>;I zwwMZEL`y6Nx!gH(&BMV15;T-ONvS7~B!kIa@S2hn?f>hwZB-S8O!~qjSshvW63UCm zXi8n|CU@VADx>61_p$QMaRYKJOS4Nq2qckSq1@N@@qiqY_U3!z^wi~bxfHw|_rqG$ z>^-@8J@$`FUW8j!LCT3TeuBAGHJaVQA(zitQ`VBIkMVMQb!}NHPkK2&F{uvH;&Bbr zC9mUP?vT&pwA3tpWoBy8KKO;N7VngA;uOdQ196ms*GQAr>yK{s(Xw|A(kQ_^r)$&0 zTIc!!`R02agh^2|^IbhXgh=5)nCQdbh=lf1xMJ z?0%r^K!PbSgVI&aW6M6*l-^);?;{=%bPi+<`NEvo%Vtfb*(l9S&$UN^SgewWoplTN zcy(`GH=xG?v8g?QTzDWz6Xv+Vslv;26f;&Fl6cU_Y^V*hSioU#%NJ?MT>= zKmmqG2Ud?IaQDe+afv8auAZsz>C9Q2GZ8~IawyPryA_iFr>G#0Twi@(2;HsDLFU+k z+wLSDQmVW*NNmg$iTs{Db2Qx|D|)#4B^gATk| z`uD$_{b+M#e_W9#PZ5-cmUN`a`VQcO`r~G0f^p!rpJZmn)p?lpuIc!~k7LZ&oJU)C z0VJAbR%e|KX z^U9EECK$MMZ+dRSTF{PMl4Ey6Y>5Z5hEpUThk==g>RtO$PR|G(3tU|B_%`Rv z?eaxZLs;{7=8epOQN31yw8f58XE5_glmZ(ncpyV$0KLqZLi<{^=(EP9G~P{#cISGwXa zGim%$V7j?O#!{i=Z)&PQ)#dpm%|{zV0SUYyh!olN!=GacSU)J+bcfCLUC&hl`~2wx zN`F*px)OnT`7+_LZfRrogtp=b$|~vKV81x?v_NV9oQsk?TnJtLMdhxR7b%z|uwz?d zz>p#~FtVFzWy`jzPh`)uct0C*{NO!aKnnh6G$d=>lZhnF8^8}SNh0NjJ8+r@j`hJ= z2xT5j_{-)@(}1jtU~z5*vCk&6557cQkyNtt?dP>Aaw!ug^p7)W1t~JdaJcSHpQxGb z&|ZoOULf8;s~31~>gHr%J)gnR!s4^(CY^&vQ#(WCZic0v^p;rv&TNH^mDFWqV@wrk zM6d{p(8&74{bSrv*C*YZft<8LU8MZLt645VX+g56l~f(2W9ASCCl2DPDnZ|l%CI|o ztzGW)?26?`J>M?#@Io3--k+QXYy?O7+)(c?n*{ojQ@6ccU0r|t7&XQns^d@+nc$)* zi3kpb%zQdMwdKuaMV6RYaDXP!%0!;iRF*3nTPmc3S9hZ8x~QzMZC#&qvIrQWroy#O z%@7*?<<8G=aA6SM;_){EBYFqf4R`K{S}L&eucoI4O4c)r1v-bG8x*k8N^u0XMuPdC zytzQf=8g_H&ww)Lrh})I6|_=zMFnu#-`Od&cWvQ;!N%v^oQL&{d8;pH8IutZB=~S6 zXO_9<9YV@+vBO*Hexj{7xu zyp!I?*@@U?rhli>ScpVVk8fJGQ>4<{G|&gyWLm@N1d7edv01vv_q89|mn+98BB9qQ zi3~*gWbqg4`@Mecv!S&pX7vlyS3GpPJ~_O8A?&tk_|3G zB2V=(O;Ug4#A1vP*nh4xAWE_gaxj!yxG^&evA+Vq87w8mv zD^mV7pV3(mBw?&5d+^^LcXV~-D3-MdnwRi^YgEU;TPXF>9ir??9~vhM1#ro(JG9;; zwbF>so-H3SKUODsH`eGg+NIMD)sQOvU9g!WPGaqwEK2ZmHZk`~+e_eSs`Wz<%18IO zR2GO=P4B3Cl-mVf|3hR%of%Vs#&1mv<+ITeYRKB%YE=YKXM{uG%XRo}5f`a$O;&j^neFB^p zwf`+~R0vbLNEW9+|g=<(OlW?R$7`xEzNgoc{D*bH`AjwML zhR%0AeHM)`n|4+nlT?+qUf|+r8Cf+qPYkZ5xyACfly5 zLG!J>zu)dJNYA?0eO>2y96@X`G34%p`?Q6%R{_4hzTV#6K0Y5uBB)C zn@88>^qF`fOeKZt#pVu>`P5X{i2$K)MPxnUVEwY(w!TTFo~GT-I0?H^iBZT)1qd$z ze_uC%O~Zb`&t2Yq|K~a0eZIKj$R1@i4Vqv@)mkAE?`S56Ch4(`sV|qxP`7}8w1IYb znv0*kNUO@20%4P}&H!#s_@(TZWHUd-=FuH~B`eh3aREcbj;s zXm7nki)$Yg#a0sULG&${T^~q;Xcns>IkxA@C@CWznp#94*8i=%`K0l6sx8)^`mFdO zmnos(*fL0N${{2Nt>k6#(TA4ZTC#Z{re9+)iSn>sK3MYCV@3lKnE2spfb+e6?%)i5 zoxB$i(S*pou9r=#g~yp^eMmT2=~qXmDR~qh@Lym4;2jq`K6_P5%G5go7+z~7fsRPc zinr`c0$*%-tgWQu;?W*#xq243Uwr$0`x|WL>QRwa%`nI@Fq=k}QqLP^XQYn{^!=+8fe7C}D0*Y2yo0_W3hM760 z!WdP!Y7EJ4`j0k$sDx6oonuD#pOL12)Oj4tZrEI}S**<9&p&?*BbZif!K=VRs6eI| zwa_TG{^eV_Md*q>L`P}RgSTXT`Od_P0=Y^z$dzM8WyMoU-~T=Bvs{vFuP zi=4)NSy1j?uT{=Wz6tYZk^ZA9$VsM`$u;6Bp$_;4sc;>z9KA}D(Mu`Ic}z`fF6jC9 zq^r+{a$A8YmloT3M8oW!?my=WBv{4>Z|Oi~GU3nh|FqP_WsqJ4iqK+;XK}PLwMHaB zarA@F&u-cakP5)&sk^i1)67=-m708Jkb?_;dc~=;1eysCS&PTMJ-1a|$bCu*@4J7> zsVhG*npw#}g4z@YY9+MA{SG4^8kTDQkvo=xqidSOe{f|lICc_XL@^j?&#GeJJ#>!QeSW^yj;Ba3Sex{;WkD8>C_CZ4ypv#k-A18|68i4;#{zVpO zSA1c_xYLMyA;!|_O5={yPs=ROKor_3#~@rJzMAE$(_@ayjDR0hwMU<S%yc>lhtzE z_xgVl8j@b*8^^kiEkH5$4YNQf;jpDc)luOS!q zk@NY@zxGC05UF@s?iXteQqHefsIv8%2bVknswt@Lpd5iGIiAhc!u!J_N*PIRAz zBkH1pGy&}Re|kaaP)7Ct?%|q!`?_KlwSoA|5ccNV#hUJf|LSfYW!ImfIDFQj5x{B= zu*BU3`Z&!_6B#LjOJ|x?L_j1_3dQD5m^3$>(d~*K)g#8SmK*ay){3jH#h_BGsUn8i zLac7q+40*HSN&w$ngx3-CS@AxSPa{V`IwO@y|Nw5d{hP)0$j-Aq8a~%xF>JQs$7G*?9eOqQQ-ub(%^kGzUJrP>K!}zmC}A|FGkj8Y`2SI zB>8XJI&_`cv!-B7{Yn>wZV8nb-4#b&maRncZW(YJZ<;FS_5%5Z{vUmQLYT08xHk&~ zMO@He1O4YSa|QOT#GMAMM|{Q&{CGUWz|2k-vf6BikVNWd;3=LXJ)a)t2X=BDTP1%k z!IwInJrr|Ogjw!LS+)i@{mHn%l#X-5S2u7;zp)HD(1TYe;zckby!xZma(LQ`orar zeeio{=&FxcF>(4l^r{EesqI3OQ%;WnA0I^f;~h}MYSxkmF5J#uUY+~*l82ZPm~X#+ zT{nJpaso#0iPRi;Mr|st{GMZ!>ho|Fq+4}31SJ^x*gpOTHRR?Ub*NHe;ef@< z5H|@6LF0%hE*#@zb3EwpMv#kQy9dt>o__2C($+`0bgq}%T= z+TN;;j%j|W6gq#&@9Mu5coyCm%W0-gq#v`fImJV8v}iu2+0b%~Uqw*DycK+oY?E6* zi>@W+MBx8!9hlY>o8;gY7FNRKTQ~yCvG*cJYJ#I_tw{yw=_lPLSUJK#`6RM|II=o+ zGghlG;61Q6wFHL7YRZb2%?@D8#gS8%8Vsfg2uv&gLlEYeC$=-ATPp*lu42SQI z9nXxuB*Z$|ObpPkVCCsws{iK)HUfgdUEy6u5isW}eJ9^z=XDDZh2uVaPwdddFr4Kd zoIK^R>nPS#X@7>l-jY=|s%u1&2-2M)J=<9R!M!SdJ6UZzihnplEz!pc+q0jq-A*}; z$0gG(S(4wgQpw*cJ#gG$XBw@5qJmAOW?dFEjKCN>du_;G{qZ>k>%%x89&7GhMyO0b zbX6d=vmaKTf#yX7x`sro{Tmp>_T|M_xKGaYMQ5Z>4m>Sdj-Z8hAmsOU1EkG?cAOTy zr|P{UW>U2px_cP+CRg}A*(Vfx2QhU`_iEu}k1!3V6G1Y3db z+<>#O@C4;^+dq(s_~#3?7{e)&W8UP8+9la(zs#Y0a59zV-ocT94J*c_+w6sqARBru z7gtvf!h|~Mm1upa++X-Rl=?o?+R22eacM4BeHAoSZA{3ne%u&A4n<(bVJ3VKzd+Kv zlZChmpW`s!LGO^7TmCTa-Ek&+%3|a~ZYQqhjCc~v$SmS=gEVo?LyY3ZbmP~3ZJ2d> zp1Bd&nK3$&u#9@KrE;x~EuJeCiF{Xo!}3{ujl`AtPmU{xQ39ydT$Rwjdw&60m~U+r2cb1D9G7)@&0Gd zQse=7z!`wu1d^rGQN2N}Qx4dZW;UDJH{6+!a>PRz*x3HET|8_eH5o22Q@tG)}hl8N3c+fApGa)?drjJeX z95iZ9uIly6KN-q23EaA_o@h*9Gg)5@MqTJ_>KA&XS^C+pK3_hr|7gz7`fjZ$3@cy? zd<4KHtV${R1eWstq3XujPX3`CEsfhkM9k%%ds&bNX z*(dtWF^l(8l)I~Tv4D*{O+t=J88hih*breKI%-?3nKaqs_2qJ9*mUuKa^;Enjz8cdbKuGaJq9>S-cC*|n{|gG*F?HE z%Yj8kJwRBnfBpS8a1b394hyCosWJkQ?vaFCX-lPNOq)-Vs7t;E0!rwRPeM!H3y;I* z=~iiaw(M@&1#!*Z?oRwaoB3!&k)X|Q0tJ(N(8+|Dk-e&mrVfR#Lm!Y)anDLY7g~&( zWMj0{e;IIf18_B*_$M<3^k89%^rHDY6E4a!)oM~K{bH{l&quHWPnY=gEG(Ec@siwV z9o<6382C)3Mr_1%0OoLfcXou*pwD`$v0ZB34xxY6szs(JOXb2FNrW;kgZc><7%DdD zYx5R;CB8%@L}lE0_0nJCB# zkL{2`QZJZc5f;o$r*-_O+spp;?k`fLQYmGG7YVr|Z{Vs%kpW~TRVu%E zCLs$__$equk!W~5@V44&UG23LH6rQa`Y&LKw10iVbZ+{_)WF)LTl= zs&UKOwPm4=wCDwDr-$2RGCdMuby~-Q!ytNOR5wlHbri^lRqP_N`7T-i){_~09Uzzo z9|kF*ZmxUw&(wbQ7E4lNR_mfhpS~J%=LPpQ0O_aLU8-FwDub?;zEUindVbhao{#HF zvBykAmLwpd*|2XHo6E1`rAuk|#dCgI7BJt~48c{yo+mx^uf?^ilcqE)>W zn+t3`W&M)6EBQ~eB84Uy&R$O^c3=suS)zI*RrjCQ?;wT&#CZX6%Em1p%)ARj6u&f7 zKVWR@?p_wsl}5eSAKuwAeH@t`@F-5)#gCbztk#Z<+*74&%QyiKBlGz$@RUiy)nUIQ z2}=~9`~jF^CiJ60Snm(|pM&>gl!E`76buH776HO1bdPy(6%uZtx!OGCR=B}i$PU5p z<^yFQc@O)ekj|lU7eA<*Wtfq^Zsn5g>twX1??rM>`Gi^x+LpDJ!jAulQ)G3_#9(4L zh-EM8WhF&kD|wB25F|WZwzE3+G}KUyPwy_R9{%rFy}lQ*diJThacRpT6EW@x|IQyd@9J`3ZWziAgwP}^S2uI-<{|e2t zKf=V=_9LsyHDDgJ>E38FOgb(eEGz6P1$dz|zNvk>6VnqZ z_jk8w4Hnv7?eyso^UP9nF1#L%W~2)SWm36R;vZZtTH%Q)kjv62W1^uS%JixQv->(B2sbD3}+CMC0 znw>}D5{;g2Ca^HK7-V0~NoNIKHlEnlNP13fLvj<%g_uMdk~nC7Uex8E+e7R<)F@6> zZYgqEc7%A}v=TXqgX2ZT2{GdYEy7n8K}ocN$4O9(vt%~(f$mmcAk2V#;|A3y@I6d> z2uL|9q?nXTmkacOIG90nDIZ#lc4!mjKD=Q4Y3Z#9<==$Jlt;{qx*Atb;n65Zy?m981KVPM5L78*ExY6I)Su8E%*dieNYbA!^AZ_GpAm1un zzpp6y^H!@(*l@7n;3Cx|;hx*>>TpAWy_Eb1-oVGjw0m8(axf{*|iDtEe1pwsLtLKoLB>1>(uJ z>$P9d>O_ZQZ`{+B=gPiWq%qBL*W#rQm9ALEYLvfqqz}E?5l+PM-H>Q1=uWupzN!`X z&>)fSZDmhiAwX=8_;nj18RptQn9%;W943T6_)0;ple?kcws?^7JK6rHA+&{53!=kT z`6+6(>hRY5lZ*o|V!$Uvb-aFIEV-qUqN}+;Hb&@yc=0&6PL&G6hBnO$YpJ_)`#bWF zDYb`^G6*(R@UCXz@FNl~W3V zlWSq_YyYz1LtcN>JOq8wIHH3Cj$nfiI-t=l#)?k<3pKwu6%y3$cpMLkN<7!cmBH9v zcB`>}t7*!;;~5YDy+<5z!)JS0z}&v1!XHbFU^||-gTMqTDRhVz^-LoUwZZ? z`zY_6PC<2ZfUEseZ3NO%nXvd32xqoSvv6*-L{6wg)GvP$uXviW6)27Cr7EP|74e)5 ziFDoMd(so*!i24UTTOWb1{oI@2!!vJ9FX4i;4Afcms%|9k$(%1%9a#-^+ayfmKm zVQZ?iCfcG4TcI~Erj_~SXi8;DqC!y9*q5fG&<=M_qbJ%1m?7GNEZ z5Vcs|iSNnV2wVVhvvqq>$}Ly8+0>rUTZWDWO1g0j@%7}*5WcaUD7U7rz|Cs zuF(`y^4Ea$G|aa=re_3=6S>^ENaSm1YCGY7Na@KlZiI}d79LsH;nPN!O#R2@tE1@# zu0Q2QCduhzi}SWDnlr)^5i60QN--Mm2s*0lmj0?ou2YczPRq9>mb-E~L7}P^wW+D@ zK=`iJ*CGle%N*}mnQgc@3&nXAEK1;Ac3SkX>)2pGi{O=j&HwTt)vVQr! zpOYhLW@&3U+TOl8YnbG8bysqmyL?a1FBAHPN`#c+Zndu8J!p+bX>HE-P$YRqK$I zLXwet&}^)VMN~RSj0kR#)=|&Ksv)T!g~rJP7ccw`WvBJKm^{}X%93L8O3+W{atH)3 z!!>sSX+w>gf>HA^Vs-TaWWOkC01?&w&wsy78Rvpm`(TyxZVRLtK!9o?l1TOa*2mcy zf=uB*{&|xMC&%BAM&fRoY>>11F3{Zdsp1a95J-rG(WwY*Y1W}N2BDDh)}8cKi!Hxgd3L;Qx!)N0+=-5XWohe>WUAZ;vp?-pYp`7n0 z5&~AJ5`%m6nP1Ar7D7pIRvKd_j9TFsqg`uZtEUyt=FtHs!XlqK+7!EL0u>W{wwkrY zJRm39eo1GSY&hs~ENnaD>V;0=c!X$i@l-wY z=CEHOkM_8ZZ`$$UZ;jROs@Iw#|HRl7Hg9v)_%^MTFC;2RHlz!DQUMtr+R-KgB-x4P z3u!s+MCGE~BI)p76+$t6bE06$9Ha)MUW1sTz~NV=@8@|2N>G0GoQ}q#Sc5jZ0!_&g zgXkmLf9~P>e~C@w_P-39LJZ2cmf<{mdJ%w6yes8RS_+uMl{lmzMLtf_m=v%PT7_f; z0M3bs-y47p=Os)49u}_D#mD|gdU4-1E;|*>qw-PBCTTLBl*08dSLUhczDfmyGYmh4 zaMLXm)T50gEG@I!Y9>h*B*LxT7>+6)u>VhAD4ejqLFqxwAcydFtxqh z;+51cuJ*HW2>s?fiR+8GacAJ&0~5in^6ohL;&+(v4IOx?nO$-EVyAZ)H*%US4q$Ic zrh&`C{3z*_#A{`#It$`6gBIWwmesGspAWaT(s@a#0&)GYoQ8QPd(x8ghkFhfy@eBj zhP7Dz#Wwj(TMv(n$iix~-rdZ`%DE=5?`z2T@{?0siPCcX=~O+2xWR*yKgSlUCFt|t zrPD>cbFMKDxFBLXZ*Lv%g6}??`Zuk3D9X8C8rUlV1h3_XOFh|7T|$h*AfzA0N%(QF>4wgn%tgu$`Q7EdLo zcnKQAVRPzB0?yQQ0)Em8ji-l)hlK_7K_n3rNtl%wE6|Dm0?YLfMaf5-55*&19=`1` zlO;r|j|a_YyQaI(z{ zhTUn6@4%4sGKLh^k-8C={RHu1E+Sh0=?Ud#`M)f{g$sb#s?+V(lEPIpa)lrmtFxED zNN%vubydi^bMU?Woy3on=^=4j8HDWvYXD)JQ7;}kp)MW&?jPn?{5A@hBBPF~z~ojh{#36Dt(Z!Y!;BP*x`wOpU= z?{2&Vzax1P!*F#h*8fy($5k*lj-MQ6ah|K0VDL_@I~#R|*vKt&h$@NXX%6oqX3H5( zqs*GJ7YZ{6>G#GoJqP(VWj~n?)f0s>LN)(Gz>!8-n_@qLbF1{rL%=m#KU2TUvHg~~ zD;{|CSG?BAYIu-{`J=@_W@1vVr_%!UGco;()Pjq_gX7XzGR2p%7n0|L;?arAg@k3s zmAMS{mvRI8Qv@0By~?AlROP!L8#?1+PLmYJF7QKtdvh&QDm*JnKrp>qnE(2a>n|4kqf5YbV76y}eftdUc%?sfoSoIirUSN&I zk>gMA4(qV-KW6q!XVr?x2b{Kxbq#Uc_?$$uJM(Ebu$xJVC z;`q>c(jY*6WSB$JUL5)x0Ev$5>De~JLPWvjgpHBf5xUG)r^`klPdq~&TWMLpoyuJb ziqeF;|00@B)NtOAu$69l(x&jiG*B6?r)tj<=7($~p~qfZ1+J}cY-9x4aS=|60+|C< z6&1i&Uq*`eHa)G-xbX~=&N<_0`nv2Hc$~m%%a`_T=1O_D=u0fx^|H*t{bD1HwsRX9 z0!h}GL}|nU1+^(fW6pxru=o6S4mOc1L+x*U+Bzw*Ayvm$Hv$Z-Zmf@Zjak=lf2?Mb zC1&WQyko9-K=^Pry#vh<{>(-4I@2@#4ZM?YGj|4Mxtb8sf1u4j13QZ^r2c%|wk@OV=3>;!Nmv;`Fe}LUA7B>&F)- z(Y$<3mCOE%6092rxsUX@G)PP2^2j*SAf7M}O_#jNcye_%3fkr`fpL@M+{T=OOP+SC zeL|QH{9lx^CC)4vCbCn>eS)VG4hT14cZ^kp?O7^}i!UK@j*~s&xnC?t>(Z4J6_qDY zz;Dfc|27cj(^s?2J`rT`tkI8aYqA-^sd`|4e(3A+WX;cG<>2~SA*O$)47Atli~Xg1 zKtjJj1)dlD3<~(hu&8RTy&g+bfg370eq5Kz{X`F_ddd7B#QTj!g@l0dn71qNm`D=& zbiK1bpkj7X@motveLCuz(s0Kk@+y&)jm4Vq~bgHtRFx*Q&Zuq1twMU)MPAM9_*_mRk zD@$v(KB&H6d1t;=ZAB_DmKWriL}zROYP9$c9W<1%jB@OOlLS-et7{@bDKtsd$+yg^=wz$7Z?^u+lG8XvIp$hxj3`i zKuKLDrBc_8Y@STKcp(+oF7T9>je zQ$_Y`KqzJ3jv-$T#_8HpI}3qrX5^&k=XX$+jBCCM^<_sC6)rNGe-_b2+0<~sQ-f-l=9T%BUQW%-Mhdn>ZZQjy1b+}68KJN8$5?)p4HqS7x4P+B{Yo&oo6CIabM=P zTzXN1)L<+dUz5viHd?W9Lw@yqVt25?{C*l3QKkxxt$s77zreL z_j{ z`cq4tP1s4CcYYF@h%&p3e-69^+!-z8_fUvl`!=kPVS4}?Be zdlBX7)Wz{v?thkZX%6r0eCywJ(p0UfcXKsw3CYJnBU$)CSy-+~51%(WQ!I9_R~Uv* zGI#mm$ZtPw%Smt$wwE~4uQhr8SSNE_4x4xB!2VPHEKaTJ;kFHqw|{Y3Co##2RGz;m z+l{9?q|Sf?MCyWh6(D$J`6EWGJgBle&S39r!Lx}gWop<*OXDO<#UkukW;;vsJo2Ij zb0z&^0s+j|Sqrw*4>VVdc#W$7qf9^~_96zyQOvDZ!)GVar_;i$}Sq zlqq1s-Ew!{1+j^bG>JA%zH$XP*vW$auqOovlY7ix8ik4+^m*2=Ii9{R#ny>gbY*1V zw)iBg6=It0qow8axOwbGek!UIa}ta90o1ylzzY~AZ`APcj#ZTk$A_`>w50sqloqB8 zke|%O-$o&!`jyQQIwk2)KFlw_FJ@z7147nP#6ZR{N1D|uvv6Xt9V#L5wpk+t9oeQ; zUcquI!&I%`$z?F$P(e^^bHcZKWigy>G zoT{wS*pQVtViQI0k5=7?rfjehv@S+}~(O@C(PmjbfACyZir*Yq(U)~N10BDFWJ;4tD_ z_Opsh!7ayJ0P+{MT;`4CqQYL1*8&Dm;n4u2Pyh$PjR8Rtx;_6J6K$4fikoP8a+vYq zG*Z-Qrr#?=JI71uBpKHA6nExnYh|RlHYbY;5;B282^ZhIdLB*H_zr?L$ADO?KP9qE z56$JGy;8%4wlEY!N9CJ06Vl{qY`4IVmxUUT@{1fa7j%f06Vjm)X&#wB_vN{j9wj<0 zPi`C014SkWIu2=Om->>d1hiROYv^BwDgZ|WK z+x?A547(@ijbn_G2UTjY6U%SMPR+ea;%&M)UOpOUcxy z%a;Gx%b?*1GkwslKeh=A2(1$=*(LN_Vz@Xf~36 z9Gh~NT!a~y4Mj%)L5vY@N`|6vct0*M?Xn6ag^$1yHt{I6!LDBC@qb*D;VQ;yc2;ngBb0Pl; zx#)NZs+qr2)+QgiU2sv!ujRp<-D&0h1^t9D*)NJ3=nTw}GifbRmhcxt1i5n7?G%#4r6wbAdh|kWk~ud9Wdk%4=JO zJ8rfgW!2Bs))Y|mRhqn4^9D-wQi+%DS9}Nr)fY?eQvBQvZ9uKqGr;OUOM|`NC|_Bm zTYPdAA2ThS6ovj4wj^0u*_JK$PePPymUv{%RC9<)(!yh)UXwLRvvJJhnDZgP?js8= zHN}*OtU%~-BIZfdwGNg)#|g7_ipCi_&wa)sAV)zp$9>C3E#zamPkz2R_{;w%oHs?9 zyFf*{=TuTJDE15)b2?aY5K8`+K3x}7LC4wBrN*o{r9W|=in*3OjvDT6w;TKri7VsT zqJ7|P%(k@RFWd~yYgv@lUInGh@ka3wEkWetRUFB@HHzVcqHdVh`YDa*v@z5}ooC@Y z(w=vsUkQ5ypV93^W)u0EpIUf0<8eInQDQ~bO+0TUprhifI$D(+Z}R6iR_14d@7r-p3xvhrO3XczbZ)9@AQ z%pY~l%w-N|q*1Eu7p3J@xzimk`~(?MB63i=Aq<#J0 zxD-=7-;^OJneA@qka+aGs&6@rT19C{VT96$G^yFSoh1tvYk$CvIPh>T(4C=GzqMF8 zC%fgH_*CO2k@}Q);yZHl@#E3}gKb&RhE0`9&Ah?o_fa5EINoX_vF4bxv~+o< z`W7NAWT~$Ac$WR_ZkCL7ByU}FK5mId3mc#Rd#~RwiA+>PK!9N;)hteTqp_}zn3NO^ zE^Nxub<~&)|CrLtx53G23NjO-F}W!l{g?a-H88+mJUu!4Pb0+O@C3*0Rd(HP%D#^8 zzC4WsPP7J1xQccVU zvn?2?R#NVKomNQ8Vws+@w)vY}3+TP7o0635BG)j<`rF#V`w72OOV93C zeOv4{ZNbopEju2z4;i15iG((9p)+SJ7#`M;w`vC&>*|`OoOeN^<~e*h=|U9Q#>@d% z@<${P8fa&UiXDxw7h?lprl!u$2^7uV7H55WniW;$%qrZ0GSWRY6O<_EGF3Nl4KgzF z_E_ur*FS!FX}`rlSxb_p+VI5ou}Y>~4s9f8 zWc1>Yb}x7Lww9Jq1)Ncu%5L!%#+lTArv&LX4V)T6#||zd<@C#{d5Q3E=5`{E@C&9m6Vn&1AbkKUC@*wR8-5hQjY!(KsK)%AyXHTn;16@3^N( zXqwz;g^#}|73PoS^JE+wwqVl?*}EU5ws~*Z?J1woV)2uZ(A9I4IKKpM*J3yD_wqX? zB_{GIGwr!v#ql$&GIz=SiES^9ECevsCp?ju_hB5KnK{ncO#Iw=Hy4I}87GD{q5LHw zIPPKf@T<0JxPEJ2hnX<%y4e_;@X-shgKtSr?+OIH@*mAzM||l zWkeJbuN@V44w8S*eCit-cnDF^^#0ycBxP&6D%vd%VfS&z24=8!qEMuZ>f}O38W!>e z{6}kOH&p72zn-z}Xpcb@nA$3Y)V@l0_M8}tAE0>%S8_2Qp;&C&)iG@(aZsQ)E#aC@VQy`)>>`d3CJtj47@| zs$5}DP_DDWvOMRZR!}AhIMK<{pE5_4$Iee>4*#^kiq<8fDn^H$v0J;naIw>rSH4|W zxkVq8F-KWw0)GzKPrr0UF5&juT8&maXNDDsAlLk3nBP$;rZXQ=>3Mq}TtzDP>awws z5oRax`8~C`loUfIXG2ho7htS3mZr~YSClMnH2pT;$)R_?QgC140p%6hGe6eZb<|43 zAtyltmRmwTars};*gzW(wj1Peltp7$3kPoz4n7Uu)CP#_THAq09OCY2T!&}bG3jLU zvhQn;4jqqrpNy#5DCT*wj|@Pl7V-uD9KkWwhDl4dTzPX&a@|MWk^={I3jdaHLir=7 zw8$rLr~F#R)1%rrbm<{za(A#Dw=-Z6+;=UKa61$ zPqZiNARa+gz-DcL4m32=97(<(J$kG7zr7{$S6 zeoC3wf$L8!y^GFgnI=E}WQ2$y?wAHgVE<8;tB&6^FfoyJxiLCL_d)W$=0h46TQQoH z9qo~rfZ3~D%y5I@?(E%kw8fn+0Zxp2HFZth28>avhRP+|rXF(m=7TMS$hy@{sDzSQ zpb>dZUU)%&xnahM#Q^I}(VzMgnu#X)cK5*+%rk-lBVWP6TabXfgkqmj01-zJ(YXi> z*|hw7G&2m_f+Ul6O{=A_#r!U>;no+~*-^meKPTsQM20L`?*@*~45i59&EB%=CfnXi zyk2iU;=7w0?B=RfkX7{a<>aIg!{SQd-`cmL*SP-b6em^?@gq!w%7e$zt>+?f9&i_ z2JkDlu8}Cp>;N#C)@P2ezL6=n1+_~1ncMkg5rfl4&99~7(>1WXIf=4nBIsjMP7W>nm)iRaG%=sZs|D4 zMw)V+&U$=UDTy?p+Cz^2%q}mK?zQIw_{`kg;KGJC;sj6Xh!OK;Qu~C!B>JqmaQCB! zy-x5k40aBxF=)TOR~v@g@cbu#nZI5$^^tY!fW`V8ZNNZt+8{p|l+d$mBw{o64h9oy zJ$e2ooow}W>j582;dkZEtBBV#X*hFosh&%siOLLjauAPHYj zsYH$B*Vpf}xElK>JJp`#*Oo%XJQr=b=$D}o*ZGA7;H*XCn?E`%SRyMS=tFeay?%wj zJn_P?e3zxrI%I(Mdn}zWA6MII9hKIgPmN)Qhll60>e7z;7}M_e%hwJMO8x~U@8+Y% z!H?-{lsLySlS;}8(O=Bw*S+g>ECRQBv4JzTAsHJ7w5Y+zTR;F89J`9GlF2UEN3V|gkeYaBX~L)0J6UC$08fW-Oi-!LAVg{!_;O>d zJP1}kjk!cV?-rK7V6+wFt>Kt2}wOo?DJ)s|#V|&qWcOGPULzlU#}734!)Y>1fgr zCHyqqQ+)O5+dx~DxqHCY#{KLS&i?KY@f0#72R&pa%3N>`GKvhy`S71?^sl7J2Ma1&E^$V%enko zy5{ZH3%TT;ev(ir@!?x5>(2Szh=V>xnC-9q%%;!WFz_C#Qxw}`0kxK&|$*0mU)zi zQ}f5IJk#@U-Ut$s)AUkCs))zM;J!J8|1cQ-_3;w)c^(w_{&4u~ z*RSv2zlXu2?*#&%`u#vZEZso*N*$h(L-CVBN1Jmu0XomaMMY&_HS4^?Sz$? zqtDsl72w*-BZrY16S$zo=`5(PR#vA8yn6?NSUPEC-+NPnLy@295G(yQUOd_`1uNA0U=A~TpffbdK^=bR3S>S6lydy*CHfEHOW~{af&VDIo(Xm2fJA8 z&j-)yG%1~yS?6G$oUXmqdAZA1N(#}lc6LmS;w zxQ4gwddQOOO4>HIqTM&m7M`&D`i;_5a2E| zyV5@8Q}m!k&q8BOw3~0l)mJ%aKU)@{F$kWzRLRp?5q)MMQX&4^Ha3~l{iLAD252|Iu^~T$#0R8_%9>+qNg$wynvoi4!N=wr%Uq zm^|5bQ%yDRe%`hI-(au1_P(z3Jn-wA`ON?iA={?xt1+ZQJ$P1@0v1tgE?N!6veezO zZ&#xnyyl}cIn^nnmt4|qXX%jR=qU_+-G0>WOZ61>K3D+LayW`8gXZk^sfzY&^wOh} zgeLc&3;9u^X*hNY&f?bUQ|%O?xEi3&(_!}H!w3s)M>oZ$NVfH*&w5RUx&{B!I)iSbT?#j|3H=3ydJE*6TV0j2ew^57fo_C566^SKBQ z+%n)1NrquzQc_%UdJg6t)W%% zFQ>FT4G~D|m>fI7!EWQ_{y^=iz&rpASxXk1BRC-4)Sze>F5RyGxVTd|U2dBX3e z_s>KAzZ^sg$l?TjL&Fcinw>E0e1wd&pT}W=su9xB*wtm%HYi{NAAyx6B8xng>~`Xc z{$s$?)W-)8JC!d1*S-|nFPYTUY|sFM3d)|2QOc0j{4rX0PV2nfB}NL*I~fa zD1F10tZ?UBKySt2CW;@|8?yJ5Jwfp(cb_1?e0}$X*xA2Ps;(iN8L<`w2TNKsQ!~o$ zGkJt2x;g5DQA*95<~|fp-USmYm&)VX)n?7+(ocS$00buW#=1V1Cjq5X^?gP50cecA zr0VdGFUWwD!nj3HzZmxVdKq^2)0;n#$TDO5iwnX~95ddwBdowJG~fc0Gb_Fq$|Y|C z)*?cg#1`#OS6-SLUi?I@IG4IIFuulJ# zqjlL0hmux8ik70&a?fA6AeiV@q#7-`=%1zo>$dKxVda(ToV#Q`Q4L<8dEw^sTeiXx zS6~Q}TlC4vWE>=7{sG1+WR z7PLflE;au;wb$4G>Dunx-)?`bWTDdEn*aFti)hHi!eTxjS1tMWjyEd!>&S!VOI0L% zne7j2VQX(Ww*-y3bpyFj{pJYD&o!O|{9IwK*kBcrLGwb8gxgIBZWsKY~{^KzmrKt9+EbJXFV>=$)*k>84-*b!KPlS4FOs%0`wW%AWgm zmtwx1YSg&Svo?kjJh4aY3o0>}Eq5O8%~)t=JdEbFYN1jQ8X|Y%eS4V0X&xUmyGJEn zfh%EE&P>gt#CG_%NObHjL7P5dUI-P4m|*DQg?r&a6Twprn3|jl$b;^vu$2?e?Wla7oH}yn#y%YKm(k3yL9H^d6WiQcau$*fBvfM z=RQC?UrvbSuDa#bjCd@vOb`JgEi8GnqvFc%03W*o<-)OU5L&!}Q$WDhx~u^Z3p-eE z^o3vLdqR(kBCjWGv1_JO4WuEf_yA>Qh;fHGY25(xDsV4pF!@-rSL7r33X+XDM#PjF z*MeQD0{?;Y#+q69wEmBy z1__cSY)+P9~Wc+kdm3$4>JYDs~_h{jOC| zLSMfW%w$HwN(&gna7!Vl4vBCcKpFd54m!hS&F`+%C~_o!yst@_GsH*Wz&JvR@$N{! z#&(TI<($VRnJ|;|Lj;RzpG=|qEMjk5)f+cOHtT7qLksjtcHHrMr{|iTXx_7*K=aV_ zG9LOKw!cnswC$q11^@&Z zi;)}E0&PpwKdN0K3^|)1KsR!_LN3#ptuYJJ%&_CuBx3YGh%7%Ha@U7zr91N3O45gGJJo${4=yw}i2|?GDjXdhH9M%dFjv z{*E3ozn~v_`cjy>x%!U<()gp?C?H|ykF*#={kp@@%0l|A`#j!rn!ao|?a;N{n4H#` zEViPY&&JD9_bbrHYQ3b!&v~~zIwo4#o;O z%q*E`SAwBaH&8yWtSDWsuU#S(;ln*@N)LrKoFzLEESF{=#>)L%>g{Y!=5T>>^uvzO@r;QJr@=E-+4uj3?N{k0juu-sR`+)iy(2b z$U~`)e1pmP6aQw~{9%)Z8TE%;J~Di0YAE~CBxa$$D}&2^qgn2Cn3iNm7+l@T_~4NX z&0ULAtDf`6gcBdK@aM}xj?VajdF7_{G4q*3Hl|gg`!$pNsF_Hg=j@jXq)Nu1Bo)k$|}=bWzf5*Jn~()`j~@n zj}0fZqyKR_1-oo6C~-#VhoJPy!=%%0Nr8B%Eg}iHS?LXUypA#SdJ6nkD#)QQX?4nB z%zyhKbCn^BbI`jAtPX4&Z*o(tS`Z^{D;cbo+;mub2mu?*^Xj_NwTxZ>^ghQpf^rgZ z_Epez|CHoK^tE6e&BR(lsYsX23+>*W_2x*p;|oSjSSQRA!ET22crEMFgss!1G_>(! zg!dzWaQLuUbFr!Un*}B_XpE;K-UgzCdaQDg>M8{K5mi{Y@~LfQpLuo+6<&e#H7{Xc zrT)d$#ik#;GvlnWlk!i9=*~7n=6(}jSDeRQSJUPy-S#rh=YQy*X>d8ErH@9;V1eW} z#gnNQqTjQI%UnH0VH9AU5->BZ2r{8-p=@~Fe|Mh66fqUs!RYHYl};!vQA~^2O&M&I z&HgZ8rEPd9pf&0IdS9FKMCqC?#PsWEgonayNO@&JqP%5^jCueGpn5<;CD?CJyx+ro>6KU)K?^lB0n$BYzEr+F2Q?Nyixzh`tKk1gtSl%&(F{FJPCZialgBF z8~%112m&x;Xg`5_F?|9Z1u3<$TqoYngr+FJj9hwZ)l7xE&19oQjXoS#@q)}(v~&Iy z$GjL@+G4uw9-BKHjLDk%q(G|R(Xo-#NGScbF0sfSt^u=Gj_4ipQrARQ`=tHP5?6ylhDSDCJ8h5Zb9wQc!j8B}VY)xnL*7%Ai(~Z5flU(jovynsY2fS5mme4)0Gs?+}Cw zSI%rxZbK^tY_~p-dleB>QtqUKGS9WqC=(!9mTs9zA5@YFEQsld6Oz`-aa9|^`QlA# z(cMnr8wYd_$0{QEy`2|AXg#2o>laAb@6A<0OtP=4oh8rl5;yb zsVJrH?1R)J`gpJ|r;TD@U{tUOrer^o5$5+~kB!tI-s6o$85UdJse@?}42x5?+;t&~^)?`xV!D1RoQDi5@sH2h zg&n&|QrW)I31tg2)f_#FQ2j!98zs5d8gMtO zMh@j)LA3K*dMEzMA}ZHzMLamji;k!@S7o=wF>0lB5GP{& zw4=$6?x~!O+NV`}{!fR}6wT5u4yUa45JQk!OBK#JR)~U;P-=;0!Zk`*fkpq{jQ1@C zQPPaq@q;_>-#33iYm17qbw!<4k|VWjIq-@w`u~JxygF2i!ultwe6J=IWG)VoCGrddW0|n%I)a(_PA4DVlfb9Vt1eo)5(_HV*2#s2@MD?R&3YU1R!A%CC@zUiMMO2MeqwV%a`%G%5KS{vWRAtISWp z1$3{%#2)sjpwNmxx9WloCw$35UfeGA7?L=0cjFM*2m!JZ=W%8pDo82FedAZL zhz_$+i`Oj*{9^{U4l#KItoY!yidN#Qc-wW(yGaOBo>R85Yj0cxAu4-!E=#@ldJ0e# zWyPqcn^+-VV)6|gohjF!Az;0bC}D(Jb(Pi*EnN*>9oi{9p#HIi+zBK2b^I{8jFCTC zoZ|$lIHt2c&Yx%NYhUEx0l3TGF0`O0gxx%M`$_BP4~T{}VxZz@>5LS2+AtAPrM5fz zmaJLKIK#Hzy0mWQ|3{k=V2-xgvdkQ9>Do2 zWW(2a_Fwx=sSh|8iYyZrGPn?d6CFHA*RSW$jbDkl^EcqS*bew(*frDSU8DN<<8yhu zy|Iz3J(3+@%{n?b46wQu#0o+f^X;xE>2<|cVmx-f)M&<9*Fq1Oon_CZ_q8x7hWOEw zDmW5t$V6K)h{q0_)S@)bBY8OhJ9HMH18HElq8GfO#}D_n$Y3#;mM+M!$yOZ=rOYqp zgYaBAfQNH`FC-iy87CJZk}&+DUf;l_`;yNOA0#Q)Pl+DqKY6?p%c1PYCCdCvwCWI- zjTj5r?Y*!nd!Fn!pPM1(TS}|9SN6C2q){{H5``{M&BLUk;#CR=P9X=@9k5pbBQbP?}g>2XGW)47( z!&S}~4sTs;*%F&Z{A|#jHZ%wOZiz=JuysXO2vb32?W!t8&YXhR=QSmS4m6bi&RfK#*>mzW-X21vP&EMTUjL_D@1Iv~hsUFBMx4{qK9mfLS_8{uE z4scj?A)2<-UrO%-bvlj@{C48gZ97hj16!n8#raEF(5B|m^yjTYI!RWvuEp~4YYs7MAdnT2)wVXFiHteCWi|T3!jiHr=cj>5Wohb@p1WN31&j!cf4xClefsDLF+k7C{lr@ygAVwgR|t^O6k+Gf{Om zYHDQJ%1g2opq}ROO2<-KG6GgbR;p*c8DbKWB?~#K4%H!H7VhRrqk6zkBb3G# z+|JI1*Pz^zVt7eG-O8a7b0E;L_yp*2s|pMnQhnYvFaApOdb5h#>AuVJ(Zzl9`b|jl~Xw_yhNx6SLHb<6HydVE=kWdBIXsd z-`&QN1rh#8M`XC8HE(A^eA0lwyp=aQFo&g-L;g? z`O6}`rH8EbgLiLubsq`X$}-BE5tz;;?T9)Oo<>qKg{0%X#hC9VFJ*GKmFDX)ZLB9fdct>}N?;0u6FRy?uLeuYW+u9lm#^X={4Fu-vK4k`N}_vruLD1eC3ukrK44`LEq8_n*A_vj{ zT7@EVhjc@qq)W(st+Xg6u(xbcGSm!F{Th_X8+`iEE}KlM)94mn`r1>Fwetk8ru1LB z$CK=%UoDnfHlEM~L}NdcLWw#fK+;*?*EQ8W$V=t>Ee2igzltJo2%gfH30xW<^WTl6 zD(YI0oA03oiQCfejr?IeqZ>}r6`3Xz%le+ddrt~v^}z}Cs8;s^^1mvvJUUnOqYaDuJs2-YZIBbAs#waue2JTSkI?n8bD3v%A=WhGqD z6rmy7fxeXC_)YP)j^?&@PyrD!Tv+56cMM#WzD~JAYe<&0J%SHWKrz4Cj2Qg^Y=j?= zOUjA6F7qXi+0zMiU?mH{vOFOBoAi&ecrLo=OPOtiYIQYs$IGNNGpTauyzJF$oaM?w zHCgs>+GdKnEJ*J^FClH_9No{C52{%X-Wq3+Q@uxD&gL8195LC}vY^xiShL1=t9UQ= zaHPCJHy(fA>WtJV99d%&X%n@|lSrS=&VUJ$(?Q2dQXxoIvo#WBS`;1W(~fCZ)QTsD zlp+l3W85g@-AmtwQe&1%X1tfuc7r+TCvW!5Jmv|dXn(6p7UY*6m^Fo0%Vq+{NBOc; zdULK%!VxLr09VV|=qy{-EH;nUkj0$KD2 z={PiqGlX&sy6FfwS7e%G{*biS&AdP6C~;Hs5mGDy$u(dxro%@ls%{jo1HX67nRN`| zp~^=Cn~gefJPxV=RD?~(&CYu|SCMQkzJ(IFY7H*LF^GuH#fILVp7-khHwK*4X`&fn zpqnyc9>~Mckw(6-`B9Hirv_nS$suxu-nPA@=B|tkroAb?O8>dp`PQm8rrYV441zjY z07jz?fnQ*J^l(mDV!q9uC)b^+v2Agz4*{n%7Z3YB&feaDn@IfkpiFk&*YCoF$N&$- z@vlkRAlJi>b81Gbi6}>MUHAseuoD}Z=pb)TEo6`J7}|-&#AuOk4+iHyxAbTfKr1e! zxe;|s=tvT0T4^ulX>kqOj9YGDow4%D0)a8@MbSX$4~ol5wX(N~QNwroK%dD`He6?_NYwI*TJfb@^0)*bK_DQE>wG$}2716%jKRP-BzVd@6CUkx$vqW(;1I9W8m+a3JgdetMmLkbp%ceL-11|3XfJ0)_m1%U}OYz_9&!CH#Q)%!!Vp7RaxbjNE(&= ztp{bqsDwDiZBE%njhN1;zw{+-6qL$Orp*cx$9HdCzrFFZR{L4FxVW(5&a0Xjuj%e} z2hnWY%G05GiL{sHV3^&e2v!Rq?dwWrfojd|%W1lP8S>!}&(u-rE4J~&5eb@kBItu; zAsGEazOskpEF?C&zcVAGJHW>%gPf`#aZGCtaq$8(OpK;K7_N?!f`?#K^V@%`c5_Mov~?hw@al6z3=-M8Zfp z6G)}(k~SEu2rKSE?9Zw3qeM;yO1@tM?=E$)AQPeyTBJo2Kk9HY-g6{D$Yvqe_sFiDGgk*7?c)QQ>-m@*RRk{hjX{h^Dm)ht~ z2#n>947dDl2S~~Q>U-n43gR-Y;>i{8KE0-%!Nxcb`8pc!uK#?EDO6qjWmrQzcf6zf zm~~Ut*<37hT;fCvtANX|&Xhr{-_*3E_?wqDb5v333-FuU!X?As5iS2vQRKVo+dof* zA&gSM*|Yqw7tILp8A zm-k7o7p-kmZ~~Fu1~jIXRRTGj0VEFSLpg@Q4nxdFtNy^T_!5&mXtbR3TJw zB06|Lq@uO=CI@`LVTo4F>rU+$Wz*(#H1v}sEmdE?eob#5Qj}ly*Ghp)fmE+?lc3bp zd1-r><5#d=)z)7poUyIeveQSwgsf|tuU=fGF=HZALaHfX)Oc=6}{UhO8dB$5BuI+dO( zi(cIEp<)Ed-_N(5Y!1GlBx400hE~d^F?v$WwdxmbU#8-}2O+OUcAgTC-orV`r;Hk8 zH{{2f2YeoYp&js)&6|IYJJPhOfz#-bS)3)14%0Ehp!a=$EB`*!KI_4J5|ZIFd{Do7 z0UmB4QM4TF(#NQG&r}{G!%u7Go|q$?hGARUnJa{QEvU=IG4-^pl?uWJ3!Hh)K;~{m z#-B(P9R+6AVL*<4^>sa2g?M5a<06N4zFj|w~tBNLM%b@J%w=+B>Dv?2#0 z?4;W{c;p0g!=s~(U&*RB(mM2H)=jILe`YqRcC<%Q@$omdr7XWl;;{}R1PkQ$UNDgt zxwhDP+GcN+NLGw8ebXGclKUsz9?$Qk4Iw&LKNpqk6RDZ(w)1mt8{>g(PUSNf4`9mc z7(2KA1E86_gp2Pc9QT&+yy(~&4GyitxhFOUE(Z@2Y;xOTP#lp|8>cerw#Q9@Il_A; z0;;?Fk`eeH3@FIRB4yr>z&kObAXU{$H8su2j-op!8r5q+ImfeZjqMP%Ti)=Cw4N%Y z_X~L*{zDEr;dI)iAajgL@mU&YBIUny1A;ihOCcxf(C@)0#^jbQHC7 z_*=@+0P1TGk{#*b0sf1@yxqz0BovyTC6?&ep5Inq-vfIBH#bcUHXhbShcw3zo4T|+ zZ$Vt7wDk1snPZ?h;W!?Uv)$Y{qFO3T3vRMQC%F1JZE&xIc5-WN*QV(QKuQ~+I}hOE z=OZ9L`$%0o&LzL+E>q4;Fjtns#~`S?{ES0nTFBB6)bR?Y%T|iYHd$xX)p5M$rR<5p zQEmRA%$08%Kiqf}d@PXd>^p(33}+0MCCmuV;91iN%DE&YX&bJ^9xS_ZpaAYb9mT|q(D)eN+3g3Fcos|-&4(}D5nXb*=4x#h$89Q7BDf**SEA|s2mg??A2PSh-hJuKQXE;CpD3Ym`9BN zHJ<*GN_Wyhsd%TcZ*cUnfVTHt7s~fYgsdUB2?-V9PCw&RANuvdq-?T?OIGm$4^gtO z&w$cSepv6VR_xy!eXr+qPXR*xMOZO=$OOxv|8ox54XP{&y&hlx<=sGsoh1NFC@}ZB$Sh4YiNk|cw zrq506t&Y&5q83VdYP!oFwD9Bjs%AuB_Q`A??Lpd}RZDLKjBe$wJ z+{0#0fDdC1{OX8kQ+oQ@#!El5bva_HH#_OCBgrUv!yU;dr{>8yhnW?d2bo7*X|?RB z&T!Gv4>h82R>WNDpmyIl!bT(jr~25&`7vu;)CjWF>H&&S!d05h{3%+g;lmW+F(B~! zDziQV_!IbfBPHuR#3AOHWv1pVm?9_EYz{*b8_oA;VJPo6Rk7ukvO%ZO2`aijX0*Aa zZX-44D3gxnEYyE4tw?N8hzQ2%NXXJ^t2%*qaFA;E?*RBiv3LHj1^y+fg#isi6u#Qg z;Z)w#SaB@09wKGgSLCkdSDTI%3Ag3d+Ln6hEoKpW4PlXU0IQrom)y!d`qx#OKVQ(3 zH07irI3af_&H}a*ueda#Foi#-M@B6UB(NMHt;V)$L<}?8+W? zq$JZyw3+JSYU@6FCmT3#!wF}^_lW7BKh%a-{-P)6VZ(i1bLh@T`=(_tp4_3{x>oqYez{>N_^Ygq3Lk=55D?SK5w5(y&e ze&pamI035sB+kvc+X($RV2XvVa$VjJZuuDD`DhrHd+<=0cyTqVaIf);!h zHF)$@y15k)5&y1^Mu`wYVUBgyyB(VWQR@{Td>*=YPBv<}w%+SVE{)@)lbcfI*XdVM zW3bM6qPB~5N=GA8-ej<43psZ)vi9tWaHp(Dp$J;?646C{fu{Z=Y;5m97tH5A275ks zNRT;l7{+cMmv3n|T087Id!R+0y(Q^MJAoFi-WG~ZzyE^-Skr}IGkXnSK>3M~qZyf- zYdJwM&w^u;k*`{J5Tuq|XVfL+{MdU@GS8xbuK7s9zjP#dQg_-%kp#lXX(8^i%s<$L3VO zY=@h$YR5Isl*s4=u$N?-al_gf<+yks2oFzG`&~QcFOMdHe%3^uGTSZ9DVh-USFhP^ zrN5NQYS-~k+}aErQ>ecjxEPhlvA${z$i(WVk%-Su${KHA{!`4K)K&6YgxF_4UqsS{pS3 zRlh$g1E58ve71dXWRgLsl=Gd8h=r(s3kWc*%9U-4N#oy1tU0{E58<^Eg)(T$Tj)?@ z?HCj)dGGi&(NXV~Kw=EwWq}&`>@Vm?aG?M=-W@4M=sM3iH8Z=aO9A@HcL_B}2;+{5id1bz$j#V9w(J$wnc|QKZdhvTizAOb_I=FSOh3rs)g(gKw z?5D;LyPl(V&sgOoa8q&KmC%HuiW~vu?_$GWLS!x9N>tJXc@3dU$7F!YzzhZIH+r!8 zzdEBE-fmBwb>MA~JP|3w>^jTzeuEr!jPgw(?)TJ`MG0L20Vf(TS{<^85gp}B zefe#b2Gh3ubvz^~gmEyr;ZM-kXdC&o$9d)C#~Yc|>Fs-i*D|);3>>wU9lNEarAGDA z{b3=IeR1SZtltfR!Sj9+}lkvoWv8jU!`dLYAYDrqH}3n9-<-cH36eYi>Sv zcbe2-1TiWJHWrqvf!GIxHILKL>!;7*+$zw^mgp=yJMpLSZyjXFomomfXz?fgCzdu) zEH9D_&(J8w9Hf!W;x=Hn(>~FC;Cbf1+)VVOporYF<4xMm@LT#nuUi8K#n1YGZ}mIx z$2|Riw{HG3{{b_+5Om5vxW`lHn?qaTmFw#|%Z6CoKBCtMcX~eLXMNWu@4KSJ%m)Nb zm-5dT+jxVFCCAaf7Ad#RrG0;oZH1B%)J=sw#LuQ=NTeq6TNoEm!En0qkoiRc*o*9L ze6wPT)`MykibdFO=0-3aAJ?QMy`lT*u-1^ZEF=B(}F03;PrgS)p_*h@| zfHL~Ip(|Oagqvi|{M_&LKYcYJxI+^b1!a6S;vl``h=O8**q0Nx9ZTRqF0^K}O)>`9 zFnp_-_fi)avIl1VL#?x7D?K8&3()zKqJu=-O-qtXNeW`E>ZF{=Zj1KFAF4Z|Wsw2| zB0&hJloe*PwauZ#-;q;N8ZxWIt>Lz_`#Z$s826(JASY6yFf}0LW^(e1-FlMyUwrDm zun3;z$cB3Dw(P_?DC{i*144b^Q?=JlfVN6y$G$LK5VRzx7kD>r7uz3E*S&5`fkp^cn?)C#o;&#>kx}RQzZGEY@W>a8(A{m-KiQzxFz~;N8$G zy6UMgtHw8zQ!Cw`HcB3hr0@cl0|pke->I-a%eI`aRh;+-~~|!T?aP!Dek=vNq+uKbr()1GMp@HV6|5x zU`zH_DvNT0BdNo>dx09Edss40QH$z5ZbuDl)I|Yr+UrE+Ak^mExsFb*fPwCD+O&{& zp?S5Z}?d#sQ%YI>H$Sv(z+GxlDw!dX*7Nl-+vW-3X z;TLgoljilFbDFCBlo{qAK3vq4j+N=2e&;cF{!%s>95Iy~XQbg3;UJ|oAIe?Aai0W_ z6ccIRgp+}$l36-fw=d4D6-S(3s#w*-*ss#xYMyL<6&j~gWk;Jy30mgr)?7a(9~ait z)R;WX-SK5A??0INvdr=&oB(jG_fH z4aHYx2#nmh45g4)@rNJrN$Bh*>JnQ={HCPH&G@|wze$xw!$a0tO`npwzEN@VQR-Z^ zih(0v=fR(S+LOSk(+E>LUt_DQM9l*c>A)Wdv&Gh+VJFp;N25=FtbXe{PZj#nSt*s++&AfwiBZ$hieAmy_W7>OqdiwiW_R=*6Yr23yG=OCkJq+HE1)s+8 zx{rVd}W>5rzT}BFdV&I zm1Czd!)%##O=Ge_I?LAM;lkj1iBHoT0DFSm%s{_+9W%L9X}9Tj(!QGnSgw~;etAy_XAbMh1+SCQeSrhiit;VeOdfg~DaQ0m(^;J#{-IGRgbsM~+ zQ6E*DD5EIjqo z)4Eqzp`gG$9BDep{ZXK|MoC@!$4&{9I-IFR9Uag9)2&;Jlh+p}v1Aes3zciyr(%i> zr_1cL$)r|@ma#Xs)9fAlimy>em04)71QE;4SRD4@EW|W<{^#VMqkBf`PO@|A2@n$7 zfHFI##sfUqW}^AS39lxxliKxB2>RPXA>7BB!f~SI;#o19C>k6OVRx?~*+#lv^hH;$ zc~s9H76!AxGIfWiZ}^zn60-+wtz!&MFM2qbnuD2@)}Ew&mech88Y-V676F`=!6-L0U;K4r zrsHER_wr>>`F%KvNcJVg6yu0ht4xJ{JQHJbB!X6Yz|XyPXgh{vbPsib$;cC!F^H6i z_=SW3ZrNKQdh1IqFt!w}uxV#2l}oAuPbKfpTOKPRAp%7XRx&Z_CNH{Oy1NyHli9Vm zidFjcVqpOd*BQlfdSNmvfF&iU7Qr*fw4ciORys13b{O22`=L%l`l!>NgT{3 z7lb4v>6V}jrrx~@EWWHLbnbRHoEO?BDitVejS(29@83yEZtm~V#nSduCcUBN7;~I* zh}G*?8>67E-33WjVa$g5Iq|=!$;lPC7kFhwe~?WIo?G+{ZEWC^Np^A~W^;)@RjBg2 zjM3GlDLW{e$FPkvNB*)UCXqT5rjxBv`%Lb&Tn+XzcZKjULH2L>r9owvJWyZ?x?)Q& zPQFx?rI;ZEg=(U-nq3E;7AUJnrdU*^w|pyf;@>)b^`JT7ZNdN-MoglRIt6c@(!XB5 z_+bhtm*iOQbSF;TN>Hb|(UeHYD+zEl`j)d-T-$b(F7X-u8NW6RnOp_1>gci(eA4vf))O7#c5O0BIH%%guGMqwXk5=G-t;g{mdffQy5 z6$YD|h}L0O z*JyGTLL6_k5hNWV%#DIxv>ox`-XZ*6fxE0)rPwOCP&Qc+=@miG67d*8y~rdt2Dm|!{Ea}GnvE5IMOnuf?8t>SDun?8e@aS9h|kypdzy-mGx5+ zEuvzi?8QBn%h-W5cgIzL zy3v&1Q&O9!;mM;<&0b7VLOzmb4Fg96;SVCC@+;vvLE>NwTG)#0zNwq!NhlB>jpVTk z0ZESeuEx^oK+zfTKqJRcc%I_M>0i18**R5#K(#qiM(@gvf|r-ace8HrV9?v)nK*y) zchidYzA71CMK7KFOEc^|<~(ki`{QY=X27L@=EE*ojG%zA-x;B`kR@lq!~bn+u+$ zZeCuV846{l*u@*+cxCqv5JWA{4@9UNr%Pzj3IvdqKgZ4YDVYf4m|8qS=#XLOd&M&6 zl4+EI1hENg0^Jx2aO7E**YpCbXV2~}2kuM{nKxz?a)_b7-kt=ktuVz9C)zS07@3oh z0Pd&}Ty~y`TjKj|?JAUrAbvl`;da7-&Uu?r;B#|+FYwIlkwWne&H&KvBk=1o_*%;e zm&)yue^X0Cah^=$Q)&~UtwchW5O{Ozfc4;`!dE#4sCW&7b}l2#jD{sro2jmlR?3Gs z6uEWigsw1OMIT2IGmm)Hx}dDf2CZrjclXCb5Jt!zVB%`Fp7X|FnHx-$#nDvS=UphG zCH-8hE~vHnBA#T@a(H%u=IP?XhKrNaYh6#7%_XHmT9ju(|ht98H}~sbmeztpi<&qH9$$(zTU{WHx#+o{%qu4+2Q>xgWcq1qQ)I|=sI7q98~)QM ze--$OWn*%Dp&1S-&1#u2Oft0ZX6rmZyBDQ~FP28ZfJg}yQ1B~|yDPlL%-xC{_QX@q zG8c$e@c|gnxJZZMsBSL^-d*`QIe?~Z*`wHP?I!boG+kp@rES;F*5sOO+qP}nwr$(C zYqE{WO?H#5nT)Bv`}vOJ?f0&|_uYlH&UGT@+m1M~3i+trVv7Es(e`FTFJMS2Mgh%M zTn<@yaJH5*hKW^ApiskKNTWAQ1YE2V|vBj5wc4yp|W zXIv{enPISKH33n^K0(l^fq~Mv{c?C0$>KBcAYL)W-xWjer@D7OE%4zE+Q_%nkA{+O zhTjB&OBE%Ru#}>d6oPdQBC^>Cv4l+9hG3@|OVtOi*DRhTSyLwakyiHodkQt#lUIcW zNbz{A8x!`#*00++&7XDng9)}RLCFa>$K?zvTu{?y6(eMxalt{_&AmOT4+pEZ1Pt3_;1T@>yXyhAt zC+yydO0&5t*wHwT8&+vEIJ8aLZ9268=7JWZyymYU~h>~v5GwK z3g8d?;4Wv3>COwyC^PA@K&RPWf5@A|VW_z@f7UW=0--8z)j|KW@*eF{o0Vvh8Gh8z z3SU#I1jZnp`jAe;x4=w&P%v+Ta-i*`>vjA`SZ4#+0@cRZ-tTGn$=M@#Qj$i6T|1pj zLcb@?QqWtDc>ZFjCE^AyLP$O^U208Yk@zPBWGbXHAcLV??QR#uW&Kf@LZBQy{>0EI zwXA~8sj5X1&`=dS*|3AE0AzE+LOS^1qnFp}GxU>Y6c!>y7TJDdSMl&h?O0|gx%Vl0 zWGh?jv;9$gs>jhFbb1{?tZkpsX|AAR&0)k)IFShGuX zYQ!Gasq=;vIy-g;qyL=bI5sH3Tshz7xRir z3|F9W2i2DoaeHfkwy{|rm-G&-ifF(KIp)C!vBxDlU-67UBRE?tnd9sUq%6(_WY1dE zG4w+c#y6+S!%0lqa2_7yxx)ihSV>qL{gg<`(0&F0YY{4(d;*=B6`Ke?vW+zf+;5q| zBP1!*uFlT0=XXB&QvwhV+YQl!aeKz;ySuv-(AhD+e%@Vlhyj-QpG>u0Xle}npei7_ z25O@#Y^gLS4DlQoTp{)}LUv-)q>SwGUoGQw&}6honN8B+aH}Q)FuEiy-JfMEmq18p zhxr(e*qKw>g*q>jLzL#rDyL4R=|-tXX{ho;fb@XV9-r zzF_y{yK47UdM9PRepWr=X~40Bd2x?pMKLOwyb9x#_ymZX($^6?$ zCQI_C&jbEBJci!|#U0ny(JRvKHtJ;}#@~P})ZvE%VyrMna}O&WJ>&c%Cf{@L(uJtW zOCQ$BAJRE)7q@tNG6km#x!3rIX{hwjPu?7{B+_!&NdJ+pS+Wr#MdkTv>uCATogY(L zQ!p2N{vPEK@t)dAr9r~_TC43xL8OSh)oxmtvk?EvFyP<#?lI=a?nOcZpYWUMSJ8Ic zcWGSvWT+JR2sYgK33F}{J=k+|iHlImF~HJ=n_F31yXk$hRb^SP*d-$$_G>a_&mX|? z8Vj=&DqkL5$jKCCxIXk%d3;|=1Sz6YbgqAYS2}Vyt4tj$!vzhN!orSKt(EG>eHUjv zIr3DKfKbsd0wtzb=u1b%rXWsX-xRx3lU;+QjQew2P^We$t*>@ECfTUKH<4~EL%7#J zS+<0OxR@$&UZR;E4F`vll9*c6!B%w@yd|sxDkj2MALN2X>IWXK)NCilodxD+XMEk- zN6*cs`jkYX-NEhM)gj)_!4-0a9V{!7J)Pc@Harp&4>n4|Z;OX+?l+$%&Ct37ps zpaCm(MLOd6Ep;Wj)zq}tl$ zeCkx&)|AfjKd$L^@+DSKhSYQ}0J{QO#s0@t-E)(qiRM81={q320N`M!DYChDa?BJz zj1$u=B1|wtS|#YzV@7^6sg>&`ig-bJCFwIjCPQ))3QG{EAxNG%8Mzxlw8gbC1Xvni z{ClIxvBt*6#Y^W>lhVB6oycnF|H?jb`Hq2ul0J%#a9cGwxpxO3odH10o2Y_os+C=- zIUfOF5?K1l#DIfs4s(a3R}jxk)C)|b0f*TPu|9*y`p{!Pk=N7H)35h|uXms&bHd@D z=KIEzKX*8u2sm>w|GbN6+{*^*>g`1ku`HDHi>C>3lj;uUM!0|t66gI|k1tdEhSJ@x zL+`HcfT*=77t%i#2NX7dLvi-%c(b!Fs{8&bXd3w6vwPWPmp0o6YtJdVSa*kA{m(ij z>MPUs;yG*@yZJG0~a#;QK@|i=%Ub*Q3&fzH8uL*)U^q@UGum~2U_s!fH;B< zl}i=gjT~5)?Oaq#FzWZ;n92W?bi25fd0^R8jQb6Wn1q}UqUhE9tozZ4rWFJIMOKj! z2TPQpgr7?BF@7F}70T3XKthfMcU9FFGg`CGi= zmK`!bDPPMDCVj8cqBP&vbUSuDXgOvBlld|EVbgE1q zI-P9bUaaf$;)}FjyxO3=J)g8q1m;`?%(mJ2b_sHIdj)Ozqs7maZ3+Rf{ON0jLuRu3 zVKGGHZX-${eM!h=bk`Mn=C)ol>o?H$!&sdwZbV7&xE?!wg{ z#R=M{SVQzGEfQ=5w@|ubv%$L}IE_>Zt|(r0e5(`^LY^($eT3dYAtNiu9VvKWA%!TK zA*V|q`c_^}{-9SR&La(eVQ!WyM*)zN^{Uq{VXv$A5B|B#L!6k{>DpRTwz0A$L0K-073MxX|Obj&>Y+ zev@^{YL1a3z6t}iX=!XTQ7Rsklts<#w@DS`tY%M4Wniamgde*r$|6HXw*~|7+uPrB za|$&BppQnne=JG4Z3EbFt?!EdEInoU=R9DR9e@$D8*snU@G(z#xj)a>%jyB`r4XIb2}| zc-v6@xL%+!Svk0WdVK2z2H~Yl7mwY^db~#O%`BdNbzq1NuAU|db;Wq8L3x+*P__34 zt@Df0qJr+)r%(`Mf8Wrk8x(66i9w1brx`78sf zrdY}o4o;F*C{W7Z<=FWAd?w$Ct4%6iRO=ZH71wKIsvv(d|wmTySe6Z z_1hD~sBg-5-{EwCOz6maxS{<;4-JW8LRn+6h)ipP0j*6sKJK?DtnYW2i7%;}*pi@< zlB|S|*$agLIBFzQ$!vP53g5>bRVX2E`2#r-3#eeH4*r`CQf2-NL<4sdJy*(crL=gchKYNH`}Wn*<84oEc4cs-Bjvy9Tr=blppE| zqgNrpUo5S=N^#a@pDN?+UR0Mz)HhStfM!1v;5)_l%F14Ir`3c}nD8f0{yS!_sA3&- zCrwvmnQ$1p13P*5y1xr%Yq#9Ald)l_?l2xki}YGzWho%W@YKO_{TsDx290vO_{IA{ zx~L_523ICjr#i7HIl`;z_$Shi^3D=qqqh~KTwsW6Eqnh=}8PaBA!mWGYs)m$sJ zkj$*jx_OKK+?%pwbI96Vk8>Zn0Qw2Mm^ULaJjt0*$-=CDZf3lmopXXoTC^EC*aJP)ad zBM%P`rVldZeO;81 zA@H}hrIxDRQ;1ad9#*gNhtMM7NOB#`cQGCShk5)atDB-bc-H1aJsloIN2-EU#8FyD zj!V;yFqUrjWW-7{Gn##AatJdRfhv<0#FZ0NH%8^k75y-K#NyH$*UH!pW35TE4|BBq zx6@>G^2&lAEtcz$tA-_4#?a^+e?2M?Nlm+(tsnDfN6$4GY;TTa?Kb;Fd4w>TXy*al zyvlOPIQl<)zzb#xyROv3wOl;R|Da^E#nEreOui{a@!BEYPl}##;w{*e8>8PJ$ zw<+Gf|M3VG{w$AVeGrX#=c9_r*v%TqShCc2Iq=FUmSzzAhyjZ@h(4ayC4%T$o>SAoZ{X|4Z5=e%E3AXhlqhQ;?LeTcm(xW8!aWj-? zBPS>FqcbGjRB6yD1q2eKzoW1=dNf$1vf-2pg7F?zYGAdyYDurRi#e#1s6}$%F1#_^ z<`k0-xEzyvdm5FF{&4+DWz)Z8rf8?q+Qz#FAY1FN{4stsltW=~b#B`WH zbe6O}+(FCn@H^<%V=9hsU9vk#@cfkZb=jAK?!bAg=BcwsWz!5PK!@G87HJnz;J-uL zN1c=r$@pzKSytsHOEZ_85rv~59^eYdafzCwU*dX&pZ(nf{hUF$ZY_ru;qtBna7 z^L?#noo#qmj5d)z$VVqvUmLq23QFaIi8I^NMj--EWSOG+a$%9;JIB5rbntXPpPJrR z=Zsl&{NwK5=&$Cnc}zBddxii<6U}$ZfBVk&zTtb_wt8b3f?VecHo{=XvahJ9sQS*~ ziVLPSLx;Db8(Vb;*aHGoVt}p2VI7G?X(X*;FI04)LRr6aZRotG-7Bw&h4PP04t-^| zr2e0T+ieY#7BI^u0TXMvz|xiVrhbB{IaQ6chCJW6Lqp^;nvG~Iy4_3^H!aR!dGHzT z2lWp3q##o5-LTH8X`u10)n9Khhjp*u{KB~Q1TZU1 zjE4Pwz+ie|LHX0uT(Z7!yFU~+6oe=U_8`vQ`{T`h*H+}uoJoOOj)7~0TH2yYILK`E zmpPk+k-!eBnQ$jJFr(FOMXN0x{0nvX)1!IP zT9%(atFzT6hKDkKx)tEAz;7@(9jVp)#?5e1fX-nczw&ulsJy%pjPZr! zy41=m1sQDs+(|GiC6xCwdk!9`RrbE9HdPJxznrynKO(JFzt9nE0T+#>kAc56&V7J$ z`Bk8;Ep2aUk0WP}WQA3sOrEtD8>Gg?eY){#KTAcKyg6e?sND3CvLh8ZQ*`eDL}X}; zY-mDa;(d_P!6%iQx}?8#(mh!aj3`&_HR7x;0UBhum$VQe8IiJXT<%e9^|guJOn%J| zIZ7=I&`5@FmR(@*Nz)f1^U3mrR5w1vMEjv_AF?*QtTMy%;UJg=)2&E<>n!iJ(>N1X zy_XWdamqVENBuVELQ89Z!>f2vTvX)$f z^jKB{tuGK0etCFcE3NGc5P20}t~s`L4o@mMRKcX(Csh`PukTn8Tll0HvUt^dY5&`8ZijpaN+ zZtmnAiIcmco<8n+HnDO9-Dj!eJu<}W{5>N_B!R&LG0nio3-y3~^2?Xv@QSKkJM&`j z#b|D!sgBESMjy4c4SCcc?l6MCDB0gW8GI%rx><+X)C!fs*^Ih_-gGS@q6jAYr{oL< z0ssZa$1LZrp1wXlA)%+BuOAMqD%h&NYU$i^LxH>p8iw*6Tx2tad?M+;TGsAMv3mRW z^|d!n;0Oe2$`7Zz83L;%Ygu0tX0~@At(7XaJHyIwcgQBot|!`-w9tSigEJf%riDD-S8JMDeib-J3#YxMDAF<>*=2 zbD_gC@0qwt`hZQE7yHqQ(6++tZo_IBrLlLR3(YHMzE#%yXSuL&y?oV60`WBv)QEma z{R>(g7y|T5VB3`b*lL)WJejC5NawVuYt4kCG76`j6>lpdvTuqgp20)}?BKUsL%<`? z54rbt0q=Lz~Ric$IkhEg1liLlBxVXRy|8!@c&`*G>ApGD!hBP&#j2YiC8 zS1(6%J53JrWa7O9sA=0Ex`j0vzdjC{-^p5`W51cHobba`BbmGKq zyavb5ObWXxrO04Yy@EgDANFe1W!k>L^HbyV#w;|Q*$YXk@_jVOF9F6)SL5fuAFvW~ z_TE(X!lLBBfU3-X0aVD*6@+S~+w!Qn$FYT;Z>>zCsWyfVF)|-%Th)>MgMwb?jorxK zS{OZRL$C~V8Kc9bvMr;5G|X0dfm+{{dEYP!0fS?4oQUSiUx(u$+q~m{TmZTUhJHgv z)EqqxiS)OgF%(n3x$+tTyYY0Q&0+CM0F>S6GcuJk+|G3~=GRVjK4^4ed|STzX+)Z& zUAQ<|b)(L=w2Y+!7G(1B6FX+z<#M%t%tZMv^Vq32S)HCoPF=gl;NMY=LBE%a3o4gY z+d4&`u52bD%ArakqrT9tGca1O`F>|}JpFs=oS|4OJvBJ-l+O_50w_Tg{bZ0%N1;Z$ zfq>S-K71z&);7q^g`ImqEyU^g8$#Nx7ghby{c7q)Yr`Y5lpDj)@2_~q{?eZw|9o9- zL%s;*Omy~1Z6Z1&X3tC$P&v!mY9EIoqM3F9>ppk**4<%SihFby{@LQ+z22^VetK(g zWwdT#F>nP{2FtWmRoA2nBnc5WmJIJ0$P%jVZQg&zgJ_Q@YGKxl?CtHFw8Um+bQmU$ z!6Bw-;>ijkW(@;g&FjedhdbjM32`J-n z5k-&+#TzgKr@sofluUekB*d;=%_jzDQ{vq+T_dE`t6*Ud>TgcaX&*lEJLw4`oaxD= z6{Lxt{Y}$O@tR^pTW==L?^1z+<3w;GPaEY=^U(Eh3)9wUHGgI5rJ%gLn*?97#5=>% zSOs5K_;`Nh_$I>NU)!~Xlpiz&rix1>)Y-*S*Gd)zywSd?2V&p0;TFo1U=P)sN|pjy zrq{K8TZP7eC4}Wk^W?}*?pdjZYu>T?_AP-!^9Sbe$*~*y4yf36JE3DtUpQxPZRVTP z@ZQhXDp}Cz@-}i6O|@^FZrl5JT1SttmsCx^)&fvlVhRt!UpgY64sP7^kvkx*X-r44 zh9bLB$WD1b8YZMkxs`6X*2JkT&jBhk*(})+&EkXYgD4f{kM^%Ba(yJ#RMV-5AWA+q zU%!I>apT5AvJVid%=y;97^1&~FOMs`k#>)0O7-VjPk~bkwYr66nAHWifeL$zOw6%} zqC+sK2uL584L?;87>PZ8mm0}|^^#~`L&FDEd&*_7;tZ9Zv&}kGdYK7~71i$S?9A7m zXY=C+Vke`sPdJzptE{`kPMn&Hq*iixCx(T&_tkK}2dB&_iCiK0vb5+j;W%zWiFhI| z^fT#H;$aDZ$+hN-^kZABu;fGVGq*mH{>|}2DL`_q{xx@6$M-Rn_r?Dhf!3^dF#7k# zx<7Xnloc`qj&FxNq|QE*B7}Rg+mTvYmoExRfl=U~Wuh>X`L>;$-*mN-uZ~>Mw_HK@ z{NMo0VpCO0Z4tkUd*kP58D!^798R^2EB5x)P+Qz%S|>;v+ERn&1Jvt2wG(>D$tA)` zGGB2Xx$O+Mj(9wqKJgZBTsO~t6o5TdlKQ>bkV7%!4BAu6{Y|%vA9K6sdc*9aoUL}U ztRp7${8bf5kAteY@ce;9;V~s+0BWjwNXL$=|Vw#&YnZQa#XOk(KQ06EWzg60Cd%JU7yvbY6B%ySxI5j`Bto{4&kT$`Vpx6Q^%=%i|^tBwwu>!asjmBJl8#7># zzKMXKfjw!h7w#-mycM9#et_}W?vCT@1;alW#d#bQZNwZiX{zE&+8SEU4-`|l51(y3%gO}y)EJTtV7JitW0|_Af-&(r49wzev|KEe2$Cqv| zy-EY1h5@=FZsRfbz0A|`H&L524XKR^R&hkSg2?&eU9fYS9YEu7&^()9H#249)uLDN zPU)^L>l1^4Cq#ket|%1@aoV2p_r80;W?3Ygt}5?zC=~jyuDrm;#zyvCIRVNAgagc! zuH$zZsd={PY!TaB{E!WK+I|4%SK&x=Xp82t6)4pdRD7seRR{{8NBcLmky6)QV|M0t zXjG&dZBOG`V6=3EbH)#S%YlurtHBr_4(|zeMx<%Wl%lb=11%;n{aK`q6l>CHxqT&t7XISe z)uzy?Ksd5Wv8#r|h6-{m3Bi@+3zn|?`l_toVtM$3qGa&VYhnMdFM`3h<)1IlYsjBy zKXmz3bGyY--|v=vl4z&H;y|J1Nw#dAb(fZ6Elp}qKmusWSVn8|q`8IPK_as5S-!>w zUa;sZ4i66pZchMC5dDxY^Lj^smpht8x#TBPG++O6>t6nyCIfN#-D+*|v^Z#;FX^OA zKc#t4Ont1eWAUN=LMG>TBCWH^oe}gEvw|lVnm+E-HXGwP*K^g@u||TEy!@`&j6It5 z(O%TE(1!5uu?4KfW9x3;-yO5MZfRptg}<(mCu@}=Xu)F9@hlM&WFIVK!81wVrTvA#rrNZu8N1=MG@5t0s*)93A=tIU9vN zuoVnJb`*u*^u|UAx{2r9Tq}++8&_mv?JbSbS+AF*7s}Zd)UK?8a_t-)b1R3;x6``2 zzp1&mwdANt$!^7y)7TBDwTq)1ep*P+aGNaES0nAKP#sF_UYCsL!4plQcFFHDbZ7KK zuHz~ie0dy4O6R9POWo;2fgF3Bl}aW~3HVM8MFF>Ka>@ZBaMkzuzd!x^$43J&f#xyAeIJihn7+hPJzCpG%~I=tTkC7l=}WjK1N zjeOwsB$wCoW_e-kv=;0Go-{sN2$xUhIQ}HazlR7XnG~6sa{`Q5eZ|f`MA2?uLXXr z0p@u=O#W4vImE@BoSgoKY6l|ZT`^`66?OC$(KHremqyh-YQkhIvNWRUPGzz-Zj#>5 z8UA4iG>VG^4>E$@-Q(U}f{?l$WTtgH#>Syi$x6OS59+Cn#=4&|?P!U(a6z z4}gQj(rAg|0xg<{jtbE2;^>njWQX`!x~?R=5#CljRDmd?4^ncj##dTfkf7JA&0^?? z*Y+1ZkrsZFsRdKA23VA5C#Bl@ts*{A7DG-7=}`6mm}H|Gn<%GUr_4O>PyTb89zk?} zDpNW-JLx7HUW7d++LNoa5y8gW!C8>|m)(I2(QxcABq!_6RxbUB8tvvFTP%~aLExUO z_uVYXTcuHB$WW_!D5S0UMp1Ws(l6V%*m1~de3WfAWOe8S{x;a2C8BPpNcUrTL&=n$f&9_t761nL|=r*{62y zeDxAVH4`1%rh^9GU7IW6R%voG3PpL-Z>f))de=WTh$SB`{~5d*-<9^^F%{QlM8Sre zndp9GXN}RDZxGRE1?PB=mW}4X-J;~DLR1_g$hW3c(=@qI`KTS6&%k>K?ic*qd(Y;E za^~5^Vv}Jg{e5+H73L9*fNvIJOc<7kBj@VxUoXu02;&Mzz%^M0Zz7bvw6daZ02tlQ zdhA61bD*;$kMR(g;w zPTJTnU{eqX_*q#|3%4$~kWT^ikvlF<3_LDS2~2$Z$V|VA`wg1*&FL)KrObvhB7|I@ z@%|D5wgXO!nT8oE^**ZC-)81gUr|k~rBLJaG;dPs|?Iw-SVp_$wA&m%}B=4w735_qL&>~XYJ#<>t zw?83Bs>VFCs=Mv{o1L9KiQ=|V?wGe|h?}xx4EK=Y+h2Qj9CIw1>x6Gb_h698pbP7VhNYk|Lo0RlUO|Suv-) zlcgm7Sc6Rq*FgWUaQAC+8I44H5voMY>Y#)O`|DWm@IJ_bof2H*@RB^sSJfIV(Hcww z#_A7DxSycj32VJ(_E8qz9LozCTR zvMVm5^`il z$TjB-+njD(TcdvFrf=T}5xpqy>@G_^K7K_jJG)Ol*R;JT3jYYXv1$5*s3&cSj*pK= z*eu1LJxUb98X5bVyDo-}&;=E1j9P&j%-M*`zd%-EAQCDEJjltE$StXTfu}F{nkpDg z2P791d_FBj%m4%j_3@LF6W|fAu4=sGoBZ||GtGl9UEm|5%4n3RF7T)wtE|{BXSu0OtQR`xc0?boI zBJ8saP(&{y$mx?94PnAsW}q1Vwf&SYwx5i(N%`Upsx-kGBfZ$3LM|OD(nM-WXC82| zrYi1+oD(TN2PT%^TRC-iH_eemw)3K!-Y|qM5f%$K@LvNQ#!Mb;e-?HdUi_R zvn1d5Cwq3GD$cAGg2?L#xb60dzN-L zBGo0a6BvMsS{%GgYDiU0-P|}3lVD}(V6{Mle`=JI#y*1UbAaRPEOU>lZdqfxgVxa> z=45mQoull%DxT4s(P$NO+Es>CyfRGAH>21*mY7-^5oXgeon2kgJxeoy-c5{|d>b;u zL|Cb^aQ75#7QAIb+~*M#EF^Gsk3)QRO9NS$`d5aB?<%&-(*(#ifzC%?w+TP!I4tA` z&T+8dN*Aeyr(mV-FhG<6x}KP=PS(HGrXt2rvy0>!GL-wKDhXH37>W%I4F&o65j9vlK@`?Jd}Gk3IcuA zueGNqkC`Cg>jNQk;TrR8=T0L_%xIU4i|n=q!2j0K({rs?)~Ov$OoMJA=i~P0RSj+m z!mqpyZHZldlOnYa(t|E6*rwa)&e`=@?goxVGL1iGv;Xdnr=z%2R*-lbu*kkOt1g<# zk1wjF4l#-H(y@WNMS;&tC%pVNqIw><_U};k-~46D(1LbN$vX=4=%YMoNU*g>vVK?zpZE*e%uFs{$jtl>{XAW-x<`C0`&aK4PZXfnWqN% zB6@?Xd1=hy85H1i+(kKkAVUV+?=>;+XCz+6=yM^AN`LWuGmsXf!k?IYqyDT-+Crw1 zW+h47|J~0O;)@bHsR6Ncp7*LK>X@-^gOSu~UJqmd(d#_A61cv3fU0zGlP;`EBl+nT znV$LE(#84PCoy9^NtV%g8K@$f5!}p0u!hQokz&L6C@AH^jAm}vUZudZ>>H^dQ?jrd ztam+?BK8?t`aD`vPR04?lWZoOv(mp>&Tfn;Qvqjjo7lz_uPJDYSnJI&|C-S-XRh{2 zTbJt%xL%+@06@mfPDcla2#+Q-I3l9ZbVMzY{2L(s(jC%(B+XhqNIo7D8dt(HYaRnN zBZ|2X6-K${l(o%zh<#VxP4&2_@C{Dcbk0S9kBkqFCdx+3* zd1f6G&cyu}1|t-Fw&m_Ed%F4h>K$7-8_PExm-j3fC`7 z7>JW=u!!Li2TqXV3Tz7?0u_zb<{!|7k|a!`U~jo2GHn1QUs!V&YdH=~f#YsJKR359 z?5)p9Ykz+cO~R#(~(19PEPrIhtdM`>j zd^!#jLfduyvDkP@=N6y#kv>HEPV`ETNu+hKV4&cX#a1Y=`uVmP!WHWVOgfe?-!?{A zGG$*%a5fM&gC)7nn==PxQCbb;~&3Vb2y2pl%a43iYa%}q9uVX}(@U`Y4*IPkd!a0*O>`O96XJ%8j? z>weRb>tlaKSM4-AX@#mgbgiz}M0K_8eVB9)^%Z4kVa31du|n`LmSy1|360Ybhxt`d zomX9H-6L}FFnZFuW*yFjD1Ub4)N`bw_5FIi0b-t4of0yWC!hvQYJ&|cw}uu5@->%X z`+DFVOnJIPXDcgJHYrlrcimvo9O;H!H-j_4ku9kkVtd1-0r8V|-$CL^WlW&Wz3)2= zc-Xj?@7w@dkQ?bKghW{!4~NB)i0hw%M$=)ZYpZmX=XgPqZSMkaeC#Dh+3y}EoK?C@ za8qk)`)FcZvJY(to!5r@=}SbZm%^E9;FZtk6hv`ZF5+gw`sN`9$UMq&&yoY1Fs#2* zg+$RFPRuw09ZY0I8FV<}paR5>uvFObMNS&HJ;NC}#+P1)-qLk7^il1+7#?j|Rt7Z@=Mes}}~7uis% z4h)#F1FyLQf75dJngA2N6*qVHHZ8ivS^tm6wd}04`9Q#(`M+$LgJJY+4O-k(9W4d8nAn9v z_ji*&@+ZDV4xGLCG5&F8oT@iSZK$aAQ*X2MS(DlY-IaHED_p;b2<+R9J)0l9`uh0o z&07m~f8x%dN0E5&Iy5A4k3vB(Awt(o0+=>%ASWgy6!815qTP~Q9=0<9rXXLBYlfA% zP%C4#^6?YB2ltnjR0P{QJNAou;e)_$0R65>)1Xg6!0*Whd3fxdt*z9OAl9;7^FwkM zu>-dE)P6QdLf1Ma$)9ZIrLJkgtuNWkZSUAEJo0Ls`t+B5pB;FjV~9aaNtH=+7oa%y z{{H@ffq|3j9ZsC*4Me@%`Zfx^V;$EY%ot^Iz+Hlu?M;d% zC{8iP8{N4l3niD=3yC615uJoJl3M<8kZq&9Zt*U?1$y59-*q;8YdX^~*e}_TgL0avu10Y0{iPt4`}% zQzi(L0jZeP;B>S&^1h`&0YO2_WF+W3Rf_lmGiBz}s9!3930!sfoC_p!oZD6DgcamD zd_~SWRt2N2)$zl*h;D;8)f&Ry@r_f1vauj-7^i_LFLi&aMe>Oke<@BFg6Rlr1$K@Z zQspVgsj}DM%YWN=U0~D@GjC8M5GpiJojR|al;s}HTM1GViIBEG75){B<%YJ@;vIut zff{f;4t2DWHT>^~-{j3tc;bPUv)l2hK^$)dzncz;~ z)6u^ZuZC>iipYow>0mD1U3=Pp0^LlY&=;U!6m@74JV!G{c^1a>dm>eF@n6Szj`|Qv zL>ne{pWy5l_-*nhQ5hRHmxDR1mc@S(UZcry+xL1wR7rjvUMQTWVgrY{a`G;mu`)A# z$7vR^_X==cG(8RT(yS%3tY`Z8(bo%vGZKsas^cMd`+|t0ePl#~b5Je6{|8mL4=cf| zqpc0xrwsz5#TtU18NzKbny+~LJ`Yk_0na!1DK2IMv!HZ%n^!sw{M`;p>`meb;6>`-PauDUh#@PlsW7P4X7Dq`U3z!IH z8UN(gpTd-Y&Z{{I*;nZw7o`(U01pa`3SvvvLQ&Y&Hk^sR4t1m$%*Zf`Yy3kOtLlZkb zx;wm|>1J3;!`Y=56&#LBL%Tg_N<{S^kOCu%qJUoirx$(`-ajK$y*7yXfX{3)@kC0v zI;~hMm5^;*B^PWt-K`nhew3qCkWF;ka`LYVQn8c9T}Sm{B+%Dd&dF*L2fnw?D%xj$ zh&caj6fxc4y&+A3mrn>_V7~M4R4fuIygi2)%_}S%@O!;`y50gx6E?IOrXX1@1cR(D zV{%p^uvaHD*U*T@l=R@{xBL716R`9ijb{12VMQX0c8ht)igS7_KfU*j6UH?gD+GLr zkBLQMZ(mL(%3vrW>`^jCm8IG9yki6eh|8Y)&qDS6Mf{g{x8P}z)ykhovJ~2ZgeO46 z#ZJJ>Zizl~y<9CKofs~s;l_EaFNZK*YgD=G1SI2z0_nNbO=XL^Ev`8Ou5tRk*}E%a z%A`7N2DtUKCdcIy#OmjH;ph27lZ_|=9^P^bTwLDuZ1j~}qU9sm4s|wQzC9Ch=1H*^ z?^z$J^U~1F4p}$j!qRv~+oD{R3ui#b((QGnI?>?-RY0qrGXj5tk5Z7^#X@Ow9&<%*qo2YkQ0?d1`r68pU+(@TMmQHy4Py?^+jpY88EFEU zVXt~!T;Kw6=w)w}L#{7771Tvu0~z~VQP~&p(LKT2_a|@GH5T$pf{XzxdkL9anMwBz-!0a$?^i!C^# z6;DAePV;yOm9%VMySxXu98=tgrT{m0@N&l<=?es?E*T^mS0@gSJzhOGDEGunM=skV96*L#<$k%@ z=}C$O1Q%m7r)b7U?fmBG%ErY3zw-X_=+h~ebgut=fe)nCwZ9j!=@xhA)eZi39{cNW zZpaf5V(Q!9S*vPw%XfDrlXf_WONEn?6-wF5!Xy${&{WDy4bX&uNxa=`fHkY8xl2%WOQQO^bt8>iJ3AjQe@zou zi8mEelaebeF^zc`*eN%=vYW4OZWLJC00u#1Rn6`cJ%F(g@_9J{Qu>eQ-RbSk%IoBZ z#P~I(4D@Xt60F!U$AJ6XxO?Ck5B$5E_R@v?lCq?KAxbZhg$Q)Wy1`gLvqh~RYOo(x zG$-;eb(l+|m{*avoooL;nyxvn?>E{nx3sKf+jcG6#xj;&%dM7|ZQHf5YT34Jd$nr! z`Q7`v-@n7RZ_npB=e%_&!oR3+D9-M2dT1AfwS6?VrxX}sj`-JO`auFd3FE{;p_iFP zgY&jAm;<#qzd#rlf}vd*x6Av!ye(^1*+Zn~>FJ)`r=Qk>XFT8se2lL`YD`&^bz1}Z z=ilo5;s|r9l{EGocAd^h(1;8JN*K!&(9@SWpQ6(YdF~*QwQ4Li@ zvxY`cM@eS%Nyvy{H~^F$cKQ){+4;pfRJF%4zgMFenDA+hB{PpZhjLJi#E%9?dB`so zIf|Ee9ng@v6;W$oC&C8(VDCaB_s;LEA5#+#fNx>K=hsUd+9K$$lt?mTBM%aap>8_n z5Vq6MLV<=UZ`rrNz)Fw&l~B|#dEC?5FKT2Gu7c~!fH9-ki1K(tGy64b{hH1OX{<}C zQwOrP_`|`BFz;*%L?z|j2^a%PsM5or2uc6Fb6mo+mU)@CMW$H(HStv>s|6%gDiBO&{#SBHzku?rBT0^_}?`#+*MLG$b$pc$+w4} zU3Q2H4OiA;KTuJUY$2v0>WF)ijw%^5$H@sUS%nZ?c`x7fzvqsy*BV914RB&HA7&Sj zA>5+65}NwqsYQ_IFKM2+Rgl?kl;Y)DVOlvwB+HCCE6brrQD4gJ=h@v_%tW{v(`i-&@|f4E*#qv6DTTG&aOb)_x>Qm6+M`@EgNhN!0p=;yX7zS7kW*75~`28 zId4($2-@A zDDCa+EQIC*Ru(LL@4;B= zL|KDLp`Q2Y405DfHJwM0QFCayqZ{ZnfAuhRLf8|M>AEuOq?l9*_E&_v=q?B%JG#J@z5m z1N9`YW!?3-ks_mi&x;!M#(F??%c&_B&L0c_=f?K()_0Y&Dv4$eEBvU2V=Eg@s4=sv z`S|iDI|Lso^V0WgeF?WTB-=Q;`u}|Xi+1>PudCGa@nU@zsCptJf%bI?>KvXb$)$79 zR$>fR*xl~B_KP2|!R*)@7@KhnGwv15(tWP`fs&n3P*nT^11EqBA?N#?lO8NeaOhK} zF)7vl!_>Rz1*e)YZe0l~gvZYvb6_A9W7XfE2z#`llLt@ydikHOXYqo_dwxjWe5WI6 zuU{@5s1qL)%FipUNpOEQflm}zrs;JRmYF=BueO5~t_#lS;C$($S=4@33au$m z_5SSN|ME3idJ?X&_fi$!eUIc7$LL&me4Phry{F*gta&@B>HK@qe%bZ!?dZSPkQ#*7 zlCv1yau;mD<2T&4G%lal#`mYL`Hz_1{tBK7)S5gPA;vW@&IEuV0nxqQdQH!hjbr(7FaCZpP{Cfku z0wmt%BM0?8?lJh|(91uG*%JF2!vWRw!(mpR9p7sl-~eQQ?-hd)QVN!)J$i-eNP3or z5k7cneEm;i)GW?)NUFsEp%@k8gDB^DtC)MfYq^(AmY$|ia>52PrLF%Z3~spvdrE+d z%b_fc;?qG32<2Xr7nB`bZ1v$31Dk5dsgxdQT2=hJNzKa*IkdT~xSJ`Xcqr!<; zm+}1hfD(c#tQp})L|ss7b$XH}iWGJ^K48@nG^Da*jKh2*o0^*b-59-%0x0+G)c>`{ z>u1Wh`I2;9tiL8Bzp2-j8%!}7vrD9V5Her=dknQRau1gh?C#(~FFL~K^`I-TPY?>U z0z3oa_kOQvx+W&&h%obGjL{Y*P64bka2xoTpDI68nWMB?v8;1Vg6tNubh5yJ82=91S0i;SdzGT zB4j}%6A-Ka=8ax8GCH8bC)bv2hagnHSuALf6XGq7a))Ql2PaM^|f`ktXSG=ePhFL1~-_z zZlfHDn~RHuiTrQw4PI5RZu^DBplh608_ff4w`$8a`W=xt-yM+xzwZPjn-OQ4;a{yw ze7RCAvKRvc1Aytf6{Pou7+}er-rdc;%O?@udrpnd?LGPSpR61OLDqLC^QwQ*c>@3B z+Kn%fGJa@SkR|17Oq^xGx1sB!8)e=-0m0LjhXj6|u{cSx6gQ3a3finM)Xm;?uG1ZP zimD933inWL)(tXL>(M8pn(`TB-rHcx3#YTymC*#+4t zH2pc97Z(NlLV3@;fo*_xBnnHB>nalir-lA9XTevTcuk|-R(lxwxZ(MscOjOZ!@d{x zptSZ`r0?oL8!i+3;U=hao}6?mU8i{g2=a*B1zmfx8JvM)uik(7b-D)!N@ zrT^YHoA#UBR!FDlMsAI^@{$kD&5*XehvIA*tlm~(Y-Vex6~Tvg)h|@q zRdPDfP>l4aKN80xj(~_rGgJX9Z(1ug>6|KbyqKP;PQh2S9?kTxK<*OF2<&rrYZN~k zXkqwidE;M}b6$0-S^u+*mFJvmIxmK2jNz3P_nbEB`Ng+Z+o|HDXlva=oi7guUUpiW z{%%;gS?*N-G0y7^DWN0HYd;yJgYF%dFluH#!jP>zU!>hA(K_soBpU{AN=DrS6O2p3 znK^WnPXuNif1`7JS#*Qr_ zkte8kRCbe&5e{9i?&ju2e?P3iL+uZu(Ucu7GGXs{gMIDxo1KIT41dVa*vd%0wrnwe zQV~&EHlT+$y_l>!b%rGo!(i7d4X`#JQx|d%!4*`a3oD;mVLxhyOW~4|GHw%jutyIN zV%7Z2c@#Y7S-b||7%edAX8_2YO4GU|36jtp%x`~HPc_= zZ#%qOAj}z$L6ZFyn$R`6qqny=$Zkubt|AO)iK9bPFFDXE;afL944;u!z@8(Ui4_T| zO4%pZu#`rH*+~^a3EE%kGloV++%hiST1l%`0vyplMN6}4hZM5RKQk-v__!1V{!yQ3 zmV#UUR@)nvH^#+=?orhpR7hdtZbgIs!uOGYX*J6ufl}>4RC#6+dULE<{4QT|HrbCE zJ5rYPdzsIG=oRr>um7K2;kVuY${;eKVjSQr|GSlh%ZZQwyxmd8G@0lR6Uu@#ZKR> zc{84(gp*;Zn2eD_-g%IiW>Jt<7K_08R2Ka;LtEfeaNbfp>l3qEc9G0W;uFszGSOMg z4HPSZ=PpCCBaFY`ZtzAO5tq8Qi7|zCNtvN zRyg=sUyCs8MJLMU18!rgVSjhSl(k{(bOVZogab8Eqx}z-a^{zu__B4HQ9@uALr$P5QH|?ITGfJ0T#_l~ zMIX$Ee=P34SLE0JSS9DI-AF8l-Vz~BFuIx@s}qgJM#OvN2k99~|*W5OT!m5G(s1Oupo z59eknktbRyB?kKX^1Ln{rghr2iu8j+n_0AM%U=hbJ~k9>d<$Ig`X+^ixYpdhE?a7k zMBZzE#8w<$g}g&QRyfx$ZXbW-Eux{kgqLZa$|4^=JHt_u1|bWHyboPCkWF99Udehs zSR&1$jHMe5W*fjfU|ki{yH;lK-ag&m`fxhuH8|ghihLww9q6a4$E@1QMj5<M-qcrIFs!_@vL%%5J*-BWB#~N#vH|BE-XPDN|_EW;WhFX`}?FKCN)W}OE09T z-(^H5X#yjbn~itqz4qx>@d23B4RT+`%!PL`C0WaipK|`)`uqL4BCRaJVSWH&%KvUB z@O1oFQ2o@=ze`L6;Z@mE-QN1Az%TAsbi9|b`2MG49@-+H7{A@lthYQK_|XQg&lZv@Yg4L7{i6z~+lan0!Vdb|R4<@>@M=^g|tlk%I?2}pZ-)uqRLlkRvsI~$k zv9lm}F8z$WUn&xw#@L00@B$Gv6hHMu^<7r4a>a*&-XprPd#Ki6MaU@Qu(jn7&ra&| zTN|QU!paDvvG|V1U#p2yJ)$HXyQJ@`6>W=vZF7Xtl%hwJeaVt_M`+eHiJ9}qc%y;~4=alvM! z#jPotlJBn#{?K_}KuCstcX9s+PwUvcMVwayBOt|B&nwb-L>A1cApJS0)~tSb;J;1g z;XhJYT4&a;$VflB<;8~#0Dp^AMf*|bp5K&hL>>Xs%|i}JT>S#V#p;~} zx3_K}U%haP=#P>TC~hfwQ~h~sbTL*zrDfibcM%nYN2=pHl1jvXKer9b^WUbUmI+1o zGOas!hYwGyiEI_xzovfTGw5AL$H9I!{4K7s*vIi6oi^INAbDx5QNh5GOlvm3`F_)i zik;Ks@^fNR4Oav0K5+(odg5?xKulV2_vP{uT(TeqTEZ4_qDZ3d{0LXYkJDne$*)Z1 zNK>#Ha%fcUdzP_BmiE3ywDF@6Hzk~)G8i}I=3hDK3q)T{K$4{@&c|d!dYT>}C1ux> zX1yyzbhVyv&lz`i&QW4)J7kUML=Gp>LV64M+)}VXnjgOwFd6%Nx%DX)xnMzxv z!03SfV-P zfkd)|WBr2;Fi2X>omFVn0LBD|RbfGk=s(cz^(Lk3Md{zMa8jD`>3732UvIP4a^G^A zZ|j!jxZ1_IafWmhWwOTg%}{>5iE(HM?`~x2T+d{G;6zGn*`|jsC=JUT*}=YmA6~k{ z)VKim>gv2Do=~cvWKk6XFiUWk%@cD@J-goInj{f257sbwfE(JiT6CS$G0I06Yjgg-TDvYQ{pq#jazff&APq!HZs<;Aq>2w?^YqjKA*=+S3nxgS% z#Qn8yt(L)y`i#gqCmp+|Jj`lnL^c9AS)XT4U!btH(UyD-TFPimZ*QTJ6_mX4OK)$8KI& zGz!+&8*07isGu}>+BE_JxRPwYjdkrJ9_C@X2$`Q~hDg6GM`sf3EHb0;L~T*7Z4Fce z`z~3iqTK8anvP|NwTtV;PEkqYf^EOMyPl;sGK!!w-wVubBx6#>I>NLu;gT4dx}ZE} z6{HA0T61kOA7~|IAZ@g(?SiAQoYqYxAbN^nFoE;KJ{LP)&aE^9F>d<{GFkA81@0g* zG*9`_L1EW2Dm`6(6Fx-Q%qgvr!BbpX(f?}!3^=`QV`l9a-!Yf_1q%ywI|q@-Wfe+R z&9lbzevw8llh`z0C>q#w)s}}_cC-{RGkO3SNPm>oteKd|xMsL~t)@qet8nIwAE zQVQcQU>51CSfG1;kEXM17_6|W2~(7MQXfJjo`WJZYN1%p@|R|P>}E()T5E`^(%un+ zVs;$Hk)3^JSWic1d36=aK(r|M`~41zpd3=JlXzUGA967-|X~l*Jfz5en&M+Wb$>sr{Cl>ocm{_G_qYQ{SSeqzztzS zBBFd(ydIJe<&5`RXAB75f-vbu!DvUH?h!)@4hA0?{)@Ch-hRq|_|5R+XJx%=qo!*berkx&Ik{p$?titnjj zW_Gsb^mw@7^KBb*?)hD9s4a9`Qao>>*V0GhwAw}u!WiYVCQEAC05ikd9R^;~uOy!v z&Q~)i_SQ?6XU`$_-KJXhCgGXkQsrsEo{XnujA)0ofX8O`-2A|MfsncxQNlvd0(|YFDk16-|}8i!+u?3$Saz+0bpjz*Qs%)Zd9V&x%X%EN zIzTJp+^y_9=AOpLEhE_g$)Qx3Aj1hWn-!{XXGHjPPQ0svfM8q8p4%Oy#y(~YZ9#t& z>J;ckual87|vtoi$#dvXlqcs#PgvDWGbu|6%LmI(w)_lIIlY>S_BV>o#> z0W{gvI%9J#BQC$Y3+EJuEZ*T zLt7_Z7@^GRPzL^-jcdLS(#3NJS})7YrD5qunB0JAnHMB&80$U#QICa<72|SYDa5x^ zS@YQBE@t>xzUGGHHoU%u17iNak(VxOGmY$8#v9<_s56&ci%0K0;9~=v-ZSGz0s$@h zUL^cJvd(uHt)FY&4#q#$9^C!h;mV3FnL~)x`g0PVA%wTh6r-w9-H^AGg!lu2YcLt% z7r-L`()ym0jKYI@sw5<$Lt}dygVkyvo9%OBP=S9yQw2_^^W<^KWLOrtEqd}E{`U0|`GabqBm9Fkj7t0x%5gB#Fm zC*Y+hj9D%p?D|KMFGP<{kl&}5O`2>IxM5dV>E^vBRJ@Ji4`A?7cLv6YkYMcNH z`OK!k%@qzoE^Bj`Qpu`Z4v|{R57s~xT z>HMXS7;8`Fn4i|L^F6;kE=PUym4n|Gz^5>`{RyZ~?4LNnEKt5nSSDGK#9 z(tR zg*=Z1cD%VcdqnyxC%fh6iaUogw8)ovWNXUDw;_cWk+x`_^#&Gy@M+iO_vs1J0FO#4 z)=*F}g%|$!N#WTVjqKV|DIiq;V&nla1%<^;4r5e>05fkDMC)QN$(=Uv@8Uy^;_&+? zg*GTZN$!{N4DM*#HxR?+|MKJCb%sM{n&7(i6jFNXS_-gh`}{rs2?n^g$s$Rf^Ap=E zrSd=j+v177GZh;nFy{cxagF z;}*4vLJ?fr?Qi$lwS0qaTz9fZ_1aRNtdJe`so ziiz%<2g@do(2!{JZlCp{LTO&KKlilK&bT~HlD|u*1F}o8?RsXiCSsCC_nbd3Jf0q3 z2DP8yhasKz5nOPKTQD+^(c9Ci8)IvOl&D(E{I2@32&IP*4oFg zKr5md%1v&WKqteJi@R{&H{lp4g>cu&z}zoiSFy_>@GO_!36EvYoBg?)|697Jt>dWF z3e)8;^y%#=(t`Dq+jIU<({-H5!C9(|G=;k&!S}6oN-R&9!@Wt(`e-g{+f?+=7_9PU zk%mQt_2}D;2}*skG~w1MBI(4!gSAcb%OvFD0b1rUq!ic^G7pXm<83Ax4lW z&ijQ|>)%gh!cICW%}uKh<8l<0H>{}VHgoN?J*?|J*hQlX4mAZI&sS)53(gX$PY50| zCj_}$kvR~7Ks1@+uI~5)vki_PcliCi2htapmp>x`<0eLW`_Yb|#48NK252;@kWH(! z<3iym?Ofzte}ZCLQ(bLEZ_(pKsEOi9ZWAVxqv65T_v!?x&I1$clD9_1 z^5Be<@^(vvs)>q3s9xQo-}9xfNm6bGnbl8V-v=NdjmL9<{r*)*G z3+300?(lh>Z3w@sMPL+c2*=bnIIlR-E4kxX46})!PO7n#il&+s-uCnjkjMe)UQO(B zMej93b(S;}(DO=jVj$#+tT6eK+J?}lOC#@?&Y7#)RTIMlg8h(WrXc1|_=SZ($S3}x zwSj(d&MW_cZ%cXZ5}!p?#GuvkZZA!vD3#LSM;7B(hESy#YHEz#s41%x2yiI=t@{6U z_?i=L$T*Il?h2i2M!mK9GQLT|D*a8GruckPJ+=i(PP2b@VK$y5+z~lxYUV zYv|jP6C3+lf@^TBKt^%b&!1ZCH8ZK(DoIY9 z23JSEWMeJ`{=9nm_kl4LWR}=|gcY!O@}1W+`OpON*D;i(d4i&9rCx71{fKt*U+P2> zm?g`?u``!T)l$PtcJ+=rTx7GuDC9eiSUQq_GYz>mSY+rjT7BVtE&Poe%Uu>V72C?P zR1oCwic!tOH$yNLT+6OebVW!X(N@)8qZ7SCmqTyID5AxXlnu+(Dn48$4>d(ttF;uPAu{!QliB7t*sCFfAA38MI z9R4SFoNd<1hiTz&mCeBUEDEtgl+~Q)u63HVN8{cNo0|N~T`35c?YmYzA z&uxumCe~EQgwY&UPxx%e&_9h|)>~alRLliKA|6IZM`vf%bnootD5rq>vivVJEy&%- z;s(_0_$Q9~+!${cyItkqF2 zjc;!vTaPQleNf+ZIx2d5>moIeOYn8;$8gYGRUB3sDOyvexVao?(5b1Z^L`t13ySCG z{TJmwK$`*9p1H+gMJ5z$yMCP(OVfhoB#Yb*c%+9(o1y4Eh{BsTuu>Qy0Xut`n3*ln z=Vf_>ge=(oot#u47j5RK4`G!B!f}P>+Y4jX2U0z@-+V&)_pTm`b0vuw5Sp0#?Ce6{ zxb^D=v384(>a-bKUhVEaJnGXm6lY!##sBIUxZ<5;=j4?|ZWJW36%W!CrKS69N0zN;@70u9d*oG&*zVxle#`3>xfkEQK6&R5&ynkX4O)vY2A0mVQY4wFtE3`owuxlM9e-ZTBnuhCI5 zqxxnn7{8JwL#3VQ%mO5aFV&oSBUy2B)9t61-Mn?>^GK4MSm0X zPaBXQ)7T4?k!cg2O=H#nm{dsm0onhdFv);;rnqsE>&^!v?nVsp5e&Rz~til4-y0E*hNN5_l+9_G5uKL9FStzGd) z70Gy+el$yhy5?RJgyclQ4t?!{c2hb4AnX z*aCTvL^`2>+Q2yh+IXob70PVRbBysTO@w5R1sTMM9?NY|CJ&;l>h1ijWcm( zK_~it&b7WMsH{pJQiF}CQM8xY%UFfL9;0|3JLY8^LKm78oXkQ{gtxxr%}OGJfC>8y zZML!!eQu}6)fu!c^jkb=+#0sYq$f|u5@Q@Ep`Z~(IgKPnF+X}^aQ&7fkVQi}KD9m4|4}`E z_;B>9y=sX<0lT$>{&4#0Yi*)b&gUL;GmZYePP3Yrh$!Bj>514hJ0C8+4U)bD?I?py zGOdMfFP|Ab4%s6Z)0eO64y{U0Os>>-lZGSn`NrX+xIYehTT4sqgd&7uBdy@Kk8=@w7VxF3U;CDid;oU?tbj0_wR|Owl~T(A7TH3HR^7%Bk>^&V zf)-Yp?X}Zfp2vf4Z=E(>NohliFR1ESELqN*AjJe|x`_!1=T{h;N)2~1M|Ky|RyU5- z<1zQA-#~u|Vt)(IoJS=`fj=1)Cpa%9@e+0bFE(Akh&$+ejbICMILU&!pr%S$?w0#^Hjwu(f6;)Zm(f!)l_GDsR!^=N6S`nsqS4ucw9 zonQjlK9FRBQILHv+K+KFKm4Y4UTTB8F)h=yyP|w{>$-dRTPXCRsvXbx;=PVQEwHc7nWRHTtif2X!SyNUeK!e)&GG}Pgo%h zLk(?hx|r!%m&y6&1h{cg9=c6*{s-b+v|Kj)bNBCGOUe)a<$7yiD{NTFP?=WBoE<@{ ztD$y|`E00A+5zVf4?jOtHD#@1wL(ex%6Db1zbdrlnDxw%;mNS%Hv)E+`4avDl5EC31sHbG(5N|_$#?k z$j4b9jhcF7`v^ix9<{4>O=K0w`G6G~c2O~0ezPscnG@gavvoZ}gbc}l84a9>j?GJc zj*hWjr<+{XHr2`B8P8vw@po5~h;NS-CrvNxPgD;^_7dd^WQx7AZ~S6V&RKfpX@f{w zA)390Pd)V@baz~IOWH80AQ6lixSQM(Xvc-pSUj5pJSir(XMb^xi>Ujyo=?nCrd0D; zRQsdUjtwUR$W+`gOgE>3LJ2~0No zX4blNvTQCcb&Z9E%~5L24u#Ry4?48%-j%<)QfZ{?h%#SqWehU!{$l%RX*aJ3&%3fc zHdK0VP$s{~Do7<3*)ylO@IQD8@=-O36vZD9E0Do{XMWG^+(%Hk+`+a(!4Pg1AZTg1 z0d9UEA|{A7GfK9XO*V4^2fb-`hwhP(-V`(k#$^|ewh;uDG<)5k-(CH zGzgg%J$0llox)L1)ziM;=rVjr<;l@{+3)PRa~exl=gVxx(!v<0X(eK*Y}oH=1gX4d zhp(i=A9;cgW&&>#bT*{uQVXHCb~ti25^}X8cJ< z?j-fXh1P*swi{EpanIf7r4{hD+3yfDYmux&>sf&KRJ@$vB6x1wB3^*Nmd ztqrikOh?D-dPidTl_MJAQ=vxqUknng4uQJNRZAd#kEKbIo+XL#H-%$07yIgmpC}4sS@`BjuSZH6PThs?UKlNnvBp*mWd2g2 z4OAliKE2O*6EdjKSADh9Ga9b}Bi0C2TQW}FCI zcb2CWEQ!DDwJL} z+XN-jC9086wSO}T-)s|dp}?0m21u1Qmp zu|mT;=DlQLcGRQLp98u}n?ASW;2#Ril$tK(k%Ih2Ae+a_G2T~0H?`mJiMy4nk4mlV z!q!ny{*hQ+g)Y~Ux)hU>zpYkSnS^ADo{H?gR0NW5u+OnhI75Qn+`2tGc}$%Gr=ji=SqFrk ztErwNlCK>F`M{3aFVF~pcQ4l=nyWg7Gk>tXop(LSqrW30mrf*#wg-9yApTFl6Y8Qp zw|BC9Zc@0svKFsujFp{mDx`pVO~ovkoayF@l1Jx7E|;zdYnGi57>~COei&K84^sekDrwO{s9v-Hw1l{X4NkB8 z-bqS%e&+M~%&Gdxxg02)fL_BMN3kV~O~Hryh98d96h88!@*GWct$#@7Cl3_=I*Spp z-<0cy?9kqQshSW$*Mzd=Y6ow4Ucj;)mUiTb# z+HFX=>=0F%zKz${d zdt22o&fi3o#m}9*0Kh)=gms)$n#{H>H!8VSKq90}i@yXzYY+eTGJutTg59?}zuSn7 zAn2W=ElAm#i`Bta1msx;;~hwdqvS*UVV%=GSn_EhGddSw^Z&hoJ0c+5nvDjcUMEvO zbq>h6A!A9kd2@kNd21R51;shjf+Nvw(x+8uvll$f6?fnesizW;Xvx$LW zR^JQ${`WFHK>7gk10tM}dr{i>1O$TkEvkLEGimbx5k@{f0`o1&_WL7X90!Cs;!$QYqVXY zk@tBE)C=Vo;k!1ptQW6W=?g2m!Ev%t*z>Z-b)9~%>2|Vb zyoaNiWQ!LlT_m1^S2pM4Y1F=IECldpAg}I)PNNu>a}?%hqoB}vDJ#cm_mOFm`1`+V zkBhR(`g742VRc)p@pObU7>HQWG;oqnGw2_zZsJO!@TCK-dK_gjrtQ*FJK%zW2^ zQb`itKR!J@WsX)VZeLE+r7J{Nl&kT>(SK3*aImb&C(hV!4LrvGwsKWQS(@ET1LCu$ zVGplFE=mqnzIToh@U~%}fz)r_@KdlEf^>e8xMAz%`Ti7N%>2vMprK2nlkqqFV^GrxPeHXEx2(H!jsxJR*f}`V zgqkv{Fm=5?tO`v+Uj()Hx?$fwk2#KOZtP``Lm*@-9O{cH2c?^}t&QWw>QdfZ4yVJ; z#!jGBwBKt)C2Z_iTq9`6Wi;>$DpQA8B5dmOu0{N0dMAyBa@-fA6O>G9QdwW>%o95F z%To6e8-hx?4oU5Ij@C+3?qMZ1!a1FW8kOjGs!k!AILPR+_-v16t0>>&!`Z#XKW1mkp8u}}VDqR6?ko5F`(XE;Z>f}m z=w|+tc>cG@x??-%1Rw4@qo3uSqGDB{KK;%`JdVFHo4yh+d9;^VpgE}t--1AZy-mg~ z=}~Yw1I$apCpkHfYc`}-+-Ao+HV7!2{H8OVp_P9A6kHPRp^FKuhAw3uaviuia+gsM zABBa&vgYq79rpG)Pba!NI4DNrYUnk_`yC_ePjI8}p5;5esXa}T7h=qHq4oAZbsGGz?t!TK4JoHo z4*9XpEEUyee#MK?m7d7viBko>&qGv=vTptGC!qyceb9e*NT!4Fb zQy)m7$49(IifB+<8=Cgy^HibV(bWZHy`~aPjs4J5adY)XMacy>%jVkJFVE|Iqhs31 z(5wH_4SxJU^yPSqYoER5ysmP?{l@*B7zP#`<-u~4+1AcZ`?xFZ_W+4Jt@+QM$(tkO z>+S1HNO}z}P&`xqsCcrKuI{n{Bkb5n6;RRtFG?y-;y;oL#LYku@R>k{gBTS@>5`iv(OUqWfm)Y3QEc28p58v^0Gu{h z1SgbZH?V+o_Euab{=Y-FQTmr=nBr`FQv<*}*-Z~u%BaElU zL<;^XZppu~8_7wk5DHRS+z6UWE8_>X#<2|)viM>Mn)vKqCEw3q=0PyOv6#mctA|bf zOBInnWL8J9pP9rwq`ioIS6>NAJbZZrUpAac8m~xs`PK6?ANR1kz4E&VopTz7%<5ly zf~}ZYzqXlOu)l3HdS#zxjUbx81-YW$4`(_$sC}QGyP3Tb3l?8%{@r)I z{fF*@#atllJoBang%FAMM^cHOBBvW|u}ws_x|S{5zLR%xN|)4f7PH<#9DWChDXL@F zuHAjd+bjbHQ5IsieT>iL*^D~YX^F7H^r$IaL)nr85nWD(dUumNZz#xzR(_w zNz@|ZRSmLCSMXlW9&bD_;p8YXVI;<(kK^TF(3%ZI@k;El4mvo|QMOpMw-tuNOZ#l= ztBG)r!)z^cJPj%LXmZ0bvA~%s^fHj=@Xq3Bwpgd9C4J%HS2B|Q;ff!v@ab+VY60)( zWe;~_NT=lcLF)D|Os7@XSXx{iNpsZpzqWbg-QhC=!(A*a13dDeg9gIBHRio$#t&&_ zFd6LmWiC=FjMe-OrtY*y3`>%nXt)$@R?R5OaZ)O#7rqMVz+~{zT)&OM`g9CmpXLZP zt*|bFXdU!iX!u;ThM+K4UqY}NNE_pVC3MJN4~buQ5)GbXF=^_BOw%b{w?{hm7KP=) zgLVZj6B#o{nQ3xa;XAKmt7GK9lIFO1iWoN)H*i6d7YlbK4w|3mow250rpn8zvA=ZW zSDZ}z?n4m>?xm$tUDz9BHAk$SYi5z4R>gYqcBU)UdE_E9EBl2g+IJV^}OKA~(A%w$a!Mk^(2aTQ)T^kX2ftfP`Q#%>C z(U=Po4?3~0^~giVja_N8*V;rR!QV(H)C)FLCRz6}_1eI+>|9ygpvJqOA9DW!Tn?Z* zc6eT!;6vW{%3bUJvhg^bP2`?Du#-QdynqiH1 zr|J8+6%Gd3#^V!Sty?JsL{TO|a~(GGdvI=iueL<5O7onlxHO4oJ?`|9u^DoAjFcoI zTg-K`r?T@WRe9m`Cg0TJeih{XC0?dx_1nCzsObb@Gf!`SFQEvfbJ&n3EX+Yrf(1!j zXi&mCh_07?W+;!Tz>IY-kX8j7b(=bnCxw@ty>1AnK!Qk+_v;AYrEzCBTQ%921-o6Y z1#NGjnuEu!wuFZPZ7pJZ<`p;>gM)*CX)hZ}z9qjIi{nB_H}!eQyTK_z2E~TMj8-%%_`Uros8=+mE#<4M)K*NWWzPRH z*MV_h9;Qr`IQ5oh>SvMvL|ESnKz!TsqTxhUV`nHvzI-a9I;kHcQ_x|3HEjAI8li?T z9;STM;{UIcRUuxmNIY^X{;1jI*yf{ib2fWrDYt3`gU(MMzgHxq<)cPe+sxy8Q#|>{ z@EeHAE9=4T%rFmXVyrC2@Eo0i*_We8=1!V=Hx8wNU<@5*WKksAaB}3?AG~|67KKY-UZ$qIK=csVPv$;UIcUd+%{Rf%j!=@3dY4-A z2UyG_ahO+1ve+<&3fl8G85p>$Q51OiUd|pDV^e3{%2A4=CZ1GrlKrvaGH!hEQgrr#M+C(Pibtb(r}Ba|gkv`iqQVphXGc}nvi!?7FHe&kwu z7;W*C*00piQx|j!6ZqGj`0IofBF&LNio0cF2kTh^t;g&*aMK?0;xF%djfAC=1giAkrX8 zcS?67-3`*+-ICHN-AH$*lt@YEC8WE%TjqQ-&+u3OaP^*Z_Fikf%UW?W=bHWLizOkF zLxzzqEF@cVyoJ3uqaDR_hJ&FsQ>5NV9U^bbbn|goj;0-dR79z)!c8GOG+@Mdth+nV zP=3DnU|6CD|G1jelWbaY%o+;!gQ_@bqVyEL4=)oe)Z2tKfK~mmDR|PNEF#cn{hq+Z z!_(QUm7~{`$A7|zK9NG@luy|zqmrr8NoRCQwI=PmQskPKyOR@8(MB`mr^$?_7fwT_ zCL54;-hS8;fx1i_U|!hJq_)VXU`r#>G>BnmR-?QtIut-uTw)Vc^9m5}ZnRpPVfrk| zf%%Ccb6@x62fvJn{?1vU68TNdAAZFKPK(5(*g%Q-8d)mpqxItov(s3gHOPS8;iE}5 ze%xT2PpqrR8q=)+;$=WEmn7KFMBsKel-Oll;zs1S_sksIpf5oeVZq~K{gBkb)^`2brtskFsD4n#npkR$2O6(w{8PRk zMc^3(?3NFggPvtv=ySkq!h@$+Dp_-Cf$F>a8LG6zW|qzKt>BA?Ll&qdT-%NvWcJ(SHw8MRx|Li32+ zP{QC9m0NQRY=bTXS=Zeq)8+x?R5gBm3HNi`qA(dFdl^4@a%`8v_W(5shk1jxY=eK2T!{gYy8(>}&Ai+Y=SGj|b)IcS6RRjaS_hShCaB){4N=PmGLD@5$E=tQ{hZQ7d2Z~3o)tu;cdb}qU*;f!<|1|}%lg=h^vwzW+eco5E z6G-7a27YFuiU6rJF||{m2k89QmjQqaAO-EVm^uqy?EW{inoY+PA^H^8iD9VUGkoW1 zhhJRv$@yg!#cbf=4Tn*mhODN)aD-HgGUOi9#%=SeO=och*0l@R<|IL+?Gw;toTyMs zNRA^gu{I8dIz}W=C4cXu<3jV~!K?Fs^F)@Z>s=;r)6p$m>gi2mPQH{L(y1?U{Q;@j z#gHb)=NCydqkm=Tq|Qw|rhMAC42^Jv<%*i&SjtA+$qls_vK(P;;%3J`_$J;GiSebC z7GXPS4KEA%JCv#MZ#j#Yqnt|O4Nsj+dEL@ti-cr=IA7UB{5)@mb*)!xrXNWiB#RF|Nu*s_XKF@FhGH zO5Y_!xTmth(AziK&Io-p{t?s*ldLdjQGF!mVl=1fO~lncW9rQe62;fzj|~J`%C~(# zsK$zHgF4;O37;3wHeb@wt?miqIquRoEj&h<<3A;6h?2=jgip`4N&Y{_F9>$x-{^>cc669Z>%$~D{(TVa z{43Ly+sJ5QYEk{Q;Vra|e61tE{;z;~W4@!Rr{U&y#;6pjx)s}*pRsynSQJt)aL~@_ zUv}vX_y*m+i^3Eps5va)O4psyYG3+X(DR>-Rx_`|rs0J$#Am*mSGDdExkP`$i_)nq zmEJHD=q#1KaYl97-|Y4EPJ1WTcBl5fs1^7R^!yi>&Hx1D`WnD|sG(+lkDb!MHN$o8 zWnI%ow-@AbFL=-|VO@eq8a~e=q!fx9Bm_K39x%@Mp&k*aYEv4Sa_~jc3`H z@w?gR4FkSkK|w*lMGz1a

    R|{ky#Y(xn#Udbz*4x*X7VfrS^e3;eMFUr48mVSX=! ziHNYOKLI)5o$*nj8!jKkH&cSp1Ls@B(-Ti!R7ec+`@*J|PF1m*RB9*sLULB7-`KiM zHUZ+DB1meo*);lZKhKC(?l+YO_TJHA7Pp@lmU>)(Bit)r0`zJ+7ywa1&Xmw+`lG2j zoI+`yO z8HK1yFX60YSL;&i6=o+pkxqY%!BMju3O>R z?E5o_dDU>r;<+{xQDT>dxpBsSJZCV1FJa(|SVj1#(>wtJ2Ph|ce@)p#HItH1;fUI2 z-QeMKgB3=3g-RFsC0~r+z+>U2aI!hg#|b0UIkaA0{g!AS`Ax=A6?XMmKC@?h3 zs^$CD0K|vii}%idtSdcY0+J2{BbALpshp38DV6alMDbMnhB+iOB5{NyRrk4sivpQE1RZ>E8#mH?4(>W8-J#p^!O!p;otUWA+gtkkZ7u)rT`qq>|x<4*F8T zZqja}6Ib03+%%D{kJ_}AwBH~|ftoHAWAPA+4&#-zSiZ{)tJo~HjBak@*au$voO$1<5_AEjojhvCt}yH1i` z@1?0(y~jg!^0|hQoEgzc*!Bg=W;(dY`}h*!WV@?_qnAgV9hB4YGKb{^5kGapkh2Jf zLpROwCWFf71@HW~^O-1@_e&J>$;tPJ;HwwY0k9xZ)lxr|H*HRJ)!yOA4!B@VQV3+r zg|l%~WDex*#2(F4uj7b{<~b{%qZ--0dUGs)_E9>l9@?!CwciP=2p#qs{KAt;^Zhq7 z?puM0$w-)aHGAW(7MP;Amy|(C{KZG6#PStt?9Ib|s}w0{Jqn>*Q$G9xXaN@#4xh7F z>%69*tfNi1LPxhHgOzuKnfNUFuz|N=Bcsz3(7=jg3eBoMO-;r<9_sQf6I0+lD!R=c zvy{|0ucXoM7uoKiDAPj;!waIAn>Y8jmS`AxjDsu=<*4!aB{=rr=l>lfgKtZsp2H*jbuGi9~7rS0fqSLk!%XAo%AH#GDTQ3wk?*hSUKtpmy8;H${F!>DnMPo0*U@fd;+ zbK4yJQc_>ejx4mULSixdZNPzG=sB~x5~1lfYKAiY@;|PE&mI-jHgM)XL+dPtc@SXPY<-%s zX5g^yN_uDvF+o9$o>TjM{d`dJ1K`SPt9RF9tw!`PGtIi0|4s@aUl_U~77;(2wZSg! zhTme?xj}4~_A_evva+1iCom^UVU(olrReIv?1|@FppkLqP>x=|&-RPY)^J40nNs~w z6dlAZM}{PhZw!nV{xI|#K9fKHF7(pBzc}w_S2R}$ao3Ull8hNLhhCrnZJ+nGPd+RB zFZ#uqtCB0eki657zUsk@FiRlJ+s*|iy6lBtbfjhF8RE6f19+Cj62|#S-5082=fFGv zA8!g=0V^3E@9>`5!R>S6;D6MukZ?Rxnmj@7w3n{rM`o7c%>H+cfj#9Jaf5A;i7|&? zx;TadO)36s#+5Y-cdeA2PD~b250>|!Rp6F>{{nNz>or7?9taFsoWfOVupDCuhlNhL zkuVTX+l)35xugM?%8xHe#ZJuRxqXRd!?5k~b8=C42Nh$XScukbu$3?sr_k6@2AqdUQwNz%&0h2^HJ=);bf=0E=ej%8zA=uuXOT~ztd`~Ojubrb zznGP5qK-uhJYcKYJa&Jw(aUIGcChMfj>6YhgMM^uYh8$kqEAzf{7}A(f|mxDH7J-s zEh}Xw$0WD{;Vyy7dE+k-0|EqKsMvmIwtcPC=uxaVTynwTOXiE6>a9+6_HjAg%6Guh zKVpvFLv2if?w{Ns%h~Qe*OML^@>AMB)rRc+1NIU{h21U-`#>J=n7?d;V#LMo<)k$y zQ^QBLqC7}6I}(1eJs?9U$qbH6+rBvs)%n9453XnV89N4&)%HgBRfc7mnH+fm#4lL0 z93NK>qf~hV%U=n0PN_#p?J=cj@5uPk>ICwB#9r#8qMLc@ib2XGv)enqyozO{nq8Tk zpO|D$J~CTv3+|+<@HBJ^y!N*k?r=>}3-I}Krl)e(fyvD6WBTm=xNEgdO=fB~tk6;h z!(T(bZ&%tDBc0#hbL)lGPA(`8i$@KulcJ@a4*s-%X<0266zO6gmZs#w?;Pe|Nr9LC zZU2(^GX4)SFNJ#!Zza(WL8Iw!&P4o%6V{9ENI{Z}HNCHoxCo|Q`Y$25;3AK757MIV zOTVHhIF|YyOZACt%}^@kNDf@Atq^z{r55d1M&gA2{j96I0KlFUZ!SRya<(S7~!{ zwL=WP;JC)^9(gidP;$OiKGH093QDU$aSX5lI9K;y&dI|KQoYEUDaFYz(N?~0Zj$}D zhgk=U!i^15kzpdO91i5m%J{Deul2EN&e`jP=IZvvh~Ov%KZ^Pr;QD4eG`>ljgpI*Y z9#v(`5>3(Vb>2!Zx5^lABSbcP6k1(fRUi&cfliUU9c|*W{(7r6vagfnVonxHe)OY! zhXufMR=%7ZRN^?`M;%D>{hWPOJu}#Mbi7_Z-#iG>E&cRndm2We>k&ZIkS5fIwP7L9 zO5Fc0Z(RPdnrh#ND9UGcEHv&O<~H?u52bu^Gg5FOC7$ceVM4(V@9V(Ix0a^fblK;= zG(A9qR^5lCgkCdQ!?Pj~$`c=(hJCvQAc&o8cJX_t7tMB(E*}<#vX$9F4QA5GPt!M( z7m9N9?*Z*eUev8B$9EEziv=&QZV!GWd6y`ro>KzGcnN2S`eQ?&kmSa_0XE^45TY zQCjol<}AzJ$h2yiO?KYfD^{b+h>VlX>95425$%ZisiDhBg#t(bZIK^$!jCaD-~3)I z%qB!o=+%%IpbR3Fodh4_SC$y1+)|NSK{NA2w7syi&iLq6*XqmzjM##t@eg4C@etDS1M>pSbKJX#2Ng-rL~%OG9v4 z+M{^xfzXAhMCV68v$&m|kKIgcp6Mw_W|;~qknj)o@=x-e974;i)<#WmXtZI(cY!-0 z0%TgGWiU_@v1YjVZ@j!v4U+`M3U6pRy5;`78Qu7RYg9H-*b%`O?(p$!=C?vyVCr-Y zx!OfdLkpXvUF0#GhgZ1VyuV*Hr1Xu&FBN|`Hx9=V^ALEUw;j?y`k2$4rF8BnH&7iM zR*RZg)sEjmM=E{3*QWbPy_r=z`Asf2*ySTP>XUH&Luj>TW zuH~EHAUD2u!t8TU;d+W)F!_7u?zwZ6xbb`3ESmb6c=>i`Y7T`mSULx;_z0STkoF7n z!vi~edvI`ZPK}CFTLc6RKd{@4!%BXqxrpc^!&=DwbI=tnIdg)z=VYZk+G0)t2bGZm zD)K^balZ~6EZyM8s{T%|=9*(XMC)sSPbp)08-5u9C-YI(j-8-<56YJW6;C}H#i=py z;k@Pj0nXyl>XX|go!M&R#i1ABwL5SO`1>2wNJna%L)Txg9kx`e@US4rN$FQ8W7WtH ztIr$AHUwx>_1&Yw%PAaNQwwr0jbxXD76I_C(P8NPP=y{;DV){yfLB>r*eG+orvhCJ zpNLuZ(~s@j3^i6H^}kqQb_>Lo^PW_Tk8>t!=Y#ha<1tBu1(L(T2FtyBxj$NF*0^+* zX8JpsSTEI%nteb6>7hO=y#xb?0Y|8Fg@l~t{GIOTk=4c8>S}RHd5i~`(%NB&%9p~z znhV*kSf!H0WL^~6r-zh|5Mt(VY<*ztBCA=fT7jS57xo%fA|%$XE@R%@f)o5T4kZWC~kggsD(Q`+=Q7O-85hs|$a8 z{I>^Glr$z>h+dx3H>Nw_ZYmt;k1<^dZKwZExb;`Hp03azcl8=)m&zR5ZCr4am}8#D zB)FEgX=EOxs*%Xgr!S}}%qwkg(y3PTrSN(!?lPdi4;Q^=v=*8s zp2^qnlC)=->DZKMf8SXOSe$_Hi1%+a4(q)u7OE0$Y-^>Ld)Eo0;qQuEa#cYpNrT6T$a(s)<}H4ylZ>S;=yL>?alCpW`(NE3w>Mu9^o`h z;TAdXmY{;PNMZV|IwUD{-&D?oW4`xCo~Es{=9N1*^Z^c(@3@1+>OqC)^YZ**`GkD# z$u`UY^F#ZXdGg6RryX%u_T0wBMIAK5hjyom4P=N=tmI)IJ<1f$pzEd!OCxPQ7?YEw z)ZOzU>D|by{_&K!3-0@QNMAKZr0?P-eNk1j1U-scTOQ8!L@hB9UcA4G=Mj=M|KAI6 z;Q9Wiy%ASLNiHO4#zKDHfDS&IcdF*Reu;wNJ;-ygv~rIwY|EYqYQxApxPBGZ@Ab^s zQr;1JaTr4RB25g83LUhc#v#qpUnZ{M2MFDa2n|9bP_mW2EnAqo1h@s|S%s|6^d~;E zA`5=9r*kdQM?F@Lwttx3m+w!E`mrSnxkox`)G1q=HHSP}w2`JHq$uCKV2ee6%o3J` zyfo@BRCIsVYsJwo<5a&$wE1SQu_7g8fM{iv>%dpqF&zHcjpOul=QYm>j^ikFr`

    wS>$Z4vYETqlmY`?xc@!b(_QRQK0EW|rCKu~j(- zD`PsM-Ta8rWJ0VdmpasW0fd$cF}1By$h*&oe)PYxAS}%K&AY=*g5ZkHd^XEq{w16f zB0$hq&cl*6p%Y$?Z>Bx2P~Wh|&zg9UwtS<$x)!+dEd$L0nfM>MlZ=6{i+bRx=%*h> z#6SA?I=#^etdjfUCnuL$|4^`MHXwk(P4b}u&(dMqVA75 z#$#;$qgM=6t=UR|8wEf#izDX9wgd(^if?l@Him~~O#DlDoe6_)x&Uq5E>hGO!ZW#3 zm`sUS+~)d}Bh3{xYw+$3`;0uA&`BY=W186TU}qI#V-)&={iIZw)GlKJ5az%(Pn^X1 zqbf5mk)-T7*n3w`up@#_hH1(WS2@NLcKS4q*CaUiE~1*@uaU1>qq#(AnIFf22Z%W~ zvuR@v2!qd6k&*IWqwKw0T}@Gj!6O6?=cUXhe4WOJ1w>A#lTnU*+C(5PI%T(Y6XHBRNU*sepd`>u_>nhM z0qT7Aj~`%lCCme!ZFErPutTo!RI0X4<<^2=PA**Gr&)0m#!*KApT%kXW4^k47^6^i+u+djO|%s`fX!W^rTW#(xeT zxE{vPtGzfSryH0kT{cD~tPMM@fMhjY5n6Cm(YXH4r6F)=Qb>G9sEPmCC7IAkiHC;CInDE23P z4AC3IY&$DX@PKp`Ny|=V1E!<35!)jg?h++>ULx?FV@XVlrV^o~qF}$^dd@=ziE&~x z%3|83)*GrEi6?lUK@!;*nFiMPM>*RN?R-LPn-mzcv!GfhUSh~V>(0OLA#C2tsc}4uFY(1teu4X)NgC22IQ#d9(lZe9kDSLy|?iu2QP>W1uWQTlGnm9p%pd2IC@#DXpdG) zp7*x=9ClswFMVc#-e~%_T*@ND=uE3R_DmlbpPR2^?p5*LPtF6sFS0r^@l5vRu)3YK zO6#!DclzMf+*E~PYVtL>^!sDw)EmE@-7_$$lEUS)5?n)gfeK=`Z`}gmz>+CZiCa_Y;dtwjUO&cq--14UQO>qR1G%<9|}*u*)mvGR@q{0YaAX-1GfboWQ5U zh~be__}W=Wib@!EDjZei78HKNgslk0BoGJzSi$raY7A_d3|;XT0PKP>zpRXwQ^&k> zAt2hYPe0N9&6jW8{+jAz{4v<#p3>&=CqT;z`inW1(p|*bq*~cqB(TFJv-Fp*TQ{q_$uYrJ_r;?e59b4%al&7o%J0VowdUAy-NoUwyogk+ z1)noI@-*2;eh3oxEf>4z4&s7+hO5-reEtiOClLR!BWQKB97VUAMI1aX1%nAZbx3WU&b0=wW4N03hN^0K-f z2o~{yi9i_aEYsKnox)MzN>H$4n=4U9u$FzoM*QI~YQz26EBl|m#*=Rd(aMaFjHhj} z#-Hnp3_}*%p0>Gs@@!eU*_*ecB{e%;kbpTSFuJvTv+4df6vDFZWqf((!V~ zKbMRodXiH9(m-^lq`ZRQe_AYz`I{-d5xfpd_*Ym?me0Wsj20lnB7y~pZ7k@7c1avx z@S2DZWJUMj$cVG1yGw+^3ncrsy3M9gq4{{h^H}1VXN!PWlZ&kd>e)eI70&rgd>lF_ za{r&kqXTs%ATWXd^XBXrzQrWpll`n~7N%Gw^2G8|XM-4UdTYP;7&FXqpbbL!{SzMEmH}?k=5z!=# zfF7_K=!-FqrH~}866)J%YC`-q^^=v{%6o#NtYNu#9f|HhU;M$oSmC;vO6_`Ils{4Z zGWNfnuHXGe7-%K{2a@$MjKl>2*+J{58pDsZKJMTcO>Nz%P{&AqZAdfPDbM9U_H9KQmo9hmP%sWcnfRo++vq8%K6EiLA-~%^?;Z{n z&a!W9vjpqF4G-fUqAB&_&h~a$vK49y7}iGN-~ud76U|~joK3XS%*>PGf-^bF^_ZCt zbcF)TU3w-Q?8&f6X9#iL>K!{FeG(JO*2G{^nMBo3B{zf=t8r-dVk$6}U#+jNA0Hnp z`aeRp-O~|lvRTqn%6XW-pYdK?;7tF!>!Zr9;$i6w0(TbJNj+CZ!6*rP>TiDXT5v`e zM;^Cmz|BsS!T&eG5Y}E&uaOugY%-)oM8!(I%sgb7Jf`~oxYYeGEc4TE+WrK94Jf8^ zYiI~#TeEo|SN9I(^Fwe>91hf*7WFhac`ZHBwZ}QKYU|AmT6yRJIOK-0l=iew6Y|I{ zi3V|Z2{YAiDZbBrk9PX*H(CDOebk*e=+9Tn^{RD>>ecgqlm=evDR_OtotMnU{0L`i z(Tc;pUr^cXAE`Meo@omp#ic)g7FRNEz<#7n+@-;o7fN2j&~L=1pyJTdL%RC(E+efr zQZPgfq*|+RUN|T>?d23W=(@Lab*^M=L`BJivmEJqX*aUi&@hB;(cI@-?ekFX(0D@b zUMhLp$`Gz1G6Ag@Lim-6J#lJ|D;Pbk5yzcv&re~D!CyY&DGODpwz|!Qnf*aF5tlAl zRN%Kt+UT$q!%+qs4nG*0inh>|V^_uu&O#zTHq^xph7$9lq0`MiX4+%yE*TMs;w6eQ z8#NCTRLi#V%C|0#apvM8#X@=Ji;A+zyo>tVQD~zPRgXje$=Hfmj5;vq!vDBJw$Qty zP%g!?OF#z~ryO3<6}fCwwmNxXKa1%Xfhl-_is;q<3DwMJfFEWdu%i|Y;x22sSH0Lb zy|rqV&f}IF=;Mm2ReW>sy`rd%u6FBt%YtrQ)oK8zCzmXASG7xU{2XW-tpkq91~5v- z#m<;;9n#Yg5crMB0b^nCUmHeBx`KVeLpo~nlH5iy?JrmaW8%ZuJoqS1P8cdj{Fx6V z3RiHck8ld-7>VG`!iSVZG8@}PQ2TM+tQYKue*t$T$X~T;G`$P5zhLJ>FXr2}m6+U~ zt{)4{FHX9}w8vK5Y?dp{nkgFFj1j-G5>>(_1uk^PgWTDy4jmrwDgl%PA3(SO(p`7A z$hYTT_nT4Rpp+*ORuMA(=;Y*Zdirb+9#Ovh)3)1gl6rJdebsEw}Qfv&p6Q?cf@jPuM-Cx!ue$l(U|(QQo26F5>q$kENsi8ak{@ffVT z8(xM#Hr}v=^~zOG9&3R_uK8~+`t92g=YsI^q%SX@IL}KAE@q={H z*L*=r*eIIGWDv z3JyGRaBz4NKetr*S8s@Dh4+c28P-a`=zNT-$0?W5n15R zUm8fHpF(mEHC<&Q*~G@L6~ZqG8ErSTFYw&BcBqxJ&O=Bw)Zgb7qmzv_)|S0(hSXDj zPsvqgj>ACI3vr^7W?H9f(i%i0*hJr!+Nhe7cR@v6RLOOgvCrZ=k&In%SxR!ey^cL3 z3#X7Zv?ox9z`jc&s;*=@=vXvE`&nsfCillA6P6};#wR_^PazUr$0(7>w=7EOV4s<9 zcW={_c943OWsC0n0o+Eh)+7U# z{8uWfGeE7R>U?^ut)qjzrhsOw?u};Ach(qgzS9e%C8rmZ3DrC&0&`h4|%tnV;dVqlUn*Xcs6(Rs8 zfpa5G^0RJ%B%W5~hZSX&Q3r$C`srtXPfy^}TK@Z&rkl}QDjlYoRbDI4$XZf0{b9JU>A+xK)XIFg2K_Wg8ok7cFVD|G72xVj$DGQ`2GH~V>$noQ{rZ+jy*PVL z;jMiR6LqNtv^Cvt_x$quy~)V@>@4+|zmyFsu=LZ#^rciW_fRK2Xa|4o_NGOyFzuz2 zg!8{iV*;L-)=;fSx|KPtl` z=}O7=f6q>~OOPusOe#d5i~jno>>gVA>Q;5ocTa@sWv|>B#tt ziEgsH<*cr)d7#K$$!8&;B}Z2Bx(DFf2`mX=--QQCLNhZ4`mR05Mqfxy;8e!MRKc(^)q-`jy z8{4lQSe;*N4J3zRwO}pUzUV##Ck|B$&r6z5v4%h^*6_*v);?veB%OqimpdOF#}Rk) zV7`Y}VHs$;FCKM7mr+9KO+#^yf7}-(l^hz|zr1cLHcf!Diap&0 zb%s>0X?>r9S>O1U2c@D;HQ|1uNKRGdx2zPaa7j=Ltkf9Amgv2idfqkNr%Z3$6n~VZ z*}K|MgG*?2sVt{f6=aj^R(@O>hP0k}Ptv zz>>8x$KNE?cZuLD>VHFq-|ejtfG;Y#tb@u&ghC^2lK`!Or~0i?Q`$|4LscSX{45f~ z&<0Y@m*pT5ULuo^()s*c(s^+#MZ(Y@d8u7KTc@UZr9EakjZPfr`w+ z2ET3#t>i8Ha;NI%J%Xw^0}sOydR*-{1|M#9`1Wfp+$f1Pf});;ipA8Lb+v}l5^hd; zTB1PO10uPK1;Le!-5EAdkGpW51b&oh0r;5)N~Ct`*Y0i&X=^u(4;9u#&W3NUq4PWy z3bPC150^OV~zcuJ^=+{09+>R+dW^Gr**6*mJ3((35pk-AV0 zGm$h@mPg}Diw>UQ+c7b(d;>~pB>MH12AKoPjypj-G9f9wU@&=$j^0rm@SY%tytsuJ zkGuBg6=BN8q{pquTc;uFl&TM`sV{4BT*{+c-*R!nN=kGi@Cc?UMy*%D!vGLOb*_9B zSA#kYOlOe_PvX^(`Kid>T*n640tpjXdv?>}!TTQ2Mmg%RuMJ_Tq-%qR{W-a~{yVh1 zy+P~`Y^XEA8vDQUiTW>?ZrmaQVQ7^e@xFj-kyEVzRUE4C1TlmXYcls-ZC z?j68yb!(r2ggy9Fb^_B^s1!CPDd3saLJ6{Sa#mMXKzwGML(TTO0u+(n+_*Jpe7liv zOZ#T_E!yUwL*2c~*=9G{B6VLRF3J%w!6Awj<*P54)PbQ(IuWu*5I_7^Btu8LA z5lHh-J0J@^OG}itx)F=OktnPOcvm{Z0+n_{UO)I_3~YYDp}E@QPGs}_fe)2;&9BQa zgYWgSmMP`Mb2KWhXe&3G7ToUbki2pJ>w%$}j%0MHey5wO+aqpT^&vyV?axT*(OzG( zbe$xIn7BlPaPFL_26Yg+6nsIqcSNGDB)K}7a+O*W>mEgl0IvTb>X=7iChNhiIW`@O z6%XI9DJPU1nJJj0d}f0B%Z3uTwcwYrRao7R8PVv3#OpF(*iiL8Pup#?@})t(C}$;qPL!>jd;n*5y@Z(c=JKL!F*DU%Fp~PyY43Oc264 zJsT!=vroNmNgTAXyT7AiMA(K*TI9rt6TsxNHhd$^WhNd(wVt;jzE7;+6tjq|JAKE! zo_d}0+d;R#J(q;WltyrG9bx1hhK7R>FQqp&8;^QEoA6&V=Az^D$mD~73N%4!_CtCK zFBzQxs%Z5@BkK_(%5x5g%bwOBo>brZ2hZ+uD`_#t%tlocXkHtE; zU7z}9sGQ!$)65M?1UDaTGOIAPx*asusl<%=o6YApv0C)y7J1Gy2Cyqd9xC{LTV0G0 zIFTY~2+0)EY>${quCCvkqu#GGl=0{mA=S#lB9Od&*o`2LGDz zx>}bRsW*zdIM#5milBYyC!}_{J|Wst%E9I(z{|Z%wh*8H?P|N3sZ|Gohn*KrWZMG5 zE!a_xbNB?FO>9qxTDVef6v)p-{w=l( zLl(>knn5hyO{^3zu_&`gsE(i^;fa&*vSp{^(e)8O>}YAR7*V`hENjkTdK-Tr?CdVS zuzC$uZ8DKxIzp~?riEG+uvGrpc?9^C{*&PY)=MpOs4}WJvPXbmf3t_zftt*!mdcw z-?#a+7mJEX>ad0qe=o#tEZ~UN_H~$ zQyE{$2&eLGT>hYrcs>T>)p&lHM!x{_MnaMS&6UL^$OuDU`!oM1Cer{?_9{^(<#7qeq6Eus6}Hy6IcM*2Ev* zH`Ip_J~)=;;k-y`^G=%>$#8L^A#1KNjf%xP^22g*_H~rp)D8)M8Kz+qCae`{SaA9* zvr|(s>1Y<)oZt0}n|#u0!;ZmV0u*9UYRL^$f8>x`t`LnSh@IaJ%fzfhaSVxuusHKd zrrjnbg$5-z4!-r`Gd#r$I@diaDSxtlEge3JlKWKuF40%aZBD%2Tl@q41I0`ngV2mW z+BK~@)%n*6?*I1!L?GP;Q5!DJ9*jad-900WDfW5Z@13C)kaT6y5Dj~tN(s?rgWUyy zW9XpYIDs2czsqlBLC;xhDCMV7c{s1?Oa#=zf!)ncszLSf=_%deqz4Y;m*rv=hw(Gh z`EnETWDnT}=Tn|$>$*hSJVEd|r%Gt|ncOe(YwQsPYvahBUN%YD)Vn!+KhGfi7g zeAGSD%jNt+U+*2=+-Bn^Wek<*jt^z=lNVuY*3d1qg954ZP%$6{IameeLWOsjzu(p9 zN2?mjQU6Vk1Ked&UxlyXpf34HH#^+g9Oubl` zrX6!5zo)Y9`a|XV4ToCFB9W^dJk4s0O4uzZJi1?S1wVLd@nhfMR66SZdOK=QWn%$R zzOXbm+=eVz{IUMSalWTx(Xa134~8@lbpV@S@DtfM@k5Bq=`9fp=@Uleb$YpeLXtNbD8vaLl?YSHxjN9ePZX zzKqzlKJq*pCeJ)}Cf#W1a+fVFh5kf?OrvJg4BwW2N^I!(AOU76W>akK1b9zqpr645sY7 z6?%63`gK{KvsMmLk%%5{5UNvoMDzUQRRdU6q^#z|SHxhr-D9%i)rkZ-Vtzipt-2Vg zr{{+&fQ^7B%otUgpF$>c^8sLZ@cRQ-`R*>&+TA9yV(Hv7K;{6K@)K&b*Kh(Oi&6KS z>zNz*_w~gNm8Rd7x2b*($gpCG$VT6g*I8vU`r;_xHas25@c`V6r>7PJZilkWFM}>W zJ^o<&Az__|jBTK1f@6coy5!pY|6+t6#wOw3M9;bDkWU24ixaI7j#)Xpg83_q*pKGH zY6+Aq_Z^&`TMHN%7+_&FVM7c1dPer^w-gY;AgR=3v2}C^ERhOo_pYF0%533LvBlSz zEsB-ZWSg~(V;?BSpwf9iYK+GXHULrp*n{4`T6;L*FU$6;Bo8C)S4fAnp4hoTBU(|wFTNx zm(|&3Fg<=xI^-#x*$>GY@ufX$1@Hi=)z?a?Hp$d#7eSXkh2(l&@|fIJi)}x=(->If zl1RHyge&y!*+M#Gh5yx~4Hax^8BO^x*s5r@5>py{?1*#++ zR76$5d8+1hS~IUqh;04gCY`NJ-IdDG?H!ljxlz)pCw?-V?vhc0Fo#J&Za0XYl<$_9kG)zdjKE zJ4d|JI$={}+J!pFh} zG>&iPA6z!j7@tj4Yj6H+(NJMAi{?FY9gzP%OSHODEJ|mBtNin@tE0tJ$SsGmT6~m; zkG6>fD>m|&n>Bqg@)18QRXPF27UMS(zEC4C6?c5x`9pmXw#83R)`l8H?jCsv54al? z^bRyz!>YZ_FeE7T$I9B8`%-(5DYEpQU45oKLs6XzW&SeOQIhmE8OrOM8;+*fmh&3_QCiu0VWrbAvxh&ur5u-_jta%vT*@hGa?i#3c(iX!yuaYa7zq;zDDr zfNhgOr}qtb+W@Htnd-&1q75xgG_n(0cMf0;(yov`*c~ctBm_i`y0YJ}q0C^0h;xA{ zY>3_3Q!N%)61x0e+HOg%##;wukG9IMzpeNnN}@~#FrpuIqRUOpS!B@Nr4WVfJ2jo~m{BCME^$657uD7Rc9NaWA88SN_X8nV-@ZI|!;PVcAh<6%vLX zk@g7<385>_|7wN=&tmvrqG9d)1CTZW4GZL}2^gkN{%btN-*=~26yV`GIHf@=IXVK= z8E^m-zupgEY**#jTEw4m8M!w2Yv#X1Er#oCF?qGjM0k+Y^hF_I!yN2Cj| z7gXj5`TuHfe@{q>pU+%3q?_N%GEPo$5D>s8sU_?fzO{VAjo6T`SW9fcEY*S=L|!K2 z@Oba~2AsxVK?p91n1fNx)7{-ae<21K`9B^;yZicgWH}rf5#S?f`>fPQKXxT3L3FbE z2F`5zh3pt-HN(k1M7Ul43n2F#8{Kj(q?m=6Xg>d7!+^I?-}sW{OO1)k6y(PfZXs=a za~BkCm3ln+qd|r`+l!ZO^j#!A9R&v_i)}LNG{RxJkBuA)w-p#^qa=um3_oaTSuxt6 z_gxK9m)cG8Q7Tq^KRyn3CHU0e!$Q`}T~A9Nk6)TFDs7;vOOIzwDuGq}_ZF79M%so8E-_<-as8_9 zoS$jNzrLXGb1}8^N;pPtu$S{K1d-Co=BkS4 zcS`Yh5*U`Nt&BLBlfiVyrlEzzV*24D)$a0pxKEGpMcP(#5w}1N6420Yl4h%din#3G zBmc%UAIE@}0>E;et*vF2m9ZT9Ts){HjLE$Wo#uFLdj_4F0XaSdDx+R8!NJe((?@Jn zBH2PZfBmX1(kN5xbugGriDc{5SB4=luBLf6eh<5%aJ0$upw{jN zW+Cu~xx93?uqfI4a{UI?8H2+2#DA*dDsJC8`JxF8DE8X6jm(icZF4gPRBE^>=^gGn z2lFT#;28g4WPMELNRCHtd8g}r?DgG4r!3~fvNj2i;3DA(`Rw?0=p@r2Y`*M;GJus;o-dm)SpPT|Ai)T{sr|>tHX{v~InqueiS?Y<;e`bqu`HI})5m1MGL1()QvK5a zIqBna7;EeTeb}11;!nR+Cqz1zCZ2}Rj`b;?$NlI(e?ETx1c$k``-Tl0$h^U_o;-AF z4_%DH0naEUbcbEDUqrWq{ZwEc2d;!g9a8-;>G;vI-r#Zte}~Nihk`pePDcO7Ctikk zr(h~xWLpcLNXw`k@2V4@6l`jVq-x1J#Xphd%vz76& z_1Nd!U>F{jSzTKza8Li?OZ~wq!Oj5N)=?hC^(1yEuovF0?SzfL(i@$+=ba>W1@_3) zSITU^P8Ayo_JTYkt&VN5iw17JD)4%NI4`anfgDqXsL5){YM=$YC*#mv)ps9JT8=X?%nQbSw$(=~5ewu#Ocd>t#V#;aBHP9PA%{H$;T zqDAZT^jv%@UozesL)t0ftJr5`m|&Yx)i#=7F2m+p-JX27R*FUTs24c6;jndBz4H|P zt8rIuJQ>}jjZk!6LM>@bm~(IRyE5w+sU#$8GLO(ReE<{bw?Fb-XBWs{kIW0=`_+DH zES83;5UXWK7czq(O#dL zZDj2IG(7X;kBwe#T75$)V{;-S2Kt|zt`0pV!_Y7?!##h6RPEiBB{0y#hX0tx(q$$~Y2P)T zZH|xbnV1`>J}TqpRK9gE(qEkxq~KiD)z$T6-j{1nSLg&KbT079vRt81N1tCxOPrsE zhU4}Z^a)EweirhftwV%&=Rl7KxC<3^LBpNeuhLY?Ud>97ds{~2=(O%?Z+u*#3V_QEYQvUA+UVD}1wHyx zl)HhT`An1Tengb)Ww-lVyx-U-<~Sqz5ad2H179Z|kJA}2Y=sj^nq`11CYxuOhSIGn z*mbUMZEY^g@@e};!o4tIq0!x7S<=w zX+2-|wEPErWt^Oxt{)z(zisa9>@<9u{x{nI?*J{l+j|fh@*UL`&Qj!axs7S<5hqw@ zC})EX60ADGz5%Qj8X0ucM54?nl*U!pJe3|r=xKiU34UR79cLGBu*1%*;=y5cD}0ia zx;QDCCewYOj-eNio(vey&7tgzEd%YaR4YgdTe^$*YlxI5A4!P^^W*0#Bp-^ccb?%r z;GTT!XX(~{)0knPc?MbmaJgZBwp7F~8Oc91=~EkwxA;qGrbCnq<#vdK&6K9R%wW2S|Udm{1H?T9r)(OmRyqJu=-etY9IA6cT(?p(BXE=$*|eF-$>r0pMTjEaWZN zErQk<=$DPSQ&+3E81QMW%>2m8WD1`b@1_t)DV@VhiPREYaK*H}xF6LK^ZiuQ{AI;p zry3;;)S8u|t~SRxWns+G=VO`29w#{mYlF^H2bR)HEG)(<)t|xaFl2Up`MS|lv7sY4 zmlr#81M(G5&FX01SRVddP?toF`AzF764={RWVKcvhp`R4 z7`%~>zb)5@8neA);M%`YLMIHHk%lwzH2FDeal#x86qcqQuSrKxjLCRbQC>z}5A8{| z$%OD6YAKKxSv}m2n-Fn9ay1idKeB7AL6m~196ut(*kCv$S;C(h^ldvPhCUHfGZ)d{ zAiY@qH_lx$HLsOE5SbT}Pb%qA3o(%~ldLCye2z~gSTu3*$rJEyk5)P%wBrd(>YsXG zwM89>*MHxYUcE)}1R$8DrDQ6@ZEJjGuGYgIP9>*!iWi1hELB=!hNtcvZ_hVp)#ZP&Guk!!uNTDP;==Kml?>a@ z#Qs1PEnc9+iLDN|u$h(M36uK$8_TvDRA59+4yNyW@cL`w8XH-LQ!7+|a>WS28V z7nz#2n%K(JS9B8L_A%3TifpbO(9EA#?EqT}z=fcyp~#*7Y@3VKg>78?@Xs!HJcZ@B z2{z3}B655~oK`^2*n)LYV?(J__hZ(6pvlm876XK9lrq1VzbHu7gZee!TNe@bpG{$S z`CXBu@S9Ox)Q%ttB6lbGsN3xZq#olCa6=uXZG1q)-m41eB>W!+Nb(01KE%jk({*Je z=R7I6SWIW82Q#Je%+KBGPv~}GCcS-!R)yfSj})7PVf>&JBhh8IJ#1fe6`zwWWW^80 z%e_-{@BP!79wTF8usDd?x9EKwJS#_A^_oh=$*_^8g2>OIh|m_iQ1I97MTiIgp|H8s zpzeiy!ymZp)#-pe>k(CHj8``J>K9qhuJ|;6-{=FD2yi-e@vRS-w`msQP!KhOHh25= zH~H7EUjS3(n60R13TSk0ELiJ7l;^fk=Ob`cY6miIkRR&n<<;KZ4UA)Q?1*2yfUV8I zDmXAcz`F@jAGDyLq7bEcSoARid{%)8Kb;c69;f41M^hu{s^lv&nXr}xVgo*Kt{IRn z7|taf&-TUJ>y^3JD*fbiBMtEmk&b3?QPMAUbMnAb$2iv1*@O5tDtGiTx5EazE;l9{ zR3cRk?FtSl6FYY@W8#htf)vzX`S7@xEo*@G2)EiPlMJ3z%6PgS@yD zZ;_I|pH|8uo18aVby|n_2=kP*#epB*qFaXC@Npo;DwfjWHayLLb28SA0levsV|1>m z#rkN9TduQlkW)%+`AyS}mJhs21B9$AjWAhKl7wHrj~so9S|rc*DIi9s*(dM|<$}$X z7`AAD_u-s?K@DMAJk&0^-2q<*3#bJ^>wM912`I!M&*$;S+ry7}gR+-eYjYD^c16Jv zo2D4-+4F7vq*~Fe@*y3vyd!Q5J)|X0GTOn+%8=q21g<1}WCyCN-y&&^g~T$D`1`wW zG@K~h!-;)N_(8V~i^dqCyl}Q)X)XK`_68!5Dr`lbnIm>D{r>Rd>T*T@HnNQq4VFd^ z{<$pi;SL11F@VaJ-|T3u$n$khU{&7IrTU?H%L1Cob7)c5GXJcCuqZ@GS{P$c&gD=d zf{r_rg0gt0uED36Jvn{CZ8Xt#_~SZZy#-0sT0~ksB`-|ngrG3?Cv^y&wPvr}Llwv+ ztE*r3Bdr+?u`PeI1-+X)I*=%{Z*!PCNcN<*pl=(m_pS@|ke|*!MiU_qexy%3R-;4? zq~B&C7emn(n#9by?rBE}HCHlcDZ(XOO=BZbI`U9ph>HHD;J=mRnz0Y`Y{h>tGi?7x z`=O=TUASxLmlP*{Ccu0ez|zeXp2&vgcXSsZ*1(OR7sKQvf^0`xwli(_P+ehNo5D07 z;*Nwj!4nI30%^+M64%!BH?H3yS=PqlvkvQ2dsme_PR=_EPw6VRPi0VC)P%{h^@Ykh&n?_dyEgj z?8elkb7Y~G=`G*m#`UY;rhsA@&CojVl;VrNr}U>y_9;CBYOy$LJxTC{o_Cj8 zz}xM$EYv5!u6+6N3;G@UymQ3;AK1wL`o~(lJ_izuPf%;Td6HS%-;orD|Jb16edrss z8`YzUSvt-=74Z-IRomVU?BO#kycn0qU-iv(w3Blh6%?nYry%ZlstxOludhlJ>2ql&M_j4<^9k}3_8W1v`fUQXlx z3j%7opUPdr4k@6G{jGTwp*d3p zoxM7n-~MVCp|@+K3`r{Ck4YdSv(kMzb}Sq3k2^U!Is$xo^{pUFvu67ij*<(piJkAi z@x@LMWN190e1xN+q7D;+(GNED(i2GNEV@?cx|afD38&Z_EV3~&2YxVA#_^tuIyTM3 z7q`Yga}-I|^b!M1?4OC?BM+DF4vpI{;2q@uytWnUkW`#Z=*)RhqES|EPeIm0mQqOC2Ye+$qCBjnYt9?plfpzz;hcZ} zF1#}C@L&DMt5;`_&Aj=;PJHq>d!|c8Q^4_I{PwaDqO@1fQ${lxQ&-|irI~Sk#<9M5 z+sR9kE*UX|dwNd5P|gG`ptG>EBvb8uFrGveMn2E;)fk4>1vRu6x|~XRW0_QTalrS( z6~w8ycC`zl{fAN?lc zk}J{|unGfyzD?38??gr)yCt~8^Vku*nbQMYZPOdb58w~thj?2HT$e2NRjN>HkVCBp zBr}AXKf_#(Ad`akQV(IbTFfpegU=avU&kkZwVuG|H6~ZTrB{*Z2KOWMh=>I9DQTP%U zlp&a}8~K4C^)>Fb5vLy@wD=;4yWnNv*66yH)}=Ha-~^|y{rmMe1ACDkWj|`DR9bfS z^pL&wh7-9l82W9 zx@|CVgO#~309f1G`Gkb-alZdy`zecEc;2YPh*dOiNQH6?40|3*g#VUd@|yGGl9bYj zxj%#LYMXV6qq{_ZiAjME_9q)$tWuFhub2O^!^W#jF63dBkU9L?i*))&)t!}YrATLr z)aBg?HHc{>w&heYqpYE`k|&GyIeq6-sA=d`lMK5Ri5Z}Gb}A51n&Je@8SeU>+_8vU zN;B;;c(aX9W_LKPUmww!Ttb>v@dE#Ao4HRvP?$E0Y48?vd%4UA;6z%pZGqDBRb)ks zkCW$GPM1e`$nS0?=lReCIK(|XO93~IE!)eipN6(4^Qt5zvVNIa?TBNR{9#p$b&VJc zu0Y~U{lqdkkhh(-DsofsXkR2=6lZ;tkfxI!nSB=DcwWG9`UfpKxmIyW#)tv9i1>t! zL4rM!Kah}pL`2}l&SP37h>lh4K5WQ!7unj_sQTCco|vXn`^dci?0$JTS>Xu5GoLQ% zuhwKGa~|wXV+QM6svcIqSAK$;2KTXTQ2zH+`$6(qV(O&Bz?tW&{bE;+Gi&`AI|Lu2 zo^RZ&vDjoRu_*nvPa?U}v&)fpom&iAdcyY(^&fVq)>rBBvk;tWMc?E*|Bk+#O-kYS zN<|2>yOFp^!5Ig|ho%MfmyZd1sZfUkX$jbMhnF{VUOL31z*NJl&wb=2RIwT3orO4t zl6zMYl=}{8CTr?Xh*IUqv63aLu1KgesTg)TddS!Jop{cQV8ml%Wa##zr-;{ccyM; zcBvqF$T=>dAAcK!PlC)hCt6XV%Fe|43#yzoO3e3@3?x@6bGTqp z?wEl5CR#lRhSWdGa8cV13DXSQ+Tp$3_1akXrzGDM={W+vo9KEbsOV+(A94)5urv$Z zHk}~C{sj?G{C?_;ovo2t_o@vszH#P%a> zjn7p7GiPCAx1doeoneMzI5?+`R!b*7bW<}Husf)|#%^Dx-GLMWXaemUTP^aDIAH1g zT51~_ptEyL$XQvIn#R3`e1yHV98J?84o#p=Feo1mTw4KyVR{J1db1yhe;lsc*1r6? z8~wYPxB&)T^#LJePF{@C&%}tSx&S^#p?Ezte$%VQ)3?eJ2a{^jTKEQIwnlNn?2d2fyNTi+Vgv0LIE^MKg~Z1*3(nPKmVI7xBjVy z)11yTJNr_SfBLYNQkbjJZ~OWl-fFweLGqkR`hvvBJ4H`(IFMJ_l~{zxCkPyz^5SChs;#mW$ii{gVs+tLU!paSl8)gDNH5I7ZuC7K@z*=&_>-Y z`t0B^doy2u1%a-#CS56(@v~nucW;b6AX~uy6*vl!7>K2;>ap{sO~CWemqUK(E6b5| zZ)W7`5}}dGY|{wd=iNv4gTYLr%Ml=f%bWd3GudXM;ulz|XmNE*h(Pr+b=^JRv?6KM z8begpP0=M5QWl+uxE(?sn6qHDGz>IZO@obAQFy~c^j1kq^RPM;C;#(SjQk-zQG?&* z)JtPi%{gkG*=;jFX6{_j%0^Dk8pFx&UC)O&yMc8234e%?gr`gZ0!70q>=)s=;eWM; zy@ZB#k)h~q$PW1gZK1kjKeN?FZM#f8#NM6eyxx|OfQ}X{=7H5})wF@i+smP_i^HXt zSmrhFo>Ft3mk*!w>v{TCrzZ!3&|j}6!i{3pYq-WFAMN|!Bvo2<@Vgu->`P%}v+2Y( z)e7}oKg970i7zoA)-Tyb#-t3*#O{7szqATZoIEt^$hx?bg$b~Y)S4D%9LvD&mmTCV ziyhQ%-zoCtEK|A-_*=ExLo0CY0xqFmE$=x7%{P7#x|$CWs8VRF=Pk(n@rTIcn|_uM zntHVFyLn0$yBkVHrK>1u*MBuDU>+SetWgY|-6>;UH$oj+Xz{L4N`&7KoBNk;&d+7~ z<;(vvbXs`)wBs61iupkjDu01Bn~usbL~eLfWwpC%OEZvfvBRM;hVWWDtS}Y!@nZX{ zl#+>1lXgX2pCc%NlD%pQXmAMGLCKtOze|f2U$aizLR9aMnfOsv{n35Y#*XkP#Flb# zp5rl0y139IWU8VvLwH;mgbXTu#IiIRauMHsvXm;)YdG=s7qsvbcVMm&$#rC5BJ29o zTUOrT)h|kX7u_I-u!SyS_C*y^{sz%(gnynSF?7lx-X_r+<<$AA{j;68KUSm*Ejt9! zHwabD=ow|r7v-l>|0m_Q zR8gnmVD<+>LU}#yf|)>qE^EKW%D6_zC|)am1(r2y_O#*_xspHml!5!DDy)m{Q;Jnc z(PIGpeUR>|M9YbaLW-5(^^KZL6kl`C*NeYQerK|AG&f{c2aFhWM3wPodqqOYO?4a} zfm4%H-eP%gsim=+(v~`+Jct09OlIaFnE#Mr1%K=kq>c?ohluogvNr6NU}#s5IAs$y z&=jRT&#N;^u!cVEoBdg>>{U~n{mJ36p`qR-Z=VLQnbIq-TX_5KhyRN?9I#~PW)tb9 z!?t<;Bh_lbJbO-)kqS}XRT*q94O^kP2`?nMfRUG0qIpW-T(MjP?;884=(E(X=B>Bq;?XoEKib;_zAc{b zhn;`BX;hmLpk2etx=9cB?FU0YFwe`xy`1^tSuh$LV_F-Es-Tm6-1H4A$4M`0+X8)& z`?pf${yVq9#SFNmX*SV>5n+;5*SS)<)MakEn^}x4&I{c@=z@as_6u-QKoF8j@jn^lKhm%AG2aJWYRg+%6^iOC zm(*w1ZCy`L_%93GevwKmrw&M9<*Z|_wgWbhOQjX|158q}w6?I&r=@mww{WZ~b@g)2 zAb504(Lh`)`RUOVmnBnIuUqDD7PuKoHmx`1OER|n_5X^dDo40U;~Ksk3MxU4HY4VyJ&F{_ttV$c`Si}9tAM7cXa&7XF4>~$K_gZ#;2N9)kvNXt$ zzGR|RK^Q9Rnbzc0LH`)zF7qYuK$iHYgS~E3qtX*Nbx*cE2<*EJMr(zHoQ};H@8klLD2xd=<=MMo- z{2xn?SLE>Rb?Z$(5A`F!ossQ63J6G`p7`cvm;El&##%i7&kW7vvLT@Crlo2ZE79DI zw7q82K2Y09Cm_UFh5@?ZcXVicOJ4@3y@>MyG}$T8{QzVKOdH@l8vEX9BFD5+QhhSS zE2IuzaV#p-6jXa%I;UHqS6?iH$a+Oj_&(2bJ3R0+P8l+MqTgE!1aY;tww6|hGjBF9 z*O>f^R+lcRWa!k>pL?^A?Y1nwXT)Ku%37t&(n7M7^$n^B=HSoP$?-)sg)(|xSIDwRJs;x24A%1)AU zT(*8)Rl2M`6~uD3yHTWoN9~vw{EvTkia$_Zi%4crRMqEwWVDO3*^o}L_pGpGCpAat zrn?8e%gSN!6eC?$f{z(l(`@6+vR>HcR3K%i9%ZkK0aviRA2a0eFt|@?nU?}p_~*UN z`fLF`)k((-p6pi_bs;?uhBWD%R#YB@&N=0m_o*CjTOeWQ|9$@d8Pm-8W+|~wIsY@{Yv63%V&_De;6#zAC^9A~shjA{h zrbC*7v%C8}c>c|_ac9O+7)-w|B2BuJF0Bzp5+L9{TaX(hWtu(Q(wanBjiWf0_ zKRrqmYN=_?#xP(pmZGqu2<;tTpM z^`xi|W*=XlxA8Fw5^58bZcqq>nZLqRB4%F8(vpeC&-@Xi3!PcA%SpK0+X`ry>FMbK zv^@EuP(g(QIk(ym%znVwrMvqTG(+ppwP!%%JO-7x>`oqN`lBT;c%=oY|2BJ=qS+ye zNj@x2tf=eQxCA+Pq9N0J^$2l$HO~V6HU9f-99g+EBD2?5yYpPIyFluOegdw6m#V0F zg6<{Qk9Vkw<&vHmlN|0Q;Ddq76M)QPot0!itloz-4B|7AmGLN*nHI9kBSAlquLfvf zIsaV%bf&kPl%7J7v+Lxo7D_x}CwsQuj@WU5?mzmyz;X4=xTLRwBb;6nzd_b zggWQR&9z~qk65D-F;tlz`m}Gu0F+)Rgwumj~z9b5fr%7KkvM- z9Guo6cO0_B8{IWxqfVo7>3A7j6$&e5H$(6~8WoN$PWYk78q*dAXZax3bsW3FDUw4i zliq52#U$rgp(abq*^)frT?p?v2GIeZYY(GzmE+-^d;v5=G%u7q2UxBDe-forrWz+OF&G&<` z23zyTtPJY}EeBXV{%=O&bw!J7XA%`qlY}G$n&s(tC7+oY6XOTfx<}+JFemG;CY0s~w(p;zo2XtVQ|M0E*J}Rn_%} z6g=5Yw$F+1W+HL% z@C$RR?DFo!Qu`!NB*@gi@0`+oPzd1*H(wbn!aI4Iicv&hSsMcv) zD~t8)Q8H?x)V>eHhu3mg(j^+FBWPv)`AkvTjT05}%cWY)sYjbJjr0R!v^5dm1f#u2 zPXa%g!qzkeN%;DWI&n+m$Ga(0Wd}}7GWi%tf2D68Y<>FK9O#JdjgKr%V@V1MxiU~e z5sG!X7!qKW5K2v2G*ArABms-1UvwZNed#WC8uFOt$1}py)AC~c%-Lj-BAW~N2dz<8 zBo}*9qtmn8Ys)Mn$^0x&{Z)A)KlzM9F$|bxoVu z1Cd5#u+C@$AYBLpyaT+%)fJjUmF5Z4?-nC{eeb&y?EmtbO?jPAWW(`pZW>>(#JtN1 znP}e44B>ju<1%`(++@l#5&E*Jq-W&?QJ%ZIVQ>tDzK8>a4Qu0|($P9>nt?7B?lQh+{q5nSW^t$$t zmxRsn9L#08v$;v!B$KMzku=p#6Qo~q4O|lMR}QA66szKg5Y4XzSP&uPSLZu|c>d+K%FwkRd7hkm_RQ>A@!7~*)8X&yD1w0m7d zpCXuoDN01VZJ!)lmibU4V;2o#(^twf2X>t@CBNs#>hPuMV#4d!*JK|^6FoU87W2Gh z##9+G(6@j8j8j*E zHp?*aS52msn1uHWoK500o(?#t_A3NoIte|{zJ3F~w7@PD$S^^HA+{|)qq|jiqI^i@ zwwTXYE)z7rX;fvWM<0VMm|@C*eocNEfpYL_Xp*snRi`{EC`?g-=k-)>YRJgiC3GKz zuf)~^2KGSMWl?i7_!GnZ#r8L%x#J39nv-lND1#XL*m2L zF+e*q0-Vh@{J*gmiJmwnSQjhVwnzM$)U~mw4foqE8?e!96A$UswX=%J&Z<_+O`vvf z3St*dKli0Yh*yOjURuJD!xh;$b8+|LC>ZKtxLY`s{lS5KW~4YBED{iqQWbE|C_#Ea z-M=xH+LrvT9Nsc=Xz3Ihq^2~t?UL(GlT!<_7&m(nDa8<@B3WEpXtnjuAH$gu5Ws0M zBMe>3vBw(Nrld;b*|UWizJSV}_a&qTth&J22mNk+Yqk9P=ku?}%rl>1))b3N=m-fQ zXeYyE64GsB8@h);R*FY4|Br`e39X#`3>;pW(w<}TNqRThIlE8I8@tCD6*{!%&kBRl zoYdzO1^yl|t~grf|ENiNY!JF0Z?5pK$?=veus!T)~xNpg}Av@6exHGWO?^*5lP&3PBTk1^CN zsVgcE_738>8BZ#4fm}5_Eg`mXcZOSp{cu+S8Z3TN_LImQnN{P|A!&wz;eBMUgR#IM z*>pg=FxDl`*FYrGBxMPCol$Jq&MfgCGls9}CpA6Zqq8$-)iJdmag(`qq0d8;yH)&| z!G1rdVyS>+!(B(SYr`3-oW0p4nfHCo6FnZfvA-m#QgD-^d=+FKFrCQE0*&jocx?mV zbs=H37XZWrymvvg>Ge^&cmZzrzi&TB<(J0E=ztJv zJ^=w>`~LUe4Yq%9MThD-iX;}+z*mKg6|DGvO7*yz01vhcEncCGJRE@4)|bea&V(mG-TCTAtuJ&aV?Xzr@MU z4>jLGNwUb}^aa=B=-L+ORNjw6)CZ-x@~ zIvrel^mxrNHo+?D{jrA{M^E;(m^Rtehv%1aYMx8I-sn9@L(A-Ahw0l5zEAU;iBVC< zkzl+R47><|RXMy<3*mwdiX@u)fP9t}G*7bf{cN~AH}rU_ISx`8_!?-AY*Awu_d}*y zJ3nR4r;wIaTLj7nRSmEi4@E^qfkxBw^*&9{T7^b&Q0th{V}H2NXZ3#ev28ukSqAx~ zDDL_IUa=k1*65FB=ydrUEEaZ&-{*X7YjK5%IC{N90X05f9UTcj36@@UE%iiBIK!&y zYT&{l+6susptVR^A@~T=l0Xdx)n@2>{8;Y_IM(2wm#Y8iV5jGAI9l~j3Y)nFcp3|N z?5gx1>wG^*M9)HexbQR`N%^E49WTYei)==@`Hr@ZGRPrX(0qHJu#ext*y>WRYuHYv`Eez4{LWc)69x46KN8WgXN=SJddSI;=?8Ew`KGj&z^sZlCcm6*nSlu&`mV^BGwq)eiwzy=!Iu z6uYLT24s~2dzet>$-sFkhPG@V=n?X~DJ+h@wabTN#6FqUk44QwP4P4QLUXy}A?UdH z*#T_hAWnah_ya0I(#-u01|)~I6;Mhk$uZwJ-Hsv1A>!}i*`a+)NRDJu;x_|Pwgy4Q ze(#&DO)%y&XJDYZHE%hy=h zvg??7*Qft_{C*!y?(gpdIQ!thYOwBGgl>*py_Yao<2AbLgWGFl*M1?XXkp5 z3ZuiQQa=Cv&+R`sQ#+I|JGI!4(kuNgLmzi!w_*)fNERS#O7jni|J4(uRP4|D(3`iO zqnf!#6H*B*!w@7mN1_=kv# zP3Qe?pP3BzB#5VX*8d&PgS?(LIHk+uo8i=pH>Q`3Y*fO7p%WDQPsMtI~O;1vSI zp{V;OHSs#RGeA86?mpnVC^y_gSyd;bV5BJJ%?G_E231-0ThH#?{XkM;mG|?Qan6V z#UCwxgn!>HhfYn?jJq&Tt;J4+Pa{vf-h4PLiKg+VLvETs-M0AnlklQXIz&PYkD-TE zk5_x`G+l#2haztJh5WooUBVZoQ}wr0(PFa zIuUMBdkD11BBsY7L0T}e=!j$XK{o!yVOdPjL@JtEg?&UfSMfd{m|zmB(x3y`1M6-z zM8DxQHZ^JL86TZ}5UX@OcKS=JqwA4ttT=&tjG&1^WE1mS=6I<`iuZV%aYRm$+{_-N zaGQ&wm1D1!8w3_gNWrowiklP3!6KKQ5M~WDTO~E=Fs}c~ycH2DApy%u2%5D{C^LAp&;N8(Ku+A>5s#6kgrc?jP#&4=S z<&yG?(aw4_b9$LUMxOv(hss{s+77pPY!*M(#rNjotVzMBk)$}~q!NF1!$I(q!5b6% zryqu2|Epg3Y$H9u_l!uasbK*_#&hZpEct+xk=|LysDJfa$?x-iiVPt+jUA?Vuz30l zklh|_t=D9q^u=h0+1C^Q4!iz9uv7!|ULYoiys!zGF`VqaZBQRz-yj2|xH+hjk(i>Q z`IQ{>Fo%2Y$`13QlD*swrP=jaY7|;QYtz9Q##~^AilYg%GoI^+Wu5>m$jor6u}8l+MJ!|BBRw-a{$n= z+2h{>K0!~s6mSf=(+@lH#oZF^b%~7_Jhqn7)i$6ud+JE zO;Z#N>cZPzDsFCSoD)1FRyXtqBB4jgM9k;=IJJbs9x9L}^dA)>jrBi_DWQiw+OR`p z(e1-LeF{ccJ|UIa;GW|;&W)IQPV(xdr1tox4bIm&1f!GQSXZ?>@J zPU3XIA2dtp9!h-O-K{s!|BM=@90=q~)2Yh7%zU9U%(P767GV%fVqW~~jKn5~q#Vf? z+0+kwfWSRJJUk4zb0r0+P+1XyHw;FZPWzec^OY!fl?>k_^BhZ2E%7xpdfMB|^;bk8 z!p5$Q!ntvku-`9bVuoGQG`|YpUo^^IFpOSs21r23>~)(|(911tY`sB`0_U1d$h~$up?C4 z?W5Y>g2VIh-Fi@%Z|xBX0pAdKAcEn&fT0O;?U?p{(D6CHP`gzBpT#P`Wac{cRViAm z`WGeoi&Gf}^DG+0SJ?nPij=fb<5+5P^1c3$AoW*UUkFC~ao*k{7k*{4OS}=i1DYCg z+X6nlV~Qlq+ZY;EOgSjtgO$n&2DC)i)yL**MkWQMuXcf0R3hMqK0s3NBg;+tRxu5t z6LSKH`Opf4R~O%aiJ=YHDy7Fr)JWbaHoHX^~3v3YUyu6r4oB8hQQej^fSAY438 zdn)TvG5_r_l1-C_=OKY!Wp3i_-JyTAXBl~Z<(dKtf!B|!VN_@cb#W2Q?>|N2n7uFA z?`&^K=L-0<-nR{m}xGiryCSF!u~xl}O8B7_Ca zqDW5}!Hig5*EnRk_W1ozAIS&8ujgqzf6&X4OgddwIW4C-25bK=<4es~-D!oMA1#L4 z1rRpUd@p6rtjC~kgmsgg4N?sl6%w!|VOLZh^OG}!a%>|~HfpKH#p}Y277aLG&-J#{ zuMuxNQ^jQ)+2cyp+FiyA$FESzq?L(T)2J&Za`@=|`#**l-l@ulhK3sB9`3iTV(-VB zeefyG>cG;FcJiF^0_z78fIk*%7WfMG)9{-M^7IozeqV2Ed-(e+2erjoi^R*zBltG? zzA?zbXW>c-#{`tQwL9au*qlioe(M)$5G}d4*VcD4L}9UqOVNNx%mTPZr_W>k8&{W5 z35G65{9op{4tMG3)_*~oz=Ov9*ww}7YmDnl2&EdYF57L|{)_~^ZC7eLxfbF|i`^B- zTOtN4&7L0N!*x^I;hNooyO>gmx_73=)>c)HqLPpXbD|1yvG=>6onq*@Vm3C2b7HMs zH@iQz{m||_zJGIj+t~iuQf>36AFzf7zV+bd4;PVRl1EfMfc|*IJeY8S`VI4<4Onpb z_z-?-mYl;(<)E`bJ9NzHCepv=>kau?TA<4oYsk{VcA`UQz0@(;WWcPh3rzF*d3hs_ zAAvF()R^?QF5iUmA#tDO84(6x)5Y?!1~+{KRS8m;XEVgmh=C0Mnbzv%?kPXV{}q_J zTY(upEe?VMpMT_L0V+eR0?O@OkP^FyXdl_ue3GHN)-N%E z^g9HBWk{O`O6b$IY8|b>g6HlMRL3Q4rlGR9i-)YbWV>slA+O+b@zfteucKK-8}nte zYg4MQL|w=Wn&893EcSW7cRet8!Oh5JhX(?Nouo;Y<3*5hK54w}g`v+G)Opcdup^Nt z1ln@5tkh8cwo)svoZ}5j;h7rpQ#q;**zcb=>;FE5*yjcmwo5ZC#V!gZD6?k7Id80s zr8A`p(!0`#Hx2R?x3SVQB!9O=4vWX8?cn3`;s?au_DfBXsG(gju4pitdqZp&D{yGu z8eOk~8yJPw?U<|#(M?g9kIriYpjyswsTu|=!tPj-YNUyul}m))F)$Vaxh`GF`^(fT z4vP(ca+lGf*e%CbZ#C3@UT*kYY+MoH?`zLhODNv;bbJG)V(k#+Igztn^7fww#e@{q z727`P;HZ&rdezUHpqNPa8RFY8;%I0`4C$kd4?}@BuU=Njl0DVO^Lx&9_t2n(qP&-^ z(CqiDdZvlxBKplECzS+VV{3_y`5UU?UE1rH4%o7C|372P)Yah%qUN7mnWY?WjL>g> zD$G_f!AnW+)?`k=hWf!K-?^aDg)=!l?r^_6F<4)w++?{XK|-|LV;d|i!b1br zGXu$w4n!HWD&pPC5k~rp!wRPaPdLODt#tbN`_3!xwFTZWp*y8yv7Wl&4G5OFrYoMi ze!rS~1=RY|Z%_rd{@Rp9ZEZZQvwd)Jl)UdycnDW3IRCCnFGekIZSf5GIy#E{%B^c+ zz65wZxXk-=$=-yRoWt;kc@+*hF^b$a(cbH?Jru^8>EkVP1`%r@NiUXv9#=s?!7TfD zsD;_}c5%UcL{B-=7l=f0bT`Ag!=OR?;9fQwV*BTAG0k676tG2;kU}3I_Va;YG_ z$1TQRT56QD4br?)aRzbfgSHU;Ghd7mr2noB%0W|)bl1C_?6|zy7%KMk_ogfDF#o!} z<6bzi;DN=VCYdQX-Jg19(7%G1`Pnv&I9*@Er@^k$LZp7 z*jkKa_uMcb(^9?6r%_K3|G|e>DySABE7mAA^uMk}YB+r|k~<}x>YojW-h;x$hx+j< z_{&ytQ}Q1KdYm_BzQ2cpp-Kh^8|~8(&d(Z;ql2hRWZBdd5EQ&gTBbk*?cHf7wH&vY zc~inxw=cMT^+(K~tGU+m-CBP}GIhE#4|dr9HZm~4YBgEUy4!ktd3{^JV)Rdi_CnLl zCv2F=gu9iD-(DD%Dv_0NH5+RvS1vGk#Cc@R!pGM>Ty50h!ck8W3fWOP;G#dn4Xl_n zO1K2ieK1a5VTj}8&PsNCN9ymMBlHB;9UtSm#cXwcB1FsuDNP0!=BSutBW|;RYVBT5 zXl3{8j49oudOCdAFQ#dTiY+rPwD{qqHTi5Gmg&|FnzfjDJDnfQy!$Yr#m8Cm8lSfI zJzR{)#0;i8Q!YZ3hUaf#a=dnJ)vm;fjV$koPTdsw*t{3u1K8_$Kfhh=41_P<4gEiw z&N8aXF51GhbazR2cY}0ymvnbZN_TgIba$76gmfbzNOvd=5_f<1j>`|n@DB{m;p}(q zx#oOkh3e!@suX8$PtQcxu%v>u-c=C^F&JtC&K9MPi=sD(_siZaO`O2!!E0bwO0r1_ ztktUkK4%hCbh)vz^6Br+Fo2JM!Tbrmo?}5gjKN-J1SIM~?EekUWL0PZ20ga_H+a+N z-5F}iueN@jsHQ!v6;>xy?U|7ivO{2f6R~edmSw9TOP;@gK2>ypA8;#%bMJJ9g{9os zpo27ywmm_J^>8f5M$)Q7t3+gSFne2uq(07Yv-U9(lp2&2C{LPl>q7Qmm65T6bPN41 zCuqvQc5+kEJzYQr#|O83Q+Jjj_YIAf$HDU zG9}PNIAPGt!24|ertFW-vYK&O1-GfSM!?rVRa8sBz!e{e5~a139M83gd!lpN6YX)~ z9L70$KK*47wU@q@b6*rHpMQd<1ly=-bo1|)WbK5eAZp~V48WdG5ZU;5+dtSg#sg%t zY2)k!CC24_dP1p|vC^#U$U<+HB2}e8Go;QsqrHaK+-aJZZ;M%R6T7|)42lgBXa-a* z+Agc*fufCHt^5>HoJs2g|wV%+HUR;F5NF zYTs$vBjMy&kePOS)4(oe6W&p!ps}_K%p1&un;YOoGAxL&0nvr} z2_z>rrgvB#e7)ZVX1312X0b^$XXgv=Pqc}ZBMmXFH9cT81wRR(s`wo;mUB-SqVMyN z%q(T~V+U@w6E&Y9#lX#LV!wG`Ez3?x#P1GdsB6cXfmq^Z->J1eitZ6aLggXgGIL|Y z;G$%XOEP$j-1)zu=&!{nA1e`75S>N28##9z{fSMAX0bNDl;KEVx*01NDVeS4p zWT`>SyIBwY)32+y7uoM*hnw?3v5mpxM)d93J&XgDjhb_N5y;a(O^opRi^5nfto2#t z_+W2OvQXmlFf`B`r6%-M!HWyR>G|0MVBH6PNAO=@(4mnS0y|F*)w)4^usRI#!uXE3G32KCn*NQe*wPE~! z;wh^2u-b{r+t_l$Br{S?nUkO2X{vqir9m@1=Xd>#52eH+V7AsI{aFC1nIJIOP%g71?kvA!lkt)&eqaZ^wP!r#$?H?ZOP zZ*6@_*s^5DYio^G%B(HuGmo>OW(@=R;FbnJSkJ%vH5}7N_mkO>94DW#(9NV-j%X~` zNrT~^k+Op|jQmOwGKN{(dcl3=vgu8&SIq{qo36lASr>?qx9|P6Q%!eWQo$0goi=Cyc zMoFNZxk@9BMk4M*%vla>39H(a5J_zXd|%a>+;R1YcB4`QFOQ0l6T*}7<@B(b8at?{ zK*VT+ba7SDHl(NJoG^oP-uKTWZu^jK_7Nj>d<1*3wcGbtqoe*W9oPGMtaEH1xxafr zheGimc18JA&B6Ps?W~7D;#-`F#C^ngAU9i)j_9)G# zben5}?eKctRf~q4kTDE(;c8fGNcTgW?l+KJMkf3&l8Ut#KejbRxQVUD2?Li zDMH?C3Wg)3f5otW&VIixs^$=H;i`Y;!r{Mys~TF+{^j-4NNbjM$OUMv&d!(M+yN)d zZ7n8|Q&uGhKzs2@i~GzW&+u0yqfol)J;phgK9HK$x1Fo9lh}LFp>Wn7i%- zKHBgfUlBDrJ#T21!HLqmrH2?~zlyrCFT=ZqpPGbd^lgCLscd{GwMmH_VdzUvL)2qMqMw zOkAIm>{T1XX}|-7p{aYi_+t$_EMrcC{%Vt_9VxabEm7qmh^)Llg7GvvnI1=evfd_p zaVwYCIUz9-3{kP>HWVE22#1xzOF6Zq_TM6hjHy60uji@feAP-FSZD^h81Yfj(6p55 z3Z*}4be7Ehx2(ANGLHh7u>#bFme7BJjfvW!Ww}_;yjcr2>R44an?+)wRmQaj)BIG( zT0sZ7@qrSD7<{V`C&oZPKYZO8Myi7s^D2|MS)ov&b*8r54#|Xq6~iNEH%HC{)K&SGZbX%jm90t*+2!lb=<5aOo7Y)sKJW zQJ?VzK37!X6%kd}`ak8~N@H926U$AnidbkCA#95QO{eXwa=x|{-ExIf46S^rvOmFh{oS0Z^6L{`H5Vl0Cf4u;0z@?Zpoa>+nkp1~69awih;uMBd>Je`ana81#1>*3 zCe5|7u`yR7pQ=DqHizefcAC;tQaKypKzP(GXBJ=Gan8xP^&s^!d2wp;dkV5}p=!l* zgDDh@<=*>on{?W$c2;Q6Et}SrU4pwEq{<*Hrsn7SZR(zA!7j(W#elOw@W+Umf=LA1GNPJjg&fm5=P)wf7-NJW`##Eslqxg!@R*E*JL?bxm# zfi5mdavJ(^lJ67-3xs^!K7CqwQnSeEk(9mg?4)w|V1EoWmM%kMBO}YXrFvc%uC~1s zt{dLCF-SZ4kYh_hPwR344kneP?PyXqwa8v$?Y)u*?(?Cd_oj%uMlBu*(5FGJc%F(( znF>2d8jl9TeRfz*|Q=49q; zKv|Y|($WC)?;qER+kb_>yIlM#CiSN_hOeKWh?U8Yx?dhgr)J^gzAE&3EkD(A;IStyT{17;e zN5HdHxc2x=L#UE5kuy82_LOePN*+vt;kGODy_flOPH@8_%}Xo6M`mA{bUHy8yga^+*SR)k=mReN3J2}+T$+RPoy<%>*E4aepjKEUiI+KrR%-6WU#7!sy zPV&$+BxLs2V2c&_q^Dph{TxCqq3`j^aOL zy{(NXl-4PJHP;w_T_yhzM(5L)sOL?@QYgNUW*eBMA#^SVLQzM!ZlC_PWa0j-a?pII%l9msA}Z=>5rw1u2M@g0Vfm{d1+&? z2n#;36{(BBmPdl3vHG+(iiXC;k#DVvFwrkRTv0IT*u!0e>N00%wCl2bV^1nAeb+!x zlQHKPdg~4IPLZwiPf{%B(m6IK78^sjY?kgil2kO5H!}s-z3dkXO34PSf=ST^3-19f8gy={NOhOon^yAd3C-{@=k}Snd zDj13_6zQi|&7~Ubo^t7l1TU%{aPnzPgg4Cn3~%GbAqR6YiB^C85)u$F8!mB=X5z`V zY2jU#TWqhhkNVeQh82vnv@o)lMcSr`TA{>th1aTFWe`|XgSckX24Ej=`>da{7t%DK zWpKm-n&avNTjW&KIl~*G-R?eDTnWoxVHXCYdulF?qTC;c05Cvwp7Nc9oDP;(HWWK9 zn)AFi6ZvrmqDNku;Hxho7;NLSOyHp;7)<4jnlS;{Lwf-%^>_VkDpd#(3$U^&Ut}LK zPbBz1n|AFw15yj&HsBh3-L4_^)rg^Hci$W%Z39ozyAG$V9d z#!wc)E91JgA{Is5>x>O8i1=y~g?BlI4yxX`Sr#KbOt9@%rKVWM z7k#L=_fRMXa}!9eX_N zNDU8Ue)Ipma}*=G)ORY5?!rEgMs-d;nH+3_r#E$x8DI-|Kh8WGdOukMp+A|e(IV-AYh_d%! zohI3w+)_@T>-%kuWey>ch2yAoy+tzlKQ=Sy5e1hy@CEpMfH?AUv!LQ-Q;NL)ZVa2m zt;-N>_#DBB;o~B(KaAw$(HH;z`|8m9e3O+Ykfiyq_k+%@PK6OP+DGcQbQvj!2epJ1 zHnT{7$Dyj*AubZDYYfp6WS^?V9K}@}D%93bo>gi>K5b@Pl(?tJBAZ+vUKsZZ zciU&yFj^eYKyNN^EfqlYVb1nj1v-@4e8bk<;@xFg>=aJc!gL|Bc+J;TP= zmwshxP!g`N2$(+KK?bY#LkU0-3 zD<4!Lq6?OFo}aI0l=_zVS&V+5!hJ^*8&Lc@l!*$=s^PZh9vUkno;P>U8U%Sm6if zXF7Ic%J3nZ6QEuT-=3{uRqiMq*PHQB)IvpVMdrg8I6Qum3{lr~_qOnV{rXiUtuJu$ z^|fEq{V629+7q!bKflfFui|6O$VdR7E!HJ-d=j!xya51Z_5|weJxSMA!50OYe;@nq z`H7A`%Tm$L6beXrPVGtiXn(R#&?f$pfcf#_T~Z+BK+pVCMn zYb$N7ky8JzpU+=_8QSfS*QLw!l#BT_L@xaYVr!|%Pl+6_5vgG-rbZD@nbu&_gqG&z z8r2QPo=NfUf@<3-@_4NM&pK`%9-8_~e;x0lx;?f~wGbs@Q_m97WHTlt2PK8#9F4K?XXo#$7kOo@{hS$x=g!S$+mwvXDSF?azz<+@dkcI&}FYfS@rh8I9 z*T2aBUB*GE<_j9t_*~CX)b_$4LZmiAhpQ$NX9WKv=7v+WmmOZV`9$FBGk;qxRF7FO zq7Nf84-0kM*D8g+Pk#qJh>FW^0!~)G$) z5yFm+nBPLun(}^9PU07eFH0D0??jbINhGr5DgUfL_hJNUs4!mzcGs1s#=z!cmDPrV zT-ZCahIo(gx=qvHyfo0Jo$CG_T&rOc0|qJ@SP3)U#Py{5UvLGBxUJ)C4&)S@tNk9? zWBCYejJ!0OHKOAPHPZ&$?LEo15Y)sOOSlv|>NL}*3|SX@S1f9vrfKkbrzn5$&&cU2 zKuvv6JT4@c=cI_0>08D@5ohyPnXyT9*Z;eE6ffCT-@`YNs@0%HaQxg(XwM2A_42!_ zs)5Nh zwgULV@}b2oprMA1NB+ZX$;eNMbE+I9UDKUeMSEw zd1WkVg}2)8DzXJ5Fhp=WEV);%&HQ~iIT@d2$z}dzBYBz-0U|8GwIkgM%vr&%ntN-i zQg8vxS~Z!sZ<_cJ3D-jo2%i3F$&&UBGgPj~f=Lfh?mgf()&gV6NH)g)1JT6T$fd^n zDFd@D4Gu%VHed4V6rcb{hh17I;ZuQ9M0ZzLwE>gyW(&>8AiqWV;A9C)toOnMoW7}_ zgSC$Q$)(n`J0JTKK17Jp8PS)* ze7^r=>AfMI{28o3!M*wI_Uo&TOF>x6lB}T-%kTlk3;SXgVWN3xPfRi0 z`ZGYBx_NpIKR3CSpFp-WN6*iEMw#IG za?lwXSZ=4~17Glg;MIdEe}|`(Q)}ozL7OTx9;0Y|#y1IeHm$Hw16zGzjJ`m9P-GS& z*f=T(*Yh4EzV=bBSprjA$D?hT5W+1{8SH$&j5jYq2agpi?WI{Pm!E8UX7ySc6U$787){1bsoI+F4cNqqH zTKb4z$OG6&Q9-b%I+p(H1-ptu?hV=fnEs{Eeu%#n(-~{RE?KL}>BHDx-c?kRY9+T* zkZ)5!(bM&jw6V;_6o!B0T?+5Qn-Q9p!l4n)=jR>mmfEyJtUZKIUtC6AEDGV8ORaB2 zR$pxhKv^t2Q5dR57=`Ica~(7T9H3bGZXrQht1l${bE@gM=~a!@C#|ajGzYX6kM|J1o02U0sSE3s=-P@+C4PMFTbUe-z5Ap(Hp&}8xG5uePErA9 z@Yr^7?P5P|JA<4da^#A;j{5v#6_OyHoHsk=M8hMzJ5v%`Y ztl#Z(6L{7zpvo`ZosonWjSc%9q|!JinKHb5(H#uczsoNLD-0kN4XC($zrJ?AjgIT8 zJKXWB)A$mX?Te-zgve`Q^;=Y-Av8WAA)(qFmZIhROB`v|z!E;O&<|?be5Qco{e8)kHyjD{#a{dD19qtbZW%_z_f8lcl(=#wZ`vTQI%N*|!Gz9>WO8emVhvMJ- z_tn&M*#@jhEA6G-`P1J&uv0q;?g$d^%Fnooc?;F@bj!Ra4N*-ipN&af&tB>9*2Ybh z(xDAM=I4_t%A#7vO%RUZ_$XYXOr^T66rO{lB4C-;4Ua+!-&0!UAK5APH>j4cwNjPR z6VhSI!Y$)19kUX;o05#VXaL(eXW2rd(<`TPx(R2&I%*7`!MzlMY6z#PcX(JMl4@?2 zAkCtB(0c84`uXFoArgAc1fz*O<&j)_aGb2EDf~*v%SvA8G1-wsVD6H^7|c&~iBrSV zhtnS>3`*$cJfc?CYJmpD>P@&`VN$-ADScV#w4`cdlihPA%U*c<2(FWD8MhPVhD^W%U$U{*4MI8Ax9seECS~JD zr_*_3t`@Q~u_^JaS?`Am4lmiyMJqRtF~Pbr`c*ziCd01Psy|ED99EfbQUv43{I5mo z@6l)9%s!Rc#Zb;(M@Ej=K$t;olw%P;tf2l!@0+PES~gU7HASpf!!9S~j#s0%h^91t zy7@UvCu{SYU9q`Nvt+Q!BBUkSN?fzy0XBfp*YP7&bYaYKMvUG?bi_Y(r46B7-?+FF znBT_l#497%*18N%n};PGOt+Lp5hijA&;s19BGtmmgKZtwA%3rYe15>Zy9mB#%}>}) zM4<>@yg}ZjY5hbL*OPb1#OLSlcOL?k3%r)fVo!U$`1P_u{92IuFeB8+!8R`u<49c;9*x7$C0)Zd+=sMF89l3{+Vsam2fZC5=G(awJXW&(fE`!hGEmROuulEWF- z@BI88(MX9Gtv7BDU-k*0uWi6uZj3oINPV|ohu|plEOVp2H zmP7eutvhpL}SITYRy&g=BOx0X#7n$Tz=s2TMIFFIx_!&36 z0cU{PTmxBzLjBkbtz=JSz($G!ulz;kd^`^__ZSP=dMEIso~)#>`){gGK^)O9*Q~#R zwl?rF#}*9=*+^RiyfLgN(1Ir&MN#_drT*=N^ieg@%9PUvCgr0vVs|;%m*fW|Q@QF+a5( zSSJN8`$HvxN~J#A4fWd3%tP%Fj_OtEi~sVmEBm~NEFZe}#qwByAo93*4V8JCZrZ@4 zsj&hXsnn|a$H0XT-t<$4n9efqm&4;|s>}TDnYEZD?BdiL<71L$HhL0wCiYKdqtpQ@ za4LTHt8NAuHTg`;WF>Jq9W(z+)1>BOx%^@_s_l8 zyiw#n%hFtL#DCZt^2x)PLdPBY=aoK|al+K21CzmzMqUZJZ&+}{wPz;2C$N;c72q;+M!j_8m@H|{Z8W@w**uf*@L5&Dd*Mw5Z^sOVd3$QRGWTZ=vI(gRYS-L#7k zn;#<9BSO#`;j3H&Mv!OJv)mNEGIFicTd*?`22!kr8h-nB0Zf_pTc9f9hs-ry{-A|+ zgM<{!9NXf>MXc4T^le0`EO+$Cphd9~VrvN$D>hQfgqA_GM}`B>mtWe8*yp*sY)~wg z#r--aMosd6b+<$|+FT<7ktZDVlXJw5i5yuJFX;`wGisQyca;a7bxARLB8Hs!R=~7J zVNV~E`?kV8xil{lwJ+V6rl}lhXc5qK{uoVFCmLisst~ke3dz=C3`-Dni1HUi$mRR? z1yc$ll~T`a?(69XrAYeL&ICC`Z}(Sh4(^}iy+q3AkjV$Z3z#!1bRqviI#ZAg+eAv$9_5}+QTqMvSz_x^FU|g|;TR{}FTwD48IPOt zaxv*@mj%I`9aZ>T0o-cA5`(1}u&)>Qb&+nI&~&7{TAT8MR3cEU^89!D`zN_mYBA@% zQ9z*mcXYFNAMdl^KB$i(qnxcQ#>KklinU))ynHDg-z}QF;4p1m5!{R&!4a~xegH@t;scIwBTbAd`|vXhL0KR4 ze!Z-eKi^FC;Bnj$hl5ETkGP4MCo)Si+v~Hsal3s8Tc2URf#2^L@dy(JMn&z%6J&a3 z9d%O;>mYLRW{{IfJ!gShqK@#GhO9z^x$tBSn-;#PurP`vG9D*Sy)iSM3Qp`@Jax6{ z_1;)2C_<&z(TB_570w`A)BXvdi%|L~lG7cTd}7Z-)yas?CQfSX*_&1VKM9e@?Vk1S zWL+CR;qUXqWoRcw6A_kYytL-zyK;M`d-Z94eTRub^m$fQOZ66nDOpk%vNQ9=+vL_J z>(Kw*3o76A>>J}iB0rkZdd8hBbKOa)DDkB;sC)_iw9tZ_oqmuf1fMv2V~1yr;-E-` z(2czVUe9e0Z50hhAAz@N_fhBQd3?GQYG|%{;sZY)pVjn6)9^G59`uDO()$ zK<#7~#IwrVnK`St z0@x?~7(Vb3-!<>6jS8&hkFREIuZ<{2YZX=au&vx0I;R?Kou)>GBayR`vUvL0hs$3B z>>*sM7|K_i?D}7Aj8&M26W}_2MFMnAzpIdXL|U4hJ43h)i{FGN;R&+R%zN(eDa(U$ z*x$5~qDQ8jJ-{D_FyVoMkm$zA23N;;`6#^&j2 zhM|;jM#@ZgiJ+sc+{pCZD3ip(vJj1wvGtlnP76UFk}g{xPhL>PP}e6zn{Tp1X{EBd zCSUr4aCUbg4%6IT1sxhY9UZFGf-yl)%dWChz<^Mo8okO{NDQ;VLzRCFAvK>8q%h93 z_QCOdT%YVf(;$zsyH2HZY-uTdTDL+|q8vdAtb-OU1ZGaSYVlFI>ahB#ad4WW?Mfp8 zxXgbpFYhF|>9@{}t4a1&=@N%r1O8SX;g}849k^HdycilAn|+*!KIYQ0Ngw2~(c^%8 zsDUf_d+&W3?3NJSe!a|O0Xb`Znia^9rtLm|qdHSjG&6FsfZBRAjcC*vjnqSWhLOK5v*u=7cK#3>J|4!}6gx!~T74o)?02iNBIB zt|*by_)@}6+wp|vGp2m1u3+f65;S}8qMOr(+hOvLWlmZ@4<8>n4zHMsS+1<>+i*T< ztS!%e^hLNorm!8xHx6WxxOF!%0(-93B)0)r}fe45DwbtUApAUF(;JJPf9 zKM9-amlw~^LcftYR*3Oa2dc}QIeu~}aU%oAfjO;}dk6*!@Nh|B0dXkho@L&guX% z1$bNiFs0R_Rh$TUS*90=0fH&EuARIQGB^~+!jbT=uwNEg5-kOl zeW!9yvluTA8$W(tAaHzAFW{Gvu!8nXkUEW+7R(uYj)4%JAB)+{COAJyR`02&NXEoFWdLu8{`dwyf{-o+jzzQpf78=!V>uSO`_ocoA;yBZfeeU10^XKvw^8CRt zSuRhM&r>Nu^9wMGhkV-}+fqp4`t4-YJJ(9t6>J|iwC~0L(am@5v>Es5$hD8;LGd9_ zSw9#`jL}2oat4}l#c|Zwc@eIA|G@DOZ~jr9a!I~Id{Lr?D_DN6aoA-tFXs@2Lp^Q) z4A)kg`ofAc;@&oJ?{zKeta!EJ77z+Mt;byN*J0wL<|=N_A!Oq17bkpn?(9w={%|4e zS+=V2aj&WB&5Ht2AVzf10S_x^bB>}TXiQpJZVbGCfj&<+$J^WFc3(^hW+G4BhqF*= z<>A+MvCGQUxrkKZTD1-|(i#<%*52#b`}$3-)z+rzK7cljiS?BPWmK`R!|xR;X_tqG zDqNO_eupuXxBB|}R!96^U$_6Kh(d$8_O};#61N*zc>fbhU0h~$Y=jQB+`;06p4$>h zJw!#RNTS;>dni)weizDiGh@LpJqzaP@^y>=z~N^Y?fr~DetcI@Of?g;5%ufF4xNqt z-M=QT13oLtTK_JnC?wWy$8#D^9$GVW}&_JF*iq`KHd6r;n zG1H39ov>ZhYG{B4JP+YaLC&sB!vTey0is!$Y`U`_9j^h&_U^vUr_^m|evNe8PcVF* zO+nI`mc!hHk$Q-r3fzxUi*v<#jg=KzGZli>W>yjAql5M(*U7n-6^Dj=`fU7Lx1ukS z$4sawZS9R&Qb7)b3az)bH0wLThS`N9uAP;)5=znH9JH!@@;eapDDqCtl9-7k_$Vb+ zQ$rBr`|ql7E1lo>*PL9w1Yv~gEOcr0dcL+xM8y3)XBWljsiQJi3z{wFs)eQIz`h&E zFcNq=#SGtcc3UmbffzM_h>(c6>4@;8yp5>**XaZ}k>eq?O(_C>7(3N`Hx?#0}(anLef+plSmbentb&K_SeLXvN9^B zDDxk>sXrV=tfws z9C{VGLMPe_c#@9fmy{_%d8SvBF21Yd_h|vfexI(PySsLZZdyf|^d4DTmkO$5 zm5|2#2z%fhrVvlRCLWN|Z24880QK$DfkCQ*t@$LWNFcg$NkVru!sk&*d}d>;kn!AQ z8=|H5Z8iaNtt59H{Brn?dD1+#RQ0?)81d}i>U-Bo?Y|vp4eW>8k|KVc=}feE*2z5{ z4Pc^XB^)SX{c--+nh*xpg(OjK0b6c6_F=ckV(#CPVu5`nVYDURDAx*#@uni3LVFr0 z*(0=A$D%{jA^-NXt}-Js_`kk|M@^k?^pZUM?B`$jaZC3F<-TsVAsBZ#zn_Q2tDE1k z?6G}yVn8RqK#`wC^--I%P_~j8_?`!ZH0fc9m6YbP#}n{$PWjFR|eP zpNz+DJ1@%akhGK@gDteGjWTf@u;l?A|WA=NG)+1nYDY zyeIvOc-gCDGx}PcI$8N@S)deF2?ec7%#d;O6nHgpz5yTiCvfM&oK`+6FhCoM#6#aX zgNN1TQ_qdI>SG!c4t%$QvB^b*;6B@SS#2F6%#|Cz(AGUgDsb$om47mv9d*`Mu?fx{ z!ej2@x5-zGKr*sE`}2#_Gq!#+PG$8 zfl*!x8&#*Z=CO?|$r%6f=k>$iUBIUYsRl*3m`%8<(g0H!%dr6p2<;O;5{Utec{EG} z>9HY}*7D}OPPVd$Fv&)dIKz^uHewU{gA(SEC?4Z_KsSFtG=Jr#w|NCNny>2 z1$PJ?KfZKFjGpDU3Sl0vtghOo->DBqjAu<{@qSxz)Xq>Gpv+B%mmZV&ivP0&I)rb+ z;);jNHjKXn!AJDq(*fG;q_6j48*vYf9r?p`^etR^EtDI+-nO`N)tPsbuH?g&EphyW zT2m77J=;rvtdq%Gpr>bgr!o2x7Y{kR70>Jk%2!#bA0OMffinGH>ljEMl^Pk~{K~M7 zXyDNCR#dCIP*6raFT?Wx^htM?kx$U9pHlMcq3D71{oUOO15Q63oHCqh2=bolGfSZN zw(#Y&Ew@M+o0L9rp0dO*b#$#RZ4~BSeEE=QQPpopL_It$9MyncQ_G7%leIm2NFRkW zuLmR0p7Sh^nKn+!Z~NniW+UQjL^UAnzF(oI+fkwv3|Lav#RW$Q=4o}<#WF1 zh2ITF_&GXG1+VK7H0r)8lIo`u;$&(oUbdpKY90M5gwGGwP=QuH@f^JX7cQSOj`Lvi zjP0B85F2}6VC{Wpe#<*K;4W)P-zt7qodYynD&1b4IHz$H8-ayz6>O;5`s&nK|phcvPe z=@P^GQkX@@>+x0Az0V*k11c!}I7LKn)T|OFVA?$z%1ax+ePMt7p~NGbY%A>}`=H|& zj@f+dg6tRf9;D|SWIIYCu-xEIQ~!L5qd7oBs_C(NtX$L=f|bI^#NbPPqmGCeZYLXJ z`5^P8Uv74&D?-#JSHtApRBF(DUCR69WX~xDp21mnbU)U^n&@3_)lc||+V|ZRf7+@K z=n(&X5?G)+D82ctUrguu@=p>$M>4_BUI>LS>94d&`2x6tKc8_$5Dtm_2&|{WP{s}> z2%V&w2G=4Wq5g-5@%4RrytXdZ%*o>{_6#lmxJfuK`1AyMLBsGf2?du+Bf-SW^)(JG-|7L|A!WxGK84TIm zRcvD{F^jeFEu?=>&QEmD5+`!AarWnb=N2ZTHmq_SIGU5Ua?)B=8DCdP$s==EbShiB zI$v@^HH;el7Erkb4sFP|#zNv@aCqsKg`oW2uh(KZR?#D^@Z_!TAxlDq*rpx-I%K;l z+!>o>VM`QX*^+%t-$>tThkuNDW2GY_yvOEaZawCt=z)xJuJ+qmxGk&1?4#Z z;P}zxkQ_wT3ib(++{1O@+b><`nG<)5d6$hCVMRq;H2C>4IAL=) z-2wc2RCiv&eMR6Gr?8GO>A%1F-!FjdIyqrzdc-li0!Xd!fWW|4aLFhsp@ilGCgnxk(MX> z{IrP~3i7pqK-0q;4v9cWq$u4Pe^xf5(-H~tlZZOlKiq3B(5uPOz64N(OT(w}RzLC( z4Hp>cchrn21T|&6?n1PU%|l;B;yYSTZrlD+ZBgs0oY?AI=sBVfpZti5ShfQX#pt&U>n^q)$BKu&pg) zIHI{ZaY{5z7rM-V(pE={MTRlJZl=Z6@Jk(E z)xVMD(i|hd@*Qlc);QS-C7-f!mS)@DIjo^hXLgx`^CQ;^oP&rYbk=g^rb#8v&F^Wj zTJ4hQ^82AMOJ+^8(hPb~9ZR}(<78TT^9r*hB(;T9qT`|!R>+}6A)nhK%%`Ii_l^As zkPNJ}+$yn_`vY%|=6*~5(ve;%|M|TYp^*y&VL;uIAHjj^fzV;zbKajj;ulySWr9pS zTNPKvl=|yW5?zHuh{kA+6*!Qdw)J@kccl-`BnJ6fp~UEP6E}3a)XJ?ZY66aHeat6D z8unsce827ST-@EUezLo>sCZ`Nz>+OP6M8dnts;ad7xJY#7+;(!Nj?=?f@7ydSozm-x^UX~@{$Af_G3NZ-OpiWn}i z=f9jBsFQ;xz5Mv)PJck6oZ~P8yFlCcg$vngKr97%Rs_(_RcHgK1UHc~B6sbSzd~u0 z_sAsc?AX&mV2HSJ&jg zj9rKyA#$irjK6LX;p=tkj$d|!0>MXiuO8#2zVs~n#jx!jWC)mR#fXmy{b_HgN^y4n zc+0`K;7&n6`z|zf=!V&>nu-eZiia>U837MA;U8+@iBBXd^9qZ zN~u9FSNmXh(ZpG79Kv1${N)>)oB!$Wfdgrn-nA-Iodw_0&e-{fF?ykn!C_$y!97B} z^X;JEm&?wVk!Jn9eAfic=7xIr;!hqdt>eQP$8Yw?s_aR|1809=#d-=PXB8BI1MfR4 zRK$*)rThx55Xe3QBamF_T*D)?Z;fL71tGVtAHU)W5Yd3u5K_g?nQ5&Ld>3^UjEO}YRQal-D@n zU+?&~L-PhRM#u_fouW0Qb`j7O3-Pf@V%Lg@ykYk4H5e; zR;J{Q6K?H%_)o$7f!9ornieq;z4VJWX%EL5ZC@pgtIN-U9lsby-=7sNK&o=DKhKK_ zlAsG&k5R8M3(X5zMt2&e#w6^i$1FkUJkw;0(kMsRmk(CJrVhH>+2cZ3J9{Dq{2^tQ zXotL2B5_pzsDvkkwrh)XXDO(7@>juuIQ*KJ-$Pzm>-0BGpa#vSai;pTXDn&4#GFRF zd1(E5`&=@Jm-ifajHo8VWg`KtHMFh+bTdm!T1L{DlCp$}2n^W78r>8}p5Y6F4axp+ zPUB)|)e{TL6f^G&(90J@n~*5)am?FR%ZWZ6mZPSo3t@dxM!9}p#<&=qF=5#yDTCGk z4ebR9fP;Hq-KBmes1LgEv&!GctULKv7Ha~Om7jbJS!Zz7w<>(W{kQGJb_A`z;2o(4 zk6xt@HC?AJEJ7TbZyt7E1O9mdc*%hki&J#-=Q-A;71u7`tr*8gg2jwJ{b32>Vt&(8 zis4SuY$4r|11P(S^%~+SIgWQFvqpA0VhwB0S`&TBL(}}U4k0O^P07~0hS7cP=0j^* zE;fopqlu;wgT*_@dlqgjv_mJ34sdtWK0l}T%8x?TP|j26SS?8Z4Lc{&JRb{l!>$oV(Olsx{qcdss5S8OOgpdT@m`GyASzBrIS)*Gjy zXtDn%2*Hsh{QaP?ESx?%f_Rn&<#65*^XG?UZ~>TkbXhV1gSgBU{Dc9E;X*H`KFXVp zCOg! z+N`tUYrgE8TkkU&Vv8zFeTL+`q@|KaU6(@JnnI6$<# z_NkRwGhOM6gS-2GYITVM3ZqP2TL?URS#f=@p8K5MX8i5>?@&G(q$}tsEbj^b2&H0F z*tIDy7R?DU1Q%7cinE^YNc~iJD^-nvr03+~QrRa-+q~Hc zhvgxOVv89-Zum_jdl*n#}M1mWFO3X~N+JAS@_zLI&fJhWOWP<}gL0pZJ zEO1h0_w`kvxB$GH-~tdNzJDcg93rjNp!T{*R>&6D9-Hf^P{tqzw=h2=>3x- zZGt|31{h6szuo~xz>^KJiIf(S-{cS3*WbS>!)n$QrXBC~BC42e`fk9t&Nd7Xyl$_r z>vo1g$9Ph{702;P#B38WFOX(`cP=gbNF)Fj=dpcUi6?;~Ttk zOA{RU2fHf!g^+=e!ULsPnVVwb?31E9T24{-fGR9B9`Hfcp~|w2UpS+jb*xg3-Hhj# z)ZrIo_IrE`Mqr&GII^yT%VWZONge%IL_1?0P1Z1p5>Che&IlttJ)ZG5A%AEo%Q=ST zoC%xsoph1gPnCE6Tesw1@1Q5qu|!oJ3Z=c}Njih%vTbRdzuyh!ZRcW#n{$3vsyFyI z+=qI5OeBZvFYI99@3x%LVLr>pqKNz+S1~NqN54I?$K~fKkl4ox9R!BvuQ&G@_y3|^ z=ZesH{Gbe>UE>+Yi^R{of8MN%r&yv zk1^>jdQ=6Ck66GTzL+pT25{XcVsc zQ%m*o+ZQw@ur7lg1ZH6Xbs{uIQd)c~U6xF37@xU^B?o_+ZJskb9Cb^A8~L}Xp*4h) z#mp-8Q6?wrL!5{9N$tsAIGEFrJ>x2?5ooGTuuSc5&kD>f=BeXPmtFeBz2>k=p6Lj=CK|45|z1YuS>2xGIMl(NCPqkFc zfc?V*xsBg}RF&8?!;gy97cBYFwS6Ypc5jxtKxo0Sj6;!j#^y3u#2PB^q|q1k+-kgdBRQ|G z*dBAmF(;BZsrdt#0|TH-MeU5HCt@UO7$jwOJC-lua5%dO$+TQsCm4J_8@686^Os5b9ptCRz;YmU=;k}<>SluzJ_@oBV0I^aHIt%%Yo$?|hRh`^Lt`Lio8_(w{pE6B82)3(3{J>quIR z&muM)MRH8Q1i1~4FyEI`gV=nUCwFaE(t#^q5Yut6XKI{CN<UE5sv)jm z_`LOe<^{5#k0DLXOl#d>{@dBrRkfRjU&kL0E}#~J7Q*4QD2q%wXtyP873*f@*z-6B z?+YmQ07k+0^(LDLWBy3!r*jreXF^)t@AOFeTQ~6C`p;qnoJj`y`d~v5&#KE(;y4NO zoj=5P=5?1Z>+aKKvE|I~F}d_5Wr8ww;dcZ7X-^s49AtGEWWC6IG_#@c8aCi918VK< z?L|yR9}+k*x6F|&3NLIz>l($WAe^~i2)P`}?B$e4Y|oqFf@gekW^LOe?L!{TSbYaS zeZ1Jbj^N6EHCFs%+s-D-f?xx0;*+1CE(}+@fD_$OT_u(NOmBXVaTqFNzhy_1m7t zFQ*Fs+z{8uDHX9vA0`nl42ftZT2AIyD;63|t<+c7V38qY`j8@HcAtezRiw~ejkVt? zp^hgr$5NSENxB5ZZZrQ~oc)ASs8%V-XSZrCA-_;~F4#WqjVT&(OQE-zMvlvtN43~$ z50h+sZSnZ`%H(ihfoO&yV@yj={m_MIZz?gUt70k(5_bERj4pOJ`f%7|^&9Eb-tiBf z@#WHa^FO1*uP zv?ap<1WE5XQ9~=+G@(Qt+1Y>Ec$8Q_i}n&r3UVXXkBJ-~dj;|xRVunWJLRZzxip3R zH>-|1R^Eo{i;G(Dk-`X>J=|menHv4YkDgY&J=oZ_hOYI+wj;WD z{CMp`MCJY*va3NhSR}lLwM`iE1pV+XIszG@V)^J}lEpgml_2-E8zy?$o$rWCi7W$T zheyWQF~(d2re$TxYDZH%YZ@^>O11k?>xM4~JhSGInwi55p<&Y9x%v6+n4nFGvqc~9 zeXMHlaPym~IoA{=EN{xj9V4YI;0@V!U=W3AMk=ba&IUO-rdnm?lQ>mK-_O_KL{Wtk z@hLPC+gFzu$mt|yN&j?5^oL@q8S9TT&YqkL7RU5HkdFtOv;<2D;uA-XxOv#@AtFO~ zH}R8+khr5{CTyf8ECwt^CLfl_E-0T?-Fqz8bx2uvH#Zra07WPv8&`GZBBLuX#A=!7 zG;RpSUIci7pV86Q1jZL5u&-#FF{8jrfo}F?!~=|MDpT_ePNB&y#4?*Z6WLbhsTpdc zfQfZv@rLtcbUJszr+kdOZ61g=09zS}j9uI&BAcL> zQ2fdV9@VdaGfIhPM46MAE~7PZD-7Ad(7lmhtpDfijG2ax;!80o{H^Wm?7*h6R#WIX zvuTt2pB3$I4-J0kJ*q3bUb+qee1<=%&o_c^HxY82V<`#zl2bWq8GKnX3ChLT7C#EU zpWs%r{>oD3tG%&tTQ+uf(LDOp&|M5< z&Zp2`fRXd~*h->US(jxYsJO;+#Syr;<01aqVt%y#ro#RyBOrCzJGAyy@HtC}adzI9`FrUqK^WQq76i z6<@dAs|-DSh|U#hOnqOxM)o;)BZY+gk6viI ze^CEl3s7ia?3VTScwx9i@w`E+zG2-k00LO$OkX z(NzXNCK6Dn#yr%4A%uv++e!aUJoiI3IwmBFa=&jug$R5migag0OVo{&YmqFSacil( z>|66uuX%~(2X~qe5q+Hy<&-qqZ);gs>lhoU&%~{Dk1%m10Su>jw#iN&B%OLQZDmPA zw`^40Tpulu2soQk4qN z4ghwwF~7!h_e|5gQZ(vlwNyS+PEB;buQlgENbb|{%^@HU0|aN2J?P9Ucba+tTE&|0 zu83CH@pGn(O2)6-1LN9nAiDl{Rut@V^~qs#Q;wvvRqoT$9Rhe zYwRFtiSYr>`S-sGj-Y&fCrP#gLjR(^rVn1A0B7@C^V|KFNT%U~w`%VRu=YMZ9%kS9 zw+{~*`+KM->MZQ)LfkID3Uj4TI{P_wzy{Z*@%SYoYjKn9{Xp;&DFMTYdCYiZLpKe+ zQU6jHIvE0+b2c3;gs=YfqhtG7!tQG7Tf6j-71h-b4w!5V+hD0(ga(8xMQo#juNF&0 z&iMHUPwqM}Td@^y7`~dk14^W5i`a~!#0_I;KiNZzx?ZESB92MQ-&I%`Iu-WUqRJ2; zCW_i*k7PnfaXV}!Q4>!*H{P}3auNv>cYS#mXMwF%h^1xSx7fqW%vd5R)K1Zspgnq7(l0B-6oiuPDM;3T?c<#FcE72o?jU@jnFTG@5L8 zWvfjN;E`|B@{na?Mu^|H$vz|FM~Cib` ze`XO0N2ZF5dV_wapch^NI)#0MLX{CZ_guFZcEy6UVYHwKjybO%`Zzo>vB$F9QXnZS zq;AUAft&4@D6^iM0UXx5cp*Q*?FtpGnxCY7SZ4X{IhrgGRz$6(ZN;@c=@rz03bXOH zz5dAX2W8)7zlif^N*RAA{~QqEW<@&x^s0QWff6`knB$HwGE04462rMV>M?jcD+`Gx zz|6d)8l{z0)8qzxhByXn zg{X7ETZ8(cZ8F9P!9$vdpMQE@*>{#WuDkMcnmQNuwZll|-rMc%cdkEF+CP;qvL#<( zdJMcJytvzS@MXq+vz~v^!&*qZO}=rcOw`yu{S1Yq?fEws%#Hw*iDF|D6;=z4XDT|d za`5w{S}n34pJ_4p61J_bp-u&+9V#hp6j?t4{}560A{7b-M=a4)9+0STG1oV zZ6Ryo2QU6Ij?}xeHK+wHGybf>tUB*1N#Az|@~NJJygy2gGYLj+sJ;g0L5qs3{?U@_ zm4}FOtbM0jMy7#!kwV)>JG0+IL#Y_LF1%ia^TPkkWrdD^-qWVc=jVES-i zR|gmpE-nczRDAR@=e!gx&5G!FtVS4V<;#ly>Zv*uz3 z?eHnTU8rmZkjJ#H9peuaeO7%qIgx=`Hud`>-dCoMGCOm55qHbu@YS)(g3)NYZ-G{o zrNEpLdw2ek_3qEn#lL;6j)%{a@-j$7^TB+d>51iO^N3dC>vtU|PfD9VTnjLfMFeKi z`P1IhJ4YaOs3l}Y-Q=bIZf-X*=AJy#C1>!0^EUd>yR_)BoHVI=nNp=PusG3Wwje@xNcuD;U7#T{Dr zKQ|i6nnVlWGzWqK!1SrMD|_iLSaoWqg!jRqO{y2cgEDxBQm;CLR%kAAm={_9IiD+N z-Rhg<>WqUVfh~TR$jdl<@daOR4sccZ{|4>yfkS=y=S^&|uKU~GShP2%K=Jo@eG;#% z#1z+6UbpG*lfGg=5&IXb2IWqqOik~1`((1q0ou>i>FES)ff&J!jki5y9TNz>2p70y z=U-w!7o%UQBKBvop>yczA@nOmIyu=;nIfb(IF*cjm_ND?@6fc$OpBMW@Jr?i?qTnT z*b`mf}>^*@m6l>d9gm_LbTJP*kqp~QLpN#hKH%Vtl=yjYt& zVffhW82@jXzk`<-Kr5v}qG=Oi>!6(LpMo0@#ObPZF1svZ_MO4<#XGbsmS{VD|K;k_ zGYn2SZNuN2w3OghW^=6sWU4(@OkPbI7GVXx&zV;BThEG@Q^xwT;(g!Ga^0ZDizak& z%%g4d%#x^|akSC-Q=qd-&<{gDw4TtzjQC1d|EzW^H@3?aX>CTWOgzzw=SrOVG0FgTDkWh6AV6;fOM2q=!!r9yk_b1)jz%Sp(S;OghYqg%Dn777^r~ z^WXtrbq~OG_pqr!mgx#({DpQ2Z2|xV0d~*zF7@^w`)mnIvZ$(m-9yT{ zp~{2}rEJ#`o*Vba5qT|fl68z`bJVe))0~mXB)lM_dkX0<#e1VUIhH6|io9<+6IAxr zX}ObVmJdv}jfl>Xt>UvA49gLj%Gc_*@*-SF(k0 zY5l!gYE;an0?O8_8+Bv<8IOv_@0(Al(&hRgunk1=*yFNJ|bYkTt*i_Rk$mU!Uj)$RvwP%X+}r!p<~krv6Owxf?hY**kU#tg1xI zz5ltm*MD4};DaYhSDME6eXPfmqV|q=`%nntTZ;pmRz=4z7D`Kb$2j|}CW13Zwd3!s zbg&91nrWypXQ+OqCzG(_kPN>disNPE$fy5Ok^K}?D83M&F6&eh=HM9jn7UOA8|6q8 zf=AeL!oQH88Pm!7RsM^0DVKSlTxvSZC&mEh_lFt6c%PLoOu^?Ivs{i14~%W@nTUvJ z^8<)7YV+Z{fpo$zi&S4x6t6U6-(^Gg@DDvgiNQ5Cu1`5@F0RufA@HVt?CC@k85|>- zkEU2s84uUkRBc~i{9=+Gi>TS5`vznVz?`R?fnY!9Iru614zSA~et2R*4~anvJ%iZ} z7|lu|T8e4~?`D59{o! zbDH%77tuLL-jdVgeN3mF(}wr9&HXB`K1H9DWjQR#ikMc|p*;|FZzW|z7xP(NF|CO? zUgZ_t7pGI3g(|Zu7L+ftwChAyOp#fu@OQ&Gs^-t<+}2 zmn3;&Ph%HyOqdH;O2B$Tmrp5FS|$M+OH0<0dz#XJxuJ`jIg!F275m*9_p^6e-ZQoY zLKNcdnLpTky^eQ3kAoBeMB*I(>(4H0x8WXU@NuqdMboyjpHP|>WbHu#R9y|Y;@=${ za!TC*t16-Pj1##$bf#}6>_QrUDP6gkv9#C`h-^u*i;4s_ew$1*ov+>{yGngzkJ={A zq+}TZ5e2}7g#YOj0^E)&Rk5^~Caxn9hUa16*$ck#Kw!Uw!hps)@_RdF9#79fdKOHv z3_8C3x5fmJJAP0e{a5~g1faj5cZL2{FaMZtQz{Cywy}!Q) zh8-BZd=`qrLH5>xiC;SXC`#B0MVin(s_jo8+L!9a7hXs@U65@!2x<31PgmFB`#*zz zv#vmuw-FV{fE;m!MqSimEN;NKP+ppX(Y(jJO}UV+AulZr>bAp*V3B6TB2x@kj9V(x zS6V>i|EW9)bTgFVw85y{5dOq|`(nQY+V4EX5rcf__vIZgBy>9tOCjDT9N!pCA~@c& zZ^QFWl2}R+%x5ZE@w`MAVTO}CtK-ct)73f@rvAQtn@qr4oFQCd6XGv^rLrm_4^64= z9RdL*M~lQT$=>enI7Z#N+PkyD^i2u`TWJc2E4xN-b5

    MWQCLE(0Z>s2nJjvKs`- zgfS@Rkrn?;XtC6^2dFYx-wQr_U}fy2@I(~!K#x*%ttuCMLWC9fPBEt0{Ce8G6@VL4 zVzc^zefy6oy`j6ihKDZ8B0d20I2LRJju0T`uqse5=5ky$%e%?i{u|inB{!3GrG38% zzmhS>>M83mwt+ZKVsS&L*AV)pkM#g6%-g!36skH7V z=fP?DedQ=;f`&sCxNN~;YSD@~h;%ZXmc_+B~s{ABdIa#3)ui>*!~ z998woV;P$8N}X~+-o>(kuUtF%WmjwD@AQDC@MyrVBfGw2wTZ4?R%%X-!ptiqvin~-2F#!-@6hGrRDikj5N=*aM$Qh&m?0834EBjNh;0W2^m{ zGM5{^o!oOs$U@gUPa+l$ZU4LW67?5_s2{oO$SHff*lY)_El@D{nP{LJ zi|1pmH)m0y(M{TEa9B8jTNR9$z`+Lei9odgeg>E5VLv{6V~#0y_G}&ubbZW)UUsCK zc;+IhZ!Z1c(&>S*30Ue4Ez)IcM`SEf$X&oUhPkeIJ=X7~#!|ITki#ta~-s(eLH|XMwA3#*mLN8%G+aS!ov{!YW4vuSqASjY;xGix-sM ztb|}a7IV44i}zvr;NJNRI(NwCd^z!cjF@^_bqiplg)%~MXxpMhj_xRhJfja>;wdY# z)An86j-HU=7w4+~h0G^nvZf@^n1K?34Lcsz@NLuNC70$cAcF7vX~JyZ&&#RbEl0W& zuNXQ_WIdQ7H95NORS-3?wh)m>Q7kQcZoDX-O<+EtsD$li`HA})n+=VeF=?>_H2)zJ z6JOFakQz>yIND@>mWHLN8K>i>sNoyhX1m9?zk+r_8zZvY70&O3hQs0`51hKV)s8HjfH0ZuP$GUh>;K81v}#ElnZrs7id@_{+e0TR~M`Fy5Ls-Rhu%&yIty$`)z z?2OI!DYoqyLK`gWJZ1~)xSv}q^qgZ??Npx+&DEwcv{bMBSRkNw`!hfMoU7gBm~0A@ zJNg@oQ<+2^hBTj({Y3s^cEQY!>G~LHecwOwW;ZfZZa)T_^>V2$U*j=(*hlJ{QR*ka zAirKxDItiwTOhAZUYT&7J>RX>IKPFn7a`ns8}D!XYQ|_Hy;?`1{J zLGeYpH7@;SmoQu3@hx}@EfWIc9~REn5KG8_vCWHRPL?)HIDaQiiM);obhVNBI5J$A z^>WYZ>b`nT%M~F5wmIu?{C~$Y%_!>y{zO+x24S94sKITV|D=Sa?PV%~bP)`>7W_=((#}8tUn)ydjPR<& zYztL=SJ&(B$#iWZpeX{FkHIXNkJ%?{{ffH0uPm^>>aLpc|Kkh8J1rQr(azvyzV z_l}je0B}V=R)tb55P{3}=szq}Uv%c{&zhw*&0rI^7sQp!a7 zFsJ5yIj^8#cUKoBc_{tHN^Fo%A(S8=;wGxB7=7ka+pj6Y0u-8(Wn+Qy1V%<3r_D?` z&|-s#R+MtL(sLmBJ$)`?|M-uQj5z`iU7OOtOR8BVAO+7rP|@L%d={a#vf9Cw2!&Tc zc%MH>zpcwYy|WYhy%PSC2K--@kFi6#$r^Yw0k*vfq2$l*!0QD00{ltfj08TW1H3iK z#N$H3EgS3D&~f7PW99FMCOiPg^AGa3Uf)-R9E~lb zith1FT4tFPM@T7-#HBiGmV4m{DY)jh#IM>Z!P}Ji5|lFm3<=_%!}gHa@cQ(Tb-$eO{%+dZ@3qoR@cU+UE4VZEuhnN86b%bX%0ei3**Y~X_h8TZ5@wU zc1p%l*ivR3rZMK-JalDEbv=t{E9A4X9VzCw_Ie$ZCGeFM78}&zc#NOe!>LP4t=1RQ zS)G>!S-Muc6D0BW^TySGNU@ZJeHlTgfnyQ(Y`>`zdIBTK@^ZSSrp%gnR}P%>hF{iy zOl$66Upz5j*}|1CIB*%0DHU-!=ZMA2irDzd9x%{cot@`ZF`7al9#f!&n>$;);#tta zsKZ8X2YsvS%1(^@#u&DaIrFS?-Vb)FU97|IU1Q##C;E5Gr7|p|pzM7W_*|IT%s1 zkuj;{f|V8d%g?n`ksyyI`jQ&CWB-M{)EgvzfCpP5Ap}1~0Oi-<* z8H-U1$;#3h&@9^EZXoGma&yn4bWG>6AoFIG3j9#hEpZw*V2Ecl`O38ypj+03tvP^X zZ7is?b#@Cs|Ca5SDi?11fb>l0UZb>Mj0b)ttM|E~bB`lg2}sXQ^g zgA?8c&EI96?#inR6%YwMS2DXm5cz!C{Yq!T9T(9Vy@m>No0&<}aw208=2z0)OgXtL z*E;rOB@D%1&MLwk;1K$W>qXKbv3MdCne6EP&G^q$(oIMGjr|X3s+bfi<-8F2_VQiY zLue=H)ydJ{#BpQtWpS#jwV0(8@+nl1#KOv3L(|^g&ZB$Y* ziL6))WzT1B+1UIex?5ysDwERwm*HEC;@MBIr!PW%=z*vh!}^e9kbnt8p<&eSd?>#* zElvE825qdSCHBq1#_zkE^F?6HgqkgmBK|tJM^(!ONLVM! z{Vz}ppg&!UJ^V~PR2ni)j+Y2eFq=!VEwK1f2gd8foz?11biIDM`1oXz;~fYqYmu+G z))&1GW>}0r8k@$!X%<6dv#s4Y1FUC++VHtFKS$sh{Lh&1{j2bIXk%3BQHf*3R5F;M z+fPXUuLS_%cqb8H%d!NERY6>_J4ns!;$8wlY?$X6Pd%4cUd)dDZYiNKvk>&tQ=m)Rq(#^ak6ffeO z5V1V9qremaaCkd3^2gGQH#7D}GVmD_?3l_ZkLb=-k*P&~c#hnoAF{qqqtN2oB+j5) z$i%-eRn&QFhK?+-m2&#jYA}*ZImX>;M%zXger39S<-XiKTzwR&6omNqK^lX>BK{vp zpa)%WzR~L}57y1J0ipFx^~@rsmHK-qh%n_}AoipGy`b0y<*-T=#4YnpeqM{EB9W@u z9nAxa8O8x?n4mI48j0DRD%y#zo6(_IeyIq<2uNJLQS{wEr&hXzyeFIw=qYrFjm%Nt zl(uz}EJEeN^dtMwJ-Ksc+wNjs#kR>CY|7=09&4%}k5_4eMqnck5hv%+&YjW`o|QEv z`t)9)>{)5#+|~5cLhsy$s-aEp^OuWv8hY1iv48&k=^kF0`Nv8(tTnhnp;xc|)zPum zapmqkUWFJBNh!v-Ib(Qr6Im*r0bP(71dVN9d zeb8elcAwP`J%-A&dYAXe=@Ac#4XaYz)g{?f?ononj57XGOLl1GmadFn74b%sWm%oK z!or_wJCZ#GbV{C9{!5E@_Qp?BW)YsP^dPb;@=%uPaOC@^*-zQd=3h6;g{gYS$l>AQ ze+Pwq?@C%<;|fVY#q|4wq8qWj=3?L2#aw~6Hos|}qA39!o__+tN7X`mZ9CmSf!tN> z!mwODK?uD>1ZczH;Yn#k21DVG5mvuV>PkxP_N<>qf9@eO`g`pqV2Q~t#ve$GGCM2D zx44w+so13iXeGrKrXW{*j}z{x+&{A$%C1ODbIRRG`S=Z;5c3A+=!I_|r+K81ZiY+5 zQb6`2Oa?i_ETRCM=}{w#tcFC{3B_spnOQ|B&CqhZsj?NULVyvh9xdZ}MxbiLO3>Tb z;o?A2QW9-nJjpjOhy=-XnQ5kpYz7T&BJ8a5;!^eo7C8jDyB5OuESyx>H_|Wa$(bjJ zMr*$`7)sLr172U(x3*fjeLXB*F8x}yn9t(7hmADL%>B$yK{-!S6JxH_u!rXS3(tgY z9&2ecoJ2Xt;oG;A)<6fa%L9#Abyd|pRIkp=y)Bwq!+sU$-W~viB1!k|A{QA=9Ow}0 z+Gz9U-DXRom;9NjxwHDafwm02wE~Lzy|<|3pP#R@%yjN*Wh{bMNB?^PYDnRRiZB6H$w^}_QUR{Z^}zL`uZ0>!NVMk4&T4?TxBv}MFz6yRQko>OCqmY$gIItVWHq? zV0zz|u=?85A<8N`X$}>X;3$r5)tLlmL5QBoS}1@cBxFwdk3jxYT zT_Jr$3bU^7;*uJ%YZ?RV?+_j;3qN!{U@;SYtXyW2S0vld#r$^ha`AJHJz2N|51H53 zJG#H99uKMOja(&0WvW_@veynXe&SL(ieXo_#W(Y3{OJPGPt||ZGJa18VrK?M6>t5% z>{`hcW~YSPURr)%@}=Ux{CoZPhag=4MZkbCv1_I<@C8^kf%fl|Hm|8_()ilXygcZ( z0O<>9n=%FqVd=qhW$8Pph_R6@5-+r(qw4&wd9L7I zK0RSf+UDwHE`Z$4ymv(%Up3JbtGinc3-4Y9B zoL22jg_Qk#ghKSG3^D$Wj4(s$KI1A}JmA2TG|&Me;uDMO{R2sdD*{5ntZkdp;Vhkn z5Nr>VSoh+U1V4IG=|EljPzGLwP@MD0^1_<=+vOVsHg5ypQ|lYDFb*;rQPK`!aWG5q zJLV%{EK5}S*c%kLU|$U@^2+5#_x8FyG*QKua^9iTNaf}2NBcX4nkrU(;JgJRjK^-7 zX#Psdb^NiSCJi5OZ@Oc>*CCC3kdG#-tV20+MWBkeoT>tBraUJGdZ{D|W6W=K`P(`* z4akg(CLI4dz7-L~Im0BF5nIX_=JQ-t4*GMuyyio>jOUTZWVu$?8+5vI{YaCg)18=Q zD6!?!%7k8SY_WEAS;gAnyXmxTSfS6P6x+0@KZoJcy!qnEh4tO?Nd11<%*{mmlJI;1 z!kmK71T1m)$?K7y=7e_!Dih(x+YLXM3VW&?X%5#VhV#|}EK2qfc;#2#X~s#=A0sx7 zk7>&C12ukB!NX$yNHj4HV_zI81Jf>T`o(kcRH9|fi^E%3i7a(9L-%c%&U18f5zo<7 zg;*c9bh%ijaSpf2cQ_R>ETwqN86uo?#%y{pPHXFC{4#N#HTtwMr|}8`fS+SkYc5D8 zfBp>w{efn*s-ohv_Y=EZ)tKdLKj#CfkrGdBO@U#E}QGJFqxl^uif*(9%Dw? zYCn#(Y0?>)YIA*koDVnA?`dt6-2k^^j^zt=F%Az8*ioFQ#eW~2!7qO2dWY-+JC^e# zaU6q>yHNCYwvlwcoNJ~2HKY)W8K=>pw>7Jc_5>qy)UYDjvN9Gzh#`jq0V0F8+j>)G zORs!%g7kog;@e@+HzUm)C z8%<@#-7c8$DIvB_1C)>6SG&PzuvTX~BC#ljlhxfx(@L=AY zd3xfNILs&%lCFOh@Gs1hI+jzxWUXAiWK5w0>#l;INpp2H8WFG!9R`;HZ zvc|c^L#C+c+u{LtpYu;k5BbVlryDPuTzr4d&dYs(li%Ocfi~PA{1&{DrH~pp!d)t( zmASIUN{KgPq@tGQww{-m59S&ieeE)CA1v^qHYb+d18eNe$8ko~%G63)TUw|Ud-HJ$ z3E(s$wMlgu)e(i7h21_h1y6DXbMNF<1WnG_2h)=}eY^QR+1u;C-%wKb9R`U4Hehqr zjJG<}Mty`&QgMe4-IH?)fl~ZTYw^cl5hU{cHWIU_gO$t-Id=5letxLl7GF5d_KNE7 zB?g6D^%fgYS43(rq<;`x!-=h|ua}#Y5L8K{qy{IEh_04K8Th@arS$EUX%9%9cswjg zBc<0Zqf~#a>Q&TVbB<%CzvfgR60HpDPAe|99^_59i&2OX?^U#Md=hi@Ogu}ZkZ;-_ zR%U8p!$+K$X2qzSXZ=0`!rDX9PN*(rzQFW;)E@ZY>8&2=mj0~)W6o;W2(8|HmNNV+ zBD$+w+w_Z!Q;mmTA`YSFzyc4JQp^cHw26*#+TA7jX zu=bM@h}7jGaE|LSOi<&pF~C_Qt$5tt7HZF^^^WDYi3S6^ z!++L@KovW9b#(>I*Z^GNgxy9$8GM2h3saL9M%ARtGhAZ*Jud((dHxHOcYcqA$fvjP zF39Y{X=3Zz%U`3_dy&ngW2cW_LWY#Re&IHcwbTSF_gAMUSNPE{YRWImpMp*_c%|xG zlsC|v{$b@LwkoNT(Ind(_?5xW$CI+sN=>NBY7wuTa|;Uod2Ii^E6AP%PQXoy5t{l; zF*rhI_6!kx!#PJZeX{~=umR?kyBY=5W*mcfDJD8tEC$mOs)D!<5MR3l-lyg*pa1si zA+Ny2nDV}SC8kV+eo*ymsXEpIY#HYg3LN6~59(!DgddKX1BTykOn*ll#eCQixN3#o zYV{QEo^1=3z;t7i>_{}(N}sxqA{-bSlObySifeX$i$8}Hp3JhyV}Jc_BUI1|B$z7@0ca__~u^tRbY8#2S4z(VjU z({|U^9j{!!2H61H0+8|(#H}nOBqkTm_P^U=#+_=WFO}`E9~z#7!9L9oj*&N zAIQP!x@Kmyl<;^cj;U#$B=6v;u5N)-#lpX8d_ZKiLs(N5CI0gy!9?`Ke1L#jA+!5m z^8^!Ds+^xrEa4c!LU|;xt~RM>%_rWX$ouj~gR*fsHCbtXA92Spzx4XW05>~7rFd=V92FpUZPi}j-|5XkgDb}d@o$?W&h#rK|YFH%IP zzOn7S4v3*>sH=>207rrvLXP(>AzBK$T+E10`gU@G!Wtfz8eFd2k|I$&_P#G}| z^Q?vnMuGr=5Cl#~;Z{qtLC!usd2pm?J1RYSa;}(#uzynO4q=?l8Z)&y>wC7XDBK8| zn$#~7y#_7JQO4^pulE!m7=}6%zAMuQgaf1jr=wb_>{>>?Mr#I`n$o&K5^HmMK)ufx_BmUsq30Pe%u+ z7fU*$$0TrSW~*p)H@dvrQ`3q5e*9)-g}~9?JHx&SbCvCNJ<7G^rPBY$#ckKBmO|u1 zx9H*lfJnf>!KvP`;drz~Mf>xU6a+Q{=4j&$xrI)yvD3q^F7JQm&09->2Ky#8jUV-; z3MmH!WZrjOkbH)T+P4aH(~-L#rD?%Yp(1H`8Y;+nQEA{)mj}v6FlWNME zYNp<$qKa2XKr&2*_dDY5GHT6mnl8x?l}dY4oEqhaE@l2}C!*HlQ8w|Pw{p&lWH`4hl}|5B)&L2g%uHKsKzC$@fV0VY&13JTMm`qx7E5?SeMwW1S>QQ(kqbi7>Vl)5 zW|B<{l$nJrs>aFNiisR?*Jy~jldAa477lfi5ko8xHVt_&&V`bA5;K6JAXgfuu@aJa zrt~%D__wvGPaq~0v0{mkCW9G4*$%XtDSO;%-XvZHC!?-Y0<0HD`i$3E>MwEGEERaz zGRp;CiwpFYp8Y~swWCCLvTF>)dr-PYMWO7l@7x=2r(hI8;WTTwfnwa|vq%hffzyfU zsz+H47MbAVe*9&1S4q4sI?1(gLT@^mHY*8PG7*hGs&X;po~EBtChH1Vv%E)AVk?o8 zzNcK{y7OZud8G1P{XT|$RGO=|1}hea-aGL`!2IKzocd2yMOivTB5TDqc(julHOiYj zkAHoAB7qv%I5;-SQY4Ktc8GXKk`z6<+=ZJDL&Ss9(25UqpBFP^r%C&hh4gGl59}vx z2J%nvkMbj9YO|6GJF~52!oFYzlQK12A27pU56!C{6cy`CkwIAY{=@#DfM-HJnjKP= zl2Re9KHVW+iL#IulY2=oHu0FXTRBjFNe``gZ7TjgGZ&FV29M}ZwE7!4QlaL;)%>Eu zI?|h&(=uCQV>*a;LcsA8-=L=5pVF;LVVZnRtkU0qRC#mK+_hR!fK!0TZTGM>Hvak9!6 z=jGG2bG|d;gmiHkg?p!P_q=qgD)W`SxM;19(oUDBVhs1#XmOSYp_07+->=ojlB2}- zVW z?R7-sF@nA4ccpDph!nEEA4^MlSjlF29nxH{VEoG2np&OnmMUOSXlZJ?2MC@nmcW|_ z-?s-8Z4vne$59;9tu|xIRgT&tFc1+PAH+P?$^ccQpwDy5eZReydO}11q8#=L_coY` zU@13`_Yz_p9CKLw%#y9sB*koZs$Cvcpx6MBh=iqt*1F^CKp6p&>;dBg2*?m){)eV( zjLWla<9W-jE!$pLwr$&Pd0}DIvTeJTZQEF_mW?gD-t+nJ-rtAcbzk>+9><@qSruk8 zmn<1tGM{*dO9&JLmC)_KLoNGB=Fjppj;z~BUiZ|=sW8hM82 zdrhR1>Dx1k99db}TGuD<39))CGG0~p3R$j?jeOshUO^sEm?!5j+@CzUeyy;7yrby_ z(Dw8A<#PFblb348fHhZ7hl&ZM>4OA-c&~$M~rSN`2Rr!Z&IND$m?O`Fs zFIe@GSM!{Vb<~7-k#AWjK8pSPjO&9%5STyQ^PWgDW6MsCHmz@3#XmEh(`BSxOCNz` zCBR{M<@*xCe#RIP*Y?~>d`?m}VLBH~D^xv=TB1apiIujJ1GwtIv}E@Pl<5FJEl1q1 z+i7t{r;5gGgtfK;o_ooMPVYMqJ%U)ub_#Zyq|ScKIf|?bOPLsln$(>+tz#N^frZDc z6AA;hL-kGE+$QiYr;Iyc1T|{0*-H+l?oydN!`>hEVny4apNSNW@m%Ru@=rj2N%^gR zRwE@reF=0y5f7;Lx{wLN)HQQNu!7>Y+iLvF?2wx?g9X;aA(G|L7jh1qf8F1`=QUEH zk3zdtgHwsMPv1CnpQJKdU-06^b_N}YA~HB~3H?^R?+&j*C1u6`LF&CMH)@9#ss zDpR|vjT0=LC$oMN$iKv-bUziW&8_eX2uukn!!alV3%>8o@uHqVpO%$I4Yf0lNFsMw zzUW-7WED1nhJq7ws$sq+W@>w$EIpNVrqxA;6%3CCL; zG>fcd!6Q|CZr}n)nfTx`h|G$2vT-iA%{?wR{Ij5R3y@hEB~tC$1~$E+!I>;;-`Btq z?Kd)G26G7cHFZVkl6>(B8!S1xMJ%<#P?O!vrpoHktu5mmrGLraF*nGL zF)pcWH?m-pWtUAiru^KSv}3#JN@4y$(kg0^De#!dw$de~izJbW?G*!4Gm{j|D!Lkj zd3TlYLEy~=WojSCO;V!ck|h*2i@&HC5XwM(9eDLv>-yU|IkRw;E`>13q^YgIxhztU z04?YI^b|>O9}t1S+UkW}riGI{a9O>ngI>+js4P;bP!q$;VlS!oGIvYXQ|LyO^$)-d zKqQlt^QokWuk?es*Pt4I$cH2)p{h^8iOLzQ7{xgF&RqOI@)^q3?50xbC_neD=XSLn zcLh}wE)?FN!cvyBUfFaLPPR(_VjYk#F3mt-*^@0yq7|<4N0JLjrPEA)Km$70o_L&< z9@y|!>Z30T>S&@Pzj)6BJODZ=Ri9fr{`uG)#Gkds-U=O94*%B`^QdmxVePK)B_hVdNZ@7;;`*zc>O+9nO=~)j;|HbjM?AeX&`9ej-1F6j6^RpflRY)q^ zP@9G>SppAv$|Qd|nuba@gSYZ{B)}Ouf+MfnwVXm5~Ud*1_Kx^&oV?%xUzZReYuyx`^lQg@Z zW!aAORJP@C{SmAiO+Iz^_aRW){ymO(BT9}f-=!1_{8PbXS#N+`GXcHC1~p>9MdNcm%~ zo0xz=Em}2mz~Sj)m>8_H4=+5Bv{~}#C)`!Pq;8mK=W0ol@UBEFY)uoxN0?aT`wHrZ zC^cy`lhQ>hb<&)}-1Sfl-x*RaW%Ic*D8CWZW^5Y<$w5&>nSLW`nP1-W%aiWQDzgf^ zWW_qY&%_bzuRnMDmM1=z(Vq!o4NTOAmL+}$}iptEPjn}r=W=^ zOD~muKf3!aO(GZGIwtpzKQ$f}MAjI_V)fIsPp8TEUzI-%bagXe7I{6+fv3lR(%%SBKA#u^W3z4ee7mIvZaGiswiYC zw@HH3JpGY*dnIQZS5s@gcvE2Cr*%QZ^ZV1qX^2SL)6Mg@skZMPAawWn;c8AapNuW= z6-#bg9N`z$D=##Qxb_)g4>~Dj*wD(c=XXNT{}w5UN*x~0ndNNAepAm5Yl$E;HbJ&K zzha#B#K17g>T`*bSGFfIu2R2zH-E5+AYT(^GK74K1LNe}TfCD2`-C4wo8Zau@N{P6 zF#9`AZhdjcyi5-daiG#Bo$hjNltfrks*-9rtNdrspxGyda)+1>MV|-)$|4e0`)T4b zVvZ+}a(42w8{}9zB)qaKUPA}R5lY>%h_u=DO%yHv{EzCjjOwQmW2lAXnTQ)_k4~f_ zN&FSDnoV^lzxOARC0pT;O;v3!%}j+S-ztP~-3!I3{qPEFbG_5sBQF+(X~$v1>I;-K znvn{frXsogdLR{(e{6_7`nr%TN^*eaacrLO81RG-RA!k5T^*h3f19XWf~9F`X-TaU zjc+ig65H|O3}?B-v2-O{fx8HbPu4(xz^I@l!t49Bqdo|w0F6tL35ywQzWU*S#({iv z;Z|6r{En2N=P#C@e@H+Xigp?_DWgwLHq7Jgd}RfR!Pn3(4}xzKxn&zM1IlY(MbGh! zO6Ih9dgmH5ULsQeWG=+SygNoim?PLuKxdddiQ<7@ghP+!NpO3uP`WUqBA`vfk#R=S z`FTN6;(I_X)EuJk3^8zo#aOax!YhtBS#jj?9T>K18Cb}_E@#r8^1)E1xKUj7G98d^ zH`UyKt)ywe#-XY#_>oCwdQKP0y;=P6cs&=5AnTX8RS5LJh4m&x`xg){ygi8cQi2sK zDl6JvPPxCCfKz<>ORogv4YTX8$~OgLmLpX8GV>uGt1Y>LkDFU#Q`3^-nD^IWZ5rFV zcI}l4JCs*VWleM>v%FikM`2i|BziJpV{GN`RNpUwj0XhhB_-5Ix!|Exa8MV(DvZjm z(8Ps*bAla}Mz+O_;Cq%ao0}N|=D^ra1ivOS1PmUPUEc39C9dg(&C^F7s&aqhWG32p zk5u3(-*(CPE~Nr^&!(Tfe)<4`r(<-hxVXrf&Zewo!D9xuZ^9wZ3RB`2y)*7#uD7qH zrb&EaQ|Y3zQIeT6x(^Qov+_+Hca!L98b?X`S7b>J^q;a{rg3igmQ*nmu6XAq=g;o% zwY*o=eA@lqUIAFf`>X7|!1>2W95z)p#$yIl89xROtWUjG!Yl_BA9`?mEI;WXQ!<Q;}Z~YkWxJeH`3s+Ea!1~elNZG^6~-> zYJsnpV&gWoN;HgcwkFNmMt_h;v&eYeJE%edCbyLNVK555kl#Jt$AtktQV82ufrhhO z{qw@c^-{eOweC#+=ihVmwQBI=+l`;8#?ox&5`ql=vmZq;cio@XPe0~+vV*Zpn@IFT zAHfoOH@wRj1&Oi+kj975{~7lT4Vm>%W3p}28SYEoC}!l^n_6473GWn%MoS<*QP;i5 zVmJ&Fa|z<9$2OJOO2H$JkQKmZP&v(SQJ1n0k4U+HW(byx`u(U_Qpekv^h1+E*P)=HpPcNL`Q?!2i z%l4{QIgOk=%Ns)!y*9Tq29&t>QFhNbh`IN9Q(btgJCz)<(-+cTRlG0GX8$fuVS!W1CiNV71*V^a z-0I60*3U;^WO4k{p{=7MQ~4=I`@-$(*H*N__WzVA=jS03X^rd3a+ISa`(2&6G&MiV z&9V?$dO*8_xEOl;V>sKGPxaBCeN8eWs7CmYTPLOV2ZW)cWFL;l!>*SN_sif77+VQ|6VRDS&yfh+9F#7g>-k z3wD0!^m!2SrK!J?D(jZsk|Gl$SY<&XIcQl_Bn=KiX2!Q$woP72X2;v%Sw*C!O2^k}Ub{CXuIGMaezq6m(1@Q` zz2v6;L{Ee-PEFtN*$@&I-v1DHQxkFJ6}60Fu;aq!^Hrm#g0fggsGpE8RY7)5J(^!5 zUyRXi;cO8rbBeaWtV__#GWDghx1n1;%+FEX+Qa^eTZ6*NCpB3(Iw9C$ijTW5qBb5o z1{JZSUAL-hR`6Tk&`A*#RRD@E0&IWXUNG z;Fq-hy7FC>v=)Xc+o$sbP@gx3#c8#5bUfewc0}eKx3qM+BnA=&TRfg{jfSrKo|oiY z>I@}9jF|PP401c&f4Q-N(8KM6f5{k_nR7BTJG^ejQ0ZeemQDt5LgkMQhaEYk(*$Kj z&q6i{Mc2F4gvYL6xfY6DpKi~r3bg{KNsnNNPQ63ayy4}yIPgd4(AN=-iIg0~_X-PLe$>(YIDt)3-w4 zTwM$B%^Xf^XT9y)gdw?KDiQQl2HWM+g5J++F${tgWLn^_l0d+7>@*?V173hhKzuX z{4bp1sN{^+BI-J1p?tVH^^4ndn}eiTfjqoZL$4KB`KzMzZNSGM~pKyoBT zSr-?=*E2$s@N%FWjZ5p`8@hhVZbCk3cKq>qK>rKR0KRztVTdFde;3c^#Fwq@R*(f32;F8H_fk_aa#AUF$=t zQqA5KJ~TV5|7U;$3-rALWzJNq0n?yVB6~^tsdT?jJNY0f*a(!f^*_cps$xkQCFDP6 z@p`1U&(SNk`VJ1VW!w1^#q?} z*T+j#IbSaM8AT8Gkd=v>+R+gTwV>%jA+njBqXHAM#-_UR@Zw|cf{TTr4es&nb=dwP z`kIiL-~SLujkL~8(@({eV4<+)>f`-P!54Q9J7Fs_WFpg0S>~dM?iYyV^7?+L z&Prv}YD~xa{jvmt{C~v#<)w3!>=y@7&LRT!*Nas%NrALJlzw|ZYShFIk!@R6ws4&> zrfj~i7;1T?95+zfyN|C%Tv4xy{QD0Wq|U7PO21rWT7iuOe{)e1+n78s&BTL}t{n&ji@e&z-#a#M(SEm%UKYdvp0w%h+KdQznAZhS4lVd*NG5*g-)qKmpHp*)0EwG}L zX`W>~OM(hpbctyY;yV~D;e;KaWVwu5<}H$tSFnx4t-v*W`)OBbM|C*$WStiqob0Dp z03QCYvJX&KULqAAElhc>UFi6%3Xb!?1bi7q9vgix=P{#cN#=aVSk|ZhgVYU)5{4%} z+=+{(fm4B$(TM$Xj0yD7{18Jav?Y6d+?Y_>O>!`El}i1VSDWxhf&`Vw=TEoz?;sBi zQ(1MTJp1Kb-wgWgYOPx-U1ZSZ5bdqare;CbY@yeL<&f?|Vg;SxELWn2P#`ahd;yXU zlZq-OM0M3K!q@0w<7><0t2?}?%N&|!m8DSq%|bvT03lrNrrXG3{Fky~f$05qKsGqq z*{Mn8U|DG8JzE|}$3=}N?XI{@{^z%Jvua7Mr9dIT)`F9Cw2?80u@tWB(Vb?=C&Dj% z+@HjUE-s4TqH{+%u;YFnetxi=`}HV0TvKdgiR8hU++)wZBG z!}ZMAitaj4^QolbHWd{9To5i>O(0I{!A7U0xtt?pHtpi$^9)A(2^??DKNK|Shf|y; z!e10zy`hFFHB^(M7)+8P(NZWC4$RjBS#u&1} zTVXl{l}$>+?%P`cvAMR$#nEG?XoTY3olsh z0uBPeMQ+0*&*cS$swCuOVQ|5zD&^(%NjC(9Q~qjJJZuJURfHCg8(oCoQ?p;j-*Glg zU*=z&^|}a-7CA4AGH>9W_)n?}xnNgq>M`}LGtamrh+s%9EI4;@LbrBt;)FeCy?9zi z-H;TUZo=PDr6$<+9c?MGY$6UGv&a_+4s?=|bKJyVU+Jh$_Oen1#O(O38?@jF6z@f* z^*f8GrUQ`{^Q`$z18_)%$0)W6Ri1v~1jgF*D#g*eh4nk zc2mE{*P*7We1*6{Ccop^a+qoY{+6Xle#sZuO^Lu%1gy5hFNqeKd^+LlFoIiJ&ZFtHYa};* z3`&%QlFF)Ec1ROe3MMt3sR^xn$-Z@1Rwxp*ULCS(&P%Kqm#E?!!P2wB|lC zf$W&h-ges9WK!NahQ-C!$>6N4rf==iWpFp8IdReR^7AwE>QUAo@b$N;6+_@4e%}u2 zc)1wi3ugOZqM*D7+SDR&!@TnAXMG*b`T8TOEcOp~cMFjW3o;MDGRCV;p5OlrFLSou&T;`Y02Hf7aSXbuToJ@rN+vR+ zr^S&p)exZx&R_|s`|pEM+R)vd^P4ff?1=VYD$?J&TxF&lbqu~g|8s1O$Lg85@(T`@ zI{9xTe=&HpKXfEF%BuWI!%Qe{vwvV_66O(11o-*)fY-UJqr+~j#$Vv- z+sRTDNXY`iMoQwP^72X=468@P6ZQbegl47^r5d$=MiDK4HZ_w_ouqeZDVsHN6*>`O zR8c)S9fUqg5n@w2v7^V;6p^Vm*B6V0Mc3(L6qvTF#lOu3HW8sLUCxN6!f8>_S||H=@Mtz3kv^&nYeU>td^Q@i`wRDN757;r~MXHKTD6s%c-D9=;GBkFp)@Q#43=wsJ2aSWm$}5Dz{T4 z;~!=7z3;wz)MA_;o-w zz%GZPfsss!;Inb8~A8RQi+*}24?I&FGF*MHXO0`;~?Df_O_6g`qc11eIi3y8k z3o)bWO;;~5JW|VTT)r7<#_?%H_?N`4Ph-ZGVeH|09REFGk$WeB6pF`Afk??gyp|8y zap+=g4Y&7x;c?64j(gd?JjQzQ)^bdd6HRTETb+?@K&GqS27yg&E*hB#vs zhl8$<#P8;>l)<{89WA>YBT|ovsflMV_ccG10)^Hhw7zl&FMsgPj%kpS4T+sNJzN{( zBn{S~P`Ro9Zu#w%ak@>r60l_Zfk*;1^$2aF*>x^Ieh(`N3F?}Y6;=o7qe2?_(lBfv z-07r7oN$iJL_FoMvb0uvxHp*C-2k7qv$Gpu_P5zPIw=_^o(QXMtFjb_WNthh3x&=t zA)=qcV5JaT-Ow{MRp40Se8<^tR`%&Kj`&ICTPs-*MZ%QwaAl2k_@1JB{Vx$5 zo?++dfk^U_(9mZ9l5ev z>C6$ODdCFkP7#}e!|QUndx83^Nv;i7tCB}Eb<7_@kAHwFcyv@c_%KLThI@>?7>^Jh zHuD;=re9q-H>3=Sm96IJEIAH$nzn^X|1|LB9c(qqLWhfkMHK-oaY(Qg6On9>6fO<~PY`Pp!ezhz2v`&|l}>-imh zNKSTtnHq2?Ob-=-%d=^xo#N)_pUh8p)reOS5}&Ki;qszS&_aS3OS>W!%_;H z>7>gAh7gXFM3)0eGWx5v8QO=#PTH^CUo5}0=XwcD%YBeXx|5i7>axg6+~t-E5*&Z%U}A!LeG|t>Z&?rd#^Shj7LXD zvn7d-G(OC?GnjdSS3Lrk+1Ey%-7lWL7RKhsE%nwem?AcwA`S3ozKG^$ zDQHHw({TOU1xo^W?tp^}zEBt!sZTQ+(y0cFjOccA@{*rdELzMLbquM+O&gkE;uX8xM>_uYcbN8y zz4emEs}0xpSK31IIOcypdadTTupBJJ2ho9)E6R+^)7GnkqDF?y>Ec&Td*mf`P-q*wLfbi?Z^(b zu;nIt>s|i2o#C`=9(%vS+Cu@a2+AMX)zkBrA62(V7xhRFJNsRteOf+*y4OLj=r%2S zSi2R(g^BHwQl9Ye_`;o#d7aJQ51AP& zByC;g7^?uv2Ks%DocG#bcu*by3afC&?JsCw-qNls@U5l){<_}<)4$*4D7CR7qnk%} zbpycA{qFw0u6MuP{RjU){&wv41!>V-w%~OY*6YY9T;UmA^me8vU3c3~eBQw~>9#0< zsG~$Rj|7e%#-v5{I7T+oAo+2R0z-M<3-|JO8eeD|%0Fv|Y8N<|*>HA$U*1}lAbd6X zC%#WJ(t?kdq5rjCNT|TH(YN;7>N|wZVhk9C1kQg{%4A`w#%5i{!s;4Rhe+@t+Rlw- z3Ln3b2Vq%=-43p7;~*`C7J&q+kZiHkv8v{f7v_0XE0;tk&g$lHhYc;4B|!J8?5K1n zIUoMv$d$=5WJYp#87jP5S`>X0wVGqt`8P4kAAaQm5u80{K)v7$N}hl#JfkH~Qu~3$ z)63re40w!;TUJp=FFwq#`6;*sGbtj#h*=0 zO{H%%79Q;pi}J+|L*m6P|0;c%v!`n!G#|*<$FiuG9EZ}5<5QH9fm#NLgo+R@ubYjC2ElN*cy znW;7zW-8bYgPji%kLv>pWTj>M0te;Oe|V%`OsDmtus0NrI(?p6OXF`ayFnCix)@c zOX)He{J$2UTtIoZEDO_>Hk-o%8D9(TN=iKL-q=il>^`8>BYzOz?$=#G} z3q_sPZq+c9>5VRjAJX;k`Mv5HDw7VdhxK7}kX;yiubyKKK=HdI#%}10C8wl-GZE2* zp8oZICkD~2ZM27U#vDpLoX6f1`O0YhvtM<-znp*^hR9=91f`?J2yO$a1Ep1{e2Irw zwKC#z74U{;w=QG3!_;{_j_Hgl$Y&KFQf$wr-(WCdGwgRG*4!@`=zW?^WK6Xm3J=$o z%WBRVtd!WhRv^+6OH$l3cAjkTQ`y+0+uucmc*rEzF7j1qc?z>*)L^WVXBuFfW4Ek9 zS&yyGvFkp>yy)#Nh{M;DS7&Nhy>(cPR!o(N^@L%+x;HKA;D*Ek&AsWazV9qlR9c6) zUCJ|#AQRS^a)J zO+JXl!u$1JH47%*N#l3zX>!q-{1ii*$vbk{Rb4TpsVq5vw!d?>7Ij#+?Y8=(Cb=Xf zHeVzbW80yU%HQhYf6=ekB^M!};0`qR(1o9^t)%+fG7k8D9d zCO11PDz@9by*<$N(P>S2Mv~D}Hl{$x=UJLZgQenaE03dKM9t_od@m=ah+ph(J<&TB z&mY67>s!o`1lrO$F`%yryje?1mJ={$f1-O2ArB|-sm!~UOzH9&d3mj?@1rWfc?pkH zK2C7{%dUqexGC`e8A>;?td)vn>Lk?mVN1I<+tCwElJM>TG^U}ueJm|4GiKki<=0{u zaiY1zEHo~6f@p_rG~V;I6VHt`vGK^%tY+~rWzZL*E~3`#3S}Bz^$12V50_7ll^8=v zY@veBcM}Te24EYmq0a^IKK$)|>&iFU^iJlCQI%K2bWLvEQKN}`pr<=AT+8xjgtSk= zOO^+ITTHwvL3$+ zW1Hd5TQAn`^)7OTx>CyiYbIPvJteEwT?L2)WrllM@K(E zPJkca+k@cS0YqGSFu21k0;=Yr>3*;~uE1x&Q2fbeIYESzHs+U3Ei))e%ZPAxBHe z3~RcQVJffU1uv&A|CjK43et`jnL$d>M!Sb2xRv)N!JSQ;q&s1VVVosuiPfs^8~7c*&^?1r+ zFQF<&qq%V{&!p^=taafrUt$6B0}#5wqKWJ{mk7DYYcO(r{6+Pv638-) ziQdCKeE!|Tiy0A?Vq+pLeKM+1b{}rzq7;d6p%pExdm|EB(I-x+O7bQ+S!3+HB*+ju zrHYjPR6GJdc3oRtUI`>t8C*C1GrQCP)ussvYR8LOQH*)f;vz*jM4HnKd?gj-GHuIu z@a{FfF^SsjnfRzpj3kB!CkOa+50;&x8${S` za2k?i%)XF`H?S?<To5t*x-VUSHL+be76Qlf07-(s;r` z!fS7$+PUqrK$u!woY=Nm^TZuaj1R_Z9L9NJY^v)lu{@sLma?8?6nPDkdIC4*@xAxCtLCRjQBnk|(@qR=wrS`5p zz+;$Efhzt&etHSsZEW{PMg)1k^zE>EtiNUAh|M}$TEEuUfs+OCPE9JPz-=d+-~0Bz zQ0n97=I;TjAQGxp>NxcDnPTPK6Mx+eWQjL7m(;dBj44wHQS^jbDc$4gPb0;pQ!DLD z#B<^oeP@XHju^bdaS*?4E?1>G7&7Kjd7>7usLGd-a`7clgBL>HMs%wZeNNmKt_Vtz zqaI&OCq=^!aVGD!Z za~(3Cu_I|hC@}=jW2PpH3Qk=KBDO5mqn{8es_wa;=Fk#t6#B>lWZ?2}1Vhg6!VNC; zf}dt;amEN-G3P}z|AT33Jk8nw3qedscy@k{<2!rEa@i4B8~+4ugpHT=jhmvRl?((M zDT1z4`NFANu(1MhN&Z%R+vkI|W&%}szr-E}f7XAj@5#ibBVwtOQqupfZ218I3#9Z~ zwG$8!K(vBoj;Er&Pg7JTXb%o+to6|PV@+{j|1zM)YKnwTwu{SHh- zM_*qaOtn&#)W-w8!_zom);5vjHsI={ggM+PMEU-1R#uQ6xmwgU)CR>8*JsA74xdVV zC_Af=k+6gl9+f}xyes{Bkj-5xj;%LaL7(99uXc#xI!Nbt&0lIx871tlB{n?NceG3$ ztQ$trBHNJ*n)|=RlxdC}))U!zWZGS2%2dm7#@QC|SGBiH0y2l<1XQ)G$kLF=zK(6i z<8_aumFX%?&gW1hNAncie0U!V*({*?YDhTc$2slg;&KJL2Hg}-=wPv6xQ__lVXcAD zeKdi(`(e_tkPn0;tgfttdE}2IA_Lppo^gH7^*W&R@KIrDfD{{ftI_<~ImwYmaZ|$c zrK6nAlFkOiL=ZfJ><0r~R8h5q!$X?58Kr%`%FTD~+_W-4(*W>?bRYhYzQZ?wc?6M{ zRO;I^Ow5dojWphu@xa-s(|1z(v^y z6XW$RDyZobb&92k=F#6Wx@5RqUj@SXQ>h>Ado68kWAE^#^ca2*YM`BvVdqm?6r;#} z?fhfMdM>w5iYqk^5D&xpzQrsV+VyZfJ8i4On@n{+OZyK$sJTqT{w>gSD!=v%*i*JX z>{44{USAzrv)0#`T4mBJ&09QrdgfSljs05u`}&;MV`~r}k5=in_Uh2?Z>OMiKI}TE zcpIdz)It&qIhBK<&{tXJJ!hlDLJP~WNkS7;X!R3f1uN#*g6oDMM}KODK31y4quA&} zGQiFEiijC9n|`Q+sYtVyrJrF+y6=D*B63Z)d33@qi3c&cKZ;SXClc@PG) zJHz4XE0v33uzs4a=1hq;v&D-uz)$L#BLd)6%2@14Cnw(Wpj-vDGrQd9Wn<|8w37q= z=O9>q90Q+V=X^JJK5JfsE^y|Me@I?v8ql&UkcYw|Sv zw%7#to-WeOz}N7>RTYtqtGwW2zyp_V0Bh^E!2 zV8c;?g&b5dE4A&pIhB5TQx#WAULxQQf@FH=QqXMw=+UV$4^{l9cJZ*I^V zz)`TwTY!hepJIgdfUORGz@PyfC|W3sc`d6aai2Rs>VJUL{AE5m5wg;#S_H`@5zq0$ zi6&3|WSQfO!!q1|d3h*O8EYcVFk~3mWfLN5yRwRdSF~?0C9|r#h6v~H;W847x zG1S**Ol||2Z7V5x0hrg+aj)Pk2kLt6zc(Nb2|RXiQQM7NTznyk$b1g@arRrZEHUMi zA=v&Wdzij8o)UdddgR{EUp`$IXRi81AXRcMzM%?(s)r^lP7KnFihZl?nEnjX4A-5K znTqbn+XhS=1kT!~Ex;B>rX$khrf**iXz!YW+;TC4&$f!ep61uc2ho`6z7SC7giwE9{Zy>|5EX&_1XA9w@q?}5XWRyqZL;WWSfJ{4Rn zH&iKbfT!pJbq|kvf5Nj@0Tg9BK)(6U@pZD>`b%+BTaSPpVyHhVzALr?$kjC9h|aR) zL-Xa^U$x#otXZ0yQ=Xg^ zoNsjdIXl+@-#M87A(nEuLtxtirQAz%r%eW>L&m03t%Tj7QB?e^>?U3_oaVUMLp3%e zCxmR_)+-3Z_3f9krbqkg8=KuJH`-C%nh`|lGP0%htJHFp z+Ju{7iCo*$gwR@+ld@Jh?{Zhxa6xSxGQ?es!ti&S#M9HhV~3C4$=>!#=Y~-uaNzWb zR%Mo_aYY6E)5*KS(NE*zS!qY-QMJ$)*Pm)Q`$fqX$bB(?j_~k*y$rHz=;AwL?h65M z002n$^b+IJp)^rn!7J&vDqjFR(Q2I+ui2o$IIh=OE1$L- zf)x(pUB@Qa@A)Zt8o+rP5%j5WT}gqZkQU(|I2LO=vr`4o#9*K4#Ow+vl}J*cE&*s> zR8$1=K-Xoa3;rPit0YbI~kT6b8PX9pfBQCQ610y5lO17DOt;zT=yK|LpFhU0> zC1Km?e$!DvTwBB{{+yG-s9aX87AlbqE!pFrt)y<`L$8Ie^Yy1w%|V)I#DGnJJdG(s z89^D6@D-j2o(dV|NK*-j(IIF1w!lssp?FaB%1I4BrA!!71Gk<3eGCHm@hCy|%4-$n z%aWh9wY9hRZ)6HJIR_VnvMFU;_i{HeGS^DYvhnBP z6k-0dG8*r1vsJ(AJV7t4zXThSnA%)}RX($Ij@6i_xxb!jI369Eu^#9wxXGYUET$X` zQ-sKo?u^MITid5CqQCF$Ndi@xX3;O%VDGMxMx8)&lcmf{xg`x zpr}yV&4q1J=TW&$-@ElTNdmlAR;X%CkL>5?l&FYoZO(}-8B)a zG`+monn&Pa4ZL=pg27_D%_TOcQP`mc(HP*>`hbiXWDUjt&n?KNa-j z(G4iiNsc5Bl`2wnF%+?Xhe~v&@oAbWW^&dNYMiNd;;hoIAZ9dFJy>3g-q!psX$T-| zXJ-?K9(F?*=AaN4h;u&K1lGinPHx6vArRRMbbAQI%$lS1N}rS`P}Qef?~1htO;$AG zWvnIO?Q8lWOf-)2gqIX8QWCpp-KPzvSoF9J1jKK}T{&o1xa~z3brg!Es{O_C3ND?w z@d@YP<`zAu#L~PbJ}*>RB2j&!^lw$wLF}h5-~TU1tZL=Uv-dlJpv@k#r(5m^TX$EJ z=CltpsHw~=zb2WxpD#i2;eSvoQ9uRZyM;e(ZnmbThU7|oOc_0xJ9svL;x_v zn6U{z-&r75=GGW3IMEp8&5`btam>e6=t1*+M9=?KVb?o(t=F%a&g@iNwW)Op@>$m*P zF9s3fj4=bh_f!AaIP<;Y@3lMWM8!fGWwFTyZ@NdA6Lhhp~=ab9aM?+bONaI4D!bJg)*zOn!&Z(wSzs+lxEva!^&nw#$iPu0htH zDNP}NaPTY_4t6z6XkdnKoCPE`p_$jyF3^Y0;P=NxK582JF2?Q4w}yY~($ZKm=7Nj^ zwkbH+kn~wxnqa0bW)g*&Wn&>v+M{^Bpn&78^n`MDvalSUKcjXTNag~{1f^CD*zh-# zTbvPXr5LV8{{k8}ROy+mG}I-q(Iw25B5FhV&DDLz7Z@<<9wd?r>qPNw?tXibwKGBm zWcc5AnDRRl_ zUAuxUkt>}c%z3W1_Gl4M_xkieNGWZ?)hRb{qIcfjJ8fJ1+O&U@mG8fB{!Za3rE~q z<>ZRoxjU0C5a`xkrl>Ye7qOi)rekR$)Lg`y%Bwo__)Bm1opvPC&;1$hC>X>t!niAN z`ZwpTa;laeH-Me(26`{HJVgD;nE(g^re$xV2y2dLq<;^f{P$RZhRN~URR%+?N!!jo0n|+S@wuvP@&y?Lq!FOch870H@^ZMsQ=+A`m2j8EAL8`}GF!-*3Zj z_r&NkkJVOe7kj{-+0xZTRQ!B#-~D#wue@>Z_;%L)vY+7ycH~i`mlYE&k-IUtAi@X& z7;ds^1v^qPlyOgwj=r?>$t6g_%H9(fvn4fVHdf9jB&Vag=@s&j+g!wtN<#Yt7KOJP zkn^%cr`Q8%&uXAPBJL$%nPcChrlJk@XJYMb^ePq#3W`O=joQOPB$?5PsEKA`?H#Gt zVgzgPZ88nwpj-;-hm)aQF{~P!+9vp$Y&~YY#LFw>S=JR|J`@SV_v`q3@ocW1dr1)L z3j#~Ha6`s7a30B#Xxv$Mgv~;#2bsmw8T!Q z8b)|8&|N`Tt&^;bG-GT9iR^Uv0KIR)A}Uy(GfkBOm6}l6Zena4a8;DFzz=$p9jd)L zf*iYFnr2eoyK%ACrUOF`(*nC?t9x^teEb|wiPjC{vlRX$d-}opYi2}Qv|W!$JL=egaPG!HdqRyh zl?RJntQhZhaVa6T`hhRJv#t*jR5afY0^NSkh#?hM62$rc;z0y_Qa5Gs5>yq1LN>Qh#BD8Oy#! zsD~Ow5;~oSmILJxgm#+m$4V zCbmHlQh1tmJjOCuE94~qPzSOM03$3}s?4=lJb&Oi&@BCrrfUqYt83eFW3w?D8;xz- zwynlab{Bfq$+*$0myf?zBPh=0<^7 zI=3C6!I6cD>i6L*TutuiICoo0b|g{gon+m4Ky(7A53J9vEyGJ$sR^zB+II2hWDIg! z$74@Hb}=@|u8?;yQtJH#h8w*YQ?L@HRtV>G41az%YZsb0Z`4_AwSN38iDk8}b3tAt z>JOqQ$mHW%vqYdFzI#Nz&!sj9qx$*?c4pw{+9uhV)8Oq2`0Is&@!C-Mi?97T$8F|9 zD2s+q<>J2d`9Z_|FtrJ1H3Sxd-tifwLPRKa;tof6I|`~fr%*dok6nS&1a3uQr3pfA z5D3#8w7fofUEKcZhCRaG7A_^q7Ny0rb8XK3$*C(qA1J5D^xkVhBQY*0^*fuM#RKAg z=vqm)O!&2_S~oLHhq`akF2*&5VBV_2v$!M_BDycLmQNi( z!wVjB@cV5nFCTyMXwd)lAA5g2hzCrzTY-Nap)YU$4YDSY)dK+Q&(7zYUg1^NKgviN zuSNaF`ucx&V_Cov1yo7a()$H8!EK$LI*wK`=1RJz`$ z`Vd};4eM{8((Oblt}JIZk@7FB`~>fFSr0c$rRZC}?%{cYSq*roPSC3p#u2ANrA|B0 zUqqP6Qu7|W&?Ld}U#v%Dj~~5bm+tHj=JJ&-%by_D3&1v*Sp2ZY`MQ~8Ugh$9d^l_4 zJ}WHPsiU<^|i;y%-eS$!Tt>G3>U1dq*D2Z2J z5|j2$sGFDvhGk$`;?yG^s*|fgR3!F-B|+h4QHLi*R+6J>&G+3Eev0Lsulqs7{^x$l z*gMdJ@jhe_-w>TmAoy$UE;wslYj2>+G}b+e=v;TyHrkaJTbi41fHI8QKaz*^55(iS z5)-)Z+xb%TC|=5vr(XpG1s6*BVr^4(QI??d;9jQ_DOBl#m`6+L$da{gC=yiUjDz{H zSfz2lvvcf_MQ&kzifmu>n9j5O;nTt3 z`fKeY@8xnji_uEIOwk`7D)Z6rbi-~F*+bmp?Ic(6%unm<65D-GME0rP@+JC*-pcS# z)Gwmz6+zN)i}V6%gQ@UwGE;|>E3I=qlTKCb{8+-)yO=fVVswTl?b;Hj_`r@VzlQv! z;7^2UWebBuP|f6!-{S@BfrJZ_pGMk3En@H$4y^`eX4M2*IP41-Pl>sd_cZ)Y!e^v~ zq;l-J*vF?LVL683_jNwjB{9?g{s~Do(jiKPoB^lRoG`}1Zm>is(ocEGt29LKQDoNy zId#0C$D;)h31r-V@x8k9ImW^jnLa`N*T{i(xskZCQJMYoBpqvpZVsihc^6W2Ziibi zuZnUI+he|A*}?y`0LX8i?l=?c5pvcpO-^zT^!o83pT3^$ER7#1k`VSdnb(~Y6yx?$mbSA4D|Ghzr+{BVgR6s~RPswpHH&hv_qs^KAt_2^FSSD5(RUHLnmh8AJ$`!; zs!-!I0kWP_2SqO48OtXNQ~Z0ZfC+Nf!30@V{P_)DZ8kf*c&W>gmVEL0g<1CMRZLfn zUSd>uKA$bXXc~4O1?g!(S2qHt?hfU z@;OMTd#L_J=u0cOv*3iEA1&S1{)2Ii2swfN%>}YEUurc_(z4zuA;wG4=-MteeaN;* zjrv#1ST8uvti;78#vx6}lSr*sn%DJ9(D7%Eb&~l$bS!LU-)w#d-Iyzzo15$F=i+MU z0G&iC$aCucyGf95r~alOG8OMrE4;)1@6h?56^Km$!7sO;%=Lx~5F)umDFlOCKHE<& z<*RR8yNn%fOV4A@z;7#>aX9=${b7-;v{ZtPCy3}?szF*4MU;Qe9xOu8fED4C>t~q| zV>|K*Pz50K8QVBIg{C@mSHmM|4ff@vpQAB9h5^cXv%OX6JG5zkEF-~BZQ8d6MSR%( z$WNRMN03*%hn3H=P-Zx1x7m&FVMg~n^TtMhFdnY|;N?_k;70FXpswJOud8HgshgcD z?4#GZ|J^0Pe&rZKRqUbxzZ$7Tn4edWk|C3@$dg=G&Zbtg0Zt`=e7pjh*!K#$-A%A; z{QVkAe>WI1=1kJATRS>RBdiCPk&uu8-uh`SLM=_kdQP^YL)tNM2B5_jFUmqs7C-|9 zinA^61ReE3WK5us&l5QQXh6apx9k>RumGpO3qIf2T~EO+7I5A{e=qls&wH!z!2r{+ z1lM1V5DbpmA^mJ|U$sUDw&|{Xfk8k;BV1BBnCQF2x6idy55;^**p?OQE9e2=SgcM= zc2eRINPowUBNbdFMu~FZ@r8w2;4yO0`#Fe2KMo|FiGRDgyJG(UQ0+W~klI8HOwO{) zf$cc6lLSw9ksQ@de&!7YUd`ljLA2a5i$2kd!M`&JOZN-zYtn*Z6#kN} zrre-lR;6BwA7~B*KeU%{H#-0B$iHm}rA>)bFa7dCEL#105Zakt{noNlD16TbILh4{5E#g`avu6CiE=(5$l3 zbO#2O`XYrP?>FmQsB)Y`v!bMo;ERK2k^0 zCi(K&f<+nefe-lRq|Td%RM{!^loNSQ1g7xqA0#q9{6f$0_PYKH^Z6rrZzW8FP*w0DexV5qpLf zI{qnlaHwI6Yl;;1;?WBz7qjwqzwFkfn7d^78*gZKN_IxW1>lkY=iQDqrJ zs5I-7q2mdKqQ9liSYTk|LmNoE@0@-0mG0$uc)qva=l5-$qr)Sjc!)ewD#(AvkzODC zLSXvSaR`Skew2$~_92~L^(W>qaTaFuplutizZ|+QG zByyEbydrG|GOBV>YsH!C{e7xmkg&&IPeY_Z>+9>a0p%Mj8yid?#7CB_VHWEC{1X{HoacU5!~RMRWn3^%G$Ky}iA> zS`Fb@h-kc$9w>c6+^O1mrIIIzEpHCc@bWIW5P{r)ugiAXZ)W5*p=y=oR=Hh7m?bBiTV! zLW6LcT7D4j#!zKijNm=)6!)URHKX&Jsjmtugk%A8V9Wd=JhR{D*2>v=YJS6Hx*KV( z8&Jy_5QLcQ2T;>^fX8TTYH|gq-pzr$c~J7w@K94Y{l%bCo=fT#ss+_+JK4&2F#H6( zy*@H9Fcbv+ds3iRccQC(KCNk()rdDmKhOEBmd2^lM_?xFFJbUa*rviQwwa2vqniCc zp?|lw>O0T#V(o}U%-NbhvcoF()MAO&x^Q$Vk1`&qqyg5)hXOXGP3hL*`^|0 z_(yY;;*h+-Ae^kZS|(RPK0Y~PXo8C5!rh?bA4JbaPu&yL9YjgW`h7Jw;J!Z$Q&~SQ z6j!tUF$RLpbQG$R{61=)jE^r`cM=cTsQi{o;)ANzbd(a;uJ2vSs`W+aR84_Fxnqej zQAauYBBrfgWld7}4;uSyDui5)pjt+4gD`5W9k@$Q+T5Rj!bf9+`h;-hYQ55e&|R`233XBzZ^X0xdSqc{@T`&?MTHZ@u3l=vUbk9lE`Hp} zXjRSF-`IEsQW~QC$b{wIDTdmgh~axyzEUhM#2Xy^GB~BD@O7s79$tP9RNmFU$m@!Y z^krT9dH4fGYM$o+t0d(V%DlaG zxet{M{r}$QfuO=m1tk5zg=%L3Ep{*$TSLR(#0ybpSJC4EX(2jYWIBIMnyR>b{ zG~p^0SbcP~tgzstZ`TN4$BhfBk6Io+%Iato6q?L-k3w`~ND3MHa1244p22XMnpZ<8 z>oOb5IpNnv!j{k0@_)XQ2#%HV#HzPOEF_5acR9&HL{XLWRmQEpEon$(R)N<}mrl{* zXNdT62o?DIy1D_7?B(%;_v3W8pS(0*O)+%)59_tkYFUIf?Weqae0)BA!Y`creAXXJ zufMONVW5q8UvIQd6h{g)PoSuKXBf`wKy5Gvl3#|2JwmGlxkE+>^AW@#7=h|pFR$|T zO}Y;#A1M={YqqH{{9Ls%Ec`ePl#bsz=#Ch z62of8x+tQ-J*9dB9gx*XHlrjb*(pI%6rPRyhT#x34Y=3Xr%ly){n?Qkbu^Co=e}Pu z!h1$01a;DCbZUw3OwRo=U2#jW9IVHC>$Ph8qkAmWKbb8xI2`k)!m#!uZbl*4pa8ZU{9_w^HXU>!73NG2YBl&qS`XEjl6Yg5Q$YVs*m zr3gBvId+#T-A+4I4C{2~+eHV4vr8^f2sM^ogs8$lmQ-2v0W#Pj2Jd~I@7>6WxW`RB zNXTN#&mIJC22#yyy)>9-`Z~Mp_NF!Mo~dXmJmgsxn#uIMsX10yGvZ7>Id#EIkY(_h z?S(too#q$&l?8P(#hKX}-=Iq}0S!}CbQOY%KDzty(s8(nmEu#6E?n(0a|Y^nZrtu# zo=~+2jJiU6g}X`E3-%AcAAimqX_)`hG+2gY?M6Kteaps{Pa@sbsnO^QXVjfsQNVp= z7m4?>^Y+%(my>^QkcsVW_z1w5_;wdr@H}xygL8OmW8=e*FP{20ptABWplIjRps?wK zY`YN_C8!k{TVl>YTOI#?DK2KgfL)O@PX*S?Y#^d7)zB00kgFsE&))vOjl1T%dQHRI zXFRLrRl@{sQJkF3MAeGrl05%D%1J#py{>rxG65L@#EM1mJRx-_2%Oz9P`qd8)+V(# zy8DE2*ak<4jZ<+Md9%H;qWg0MHEu_gZjr_>sjOO(!l|bU38Pc2b>@uE4ZJ@6UjAHz zD0Bwb1)cEYRY#oNnkLtG$xULRg`BSBTNOt&!*Tg|zbgh13Z+yHzX$Aw5#JC79B{*w z;xy$gwAYqh^>^=SZX<6cs#{*zP(hx-BAXJZua1!M{uUrAvufq^eZJSJ1lK46#$^h% z0@8hO$o-#q&C>WK2(3ZpoQfS6TUcGOG!~0xXPFfg5~5b9fx3RaKl|!^8JTQOM&DRO zUnz5te}k$h?(7=cnrV}hi9Ccdk-ZfQ1yh4_r+n}IVHQXuMEhH?i`rs^hd#88VO|14 z31rn6zdbL30a#FZy^KyELDzkwOoSMG>|?A)OLbl-$;HViR=DV zqk8;rq5)~~kP|pym8}Of38}y*^vYLdc#~HJ$3MWs2MUcmfcD_>-^FERw*^E6`}rHr z-Kb8fgf+-E63xIw!fAo%tS7OZ2_1QT4H!jUA-z%ifQ^h@U+HH4tLK(O_BhLo_HA>M z1j>qA=}Z10A&;I&r5OF*K?<>X0OS%C71CvRchI!x{V;gvnvuP3U6@>a>B~H|jgFIO>qUPEccXn# zAt$q~8*5ODl@XVk?kyJJt{L;QYjOlLW%@JrU2cC=0oe?Nff*RG#s9%Foe+W`8n#1Puvq zgJmcOX@PF>R4vWlY-tN0lg1+l3l}~pd6dEd!-Q1kGK~g1`y{&kbG3AV0(v=dtMurX zhknE_<-@ROCo*>A?D+OrXt(JpXadYnklhlBDH4bt_*q6}J97ZTBxj;in`2Op?Bu4^ax* zosqrhm%)l*C*>F+3vh#3>ah(_D{M{h z2u~1uD=gT|^FaNQ>`HgW9FeI}+jXLjoUrWZCYfN9<&T@Lg#OzxU#E+4&CZw3b7a;k zrKNMTK2Cydk1Y0aTD^n=W^B-^%X$fFozS^KFHZX{>@1=h$?TZVB zQ@qr@KbP&ZHZ?7BLUoiVLSst?Hm%t`G(^UDsu1Vz9AQwSs7B`%z~`lW`hi&P##+67 zFXNCZ5!F{MAh2iz5E$~Mid1B>(;OWJE9jg}Dw2*KHt#pq7u(5d*9>!vDu`(&r_;rL zfbRDwZ9(z##`kxJpT2Wu%3qb&5>A`;_0{Xl9q26&8xzlK;p}p(ppXxr-lln#7>>JQ zVOODhiN!S4r^=2K`Geq9;0&9codv^QORgFmAU>s{)NQY_8n^r2f8>0(da72j#r?VW z0RdJsRA$eq;!hN%H}v5&qcT)h?)to7twBb{xhgcZ2dBCMo^ON?8w=b~)hK-T>C0|I z8zQcsg3tWs#>8kcb{%Zg*n}0d$(Na5uo%>;sZ6JdrGd*kC*eN}o%x%U8ns8SSKh#F zeq%@Vm59JcNYnUiy)JHES1ezRkX4XXBdCBH@0BsHnB*Q!R6DY5=(S;)cVR`wDAG-f zCD%7ETiLot^z}1W!uThUxB~5|RgaD5Rq)D2-D&w|{B{-u>O{`Z&nwk`m4eK(0OEDq zUJ%Xj`n=Tt(d7{Ezh!Fow45Tqt@od2Z{zZxMeQl`iQ-m*@Ks*&2V`P)vb=ABs*WeS zyTv5m!0Gz-rIX)h^0sgGD@)8aL~^ERVk+&}&9W^0LhK}c&CC4=eU3);Y&4U8IxT9Z zH9FDO;L_^|0+nj>+C>IZh62=-`&R!B@>18NCm+43GGNmFzFr2sO})KL)fG|ZePE*o zMX1-H(x>13XcCmYVduN+fMwCD^q*((x$s?z@bm5WX>yzY%4PZZ^nm6u=q>QkI~4ov zq58MpLSoU2F(+FLq;EranCO~WwSe2X(kbUN$G|av7D0T1D7gggk5(dI_7xbrc1ac0 zG@u_EE7cgwr`Vu{_}uD+W!754 zSh=uS5BYwO+k*qr^%kE@?^WIf)3sEvW642ctto{wqM$Vk@bSew7?o@(sBt2kR`T%h z$mG~~dfo%L8=yiN+o=`rN?~j*;S{eg?84(U+8y{ogC(I($WOyR6_<4p6CNJJGl}x< zc8m;A66xV@UaJ6xS|H})46dVN(L~Y2ym*?4K3qBD#mc;V&dI}pNs6V5}QTUWtn~#|+1{vn8L2WuK_=SKoIH%YL z-$lE)$B_Fnoc>OELQI`nZ7qWA>qLDM)>`r9DSC}+D&Hv+3y0_gE6dA|i}nomqd+AE zhLP_N^p8^N1#bVSeU$SIXX{$1OJD=U;8b#WrB)4O_~6l9JNIz{hNv(V+@W!Y*;vJp zf_K*=n8V=2+T?Juud|3<^}jW!IHFLGAMcObQ_Uk5sW;1J5KJ5J5_g_M+*bg!9HR5Mgx>Fl*P}8?gcXLb7?guM7z2wA)(nM3u_z;Mb&m*Jd z142*evj$kVDqC2;Gs>b}`u(`%CowD|K-UVoQuhM9&kT$H0h`T5(G`!JZ) zGoJD!?VsxQPvC12eI)&4s$i|jwPF%^&0=QQ1U5xDlkYwpEEsSl*N0AjonxS3aUNj`>W_I1_T(M44wBo<*kAum~eXd{DWaHgvB2K1h-hUe~m?I!VvK{EC>A z6r}UrtG$=Pem%s_uGKwj*pua6abOJ(qNB4lFYp@aIu&1z(f#sNgxey<9n*g*K5U?4 z&Snhd1C8;lu6?cn>u7mJ-JHT}gM}aGa%ym3;~Qy{T+STMESVO+Ic7Hjl`}tp&vT_7 zV*CAha8NP~$*SYNPQL@Fm$z1EJx2aLKE=-|3J7Hawd+?1Zqn}l{x6sbOItU)Wm;8U z$adMo!ct)X`|kwYwwI?9B%!`2KT|cDIu~Jq+Akp;57hLz4r*#Fk?wQu+6RhSYH;MMEi* zQ4+-Ue0X=~(cX_?ky>d_dLdPj6H-`IpT$)}FaE?F)iP_|MwGw^onsTWP5;Ak%eue> z%?F&vfX1+XrJtW5_thoo`+)sq*19QA&`V4QG<$3Y8X><6n>nKCW(fxN8mq)!0{RJAqC-YUoKPhwA~16i+_Lf{a81nZJNmQ|RX!dTiM z5;;`2s@9-MA;%9%t8CCI1HHxI&@l$qzs$JnG~Y}i@_?xr1_T)#TKZ2N#3S+xe|0XrwR5Dv!Wms!y$}FrJ#g1rz<^umBmSZsAjx_w)hdsJWFc! zGMlyJbFWVXART>z=H6DTR>I6C_W;vcKPR{JC=sZ3p#CE%?}x{6TD?q?Y){!mii23J z{qD4;){IJ$BI`t4{4~~#$$jx@twk*1j4Ub3Vbs}Dm8A9s%~!(XxyH3>m(%|eKWcgV zJwYbCV$C@eLxEShU<+!k3IDUBoZ3z&Ec)mT=06c!Wlb?PF@9rt$?j2G|w*9%wJpJdZ^lDl@rE)LWM8=apd`wfTr>oO1XT0?5N9aFT>CV3hVZm%IOk(XJ?7kYE5cCATKHuEj0PX&X zlLSPRj?+y{cZ`?e9NNH`RR}r#&Eld~GG{6oAfs>KZI&w|7OKoBJ8o7Z8liyAwYRHl zgkeG4%~?flr6!vAH577om9%^IfX`7TKB0mE|H~^$WRppJMt!?X*WI6kA)HG z4*kb@vBka-_y0KidOgMp%GU~Z?ax)sF*_@~Lziwbo_&dOwwCZ}COiYFNZ0)J7zwT9_Tdh3 z-&R-k)NE3MR3*FFt-Ul+=E?u31>i!8Z2b={<$&>QlW@6x#!}=O*$b!k4li!OsRb$Q z_3veIYlDhA21sWAL?z9z1mf>a7n5+3&Xk-5Q+{!e=hsb5LpfinlE8_^+2F--4;IIm z1bqh(9#j$mXQLaigbNPMB$Afkfn~CdtS8#cYA7fZJSD+FYh|AZv4bm4C(_;B#}+52 z>-EYT)P|WE-2^|RuZhNYFpJVC=QA=gO0cH0X8-evMs3e;pu)XZe!EkSU>L*!lh)gtC50)@ zql#x!qD^>WmrGMCSQByf669X^pF&Q{X@`ig3lRi|Vf2wY)dJzd}Ws98LT^)eGp`+r8 z@${U2ci}z%7l*T~9r@hP%d5S=pR}*3yE|K!(=-~Y!mEu7wcUupx0Qru9R%gd6(cG zVbxSUov%cc9w}5oyLv0{u?ev?OI6e}?H~rRa@va<1Rd3D6A$LP4Y_?{OUH=l*2~*Q z4iLkC!J3d%6Ls+x)p^&=uBXx4;~B{)@U=|3TfErRWhB;vL83s{lsJd^_`4k4iS6K64+LR68?i)T|7-(#LCSjr_$D#EP;0D6gNttZJ41f zls^4jAH(`^zVGbjHrJ!iU2nTCkRb&pX5#>n@BDdR)ymxi-fGNVY9ahLehrXF-`a`q zBXw10o%v;_ESa5rHpVur!hEE-d*^ue1yeOB>XYPTdvHEy8n2}%LR;jz%1Db~Oec^g zmw>yc{S(OgH^n$bsg`(+ku&rz<*wt*P8Rb=#72NBQ;Q|r?yFDZ6%ZKTZF>)^yv08k zhDz2;o)xAzG)0eC`&68P`012$)Rd~V(fn6P>uxTY7H0C0g^t^6t*=23KHElHk7fx8 zvw6Uw!D9}|~jzngYr2Cm~{(Tda@Ritd-edx{73<^I|TvBII}yMLe3% zI7r*j!D6Jv#A{SP>9d>IbJ}+tjyuUA`1B!TB*%&sza7)I2h{qi?hmP3#V~cLBK@JH4!!QKCKS32!HTuWtlMWVTb*mJqiX zmhS-63SOrOB$`J$y1KUM4B9+vj?eq6KL4&h3j@6nCsf-uJ^dn>7&kXJcXoEbcFkU= z*H{B%5p@_mT)^|XC(XuqpYwL#|8I#U@EXb7MP=b16J#xO#8@&~Ojgu9;|+JAkEy9? zP|zE|K-(0HVrSE{Bdn9WNG;pHNQiV4PTI%`h9H?lA>bh7td+}281DQl`P`6Ah(bUI zi5hCZB@G*$pP%3N>3SeovgP(u%|IMI^2x+V`P?EYhj{Yv5(Dlzteo(i;yvH#SB~uveor)86 z?l$B3=RIhI;|7t$!T5b(@vF)N^ul`~6%J7}W0=s8nUiX=CEs6vOa2<{6bxWcWM;t0hmWt;W_jm=~fSHD$%anNaNS(Oyh~*k#<=wnQA3`j^8xXl-3v5d7FD{sO zHtI>}Aey^|73scmCjwtCm0q+^V?E|S#Y=`6i1+R6?lG%9J%ZvH^87L~suc2|Z;9J! z{m&lh+aFLY%7^efgH3m7fwcUdlZopE+3`m1hkQa&!X3jx58bmmAIfzeg->sf>%2Q= z_}HTElK2{ym9&amc-@D<1Z~*fN^U*ahUM?|@uCCO7d(tRp~JWHoUAtcZjlKXFZ6A! zPco5O*q9t2C3wAD2`FRJckBo4m?8AuQmd{8Ym-#0tUU`%=FL+X9LK4|uyN4~%iZKY z|GrEtN+(?3_+QvqR1$UOTcd=3qq8wao-PQrTT;y zHzvbbWXo+-5EYWc2~gxL$HRS7yoC1~^!_kh2DdOg0H8pxqGCnUb%5lpic2lolcC5K zIm=1AH*@Ih(3Rz$jh0E0=Zi-G5h$ZAO&9$U!V?9^JN2-%v1?}skIVrLc=LNt^6!9U zM$y8##jSYNJRoAnmp84O1Ime7hX{kt2rfYJdkj%rOwccPA0Gm=ST8Q#E{6dk^apJb z?UX3hiy>uO!4i;_%&Ncftbe3nA8nrv+w1n&nrcK_s5=G0GYdERkzS($F_$q8Dc|H;Sl=-b-qB(T-&%ne8rO^@CihY0qzQ`|5!YiwDfuh|c4Y1` z6&_DWGM2e4A#w(T^j`6A$xxK;=U&G!lZ&1-WEJn^Qs2`?*8h6jfzbN*yi_Wz>;fW! zn@^o}!3y!o1}u565`;>TUVbdRgJ1QRFqKFXY9kI4R9{aww;Qmc0XLu1GcpNZ0ndh1 z$z85tYhauSJg+=s-Eqwm$O)_d9rg|l?8iCEz@3a4eGh0PKR>^$@1YEny|+QWzH%d$ zK0dtg&H(|h0P+MqOFrOBfCCW3709KW>aY>ak!{RVEo_tt1f56>AlP!fZ`S_W+4<)O z>A%Dx5UUHE8`N=sox@BIwmVzIz9K7$_$Z52Yx0i)>pC|#_gX};3KvNek*RS{1+z1k z*31p^w~#L1nR zv|VH##jek1K9~h|8VBMq!h@c9F5`lJO0BhtQL++_qxsST7}NDAtxf^4ys-8e15?I5 z+XF;By%$}VY?YF95eh|Bq=;8oVcJtZzZlKxk^52VE@fVM8^cJ+`w#kf*vYf%3$-I! z(Ghb~*ha}g7>213aKlh>677j|1bV@(rGdZY^CC+hqg?GZ)RGI-+5;S#DCDq*K11uI zXtmgnO33+#=Y496kM?^w*F~j8CqvL1E{R4Yadw0F$^+yp1pyDbKabLvGU;Sn{}DQn z6QtvE=Bd>`5i#=)0e7_^56>r{M*tH62uNybYPtr|z93l-i|NhT&zv`sY!jbd4}zm? z2|5!e5>JD6j8B{*)ZqrDd&fq@CqeJ|>vB>cxXx9S2V>;w&-tkr+fZzM^fZ(mypb1SYl7%xs%y7W`TmIgh$Y z`@=v!rv0gMn9J}c0~8gOF|PX}i%hjS1#wlwNs`+dLP+@uPV0l-VWN*za?FAklE7fl zN~eh7yDSju-KAo@8l+stQR)BP62par&tm8Uqowa85{W) zWE)w8`6cOL{1q8^NoMBFyqEZ)x<4~Zh*$n(K#UyE3q|I%Ek}eqETp+_HMMcR&ywX( zr_k}IC`;5QwYgJwfjc80xm7frLqt_?_!IE6gDD-Z4FalJDeD0I@8^x?tbk8;T1m!w zr-x^NJ_VIO^F*{zShM({uDzE4S_9>iyNt9NrRJegPFkv+;$iXti7p9vlUs=ImS&0kT&$pf#EXa@Dl|ouex~7Kr&w zY30P_(yPA2p$XFYauyd%2ML;`h>1;6yvvx1u6zl;3{I%?QI}H|a6Lpqr=+J{yRO9f7dQHSYO@ zaY1>=MkS#oPT;lZP?;-I`$Cr`%iG6N{V1>w3KCq+&G&%Z4Gbl%r}T25OyS>&a!~d6 z#u*d$z)5gEs-KKzBZ%_v_a2^}o`O>nTwrie0tJy>P4vEwdws%Wd6kiCws2FG3!>E{ z_kU50pneo=EiL3_XdnX>FzTM89*1w65Lz_kyB|>uO7xH@JtKE_MqPo_C9AM)`IDJG zf%Pz#0+qdsrI$s>Zrmo=+kwNAFJxFKc^cqIc?iN6sx=$&9Mtfy)1{LLQ9Ox%!fvSd zF}MulAV263>tk(9SBeT>+}&}iY=%n&tA+$*Yn z^Rs7(VuxE{BP~zXtY?ZexztQ+N>HVZ7t>(boLJr5tQTXoME6bdb%t&!^u(~DL<7m} zbb@g6*oh_ur4?*696U-`+hZpJeh+bb%yr)uS#n~raqKiy?!aLQEM*{wx%3=E;2CTM zPOtZgT^B~3(ew2s$Qrmuz^4l?w3)!4u0Z*p;>ptoi#5KZykStVqDPt2t$!Dgumv{vc!yigK*juh@8G zOZ&~a4tXOJs`rD#YbG=6k3HJdsac7?{FY=iJ+y3-p_Pe+hq%SI!v*v?DNS6`Py zW`*sOY_Wy)vf^`H(4#XYLVvlaY`yHB#m;0Ck&IRv@QBFRvV7?{YkLg#nc#mFBUa{d z5LCFW6Xn$uVJ^w$+d_fdNUrP2-_oQ3t-Za9*S+r!cUXnpabD#tn@qOsEWtB4K~66O zpO70OqKJY~AzyPy`Pa`vM%tHlkvY^=L-m2G1_ zyGE95QjX-v6mh6W9grU!7 zp|V;SlmCa2RVP2@nov^9tobzXOCUuL}u;hMCSO%{eTIK8_4r@lQ7JH+R<0ur* z#I|5i(d6d}n96j7!`9iK5#$Xc*B_vhicr62*d#rP*Ee}1(l7hmLJNbK&u{P%=t>-C z;X|vRAC-&bWzl!BvG3DfwN^gjzh^jFZLA0lH5Z=szyuT1w(O$UFw zUmT3(A&-N1R+jsk?%9&RFR&*<)>C@(-8nS2p(gn}_kY*3Hj`IxKrtH~IVtjK&rWWNtF8dy=tNc{tra4@#+?u61iZT36?6)ft*7S6X*ijHl=m#S^? zDM-7*uf=cWL=u-HvXdto73Xi07~v72($Hy2O9IuOH zGfqzac6=2a)tAbX!%AH_)U9>}+TPMmqj`#)cEzUz`{|RJNZ%y37{>EotBc_q8z4L% z?mM>Y$bUpo&J`73*yT$x{zZQ&hEHA$@NA#2q=mlZ%j#5prdODPk8S#wRdYcdz3a=fFu3g0n?Po>ZE~njLt|B(!GA6o zjP1m(HTIDB_O5xZ`j9R2RuqzzwY8G5nK}ss&auJYHdfxc zn*7OFwfEIlNoF%pUw9Q!&)P9P|3(QqGTIu-rOs`z9J`a^M1LM+MO}-gXE4y!Jz*L} zhs3j5A5sJ}Mjz_4=VWQrx8<{D~lq)NIrRvXnwIsgsR_VkBK80ZU8kI<1X(+l2 zt^)ls_%T&7H9M+Y$ByT*P^OZE78XbaIGtcZ7whN$Hd6NAqg`aDUQr>L$)9PxihraV z`F~-M2`TP2Mq`zZdrfuK(=iWe)6pPi@oFEcu`-If0>H8CMlDylu;9+q)6-mqGRmAN zA4&qcpDRoJpf z91JP1m3t>K+Bv^hQZDTASF6lu`gL3MC0em6^|}4DfH6=NUrN2mJo#L3@6VOa zYden|b^f(E?)i#p*d+X5v$lsJtYuO4G6`_pz~D(!t)twguhr@c_Mrc2P!^y%)AY?z zEI4~ZPn`;E*Nd>rQW+gJ91?i-6F2a}4YS}fRqK_pR$5}`cuHG4&fq5 zNT4Ws*1y?7QPEb3vCi&RoHnvd;T7bQI|P!P#l`g8EH@fMJKPcxN3gabm?p0+h}reY zu$7u$EyceNXQ`YU$5$oT2CUEawusX@8&GzQPFHbYl`Dp1*1~P#;`Ap-vsqeKp{v}C zq zu{IaHA%kQ~Qq&mW$*VHM^2gQUBJ@8+>0*~&55n^Q{x_d~P$ijUv-%@qufPj%9N_TA zXo{t@AyFOCMCFN3H-3tf%}aIn=2gXE`n90lE$2gY<1#Y$@?WTgFt7@v2KBM1_<4GA zX_X`~I{M~U-iSz?mma9y(-(jU3!o)&+H-AX<%W9%gC}?yyB2Kh_AG$!m#mgsOPcmI zn<<=m9uz11$8wu9a>tYg~j8ADPsk z%S%D|0Q+orl>0#~ZXeGV0^y1C+zsY6?v>9{s=KW7oBMzc7iKS1ZDkYk_i3Ncn`gkX zH`6o{mL6|aKXQ`k!0^hpBx!D|B1EE#7Ab|8kyIFMccYl_ncmNFSh7fc$V6^>618sB z%{cI>3vxFNxkl~gq&Q_=E(H5Wor z&PB&Itt3>M9&aaVL7m{eh-MG7e7C}d%%_Hgag&kLe_dA&Wox^GF=f41^1uI<3nNP8MhK^< zR)@JzHOA&&{8YU2F^}GnIyf0)I=oi4(e+*JpzETd7?V&Ywz>!0UB|9pVqzy`y>QyF z$5Qp%8Mb|Zicf@-I+gvVIMe5io%2C#mk|+s3Cnxh54KVqRo)4vR_t+3BYDS?&KVV` z+=5~O-0FETpYsK^)IZ9!E_Ht=KMRz@W988hCXW#;RH#QUd(4K6ExBdmSb-#x(T#8P>Z514pFabcRO-v$C&->MPfjgDA#i@XMYF1T$Z3*!TQZ8MT8mTuz^8YzVkpW~@SO@aD%9(dOO~$Rf8s&A>vX8w zT~Go8rk`K%zbMW_JXuBeu}tVWF6R&IZ;;$m!^v3#y+7K#ll9jzE|<%%b~B2Uo@Ag? zq9yd8ZV_&dXkSa5;2q84A7(f)iBLMUJXK;s%f;i}!%`MNP-Nisscm8Z_4Q20Y2KYxt}wvQN0+#-&=x9PRZSL)4B zyMG!Fj7G|70={1f=t2}b3ru}l9tAKS0lNdD?O#B(*O6_tIRl)EKA=%R`1!|a6Z_(h z8!0c5x%xOVG4(fkhm?*S<)g*pPbf3_w~fFcY6YCa*8`{jV)gQ0$(vF+oHpDm zmQhu9ZP%tt=|(_6y1TojJEc3NyGy#ebJHEtN=iz%bR#JtlJB~|Z#?|cG1TFPz1OwQ zdCqxE;oosC${ohE-IQ&l%Z6Z+Vgm5f&-K9d@#|aQH!P6n^eZ|e!}Gw<*}C`CtP7|p ze)_LTqMCK;2rT{vGbKjBlHbuZgl+Pb6bi4?IZw{Q94!CYvOn0Z&4GRR9UfJzK2@aWL1P^Dy<4B| z$tmF|-^%mK`BhuEo|{{DnVT-mfCzUCzi6~E{y#4O`Uu`)TvoGOiS~alW@Y6+Lt582+D?OWwVdxMJrqxNQfPQq zgy22!TP8R07Om%H*EIU{$gg}Q3d|VBKU~d73H8fXq!ttSD=1X4`X7e^6^LPWUkuj z780IiP_gKNOckQW#pu02x{#=Y{sEc3M3S0vu`wU6{QQzd>m?qlhm&i%Zdrp30=cYO z`6v&|WFUBjw>#fn5*ng3)bR%G-ER`pyP_49F^F(?3z-g$KvkvkWAvixoaHf`jlw!% znY8D{22%kWUO5Sh8z}SU-BT*{Q(@T^$tBfhjWqat$<@RWpN;p6*tiY@?Wp5W#2dVjJSQSk*n2lNbb^Tn$ zn2SbWEe?%eCWwup*?YqV5<1-e*G6u-F1G;A(n{z2B(>MN^I8&I`uY?_O&m=@WY~v=>rkA~{IX zt1SB4h+(ckYg|FjZb^wLHuz|L3`N^a1Mm5WRH{+pEf$ydu)y0XIWx(jyT z`$hwrk8}DlZ>eF4B~%32%EuM=gc2V>VxTOKTF*_9$laD-d5OLA+ z11OLIc44h%`tUb#+3O|UTY8vH+eb)o2jv0zWoKi)ooVpm0e4#Q15wXhoTevc%@e;QTrN( zyra??EvtAvkyUZ&a-+vL%H@s&J|6dT_#?@BYDeuyQA1VLl|SmIyaBc$uM%t?NVWrq2OATcC2Iy;;&xxm^LiMpRv6(r3yUmC~&G zP?MAl0hEKCrS~gn+T^Sdsgr%^v*}0EWi1{V%AiiQ>Cu>(zmX{==8XN2s2*c2np12P zrJ}AE)6)u?Il<=@_{|weVD(594s)?8I)XM|?!JmVu1wKKOYs<`s9fG|aHL{bjmu{+iD%s2PV6Z7

    CgW7*_i`bJ8hlv%RWnB7R#HQ0Kkm~{v_>I*M%>C-FuX}oItN3_!4E9qnE${ z!gEycf`0c-;C|}J0)N$ZaRFys z=}&~Sk-mRWbu#)m4STJAP`cD1;rG4ed?mqXYetMd1$>IhOJ2Yf*Gn6Ou%1viLQKes zj41kkBEmEc$c6ZnH+y`}l|Mk?@ssC3Uu))Vg=-TwKHp)ZLPr6g#M@GsMlAKpP(wlo zPWZ=8E@@&*hWU#atfd?7gaz0mk*r;N2!(jDab~Lp6LT)7{iA& zGV*2u-Cpc(dyBRDKoHJa%w)zW^N<8SYjZr-)Q8T4R{N!cKqsf^iN7IdvvBTLO2>f9 z>FMDy<_6;poL2XRy6EExI`1bC4pHE2?%0yl#TQt2in~Cwow#z!p6vcVK%)svXZS!Y zTt3uFVLVfu!p;L5u}v-HY*_~-OCKV+PV-gY=V}buwT=R+hy2e1py1-{Qg_1))fnfG zlc!F1%s40NBtWcvzD{5D`-krv3Z{dAX}%Rw2$OJV5yk2;@7W#RoodNzlzA|p_|d?$ z<}n=9xaJ`g${TT=)eIfjdq)fWomGrYCG?ZTHj_MOxP*1Q3CK!>4feCY5Sc>{(ndqM zN-f^v;JNODhh;xkr;?AT%5oJx`5ks|9?w`QN3BAn)Zkt5YG17%Ogi+pai<&A@6(mo zv2CjiCD3?zYn~g|}ynyVc9G`CIA-5m7@uHTm| za*ljeO=9N9EqyWFB2E_C$miVy#_C~sGt2Z;$vZcic~OvT}rkUe2X)#T+uW( z$^Q-$Wy}S78n*>m^r-E;7egQnryxI{l$dz0jYAUGn?36D%l_1t`i{tN%`;t_9j=D} z(&=+g;@)7HuOsv;iB+>Y8ojGUB(=w`^R>@GlH$y z9lM3=Ov$sLvvj$W2Jr_O`YWzj_jtv1k0pgfFMB8u_2aczKV5_;6_vLu?}O?i+z8xoc!#Kc?^t0=m-7F|8j=FXr0cI zWuvaj|CmU7KW}_)|M%LVINI%6luKr0Hp-jOyK+eLLgce>RIoi{(f%O_{xa)9MHcgw zm=i>(iT68>s(+zR-T_e*{k<^GNov#rnc$&XRDdGxp_6NgC^HHdNqO%O!~NB+{lW0Cbk6Pi_b!||K^U~}+`GL46K+XZtgr>l6*1V42(UR<@XL;`Y|9u7iV|ldzJ!)u8?OBT2aNanZFV6%z zNxY`snKn?m`7rU#ij4In(kof^EH^k)Ef!eWmT_?XcJ!$`>6SR&2Qna8&evt~6z{P&0=3UhBU>~_ER0`Q& z4*vE>>D!?kp3jEp7AHo`3^m3**GnHzB#U^0V{5V`He!{e_zxtkk zSn3+{!EHUKUxn0;`e9}!iOyZavN17C=KLF<(P`eJV5`(F@uc)$1}dEVR+$A9E4!QN z<7esk%n~6vmNFDq-VC3CaaugXL9W#-x{74_`oUR4LX7`|yvxG-_u=F2U?Ql`!VFzi}P+xo0^E{Y_g<1@4n z3Dt5|?ubGACo)5YOy$JZ@-q%TjD&J&GBGhNK$5!XJ#z67f>l2z!ZUMp09g&tnwnMV zKZ=cwlqGoqn3Di6Z^c$UzVuh3e$_*A<=~ztlZK0db?iTZx~6T_i4=K-0fhkp^_!{} zc$vhAFFFPWd4CX*`S5Lj?;)NjW+?l5c?|CHbC^bb0EOhX1Et$7BTVtkX@qV*BmsgM zJW{koZxY|Zn^{DbqC|veK>x{cts;@Ll(#ZvTo10dwOHlUdl{6vJ-&3KJ62nw(JeZ8XX5#4=%U9yejKykc6^lD? zqZ#b^<7RuXh8w6agGgVuiN`R?nx{3Al4tHi)`Gd$o2Ahwa4zTN=Wlel(!><`THBU; zv;o29-Ns68AQLT2m6DQVNvB-ho8u%;BgAHvbh!md2G(ZupsscQ*0(8JHR}~~U z^H~X>)2z?Rx7Eh2Su)DV-OOm8bUv+zPHva#F;rN{STUea_U&`YW>m!W$qXWBBOSD! z;A`u=(hb2gA0xP9xlKeGqBKJ02Z(n`9T%e1O3O9bTeTQ#c5ZM^@+9i~n&@ryGp%P`Jmbn~^74`p%{h!QPtPo9($Be%HSadRsoWR_UcllnXx6$6e6?tc z+uKDyc?pgCg1K&t`@$Qga@U)t0bYO`F?)#Ttd6!6gS^E~ZT4U&fAM)2v{uxBn z>+Dt8c5AeAP9}Y0Rc9#*veSMgw z4B9(|Gcif@yYX4~q{L)2jHIaYng|)MW`1t^9NGU~Dy7(i1KmV+o?An9oh7MgC1icL zLqvHaF+abTjc`2yZ!BGXeRcHj@{`DEpZ9toklq<+PS2`-O|R2pMSmH+r4zpUHJ@nE zd#NPOrKx@E0n<5oAOJSVLPF1bDas+`Z>(HTs6!TLufWU&N2h2uGgVKEg(??vlR@8F z-Qe9f(Mk$Oau1zNj+9h^tW4>poTM?1l`F-V#uTlg43^e81lsOCi-`i<7N07ZUC&7c zi$2FY@ff)xF z)~s+ck`{6JVm2N-|8N#W;8sft{f1yyj46omAWbxG$R#^Z5)CofoQ8D+O2tqNe&aH@ z0D|w*x97XH%9fAJPm+cO%r!i5N~4yQ zMh1!S#_HCsM9A=N3Uvx!HZWs|OBZwqZr^@{<}R+{_9F4`opwV>=9CsSMyCmxRGnLr zuTCkM-T|)+1iV?~M!lj5w_t{qGY%SXQ5IZ@RU(|nf=!=&&ZH&tZvEQ#Wd$g#&6;`yXh$uoh!t!gimoHGWk_>}fYfFZ(oc=h%aV(nm zbOr8PY2>$vtkhiGt%~8(R0%D!KBZ`e4)3wc*ETlL`nkggpnr=h=}@o1$FRg!K3G4P zzh@^LYtCq}FJpj;`}m@^UHkbPAm*|J{u>9rM!o4yi(IpWax@(K&hGAs%dv!5y=qaV8?%{cwef7#q;nEeRf^`y?b!o8}%&|j{lsf^Z^DZ_#YvK?mDO3EJ+vV z8}&}y*z_?=*Il!}5v(K~SsT*of-&Mm`ipuRvd4pa?|?f6b|~iGdM7JH_lU+xtZn)b1aT&cPw#BJALu?OSXOE` z9?e0Hen^VVrdMCsD~WF>(-c9SPb~M{C+ZRUx8lDm+SG6TVUk%JzjD=EeRf3Xg$8Nx zMAu{){E8X=DO#SGm5+Wx>{CY#G+jF1Q=O5j#3jSJsc{9~DnrW8N9OQ87&1N`{34UD zQraR?qBJ^!15J&MsvrH7zOlO{pZfF_qZB2K1UUY7ZzPsw)VDHP(*Yxwjb-jPbBa5 z<&RvS#7{jVa z^YW$e5k|}hpUQj!&_RmZAcjMeTJzSLAfwD}f|g3%!N|zyNBSRw+<1p<{vCq_2A5lZ z%NNeY?h&ix>8Kg=ux85q$jQbJC0PrvApmLpc_1_%dGaHed7$hr9c=B*>#3wKE(66A&Pgz=w9y zCqIrHTq!#3EQs=?)el_*(fEYLJ%=bb1J*YH!^!d$vM*^$e)uSWiQoxg&df=KXC}+dhSYKdJn=EuEDXdswz^7TN z?+S?x!k;P+D%iTT3Pu{@wnm z6k!FgPltIe3@}c5IukD?-xtuh8;Uto>L?aGY<+~J8CFtoXb9x+>WDftt8L0sK@(3C z&VZ<(i4{hE5TD05NO*cu2fFnK{-D5lcQ#k*Dv(G17 z%JNgE$cQsP+oOr~8`r|;6a>j9q(0Q{+#3NoB5ZFd$IA2HjuDkHf{)gTdswmkrFy7rQ#E)>RGhAQ%c#oZe_W!LNARd%}9@$kzZ=3^)nYG z%5ZcIrRo}piMWUEDqUks7iGNDh>>7vQZKBg+g*y8K(3kJ6cDlYeCW^vHTIYDW2l** zZA3m7apw8k1=^(|T}cVau5d>l( z+6F=UxRJmA^xLVLA^A*~gQm#N;!^Rr^WaDpRh@@EH$46&*KKsa#CP!9K&He>V&mS( zf|>YlTHR?G)|aNTYPAp>DVqMCmyPbSrPC`@#J^3_8%KS?chN4Xc?$yr3P@iOVH85tSYFyQ#k>QR1c!*s$F`NDHLlAP!y+A3Dxc?SM^|2FY z(Ir(%D_EU?n1k_c#N7C=$}X@#0XIuwOpMo4nYH!x9`O6iEio!(_g%nB1j&;nAeG(* znLQj8E;*?D(nr1B+S+=3DtJwiRsgM=ZwXanSs+%6VKaz-s;k*|Kuy2wSbzOKvT^E)`jfn-v<`pV-aHEh?nG>Q0 zN1K@|ephyUc!u)8NHEAAQ$mWH1V*@ayYq$;vo8#Abd$*&UtX=%kdi&9`G9 zBn+f#?z4Hu5)>DIFAqz0w_nx}-zqv2bY9jxaK!I~MR&$rmZv5J(-#J7h0;=D;c=z4 zwsOq|V4sO+P6{QdEzmg9^Po^JbjNyh+0Xm_%?q!Gs1YKYSd7)GFyy#EpI!n47^z4A zacm+<4t68XHSGhr)g-rac*P1Te-}Inx`P|;8jSLrfeOP3=#^oLjF4L>@F;>eo_&Ah z4flOGbjwh*GV;SMQ`IiEg*^1I#u2Fk7Xyq<-j)wL)Y$U`5R8I-U{k>u+H?pK|Bl4a zV)`_M!~CNv5LsybOY+zmTFpv7eGLdE$`>~72>=a#n&jCmeY?zlkaXLqRXk2Ng@bTt zJT@XXnR;c}b$+^$c6JxSWo9^)qomdXoygRKwL|>7I>J6!P#3$mb#sbP6GOPiB|PCW z<5d17V5b-E-!F{xqcTN z-v-a2%@Un*nT5a^1FFm1Miedw!VTH5{%`g~~2x z->pSNM5GJ^s!?^1>jxzb=G{8^g{zP8+qHxD@NP=hAJnle9{_eZC8+%K@45xX2$MPx z4GPWnflq!pFYwXU*3vp5oG6_a`tlwJNp_%jsb-_hm!Z2-r@~(RpvNMuk;UTtw$a5lg{T;;IA_ zvDF`!01os$jfnk@FFz07(??p4IvE+dqY4ZDEKi^FHig0@)3-IZ^hY-4ORz*{pN*KF z6TF(g(>nWef^?p2El?6Wy1E!@==nY;tm2UD3^s5a^StgWpOWUi5&w>ssgFQe^;w?h z%iLO1*tMLh57sXoR}rT@fdLbVXVL00i{H#yMIwVg1b19uySUldr!0Hv#r@6e>~Z+$ z?d2%;*{49FYlbA?R6s@mguh(W}g?e_)k1>t`!jPfWa#>Yw!=k_xg(5aEL4Skw zZmLp_t)cik$ioAJ)$A|m3SFL0;<`{-;^gU0RD89+oZk`MC^!u?pkhYqLzWMjg=Ma<1so=)WSb*gIc0a_TK(v5}u|z<~L_O{|w^PSxE}JOZ^@~e}FVsm7 zkAoPs0`yI55h6MU>tesX-RsWrV|PzIz**mUe>>9TyvxhUUj~g&iTRVN3z|NugVnGQ zMe>UDIhQ_95?$kAzrQ_q%yM6>SZ;YTHSi2>n7cy8H+sWbI5TwZKz48k(KdqqFE%;6 zH0|Nx=55vi+!aAff@*z!ucphAl)B&K?Lcj(H6g7Z5(iahkT@fGbjTzl6bELH896Oy z;>h3JYY!(UsHB=-`cBEgdDn}L9ad~M51zW-fk0B|U-7SeA)reOP&l$8q(~}=IvueK z8J@rVugV#byQ_^*BPs1epLpV^ zf=%#$XrQ-Q2_gM-9@C~}_$t2uj*c(2aZXD5v_4noyRB?`6ZZ%th5S5=l;_?2od#kB zevb`OG{^m261kb6ttvz_y{Nmp`)TU+pU4z)Ukcg7Hhmo>cVhxyCc{kp zHWsC5QHr=343S#*#zK$B*(z9}Rhs=li4ygOr#)7Hg?N!aXcAxq!rqwp9OT;QA$yIi zQ=Aql$qzSLSxZ`M`kF)-31OtMppJF%E+Ayzi<7Pl0!$WFPu01S;-)su7klv zn9=i8^hNATUrRp+J;K;D_9-i`+9o2}@t6HN;fJG=7HxJq2o=uX-?A)pvl~=pey=aj z;1&N^{<@_UI1ii}#RuQov`@xV?K zQ8gxc!UbuBzh-Lj_DTw_)Qz~*RKs5M0+aM5!br6xdbkIi=xJx&Z6iNS;;B2jyK@l` z)mH)=VCQ2-$R=7!IYApU@~nZa>h>TR(Nhi55^%sNEazyFhdV}J0pI^cz~3&id{8+^ zqi_w{ML^wf(V~`Rq(aqbB}Fs zV+6Rk0;$hd6Tk!IG3Xzs)T$$;H2An8%Ku5hp#B0{Ex7m&0nic(f+TLX_`SpcVjxo3 zgX+>9k68U%Bx)kNPNlBJj)jkNKSQjm@h!0!f=lVkYU{fYcrazBkpCQ%X>qD?{FEqK zfU_{YnJD%}_$7}Vfys^f>vXNrnBHvOJWyqkzX4LaO4)y=RV#-VJ$p3T=4RNc7_AaBJEBN^l|0z36Y6UkZ0F4VF zq=l@3M!4ckeT#Axsg-=2UH&C|(cO9<#`5sPd%fH(g5PYXIz&_nmqzP8gZFj^#qt?IS)^`P_T0o+wetP53G-e<|jY^BQ}iy}*9 zmz02gBQwfOIqRM6Z{0(b{>*5k{=$4tiC!55M)!X(jFEMnF zfww|A@In3K=M9Ef*z6Uqe++}G^`hD<{B1Kx-3JJ8cL3UWdUhsN>vMm(4Wb@NjAJJZ z_j6X9f-SSw+s0gJ$RpWMb-yc&ViHtctej%aBbc#=<-ns8fPi8aHnGbB^CeiYFMMQu*PMD7m zbeKrtK7qHwf7QE}O&*E7A&FE*Z9P2(^4cPsHY~jb5|gbOmn4w#(UcF{%}lHH0UG#O z(Q|ugUq`?Z1Yl|FD=QzD1S3m5R(0NDU(s3roFIBlHlPsDq2kMeLAc#pS_wGg4$$>V|prvd#z=cWMA!@=?;!`(a&>+1=(b9>!Fssu#hiw@1g z$4b-+dUM>8w#S*c!!SnTbPY@Kx-)svs`T`v5V`FmZd}}(C2~rl*`AP+q zsC%5l631Nf6JX#5BQ}O(esE8FJFk$C|I3qibw>XBUsIi1k(V3l*l)-|7NK%P&JJO{ z|Lm}%QK&V&G4VNvwYD=G`PcOYwdly_w?L&g^6I+X{#u)a#PA-f7zZxW8r?!4pX0kN z=6yb|-WX4lyC)i~}~1xc~D(Nab0G@LZYuu2V|$vXfmmgnqH|C(-rWdvt?qVyCfDDKir z3v1hg!ouL8R(~zmxX@JRAj3HU#WGYL0j4d71sq0?v%A&^@=}B0L_$N?0OgVA3b`ngQcbWe%lUzlOv@tU&Qn8R{W7s16rXEREq(jHM z$MRru8^$VCqS>I>o9TEvd=gf4ZnahMqxJW;K-r|CIAwvZmufSzsh(FKc+S3Cs*M0B zrsw~>Up0F;hjZ2U&^OWDJPQ$g(FCpNx5%~5N;RBFQL}O)T835QE$cQCz7_yLc>GZv z*+k5x-A@~#>8FW4c@&O*)6A+v%c4XH$6_)S7AeX2jaFaY5F6E<5290l)Sd;-kp->N zPh@}XQraVyklDo32_6h|F=$G`1BR*mn3}XZ%lty2sz@e1t^>b1?|}3B`{mWn*qaWY z-)&@2o@%LFAGf&(Qmet(^hU|HZD#%~UrriBLhl9K>73ozR0w{LIlC{}sZ>=8xEi@S zw$&Jodg(f0le?zROJ766cfE~{jgU0vM;HxmPkO5r4Ck0f6I@9BR>y$y4*AL&a%8;p zbaT^k?gL+k9+nBbqg=Z9?O;a_24Xzo40-~%UQp@?vLe84A+5{8!~}rCo(>MR@!D?I zMFhzl#^El|22QsKgBNK3Ks*dXRzFcmFU!1o9)1G$?BZhS`z+(e$yvA@xKQeVC9%AS zo+OWSn*B1hY|1e9g#SL^;B*E^YiOAO zz4rQmxm_v=?7qGh`z%UXl2uY}IoE~~f*d+@U#W-z)usE;grG?t?I_P9(d-i}CCn1A z9T!FpKjkZO*>niZ{KHv{N{B=Szitk+H1O3{{|yWnv4;z5x8x@J;uHNzqPeC&9H)Ur zIg)0%$F10$cT7T-rs+@SQoF)b>r*ctb-Wvlnya#T!I z`Hr$M-v3UtyCY?>8P)^9_ag>0YMBH%Vleb|IbD2w9>B0BN#N6EOxFQT!iGvFyIJWY zW5sP$@zqsms6e9($XJFg)LU>nR&VJ%isI|)>c9go!tqdd$FDWby8@_r;D<(RQ5Fse zz%U~)y9CO$-1h>de*oud*GNL0$sIu#XE+samg-1Qa%_2dnN|YHTr%(clZ7F{$tqcs zc+XGbT$tbJiwQyAz-k^6R_D|v9^oC%Cx9q(BHBlSmvJ%`lJ)anzxpQJ0DryeJrP_& z=}HA6Rr>3d$jc89o~GfzET~aIdj{oZnKo!?`I45IvY(f(WpIz<-xCuH20Zb~GKe$* zK<`)3t@kkJ_;hL|A|HDUOq8$NB2Qo9pTD67El|;m|0KhiV3Q~E(yk!d) zU0O*>L=+2m{M9~#lnq{L7GKp4rCObpu0CO7$cnJCz?2(2?xd*qS@FMpW5_3k@?z9m zwfhDLy?ab~x5117n}?FzB1e*^s~|sLDlu;95W@QJZjP=hU1byr(pA(v3g?tZ1X~+# zAQ%?IC?=V5jA>+VQ)e^8g#`C2OyWggQW&WSHMZ46rzY}#!~?95=Q(8&hoi8hNLR_n zQw(~E*OTgc$$TME#UvbG9b}D?j~&)gkQS|K?d5vXlHw1a{2p#97u)!7V1B6=)SzFu z$_ZII&aV7c-8Y4&my$eA(HKkX+vdl$JD$sE9-t__Bzgn6hoqD2MaW^c+dS(Wl2f(D zn(u!kMjIHU8+)fa4VAbd@1{NcA7w&=r0SRC++0giimlcJNG!i==gaByjg56UXXp9C zRMh%=N}NZ`8Y(7T8cn1U8zqgFW2B&2enbrtAHf3+<93e+!k|DS0aJ*BXHxpbdRKWL zrSEDoxydovKrxJ;68HMsxi@stB#q*cQ|=+5lr}C_RB^czD5n<}R*0abBjC2$$VBR+ z0faWq{;-RmNd3F)U!&|)dZ=bve8HvHY>rt6ZD;p}gXPMQSUx)SAa=yguR(E-$mYQr zyQkLAIRhxSe^G?oBi&?;8)wVM;8)AR|6$2pZ7~9e02B2c%vB3c-Xkc3T>Cl+n-9YP zsVJ>gN#6bU{D2F!@!gB*Z#Xp*4Ar_8dYibC@@KMudJjI+FT<@z=`>elhUPv^^JVWX zobx=)KYlOf54zG}I-Qxp{HV9oU|~-s^$w-hJkt$kSmyWXLP-%_P;KVqU0M)jmS)r& z&e34`OQi72ye#ATO(MBVyDT1oZb*1TFn*Muw zjHr^So@Mcvh?Vlf7v1&AY{MgAT8atSqh`T0_IMwWTTpSg8)2giR~u_jDR z>O67qP(?~G+GK^Z|K$?2BckjuaHmT%$&fR-0Z9T`U&}Et@Y{!Je!c3G=@DXQr$TY|7wDnJ=$)Z$iXXn`8N?$V! zvl<2HaZ+i|pzs}qN0ghXpMEsWgwm7tA$VD>FlaeMoG7^DT75CzJy7+Tb^4WBO?JQt>Mf+r>y7IQoyD z!0YX*J*^lQYLXH`$u~t#3#0ukeHHJlB{*#shNO`K${xW11Pp#aW2|@+3NOKGlXT{O zNS-J=C-;hDUO&^GNc2HdH=Ny|C9k*GtdgtH075@4QiQ#uVftmiz(>phS#o=sKR7pHP_-*G}#L}cCmKQ9NkXB4lncXgwuCjtz=UxTt@$IqX?$o#k5 z{k*_|?@Pw`x64L8?aH=!vZ1hgkoNU%?K6knvES>t=QrP*BUK&ElkpWpY$yqWsJHof zd1>5XCKjnM)@r2@s%=pVXThdPlB;$>L-XS$24$=GFU)c@;|_kVIkX;2i!DC?g=7sy#`h9b0W-^QyGX3*OO?C;jEU+T+AXh z?^Jp|l_Y-Z5oJRP^;5nh&kwV$YhyoWe5{0%{{bOkd#Q;jc%4Q0qR1zOY<(b_)TG^9 z$5+;RFzuwlE2D?Lm8zK>YKBGosZs~yVLB~YmC7diF9~a05#Vj%7*?G`{^=mMhj6P4 zVHe}1z@ktcoTA6=A|RCp>GE=xDIHDSHGag>o;^3TTJ{b9iO?3TJ{imN^fmqh841r< zIa_mk$wEg~-e;-G(hmh+U*2ps$C80x4B{U>@?acOmTyU` zo~aejYgf3i!)AZt)nBpT<>RB1w(;^P|DjB@%bteD#ax!2y?M50anNbN6db<@Qv-f< z-~<6lRES>AaP}LXT!Dwz8z?^4ScySF#BmoF;IIpHP}EeY)+Ob zZhO_|!6sH1uya~Dk+)rubc41wDjvO>0-We~r^5^~r|30*~&*wk68*nVB! zll`VAvZvG;Hgyo4(=z3uuUCeW--LzS7oYlQZE4j)KdXD5H3y~<%y*4KuPE$WHCCd}8gGnjBPir&@b4RcwB3N5cqdJM6#-wA1DDy&+?f1~x`%#f~~M27R~^|wx|L>=mQwwV?>QM?X4 z=bE|YBBp#0hew|KTuz_!W1FcOy}Wu<2-|j=%NWNFT~QiqtwsH~tZ#d^ypWT8T=KKS zuT-D?q3zw$cg;}XwQ~_$v;z~ktBXrWtA;tUq^P{A$RcO;~d5i1}V#;a_x?w~%LWw)1`Zh$JzZ zeqGfyF{uIE3f(80nTPTImHt=-s=DIiQ!$N>P!Rb8XXyI+x~b`xL8oO#g}c7YZ<74< zEeH2L{aW?_nq$pGOc{0Fumvj87HUKfPt|zu`}_L=XDpi@L$T(X@QTUq7ez&tv?=Nc zgzW+dFLOP5MKe*7PuN6U0q%M{SD0P|LNJW>Qs4rv1RHl z7X1y-IO8C+R+z3eu?T(6c`!XLubC~D*n&pccz!^6b*l!{j9U9T{qo5_5O714M>1L; z=~kr|&xC=YF)%(rk9=o$JV}z-!@Gu*o}NyTr>T%PBL!*2k44cY|B<4N13TnZIpf|Ma{}%!vcC`XLp6FIt-vV@ZgpG^7(V-puX)o9R0HB}GM;E{`5)lP zaqb+`Nma?NRZzmn*D2QMDynd*^j)cAQ~uJoY1eM=c2a|%c}EVKgkm3GxcKy^(!N%< z+aq!F7&4@GCVP#1J(dx;52EBqKC{fI3BwL_%ir6!bbl`IJ#~6!XSI9vWVzmu_m(o6 zp@cn}W0+gU;fW1Z#kz(`N(d zu(Trc6Vy`jQ2iQc@=X#JOQ*(|i#S>>$j#M=bPYkJE9ta4xdf-se=g3t_Z=_AJ$&h0 z7k2Scf^A3TOXw{w-oKcKX9}S?@n9t*M~==uCwjwXcA*dTuJ0Lk*e#A}KU6PAqQ8A{ z6EBTz>RaH}U9+!@dBHaNdv8wxVYJ6y?mzIuJM zI-n%tfg)T<{TYU>48B`pS6;22-z(&nE5O?hwRJOes@PZA!~~ede(dT?;gevk58Y5e^mWsUr#vr z4l@Q4!kzG-h@_CNejm8mto4Nm-jWQ}+igruIVTqBGQ`#V&kGP7e%~KL8TRoaWvrOj zSlF0)WKvI8m%P22ddBh@t&{UzO#>pU*8jFe#{6GG#VKqP z8VS6^+BXr5i$tsH5MRUJ{rvZCWf>!jpZy^k$FS58?aaP=i>(Uq;MMi=G0{Wmo2du6*uYgtoZU>-Lcnr6xFy4)scP&zTv-8&d z_9yLMsmGA7!&p78he}8P=Hs8}ve}zYS770Sq%W$5Az~liybsyTe)njR4`s{r3za#` z>eSQZ0X)bC2|2!T5O5e!no#51-n99YDsfSb>8LW1B^8d~o3vu?sL6DKTqB)78WL)= z=cu~tU-8~Zo8#_&JK%xFkEW(y#YO>kYMsjcy+uJ z+j3=`79RNb<=>xxL9)_-%fz67bEul~FT*6-mk~s(ub-rnfoK7ib7}8Sp7GPNZ2J=; zccT#6@UM)DFEhOh;L)xpli}3x$C4kP0q(ZY;g`zAiVSvF)_sk{vT=&sH+465$LyCT z@K9w9#}j$dFk~_?C*G_3H$981hJN+uByg}uo!pvn0@Qdt+IG4I;H)$yF1kT-(Ck-5 zwb{`s0W_1*sm^u;gJS2C;Cf77u*QIp>18?ZoREbMGE~`c6@GY&%F3v=MeJ&%Prqk*AaWXyp{?h!n zl9rKVR_PL24-NKGLd02=W|8=<2q$Lr;xIndP`+L3v9E}ch>mzn<~HkS&xAgXsdb>d zi7kybHVgLgXJtmSXU%s}XZ~?}q}UhwL5a5+IP?$8Zt|l{x>+86by#wF*}9&;?oa=O zqim};+SRo|e%h8v|Deah&?=a<+=}IUZ=5{On747sw@kvXo{`47cnIGu0Y$8=2(Gt=EQHQilDcXu;wm>!eU-OY4& zcXxM8Obiq6{d?c*^{30_aL)65pZojCw5KmeGFxi9oIx;bTk}@m6FA>~3yS=_GU@7Z z)~cq~A!?uYRGgokMM3eo8SWVh5pq(Bnx#`7am*QhcQ@~m@f=Q%;gBcX>!Q1{hkokT zs$a#Xlug-X1sne^1IGmS&%v7(Y7a8s=Wl-8`F`f^B=7MhQR!n70@*JX-ig0rx5&E~ z_(<;{@WywSc8PblBnQRl%y(KJM2*@pL70?Sm6ANlU_X_V`vRiX|7p;lL32@(%i`{K z8(h)j(HRL=JoyJMMHbd3K?O9vJFS86N7&<-_*x&s)0vjbP4{myfA9Vf)YsAiWNEn$ zu3#r4JJ*u(bgPk{s#d(g^px0jm0!I5gjz5|KK)0o4f<iTHux@MgPv#KcYzsgoEHvh4fpx^z3 zVl5wMxBM}Q<4!w<6ZzBZ)?C)*p9X=b+JehR{?<1XBMax;;apmECKej5(3zdc&#hksB5bsenOIkO4MHX}1^t=2 z$XsH&zgMmBsLjoo0sRHZhm*0GOEDzYxKb^&yUImuj6Lv1ZK z28-t`h|XUEmC__PYQm^EQ{y`2X`%>TQ4}djAcf)eTJY5c_g(rvNU=Mp3B)O*4jpp! zveUAeaj%mEdG7G5xJ)Zvemr}KdhPQ}QZ`}SDb00<&N}T385wJpaYD(?m>Qme(<$vR z0|iz?zeWIbWfon$`$Y_7sLe5n?Vb$pPl~PCehx98w!&OdV+j86POy=rrqcRlyzk2O zA%nnv`%E!|(2cK?&t}#158#pfz|!^c!-svPA&*0*$%zRp*QE2G-xE53UmxW6ieea| zkzLc0_JI`mghIA60LI_`b7iRAi+b}TM-XN8pbntP?*+n2N_t`$i%Thikv=ca>9#)Aj@Q(^Q_h#X$ZU50|U6bDmqKwOvU= z#xutNa_@A<7h31S%MYT0!h-j@nmoLswZ%OmD=Pg~1a|Pc_eB_*a`Wn5ES3pYdX|!^ zh@FP57mO?4Rusva_sSB)25Fv#$`#{0U4&q9Oq{7L-dCmjB1=yWKsZ)qv}%3v={WW? zflmeOZvY7ba5}K2?{<(8YOF8VVLa=mb~=mV#L)TIG=MB)qlM<-A5x~m8y}j<(iJrB z2tMcw%SLO#XpWaeD9m%#(=!8|mMT|%IT410fLx2#{L^kEZ5H& zJt?o)B4pC~^YoEKZ-?5fO<{*Uy*D>uZ@Ab(3>bEQHy)vhr(JlAU-_$r&V>Dbjmxa5 zuMPE4*m+WXJr;EPoIjf&39f+uK!H!ZtUPai?VC54c-n<_VFi^6XrThw`C#6e_7T0DtsSe9uBv~)8Qjch8RmVU{ z9z-a%8mL?1C$+a?uR-e#y~8S~kbi2>en9j?$zHmf7*0Si_F z(ky-GgTeL}wqj~^8~VdP#!4Z~u4vL~_q>#Fr61QbNJ8QQ^mB+zqB|tqZ26>?j*!y> znnV^tsZq(QZ;D&kB4rDuoz!;n!C1dsY z%GxsFIyU*!adpEoTHz^{>9swA(5|^QX)Bn=i>`#9X=SUbwA$qr74!4I09No`xjmLm z>Wdw5PeX@=rO|G|z`rIevIJ^`Ba0dOv_%!nBJ$7K;N05;(!PDwY&1{G!t1Nxd0lO9 zD9nu#Zh$PN{8Ze#h(_|g^R8Ygu!PcC_ zY`}#@x|zReu$*_u>Zw#w_DZ9W%~jw`uoh3w&C9z2G?qYz1L!Sa*}l8uqJBRQ*T7_T z9Ak1gZd90$G*zzFvxAXBqMRF?_+Jk>$jNclXBW=$dprg*=^6hibX7^0`^Z0#YPGH% zkP!iZq?Z>z9@8)C1cfghfLy~#Sjo#SmI6r{Kn~jFA$u4t_eI!pfHRb4 zX75x8WP^O${4TdCI}OtxG(v5RVpq-+BPre0_{N?MPV4>HDf~y(D-A>JpI=&><)$jb z8C5(lvdw4y^L*9S;q0mXT6R14UR9SsT?$ZO!+pNg%_Yf)XDJ#={Em;yStO3s!#Q}< zzKncA`EAvTbH*7d2&%#>ztl;45^-oJwn;#Q0r8jE@vF)239p;B+EaVg^x;%VJkI)c zOMGE05+QWoEr;02lqyVeXw*J}HFq8Ba2&|Bt~lP{-!1Fcji?g^+3>L-__R{5%zrO$ zy*0gm*HbcAR>a7qQqU$a1f7l8Kk7eDbX#P=D>nM&DM>jFt5uqOy#;|}dXhLfuA%ke{`r0M4 zCf~!?H)GB3`q!!2{dw!f4xTAS?peN{YIgK3kwIL6ThH__?${Cs7kBr&=f9ipD2gW& zrwTX_>hFW*w26q4gsb&CQkznz8pu?3{rIZJ)k=d)#W)I4zszXvu=x4E#rb0Wo)Stv z@-+@wR8)n)3{G_Q7&5z)Vf>SpTddx)hh&21B5bTArN+wvQLS$d+>PMz4MNqQLtigH zhB>7U)VH>JgZ|2Yo3Ae)U#~vKzl66;rq1oIXaD3@MSDg zADY5sudizA-y3ePLn_E0C&Eh)gpw{f?vzzEdChcNb)XKSzhrQx zM0Jh3Lq>*<2e{GfuMdF~Uw$6DKJZ&r&gq(Sm} zH-&P?{p_qadIfS8c2Vec+(VfjfiY(8g@&>F6!aT>#x(gKh~pv$$XKFE(w<0*>y*W^ z1bo4a5oZnC&9*bXajhHC)cWL*X||XRN$o#XWSeSWVhD;?(dt0l6J#Q ze&@n3abePcwz-Td)y9)v$+FMj*yvy%YUHRblLB^vJWJ_$KzZ4?9Yf1Yii4{*WV@5r1&y(r!g(NNJ# z9d9-=Gcd%=2&IFmAMulUu?GrkC^7P}Qy8Bo`d}fPssIlhpgD*Dc6G7VtcpkhAMAwa z7FPsESsTw9_WtGfCCSjY4~RGPVgc&^0`l_6MXCXcjrL%?=hm;V@d%>7ff2`*3OOFs z(SWDZU$8WRH~M3|vAWDj<9?|eJjYSqaq+l-EbiP4BQx{Ik004bZ8NF_czJu|Kn!IP z;qfPqSB<$`M4tM&z zC8Ap*Gkb20-AZ|E>zjkFxM9syRp1{^#;5Nz>dcfsN(_!u+)Fx2>S@wGMAO6 zJx1kPgD|6c+en5)Smgwe2x1U7jDOw~Iy$ zW&Zpv7-JfU%_PJ!px;XXKk|C?UH@&)oo*?WAs}~m@+~m z%V(d6qRRifSnUC&o2C-lp{QDiecumAJfsJtKja43#c-{k0`a)MI67{fF1lFW&e{Qq!7jG!w$#ZM5uf%Q%$ogYxNZQbiBLqw|H!A49sFO2Y@I zP~cE-;zvft)i$VVU><4Z-Pi-tUK|1xdi#ThspU&bVrwv{Ikb$ALtwv#ydP+St&&vW$Byg9Dm z!uZTmvm)y%#(uY5ST~u{&*yGjJU7nHaF*m7e()O{qJ+}x; zV}3)BcD8)gv?wyl5IgFt)Q?VPYg_pb2ySDX-&n;QPE5P??P4U21NjFk2ps)8s^q0d zpe4xBLS#McLH)UOY673>eGV#-wTJM01x7Dn63AIFAGI?Q3o=gn`4dAQ2p^jQj2~I5 z4(_>-jvgPiX*>Zt;gHoD7${%!{g>9K$YZJtm4SN{Z}{b>)Lq?A<*Piza0cst3&)vT zj6H+_=^7PsjL)7{egi)EFLPuK`PHZO=NV$ZZu3#+M`@Y> zqjb0oUR6sh!mNPwuC!iXxY-n;lb&k+EF@g&g8J+N+)dyp&X&7$A>Z`IpoLaTR(3pm z>u8zhP5((XA)waRf#Iq>#Fg5`woAh1ZNVz-vN*GC6Eb$$LJ}|CA+J z#g>ChhwPq$a~Rs4Z^4=<35~`&QXkjubxU{V;N-;m>>=m?S1fole+%JB2d@eIxk!U5 zr0L=c12ReW^%#g@zTZD3Ax75K8u=4T(=b0K;R211BZB(IhEdQ8;)A|dLe!B_cQQ8y zDh&dmzUubb*TSaBb8xT)L-CV#k^N(_J8EoPSATzS-1f%C#>Q$+k^g+)< zABHs4&^#z`7@@<%IC1Q3Y2oGOmZDuNH}z{kD*D6ATD>9E#X(zhfMP-Etn*#e_@Rdd zUw$cm=0h%74!zry@s^y-khqw_A~oEn!o1}`xOi(uDz3mbIR522>4wxik5c`jZtc3C z#9UIT*lJ2nGuBdS)KW6E$`szD;XP?-D$nT6&BbR$b)lRwcbcoq_?lct551ng-cT|w z#JZ+?O7Yl)UMN2@1J6GS_}u>)Wv0bayLPAhnyJnAN@4%PKFTl6QN4;I73?^zw*Cyn zuM+2}?zl{oeqL3Cx*{Di94c|YQ#E#vDa2-_F0!;jz82kYpGJrm4fuqepk@{YR`@2h zlD?Duni9tEL8^W-CQSSR>4L`Xk72CYoN{_ROsSVu8khdw$J8m)CH0cgME}3Tbg@)1 z>fCReN?g?vCM*-~CfkQ32iL;u-m^wYXkO1|;8FWfHCW{rh7DfLyXw|+mZBFKqL6T} z-#Dl6V72QPQ`tWRaP*L+Q9G;At|TXTyg?V_f*+z~5)mDvg8Bq`YSyN%EwQODnh#4- zk&hAo^%e^ouS6avrkY*#svYeYBDg~83E;$FW5hLgAK$o`t>qBySD-z}-g!ZSS^|2r9 zc}wtW^o=pC=@u2z-cU>ZiSrao5j3eNKy=E>shyI!)cuU(IRdI!DVDjUwgJ@l-=2T3 zZ`1!&lH|++fma!jo-4#f(WTzmQYH@?;~L<`X@n;L;4udT%u+(R< zXt_FC%cz@EBAt(nvjhw^LwlyYSHo9hS?S?g_fF|~KP}ZC*qX-I5wXK7emXH&ocF1B zOXW{}a-XNZazuB>3}a`dJ>-nz+5BkA($7gP$AToO(&3|+tSw%uYj|G0&|K23yiV)I zZleI#dpPC^Lt49`*4<5jolwLzB2ai7q=g-u=msA~aU2&{Sy3fe!%!emRN~&PGTEXf zgJy+MH?ecifnqOh_4Cza5bskjW`cA;^15u|^jp?U2$qITjyCPNB!-)@} z)SR>Cq2Op-S9C9cwgrNU96B=pbY=KQ33k9SEsJ?lOUe!S{Xr>NB0*0|E0KuE>31AX zp@o|*U0Yh}%EVxs2=qi{t{PsrnsujGA-N{AGuMIPF1)k;y`4UxhH(9~!wBJSOFq{t z(MIEef~`1&i)4ba<;j!HJ3urxfR)`}TLde+5~>5`XPkWH#>3Tj5E|5Rp&TVm zk2b>3F^*1fPb9YLc!xQ&6Q`W%?V0>f`Xu(CZHHSece>o4`IFSvUeDM0bL z$0TsixeoOazcFL8CJ~WVwJ9{rS&bP*bJbbYM8NM!3Oy^*)C3M{TV3@p0@H$jMo^jV z<>hnF_klls*3?n&3eJH~0yN0}%GR=wN$s+b$@Hb|)!&3#RA1GeHQ$Rm(=@A9Q%&uY z>{^83b!fkRdFiMCaoYDF2L!EuH`u5?9_4Lhy2+p_3bg6#utZN!a@Lcohwg5hcWEpa z^$s4#?{2mbv7#VlZEk`Nc?1yTDl%f5924XSiznD))iaq9Uq>!RZi8fADFzx+Y9zPGf`T zScDE*V6y6i`L0C|A{vGKfX&36(Iw-BtuykAjR;L~55;2(oK_DG7r56ra$0ybl3io{ z-=vyeCGUzF4>l28V9+4CdlW3Z6)NwE<-YaGx2KOL}?y*$Xc`_F!Co#mZ{fP(?~7GJGtu zN|unstq!=K-Ta1CitBc@yBI`xZ-)5-0@KdH#jKsdA>7u`4ul~p2`*#=oI{n0SIn#m zk;mf7BEPBb@#YjpAU~Czh9TQU!69vIUsN`F(Eha`TKQ3t!#O30H_CyxOkgcu4vp$T z0GPO8D!7q8#Ry&8n|)_ryE+89SVfPc#wB=y3?8W zjBwcV2rX9RwP^~|GM~54$WNjp4~oiZ=^!xW&APTdBD^7CL&M(s%P34*^Xh!3tf;DZ zI@t1lTkMYVmBZ+`WEGc=Rq{auzX*OIy;jLl5W!_EHa8fiyXmu!_G0cZN!xPQQX*a^ zmEzE8WbJzd)zo(c9wWo-tS9{F`VkYgDD&(b%G2mvTwxzr9A!-L6vYU;1k%&fw^DzR ztDXr>ZNlo75vrWA9;BrF-pNs}hf=yZ>ZL~(|9y6jqdbp&_%x&_;-VC6W=zmcv8@VS ztoD!HQ`J!*j|OQppDRZ-lP3r_2^o?N51I3I$7L9Z397#r0lmDgj?Qd$2BAj0 zkckX$B@o1a!L*OXd!IM_n8GLzXI^S$NC$9|VLF~@oFtSUBGN0#62o>ZqbcQxh&>;X z8U+t|QWP#-Te~9JzT>ZnXEh4S4n6{BBqs9@(-nDdCjtU+%_;IU90!-Sx(SFaEl?Q# zUkkw8?HAy@zHr2K%MFESNCwb37&QEBiM74ZkA9A>cCHZ>Z51M;du3GZ7akrjH0G3( zw6ZT0c>%R14mJcNl*gB4NX-I0S}91mS$RXrP46HwP3v zNEs8qtyWr2v^--vJfTgBTcz!Ggsc;gC>078mZqeeL?^)clc zc~?~^dze3#-l&8VubGb%YC;-EUgcM_rd~|n076z)mPWP=0y%WRjaJ`G`$`{4Dk;Wn z_bO$N5_GmcMpoC{;A2urZnHd$pRo2jf3Dbjnh+pCRTgh1V~za0ubQTz+Uo})>mHby z!J>zb($myz0s|hL8{^%os$2q9=a3c`7YVK(41oSTu+9&wm+niwWIY2$q2pOzmy7AM z0YdpgCcKwsz`2zC%`xJn6^~0WH7z%@Pnk4Vg#3w#)53vc&2l<-MiSqQrN-iudZhZG zxiK>5zGH$Xq;aXjHT<5fI^nF|WQ_bUT!Uyt=?q%n5dYcp^) zKO=4Xh7Di9S%kDfqJ_da*eS%{)S7gMs!$&Xb=dm+4)Gf`@2vhXB6`M)71-bn< zmHZ5t5LgNvmeVBL0jc7cqJC9{P6qUVL`;^&UL5)3=guc9eua_hOuV=mlKw(E$bgQv zw#r{dPN7nWx~WmAHE>Z9;*1EL2EiwCS$k5o%`a)2-m<6^eQ!>@L0+>zgmqg?MX;hI zh{b;UZeq{;ywK3To0?^gDXm5|Gt);W>u$RjAt%hEl~(^sL%{b@%tDKV;zr){4saFn z)N=AtX08qnZ}$y~hb1?AE3xh+e2Sq#!#!@gI)6rLqEvyfc(?$K59<^}pq1F|H&;LV z?&%0mG%E58NuHytD-L-tW@sPv9Y@K5_=9TKa}U&>Gd6c?gMZjX%;3%{?T_Pv*C*?#xBB zAD4f!S)f+49`fR1E1cr$nO=qSZG;%uDl2KpV8KlzvR)azp)8_ms3HRlomN*wVEPNMPRo2{N!oVgZ!NrW# zPKjUgQ9XGe>g$l4o`C_mNt)2&%=4cRVM9q#_yT0m`plZEAoH^YHUTs#p{DqtLx*V> zn_FH*v4H-t(vnhJB?M#KQ~*vAAz#OpcUIM+pfRf0AZb)^#Zb5qMet}-GAqrdXWk!@$)oSW$-M(n?w4XhOwAs4GP}9i{_j&ncCZVPg0NAa5rK zz;UEp|BR6R?U+NZI=}H}`$2}V5Dd0|G~TZaw+#=D zQO;0*?{V-aiRHlKObrL(kXwgG!aV<1xCJ^(0Y3N9?;iSA8jGH=b|Pd%3(aEVeF;Q; zI_H71N8$++&S*RFGnNoQFICv5Zr%koF)Xr~y0LLF{4*aPJ&iTSe7Z9Y zU;S6kOKV(H7G*kAqZ?j(Vg9^1tOx=idC+g0mXb8{-zHPEBlEs?$$b^`1D!CSQ32C; z+}^d?iZ0$=Y>()o-dF{ODd6iw{+n5n+NUb2k%2BAWdI_AG&pcLFBT0f)@_dxU)ML~ zLhHxC6jAGa$CVaN+T&!FJUAnw$VuHtX|~lw6>pGJm(I_y)Ch79K`@>(8OC+oD_czo z#X9d+J6NhOK?OlHNaTDAD%H3x71o>p&-TpjERb}YxJ4fF)%dBpE7YO78lAnB$!bYHkGalG6>-8A*2NZU zahI8{eem%ub-%+7J$nx-I)dJzuu1SqHHrt!$e8~9$zy!rVK*Hy&h=n=ay$)vfhem= zVTf1)2|J-YRwPDJtXNj;$|9SmZ92$%x5Iis!Lqgy@IV``c%TYNJi!V5&iA$V|t(62kgAPVVkh^yTc~pPtTY0Zda>C5tO(v4`uyX{EU3`)!`5R{+^;r6AstJY-ie z;^ovhIVylOQqB?If_T)ZLb40H1s<(0Je4&3HsCj2?fx~NMBwh2y`&%}WticV`Fhyx zemFkImJ~dLIfj7FW^nrRhi8rBqdqUq-?nQB-WCTpA>4RQaorGkSj2=1{&~7Yzjvo< zsI;sm4TKr=Ew@qijQNwnHZg^wP(DJC`9vywsz0B%El$;G405qJOG;)q(~EpyPrr*T z9Pdo4lBX8WitV$xiyIm(sS2lm969wku*_mCAD{Q0=Wbq(|44>yQSIc%8b=lWLnJCf zGTEf%J_V|=D)NAN<5OwHtR|nUdEHvFhGm_Mr}jLffSkLNtE;JMDhrl7x;6x2zY#U7 zkP-Dotc>(eTqfL%Jk(#);JQDF)iE@)C_?Rf-nub#^U6BnTy9NGMWtG>&FEqTu9dAe;;uRzW#7j8``>=B68e-k1` zU8~6}D{b62utdqBKJR4y?{#tt^5gd;C<)MHDGaf6%H?MiKYOE9JRA17*cDY6)+Dwa z1k-Wj>-C*KEXdS?T5^7ocESSn6lTbR4;6xF0?%1zM#cc==xp0udClKH+8g$vO=tjY z3&xTlj(ZT_!T!T#(Rlt4#O-8f2d0j3TjR(Z-~(3HI-S3M^>p`-Dxi@HjrTnQ5f8hh zT=)Kd!Gz>U9HIfl5()vd$rF$+J^sDw0K}xah6bfVV@NEV9jvCt`!6!0RerzhsspHr z9&c|s$N!kKB%-P@E3=GkO-ZH34J^d8g1!UXcbGLhzC`T&44BoMClAYAe|YP^!8hDT zzC}n|IKzwO8cqi38i)?G>e-pe-JILUJ2+w9CM5bxy!7U_bi@79%Qrzg9EKQ?{;W@I3fBgWD)Y>)giP_CzW z0By6#)9w^?Oeq>~iLy~497xlh_u_U%kRhxutuBYr%{8@V!fpCe2XJm)6Ub%p*lefh z+RzKqwSnoSmGpPmSdASWFJL(WD*1(uI$`6drw5l-5Z_d$`r|__t@I(@M$%=1eg9?Z zzR{{=7Pk_)i0;jy#EN*t@uACzzLqxhqD_MbWO7cA+{mhP{`EYa`he|YM-vn25XesP zd3iVl^cWS-)2`slE=Xwq^yyO+9eJZJwp08uNdH*R6I@tCQ3M9;Xb%Vs=it+`bg?h8 zIiSN}Nk2a&32L$1*l3Z-f7)syoyZYqWi~`(xQx$PU7j+I@7 z&V0U&7+mQclHOjgtYCPnYcHGaeD2VzAZ}2 z*O#pa&OStQ)B#s$ZEYUm`0=P*TDD#^6`9C|e8CqLWEfME7DRJ%%?;SnI7A2Snl>9g z3(Rj)>TT&?nQOP8mUfQMUC@q2c!#&mj13Q>jt_<3b)arhZ1{mE}*RD1OMs zVjNd`45cy~z%s%qTX=p*DB$@A)@xLj%Av~HAJ})jZ!h_1xF@+=#*I5UiP1~l+}-gK zdHbxR=?uT0$Pf8^+b-nZ_Dpvq5+y0f!{M{Sc7}n_Z8m++O5&6ct6tc_f=z9IfO$i3XGD+4np| zF4Y^k%Q}mCWvSY8SXVhmT#U_+zx5hV1kXEE2j%YN^eIS55A#Ddy-HS4P`7&|&m%Op zU_{X-CMUB1Jqp^=V6CWv>V$FhC+|#s=HS!R{KpyOo2?i4unop2V5t?xTo?FUY`FF( zmD_$9cvOFAE4{gYqT`zG=@t04uKHbCta3$*-FZ&IT?l^1`|vXKPfWU3v+swnW$4Y@ zgYow{6^RHR*j8|xeiheJ*L($?ffeVr)7#9Zdbcr8B4=L*yr>G2ww-mCv*apesflb` zYWolQo{D5pCE5;-q4G_t8mFfFMiF22~dQ!eQ#zV%B%?rRG>26JO$mLd=rlQAlI@m{g^q|x%?1QU6*jOn$3j0k&&<& zAL*X7(bp`I+*5(BzLLKz6*Dwr9R1)^18SQ7JvxuMUKBOPE3Pv8Xyy1Q#1W&wiJ&Et#UI$W`duT}9MAuP`5v>;KgN z74N~jpa=eBgQ_KrKnza!JJSsC(;(Ro@b6{Ndy+V)3DLmDUYympbZf$-eQnAM6;71M zz+%t9vGIWeGyR`;td9O{Z>I0W=_x^ZY6Ty?6tu>UOz z65f0s9!B!G0_;IqRY#9_s&6zXu<-xa=ub}xtg>JB)Fw_CGj_yqiB*yu;<67qUa?K; z*z)_ew6#TcY>4Y>Kf~omzPGt!K$S|Z<*E_sqZQ9RgSP((J=`8kVAjCaEf$;}mG2hR zUf4f6{CIMt0j<*SEdS|`c*fESPC8oINkvN4Rt{C2%yN2J#Q7Dhon^D!&!Qepy$4Ls z)PS&2cDDrJle>z=Hdf%9NdcVJ<96uB!jb!QGoB*++BZ?=rBnDb+GnX-7ybQkd;^(H zuIINP$1*;UaLAINJ~y%?g8160I1Da^#KZ!BmQpm<-hoBS7rwqMX+fSc9)J)eNVe@B zZp?1=HpJ-!HsjFYM@fI@AJmNbEHWMayIFIF6Q`QQ6)-w5ufvXMIHeM-tXIX4YTxyH zaQ@}_x!t@p(w{P>*CWiDc<;o&T=MBNYkGN|3z_X!5$qe|p}Bn%Z>e(d52Wp6H2nCG z9wZ>@_t3EdwL6&4#_>-jHU_8PQ*p2`1Q%iKP>P2V5x`fS8ln-d8c>+5RV8G%MX;Cb zE?1!s7aJ8J4_>|%=Gtc8WWNcIn@uj5-dhWW2}0cJFt8)V*1uXYQ`LDJWmMJL=h%}XQ_(BQ@b;$>5#bD26~B-+ z`>*KC`m(j@McutM!}s4cZ!86rO1*Y#P@SXP#@JF>l~S3qi2a`e%WFeob&|C^@r6`j z)la<(a(GloZ%3pOYvU7kQ}l@4yr}(IWZgg9(uT1luE?O0VK`Ifzn=YMB4NWYgw*fYP0@*G*L zOK|1t6Q9l7Nad71Ix4GsM3H-%0%pVBdx}bT_YUiyIb$TNsE+KSJe%fjVi6BdC^5v zE?&-IJR4Q|J02YcBNaKqc^rWG@vRi*wa z!?O{}oJ@D_a{O7$s_qO}@~<`+Jlp`=lvFXh9ZY8B@SoBU;90XlNq0CYl(wQvR& zok!!WM{yC&)<+p5Db-F4%}IQ2O8YswgTdgiGYPgnuyBJ3xe1n8P-ie8#?FIzLOoOc zbuC`{dW+?lpcb1~I;7mGt{E#=DkULHtjgnO=_89UuJXcU@-QIJZ%Vk&&i|RsI+Re&k`PoDQp#TQ z@JKW-VjidwbH>#4rM!4S++O7Da1WFvPDv@5S8Q{gNrc!`8u_FYQ%-a6ht~#R3_frP z;iVK`DRoJnGoQFJ_#Ie|^r@l0f&y5eN7e0m1npBue^Mf|+bgZ7ZRgws;og83s-9LVHG1Sx+Iy5lZeZp zn<`v9>$`I+E&u&c9^v=GCBqcQT{p^*i}WllFDrGu_9bcFrgb#P?$*qfY+xZw(cOdg z1Me6?8R4UTr{B6|505I-_bQrV*1>&y=}tJ`krGj;-X7ymlDb#|0q7@PF@fRGBeQ(h zHMJHV+2&SM4xZ=y8ZM7Tr4?jMF>2q@VDFzV{IkaVduCJ5ZSG_sC0@OA=ZIushWI!b z7@PT+(C}UKmi^ZbwzeRs;B{8;Ii5`?TgLh0-=pu`eT-k&w%t>IIP5v{G8o0*vO=!Z zsWPx~au|*KObu3?FO|}-6?m|rw%sR^*-31aJ+h&`9BD=th``FSf6M%n;tVDDQ^dv6c+2paM-IyS{ZJg2rk-(#fcaqP4*wMHacY`tvK%zKGuuL$=!^8SCFeTJt<6A zzp3G_vofbf8!}bXqdgz{i<2ZKXpWI4&Udetl^7}1xw%x7JuGZKp8LQd*wxi?f(O<13+VqSjvk| z_Lr(C*e&q0sqworxrv_*h|ke9`{UY-u&=?+8Z5sOdh#qRJdMpM5z*X{d>S!l-t_lY zudG?WIY^VnN}PdU6=DzeAIGRIsuh!0;pdLY6J^iff4&6M#Q%BGzXIC=bS_+8vb5~* zJKt8fZYir~T$-DI_PQCONzW}fjd0G)kIm?a9OXj&f_~NH|0)m_GV)g3 z+uv^w2CKDrsFC8LA9?vpSp~krZU~&vSW2Af0KpfC8=StbE{z8mRin!C9oX$0gC}Qa zpwJOe7oF)Y;~#dVG~wWLU0naT zmEiPdixTFzae0s*S!O=892rY4b_{6BYHC7U`%x#`zClryn22i+cR7u?sKlOQas)97 z$_=v)V9;w3F)iKB%oJ~AN3wLi;n4+w$sLYJr%jpW0rr;L4hjNcL3x-ibQB^ za|v|mBGXyd47a2Wo+TJdxFDyF*qOoprui8N;|$K=ZD zc(+()k(af!dEO2Y^}#6epwrzoBz68hczp{M8Gqmdvc0JgEI3urE*1LvM-aYx=B~l% zyTr6#DJ_70WRh zz(W=lCU||VnuSv^=LQj!(YouC+hr2}dWq^1m^o-Uum+3;P&&Ua(jE8nvPpfQHQ31U z{I3kzdE@d~1a@8pnnx^mWaR7AUc^XoEC3=I0Vy1leacfa@KF%f6J@8;9onIMJ{$9} z*{BsOhvF`&;@&M86oa8_aFSO^4Q10I^QEit%+0(n*5N!8q56RwO(R(P!JD|E*nek? zx69rsMm!BlRebq=A`!!Q!?cf%>z+yK)1s%BS4(H-X28vGte$I=;ymVZA4t#v{wxn8 z!z}UaZ>y#1LT<%Gi@+Q8`aTVl5K!`RQ2jsaMd}*4F3w7VH;`5~gDk$DodA z(`M>8VJD3x$Aq*m9WJK0+D_%R&X9+gET^O8lD~#h>ZY-y)9_!NtV4+cRZ58~*Zj&E z#_gAX>b?7Q|NM8K&X=Eb%XlSR)kXyiG}Ezi>bcz0>JwJo zG3Fv6i@iST$c=mbftrpqAqDx|CCo^W;l_5ntmTNq-m;RS6aAe#TG3oaRjQgn8alVb z`U6fO_g$3WmyAfNXE_-~yLds?lwIWoKBa%Ij5X&TbBwexAOl#SyNO4bmQA_DeCMcJ z$Nl40oKqIl-XRAnUe$k29CU)sWF6zkIkJRhKv9~0MdQ7E;{u;+Ru#v8n#+q2B#E+{ zD^EMur{~Z?A*AjpWA$O-qD{Iirt1x>8ypZwXVvkb6#hacjqA1H`Y!Z>qNQPVed_j! zETWmb6)1pL2Il3zxR2l>2rb^}6R>9;?kvSp9dz-A3jrDOhem5N%-!bF@o{-L$60tR zkIL95Kn(a_fAVKfT)a)jIn{AD(sk*mNw>~O_LWE%w_sDL#i4gA)#`;J;`g}R0x_RP z6r7<08fEaRo9Q1qvDk@%mlLHHXR5qCF zQS_{UFbyC%#s3XVk>@B0J`N5SAPpwM1^6K$J*Qk5#=}5}ZX~3X164IC@Nev1K{MYO zMhEly6ID4ma!?52KcWWu%d+dPmpRJp`~-P!kWzeo5QR!NAxju7es`~mW-D9+Lft*C z59EoA#Btt72pditvx4kD1}2*tw$uOD0x+ctAMb$r2WJiF%6A-u$fDrn?ph=qth}a6*h!@+y6b1Ab;OeF4GJw z5tgmZCMkJg3MV5H-bLbYRAqX>2RKl?iIiN_t<$V!XS{rAEtbL16V(-p=<@?9oXSDc zH8Lu3Xq;tQ9cyf4?(Cyrs7fxVxBUgOa-fI-W#ek{S;s~koeZEaRNMogaaACq9xp%f zIK=!wX!syAJ^e`EBv){dmUS4Oot zSNAH$5iFTlQfBKdnb>xgk7-$`wykRrp){G!iprmUlorlC>F4O!=t^Irge z0P0LWDs181Z&uV|Udu2D0y78~m=DY?eDZ1e>{QNn4~js6hqW(1_xpHkr0z8+j6-pB z;P=W$Zj&`iG**dk{cn2*Pq5}@TABYsQvWL@rbc%RFbf?_#Du)`8$1QmsKMuKm6{GA z53`Y=f?o#WPXO8jDxiC<{ed&|;DAc1#&{CI?5`wh1o?#axYV-(@(PkxjvsnzAVmuU zYE~sFVT{F_jC7$l^;9Zc92{OMM7v59s|g2@O{I7u%MQEL*$0^;%8{q1baadhw97Hw zJT_KXEWvL)-yy_kz>Tj+ zR7F9>4a!(E>8qGdh`AGnVYFLL5XtS);4U4IB#15qm_b`Kir}lWs(w&e4^>mBVQf)4}CgH13~M6o4o z)qYJDHw#VO@@hSI*sG#d&Z_=fzB)!GZ72LdaqLSl2X3UkO3=4rzLA2*Zzi1ZE6sB) zh8c2NTCzmeR?;_iPSWT1c!Olnu3!aO5WAY0>nm$4ZA*oej+$6!JVSU|eYh~LgAa{+-;L|e^pkfwiN30$TooqonQeAMB zr38CkC@2jK#7c2I(=fjV2e_xFCxZezmOZ_@eSQ;7L?N(hH`dn|bW)9*zcW1{A4|>L z#~sxcqO2-q{;znYq~vajY&@79SkOp$bYACKno1McgrI#LuCiWc{r~KpErHgUD4xG+ z!9{06pGQ?;CSmc$5##oFGYM5`itTV}QpHG_2TL!k%*A-9`s);|tc(bM^Q(pLfT!r~&* zUID_#aiIJNZ88Bk37k|-KQ>(LyF%pBZsbB>-v#)hUICb2fT-Ffg1mLa(yas$!CWcMmY+O()`CFXAPmXv;7?@v|S#N(N zVZtL)V6>iS4*qbgNFZJ2{V<4$(S-(U4Ayr5UUu=;58Q~SI4L`%&vLBn<<@pGh+uR` zxEO-5S;G$yGk`*N0!yW_V2#^5SUK~m4A1M20N?0#0egM^W_up5yDIt8637ZkHuduL zt#F90;RRoUf{TWuu$-)pz%>bUSe9$tCp!ZJ1K?Kd08Nmf75DbmElBbWGJ(&0wsyOD zO{(MqHB1bnA^i!x;XO#Bgni(k8U0d*E$nUWbQEnqEkJt~1D#(5!r;C3zW(md?(ntPlY}JV}Crfb%&IEqzYfvTFu1l+w z#aKEK?G-WnIr`8K8ylHhc4lV56?a`MkN-o{S4LIUwe2E;l1hU}cXxwycc*lBOE-vg zcXxMpcS#CJH=B@QLn(v#?@qfQ|S}#<^biM%qI!+<8SKPW^ihHbKI@^hjtqm;CuysieJWv zr^eZ|ZzmA)lq3`_%w+Pnr3*{d%8U_%9!8>~klBZTML1V4mTiONJTSFHSXFoo*AXZm zfIIGP-EDJGaYZnxeygzr@ehbNXaoTR*nXGT02~B^ceXPATR?>Ae(=va(V@eH`RhGkoKSwThepjy?V^3=cbUm4WDD$Y@$&lyp`^5~Z!py7qh zo!ZOS)`1oHNH#Kxh%h2M$%A+Ly`ezSGS23Wtw~wNg3=s#2AqAR(;c;T2~y<&~4#=wGQ19YA2(VBQ2Wa$` zc5@p0s2icN6;o3+(nN1J*UOZNvd6D!fK8OfQ3JzPFmFT#G3Gw*g}*G&ukiq&rl)Tk zHNI~JO88XK{}|@(5!cjK)qUAQ_jPJFC7n^;FAb?`7baNh0s=;sZKX3$4-XGxW76jz zMvmCyPKL*X1O%&YmIGi)xo94hRGfvNIrHRY7MQgx35iDkuJ(lQvk|oIdIcz*mX_8V zN{>;P)$m$iqH%X|X#@?dU!Cvjj8h$Htg`y{E%+(f80F`;iTySq{{_Ijqda8Jpu23GcAAm4JD!8wW-yx? z_@_L(z3v!jMDOt#&`5Xp+^vy2!5{;7MW7=(Wir_V7;McrsG(S0#a+mt4d^d4z6W`s zV7&YOJ8NMO6Ru|FSKhlsIta%NA8}R2CK=&??I-x+Nv0?|g8r9<)KY9_b}lNS-m~}b z8pz{&V@sB3M1L%|4wb*=xpN>`hePF0(*xHG##%PR>Meft-WmnHHrjUDC#u-@PfDj* zaW=lu*+3g{1C9Z(lY4`=zL_g22Y3p=H5OQ_Kz=a5Lrp+L9dPgc&&~(#{yQ7KKofw< zl)){T+?twcRq{AO4@Il)_1p&8!8d4uN>IvM5KIy-fWfOT_0Ejs93?6{MlgPnT`Od0 zdxtnZ$>3V$Uk*<$K_$;zvh5!~qFOqxWKB}WLlB%^mexpz8WHCH(oa#+y7}~`PSjVw zka@(P1+}U8u`2k?{QC~mulN~H|2o_fmExrU7a@$OgOBdD;>zk98Nw~yStme;pnhYi zXN$gwir>f~lj8E0?btdR*eBfXJFe0^<)dm^u%DpGQY!UCc7i*~MYE!QNZ!0mz~uF+ zS*fLx{ke>Uu1)9FYEc}w4jCk8M}%FQvBOy8A5uStTr3!e|86OYtpd80`f>%o`1m=Bl?#Ja*mZYGz;8{l02~|?2mFt3|2`B zr9rveaITET;Y(JB@U})XD6I@raN=P%>5_gVBkXU7?`1?CXl(ao=voPXSSF1du#*&% z!NAzy&aRrJWTeXINyr)sz=jYsUjQsiXS(bx~!*j zA0dQ_!1iN#C+1RMX)09*I_qZU(X(?dO6nWZ^A`^m9Pj4Ni9?D{Khwd@1qv17K=43* z?n4sA7I==sxRki+Efyyb?p%3-V6A=jrwbTf@Pda_TuT#EKw0SE6niP;$&Cdl>|Sd9SbX0T`=${<*zQub}LY@)1*bN1fs_u9_tY zU_6Q_z9s=to3C^1w!k;;# z9*)TL+7yz@dja_U@mSgmwf*K;%a}mNu#4ewI>JBm3C=^tAEQ){r{$(TXgihr!4SYfP z1BN*+(;F%!6cn zMf`%2uqnWaqY)OfP%OuK{W(45^Lz0QFE8XZ?gJuLR#pc3CJys|Vh?t>xAk$J5YXA+ z`+TAgtnMAFf}9ytqD%VdNgMSSreMemsZ{N@ejv@HlUS|M@Z44tOA3bV`FGAsj1t>Y z+RNs6C#ECeq`JnC_AU1Zjr=r!ztu9u3QM_TMN z(EnNU0{PD#xE*F9ZoinWM12Wd(6vxZ-8W_EyxVkAp}C4=<0YCf6Tl#G_7f-2VmKFfPVd z32f1K6i(EOlP&DuCPMCz9!J+awjPrc4K)RdX97jV+sH}P&>7lcE&uxA>ERk$8srin}^H=^+Pg-v~8B$e{S`epS^`_gOXlR8Z>mZiq?O6_5?WAb%7= z#j(i_y$zg=ng38h$$Ykv9YFs>rXM^0_9CKPY`H_LxWaPn@bvsVU$u3p(%C|L*;IAV ze`wCvp19xnG66m`DH=(5g@y-z?@iFQ?vWg{6}Uxb+bDtFVC>6)#Xr3{=sDy z;%IDdX9w=O>r23C`|yo99NmI_uPdN=u3t)9KB6|qkapqoNjoOGgmSC}SZw})w+^tr zCpA6dQ4b&pnN-E4DxG}Ir&5h|bj+l^yqhoZ6++UQ3MSh|1Z9%01P%3Y7LN=1n6yMO zG2?c&u}ru<-#5Z<+*4F&9m_{x98{h!c6I{W(|$_8C=_q+?2tU6(!pWd-D?jf zk|J}o0uMDzI1jMQ@j5aPpk z>>l<=maQgsOSY(jBrN-RdPD&`=00P=t%UGK{C|(g#+?6Z3@Q;Uqflcf-yYA^SuLsH znv+ATIkTFQ%{_UONch%u-vFOGXzF}^{MAEIc?}RJAd4GN2B$+O{)m4Q*0*a{muf5%y&*yFce&l@IdV0$A#Utw2v1p`# znfzOYXtO+bK<8MwGlNipiH~n4#Ff6cFfU12dgKG`9NdDFU;INBAHGhXs4N56dqSL7 ztIFnkP;I8IMBavoKT6To{n9c*#r?9`7<#Yntmmh-0I=&boUq*@Q~62!%^@}`y}}<>FxG;RWQhRgvnYjDhJgNlIJ3758{_d&N?BgaSUpI%uK;MBJQo}O+h{y z#$-=)$_bWlw1f4l5PP%>r{GScKw|8A`!^Y8urea`Dcj>o_rOJj*U(wngL zx*pZh^_}l>6@#TrYSyT(|J67UWVT`{e$3lad}LFbRC`-EkGTm(CW+tC;Ag?#Vj(6& zWOUaG^Xt=6G>5N8x80W76_w%p>d@S;nxBB_>08^5Q>`p6QwR_WEB&n4d5 znj`){npIG91F)sC9EmTDpcT{6AaKQg$H}WHCOv65L%}*{#>i*o-n0JiMm3hgKfqN@ zm7%dq(DLAbJ6Lfiw>jRs?rI+e!qvXi%(AkE1G=RMf_rzF)waSfyg2Qub)^reuKXn) ze0}N5smhO9sy0KAYlRg0ngjL|rYySxN8NKnDAD@3u0)a4bWQrByg#lM$&?x#h8FE- zAcO{WA}o(Agx6ekeQgcgutd!>rs7o`ZOTPC!4n*2D97D=f)3aB=k0WcpVw)Y;P9 zbzE7rrP_@b<)3>Q?LS8n5)9~vP5}EFh*AvDA0RZwBb%Q38?v3Afaw#))UcoACE)Y; z7ohy*x$xW9>~=W?Mb3HXIt4;BC--OHyVO6x~H`9W{-wr6eLdSyrmtbzWsR;x|9o-d+Qt;gY# zgm$#ftj&}a4nRQwbqzehP;0@xrDq4nf&_F@kGXVu-Wx77*D7F=AjvPqC{U6YKydCL zl+t@g(esFz$oE_iF9ZG(P%GEGa9sZp_6b{gl5(Yr z7+DBztYKGHAj}l}e-HCIzCRoKCL)I;1|>4!du$91iR*58Y7xq`EN87;1my8faUhgp zn`>(}FB${uOsRt-bCOcKkB>Z>Ra!IbdgNI_YaTqB{gpd)dxL0jURi zC~(@_83Mi1KQc^6zj9F%GE8>Q=w;`ZNmEE&P$_kK-biDIJr#Z{uc)9U^1ZqMJl_lc z>Y`>UMu#BlSOX8#p03p(!xBQ1%L!Q9)zpBtIzMZk@GRISUCayM0yUt42k6Z1d{MRD z?tb(?Q3t;f624XQMTDeN-|xAJWfDpH5U#m@t5h?I321NGit-&;?h!%(@dTcG@zOWV z$%PADI?hJL-DLU6!!(>ir7HAfeM>8nT>nxjvdHvI9&`uA|He=Y-yV?Q-4Jc&$O8HrF=RiBL^#gy|Q^{7P&_SuW=;T=0DT!|pt-@bbFtTxZ3 zI);nSu#m5xR)KU_F34qNum7wvp_jhp+!@7F;u(tYf&Kj%5B=9nUD);dU=v|tf|I0kUfJuJZsWOx+vWFhR%Q+(V$Wgte=q6ns zJ#H}GV;tPWzdxu|_$HZo!kzPLmE!$74l8CA{wy~|WvK8~(2BTM@~IDfj+pG~YJUQh za{L#wu&6X1NNZO685R4!c; zo^VVgx2M)Xw4n!IE<5w~o;)Q?1uKEZUFT{E(mlvhrtMRULup%^W0Ez~X(9WLd3iQ@ zG^+&4AicDdu3~(=n=>cPEDXn8(G8gfsoY)TF(%(iW*%>tMhIiw-vndyG^?f=G?-`Xo}+Z`unmE zZkf2_8&4fHGQP!mC|FZFob?Ihsx2l3Bz)qJ9l$T?`-g~Fhnx+Cj^Ls3WxgKwA48Mf z;~wLmPqHtJcK978s32hjkedIMnS-<`T6(jR>i(>8O+g1rroZYAWm4g2Dgk0N3+ZjZ zyac4P7S+;N)Xz@mOQiJl^nIp87S%~ytpQqOu4n%U&I@;PSZ|znq23g3UQ36O@x(#8M*2}%mGY_%M_`tTuO0WU6oDv@P>A;+Z`sC_SKc@nR{mMA4rV_*5dsYT2$*1T{>}+M zvVH{ouja})>!o&sR2VXDOKjvK@Sx4}8YD_OE2F@`H91!QMCKFa`6!2;^W$u12T)t$ zSt#TW!Y61G9|~n?L=A@z6}h9_t7OrpT|1U@DO!K^pc9tN8AKr#F*G5Hq5Kpj9AeaM zdv}E~NU@>KF!B-l{W=Bbgs!s>lTMIuuZc={X>J!*$wlJ00XY1dlHZG$bf1P|x)+9k zW94cQtl8B_JAhsR0@uubP!S2Ln5}bqYHKebi?oi3%pUiSax*T}y=pH&?*^w!G7Gia zidG`8trSBbqEywmE1fOwhxAi_Tsy0GEb={ByyGb4aVysJC=op7kWn2f*&(KU=Z;a;0MT9 zsBTK_Kygp)by*`wxs-)5%Z)(jU{O~$(}EAan4|3lvjx*&wrPhzn;MA%GcOS$NLpsp@Ta#;|3vN z7VAZgexw`dL&9lP3?b|L>%9on{{?v6ZTi&+z5hY@upkZ8VpsjFtyc)L5>=n6NoU4f z!|Ja5NgPTVJC37M1?M!+B+2B9P50ur!dP{VBcHdA`2AkiI5^RgbVlG+8?fD#wJJY9R*F_}`XdE20)W(Pz-- z2tU+A8kk1aHhi3QIb{Ouue196R zDN8?ZsOCKBjPuo*S@aB<%|=u6+LHorvPspIj?RK>9dKzn>`E{fR-hu^V`6#Zyo!PS#D z&Z$DMCeKo2?5H^_Zg`am^_6Ge{JO;Y!&|<;L2T819i?dcvFd`uj4-pZ@(FHuDkP*# zVVwLxHi%oW+3Yt#cQtK9T9a%nRmRtzYeq^vS6Wozx|FQ3=09LgNNY3afsj0o=Tn{t zYOP`~U5Bx3C~I6(7E_@`Gb^+j`-!O3x2IfzP~DHFxE5m77WVctL`>|O)Y9~0^DYyv zC9L&wZOy~UVVO9=G%!PDX>xy*?-Ej6!|m+sz|5sCSUCcy-}gZ+TC^SC}2oIL03P2<(uky%M=AE#nc0qm(U zx^O>gTNA0%O=;`PHsJkX+YzQRnU5$-@L5?X0>JYj-RM8A) zi|9?)qYKLuJ0{PtL2^et|+4bS$N6T?Z#k<>EcMtN{ zxvi^|+=Q}QgX2{EI_pdCajs`ix%4KLn_iVn{@FHT3P^2WuCy?3uQ#NLnQYjx@yA0DT)ct&LY-~ zM6;FRF5wAP5lp|Uv=wwTt+5-~7QQceRNSXS(YpxW^CBD=?>QY56ZTaLiy;l>{=r+H zKQJ-4c3ep%;YG&f$x-66*Tx*HE7hSy-ikvcmbhjm{COl#SASEfmf1$J6M-0IZw~iWi#wr)i8Ehx!l8P;5rwf^kum# zUQJQ>AZ_n067qu#9(~)ISG4YC3Iwl*b%wO9F=0sw9@0ZM=w>9a^hS^qVDS|-U%bH6 z>?S4+ia%OB*yYlcF8+M_Wx<3-b9d z<`RVCs_T*(i>w(a8=7pJ%K213L`%CFg#rZhKTD!iu#7vnAOSYoXc@I$YWo}lK^T-` z!pT#mT3MWb-X6)kJrd|gjG{@e&D1-P-5P~(*J(=*Dy(@E9V^^otCFSVv9jfer8eGisZ9%cNt&`Z7X?_?Wt0)TNbGIJ%- z*VP3foK`@F0p9>>YG5mg0~A(LZlrR^L+X!W)%r!W#h99dXcU!5F=-;j5KEE7*4Xl! z3?d#(wJD7SbX5P`g2jt6;f>9D`Co*1933jPGu>5J*Px}3Lk1KTl>XVKsT7ywUc}$R zRKgPfg7zdJoTPbdNaf$8f%K11AIZi}H&v-6pvvxd=LTY3uy^|DYZ4xB;81A#U*yKy@{KHnC@uou z8*s(7_Vj!lH_Wu=v?G|nLscnMRZZvwiL&LV6h4Y?4W@kJ4ZD6Pg_|ErzEffQJ@^+R z5w~VqKa`&dahQb&bwTH_Wf1L&|0T;BG#i_vg3@?$RM#xEzIimOX@3hLLPdAcKS#QF zz8Yh&0-zi{)bBpDwcYm$oDP76PM-%oEI_OVY6>2}Ut{y-wgs#tb1VmykZ4eNUzT=> z7An5GZx?@|q1brOMKp^=p%ZnandLU!h7=g%j2lAumB5!dMnBbReKMw;xdg{m86q8* zi5^%8C`Hq?K%`FI4gr6 zJ=cpa%(=Vd70^-qo6|wNcdr!pjl(Km6eOA&ILMlRl-;@lh8Alx5o50JE{cd!YUQ4? z`|S*?l~>bk2}U^Vf685^MiKkU-0BN-Hsj635sWRVN90&iXw$^G-s+6V3Yv)Jnkm9i zQ{7I63(IgS_&P)4@9HtiXl__HboZtN_d6bN*+U|H| zRFzD&p>st?rD9=zP=1qW;cT;$^|1yO#-~c?^>io!-w-JU%9K;wJ+6j*`CW%wRmpY3 zO4{LJ#m|hU=T?jGv!%kLxVIyAIf`1HQ>|4*1x<5a%$EpqznKp5y_p=my84x8_c@GzdOdEV9Uf_CE)OvX_Kc_Ao zHN9lbfnmvVxO=x69VtBJ<9fmVro_C$G>b7(E?Jzvfdr(h6AW;(emMj}B5cApdl)sM z!=)HVa%Q=2ubedG`oEPa{RAlf+8PK810FzZrl98h}CY`>M59BxI67Vr9-nD+@)Ne!Sqb&Jy=nVY@GdwE?W28MB4Zf3D zf>YZ|wdqkPH@3932d_O`5JQITc@#-EU0;3p<)Fv%sQ$KchtCWA6pM;Yk3&-qdwY6@ zcV7bh5g;^%$R)I*+2x<+w_IY6Ox`f|_R$Q8(TqdgyS#`gNg#a*C~s(By;gTI2qBRp zE`(OE82o)}gRF}7dyHpr#cKCPdcpnoXwT?VHZW^_;%6y}HX=L(@c_8eM?S=E03Zcs zfS%S?O+7she!^ak13_I(85Tf>6O2iqR_5X7_r2T^)8u$hLnovwMIprj zn;_S*s)y1DZL&aNR<)PbnI!)v2}-~}J^^wD4m_kgM}7CM(~H5v+>d(d?%{)EJN5-{ z@D?$gIY~qW^x4Ela#?WZ8{68_x(9*mX?9lWySzsk#>vvswP}>{K6|F&5+j}9W~lD% zj$Gxx`^$p1ii>ELS85i)KO!imzk*N2lKOr^I8*a5m+$WGj6EclbDnXdG+o^@-*jgG z01|saYMPLI!#%z_43L`#eA1r0DyG&AdPsEBvnQUyx^az{9yKWQ`o>qGopT z5nAYvvK0-@kN10VT8}Gjbp;jgATp-V2aCM$<-5_ZVH0vY zCd>|VV}sWnnui{8eqUMY>d8_Ri#bCw)J}7)jDaoo%T<`Cxcfa+(|=7zp8FIuOtTac zI?G4Kan33jXevcGS%hv<6@N7web;*obmjV5t>zk9h=ebndRQ%|^h1RfvegAN@HN9q zVT6_}lc<<7CoqjwOVmAg9nS+l4gV=Rq>ISDGK*Y`wzDl`F2?NMO|{w1?x^lqUWBwKGcC~) zRmz!U?N^%8?Bx;1Oj%K3rVClRUSd$Loj{*H{zFoVoBI}&x(~+XoF9fwDgD05&GSPr z_=rcc1c(Kl=URH&SUux#N7Bp zZFKu&(8!&jsIipWCgN3$i0nZ$2dL`T)U?ZycTW!{yt0xi(VUk~7D%@Fg9Hw|mss{Z z<r!_KpWcq@4SQ4ek0doCax50u0UfAV0%{lKSHYYB+t)=_uL>{>WB&3QB|WXKt=HShq0qKVC}J2Pq@B&;=awz z3`Pr2!_`T!dFny%RGaO_DYcQ~Ypks$0_AEhhCg^S1|J`9teuFXq?Vr44j#ZP1p&w& zH7$x=8h;TxGejcNYf=iKPZEoDj7PosO}3AY;ONQ2-Ff;-)tn>)c>!lM)_OpJcM~Zd zh>;Mz*M~D)R7C!rA!J%S3$PVt%*)>5Z=rdq$Jib35&ILb>gRu>AWbmrre6!Tk_8Ak z#*8NqR|EcL+omDF$W_cD-6wY{6x1CH3n>UGS43aWE9Pb1=TPcBU_N>RQv5>hv-EMB zq~PL0#`M*9#HNM@=Loy6xp;>bkdQ^|1^_Yu+o^Nf+b~hH)#@ngL=pKYVhMSqu7-x7 zI|L(VN9Dv=n0^bo4(pl{xt$V)co;5!CLA>u#@4~e4`5Vi%0^uod?c2Cz$gXic-#-gbOs@z z{pEJSw!(uJyux@0K3ZM}EqlmopL(`H5mO@^+W5r)&sFD#hMDB^v$MKuVK~m6l?HS0 zwhoYGjjxEx1HdQJTDJY~)6>^NZ61|dIGX1vd*AERl?K0m_OE9^5`{d~64N^c1Rm7C zg!Uo3@Ay`@2s>I^OBF(IOU3NiojBvx#M~k|DyAbTg(TMoUZk-^V=gl;M3iXK4Ov{5 zN|p#dYtBm{?eA=e3k-F}hCJu>9qO~pKs*9WJwLKq}mxT%u5Av z5_O6uyL~m*mX)g^+p|gJ!bRYkwUmBPm2`dtq0u=aO9s69&Z$oNhp}G^a9CXozIM90 zNv^arY-m+Tj^Ta%LB|w1^Y>=%)VX`9`Lj2R^!inqAH$h3$<(+p|d48 z+zZsUeWfyyjjf<2KyNF3Ox#oNB5O(I&kDyFxeuCKT__`=q@2=}@iw%^>iM?5Vym~X zBX(uz92tUZ0R063`5z2*yg@2`^9H>P&0;`69(V_#-~WggjP{1FD%yR&#t{psG= zYT)&{u@44=0^JaN0K~|npP%~OkCDZ# zjOJrax%v6A#tVy8H<78)o!-h3GBPNX3s`*)x7K6Xp3Fr#`96)6)hsW2pqdaON;|gLL<_@qsxWoj?+%acAwke#Uis$wwmx7vN_@#L1-9j?= zQ`IhayLyVxsN^W-;)!I?c$miQdm z`EqU~qaZVXD|EYHrRxYj!>}SI_ODHXjToN!)&09Xr$)~g6UdC!xVmgf`6?vDO%3eh zZJA2jwMrI?#~JB6%s|>x53*$d1QHQWIYeDr5zTb^uNE`r%Wv!a4JOot{81M+Hvipg zOO^<$-^hPxBBb<)4m6xdxSFGr=ea^J#k3n?n>(bURY*6n5Fw9aR>^Oy`b=!)r0h&j z{XfSwD@11y_BEiQOQpDnK+3v{@?>3;xhSO+7n?K)mod7+V2HdC3K|*FP`V>U7912u zjBZlXqlxuj5^}IN;0S2+-sP#AIs3YYO6s)0RmBOft>~PV|BY^#b6sX9F*f@)t@Asp zr@}uGCBuwPN%~it?{&VSDOt7;0+p7z(;HhLaHUtYQID{uhfw1X`GF9)u~pnK{?Luq zW=9%!wgrsH{a=%@W+RKg)OJ@1C+m4q@#V}R@QBF zWj9Mv)uHzVIz_fqO8-h&atd5b#E^=Q{b=ft&1LWC(3 z8$q^=nfnig+2y8DUYJJ|rlx~G z)=Mq=7W%Hc+!vCB{N{(4pNEH~dxAd!jQFQMTE*XGP2H%mHa<9yGa5$9#nUDwaKB;J zg#EU?HrSAJ4>Xu6Rh7bB_GM6^v?hLFM(3QzDB5UXH_t4?l#g zRAek|gi~nc0)n?IGEhyBpUd{HYJ@vUA}Xk~3;teRv3wzV#fBlZEzMYt1K(W$G|uV% zBWuQj=6%^Pw^Y@Mm~@8=P=v2mma4Xwk|p_kkgDmWx(z?%4YAa!1yRc+J!M{|Uj|^& zJWDkM*2-Bd6SOpizloz{zC!?zti9;l{U>l}0QFC%+2}5aC0(HS@x~Lbz=RxxjL^zZ zY;V6oYpo349b8&+^zcXv`Sp46LbRpz`+nvD2;WSYjLi^Ru)Rd=APpA|rZhf!4b~gm z=Do&5vsU=|2OeF>A6x9m&A>g)?G~jS5@S61?Q$q?E57ApGpi0IZYLY&odcxudR?9f z^_j;_G?uSl64@N7v^oj|iQ5A`+H7(tz3TXW>FBm7o`J49y1Gp&Mo@_+;x#25 zoZJ7W1<=B?u(-&wB0ha9p>@CADB&clEi~R z|F8FiuLX1Ucfv!$aB>d4*7X6x7y%M@v>%N=U2<8xeM6CmRPoF!tooXjHt4fu+TF%I{U9&0BzXW*jva?UTC`1{tzjt3L+tPD_lx=i+h!pz+pIcfz#;bzTLcwc@?)`9QD*tG;xh{*l8__mYD9nTLJpPJ^^a;b`$3<=)xY82q42Y(1UoAPp#F z0N+Fz*IZ;f>D^6XX;$cvdus%Njc5`D~$xsc=QI zkphcq$v#x60y*=p%m~X4iv1K;Mp$hFdzc)sd?L-GqC}n~)Qt9g52|6ieQ!D&uFn(l z2iv_U)rP-iN-@VbKyk}{fX0D~_2UVJf43`?=^k#XWz%sd9FFlo;BD5extv~S+PM=T z7?&~QyxCJf-c;>Me_Pb2z#g!KufFMoVnyO{9A9X}^qUxyaMU{&dPoH&^ron}=GeYl za!RH5*L1n$&s^8l4EaUIzi;4FkplnX7cE7n*hSYkFe9R$D>_0at)B66b8oj9X|-p&UZ@e9D3|x`S#ZH(>8(Z19ra(W{byZ} zY6EFidV-7C5V21!KwzF0t7(3+mnzxzIsF(@vlgZqP9FOgg+jDtX~+`3%|%<#V8n`B z3U-X_RZmls+B^!1I_7#DXkm_zgJ1-`dD!&(wwfzJKG4$Dh5R+zVcP(>D^VUnRxcZ` ztFiI!fALM`=IK}7*reZ|l?sCRirI2NICA*0Zx z@=Q76!(S6eAj{n)L!?O5LndSG&^gtuqC_N8mg6M;gM3w9hl0@eiAH|_g))qV)|{rIsYHyPeAFax3*z0iVs z4W8eg3uo1FiVRx$?1M(1YYgG`s}fAr1uQB3qE$Z-htaFf>j&4YfG#LX$Kk>PgnP<3 z4mHuaiVqq8<|hB^vlVAZ&hx7EfXe@Fy3v+xK)r85%;_p0WQ}HY%eT}Ppdq^iLWKV- zM)>tBq{9&U1Cm2*G$o3$v-33s0%_@aww+VE11S4yR#~XU&R`QhY&#_)J9Qxb2pp`z zuTNwvCCf=|Ev+VF4IvrwBC%ify+0AAeyf?u%wic!pA3MV7iKrC)#P*N%HwW(f)m&kOG-$I^vGEym^n?+(r0MCo*8M?1Q@}}GCNyk|n!eEUiQ0{W+e>~zc~{4Y7&G*D2TQg1EryNMVeM_PPI+otvempu zakFa3iM%9DTa-xj-2QJwb7!%^wno-HOlfY_uz3ZkI-}@L*^#=eD@shMRtKkPHI8(+ z--C~T{{?NI^3$p-)2AFP7AhqDDPJ}|Vk_@-U|Q0&=>T>mAvM$t98kCk+1rD$f)7YK z@kF(ZiP*FVTuW-T_3>FZH}cmpnbm=6PemhPeG9EouRI)+Vu&z;WRt%B?eaeJ8sp?T zZct_LF833GhSLXDgb!u}YS2K04HngcHf=0aPl;%m=r>CA{ecM~XeG)Cmk$Jtr(?dB zTXI&xv_?fi27Gx*E;@gnM0@a%jE{jr@{+|s3Je+T3qgYEz13Ci8{658Ob;Le0l*ve z4^Drng9Cibr>RPBpl|@vL_lR`NP%P!A8&6krexE9K?ML5{^_=*2h@6~z?VW#)l&(smo5-bttPL38cM72!ueRqV%4NiC)g2wJg zZuOwBRZdq`^KEj$W>6Un3&41Rj*u15e!CEI9J^ewui=)LTDihy?zqP0E# zDL1(M{ZuWkKdSfk!GW2r?bMtQP1r#qQo{gn=OQZx_ z06!}{D>`BdjN>Z+#+9Q2F!)<%U6|tA5CJd(k zN7Ge>RT-pVKtMu}mPWcky1To(yStI@mhO`7?vO@6x?374X%HlK+(IaK`ZO-}W7PNlj{jjTJic0qUbU^fXv<`w31{zDJaKJ|GC4ny}1E z#hJXSU}X%8OC!Hq^j!>z9d;f{rItqOOfe@X=X6h1gbZyjLQ&4456!3}9|LDbHGrwX zGzNVB$2qJMiiQUd^fJN2O-NT)(lcJEmK8x9VvnmOxCff;O?Moxv`8)KR^gZ4Dnu=l z?@XJtw93t@n%zzcFJzR>3B28jKKO;tP^#4YjlmizYiNT5azKvTENG85{-oTI7I7%5{73T2TsJwfqxPcSyvTU4LjXF+aMx zDm1Kw3b$N2FPAGr<;yVjP6};Amag0B5TCy0udqsxA>TkWPx-eI`%~(%#@O7SS*Hr3 z8<}pn#*v(FEJ$2`t4M4^jCf$xttcRMu%2%ln`sp7!xFN2UD1|>(9_oss)o{S}(a_ zhdN*xz@jY#&6s9L`}aXM53m*&|CYJi*jKL1j_@OmEy=yXS3j%030_8p2qz1-v$mY9 z_8Zv33!lz9D578O>kEt`nf>-C!b6KP7-R$hEcFA$WejvYZ*HAK(f8ZFR|rfte9}-_ zeOQ=>))FaN6>nb}dvx`eT$r7|Iz#SQ#Vx|IOY}ngZZBKSE`<;+?#Yy+iJ3>e7NO=_ z;^KE?>5o(=vr|m`vSdCvLl*B+wiz+qCW5E3ks)P(zMiW5*+t$T?H3J-f0W$E1SjE@ zc&?)$7v)0n&N-`*w{JM-`vfmCY-%ZVHkX$*_4J-M&i&r9!t>|GxZXfdRPVUqT#?PT zMh5u_nc7;rIYdgUppFe5o4t|GSkzsZ*W1!pJJ1UA-b6fCZpn;_WjN~Zhq~irkbN_6 z`~{2Rpz|=+rl=ma24M>r@RUpohU9;p-Q2i>cw)c2{P1Je*s7GuzwW zN)NFPRP^BREG{ig-hSm~o4e3WU_s*- z7P=P%7VBrKCT@pcix^+LRF)7H)jJgt_m#@!z7BuHc9wOMtjAQ@WSSzOcP-i#=&zn< zPWd@a?#X)A>r+!aELyV$<*Qb6D}j1fLf`ZGz6SCvJ_5wAGV!UdYK~vBt+wcw0V@1}bniKe8$AT;Tk1-Fmj)P~`X*Kb8)yS9&w1Lf$yylY?!l{pCXbbka?LB?B?W9_D!m=Thn8|pU_pzt1tN1oBBIaz z$uVD-XOVi1W5YepHy6Gm0G$P>F9f#})PcJ9ux?tfpxAz?6~ScaECj9{`;4x9x}zQV z0pyk{E(LN+T3u|6k^KNN8f886X<`~fLpGz7Q?a>xbw7Co!DOse=I2h=yevwyPst)d zOvUO(P-63H4tJ{6nb_%Axg3-U+d0Wo9VX<$=xAh1$}%7L&lTa5Et5hd9}hl~rS{DZ ztb)DbQnB6`LvccOO zz;Nv`A44Cl=U$n|vr%En0hxIX(>53r5wl_#nrmqc6OjZ!b6@iNyk?kt(b4AX2 zf{XWDRd&$U+?jWsk7AjwMs472WJDw%l;$zEU8jm5+7EzH_nefeIw-=s+dlbBVL2~# z|4>(Hs7a8dEL5zzX2M$pW$E2~1+?BLSF9ogz zG9fPY-u7&enPCiU9R()y+vywJp}TW@e-NgQ%pzyRC+SF>o{h1G$96?=GEM2g-5%OzpD~nAa)!}dC$JIwoOXT@vY}@PS{3raT=r`XFO9aiLLf_U zS-MxKl#0xICOdW;zSIrHNcNO0MP_2~aBuH4((RrekR0pit^)LW>P`HqTTiA2IZkL)KtV~Sy*bG>4%ahzC$X~G3`mio3w91CL+ zx&mB_GjF*VJ7OXet51<-2|L2yzbd!y7X4R4s{To1h~~;@;UJJkLdf3(aI1n3JaIrN z3!*}iiq}9ZC)=nWxX+h-pf4kC(N3kBv^0=Iq|0LOwBj`y{{}su$-J##+ESCtlR{UM zMC27RKUsB~5-?Hm#UHIPakN6M9VJ|%cH+BKWzqIMpu|?kj%VV06}Obr$|x@-hXxZF z0x)83FD@>CO*xwJ8$>*4J^?243t-#+MyN*F5s;Ls=-& z_^%LZ;3oa_{&ib`_w!xMblY5kmj3MD(ntSNQOUW&0UwnlB&~m5$n9<5M$u2`W?-Ma z3S;V&mc0j+n~l3WTONZGgy9ewuWx3t?hDy3pdzbW3&Or^o-FadKeMa zB}i|=g?xyT65vvmt}9zG3!5q1%y)#J3a$zS?ZImICULDF<~5M#{cevJfJpY$4*C6K z;=H#tu6G4gaPM^PPhXG(z#MS_xV`XO;NJk{0H8G*`lh(=E`S7;3qsiV8QIfDL2!yI&#p7r<98Sme}FBSHA75zB>aig3EUugOJ7~#pc zJeM0NZc1k5MBc`tPqhbQkx8W0vPStdb0`JM`#U5_tW#4{Lz^lTqXR672i@Zz7(Yat zq_F-G^{fLOOw||7f5VvemA0 zlU%SOTqub>^xodMC`7unn2fv;C@#RN0>(InoR&gPE`}>aDvz&#-2ui-_zf{Lzl%+t4;Thj+qsBB%+x21Ko1Wy8P7QN1bovHeN3SaqN;FKF=k zJ$c&L{5afN{=S1cvBs!?*|({8yFeEd)9>^leUpZO1De~Jtw*Qb^SH{5CX?cK@ARCT z?g^%J%Eycj%eZcI@sNv5FHS!)(&}ASew6VuW-(_Woi{&F2Heh5E z3g))1C6O!GY@M}?ig(j~WZcwf;<+)(bFaO=8f3ScfeuUXn$IBDGhGK_E}o+?e9H4Y zR%V=Kvah~(r#LYO7Z>q8ZwXiOcPM}Ua0Udj6;UsW>V!xqRfV{~VsO&881iZ-wq{g$ zO2`?i#mC4hVh`GT!|}q1gR9P5H3FNc+Bd6OIl+Mk^K}ey@E&&_W@ci4;hjZY4q~lkCRF}lxt!PpMyg?8)oLJm zU;TVp^IuzCRnAT~X5h?S_4Hp>O;--IT|5d(V;h%mfme)hZfj~9jE2DjydWD1t~EtS zHyEA^@VLFCI>{sD0@8^)UO#K^Bz`KXrFRo7msmQb0L_M+rbWZH-?DKcTllcWx z09vcsl4+Ajc}cww@f9(KFC$u!KvBHix+Tt0yH`HGw=A48w5)RElEGC5ly+Fgp-NM zn`Ke;Dc>dud*~#!@QCR1`vuQq^m5hT6zVOqz4d`ziiD7f9;K3&Gcp>c089od*Br-@&Ti74QcX6g=+#NCRzy z1oyEF9c^t9`B^)~*O9m1 z|I`%qbp$6RYdd*F85O@}E%)!c?4wf2BlEh2_!%ag{056SpiJ2vooAc(YLdG_W~fp$ z?Bk%%mqv=8rdU^XsLb5MQVBkH;Re#`8#&Igku=i!={F$V8WG7bsUZqF;Dty zL*Bdb*vM=xIEf!Fkn;DXRBm`d(lm)0@7l)eMVjXit zx(z1+RSN9+Yj|t0#ZTuWU_bORR8>{6p7jwvRQ@q5HgU3YV7p|pA6kAVvx~|ru9|Xy z=33z;h%70Ht)cWP7n{nTAe~uK;@9~lTwN#bXEbr4ZZ-Aw<2GQ z6c)z!ia8HzL)3}nymt+j;_@GYKhC(23-~?#0pr*KSV4arL4#~NLMoMap!OtRuf^Go zn|ymKF=|(BRaPiBFYisYnnWcGOz#wzrCXdPXPH-6?`+z@cU*dRI{TBulaaE0{Wg^P zPdjSlb7Q;B&l2I+ZjiGRhW5jzqG&B`-l0D-oE(fzWa~4Bo&-O9w6C`Q%1ZY~z|3GY zc*9w_nB>nZ{sTtX#S>U3&0mLG-{a8LRO=p`jMr6NvA?|@3a<8J-hQGc(KlT*`~4PI z6?!p7Q0Eam)!nVFY59fv!GpS4c4^GXHF~XaqLwDQv?CnkOV1!fhnthL%&rsV(?owd z2Kl&}+o^EXNN>J(B#)nzL9s=iJhUvC)e|@LKG$Uhw`5RG1an$P`XK+NDb#t6(CD2iw;8=B8@Gz`#UYD8ufd=jf=37<@jC z@7=-`VlEY*f2X;#y*j3kn{U!r$@|yWML>r{%QYa4z=1pW>4Fk$o+`i%$zF+w47;m% zwkl?VfDa+WLes2vTUMfs%a3MrdUK=4Z05b=R0f214y%+?sKn#t~kV4-~02Q=?#Lt@_0?9x+B1@$(f3Zat=?e&|etpV&z5b`OaQDcxM`gmIKM9vS0rV<7Ua>@b zcek8))K`j~Z*_G6E~smkR#uUC2or()lDRVufQJ~8s^E98_J)|xr%1l2%1Eil%eK!@n^Je3ht0zs4;Fm!U7gO?A*#$Yk9}`rjmG+ z+?21@gyo4;|JMSb+Z1W zItYk}PU0=?9q53zmyh!nWRZjDoOv> z-9dih9jN|tcsHu8qr)O=a)%}?t7?%a;BQ|gig6Cg20$Lp^-zb(LOrJ_X1=Ww-xX5J zRaWA7Kv9_;X74d#mZDP3m$BuEg6f0Js#4F-lMPiQAF3a<_^6 z)uPVsN8%@Sq?n_E3y)$&EA@!=d)6K)c%`wJT2&e{Giu%^N&_pU2(kC{i&5wpv#ROG zl$a*A2K3Z5?oXHfKgzw?@iOdgRKv=9v3{4BS2>77=R$dG>n>+|NJx*Iwi@X365asL zm)auq7n`~bLVW8jPHW=x$Xh8C&idx~B~_(i)2-oC0l6Pt?gtUfFEp77_-R|8<5PJ! zBTYi{U&!bhP#03(qeoQTKY;T}5Z|E`>%^3MQ;d3I`;u5LJYq17!l4_=OKP)6xXNSj zzKZ5NZ^?39{-K~ObHV{$o0*s$je1eE@OUcIrLYZuAId^TshFEZenNJ92MIHKTjvN*VYt{Q z%W5~>f>Jvogmvv(>sGSMOao_a(Epvnaao>MUb{(JSauO5DejHt9LJAH_@M(tfsFdx8lLscTa(Iz2mtjynZbzuf=O#@z?T*cl z9-pMhTn6gE+_h`V`oyv~j&oW(Ox%3Dy*y}CoJO(c5V}@Bs^#uMJx^47i@SWdW%fH^ zpzvtYFR;XN0p|n%#%<;Ecayg4t*jUsNfp>3t_+&f)_{#NwRa&eC7ix$uC$Rw3Q9*G zjm#w?)*Q{08$ONK)OQ9N^!jmqo!eAp_I%2A(G6YzqL%xeAw*KfNa_(~GE6Xj{<=Z> zT1u^m|3*a;>LXtpnas|wmuPR;;^@ATO~kjFte~VpD)Faw#sY|9rYT*QqICqZOlUsspx9<{4Yncp%2Nfu6odw=xIBxQ%bf}BvDX#mP|hu zG9xFqb-4M7tjAht$YN!AnUja7aVD}35Pa%{@y>7af$KZ+ps;mNes+3LbcsUbi&RPp z6_;j_8uPR$Q)-K_hg?=;{`bt~d~qpOf!2mS@F4Ejkn{lSO{(;lL*T*mcXdrZAjj$j zH+|HbCP^^p&?B1c!{|W{kHxASSW`5Kz;GfOI`2)-m1HYguR}%zK>SoAtxL#^`uwRD z?9$5{M)&U=*j}j(X5S(7vyO~t3bbJZ3aK)4b-fjKgBkhtNZ^@r>>e}Fg8JKWLLI+R z74QVbG4XxA_XbyzNx!R6N|3MAVX_x;8=i>y_hS2vAHNAAn%fMvKek-@$4^ZO%PqCJ zKY2WUf3%s`8O&`<2W!@_oXe{OvLr`@C<}|nJ30Ez4LE3}ZNH^g)GOxdlB|CGKvb!y zMe7RT0dqmci~KP7B~u4C8geWt+hDi&;MAq$n|;-%2(5WOE-tBJ;?1(SF8I?I>aPP4 zXHYRE(Lu1L=~yarfp?nMNQh~AIDf<#k)=?vu5o2mNI8-Az#&@W-d7S;}Y1>@7m>RZ$?$dJgk@#{jmR*cBb8flYp#= zE!PES$P?8NwOn!YDF$r>w31#E8g!11Aol_q#04bMzP|i?<>BOPYi|c0U#Fp>z6t}- zRs*J9O@n_g0l@!*zZUnJct90_113u|3?NUy zu;iHb^?l=7p$}zUReG0`C$T8fsjzDz0$bzARJbTcj(qo>Vi?y_E%M;l8fN4VK^0ec zxM+oG2aJ?p8Z>z|tjxjQ)$8Zs!S}7q1>PT>%M{OekiJ4iAJ#!9JxpiFms}~`X)CC= z3u;R?Lq@??RySCJ_;8adI zslBjMcO$3c98ax^7Ka_bmURBy#6m~B8FF}0A2AVcDg92q zOVYFu?YQW-@(zpl!lA5~GbL}p5M=bVswQEy<(*ZE=u+@P^_NAJc8o&y6efAzkCtw3 z3!cWPRS1`SZyG6#k2k8!rM1~OHI3(Og!BceKN!D(e*Aj-{B8GF4SRACgp>U8=sUR~ zp4PaOD#oyPWAhVce|wuS_-Nc$mK>pHGz&_V^y#}7Y_m;wUXjN@yF0%^TzelM9U`2_ zhp>EJNkpXDPujFXLcw?324gOi&A*Ph3y*%Vino4+=o@cFbDesFk-4krqkHtN<*voZ~X%5MJ%=g?K;`xAS9r1v1K#A^!QF9cBftkl_Q`YH}>D{;zMO zGrhHZ)=}wa|6qZpI>jY%ANKyK*x`X%vjyJ1$hdZ6kemTr`NE+&Z7pKzY-XYRO7aKa zzYu|eecN~RK_e|fbE&0aiLKtlAiqhu-1El-E&NhE?|dS@H%#wRI0>#D zTxLnG)h2qd3;1EkdsX_<)c~lJ9eDt(_NPJ9o~=gMn|Zp_WKc}REqqiZaR8<}#T9&6 z7&O-|3Y^vvrl6ck>a83kX!gqr@P=#1NKeN#$8UN-zV`B&preuEv`!UHrJRa5)Nq2> zB62FZD~*n(w)P|A>wb@;&w}J(t)>__aX0L=Bd08RTn=KzFDh<{W0V3d&4*qx%N#^eKna*f;dq@E9q())!$-vSYqJj?j zO6EU235@D{dxJEQGxVrQI@+3g&>Hr@f#US}_Sf_DDQAIfJzP<_+E#_sSOAo$)SY!k z0)Q%J_70$hrs^bDEyhRs`uf1E4Fm&L7&)_PRiylrw?%F2VO>Ie%x6PGVkM*A-kv|8 zQbZ1A3rSbohQga87jJGqj4c(a&U1$wq}3-Y7vL#07X~5yaZ}o9>Wt{(T4)ngSUl7f7S%S)=2@FyHpP z-oL&85o;cx0|5o*3*c^GO;0h>$A_OlI$gHN^Su*zJ$yBFZ-NE;WmcCLaHIaq2KdnP zX9z&bua`uxsH^hp#~@L$wI6fV8KISC`cDy+;p@fw*L=~wIsiuTdR>7l2u_1;$&%(H zR7~=@wG88&ktReA6Z)LayA_O27#UN`%_h8*GLi;zgeY(+4qpfaYJ2atPw3%B4@x6Lf>hml(aQ?=Iqn`?;DMCyRehpmx=6WtPDOLiGDVQ2B=%(F5oLuB~f~CphJ7t#Bt3+ycLdGO~_{&w*B%^;X z2O&z*IVuvumnI}v9X?&})frUpnii5NHPfAjrv_i9!Xc+Nbcnk&=RHma<2(G2oq|rp zj7M|w9I1g#@G(~KzSa2iTxW^#BUpn>5{67L{>$!E@Io(-Ez3NM_$i}zL(xoXe1X># zb7=zsn0v7TA&9R>2I`3{W!hP?%V6u=fO;HDm4xA0NcRa4uTFmo^<6JIL&gvZH@(?w z!j52KqO{4047PVs#crQ&DmfIl=V(jI7vH7ZvL`52HWsp$oamZY`F>$Q=Jz_qZnY?b zXVt2eB=r|YlzoZXX#iAgZT|rT5O~eZ%z!vL=#VyuzC|nUZ=l%v=UdpBbp@URbjK2^ z-%1@R&8+IEI~$rsgEO;rWs=3Vg+Addh^JIMYRx7hSXfv=O_c)nh@4JJ*m|_xK{##PyP^e_5t%Qn|3(l?6(bg zhp`H4X*cs<1K`)OKavfjQ_Q4etv+Br-5R{QmHtu>z8JSF(7yJbV3CTSymKl6jQR-1 zw|lV3Z-{Q&c3dq^aF=zj^r6)Op(Yrj?PB8cd^8)0e?WXQg*RhlwIp|Ig_TiI?e>t} zpFg`W2}-I8Pqlk*P6RLT5G9@euJbl>MRlXCAP4c6{&e_`N>oaQQ&^^lOGO{|1X>4} zD^q1Rnp64)<;$w9ZK2+L4>+I3Y;I@>LO3im_r5MYC@9ELKhyBjXhM0<>4p%}=XFb@ zwR`|q+BV2g?!77($lx~tw4Fa+pMToWSh15wOCK`14W;Y)+BUo^<`@l^^YfUX@Ij!< z-&3S|->nDg!GSIR=;&y6RykRgU8204xef=hxGG6tR#CruN*ko|cMnQEF$xdUIMUUtsxxtdbSCa1w-BL0`hXq1ytb zb13LAYzuLDuTO{mw;KMKbjY60h=bXH@h`sLo8<=y0eR1-7Ow|CpRz#k&GA3PmC+C= zM?kaTqrvNmKRNzg?aM;XBT#Vg-ho=Y&oUzpV9@>bD*{zS;N6uzI3dBGWRo?{Oo~Bc zTB(onC7WLKY*&rc-<^^viq5T#u#81@t>yO&=lm4bkR_~S+$luXzg%oR981p_>S+vQ z$ZXu_AlcE5?#OEDb4P;% zOuuL<9;B(3sZqTR*K|RH`=>6R68)~CRYIA)U_Ss#6SbOCsP|2vwfxN$t<^Hnvq3zC zWf(4FC;jo85=E={lY&x@e%o=vyurzLGHKyHs4xWFl`vnh(DtDAzYO+>T9G?A0A5q%FM7u*Gv|A@_+R*?8e? zV8%lN1~r;Lb#BNR=Ajdk>`~-{Ac}waH~-WcnI=yc=QDTB&CTjPTRao&M9{glm~l5L zGzcGc6)~f9qp)pLNAkonf zli3e~M#k|H*bf-EOP#FLo}W&I^KegDG?gNvF)ClDBDEK=%u^Uw9nTZS>AM)I$?65x)NA6~o2jzJ=hAiG}s zd>cyg4i(HL>)E8YwC`@1=x-JsKBP86JW)BD81h8R88tVg6?>1jYNf-Pa5BS|fY7Nf z<-_Rs&hU4bRdoFWW=hF|}Fa@d{IscJb1L$9EXcapDY{ z4HWLg_%0?U!OuA=%W8^&xL?<#mYU5hExW|dQUm`wvYs|754LH`Jw-;!-B)DB7|WLn za~8gDeGxF4GIS9UgnziA^#2n|kkf)}K{r3mO6;zyub-OeB9e}Xn+K?J&fPCh=n z3R?om_UfzNOc$8G+h?sPZ!#Bh73HFq>4rFQ$d0T=GoA=uoTISb9Rr_xJKRa2{H3;|asD zW$jTk!@I@i0_MTBbU?1Cla37UcV1)Q5r3VhTsnC8NxaOxwPB$TqxrRMF({x$N8Y?4 z$R|ef*=k8mO$7)lZ^cmUlTOo__<+-TgFef4kyI!JGCJ3&h9%$q|0E>D|M4z{MdOGa-hb(wpg?$(9=6q@t|ob zZ;)&V-rGwbkLkF!!k0A}CUq`a+#F2c(TCf~p-LL7HFr<3eoK50y2b~5YQ$=YRGxS% zbssPe!|j~1z}pkF4bp#9ai{!d%IVPXrpBN8COOEw6JZqXRUX*?S-)B5q3r%^#kRD8 zfrn=skL=LTo<3KlEE^;LEalUvw<~SUHmxBx=}>X>{V3POAFamx(REBzfGJ^v>nm@u z#*CWp#a18KTJ7k{=77`-xKyY7?i!z;pL?Fydi3=5|67eiNq| zH}W3f7P)+%-9eH7kgyUG5|&&AdvM7xR>$nBc922X6RJLwJYVZB*dEcS0P$Pj7G#f21=h& zUA3nSe-b$(L+$#Ug5bP)2;2*`Ts-PrNK|==^sBN+ioeUs^gkBjX(d$x5}2jPT?$j7 zqgwRa616~B?=}gfLIVU*T+31RNtHuZ0S384GP9u*hCgZyGnbhaG}|`QR-uPORpU@b z@qG|vkHS=+ala|K*2PEl1t5WZ4t4j}0Sz*VT zn8|sBoVnsy8#7y%A6vT^^v>9})iZM*`cx~cM8?0BWBMT?9()1cAt?R@+^vpwHihC} z@hK6PmKQEAd6RE^M#Z{DZ_eqwq}typJY8L(HER)i`}oj>4a&VyAF+ElF?M60L-_*4 zMF7)JX}QP-&A_LdAo#}WO~v`j5$+gnJ9A2ZaO_STd(y}q#_6KCOs43;Ckqkpg)r#Q znBI8{9Xge@?a4;*y}M69*}9+fV&O zHs<}E7OL*=uG?%0Jq4AmnWGX(;R6{rgB$9?L+h$|mGx?O>+1I?+he5cMfaBU;^BSF z$MBi`10!qK9~k-74ph=g4P#De(uV8YjF=Nq!Qs1$Fc~YyR^{K=La1(ND3cdOi2X>n zZ&<}F5w2?WsJPhUin@HU^oyi&E^036C}c5*V+a_tT5}=P`?JZ-iFIRlZ%n{jA6_ZA z7-_YENpv7n#ZlZz3g!PL?9$do@OA+JOK@o_&4O3+INNe&#zOHa(Q_A2zhxyK4d%CC zA&sioIXHG9K0u42b-_fJUh&8|zWsP1nViJk@I{y{5qgp2>(J=4S=t}G@0-U945s>t z4K9#cymVOJr~vfci?9Q?Xmv`o5);cGO7B8Z@Gk1*IE34%m{ww5B)SxPs7G#f<=}y zNU=`IuMJ6I97NWGFYEouqz9SOaR?wL8AHish-zldlsw zwvvH7T0c(Aq_6JLo*=-AJ~mtaTh?De5(tS|65Bt`%m0RN1HT9I9xou{@`erVoMzC6 z7aHfM*$eoH*R9O^<}Q;Zlwi`_=+GPLdvLYQQBe98wZdvpV?vy0dfXM|n*Ao%I8_gN zT>MUHqR6NC$j>vwp|Y8g!mpHwv#4?fKiXqE5+h!+E1m#jk6s)~YiB=HQ3HQb98va= z(kQH(jdNgpL(lmhRr3qIM9joq+0p~vTEVIav%*iG>j}^u2Ewgblf*TXGr?!w$8&ns z*9Uo>9&`q5#MJOqn2mViMB`)GCU3eisllfC8{FzA+WC2SI=_AUjY5cz?`aNO6yk$+ z0(D^h71POWRxsO6OY9zJ=lD>1sH8VCTv|W)%eSsBGEX!c3R9MPJgs|Kq_NG;Iv4v{ zI`g8R2DJA5aP%fdJ`j9$=LZL2->tZ{;;)r(|T z2Fij|aRjGCN$C(7Wyr^@-#FnqZC+OT*BxuuP1?>#x_YK|3>msa(9kWsAk61%x{v)` zB;@&A_Jb8>R<4ZJGCR@Et#{=28ZO7s1EemQ%OZYb!Ju%1EJyGB6|D52t!2qd^0vpU zA|!&wymqf9*W8G>y*IR`%&`^FqJex^9M-_MNth?+O*hMBIh(#^RsxDqOyycdiA7ut!NblyMW-~xrX*r$x~_n1zV+UVfAm{ z48;BdhVeUsmV1VnsiLl{M(%XZLQLNZ(>!DL;J&#BfT7U z>*KrpqL%W4G77VC+(H4@-sEx^Yato5m;71KKV3RtT{kr3;?_eWJ`qhpAXnW(qO-`0 zNiVQsb2SDorLx4D$AA8$&teTcg0=)^DkR3|BF5*-RoQw@%mTOPe|VGMljaCjjWpy0 zj(nnlT#AEbS$lAGG_m2#xsABZwDV3|vwN8DULryDa9nbH=`ak=jlyZfumy<_b!3#^ zlZbQUIz(xK#Kz^FINK&7l0R?S+4nEFbOJ($vXN4*YOP9&4QogN*CwkDx64UnDoIWl z!32$;p7~kG1C#s35aj<1Bqc*07+d&<(96H!NeO{vZ?`9GWA{RJ@eXZcAN?s$RZ%{W zFAF{H7!Nl&#Qp9EaL~=NB{hS-z~5^QJ=McmX7+N{azWCpiE0xNZ>TVNsr<)L!{b#& zJ1FzHQA?GD3^Szq;9^=ZvEE1+8rE+EPAsCOtil)6MvSllP>O2>P%E$3{x4Ji`Z)Zb zzWW2Sme1{R%9JZDpp##+KzTR7??R)87xZ;?(}P)bwzGYp^FZ#Gt%Ji7AEeOr=i)A~ z^;@(3cJ9o$Q_ShQ2vTNTv@$UP);^Uq)}#{xqkGOU;HZf;FTAKW_VM!rQeDVPI!B8V zTaV8i;rD^#Apfirm@EtGpS&TDmm7AaMA;~mL*5Q8vJd@^e9aCqOyk5wIfRAHXjtm{ z0ND#r5|F$Ps0kmbPjVz5O2hnRZ;(DOC64*|8or%EcvWJY9`!JI*8zVbTQkDW=l8UH zAru=MMDD5cJN*AzfP-gnKsJ&V%;Is2o_`UgUFTgO__!Fs0$rjhP)g`M*al6~F*)IafO?v#Ez3uGmlKP2>tVQbcE1?FeD}i(Fi9RK{4z7rW47kuyr%Q<4c+in& zkkGSHHd_|l!1`d;%ediPe~7j3Us0pRCBhKP#~nYtlBs6X+WP}7HN=HRSWY_spnyTm zKAe4*I(A{on`}*7@j&Lk5xVXbA? zk%d%+goA_MN%H$$3>xfvl7}1W6L;Frv5?cyiCXOFUKAWy&lQRKjmT({kz{OKHpB+{ zH1kjhDIK6GT9K-I{mLw=F@ zQP(bmQ&p$WL1`|^jXc`5kCu6YW3BGtElK3#=$#BPh;f^E6GhIdb1^7|X=T#51i5An zK4rMMzhF`Vx?%u;m|1|uZkypZz@?;rk!I}>wk+P(N>O_)TV>&1L1U@>JvT#uHj5sk z*LF-mYq)}lJGMKbm&r)gV@*ti;7h=n$&hvVC)VUoPOgX2iYIzeGB-)ya*X5!&74Lh zw}_%A&4?4Ow2w|T&JNzCg((XKWouak^xCSMqnpw+;xUB5E>dSJv_q0lVWcqk<@3G*&;SKx{ zqKR%#gl@sK?x4VStP74`$x|=qdxH!axa9i1R3gUtmph<+IPM$i%qADW%%UO_Bgizc zP92uW8{S59#4SLStZuGp*Bc2Fq*3W=S$by&px_lC5Hq1BRF)~r&2|q)%hn&UP8`PM zzzlhIg6dN{%A#n?`fcRsKiU7=|8_xR;dhDsM>xhiMIg`u zT_@v%;ra!5ILa$Bpe2ZE4ba2A7}p@&p3LF-7h}Pn65vVI(i#~82*`h_As|8&Y|aMH z$Do92pV9x}-=@6O^TI}YMDKG2P6Tkd#hqh0tgWr8G9=`3!`88+20Rk5XPC5N=5aY4 zYaFaMnyA&0&irwRq5+E%3=>B|pp+?i(m{{!i6`C|-KVOH4)Mj$+1a^r5lWD*b1tvn zSh9CLA50#q1$#*dZaabESCOw<(x>`KtkzI&VM-T&ennyJ#DZ=`AUZI-(iUV{0=W4~TLi9^hh9%~2OlhRWAm!>kK);)p zdD9F9O?4%yTSsR*mLSF+>k?rsIc4E+IZ)3yss`C4PRC{}I!$MQ`MAL*L283Mm%W?i zdt^$T4W>qBzPGb8l!Tx^R*x@ep9VxeIMiG*i;;lE7bqs!gPI{7iXUUT*-CZA9^<|` z*!*FnX!@wAu7wT+7878imBC&&ESKs3+gevjeV~YwHFILzKvuWfAX+7U-{Gh1pFWCd z3y8w{yvQ_=a{hew^X2Tn&aq=a3;>DS*$XgkKvmJ)jQ*TYKj28$;wGa&^#j|<@$r~t zw2sj`{xl~dl1d<6Fd{{`!20lk6!#i5YWp!}T0{L+b%UF67v081mOTv_Mad{&V(OAt zP?%$?+Aqx|@RJi`r%Gb87uRptHgQ!kk;P)U#-o+#P_ zaEsh>r4?AvV`%n2u?kI=!=1b1(#8(9l)KIk_TJoXxKe+a)0tkl#<*61Yu>yLT6@2% zksMb}tZ5+W#jt8J5pz`g*2dK!Q3Be=IdrnlChNlWDhL?viT%fe$Mu41qU8Uz?VPp# z1X0)I4)=SbNw>FddAOZr=ZTv;^PHFwVsutM)EwjS)y=!o-94(QM{_%7&!un-zwp1 zL%Y~2d)vBqcxc(K3j?FIVjI+nAheIk-42bio`}J5wv2CgrQbZJ0c&L_bj8;mMg7Wp zB0te3YhFtx9e|1S)o0-?H>G{2r?7Ztrqx~?G-uQZF{xqOu)tCtrb8EU+VFnVS|V}f zS*1K5#v@9r)?}0cdn13VhIc%)nunEiYRS5in+7ya6pflBmV_+U)HRj`*?PyPG?-GW z95cen&b(&i9_e>?H9uY$EIKODq2-96BlFl(oh&HL1j%?^F%VKKcy~z|ts;e~=wL7SI0+|FyEpS7d#TBi1Fv0D|9AT13(~=C@CE zv0_ab;itEB;-ZX~g7N=XF81|#ojDzXK#h2JXyaP%sNxF~&Q`OdvqYO5n3NEQ&M zvx<%`KAeNZJHk3hz6=s{sW%0|Vu?%>GH zQ)_Bikj?QLFovKx>}lxo(kWl+>k>XX8HTKfKNObACToC+yo~Igq(_~j{qdITiXM(u zQtcb|Zm(-|&~E?q|xEwq*Fg;iNzUl(ml)$;UA>xecGcah<$?5WNo z9@hFJzgn*Jmx%*NpP9GVJ`MXt&GgeOwi6lE_51Haag_{4E9+;`Gsa35K#AMA2s@wl zs8~eq@XGHQQ9u>!FT-k8a3L%vS$dvYWBeJt73D|o9rAyRh)+o9jz|-)u|0`#@z(`k zt1z!x;W|#zg;kN^w3GQM`&v>AvIy|};`d{3k}V!u!!}v5zf*R8^(O4DYVa7~79^)S z=AN_rtRvuJwmyy2^MvMlry9{Lj@&-}YYG zq5AXAldeQj4EY=uo^VVtYr-=c@91ojjt!wje8%~{1o`O3I4lQe=0uMrvL)%~ExOsRWpUcbf7xP5?5+-E3 zQQ5y@#60P$F$4GSL^IUn8vi2Y?^#k3Gsy9q7egXSDzj_gm0+E8$ZINdmD0yO6bNVG zzmxg!#vb|4UkkT1I!<-#1Gs8jj=nF&>dT5jqtq%+w*v;gw+jIJ&Y=1><*HjqGoC=J z=Fm~sew}HTWwn*P6>8?bI~Yk;Qo;T8*CYC61sH-Q*Q8ww6U>oVsYb0R*B(kSZE9ub zJsBUFn~6a?S0MuKx@gtf4FLjcX#c3y?NiR#q`wUweyv_Kc`YsFtk8nwhw$<)0Ga_U z{htA@@eNj|l@p-52_fEZLF3eTt(Rj90K%!hY83o@-p%CvfF;`lL-^dRl$T4{#BMRn z>LdTTPO~vOKR(fw0<3tg>u^OsHm2cJ-ydcJK9P%G|3lL?xaIl2{j62Xw%xK@wryL> zUbdE9%eK92yH;zExA}VWAekp!!l014=CSv zC-YJOvGikW3$%uU9;1Zx6N>xfAOui#k*xae29u~|1dMBBPi1VW2tq!$!$&F{vZfs2 z+OAec@MUc+EihLV%z6^kg=W{)w#~E-?59i5&(B~QFXd>?&7|Wpz`=-8{;<69(;EC1 zk9IC`hziHeyo}b9lk%x1T1N z767kQAvV=_U_AxjaMzll=|*u^QZcHl@9lo{6qKDT4YuB+G>Z0Z2%@|)qGV&%CUSBr z+0sp2AtHU~I&&&%1YWZUCu70NJJON&bA}1Qod#F3PM@vV4-82to97JNXBr~`p7%QT z_CyN)6d1sPGy=$^|J%2#VYkVF~u^orO6@oeoJ@e9eSQ*P@{}!7nbjZTsW>I1K zIGK*hO1bAMH)YkeLxh3aV3Np|RpNwg;dqgEY$J2VnQXSGHEQ~a0>{(A-mD&Md6rwgH|^`yARd6(M5oE>y7zgo0pvV90?ZEtDV>wt z8=<4G5y94&Fg2Ny*A2~=Ou480QKT9mt9?m|eMIVgYb|b zm)_}uDm95#P?T~k&?H@S2-CN`<@7|GEQ344DxD}PcS@y`SYVa6^vP46?h`i1JgtO* z5P9DH%HG!$A=b+4QdDV`X2Ql;!OJaZQp3NeGPOEli@hcU0T=Yy^nFT2?8_dWwEQln z^&=j0?WewHDMZLJtoE~R(D3-@+nZlCL&xW*>t8~q6tOj%m1X3l-CXH1sapJbGm66{ z4IVG#2|Y^@D_J=8%{h1yxfx{=BZ$+yWo(}aQ`xa3TX)vpm+rI%*`{|qlv8UtAtR34(EUUbWb)V%qDQ0`bu0jAw5-NBN~5ZRfxuDw}wkua8{d|VMxyd4$3V?52v zC6PeV)De5Pik+`oaWkfm_eh6JU)v^@fetaL)SIEBa8l<%JW}OX;|?LB>dkPr%u1P# z0A$`~28Mo?+LD8o1vxJYGY_w#f1junh#qkSBeSBn>!dd{8Lh=dXV<3mv@aELfQZo)9m`V9v>q?~FXa*0 zs>Yx~!3o!gp#MLT@;^Cj{M3}ZYQX9H4%gI8&1bcoDxS_B_vD5uHLXuJWAC<+uy!?G zd~op_y{rVlW4?00KF*DmCF86f-4}|>qRe>;^6Qy0sZtiwIiN$4%GYtC)Ix|Mi)$J` z;~q@CsdHwU;e&bOV94Lo))Au4yWOQf$b6&YLS}nQ(Ufl5lkTVY-C_LqjK$_xb_PBG z9yE1Ke$KOyNpzOJcJ}qvv+s9!AN z#SjFmqM{O2y#sif`JZP`9rXLETf3@^E^YJ%C-3yAOnOh7W!cU<70;@L{)hg9g5MyX;2+;{q z3t82JXpBWjvQ_9txG=)df1#eOhPa(v@I#8*i_cR*gJCJj$?o(mKR2AzhUq)$M7e4T zW-TGVbkFy#9fHJz;K=b2dFd1DcL$7TT0>u7q8~U*84Z4Q%~v0%^1YmWdp!d-U7~{N zg}*a9e^FLAOy+?|>%PJY22;ru!j5sT$F9auq>P!;mK0ckRFh_1)UTbek(O)ZcxWvJWDu%4f?`3x+_OK`_ysH+(hdRjg zx*i=Jk>^z9{0Ee+ulL923GG#4a(DZHK*`UaiG2^!TFF5TCeMI7rrHU}_r7Ncom_5KUMW*}7peL|=<~gHiRvHeqQ4Rdmsw_> z)Bapz;$D78nQoM5-`}CG<(pE(bp+bMOf}lc+&C>{t!nLS(cFX=s%%o8BRoC+@}vSy zq=U4{Di-z0kG#C#OqXnqTX0~E4sLJpnA=digTKG5`w(*remjru89 z?zv&(SWw{xPy1qL`n{2ElMVHCKQN)YP}7PAHdZg1n!EBD28XeJx5}B~Zb_s2jq7a~ z|LwaxRN!#bsvZ-2VZ|j9hWU0Qh4JbL5L==3h4dNEWXWpg->RpyV(bTa zWcT?46m`VkOz9V4W&X7zX&S5+^b`3XF8Ug}DBo@1hDvX%StI0r??)Iru^gkg;*-rcBGVOnq$^Z*bP zLg#dvqNTwCkkAQ;9-y=Xt*Hx=!31@7E!i8)c*K;gefX=&fU21gU&A!=O^iH4Q?h$B zXaS?g3$LoScL=Gn#h;tnYz&9PuFJI;bL3b!Kg{+lc8wOoUkgRY4d$%nr;|Tj7%;&44G{kgZ$2|Y-gyXNp3+}e0^>0vpC*o7Fpr1 zGJHZ%QhQ(%KBN`%!-jam{pGqBP?JB-ZloW5mM7pPqjDl*ME_<@-8dV8SzUxSgDoJGf63*hEjyO4bk~g!0{eG2=S>xMvvIBOD7} z2(Q}zra!*##Ho_gwwW+CGNO^@qJ?|vy%qnVs4?`X`!h0YUNBI?exYSg&qc^174ijv zTo)u+F}x4Pkh1fbzbbz#jN*($z=e2KhMAuzpxRY3R)GZC>z_Z#;-70I6l2x@UarIgPi0-V#9Rm`Nmlm$`@uib07a6UWhG{J z35=^7pwp2{nV$Od;rsfYNdZm=>z}3)}M95zx>Yy2YnsX8)M^nzRL_7pVliNsrZkv%uyd&l#HHSccg3gqQz1L9oGA~%+4?VPsxcpet9rN`GYmS2hE1!`3@ANqZRtC6!a`32 zVqa)UXo@cbNA{^7Ze%@#RoflTDcRIzk}_uy*A_^1Y%4)<4ZgD^J%#;ArQ)i*|8rk# zY^ns>MGV2Bo0e3UG#dlNqAas~7L#x!whFfEGMCM+Q685p2Jd8o%uB1KfEIaD9@ZK&z@M=;250vFIhcjK~F*PX{9?GA=D>)oS(;NUX~|)X-LA32{;5 zJ~sdKj?n$(Ucz&2nLK2H%4yu9*n)Rx8q1fa5RlkYig1qbhzS1z z$cfTuVjseEg@v;AcaqsW<^BbeB5X5QLhdXa2Z?g8*5fk((kg{MSg`eIZoDK%jHJ z!KVI{R7d!F?3z_)vq+j#5F76{==f~Az=&Vzg!O}ZX`jILG`tPd?TT~OUpR5$W{=Dg z;nG$7!#l^ES!i)DIE|H}%T?lOvhQ0|zoYjsT$6uv*vkxCdf7sb!`me!_H~8cSVza% zNfZU9ejCSRa|d?Py@sqEu<@)*(~cS9WY5!}nXF70nZQujaIn3&`%EFfOl2(I+%&Q% z6^t^MS)V$PdGPesNpZDEglr{%LFzAv_&ZrDC-X+-M;WkN78H{b|NI@_@`O(Ii^Bx{m1|Y?a0TVhS1b6oG8jWM36*_dhMb z-|WRTOs9(Py-8cq=XOuoY0m(D1^Mx-=zHh?c5%ODAW9?`kcZe~zAGE^6TmDS4 zRpckZcP7-p{czD)UCsCfB`)fO2Fk_##z_tkuG}qY*b$1bU&UJO!m!_id+FTpDK!By z(Y^RGH*#9lB={q)o*$RL+Bb!eddQTbo`=d*Y_^@nXJ-k>^pay4h4ucOtXV2HgFg(d z@P~C9dFqQ6o~2k+)|ZC}w_^W>lZtT_aMJjfhKZ4W#x6=iQCB-ODRfi@rjQ80=MP(D zG6T0FI3uw$*7=`z1aWgmC^#p2sd^^HLlkU3?T{Ryuar>sWZ_nf(QRev~^vR#N7O^UyoLWN|ZxI8W9b2W?Z1mXBh`=+iBnwIW|Hr zXr>S$f|A+JhfASG76DyJ2;?v&gxpu@vW6C1QF?%Zztqv77iSmU;kWz`t2~DK7{!!!&`^J@~xIw%BSe;Aq7pv{Xq);7OorSGAzB;>n)o+q2~g; zB_%8c<{-74XMj8z_4&&(HnTyU9CO{i`#8$uD=?~Pz?`bsCUdQhC>WB4aWy&`QNc8z zsKWFGA4~sE)U?58>lK^RGl9tutl?Kjq-R;lQBd|FR(~u%A3Yz-&9!W?CHIWTPOW2W zN}nm#)82ej8`HP3=}_B#LKSVRA>-XEl!xQ(=4 z*GM-I4)Z0)nQx4oqd;?^RgOLhk-ngWnj9h|n}}FtK}77flv7iXg_ZT;&p3=(LeLu$ z&)$ocxC~`yAzxa!8wXUvUxN#!n0O<%7!(di+rT#a=+w0#rkrp(MccOtGK4P`CaxYH zt=-*()l1JVN_M}Q5RoOEN5Kx;45*GrZWYQwpIw?usHlOtYy856U2Zx*v?t_z0^j-T z)Z<7*4f=Oary>)_O4A0(*CL;XClVj{-1#zS?iD`N;Sfg1=9XNOl;KS9*+%EyTl@xE z)eo{CNi3qf8LL)BuS!l7J9(t7Jjt3=(3^~sU18|4 z3$~HjjF?-RuVd_1OcU^e*XZt0G&SnffmO^fMj}QSD5+xd5sY^bWT(P1B&h9E(B63x z^E7W2|K!A~Q$v~aFrEK8#(m81dP#xS?UV`8i@Jgs*KpYaNFn$>InGCx^%*hPGtnb+ z?A+xUsK=`4GI;am6Fcu3uQLDv8E6MR8{sk(cCR5Dbg z-{9)v=+dm_=k4w7>AA{hVXA`|PWn8Zn)>>yUqVyr7!X)&cSXNVLcun6Vh!Yp;2Mh~ zy_Z1}FrddUcvlegyc+&8kW0SD@oCT?Px^_!me$Apwzd@nG=xkio5Aua4bT)=_K@Z; zFpUiGCpgc)-N($zcqc^7w@NP(DLmtVR^jHst|d%51CO%lfL+c2ph8r?f3rA?I%u8g z5)WX%ZK*FIOR%;nzX`k>g$I9MTK*~lS~%0-pL^xIfhU4(AUg|ic23;71(tv>wz@6< zlB?|(HBx3uJ6=`#F_|^;cm0G$&&&55Raps@un#u6&%*0}rE1?!Jg8C64O6rRh1WMa z&!3MCgl$4U*k1)@W8Q( z^H=Y;;k%@i%Ab%8^L+U;$YZ(MB>mbnbnnf?4SwruURwlC3ZYDGS%=_4gnwV;vfxl_)v%jb3Zf%HfFo@&?d%I7$dD8|Dkgr~u-)gJeaf$M zU*W~lxMs@umV=JR)Tas>T$59n>h{wBfn z?3?FCHF)gsws$b(OxR149aiuM=aY@0r_VHK!Q6rhDTNww;112CMeXQ}Co+W>CmHv= ztEqg)<(H5vL4Ap|Y2tLviGq%Y^LdH1(gWL9v)OCNB}VnsnViAJ(-TfBB{}%_QJfKs zHfqG5$X?(BT~(=NL2YR-UVrt(q72NwzwD{- zas>QqiP4s945kFaG>wTA<(NUk&U1i=zs#K^ovCK8WA0&2A@5tjs^vxQ;huY9E=go2 z#(%BpEWq0Z^B9@cSMh;JH7-?aYMOdPo~%9g6P?PKb^(8m=R)u%U1Vl>Q=QG?hmDI1 z-BjVj93VLD7Lm6FID-5UwYlGak7dB?L5A^!J!qp?_Mcu5c(*_!=Ku{K7P;ZFp8gE!gFy;^ z5<>-SQkgIJ7CbuHzdZ1Qd)wamw+#wPbBteaGp^N*>Nky|7QuPmI~96_u+ACX&Ta(r zmFBy~2A9Q+%o0G|czPaqLo#o@V3qSFQ1^$r2Ai&MgDU0ix*rFqjHgzZmn$ z$W7*6RVu~CiaYu=q_8UWliOQYFE8yLPDrR#2=wSR9KTqKs&N{IQx#cD-TXyJY~4s{ z_dFK;h!#8%I_ioKX30ONhA)f5ctQ~WC|JtKeisbGN?6RTLiey6XTRldJ`GYwtjlw> zwT*6{w8R=pofxXMvz^;Y3&ncRBVeNj(}cJvB}FDD8lH|t5>~Itn8Uc@Pb(UQXTG>@ zpUe<#jzo174BL5yS{_OcH-Ek%_~;(#b8Y6p!xox&5d-}I%$0x;TZ>JJGc+%Yc8G$u zUN`@YG0ncI8GV+XpokcvuK1!GEK2FmG^pVeHu(T?n(&^bq#(7^e3eLV;0IMQ57&Vf zs!`guk}0zUjuNx|sp1&H?}ULFQI6;jt2;|nTb1WTQ%%AGKRC8;63-^`BhFPmTHu_r z**%G5Z4#l7t}!9L9lDPsxE}&)a9sylUxl)KSzA;_BN{II=8BuTHYa(&MmJuk@_i-e zR&i5I5=W1@j~CWdc8iAG;D2x#@aKQw2o9hgLmr!>n?M@Sck|9Jr6b3P%BFt<_DUej z1!-MCX#y1oYrx>WmxBW}MdyFW|OVza}MwzC;wGgYts!)9|3_F01O&h`YiS3vE-P?zq^CRiq zXhO_NRG0(BzVP}@B)>fby^o9=k-;~KJ_aM7ca^R~y46`4QfM{Pri^a0dXSBbd%ntS zpE6Z%g7^K|+X>Aoe98C}YD(aK7-9PR`1+oHEx}rqFzrxIhTk5}>~-=DVUmL%cLy=L z|CD7S%9A-FUtdy&2cao6*NJQ$5Tf}n^v9GXo_=5GV_J7iH|#}waokkiu8rg12h65s zV(f9qppeuuM&4wlxWmq1R(>606%GC{^LGGwFF_>(CHymfYp}pd zH$g1TPw_Du!Ja6)*-y-w6=5rE)ovS}>s!f=YiJv^qN7y^avQ>+M{^g%?1Nw%$`fom zhTOZKRJ0$)u4hj^n30vK(O`Pu%ln&~Q+|#-yu-N`6~b5zA8(%a*j1iZN~vFGY_iyQ zw8wBy6J@+Z45&&O+?o79P5#T^p&=I4Q9aMgV88rpfUmoI$(P&na|dhdv06ai{{!^; z$Vj+Uxh!j5qt!b`VVn&rig#Wh)`(4?d)8Gb;^fh?T3+I4oO?SPgh6qlWlLs$RO93} zD?-haz)R7~Fj>AjYfq95|`X$25DJ{$@9UUF#{!_8reGneMs4T>Fs7990rB+XLM!v#P*>S5gAjGpD z>;9v(yzYRH0f*hVGipP`H2(FF?c~z^Iu>z%u@S4H7|GFW6iEm(M6Yu3J91w3{GG!{6@z?ymJ@xAp9L6=iXU zcUh*t0nw4ArKOM0Mn;uSOiT zkL6kgYvSNFm^dJxbA3XbilEDawOER-2CwM!C3lV7b#KO}%u(+~!ia$t1Al*iqB431 zE8C@xXtNVY-ePM6q-!5uTuxiBxmI14G}7QlITt$SgaR;?{b_{Gw(og!%~<#(5L_vYjP5>Qi7DR zO5cE3C#@M8+O$LW6gR>{Zx0Vx9g98&@3C@Fl7b{mLo%F=4W|=~!S(@-bbuXT7{7pr zWW@s%q?zRxSj@M2umQ^l%f3l^XRV$>%o&&&A_MfLAYN*e<|P>=XF4@R(NV*#(@dl| zYK+u`d090i^Xv>w!t9tw#AX8z=I|`0%kI+6#D)Gie9B$gAKKscAl8&;`ROq4IXXt# zW&a$t{;~N{D}=8+*N<}cIOV4Ljwk~A=9^Ak9Y3yrV4!jC^wLd<(;1Pcu03rFf-Y}G z7;b(scY)sMpTT^J_p7yER6+a|GTlw^%VcXKArlF#9P-y6;SyZLKfs!G<7twVc=9N2 z3tFU*Zr{Vi%jQ?w)LkhZXeE8)j@lmLCW@RlI@yen~?>Js`ib$k3-_u+3-qp+<(gMjFUGqPmv~i z!C26Rdf(&t5Yv#TqNGhHXOMNhQuml?{}Q#5w|FGr#ePiAX^itU-JMi)%ebr9EEUzU zVMiQo^LBA*WM5+*;SDy#4v-E+rS9$N5fl_eu8e-435y7ufeVXy9U^MJl5h)ulEynK z%q*%N_FV!+{6!rZopjj>dpC=v8->{=yWT(m`eV846bs$9f+IDC_8r>`I3M6wneEYH=W?!k6wu8mHJ3wYu4 zR{+~kn)9fL31eE-nlX*c{JTTJ);Gf)^Zy;Pplm0RP4&aVc=BFsjuwVvD1mdf47 zCljLQK229LNOaow_xfm3fnY?hnOnFgbq(2Nr_n$b6eX}Omb?GTUr~|`e>vS`%>k|$^Fev1MO8lC5H;DZ&?G`7Kgn-l)(oL zRD2YRm}mvd#H_?+9jvc{$UIqmUy$VF#ZO;e2$Gg6*8!)rzMlEAf!#}hN42!H7EPsQ zkMR{&*O?oS)0X7V5X59xcP6BdUcmkRiLPhpu7NU~mtE%15?{8{kX+Gb=Al;z=~4B& zmRpK9?$5`=f5emkfREjneMxm58mMbDslQL*%vK3je0->#&v$Ue^>U-o^% zDx9^DMR45J&<54`G!Cj|k(Tjmb4^4AHRUKmDy(>T@`Kv0yBkNtEC$FrgmpMBMO1)KlVXgRO!IHDfc@uHc9UZU#^_EU8 zpJ+*eaWOlW*#A6p(bkap{QLQhasa0~DTQv%HycRbDZ9eyzqc9RhD#OWb?R*-mjHzO z>Dxb?v=u)8=i37y{sh@ldPdS%pbr^EFwg%7^Jj|3>Mh<|Nm*TV85PwG+?z;ao4;a3 zR?B7UL*U4Zf@;XAMAu?aZQBxoAlJRK1M11RpiJm+N3+t^jTeBkc~$wC?BUJOGM>3JW>z^|A;ve9(7dhGl*l-WE(q+6}Vbm`?M3CcZ5bC5?fqAMmE z>qon)Og=&yp9!|w(_e3?iOb{2O=&pmqXgxTg=_jML)nNKc2R!6@#au>H*SM6Vv3{B zyYB~g1~BmD&5Qsg2-uOP>90Z!6RtK)^R3yv%j?kyV_B9z#xOh|+^)Lf=ra`}IM`O) zzrF?>R|S-DW~}=Q;?evA7Xiit5IL%IUE>G*$d=aCh&J3tu4=-of(UFoCG55q_N#t4 zAI`}MDfNlsNPMaR~avl!O19IrG=?0WJN?F8W%+L4URg` zU5{7gwc`4`p6mHs{TC4m1X)l}+%gjSuY1K?@$

    vQI-cTnjtS50D`nlW@Uvt6%s^ z+7`kVPx@1{G;meZl|ufyDbrBpMvI-=n^dP?H-mI~ddhIxOhn-PJio{?xua>i6ji z9={n`1>oBs;yHNwIy#)^+~fl=^F7?$n%motVq=adu=!6%WQB8A+|J{Zkr}G?{i>b+ zDZ2&k+tQyXacmz)M4eThr1ANK)MWg75pl|uEGQM4Qx877Gz;7%k3>i<1f+-rId0KN zi!Y?Y{!t4li<3kqrzY-u*@YyBQ*k!%6%-Q0fxEnHvVmf&E6i}ByGfu>ox4$Ku};h; z%_8)T)c$di2t?34=6i)eAW$WCpj)JM@r$)l5_xu992bs}_?})*ldgR2M@Rjxrrlnp zUrOOJ0fQl9Ak$E>i~qOe%?G)%s?=>bxJUvj>*|leZ_A6;H5O=%1A&hpjhS%L#rAph z{xk;mASmPT(~wYNvlV&YuvI5pRCXCJyT_XY@L(Ap0v>=mXd)kh3lGp@7WBTz5^E$P zJdqeJ@c`-xqbxzuZNP5RL0^H5{>R|)>xmO>A{~JA4xa}pP}gT>;s?-~Fif)#Tqg)< zwdrp$O_$w2B2}>2&v3?#CH;_oC@Hxg#aHX(drzYs#uIKnh&dqpKr(C9+<`qm(fB7P zTKz={x5tx#7$pHIt9EmrS%c#zbFr@Xg=CkXnuIW?Yw2(|2WcUgH8ApWPtlIQiZ|N- zvVoBfhfGj!?ptl-d)G^`U6pND=wLBwTWM1ZJ%4TL?MfBI4A-5$%J zsGj8QxPa6zBHC+!5 z7>sMhE2#FYDmqLpt*tBl!!<42qBl;vR8OF|Xk$ZH;zaCPCw=MwBQ);sH80}*Sk%zT z!MmmrKBE#knaR!hAgt9)t}&)Mct(qRYgWz9aC3^YJ+%e~kK%H)nnZ`mVA^PD<1v>3 zO-CC4)s>YM*UtZJxpEfU|3r}?kwo8Lc3`^|Jqfrc0}UzkL1;C>?~rsl?mHe|lkaDE zFcQ#E&eAM%y-F;-=3)hMB{hmw;ve!}7LaU)5Hv)7Q;f zj4bW-4EQtdoJxr%2Jn!5d!G3OvaHh7;=Wm5E#YNS?YaX`K*`hk463CCsNMeH0b(zMDmiD42ay|$5D;1x?}pgaeENOlgf-f*lebf z@E#Poh)sdlpQ--W^DKFgmg)SZ;t~{jF~-L%i*-@SE+KzXTdRB^Z~HR(M=R<;P|?-AG5ykEa}x-iqh>m|=A`Z&_}pqUhFF8F zLXqMeJO?k_umT!~h8Se37a{cs*cmG^ig9mg3K8GZZxkbH;EWaB;vnlh5*qG3lpsVa7wyrQ7d|Mp;F zTVyq#8&!U-=%VTq5F_{Z6+FJDt2faavcKOknkb@QCNA_UwpQ|DxzEZe!aRt=Fze zz(?<46!_1U4*sLz%zf*Dr}9RJUbN%t$33WeA15HmaUmi0lpLox&x|f4+=v`4+D=iu z=Ie)TlSE(ntRO&SFVb`T&7(b7{@NG$9zWa=KM%_LuMX2amAMEKCJ^PF028C4^DB`}uVPK?RV6vmX}bii|CKj+uw}hLM&0 z`3=m>K;qQKIlA%u%qJG}Pjei*3x8SPv9k_mRnv@AV#S&!i?$83>v{o}+o|z#{MbPl zNn1?3?!J%nOU4_BxH4<}`Lw%+FvPD{vGXFdSB2o3U3VuvlZ1WeDTy0QWAtCSDti`~ z`JyGap=Mobpk73>riC)gaKtWI-++r#pWON!Ub+8f?3B%?;wN-czI|r0{4?!BKVGUq z+H$O}hy#p>d=|SLrR0c<=5rLL;pc87vr|_v6TRIlzrm2#hMF&9k3Li^{GjMC&K?FO zWx29bbR{Rfr46ZN+^&z> z@A8IQ9*`MG>1UpcFfyyWd=YEE>1Ub6zS;A}1!N^Zi?Pz?8fMQO1&vHtH0dxoL=Hit zxtyeay|6V`(DkU`VJNNc)nV!bF0=}2+5XHg6BF#}u<7BC`H8H;{QT^b^S^@Qs3a2i zD$vG>5k8m=D3q&rdBk|mCmy&~-f5#T?vWwsj&SD1`z=Ac9Z!^}3a>X^i)w{8&*M5! z?%oEa;KYt>Y-EK~tfc0D-U}U8a!_4bB;F_~ z=d%HwKhOTJvBrO)BDg%Eu#Y6@xQ9(7@YG#fn(6;(CeyPj-3oSATa7Ox9LQ9&@R$j7 zsHiL)_m5&8RWWUEY~cSkRv*U`S{pcsX>t_m_6n%Mp!8n5VF|fdQmayHL*%EMs+*gw zthmNm#m^+Hb5~XxfV{pS5;ZiQSnp1Yhm%{ZYv}o1qZ(we7+o1;0vZwG z1AfqnlOtVoreXgyk7(ii=qc8#&Lton$av-1Ih{Mv2_G8g@b8@J%*EZ^!e$yUPC>rp zZHn9q2ZC896)6bKEt_z<-)DQ^VO1jwjRLKi z$@%Zi>@2EtiF2EQVUpaeipt;)ni_oy(ZVoA&|d>7K3`M0>*Co!?h(FsLvmr`woaU_ zX)^_JnUZ1OSpq}TIXZf6<4uaK^o7*~v7~-j`;J)&T6YYM=a>#$pAef^kw* z@7w~{%j62jy>$!rY(zkSEW*E87ePnli;7eiyahDg>YsrE6x_m*bO*F5>8~c6D&Ba^Lgc;*l zenKCdReDVaxp!))H}0SEu@8{;P^!9JR)$(wr-hH65Di`?e{cL=Dq0ldwm&_?a?iI( zalh6sy~p{(p`g4p{1ew}1$ou&6<(&ZhAlCLmAG|t7Q2V|045}pyI*U3`;!1Z2eaEtwzr2zGA@cuKG zmF~sqO>r!bgv;#2`;UKv^aSJ-*K%|Z>17}iH?&MHD~1h_@q@Td#a7P>-kbC1xl%w( zim7xYYpUhRJxyS%H2B}{PplaS#-B~Hgtx)${;Bxc`E+GSBz*w3%*4x@s_ik~Md(Ln)qq z{A3yXAXBuzct7qGpDVn9ip=Bmu{0={hlai1ua~F{lueP#X|0gKh%nC>PBR)5~%y^oWTjp{38y1bm7ybIVzIAjw z6@vqYEZvJ~8}|5xR=Ya)i(dM+aT_#&_k9&c$EmDpl&sd$|GgG3AHc3VCSQ)Z$nw zy^f&hvELoFc*WQ~Xw}%>erPffcSS~7MXphqE&pbxb!aB)zZx9p*n%X6N>oo&gbC+d;tYtS)pVi zx%@40A*uNXw!-8_U=*jeKlad3%{wO;0x%-T1u4RJW+I`o7%IEzG_QB}Ok>HHQFhSc zK?{&x7F2#U58Ex9@f0dGGTVf)m)1g6pc;)y3mcho@CZ2A{S*8*K%+)gGfe+n(J+PP zdYtG5r0n)}b?IRSoz)y)yqeLSz1LyFNt|4k*LVD)>Va0_7`~LxA(&BdHaUru0}(?0 z!QI8h1!#`aFTwUcJDV_v{-%TG_)w`hv>T}H@YV}w8BK(9 zyP8Nn$Q)&aHkxd4kUJY2m3ck$bRo=3s^vzMbJ?MBO*hYXN5FLPysWbUvWOP6@up}f z8WdZa(TWgoQS-&jnNcO%T061KG~Jhjt`ccKW#ffJ$=DYbDaE4(_ax+gcBzQz9hpcB zu{!a^xJI!c9}K8#aDDy;Gz4NJw1M3`J6-~i5OlrgRXgS3dOnX=b_B`0ycBNHiXmyOQH!mjWE zRJ0!6J=X{Rv)3ANB(|1?=kW@}wEtZZLg7Qr7oP1IOGi*bDVO1`bv_rI(5xGJNL+%& z?TtwSBUz{Pth&)mq}wj%s5zjVw3Bxl6Kf9ZYjAXXT!wbfQ`(~1i*!ADGH3o(cZd{Y zt$WPUt;9Ujw;rziiOzCXZqK$MfswT=Vz)U9S@?IMCl6#ny%$O7zFndPxEI(m== zAG!}CNdvrlzI~f3``Htxf$QlLR?1&F^RWtM`wDLCaLqon9gX1#f5-Kyie>U=>E$oV z58HU3xwK%AGu~3IfA@DHjg~%V`)d}%B%e(t9nln5w%4c*8N8}G*Lg~6LrsCW5WC#i z-l`-Vo+Hr|gOyKe1-5^h<8B1y`^C=WR-Ui}-1+lx;{av=Yp>P<#f#cA%o z(4W`C@CI#_$)txd<$w6q>^tn;K?fIzb4Hu&lY+l=dgyi5k|7+g?zcg7Gw|z|Y0ZCq zAq$SDB<75C?{97%1J$+%e`;DyaHQpauNeUm`8@1xf-!~7ZH+X|ekT$U(QD)~gsu`R zjB;_Il3}xf18oCUspe9{xtA9grL1UWb2l;-7R0WGNCONLT=oJUAeec5dmEJ0SC;vT zHORn|Ydzqme&(wvo_EmsaSS_XtS~L1#h%wr4-Z`k()g=$i{Qu zzG39LrZM`9(j$XWpHGiFfsr_z86OR0q{d#T#12}}1p`?DpII}2*_|~lOu;wo@1!96 z{(if;yA~~x3k4hpQmCNTYBpRL?N6>E&<$F10$nk%p&dsBWZ@Pe3e(!8Exb6 z_b=bl@IwZds_sliCY^-Hu)lfd&K-;6VHzxpoYEM=6f#)J&=&P{7J|=9;w?cSj+;-^nb_on=AU5~dX2PZ zuWfMNQ1i#q>F3wK8~4hEj%;b)H!IGvLmVj_=q5>a+6`EsGe-QLxc2YZ2R}x1$De9H z+QoFfmnjOv4C)5XfN&vUVJ!&f27J2fEr4)LFkqkXaZDR-WY2W<^k|631hZ=;ocVj{ z{uJ$!&%8fQ1pUhZRvuO9zxA)r*F73$Rym?e`iTO>@XoE1-jFq}gF{0@8j0Ct!xcux zpr7DjO%0dFvQg*!@)8Ha+v;+ZP59$S>3&l_P&Wc5cHGzz(Dqcz*}3E|{H>$o3B>z> z>Cw6wz!uM-(hGo||FzsE;9X;xLE%R(a1PJViEuSYFb@sZgmxSNImOeH4tJvg%gGY9 z0#IRnQ=lnRiSKIu`XBeERPK$*<%sjkD?UoJ!|l!J*Rm&LEu57)ULM+L_73* zmd8G}w&a(1e4wDTo9tbMCo?oFyL>?S^2>M^A~lDJ-YfB?qaQH=&V7$Qce)Ha+^HA= zv0sWW)#Vz$=Y2TL?0SuwE%)7&8AxXc;Ld>+^s%Cd;N*1H-z^D)>14gZ9NVaTIb8e{ z-6i(M2H}nsC?ScQKtyZFRaC-gJVeGPlcX8rZQkj={GA}_@_w`VJIRmMWHJfS7!hsB z)kPQh2?t3d^a%-b7?`m)1oq~J*@^L9hS=yGmAL&+{(X4U*bPsn^^J5=dXF-QSEhrO z{OhGkirnXrb~}hZQA*g@?hZ5v&dM{*c()|q98wh=XZ|5sJ^rUzySsCvy6mAP3jmS5 zhlf(V(pi|b@Jcf{@ly!8o{9uqcpL>4G;IUCD&2_hug823Gb`Ei=;F=y)t5vl+q|p2 zQvt@4G64Xu)e%9ccay5=mtNjez<+jEYdLX6RRqJ2_|D=MikK458YTsjQ3Hv8Ks9b3 zU#Jf~(lZ3wDMCy&=`Vvic5FwF&^G~!@Cms1{Q{Se{&Cq$@uEYTR6I3dJHM5$;{d_|0F`R33C7Jk(!&6LwIxPz#Uutr4*l)ZBviT z1!e)1)&mL6OIMV)CFRTpXockTY7R8MQB?=+Zu@%^^D z$+laYcK_O^9c3T=o910F9pY=F{y&<|Dk`fk+`>}QNK1Ejw{&-RmvnbXOLup7BOu+< zNQX!_2uQbZ)_=}8TsXYZ!T!Fz*M8%fb5i5cS#(Rq+6`E)%Zv?%A-Q;|Y`oTdZLulT z5dZ6b0Q;hGL)1@*v4b5gVUx@93LdBwOp9d+#yrj1m~YK)nvpiyP=9Ue>+99ZxEb2B zl6((;luq@la^6WYLL_1Hh5GY1=ZTvbQ#|i!1{58t&4fBSX%^yK5{7~kPq<)=)|D2gQN{|aC5bynQ!ehlo4 z8jSdCa^J?xi_rT5)LQF~!FX?ljVnRK_KTnT)Cxy&gQqgg=>cd84G5m&hEgo*jtp)m zsl3QU36|ALHg1R`#UpQc1hEPwMcOPwPv5D%M{xVs z&g=YDJEwoPJ%?mqBApq2xE)jV2p~fLEtL)7PfDfEr3(y>HqDFIHht=NMX;NoYkDld zO^&n=cGISb%c*1wi5sVc#1;x4M5;{$Zh3}3d{=0MKW~ZIW>}HJlIy}cu86brsVH75 z7jD>b4f_>kh|C^jxipzUWMtniN@YtAch~zsz7$$9l_B6|{3|!!-YPc}>9{OXHapPr zJ!CV?k{R+JQg@^)@yHSm=nHBR_X=brmEiF))5;W~azQS|LbSZF7yyX=vNE0lr`PcC z@So*+ITcfz2Hx|qBzyu4{OX)*YQJARX7uScDG)?t_dY&82#~;xo5@-Q(Ng<^cbhBX zPpcOdRUZ)?TCSArN2mO>{uHhB9_-|qDmhn=Mr{IO;=kbM{QRW#u0EGwRPN6j$q%nM zu;2lQFZixjR#%_4!->5xM1G!~)p~S=Rtq%D4FH#Ckbe1k@+11Am&_ELAyfJjdf@U; zlc*rUL$Ej>p0fM~=HWqDp~3&nSlwJ*+4HA0U=S>?U=WhQVg|f{pyVoV$HvA$9?5U* z@8X8WGh;f?W!!4gA7oQsS2jU~{sbtk0N`tQJk0stM4g;g$yRy2d#Gvn!Xb?w6>I7e`uAzp=FAZ{YQ7f!-d*L@J|$+ch^VdY2BMz(07 zb~S0)V8;|M>-6WTHS@!A(D=02i*N=e`0eaLIz_RZeyRB3YAgd$H{ZX1$8N|$dp*iw zsS-?9*WrY}Y(KV+O~-{Q?1=aGWhZ!2n=F8YrKqyzs*Sq&DKXfP)+o{conN z>ZyegDU?lc;T?f-^E_Dx{&T$?T{6;7Y+j;bAEjpaIFj4=VL#t1T_(KGj-P)}tamp4 zZR2Y0=;HF!x>01*N1N+j{zCwwC>)$K z-6p}WwT_#-STDsKvPFe!KY|h$Oia@xn`X1_qFJH7#aOKNIiAUpW}#;@9gg}cMU_Tb zc{0R#vP?ykm#L;`2d38gjUV=NNCFyINKk=67OL=43!q8M*kUVDc6(b(YAb zA>+te|7g4M@QA$ct*w4A0F zCqFN8-p~^8Bth%gZo#|`pt%v_behG${R`trN>Y@*BO62>;`I$HLMHe)VdZAr*gwzSDVJu}?aeYZ~Frk5kqkQ6#5<~Tn< zEJb5H;?}8F;Z`Lh{_kS&1Hh-iJ`}iYlmz@)MlBt?VC4LxOYiCF;dh^M(5EpVF8pDc zO4u%giu;U(JEZc!HUv&|3>;;kX6#$y;o04*!4!4=W&D{GuSUnjlb+T?NnW<v=l7e$n#ET{t znDv1Pb!nRZv3$VYDX!iRTVk#yNzfL;pi99A0gzAtwb@c>k-D`By(LwMmN;4u04EscFPG6#BRhAYnSaV~ z|3si&bl9f4+4LZP( z$ky*FH{Dni1ZwpDXv)PUx-o&(fLI9UOF{{z_ar!&J9Uw;b9EkdRLL@^kE0)=%s;NT zX|hQ{mQ8m+2KZYKGyZJzFm|r@ki(v1a$=goQHf#TK`YG6C*cQejMshaW0Xv;L-#Wl zYiWPjCCiQ;Rx-W?RlI9C9U0X`NMX?^CWfhcEnzveg!Bh*Wwvt0g!MF(_*An_b~;Yj zSPlQn$2il_`}an1^M@ms0bCqX#L03cx~Z!c1X5u!x6cS(U3oLzjz}_V8~^>}Occ5@6pi}fh?n zs!O)AdhfCyT@bBBpEa{QZ zUHD^Kn`HTYX(~vCpNSG46z-IUC{Jcu1 zy=xAsJYfUUQ*C7|QMJ>jpHIhbl*1oexYiUdyX;6k3G^Ch z7?lNyr&c4-XxWDmFg4`VpQ0Abh2=JO09oqqZ*T(gOKVjo{Dz}^!J_W8HleMli7k6- zCF=KYz58krfh}Gl*nGK8%Gel`X_{kX)|%tFrHOe2d^`qin1QuV5nrPTu2(;NL(e0K zfM0SHfJcVpkJvEb?FzgaB(6Y$vulFCwP9I+19a|R2$-IEn)&AQ|d6*hNp(iZ9iw|p1nL>T|i0=OHf zSOSMV4LojO4au6AX<;GPTmuHA&>GaOwxTSyDdu?Lsd^Aqxz1s86-)z|*A0%SgG%{= zKn)G@Q@DZl%m3zRw)b`UjZZ=}Q2H$V72N?58Iy?SZ1V6LG$?lfnBtJSP?o1$uF@a& zX}tnVF7WQV`+h0nJ%*+TgkzhVo7A0&J)sUg4*D|IjR@5ESgYSV`6rFfV&Rt-4znFi zqlYFHs2~Vp)>SQnO<$kfhpeBJrhon%Mz?f7hn_`tv)%73_b@sm~6zV%O*`-AdI&Qi#$Sa%Q@m`dIQf>)^F=~Gu9US^P`xA-E@HApq8n_%OI0*Ms z>8o7>^3E{EAfZhqNWzU+XMm_XX^8f0d*2_|Z-RRLVBT117=o3SC@ zv9Z;WlS7^+*0Ft-ePN%hNi$`Yrsb4prBatM)3lQ0!z?KjM(`_ywew}OkTeF0e#U%U z`#{mfBl+siE8aryrEKwm0nte&gp8studqtIMdo(X`p}(?-vE>cMf-qu@$k62T{a>n zCN5?u4OkBBWk~?*guy{EEU9Ch?}kq#vi(hqInrE9YL^1^qo`JW zmV$l{Gp7+J5#Fjp9tEy@PhQkxE1!TS;t~j?$^1Fxr~bOCq!6a2@Aigfx9+6zEiGM7nG9V ze&eJ#P-Z`39UvIWU^7Wv~w_@=P!dr{#P|PRu~(zW7_rP#L~<_;+onv0bUye3JKp# zf$*7W8o9W$Y7{?L^u`Z2RM0h;QKTzUJ8F2c0zhjNv+aP{mrqG!_*)mx(27U#3|w-;0LDES_z?6%X=*pO{2k4 zN}}-aS8bt!n;Q80fd0JxzRpmsu+-=u0K)u8GvcBiXzWs6i5C)kD%c$ZsP3z9VD-Dc z39|#x#y73E6C;ZoO-;?ayE}yak;tgx5(}cCNJ6QaVJLUBxwu9Vcfuv4eb*QlGaBQp z^HFKj)cYuLWP6iLHRq@sBI8f8>@iRAPl(Nku~pkBVj01FA_vPwB9)N2yD;DK-GwR2 z_iacXIJ|yP!yzz|&xzP-&-N@WIGdx-Q*Xt^3gu6O$s(|MhCi%zpH-skEc{ps`xj1U z4D`4_wI{mT-rDNn=ak;G0s{V!Cxd zzVvuqLc+B8)wq1$peJE#q51%><=bIEGfe%HY3d!7D6sEi#6}cg5JLw{7-%aK#JY9w zQTXBgV#tpdhZFTcDNd9Z+8PTK5`pW~W$!te+}pVq9zH~BHCot)u>+>zL*DE0JhjyV zk3-W?@iDAnt%?9}p$T!@isMXu00yg6%3tf!I+{pae}VTXIP)WMAx0~b7h(=@xI@d$ zuYmk2AmHu%JdSu_i$GbG(3YSUO8bLqc|q2d!Qc-T5>>~*TIo{J;+ai!Un#821+or;F#GhcmN0NZ&&IEy^6dW4~?aE839!~@V5Fdp95G#4~#BYBh_Rm zmcPAjzWHMJBtjmSVv8c`kmnWL84p6NihoTg$T}T>HIPj7!!o6>*7N2=#>5gcSQy6g8Kg5;`{Sa&R~K< zjY5eGk>BE$du7~~q4vZuVtD2{7FoXv>8m<5?~_98xqHFof|6)wIo?3o;}CfCfaj9) z-PDX;0tH{AKwFofuLdGYSPOt6zqTD=Dw0%D^}KbX$fAnn2znw@UxZGZr1g$(6F-JhFkaq$*gbXWVTCn*DuESNqU4?b4kX`Bp>OkhU)-XCueW ztW{NE;t-W0RqtpyS8mFSxa2(aJ5;a!tF+F}K+vtM5h)b9;TntnpkMa@n4yF56~?pY zpV*RypR%(Sl3`_+wW3kv@mfBWzFJ4wGuj6gv~_sQf}jrvJ9)~x>95N^@fs|OUG7N0 z0tdb0zgMQ&-(6z3DK=u4Lh)zzf?b|ol0v>0XAxK5)K1$?v%I}zQ3y=VhfsaU|*U5IGnlaywapjIkTt0LuTFz`s6LG(+p5S%9=c~^y-mRS4th^ za|!U15RPxfy9yb6X5w9yX3xNT+*2=LZ@WeIh=e$K0jCOD9&<|N|rN|RD>;0{4FEM`usG%OS@dJ-oxlP zeI8rflwK1&@%oHMoEk4VBP&l+W@rQ@=bGb{*bUFc+Al)!ld_ z7n4KDSDq%oZzq7+YOo?K0dj{*^BAl!Um||Eme`MgC>QK#n2=!+Xzy?84(IVQM*E-W zwS-kBq73ZwHUB}$1N&8SY_jR)l8FU%si|?WcX^M?au3enO6z$dwGFtvR7*2IRKpoVO#9`46DNO=YCrVx@;%lySuoiPf+ zqk~oMP>L@YQiGnL{Z=fWuXslr;XLz2a1B*;evPBBEDRFTBMiUx=R+6BMtgh7fBV+h zXtFT?tS#N+%*vM#RiVR15{5l$`z!b7I!sbh{te^NK~ni_NpCxDz5kkmBi~oAaR;_n zW%C8y;0?T*;)QiQB;W&pK}x+t2k3EzvSA)@@ia4nXcKW zkJg+K8U@#xxF<)(qL>&?P0uj$IR!nC$%IxkLLeK10Nyk8(4=$w>gVSX)#kKsM3g7p zh2rF_wMPRXC%;q>(f&Og}YhN_I? zBT2kqfQ1;!Nc`QDb~0w5evw@2ABL8gn7=7pVJwre!e&q^qg|bHrHr__YIp>U0O65( zarX4c`o`*N@REs%gr{YVA*_dJ6_AYlknq%8?p2ju)jX#iGDSa3E zj8P09o%wQQXQglxAEX$A#b#m`dH22Ngy<<+_W2ekCL8f{$|d7D6RIKhBHKEHcJM#w zI}kg)J4}MW9@RaIvK$MJds$RPX=$=kI~TC6Q2x+TBd4CWh(@QVAs<3~-Ori%R6Bl5 zZa;3VLLh$yAL| z)ZMl5`fkMhILzUM^x|V{$o!LQAwA;0t7t)qA*i-Noe6rak9MUN32+rop?7J;64_L2 zPG5sL6FQdVR~g#z+IMI7au)U@@U+FWwCi_(z9%2Gv5x8&aHojJ%MbSD?Q-h~(ieLE z^~CChSUhCCH$TUzX8<%*%cMwQuA=^Q_w%=H#LjIne5 zI*BQQh%yqwbBMWN=@cxRphNuIsIRw6(PuPXh$BhOretwae*Dq$x^!-a6ib)IONmlI z6)u;{U61e+JUMD7m*73FSr(n!kw)4P2B!PwwzhHuk)NHxboa}by6C8>_MV_?XC#62?qxb zIGEwC5Xdp==`mnm_MBOE(7_OK9)S(w+26m_p{^R%N-TwocY9haa6`}PV@trd-(!T- z;^f;3x!Upf-hXG?+uP=Byu7@$QlhuDbs-dp)>!MZQB5vZR9{tXDMK(fH#T~FZV`Gb zbr;6R#}^k8?Q`&Z>wyvctrO23<-S4~EBt%;|CwlEQmJzf%aYjS}7+_5Lr0>iMr)OT$(62w~bl zcfYz@mwfWVlTM6EERUe}y&h`(Ic!B}RmgYgIf;zrlxEgyH`|z{2r0RaJgx!~{M69bWfPg`3BZU4aP3zX#n|CR#`POx@EI?|x>Pa4pF^7yWD zlJ=861I$9;)2GEqoeXYtr=%Mu5{BYdi({s87?qT~W|%k1bM)6B1r2`v(67HZd)YiO ztm{Ta!h4o>Ih+d=Nq9F(_OK673W(dkl)h_mpd8i4+f=Vkynyph9^uPBZ{qxb!h(^E zE_8@>I|!?KhB=Q8d!y%48XFs1-}5wnq>4>t0Lbm?J#CwIgbd@Xj2XV%5OsoGQ1Aj} z2O$B0I$~wl4d_pRqQ|243NIC_Zk%a^3rMiZSHozJKg8r&iRs|0?Uwy^kou_gsfCIg zrbjbgJGSrK@yB`@ahfsb%cJ&W!ah?sO)u>0M%JJZpsiNL*CZx z#g@a&PT5zn0z)lXRv~iQDzw5ypSjL&)WP|HJ`P$;BN~{4i&*fLnp=_{k$Dj;GCCb- zbfycdANBd^y?%6hVcHmI_3?`Hl1hGXo{lbt!-+B~vA_&g1o}9rLDabt`p{|EWn(Ws z*j7MQEE%st^%K8njJIvkO!K3ZqCN-r{xA?z@c%Bts8VionsSx$m7DA(=S1k|amoo= zsnfDga+B;;5t-so&*z@_*13MtDV?_h#i0~+D}x@hc}87p=^tJ58M&1AR6JnN79Oj% zriO%QzD(l6fs6S2P~x)X(IBv?d5PCW4@1!OSHkW1RQ);+{fi}WWi?R`f4LPuSj);(v{n#ziC9zuJcoT~R^F!@8`|tO#%$+)zs%+YqKbG;M z|CGlTFW5R7^vAcsps#xHBB(ZqS|K!m-K62MM}zE=a_|siCuKWkP>d-zX`lX>FwI>b@ei}{BxFsXlAu1Fj4(u~~D(2xtYp&_tv z6mJw7hYYt#E;ozTq~0NP7i3=W*9_~@5(-(idnoS2{nUmtvnM<%8k^P`QxQUGDk$}j z`7$SO9|ig7jV^?PP)x`56gh!jq`Ojr6&!t8x{H(C;4+&{1-v2H2Pi4Vpi)mchfCpT zyOXGpUE9W@Ihq^U>Pwjr={9Ug?5^dNtp!qj{*I2}b*kWv;fhqakLM;WT^CS zG^G3O!Eoz)1i^$YKVzr%xa{#jq7Zv25Qzhh-Jhgng$tTGcIpJlK7qybN?cBT5PihU zn07zkAtt9nAurev`jd3)wGV+_>+?4q?D{S>5A^E*Vs&WA-fdv!Hxv^V-NA~ zoP~5JrOX-8Rz;2#-NTAO?86@BqM{>znWxa;EF^+Q+)-}JTUEj3rXrj?Wb2?!buCt- zym~MzrWlYXrEO7UCmFbJV`+f8fTe&j;Svk2clPv@;*VLrzE9bL!K#4{nWuL0`x$6! zi2PO#QIp6$P7`U9FpI~w;#d48WTI5Opdc6HINU)G06 zwTW5|lXS$n!V?-+*2_o}gwURo@FveHNv==2)todnMkbYgEjX5Ns(VTvZ4RSDXW1^X zO!3NU*$$N$rl;+g;o5L(r5e9PTyK&-chF?xz7&)tQgdg(yElveAu1&6t-nsRgWXBe zSWl!AF4B#-5oRUdF<6t6)S~_FPA?t@I{&e zn*gIob>xD^t-PDc<_5CsfxrLR^W48kxOoM*)bZW?S>IJ1;SiylT7Nj%l4hcH|LHT9 z>>s128#?oNsTzbPt4z7f+cO}?L<9+#m8K=}9rq}$KX@wUco?wZQg9>L5kodNk?TqM zrb9S;8S5L3&U2JHxBU_g6($lJm>UMN8n#^_d{jSxG+Mgx4JSNp<4?_37C?7TqlR`x3so)Y@=5>|$MuHLp1 z>?hXcR?=8+g=e#Laa>Wh=H2|J0tpI&5^nWHNvBEpVZeZn;~uTw`FcEH06KtZEa~u4Xwqp^>P)@@;L%m*zC za1K3fxVvjyf956pq^Kl!m^9MWBzGKFJ1`DFx3&s_LFTWXBmQO(U zrl9p7aYwEK-J#l%@~(~6Qtp@4X;LU+ZWIUqDYMrAHod~~Emf_JxIv%4Nk!-TuLX-5 zdY(sm2)}r(8GNckrBzesdN?48CA)S?3jDO8ib;pvA%9#J!vE{KO{9x%q+nSDdL-@T z7dyi@P|Ve?t-#A)I+cu2?R|t-VUgPHgAd|d=%fFHEjd(;)uUbvBI8@7Vgw$(=7J*l zQct1?Jn+EH0%aP66uG;*OQ@#&ow*I9H$hBVl&iiSOQyE`38XE2>_D;)ri#g9djLo> z{N8E_H%^DEAte`rBNzQ4B4_92kCHk*KMxOxF!~x|EO%*Zt+g1f<((fyrim;qTl57e zUZ2#ysIi<`@owbpf&6+^Pn6Z#8-%cI04L4KjBxQ0$rFp!F4Za?d;xU6cS^t~kezh7 z6NXaxQ0NE!LKBW6q{{WJi-ape>;{3qRCXCj!Gjs~k=m<_Nh`+guvUIrSesgbg6=n1 zjjFQU-+&4B&5e3==GrqLP47@jFy0<6s;piI5fQ#a@)di%eY>F_R`55Z+AJ~lwCBss zVhmK;9yZX|uc&sWmo2mjy{a2J1s4pq{G8rk62ZT{W)awQE&rZr`^?$6G4K~2pBLpx z&G-YXVrXWB3lEnV%@d#dl>xG5kCwG&|AytT-6psbTPy$MY0vizn4#X4xaAW|%F zy*qc6)VJ^Q2>kZI*77|=+>cx3QvqonNA%~ZX7}ftTyXu;Gb`2)i&{pUUB5HTJU!a= zfo2G>WniV3wPp|s%xFQt!6(mKjTI8&R3F6$3E&)T6zQ|w{X+{0?y<=;)dN5ipJ05q znQftzh)BA09$qf< zLzSVb)>PlC`3~Hw{fpF!%h(Q^PoF#l-PC`zwinCmk+(msh?0Luw#U6RnkZ7txB12_ zTOz+60imTE;eg)av3DTVN+*JHWP&~+HCII())&Pna$VO;PeO?5Qod4s`d@lIP=@rh z^iM6dKYq~Nsj-o<3Y1BicD6C{X@X!z?oYNnkhEovNXGY-D?wxJs_7N{>NaNU*4^Ij zy(S{RI$w)3#%688g|38t?Y^Oqlf^QxcYp%v0ElP2lh(9Cde}OpZDGA zFMxRC-&2Z+@zvD0UHHfLi3*Rw)9=|h+S^YZUW5Mh-@kw0cPSgtWBT6nCEU^~6#xBi z88<+M1v$5*pQyz(8f_5y3*Q%+s;W7{Nh-Gjy(U&lTEv_iUoBB!;j!N;;>C9vZ8NM| zd%C9^b=q{_EiiM|L(OpU_C5}#`I54>WM1yHgBNVXD>#Udvz0pqQl|g~XwDXs`LH|Hf z)wf>^(CuUjLvQ&c->*JiT|enaZ(|Qz`P~^`kQ9hr4}?a?6MreF`TPGYfY8@**2pIx zeHzaomQ1`z#5~PoV1d!_x-ZAO!|=clLI zGA9q)wmqip`Ziz0&*h-ndQOv&5jT!hFLXF{H-D-@oo?yV)vMzD_Vo6a8Hwuutc9U1 zgWs(737Y}`L#kUkHFyNTQUuUPeu6@Ld|6YL*N*~)s&48P5Wj+c*?G9R4eeTGejfX! z%7IIX@xiD~Z*H6OlQ#g(pn@9)pLDt+EPqY|1=`qHBwJo-h{I3;E3vC!e&@uZloVrC z&Mr-ZhTC5FkLw2XB{nRTJXT2o^0e}Ey(=CQ4q)#1H2wA{6!5s84wn84=mD3}M#{s| zPK*a;vFh+Q=7WqiPplWKyVn1(nR!oEt0Bn7-u=LBjK|iWH~}NF>vO1)Ta@H4W=_M4 z)&5F#=2>*)HUBb=Y&lnuWl&Ev*?uSfc!vrG8rqXl7?8Czjy<~b=U|!ynpj~0MPEjd z-9?%f+~_CTVX9Cghd3qFf37(@)ays{l2q#CFd|V|Q)3V45%yULD zzL}QZ@jfh3G!<$KX<2piT$OF4ACAv$>8j~KQS-bY5^FWtKaQrP(U%hu3!?Pg;5gT# zo75<_(C$_|>~-88UvvjArdpibY2gG3;AkC&ljSktC1j)27ou*-wd!jUNV%%~V#Eu}OZBFL7oGSxS7LHqZ6&?R8#PA|XxqC_PT~~)J%UOq3IBORnkIm6peVSxyuyPSry>T4Q4{+oOO;1--}gA_4fw9Hyp=~%+x#J6-ygN6 z_7#XbyXSw2pwm}it{F!TeU=ozH3Wps5OYM*1?JG-4ot3vmLv%?$%>hd378Sy=wK+n z!MS+Rpa^${kd(1M#si(4s28%#W5n9wIF*FuBwx5IuE;rBb(POpl=1|;pYLj`R)NZj zT`VLNvZ=FhDrA0eWpC-Ao68LC@CTcwjx(#7M$C>I@_EeghsG;a$fNO)nzf1q#_&*i z7>Ux7U0mS#|K(vDmV4b0I_=TPuNfSsySuvqkIZkSl9sPL!iO{xZ zkW;Cq(0PI&v=>)ngI0sG*(kP_)_7+4{R@^rNobYE9(Xl@BqsObHcf_xNMEp~8dT9W zFaRbUDhffYi?pYHR}+{T70Qp61BM*zfXU1orSyC$^zA(FN__S^*rtUBG0&KKKMH#ASfnY#c% z@OQ<1zMVU0}2GA%4nR~D0h?s@3;sLj9d#C3g;HW)@v%781D%8q4+)TuTJMVg9)xIkw$hLaIfeb8~{w?1(Y<Lj%5S=}FDg^0-v>T?gPDSsiBy1W&}YJTOzeti zOa4>EI>U?dTX83-TG~^{ZS&B~elIU<_hFhg?(kjkSx$4A>@$SOLnHBQxd}HLZMlhDKGt867_nu_H#z?rcTTdxoH?b%P~M!cP=3ce z!3Dj39I@0mvxpJHG>B7tsk{MVDh=`v8o zsr>nYKkPQmL(WV=UhyOTqqH8iWbL>R_s}11jrml+*OzuuHHUqWzY~xC`7>koJ+&rk zt^mM80O%6U+(T0c>~ZayEu6El5IyBy{c;TUGo3%L{;Jy9TE%k*n_v%5Pk*xlk98Yd z?srnPOcVQngk7&sS)8&@oUho<$DpKz*ivGBTO`#l{=nB5S9yg z*aom!?t7H7EoCm-4q_fJB>K!FD!MCXP&_6;hgmCjjh8nM$;HBj`Ks_ltn5f~DDe`M zr&BN z%2wxZgTjl-P}Ir(4*Kr~$v9gMytj$3@f6E$ko1743c%v!DI6hH-Ly1*3$>0Xepe@u zEJR%;iou7`S3l2#pO0*`7rjz;NiKw*US#6=b2t`Gq_<$Q*bEovVS>>x?!(s3&VVKD)!2sGm{V^O`p4!KOj{UY4kFTjj(@Ac9F>$fuKG7g`U$o} z_wM?*Hj_A=D?Z)NbON$r)zXGl1#~5{UC@>Atuh3=3DZg+g8)5)zOQ}Sj_zVX$u>l( z*=VZrD!{+s?IHdxf^^YJrPTS6YjauKHJ%lrMccKhe<31mqLeNU4Hae2oUQSh3vM!~ zIXWV}BO%&)o^xWk;cvBy*`D&$;2G<}Mu&s*STsIbeNO0mhhYt8S~tFD_eM1{Vq5Zk zCqx&%=~$F_7no5RLc-q)L)J|0r__y^n{>a&m)S*0CGnHaaX zijezTy1HT@Y~h=gIsGA!LhyXdVhDUexxv0<`F6YoPb6L#{iA4Jw4jP9^Os#&Tw8DN zU(RILD>EGYMN3(-8|Ti{A~=z-KeWvccfTEXKZ#S7rn1icy6L%GAIMHZd2gfcX%dA2 z<9f%JY_ZR#StNR@K_+$L@#@HUVV%L{wLliX;|6&kDG}mQloo$x&6iS|Y^+1ycmD(8 z?<+RiV$~YKU?QSW@P{9k3h~<(ewG~5M;$JuqW3okk}3_Vt*fEkTD8Sy&x*usI~jSQ zPI_xH^qIq+ET%R`@P7Bb;Dd^CQ)eg$aRw%VE-qK#`a5KLV*gpM+4RfUhj6+(yRK}e z8jrB@Ou;%*>A5s+OYHWDr%kTkkBeXgbuE6wxQ&y(;V(S~z-)Fu`GE`DCo_I4!r4Vw z)k+4f`fR?k;i)O)8yjjrAj^%}C>BpQvI>sOtNlVZEWVT6y0 zSs-VaDZ*+Uv&>S0-X+E<`qDzH7~4T6vRB#J%DUYaHU0CMz)+!EA@q%Lw~(4v42u6) z(=y^O&4)rr*tW}Yl#YqOZDf`bc9KFt0WGd(sZNRS=oKaBz*&{jtQKuLDV9Ie#1U7H zzv5+VlxS=cTYXB{(S$)i!$552@d&@&L@7I@Wfb$9CYUv=grvSlrSn~Hg&Ac>&W~xl z;hzemaTa?N=&mxk{aMuOQtpt<@wl~d_A(=q`%d)l>oC}ghK~isV`P6FD($@;MOaO5&r0>^#B-Gf|^F)o^o2#p*r{?Vox;i&L z30PM=Mo6s4QPT$AP+C$iQ{r}yv@T_m!Y90Q*}f`!mry);K;op7bxT0+0#p=8d;xP% zt{3`UbwQQ3=66t?#Db3cLi700DE_E$f*{PjN|H{w`MMG+{nD_1J8-t`y;(MYtDfhn zh>Jayw%p0u?aBOaO&<3Xw2pf|1K8wRa*V@w-JmieCM4X?M)!!cI(6zGAy;C2O`#tY z=Dna11=C{C{{dA)PIzKdM|=A*Gd+5rED?wc@VCUw3(w-LBpiA?X>BfAMzDJGaO+4vzal(6@$qIKlUT~a-R;>F`Z3`SB5`GIY+UH)0Nq+)T; z>fOE_*EP`0j@|hQN>N`n!#|0~q14A`7Hy#Zp3N(R`1~Lo!mp|#V|YKZQFH~B&0E&w zVC6>2+Zv-A_uuvNH3+E4t@%v+`Ayj;9~)%4(Lpfxo|k>y|7A*Lb&+y^34d8^)i29Bjzipvb3R7C~}!BcNf9 z?AkJ)^Psb}pi0M%*>-b_Hyl=#gvMeJIsfwUXM4&0)6)|Ou@BKGeNfRV>-2VUNrIEl zx(5y{8HMO`&El$uIMJvLW|#3=^OJDrCH+MxdsJ07(rXE$Nf%1dnHc@S>AG=0rMI@R zF}8L&=BEOito0KPI0(x4G;hC<`rl?W#PG0j4fG|2F3~&q=n1(ED(9CLq zCIKckR+_xUSs%~~U5$%=mO@#HJkY|{x3;=Lx&A51pJ!^|Sx}sZbZvcOZrmL+heW9$ zOK*GN$yyiL7T~iXUytsMry0uaoW5&fA%oO==`+vM_FJDowsxsT#1wpeRbo3N7dN05 zHPy~NJ%PH-id%OYTVHgi9FtKgb@3GWe5Lm)>BNj(IZWShp%NSkj)bzYuRHu=7SH#V z#hU!G(LXsgcTG{rQ>gGK9acpuwKV?CaxBmy6DMjuLP!|giMlPq;cJU|(y}rKs*m3g z7S1%ED8`7cZam!q*xi;U8g11=)6kYUnPM_TQa5cyZ_>g2I|rKopUkeG-95J0Itpb| zHj1st2xT=j>1gtc{4_K7t4CkM+BHA5Di6Yl$2J#|gv2$!qp_)mVmVp(N~qT;gxFyU zfu{+EpW#&rzkjBeqdI!#2!E$d3E#H~e4>Gv?_*>xb#+DLwC^B^vy1U!^=-nN;c#XC z^uJyyfiuodH`R3$>pgIE-Y5MPOGkH}Rey)os0E-dz$o#ed8x@0f6mtMd^U9kXkcg- zx)KAPbb=sSBVSoaESbtPZlGHmo#K&{5J(!9tWq?$yMxrJ? zdqUAa#M_{s7#TKA1}&IGoo=YGON;Q;*7?@$ZAo_$>IqG)GM^F%u{&M_8bH0LHOX_Ix zZ7!i3_)q&Ss4+Cn{m|UE973$2+r?1r3+Y?kIaTL`b$G3RyY0QZzwiIoxKM~gj+YH< z(ld;=4XR~@;jIJh&|f!gLDK-QC?O-Q6u6B3;tmUDDm%(%ll$AxJlT0@4z9d&j*FfBEYi z&-?DZ)?9Nv6XO-QSs)U3(#UbmMYP%}@~tCY98>?mS;Ua+jDPu%Pn3!9Wntppqgze^ zi#HvWo%c<^vNr8chz`d(1(P5#Em2Ce-wXtW*gHDD zmyzkWMUbm7QLr}tbH5cZ%eS(ozm3A^n5s%0=WGKVV4Yxw*ut^*F*?bq%Kc-`h+e(7 z=GLeK-s>O1>#WrZ!Sr{3Wb>=9F(H?Jg=&LLw+g5zi0uHfovO&a?GU8RD5Qbf)yc$d zP0q=&|K#-IR_61}&t^0}~p{=aRA}mZkj5yrz8bMz$Gw^QIkvmqeB-^mMrLaasDj~WvW&{dC zO^#uM`F#Ae>bS_V==@+64RsGgGLHvRj@^Gls#n+{_?^M z552h8A~8`hT9S-!j#J|f=%LD9KGzJDFkN;i}CAUGTP9(mua0s{J+T>@5l zRs)8!9Mm>BC`;{Atg_SyStg zF+bxH`0*2+G*=4-ZBoj&<+IQ8U;KjU^1ajNZaxCM6cf*Xe6uVDH!HxG2`Y2}rK(gM z|4ccIBQ?wFELxk@k^R??3u#}+&<{)F!Cl?X8C+z?AN6C2q!fkuOP7m67^cT)Jr}N} zJxm?evw1va6rz%@7TO=lH`bwm46!L{;ec1LC>7x6_X3zZJlW1H%Uef_t$v=KwATR3 z!q7sd^A;0E(AWE9B6L8yXB?N4esY` z3g`&ladTq>`0Ho<(2e1g*8l5!``ahV&u{tyGMBtTawSX@bsToJY^FG7Lu~Q;y?8fz z5AMxdV0(Ce-Z+)|gj|>iT~u|Mv48M_an5EwhPChBLT!(%aw4irzmOYE8SD+fJGy_@i`2|J1@1 zmcj8sCPAu$ZH*=7lnVdgnrHUEj$3{nv{P?Xc@JN&4n_6kB%bcp{~!(C^+n=y%@{N^ z-wG}FvZ4Ak$~Z(9(9x&`eoUonosfS(RoTvElwcDnX_sR)Q;6{3$SjFQ^BdJ}5)WtM zrDA_*l8zS8vJ}Su8Tuy&X($)TOoknwEkAz>l@rZTao#v zjU2L#4-?917IvC$l-kZ46tN^1Jo@^B>V*qBNvslcZ`uSkI}&@;>wL4? zNJGPDRH&B1L`l-psfJk0ACBaMQxA(Mp+c?W&nb728|YySSZvHxqeVWt^w_l!yL8y^ z?k0D~d!4F?!6KSb=B%#>JfRlrpdn$syb5(3eKir`=XtFtEA%3f}zRxE$C<-LLrQ-iqVRo)muEGh}p(BX|Uj_P4e(&E_4~*)_PX_I2 zx<&JAottSb5Xfvn%YjJWWVO4-a4|`K87bdC)={l8-PiV2$MmsW16AH1>9i7fwe5Fz zezv#V=fGUujPJ!&7@`|26Qk!!Av?xFiWDUxs+Y}>RG?5^2CK`oW`V|-42y#IQw)9P zXMia@>3hI^qkuR|DAH-AkE3D=dL=coBaGYOE(@bD@70Ttaygf7{<+-T%o)5PGz?}O zQAD(`4?9EfS4i{uc*5Ae%S;t5LbVD5cgxGP?TShhAxZmAm=g6ADI#8%9|dwrh=|5X z%{bTeROrahCHZ&eWqB(^DqBi3oVCAgEEyHo1@B4lGrrhv>+rQQsG5bb)OSjuJOXtb zH2RP0z#$JpShCEx{JivW$4o!vMU8}tu+dCJdSeXXyS0LAHg?wm>K?5+^<32N33R3Q zgSnn9*WlNYk&yxWDN_$-jdZ4Dy?Y-{7bL?Zs^&jC`}@y?)YQ~GgOpR^f!sskSu4&) ztTXvM08JhqM%3U|mqAUU@?lptzma7R{730C?BLRSP_k2P(C6k9dtO??PWq~ep8Z^a zYwqcZdk;BUXpS{%Jz7M^He>aNw})>yF$9G80Fo8MpmHNN$JsSODrKgMam$M1LlO*O zkW~7N6E)Ex^aw3Q8&zC?FiP_87+)q0)kL&k|L_YvJU95d}2Om?Zr z(t*hjayU#m{$rOz=Nt=0i2r!hI7ldOr>97MUSL1Zjqy)v#$s+tv8TzqGKe|pBxGt$ zTId0TqwT!i&~=QSGIGR7e)n~0c2l9vh5i2MfmPGHeIQ8$JSV&boo(lUXAqQ~jN`yP z_tUQs_mTzsd)^&j_<(2k6wSFN+I6=q()iR=KE?w}89m9P1?nMmdV){;y+bEpKP07- zh!3M}D#Xt}qMOG5y?(hIE2aAuCx#>Dzj$8}z0mT5O^+0+k5C5REorQ!#lL2}t**Qt z7&n%a>tC~0VR@0*P#FIa(t#N$hz%v9PH_0Zy``YP_!1dST538|EsDu379kyi1>Wdq ztLxGvmF|RTm@s!n(+us3P)?^1;{c!HP>syP31DlIW{+eeM=>0HZf-j%b(TfTZ$kbA z`P{{8>a-YHsc4il_K1j<&6%sMRvS}1tWqX4sUGw(wZo@23^8&s_F{}c8bUQP1RjpS z5Bsn=IunnJ^(S();8}o0`6|s^hHR0U%LOfEMb0NjJL952@k^`8Q46_q`XxMEzAsX* z6T&wh?u+o^D<7Bs@-ViDqP(m2XhCCd{Cx&uzO z_U4Ombx1KMS-*#WvO;`Z52X!uc$)L~lWQ)~#`8iQtx!cn4k8FXLK}lF?c8!CCGtH( z*v_1Oolmh3#+<-`P8#TV6* zYu-ke-%^Y{i*tIDuHR~%ONgcX;nTl?tP7I`M0+%?T)|!Oqf-$3JQ}fPPa`hC&(BVo z5QF0G9+P4l`4~9`m5~zD$&HQ2(1zRku?5lD&Zkm(g3ObF11G%ztRhT67$ zeb>aB&>x)(8bK&kEGh>~>T zcDPMI%bNMUy>}xDrmh9oKajCm%Kyo@=6Tf`(c*l3o?N$R)rk zpbp^VuvXww#l^!REZ&NqB1@P$I6AH+LOG%)eNz1{r^zM7w%jYO6Ph$EQ4|q+7>oI1 zJ_to28mm%8k5hh*!@SFo1@I9f9Fgk;1O*pFUq^6F{!Ls-->yi_@Bgm6J&L~368LOd zD`j1$ByJ?KLSmnBGbO_O)K)e(sw{@yF zglkB%!adP%9}P<8;w5GLerYn{N3>K_`0L$Ws76hl`U>MRrX}K~mQQU;sfh7<@azl; ztQcOQQrbkxc{<&;ss^s3{9QR^7nlyM#FmrAmKyNPa21>L(-_j?nod3ew0M@ra=QyB z0%1FG4C0k!I?A|Xv)A2t%t6Q&u5}5g9um*Yfwb7d=Pce|P6)1pRUEhC6 z9nFZ$`#BaVjl4aj4{=nD@eJ^a-B{e3E5O!E4pfvG{S?pA(0gkvbvyrhMUKL3<=yZ? z7%@p(2pftOx=6mXV7N#2q>3e^vjWJ!^4 zaABwFVNtTfSGNumX;>!WsUU6Fb<~uagv&QUS_<2&<-i;RFz>dwaues^b(UhJAq$8_Gg{7cAO72T+0^R{LJQfokmMw?@fQ z>#J;w^Yq4vWnl(R3`e?drqVClu=3*o`v*+O!26Ko3=(p)It?o6FK5bR;mQ^&KcEa# z##=XWsh;&{H9FpOb)Ws}XL<~z!@tqK=%LV9mm{H3c1sEg8CcOtvxK+Dx!VAw<<#uB zNt2H}C!y|B0y$>cJw3t(&*137w0SGe`JwOSKc#oGh2kq2m!wyizEZEIHt=LHL^sc( zOx!#DDd6>)|LQ#a4Qcl_tzcDyF{Y~0Edot*t6%t-;W&ss^6$IjN_XL{$%oM2y6j45 zhx#AH<@|=+ZZMD}ej$#+~M10`n|T@v&^j7)}Tjy!w%o)w1dE!1)MRs+r4hx63s! z>9xTQze}1B8>C(8b^k#%^Iy)b!vYiyKQ9IcNmo67q5Z*lblXHYr*75+O))m70=gz} z6;8`U=h?I8+7-gSr;t9F?4bRX=&a#2?jOI_r9h162BP1;499y?ihX*l?;Fc%csy}m z1P+IDX#?IP+N-kU_9u8`g+&G|s{N^?0IAxXGLA=(A`v$OZjr@~6E|=|WDogW?SilC z3+a2$coI3rqNvz0Kz|!%I)wf?_LAg=KfeDdfUhfsT5#d4^Dk_{4+~4rCPxS?DUNeh zSyYwtLfX572Pi*S)b~P#6j-M6ZfR9NEc0pq!YM&*ZOgpANCub4lfuPPBz~FsD>Ch{ zZ0vIZV*#@oxB|{M;Qcd&0J2XV3A)b;+s(e;sV`BvU4wYMMh>N3tRq*RcyqVr_ltB` z7>onOJrDXEr}#RHicD&GK5G9c2yULzPzsWMzJ-P$?4)c0Ry5AWzIt1-Sc(vBS3{{9 zi};?eG6a4$ zTWs8)TwEtAv=0c_lB@G&z?mhbu8yX)1^=Nt+TiAm1(hCN8F$8j-x)F7zp26io66&ob7G0@DA}zJQnQ2;XFx(E#E(J4t5X9xkYJALJcG?!zaoN z_oTJvH#o(whI%-hsYMzVR$UwQFdw-Iv(19fj2@0@#*(gw<2Y^p9OjhbtqJYX8~IA_4W6g$nnM5;eeXlXQCg*1`j5MYzT64 zc#BKbu9pdtYoeJ1U2GUHZuG%9W-%81ki8XO;W&d*PTM4uadbaOV4RV&rWwI9EamL3 zwv-cP=thK%mGTBZfn^FHuU@%Q=9Qe`5*MfFosuj}(psxC>66!(;ci!+om@$Z7Vm4X zSD?y;$dp*vT^pl8H?pit4)2@$_c%R+6BpPJKo~MG(E?8m7GsnYfwopJd9br8ra)}7 zxuO=vo((#QRIh ziaCv3_Y&(MEf|c_!GVnl*&>he(X(Tl#0o6KOSqhvV0b0=A66Pj4bJt5HJ42_IR6C)S{E*^M zc{-3CtAO%bJk_xDr?kz3%8)|*x6qH~id?^p&*vJdZo>5(y*^3FXm$GYLY#e_eM%(f zIu!qL;)`K8+gIFSyX1Vypz)ohg}rGNoN5)lWVa%j0ZE3HFJ(gR&d!hwwa<6fFediB3a-sNx6de3Un>H;y+eSgX-aQqJLK(rqFGlW=Or;Lm_q+j;ArMl*C%4DL zXJS>$*2D$r1hY=hfUP4)k)V2bLt&X9Ro+eIUB+Pm9sk`^QE!ez+xmk_@Ex*Qygjz& z*dTn@Vm>23?JWXXB)Vag(eGKhj@5Uqll{}Vfq^}Np3DdqG&&pv;R^0u%MY$$fvbc0?HzHpMi!bH@Ka)+tX+( zu+$o^X>fe(cYrW2p&_!ZVOWS&&=I=aadHtCo{0N>`?L-Jpoqz_c}1g_1v~kc%NjaI zjpFxX_Op|RN13U10XBDyYKLAa%I2U)&GYi`-2=O`i2&TAq@KjN=5p6!F*3*9E}zR% z#I7~$Q|wJOAH1yTv|?(8tgkrLT17$N@kQ=b*=?FA4IkU7Tf*l<3dOl~-4jJWR-C+o zIuGSM)TU>kAhnW;=KtzuvpUC&<|T96v6eU%$g$1PwlkY}Oic|STQ|%QoIx!ygo{b+ z0;2>3+_n5u_?C=q(PEyQI0K+8nwY$Sfi4L()4G>cJTszPc{lnZQiJ^qU?opX$X!eZ zoTwZpx7L}|&ytQU=>^+0pvy3;uBU6IEo@fgk(v~HWaw%JA)I_^ymcG2Hx|!hQ*#Xf zlqj~fA}DS6kL4c~!2}7s-iBeC3k&Pa$g9QjK3Qfd7FOPM1h*Hk*~j5Nent>QmrqbF zMA1B}O7yC9KlzjrE(3a#a$pZ}JiawM0$$Kq0RY-+eV?_9;N3{@bYH{v~``>Cl%x!5-rLaVMd zHMv?~uVH7V^h8Ec#t&Y*`}6a2@Gt=Vnu;N%`rAw&)fJu$D|V9(*LK7AqSniYzPZo( zML-*)+nk!6{e);*LNFPV(XU<6zFdw-SS3j8n@(D^npN{IU(IjT6_CPIXi`8)3qlcs z@gRQa)>L0~ze`a7t0}}b83)r?R18N-!q#r%Z=n4%*Z!m!_sS%<^Q)j*Iyu3`{8uCX z&&t?=>?{}tmLx|1hf7m|-0K36F$4YpKl;^d2V<*W+1pyPH7J3Y;Gn7VRiJ-8+cwT1 z3?ziX>vb+;;7(SiOoa5IGeZjlt+=JT`}us0laOkbDZr+EezhgfLAi*BV!OJUajHyB zvTxl>$yl+6{6CcAZ4PxThHm9#$_(k3EgX=78u}F|1x4zdd*FzNeF2Ge%i$Yz(kB8& zc2*02#@RkGC}Iwq65{K=LNon+esoo?>JWOsQY6xCZZ%^lmB2QKHP#9=%m)Ci{l=_X z*j2r1l=)qJO{o2TEyRw1T`}iX2j9=t7owA&`*EUd<1P23{a4(vJ5A9u1pRjB5lh7i z3!+FL(sos59X&DTW$7N#; zp6-Az9qDz$40wG!(rw{(_*yA2YU~6;(ts7722*=;HsF5KlZ|g!B?U8AZbx3s9E$RU zvppl7c>LHb7(EG}`-2Sz;BW%~^AM;!V746P{w5wP8yPQ0ebMYl$aFY+)U)X&l7tAn zDDt-0dOWr`7w#)1)8&+Bfib{ZqQwzPR-}wFe~i;;rVwUgX6E*xZM3_My6K~5iQ_kN z`m^d6ZhchY)Y}^whG>j$ZMr9b<-FrY=ELzfuJVAlC-u@mBMftpcu0%#Rq&17SU8+9 zJdLPv#iK#N7CTG_$ql(YX$!>H2_xlRU~tmF zKD$j1;#~0u8al(ji*)Jw*~~b2ju`a*ZUKdAjTcDkXQT{zbS9XqT(xx__6b4LDNNg+VdyZnL+ z@8j&;Na`dF8un5Tit!x7#H|W4y65$c4XguNF$y69t#@JQ<`VKHHwY=WDkBWLhNbKb zIYuE#YHJ_I>;?y$Mswqb6VZFmKVlQbHsfA}>rZ&lx)b(|M=qKm2AfU~_%>=~FaDU( z{(;JaB=+7TiXitr<1s#c{4s>0#1cuuoM9E7v=W0HiTZ~5l+23#qE|d_Ztirg_62&d zE*hc)mwS>kW)}Z@Q~0lNH;*8|8r1M$h`qd=PD8x2-NT3zbzSck&=PJ>9kbnMsvGA8 zrYJ96p1(sapLxF@Z)0EkKixzHDt}w;{cvFTIQmXdoYI&rQxRPH$y5x#y;<^uCFvt1!XN*Mn`5*s+L3@(dt-IjP zgUTE>@wE>gjvcvz!l5*8{@e1hCeysC+L-Qtrw_KlPSgjpaDzNq@8KCE4Akk9 zkWsTvx~sqVP67PnWBka7lrSt1rLf)+GBg32mp!VG2fMHMwdR15GaS7E3{I=``bI#x6*8FIfir zC&#Rns8+}oe<&HC;L*n4wS}+%>HhS{bNYUh{FJLXoVugb6)ToW}`Q_m{of$ zmnn)?i1D^^d!qhlap(J{L(-iML+jeIxX8?@Ts#>&Qu)j7u6P9c(07lpfG8_K7w>9o zJM2HdxDYE~lmCx9wml^1)4WhS=f)3OVC058cws!Cq|^)YTyD5iH{{VIc(76dtkhLQEt40UC8}hf3Ltv&SsTt_NUaqdLR#u1kZ;$zL=B`^ZnRbnz zdNQ3Mv)ZTQleBQEL5aW1OH4v?jr#ANGcb@SObblI_!L46Tkaa1K2s|sBH|IvfVy@D ztlcJ>L6KaxU;wqhrlAXMr`j8k#|B724Ryp#+^k9$!$meq#jmAKDn}`f@!R=|P5;&6;B$6@_&v)(_bsw9&NYfiKc4>DnW_1d2+|CO zpnw+MIbNI&ebQ{4W_B2^iNCP_&M28Ei z+T(sy(1T=L@SH4!s(i=H9XHY~35h13jluH@%cDs!D(9R#P&U>h<+e+CYHS`a8hO-#m2j96Y=w-6saK^lXURZB(6m9Dr zj0KmfQnU=EOQ>g4u;q}yB|zf{-Di=7I7c(N2C0Gj8-KJTCCh$(r#AM*#@xJ^2G!Wk z9>;urA6i`Cc!?F!npOxF*ahK?_*PEXI0L8VU(E8Cu33-+1;~(RKztncLUNcX`EMFys8_tKQLlL=KvA6U#YRs6S+UNM65(e=( ztQ^}5>B`l}$d?J*M+V`Im6lSNKzkgwcY3de(wzbhw4v|^gAb-fJX(YJWok;cSf?{Q zS~>fgSQ5{lj7u=MiuYcvuVEHYKl9xDe*Nz^IMQx>!K})RM6Ol_a$6K>{l%7MMEE%R zB!LqIAM8q0oVZFAkJcuNw=WartV8o3Vp)US0xIRajV{sMU$KwkS;ehF{? zzZZZj_;U8n7S22<{dobHvm}NahozvAk&$nj7uIUwV9U3IRLufj&P=i~09CQKw-;4Z zerd+Id)}=qnoJcKw3HcocS}x}L8k~J&AuEs_C8vH z;!iwh?8E$tKY3z&cU1V|HYv7IDbE3PTK!UvGuMVZnJj??Xc|kVW}Q zyMHe)Yuj;y`V<&DwgTQ>Zg07xgD7R*=AO9HS4^v8;wb4Fzjc^)Emi(2ex0XNija@* zQ?f9@*}eB?v{T=}AZBi}n{zmYrjEkWV=IY1pe}!1d3!Pe$xp9GZ_oK~1Ykl5 z?npQU?Je=!Yp<(j0xk3gYExN*lD6GR4Bz3WCxI@Vj?z)09}+e`u0kpAJfpoTHlp*R z5FZruXO`gD0*aNn;C>Q&whnN0XQ*i)1;tnRu%~+%O8eAiY`LW#KVIfGm4&uoI6h_h zXcbg6mU=&c)^o39Q}XY@jG4Yvq?0wJN%fOi;u6L7Z|Y0#u~N%I!Pt4IT#j76g8p^X zEc!*d{h1H=#TH9v4OV%lAQwC_@dksKx5^c62|Tr@7n@)sTft$N%}pA;T4Nw^1tTde zR?AxOGT}1H26@*6MB7Ii<6YwZ3hMj|YF!Xn@y`aa03Z{&y$k6CtzJTZ6lx0R*>#}MyYIQi_PbRpUB%2^qYGb7;1_qZZOl23pVtKm8^}gKw z1d#zlL-5_n8bEoo*(pB#Lg~u(ue6IJS6nLAkPg5 z=;Uafir8{iF(0zsjuMp9C4VQQ?f>pHRgBd^4c`XVYK;$UZp^;@Pa6bGs0 zN{JQ2TA>5BwGXW`Izs5QB5tL!%9hizTA43v?rjqLJFU#9PwR${Z=Jmf#A!z34O?%c zN1tqR<#XcuV`e-Jm`t{ns)5#bTrFzX8dO*inprU4tb#Y`&}z8t+Z2)-(F!{VPvjq- z(IU#K8$5H9k466@te+jC4x~-p7eO@Q#OJcvwf1(N{G7QWKMbn>8Em;uf)5LcO=>@@ zRZp(3F^)BM^v~zl!&7N>1H;rx^4@>?D$}wkj-Ag9Bj#M$uLiSxIVK>O#gflb_=L9`89cvw9UUsH$`W$8*SplRDKMvVK9y}JqL4$uNhJ~jWi;dRj`4F4A-W%3>}h+BtAvW^xpAGV`s`Qg&7i` z(%#bErSguJ80qRl2z*VI?>B>vOHGFp8(m@Ub74F?ek~7pqJ`Z#{~Kv>8)Ne3sPp^q zaP)XcHULB1GDnfUCOTD4tpG3V09`}dEx0u*oILhFg41*jdEal9kqDP&$KM>cfV+;X z(FZ`8k>^cpc);NG3M@+A4dD3}!`MlInFEj>4Q?x(cU6)?pL`#zr5bQAlI|u9C$Zc?Rg9 z=VxGbs9XRhPOCw+Fi4x=>wZ3~_N7Gajwm(3F;2MSVc%zvN#ty1E2rTpxO&JEWKSRv zfoZJTyKTIgAJt6cAHmWNa+`Ek}_iv^uNBzYwnO(`Ls*b`%LMs?xc>w*cGJs%7^IJ_Ya{%SEF$GTf zI6>p~GK-uEL6ma0%PsPWq=b2QXwj1ZIrfUn#D8y->M-|>!b^3>P*2Y}`rMzqbrLiH zI9udBSW6Wy&K7Y84q09c??0i1cNX>WGxRlJtd(GO3r)p5k@2CLSc8pnH1TkAE&QK& z(}>U0Q&Tn#NX>wVgMJd8#BD;w#>=aduXe3?->%a-Jqq}lWZOCs^)^{Jr*y_R&L1>+ zK;H$FQ?|SkxP7A!$9A!Q2Az|#8Y*|b!%x1;PJ4HN51+;ZD@C!-fPSCEY!NA$+#Ufg z%l1(-p%Um}iL`ZZVJBMQ{)-Fd!gs3ZpVrJZk#0#1)vu9HVX)Js85&8U_bdNMN%eJg z{oVZSAAt);TK-G@j}bLHZ&* zU=E(a^mcf-*MY3=?h+T83}o?*>11COWxRKi9DL*jb{as?fI}=+pXGZOGf}#q(|w*3{O|3nIUI@jajAu=*U?q7SJl;QSa#xLUSI4u!2F{i(GKpi#Uxm+n zo@}#3xgrOo)ULYx`pVLh0%zB&aXj_+{GAC+4SAXL3Vf{&2_HI>80c2+LgQ8m<#cg| z8||G`rv|*1{qt&=RlB4!Eo$ds&5dLXa@SSH{^rSlAPA_FUhguJAY8ARM?XA_$$mIe zkZQB7lWN^_(B~x2^Ulh#;Xx>;QZDHw-F& zDgus_+-UmS9+5nm!`v4;?boK=UlsA1nd~2{^McVT)Pv!$$}$8|p%5G*zx-Sz`~>BY zsL(~*&00@HE~TnYGpn!!O>G{kr2PZA*LHOuFPR2J(vaS*?Q6EElPfS4LJ`wzQ1j82 zoz`7CmyDJF{#40dqT7pd=OAQh%{3m9WJdJD7PF^g*X+4-7B=Hm+B5CCxIr@ei71@l zo>@e*pWk2#a*PIfw-&#R=a9fTWWugPM~z-`$PX{Oe{ZG5b4Ir?A);{|=%wktWm)8W zLvpcrdJ+RbWBx~(8QCzD)nJO%kN%O+mxt>Q#AlGmxhDh_%^Avh+Y^kD@N`>(-MV~K+e*52df!c=5o`=#!(}{GXkcqZ&gk!1iN2tTcPdAo1Y){5@xW+YZi*M zH*`Jg5JteZZx!3t=4NJ#mec!~t0y$lsEVC4Y?2&`whF}Xl!=mPGq+=>QnkKjX;0$M z;e=0{SjKBZcJgLmCxfxLKC@EIGi6hm$xxW{02X^BX)P=8Yrkf}kB$3PtE%gYQ}YsAgvey z3n%(gQk_^)`YZbQ0n3W)lG8j<4|y6LNSz&1khkYzPPWHFKGzJvUFz{ID`SELK?hMM7+tk$6%-eoepi_j);s7FSaaL?N_8RMWthrPGXM0x#Q9H(j|j2^W@ z)qp{VFIJXxq!=Af_(yI(9q3M=?icu;GX%j$R!Ll=mz=QBGJjkM^mmT=d8+s6=lW*W zlEdlg=^NTZM5>MRA0EIZG&iT#7)1I=DG6mX?<4)EgTa8Uh^{A5#0r znLXP~-UhW&ZHL&$OGE6W!@^?JwXeT>|0;Jd9>M0J*~AssU5)2-((qvU;Bo@v->L{I z6oI?G9WomH=^LPY`4yj!7#D>OF}0GN zC)s(1-mAAf4MuwP*sbQc98ue#Ygps@hCE#;3l%aETZF4XZv3Y2ApdsEi@Z74ebO9@ zE>t?=dXMav-UJ4=$Zv!6U&Y0DDBshB3Q*jR7*SZ02a&CHjc-Y01&5Ayr0+rQofLVN z+?W|;FYv~1Vb7tLUfV(4Mkemv@R06yw^EY)1IF65up1T0Oa4i~4flTJeyOsq>*M}X zgm#p)XQJ>?)y2BWR}xQEs0KGLiY{jAN2?f=Y*b*6DpsRd@i8{>Pnw+YAdh-z{7IZK zni2#Yjx#=i$|A;)%70rHBT{&B2ikJ>YY3aWiBn~9hZznCLwyXY>gXokq_BQ?Sib{|Gud= z$F=w@2?lBcl!hnWBXo2uXO}~$ej1!F^10g1?9zy<$+Mvlt0Fgjiz;@15UtuAq6&ct z5*>xyV#Sa!6VLP-3VFbUDc0$VjcHBUwT2?b^16!H-Lw;feu#rqxjVWZAAR?IG}o zy|72kpM?4oF4D0k5cU^D2#1~$No^~bN1cv)kf!i9VcC00xQGV4Dn7-re(1hl<$Ad4 z7SKeo3)+HJ{zA-|@T1A4ep_e<>)Zw8Q2=WII8?kmtdJRK4Di2^kni5yvy?u}wq4L`4>FM2FTgwg@^#Lyk z_--5$=9|F;l=H}tl_va&GoxUcU~mxX!0KrF**$+sE(sDYj1h5FkECij{FDgs^N0Ti z>37is-#1|VH&@V`uH+;}Ahu~=!!~(*Nj-5Z^6YY41(jh}6`$7H%DwpAjJ8XUf-2{S ziq1LY4^z_(!LPy2PK*E0c3_nLj5^8yP1w<^dv$gc%SC=}g+uXS0)yD9uDc96&5~W%R?+jq^_nkqpb?U;j=P`XOmm)?JO8xdwDZjlUz}aTikvMw+Wxxy%&hM zrre>qN0gv=#X^E5~b#am%PwB*egmSgdgJt;b^~}sn@KOVJ zge<(Gm#q5%Nn;EnxMMBVVZ;*=+}lsbCJ1@)q3zIOwbpc3<@CymVX?+pfrhM$yOUwE zx&WS(lB>+FCirII8|DM&gA`*;h;IhHHj8hFdn+Yf}7!JnFi^6OL}WwPK%qoxrxJ0 z=R#m^xOGhzKU0`qja=FIv=DcV=M4ON{413-GT9#O?fY*dmOk0nC%lp&rHKvInvYA{Dis@^< zwIyXLC6`q*y?b5b_OpyE2s(EGw<>mvM z@(lbWsSA~{s#sGdE-(~7{9~7D5LDedo_i68`N;XFW8Yi*`4Ovdd+_F?Yh|RR=3B?3 z_*K6&eCe0`nkAj8Sq>|si|~g6c6za_ZiHjpd@~X}h5Fil$a^Ev?4~@txgT*auCM1q zn<`jP(Cm|m;WsjpOG~M*=a)OYeF|c|a51edEiEmYBjBzpff@@kW{!X`_HWes_74~E zdKn@5JOuuNO)Sxu1<|W5;6D0S3co#&zU^&q_kZjHu0Ca!$24zQBiG+lGqYtCaqZ1R684HSL4(TnoJ{n$?8rfQSD;r<{e+b6Z)xhTQWqC$J$I?Sr=rNHD;mua|CoMQMcufkpTD`to;aN$bDZeD&R! zx}T06$wJ~9>4FnsWPya}&=JDw&>OJv+UD!y9E=@iFa^qSN#Tz)kFmL@5URWR%HxIZ`6)j&>FbE9o7e^KE30=DxU;}8r#u5UBkiM|rh>XQC*++1ICEW^=iUB&Vr;D}*RQm}=8 zCb1_9yhT1sy5Fr!(mE>8cOCd<^~*~4J2t+xLaH}oiA$(##o@$Piopbz^t}=M@{*Ue zjbc1MO)ICFT8Uxd{yN=3VlMg&chJ`JsCEk}ReUIyJEfi~9@n;t0h4-`HZ5|41 zEv9Zs_a_t-@(mYPstRBb1lN4N>7k>F)c4qu6z>=UZYc{6vAa;+%uwCtFNbO{%B6Lc zx|SL!?)0+bzdvc(x9wSQm_~P5{tdZ2Iy z81BM@L)?Yml2-X&SSJ|M0lH5y!CEXm?%4Ov!G=wshiQw}xwB|0hmyiEbCd+(Ewjyk zB??4Z0xv+S^d-_+;;tOy(%a2~3XC)bf~N{`Tj$E!<26EE(3c~Xu>tGgXwByei5qMI zsco4g2d_sr-(4P@JI-}#z1E9z-d)sR8j=J<4+5ea$P|R2KBycRjUp+Bh``qVOFH(W zT$;j39dcL1Ep2&mo`_^3K>fdS6{Rlp<(k;_zP~em{eo3@6XAAE@t8(uL}wQe8)q8T z?3fL2xZhVI+$XaF!;Z2-t`_o70khpGrc+_cU zy8~*5fqD`hCF}C==&0}Q)#q*tUVtjTXH)a-Pt3qpbi5I}w(N64H{vgSJ-xZB zZD{anV2Fn;aYbAtC>Dc_3kQ+^(rgi!_ERd)xag36g4jY!2uq*4_=I zH^tZ5K~btT?2*(6#{1Pu4z+~Uz?&l)G9+=wDh`gCXCh+k@WjFKX09=Ot~QuHi#fD> zK+g?T73cLAx0=7439r#4r$~EruJ!T%taUhh&&)knx-j1j@ARO;)*5I= z{O$SugT=KyhbefNPrUV@=1lwVCHGS#8{*_@o0~C`RZbhE*IDxW!w~x%H*{0xyM5mr z&(Eu4di!b-(NMCV&5c|r|B7n==UfQ;IH-M@DA&UlFX-GOyx#EThEcheQkB~SrefO4 zZmY-Fvtc!;u(r+-R-r@2h&?WWW|cRYHN+S6lCeiH#Tbs?eX0O-0bnL#cxn@RLsV*q z3r%5+Bkr!Z(X}$m_jjwTP3Yg7d2m@(>@1>9UF3A=<8K>Mne%Rp!t<3Z5vu;=68=tX z&H7OE@4c|Of2x>R!i6N?5y&tPc*qEN05Bft3i<{*0Qoup4adLV&@Hg%T^Oos-O*P; zzj8xDw7943gP%Q8cqiqC6V%P_Y~sY=1*^l(4Hil4DC;D- zJa2Lesr%SDRzn5E;Q1e$=R<1(+#ey`0dKGO_k4qvUxwvpKH`U|HlTbM3%G%}6X*qF zZDV^o?nH*WgfdPEXekFWk@X}2;%Wo<>^xx5`354J5+VZ>E|X&3CQH{EZ1gM!{lk3M zGRo8C=t;4PY`Pye%f^cr&iR*B-89pl~e4RMhT2IW$BWOp>Au$iQvP*X<=w& z)aDHTKF~5bQva!D0Gt}YE?F4T**=>RHegRrpegB?`+NZ36e`5#fOtev?9Xge)j5^T zm$!gZeTnq$nGx-GU)2f0B14UQ`*sF6;Cua_mWI*L`dg%gA-GlqUzZa_n(SWCr)wJs zJL}11{aA)DC4!U=44}!sqlR=>{PywkvOZG6YEuyN`j7G}jDYZ9U+8v>Ed@2t!7EPv z;4a582<8RHt?t#eHB5<_ZdOf`3)+;4fq{X^$>?KHV7Oemgxs7t{!1&H3a5ClT)cAR z0OE?lbTM$ZecBOmFt7q>Yd$iUVz**PR0vVefA;$LDX*~KIn?FVX#D)|6=LlrI=n_UtOJTpscQf9~+XfhklLSJNgmO9Z|06E*$g` z3=!a{sik(7M_ObL$)Ux(v-b7Pu?{l{Mjv7gtyi~wuVgkHin^qtiuKL=|Fr;%MI8-2 z>bf>;-!p3x?n=$LQ1d|<&qd0-BZtX^t^r3qYYC@B@}KR#gwLBoNKAGe(y#llqcP`I zXS5Xw=*=W2N4~O;7WDWA+WbGZGY*z%Ry{4MR^ja!&zkSe9L=&1DW7$U$`|W<*iE!T z#|9B$MwbS^u-BZSA&?}HYucj7TAC?eFS;|{;i%joCq>tJ+Y2V73aG33(z3~q^ZmRN z`0-mUNyEcaZQgQlt~OleYleY?rlG>Rn*2V#eCYtRwY3r^D!hB6t$2IIib=f>H(x^)CGk)Rx^t{5W8Blq%vA*7t z!>`B}^L9J=eJh@71ee#NU%tiJ5685sv$InUpW}i?r}-5_3GrzX69{7oyVW0IV1&&?$ZS1*U0{$Jx{?m6bu$t&QEg_0hXUg+*y{i;1+*X6D5jIo&q92?8k=%hMG~1i zAi*67Re)$4$Y<4wmj>XznhyLcGMEE5@Es}5$o#CV)vc{~ZUjAJeSILGip#Q2nJ{;7 zQ2xpq9+Ohsy9YDG4y+<51^mLoWo2{LBqEO>h0bOQv+448Bt@K^7PG3DO-xO%wYEZh zsCt?f0UU!o^GS86v433fgYL~1W?!T}26G?kYF|Fj3UcCP#oBlErdjE!-FTLXcLtR} z{c@0N@2TW13#I<&0E92gC?OpZ^(i9b3qGCqCJ6j$@1xY$`U&8DBN1Gv`-%UF<$ZFeHiIYN^z`wmP9uTx0?p2# zE^jqxf+rr4#gW4%tabca-OX$b>*<|ef@MT#E_Q#UdQ+3Ff@$?nO>P8bZOW*7*lAFYv8mY)KxR&Im|5u*C9%u?6Y%N-fIVs*rI+eGb^NC`hMsQu>~#JvFGrC+If3xl z@p^pm$5n=`dTb!=A>0WB*ML@B3~~D)5rTqQJeBS*SIqPYI{6&YB`0)rQIy+Yg zW;adbQ{c+_V77>~baP|a(#PU?cqzT)@MKovuG`}f(aWBDgEv}F&_+U`OFc)_;qYsQ zIsgzZtYK;oFAJ66$pQc{xcOb`i|dCmGY z?_4dxI^^d$AG6u1J0fwa_9#b#G!i`gR(ziZsS65{e2c*av|e%M?cWmhUb%YWg}Ch% zuds5OI%~~(f^-Pil$O<1)o{Mcl5UEOnVTB?0iwHKlnsV|QQr?XS3nZwkF+;q4F7P7 zAws~*<=l|-BK39D#d9RyF(M?JpFbG$buE{fTyYF|G7$UOlk8O`5xV8`9mHy7aCI=Sp&MEf`jP9&tsXbm)LyNv$7vxH1($v(HjFc}Dqw2b5vHcqK zsJDlj>bz%SjP0W&^-yT=r&NqG_6GBXQrqRmY?6nI;eod?*p6w$NhII|Y34wc41CP} z(I0?`8(_KGAy}jn1P9ZHb2t8AO8sJCA?-N_JQGr8$hB`z0dEafy`7y&@+ve~i$d^u z*19V9pmi%Q4yBgpEBTcdEPt2a_4`%&=(SH*mfUg&>MoG**WKNnmHr%A;}_uTXz)7_ z{QLE*HlzB1?w32LcKWaDQ81jZ1D~gpPLQL5RsGS81 z^tXE>NEjKLvYXckd^DGNsnx&kE4?=gpk92MQedo2+*Ad(q*}C7xr&kD*_zKPC$|=o zP){?nvVaQVh+g9H>xfBhuy7$B7s^IfJycnpjKB96M2LD!?tg>2v8)XR53Xqn0P%+hc4#b4gX;gMYw!|h*;TnJhJ7Yw|J0J%G zDtQ_250Q5peg03{REcEzE^v>w`zp~*^VL@5ady^jwFTJea?ocl1Fh8~i^ht4H7FHp zTWSG7(}B}HItuV*z-s`C;$t4cJ6FU&yFsym=fOdV&zq1>;E}w(ihNH5!!Qt=F~ETr z7}T7AQEvCQvmCG!{10k7;_YK6iD%U8_^YNMj&ZR|W5F(tnU%`X@LV3luT2bn+*;2p zJ-mx9{{gByQXxEJEY=rOCW^^yHbaUm-}lN1GU^x`HuXCWCio_hxMMzS61>$%l@b?! zxM3>J=h&TEzuFI{fAaEZQ1JUl%0hD#iDp9(q9x4Fujc+ANeRR{zSzjAO5YAxD#$QL zeax(Y^Ai{q@8d&(=p-d6Po)BJ`d39Y@+xE=Kam2ks-6+(^d@--%v9q&n9O!glzO+a{Ne>zUHHvGQopkyRy&b&xZs_|7~x{#pm3 z_A<`aNaahEuID6L&Ve2yY||0Dlrt@y>vUZ!1+2tbbw0oHWog5gRtUM7?Yk?ux+9 zY05ow!#v9^tDsq4M4`JQ&7l9=+t#q{ReN@j5wuE}yJ6CgziMCMT}fOzf@PXJ}=1Y_iQq$176F=F$j~xx=K5eh8slefdHfqXOwZhj?HfZB7?b@?> zpn4xgiizetnp|Ja?pL~>Ii}1|#^j0J9a)T4aGQMwYAe@taH!5Vv_9;Mr3os}ME_kX za86pI9!mP>)zmvo5+Qx^hm~`nDO%>jv=mwXx^ivQSk&us2Xy4951+Wa;IDVu>HO9Q z4%L)ZP}5X#(GK_v1>GC8F8aoN4(|vD5Xa!?_y>4^wUb{J@5Upbq3L3hQZ&NjbpEuL zC&1>bZqCtg7XSP{^Dh^$OTfviT-_IFGp#%GYc>6dG!DChFI;WjLY86&J^CIBtU#89 zy}eJCJqnh;rhu7%n3Ng~l_5J^a?2&CiK<`A^ZdKgIh8jDGgaFdC)6ipw$Gz=cZ>R3 zxjpUeqc;-Fo7hBHD6^Ef_!S7cGyMZed z|Ma88#N<4#DDj`EvGmC&o?G4_4A4QPy?cMRu&cho?{C{Zr+s} z7%Iji18ie!OGH4RxpT77MS`tFC|Dv^nun{cWv7eS{9K4dlF3M;7{)ftke=9L zTH&${@hNg;x%RcMUWYqA@R`veM4CWPEziPfcQ7h)QF|SyW^yGW0hu*1u3i^N9DIVk zuxDZ6FYCZFjWdc+Ubrq$I$lL=Yhc!4igP6Rr&k_cfvH1 zT;Oj$5rdW9_#8q(HQQpu{r#0$eWHa&C@>rWbmR(!Szl5G*jE8~NSlJd7RIgw^#%}G zAe#QFqD&E^A|X7?ZOX}=kaL6KqKQC08wE~DprC=wH2)Ul*}gawgWyiE^vDa`hoRvP zt1xQlgzApH0bxvx3NV~m>{0>8z>QmiGF5%`^fm%{R)CY!j#BkT4UyEe^O>cU6~J z7G&>g1Q-EO)Le6t49>bymVjHnQ}ViuYQu5 zRZyUI?qXZDY#5uavr9fao+LEFF>osVu^5z-xXqW>uoRk3XE7&nm9#qlg3|1Du=eb- zgmZ&3nx|)Fhp9~zakbcnT}A8tfb0g7s5VuVhEnXZJG3K<@@%g#bU!HT|BaEiJ->`k zBP-7$BUFl&^dgn2bR4#sbIzb^I?VqnWCi9M%cVQT7y|{|ypy)4u?)76Vmjk_q~eB6 ze7e?9O9F$8sqV`ioi=Z}8-;(Ykvp*M*#4qJnRIzmTfrIK#8D94i3f}D)o2F>dI30D%9M#5A(x5gO{GXfeFgryjcy6 z6zODjxw~G3r=~y1Zp><5oRRMlnXWVH7lGdMbBvPK%q3tzKtvqnXi6(7+<#rX|LM+r zb{=9uWFj37`jU!GWo*vq>{_iVPQ&S5$>LWg7qbxTlvw##ew!7`a_bwHfjHf{_y3s) zNdul|g`m~AOJ0Bg2?!{#gAfw%49awrdD9T_)h7;sQYo^8m5B+|JCL_n`%KbHTnU+S z|2!&l>2hwVIiDn??n)|34v}7$YINybFj>{r#$eg^&U`#rr=qIo*9>-WRQB`j*TW1# z?K86DfvTSecDP(6o9W6j{SQ7_GB85|%T#9~{82K;_-}(g9J0tF**`&&AXw!Hl^RbX ze0(Qte3p}q-wm9u_TgUoRChjf`>SD#jDx*sV}nRaY>D~&Z-5;UnQlmRy4RIp zO_vv9rTNj=rP0PH;a&EdPp;+7;N6>6KjUmi*BMv0r_it2jg4H)LEWhZEHzgj_WGw0 zBwtJ`N`WGHF96;x9y!;%+ftDs1SLc5@J?~b?msf*xoZqbfF*0ta^ z0OCLtvDH*YmGWB?1??aKAofluOX(j)bS$D+eZtpddacxtxXMPp<3f~o;sjJhzjHjkyD51kN4P`LwXX**5Rv)M*k_#;yiVNuYBQlysorMh_u6I+F22llW zM{vksJtjmZFV;&Mqo}&Fd-xF3ksSLOKPiq5%ceO!~? zfnM|;ItJpB8O}z@who77aBFKz^mSjf8u|^>L&aVYWRTRY`ZZ^Ec{F3j%~!!F<Z; z2@I|KJE^c)H4nO<1NOe4od>nm1sj-2tXnN}(yMpVb43*MtX z{1ZCk#=#!}7O;dvIP)AM-Ie15{RqeYAmW=rZJS-GLQF7DHDj_iKC#Wv@yo9)7*4?Z z4iE8*XWD!}E|Ljk|0~h8-4(|EbKMu;yp>*~1Fi7wF={RGRS|T?6sr}nL zTieLc#3enMUo(zsyP`sNhInKCG8IyZhnmXZ^y_G+7%HmU-6N$;NO4B8?SVe}3t;5d znEZq5z^Tom&*cAs?%dALmKHKw)iAj;rC?qcq!GBo^+)vw{7Nu_=Nh&UGfO=d_)lW-(^eY zu+xzPUv9%7F|zJ8hG|m}HDXzHniS%TcZv8!mKJ;P{rh*YO{1csZuJGc@do_mmGLV! z!TTNGOqC0h3XE_M#kuP@#tYnbp2L}a1QHES{B?d z@*c(GuW zzfn3c5MnW#SZWEC73t`PwYs{yfuy4dZP8r7dJX(;v$GiAzB@~;e|W`ZyuG|k+|5>^ zd2KLsCh|x%^el7nFzEAc;}uPSsCn+c^r-W~?Tw-@v=_@Ex=;yJ{!|;4@*J;+Rbu?j zs$@q^)CFEHIdX3za{-4Er5ed|M&y?#v)75Mvu~W}0l}vB&4L&{WW`#(y0TauF`T|K z4OTwT`IKFQ#KTS~=7ZoOI`$L?YN8Y}OJ<}!EYnNyNWGM@M&tq&`dGzE!!u<{V&_c+ z%Vx`j9T*B0eTZA=kbY1xdxS**ZV$}s{3;Goz%*JkH`|;{f^EPbQbIY=`5uel6z?$`=2EOCoUOTn5+)26 zT&EbQTG-W@VaqAi{Hgj?-9Avs0tOi}6FEsrW^>Xxn4&HMYS|+9QCwlmXwG*Y??3l1 zU?n;_DoBMymMhCe2emK}X-Si(T)BJH_-BCjHn--WKiM}#PWL%=!TzL1r@@>QGtu(f zG3gjRwHc=@vD!e=>?idjd_sM~{G9UWolfY+=gn0JdY8Rl0qQMG7a+o$#n^skNw$AK zGcP~C`JHW3aA^Mqo4DI@CN(IU23Awb#+B|iJU_K9eI-_PVX}?+UB@NzH5)_fr!6+> z+0?%#dZWSCaw@C_rVTQTG9U7<$Mh=S7y=I~<);NQCZOZ3-83GuIq|%;Qk@)`RMgM6 z0yKpamQstHwK2(Cdd(v0-q(bq3v)0nS;7kzcXf*Hgjn|fEoU%6nYR5>0HtHn{Ttz@ zb|*+CxQPBN;ctbqiR^W&9$e9c({!|+&0)w){w?f!;$d?qz;e8v7c}vv;A&&d(B)9m zgIYSm)L$`c1H;arCFJbwqajR#V5WqnaReEE=&Ge9i5CRds~BP-MqwKN5H%~ z1LOtT994t2bW6sXw(P?z0t3)oS!p+ey8k0hK7>p1As z-|m0yu)XJU8Jhnel8a{(37uqb0^RlF79*{h<_*-!?*+cR__wc_Esz(mF(9vr_V_)_p-gg7 zPf~uiTQgC(RfjT|k)22_MGU<>S2}J9cCjt=C>dKhJo*rD5&s~x++Az@G zLMgTaHVx-`x}F@^dFZHM`n(TC2G%!V1s`pMvmttVp;)-;xmoLw&`L&dL8`I@na*V6 zqzM6gpR;o^ulqBY`ap{r@h^taAnZ--LpVkvwA7EF+=SLM`7+TLsHWvl2pBcudMuU1 z!w$Z8%hg!Xt$?|?v3$a?m<3Bmk6B|KfF6eUO-9yy+5|RiiT z5x%nx<;UTs#U{gbb^kBl54EiAL*r}SOL}YKRK61Q1*%EcjvjMBU_at63gkgAApH38 zfPube+f<-bPi!tceNk5m$t7Rt^lPp%rKD+AL_ulAi0%!<%U2v1I!OSfh(7+Y0t9Zk z7+!poQzD3U^?%VuK(2;R>O}Kaz-?)62J-GQA1k^Upj2LDGdW??Fwk3rk;!;!B413< zaPTayj&V{SRi;uZfxpl!HKqOZ?*n&qIFViiydX|&oc9Q#eZKzSUpA)65L|xp2LMyF z9MmU##5NbWRi-02OxUmHQnjYz?gc4cZMiGQi8SyC}?gEJ6W=4=_a z3GsTiXn{bytnd9Pf*Y5I_%V>P>X0wB4!i2MBT^G(eG&5iwE*fbfoP~*UShBWb~dH* zJkT^;bwonsVbSW;;<<`f254AAl+?hE{UC*#5m(L*+g!y;QLmr`o~ zjxHDLTS?Yvny1&?a4a(Q<@(CX{e@$|x1OFJ@R8=`=GNBGj}-S-N*lzi9Pu0mA*mq6#yWC6}mk_9VeFWXqC-iADYxgY>XR-rSSXYmK*?211A>e#0YXr zD`qD~wF!1pC#FPTOnKpkn98zN=^oxH;fyIcbER&kbJ}94>bobn!Wcan{wM=m&!;EG zNl<9(202$UDQTn$qm@~+;ir*!-n6IcU^|nE$hL=2l69+bhd$MGyI}sQyBC8N)jE5) z=vsn0aUOvF8YG*Z_O)?7GmR~c2t2$K3>C6SKIm<-w&8Z&zagX=NH=DT;+#1_`Vy3T zo{Z`T3u70&2!7&2==L;pgn!VkZU));`+<4^tQG0A-89>FHG1t3pwW%vgpas$oMia`xO(l( z!l4tJU_wki>u5ttm*Ib_F(45|sbZetY<6B^Z|p~K7k$>0p$U$!c=Z5J+M#-r`zy znKv~=nTS<^e69bCq?9g26ugkKdW0n{L8P1^M~36y^(@-+;myH8t!xDniff5MfHnXT z)x$DZc=KeCfS-JWpZK>_mN&AZY~I^0Crk{ODBE6FE0(qGhFTsnq-FKOH_VC>QY~}nN++@8d6>UQ2-z~RbI{z=5M>>*tuYtV-ogP z0B8Y%5=2c9lQ+IA(EOSP-Il`$le_@VtAV7TY6KV_{+REcu{K@w2XZaUir@Rv7K;9r_9mO=Ym++vzVP- zT?%;+%QRtR$F58eC30+h!4ZkIwT91+Ug!kyOq!3hz_hTox%mQMF`y{)3hIi$+e+?D zt(*VI$okhPl&?0{kc_P>{imiL(Gf((BYRHnkJOR%>Rt8`%rhcymH~M!tUJc;{|rBA zoGATinbuJbx+yV|A);DUYTE9hHG}4q9oiB9bpyu7$ICd}y!K{j{W7mPzrnx})dPDFwb|ms^H} z@D8BK12FoNCzgeOD_1A-y7BBOEiuGs*qZ;8Y1h2&iu<4D$>WZ`CS zM)Z;6w-^=*5z`MEipPjaO?k7FaRidzJA4n zg4eN4RDRLMP)Z(32>u6*K05JwMD78T6Di5$_N`*QKVR54M}Pg|QV5Hhn z)}SO{{6_7aQy*tNMBY(E(tjIuKVroM?~A>s$_q#B-VNIaC5bF+2N@zh@IahN;0t+1 z1hBih`T~U$1hMf0LdKyJSA?YpVE#%j;DZMqQ}CkiG9`uj1{Q7|9K@og>Sd@3>7tK@P5*KI z9AHjl;A>SfodS54;ui5L!>d~NaNN0wW3_Uvz}814@rJ`hd?6DKxOO!nZ^ z@b-?sg0hR{R2B;HNLr=(e>m|dKNo7VSNQ~4zP|Lm-SNPrT>bl(n)oS@&;O~E~h^Z@XOlNU0=V7?ai>4*03X>iFvr9{ihmk zYfH1jun!!W7o>H(0)YJ6CFyGjsw^+pUetGoBYBIK0IbjMXf_P$P^(^eG+|iIouesH zCM#r(P&}fl9aELpRX^PpCe&rMh>6BxQ-cD&uU8kecIoRig((N?r2d@0vT$<<{84`Z zf(iXfa1UnE0!6hXsprrUDwIw^%*kPc@~bk>7C-mz0Z>#b z1i_^wjG|v;dBh4fFKe=+>+5DsMrQ1yHQ;mvpmh(@UZq0jeqqt5XLRLZ7quG(NoPI) z-+?_*MdLv>Im@X!hGy}aQN6PjBj?E3$qC@WNcGAeXostpuof}iQq^@MZ|O9`0ur&+ zu<@Fr(OXf|2%fPHhaW-m$frB#Gl?iubRRzhCt@Jh@%~mSZw} zltAnr(?1BU%3sB)Pjz)yIHw+atD8I*_{~9!Q+CBcaMyrdbTTzghU=V&u`V)Q@+mt)#Uu!c- zf`|gXg3(!NCu=(kQ(-pQaU>cR)pHjYMNGvpM&hL|)ix15e9KR{N9b=Y_bb&)PLopc zBgWhCf+boTtw=vtp|>x;<9Rr@5e#H;p-Fl>9vr67egM7(q{2;jKRM#C{SC2t>9`&V z!{^s4_PA^*91_qWSOR}>fYUNSaVh!_?CTL{5re@dxk)yaSlhs zMpm1mlX5c~5*b7{aV+5_i0Wuz0h8+F>PlI|O0|d9oS5vY2;dJ2&W`|SE(8joi$8xp z8XN1!0l=nMdam>Y51(Bmq1UT~KZhG~IIEx_!Vd$D>;}f@7XwoTJkeslFh9h0M1u^b%znG}#_LS9w45*&)aiUCdgaJM#w* z^jHHED{DycKrSeM=N@*eiM;EO4$v5`tf1r>!&< zcL!YaEaZ3J53zi5)k7rYn}jE`E!x*q{j49kv=HfB9WKn!s+>rzwcJ!c4{vnprqH_e z0?x(YGLY&h{|fY1AP^O#GuU>PapD9?|D!LNPk(jP>Sj=?ZufL`eK%ZHfmhC!rvikV z{LKXfj^MVsK)I=rRH2>HY}M)(rKzih-8T4 zTJd^eGUg;T!h&1$SsF!kW}`%-T&aW(q+d{Pw2~Y^cYkr>n!J7{-X=en^HzRz^YZd? zb1St;bwu=9JclGO*40g1kqe(4bK8KnVL_OfH`i5A{fCH|BV2lS8GBxQ< zA5hDH*rnzPi6vk*0(O_bQnQgHB7Sl8jHGiWhBYrO@MkR?VwU$Idc@B6wF zer^p#PD+djjQ2`l5>9p~{yfphx47Tf`41&Wf89e$D0FIg+65xJU_OgUEEs$2-pt_3 z-<<8xiBbE=`g-ic(&jXM6#5mFX~0$_nJET+oc_^*Ha7xxc15nEIB* zIWelOCWyZ3W*mYa8^lgqUA3U6Zr0?{Z3L=EP-;5Py9p?lx=R&D&*jXer*D%Q1j|6w z)S#w9YLzcd<1fDjBhX|kh4Vl`X~1Y$3%EcYKta)nL1IU96!X8VebsAJILBd z1U6v+<%jQZUFhC3CSw>;&BFn5Rb?8!=|{d-%Nuz;~2+nb#C=mo)t*|i8QiPVP(O!j|6%@TE&es$nbGmRQ{g4ng zI^omDX$+{e_qDrpsVQE{#DzA+?u&wj`{P9>Rch^`rO2>EVnYIr*r&CfJ<3pf(#ehT zHkm*?6mwySY(vOG__Vj|ugRw)hS2&s)dq{wr_DO5Gxuc4C_*6ZtFR+8`=~uyX3c2{ zQ zid%^O-j#^^`r)tDP=#T@oV4?TyG>fOs}73a3sB>?xrCRI=WEMsO_9g-Q!{*w6}?h@ zY42jnx#5Q`6etJOXOt4>0;_TNNqw9VLRyt<)xbtLi=x)v;KpzuAl3T7UsF?32#6I- zaHhYL(P)l}ub~kirp8FtG$fTe)G$8U+Z$AsD-a8&s(PO@(nQ^+t%2u^&I=!)>SBDY zt-vWN`m-0|&%)0p@_!N_VUa!aSHjjb#D7o^5U9-;{rL%x(ntdG--BZxxvxWNiMVUl zz8ZRGLLG$-=B3Q^7rMa_3DqruFABm70bIeX!#sq8c@r-7q16^I@Ryf(|&I+cWm@cWPy0Bzi!T#Ws+omPWWq_D(EV!$+n7h z>S+?R*C&=3q*FUPN1w{lF?b&JnO(#7OW(hQm3Z}rH+|h~LQK=28DH?dza(!gFTW{_ zgBHJ5<*&+JThScPZxli)@=y?*E1?+H#ZS+qAL@te1Ffyf<=y6IM^%Oed3jeNBhr3d ze1xAC&DrI>x@|DRo(JMm3IvbYGZb_A1V`cExr?Q9C5qjB4(t#HF4xx9Ku(D#feCGGZ5_@olOc_Ya;~wLXXN4EQrix6S_gP=TSo8- z2yae#!qak5{isOh03Dh5qw1_jz8vi8wbuGm-Un2PcC+qN*@T}nu!h=L#n}qa%7cA) zmaC;=n1LFXvTCdr0Wmpq5FA!T%74!mYr-LTV(Pxk0YY2Y?;ic{f@HJMO6tF~LNj&d zUv*@eD_ZVD{EAd|`yZ(1u&JS|e~4th-GjuA0R+ts-ZW-A7JR`?%tkab_r{+;e}>_< zwVrpv4o9vGI4JWfvQ_d`+o=2w3sL6h)mvwy`AJrNu>B3SHl10ep@cqEyX18~y7`Ap z3yiw@5Wka@S&&|0=I0xoa&l${9uprMo2Uki2a_Y%1OL}&JxPR*^L`%wR<9sPQGP1E z!!pm@FOILF%W-N>PiG19F+H()bSHc#Dqh?*BHJg|1?o5_T>~e3r+RV-XUfhc*iBME z;RUmZC5YfKOMq%t*7lP-!Px9BdnZ9}D9tL@F&SPaHerr1eOQxTH9<4%GxCG|$qOR?(l@Q^w_OsobTYn@o_D&fJM0^TF?584Ss#QQx>w%Q1upbpF%0hAK>I5jod zzKIMq>X5AL39V?tZeTK4Q}@G?a=5vf=Z>OL7QAS_83Ng{y`WLIM~=Q>Nuyz7Fo_M~ zUv$o{a#r|(<^Vo2oT6HOc`U5H%IB7&fTbX5>!lBKftOEQ+#^?#crn_9%&Wm>aY-4!54vCn7Cm!XU#b zXNT&x-uE7{rg|-!=T9l!1NkG7)E5%a-Y|&y=DGob0jvK$sT^)S$0y!DAM!0ROK7|! z5`1o>!GTfV*m+xtcSd%iOv!E~Af8jEqSrUfaVivc|4x`iiydDLVK*Q5r}FEQ1j?66 zaU9BjS&jO(8clJ4v;wanFqIRX`k4}$klAb|u@F?LM{>m#=9;*k7L5ubl2Pk;J=SfA_$54}F{A~GEJ z=p+d2cOd_eA@h7cWje>Q4cv;aFUkn2w%lxs`p?d6GcsNd+P_bV;Wlzyw}M-*lT4k` zFNYD^v<}$Ch)V71>kO}fMFe`>xUzUePCTW0gl9Kb*ZF&)gwXMDj7AUuz3fhV)eCtA zv?`fyx3j$oOh?WqR56-O>=d>mw$aObpfXBnbBh!IInOaO;>$ zWeekmWe-1xFCJbBosb(koBGWijZBAR4?oE%m+J40t=m?>R`i?f3!IK%GM98?6pFCdWngs)h2I7I_{UxGMTzVM zJ-cZ-cYFB}%n2KWGqMFLoxs;3la;*K@Pdqq(#HMLu$*xyAduHv(~Y2>NV~(bC9;C@ zBB92L82-5pNX(u&Qj=Cf!Evpi(#Z4=TY9B1~M` z3;}i~UdoVTohF}QWw{AxV~_IK-Q6v!O-4*6QJOzeR zMFEN9E)-j~DuqB>{~?_3Y0D=U>lQ<;LOIFX@kz#-o_u*{jcXQ3%{Enh(aMh|CCUoo zoi|cD3?jXp*(w+xz?iXF;us-%*B=cotdADB5wf>J7I69G+9p+>|29m@yc5pmq2W=K zH!7d-abiS00I6Zj+LT(sgg6p9U#oMZth1kg^EDLC6en=ES3-=kkV)E5MMDy^PER;) zRSLR;a4X#+L0o&OZAJ+5R@4VZol~5GvJ8LMr6@_w# z)JaZfGJg?K4V>V4VmK3E?13ZE+1s(WiRZch3%HiKBeC>QqZ`W0Ua&mP2j|(D2oO15y*M!aRK0=uNQr{N# z+57RYB@mgLAH5Zw_oVL0*3tiIIu?QqmLf+BHEEEpM6m2oc*1%d;eCYkL@70=WMeUv zT!lu9&8O-O%6oj{51>t9<5N_mC%N$Nhc}W zxzW_7v$^J9JQ9ZIo>7BCd|Py^FbAva7<6>i%#BZ_QN?ETV}TQgdFTsT10Z+p?!6Q3d%w{+}ZB8X)drt*`=)r*nA0eE|e8 z*;8iluaR`qL{M3z5Z22Eqd$Jg)Rayoz=ca9enU4&(n>$`L8o<(AIXTm{Sfno^+(K) z?Y18cRE(I1@QDB-2Dva#d&FI!^CCe1tG|phEcp6WTj`3kzWAv3p5JZLO+{Ya9+4GFBxp=YzT! z9EBk`h{k_WQtLTGK!w$Tq{Qph`!%bvVJ{7(A5k`Lo?;ptdZ$bbKGc7|?2Gg_@Lz*- zJaWKm2k>sAMR9{;t1|GEFuDp-**0iIFFbnda`oIi>JmQT|4qiZt#<(r*y21ArowZordkIX6@#Ed?9BQE6>Nse8U@c|$W08&3RXa}x< zbOeXdyM4c`o$ap!Q-r?Qz3tE~cUTQBNJtzW07%n!g-Cfh`_(9GBb_R8zS*2yS^(Fy zk$FsSVy>O!YyJueFY(O6U*yO!!4*{?kfwOLA2zB|8~P!tLXdkNqKwWDus@*^foPdo zrJ6n%@aH_tQ+kMX>{Hlf!NL7D98qsT@gmaRZUJkT2xZOW_AWRmt6JBY)5uHwWIii( z*H;k+F?~e=#zq$P%*3s(YXt9O9w=zGK}a*wva*5V|~276KA%Kx?_;L#RM%ot2`j-X8g5BkCVJ&r=>TDVla z5vRq%tj?ZaRyw2l;H=4&fzUuQkX@@Bs@HjeyhadKprM|OpzS!X8qL5GZmwhQC|k`B zGp`<$b$R==7bhrkq$N;;UfC(aqp^%_SJYWee8 z<8GHhCXlogoPwNrI~gc7;4E2hW4oqc7@j&!Z9I7JzHpc~0aY20gd%N`x4(^_h}esW zC_=70mCz@pquwU7i`H=i^$Ct4B}6gW5^th$6w1}3T7O0 zbBPcrX-WNz2M5E7aZr~@t{_dlBisXT;{AXCn;SPWcIPAnP{+uXsf+?|4n7>8?JS5oj;&GeL=)u7 zs7)jeiW)CX%-tpd;)$_+seepD!p%CN1fMMBt;KAf%JO`908T>{BVAfJ+r|^75^r$3 zy6@;VYt+C63YYVTz<~C$WoE7Qti<+(4907EtKHNWptA!k<@C(bHxKIpE<`LVT}`Qd z%*ioItFsPa4EgBs-7PI*H44P7Uj659K;KHea`UOe0wxeVGyrqsjyxzATag#R<8Mnk zfVUi0UBP}IlXYCAbElZ~tbU&Cz7rO;W!dKOdQN&N&2kEJ5bKbQsQp7ogjQbfrifnOfzf z1f>kEO4Vpyb9&7E`d1*y2WEw*-EVXmB*@#1F=TJq`&xKkG+g4B5>qLznorfL^`RzG z)6&eFGP+~$=eIijG5S@s#<~_AF&Db{EKF91g3-MC2m(>74hEC)?ExZM1@7sFD;)~$ zL6S7MrIg-i{$Zp{Ot)$9XaGTw;SlmR?at$ARUN=Vu%g6dSA{N%OGcOE9YrFk(5vsY zw%*O`CO1C+N3Z~v0MZ_L7hkiZ!Ox^^3W1N8H*4m|xQWR~7Ya&6?dH?n_tw@Q=Cp66 z?kI0|-pczq)xR{(4CuS0zM_=tkRBB|{T3S>enBW6Zn&PFR{vyNoy}92)bg+VSpqN2 zKUeiYS*hk@re>XM!y!ibC>IAKW33gGNZWI8UC8w;oNan_ zp&tZk3G@pElvV(zt-QBcE89qqeuNz&60MhNFQj8^G(s>tNw@+^Jj|yDaX9fQQHvCB zDbtc|gwG|OsSfwy1DtIBh}v-z(htNGbhIA29jdmp{dsem6_{LdH=ldcWNd z^*6vw9zk>4$mXtmDtX;$fP!5XM&6a^+_kv)FAJ{?87+ee_I+Y53=g%Xcvd7Yp&xs$ z65g|j2gI2Ths+{L%8=(@<+f_VAUG|3{S}@1)>et<#P5zQwS^i&L7$BvMD(EjRL2$M zM)R1FjkmJj} z&2o<=n&kAtiE5zvlrdkz!ALV?$@t^nI@b-ou5U^mznWEs|2=s3w6q-D>Ke{0%$gp} z26%%<30%`4J@eo`pR^!xG@Le&u;w>)I^_mj>*t1c4a;dk(m@bgEP3m60w#2j820+= zYwT0m{S;Z+(AL$ligrTRYX4J8?>70!X-SUq~C50*zHSaWxX~?{tots))IU~1L)Qgsflc&s@Msn3hH&<6dleNMH zzb5mHLEFAjLwt~}jZL2dYRSs-a`1ps$zpb+>Z@|usXbtWK<2xy?i-MgxW{z+YyIIp zrTcwxfi?{9X1OZ?ODrtANWPIWBSes_Fs{5UKW)YuQ)L|HdgN_xKFTUVzIerqm=P6J z^}Jk%mj~)H-awomNEXVJ*BP86JrbuN!%lpU-`g5`<@d20 z5AIsDYd)${fp#ft+(bli#A5MrbCXCUgAWmk8aE*HbXy4XMOwhP zY2ex@Op5lN2DWzxjVZrUF5Go;4}AEB3ByKLpxgFoQ{yjBvV`NyuB{u*(wxW{5XTV{ z5WxG4exrePAw`Sj)Mn7Ax$QaG*;V^k;}C9&zLJqy=H>+=w|S%>ZvObadHpEiB=|{W zn!A(u1uT9Q=$GF?9+^!eY#xA~9*L;K&8b-9QYM%v`r$w>3dRCAMh+aHAACcXmX6qP6+m|#Qz8i}N=}n+i?sjK{N%{>( zPHKPQT^n?HX6Ey%Q#f4A`4Muo2lZ zl6R4VN@!8(WAZd@0CJPjQ{9jq1DfPoARP=O4Dqht17RV3!q!HbcqRn*tFR3*>^gUU zGLkc+$etnD7zRKMxY?K6T%IpWl(ro*!g!OP8}|b<#3wu76EYkqH&kVdRI+4E4bg}D_x_!+Yz6mma(YZcBzaU;uhl^_+BnN^l? zfEP{;;LEKv)BdEd=ubi{*vBl7mBjG)22+}4%uJ!idi5jD(>_SM{TKJe=&<`Wla8|9@NI6r8iQqnI2)I2RC*e94zl9cRae8 z(~bH^e^%Nh!$YHAa=}FT#XItxd{!Ejw~ka@ymzp)uD0V96K013MTL+y*etM?X0d9U z7Y~!Hxry)7utR^#c@>gEW)~o5M1#P+7uby1s((3^pk2r#ik4LAO5xZn`Q>~7kmMkO zl9svTAP+I!Vo(tY4b}j1lj1a~_1}%Hg%iHIK;*TCQ}2?H7Bg#?e&$dQNgZ=V>dM9F z20kyckFK#q(f1Bb`Q(}i3s@!Of3*uL%lo85`HV)^^Le`-DydmT1@$W79JD5#q7@JE zNPA0&6-DYx&YKv{|N7(9?qq0KGomwZqoGR%`Z$XN|7h=HN@2zqR2ceB+W(+fWW7OT zFKH@}6OdO5FLF)6Xh!9M+)!>~BOtFfG&cT{O1Ck5upCvBP|UcfI)h$=(Y}nBGn2Z= z-A#MhF{wODQjyybGFt)XE!v6=}#n+xW@I5%hj#}27F0WmQU zm+UISQ)HD3&13~ZPjd)L8f6qGlKO*T<0KeOVW9%Vt3x&e1H6DwE8-w#>8L_=F z>@I8*S~AUs__{HlKs2ywzykrU0RO-J`M&YHW5f$UjlduEpClYK!{xJ`M}YjKKP6O! z6`bKX@^xcsiN>18=Y>l^<%l{9a1yj)9PL{~AJ9!lV6>O0OZt|`NMvkLi4y#u!96%8 zKlq(p2;$d1vW-MO&Vcv%SQP?aH!m0Fa~ zeN}>v%sU46>*wz+DH-WYV>ja0v`L(?0JWgQlvjbtQc)6c^7MQh6?~mTl);*0v4f|_ z|8W;#yKBnl`PTx_zkYsxU=IG=4E1*K*$<*x!nW46gg}GI&)d7Ju`y7@71RiyxI6+o z*YUE6>Zgdwr?s`UrKJ=srqt2lo%Uz_u~>iUn-w5^w+CAojv;#KI$l)RA|Zv9PT{^`_C)FwBOKTT#Y6Q~JYXh#gAo>xp* z9BUvQlSiU-QOD_Ss5H?Rx@tK;eZ(?k;8MOjT{rrU5i$>H4NH9@Mf?QtA74O4PqI&` z?_PZ0wClh_X10*Dd+$5$L*XSDJr-1$B+ba>fIChIT*;ectOy-U!yfY?XYzslr4JORqu7 zsM2?P%C-Zid(BYTDEGc|nW@~}RCw!Dii&%eDm8&g(eL_10w0%u()zw17i9qp6hP&< z`1o8zH1_^(hwQR>Z{XETEq;JmJxDR-bZDT(Li=4kIzK-T2p-`}y_@6Xa7kUyZ0s6gv!)Y=jWQS-+fopPfQ{mO;!U?*p%j&U9+-KS5tb34v4|H_;(phc|8s)?s zJ*_9WUAI7x0BqH-YP{(N2S7k!5CR5YEEYRddIZKl-5rZ4wo{)Su;6299r66WSHR31 zx?2Mp&qklsjd@@s0cITWSl|*#+K`K;BJ4i6VJ`jT(oZFdx~e*ddt>Uu+wIZOlo8CX zT;tv_fw4VuO^`KjB)O#jcjV|iS<3V1!m)4#saEKN*G+s!KhKJ6EGf&64=eh9KAxVS z=|P-RrGYVcS~j~pss(PD^$GZ@!A{WLPE(c=V=?0QeBW@gBF#IQ|uw)mZ~ zY(p#WIhnVOtjdCK<2aE*zfgFxa}30hsf&NJAW%jz!dHXOVY8XiLV-a-evbHE^2{{Q zcH$)%nqjpq8AkPV8gh7S)*#V8#@UkBGBLLK>^WkO2EO`LpvFJMoI<5D6RBlXg_ zF$b7h~hWpcq6?v7bfq>NS3`nhy>sC#NlYL*`Xfjft!(sEN>?QBLWh zUW*-{b}CqAy2d7Sr~^QnHLQC)QT*Ux#u+T07e|eEB0M7gsWZ43LVQncG1g;wdQXII z6bX`KAZ(j|V137X08(}v4izHBfBzT&guQT*JhBX^KcVmSpJ=YU?k*Cp4)>t(U+sE< zN|^lv&nZ^#+UV7V2i;``t$jxcuyX;DA&UNUyP{tp?(H8t>B>uzZ$WWMul?@4y09i5rsO6hG42ov@1{h`!h=POIct>Q28l;HNO8){`Jr=U53(KXiP!o%Eu4E_Zvm*>q5+%ZXI( zI%bgz9!!Z1{K%01o|LWvJ=?=2+lmgKLfT0dK+@j;cnK7{LaSt+YP<9X0)m2mx2Kpo z^wiIfk6H_|uh>ele=Mv-NjYTs7nHnI80Xbu*6>1@AP(}izbdrtf;K2$P;C&|Xs{{% z-g5hgnF|0+gQrAW*Dh6C|7#}RdV9U=eFH5q zt)}G|u)fmgx5|@8&TougD~)&nP#JXvbt0MS=+e)Q#IXaHf z@-svzX77Vm;QHWd4Z0}%G^wn&Nj5_wBfnszCeyz(v5=a?+5F{Dint>2bI~wav*ExS z>VDe_1C5x!H>5(E%%60T@&V3B<31*41H5VMJY3V^dN;|I$e!0q8{eBpZ4EiCIq57v z|BU@Q-fT+oB!0eZhE!8m2Qrg29c5cb3`N7tKI6O?h3pzP=$6Oe6YaTVtA%|}Izz6E zLztYVqzz#D(0e+b zJU=E`>nlq>k{he7Rs5-UT5UmXbbJDtdUBHaSUSOYV?GPfdtsuV)Us<4C-A1HQQvh8 z=lp5_lKG`hBmh78tvu?ZUOs&_l64)w-|d$fgSFqr%^u&f^_7;YX;^jMv_|+2^#;M2^W2am_=$Bcx(SaD z@l={)EcRWG%%!);ysI>$(G<|nef%)t#f}-kPwxB2YNZb(eBC9{8YpVD0x4ziKa2(n zNl4F!;@S0@GO|+oapMLraD>s$Prj!-5Boq2kPPq+o0s~17gCH3BH7v8oSjvS1|!)1O`F=-eI>*#!BTy&Neu=* zz6>@bG7m6*0Xxv)$1UaWjE9$>EXOHa)I3Js#LUlVPvUE!v`$DP0!Ye~rW9w#zr0+y z_p(md`uOCCT0}lkEYbK`vk?BGLak^6#dN0)__7Zmqw~B*JmTRNAON5qg^d;>g>$Z$ zLX2%z#pWyvCx#l2gnB6&^P*NtANgOPfx2rmqydd~wuoX7{A8YppTS_K(a0nDPehG| zu}wNfq(stf!=XrzSK(vY67Dykv1Yx!OOQ9ENuRya32_4v|Dyc+le7v5u9#G95v?Qe zl(f%rf)DA&L+Te-^`C~Oz*YdxpFQWSV!cV47>p`O86!1kV%KHh=Io1@=ZyHh`i>?w z-rCG2Bpm#|q)AoC3cRpQwTD^eJx9e>f?m-Mvd))G5Yb9-WWSTdgyAi0ROG&%@~8itfjO^ks1*Fez9qq5WS2@~YE7@GO` zynyQt$?OXi{@J)Rm;nue@W&ifMx+%CE|`?aN$i-8nfcsIanAh)z^Dh{>*{)6e_9r= zBS}^8#-ZP3z9y-dpK79S#W%@f{oLFP{nkMVmZR8?&J3J2Y9?~wny#GZaJ14s`u@n% z%!_jnWyRo;Dj2RFe{(!X2Cp=MCS+0}%Fmn~n5t2{XoK?W`sHrx>7$(tQ!4yd3|73% zmX#EdWxs`PV48GmN^bmSj^AHC@;8mLuNU!CaEq+z7q3J~;*d#n%34M`E{vJ-v)~d> z_O%ibua}c+Z^v6Oa;UP$iubW*$SP;ezfs%=labh~|H4WUV{no4hAIBcT2fQ+jYU~9 zb8Vv)gIzH5$dx63UBSNA_i-nqA$L{gYxI? z^$++{dqGVtIR^hem{PH#hV$N@&3lMkfbeIcks=qrJD-#%xB(&SU=e8%r~vpzrBjUW zCiSnNV_{9NB6+w1ikoKe1qF0Fpew-Nbc|eD5+=R;*(>#h3RgSl7 zjGOit_sXlh|6|E2#mLwpM>=$MG$;gu{0-f-q>HyfehsPHm~vYT~^w7J0j+sj!o7io;uZD=DS< zEromBU{%@;7V#$$1J$06yh!*O?<2UjqQsAyb?TU(NL~zBLYcH;zUw*5UmwaM(L+~hKn_lCh!U{fp zi)GC{c6?+Afjr_~y4*!$zhuKkw+zhc0`V7Vv?s|Lh2JR)QcS#>M^W>m&vue*rAMW3 zDl_0i&pt^=Y5m(Ep*pGh82MCjL0*LZ+PH@dzYu>wIbq_-guT^rP3O<_kb=h>X*%w2 zEOlF5tE|-0E~d7v3#~B-_$a{maAjc;{FLbpqIzejp&=3Vr=JdisO3k>XwH99?oX#H z2PinV@jfI-6F|x3G8uNWvE0#5J9Fod*I;LDuIHjUt9ZTnPT%0eSaI$QQ~CTF;{7;1|~v@LwvQQ zj-fhY!Vy)v1Kh{sc|SO@HcSr>!>CUCA#)pj1X}5I&y46L2OTw3Qpqo)#W{>xvW#_~ zS({x5;EHx`B_7mDEdjuToNrlkEGVZX3*8|_Hkp}qT%{Qrxm2KP3IoWOu`c(E^#?$v zr`RfoP2mGEwvZpsQ6d2+vpo7g^(nG?WAPI(z61{8F-4>@MhLkL_LnPBXBTEd)6dKS z-B^XHPVWcz^}mjs4WE1}(8mPbCXv=WC8*z zuCM< zO)pWCKT?c^G`VqwZMlQDt?h5%j`HkSa)P#;7vwJMQx)qe-3H`c2E!0!m{P_g;$p0bm=FOY=$_ zTU+-3aQhPG`5-%8_JDQy=0S(yXnWfL=*xI=Akmu)?2L9t2}se?(5YSzAk{ryZop9m z5UrdXLP~733CboMooH;6OK`|rlHp+`Sco@mt3V{dsD1{Je^@C(F0(dzFj}FiuN&N& z!)N*Gce5jCcod-5($&X@&{p%N#i^8Gb8U^r!hY6V#H;dTFFNY_&C#i&3u-Pd8QKQh z>F@DeQB6(FVO5vcU9BNy+PXq4?)=iK{QXM_1EM?xBzg&gSklX?P2C# z;Q1#2=-ytp-k$!8ymKK>Uc6D4$5ui3ymy;EMNU}L$h!fxV=uD9_$(|t2VnbV z=T=H0cb#9~u(ZgBEL z>!w{6yM;a^lE~z9adK=P_c7Y`brYB(d-|8T$kowTf7;QP-ngAb9VJq-!MdA$u@d8%i<8C&t<7B`5AFt%Va(8z`A+Vu-a_- zx!5kdY?to)Jmg_2ULRn;G`~wST1c+J2~gFd&phgXam2PDV#kL;3V6tS4l5c^E7ICd zMnqN$25om!zpojJ6ewnng1;&?%Yn=l!l(Jl=Vq9%F4C6Y{QQXFwD}--()>#@PU{=c zP#e2K>=n$iLMZs#zJI4o!Tf~qYK3|PNl0$k+&6Y5!{tA0VDc{TJ|cZ*pk?0ROurqC zUwHBO5_q~}v;_Zyt8KJ@5|q;8EDd3-ePhX>UMd|bpb%y=gIGEXP7zfA`sB&zrpgNt zsHepX^J1pLp*BSU&_p;p#+=)x!4_3SZT}?qs`IBNeD?m3Y zYe+B-Qy-VOvRGJ^KRIAzblk#Sr?dssE53^t@aG*H(|*<_tV8a8>BLd@e}YG&sacBJ zmoxq2r0P3bBcV^B^k*GVn6sgj7sWX2+Btc7_zDF@-1Mui;sw{3ErTTYG7%{OK2A1k z-|h&Q1;^CGDgbfHwk}=n;Opz_;lZ6DOI`23ef9@H25#pCf-tKW1{k#OQw*#}w}H|I z#6QFpv2yx|Yc5=0UsL1KsQOcjMaeu(UbGb?l#ZVI{7?%bBK;uL)bBl3a9t%EPj~WI zTqZ#I3?pxc{8?NlJIr<{{a!sx6q$Hll1vi-839?4X6df*ytTo!(_k8gkIn$j6OWDz z`R$jdJGHb8LI)z2mP@jh^ZIw%BLah&Vxd4pF|}mM>B6K$SCvdBWrv8~JD$AbZ|s7F zlr$*u3u3|HZ!`|J&V5cQ{1IK4J7t03q-)SX%_)#00or`%liD>z6lndZY}2JE5!&zYSme=xy7!kFW%}z#pk}kRf!k4aCn=_q^DkAh(-n6sW@s9 zDP3uyDNV@bE|M6qjW@6UYmIn&5PUmYs`?7lCU5`j-~NG1kLmuMk;{|Fi`F56C-gz| z07+wd=%@QMrP*cJ2ScaYLcA8CEM=$+4NrPcn7CvEo?4)jSu?K9nw=U-DdxhFPgnpm zx)ma#(;x^_NDB2YfGfa4c58Jfg~loD3T>BmNyKN70E{mXM5Qn zN0$rP-8X3(NFd$aczQgmQ{xktpoYge*vev8yt7QI4<1%RN+d*Pvt_g)`)zf2IuwQ0 zhgdWz?Kn?us^wNQl6WuZo)V}m%h*DuKd1PPQKk9;m>|G49B%Ms;+@qLG(kapDNIxG zMjXBfHG){rqOJ^XIWdaD>5Ol5eD6ack85Na zw4_Bpe7E7r>8QnlMhs%-;woYngH_xdK+l4r?sb(tON>%YQMk4Ve;1L$mQht-eaM39 z?_CWQY7+aZE>OpTnH|in5GGRk`*JY{=F9*nNc(FDymx0<4 zU&z>6^zUe>=Im(};ede_ap@425MM@IIawa#8;V^b3jYtiNrrf%@H2nv!9RUKARqbw z`)4^!*#N>Ef#qySPgggCI9gJz?8Wvl-c4!}$3t zPtcD8rn=T4qPba^501mgW1!Kx(56jUuID_?&+lp%z^-DX7-NoL4WEw?h0-iwN?_`w zEL+vNsy*AXitcuzF(v0ErNt|11)7ClTd&KlK$1#HPTwh0^fi0M&@J*bvSU~lm0+JZ zN4r)rLQiq}41Wb}7ORuBBo5WlT5BD+?f_8;XkQTbZPVVLa1w{rBt5pLsm%y?3-)uc z7seXh`t?~KUydo(Dl9Y!|NYO2+1iSYC`(ak=VL_I;zdO(Y8zR`#mfuIJ8;Xi{Z}me zsNVg3eeohR4-Uh@h5lws2_)b113(J*)* z{qj_^JnXlxkZ{HY&r;C>D4;ofIS(E(O>Sh(z3XcyusHCpQs0)u8Y!Ow`72m9pmDs< z((Ph~{=sh4KQpJZNkFGVq81+R)D}`@RdAx%I2PklRJeA(2bKa;E&&qqymhPh_!_VU z#^~!;lHnDmxjCl@J5dn|5yS3m9Sl zYxKZ%%xCTav>@52heTL!Y!ZtVsyrNhf})hAWb@ngE6&~un=}_MQvg- zeT1nDI9$n;JzjJ;+1t2l{xG5qUU*mxn2}xfE=hh0X_#wavjS3=7{UrajyoNs?aQ)f z{z}282T@qIzn{Kmb*RjIOyokhCEnW$j~zho?MO) zwN1IbrSdaFn;bKjTw~Q?cg+zDfBiXUV~KG|shzsf z+DW49PZaF@3T3fEUx7oh?CM2=hvMBhmYFdl=CYCTYOG>x>|S-{OJzqp{_izXUV&eu zl2t#%;)Gy-{fW4|(<_!*fpi>y>#iB2A0`wd*Aoy|+xtPvn2yMlTlQdKmk5iB`%4zZ zbdb=}xAa6$h=!RNBQ57QCm$bOVRlr0)8Kl4o-d$7{zL2uwwm1gpQPE9w`w=2#VpwW z(#BleHAU&BQdx^1SWs+CzZA+LNU15Z?>;=J{#ruH!04UdUR*pF6ITuV5fRxSN_9e0 z+|{?>?8`x_1=qG*aC>v!u2qQ9pw1hr1tyJ@%HQYb#jw|pw`YI|6fok+nIK-|5aKo% z3g?daW0eKtz5Sg!_-CMyTTfn7vdlZ3c$hw1%lP*+*-OJl{Vwq-j_=~LR>P#ljgJw+ z_tpJC27+Q2qPuZ8{eR^q;PnGi5-^O*s35(R;V|~`_u{8?R7R6p@u~CZc)xK4#@wXz zvArWd7Ay<>!LeLeKUmpwntb(N@sz6WH%@McqD%;9qDE~dqmRRE7(65{8Pd~s#XAlO zoMs7>8j#O z@jsy~eAZ?&wIeIw%bN`LgBb@^C1m-ue}AMWFIE)V#Mun#dnYilzwR!dTw}l1B5)Ll z;m`rhFkP1Nx4ixeD=Y8$AeTo>jFA{&FH47Nu!_KU)L2~370CmTpMiQqn^;k7a*&m5 zMH12Y(OT2uQ_^SO+O2q@x<_NDqfFPfC|QevfNW^87ugMdMrJ z7={(0?b!GB?;0&6E-Ci}WE4%gz*;pX0Zz|GojsOdEND02N44Oy?5k$=%!aF}p!H1C zrk4$Lq%u5IKFc)@-uT?CE+9iVyaK~AAnKxsh$5prnG!_tzy=EuB{vL`qRs%U9p8o+ z1~8VS@!)tdiiS!>Jjhd%t<_b@pIr%UXnYXlrm)&br)b4jTzx8w(V<=zE%LlvWkG}Q z37QW@1ln;_&fWf&1q4Ba_>awRP(QdyEcX9h3tvp@GX7vt$1Uvud$#j;`pDV-w}EI| zkUq8)2eJb+9$x#8_e?6smNq?za9$`U*3&o=pW_zbXc_KsQ1A^f3QC1bZ1PKq@6%cj z-6WRMco-^4*&d}XE1H(P@n<<~$rlB^lM( z3esT{Fa?7qxA#J9TSs&_V9NV-V$?84pk>2U$R)SDe_sVWk!qNzbqsvcUxeplBm=os z=z`tc0~)JSRyLaA!hcf>drl%>G1wE$Lt*qlgap%_T6jhxvU>UBkrvoI@{Y% z_zTvwAc*By*6O~M7Yry@{N?RN63sx^ zE4-=kpE@SJpg(dB$QMtOvORN_pN&2O(_rSvM2a+A3NiNCa8h1^$I) zvulxS-^4#g2~!$--`9AQTn+3WnM%;>;*k>2;(q4$#L_`I8N$9TJ;m13!-VhjB1bt1 zvAJ+HZs-BI1_T|e{BsS3?{n1s(%ghxYB`mwYWEz38#_w^ht|hv2UTX#Mr?I<<%Ln9 zJXFhf$YtMv0H{pxWjsSxV-)czitI07)Ax(m{71NbI9h#u;|oL7q{SdVY!k_tw2ZX* zR6_G$M_#)csbFEBa7?VQ*M-DGES(_ls9B)#ho8{dZ_cw_DZ{U>%XVaC=UtFvBK3V- zpx;gV&K@+g6d!qp3Pd*XFs4u`$M{U=!LuwT+NVMI9?HXT{)yixTE0<5TDoVZ4B9H< zLJ@`VULs@h4M57ot~dinvh&^BOYd9jau=#?^tJ<#>&%}|A3Z*HkSo3o1NwdX{P0lR ztFA558BOk|BY;bZ_2P3A0?@3+0NvzdHXKUce1D4?)k-q9!xRp$s2hM%{5%wltzK?9 zsy-hOoW;Zf94t(UUHC_D0_I@ujw4EJPijgCjDD$E1Z5QEt9jI;C$$zlu_qx5Rdf*9vTy>uoYNqOH-B z#6q_|jCvB?tmeD9gpwQVEV7kJJqYy&8{P(|mYuxD7H=CkPg&+0kjDMYH`*x17rG?9 z2C`isY6cimgKtEYR#j*Nj*JM!Y|uFI>45W@n!;Sto>5q=hvq8tP(KZOg<=>6{s2cT z|FoQ2nFYl8_HIpj9XKc#8c+;vdg8mb0daqcz4XnncuGz`F}`YDL1#*n992;!tPMse z`iY>*G`sxl_JDFT(-!W%6BfW1ZXwU+tgDk`gew**2E7ss7I}V?I=>vI^9GzKRTioV zue{Sh$PO!{%wXSE)|C8F;iTTCSbui4 zBG|gZF{BOiWBv*A>3H#`ny4<797@T3dpdcfI;t3gFPUc%Z}37x zWb1XcP?b)T;O$tHaS<8&$OI*21c@lUL{ipJ*%@0Y$HH^Km?LR?!=K7P#>`5!$mJDk z+0rj})@1B$Pi)(T*T-`xOsFP^@Diq3BLzbg^jD&&-5nih^I-7<84Z%$so#ODZw*+# zwzm9$mIH7XVC$)LF77p4pS^Y|w}hC-vXoSFva+FY2k9X#U<5 zZDp%{c|{o=^0)?etXUihI|J))pR1Jciyx&j`pT7lHlRdEiU$Y_7ZJi?MdR5Aya&Mj z4t=V}BS$sBVbxRZ^>zS|Y<`jU>Qf z^xiG(b^aj^|ZiZMV zSwrs5T3tCTEN5{Kaqh;35&TdRi_6)1a&WVZ^sK}FkE>Jq3oRG#xWweK6-m?&xp+v# zn@LJ7S$bA=TI_@uhF&C1t{F#vCC&%-hX-Ny5~Y=MRwZSiZ( zM7Wbq-IZ<8u-mGUg2}rxg;tEoq6z6Q;q0Dg8?ym0g=kmc=>h*(UJ;o}e>5pAY570p zmyB3Q8wcW7vH=1}XekHx(}h6gW~`Q=TJ+g3>9L6E*xq1;2uxpj*Kr#Vrh5hISZcVw zk^gY;2(`iv`Nr-)45q!!O~B1$IEC1-{?t5CHTH4wmNvrHt=s}|ogSp^=s-=&u;^#(% zK4ugy+9wi~_0sjc$imjz4|6pYtc$$!s7>uLkHbDHcZe+Dr@sP-3rMFf|AMt0Yw9yc z{lOoRuSVog0?KjrhEaPb14EY8>@0I!W@Xn;<-V@gqWSfPUk00p z)Lot`s0l#hQ(5=!v$z!)E&akX+Xs_MAibUkE}0*BF~Za@P+JZ!kRNhF+3(Z7MMa{! znhLE`QmH=$O6Q)z$|e(wyMUlr97tXgU;7uZg?IspwW9dY)CkQH6pvadLp36&=0){K z2~B=+jD8mfaU&`RWisn@(Y9jNcqWhMyI5SoToXgWWdhOb8I)YFCtVnF&L>4q{s z=0@-DQj__3dV3(cBP~XGjUB!O9It&)VhzWt8X7lgaL)VtsI}?D1}_>SN=ZlNbm9q- z*Sy3(SWFC0SGUCh&=Tl%`cdIs?p%2iluM$BdLa+Rz2ghy3J=0m(0hdne;(S?A%f4g zvTYoboL6TP54dhr-ob^tI~>+MwL)iu>A_MZCW+Hdbcc|QlJkWh9io76$k+`Us{G>x zk_1^ya1|zv#>8lc@F8pT9jBRQpgM=-CBm-DK>ruykN7R=R!h*c)^l9k+`vZT*&M|W zl%cN=d2gCD7ft+0Jpb1M2)^A2@@wOf6j`Z6Y8kpo8X|YVaJQgNAdRDz{!N^~F;<%* zS^K#0juC$R=PK;2;**Dk&;~-wW6K}tr$VVy&DXO65TV`Dw)_JPPHV{yZ&DMt-7Pm% zAL}dkM2HXSZ{_+#jS)Y(7i-N0OQ09VADrg$*IMFP7DyVFcptf=a3ga3`K)SOJyVN> zB0O8ZOik%@Db7vX`q$$l&zZr>m1_#+W$!lj5}b={GvyWJdO2R4wdkl?>?>@B)q0lZ zz%B=GOMAN}ZA)`AK&b?GQkd$NWQxYir3w$qc+RV?S_oN=4LD$XxOj1BAOn~*cFRyOA0f*}3?}fsyMKH-@yhp^+=J(v0L%=WkaXS#HmZTv=b;~$D5L#_cbf946WU=)7s|2b5- zC-^{8V~b>U^TZ>F<~st}HjV9;kfoaFmCsVTd7SPVw5pSD9#n;{Zz1%dy2e+5QQ88= zD~2LW46}2nY#fJ>h-Q>}KchA2xvBCzl;;67UIX^|NNHa(qxK;h;bPZD``4g}?8J)>=TO^E0@z8~TE z6IiQXTEWC+YizuCc{zJ{-F7R~E?3==-e%%NUZZ+yk_-$HV{UC^(%Qvv(sSTPQrL{U znPJk+x1GG`AACekhd~U;GM0G@$Ii~qwlMArp@Fy3%yO)>pD2|tg+a(Kh^-DCx#ND5 z?PgH#M+;mz(&pG5mr1p2uw>%*;EXaRDY_R=8AeYv{y}T14t(P6-$}`_3oaAN^fWa+ zKuUvZA&!g{c^GhDydzwcWZf9~{*KWnin2Si^tu+;%&@uZt``1H&S`Uk|5 zy&oT2$!OTLmuZ)TOVLWxO{yK_`g^BUt&*p>uGd2=OEj6sEIp>fts)kUm-k;al*|fF z?-6dO_~bnPSs-n z+Gv>4kwTLYt|9JA55cvWokPCs)-SpL(R7wkSw3GErn|elySp2tyE~*qx}+PV8|m&2 z>2B!~X;eUv7La)7xBlzpvrBmHXYQFf=j?rLbhv7Zm}e1nxiX|t*9ZgIA{NCvzVq^o zE8=m@6V4ugsjXP5pBV{pAA!>#Q0%|v9*Eikp;NOfyw$iXt3QIef@7qsHVLu~B(yD4 z^gET+(#|sdMZ*aR^ltVFgna;SDPtNh9@ZVg1%a@`g>WPEdMzC29lBmI_06`aECbC5%KL+#$4#U7*4pGZ?%yw1!28A>f$W zQrO+3G({3ZV+gA1ChJ3v0AZAqjKuam*J3u{xmx~|QeTiLXf?bmPvo3=+F^pH{rR~j zxRWkZh=9$ibgB!h)D;XNX7Ni}KTo5ds)TdZe(z!7Fcz)BT)??^h<(4}1 z2=3PRJ)A|ck-!KF!>JuPqc%2W?MGpt0zpn3@deHJW09tIoklfN5hRa@VP$e%Nu&m8 z9_PvBsDzXCGXoqymp3(`Z-V9TX0AEM1Y`3;t7J#J@VJ9GT7Vn102wJow`vdcOe?aY^21w$|&8vG}EAB?FZ+1O%lVZ7l1P z%oN_yMBc%F8mG9A*U`D^2#dM^A5BAqAy>!nc6CUucy!BP-;cWHbkdNKzOmtulRs@= zces7E_q|w2jA@6k&it2WC9%RI5_Oz z-OIKU{O1BUuE)QQ1(J1lA;R&}r?R>vgqd|BoHF^&E5UfUGDv(t*-v+$OUJbA+uAik zfI`-J=a*cmm*i}n@?DWbCSD{?$Y95?O8=&8?qKR>lraX9l)$sHmrzKT!n)76O=FId zQO7F(>t%sP;h1K;3-dY+VN4e0gwf~+Z*RO84i8J*N(7(FtV^v*pQFHIVQT$VSd)0) z6?#h9c4X$X`o?%Aaj70#m*WjRai!`N7zkDI7)^1@SU4v&ayG8kf*_ddh*#(pCV`rLd--}6 z3_L^v?v;z`_QpLY`Pds}(Gd?A9@la!ib8dh8CM+lzYIKFs59_}wP{Y(|*ouyhUTr@9yFCFYASIa3 z*b!3*e1rMFW0KMbFJPi0L~Q}iKvV{I4V1qPZS{A+NGIBQe0-dmnmReLH<^mFq9XW0 z$T?jj#Sq5yyG3K@7cr>i^qp)ze~yz}L*q8x=R`Y$_`46fvHywG>y3;Gv%1SOO%^bo zFd}Z5^(A=V&q`q&B=nQ8_BJ-sWGL%nr)6g(gypG#g zAd_y$6Ge<}ej}Pr@q?d=D4IAC;jiOlZGmp+c*Z4+~3xn>neTV5OA!O&95GG*AP>frVLetPmxO-~`x z#MQvfIuH2lkcd>+DMvPCZ(^;U+Z_!|9N>zy2uItY_ZCgH`bB%nAw7s7XC9S;3&cWN zE~mZjWe5}~S;-p?vi!Fd2>hhsf6_l&G*C9Aa7@OX*_n# zylyr{L0>>}qA0%FkM)=lmKC<_F>rpFlNW6t?A$_mI@g7AVo8d?J8lPMRsIWfUrb9y zvnnU)yKx0Eq~dhcyKuR+*RE!`p zP!G##fekZTI@yQBi2quclk7Z=a?gk^Bl?O86Yu7J-nj1_f)fE$VB0D<>HKOtFw4tS zmlT;}cXk*@`2RIPfAx42TrZc!gT^Ca=MojMJR*JuS=sP~&ROG z2tQu-S{}Um0MfBo}3= z=WQwk@mP!#1A(YF!ijZ%YITbFHG)~t-Kwa~J`e9{9Em&<-vZ_LP!0T|DfV+8b+fp2 zER$`)<6q-PiKyY#R@yb^54tK!W6r-9S;IA{z=(diec##@01b!u_-Jn=|P8%_O^Nv88e0~Qf zi|-8ExA+&HWqcGxxI>t9IKLKxZ6hV}N<@P=KaolsDH7!O#f`g%GqbEv640Fc3yFI{ zG>?I_R#4L7J%O|}tJ<(mqDy)q{AxWYEOP7>9EDBTBX;CpYw`#lI*+Y%E;J8IOoI2Q zSaByNtu+!z@meS}B#m#(P%#`c$q%Y%AL!Ks9xn#hRG(AlQ57ea+-bq=@!pDqpOgC#m+O{ zoC`|RD*GXxdn;_pcR$;6w!&-X{TF;Bbj}!Ag>m`d$Lq)e3`GL0##E4#R^2>5k+i$R zoq$eatwn~0S$ilzTsvv}+L(}!wkTkZ`SAt}Zu~XPB~rOoVeSH<`i1zt4v;F$< zjPZWnI&g<-+Ju_$P?)C%UVoU77OHQu*nPLS8QR$Ybb7K}d8IjF)BNv03w329=Ne^i zdCFV-pvntQe|glc@5EvnxQ2UK2ERT(o;411*i>hFdZrmY-I-64AE&}evrBo*|y^p{j*1D7wg?gl2fXv><-e#)_nth%UO5HbBLBF^EZ$v7rVhIes%kiWMJ zWXOWA>G;B1ZxPY{V44!v5)pqPdLZDhYA4J(5X!M6y+e&j88aZ4rNhbo)#C#5n&r?; zz}_w40SU%sON+C)=B5e7ZOQYUD>G64|9ZrmOze1R+C)#|&qi6QeS6GzrSa@Q)e=?BRJIH6VP*>NDW zl(T2!d7bhGSeEHPNV z2=iAkl*oe!e{6ctg!g)RHDDgf*(<4RTCj#IYipT33c)eUQTJp5wcWZ?LUdSG`uwHW zxxA-E7`L3E6&>3(U3Wu0R3%yR^bmKjCsxNTyhO^-83^M3fKOgl`)V@HsA4smOPk^J zZaV6{qzZ!j{r2rEvw8(1#umka>6LLi`>h6br*_Y}DC^&>R9}TEr6pjBvQn-GZRO>(m-!>f4Ce$w zPoV-oeoN$X14VkT9jsL~Z=qE7d_ikSOV?IEmV87)#Rp?E|F(UJZHoF##yHm(&p{2N z)ydw2?*#6c*kR9k3=#JRkWE`#8)~n>Aw$;IAv1)LnOM;)(ANF|`89VbHNj>ib?jFx zW7}UvmJ!KO)YALj4zy#;a&wR#scL!W?K!IG=2S}j~B(()ODhI+SKO& z)ZoTG;a$e3=Vr_-K&{Xpx_Qu37YJ+AP4$bO@Y*&Qv7LH*Gs%BOi=sg_qpvooV)W|} z2E~u$vY|%Q3yXT!kYgHDobFpf;BcV0oAzjTLAFGA!N5C#0WM(!jn8Z zpBU$`IAm`%7QxXG3^(=vyZA!HL}@(OwVjwp+-A~mLPw%ZF$oS6TWH{{e*3-II=jaz z@(ce&?~wb`Mkw{u!B{*XDu(uF_Fa9_gCHd%B~3Jp273Tl$CEx6MHl}x1~MzTvF%pQ zpT3Od7vA`fq8~!sK?qxa%~k;u0n9mM$Cx^x;Lnq&6wUl+?g3z0A|faG3B6RG|4sVu z{nbH2TCj%3{GcuQ!cHP1ojLRkyr;n}Klzd5Q2*fVJ^YxNKP#dfm=dHuf&Tpt1R*@_0&otYae+U~Av)^YtPmMKKm0 zObLwAVcll?k&%-N?__6eqq+&E_IKfg?D)!bXjBTqTkCYQI=*KE-A~2mBQyjCq+xlGTt)E~6001k*&+Osd4{awDjiaS)lCFxr+%QRx>=Psqm1sC!9^U*jQ>ft-&}fN!{5eQoPd_JeB(}xCB#a zyaT(hrR{9dqEmXlwX~GFfX|IjzI=qF!qm*m8r-EO>+X7Fx9u(@HT((e9Y~`gE zyGYQey{LAbOnpPc9y??0u?8^Oow8z-DIu2+Ae%bsWcbMIoN)&$fq<#0?tvzi z4oEe}wyjU0Nrp&s@107+@vG@Q7{4VjjH=>#j|!_~%l*vyytI zJ!dV0L8|zHHDI+;?(i;NHc=!_qs41Z<`dER7cHaKGJaWs=uOTACm&0>*#_dzCEa~4 zl7aElflF4-RoS2AXWc60VxMygus&*|hL7n=a&-$pnh_3s!3ZJio~B3s{oZ15H860n0dib!*B zN>CY#Q~~rC=CqN#H3h4k(hLm06AtNy+cBN77OqUhl56`{?;A_dh;2AedweX~4}j7* zckDe?8I%{kpdbxmsyfTJ0`DjaQ{)$c){>p*W_Uh4o=(W0ao^AFvFFR)t!h(meo^Pj zpV`zZyG{hN&cU<0JFlA>+-ZQxkIbNR(6eF)b1yw?B2Z*Y|F7!@Vt|&;!EB?AhHRh3UJ|o1+clh+jx75kfEUcF;h7S`tD-8 z8(^=}cDlQ-`7r+`$GRaeVKHUj_%tiPekNI9ulU7y7pLK*<#3jG{UH0a`cN4>*gT-7 zY&#R2q>BUP(Bov>+!dD`u@+udkf;iHS>PTf`cWew&G`)v2f?)^yV&Ca?W8NwK?$|= z_KD>gU`p=q`N*m`TmUW^fEr717?A>j`T*ofgC#FUF`6?C*MAKBRtE~7VA{r_mploR zw20CwT{L}h5fX?CESK(J-UD4>EG}KL#zR|gFUgZ1GR;$l`0QR+F^9|iOg}%;Nh10rYe1Wo`g=2P|2G= zE;VMl)Oujbn#U+Sn~sGo2?as(`a)lY|YQ?{e&w;n|r z@b^CwvC-+nM}#`0Bi86Dsq7j7=aRfg3ag{&yKg&I(8Zb~oY9=UsV~ZI*cgl*YD#qC z@6au{akP}T$A%`l$97;U2(M_w%avMNnKlE$_a|~ z3}#9ghrz<#9mk;~|KY^*{)<7V{|j(ob0Yp3Nv$RA(LzFh7Cr=GnI|xai9M?Je|G_h zkCHzxRBx(F&^W>oqa#xjZaDi&XO;-!QeT?2egX%fZGWQ1!UjEq7PdHkxewh$rcS6M z?p%soa#!%2P`d}bqFo>kyYSaVWTeyNN~KVF$5~b`iZ$nS<-`jfRU?P%s69M!3I^b* z%Q*Sc)zt;-K50!XI)Ux3lop$d9x$AHwuR{ zp{Y7i+(8vRHlnqs;1Az!TB^=oCjy} zCHe)V&vzi>zjS)r5g2!JX?mZcLd|+W;w5TXkofWwRb`|Hg`}E-uI1}4cYL!{E@A<2 zDzUYgk_(3ty&H)s5#tEL_fk!LlhcaK>WVbPITh;4fx~|c^rDakTK-I72p~TGShP

    O!^!(A&_|%>Ca_^ssEwfVG47I2c^o6phNN71vXkYQM@pp#Vfi9 z6cH@tFzDpcEX^MIbkXoWH(n6>QbhN5r+F{)B&Yl(Ls|Dk39!hr$4i#kH=Zam6Ycg$ zHdL|2Keg}ux2JEFUy6m5t>Kn`2}qbO?tUccL;h$E)_LD|AV5({{81sBCr&P(VyodeZT&799|Frx1?PJ>e#rl<9cQBF$Hhv)}w^Yeul34!X(Pql+=&^9Gi)MVUkKpY;>dyD7@e0?UYos^xC+@^|r6ngJ* zM_;-t_uasu+K>@aDA*il9V4SgMBMNC=_s+sF9|7v(QrWn-Aqg?)q>?508eKxE>ptqqDo!WVUiL$zYT&jj@q$(lB3VP9pTuop)pQM{Xo6Q`;ge$<)@L%MawBKKx$d7}A%ah1b%>1)L$E|;U#k%N9VSw_C^rPi~bd?qixQQbz8Lr-IlnT zD&!>sX9l^DlF4`O;N_*GejYe%Rx|BZ7j;@u_{*B=YZ%~Gfeu4*5*T{rle|mx!DrT&r|Iw>@eN7xA9ba!^YYwYb#M=l`_;DpC={H~>dBE0Bi1>q; zhuNDy95sRk38Z;lmda_B88%%$G;P^jc!(NNt?xye6Y2Qi-Q%A%*iHBnN#jjMFOepX zKcU*&{3PuS={};C37MyaNA)M}j{bOlyTYX<-b#}{ck0xaOwTV z*jVJuprP!`Wz}mZ$#@V5SaVSe+@wtyIp)OjPq^GXUu{j3GPTB&PsZ66IBt4q*%Khj z`j&cOGOdDYaLEo)TEvhw7ddf+v_ejwnjqqatY2$C+aeb_%G1oN->!?2&DBBkuuoTv zWW3WK`i{#P!T)#;93!WhB+7&GwA(9?!*t+VEee*>|I4IX!vyo(c_5*Y#S=_Y zAz@y%Ve|Vqmcv+QGg3{e@j(rd_A&f3;cRi^Hi~T81Rp=tB^Z*)@2WtBb9}VqJ3*n z!NtmIkg*~uP`k}zv1lUTxgE7>z*tOUFfmeh`N#eL*l4sz`j`RpQ-`mj3U?8|}h_MDX48o$; z+$7EA0xZWjBbcfb6V2iPm^>JU$<&6O)6*I`)sgQx1`hI61E2>1?rPUIHeBKpiv(2D zmZmD9Pau~859Yf3M(9j$s?rbhhe*|S!ZV}XVP<_TRYp<&q&;7rh4B-v<1db^5q+xf z6^A(ZZn#$EgmDAl0a@~1Er8qzDZP7|Sk$~RKDsf7tclbBq5_s~xr~GxU|ce{?r+$< zth(M3%y1ZIMfmoDyKTp!zM4;LM0p&*n*bUr;HC2KTSc}fYGZ_jizKm{IYLN)`?n)B za@hi^IVUHl72Zdmw{0nni8o<1vsw}F_~?w!e}O0r1W>$x{!SG$_Vjz&lb`#0TmFNk z#zd>#*Rq#-bbg{~E$pQk~Zo6@*!w9WvXtZUWaX_%a{)dRsvo@?cFgW5#6~`?Q=Y8b`x{>8pFNe(VZU zSNKvljza3V5AU!~Zpj&;j21^&K|ukY{2w=QI4=)HXB8&w6gRVhVCPL{dZUjW@vY%E zbTDkEho8IlaFXQaB-u7#Z^NFmCMH$K1(D!=megyOuhqnb4`&5nA`_$swZ5cbCa5xv z2xz8-yKnxedLuY z^lI~6(ZCew_TluC9u&Z*mDV69$24)t|By--WNNF8Ql~+8hgdOa*K!G32Eev90JJC^ zk|0{6luZS5y^4rU3L4M4k!TrmQ8k?F3bNT{#9P~1RJ_Twd>`-^flRJO3=BDbiT{lf zFHT%+o`CF^l0U0h&S_UxrOzABrIq>CTYcJYf4)w#z-uqiqJ`O|>xc~PxYBZA74zXn zt+vKPIg{b|{grboT^FLyb`+A<0AQ?x7@Ti17ov0jR7o9mxqZ983g|7q{{bjdH9`LK zqioU;xp@}xtE3>C{Y;-I+Ms%XPti@Rka}d8$888ukxJ%GqP13orl7tgs(#z<*vL&K zs*FjFS(R`-eM%@Gw6_Atua8f+C&x2c|LIB?xq<#&w{1w_hS{YF9?(qVw+g`lgU<)6V*U?Hxj4OHu*v9}YKJ8zUk%pmW3 z1Jt$G+e&d0V`Bh(mU#^XGL`>O;4}WX$H9eSL7-OMimE>Z9?Mk;ecWt0NHZa#WbsTp zEjCvL>uKk)tG{n&YIn*Z4WnO2%+1@I8rsmG1>ZJ@R0=0m*2pp*j1OUvp#l*$7k_Cd zz`A0hn-OW{Ta#vcagf_0{lg_KiV~i*qQ2DZJ{x?1;e;pNI$kfwh4FSIf}PMUP=ev$ z+rWqAx~P+uqQ9r**ukwQ!MQY(NWQPZQlUCa+%H07$f+yemGV-Fp?hMRxriTyf7Xo* zBFjDJJAkB>oFrbtdDy5|7E6$Jcwex&6c zND>ELc&=MX`d6)g2c(((38HfH?Jf)$`>&Xbj>ar4@FBV$!r^`;mmoC#s3#Zo z_w@FT8n-OKO@WB7-Z|Y1zT694Bmu2d9hEZE6H8q$e0*JlvAJS$$tg#tC?ZALYH=Eq zGU-e+?)(^~F`!us6q7${uodfYH7aj*tyS%zQ=9qdLP_N1@UXk2z4fS^qsz-eQw@cE z+Qu)k^Pid)s!OA+VsnUzYH@UdNAA(IpTHSU%q33c0TVK*aDb&kAGXHGE#cQCn0x(3 zulo=|Z`+!K)@TF)|CDVw3}ERw4rxE~d2nuTLkfiMAiNs|M*Y}`nlpxprwvFBKom!O zS$jUBvn39?=8q!D5XDCKf8-XdAhuAJ>V$BJKPtB^v{>58sl_@v`bl??K4QQ{XkPDVFhHR<@{3el*`}=ot#wvfgP}f?`q`@$1lRC zi~RPZ9Xxm%_>FJhkpH@>W@0oiuFi1~%Kz(z0-ffqwwFvfb7t4{nn{pZ3|Qos4~CwO z{_5JMEO^G@3o{yaY?J2Q@?_{1-a$cqClT-8hly?~FwIA%FmiJ8Dv!RtiiOt1X|4uK z*fKVZ3m#0ujJsR`v595Ek~Va@!%TA6^$g>s+=nyocyc*5%_0Y845B<2r#Tl?ZB$ru zQOmrjgl(*xQ@mY=0aAM8XbW6>JtkEr{_hDmlpm9_Xd!>7xGv(jB&H&q{2JHsajo%? z$@3OL({tLs+O;S}9NrRp@WAp|G8A9XzezdQnE~wa&*j?V7mMQ-b|J{sKi0ePh}no_ zq;p94qBM*#pGv89ybrxjXLJ)NT`1@j11~`r>Grlwk{?B3JLU2P4EshUNE(E?uUV2B zDnXjcbzf4ST%pYE(Z45p4y>8`G>s~gAq-1mTYil(jHTW>OW{XL@$uQuAn^GE< zIQ>4O3CkPS4Eh_J`z34sI1blESLpoksoFUWdZI6dTkju|Hd5}iVFT=EU|+e+fLRQc zn3TS^_0c}nS5>e2H<#pP^S?O$O0_r81pp0m$-6Lhd!eUiC!+b-U7 zu0IAU2=Qd021SZ)B>Di&*#RS#neknvC}yoBy%3$*ZGve!Kb0b900w-ge2_xg+vImGwZ?WVqH8)k=0d>LPtj zr^*IV$+r%klxl1up&`x|H8TutcZoINgV=%;lNe)daLYFi^tQkIopRzyJ*Zhz`L z8ccYQ;+q3<%c$q)NxuABYFZK1qOl+6HZvkxI2geoE+5SqQg&Vjh=M>dbSYZXS1`5! zMWw$}kZ?T8-TX=uG?118i%-iO(adJ@%S+IdsZaDz$5S_arVt4qxeR!?MBYPzjN4+7 zus=BbEbMv7m;ZG=flXg7D$5S;V_E+7s-Brf8Yq&u9zLCdD8j(fc5IaTPz^H&UXo!& zEU$REeB=eZ$6H|Z|M21F_ivPcKfvFh?FD9Iv%mg}a|95+`Iz(eRIqd|xoUJ09VyJt zLpa0RyNCW^P^Io9KQlCJ6OmT!{4xxUIQS6}1eza&U5FRp4C24&6!9*9FrvDkmcv_E zC`&SmjSJ_z4mr(ZsBLWDET18LGlo6`SsXwO0H^QU9wXb`8?282;!=-UVy}ZL=KF(Z zg^U`YaMlZ39UbJ^Dr~XInGeCMCB+ifE*fxO_nA7>1h!`7LwD53h%}~P-6cR`SqHV+ zM^dreTXS8pMXK1W_$B{3f<5lnV1qe9D2m`pk2WG-P$bl@o^NC}Ex$_(uKEYGQvg;k z8j|e`AVAf|1_qnk+tythH<)~ul)|Bhp+6PnP3|!Tpo0?~+yO!{Pqngj6Ab(8xM0lx z?v5Rj>{Uc2_)k$&)>=lnvcz@WO~mk1n!!?nAaaG=(&3x1ytB@+<6`aMEZK&2Xed9N zknS=t1gsiWB)=XWo(v0ML2%BAb0kIatu&U=R&Pf~=32k&D80>FyZji_Tz~V= ze5acfr#|f*T&~D)x_7Bl$ps>=f}gO*Lij81uCKZF2K9vRQJf$m)Wie@A#s%I4+Wqn zBU;$L$0$;6#7)7T?_(-C4#9hEa-SS_>6|A{E6nmDSA;US633c@mSv4?wv^$&P%(Qr zo%||n4oTYYM#_$T0VkP!He6?V5~lC!mdrVpH=;SOIkidjf;^8?iyLXanBb9sEWJ}11q z=3YxRG^e~lx7o~2BHR)hRr)~bgWRuhRSgvaR0gNd30Ub*3~3iRv93I!L$Wu}F*s14 zMXIeRi2sWx;;~2=mQ=F5D3C6pGTKE~*~sPZ8=iEDb4%jivY-R8|GS|HcEP6px{SH;vnbL$G8`r~dUP){8s$Rf<%*ht2GA|7!ExVGS6 z(`Z>5Cf4D3#H|L+t|R!98&+KSnkBsUp<$-Z4%SM?rc1%Po}sqO;$=5 zN2!kZ1HbHx z*D8%`pCoKKsnwfl5oe=tsRZ?0n|(^N4R7Oc4zQcAS?6q)U$qh)^9?zY4oM%+50gzO zBi&a@@yu~WzUh62@FOW@NN&Cv8SS=l%8KwKQCvnK?)9XoxcwXuHD6Q*T_2}K>MDG|AwDjHf7E!^+v?x$4dAcNW{spDrC<=#L3{n){eWOc5bozUFnfyJ? zHvi@0@9zd_ItH2F1K_D3;QxH;l%SE3GnA|0oGPQAvi4u1UpMMg($#61t#N{!_(uj$ z64r%25cg&xga$LM+EadpZXrRkYxk#bEq5;4D#_1NhTZk!$2VY!0Kmz}^#5?K4d{+* zg|uthZI~E)4&|rizdwT3F)(R?XJub@Jpy+B5O*o^HQv4@B5N0r>;RxP-dLO+#kzo?K4(vWNJ!g!5H_i zlxew&L>$&vRweqx^X)&hT2a%EAA4vQZW0`G4SKu}0#)4;?%xSc_yneY#`~gXj37r7 z&F5HiSE+8>9iYUluV>9E9%w0XYJ5LsOTbKGKL;Zm_g0ZBI`el{BBnZJT;7EHB($RK zAR?Fg6cR1n*Zo+K&ZMaKlCSD%F3)O-spsh=2(XMZ3#ay-ij=}&&(?*P#O+Zpe z{Uz+jO4gBydlJ}^+yPJ}Buip4v0F`TCI4ER5gDsyEkW8f{R-Hdq>j9PlaY{cxTA1= z*8ZmR*`USbEB-wj?=Q@F9JOopuBA9^CUVk-TivaE539uI_X*>7bgi<+b)JKWN@8%k zd>Lt{r=Sl80*lIx_rT$J{}FqlDL{TcX}0&C#FZT#6wu{h%zB=)Tky)y8PoIjWqsDX90llBd0e2ac}kTnbLyj#H8e7+AxhF|rOnI45HIs6=zi>=cU|t7X{G zC`nsaLcFR-4#>h4n_`C0=c?fYQ5u$9ub9A#3p#y|An@#ylU>U>FP7h!VmT&^{a)IFxp8fqj`NW!uiOKgc z0VxNm0!R9LniJY}cx`#36PGY*Oe8tnPNdHrsrdhZ+vv>EZs;b7U3pgut zBw%n4pO|)r#9AXjeF)6G(>|rfS#WmS))Y(U!qjpv0#A#ZxAXUPQz4h7k{b zCvkq~zUg={Y0=c_(7mnqwBhE{C3>dp?ia7Kwb$2v;wsbc+k75t7V zKYg#Bij|DvUv}sFs$Yr3{6c%+D;5?I&^I&l+5Q2#Y+I=cO(w^DsP`R^D@d9?K(tRwJW07+~$ zQM~Y&`E(`Il9tdJ5Yv4GW7~AOjDMle!RjgJ;lFS>v)r40=mAYU0MS;pJF&++3%$P^ zDzs%&tDgL1^=Ip7PNoptV4Dim>(CPh4O|jj$7(>6y`jFoxGqkin-!z=TFy$X7f;7s zBeXuUs`hx>TMEa}(69v$E@HPoD8SYA4|tA@Bh{s51Sqbc#0Wdd3mTHIid)y(t(I|% z5foGHc7D>qt;66Uk!BJ>=mmYN#A;qA$>X}0Wd)W|B$c6kv4nGm{ZmXPapd|#%c3$+ zp$n?_o@SW^clY(7u7)LFbKMzwSTF_Z#Ftx)H`{y(Y<%MX)*vZ>r?@o#(#Y5~!4D@e zzRZqI*6CUN-D|rNp^OUeY92k&x8X;6D?#IZ z7Q!lNGA;%zYtNd&>zX6TFNQb$cw(yaS#` zJA%eqe{h&z@$a#heQlgHqLuODsB%ISPtIuTh)D~_|AO{ivsPE!chIGejzZy`Zek%m zh6!>FXw~|IwZCWUca;tyyR|Im;fI%9VV06yVX%f!+P1Icmiw(pt)bY$tD}5>WGg-q zGM!)bfP#^c)UN3V7b0w!FCXDq%KcD^)Y6w_Fx-NX}TN%{)9gkRwPh zn_~Dl>tOPT0`&5Xs#v-AEgVf}jF>}^7p?tYokCgMxnaZ1Wms`##};@8?|4e6}FP zdJW4*)MfXD*^>LFy*$$_nevb>NrHNu*QTJ1T+KqliSxu?)<_1W(-pXN{<;=4V^vKZ z;C}CAF<22}=K8j?^I6+FeS;;FDbRi6#Q5ODWAW$;3pys#wtVFF;g?`7I$b@z7j{ss ze|sIw=1XKSBNm+37|Y$aQeZu;VOFTmNKGs1BZ^UTi51ou#N?FF%tc~1hGwoESgjI{ z^Yc0_Kd2+orIVoN^<-vV`v?SFV6^n#(G8CCpmqxfE>k4qIxWE{zI-mWN!4~4UF2yB zeMroHzZTO_q6l(#VuYZIm@#M3egj(sQ45>j=feMf27LaI z*|6cT+5zcPn}p(t9{l(i$1|-2<&|Lz=D6f=M+onIt8Fqml}xdoia+V{E70)(>3H~f zjAD1r&CLy{1i0UuR=*^_!`mAkKD|_8>q%vo_y|Y{U?ni3s_9I=>_0!}-}Vc~E^aSj zJDTb1SDkaVuT;yi(tQ_HS*}kHKj{!e{?+}Ol5x20=RID$$q!P}z%)n*6|}K}UvCQI zSI+$s-x=}|-IrK=D7)-(hG3p_;>!7be!g$Z$5AXYJ&z*K*FNYW68MlT_;NkNo>D|kii6!cK8>|B%ozZL*x6yqb`9j&_bipEX6$Xuczz6Yg8aEwO& zm);b41|q;nRB2#Lor#AbD)}BG&D;=2H;%nDx`0Dw6*&1kgU_UeN$W(=KsNqV`MVrU zkoAZo=?=4hUgha$y&nOGlga~;T?keGYF4gP??A_~gG|j`8Kk_Hsrd@m8^yAl!%z8p zMzV%kGp9h(zmG+KA3b-k;EONOrA*d;jt9@OMQ#UeIVA3KjiJp{CUAerwaM&S(w;Fb zB+p|W>8Rl8e#+AL*)MM9lcItD?`R{6e4h8BGr?MjiP9iU^AjO;OJo$nigK=W7C-OI zMyJ3vsivgwZ8M$1c$a6uNnmvE#v8a>;IPUy*AsvUHKETEJC<0{i!TBlq8g<1XeLy{ zi2i(Kwe+k^GvaH!RCW;%ahcLTX?w-A*q{v#yK;;*a(Hy(*5~cN@zZyv{y3X=WJBn&sc=b;8+rV$gQQ+nRZrGb<58?^ zyl{%Gtr2WsPzet8-S6K;MMdjv)fvWA9%%5jyr#`Yq~Gkv&$hM4%2VAFP{OcH?e(e0`t7q88iNZF2DBS{zh~ux-5pHLM_0IUQz| zs*(R4SRZ5wULxJ0NMavjk-AQ+74*#gxh=E&va-ya^>{aJsnu+l<`YlUIvBL$-il>t+sLm;Q?x1`5Qe$~?O zbWzpeT{Q31Xn{qnBAFcFMm_+KuYWsZ|>Ldn^`xbX9*% zG?oZ=AD{KZ(Ym25l4JC^2m%@Ua;f*y1&1%I@2E7@n3=r7M_aj$!#>H77$W~r)l#Hl zRK2MBCK^{SC#vA9UwjP`3dAh@#?L6kgHw4~|fwA70W;T#Uv3xuTadVvNg z_~pzjEeG>{6MU@p_OY{oPNkR-bkpcxjjJDTek7`!gHW2E z-*AD#nC{C+7~*MbD3(GDxR&P*%bz_RYfMu&Wv+CTxt>U>_cV1X_+~Ys0Iz} zFsy&A+e{{fd{dEru~IZ2$=+ZPB{g0GgEY`P2MQkzIHsk8WNjkp@kg%PP<=}05Mq9p zy2eIi8tvbJZLxGbhFxelTGy%b@b~R?*Dmr@|KrP3yY&e+YlId}oo0$VOAA6kLQLE; z)(BEnPs5+rA#L(rtQQ%4W$3MooxZdB>%Cve=DSy@Mf*b8?8M}$zv zq|hj|*cVQRM&@Sf@+mel(;5grYJX}d682tw`L(gY$hD$iKxAO3HTGQ%x?dbg`-S2B z%IdlLYq9d{FW$;m5lg>BzEg_;#C>%wrfX`{b0KBC8r}wlN?~J0Yda+_C+otyvqStb z32VIxFJ%bFTlvIqnY}#6=4G{`FMqzie;_TFQYmjIItv>C5C{7`8E)%PY;wloJ3Z>-zpk)~KzMkFUc?ZBYamiQ!ow5_9~qpi); z-`_tl@EJ%!Z%%*_6gFVbzHL%(t$}8^7XLq*t}-gB zb_>&u0@5Yj9n#(1-Q7rcH%OOsw{%H}Al)V1-6&lW_x*m{`H8MsGiT1(@7~XTA{yJ< z9yYiPIU!X2r1LIdE}!o@dQd_=4}W=!1Id&jQJ4P8yFRx9xxBa#m+o*v4cV}tIJKi> zoUzz31@;9vcIW2gh^N+@Pm7^DxvYx^0^2l(oR>xQsFQiKVy`|t@){EC<;pw(?^OK4 zA(xKdf{mSHD)gSQNR=Mlfz{GSkw^g%v)`hI5YDdunuRvw?3BbQOApw(?xcVHN)U?H z2pD3%FpA*a=I48Rd-wNCJqYykRBXHIXU$w{lia1YSNR>o6)=CNqc4dG?fbZgHBt3Y5r^$Q z*F!WJvPub=k$*O|=Y*(rhT+FMEOb*d9rxP~#5&sAmBz)GF++Oy?%moUpmyOaVrT`m zmqpWCaeAh?QO0X%7)4?>3iJMwtjZt2Tm|&03ghQJY9W~gH#@s8MpKhc#GtjqtjsZ` zs0QB!q~^IDF?T<^uw{Y)1h7{if?ogpePx>W3tA6_2gpM7SBNxlCaLL5{54wf0Mgye5y@AZ3nWu*dADe8U z^)w(E{rPgIcgVFBsuJ>^mzyxZEoVyOUe#C`xgoVW|4+aS#@8o+OS2b-!=QRpqqZ-H z#|#2dH%OX^oGO!iE>3|bHOgAcerL0a*3{{G7|$DNq3WHy>XpA97)nAUhMEE8s1k7b zej>^1YjkFSY4TR!lhRw|i~(zCo0-&z%idovnbWI=uV}@OPi? zQN0P@`)xK~yv&q`BH_a^>6MB<9OP)Yup$QzVZ^?GuhtH#GN)%m0yCDWd*%epa7LN) ziClp^WYYdjAa4Z<^+LSD#285rFS8`rIG|SgE+5hOxuC@G4>uLImkI)z_Vy&C z-lYzk*pez+2RB>qrl>rv{&`q1w@l*6_Wg)%ime`U>5d2ybgm~ly)xWdVMmvclL0Y6 zZioAgko8URGABsQJ@GLqNe*6@8R{$cezfU_!6!>MGb4^mJ68%d>Z{pLRbF~y)a$mD z1|t6a#L4!n*RV6!eCXS!`@blrKC5@3>j#5#OO#6(xKjZxE@brSkTGWhiW*-N1>rd6 zBP3Y4Ua?FR{|0x#%frK3&`;oX zcZT;5*oF;KeNjw4^t;@Vz$h^U9*@Jwb_=PV9`Xe}e<}&dFdDDfnCj%926szD_qppp ze5nm#eFu1NviHa${ykhEIE{NH0GwAKm*N#@j&qP7lGbl;7mehyk?Y8z1FF4Cl77v{ zp?V{T&U3AdsUX-uLC}6&Gn^KNWYS$oZN|nn>CXgWACSxf=6X(I_2x*zukVIaQDW|m zm7pd;JEuBai*l55C$n-li5YqT30$+j1B9`*H0Gq*n-TB3CQA*340kWpLbSL*9=U%E zD6w_b)zW7grr*BfpksBJn=OCbU@1MEI(xCXahRq1qq&Oz$FR&MAb>d3uuVc^Jx=G6 zCQi`L&(FT$#5mXV**!$x+{Q-6!t{jdZNK~ZD;blD2xSqVT(BsdenC(Rdt$w*N}>W% z?zc}Vysf?Wn}G?|cMUQK`5D&_caa~p+3))i3PMXCw``-cwEAoEU^KXLPXPO~NWnRT zg5~6N?p@_a_7QcL^ae%{8V3(3>vHLN|D+ehfQqe(Y+_LNT`=oD{B70VEE<;GOH&9+ zr|c4NKuk`s9%bZV-tC0--JX}-i#c6#;)y+5mpQW~=aJa^jfn|d^%0k=Q)o{7iG&d$ zxHeH$mkIOG;V)m)SXLEF`DwMn*bP5IJs^7Bn~9g4qDB-yFC1>kE()=W>I(TJRla}2 zgRGt+4U8L}xt&V5F!IZM-|7&*e^Pm>zj&Rcdi+!X?cgtjzkHm}udna% zNJHSTR=VJ~@RADA!${{3aZGMwu6_X^dn??A8t$3JPEvs~XP&R(&RHrfg9VeEQf_N%AJpgx7ZGPQ4nu^Fg>!TS8N2B>taA`IefF_V(gsHOrkw z6-_<(@NlluGShL&4NGzg?=k1w(2kv?hqiKiY`Z*4B#Bn_WHx*XhVvRU0m^(2>@$7N!bJ)RCq#DF>ZNTffNi z`X$+^uEYzd53Aa#jtWljU=(u=Hb(O(+(gYj0^bYHE{v)$T!xtbI@#L{s?wpkSoZ8G z{lhG>-Vx3tDPQ)|q?Us?vOi_13zAPDMkzEjv`j;r{6P+dk6F`~hwlI>eI(GJ zn>Mpr`Su+AoBltjXpBAxa1;aEPRp_W>YpC1HCd}ic+VHZ2$K%fkrZq zt=42{2Z%WsbZ*eL-YM<_Hm1B(?g>CAfPK*o2@w}wvFn^$(|<5{2ODg}aC8;Q@GZ=! z2Gv{=$sqbaA5&tnV2<<_6`0HVEuwC90&frqoI5HLL9ki}rSJT-_T-ntLF}*|G7`Rj zam5a08wfo9XG5vu=#Y4CKHlDyeDD1tJai!@5QbD_(QMBa3X{O@h3Z4b0FIHLGcW~7d*SC_zwQ|0v&??ylRg;wwN{!;P5ZaG$6?O}krft-8& zAB_x79X=fpQe*9-D^y^wC|()`qK249yT4?6S7bOpZn6wH!<^i%2Hc*^PX*kuqh#^V zfvg~qZDC@bls8L*S9&k>2~I^yZwJCmD#7&qrujvwwnu6T0W&A%o?C8D)Y*8e>zXa@ z$>SMI0t8D7;%{y%nID8l{1im36}7)DzT~vme1hYO?63%plkci$9K8g1c54H>4z2ca z+jf?XX(Qrv;I-tJs9DT0Wz3H*uFuRmycYa^^7htR73qVB9f4GeGm52mKzIV68*qY^ zy_cY*@1gOiSx^;R{^cxf*EZQ!O2(#WZ8QEYxMZV`=58utsFL>e85h^hzi87cL?J&K z+g~vK1`%$-YGc-_74MZ46f%-t} zeKxxB6g}xT$kq9s!Ie$2$WLCZzf5rm-Gg`OFJuG6(~_1YJT*d%>BrU4ZC-2fPSqm{CbK zv);Ga5B$|PhNp0L2pRt{<7acD1kA}4!aoN4>oTDTYQQYXuJ3@kYW8BTLhkdfeDwS5 z5lyY3U%y1^q;J==lCzw@6|a=Zw~p(28d5;i!s~0RJ&t{4UPZ((xAO$Hz#mDp1h~16 z^6Us{m+P!47~I%hu-QN?Q)3pD^iPOa){iV-i?w-=Q2+iZ8C8KTp-bc|*_w z)`N~T5>ATU{6J=OT`@~hS=hzR4W^c~aQgJEbyT*#+N-{jjycojjxWJM)=en!2MCd! zQ&gCl6V>Tux7ERd)|TG6=kKDK*VDM+;E5oTL|q`-&al=&#Ng5sR^KBa&)72}a3xMb z_({8H8mN>1RAoC}ONKeOG){i1y+jdnRm)#la6a$_2lVdW9oN~s8BY`bs;xTRm_fbO zDpli1pD5^>)^X8&NYK`@f$DLfz&-&2)~$7~sq*-zmGx5V9UYgjhkL z5k=3R8f$awSiTt%ZKgoO9dUT}UWL&%mZw>A!!9|egIBj3CjxVo@h=BRqtKixn8hnSnA0L=M+vS_1i~EFHg^} zm_?=SZEecSOY7?jMZ?NMBz#`))EFG(uCJc|fm+kh{h#9tdre5ZM~?&dz_-!f*Z1G^^M7mb0Z<3qJ3Hl=BLYELj6u@EP7+Z1c?pJRp?}L$fSE#2 z?&agt0epkOa)qeO#{>MSrK^W3!-xGxM%@mh*T+YBw)70xVl`%1GSpfE7D1Mzm<83P>LKHp0cid@vptM);Ix%qK*w?&e9PByQvJw z4wLXUpU$v)TqST2l|MN4UM>{@USUf^LvU?W0A;UqNyJaV-f*N}!`0FA77%D=v(J^I z>)Z{~1d2S?#kD#Dz_J4o2aVyp(e-7@$q`i>Cp8g5sKypTD`h3<-&# z2=op2_xCb7q=UWa2($EaaeYy{ytIn3P#n8&FSt)0Ah;VO-}>N9{zNlkS%I6HK|q1TF( zZXTpm43?*-Rci=jk8DcrNK;oxVoiI?-r3p%{Z@s%O1D2Q<}JWjfG@Gl?9G)kRTs3NSJcWwOqcLJrriFzg8+HFzSN zDACfV&X?Rk`xt|V+If$KOYq3KqZARNIeUX}vup`_6Tx#_;` z?H9b9sxAj*C=0b4TUN19(9lR~fa$(h5;Xy62`(1Xd2RZrggQ+qH zM@Q@t_A%hrF-ozt78e#GpK00D+#JTv_bE_)A-RHX$3`g~=ipJP@@NMYr;p2b)kZW*K_MXc*YQOVC-<`Zx`mE!oJBNk0^zDCi53{x8AgwC; z5*z!y#TBrgR8fDnw6#T99Da%8**zN*qU5Psjwk?a?4OGZmMxM5K99$ae=544W!sGj z2~Q)c0*fS?o16(HAIG zCdr_Q>W>qQ-34{AW1NrPxU#_lIbSuE8mXe>kdPuLR{V$X&U59$m1zpBUrM{F@?SBo zCnhJ6o+xYmi_KDUWQ&zfvy5sfp89U?lV%I!)$v^7(2!LDt{wk#7hk2SvN z?IJAJ23{=NMmxF=HLYQA^m50?)35X=R3yo^HXUZW4APr4P05|6OJ!u6e;1w(@BVCd zzdvX#gAy6h6Z=Y+SvBwXxc_y>20^r<`(9@R-zA?rfAJ5TbrSdPT{er4qoZP~5+&Dr zbIAzQh3Y|oT7tb132R*$%#uMpbtfQ%Ebo*hYz#Y;5{tvZt0fOQ^mSKbZiI1#en%kz z@m7ScellNr(c{^W8ouOiqI)Y5f6=tKt+lm~-4A)66#UCpGZIBs_o`t@n{F35U%(d* z`>-Nw2>yqjwzly$`1YVrQK-BpN%$xP=vrkWRGamNysnH#pugRZ`IKx6Y(yFib;U9E z#3`u!j)9f{m=UzTlg{!$F(cTWjXA98Xt(E5VUCjJOug@@}M0Y z7fgcx*8I=U{7cAt&WDpk9gwX)PF1;UJ<9w?aOe@pKY(5f*vx=dQ3S=ddns!KndTWO z{=_mZzZ&%^_7k6+lZ7Xc)2xamU2Z79S1F^GU6|tS4U^AzA?cQ^#o+0) zn;~c?NkDg|@t)s-t`!J1JuR%#jo)Y($x4TTU$8L!jp^Cnzg&;vcxuNIAA`TTdVAX} zjRE`ZSUWWQgCG2S#@_>0Z^-Ods#;{+x8uG!MemQBJ&Z9L3-S&t6K(MJR0t489*_~?Y#7Z64fzuil zp>d>zgta?YJhH)QPA5@rmB0TgS*?fUjy`des&h;LT|I;H|6Bk<-p|lCQ#xY{AcRrk z-IM;0*(#k|4}|Y0%aut&y4bpzlQ(P|jn2eB8kHq9Gn3Ki*EblRZ@bio-H1Gic{uYC z>HII|w1@Vsryz%I0q+dud~q581QJ+^S#2VV|Z-oL`nTIt1Sqg=o$)c=whf zQyKj6iISN5L^6sSQpk%H%0t*|=Cp*2@nORlNV<1A@EcLGWixsa-7Qmo*7%r2C`B3+ zq*=E2Z?1R5Y3Jm;&d*~R>Dak8p?k|ne2ovx%_yayEOcMuY$^W5kdy0)i%3pQDbI*f zk+ilrGA#zJc6@sR4B_|NZ@toHffL$CA|i=GiOH)VM0S~9NAFM6wv#|EFp4{5jXc!{ zX;>}Qln;0Ee%k>1`Yo0^qANHFRoZ-fQJkfwRMIV?^gS@}_CzDJJnO^*EbKwV*!j5w zE6OKLi86pNNhJ_N3d2e(bY*8*&m0ePldq1t*)CK%BMHDNZ6YB>yGyOe&5~h#0q<@1 zp!bg2ab1-Srzu&iU0==uaPefpi zrBZa28#WZRhJeFQ`JncYHz&tF49PVzDE4y}W?mH%AHegIfK}NuDJm;&hh(g_liD6E zi6>bLG%PZb9h(l#7u-}3;>i?x$KR>r+SI=n2vhSoZNIxDx}uLeIhB*L34IdK`+6Wa z{cM^oDdAmdEb32Mc@}lgzVM;sz7c1r8cEyMffD1YmO@edd_pdUp5}uWSg}&=RgRE5 zMVa^tVscLPz&0|Tctuwl;m zg2l)(91sSkkoLrUcYAvj(~LuB-av1i23eIUm2OWF5`3>euvE_9x>G)@vFVojeW5o5 zj_C_eJxh?d^(-$FF!%-(x)_ySQ!{>Wh7c1I8yXrWf2^AM3#t%AC&+AE(JoP)g`FZ@ zrg&2G%ZvFzW>~FFZq(ibs)}U0FO!_w&^}1A2L+4B{PzNANTqtcn=6srbmY2Ja+>Sv z_myw#^jaMVowT9L3)T~6re~h#hC@QHE{`)7-6B`L?!&{FjlQE1sfmoF?j{FFTQBP;ox4m|JnDLpv99^f0^P z%eB@ZT7N-|*xJg!oE3~#CZ>$xe%pmZjfdLH8XwNzkgyNpsuT!7LJZ0DX*2k9MaMs& zk_*NHl;HpLuJPaB-=Z&l2kx*UKad`M!2i-wl7rX|K><>U-D{wt@N{rc_!Hb9@pZ!Y z!hQFpd}K*_qWdws+hhkYTJP@z-|hqNJp=EbAFof&)uxzEA8?EAqn|gwWbry8vH+un zQf@Qq@>{*r327qy(%jA!KzVlJuvF`-YdS`OKEh4V1z8L7g>tXMa)FH9s{^U^eaV8Sv$_MvF7npjYoU-x3>=P{-_ z3_lN7Yh)90b_ZgHs)ig_E(Ky2UM7S<7f#vt9PqgE|KyobXFa6US3l z2zZIlVww|bW~}K~G1tX*8H?7D*`IP6%xA0j23T+7~~FdtjlQ_p&2s`cDS zxoHR?(``EY&BRkHZpksyQwvN2i-hs)8p6EUZ|2uws8~atSyzhW>Do=n!B4cxrQ;?&Pt9l^NgleBoUjc5UjD44T@2Cq z<41L&5*aXfDU;X-f~^EXg00Zl(urhqopdQXH-@j(7#8fnI)bJB>hC7NNg9|g8^BZiQfS)G- zS54x2-u=X$>ouybsiB2f@_MW`m$lGr`=wojR$OkLTRAyB8WPUn}@E09;-h-FX4=)u4=|GdY zC<;DX3-=_hQcuEltVR~wStTkETbGA$5HNB8_(H=oX1TVEm zzuWR8kA|kE>&>@+fp2whx7~t3DGUNqKrUtVT5qo?f9C=X$wR2^s9M!Id4W?`3c59} zH2%mth{&rHaV}q)0y?Pn+C)lbQ^PFgXr`zAuSTF8+m(cWeN-**3+I3fBM%x7Yc%W* zQ240qJ_L)$)J-|K^$%Ad#HWl}1Flt=_9K^${&9S%`~I+}O|zNSyrgcJ@{_r2(AQAy zp_WTnGWk}~o-^kYC*Zg%1j5n?F2K%COajlaUzpe%1cKlxFthBUK}tz17{Yc9OiCY$ zC=~r#8!6>PO8N4!W;#k&GV-wi?IC}u=~F9ezyZwe!DTHKOzX3Hruh3oE#2O=88FLE22um+BZ~_UgD0)5biT;l z7J+fh(B=pm{U?+Oc?O@Fo0}=x_CrO7D7e)tIz*dr`Y22CPasj)@Q`Z!AUP^=6DX}} zQ~+nhrEfa)1T|^RLQjb?%j@HsJM3opq`gA_dK1S(h|*%IM~>Z zmFb;h^)jjJUW9j^+m#QUg0mbEQtNT}zh#4G(*aJ;sS((%SE03O#K@B+h3SOQ0eaxe zOAP*X4j_sP<7~AFIZBSQ<^H0^c%_LmyMR70xO^lNK6jUr!(wrnVZU>H(8-mc_NNeD z#Pi!4a5Pz(kS2GZO|EhHBvOF&~Z;=%;7;&))G-bdLCVarp?|;Hdv0ZR+HJjohDxx^$F2iQXD2>lQmO*B@yGV zuBphu#C78bhD>@cXErSF_XxhWa1N-RI^S;as}Wc#?n?8H0P1>i#=`#L0>PgPn@JxR zMmf;2@w93`CUK;=e$n{`zmv*JEHCu`?80g+ZO(WX!6TKOJO95u9~1PB-+^5iNt8>Mh)@tD%8(*{ophQdN#~ z9b-B(;uMhA0IvYRJzySG!CgB6vjp1jd19delw;xDtPp8Qx`6Y<0X(p;x*L3;2R9Fh zqrHo;LmO_VIT3DgT14j5kF){Vi0t7_kIVS?S>dvQH=sEXdV8D#0oVYWM9YlB=ImcU z`8+-WHaoYo_`kvWJ!}$Cw?Iv6;lA{*P?c{+WiP9~rGn9p<#08N4Vs+!1%Y?Gd$TEM zEVcX=kd$zwANZO;R*p(*-s}$8EP&tSMiWcp$2kJ3^Hw%{`Cda1L*D(vgElK3f}Y0K z^D|-MuWKeo#%1+VZEfEXb%p%^>$G6C-n9N?&?aETk#biAp7jl@q3ufz;}7h%c)5C* zecN(xVZfUBGy01w{2H(jh1Xn^Ii~Eg;o0&??yAUYjX$TJ-3)V5B6#^#(q-j28^)ee zn3vrqkQjep?0$Rw2Y~(VJbYpOfUSRksim{BLXUr@oNH-fBJ!&*T{As$7jWi|#uWd^ zrgb9bA%4Gh14TQnlXEKBPQ~YvZAgmzij1NYfNQ^g1#36rN`c6}XwZk6#Vi4R=+JfMM2&dM>{EeKBKgAWX#Vqk&f-c4oQKIL-5i zfB#-**S?)PZ43octNT`89N@R$3b)cq}eU-gQJF^Je+Y^jx-{JNjIIoJwse^jH5g0UOpnjvA|y-VbW8#h0HwbQWiEVm~o zx;i=Rz-&_a9(jW-uwJE=jMt;%O~dHxRUd_PP0NuONLzSLcjB#}-w^X1T)!HoG|Ks@ zO*Ffhx&e~9udOPXCMPB!nJ5%`wI1RZYgO>eUoS4uM&JKN=){ci&2%)}L-de-?0-)~ zhfO!0q}7Nws|PGb`ow1Np|z(S3m?fbKQobYay@4xoiVpuZt=U+@S7e~G?F8-;;ls~ z+xEP6K?YT^CEsu`83cleWpKkkJUn1K#6M@IkSo&N)HyO!Hyeb#^2_4dvRmhlQ_<`) zQqQ5@&r{?2+w4`0T@X>c2QxMijQv9eN1gC*55jUs->|HMAf3u(&fF{(*ZOn<^KFh0nazz`qU*R2}MM<5WcK~)BYhu zBdW$$Qf=^NeQAX7eb0dI+E0Hy9K_Vo;cR_=W)*RGR0*zovumKzUS}V z-M#ZQbWFI6Oe3a(@Rjl?aUJjbekVg_Y5 zHL0iBmo3MJY*%pshE9yvbqaQ=zP`RUQen*h70|o0Ou9$~&~&2ceHF6KX7juI!u+$x ztg#NXE`fkX|F-=;@L@zLz{St+ERK_s{r%iDA@eyXoh5$_`6vh;K!O0MvgoR^9q$n4 zHuT5V(##NEX%Ijxab3!P@g7wua~=dwKeM&AzJS>^AwK?fp!)&m1}$_$9fAIAXd+Xd z%3fFMvxmn5b-4fd)#c?SXj-42p8-btoWrxSwiec1VyN$U#=^VH%4;&@rF5o*ehzZJ zPEKqMYQZypJBB+ay(r9PZychKH{M@S%bO{mleO{-Ujz+;LaK#VI{s{=8${H1jG`)! zU}KHhlFA#I<^1Xg%*r1padB|~k_4Bp#Ie?LS0f>sQhDlkI=ol7o^}uQ)#(?T7RJJH@xf^W%EOgk^(YiznVHClE25cuftaP%29b zwj~8j9vC0m$tYcGSk2AMLNyNCPvQ`E@c49mHui7`^Qk(*ocaD$`~v$B(3(3FI3}QK z(U48-z#U)9=W8VMB!O3s&b zqxButvFH80KGq6ELUHp)+k^i{I3)B;8PqM5o9^DFw47SDY{VZz8@7#F%ae%K%ZK?^4ajYa@y{$_a`UmAs#CIq z0#xr+-x3?zZE8vkv>^lbo_)+KM8BtQy>~U3oOGomAx9%}PT2|%f;wo3j&xqL48TRt zm?SwuZ7uqpco0EP5=%e%3tN4RyCCyp*?4w{sscxx))(pMkHyP%u41>XcJ}fC>X)An zB1g=ysDm_1iWB9c@}FkeS`>32#L`FI3D86l}jNn6qsMOk-0pwufZ|Z>U6(leOpS>#OH5{nZo&5&1|sTI#eC(E`nOZXB=C_wCicFk^>cP~rCQ zh&n*!Vac$$_9TwDADdN*$IyCM*XMj*<(r@hc5@CG4x?*|zTgx@0tRH->B1)0I}h3+ z#bejh{zi%9dUyL?ZZ)qKUcga}jn@->sqbct(-%z^qC3}k%D&pin-CTrLV*`_33D~H z0*-#Qw4|Tuh5*d~pm?O4XO)uCJ~MXV^b?BJqe8Z`GD=nPt^ETT5br5jU9T&$$&5E? zbQrTkSVau+6)Cb?$Uq^Q$`b%C9JL%o;mS?W%JTV1^_@7`>3H`ClMe1J_wq`O&XzwV ze_s!BQ*eCj);L(xXK@ndp;jYkL1iMmZ>b7bFY*4){~O`6NaY%axG>N6yVYkM6>i+c z<0D3m%0z-Su+9LPtBegUb4)Gobf(2Ql=Fu4c`2_gOk)ob?S3i>j1F+Lav7l`zF{#o+|_JLkUU^s<} za?U=!{XlyB7Q#2oFXgDd`q26JC;P93ih|Q~mAJLin);?Da+-#CR2boDLRV6jbJb?Mg7G#G^umjL3Wcbsh2@O?AxC^b&ts>m)*qhNzgYHa1K0@KSCng%y~+ z!6Ee}FVt`j&jYC}{X;Ht9zE1jiZ@_4^?fq{)yZzg3sQC`2U#Q*p9E|V3}gb=W# z{*%-K3W6T8MDx)Xmlzf}f^T6Z0cgHT-PyjD0T!~rwW`WlraLaKXxF$um8@@3UJVPf z74edbGfg_UC*E}BiKuF!#7IS-;*TiX4$(<%4gN{oaSEe4#Anu$mJh0>^p4;-dpXhmoFM9|o>(50>t%%O%2Nv3a1Hfz-!z zH|<<-AEO0hd=67AXD~h1E9{w0W=GEfRGpkk>0Eir-luP#)y(7z@50Rs?whJAD4a2q-f1z_fyDY z?gJ`O4fNzR%3h6hf+8ht%w|6{*n9yq3 zJgUsPEH7ExYFXG3kjl&+WtFq-s~?G&j|* zks7qKTMk>UWmr)Wi6z#e-q=Q)2k1>Y?KtbcPukhn8!t=$!@I9a>TtJ&jhw#$KKgp; z9qklByKSO2uRP=%jN6hFP@nsrVt(9qm2H-|{Bh8x?HzHyF-Az1+$lOsd}ly4jD4j% zV|sf*r+OPmF6VRY^Jis4)cg+3Bn)yQyzSd3d3kJRtAGH(%)z93L>~9V@V}}IJukD3IsgGAjPtWXxybtVsfCGl}p2OssDnfYQsez4I zAv~c(J398#uxXU|^gJ#wE8^z<6t`5QA1}v-_qz^60=u#TRT^*|1ZWTm^@^(7GBNO8 z_44A*l*jO#x|iy!?a5H({Epn$5%?x(&F4XV{NgOjp}3X-NBs{!vKylme|%V7)RPXg z)tzW+#JsVo33|^TAPxZeo;SGxt91IZI87W``pbCNKa+fUAWo{~vMgRcS5RB17}u{z zdgiFYm#rIcP)mqeTJsZ}SlDNWdk5V-(faJ9THcVI<4A;e2ouo2#Y*s31v?;06$6 zQNA>-&fQS=VJ|mToOBN0wYVV;GvJU0YOI47pX63xEMK!c;!N8mAg;pQl0FOer9hf> zF+ko=(h4J>?xL%_s1ypu(AM0l{5CVWCsd;!{PbQFGznsb0A!a^gd?#NXxcI(}uZi>Yl( z?urZ4saqg_`jn!s`|7l#cAOLTPhkCf=QF}ooFk%llppD%db?AVOsn_UN+P!)=It)6 z>=_{QQrjz+dt*~=y}NSj;J4w);Rt)G6CT6$nwy&X6pBCpXZx0VrHesz1&57;lO_gEeiFxC z6_p)eF!5ltMJMo`A*$*BT!2(l8i`Y;exoE@Fk(bS;hOt!8wEU;k|k!W&8ktrd_&Kt z9J6+c8%;Df0q$wQuJM_VTPabjmQ?U;i656o=1s@!$ZKP|)8&!N*DHi%5r+-k zVW?nt5iv0;2N5S;%WJl#FsymH&5)DlVGj2y;1gvXjewv3T+g8jcL%`TmWd!Z1hg;{ z&nzZr{WKmpw!`xTESQJvQ7i@m)*%zRo?}3+mDOm9gZ-gVVAblQp=JhjeHP zv|Xf+|8kuBT3TBA`wQ%Tn`b4ey^B@*kW4lm%a~zMi^tAb*jxd#sWN_&!psJ@tWNe5 z)Pot`DyN?naaw#zN(P@Rv&|h4QQ$R2Rb%JteN&*fh?f?CF0&JaG$?)^^|`1_EpIki ze9-hPA<15?I8x6-nv@=}RG+O(RnIp=eeRL^p>FXQVa#oTL3gZ-zuo9OHm4q}Rc9yy zAqGH^xDtn-Ri9-z@CO$ub|=5egaAZNwHPpBHZ6kw01b9s;ESD3rX`1^m6;iNElnfq zY2mCR-^-bm5FenYFE4w8ngm*-0lJk(aB^<0tf>B#9UeS!l3vl{{dbp*vm?l=?1Xl~ z(1wAH^`w7~ZNE|oF&&GsMHAPGU7)-UWg#|Y!1)Xq6;@Mu7IZ}3fm9=52-p#&Eeg88 zrtuZXf#=pk@=PCNwj7`K|Y6U< zDpslh7<*u4B>Rie9csOfmPR8{K2C%73$!Y6weNQ(7l&brq92m7u<_+2B80Ph2l!q? zm45lxDNI(Wz`mq3iwM+Y(3sF?daeEmo&jc()73GbVYN)r!f3)DvRr|>DAFwBX5;z! z2Pal<>on}o`Df?@GFJt6DAffmPojM1fPg&vn1s?PZGIBphQ5LKqhmnx2|f^AfI~&Q za6BTc=R(vA0D=APZ@=dnDbp~vR+K*=kc^yi`?_}x6fVRT1|j5iyd9%YsTc0`|N^Il)){I&y-nNx`#vT zR@QOJCwH+Xui}EjFBPo7u5A-?pKEo_%$8+Qd#e!v&xSIAyil!9PI=@-dVz3NTd_KG z+8{Ow##P5$K_W>jSs1VL-FyX*hlS(0L7$di&qv?0o}oI`2~3CfDG0w6_3!SQoj=-M zx1_t$qp}^eNDu)WMzWK}>%Z+9L{u5RzoBi=2qr=4Q+6KNz_{I{yrsuKR+m|683^U5D-K;;|O`T62{XuOJ~~7bd_FGqh8L7550! zsINNx{xdNbW$qx{&e*VO6a^H!??CRcrAy8-Gg%u)v&ob8&2>p(FX_hCLVi&v!J5a) zpz+VfZHf}qLX=A4s;7sCy|qbtu&mpy!sM*-LRcz5`{$2WJV&5?J%4`Hv=&wLYvpep z8&qY=5G$PfEBhx5Q;QAN$nO$1XCB#2nc$Bgdu$++aNQNHER}lQAZ~1LV`9IDpoFD+ zFzm=ZGwQ)vou&c}#O=jFaqHt>p#56hL7&}`slg*mWHb7NEWZEzkYPp0*M#2|dPetX zV{5N!WJc~d3rKFdQDIA#R#tD!;0iC?421@z~hkuBJ?DgmPiWn;4{9#VSk*n>(0AzPqc?rb(3R#-gvep z^&aHF5i9lgGmYxih+)0WvW`wUVp;Hwa@l(tSwk5mPzSuqK`_awCZM~|uwTC#_lI(2 zkT?60?URX%*H$7N@%!u@J~!uTf#4bpL&pRM00lK zVgGb)gU21DKK*Ce3ABsj1-BE|{%V|!V9c*OQtO*Az+7^c{pO4;OsjFMKbHe0+T?P>`@h2nE z)8KhbqLU~g0fE~h25Tf}c6N3UXpiQz!Ve+%Twob`H9%NVhhQtSYWIw1fz;ayB?cT) zK=&e2>hBf9i?eHwInHL+qO`&@$a5*!B7@ZDw*|mez_=eDvP3?4(xxVtkE?-$Kl}mk zTRVmQGZH~sR4D?t#-%>cZ6+z!ElfxyoROyS)8=b`5lA&dTV_Ni%7#1RTE84eo>ZTI z=*JtJ@ih?xOv+CV)GOJG)bCoppKr@L>O~7m&lOhqFPR*A&rpM)v{FA>_{~nw&w!pw zb5T`gXvS`ZGq z@B8p}Lyd1zoq(wBuWb3sKGRoe7thi0F)cFxDP}5APOWXJywW@n2IlVZteci25k6J` zpOKZPgjYy*H3iyqLVT>UE?#W@MGlX((!Pc1H_HgiqwEFFD6|ItKr zV0=8*McM#L0bS<8w*)HH4PrOuyG+?^i_^7@!N7UOqX~irYn6+QMwjKHanU;11<=0y zr@81_*71@g4?TNVHW3FGghTfS|$T zJL9)7E~faHGJ6#$HdU*e?1Tl?-1&?$u$BNF<=k7|^Nc!warUg5wOlG<`hQ&}4Z$kU zv%P~YK=$7)K#=$VE!Sqi zjB0V`h*V~|45pr@!hq=*iV^7E<l+P|Pyf;|qXK%l$;L^ZJq#)|A!0*)HTEHRT56f{eN(Ulbf zz+`##bqiP_1hxVDdwUeR%~z7lproir0$$had6;nedWy#__`m!gei>#W!)0Eq%zhBJ z?YryUl-akESjQjbtL(bpjsjC;ozhK2P7X0$4~Vc4F&e3(xlp0d1qPL0KzBOa?~eH) z#OD=QnEp461I9M^Yk_|;VXonOtxn&k)H9K!L|2XabEobk{mr^c@{126!49v0I2!YI zELzu!Ri}i@LAx~U=6t&dR|DdA9333^`T~Sa6PH=WbR2}rXo#{EXiD!28@$+MJNETt zBEWzGRFzg*IkpOU5YUW%ayu5)VefC?wz;V(^^e-{%r*yS!NUPRc-pcE%PLBm=NkyP z{(KjB-rLy18c>M^3T1XcGyca>F258e-6-Zsyi0$j#|6L(pO2r`dd%2V?39$i<1K~>d=+tj|I|xvZm=EMMe4WmCr=rk z6m<|D{_SOXx}=*f^rjm&;EBWQ#v0=^c=#$e1M z?P)_CZmC}Td8`Q_vEcgyNDr8tGOG!XEK~0QgiT8Owq3g>UV8x;B?BEcG9Ro{vgTSL zvQ6^pQKb~ihD4~djFJwj5VB3Oy{|}+h(e$ASb5#0#`1A2;-M>NIH^LA@JvajrhTNc z@4$KXOl1Nz0%LF#0t#j#O7%-u+uNvTxLt9o$A>9T%8{%9!asFptQ`juq%@YisN45As|g z4n3M_5r=2lJb^xj@L z5Y5qea_g$ME6-6$^-j?CDw}#bp^M-`HrJ?T>B$Lv(WdHv;%7v|{le&bAGspQo9n@+ zq0$%ohc^RGVfxYM#S}Ge=BbiHamM_fCP@}`aB4sQN443#b!fA@s8}F9KLIEQfT|5T z!RUNN#`daem<&)AZUJm^I?NbSLi5AT%?+d%XIC2~3;H&rVkdR(yu9uRzZP*bSx4{c zv9l4xVo}|kD#KR>ArlsFZmt5`U_hI)6o^gRLFHIj9OEMHKnyK+`rPC(5Fl0_A41dy z*}g^l*~F4T=OYgkU+|ZAPlmeXsQKQQraqRI@D1Y2fY5@+!^X`mjluApals{dScs2r zhQpq5tfo0TJ2#htMx7R6;?6Uyo&ZirU9dZ54f_+1GBDM>FsCS4d8n5dlycLxDz6fm zq6Y$odEkK*?d$^-42y>Tr!U+h3n;@TwM9jgu0_^Iqx$4*pbZ|c>&oqlXD>~Y@1 zQ&10me0_cWzWW}wuOrq%|FgmXAW;^d$)!Q*Db$1h`?HKCyPKk1Lira_(~&KY6X4P< z7oI|Dqe7(7c9dvQf-Hkk!&`yb8dAg=3Oq9-VQuXS{oPzrj+xpRkcB0O3+U-2mncoI zUBk6vSmB^dx`EfRzo}{eQ#Go6_9t3(^Q*!9i@odi-WDDmcB~%N7^KLhW1JYXExyd! zAF*6kY$=^^R?!r;q|b;-mF>@98rTafZ4jO*I>I9IM$sX!otz2N?!7K^F?B4mc;4jt ztp9BjY@NDaP94Gh1o4Rv(q0RanHnBPVt5SseHuZL^&h&){Z~MBvTFgoeGyI$vfCU@ z)xlF^D;n~{92x8HMBf0p-_NWZ7Ut%#nYDc(6_$scM-mB){C{&!pW|1-pqIcU$HU7` zCqRxT`@Z&L4UOX^a4P`R*B-Z>KgQn-at=m>tOve(m8nuNqGrTYOc){z>I6U?ezAc5 zH#}OVR@{v_`I;YaCk!2P8+VxS=186#WbrG9w)(W@Q`?OL|*1ayJ8<{DG`#6Sn!mM{%2`@RhxqeTl zKS2JYq6ryA^Fi&}U^2YuG%^#rOdXjEN_()SD#+Ev$IEtD( zHb%VNI=-cT=&5~ANEWNEgz>n5=E!XJ0*}ggXPn;W zM18lOfMz~GK*V&+Nw&5Gn(s>ZxYstZOm|CUp`XsVGN*T?%nvr!nF%Q7eBTrB@{-&+ zB54PRCCm7;Xwr1p-|^obhHs@p>n(?i}72}CNa%Oj~rO%CfzYSeDrudIk5xYk$Bg@R({^^xuWF)P@fkTQqRzJ%j+xI zP;rG*L{i}`Y^*kce*xg#JU;SWjp$GqaKiU96B7|pk^K7zmOo?>;P;pv6BLYGDo1*P zqXM*ykVHT)-@^t2nQx!TiD+C(|HaFTVUQ18Ebq+UOe?7F)Z)st;EfX`QoaMrJ*vni zFv*)#&2RMQ=H{-qx!Z!~)zR^TBPTca9gwyFu$fWOB->BT6Z>KCzX9jpKP+d^T>|4H z*mGf>p+GI=gH zUfTT^vlTtAd01;+YGEC-#juRhL?Aas9L6C+eMMq&{;o6>Ch(O-a!*UuM2Y&e#SB(7 z35)Mi+HL=Wm`<)>C=WN=_SlPa!>*+8=!dw=dwbpoega~@QM}pSFrR5*wyk9Pl@#NN z{L^1jPxv&pf@MP$s&$oH6j)LEuC0DsfC~NjXgJw2vPK)>(<8*Zw?t15@M`# zz&chW5PJsQ;4Z!sJ$Qt4B@d_{BmADSn=4ZG`wl9p@f#xuVT6nD?a+12 zIqFZ;t^5>}k$Hx{%%DdP2ZPc)ukc;?)P@v8jUrT=$Gv0eizei;y?V~43vAJg?w22L zVETOH_P^rpew?o*P@C6_+x_v5=VWRD-jcZ^dv6o$(UilqE&$9N|O$`{jdayV5-i;3D!3keou`5*sa4tehu zLkuBDb)=|q7)hBX<0G8Q3<-*?I^Frsfd4WZ+JwxV-RrojZK7$le||~hps&%qu2K2f zU4Z{N_1Y}KZ93i6$ESMSM0#tj!{ef_k<2K|-%|MPW#jE-b(N@+V8;NOGg~Hib=6Q0 zTFf*6!W3hgdR+IT!#~i@Q0)R(($&Mm!`a#R(NT5yteaQIh|RCucvO~(3N8<+83twa z0ED0vO)M{Gj1KU8{qhgUuA4?6_!lgkomJSeJ*={o$Yy4$@4)(AVGnq+|N0A-FrO)F zzpVxbI)Ir6pw5H+Vd#UZz&SG>v)tx6Bg5B;!+CTSq`t8&gVpfLN>JZ%@^s=(Z6U5_ ztrM*v<>fP^Hn9_3>N4AB%IHm|H?>P;&UZ3n2(NY@2~C;G2~46XnnpZoJRvabU@ z3B<0>&gAJ%m@K9AbKr$nHX3m;v?)aGA9Mz3)hfx(Va2sJgl}i<|EvrN?g{l~;!U1< zY2)JJ23>{nYI_;yM28~EAxC;V=X-bzs_F5SsvuZ!xx#LE2dW4--U++>wIEjCv*uL$ zK3O`igOZQg`+H)-`NC%dkRmQt$mZ5%6GgZ_@fpToR2*-hE;Y?(dq=9w{DBo#?0(Gu zg7SwGZTf1H>?fZkfCV{cBWyFis{6LEi1w)Pp0#b`sKt+%V)|%kcUMLE`1-CbCRk%h z?4fHAC%2r$h z+H%X;=bD&(e{gAa7VCX9$+zv>sjEDNIktLeV&Yiu<^Q?f?v*om)va}Rl*hQ~va|Ag zE`dm+N+?N%lauZoYv$zbM}Zcp8h+M;al;i)t&`7N#D2H}!5tL>eq&#{Cg->4gLD{s zV0&U=u?H5zhl~+aSiY9;jw{u$-8_;6MjM*O>dR7SB%-fu; zh_2-d8@NH5F8BHU^Dg9{uLwG^NZ^}w-1Rm;TUhG;7cljYUT&vAn$H%UQl`RwF?9q~ zO5(M|C752BrWuk3WY069o$s8piZvAI5y5IsI*TUCtK;a62*fzwhMQa%=GiP+(%Z`3 z2InKF03rDU3ky(lftRKDCEHw&-%aKY{Osk>xksvdAflLy{ z?-ehZ@a_ZlYK3b$$p1buGPJ}B@Bj^&8iP1A-%5kf8-6p!&=)RDS9|>t$k2Nl}4d%YV6N}5ri`xpyz1;J` z1;YKwCPm{X=l7nkLqtMURj1rID~|?WClFJ`r`c?Kf#qGP`*pSjC z5jM{YhqRk$@XGIqDCp23(~Uxo>(1g~a9Iw>_Ne`atrayxb|@F=Ju7~1P$rJ#ma8?f z0h?j5yji~X3lDL@w_-7?3PGf4jJl9umT3yWa=W}P-u!a4+rVV+#{NFd0kd6_>U2P| z$ZA^^<%8p>sZ{Kht|IGo6h!qv9mB)tiFCsVk&7wC*t_U@rW{S?@k(uxeSt_#o7J|s%0KGL1NUX9<4J6;{#{eyvA(v{3|Dwf!8`?=|XXJb#UJoZQngk%_zs*gEdf;NQYNUfU0)sA! zLi%tpO?mnP-pf+dhCH{fsdgrFDmBN;^K&QAC^kxg9c zT>{Y8!^m+YjcnOqztu6Rs(r}bUQ$@v$P@k&&#V!{L{|SP9Tt}SpFeOZsu=r_xN<#r zM9OL24Tk?ej@^R}u395=}KRp9r1h2CY7m5 zHQU&30?3l)w!^{1-X2X)n{!~%i3)T48SQ0$k^zaTZVa|bcFJnD-d#TV^gRQ_1W31j zeSHO2oj~R>%(D)GRBi%C0YZs9y%=ejOnzyulBj6`MuMH)5~K9E1g-2xVPVp@kqKK+ z&Q5$d-s)pVzNF-;uuoebsB*=%zRygBqmKE$v{9Y?Cy8a7vWSYO`1akOET!#n*32m# z`4VkCTDDKqyeVJ($PHX`;K#iwbA@HjA5^N3-aZrUeu%7$UM;Vi1ooDsL@*B@+g9J+ zuIe=>=sWyQ3OiZc^UfcZLUd{6{)VU&dRNMGqv9_-f$%B{_PykDwu7;+4?e_*t7=Bq zbiE|D2KQ;_J|1d0FgH_9Qqd{JQhbIP%o!FR%e)C;H-{r!N1sHBJf1~@?{hcNFs&&k zVFWVd8Vi6<6`VnT4-dR~x;)8RQ*cW=l1ZuZ#ieklA23&$1Ezq@h>;!1=Xg~QAro8M zUt}~%!%4#lsH5DSZGd?w;QNSe7HCI)zop4!__9el*QHJmqZjZe@gm5Qo|TcyTk=rC z8!0}4O?WK)XAFG+^6vnh3pfY~`f|`n?C0&RrZg|OsqF{J$ykb85(!8m;Iyd5nk9YP zfs!^=H}2!+|Ih-20Ey)#a4IZ{r{#Ve6v;9grP%`>`}Ar*(IPfK{H>9z4P*jK0Ef~7 znIMKtWBU0DY3lqPZ>-Y8drmbXw{4$F25EbFQ7H?_E@O-IbG&6~OjV%|G*%7m)Qn0o zktN@`d6*8Gf;1kN?c!|&$jET50<;3LyYO76>d4C#>Grj8<^7HA4)EGP0HMDa6^=F5 zR_24TT+wyIBl%EMiEzeFG*}M*DW1@ zyb{19x;jVf0t6MCpR;SJ_S>S=Dx01A&!K|Vowq9h4l|=C#~!D*MQH&<=`G$4rOELT zbTnv=f8T#@#Vaxvb;=))p$k9Pb#<{wzZ0J;In!_3d&R1GFDS8Mv6sniDi|Z3yzaD) z#?TbLmda7+&uvSAeFOY#fzHrsv~4}P@xa_m`c}e$2*_Y!^pje}GJnnU6{7CA{tMk} zQyGrNd&n&;*KYghYX0jqzj0qmclXyXc{h~CU{V1O|V8D!!ogpCM*RNmas&{w4K`D8gb`MT3L6swSYJ0t!Ji`}7as zaf*XDh0$%VD5r5zX8C5qjNDcU<*XvEmWocFtc!AFR5;9ZApLAe z9LM{vQ&8aw9xGc;@6%8YkL*aMvT!jI5#`|#3}jXk9{!+VHR8v$cMw6>R9yJ3D{t>m z`mI8mKTjESc#uO?bdJ6&2<9l4_)f6!VaaNhD^zRNLL%T^c>#Ypd=}G#vI^-IJlW3H z)_dTODuIc?#Cf6F0R)gT4jL7$)2cI&ntYG*%{w3kaJEkh+l6h-z5N&VO!-9F``Oa2 zZP-BaOu}6un8lSYvubcQtM(lQ3X|@xMg2m2dE=BhuvQ1BVll(Q%GCZ4574?Jo+)Ok z!xKrv4w5N-%;x@ZiGTnj1wmQW^D9HJLmgN4(_Tg5P{nL#BBHvXi)DNd?_53w;mLia z?&laOhp?z`m!$(I!Y{ldTu$(Q?;o(7QlG!P!wVcUDEp3>h}VK^fjm<}n3>DNQwW)$ z=E96vanQTGwidHFrQDdAv=yL3n5HpFHLGENeDl~i6M=A|8$2kFb%XU?% zva{=JAOiXI5Y`U6Ol8YGnd(i*%-R}XXVZbHi)rtD|YBEDD|*l|*!~!dTa580=Jv z4*&oLlxn@L%j@eka;eh8{HC}72PmuN`1p|=)BP)vN~$YpLjC>yy}kcv0ma`rLJWT~ zTYi62L?<88%?H3c`DEenNfujCNlD1#+{nS<48S=c741I&&n)T}t3p}EBXAE^I0TwO zppMmZd$1p1d^Pv<#D9m`xC0V!rSwM+1{)b`%(ZK#D}tI>ZKh>KHJ1BJsIrmD977gKqiUjkh_=cmSvw05U;g z@BsQW;1q8fk7DR%$0bo==kAV!G7RC@gz#YcAZ5ydR8bUDmYn<@x`VF-7}c;AdG(}F z01Jb77PT`#!x9&SrYNsCm+pTRMG&eyoSVZAfz|WA+Ee_F;rE~Mg=dJelIR);QOf#z z%o9ZVt06QPt@ed1xgd5swj}c!WLXmAtwkM~fv+as(3$Kj83B-mn6Rp4yd0EblN9Ty z_(v9gGdKbK4*tpQq1BUeKr^EZrnU55{2AC6gwzp`c@BnDn) zPDU?sL&?;IC>$XYf43Mx@s0}dDb&1br)&`Pf6d--^w3#LVD-wC;g*BI5C8eTA~lr~ zuBJd~li(^^Xw@JuH+Mnj!IZOez-JWayB?4EQd)FiwTV#R#jzXx?BDJ(E-oOvU?cLo$ZU3 zq2Xa*v)n1Os;z>*8>r!Eey=wuSuiLa^=0C9A!gXQN29XA<31drHyPXSI*gZOi?uga zNZN7;IOTclmeZOMwcfl{-6KOs>a4|T#+7W-psMMTv}fj9Ch<&nEh(iXM3yPqzyFSA z`DjFqLAL+F6pDZMyn%+lA2s;XG7UENhmt6RQ8S6NK+RkJ>k5OK^5pz9-9tyc)B>!GAhD$Pf_ zC-a8^5*wRhd`(4wX$L;yUzG3u1xfW+7<;-W}u zee(9yP1va$a91^*HMBk5+;%x=epLp_ZxcJC(+{Pgm5FGQSJW$YH+7!{Deq-vX7ULL zgt&XjSg5EjR#V^nNsmYn4n7*HX>uV>r&>3oU&u(s&}pNK++N&Wul^2wGI@)Lw9<*( zB45|pc!a;&J0r$T{aL3`KC69Hi=F@*>pfOS{{YkCU z&X3in0|Ntq?V6HMO*4F~z*dF|I>f9f>xPDgLh1o5Fb3bJ0_qA#WrW&=Lg3OfWKanC z3%m;e8^rt?ARFb0?$apgS6g0Z)pa-1o!cnDm~EDN4npH^$HFfU*YPgRDYHR6BxD4; z&jtoutaGS^7q#YzE52^q1tFvqKll^5^q^a=vs}d`xb@o(53R}8fSvk(O!L>o<)486 zeh80Ht81-8#(AqxS~E$&K|LToUko_n0qXey=nqzC0dwR0K#?*a#!L(@WmXj)t(17z zM!CYMJAOsYz+w^V@#X3}qyg5B_ciDnO$`m(G6(vVfs76DxpBB4FJwCF|JW9pM~olKZ<~jR%cUtduGnZ11<_w?|q?#Y~5dp!%>3FVr&&; z%Qtz;>{j3VTs8RLMepMR&Qg|+&PQ?PG?kT&4ad+@UAP=tFLw_QnSZ34?jQz3FWn;i z>(90}hCNDB#)bj@qGlN5IqV@c1pIF>b0p%`0h&&KC>CvBL;<|OMJoBilPsnIH%1)d zg?>d>h%rHg*D}Sz#55(u-f3mW+Q4o+OU|P!?U`f-Jl2}p+S;0%QzBOZE!F=X{jHa_ z>D7UIQr-ABz#%|J`#_jotoaWIYzSH!8aj3dM@N1~FR?0e{xB2-B`cf{7r9iCU(7~n zjeZ!xA*CinYv(-JQ;H4jLXX{msX@Uo^hdoIpkWDo=wOmv1yQd6BR|fHrPXl4oAu<$ zl#+sM#)VBVj+^0ia(=c2oel#qSv_$G}fmtqmFaM@(RxX@VI{)vlfv@`Y(d_RJ zs6CJIJ?@GOQPX%_IB27lrdn#S6UB1Ql7;H9S~mD0$>Gv!-2s^5m|JvOg%hP=i=*iV z(v*D+Pv4N{<+XW#wxl=}(n!MW{_P8O-3|ViU`HV61{Qq)N(Mz8EZ=T#0TB60bZT`k zb!3ou9A3i2`vRFkzdJBvoZp`~7x&Gknj26QH=auq$oiOd-q9Y^a%bt1L3&eg)!xmD z$!cLeUj!Z^OQx&xJzAXyL-)#F5Q6}6H}aVwQA7s)LFzPB=Vg^qGI}J(DPVW2-1V@kz4Dc%}<^%5_U;_VVC!ixW8$V7ssZnd^d+!Y6(|#henkS06 zBbNkN$Es)y^I?0*xe-vdRd(1#?$F39BsrRjT;E;U*Uq-WAp?W5xvH>F=_b|L2}12U z0h<}Qyih2a8j1OgH;LG~vfhm6)If7ILGfRNv8upVI(_t3yx#E4?$BRiY2>`RMv!g! zeQQ$&Ft%v*Ti9u#Q2XL4Jt%sA&%nS3f3(`vsHv%q4tV&+8dm48RXcZs0|wY* zSXfx#`%mO9MW;UcY_dA8NA!_OlNNO>V3g45aP*toB2B{sevA|@R(M7?gtpmiDCKTr zpi)H^LYdR-tSEbym<4i6dnoFle8VdaVK!gB!i@UMcfh>+kzTCt;$n0MHtOIFjy`w7 zRtQvAZ z_+6F_a0&{({Ff>L{7$E;q=xI5d)Sy$1BLqAyyiCR-@alS{agTSq|WZ{TI>t*&_T8T zOp^gwbP{Lp{pu=#X6^vLxHd^DJ99FAkkb!a?t^}0SPjR|B|m_n{3-dv1gYPBU?M^p z7A+><2XQQf0&0dVTQdvl(7uFMJq?X%Z3uA>Hx2^Sk_CC>PNS=+AenSxZoa>34pun- zT-34GK$py}{TvQ`^9(#pG5PuPCm4~T)DLJ=3sdb6TBwG52KJ6BV~}67-tGJm z?DmHQ;zLIWnQgdrmIWy+65*4O$8wlIVFJ~{=&k2*gLQr?`SYYw(~nd-H^1NaJR%a^ z7AX&&&y=uYF>t8UD##aa7Cbt1>jiNQ6g^>BTO<+`{7FZh_YGqRTtuK?KuVn2va?kx z!!1|;iDeaAuaOp-Jas&!$$hL~6*d`d8Ni-f4Os}cvC`o_WH?q2# zA`V%rG7_;H6nik&iZV21@K#c0;+w152#3zqWaHnI7*2oe2Y9CFiftY{KAtu5}EG$aJu^&i2(6T=?*7 zX-JJz1w~EH^Tf)&Na@~x^_|yya4$v57(5v5dBfV#J~j6y7r@lEN#1W_2f<{nOOD`O z<1&a!Prz5|QLAHD;$;c;w7wcoMPDVyU>JB@2vKTss%WD3%I}^5Kt_HPwJ)~TWN1?x{ z)(M*MA3yf-M7|tdpOo@<=1v_;NTQTAx^;PNAB81&g3R>SS3fKi%0BH;lJ$C^jAWju z`5hGAu4Z{g2!**l^IiAHe{A>n>K;8)HUuO~*|j4nM`97*Ip&WK4#Jm6t%erV*Bxc; zlVGh^=O-u8jBFhpKd}}}LN84y4ydNetI=?!Q&eY|3nC;JT4c+kzn zPkT~}c9TJ)cwxJ2xc$^Y!3qir9>_B?xMQi3F44OJC+bk_^KZ+ahoSPmfZ#T>1GV>^(*Oie5TKX*hw?zG$=Mtb|y0Rm}(hydZ; zDrJHu0%CWl6j1wtAKt4FD2iCoe#vZ;;rqT#22ApHKCX1llQz+}ozj=_76K*qGD9a5 zqyhqx--X(o?Cj9HNdIKEGgEb7j9-E~9zfsRsw{tL#X<4e|H~JeY#ixO15}N2GIIdB z0*KAx{R}HX;-TC7)YPi926B2wO?G5OI$^L8zvKNcMMPIOs+)J9?!Ryf`9_>JXW&jE zXh4uZn%77Lu^oPjX#FxkqLCWDucRLvI4^ao2xR{c=Ue@t`vopQAP@tkfl}|ne}_hE zW;lE1hW>nZ$}+;nS~iRGsM944W+*{MV!rnZ2TljU?#TB`2Q`DeTXUN_Wo1cL*CRkS zLA~=vbt$Ys@0+y%eo9OT?^&I~6&8SL1hGP>e)cL37t$y{8%;vPO@u^Xlf%0Z0%4uQ z8e{SJFwPz0A^zJZjun4L+drhlhWDN6bHbFXM|WL)w5vzIhZ>*Cas#{3 zllR8l>opfgEQK|kF&UrUiaX4me|nthJJ~Y2c$G*gAKj!Tdl^)q+pUW4y7<;9hN>V7 z2kg)t!RXO`Fxs3`A@?77uypzQJx*jt*E$=u;KV-#(hu|znh8i2y?^)htY{Yamr;%Z z@(MU%pkRZGK-BO1#v9;hYyjdKs9qpXG`vlWO{*pwm-YuFCkYe2H0wxnn}x6(+q}KtBmsU*1(gRGMQZ1tiPJtcVJ7EPg-M8PU|aoEua|B-{jMEJ zela)4n1kp*W~&ZaVvtJ;i?^^{DYe2T9IkkgJN7IBWxQ=MM?>ujDI2whj;Rc1BfSW# z4FAvL?J^$UcP{8f{=@jJYPCN-L?sJvGgX0U2C97u+!M@H7bp6%M&#X?Q>uFZbI{wI zYh*Fj3v-)w?FJLnd)+79Uflj+nfYhDF)pSRMu8z%1gt}p0H&9U zEVX2253bX4!k0Y(1KHV`gJNqv zP0k-F>7P7@H+)IGW6gyyT0ar2QBZB^aRGBea{-ARsq_;|*j@shF7imv_DH~wWUTZB zpm6Yeeb~pv9USWEQfB}jwP1CY^f%VZUOdd?NZe%Z;=;Mn-S%@b&9W%>dx&I8J#Fpq z9-o~dFhT%jh=Wmrfd8vrLS9-R<4-jurQpxoc}05#ydDhOdKe<_NoBE?&49=cIGMU9 zEE5rq`+RgUv#~(}4ZgRnZPhx9H0Ds*@EDXTmQ$qN1;9ZNlF(u204o6GJIKpq^vA#c zT3FC*iRz*C86c2b1Z#)7_V!=b*5BkGmFWWNm_vfn);c_0-Q81cYyGpK8`KcG5lJ{5 z`c6SoJaI8}T?4Qn{ZgMRAtnA_?L+r5)X@PY1vr_3{BCNYlksr{3O&|G7#7(bbo`G% zfEv$l$@Br&m%e3ka1b_|;w>f0O%qUwa2W9@ceYk*==I}jyuMS@qb(Z zie42@tjl*gahR!JPJSnM+2FRe|8A$2lE;|vkqXHH8xp%(Ku+$p)s!qJE47>9T}HS^ zD-zWkm(#pe&`OTNw1GDJPW5Sk;E%*{X*|~8A6?{k+xI+NJyQk2gj_Ga_rbzX0Vp9lUTiOtMngOT6%fel$OyqefKHE;@Pnt zb|Z+${8_N=7h*X3&SAadXLB=-AaP{fOM|lj%@l4+nfU{jeGrnD# z7vWp1Jj+$egvCZgaor(r6AU@5J-y8PiTO`_;?n=3b-p_>?U6k|(?4K!iL{>awrKmY z`wqnrE4bE*Tq%l(qu5`njsQyGf;G_?zkMd4Mlgf?raKg6W9BGP&PoRBT`+;qlM|~6 zby%+4ia{jboX@qjZ!8zu@&#}uVnhRKI6aS|2HsOWrUE(IgfW;eIydA+Tx(|IZkXYU zT6l0C)&Wy9qRtvrz(M+FS63HUP+T9XP22-kL6Zb%0WaD?HoN2No+GGeBN`Vgebyxi zHanN^{UR+=A)u)biZT-0}0~%z|Dw* z=)AiLj$n>{BZKc8@J#@=i{s-cCu%9OziG{h1i}%vnm->50lf#VLFZ)-F4b%lq~K^f zjI2wZDke%0a3S~KW+agNzOEYu!xGKx80&t-+ONJG6{n9F)mEhqF+n8h`_{hj)d?C?#e~R4GTmCRp zj5UTkYgHzCMWwO!raagGPB zOn&xgM@cmi&3&*|4yI!ZQ^uie(`PFJ$J?Rp?OP}zMd^EmBdUo-h`(r=n3#I#IpB`} zm_*Dh)`qcMyiX{6JJw$^?1VGmy2Tx__V>@Tz(+!_6q}R5S={sdL$?1j0r#=85Hhuf zo4je^4CXNNvZ9SJUA3C&c+*3~X!_GLIrgVD5rec4ofxD3S3S5+gBCydn2+m)6+s_W zXPs0^YfyK=*je{8I+##yWDoG9fq0}J%18JM=ebZp6HPPl|HZfBA&9v~74*K1MyUTC zCpT&ZF5SkE0N!Dy7WuEj2|Qu5v$0Z?cJ!$XCYZh^i0PU%>zO-F-RJamN;X^M zRJa9+B>}1FYaj?_VPPS&smED)rk5U?UaSb{$}jZ()8MCD>|_8&@BtJMiAGCNPS1d~ z!hd99Pd$!YbFjre&v+5!;lYzittVXK>xC)tEWU%O+*ubFSLG${gEV5(v(}HNx}~2Q zomaE3RoK@97#R9ub!HMVyrsx+ITg>_D+`NRt*e`xM5Kv@1sv><{Dp1Z2q;OEk{r{~C!YJ(LwHDOb`1$z(X8U@~w=xzh*k?<~=yY8X z9B;a=TL5<+*H=9d&dY}>R`+YZFf@H9Nu5=OwgqItRB#iOVECV6(FsCM4SGz#3iI)S z{DfXGU;u97Lq+AbyCC|<<~di!C&_e%^oOIWS_IC>Sn!sIBmC}K9$uP#H~=3@VI5qg z00L-gws86r-Xr>FO%J;}-wx}fypCL|fw=jC2Kf(%)K{H$k+LA-9YcbyGq=P0&DIQ| zdlgf7aw}l*L&j#L=7GC6cT}&g_nlnt=v&)il%EC@6J>Y5-mZOCEJ0mOC8?D=v+HXF z$J1{n-y6j3hm4NKPm2C;dBZzJYREO@dctt>FH2$1*Mg69$2KRyDvAA>Ux|I5jZm0a zIRBBwfB8#z1L6JdR{>@Hd__A(UVWLez% z7ohP3e(s>*v+x%kNQ^8+Ag73lpHxDUw85lwD;YGfeN)EJa~bAJ2Dv>h{Z+;J+atg=w@^h8Wa1n`cZOiIXb2Fy<)L?FtQI zpfV5c@A@8^qvOELkOP#Vnx^%^eRuCzV0t1cii`245t zsGjlTngw_9vweXo7yd1JS_u!e$cAmeh0_WYO8_BD2ZW8Az50BJT=Lf%dVAg|7vXyM zhDT0;sMoM73}`3`=65Y@Z!3S9T$sm*U$8dc!J`8nY3cq2*T` zkzhouI{fQMV?OSu{5v11O^`<~J^87Y19l@4VzGtf%s_UTy`9+o_szITM zh;2u`3;h?#%f8n>+Qj)R6|dd^XEG%0;;jDb1~X2I(w3Uo+@87GY{^S5aHXhe#;U2_ z8<1M+$xWiv*%~zaD-+htEJe`AGu2~6uevZ8yHMq$UXy(eftM`6*MJ+Bk=x{_Zb8jy zVBQL>gyfOP5TGLyCp0BGJ%Kh3G@KKC@yOiY;(q8TI^d{M&FZrDT3L$Z3j3p7I0n>H zey+;*)?&y~SMK>yg^ek-aHq`tzWlN*T8GF9DDS~8~bHmPc7B4P3tJXg!wTq1( zZc)HPk128$Jv=l7_>0~5+sHIuN8XJg&uz;cBb5^)k&+R*vZ^ptw~h2YLfU==n(|X_E@bKFHuE` z8kT{#8UOv8T}}zgB@%-|o+RYXbq1&E`#_&K=LB4&idK;&zpyay@#p4iy!pznht%et zB1I&lGQnAxq>Qeic^+oNEhOaU+;#JDL0iC4K}6Ro6sVVSX?=2NgxU|QnOHm{N5{B9+>p&YAeD0F8!!6p43#65+(d(T zc@O-xrM`J7{nM~)D{5_P(Frv*uqEveSRYK)7F& zReXdoed!fBBIQE3%)5O?FEKjaV~P2Wy>gOof-AcF^v9f{#8oSgbP(s$1vXy?GPhS9u$ zUIbB1NUX7qVNh z3tAv0^SM!JgFPnagzXZw|I$*sQz_8RZ7=d)rUc+Le4GE(ccr@bAMpc^BX*i{c@__9 z1!66tE-X#WX|)0;EW*!2sFP&i_GLtioL(aa4ITYE{q-afOU7?NWDx2y%Q}qTn&H-{ zV_9gLvYE)q%CZ$nNzJBlj-*vp$IPMSm0c4sh<-nS9d(rL<|gPnO0@aFt>qC8k4%$I zKC0U3ClX^(uOU-CvYam%x| ziIvLgwm>QtiQ#%LI1JgSN4*sv&Zh=}56BEB zXj%nc7$@n~?H5sC9b$|t@gttN9Rhxf3Ie~};N6;wq}Yuqz@etCJT|akf9&-n?5^7> z7vb4_QwnERAN)zMJvT3d9Xk`K7j?+u5&C%y+45x z83Y`eT>^k3Gm*><6Dd@m@R_e#O^$|N4)f>!=zxwY)@;DnpSbds^0xl|!XM7Cc_9pX zHEwW_bQGj3qOMlWB4mtF;d;lE4i@VZCOLB(AU$sn082Gd9+o100!-#Qm0;gN>mx2R zq6vuX@*M!%2T(j{;ca;aTtrrO30lv9G`Gr+Rz?6emJ_Hs=~T-bjB*C1aO zCJZ18Qp5lESA|F- z&dbc)E>5hrUFl-S-biyqw63 zsgsG}%J?GX15WE7kA8@k&sb$vz9AO?IlH;Ikugk)h-1aSzfYk_K5O5=Um|r0XgfeQ zzwzf!m5%OJscX4~eDEkPaLfkM!#YRzKhvc*4|IhiUrF_`5GLc?^$hwGA@IHYYMDyusjDkCRw8+=LJgAZ z1gCw%MNv_);`5XFe9_RM6wFl^Y9QE)cP&*LDs3RO?LYkI1v=>h9OX1(q!N)Q!-nUN zG+G9rYOqox;;pH)mqqS|!Zg0Lef^hP6Hf3R$dX~^Q-hF(E%SVV8zaL%wr}|KGqP1z zS^>MSp`uSSJe$2vg{8LrSVCir5A6HT;#^~#;unYm4|7`gZ*OOB9Sf{q<}pYJ+B4bt z?XXzX2utnWjTe}Ry9Yg<>_!LbC^*k5Wi<^cIByrymvTzb8%R!u8&;V*FP-}2W&RChLnlmbL9(ca&200U8a|Eyt)-Tkvy+1!GD1_@K`hy1P4A>9l*fUU*1SjJ_ z`++uEj78OjGs1!?au$3DGCk#>X)734V&W0TvBn$!Ak^)Tf8(Y?we!um~+z~ z$X{1?TfuLNQ$Qn_o7xOT`5&z^#n`@Z3MUq;n`dw7PLIhZ4{HVgpnE%(n58Ybqa7G1yP?`9kqI-5`i`NOwqgcQ;6Pmvn=)(jn4~AT1yrsx-bdQDx3y=L8a_t9i82TAH(%1P&0t4qa+$n8LHc5OaSkH$Sff_Ss zwy{t0d?xfwG&468CM|HY0uYq*`=RZo5^ijn#d&7Zs$RJC61^XWRdkq@Pw`W{T3~r? z)c9jb@zxobi+8v+gOW`=FI_K^OQTH9c>o=te5_pRr)7At4}{l8r@mndY2>VaK)VAX z8sZ^B?svk%wU{$Lz`UG&Lxa9x8LT}umBpNwMn5B9~zOwz--IMg2-Pi_L2vXwI(O6aSg{5=I^|B2KSmm=#Q4Dd0ZjM-A#t@D z;u=F)>YB4glg zK9mLa3a}On4;A{+4I0A?y!3)vratrJBh(MEyz>yDF!pZaWosCr^22VR{p`gqq-RA^ z`Gss3mRoD%%Y>sHes~ZsrW>Z_b2Y`&Asl|;#O2}-rHUL^e2=5899VAk#kv)o`)h z9m>jaJ9^O^sg@P!U82b!X)aeu?*%cs~rkQyE1;_1liLXxl2qWeLT7l!)8u4?%z7tKVl z<6WCj?qnV9@09Jn$B^8`*cQFc9qIxOmM;e{k6*yL(ZO+QdGmMJyYRx$`bf#zn4w|ml9OE8|2If7B$ zxc5UBCTE*8juDv&2FV)7K^E2^?2r9DsmpU`eNqx!g!jQ8_viaUaW^q;u6$2aR4GDtW+p^T)o(5A!jTo2 z=pWTFGA062Ec}zD9LzjawtoT~oL%yfZYE(rpW$!GJhW>9sWzsCZko1L(ei=%~(E8 zo1Gz4H**b?H-^FPeF$iQ<9LmSWV7xD9Q8XMZkON(Iw}9n>7vXlZbw zwQPvvqlPw5$Wj7bmfT=cnRx_I@Czj48sUmj6Ng#6$Nlstf~KL&*ngAzmYUXu)3V5@ zZ4|qD>&Ys?jls-m$`j!{6e^u9U5pl_V79vrq|KEBPGk#6%v?2SM;S2Ob$D`?coqJDpGWRCbll zg02_fXapWMfKyA1<*az8&O%=cFawra8+v6873)S)J%Q~lr+KtH06O_(5du-m|H-b0T}}5 zq9~D7Qi;)ku=T;v(86<;mTdaqsoUJ*IcpwIr>w_nUTP-#mgoB|5X`N0fM0DI36Pr> zz#|DEhvQPmTJr>XhR+#y=+_Va_Btk2}JYM|t{@(LSCCAS2SlTG;f#1pO zt&NLbdlcF`!_61j9&9->;uXN-hm zGdk0G!xhnNZEcZ|sN7^}UpZ7_|!G|5ZZTomwRH>Y93qN*)uPYSQ7U=Z_!#Y*j?_mAz4rlQiH#9?7&6^DP~&|#nXw`=7& z1lZgZga=Ur`tX@=)k$T}2i0fl>zkV;Wue;W7l&LhPKO`A?untGV*Kc%=}{?DTKV!N zO-P<4fPA1wN4J4~N1zy)+r4CUoq8W>6SqwN8Y0RWScOCojmdJwcWo#>2vs+a&{q+P zGW;SLaFn~}*0-lut9zIlZ(A=lG5-uSw>hE1N<#IY^QC1r_-6dfVe{44N00x^AyFg7 zXwCN>Wzh1<*H~ZkFcHjZ3vI}qJa^vWZnTA9D~@N@A$qDBG1R3QrDSmV4wfh>u|cE| ztp56ibNMN*=*zrOYMAc+vLr0XDovP=oCmCSu>YhwqV54s0?L4AFPtPr_Xoq(3}2(! z-$B#IZ|pzZ=b64Ck;n`gElx>?3ttTyuE1xN%a`}_^o;bR)2K-lEodRx7mcRiHHZs_b z*pMIxRY0=+f8LYKZ{KcoxJAGJyvWzAdhAMpD#w&L2f8_bFd{Y~tP}NECt}ZA zd<4G*{QXcT2r3Sq0+iA)R2OeN$7MEriUFlEeG>V9AcGhboX&8*)yy4hci^Xi$s~xS zS^hbt?zQ1)zpbediKXyT1Ujc$A!- zM_YWp1f2(4PCXzrZpKoxhAU|6JIZ#h=>F5ycMhm5SQcU8(%Z*-7pHSj0f3hX z>F9%Qy3OvmKtjrBy2?UuWkx@!0?hktdZ-7`+N^)ef08YE0DDb!$?)k|d&}4V0?+>f zlv}U)6w51g5q=ELl#WorwAS00vLM+)9DQRfE=G{ z*xb35=q?Xibr(;n#e2YY{{sN-pk~%sLBIAcsuVc;)QvzYy`RrFPk`P)T}+RL!Gshd z=+61fSQfbOj#ol_xTD6Ph%Ji&+e>SfX4nJ=$M=_I;8#aw1oq-So_BH(=tA#N0+@1P z6>fUt85v^7QX93>0xN@m@auhq_JAJl2qs%dcrGg}U%T5pz~Z?1raR_;rto0lac8*t zfD-O-DI@W7+Eo+b&qny*N%)j>SBClnn_n~=>3N6=rbTj_WJ;C148aSWR!N_h{cwN` z$EI+x1MK7QW30SsPtwzjfrQmpd6gQvJWez}Y+Ewc`f$t$eJ~cchQx4z;-Pj0U~yJ0 zf@+uF)2gZ|i=@xR*qGcCB_Q}T=IxJhKXj2|tQ20#?fDmO#azkIA-k}zjRUL$9aT)n z!}N95U~T|rZ+9SF2CT$GWo%pRXeD^=(44GH(8bE9RBr)o4;Y5}zx;X8k469Tx9Phu z5tzflTMpkv5Sb5Fx4<;EVn8G>vr|5x=U99F0<+WA)m4zOl^%KU*0CWM0SX*d^xJLt z;IemwyyR!BA`N3pb8Rl={x<}vAf~kgNptJ4%u1nAxw=4&eyZ$@e_qqoH#FGE#0?ZkvuUO#| zp}4D&DSX66$arX}bSO}N!DJ*pm37u?`e^yNbut*yoVdQA%d0!8fK+$`pIPg@Aqg*K z_g6yKqak;wIhcv+8rRVQF9FkkA)8q<_+p*?-agjD^R;!BtA~$T5W*mfeCP*#UUIE3n72fD{EE6E20DP%my8 z-AyF}FC*o$wnFtSeWZ{UhJ!WFli`BCw|<$|asm#$4U1byKD+T$Gslz0aJCJkeg*Zi zfY=MbyzB`4;hr5o0FF;FZX9Iv8>iZ3BAPM+Eq*a;t+d#_4|>J|>xXh@Kc1jUzt+&8 z7{oTf2}-GK%5K_o^Fz5L2<1i71T_N*rqi+CTx`O&uKV%4RpLCt(FyferTAl6)j>I- zEJ$iZZTVX;nh$6s0`ctyT!_`Br^t(Q-Eb|}2^5B-7$6E+Ust!X4n{#CU>iu|Cn@Npon;1P8?G`v#sgnbG1mGNeQ??BAl zFhtoVHy2k6z~$;UfiK1{$&7tKgJND4racix!DhY$tCWsIKma+~tYKzlvsF6Lafrc8 z$~=i3pyDM`vbjI%09a)@7|F(1j$%IiRI}9tbRgjN{?+ahUM9iJxOpxBcEM{xgu$O2 z64ppoBa}{n8G^j;V+8ksaQw7cVh9WxNsQU+OtAEy_Y9x+_V-IwYIWa_3gpx=wtQ-{ zj;2~%DZ{~inbaF#Fn0rBUQ2tsRjyQ^?m_@U^CXl8#DXH?ThvPix?!0*e$DU5!NJ&*5 z6@w`=a~NQ+aqVXM~BF%ZC$ju%WP>1756~1_YS+pnI8M0;hnx1 z#I7*oH+8@5NNcsIHs^QI zrFc?oGsCfylTIqKX~zQ?hUewvj1pi=ozPU&EkJ5n%?AvAjr5R&V3-Fa?N@1zpPxa} z2Mfb$cH@3<%z_1$XaIHAP&MPg!Tv#s!7{VSab-)nO4dyDZtj8K-ED#2-(LR-;mETj zl$)6yQCJmoEq04nogCRO(6k0`mOy>(#JxQbtqNH$yC7a(7Ws=Rdi>3fd!XjdMj&@~ zUcmJ-y{K_4-siAK4YM^A+7JwX%L=J=G?ipZSax8Gg1gv=Ku>d?2OnFDRJ@~|ZEx~Z zVm56@lX(xqrVuM4wl^9*1X1k#YDQ3G6&V8a$cLx+ix(=U`}EB+#y4B3)Hw*U zY8>v#4g6aS>^qGU$_Nq_^elEwO+gdnEK0bF2OtubYV{GOqDV$7kSy-~^(n)(g14%) zZ)5iCyTN9KS9x+%Q_;+uEY&*0CaK@vs9`JUFB6B~B|WdK8Q}sv5ha`*aEu8@<^`js zdtYFM%gM2B=Pz77mPlK3sFBvAk%SpdMMfeX$qc4O#NBg!&7W4XztdF{vJ~)YB1$~` z4&L+3Orli{8^ZJYOeiiaImaeGG1^C+0=IG;5v{x5bloCf-{61as$X{R59xVqR%q_- z{zd%{uAA?EVPo^{^N(Dpcu>b&TK{GvodN(FnK2VE%5jCIY>~oFa`3kOt{6uc=?qMs zOiZ>94=uqb48H+WboZ`Bp<(CWt@*hl4!wt*(49yS@wAMDlK7->kg*Op<){%_m+L^2gjxM0GRGljNzc z6yvBjPA9g_4*lk)2|FSk^}5C0^ZfX2y5GmL-*t2}Xhb&P!fF}bt2REBao*Z+&iK*p z-yn88z=S_RW-Pr8d3&qCn#%^w0(pFcU3xV*{u)j&K@HfRYFN}Hm_n#$tLSolSAD1 zJx~}pT(t*n@*XD8ws-R`GW>}{RrVr)3Vk*bGA3Za+EQ=q!^vxc{V|O@S_6X8Td2 zKFT-Bs;%Pu5YBt49WLny))IOEy|M%jCrVuh1*qjhez7uSa4pYMZh*qY^5OXS7~B$w zPRw_JekQ1sdupmZz=L_YETr_+_Rs+Kl+Dn7#M?97HYnFEiNY&3U~e}IdYElwbmsu+ zVrG%?W5p*Awx%%}@AqRgsiaqSw==)A$6K>mTf!kxoBvD)*ra06@}CVnOad+IX@eti zlWn(^yi1}GfIC5n@xdeOB+bdxR6;At*b2(FOM4hmOjLz6)8f#~M2!VBxPYQuZKoMz zFVjN%Yq7@!P{si70dVT%NuG%-2NI51Ztl;aRGsio6#G zfV=>N00ffgA^otZ&-#8auXv5s2vTlFCPk=@h^a5kf!#I<-1vJSQ7GaIP?%^ zFxxTE(|g?K=|!A)WrpbK!7Sp#w0Cw25XO=UdYl8gDeGwy?VemKU^`EMAq`k@;9vj= z?eiZ0{=7W(zC4`NrGm(t?tc^}ytje2b21XQ%PqL_RyBShz|SV?(;02hBq$s~&phR5 z*=+NB!V3l$7nl64>>45=hXCmN?Z2`@OQ97+Ap9&=uzrX|&&5{X-KHFetx3aJR`=v+iJlQC1lbRj=z;ii!C7)?u-$U>8M=*n;xHHo& z8^%RhR^|LIFmy6bc@`8e`5a@ljv|(UckliqRn~xe_G6pOQfUMV*5(&P8XsQxb1c`J zqXU%?&nFJD8@vc({Z7fP_cSvov_zw>nv!p+NT=mg;NDeBS_^7=suT#w$*5g}#0X5^ z3d=*S!ELG_C($I5y|f`#LYVYs1fC^?x?K}_8bW5=5}^_(YetT_-KNY%aq^z*eryLt zW#uTE=KYHGg%uXfpX=+md$hAk=wW&4y+@s($B1IeS7jmFvI`|3`}LXCfX!;19eyYh z;b;ftm9FmK@ZEb%gL-q8z>SwI^emVm>?_U3UB?zf*-&g)5a3_QD~$?-C|wc>-YJ9`&6xXP5hX7+ihL2$mY`m@D801V#V=-UZ^* zU*WrSkbajsN06$bu5pURrm)sFI}33ss9?6Gw&q(sRBcx^CNfsz_eePY1q)(MuBW>+ zZ`t~04Wrrlo7qGJ=QB+vU4Z#FwE+B`nOJjXlTTski4vSF6MqK`eUH}H*8xGkt)I-^ z&d#bXR7UeE{I9V%3+RftF|C>kAOJ@&J2%%Z&aI(32SzW6Q7 z89tlV)bFHYBUjUnQNLe6hJwufn7+2*JUS;_<>}75_Kit{IECf!Y0Kpi&$SwBu8g_F ziI_`=tHX-?$GUG##ukB=;+`Qr{0N0fY-LV;%Xwy`YZTE`T@7- z<@CuqaejEjs&RA%7D@gqxAKo1TjC*Yi(#Z_I79l5&%;dw&7V&eS#*DKaS4bID+2!B zR<`#x*4HOow+PevqY;c5jF|$U6>M_`GX;B$6w8qte1I%s z69Hz42(Uc@#8dE!e}C@%N5W)*2dFvW2Nqyx4a`-31UL*MJbrz--2hC#-~{4AHiD8;>%zDGRGi5MN(e|@~bq_Uln$qN}+nOpO~GJvNf6zC9hH*OSZ zO|>Wo4LE-V+F;@v_9WzU$41cwNOT=UI<|lcQ-8DE_SUdx4g86&E~YTW8~%{W9`GqE zTO}q<*wfPm@8E?Y1)GXgj0uGdmQUM!?+W{MJt46$3M5U3G|e9vvse-hc0S=fgR+)V zLK{Ma~MayTDW5+z|yz9!C$WqSgfbk!C`z+@%TXX=w@lr&lDom06!DdkQpF zYioM?C68{@b)&;K1Mi@Kicwlg_$Bpsg{*WrH}-ry%d{w01e~`nAwm5feMe1gQ|~YX zip{!L2+sG)sbaLq)|DUYHf;;v6({_&+-}16ZolMLsffG~i+vU0w7uFo}2)`w>Jjd5?x3ACi1NX-&LcNA(LMeCzuuthoRy^@O^Z zjjCMy!dh#$A#h$BDfmV&`oU|pfvI9{lTJ@NdeabQ;SrBROj6sOC{UCaW`lynR0}e6 zGveb{do}trVa>k_r(%jbAS5Wlvcg}nUtdO{MizVsz^(@ayX4up_s6lCD4`zds%bVk zW_}X5*FavOoH*hU{t~n=hav$jm0qGONF6$2A~e*|N!UOO#UEZPL7FF)WLu(rPiVC< z1o<+HPSZ{{tI^KSqtamsTs%Kh9~uEgpr=F>%3J{hv|cAOY;pQ3{}($`AKn!VC+eZE zUf$wI>SsWc1ctzjW!it4cq4j?Zh!77lTV<-+!#m$39hhxC1ji?@+zq^6`HQ(Lo`v+x`e z@bPIYKki2L`g$|aNLb*VUi@!Xt(KT^HVK669V$r<^v*paW?ljhv42V3pA=Q)lbW?1 z)0WFUmgM;aNpI6v=#gM>BbjtYkiFQ5`F3I%cJ5vd}h{KA^%`Q<98e4`x522PyXK|FR z+R2_B#uK5h~$A2R{+FW`|#mTQ)fQiM3dc-EELL z%q(2@$yZ9LsPTPTmlzUACo}2;jpXZ0*wLR#90byWQm(~+dU8^;_;>&W@PJWDol_vG zfOw8Yvc+nJJneSaP$gB0)3T3@M)HaFjfZ4^&STh`#g!eCL--2y_ngd3$dk=GS4-gH z*xS|?u`?%`3Wiu15Ex`Sy<^3-5USq;VY;`*q<@OBFKWCIH*a>z?Jz{F67qY**FfRr z;N%Rh+(~$Y0ZG$2e-T!*w-g40+7JNK6ebdfE&?lql^iMdgbep#A@4D@;sAlS2p84sR^o**MiP;x&BTuB0X6Hk>sy&YC5hvt=TO4(6t-g&G6t z+h8Wr)!X~$Co&BYs-i+RL~<}=#^Pc}eZA3-<8!ZLrTV)E{#VzM&Q9cwI`VG?hha^v z_6=XJcKwotX1-B~15vP)ZdX`{*I!nFHR1#N(RYvCB0gjhD~pz)_@t{_+Fx>V0AV?} zmN&5!ms+nc_tpK5n0Rt(3Ni**6@jVjGJ3%@df_XR4D`nsNU>&aqYH?l;R8v{Xr8D( z(yj`NVOrn(v8RyF1@qqTNm65n;CE;Jp2do=d@GS0{-X=NdTB;Os%B`mBXC%)0md6~ zAZo2JgAYYGlfj75JJC4X; z6n10UcYz*%_Sr=DI$V6Jp$bDTM#7pX-$fQlLYGWYTJZ-HAtEf(fjYjhfPjWMIN@GP zX~xu~H*}T5duEN;^N4DhKY>~RE^aILwep~MjMvBhWhA*k8^`fji^yg~GNx@aJXPQu zFqt&&_3xI&j$wsfh44Z=^#n|SB$fNzakl`GO8t3AdLC_VAg(qP8?NL2@Qmk&L?2jt z;0wVR{Y6`39|>G;e2E!`?{(177_hK^b$e^CQ+!E^v+~1+*Cl%qr{EddygmK7qx*DX zIGk>;(GWz0Nk_TGh0!Y2jGnpe5T{r9)-=T#Uat7a=KBCG$r_SsVli<#fP{gw+IcmH zznk}u9iTo>_^E-^*44H4^XC;`gGdTHRzp&uX(m@mhT+!>G?Qbx!)rusiZ0j^REjMd zVXjR4=+d!PinoauA$Pfd@*7~hU};jjkoJ##o8BL~mvlZwFTfFlf>r*RMGBRnoCc2b z#4FhgV*{g8lr_Yukt(*W5u<=FzhK+5{_~O8skfR`$mp~RCleD|kzUkQzBAe~2%U1u zc8&r6PaukFC!PK{sqU^}nqs<-4H>L~%*f$_W+VHF2keY<^3iI{p&4m*cdq-<_>eX0 zH^Um7xvQTd%v8Mzn zYF4Ioy8&o5PdpgRq5U)_sLhqdecT0q9`};kfkTCkB(o^C(D>G?hCUDci>=7d5+ z^M%|^#R8uLEV`HeM{+6B!hTj~1w+lJVm^(6b2oQ^1UG?!&<0LH5mswcbd7;qDR-aI z%fa;iiTVs0{hR7k$BxZLS6Kg)FUOkP+K9*oMFkw?B>#fNRP|o@8k`s#Ms3%>iADbS zd3i;Jn>1EpO?+gZNMN`jQ;J??<73-&Lhv+p_kke)sXH9-zym8Rdr*u!cX`M%d zX!EDnoF@+gvfc73_)S(4qrVZidtkT$5+WyqUfCKZdflKun6XTe#hso2?gcfJeaUoq z-=A*3_AXqN1RdPu@}v5K`ssBds#fPkj}zPeroYq1LHGOS8 z967FGvxyQejyv8n{6F!~3fRO8y2T*$=@G!;55K^3fu{pu&cCslNu_4^`lTl;O*<;c zh)GC51abM*tFu((4;RYnuisoq=AFrJYEqXaBGwWY!`OykUM)sXo|aP=F}-xfuD)C0 z5|v5=KhUXHR`)(A8aK<{AnMIz;lHEZi+=D{_br$vHXDr!*)|Mj z>KQ@*X6dAt{Uv;p7A8nrkm^~77O08i!NQ94>kNuJ&ywCgAtOxCBm(ofzgt0MvF-ZX z!=!)Z7m;eNODvSXh+_{}xq)v)?!Wa|A}AUb$&DB?tdJ4Ot}WtGhOqVTY;Fb+ZPO&j z;q0TXJTN%N=#SAy+oilaHbW6kK3`N9axV!NE!3Pyzr6y)pT~U3wnR@*;G0ZrB@7|7 z+LnHc&=VgTH~jlniLSc4JFYk1-#FMvU9N|l!N-CnIm$C^eGMdTdU^53J%RvkAfKLZ zHCB4MyW>rD8J>?ntL~|?G~7Z2)-B0OAp3lQlU@!!NtN95`LVrsFO{$H4ola%SOHEV zkd`;S^y-z2Jw1*2{*nUpjXNW1$ayf3+xTPFFd};uq$hw}&rYr$DKE{Rs~NsvA zOABf=V6Xd|WOC&4>uv(5fdH3@dS(wYBsH?4EP!=0IK#vNQeZZWM zo9-LfKBgrm#fB-TxmixEIv$dy>$WSf;gNAaVX$ia61dbQXwgjzCvcBK{h9mF(ZGbN z%=4{r{^?}Yt5eqT3}xsWPECUi?;>^?`LPkXmt1Gx#FHzLan+COPkrDSvbi?@v<{eR zkFQuBEL%uPElFSTeghQ>X`@;IdD7{r9iDVY)$K>ltfJ_!9YYiwZ}2wMT}mww7z#f_ z?q@=WMFtKIny8#cWD`dZ$uAOVDZ~{8IXH+B@0+Akq%j^uX1bw9EuG!7E_#vHF5y|z8v448`<3Ido(}`ojp7@(cUQoy!rKK1FxsQ--WnJNq(IXrdkEga*lOdyAi;FJ_I}Gd)dQ zTwDOhlvX@Dq6apgFu_-MBrs$L7ZvEfgt|ho7VEpaYhrbadN^N&p=L~6NkG@2^bhod zhQ2oo^YbZ-M9&^wv2BgRC032KLeSol z!Ihi4#PLgT2#9hEH#0!{5IFSfGnDyJ(G0yUER!mEi6~($Hi68N%bPHygC$K#S3JfL zV2I+0;&nBk+GVQ|1{fqCG~dKW_<4BTfiayxiRH|>xxRAF5ug!(8LJ`Muoo2hp{7Cf zcS(gruN)!KvV|i3r{^bclnY}FD0=Rk%dr6-sX&$HfQ98pOFA=u5BS@~a1XX2rX3ET zO|Vko#R0N&M?XJO?HL4ZcdmLxDP3N)c2R{%V$Uug6`!pCa{-_#0e`sl4496h&hKae z%0!5c&-lqwU5le`^1HjR$sSc_QG?Od?}`HeEYsm;>u5?rvgI_Ba^;Gd7fNu>X-9&A z^uTiMb<6=YU}jzJl^y}OtY|(oX|4)C?LRoC(i*e4WTp zt;F%Nmq+Z5PWRLDM`Ql8UgGTqGX1d=th}4o6K!hmvAa8D3C%rs;K_woi%;AV+IWa@ z>W>E7h|}#qj-X;_&dZ>CehS{`M_VP4h3sLv85v6Wh=d9paLT-+y+x# zAeibEY3V_r@UpQv0S^4BznhQvjaBhWweKpaj z7%D?j9Od-m86~W}En)y2$>Zx$H*=5?Ut1w&_eVpI#Kaj`aJAc@7fyC!7!ZhCmUb0l z{1ff*8gge; zg@GzRlLOf(EA92}ck~QL9k!=AbNxnC#4??d4)k?Zd-Yafh$7$Cm89@1@R2^vH1dJL z-M2cxvk#Z2|8rO(Bq)dyuiz*3kM5LIHCdhieA-c(@Xv1bYM{ zD*)pFSrZ9Apc8__42Q_i$>{><^@BAL6gb=SzsTbm90M&EpxK?0Bm)K^pxpBE@O-0; zl`a|_90UzCm}&s&vP;`E-||4sJQwI4TS14%R90FFq+mbtiz^0(YIWFYpfS6fi*@gn zsc_K8#TIg}&$lF6dLrDob6p6=9YQTw-o6EzUb^h6d4%_5WT}wRs8}v$@;tI<((#Edpkph57436 zy1dm8aTs zm@W!KYF@YDv0MX~%3{?K*h!Z$Lj{Qpz}*nQW0mg#OI^YR&h$mc-A#rDOOYq2H`IXa zlq>~rVtns|Pcpd}L>=1^4K_e0$MMU6u#qR=D}g`@B@p8lBSxNgUdlzZsH5G=>{9BRxB5A!^is#z zlA4x`H8h#~o%;OXydFWi%!ZOPj;PG{KaR_FaFEM!VSACOH?;Vw-ObG~p*Tgw`w39f zK(bcc#I_3f%|E}kv;Z35KQOjb$l<`RASaFFV4A{-rnzzVog%6Op-YzB=86_*UBw zgS-eB@+&QuLhhWjr!zAcj|RbI_b8*?mwh87UU;Lv$HAfhj08|HbW*z`ey&-6;{t~T z;GeC7L>~d(V#0Qg!dq)DQ|R2)-R24DU58lpo02FZOG#XGtkzr6aQGa;Cq`n5=4oxS zZ@kq;pY*>xIrfN2 zf@XHCn48Pg{1}`GOn8@_B8WnK{ruJsusOo=P!eH7N(oc4kWDp`OtHo_5n{ER05KXx z<8Sk$yRk9F^_<9fxheeZU-ik?STW4q5 zfx5yVm~>_8`&QUNyat%1;8&SYK@Uhc<-_b8Utdds4`$ecV6heqHvm(=-C;88&ef5X z%etunCmd+Sfoq7RYX0F1h=T*=7g}(wv}Oh1I*&ix-6%?GJmw(%osibJY%L2)2Eh+6 z1b)XETn6tw#?FibacaCOC^UZmHPOlGF&o+KH=zql!APb!?|miJZ7w2nAPlZcpuANy zE)kXpJf}B3gErBGVv_({exT-erx6uxr^EbP6fFlyOg+-g2=P1^J1zMBEmf~VlLAAH z4N8lNb3fUjHtypd))~n)4SZV~efNV6B;FSU`}O9{jntV^RXm@E4}xgta+H;9Aa@GB!X(?2;Pp-N@ppioPR-9j(NJ;< ziMUjVPxNl;zhtR2vrvTTa7bV?EK%hK{wbv*dL6v?wzjqguNrtL3R51>jSmJJ{RK?) zlUFAuaX5e5zcmnrnI$8tkn*zELs6mcOh~VMAVNv0O4w?98(J}J%45V%&PyEU%p}0@ z6S%Ns0B`OXk+^VNsHJKwquB5(|An9wbx8G~-{YyR#~@G=v?Y`U1=iINDK+Kccia&M!Kg86haYnB8x+?Nal(YGHH7_~9%)u$9?G;CoC zWGU9kW}6}~;0u$q+uW=WZ|Ecrvijtkqg69HY6X`aN1be45Zjk|v~-VZCl}2*uMmU@ zcWukSwEPLs<7;YI%H+#;?U@LFP7&f`)zAlmIaNy~z^dfd2WYH9B5m~bE&6c1QC5Gx zhhRmwgJ&f@Vh)ViguAf3qz4`V+1bgb-lOA}NYAwzv2d((-dl0(JOeg@98y-H=7FVc z{?5*T9;UFeh*nx(wfqn0qy!})%jpt-2jW3`{%|_D>ipB=LSeHS8%*`^dD^^yUj}o3 z8Q7vdTw5)dkf^lx+9Rm1**aa7J)+4~zm8N+Po>seVo=xP_;d)3{ys(S)5-{K)km}h zUD7LasnXAf!w}Gf9c(wEHzVy@TPDWWK%*@NRN;`d*;h>K?ETGR3ir|cqdwfWby(BB zCV&@lGEoA80oK}~;`arz-)DN^gZ0FU#Oz62bO=5-@rkmd)?siFvX%z@nAwOv4iLr-q0sD#lXj+F+w4Zx8D zG3ghkW{Px=y^rZH9Jaghgt#m;zb6~p!p6m?W{CD7?36Hy$&jJ2V*W|rn^;*P4nW0U zv4K(OGMR|XMHriauJrTwXHcE` zq&R$r3qeg2dW%R02z+W!#ilQH_-WfF5d4x{Lf;w!2NLP|)VZ(cOxwB~%K=!m#Ww!s znc()59{~0ckrUSI@!pU90ZRVOB49#*S|+SMCMw0%y24YxT;Wo%_ifQS@JF*rSwA$7Us*9ZjfW=HP47Htj1V~ z5Jxm~X~X!;=*IJ<%-C|0{O59gMU0OxTb_LDwo1k~a2Zo3&lhG}>l4XjXN($+_=DMy zx3>VQl1dAh-F!-{?5nqad^qWSKKW9r%=vqr1}^RI>iW9h^CNI;5LAN_RwxzC1)emz zX;JvBQL4P(dxvQ1TG&bx>p-4-GZkQG!k_~p^YhuCXJt<-fT#M5HqqytxnWATZk#b^-k!%xi~i{ zr`vg(YsPxl;o&BLe2_FDVA(?v9Hxsf6%@bFbx>?4;7dv2N0U3S`4%t`capiw`O_#A z1f)c)m*_F)Y3382+AB$-O7SWzG#vNK*rruDgiNY|-sa7pifyJ5TRdJ}N|zqu7;$Os zVcasp9e5WRJZtANFtO)wABC+9{nIE0#l;3$9m|X+9e?yGrikbAo?j1?bzs!TlloT9X0DvDH z4_S(FNbSJ=qhs7Ptz^i<#g%G1mvA(QMkO7qUop)WXpkU6>1<&JLyow4*ZcDKWnY*b z^#eCN%Id>p?XR20VZc0_uKhTw0+p8E?UQtM2k64mR_SKHd~*yOG#<`4P*27h#<&9Yx6L)WL9oXufN@E?C%CtqIkTm3CXCijfDzE2Na!oLBQ zczt~hzW4X{gUE4!Y=bgW)Qw9&3B20R45+4T+n(`vuTCe{GCBpo?QF0JLLgy znU;BH0U>*nQctrWIpaTug++;L0hwq6A{@Em9_h-T+FdBCkWq zVq=>;2ElhEl!{h(lE#+`AGB|gDTG?|ES-+)IcX`<$S;)p2WtY&tjIdO?TQQ=kw{7I zN|o(Kmt{0RMTWd;OL|1u?|!F4Z$FBo0~l(t?8}#6v!^4pkv~tnn3MAk!krHcx;@-q zQdFuHtI+g+dd!2sWDhxvpf|CzT1%P(}v#?YcBb2La$?r+f&vpqe zwn$1;jBMP5yTNM7yeT&cx!{~#mZN`B^rHBg&9?gdqv* zgce8&HNNGI8@I?QD=E>m@Wt`gRNJv+8Rm)VKI{bv7NSfi1VG5ZeGD%Rs25!fXWyMG zRJ|zL$3i|SffQxk<7kwZGP+UXeOLYmNs_Ug6`J2wV61rDc5X z7jH*uM=%-Axl5RWAPBXwf+QL#>rsX+qs~oy+D2xwtW%;RjJ1Mi37afG6Zw;$B$&1V zvCOX~w8m(P&+J(HToWU(I=E4bZz=}>r5s?%fa9MB%kY&7p%gKjS6JAc;->#0jiOH* ziA6nS0s0dAT&e-zrHxxk*Q+f+Mk1|K5b1tk{um$_;M7yQ8yiDpZ^14y@ef%dk3RZX zv5jP)cJ(N7`s<@c&Vf7E@3aI_QD`LxOTvVN#BQ^6Cant1J@SgjqsOqEVn#lBnhR%> z2?dj-YqUdqcg)Sdn~c)GLYaHlYd_cg!GdR12-^2Nn_7$E+s{xg`aE`5-~3HJWERpa zb&ZFiP;bUmG+d}mLI>%n-_9J?gIEz0wL-pRdvUWD5cV7M)Gk|@0R{uS7wTo(o+6BeO=2nXP|zPhL$FY)qz&l9?WaCM|Ka%cize#b9+ zX&7GRS~%;-rSJK05GIlPyr!Uxe%=WDD$|a(24REFGJ=i>ChA4+4j!9&d0oX8O!1qR z42GJde12hx-!grkEBYm_=HK~q1G;tbnQC2EA< zY|!v|?cciF9uwaw&GFOEgVQoBX*2;n_W1nq-FQ0PfZ56-EN-$&gBAIAN(TchJDSfx z5Lm~s5%qSs^M(nO$OrBqCSRh;$o% zE1+C}^jwsQpy+<$;KYV6uq@@?{rmKK7WbT1RNS1X1mlmp#@{j^0Rx$JtEUF-HE?iY z&d|MKPrY4Tjwri8L=OO5RsGG)O_gDV)Z-SxU&lTPQG>wBTm0Xi_{HTVxT9VGFb*%t zz^O*S*2BT!IRD>qKDP_a=?IP-g&Nax_fg+lb>MOP4L;@7gHupd7i)}GLPR7Ri8m;c z$RljK<81#qYa^37V*SMce`v~`-=umOge>VK;kY3~#}n$LSa5=cI8QMJ@#O9as3$OT z4BM@5+@K`;KSzG&WlWYgH8`X&w9Pbk8h#!TX|_{7umHMYID#V$5i-R}?gJLY_TK|qe8Jc2>qcWeYn3f% zzgEh}Qq_N7Agi7m^$#`qCJ~cE&rhuMQI7gwv~r}vRcqC}Fciu530$AF!`B8Rl)oTZ z_&+}}S*%>bIr&#iU;Qxn<36P1qKDFw)~!etEX(}S<5$?XfiDUZoXrlCQDf2*oYZAV z4Rp<*Uz~e&8`TDY#10*MSgX{#;fXCsJ0$t$lt_X++`%$>r&T@5=;NCJ#7Aidk-=6Z zC7Dvl6Z0d-MjZ{lZ{#a6M&x+rP!TpC%Dgov5iry4S$0I$cWhk;0W83QieFgx)B6ck zg`exIXKM7c#2yKfwtUteQi55u8kl1#PB69%=~&xJnp~y(JtrO3S_cWal~P;Q+*yk6 zqMzkWH5YpeOca8N5SXxJkp)NgxOgS?HI=v=bCgc)mpyL)5q_+I=x4ghdmo=SxI==n zM8B4o(;~<%G%Brd^Tv=4kovNx>G4!hb-T9+SPJ6DL=>BRaPr(Vb)$ME4qRM}$m|~M zS0LP46!g!0K01dhh=yYVkYd-*_|N1+n}59hkAkLG2#<@>n`K3jNz@L10@;ijJ#OS6 zGI+8<06lT_vf~2LvN8fqA=;7?Cy@qwtkEl2>Q0?Kl4^^LIV?i{+7@&>F;8@Gm-23x zwJSejN97z>Y1v!mE3izQf_;b+_0y;j2-JF)ah2_D?YM_LDN%%D#AQSOQ`V5Pm^v@a zl>n|R=~UbN?$rVV+CTM>nBFg5p_DUk0r?z)9p=8v^(PN~oQF!i-HGJIfbp*`MlAfS zjkTG~1aN>V`WR6ydq9}I^A+;L$IT$8JO5ga(>p?O3iP;ebm+9%Z+a&mkv{x$HzK}A zw!RGp#lc0@z?SZ=l8pUSb+NomtT>5TOr1T+#r;?Ua{(gh6e@Tp+~i^ekBv{dX~Hk z`f$Rn!WJCzD@pnOum5HXC`#i0t`l^Y7o;eX>RqG1Mm;G$tYZ{5B1A8834?~(Y5X@zfO?`c{F`q~GY@4Go$8yVN3hP}1 z11UX!j`AUa1uivZ;JK71BEt;E>yb2>w_yBX<=Arqxh!dJWWG*FSeOTI+0=zU2Ymlt zh%~mHXjqA&Wm51q8is`ri>G%Jl^JySFk#Mk1!8;__SMTUM@Q?;4fFA8fdW5Jh+5nQ ze6!wRATt7P<9&gjrfI3x+K(S*rlz&ajvZY;(}1}vj6quWBO5_Hdf^m#^Yh7aHSmXb z=OhYZ?oiV&Gpo0&8r*(;*+x`Rtmg_Pi>Gk*XKl7s-`NAV&O8-)-q7z0VRTB0`_5@H zjV3uk??Gs!Aej`q)sRUk8HFG>!IvD23ivVi>>@ASiepcdIsnZB>yz{Qzvh0|;bZT; zyjGr4f`E?pK;PV-j|lDd?Ma4wt-B$bPfHvMgoL8Au*Dlx<`$#c77IAjcqjsT+A!HN zO$?f6tiN)tO-8jq)Yve78EBV{E576}$5%wwG;h!Qlk5%muRgQ--=RNIC^(Y)EX)W_(?; zKg2LSM()m7)6lFSU3#}=;~WD4c1@#Fp_EZ=jg!ym3!^D_%-q4*XI{N>I`JVtWO7Y? z;&>=sG_uCe9iez^H_ibc=))3e_miZJQ_3Fs!yEOgm!0@e?|knrP)DqPfTkTRxLsh@ zNUW!ia)rXb$=ehz^Q8}TLm1Ayzo5keXT=ja7z^wU1zlRdB_azyfSM5Tgn%py*z5}| zb`(t>xkrdV(1&2Q9!`exn;NlW{~#G+6Z=AHYfY2Aca~QVvx!{ zRAV@N8bVJKrh_4_Hx(%0)FMwZe4Z%v#?_;+_dj4MbvPCi=>{D<7;-=5X`X z|34RiPBRORP!p3nBM@bae&6rTS`a>tDut3K2+c#uo#M?bZ>G$GG7%f;lIP(i7s4H_ z%-?NX9M|j9B0OU&vt1TCclb3JN;-TR{%__H^{{bE{Muv(QU=QG!1W+unyk1^iT|GZ*J-ySI@gXye zeD6Ud6_^rJf-aI2N?q8vOfPyoq3$P4h7s*6;(I%mwQnPor?&G!@_oyX0opMl8xA7g z7*ljUF&fz8JbfJYa&|Zelz(YD8dwK= zH(-^rS>ZNW8loo7B4mRn5Ik<6j?-UWZ=Ia_7nzPW3$!{ zy}hGa6km!m(CT(uVzK|O#uq}%{E?ZG5hD@N=N&U8jX^I}D#q6odJ;_rop{^=t>Mbm z(MRnST0J^3jcmtO6n$#R>LYhQKQx8w>Q-VBs!$V3F{$5S*3cR{R%C@y z;aK&h#F~?Xg9D%@0_I$i@w{XhcAPPy!S)EYg;*JFvrhe>o!Ijh2~fMK4zW5kZYmDQ zE{6mi;YA%T{!zyY)BlW=BveJy{3`Slrj_^I&Oc(lidNN?)pIYK@*}n;G2<`Zt4#X8 zr*2Q9Iz0NbaPfYqKB1Tn@8@F^uze6vdhrCOcFbHOTuG_y~eD$pr5ViD>@Zg7}kCpk5P>=!ia$eZ-#l)WDfgllCk! z-mou2w;8SU-gSWc6ZMe5i@dV3FTZGWvPB0q6;ZpCP4DVyu!g8^g&$bhUIHi$_Sid1 zXS{Ah7yJzgP;kcK;|Nn}*$ewYYf>v8yao5p2${DnGD3~T8zj+gu(*JDkvj!I#4_kL zt-d(A)=4H|Dp&5*tD#(>VD9fpnqopiUA?{OQ#=yLu~|z!-E!|dc~(SP4BR;9#i)`H zUYHl%wr=oRVQ&Y0bZ}-h|+`4GK;!(-?tR|h# zoa6Cz87mVEhbTEM)N}U>W$)B`o%5amk#`Z)fCIZGb2#}%2RX`&0(QWNM3h*de=9vV zyJ?TgYY;vd2c{Y8VnM+kmwXRRK#@PTGxP*0HGvRnx+5p_n*?Rbj7A#lOmvbWPxi~r zE8u2=({J{cmVw8Kb=;YXefhc(Tm5ikQ4E?}^2n>3 zh&U=ei|*`IIX^9#94XmDr^GT`D>rPuI~44FW96LTfbybN?&0TmHdUcgg0T-D&#iLL z6~xzo%5OMwP*YdeX2jMi#ts{fJ_|OK;#&so4pP32f#<&Al~HY(Wnv1B(|7;5suRX{d&O3>Kzcm%XhcSLD{_| zDuLN6K(&V&Rd8C~UCn(`$m+vhj9F4;+cArFD|x8$7#bHB6N?Cf%`T20R^ss75X$HZ z*5tz=$d%H!ScD^eY`H3Ven-Hp3YFBQd`1#+BN`vuP(f3JZTIUc65)b_`iqHK@`B$w zheW*?@6MV0nBi-^yZ zj-#$NB6%$e#H_d9Q@0^*XV#Ur8r92D`7sK`Y6hK)hw0&pLg5=L4 zTcr3W;)#1-Nlc_GewI-HSjN)}$Sn~ok)4D2gYB*$KA$|$)3&AHT6w#HQF;pK2>BqH zs0+9N0H=8%f0S;ak@PW~jUI&wVhZ^A(VC_k*S0V%M@m1oNBKYvi`kQ+h1S7!K>pZ1 zy8)6;z}5BQ{y{RD|l_Io*Z5<6~j#cPxiW;jqbJaZ91i)?En!B)XhaUwI{%P!^BE`Z;<`N#lu4XaTnN-=g@5`;p zLO~{baMIW+@Y7*c8l8*P$+FgS4!k*%WA-jt{CS!mZ4=e_P-8kSl^UIgT>J#4va;ZXDEnctagfZ>Kkn0Y$Dj++v3y!O?oY{|m!aq0^ynI>^UBcfIrA{4lZ0+`%A%>p%#& zdYRZucW<%Jpl*zPTxas|(%0ADA{4;04sAaCc`C0=s$V*X`5C8Vbx73h9x+t1RxgyD zD|yrG;VX6iz)&YjsM4EB6$J&F{l`v9hd;oG1d4_hd-6OgwRqZ*mqZU?{}wb{0g`w| zK{-Pnw*BM2-vVIcdquD8>Fpf}oSKusnHj)qW$pVI7`Q#lTxJ8K&+2!$Wj~|K3d1MI z?F8Z@*PNt;u#|Tb4uZCT_hk=T#;OUPHP?>}|5!L2EXsy=fB)0#=6%-v@JFg+)j@+kAS4D{+7*&zeq)JEONoGC(v!p#QjJTutzzBtAo|FAkR+y&wcDy7`y(o*l+FRIY5Y-t@J@sTg7->vF>sHHiO_AnG@;(&C z*Oo6%iozbu%fO~ORWG7dLOXsJrGczKT-Rkj7eis`MsT>!wp#G;mUl($ez z)y*~BEBNX0oSvQ@=^$$@)+2iD*2ceT*R5`Z8y7ag1+d6YE||+DN6gV9ebTOR4A!38{_P@@|Z2WmJ4S$KXFjun)>xTl2qyQ)A8 zx2{0RB8gj-6g)Ukc~rPor87^hyGnITS&LoB3paq^_3e8_Z5Vjpr~aiA4_`nbZUIaj z;EZ{BU(DiklfhGLNq{;0OG4Kw&ME;Q;X6prS4jJ08P4H+b$r3Ej%AMe~5 z(wW)ReDT-fpJ@;gj+wY)&BRv>+6-ZiB-lx>K^~_qe`OQqrC0ajaq6|@heiyZ-~S#S zzK7G`{7QzQPgQ@Wx}L;Z2fS?3_z@6L%w0>&HlH;_W$OjUJ8i2yNnJv;cL%hOpuW5W zyaIT*#}ZO4xiM|qyyn#O9qgr89v&}2tZBkb*E$?$+{H3glqRhp3joQ1JIln>6g^UU zQjiSe+LvqpK|Tp1I)krPh*hr4Q2xR)X(19*_AIIqanazUSI;sO0 z^np_-aBx#Ae@mCO^1Uc0hqSpIHrvAfup!M{oG~7cTrP}09OWA+{0JZw?N4AHJ7&G6 zd>`qZ>$IzD9hD1a7ahhXp`|K9?my=Hn!}^(_%r9}C13zEV@5rA)_Vi^_}al)-&!x$ zyS-2J6Wo$Rfm>Br6uLjBl9i~{3BnK1sn!j@;AOa>N@|V@Dd)WT!smTvPoRo-+gtq6=)Y-?FXFDZ%5)((wNANp zo;J;J$>471X{s~h$W@&N31Usu<}rTi%EP^x`%!w-vkPlS?l&AH6V11qPv z_cB{U5adgEOk^IKCujkr`ZjlgHO|G2h(Sw~Mw<-dY$vHPrO?6*skZga&D7))0TUce zH6HcnKyU9%->UCo=P8=mhz*(i_E_j}Rg1^gylk^{V;MS1AD9#d5Und0MnIdJm!05L zOq>iJehCPadzof|??<8Iuqap25_BPHpJrT6o$BIdQ61OO_y=NrfvRW|PM68hcWKiG z$x0^DU>q9>ra0K{QO((gLgjw+=El8v-c{(}QGz`u@{(YqDa3@bN#>3Du5^%8V6i(;a?eoH z=sr~FANKKRvxV07Ej35fnS)SnULG~dVHHC^jt6S@xdm?<4cV8nrSI74R{mkWX4B)? z?ximix*1s|$E#wt?3O=ePdW3{8m|lpkVDbl7@2Ol=y%29sAEtH^e+AIB86{Nk(;a5 z;U+Fi{Y+Ox#J&SHB{}YOMLxwr%xx$Dt1$^CSlDbCVZ$%^Z8hI4`a|qkKU(t{OxdrA z_}o~7Ttr3LjL9(to+Vye82{U0q@U7gDkl&fLt=(i}^+4iIJH6QN^)`sE3ts zSK>>kJeQ-WPzNZPW1DEj`vjp~+_WM}UTI43E{wBiuPj4yq;QPLk5Qd)i{2$#fy}t0 z()cRW>)Ic>O(~X?y512{S_r~w5zCc6TzkhY!`sZnrBTMYXnzX+iZl2}Zf19UJX#sr zGzP~fE^{gSHL$BDW08*N zOkD(3iioZo1A&wmH|!z%WU2VH6N1qMOm+1hqFMCvKh5w9w=ZD{fCRx02Ao7Gz2qnp zNBUi-bH78vfX|(lzud;HKq3l#68+GvUHs^tQEgjeqnoEET$0b#PH>x{v-$C;iJ{@~ zoo~F{;Qk(%oJMm5?*Y)8|L>Mz8Gg_ZB!9R5NZEM%6VQtOV}ayWxWP71VV^kcs=Kl5 zT|Z26^vO{8-5w=%PI7$&e+R^uc)3u6wESgRvr6DGz6+H7Ja-F4oo7+E5rcL0^?RiM z1?=u!XWjrruZ-<#g;RS4%{#29I+d9oxMY{f8*9b@>4q%`vrjvo8y}>@N@14 zzMN7mBpf~h+0sEFhLBada!YNV@$fASqK z1#2)@NttSrSQL)`>ghr`dngpKKc+oqGY5)_Ej_Uet9v4jw-{}E8)o}WmP)~QrsdRN z`!RD$7`n-&+h1+-FJlSM6LC+39(e&*eSJ9C4>pu{*j<2qZ8y>oFi3kJN~vqLasVcm z`T<&GdK^i!(n`D=>Ewks*x_Q5l>=U9wP-ICp9$zCv7qW|A$bKK6Bm)I(ny%cqre3M zOa!k;MXA&u*~ z$)n6GP?#AL)7|{cWjf8C{eiNP|IZhd(Yq0D&nk1uXFoM*vJAaFi zt%k)qb>!f#w+KbTsFnXmzQ^;syH2R^T0EA99Za?d`mi*IN(#FstsKJo)MvIV#c~7*`A2)^A zYR~Aisj?D`u7Qh}4tE{8cod2ba8-E7V4V_(Pk@sHXYcO>$J$@bR`b2x-GBa(Mdf)L zq1_jgqh1yUYh{?8o{m=F_xDdNm)#$oo7~0;hl`cnnYM}$Z#M$P`uxZmz3MDDvagRK zp{&4b@fvVG0HsC)NA|OZq4b(^?9t=n8*KIndqJ}GIkWmmWH6f%5)g#U_oKh zC?8NgaNH0u6T3dg@hYa&|MTUv7^VfzeRXgXcenlyQ)Lr!<{8$?80V#PfMJ8;o#h2*@jJQrw7|AF4uo z!LL1CccjO?d`m1(jWk{kEAT-lKrg|}RydjH?Xt20%Q^D>($J(P|4D(^pWEBifbcs) zu5?j));Av3sy)T&Dj&Q>_$qiad!IkBii>CRU?#_Y5%rtXvkGtncZhbcHE;omZ@|jO zLS_$trJ+h&+m-VA#qgBi6PGNSVM14#YR|Lw8JDQna_uIo6a$NZZ`rThdwjg*Z*G7@ zOGQhEwz#0~Rr#;4Os|`NlPGoio;;-VDSb1x6Z!9&#ZG8_@2*elGh*(v8_st0?jH&Z zf0uVcEY+R7|B+rM5>b)kKcGiLUfvNi%JIsjDR(6IM(SXMohq`l5Ehs`wg8vq+WLA# zGL8JJsU$WGb0WWQK8h+sMIpP179Gu31Kf9|PMN6p@UCTT5In_S-M^Unns#W2dAfOg zvNmpX)?I2Mnqr<~3*OxH(wCeSplRkZ$*PWIBO7(WJ&%BEi7N%Rx?2qzs?N>+cuJO9 zIczA}0zu(v3w`)RN%Y{P&P5AOP4;!TNP9Me6~zPW6mkW~_NFGB)pwARy^8QO2L2-9i4~?;$#6YAy`Xo*%2UJ{Oxh8&f-J}RN-0LR?vbVV zto64l4s)mlq+&kI4yC=H0{EblIQ^d;Unw0Lj%LEzF^^->C?GQelcKra#ycXKO&P7g z%WOUK+U`cW9;(Ib!`4?ELzaUIx>u`iB63T{C?hvvh4inDLlqg3iouKVm^|zN^od zQxmRkp)fQLJZ9rW{i)evA%ms#0iK__RG!dkWfQ}s2kR)AU#3cALBH}`9)17hM2TkN zXGXfV<+r|dJpJ)_q}PD~xriPe>AzUMx&zh?QW*+j+A}C&nbKZ)>;{3;3XWzA zCzP0r+_f{9l@kWDp`(NGtF_;PBlFR*r;z(i%acbD22rn8s}Y^RAS@tFL?wcO32gg1 zuV5wvurwTv2857UWdD2U#seXGn+l2)Ut6q-uwOeb?s)u5M})bnoJA6#1(d7ja|hA2 zIs*bOE%F221O@O}YHY-QxCFfJWk;Yo$qnb21%2w@?V`Ga6dwtCX&L9MC`A;TsVvyw zMa;D&X*yh>^Th)}R;#P8udkmUnI{?nf;MdH;s>d&C0OOJ8yqn9%(FM^#ArWdI#IJo zb{}CsD9#s)l+q8Cl*1eo6-2*zTLz+;wI?T>wiy{pCcjU}^FUeu-GPF_mr#_E)M;Ei z)<{LA-0a?Y+m!#+3`nKVcXoE3p0Z5}*cRQ|dj9vVu`yWCN!_wnZs>`j`e~TZyg~oo zN%<;!?mEQsP1hr-uCx%|vl>dk%I3YRwM)zoYa?$R5*$lABkd)jXY8b`W27n?&$7pZ z_8@WqcO<;8R91=Mkv;v~1V`H+9r_&x2avH=PCvv@FbO0#3}=*F!MAG}+xQ6L*@p4h z{N~X~WjGk!n}!{gKc;16_|;>rW!ELpJh<~Wp0%)dC+=zb=vP=J<;?7qjst(5bHL*|WRtW+e8vX(QK*`iF z63;zCL-tbpc)Z7NQ&^kdzbjn-*w(-vAG_h*DUX?*guTHMODqH9YY;`9>rCh@a8Ajj zh@YLMvonVuA`Yaz-t1U&y6Hwzg7M!hQh=rU5y@+*l}5sGPnkHGAQL%OuMm({fh5d+qB9Hb%{d(faD#Pi=PFKYNU%}Gc(4(>N~p1p51I=}P%5`S!sx}T0# zjh{HRArp;DrDdcx-V0`fAIrpElUitNfTZ#LyM=3EFz|&j!;+>BebqTrRr#%)vM=o{ zvhOW&asRhTDS?+Hp6HsYJn^$cu7Nl6Z{kL{DCiB?HNB?q)UAdo<$6@ZnJv#k-b7-+c zEbsn(=*RQ=4y}xhFH$5T2C)Zo1Pqe9J|iba=!65 zs5FBzT`Dtfz85e|IXk1jSB8U~ zP$6B)gHpj%4@h;NcwGic_i8+haOn zPb(jo0pAZsqC54lNw<2#}TQwp^rnGhOnwN-(ia(MK@Q#jn_L-MqZy^lG+T7+9d1!m5aI z3>AaABHL0=&;>r4gO?R@Jj?|IvbP5?LtgraYkS*a@rbHN@B^ip2;aC^C-IAp0gSS* ztH8~tc?|*~Op;9G)yCrgc%UZAe3!iRe7uJMJ(P6&owyVKE6fPz8^vUBWSUPVFZpYWj|a;mgaLI_G%2jyt!&&QCO{E(&RvA%!4H75eIyMZ?Aufo&D&ktbw znvJ&HTJ-;$boq?!+{-H=Gr%oJyPpPE2Uwft920DB8XS1X-y^?~cB-#5mr0rr4k)fe z4NSeXHq%flMB3A&T)jwl`{TahS*kz^sHR9TGM$W}?>L_V$9R82G$L2|kN0-phiNVkZ4J=phCy93#mI$+j5JBOpXyv=CoE zZ^OV|!gMA)Oj>p1L&KOw{EQTaqLr9kx}^PVtAX zu~V<9lXN{YVc2j>e>=^!m)yGrV~b^kD>bB07+cq41}kZhs&bu1bEJ69s~AIF#BAIa z@48iBNtJo}d7qhVm1G=6&GRF?`GkYqXByE8yu|F&v|=N$=n~OkwMoEJ_f9opuyAwd z=7#&uLpeJ-rV~5a_4ExHhU_0ej$3yCW!}}#PlXOqsdjvA`u>!27|U*G&SBK4g3^m24C~Y!D2ne_^duVo<@${e7r=2brzCR*z-T z?k%N>G^Y$)DCA15o&flG^Ekmzq80+iL=eC1`&%7UBFUB@83KkTRfl?{Rr(g0d#Rg| zKc$MqS_K=*8tl%lFvk+zl0vZ+#`WZi$@4!Bw6)QB)l5&pGM zkwi!~Gc(ijVj!sNAhcuXu-u(AmzOfbD_YdE2O{RC&dz9sjnlg$Yt`~ab@7*_EifB_ z{w;yR70WqzCwM|&opc9)gx ziezm_>jR&2bJK}GXXh`F$$8fQzG-*>Y(uZ^EgdB|HEOg7uZ%w<$DT3Ae7fF> zqvSvx*q3^Ppz8hl#PZw`B<%?M+&<5?Vbag1&(D5++n~z=Dy;YRTI%AWHb-5=L|h3L z`WP-wciS;5flhyNQ^O`@j$AM*B-;l#iPF1A(vs0P%l{s5FcLfyupsngmB3)RF?J_=W?9P z2*!>HFc5}HJic9Hq5V3r`3ocQQy8>lF;?pW3c($kDw=EN)%Id8^vKUqo6id#=P!>5Ka|Iq;x7HH7Bdl$`}-hvx;@$~I4;O4S_4H{`pV+4 zb-f|T6)-XU{a+3bZEfGZn?#XoP_&1)NAtqYNo;8FO(e_sarn%kd-hr zNQ}c(Z3ExQ+pe4od7Bg#YbZ+uR(6C@5x<9qEtg2<%irgsevoNwX!8TMdHC7P=COGB zlM0nb8KPbH^4INlI=JydG!CYyP&|?++qY5%Nc(33!(7DL)whRt7a3@tbiO`i9MxwA4%_&dI!}t%|6B!RfGMn> zt*>YC>^b!ySJ={Avn&3hqKu=Fu(Jl*8`7!N9gJoceanRY8lV<<{oD6y+;&&Wqs*8U zvCE4Sf>ZL6O(1O?@2q+{Vb9yd4PL~)W^!N4^m8A7hoy`U#eP>cW<{S&^cEMSNB~X^ z;|RY(?2$cLY&x?g27OiKjgRy%j5zICaGeOJ_6Ko&?0S>K=G>aTV1=cm;NFUQ%&D9S z0d*XPXmo4ZA`H2KEGujsd*A9B(n2=BJ%dZb;1s<-`*vZwfbY!amw-_WzgXCfKqm%y}EP{F*L|O{(e79z`MpO{*-DYP}r<-5HLcg+Qw1Q{s!wxa_Pa5%5XWj(fr5mJ#lin`A_Ke zJSc8~3Ccsqvg6j~rUimq6etBR0pdpb;7|H(aL#Fl1$)V~?P8`B%dt=_c41;~N)|qB ziLkM1xZxMIa-aili1TLoCmQTvkdoPX&5;y_iI>LS5VsY_X^t#xYvA!LO!y{GEsfU+ z0BPKM?owV-no3E)P#3WD!4WTB?ky(~P}+R#Hq|<1#tP~K)a53tDk|g`fAQJ<~fCcAO2GDnb+Pj+|Eh^zXRJ9=R?fyW+kn%lYR4rTy9?2zk zec7Tz^BP(oW-)q8_Q=SRcd-H|xE6xC&xf|Ur|Ks)^JjV*9g^qpe_`SQphHLFK1)@l zb-MNb-ron}$q58G|NMI6-W7N03S|r!iTk7{cSHBHHTnQpQK?k;XOoWRicpBKGV=oj;_o7o%=y zBRd)zI2VsSb(V@P-tS8JuG&Y0eEH^aV~j3ngp+K9+H*^8@0Ey}wE0JGuIOs5WQe&X z%l1G-@kTar#6q*V%&yS7))QD>WN4}$8^;}XO#wov)pY3u2|CQ*3>SlH>U&0V4~(up zwBfEeG#n2&RMc=)K{IZqg$f1w?MCmwAjV7%7?oXj`2^Y!Zmo+bV`EFjRvtLgi3btv zFTCo)mRe7)qar~$K~r}C!8NM&@&p)TrBZG( z3?MSM!G=!6(A;95_scC_ND3Ttgi2^ft&Z!;Q|96MZ#C49<;F>F;rL1qHp%R zj;%%k>DMnHLjmOK!B1H7X1!^nO+LX!zs}&qczknB$UmkG9t_M|tfZ+Zg+h<9h=Hvl z&Uh!O-yEw$avkN38uWp(OXe_S&`yj*pXg4Nf55NL1aV>+e@ zgd1r9dGQh?$E>W`AlWUS$_7F9w?qaNK0Rjjgd;V!Bi7vFg1Ic-rMDX^-Bo(gu#@2v zjG-k$O};?7W!AZv$CMSF#VNbWI(W9%vS45rXGAalU${KGI|>NCBIE|X!DQl#Yz;U? zf%zfEyr@N_6_#Sw>b%lk3y>z7Oo}fVB4$@XZ#2)J}l54uGKmmNPcN@OPj{#Nu|SS{=bKj-eE72^2CxwW9}hAzlc}JbxS_%{;3m90 zJfzirpt!nfI?g@`#si8EI3r*@19qDQXT|C%D?`$IaXKW$A*Q(CXr6!6#Z0C$exhWQ z+v7;6leaa7SO|r9t{T-xm3|Jft>%cpbMz^_qL>V7v`+-IZM!Jn{p4?-IL6oU zuqTp)ew(`00WYqo*eid`MJas3glZ{QhSusWHFnj)ulkwj?O5PjitO=%)$L0Py)M4@?CZXu*E@91X3x2xK$YR< z>+UmyXU>Lsyxn2LlxBDI)G*V7@8c=r<~{87(s{?*?a$>NhMU`1=S}TF_Qf}>k?M&u zdyPcRc{xNDdA$D9gYxdYb7LZYxkNO8Gf70ae|+B6vFRnC$mvL)e_N5?`5Y6o(GO2a ztaxsdBpBTjGPU+>@^a|=Anw>~=zC=j1s`9jhwZp*9E>;l+}igwf;)Tp0cR)j(5I#Z zi=Lq#LuE0?-b6N;1NVpJ;Et5G!sW0|Uq?;XbJcX)HBu)VGy|5w)BASpa|h8Ir{8*) zEHND1xA%ca7jbolF{Qm5#u^ghE#KX$PJrM0qfF0xS*==mS_<`e77V_xF9WmeLsj$a znA5gPNNi3uZ1rgkJPOH~zLuPnY41{;OzE!{99`Ifx}UkfMomT?5(1QD*6CRG60Mx+ z?@GO{v#~a;O(NKj){M|2sLF~ZZ0QgalAQ8CBU9E68h&F=pChnIDd?V7G(lH<9N z8*8`Wil(Bv`Kg}Wb=?vIz2mI;xtU+V9;T4%F;P{K_jMUJMW^F%PuI5V^v>GtWn@)T z4)zW17@*-6qB~n{LLoqYcYWd-WYF$t<11>q4r7p! zp)~OAdVWkbM@Ka^rJ|74si)*`ci+g3R+X`+JOAD`U^ZoA5R*CV!O`0f3cKhN6i$^ybr zE_SZ-bwXFKFO}G}HAOy*%!CP>bgvGWn^Du)XEg;vH|appm=S9g#$%O{G@Cp*o!o(X z3d5Lm6SsgsMTa%GeL9^g@ln(v5z<7rrA_{%?5Lg|zLbaIko%zf@8`d_Cv4!qts$9H z9-tblQP>FkWJ?U{YGoN^t}9U4_(BN*r+_IFhSl%KyU&JU&sZIh*BqM9`#)E2h2G=t z(5RgZODAi;nS{`axAOCEPgtzIP;~F+?dQzZt`mh z+*HBt7IaK{qRg{@x1oEZ!8qG&?iFq@a^WMG)e5Fpn z39HfSp7M>{GpyQgF>0^bcUJ^^dn3r!>fWZ*fJi4mVe(*dp;Ka#H=W?u(9!$3|GPti z&?rV4JJwOe3wiGQ^tY~J;4Cqn@pa$>(5zi6UmU44hf0+&&q4iu!7y;*;cgK3gv5`JKsdse3HF==#zN`&osxAhjFOa=cim+jJ*DoIY?w# z$H(hq<#j0`gK0TnWOsiv9n^ERF~>alREvJ!;}Lx@g}73sq2@K7PgQ2`+M)?1yYNw3y#fkbGMD3lZkE#zClu*o#{Sx`xluD;io%>>tf4|- zti@{7=oj;t`v3=`D@B}j6!$`M4}6;wFH7?8hXv2Oc+jDMLdTPiS$KR;%HNtP!6`X^lO3@JIVUDg#CY?B6OCB^GO|>*9*F*1lN@`P zoI=zF5q8q{RJcX@%K1Q~P0a1kN=rg*d$EGO;YbxAfG7CNWFornS7lNY&-h>4i6{!O zjACWHbFuv|(1&xKUslljvJ>ZIsV;#Yq2ROg;zB$&8V%vMNN&TzLW6C>U8)?nPKbjd za{;QIHJMEvkE!z_@Y#Cymt^!INUcFh_fRiO2(}c5j9n3m z(jq!>tMl?1M@WWXGYpryP#j}Il%wFwxd_-CIR=gMmI~0VhDG_|r+MWF_9#jGfJuFX zX=1TW<%KU7#C|Jd4YXTn(Q%s~?7G@YU#sU6+NUiF(zCe=Nsn{s-9Nh!sa<#NJ`xy$ zVBpoCQ160^0W2Wh*b=+WQm2dugQM&9^s*TFZX*tb(*#qoe}Dt` zF5#8BFusWPY>C^pvwwcv5nC56@cz_MLhk3H@d+{!ORRLiRu4VVF!B9N%_QH!D=D>* zh{^!KH`o3UrhGqd6v&Z9%z)l2L4x*+$5Vj2>-$xoxR8;Y&h!^H658p=-c{~^PHJu7 z6>)~7lJtvfR_>1g_T0|*-jULtJQePolS~Q2SuwgO8e1U+FmLqGPv3>eO`akm<@N%j zFB@YKWO9a~G2wu2cqs5Q{AyOjgyz57HXt@;6~rPqA`XCUrMkTYi;Q46+IYA>U`#LR z;~7RueR2mr>-|=Q#n=@0o_1k9C%Xw$=J~RK{K#oPFoT$Q3dTTk11Z%TP1_tuZ%d4q zq?P*(x&9fBOKc>^T!|>F)~de|E8K&8xI;8Bc|Q`bS5ZY=%Fs5p>IFj!{4@G)^H^MZ zZ??FMakE?}x=_GPTI=^hqC3Lth+nMh%$gN=T%my8$+}M?Np=I`b}qg1O60q+grs^( zOQcT63-C4kIw+(xeOkn-Q_nL`yq6ow83L8YV)e+q91ZREQxI8SWjk3%eZfjiN< z5Q?~q2h+&Ly;ErDl}H@+O4;1G{4_7JzkgrUVw&&oLF{Vq20ZcORhn zAs+JO7{y}*zwKNIlQe$sE`~%7j|m^}`AJa~c_V!mM{7fQT#cp>7`8sEmSAfnX_q`PHIYDG zk$v1JQesKXK572=J>h=&0Kan0_kY?l>2RF=@#|vwM9R47Y5W?jd9~y18?n|}< z&oo3v&`+3nyff?kX+k^Qq20w>^S^!=nY4l<;z&_*Xoe2o?K zd}LXv36rjHI3$XgWIQG0yeb%2mzFZ=1ztG;Sq)$A)emPV)Cv~Ofma@}=pQao zG`)c{g$dWY6T2+U5%n+x9y_+>If3hT$J$=D!k0m!u$H_*Jfg!Ql60kGm;C0T`Ei`f zb_-uMEKK0z{;0K^ujRpZLJ~;KGS(6n-Uq@S7RX8GlEzYC4prQIQ(Vaj%1c#g!C=oC zyNb-zSQZaXF{{N6A;}UXc&iVb`LyeEJX21^xCk!U5ATib1Ig=TH;Ts;N=U3#>u9Yt zf7wn(Fe>%~Es$+Xrq_6@(VY`nVS2ip9#A0c+Z)7;ms^or07Ha`tR#I78|pB)(8duD z`-NkHtyCr4)xbkV2u|9bAAdXxC2wSKwhdKUXk|OYINuW?PsGy7^ZOsnOxy>Yu3}hp ztc0_?Jd|8`YRC?PY?DCQ(z&#_vkI{pJ~XbF7?GN@O84Vrn7nJY&Y?4`b|}j*H!gT- zz~bP%Tn8O0r4p0r2zsB)cR5aio3swct9h{+OxyU8aC zqGd5GX|iPgnjjkcwo#oq2_*q4<)|Z6$91|QD}VcX$*#Zy=%j{T(F$el?nM`-{vlH8 zoJmy}*z|p4i1$?CD|Am*_w=w|LL|}wgN{?-Cb^Ujs-<6TOmV-s?OT-6gn@BSb7~Nn z80RfUL_UpQws4vKDIPgTdPYo*R;2Q1T7)3jH6Z%F~^Q}DNvtYaaFFQ1&?1>}y%;nim9v9p(Qjf$4k z)ugLnktWKt>u^v$A&PuuVfPaZ|I7Iji+TgTW=~OSoXnUS8HkV#>9(uR0Hzu?nBQeW zR#z0TqPZ3bJL!M4kEDk)u7KMYhg)bdZ59T5{{SsoO9?A_D76_%gKb)??IcVr5(mYG zCLh`;sIBUToL5kPX|t+0ZPD~?6;}CgN91R4TT@QUzR=?Cn1_U>JhjqP&6`%lijlw( zlY|$AmSl4pZD}|fYb<)iKqC@b?cTURQACv=qE39UaCw0Z%gitgXY7F9xV-Ib`g1%Y ze510#j0f(BSR=$i$ltS#6@Q(Kr-CI*7%r0#n-smeUqxFntt^Dazr=ci;VkNTp5K)0#35NZ}7Fh%oGw}7JRkhe*X0f6g{Nmc9Rk_gR}}x zdzzry*XShOSypZi=VNw^-RbW#tJtf^CP^Hkd$KYU=|QvAYhHAJkYs?+eJN#(*`H(#j7Ln zr1A^%sM$<{zL<6^LZ&#*hZ6;r{8m%NV1wPwBP9_^gq9Jfqm(Tc_~qdttgfs-7SO+1 z2=+4bTRApdNq!sRVNT5H{Oq&Pmrf+iX&wPW`?CW82DhV(iCkFEN)ns>!h9T$MCc)H zzT!QRwjctaOsE!|HNzhmA8_rhmW)j%W8$JXhZLLyKpyny%}%I8mo$Um7|)9aUvQjE zn$|Ft7H?PGju4ssBeEEJgkYOYp4E-bJ+3`3K2Rtr~%3C9!+zn7$ibZShfq&LUnjjk4E0j5>1cFR4>J#f*G;S%+o z(m@s+!BTtmh%HZgFqn!v&ecB%)degs_=)s3sBkpddvViqakMZR-obc zCqeop-JaL6NPnjGsSZ8@DKNpOw3d83pG0n2Rd_y~J+Ii554VKLh^#l!jS~0eLU-i2==yA`3KR04P9Du?`xjIseF6y$aV#f)=nL@boY1k1|V;fB%l-z z{gp%+;Zr1lX$c-2qPdqquvU!HpAh;aaJ_PlZ6Twa%r+Y(&kT?Zz*0|j;rN6fhv6)r zs}s+B8MDHcm#j~f%b~V&|A+c(??fMr?62=}WR{YJdB_3%6;L6``pBvfVPvcj=E6VV zcY_&*;z@v1UN}NX>rp=n-|S}Tcv6ddVlC73*gw~!2-UBo()<5QYK^-rD5T4@i?6)FooueF~~^x zwn+BVo{-$~I@dZww;hhAfS6RksniF-54xLzV7AM)&L`06;*=h`21Rb{3(srEq^+3Z_!k`jNELfTl1#zvtIK@VWn66Vk0$8?wrN5u|I8>839U>ZGoECtZ%_^!FbXTx;I zp|B!A3hpw-yWc%d%=Wm{TO;$n>2B%MqXL~Oeg?u2_c4)ZHoWgi3RgIB80K|A?uSTc-0;BLXlS z1rN!oi=}9zaY<+%Wa7IlSR$Mx(#K)n^^_bdd?o}V;oEg)iE}185EmAf{){#nvwgc| zHl7!QmsdTLZo$a^y^k=21x?`dmlGjc1aJILl9S|V%~kr4;hC+_7%&NVWjpATQ6vi- z;09^r@XD1kjvMs2imxOn1eZG+Fl!_Zk+C~@^3Pg@nMkEca6O#Rz|l%W1V^@y8P4I^XS^6^>n$*`ts`Jd(u2 zwc|Wur!-sr6I@h zt?qS-vs0UQoxfU3o<6{Yi!b`-W#>Abyv)B;t)Tq8GVmsLn#;-xn1?1Q^OMG7?++^g+)yf9| z4GrxZ(L@<#95>ZFAGuboft1E_$k}r#HHv~@x|*>>2&GoA3kGh^a}W(wD7In{qKi_r z`K<8;J`*zMThvy}=s^=X{Y}!sgOPCR;Xo~t((z2TfLFFOkgkdQ8zE8ll9`ZF*?%C9 z&lH*Y)m9z}z3sGC2(p{xxg0u)ODUZI7}2*-N_ZOY{G|4i9bZu#QT8{nu`w}**&WbR z?wKb}bSg8Q;%1r67*T+*h`QXktn@&{kQ6XTmwF+lq-;y!_cEETHu9r#FbMir)=!D* z9#aO7&+fE`!F_jsu?(dm7#RNI!x{GmjAm-TA z1A$GVKV9lWKMyarLPt(dsD-$SgBh|piwt6W2C$DnNSyM2*`Lw-oLedDuUw?;l@u>C z9zq<@5C+&hd;u@?>-}zKZ}N zXW=Q`pIXbI+zT%pSnp#MDE~@M2V}BUJ$cgOY49RsGeD(PLcKfJDi}Qx(k8XE zpr(R3Dg|lrL@H!(xJu@*<`U<1NS`9suk}0~GC?Y~FxcHR>Yes0cH4P*juESm#k+s% z6&|5HoDi2N)A39^kYJb0XR+XBh?oDGJ6TgkfG;>`>%rDW87!>0TQm?% z5VP-Tak;~Z7Hk&2x+3KBWmp(UJVq%wn&f&@AOq_IEWmjU7>>ftO}FM%AKljG_u?sj*NF8;g<1>sAYXH|W1a z&tK=M#(4%Li8RxF+6N~c!xj}}F};{xPlOrz1(4WIYl@gku;k1|b^4B%mKuDuh$>lM zUY~~@woY0p?HjkhZ2bH3Q=3c~_zSE80@`XQCEd~6#d6d<`I+psRagpdLQJL8H?B|i zqS~^A3k4ecWhLneD4EfYfxalH*U31f3>b&xcA>CnfPmq|9iLgaQ}DtH_i3~P@7|R$ zB8I>umu6X}{GV0!Fu}NaXt6$`2^-)Iy^Sh`pOr}K4l2|w39RE%2+EN;VNx*d5xlrY zKKpQy@+37|@^n@w$f@X^L!ynhIoA#l)d)js1&Iclw&Tz4r}F8uH^7VR+#Y5LFkqIp zFNHF{l$6H}NZ2DrPgS`5uIKIWMIJi-fm5U(Y^K0H2)l>rPcAeqlvgPKoq!rc)i|nv zehY=4utq`B6c^zZpKx2~6Nb36@%@*@o>f&no>K23Z!0l;S!pcURb8AMb!!rO+v!i> ze2kyh`Y^@K+66N(O#Cv~<*vXSyBlyxCW{2#k`YLyd^rb;!1t@>ouF%6DO z-G1gV<1?o9+R@#XDGbiNieKw8UXjm{=K^n|c=)J{m9qplN(faXETC+drUJJl{TU-7 zm(H!N8G_1HOqz7r9fHSn6PqRCH7u3zarA}kE9S^Bds7brWJNX)f?+Ha(?onZy5jTd zB;}&QmcFQWyc>9}9{DjJ4%HAxV1r6N?q?d-dr(|7?udVVfx$S1HlLsm!*E>=lquKZ zzzU(Y;T|tgS_`niD2!&UtM%oB%Peuz=Im&J>ZV>runjSBWx4U90$5_?-A+L?YC>+S zKicq4nOk|me++|BNy1lj<{}3!D^CLMryyE8f!fkX#H_-l}i89gJ*h z@RH_jtu)My6d&%Nrkvlo=gPW+xx@S;MNW)L^ zl&yBWP&4w&`KEpdVKuBn9uK~>xb4=Oup_g=gPJGngtM{Q6Y&6ov2L0l_A4Z%c8OOF zG_vqhBHYdjN}_Z_X}0nk6h=M-NNfSdAE|GTuZI%Zxo%Nkd#!k0*unP+iIH8cwm0^ye3yMlrU zNL0g!sa``{p=iio5?b52^iaTUD;2%Qck_)#FhNshXNDmg#A{ajASyf_t^)m_G=72n ztAlvwZWD~S45aF$CVK0KL=J$G0g{-t7!;WePK3iOFZyspC zlyte5I0YR$?>$%q*>?SuP{s3+*1dMdF0NF)tW{w;GGKkr&$CM+n7RN^HLdXqFzexQ z9wD$c`{YxwUso7FGzF=NoI*yYO%B$)oIWno1S>(gyvOmW`!jH&^v zyb?{p_>#pJ@RXt~^O|Za7aoTgxW#Ighfh9|hJ_-|dSdxP9_+uVRR}{BQp7qPL*vVw~3zV;L-kWZ=Mw5Wy@q3a*n>JFp^?xr7~NhlCd6>S`u zg`w%e=}MHsJvQUkeHo@?1cf>Q>?EWrgu}S8DDwU07+TcoEVIGK_a1wJCcnF$eA(J* zrJxD8As>FpWHqVC_9`{P+6^=xKM=f;xuV^sp&g`1qhPkmS-t1NI@kBHnPk5@(KSz} z$(xu5-7*hbE82|eMQ>ziMN{O9#)YT*oGV1T6f$pM!iJdWj#rku)sb&&>T31s+M7;e z6DarM*SN7j&xWL1YGHJ7;D+5!42FoR? zC3GcqO-Z>qUM?xpw8m$gOCe#ZNNxT3Y!U*v!-FL_T}<)&${i^&>v(D_aaIAuGULLx zVmGVD2b`bJzqqftPIvpdIlqk1VpdNG%+7pbOHdtf-OZwm83;Q|L-La(AADipLl+$ekF_$Mb$wPOc>s9D$`O0`tV3D zE6hkG;(53#p4848tDZe2Frt@8mf`11HU{#Y#;nBJRl+8NWst_SUqq`7Nm4|rS#Y?qltQ3aZiC)`ov-MG{Qks9oe5|+#NRi;I9P#7cNu;Z zaLwHNgyIcdebd~t3iu`5(2k^;WN*iPs zc=V4C7$7|p2LSj2kQNhGb6-6HdU)%(biH3r-Dk40u2ATkTH?9F(NvkCr>J05tzoWo zF|-=q>IijeX+uH=)Q3Z<{e}688LwZI$UsMLLtP|)*j=n;@sok39UwT>C+JD`+ zVY+SF|2<`uFarCp`vnFZ>>X7SpPJg{TQPO5c$D@a)2tpuY0D~9f z-!zEbn>oR&g)s&~PS;AybdqhZ$x!(W19ykLr(3)^20KEh^@s>V1-{X@QArbd`tmaM zMywgfw`F%Onh9eTx_?4$Qp~h}zTHdy^nDQ|mHfek(BCo3^dp{BLhfa}Bn%0+-4*D$ zNDk+Gk6LWH9a0on&{4HhTgvcxz>^6>XuGfG9rD}W876Xjsc%W?K*GfW z0JsLc52JE=&i3E$H&YBeh>XbJhzE6 zn3(4$D-E0;;teOQ=m~yHBppZ5uku6Mq$WiIZtEit2c#$dj)J}-mE_gUr<}+~$ha(~ zBVBGl-@eP?sFAwi#K)Iz_T$CtRFGoA;@}w{uFNOj=d;{4pU0ivQw9CD0@~a6l9Pjg zBW*b^1B*6mcPGHHH%QRsva$UJgt-Hqn?>NQC2r``f;^}1QK!?UPP-bBT)4~7;f}Az zE8|(~@dlI~-P7)E&vLts?$l0gb(`nx2r8)<+2?45w*78Z$yh>e$Kdcv{f@V4uk((- z`8DqGix*q{See&H8G`k4&s#&&e9rK~ zjdVGw8`g9EJ-Fs}(g`w0=Z%b5dGqcHXD06(dVxgD%UMfJ>p>vn`Es4p`G!w_C}P)P=yA8}V^I$G`y3vpI$K!! z$^rn8i`;$D79sdH^G>I&Vmo{~kQ5RU;wImw-)PF>xXv`MSd;C%?l6prjh*9tB~7bY zJ;~I^vvcFn)47G+^LPs3b$4cCX{p^}+s|nCFt}Ki1dQ&7gM3-i^C?=ow;BjXEr}uY zS?apa;_NJ#U6>+%D68vpwg zcK5|&#HIVo8_aucRsE5q;LF=fh#g3aKdZJb5;zv9 zOrGzF9yZ*1vaSe7L9`W0Q$Ztm^GlVn?V+zFnJ#+G0hOALF4J+?ro;8r^X}2_h9`5B zX`Wrv&;#TS8_r`k*L#euf48FqK$A2pbry~zO$1)@bZy%&H#RqV%+EK5-(L;}u?;T9 zuiv#gY+vO$^;#aY-0sdcH(ioYNhS2WXEf1zV(_`Q=VuD+avZ1f2czsdc8kS4$w@+u z#|=m z4!3r`Zwc<-(zWZ@*$N}Xs1h%0zA3MZm&627Mk9{Qc3tbe$6<-4JkNe+!~N-+9}tl< z%l*Z{urR~ok@(~S!=^2pJ)V5@!`Z-=eG%+ z8PBCjeVMYpz`!|$=jrpe3&|PJiS#B;gL^0P{O4&W(8bV~VJCvu;V`1Ey%J4@w%2A| zKcBF0IZ#Kx!}axYOA@$o1cTV$x_3ky%fGh_0!)gJ6g5)S0%YEeF*J0#P3o#9j2=Ae zJU(lG3VlB7I-VIWju`Q|mutH$HUxSs0cY-F70YJ*R%b|PUKgatbb&rfpRWTR;*;r_ zml#)F$-h^ab7Io35YVF$N@j)L*`A=PCGLH%K^J!*VWtR1}%y1 zh8N>c5Pt}~KTZ*Njo0-&x#)uI4RX^OU!P%px0k2uocDEWr~TX7GcVniXpncb+;80W z-QcpC_nhc^Y=Y?3ey+yK+O0(2?ELLDW+(NVt~pK3`NC<-1_=o@d2qAMId84t<4!#H zQR+^I?TnJ6UWC4BYkX?E`7Vm;%>Z&^BGd^z@#ZM-jge@ry)G!fX4pZju#wIEtz=5~Wf86Fwl+_cG=8LQNANLV zt6!taz-gS>EQiOg??=kFXhNTQv$VCAbFSw~)>wh3gOEfNaDczB&$k&6Vex<->gwne zZ@lwzHf)^ox}IeA7#Yj-IPwzunapIUtE*S<+|-_hqmmYHc-_M@c5^vt=z2DpjdfHX zzicYj7~I`m?d`F>@)N8P^6s(KY|gj49HZwYY0A2Tc+KY`amE1s-sPBcJcCovL*M0& zQXuJW)0nF5pfx$URYytprb6{DmKMo6p8HugXPy18BoRWA*4a3Lc+y07H7ynfKTJMvc!+ou#Jtj=QQpXY+&q`>jG7GJmhR{s9mWer|Uj-I}% z(_)%A1}2sOh`};AYzR5NFGnxEb~;O0Qeiv+i3rbJCM^K~e>s7caH-HkbwQsOlYImt zfs=(L6-mq2rIc$@G$X&T_}Cc{4DZxU=8! zEH&wi^eznf>6pAGX^{o5N)l-&;?0I#T0|8!v0KZ^$_lz4QCr$&@$V-|5@js9 zprr8}@1T1E8_f=ov4``kFAbuK#4$hHF0(K1{F`_X#5##{A6?_)vMwp`RXaI+xw*@D zXK4TZQAB3fD3IscWWRpt-_SU-0HHr4q%kP*KF{|hHwlWybq)Xf#b?Ii=Jn`EF1Zj5 z<=-QZXaMM>`e^^ZJ^2t3;=7Lv@}PEwMf!hp;HCdB8~%UZW9lXJ`5Qks9K-K(vMfpD zQTVQ_nx}Md0o2s7E>d$nvzkii5p3b{T@BfM?vwT2b%YWF?!s?)JlueC^-v zyL(OkW%Nb>0$=jrtqH%^Un$)V`zQRvK9^xjuUFWD-KLoxCv`anFSpOhoDQx3UKZ+& zXVo=}^bTVCtAd#{E-(E2T#hE4&R&Ka&$B*XR5!T2>`Ex!I4H$cNkxO@A~P!)ePEo z-p|GUxQz(sLVVA@e{phJ(vXad-O1d-AWD*@3P)PXRK6=zL~#J^giy$;Zp$( zmOr2LyGzqtS{Mq;ekvR5@mb*}_5Llp8lSE{^?scbwP8cWb%vhe{hqN;q`B-+q2F@2 zu>Z#HCo11~u-wpdb6ewc79=W182BGb06%Z1gc0}J+tqE&de?r%R40#_xAdqD0V449 z^u6=xxW~I|cX>|Gb2M(quSTy!Hp}C5Gw11Xh5T#J^8@nxJ)`bUxlfkXTsD8+_SDAv zD*8LWOkvY@jppm0vqAa-0hTiyH_gGl`{>w>hnvmn7b)d6*h=aS1zb|zJB%#%@6t{S zd-r!~CGRI?=DrTD5#dtT?O}coug{u8V?)^vGRi>S*<^gY}pMg|>@yqJ`a$?nL`kdwjN;w%tX@ntsx*KWMsB(UzOtcOA13&~>H z`}Mu}t}MUo9{*j{P7~)xw(z*|buoO(d%tg{Av>qXdkS;-2ZplDqlDp8KO@oc z0>+a<>mM&e?}z9V1KrMJn1ZmHho!M3@toFY%6+0kV90qZe9hb5=H9#SP!ygo+g&CJ z;o`s8w7)93TR&2a<#ROad2S^#;IBo<*)(sxOs(qLEXc^|c@2fS)fs3qnGClRczk;J zIiShno%-EtCql6MW^qX0rHXmY)_rq^(q$uIgY$m!n5c&5PS>yddYeU6Y@lkb-K7VE zujXvuqec48^;x{GqsNv1e5cnwQmI zZgh#~O}|$nyVE5Cc)K;Nh1t3vbFJ5}p?A7Fy8BaWXuMD3u~{feq=J`ibs@a_uh!c7 z&-v|p(SGzRf-jX*IqaFkZ2xIT2zfliuKUsc$*ZzJK@iyUG-#gvxUbs*AA^HspYGbz z;<$Hi`*v#GL~gGC_9{Ecmp`)F;yyGcyQHBjNo0JY%lf);eCBPbD~8N{U7?xj)mUeD zHX+z<{WuL@{d9Mz(!syw&-`^BW>f)Jng9L~`y1T`>rJq7QMvK;*uA0G1Oel`?*nZP zZBrY`2QNUAwQ z$8pMTw`U*09IZWc)Vj@_`wYYNtARDIuR4#he9yX^-jBVn_Y8v10o;D=rXxq2dM{O$ zYu}SPxvOGZFXAmVi(9Efu;1s0F1b=$jqSZcBcyh2-03?oZDtZ9Lg$eu|YmC{Ft7JbM}U0-n!M!yXN2k^0X=K}*0FcMq2e(oq`j%Z4Sntf!w&p~^!4 zQYs|g4}!{v(RjE1gggcq+ZjqfKF;_mVSG4EJSad4tTJ{QxyXYmb|o0boMTC{7;1}2c8YSl-(`V98}x|hDNzCLaM@b`9FEKxu~ol{v|Sj7bTb{SJGE&P@xbh9dx zS_7{xFhMPutLQXaznYUA_Iu%Tr3Rt*7sUppa9_^VG&Q}j6R+Nuo@qv(nN_e|^t(L9 zB>p$#V~2mULWiI&6$=tocsvHwQ<%o;cx}%T3?q(@vKEp~K8m)0Fg9>HzzFYocZ;}K zq6O-V4y6h;IZ1npi##j)fX?;#l9g4(O2x-WBz;INK%CoX3Oy!jQKCxLY-!_G(oQSC zoqR{VClKzA1~dkQ?7wB9cIQ6C0ofal%wUse%pj9@T4|T)&1ya@!R3r<1SaGw?QGA9 zP}E7NCEZf|<2Rb+`DV7e_W3M~thM&@nO-^U2mRo;gEG`FJ?;eSgBgKJE(8imJm6z> zP2p%oon*A}_GN`cGoH^1I&BaiV%7c=YkB;qdf>Tck%xQmNQbzTM_(=Gn8$(BjCgo4 zqvgBl=6?vp{u_G9(~1|0My^w`h|sPtVYK3)NxpzOWMW&mpr9?$;c1TeFHy!X|GyyU zd$!b3Tu(ico_Mm^D8{1d^5f?{J~bsby%!^X_>;dV=EwHqBPTF7pmL^^By@EvvMC9j z391qd#tN!pOgbi_>#AjEp+9o1%x1B~rekwKVaLP)|1#<4ogWMwOGkql)++r4lrixI3Gtg83690#vF?K?03G{4Txobi8TG4Co4p zH7;&^p<8nJnGzv^Z-Ox3Rxs)EU46ECq~W&VbI0W_Yo>KwJ#Byy&-rc4Zqi14$@I4T;2|WzFZNDF2Lz@PR$#!-ye5 z@gP?ZWkKYwAVD|K*&2IXCmJR)| zY@ntf6-j`9S)zqz*ypc6m!7NEn8j)=@|n`pRZl+~*{iDJGO>Y}j%b+t)rHZEugoh- z(*M)mKLl51vR&|_YO4z~;d8ZutH(O>x6G8)x}SIQLM?bQY93eJ-# zF&%<6*Bw;1XQcmyH_Jz4-J>Da_D#65t;ZYi-Gb1hm%g>aK6~Zh2*8WmCGYHg1~oN#T0VTjbQ7>MksCZd}h);Q&+7Dl_pn$}h|^t7}c zx7f%OXHsH1qIYX}dup2Rd=8QylHyuE6qF*8H+{073~JCpzZ&74337@+-1?lXubENo z_vQ4vG>>%l<>nVFgKXKqqZ zP{}b>1-T#IJw|&(ee-m?ndVm{-~79Lmf6PW0P8Q@Ehz zNbB~bEn4j1tZCyWBPq%89U8byX)$D!`Mr8?P*wenLBt59>v;n!+YAK!RT8A)N7_@! z5P=+Jt!-79hOAsT zx3IKO)U|Pi`v%_7(IiL94)k>KT?+=)Lhbv4uWdVa?|KBUuA((J?Qo7Zbvf&E0)*L} zkeb>*Ru%`X9JcIHv&)*8(1$k0Hiz8rcrs6T-eFaq;D-nu1hTTz;b4kjP#h>KA(C*p*rCL2E`9$TO~eAn#URciq`YP|_o)j9~#Q@{s)wN+@X}!_v#Bu^1kJiZ{NT!hjn76dUv)x{ zo*b*yS{D?$18GFQq%@9a%75^g5YdMl3COGgWX0rYCytwC?sW*GxMHeQs|!Km>PJtL zW(AlJ>JeGXKIrQJ?;|6Tw8S%#) z)3FgAi=l=J&fRFg@;|fte<(l!*@O*2)vPIGb|PJr)(vF5pnrloptT(1 zz%+C|=9)f6kCw~afsWbUUnC&YzRb!(R5mj1N|dP4D(m6c#+2x1gEV2@NT885e%2I#wwKrU)%sF5Y8e@X8z$rfjw~`_t=yPW zexj9PS%Tq&{DOf8qka4y&nFp{37L>M67O7f&xe>1_6*k}3G zEJTZHbU0~U4LTA=piU!AtWndrGul3KG9>U1i^mfl!HCZ~Hy4tY7pU?OA{^@n$ z-m_-Sy62vIX6&|Eui!8*SkS*1B*t_)J zs~tK~q_q@eA6RvB=FWk?0e>wGOFg&7+v)nA>$$nA8OEi@E_2A%-B6DcnLrNcwW`gr8EaxYaK-jg?VB0jrNfC$Hy6M_d9m%nb$nGMp3V+ck&OUH znFhi(uxq_H!c$+QC|3!R_e7KoNwcK~b005GTnQcPRhPa$(5O5Q5XC_YX%eE5?19#q z)d}jAKsBm=!Xg)jWFAI~H7Z{E9o6VGkZ@(H)sRgcJ*k59H?;j)wrataXN+2PKhiU> zOrx$zYfbEoEjC9MfK3JtW;F12$BMZ-(YQ@E_3+sv2C!va=z2~wGh1ZcwZqAGLm+K$ z2AdIgM>Al9|1s!)20NatTthFKA}#CMjZ3D%>gCiEl?f@fm5c@VT$)s8`+=#X@D#&h zQB^%HIgIMe=3f9qFJRE&Xg`FI;HB5cIrZLNg9`FpoDJ-to1rY7@@L*|{q2fb9I$if zUGUW-;muF*C6)6yaR9wp0N?>62#XZb;ap!O3G|w!g%<$9p~_jwd`s%A#~iQflX6jG zv~fWZ^% z^G&|?JX^Dk5wOD|K_h7NGQwwdYk_47c384$|K)Vz87%D&InPbX8OTa?Z;&*#3tk7C zr3^t=pz^6h(aon}2`zC^OZo-CIf(92;UsX;lk!pvUSeQe;DDJ919aV?O5b0vS@}mP z<}(E(yP#xF3E!O4$AT&o=>Y1f9L^vHF3Wood9(Fyw$z|=4OC743W}kUDkT1ot?m9p z&`DfHq0F^-zEK*>;+VX5+YqMxw~8tj0BmD)D-U+6TdN2VxWs>PEL+qZ1D-G#-56Tb z0@egt)fu9ifFUa|_(?A+FV|NR5=@}+@fFWyZi3`0#m!EyX^_v&H2G8}Su%9rvn9?h zM%1ExWdbi~Onq;e?X#_DugMDxf;W{H*zPllCbRb<821g~`v0G)Rb}Oo&oY~j!>rAB zS#ME@X{7{n41X@D@Jj!D4f?7t>FTRl*1rzOaXyicd}M> z=@%nQtK-G79|MvHz%b-xoA?!JqgcpvzR0@x)pZggg`Z}x$;s~ZuWKKSC zQ=CcH2cZ}w^RxrzKoxAZwZC=v0wkgUd#;`7YTF7YhNZm^egvZhu8zs*eaWVkoP#u*B%anhxb?C!Cuo8+C11;6l$sH={GtWOxO2 zQD!XF?6EA4@cfoU2d;DNM#IF8eScbrYo8Tmv{t=0ZBCiRtjqN{n#56T?Vbn^a)jkE z$3MU^Hf^gMHxHBUev(%4IW#;Os9Fhqj7!dM0IEx-;jn(v3S4!u?k5YTb@!KaG}a75 zX=&o5)P^E*q<$XbFMEv3g$>^>8jkv=HloB8v<$iN=hsh_Vt`^_!VV4sG1UIrBCZc% z!eV~!d}Zbcm7BXK5eIyFJNj8xz$_s25zNwx6ZiG# z8BTwJI`>nmldk+xPHP0vCJ1nesm}J%l4K9(Ou)*TP=N+*H1WRPya9<_F;Hh9^|o#I zO@m7E==Ixasd5r=XsYvb(z_8&zmPde_81u6J%lPrh6!*TEfhiMr+)sb2lW-2e#%TCx75^*I5VqMpF21d~J(kW=}BEKHXtkpOh!}A=qN9 z7#Q#+1R-7gmZ43bzCWLK#ZbY=tFQ0$1P;^y|6m!(QNwCm5bSxju;O%Bl#w+JjP58TsWp_(@1`*&E!9HRF@AP`qp@$hEBVVeoS5jr^`1T2IlQ$fCnQ zHH4klQ#(Dv+fxeix2c&&0>#SL)z#^l(~z{VX;l@f;9bxd{PbdyiG=c9-cuv>s%LlH z&85@Yr3oa7Bcnq#r@`P7!H%!}%f&}YKR+Z_na9%d#gNVB5>RR zqX!%Mnl|srEt)?8b3!}5X98E~XA(PA-9rwwwg>rrZ-LDb;rb|s0wlOtWFwC$!r~yk zl9`3(p9@jV74Ncf30Qa6*|^DF&{aHe!C$4#@G(MTrCRPfO(ASc0GC*T< z?Q#h=n<1MOnza^3U&B(87spV5MYv7?GeV9P)-HV_ABi=vo^F=r{O;3!+ge#!S=hK= zuQ1nnS!H>ic3RA5HttTa_^qv1e+0-E@<)NyRb*>}rT0q=GB08Y`FwhFBqMmB2Ymam zlUzdkE$I}HLk4hQQQW$Ttclxi;5&&*EAQoMnE%Ydj33jeZ<4Vg%xT)+4on;7OSm4E zq66ijVP$El&4{Im#Ab1pE*V;g>+vFQZf&9oB057wO!FIgoTf@|zCF-c=kelV&lc3f zrp|q%^3^L6_b_-+HB7c}EH!rO1uDBN_b!=@zUVa8H34uc+j%eCLbbB-cLs8o7SJ$f zGg)*VI=z8#NxrM&P&)9|UoUGw=ur3RQ>2kVD#l4GuQ^pUwRlX59fkx5Qr#>>B4Qp& zLdSY=us<&h@-Kzy6Qumd^Beh3+X0)_`2wsSB2XJ5NMcWp!bdNYj5R6z>7%Gztx47L zk~teqHml7%QZUe;y$zt|&}AoZ@qyz|S_T8ybViU~K>!q4=_{20 zQL7K^G(4+7;GqU;*D$*N<3h+QPgBwFZt&vh;=E9OosU2sb?hB3dkBag|78CztCKT( zpp5)eckPBcxNLJWuhvTma-<@6+W6Sds%9i3 z_2mo30r6U(?mj2dk1%ChVXB_mM1@NR)OYVHyWhN5CW5+QV_|v~233AP2pE!gj)h zN3fj#yOzpA8r3j4+gd)_b+#wSNePdv19@@X^OrGZW4AcN6u>H`fBM|Vsz$0KQ$-&o zCDWpw3nf7Abjip?mkp;Qc5$>^e=r3}`NHkiX!azJ*;Y!J&JMEx_=IcOr7~l=EqXK* zfN;O?5#)aeqhH=}lUBLoaIz zxxGVRzM1?iKxB{AZ|iEvNx5 zgMl<*z94_y4idoasDn_3&kFpE+-$hX51_LfVIL)BXIpBGw;VAMSu6Js_A#wID&7ts zF2mMjYOv_gxtbPhrC6ye6_NbajjOsD1k!>@WR3NvgF2~9>Y6r}E&f{v^lSU&7|8{P zn}&;4V9-J$6eAf(x~0RP^}+nd$KF|BO&}4$c4Rq?x8Pbu#jiuPHL7DD>Z=q^cRKdf zOKGOzPX;qSDW)Olh`+MJo-x0+6R0n>W=Az%>7VpOTiR~0xy@{A%3wdQsW$bDfR9ETkS)n2bLZFjJ zD80JI%eeToj^FyvKS(hDn4~6J;(fc52sbJwFGi6Ky-~&~>51vD(&L{UPTV13G^i-r z5ojelKn|!7~l!%iTD2`yMKPpcHX<~jYm+nX>V;hw8?qpF-N3AAJ z1psMNb}z#@uqG^Rh9)f{AFzxoM(>AlFLA4Fd-ZDf!|NG;Jav^>fT?4pvuX}!Tq*qR&p1P z#;F;SVPN%}5P|J{+aMY$0KKz6M)FZgr^u`NmjtA+kxDmgm*VHzgvU}fZ7PIYKUq%J_yF-boRWgeqo zqWIEe4cG`Pw4V+Cu4Z~RsMTGYAc83FVUhTP{k1PX>AuFE0!3i=;t;Y58hT!Vk*4iB z8*M`KswVGq9g>_B%I1fAX_=Wi40ShreUWFEIY5O|U2pl}Gi^V)^p%myY5Oc04n!mY zJ0i9-Gc&1J?N6bi26Vn)5$QQzN@x4*j#lt0#=I1wd`HTcbobz2maMHs@9B zicwTV)$=FytYcIEcT{57(ydqQ=LqJ1Tg(pIVrUSbz7$vPWl`eE!nYb9RSJ&tW9M)6Pe0FK7E!yvlY@LXvDC)OuW;P z`PsVWNZvfN+EnATFu}FN5?0iq0u(9?@5LiM_eaUF&Rm?SbBO3<5haT&L{a98W1|8E> z+O>t{oof9zB?!&kgMwwo;Q9lBAU&swa$XHI->+u?*$cQ15(E>ft8w~B}U@l5V$y_5HC&}DQ%VC)HX{|wTt;?K;I4H1=T_QD4^?tSczbJ zMv~0rabWnx;1)iAmM_l8gH4?lf_Z3nbj3-%&KIpPR<@|FY@9O0nrH+xDH$3aYLhK` z7Vdpz3#xQvtbq(bB*3Tl+N}a3IV>fgfvHN_PES+Fr?+_PkniI6dObm&E{DUz7X4g9 z`Qhq9yzAv`?8+ow4O4e?^(G!q(TxubnuPd3vC33*DM}_aefUfz%{C9xQ<8NusMXo0igR~&aI72__&uf2CO3!2`k)YC3^6YO6}tg{tl4_M8=&bUYZ?FxLTnH)H6 z=uHJ#9%qIc^h{NYp}Kp~T$*G*t0YLJ+^*%_16^Gj@_w>3v-hy7Eyesu{2|ff(%Vcy zrS27_>?B@V^v;K))N=eG69LUsrFQ1(gD5iENO?V=eLn(M8PK?k=+}Y5MKR^G{@llI zW_dDux+jr-nVzzQe|Ei%Zhz=Fu5@)_T5qXyRB*w-k_B~uU@4@>;~iruGXB_REQ9^M`H$J(In*847(S z38!5&)Y=nW-e*=%(iM<@RW#RK^iM zO#ee?g>8wh4}U$U&j-iTYz@)fBy6r3NoxjiK|HLtPGl=MU#%zT_mbF?j2O&nlin1+ zJ3*cZt8vqiol8ZNG+ms68KKr#b(?4Qt*U$CMcVHo zR_4n+r+31q!3lj)WE$$~Z>a!2zC4_k_yfK-|JtIoxcFig5ElPmfjeIX@`r&gYzpmO**^6>E>!y_heD3IMJC zQ3I$I6IN}@OC-a$xB);XvbtiF3qb{t?B9}UK|Tj7@2Iq8YiI0iqno2$ZRc2%4$uwV zXZoTW@2$J!FF)E#CvpE_T%J4{37rT#fAW%dJa1A@^HUI-TZP<0*gGcLG*{5xU&KZFY5Isw<^s9xPU{G$vK3&FpqYR!)` zYZ)h8z1n1RGtpDSWRlbhM_1eVO%^$sA0r;N4BE?!%znLy?E@4Sp|WpJ9`n{DOyHtr zeO~{Jjngdp1b~=0kTO%{FAx|eRb;?=RR8Es2S}%SvrKNE#S=fKsj8492Fn;|F}p6W zocqeE=uOwTbhk;5zwDic`y98!>@pHhI*{cl*COgO-Y(P^EjX> z;PZIra_DiP6?z#&wa%x_r_rKrYYxo27=8wrRfh;#h?sEmE&uHUORaYind@PLPCIwC zwRJv6K3O5gNr|21z2xwBW+(Gj_8@Vr++CB{6(7TlNo2;dRHs5JiQi`W!n-`>K=v}O z)d1Tqwgix&fQVFKyAzw~yFDoIOh~S!?ro~|QJ8!3RkgJn=aPelHMmTpTn|D?8CyD@ z=dGQa#&t|w*O`;Ve@ER7bBPUej)ZCs#%v9T-#8|szxbWF^ivH_6NuISgaAmp0KT^D z^djeWRE`5}?boa^WO_~J8ct06S04PQh0X2xbq&)7n#N_mJ2T&QGA}kx40=sKe-D@I zYU~-UR&4!~EP}RPrU=>?%^rR$Pj`O*1@waP{7%&JWu=6KoGkCrxu5Es>bEEc6GeCt zOf?M+ZceU9UfU6)+c}uS{85pERQ%3GkY5TZRW+^y2sE%JJi|IOfE#$})h&Nnm6-N5 zP~Cc9%#`{xWvNm)XGO#){Jqa=_m1zwRDq8>Iu=59R$_c@#z_m8roN||s&O4xfnTPA zm+L-onM+yyL$rU8lhQfXTR~lZ__>9O7S27X-~v#rY|W?kiz3AgzlJ9l;6{=NCX;>( zo%v3m49f%1$Rl+TlM($`FhQDp@@MtctAm_NFKX>!j^{g_!c^j4AaLAWQ`3`xd~-A9 z1agV9d-j)0;HKahWk=^w3($N!Y+!^)gtI5Pi6+|omU-<48ps1?pr$f2_?!oRbzfq= zftBPb0K-aOu23e!a1(6v_n2num5OAL)5WE${Tld!TZsFW1CaMuS6R*1a&Ad=MI>Mc zizrRLwv)XyQ>cqf6$frWbQa6A_NQde?m&g*zzEO(y(yh` zbHBXqSoL`ABLx4&<4*;qQ@aI?6>Z)96T6py8v68;vHZld)ub7i2`Y-w9bb4!K?RiD z_oo6!u5Y^}NSLNn+eGTK)(H|7$JY+fF(rKpUpteQNuZ0<__0)5z5n?PqTnX?IehlW zy23KK02U|yN5Ci>@yl&9qr%zk=!OCr4xsQKMcp*pgM9$$RgZUXzvQjn(Ww38^z`(v z`M<}_Iug0AZniU5Ltn@}{nHE;bte^+AQ+F91PX%VEst>RIy#ETXjpqgf|6ssFqZzY- zu@+!zOUQX#MOZ;2k(7Zg9ib58l1C6mloA2f9*(@JOG= zWyiih;`GAFC%_pcOo6c;oSh~Z1}!vRcj08!j(V=D__PQc66YskUUSd%Hmz#6+3e*Js!+l^ zTkn)-1l6CqFVAQv?&kqDncRQprVF4wOn7LQw))`y*;TLb{Rin%Kr#aj91pvn74-mJ z8E2yBDqtSizm$QI5st7umD)1va?0pbVrz54@u_L8Kr5nv-UYS&0=so}yEn@f*eE zawv-yG!S|s*FHZ>_y0v+|A8|GijG z+b-`;s4K+}RS@{QsxJkkIP@lf9mzF*uqNj6z5y;8;sOCbX6nb+-m_P(3?Xg}*31Vc zFH5+94;daglLPe$Ft*hVMw}cnm5xw;Y>LpFo@u%cM-fyMeCEbPo7~sAze23{`IBUF z@Hrwwpzs^85F%AT&d_?I68JYJWM}GkqqczN$a7oEDZO5+$SI zUGbpE)(J*@tI&F7h3ViNYxAj{wkR@$?8voNB{G!k2#SxBT#;61b?FGq;-ZJr$gb|& zp#XQ{_lzFCz#N4MtR*Q7FX<*;!BUc#n2?R$!%V1`LgWLxjsMKJM<7sx_UnReZ==XF z8*_SH>cW6F!B$l7IWM2|uHyaGX8(_CPz@l8H zlsrcSK^^ypl_~ubRbfX>iwgU`GmFN}=ZTcjxa!B(X5CW?UU2c0Kiq%t~k|W|W7lG}&hkQ#{;lxQLsvH-ckhyejVhAcY z4v;c{Qb1SZi_W0}tyv-FHc>P@<(I}qzKDb=CW>$3#Rs5u1>! z`d&+mXc~r|qza)2(WOcj;-UN?m4X9p?DiRvd*3(y?59tx&MPvx!8f5JGfS(MI8R{6 zz=JZ+m9+;2R-yz_?293tTv^F-j5_smy=` z37dp6LKym!BWu1HEJ#UZQlJ=rwb|7(SW~NSI#ttX^Rs)6hyyd?d%p_F@F(Tqt`<># zy|YzmJ1ZTA@?vEIqlq-Emb%N3ww*my90@ir{l%4ZG8rULAs%AjGJA01P}Unw&Ritw zJzY|{{(h!DFbFfl`zi0y$GHt=L$ux?r>0D-SnI=`9p4$Sg(^QFxbes3$BjOu|E(4W zf3~%oOk3wmxuwg?Co^<-%6uej&|=rCn*{iX^)jnPda4#rL#$g7TnRQ8`U7=*w2@j9 z9eCnUe$KoOs3~iy+D$MvgOF85Og@u1sAE>I6%Qh_qU1yW8S@i5d7J%tL>iXR`OSgB z!*JT}A6!IHps13UUe=N@H{V$n!hB;0Mik`?M>|+O(u0#X$v6+vtq2P3<=uxHBhtTG zRTzsqRff|PB91uKz6$^R=cr5vdO3+ogCac2(E&`LbM=|D-F#ag{qfnwp#V>SFAWo`5dVE9KAmN>x&h9v-H?c9Vh(;r_uQo zhwldPO+x7Qfj;Z~934M?0GGcvB71B? zN-ZcV$eNnQv4M@^C_i4L(e<&Dl_iy97pqrHJr6@&Kcwq^uI$GY1e=%gPu`xxtqd*c za3Ux>QLN_}sS{N==S@mz%}K{poHT7lL$dMKkoDvK%o_EVm6kc}9f2*ekn8qp7MyUV zcF)_(IiI_V=d+0Ci|gOnCJNYyY?8%T?b@eR*4qyg6mSs~C^>5vmq!fd(NnFgn+#&R zPoU3Hb#8m_Ej1$p$PEK1`VYTggTTQXjJEm{cVCn6E6*ete;*>j!hW}^+u0GdE6)R2 z^A<%)=Eri0CR#6%tMeW%h7fL3y%YVQF>|hHmBQ4({WwKW7gfz1FO4423#6l zij5C^RL;SuffV`DD-rf1R{upj6Y$j(`{&!xcovtjmw4qS)D&VA1513I@)Zm<<7yQR z+cg&B1M+#bw9nKdf_z5lRK*zJl--zu8N}p!8kK$JB!xj2%j$3sgrSgR0B(nQCsTYMkF94tu zd_gpW_xm#~o`&A-6R)4h|BT!E8oCQdV8y~eh#pdRHP#V~Mlh#@<*4Dy5MSOQ&8y#@ zOe?(=%=lL*%*J?P=y@I(b-Ecr=IceA@J1+&r%P=PNSvx{2#utqdN{RTxxwo{HH!?znwF~c2SH*2nK(BV;TI#uRwGle*hQ$pCN}m*~`^~EwW;H z7dfPz*eB_)P0fy{!mv@;1v{2|y5aX2?(=c77%js>Znc89BuWBf*h4GYs>}^zXP3g& zcXaB1bKmjVX=AI7QA_^xg2e=qP}modx0KsqHfTy*XMWZZYf z@bbnF1V@A@CO|szl9Nf|moqxlp^xo;d$K4nnr8UYxtEDld_K5wLr#^ffYtCRp35n24euRB6MIqbjj}SYtLurqx7x|WzkP0- zytw_2ISf)!4L-;`mmzn9TdjRr@n(g5kM^7G^xT%*>c$B?l^h%Gw|NY78ykz@Pgpwl~xZm2fdu?L&J>tgy}^*;B^viK|*1X`x0HH*i++ z&2O!b<>|@3;%bOqju6Tcf$d$?Dd1nO=Qc{nBbE0jY3>z~N{!PFW?$^9$=Z?VVi^Vc z@JhAHvdTv5SMVLH2qg3ou`mc*{=7kJ<@pSJ07z%8@_%LxCADCPy&yJGigHd$GeJR8`=aI`RK)wHi^SgE=Wx))c`}?}XHK|D8H<&x%!H9%mBEfs zxc&K0zKjK0zar_zEAilO`gVqiTL{9<7{4?W<17dgFx%ll{c$MR$0IRs#|UO=7~O!a zEc!L4A#SG6edn_F5K{Kp^xs)56y8d%184K>OUWj`<=o#E7yc9b#nfYY3k*5Dr27HHFvnJM$6w-_?EgcXL#oHhC53n z17A71I}myVGReVl206`eRnlk3u4s&~k4D+|uED1SQ1;#k)bx2TA*xx2Jz7L2c+~8f zQH9~%o~ANd@B53=WuNUx(69Mg6~ITlBcZF8GwoVt{0{(5sPpjrOWo7$bM$+S^Y4WV zUuek_?0wRXM9+KFOEmkspT~$8`{Z#b!LH8!X(>N4GxDX>?41VnI%C@PNirr)C**Cb7#m~>Lvv%`eC`IZQl+gZ4E;GeaN@7&=9yv3v zcu-NHQGGv&Pemo(9~Uylu6gy*rUwKX#uhI~NSLZ5U;cdFL6H}QEfMXB${B#&U!35b zhe!`WG&=Hfak~`NoUp(HCBn<^M6R`QbIl0SkGzD>!RvZ^{&2OE-v*{kT4LvAnP@)r zG1-XwnWzEe!H*p=NT5_$ zn15I{`!nN%bP-066!SIlFrK)%)kLMYU+?3=tP%$W@LQn>#V=uIN!cpXX+dxn{XVMz zR+(&=fI!NPZrG+u*Gyf4EJyErG^k#UOm|m+MEHh|EVo-rFhKCOAs82H{l0Qvz606V zGhdk$D*0b#u4)}y&m#kJaB0paUvOe(iP`(?s+Xa0I9pd#q)Fjrbj*5i?560klCLKgg!{&djs%(4l3LRi27Qo zJlcCMU76M)ITG}bi=$|dASyH|2r2{)&ssCKK#;~*y)z=2GW3P=>BpMSib)Bt!O-K~ zJPENt|59X5mt4eh4#5Fy98bt6@Ud`%<+W@b{*G%u6vR2X5<&4)5M9A_k&XjtL93Y~g^2dozjE)zRVfj`m-N&F&GqN%f z65y;)s{ZuQ^Xx`<{fwe`z2bL4WEPEGHa7TlHy}8mYt3(1>iOC&Ng-Li`}*~=s=V>H zwBNM&AiA*$2tQZ=Ka#oHeSL=|j%$Kz$Q)?>G6rG@m?^ zlX(E(GbA_B+^SC#V=na1#d1mR0#Ad&t$oiU&A;dNnr1euZ)NCPhRHkc&F6d?3%Jj!|MRmt7u$Fpb9IXFB^t!gz+=@qe$#p-kVvQTl z^ByZFsYnA=EE!y>gf+|Rn4pXbB)D^5a^Hu3+|^n3xjI#4hQ0}C9{Hb3w8Di(r!Uw1 zdDvsgsLJ77+tP}4>#wFbLnR*({tJoFmL+Q<@B}5SjG#gyCMH`65FwEo@PL}b|HO6z zYih|dA%?|hn-Gr39L_;=@%%ICw(VF8;>>!OhOwbEq&lcl5XvOPtz`V+F{0sALBh{Q z6oTxD?+Bkh(tV}pxw&%UcNJC~4YJrewP@waLn5M}2qgbgx?h#1Y?#)CPlz_}X8|w2 zHnPBx`WqW=Mc!;({2*R(_jS>?uV^&;iay;Hy1F6L2_Ixl8>v8D`Q~&*=>R$~shrxm zX+fQ}B1jqkL07(n!SC`w`pz!d?uC)gNEZB?N#s@(dU{pIkypElZ~DpxkF@EfX~~un zHSyfHLQNWf=ttA&V#v-b^DvYcZ9#DRK14EH^Y~5(+^d)Na0iH84!JDford~RbGzl3 z5t9)Y4ZAjk1{n5{r_GrL(InX>jY8V)1FUeHbAR$kfnp()LE=)F3a2a#u~*n4GVztK z6jlIq>u^XEu2$rM@US~6`^0GiIgRk2+Y^HUw+H^qn1i@cAD*wW?EeZo-QG7hjDfHx zO5UeLbq_sJAw?Q+BH!a~P;XDS2c;66vgx2{RZ=T5)i7D+lQJ?hsqjFZNolH~$6W*n z1?yFDukbjR5>Hyl#^pXP%Q&9a^4`b9?>~K+Q{t!8PFRcR22Q4zgj8}_oWFmaDwVU1 z*4R+1BeuGNPXZeDN+pX1ny`;+FNk#s%Uq;!+2S1e%CA6VLr|~V6m=YBmJ4v+)?368hI<{2xo%1K^N9Epr z8;&FQV{Kk6CPWF&$u4RBWJ7w2!Zn4SI%nZRkP% z+^dUCdkYxT+F=AeW$WCM*p%4o3tp(Kp#e%5`1gtM!%QT>b&W0gu`0i@gQ+EFF*B`g zPCBDhBJ=5qN@ah5vYSiN7UecH?|%hF&6if%PUlY`639roXw$`Db3MWl=7!GMbX+wfmEF(6RM>8|4R+I1zo^SN@%`w<@US#peX# zx9~EY%1sG1{QE`ryD++6N#{EG^Au&GWDP6_z6g-zU@O!O}BO7)73=8mfdT zdVz6}TC7%)2xZ3hhsnA6645n{cP8DT%4i-&Rm09*4jL-UJH+CBf6YmJ<;;U&zqWqd zcx}grk^snn#>Z0&3%3LL{DU3=g@k}a*Kvmide_KQy4>ZZ+$S{}pmG`!M6U#qiB+c0 zQ*}x(O;jcPGCA0w7wbKp&0++wcSFxVs#HRswu&@(`Q2Rp^wf}KQF1Wls1^QHY{c=H zV`g_o&@YzaNh*IB)d4;b)unr%z8T<;o;N~3g{KUuyN;4sG{oPjW($@6Iq|_&6DjG# zesmncV9L>l$Ncj=We(=$UE#i12UB#cba&Scf_)T}!0a@qT5!mFZMawL*iKo1)xDN385q~DjbukIw*D$J* zpN(3B2{oMzvzLj=VjvTuaEU_ThpD=)5UIs2skbO{G7Q*6P?Cu1Lw@RBqVZC7YhWG! zh;$63&`y8;_%3j2)&Xr zeNiIATFuSvxc64M&fNREm$E-Tj1jvW^J?bpVh!U_i|=)+gx{njF@D&6)g*g)h{@hf zr5(seYiq{vwF%XS2&GyZ7q!ee?+pC=c~IjKtoF1{3!z8+%k&^8-sF(+zcs)^C~dHP ze44Ga*Rmj@CFkY|gvcs1_t`xSW^c$g2Z-2vf@rh6K9Mvw;v!B=)`T~iyY5)M7@yx}mw2C`&^L75~!< zfol7Dj@!3tB9#n7Obx8?Db;vW*RxXics2)q07a{vr|ojJ?ln3U4Z*2WhGCZPBo-4((34L$gqZfMY~SD{Uc%A-ZOc588y&?nfz%_ z+!;F`1yxhxWt_rd1=;VjuJWBdCG3P<`?ndTZGci76?6D>K+?|hjjyu%aS5~4<4@@G z>CViO`>h$1M8lS_eePm*PkQdtZ4e3wDBM!3a|Zm+ztdz5sUL$X0r_E7o+P`&iVO~9 zI*Tw2%{4I(ti&WM8$~V&%ysPbO8z)pL?~Y*tGP|j&j5| zSJh(z*o&XX17}2<|>y=mKp@=w$JbpN>e=rQ!e00`Lq~nT3E-A760W{&tYBB4pZ-D;{C);xwfg zASJmXpC=-_xu^N|uISTTo{J!2-$$OW-{o5iE7z-mm}r`7Ww4<|A58@L%U0|X@g&jR zW|owDJ_C~2R4NrpPM(GHaW7O*5wyIDCKZp!ltZ(72z-wtj{?7*rLpvJBFgP?&F^_S zFCzI@9OYY68*iJH*0kp4rdFtGsmy30rj6rtu0EUy`!T4a#_RP>N7C!Nc`1z#RB=g+ z6|D!eE;H7eRbWOUoO?_=@3SKOxkt8JZd|9}57VzzGkv#^80r7;NgJCC$^;Q9fbX9?ng{SkFByJ?Gz}u(4h0(Pah<2H8DfZp`ztu=3f= z-kt8aUAFD4Xf!xhrYYQv>e!V#Mw`Css@ifpx$kHEE%oxOhxEtsZ4l@W65ZAXBjVVP zGI7Pe!(}sFvSj-6z)A>`a0qpi+4nz7C5#-6iaf~|-pky!N3EZF>t>ekAVL-F@3oCA zEMi|N>doH_*n#K0EKky$-i(4iZyyqaczho;IbSi~ zVgTKOZF2c@n#leQ6HC6zq z@Zold(5sYE+(xkgY3f}I=kj?u)G&SLX9*U{}7npoe1irdN^N zm-Q8mIiK;n%ALHG(S}$!Y&N_xCh_l<1^F>Lp(#p1C?Pd&2uNB-4Acn=$vve9vw(D3 zQq-rU>-TFZE`Hi-zb~GN#=z(HQn2(C!H-^z&j_J|MZsnzjyVlC9IzLr)w2B8p7}n_ z2prEZdzUonUVuDSi#DA64gsVZ`*rC@<@Ws9#HICKCHAOkQ~Znf7(uozWqJqt*oXSq z-`jbXYYNM(eG8rRS&7y?{hM)B=x1`SYc<*zBE&7-AYL~Y&`}+ynO`f;T>xb2yPa$U zJ+}TGq4T66f)nLp+vY6I^GE)|5bT-^fN^tENe)-hP?-99f5uqR4u&w)GZ`k$t8J2a z?h|dGgds^{*{Zm+={~Bd3Na9ReC5QnB|r$85PrBRm|d>^*V=g=(RkHVA!kU@f#vsv zQOqHYEx}mx!_8;Pkp;-KjHJpC$~W2}k`aUm{;Gd?CZ$pP9Ii`9V#uElUsUAu(B#N) zEbT$a58K{s65KJwnI%3aT815mbXM)-pt4}*?XcK6`5DyT>I^6AZ?%74rUS9CRZ{qw zezy4grS0brJe#HSp3qh6@@G7N^wy+&*u?r&p{n{sM~4LJAacYAQBoEYdGXPO2q5uh zUqxcYJ>q@iv1!&J`=d!Mat({=}2JI_#kRZXS3D#7L2hq*(>`_uO*i^ zBW^=_Dc;i`u48KaQh9+C*s}x+PVMWacZg-){~u9b8I)HOr29f}cPF^JdvJGmcXtR7 zAUFhfhY;M|-3dX0yL)hV*u!^s>sEzdsiK%OJw4rz^q^Mu^*zF?TU^9mvef7ESrrig ztx85eJ0)^x-)g05>|_1bwiOa6PGsC)b7j}#=6W0eG`_ZK!e2>tIqhH@t}ML+C@_=5 zmzJ~j@eiuZmTQfLn|pDgIZ_9n#m8Fj?I#8t*c4m)s6lst-Ewv6j3&j=z<^6?QN0i| zo01p=jf+fTx<^M^wItV?Hcw>Dw>KmCeSI-sD-p{Aay)^5jdmj)mG(=QI__uQ8m z+l{KZ;4@lY%mh=tf;)o=0a`o+ zx(1K&IX0FwT_X{|&HHA%)6e0{r8uY4dZnW|=W^-?YmzeEg61evb~1Q8s#R6b+d|U= zA{MiEmg`eSpZ{!*08j?f$uzf{Gb1lw&X|>fFa4D$w1oPptd)Iuc+H+9CRy6I^E~f- zDxM1FS2FbbxOU}ItF0s*ffmpqY2?+{v$5@^Y%Wf-hJ4=bi;v~MH09+M6HOnQZuS0d z&6}yzaAk`3>q&t#nT7W^jOpYVFqfC~dXh%iCh=Xd4*-(sP816eSZ+cK5o6!-onAwZn z9Hf`|Zgm7nL(pP6%G!u4@@6grkH)TjJKcm)E2Ue-THA;Tv`a{d0WSNn=t^D$)+MX# zrC5)OOvnh2HHS{j>RAT&E|-DN>TFG|=_x_*wDx^W+D0VW;$LkKp}zOe%4L(rqhPW+ zWxv=j(vcw$!VPfutEsBhH=rHwR|;$~BLp7HH|O37O-?mc?5|CtK+{hPB%(?GeY!Ix zeVH2hJZLZGigfFPfZVFQ9nrBx*#3eo0s;T5j2byG&}n=``8OElhq0}K7~t}qOd{iVGC3Y%z(1r1sOf{FmHOje$?oH~sw4W@s(>th!yiRNqiw)d9}gH43J06DX3R~U472q$OpBWiOI z4JDyI3WLl{S&w7>w4}mTwa8Sph)B5%Tbt$#?N}urn-5 zpE-~O5wxAZ&$i-y^nh|}?wtq?_OtQ_N|_um{EjFEJeUkDFGEaZ1!GXLYURbAHdd$s z1E9=or*mp9w&#KniikfIqA9rJVOjBBGu>qzbtoo}0hMJ+ye+vQM?_bbzG^jdPg-&M z)d#~l5s7D7MBx&nC(5PthbZ{=qn_3S{%}oPobb0LY=6xWxfYlEJ`_?~*cggq9yp;* zJk}U{!ZytjNL(jGj_hpQpD^@+X`*AtN0(6V;YOJW&IrLRrhkeJT2cdRfZ{XycM#|= zhah(^!QxCMzpT{;!~kmnmuaaS4{~;{qk(MXsn{{IyW`0yx5CmE(?Xgd>~s(Z6%xKR zi?MiLlwW{X2uysQ<*9O(_}7P#t=jA>IWj7hhsNR~f*9$#PZYe8(jcGr*iaux-v^sN9Y>PzeeNp&pPaSX4Lg>N z;8^k6o+CIR;sy!DS@X_-%fU0tOHNGbzQl=W=WGb}%}mZ{MG}X%N|2(y-*dc&h6C3# z8=~i-3=P}ffJ8-GEOdgiB+T4=RY;#f9i&TkYrOWWrQ-N$zC3WuMch30`F#r@KscR7 zE#ke=Nut79Vx4JsyS-AL#EvRjEQ@8U!JMkMcBF{1GoyE8|C=_IeTet@$47|N#8ayj z$4nlDHBGf=EU+YC`Khp}3Q+82@-xmA2o04rtl z^vT9dOF06=I{SMInsFO)-^Fu@e&o>L8ezn2?$l@p6giTy%7K8a%=L$4j@JEEUhxbp zAFgLoV2Es=#He(XZVC;4Egy~Aw*k2!J0_l~+Cp=RHkvNZo^o3Vd$Jgft;2e}_tWYW?4_1XCCWRoJrpAM@+p&g3BH=58{<^i0w zPyCHuuL6Qy44gJzgbh0*YOB&wD={;Re@)2t05tVE*O`EaHEr4d;;7X=NE`^lA4V1} z6(FONz+Udqz6?_UPxRU}&agvIqyk>Xas<{yZ?GKS+RdiXPod1drz8T)w{Y8a-hVCQ zr-ocJdbJq;cADAj@UuyHOg%#tIBO1=XEu`k*ibVZ5XL0LKdZ<<+)Z*6Cw1p)pr7n( zn3X`I9zg- z4W!9e6k_DtI` zZYa@J_TY51EMw*h%#*=)4jj=485)$BSvSgW;%Hm~YjovW9{U7^Dy*3XBoygJbLqU4 z$bq_nHEMs9HziCQ;{lB3IzoD?L!;TYW7+KnxA8eU-8eK~6^RGRmZtm#I`7Vz3R~e= z762jXTrjX;rF0N|$Qd}@zP^>jD9zi*h*y56D$q@qok7FMfX&3YVu%!?A%QS#v_LsA zdvFGQ%0)CQeO|vF^E2nkcP7Z+hH7hTDN?8ZDX-~R5GF$7eqvC1(ujp)M+{N@rEdIY zN|IzMJIQ(3qpNFpsC)VQ{n?vW8$x)@(viFOB|uwDHzSH=iyauKOonZ*gX9090d$%MD=Pmm zKblOuYj5w>KkI_`O+ax+xCS-?Wi0SEtHY}yb~^^K;{mcdpS|9PQ__(w`#rl>TPVmg zV)&ij2X)V};l(5N#&P3?0O+z@|MfZkd*i>Q-GDC_iO+}sRC+g2#!g?zD*X*;N3BOx zO2oz{(kt2pN8jB+pkM~nfM;?9$W2}|^-wl|gu8%7bIlMaRekp2~viP`475E$Ia8-5=xDpOUI)g=9c&# z+PJf!I~ECB8Ii5GMPQ}_J9yPg!~!e}6EmzV562j3CF$)^LRegcM*SAw_v>}@eV3dj z7K^0SRmgd%=IA)}n893=_U}Vllrpm)sm?nVBRnpMJd!{)Ici3l$|zIPVFV1}9!~h3 z7ER!*aP}R6jsn~AKKijaMpSbBrv!&P=S@}hd7#XFpVA-{L=lM!EOY@aQY-BnM|RDt z{!l=3Q`g^n{%npw;zK08owT3s$gDu=@h1USsCDOd3LXj+Ox6ZoW1p_Tt?PL=%|c3P zMv2p$np3(DZM3z^hzcR(l+|}q0FGE*q;NBl`$lN3HL!|P!08n$GU_6%g^45Js0P<3 zA|!TCs)0rz2^0`P^wZfhHA74pkg2Vs?+m!jg=FxfBu4=e<Q|u@{OXD*(0<0sC!Ss%ecycH)L~HZ_(piU z_Vcq*`j$$Q?Z`2an#Kl%5?TW6Fl&fm8|_jncac=gf%x58w*z7}Um&r?bI;Fo*=4@F z#xwe4U`>qxCP<%y0s3wY^9Nqly$h2 zeCdR~%9^c-OE#?JzDPN-;!vIaUiJ6Vf;u^C{9g@j$@VO8#JKf4raXwp(alW`-k~W7 zuz_iV>^{=E!u;#MK3RXHZAiAA%2gC16y5{K)y%+nmv!#TRa@x0nE+B570;c!I|cg$ z2HdT>d-o?@k4DycG2GCcycE;&z!%~R3bZ0Lk4j-JwWPSTPIflQo>-?Ol@MXAqXN|` zh`e0D3q!ktPWovm-nGaYK}b3;xDqJabCZEQFio0_(L_?HL~;E}PsS9lw4e$GTi&sb2ZO}=+0G(vA%7xO&rMxm{!kWb$9I4)}uabpEZ-AV6_2$9MHr zNm&GdF|xo#3x6Z`)yaD~GwY8Zj6xbqm+E;fi*uu)riX%hII=vYOSE#F2&{Fdoz-fC zDGEnr$p_@THm2`!HNH;9fkQ!+^k-p3gvBmO!1rOK}6m$9{&vEIDOBk8YmTv{9-4Y>({u%nZoFX?!_`#9lPzb|Bz-%FP z=F2i&n+uIjQXBZC#l@#lHgbT{u{pAJ0`6>iV5`1a3mpQ$q*on zm>-y$z#v^()u&GtNf3oeNir7Z^qS0_%xQP5iXVz`z_F^YfHFXDs*}=~6bM}0^Zc71 z_!ImB>$Q)g#TV~&(03(ChXz8T`VXT71)MF_w^^<~gkW*P%mwl$G=-h2$2uru4u#wl zN_(AZ4(EGr&#Ou6$7u6D9?@RhG`H)m(B_l1dB(03X^uJ&Y)| zsqlz^{v<^>`Q&Xkjl|R%+ELFJx%BVCcw90jrFitR9YB zq@CY3koEoU9Yz_cU`*zf3&?KwTX3C~X2h_?rpV>|8%J5&z&qwQ0w`UQD zYh+=l#i}@6T;MbCh7_krHqb}qbIIPajjVu z`@>ln?_#Ga1twEwM{i8&u)sRdS`X;%E+iGdnND`;yZHemW~sFBI(;Kt{JxrhB;(^p zxrOx>m=A==1sv!r=L5wT8&c3hnr8lLQ$f5-&iX3|GNR#0EpPpEbQT$iScrH)|FVQT zuZSR(@$|2ohJrJ&`0VB#5DI>+inGs;Hud$C@o8bLt(Y-6H-+kkF!0t4+!>V zaQq-Qy%lKM$2hbofK%*3Y7Ew=Y>GV|A(=?9MsF$xDvT;H#WS&6l%lYM_{)Bhk$WA4 z9OA|O>(j4yhpoGgta|Fl7EPWU=>b949mh`( z%BVWlzJ7vkQA{)rNXX%gK|sBv*_n@&_!ETISM9L--QW~b#%rw5x7Onr( zn{IU?E`RC8;<=ZvV(7?KD5^hd3N>kw0-Ct^nU5Q3s>1iM*ZK_#4n=vi6lzs$AF_q> zaxfO5yqbQi4Np3cUNr_Oa|e4|Z52yo@IT!~6HTCfM?Rft=-d?MhcYf9hQYV}lNgG~ z?Y%0NvHHtNt-A{KQU$MCqAO2D4TpN!g{0jq-ie}C(ZgUwWvs&k3y@x5OrX%BC64)M zs9D4-MSy2mvU%rz2v7oL-7zWV*L>G>Lh(%N_^1`o-}$OXs@>YiAt1;BmYZ^sLB=uhIoVM#A6@(+x7<}F0CQcHi2k3kin6R3tN4GA{9&zH{!X+F+*y4YH3 zgRJL(`c0=yQwd^9CkOWznRe?ElOeq~(`Q1|V_-c}$uOH!L2}5uZ9_)k#d?x=D#3sX1O=!=s3+oCk`P)#A&t{y zN(a(H!UIs65#klNL2(MaS*Dc9W2cs?3X>Fho}s{y((Ux|zpOywLhESz@ic{90 z^RlNW)nZ*1@JRp1KZZr2QVmEc=9RBY0_$$P81wX^E%}y?#Njad*P`EzGD)*B9BM^q zFu|iTi>Hnr9Eskj34hP$RXZ*)*#7g%on?oBSg7$`ry$8K35qhdD@a%yn@09Xb@NV@ z$@ZsGSLk$crcYN`JT;eDPCev>|J7I*i%D#H_&AK|FC)X@y^hi(6SV^LqwQy*dg{23 zn6cXDx^4W^Q_}XaX(R++TpsRx-rSeFLo?keLXuQ}^ah@VkjR@#j83^xX6b##UI5%M z>n5R7K3o7p|ErLu6tbleW`(Tn^JZWC2#zTX+_tHP zPx0H$*|Xr+xiG;yBDz zIC7dA)c_`SFiDB6hsQ`IC|o-lOu>k=l7N|T-8vL#zbXe0;(k{ES}g+)^Wq})%v!(Q zn>%Qt5GLQZW5QEZn}7j1Bg$aIR_+wDZ=<@(KOtGMt*OUmV4-oLM59t$8LW6+?bKNp zhhJe1TDve%qm$~5lvhIX8cd~!m{)s)jP+qK5w5|9ooUpSsiKIyC(jeT)nkC`t={md zvo=ysQGvYcZeR!VlDP`^9h6nO`rXrh5IiD}islfgsVu_5~3mW|Uh{D}#G)cEywLm0;0 zm{`5SSbe&(r}&nX_`8Y>cUcxsjIQPsW(}xED#BA?pba~;Owown#rrt}degAm4WC2A zWclcLh2!*0^K;$jl(o`e!k9zvxJ>H+pbD;ZDFP=w6yDdLqS)AcUz6fJ%?^N!?EB74 zAWvzcK)Rpw>WYFRN;3y|WCU*|frnz5{K?Ts_S)Dl#a`+Sb<8sp*pjqwU#-=4 zqMF;`@H=7bp+LHn(cCK53ixef8Hjz8^Y0J2jPDW!WS)M&Yt$~e1?r(IN3-YJFsws0+&q2k5DV$%+y@inLH4Vh zg`b6#s6$-rN{>z?W2^FD;(0cd=QKOPK~)E{@8mjp1#oOk`z|Hhu-lasNAAm9h5W~9zs%}wx9hWg$&pGV%cJ^JoCv=cLjwI9S zbiXq>F*72V5VFe__uf0!AP(uLi3>nM#3rqo?6rI8E-~G@uUYLgnLvltX?qDU>tIF( zii)0^&Ba=ez+TN|83niyOPU>W)GVy8UL8)R`T~x{pQ_R*11F?-(eu74N{@FDTBqJ~ zrSo)avLAR6f+4}3;@mCBG4gOCT-zy;IUy$9qXA^t(XjKfRFE|4EHtC{jta?3z}xsb z0exxswl8=XHzAFeXJGy1_J{4rr$Zf9GGf=DnlzCfCov|J8kDW8^0psbR)tjg2CXoX z`UG-JTC1T1bYn)cQkqL#bV@P#U(^303Mh%J;PGY?5OS{TyYp@-=5|4Xr20vVQh_5C zHE06(gN9>?R_Z(K<+fN8dQOv9*lfE^A_RC|?j*xJE*MX-9 zKJj2h#(!525F>p{^}h`1eu=c1%LRzl)8+Edn{gZcc3LMLHNum2JK)|N-y$X{7lNW`{vvI1+NhJH7L7eF+5xmlG=n%BME~E=Sp_G zng;?YNxR?N+!Z$qJcgB5<>&JbTZMZU?#i9_wY8Uu|UTDS=_g4^%3oJjWv z@COb|DYM`Rpc`W3Mq5mFdPhM({FH(~MykilYol~uwDvSQXgD!#`lo3f`F&cFl#pBl z4T1$ee0XQ0V{f1Ge73Q9>ZS~Wo4iwh6oB2RxP)xv_nU^WTypHj{6L&_>z zNI5WC5LdhsSY5{^BuMKf$HS~7Y4k`E1ULk^GcumA(PMz9;PnCb@>cCyOHO4=J60tr zw*)Z#T|Ct}jb}&@vx*6KMnfemLoF-c`%;Q7XbZht5)X@oEDhf~CEX*?Ugx*eZ#ciN z-ZeGV1FTyqzgy-w1YH9FcD<08{uh{B^{u+O0iR4nFo1R!tym}e+?ILavo;0p*~pm<>Pyj1Cgq$)PFYL+Rh1!A@W zf9)RCCsAeICf6W|5=}q}2l=d*9Oevo8DcO*-~gOQggX6I`Agz{j%P@qeMW)|Ao!*! z3}%?jmY)~z9Bp#N#jj0ZS$Xw4gfuX>Z>>`_&vnjq9b^Dn$RxlCmL_lGO(FcJaR84S zlj$An2HOAC?hk`4QG3`j70ai~NbL_bC2(%^03}oUd!s2?k*+G~Ci3F|_-)xCi%Cs1 zw%$I4EjFC4S1vM?*WObZBQ$cS@OY^K;nIzcq5KPC^IE6RIU}zs@IA}`d56IL`r6A% zX>$pES$&6^N@E5h)<^js7(NnriAH$_GAbGzbhTC*m5X!|QyjEsGBSJl<@Gdvc{d?M z>(K4}utX%#7K*gLigUvy(n%YmuYwkwPaqj_66=;sUs|B1QqqKk2x`NITH*U7Lrc+H zySoT^o!z|s>KH?%x3TxMwdex;K4)h8qAdQSQTPs#^FNjYO zMQ>1|;w|4aMs-#2pj7iraPs_piox@ZtWm`zlucJJONC{nvu>FzV2ndUxh-(DFxnvL zutRp4zy1yo5r}hYL^=bkXv$}g^3``GL|?T zSBC$yKVV9e|6>ATbvsY$t7@|PbKMU3;dKsUWPlVZLLlf&?|)cx=UL&=`pj2F+>if~ho{(999tvV=}n3NV{=UUJB9k))3%qe zmX>ha==$hi*YWGB%Z^9^x_in=moG|t5*(5z zZcy4sl-Cg@BGA*09g4Q2adY~xSc8gRo8duCpc{jTA5@GU;VcW6EKfBiquJF%$JEH2 zC`Fx=u(?n(=BDnFnW@0dX=irO6;f|`LpYpoX+Vrp2-MXclVeh^eO^WlB6k zHCy>&#k+&Yy8jyu2gW*Xob|5B1h?-J(zw<7fdcy98_y?w7**pUZNt4QscXk02gR%9 z%*m5HzP^N-v9-Cae}n#cZqUMT0RR&(6F*hKmzU{6%*2* z_-W-B3RP#H-EU8QMs4YB>R>Spl9TvTiI?y})+aMdwlY~$XDxfmB{rkkXFC?QJFtbe$BAL~2705NhKi8h!AGCEw zludDFp5{5fi>X2b*JwpXOEl8y(4ke`jNQK_U*BO^`HwqGpNmke_8#PLTX6sJCsN&F zC5NiX-oHv*0sVuqL5&d8sOq?b=kmJ*hFR=|-F&Ba9OTAq{zP)d^W5QgvJ|c8_%n!S z#k#>8a!JP`^DNQxqBu_RfByHA;I_n~0>&d8tCn>7cg*@Y)4 zWJn9Qnw}xVjJTCAC*yWt)TQ85OET4&3>8_yR zp#$-tL_3;diCrc-qC_WTktrEOzrv41?YxNFLpmyuTGG_sN5w z#R5+9DXO;4;2fkUxiAR~d>|6AlyfkY7{xtN%;M$e{9n{_0SY0&iy1&BXSW4}gTBYVp={B}(u+A2uA>U|K3jd8opv`M_^RIH8|xQ61`H@ln~?7H_4M}% zopn_IndD-pod}jP925(P-KQ`=@O4>wEV_FYGlRc`HX(d2$J0e5j9#AY`}l|5K+Fm} zTg`I7^Ofy;hfpiMRS0=jR9hV6)yt><;5+ZY6mKFbKI{jENSApAoDK*}O z5vg$F3%mE#g_X(b6_L_C(Z}L&XQ;*Q8@|*XRW0$|EniPpz!IB0<_iwh>Mi{>IU4mj zSv2XRFxisw7l7`hhLM#C$=M^^UVOmO$KYVm4_SX@AYE0~=}JON+gGg~75$(>Z(C6jIUd(+WfehcCP@yzqjmTFP=Me5pstJxru&-_g1{(0y~|jOmQY<>rj+ zvaen3@fFrWm(l#(L=(&aCd|ZSgb88H661#`ySKsc^sG4T&XU+(zip9kEyrzhIUQ4X zK1DYU*Ew|iRBQRRQ{|rzOfC|04VTF8zW$AT`psOlB)XlgJ)K!hvuyt~;~3g= z?9^2f7*m#nWB*JPdKFXyxRoq4FzRo*oRBHdrk%QzS!PICECAZrVuqWi*NrMH?1*7J86hpkvK>#szG?4Hzr~0Tw>o8B%Ma4uVefz@X zfG#|9HDu<1lJa@if;W}wcI)Ps_idsT5}d$y-77ZKMem1yhQfkdX}WJ zK3yD-)w$w-5%K<3s_iD3t^XLb2h(W%n}yC$CkM>B)ZV+?oCLH}ax_*i+<;KK+nHS)lLTXDiNKMKX*OUKu>k^| z`JdRrdt+5R04_3mz`V!Z#>=;`-g-J)niv-I`P<<^v*H9xXL|FhO&8G)j?KaiF?v(m z@fqLSYs$*Ozaz2_t}B!YDYaekVF5mpjZ7jeT6TSHg4_GPeIZuB=UnGuU$gu9z5agR z*#&d&=|NZB^2j%3OztjDEFc&}3K5JVCbUIczS(*2BYbnLeh%5X0C`c4t%o9}jPTO{ z0u!wNmmp?BO||iFa%1QaX(?iOXkFP3X@cpr-y9Q)ANf`?IgjxMuf5<8K$n#B#qHv6J%0h-OEl^cr~^N+ z>2?9punR-jejBUL6$Ces82(Dq6a<_6=Sz;BFQ$(X3Ek8`tk}ITDJ&K2XhSdysI|>8 z!BP19VeoWs-yB>Ib5S69JSONc2*|->tM%F5iCf92Nl281gGIKKsQG>7Pav zd+k7J8f6#h4WGb}2t`&_hVBTwweV@BZ+T1<*??Yf5id9=(%EYq`t!pvFcT&&*FMB) zxeorz`=p`3V=x<%w$tvEWY*UkR4UF8%Qh~0aALSV2=qW0;h6C;a(8;(xb;T+m9s+0 zoS)WhF9^1{gqge=t9Js9BFE8xaCT-gigLZDj}rIX7@uMl6}z;j6xA5~eV|BoF|kvT zhrUkNfT8q-M8NJljTe6{KX>m&BdWQQxdQvi!o8zfoK12b9|&X@%lDNCbRUEtKa%YB ze)?46?!0|Rv-$hfHnUE})%Y~fvQ6+{H2hlyt-EU7-sjGZ=y?j=jVD@GN=gj}CU548 z-~3h>y?|M7JO}<9I;3eJ%BW{FK^;nvIqQna5jn?<-KNmfjiSQ%Acnh#$7n5`axVAN z&UNJLzn`M`bxRn~-`!T1h~&LKlpcHW5x9+wCN^6IGknnr8bX@EpGWd z|JSu2f1pj{Nvm_ZyBPyHQBq2WDNWC7>04 z-;4j+L!=gj$depeYcO-z93IGgmy|^Eb@R-VATWKab=qJ)~iQZEh;{x>9O5JcLhug`X6{Yy*I#{1@< z&epx(VMKhFCzB(UFtD%@v?K&bT%7FlM(tD+AQ;g1!_0vC8D`f9nqfl_=pe^EXXML2 zv!f)4lwdJ1r7+ZxmeS<1Eg>ywJf0BD*R`W29^t6?)Rz$&W|N) z`3DWJ!g&PDPd$g+6*DRN7vt|;FVLEXpR_M$=PPwVKkLh{V??$Bf42EK-E!<~Yf~z# z;-m~0Ao)Dr-Zm;4xdRc?(J4Qkl#j^bg%HX?myNduj|OS|#Y9(5SzsWP3WDfRx_Jz) zCAP)kEXuhWMt0c!vx7WH$Nh$mu5keOxH=I^o3&6sU)t#$8L% zk`_lf2(|HV<}SK!_wyg*B6-{RG7sQm{QHSz(*PgndUkeU#Lumn(w&#!3oZ zF6R5I;eat80W9ETf&^582R1@dgT}HVqdX^>mR_&T(2RHt*1t@;?z1sU7}_=(}O!pF8-Q}u8>p%mvjOb zRoFtv8t~GV*LfeslhYTCXm}l}(ia)xdCQQ@EBjDp;0Q3{vVaqVK;q)FVE>%Ne;<%> z?=|0wzSJf)F0KR#p}%CQ4t4^J8-W3sJvKKt zb-3r=q9Fq=`%58Svu9gEfge50*-;A$v|a{{{R%x@S^sI)SnT)Xso4@IJAx=MX*A&O z&OK2xiDfJ!z7tg~o0`_;B%b55pGW^ECxO+kq5-d@EEtf5dt1<&EisyCs!)4zUuL(y z8y!He*z$O0&tB1iYNi{EF!Ka~(S{YM9dTj6Jl@9_a@^wCt$}`H7O1RG2Szu#Z$E$i z3v$GRDUA~0H6}yOzx+#9&h)DITkn$`yH6o?cnMBEcmmx8cb#bzv&5`LStwZV*ds}8 ze=ja}>fD{(?Ve1n5+i;}5LYw5*E7*p0+XMtixwIh8m4@>O^01ye(z{HjiK-B-ctQ! zb@Oq^UR-jCB1Y1-tD+I*)A7#}Y-P9>P8d`y%93iT?E7-6`KqNA+{#Pjt@K94>Wvl! zq|i%o0F-%B$5x!HKVIYFo)vTxyFPU2RJZ+1|NfX@n(a+Zh2P8|K{#K#cdGLxzFl*j zXQ^78RO5Te^sD)~!!Kddetj}ji7w*2B({CTE}jFuin`9{8LvN8`&0%3NC!>}hJL8g z5_{uyHn&0OvI(qEIPf8}#FN4NgfOTQV!gk5{?=LT|01=@#suN8<4m~XVX0KSow>o@ z!GTahySwja9W~eWp23oXg9moSPgCWcQrf3~jV%mm&M$1;CP1W!Wvd_*=ElizlZv@g z!LW$~1jz16$iS1FIu(r3#u)^(Q}_Df)vmqgn%#h{4u9R{-Yv2~9q;E@qs8|DX#CAf=R%uZ1(Aa13ZDATg z6eZ9iarvZC{0CvR_3D9;zN^N}i0;gXxdZ(PV zfXjek5A!x+`Yp&ni_+Kh8l9uOqvauit+;0oMLk%Q=pJ%bC6Wy9$^MHPCORY^=MKN5 zA4OdFQbbzzqi~Clk<&38&jEqaj_mPqYv4oEiet9Z9WC1_-zuv$l6%PauV3jzm`QNZ z#bCDGE>r+gXC&Q+58FfC)vie}BkKNu4ov@!w%^#^=cyEX-Y$tC1=#JclMRV|aNk`G z>^S@$;^%HX=Ewsmlw)z$11PG$qXgh@Bd>{{oJ+fcf_rL#%$dN$pWg@mb!Uyr@9q!Y zUJWm&d-#mrV{;~F2mK!N&UYF+Uv<3v&6=FGiynsVF6k%TITE-hWUOF&7SPwzaZQ_R z3!(!ngrHxf?5GDSH9u;8o|>l5CO;H1_iq!>Cn{6Lc8}6$N2CcnP(ufU(32vjc`DW( zdf04ptNMKgn4@(5l$IpU8RtcfcRz<bmh}x@N>{mg{9;asM#q?xm1w zp4@O(n(`k`@9So~M=b@(aki}$8jo%VNdd+<_v_7dP_DGY z7Nx;K#D5G>lV1DMhyzivvfbYcjT%IpZ!BGosUFYU zeN+E0mzfR*^C84wWVtdq?lCqU8|ZeL4&Sx4c_j2Cl<+0lma}MCM`f*sZtJ(B%~(8i z#v=+ms2^@y(`Roi=?SaK~8gi%aO1%rWdHfo+G%gso((o|wf?R`1u z)v|-}=adopP;uL2O)cd=B2C`(Jz-rXe_8Dp6>%ozn zub9YMe8Ipxm|HuTA;rSyHoChnm?@2V33WB%@At1*;|5b5fZ)A}P|)JYRCPvz?T@+5 zm^IcKsfOv(MuJBVX6b`LOlfo4Bp?WLKb1+ke(ECtMxJ!|II?EDT`kh(;hx9+7w3x$ zmv~M%1eXY7KN$Ow1q}?{cl4v?^S6H*z{cCic^#L#FxwiNx!vcpyHyh*7Xn9_rQ-h=`8u;P{hQ%JG<0|6?$vXt z$?YFe4{v_mc`%#tQoCIy}{v`3(x@ha!af18o`PtM58*1Oe0AA3GlpBa5bmb{hg* zv)U6gt6#I6*Jsk{9|&Z;R#u6_p=1a^n?jZ<_wh#L#c`vx=~Irkp2hZwz)+qYuGO3T zWofdId;U?V{OYdPhv@fbG9D?340kmL5;cx2t}Gj({GIWl6*O)nIK;K&Ye{~r~60%bP4$vqsz z37|soCk8P?!Q?fs`^aFS%}dRr+9(}-o@VxSs3}s=zBir-bn9b#dxh@T3%F1O?<=lTm;_6)zJyht+v8@zcojwc zl~Fa;x!iTNP4PV;=g|oj7hfvhKk6FN5Cnll;( z&HPLA|H|fmIG%>0f3K{8ub+^oX(Z zqcwb64MDeUuY)YXJ*E;hBk5Uqgnnwld*+#&AkXJg@zQ>6=ShB$6a756u~t9Wt#cn|4-9~9#dp+FCOg3dxw(5-?Dwt`kbNR+9}0jo|RBV0qhB|{qxHmi$#VBivBlkM} zy36CY`TsEWl|fau(b}7mO*d@1rKP(YX{15Aq`M@g8>PD&B$e*&F6of&ZulPGbI#27 zgMZAPd1~G3s`6pVq$q@ zK*yEA9!wC-&oyCSTxa_My;H8Lq6(hdy%adeDFvR3Z(d+tbQ|mrjt^T+c-Thdr}l3f z^C&cEb)_NUVr7D71Gpq>96oj|Rny=3R_Yf=;WlmIvyMFOTDN0==C*a6@Hcp|Bi?z9 zn1azkekW%~6R+16JN|U?Cl~QkLA0iF!Mse>&VDu6BCV~ z<1+fo-GH~`sDV~UPtAuvXqI1?| zKRJ9JPNbvm(Ry+nsMp3hG2Il#@J0>5Ab^yyv9%nNZyFl|=1Wh4LBJvgBGewR`?eMC zgq=rD+e_=th!SFG5Ac|-`y=_`U~nS)KskOnq@c&IUM*hDPyjQ51#&xH`2d~r`t6lE zlqnTGNmWeD*eSQoXO+9MoyWp;!`ymeU-50d6Gb>{OXb(U z!xe7Rfrkhc_>R1Q=L_1{ifl)Z?6Z5gQK0^HRR7Vo?hE#Zc8vJ2QfW5E3EE#F>Z+j%YxOW5o5!Kpw2KWfy^ z0bIdx1D~ijb%N!An9p)fAS!Z*P=O&;rufOR_;K$`p=B4nn0jA^V~|Rdg~}ye%ow`Z zDeM+?wZ4bh+}ikv#aMs0u zVS5s>-xd{<*fW59*PWm8DX6eS)1IoRim3po6{B8G`g}2#jHe&nsO3b1(rV4<%A=uN z6Ws7J#(6?GuG?-y-_kXRDHhHbOjakmr&cEPj6$(1)JIJ`X?O!$DDdNV-%C%nefWU2 z;`(^#=*k6@90dI4Ij86J9b01O@r-NYytGd{x1Ja4cz11acLXv=)(c^lCZTwjlD8!} zAfL`DtoG`q*RXX7!0?1X+hM~=cY8JTLR)*q&p4Y9gvPjXixZ2E9OBp>HdoZ^`4e(j3!HzxE<)J3Gnk`#{7GlQJB?ep)usg zXdPCjW82R6m+e~{ulfl!Ry=wlDl5l__}N$5E)}&OX#iUMhr>%lgW^X3jYIZ=8E)!g zg)Z+8O9g-bqgs4bnv40xCRxTpKdRi3Qw-WCgrC7+xbA-zqr+<(;y(H8bw#`|->og3 zuY%UmdBwxHZ0awfa;~eJUG}5>=J#(Rji@$ge?tkv&%T%Kpa6`q6Ado%N$&{v@aucN zGTT~cB3$~&wqY2H6}HkRq*W!C>;Mo{Cx7}YD|zyLGY;G( z(fDTI>az8TU7Da*y`1mwhN|@0ouEp50D=M-w2LKb+1JaOt_s4zdYo7kYpy3PKL2@~ zXT%zu)q-2)XEIhdAt)HkT=VbC!Yh=7GDiD+h0`V-1RYE(W0P{^`{~^BpkR9u8N_w+ z`DuR!%Rc5q1$9IrZe9>9`35LfuuTdTlUd`ZZ?#jYn0RF6LBZ^0u;F7X0+x|v8t0%w zU1`rSt`SOQxwFs;%ai!dA!@ttTpu8pKto!*huH94A!J&0x7>3y^UKQ%>N387DNa~ilI7L&lZRo&FwaAiDh15CD35`Na86a-zq zXqRMLm%QfNXpZ8TKefM5)$CC_fdm`~y;mk@r>wr7S=36#}L~be=d8eQnMX zF2jA}(@ezrYX{x&?uUQvnq(KTCf@7!2$svx*=g41hN~QAboiB zGsVhug~y$A)nL$ZxRtDLo!n#pX&d0rNzEE}zok<1>w8@#(v$k_@B|nylYqbF8B6wg zP}to`jACLk!UhW94t*Wt=aTES8Na6u(tN-Q8zW-K|Jef@OuzxsYT4{Mtm5x;tFwtW zj&k#@ZhL264k$>sY6s=iH}wG9w#~_!<#daYD*OB_`;MD7v${u>Gmkc3XJKk`lCL9C zVA!H%vdX^2vP}QWN1#)nlU+cw;zQ-O8nm`kKYt|$dvOiDkelrX1quWQfzGcVIlWrm z$KepnNA=gIC}%@C&~-a$_D0ybm>|CzYBO<~6JeLV9w0r;DJzFMa}A4h;wj@2&o~XL zjP(dzMV$GmIBCTbZ0G697qh|6m)rlW+U?R*BNU5(uT3EvlU|hQ{ZrXbpWg#4Z*XLZ zD}6JIqS;bBpx9!gbQvjdOM+i`k+{PEdEDGsIVTj#eJ1s(-JKWhVHwX7)7ykH9HT66 zdwmC7G-iI-+(g@c?=umj=7zwxNpFbJBn;)3oY0(-xKwsU;$1^zMn#4GZFsx9}Hgr6Uh!gs3Q6?X*S zOQz}2MX*y;EEj;wrwLb^(SYMS@A8w-YE_BO@4XX;e0`5+cKsqOT;|5jU=V}H)O3=h zoG#0UABr;ut8WTJMhc&z@SqaLYw7LnJdLkfh}H8EWRYA42*wW)o$?P?%*2l=(9NK` zZ5b5mY@s~OtI}Z3iQ+QZ?TWs1Et7W19Pja_(9u`?W)aPmLP57#)S63glL%*U<>@b( zF9W0Wl!&g=W@iUc9G1L2|3N`pxjdp{!2J$z&>Tw(RU<}Kh*0Dl-!98VWQa8&KN?b! zUYT4ySPzH$!U$3lHa_HCagwhN|@6U&T1f6?fSzvtwUoCc=wc9c<67^^GV1#qX~5j$yw60O#L zu~dn4UoM!a@RM=UQnf51hO=R>`?L6Zi8RN1?{%iDJ+*+>;Ky}1>T3pq%|EQ0gZ5c1 z+N1eUp!N8@a8iD%*Z(BZC?>;xd&{+VD-0omi7ecj(2&`@e)_*WyoN`wg$$Ki}cIE#4 zAp4x;_#x!_+>`#UvNo7?ZzBYFJ3@roPfps$NGp8IU&PPa7s!jNN?B)6#VxU0N#Pkc zK;WOAl?20+z@)i@SGz_v1C<~g`N3W_0WibeigmXmIWNRSz>+7RM~t##Qh=Xd%hKu^ z(1o7Dm~$$gXEN3K|4b8=Z#%&5?<~wO3<|1GDK?sjmWYajkcQd08Q)ok{G;@yMPA-s zCU6$kKg%*ivrr)Rdr<6X29a@tZs9^P%JV4DP^UDZT8wfkK2@4)!!Nm^3@w)U=*=U>vT~p(jQ1r}L+YZ}#|k?G>xhWBWf)jQ zNrDlc{xIjF!g^Ak6%*K4+x-nBmE-+G)kNiqMUb8md*M$=>JZKmeJKBGRS}3eGttcD zHNe5>cK~Gzcx`&54^B>wgdFEFthtlYdRRpxBG^4YtAi^7cumME8ZX!xEbUVVq&=xM z;jU!IWnY>)hlN)yA^mF2kN?qPfM83D3mqasW8aV@J_-j(JcYwKs%v!)&fAItBOy+3 zUI?jzNM&LmGVv!8_Q^_qNzv++`s?P@jU) zx;O)`7z-YbC`>Y@YXbr>!W+%SD4;#qr@3)r|3JrQV8VDW32q0-1TcVZ4l4SHc@nms(W_ z;AiqeK6SJnH_lvCX;`QL>8un(hC3bes#f0gQyPZ{($}%Zssa7?VSH#?IJye|Nut4J|8e_L9;fcsbISnR5Ks~a9)h~%*2}H3M`gQwI zTs#f>4u~VGxe3q1(zU^X_|g=jCW)04QFpq$&hY-H%x3A5bV{a-PDV5E*7grCzty*^ z0hlp@AOb~}>VOU%g#r3%eWZFbA5)E38ZamaV`R(G&I)2@VD7$zuiFymkUubZ*oyq& z#+2dyWqYfTsVmGWhk=O%gGhtZ(ja^aP?)w!nF`}$wpl3WngO_V|Nv9*2_}xp-iPOl0%8SRxX!Ki>*zP(NRK5GKuJ)}DGGDM> zlPdF7XtB-5iut3-=pUQ(CdzxjG0@*__|wbv=EQxS@jp&2mj!tn5Fd!Q&NeT8V25Zz z4tyn5ROWRsAwNT20c|yuzPk0N&PwHVpGJQawcSt&VQ!QNAr{rJnd~(K_Rw*}x{n3D zD;1TdzGq=8KGh*SFwkSzy8ZKULo}1n4;3;HT6}OykL)oMKUXA&<>@>JbSIcqM>a_e zkUuf~rUk1_mh1JTNgV@<4ibf47S_FA`l6MR!bIU?CpWvQ%St3@^%_pSPyTL?BZN}k zu*j5srw3cOC{UuzcsC(15@dY<_WMPt@Et7TmamA`kE2pVMG%MGiSTYmL|}Yiu*gMa zR#n^bMFjr+XB~8uqiD$u^6_H5&)t+XkwLJol<{oizOayBe*zCgMQ{67-ev$WFQ7|- zbF=KWfx|bufL)~V<5lSFsOKeggZi#F?;@`2arniFVZu`&qDr-erAUo_o!a?WS3Pfk z>URR!fdc_Q;f%=0(N4C~T}ng_BIntfME$m&CcnkvhX6$Au+#PC>o8Rv-Q}Xc zaU4=#_~u_E=EC^{(sg`%Ru5FrT47h)EZpyENCia|FM;p>!_xA?%TcoMP5(0C3J$w2 zN8n{roQRer4^3U^m(GkK3SHM_;|%AdCk>Rbv@oxq*a|eE>lb~EE-pdn?~>av-#!f^ z!EgSd&2nBmUz*W~V-(zNq+`J>0Psk=@>he*M!p#vRB~VBpwI&d22dD0h2EF^0waOq zq>AXs)l@7_RQv@WOU(Br=gx0-69#^? zL+JG=ltfp(sjkJ#Ok3juSdvll?DgiPdBZGvQl|-qQmIKa=RJZ6c!(sFx(hJAI{SH- z_5ASmN=uR)-x?GoA?2|%kBkdr@_EXkQN=k}GxZaJnj`$3h>QxhO(8z1SOOh^6kxr& zNYNXYW7Xi`k>csm!iWNkYKf+hRgjG-*+lNp<_Mbe2r#(mKXfXrH$6tsv5@=|+@xu3 zt@FO{@Q*dk=+(!Fca{8Yiz}tLE?A8S31=I9F?&zk5UA_QQz6ixqu*<-EMlW!sz}t; z!@MH2L;V66lqy>eE+dp$^6DVae#-bw*H-5rA^H9DvL}i_qlfLgu%&ICdTApmc~DT7 zpWorE@a4rxboq$ZEcz^^h%zo^QF8$Rr!m(fhKV+nQo^##NvJLaoY7`sx1c?Y?b}*{>ms8V`93-0A2x_ zY|q~6c=Ey(QnhDt>K=Ww2ul#TTJU3+h=f^!YUqyVFK+pnzJwIU*fz|;?do1_!=Tz# zJr)g?_bI0B-}AN{@{{CE)1bu_A7C-RTGWiUpC6W;eRl0Ly>m$h3N>*qP#w`-id#i7 z8LnVLo1h_|c_W?MR8J8MTUDVLRgCJI+ zZ<@{<{zJTgQe+@vgbdm4A#h#BWiSlisSlw4B)sp_TcgcpB>cR1D0`fluud^kgKv_- zM+74InV0xfU#@hsudGYuqziSWk3fx@=F1%c)eH=6Thz4|_qLz0IATak) zUcGfSQZ62(P?q3~b+|{NnS0OupDZomKP!Odq2xocXPB;bWwuhw?yD85*?X7U(!xJ+ z2D3?oN{GW(Y8aS=Knqpx%VL&U4J>U#mm9nY&7+8OO|(kIA5>+=9j zUyL;DszocP8ER8+!K&_L2~4cm6vFCQP=CI;pp?Sdfu&RGulqleEy z$|`NQ0I{1^nNMjv>a73HwLKY#H&UuDmRCteRQ1mg`DmE|qv8P28jZosM4rGJ3M8 za>QCGbIJpKgl=ggdjho>NgVB3c6m?p_EL0Jee4sBa*hEH{K791M0M~ssHf!tA zMB`}ebYZQhZG%@~Z896IKvp$$<}}4vNPWlK(vBp1sInj*(;pQ8xiT zgOPGl>~v~<;-tOTZU~ATqGnPq2(r&Esck?qU|LjKhK40&&R8RV_<VVucc0H? zLaS|6&cLnPRl+Ohmwf+lD;khh+YGiPG7SGeFMuXV+?OR}(k`Cm2xjq_f_TMghbSQi z3}<=^|6tY60G@qDehEEf?RctFkNj82{1#$)yg9C-X&I+3w5&%<7~`Lhd%W;PNz~L1&fF zKkw`00eLsIpe&^3Q}qO$n14!7c!VU`qG0v*PKPjSi`mf1pR4{0@qa$s%Uf2KcjUia zE!={fF|iLFrgR2<#5B+9^KpGze;3*gM@0j*+TeakTit`wz~5iy55ztli$0W${!9fd zG28xfaKSg;kK2Z=r@I09{LPtbokUR%=d58Ad#uH0>m|u-+E9x)7`vRN-ej5UPjdBp zhqXN=5|vxst%ljnhzR`chZ8V9ULM-AF>HQT)_o}{X*~F7yyeuPg+QHP%(mT7Vq{Hj zO#vnrm0{0Ky#8Zp&%MN#YUL!cOE@q_8Fzq9WK(jWN+oR`Fzlu>HiPf83I-;99or$i zWMAOZetl*-u%|@ssQ_S~hH&0=<_n0`YK0PI(9j3AfDZ7A*j*m3Wm|y)U}L?Z`ZCWk zLPWHf8WlO~AEbZDSPJDG3~!K0RKMN~pr$$AukgYT@oI<}BlfUF4UqU<$1%LQ4xEmq zm?lSUg>hJJN)dy2c0Tq1G=8E(oa2DJ%0hc}t@Wcz2dxl`>bP>ARV%7ULJeT`0YS*s zX;KU`sDH9ZL14PUCKA|NNZ+-x>FCiBL|MK-e_tgTzSQP-vtRq|{Du&(97+v<{N_%d zyLDAQVat@FCz!H<`{9{ZD1W|IYfa-tk@b3QKt+54ymXGMO1(r@y2w0VzUoiuyDbny zZTn9e9yKJtzIqJo-X)W;+I_opuX>qim3Am{!q_Qf@YD{HX;^tKu;_3czMLuU@6`JJ z*!A{sK@B`_Ny!wlaevk|E}D|Vg3;p|A_63GY;bwu@^W&lB|9{n+sG8ltom(?DCmop zGtut(y$BTFqWqM^=m$AyuD|DB-?`Z=*SFX%RU}#3I`ya1{%WZ5dj9j{SM+udPd4Yo zIStD4h<-Rek_nYvo>ul8-n!#;oKjSpdKH_&z1IWkahUh^fMPqZj9Hv$SsfK!9n-t&c&Fp0=}wAIt3kR>D<{vBGN z*_Q8knT{5r zHrOWpj2`^-t%-E+b~WAoY^B5WV)MtK>1F5-ppVh}tG2MtHp*k4is4Xa7aQpIp80GQ zFwApBpa-!85pXncM6vqjFh~-|prga7hH6_{6_rdVp_4=%qlb*P2C~hK1^LDHr7NFnNZh6|AmqE^8+a@fWAsgp252dFytEJnh9;C>|2?DEirEEm%**)oaj? zIDuY|+s>@vRJE5!j)s^rizE|VK75QL#^R$7c1mcMz5vBea~Du{V0OR45ZV5@*Q|%jV?0pKKy)DiU)D|DqfUV~BxShao%oxKTZ?YbOA0Xrp+vY4W#v z-u{c9<956!nsF4X6d3K49ghmxg>>o#(L+LObSg&hFlb1(Qhg`dE<2m0AMP8ciRj|* zRH6eZ1yO<#jsy5J)F>n`I1pe0wj&)k9!R!T%9uF*Hb1WMc;uarN)Y%lw-~VBg+erZHj#*s%jazvKTHm?dy;X!A}}( z8Ew%Qk|W3+!Ug6j>!MiG#zY#spPAwd%PKpEXLi1R6bG?9R*2nkF1W~#j8pgax!NdN zzE2^cYIi<@Z}R}I>&*U-&m+wQWYsf~xx;CX0;J4Y@r1324@&v?c-lft%C~=BbN)ru z9~d=a;BR<*ARFk<+xlh195yAV=+X+oRrn%uNZ38(>~M9yZk^{^T&~EJ9Ume5tCY3% zGApUz>H2uvb%m<1-?NH^x5udpz#Dp&n{4-9s+tAxd3*mUzx08Di%{ttM((M37qN4a1<{S^C6u7`Xd@5r%KPA4|5({rpo~84ClXPxd z-NzqO&Qjti)gXUbun{Z~+?{0|3s|A@s`hh^fRl~q( z$@sD*AFkdW?{?R_pGIj_JTGj<1S9e@tGe&{kCb0TsUa$IL|6d=m55C?n)TmVOtk!E ziUjHxyMc~P&}NON6&nf1_c+l#>-@)jAl`7Lx_V!g-&MI$3*62cf$3u9v_uy>UQjRY zzeaV#QQ|ll;}d5T%i{ujhvUeNAJKt}+W1;OkE$5BXzV)jCsH!hhrpfykB);y_2`XI zjl@W3R&|xA=QHuVB`FU$gIRm=OrWt{nl9Ud!aL8CNb& zi^O;&m>Q1a`laRWx-Lo$f2*meis)VR?5%BeUG}#M2Z-(xnZ38WCwv|P>V)4?mGm6$ z$>q?r9Zctt8EA-k;H5mL9gN#{MPljrdXm=Ga4(VM(M`Oa9JK(NHKi6H(yp(PldeVq z&*}H=9DWGv$$BP{n=r7MoFnf*VhXJCJr6VPPob2cSG+co76^3c083^Q&I_ZW0`_MS zjgUphoiMua9ocU{b1B4R9jQspGn7|e_-4Djw*IsHbqZeunX?lUHi>Lp;&MaL;(<53 zC(tOdL~GV93~hgGY{Kt((fPd|EPk|plg`lt6I}&pq#Z`YD926DAke3e#SpnZS{m5s znvJPdYFvh6W%7BTLb}JUe8n|#8NOr>)tE^RF{>4k`G~yO4sx^!LCGQ zoNAkznK0nPSFJUaAYSS8uV7%=j*yadw>>?PPyE1%qarO{r|)4YQC;=#na38v^*2mK z1N4vWrS=b*f}g)_f&AmZ2f<26w(GxKndh{2+?vzEq)Rt`Jx?I5j7s$>&Fgmpt4X&r zFZUZtKSI2!kAP|?6NPEUm1LDph%M>&=P!SJ1&qi9VD;to-W9>FH~`qZJR?bR(C0a@ zm|;;yz#&t=2U!LkO#!MBP3FD7phKrTq~3&WVArmX!qtOsljQ$S99IFr&lBh4En;DLGO6W+WFF#CZ@VwM_D%4fj`%f~&RnwJz z$N5jrITHzkW{F74lFu7mE{4g9_Mn(6^KHif0Ct)Gp(Pnv_m zP00%Gp%D!o!tJ|^#!}gfy``!2W=K6Ys`3XNbj%-#(-GJiVf{S~FYq57;-tK{Gp9daF{9Ff8xkePFLXB&`@aP`uHq!wLjdi9E8fD%8BKT zKU6U5UH|^~7fa&m^6(lG4-Hm-z6lRd&n)57;LNjH#8abG_*$``?=r~4=#Z!v_&1Y` zm0G2p)4q{)Tc#UBECWV*Ha9$FwT@feji8^_OronD)DP>38Y78=bLWB^JslSk$a21N zzs{9vs{`_91{Q0& z)KKdR3?fZ3wb~Fw@>KvvXdy%OtrX(Oa4D7CceV}>qm!QkQ{6Q*gPpQA3d_(P#=jx# zGU(c!@wR#AuWtgw0=?XO)0ezcV{2MneXc5hcRa&9KXrJU>_+`@(x{+C?zso-JepgH zGavVIBvJUeEo9BY14`ok8d{ew7M+&k7Ev4S7Jp_)~(#iQ+%7W~{_wXW7f12Pz?71Ji>!CA_H`_DSGfK>uIe*a z(pB@zUBl~X79q{S%Lk%)UikMV45%57nAvB(aVS^_t z8QNAFD-Q;sx0d6^9jA9m-%FH&dW=9oT66ES#}+pK?_pOvUfVx#pz7lwEL~k4sGQQ$ zrkY&VX>^3p?)aS^pfT^omUuXx`-Sf-Nu2=$jY>qj^N*be>+%F@Ri#3z)0UodrRM5W zQi}>(P8>8S?0|+fMR~(eSAOo|(qvrlX=V>9G}iksEvt4cn2@WIIU|=$)8ic&X4s`1 zba>txhr*x`@5qn-2}3l>sR3p+TXX#;|Li&MHdMmvsTt91p-%*i2}pE-Hda?ZS`+O5 za^SkAOxdGY4|BO)yB9|bm6wj~q0t4-;vlnW2bVA~HzoQk8QOzT!ED3>{UWB|Rc+OD z=9Q8kE5`C_R0!*>M@{^1(8Wyrd-sKGL#1T&1Bg5L`DNWRmqSv;`Ol&7R=*0Yk(%lA@Aj}NWg-F z>Reyeuj;nL)bu~Rj>uD#iZC4RlR=c z?t%@T3(g>JIn;77NNKg1MD_HnY@MOjM+hoN41xhb#hs%gjFq>B7T@O=gV`lD5D1cA z#MR-o;DG86^5kJeWlYTRd5SL$QXQksVBe_Ne`;!rsQyAf-1XBI+sCrpBL|-t7gVcI zWCbConrF@fy}!rvyRRxX5O^7`dLdKuhI#m>9QJXbf+V_RAeDtq{mX#z?Ai01K`O)g zBwF8Nh)$}5)AP*Tz+X9y`X}4lWrZ#N9#Nbl|8zx5q_~vj;5YHoi=@yt{wSHc(>Z7~ zv#Q=%zq>=yw%b?~O?{oiLm(tAKX<+znVdP4@=TTUByxuo+m52GzBC(h4fI@}ASx!M zA(mfDw7I{I>FJt;LwRXwPSvvek=UsP8vU%|ACproHIJwtLr_fLG)ai82w}f}-Qo5* zJ)SUl>q%DvnwqO!Vh%UTHq5pYbsUq73wCJG?#E059q-rgaktlY4GOr(cQv1stk+DCU)4F;qfN*5f%I6&NIQ54{HK`_h)Y*Gk(#KE1(YNM^rG zKoX*69C3uj2iPDJ(Ezg5sxQ8IPhoi&>OJ`65HYZ!!Fv74@-6n!9AUJSv{7sT2tXMW z1Z15MmEm4vrmzG-J>7J1XIx^wfZOB~!g;;h)hilKufh_rNrs9ZYZeB9MJWTT0FYtk zw2E-=v_Qtrb@zKj+B49PLBY2GaK8C4IiiN^=cqQ!#q}1SQlU{SJ)2x)Za0V9dNPNTcZQ&lCtws!;KOxN!hUJ3wxh*p}D z!w5PD_2^9T?pT3jU!EGJ1y@KO@T-{9ykiW4qLfe*NN5%lFJZVq+O2M7m+wEm_!Q5} zB}Z`E2?a#r0iXYjWB-1e@>7rIny1rM%NeOp<1bfIrG!5pOyo8HZ2oxP*1^9zdk6!H zA~Ug#xn#bye$(tz$}x;7@Q0Cd)IdVu1(U-q|kK+r}2*eo=H^ zRr2MC*sY7Yoc|*#UpvabE%um9mn!A2Wq6S*H_XxUazfnku#>4tjpFrbPseyhj)TUC z@n|Efu(A~?n?$+w1Oe8IbJ7GD!ti>y=bqs(O4nCE-C(%eSvtCb4lqmP7XfD{TR!;APgz6(f(@k;i@KGtd)U?W!C8xyt<%r4> z^6xe96>2!kupV`OYC*k%(Y{Zx;ek>1!^NGi$}5M~LlCL?D3WB+K^Ems2H?g@NG#Gw za~ijeH!G`ozfXoB`ubhR*BZQOr{9HN6t$qqISK_$P7Rq_A+V^)(z`h0?O!vYBhF-H zF8Lxc$sW^#3F9^{5xNl+n{hQmiedt5*&F@z<~@;3(%#2rIhSCas6fI->I!u@j6x1v z>_vS}G@4c>|Mu1skkN72MqvQj#HaOjf**o~yOa?T5=Q(g)gIeXFSvUdUD86{kHVQw zr?uNk&_F_~G!pRs9%cHy!XaNAefI$J55-Ya>ZLi7^wm^FBr7E4d1Gb!zrF&@&HV(k z&(;42wE==qx`vdWkwT$)H!YBC(!0RkpzL~u-rESqXwK)ah>bKyGq8s%IY`{(=ZM#B zlZF1uz3G&eau4_&=Yu{H%i(#F_BR;4(xg97ny|gRET~<|QbEBOY>!MT%{PbZ*)P4o zZf=={IY1|Pe2}x=lo5;8+5Q#K(#5NW=Bm}YzSKc8HIsVD7Q%@n<>}oii@XRTGO8%y z(R76yG&zky$m6mgIf@4|bQfidOfKTA`Rj+v*<6oILEpFL@y({#tDTo`_25Ze78lQ$ z!~L3bWW9WH-zi*Suq#OFVUiE3gPL5+?Z}OKxwT}zK>B;f-$g{|n!jTiGQEuH8|66p zlMXDtP|>q4Oij_FVFB+EE$zNDX)|wP2NCWCq6E#!)Wxu3E;T#pXRD0Ua;tKz*%u3=<{8B1^Q+3KBv$}v$Lxbyw`N9!GlO7+Gzs}vAwh*WiJmAtdHL`F#RwT!7~ccGmk&`21+qKiJXl6Ks90)Ch8rYPTQC~a)#4~= ziMBqrMPEu(u-5d!lu;^Yuh^hZ>aBZ$Su=`R_hQ`u#CUryoUt-(RmjF;T(c*E5}`21 z_c7la2THbP%uFddEuia!6SG7Msor2H(0I-!jxdll>>`0cs4j(|ji=;wm%#u^22G#$ zDHSk!bPNitqWbX_S>H0fZjWce40Md6;Tl$btqUXJ;RA90fjpB>l9UwWMG1k{RZ0BT z9gnw5s!D^{m>Rj=H5_U<+)8&ySl8_@rKT&qlZgeW1AxyeyhTVgh%*<=SpraW-Wc=u z-SsJnc_}$l2rVUKb<-TcUB51vLGS_&<-4_I&%w~7=c_lsed%5J|V z+FZ%3|I0&yL*u<;p#Y9MFnz+fb5{&G#GlXGeJ{zv;Pcg{r}RevV;e`16GZzy8pQb2 znTYo{C(j4pTS-u@0&h#-EZ=WotbcxHO1sY&b$P!~p(T5~e>oeE$ousN(4?z}w{^L! z;B)=C4aL5*hsyCX+^e^3i4`)w_7wyyFS6$@5OT>O+G=zWQJ92Xe4$MYDM8Y(%%a!t z^nannKAT)?M|Hiv-Vr|6;Stw*Kv&rS80qbPe$UD@h4c4AceKu?%LqW8S>Jipcyy>Q z33)m(RwfYoXn1#u5ur;(gpem|c0&H(;xv7w-vleHM-pZ~cf7eB1iw8eA`X%30e)ur zTB3AE)PNyC$e^=b9e_y3bmMq2LVXsmtF-FfDFXn!qw4+nEfLSncCnJ$a#w~nu<2v& zBZc|Na-v}Z5?`WW5KCSHC8+<~oQQhrDb1#op2~&9!>J>x3A3C405yxVT;}(L@3LtC zAE}b>7CV~Yudh+p)ZOUF<%8mJOSsOZ4BR&RD>Ggz(^xJO#fgVu`;L6c~-bFeLV^Upx#Gd@&h#Iwgw`zwzmfrCX~O*j25tH8sM1Wsy>V&CRfN9)?8^Gvlg(KSPJCZruwmgj0;z7%k?J25WndZ9EU|2Q zy?i#IJPq+kLFxUMFTvVZ;wVh*xv}=1`4(F5R`JMyoKh#xK<;&QpyJElOXnB^zO?rS z|2rxu@+FB@W`2^JAK7%#0s@zt%`V#a z5RLUSzuVcyM)&AlZ%tv3RfXh*aT#3)EtsK11C>x<_Q{leG)HRcXJywFE*k78(=y{# z{U8|l>69Fo03cnyN_DbQH~usz9YauxHLSIPM87G;G+lrcU-9-R%pH6BT4o_1Hn5U` z77X_=2;~oBApl^n`Lyt%(hgwCG$9IB5C#SPvG^rMu!ZaEe?fO%?$9(b+yeuQN&*5c zs9BtS!Q_iAl=@psFB^x}muc;UAvM-_A1-_h?3qC>cP^2n{4IP?h6Cd#AmuG~M?xsS zn{Io9uR~^JfP;ESJjUzHz!MlCvib8@an|?&*wD&Z8M54!7`oto!Yz zJrGBbI8N01F)aPtXZM*M0KZzYKW7Ce^}*XPBk=6xKFNreGo!0rS1^3`?qr*p-RD-A z@ZkUVqCcOF=#6~rVd>?r(Lx4EFueQGkDT5UX075|w1-5m@UvY+M$l@ixbpRJVrPYC zvq9H#l!q1qE)9%lfL|`KbFJe?YMIjqowvO;zYO-oVhRebgpjz)m%InktmC}hU>=tK z(jKec?m%>^rEoxjN7lWg15)Q!RJf#kJ6T@yo}g-A*pso{@9q5+zsbB1WG^@(9+wl@ z`)AWhZ8Vga7VE0#mvEX4SkTGQ0#sEPf4IjiO+8tIbrsYAh!Ol%7T)$WSv;GnP)Hiq|j#^CABek_f*Wy2qX zJ~o`99xVEMUg$tPl-tv9GCcJRLUB7mHQ~$1TckXbLw;JIMp~TDWd6^44KE zi@^T(DLH(O-2`w&EdLoY9@7xzlG}cbA%tlga zoi%sp=4{w*dK2%Q;?7J?H&nSiK8S&pp{e-(o5k74_IC4d-TGaI^MW>~j*Z+J7Qfrp z_wT_}ir`3cn{OZl;YXDmn?mnjg;2xNc=KGpUcShw-WQ&W%E)5wi;)L0O~%0*(~P(C z4C>kp)l-cu6*kqa?PQ$A@;mR1f8j{O|5(q_j@FeV&F+4>!h0vU=QI8!6f5gB9u4hp z;rkxsWV!5kZ*w^8wK08S-?+p4mix*J?cJL+V!yT)kOu88-~V=RA3`Ck+s3kCgZ<$aPt>|>{CG* z862yreADk$w>+z$;|F*6*X|emY6ew}tm`xx-5jIeZxDYo?Mx&qv@~%WcLL z3s)zgfX20Q#{jiWAg~BHn$DylE&LReQ}7E32@$$1K0~(qRWv2+ki$^p`&56@Rj5_p zxIMm%w|`JS39MseqQVi}Ktw}C4M;XVKJI*)MMASX_8oeJ3wkf9f-QM)c>K83;qCg7 zn01pt?;tY?jZ%`N6p7TJ6n&0!IMOwRE3{$sC>c?K&U^y4dQ}|yBF|YD9_a;jY z^_gCxRG5ND@QbO3`Ib@*}mEd-}x?yBrUOwqr|n0QUTrR zs9DqQulDWNrpqJq-^__TD36sMqaSS6 zcy``%)Z$igq`gjXw|XG@)(MrB{GsF6OtcyWeWOBQzVgk0*~|A$pPBedX)ge2{2O`# zl|)cowI@0h_?wjQjmPESUkSITd89n1giJVC4gdL2BgjJAOYPD`c>Pe>__JvDD6d`S z;WJbp&9`sh`aVj>zEz?U4-!!_ScRF34j_wP@rkqd*LMlJi?`vL;EhBgTC<`4RmhA|FgzU~!FW_PjNUcm#Y+zc@T!ChHf@>XEr6Ay+3! zPw-CFe{gj&&22h;L0cho&>C^p<~<|nwDdQLbdWEKO1O8HfURak)yiykA|)mfX5(Rb zJ+!XU9c<~i0XWqY`z8rPQM%S6qoEWwyce(8d?%jwg(z}JHJ<5z+BO_sT+bYQxXib2 z&z?v8Ubd`fwjU(%u6I7muoWU>uqM~D_1*eid(tf>4em9X@kPi|2Y-?!U3Pz48b`t% zG|Ch_PK>nB_uvS7gM!Y;T)Y}QMO%GNqQ~OFy<}X*45Elf2LwFiXP0R)B)>5@je!;$W0=nm=b7LZ1|LAo31 zlJ1c1knT=_@9~`T{o&_a7yH?JueI*lA|rpY&ek~3oG5IhOa3CmVIZgBUBUTa%*kX$ zmhgHqLsFsUJL;kS332dy!KS_6Q=Kj~TenVhyidHig>PrFmU#EN=Q|ebQNdxeX|F3( z!RjN}K%f-weZ)7C7qyRF<6I^xN%@n&3tam5Ij2ttF~DUIDAVFyU5@mKhmDciCvKs4-+bk9^R(?+f@UQQ3a^ zQ*Hey;G6Hw`I2`F^is|{w9SzWr;FSEyMMGV5nIUT0?qSp8UQ5B>G<$W?R;x#&jd`cxhPp0&@?vyR z0jk3bHP5+s9aofR9(%7H7h`9>^Kzu#f2{0e<#+MKDk2rJ;St_S(e$gXIUrDI(VQ(3 zU6hCa{HUU8iIe!JnX;B{BxRT%*A2mX(fJeAiaqVqBe(5Sk)7|$@jITOA#cblu=p|` zIXJF&-P(^Ip1ovvA?l|)%edy4ISEZMNJ6hBQ=aF=3_)yft3Aleurc5a?6=QrIyQBy z+A0w%#YGGdEiS6>*JAX9&!&Om&>yN$F?=E&;DN+gRr&MpCueI6xj|V9p`6Xy5BY@^ z;kKWOhl-YQKZvC+AOkl8DUW-8Y5CKc?>%ZnoLP`Dn=#c|N!+Ev(HLn#SmFIAW%FVnt%nt>LrTQ@DtxZl)b3;*MxgxO+O7)L1TRFYjY#Vf?@IT1+A5-4Be=sm1(;Qp9) zJM$6Nxi{;&{6>Yv#5m@=68}l(x=J~zq?BEdf;F|Nze&y>R$JcmN*4~i;s}HYp!=Rb zzdk;kL^#Gl{Y#Zbw!sFwIu{ZfI)lhJs;}1Zch=Fp{Il*wt|w}CFLM>I7XyCh2k4z= zyN#U(KKv{`VqUq%1?$d51iwhc{XynPw*s|KfHUH&FiI&^6@*AzF%05nCV|k^cay5i znt&<>m6o!6jtZ)UfaTDGN?KV=EFp80L8i8aU7pan}I zAU(>xjrBK1!4_H@zWXFEM?^q`?{_m&Wwi;X{z1?)=|_bOV3D?GM*gN2a|ZJ-(A8m< z30HRse(>I;O>SVPOLvN$;00|YVLW&+qRZ`H6NFs62zwqao&!Fb7`I|IKk6ZqO=eUa zgLg=9RHAW6rlN7Q@kkVWxK*o2u%BonJ-Kzl87OZ0r5rhLU^HiIs`TCAG}u(3{&^}s z5;15Umxo6nkyxDOPron##ceot9%2@R!oS^|i+w%Y$4l}# zC+E~MyOcQ^_Qhbb6mhaTVa`wtB+T#x49;Hbi1{_aw1}RTI|*T(>v4V!SA@y*ClCYy zFAkcAM9paf?@xuLX=)qtk#9CRZ8y1X`;vyOMWgMYyUx6N?ES0NWC9#K0&J=*!p-{} zXM%KrpZ|*fmAgsh&3!oN@Oqxl#-bayI@J_Cu+!li#J*khFwK%cT~%1%<+y5G*X`ob zg#mUz{ck~O4q1rykEa;I^Q)Ws!Vy&1=T@Xt>B`B}r8UWo+Uh)M40ef^x6Q^KoGNsd zlGLR4=C-eF#DDw&Br%Co=LOUF3M5anYknG1d;299%cnXVt!}@>%5^iD=m7-1RRU)( z)m%&U-N?tt*C%wpR@h$yE3&m5RR|0;StI_Qbews+dZO*zLc{3!)@J!DgZJZn^4arX zdeUAqIaEw^3qB63AlgntUkZgaqkw4t#moKgV8FA_O$sJ6)>Gf~8}c6pmoS(1LCJpD zC?fly=rXY`e5I<3h zhygcMKj(M-S;)>mP^eglUMKa3e^WO6eu zV6(9IGXsB)*ln!?2G79s6=<9}$~ti{_*-wBf7jzx8{YzD@W1}UBH^HptFNsF&6fFm z4Yb2i$-Q@MAt%WSj>||G!_qpdML_25M}ga|fH%)qj<6Bwt``oG+2Ycg!_MD$&EN>- z1e3tfz^|z+_OOK9WujkHxfU~tan8V-m&;@`tlvl z9WynwtNFW09IT?5NWFeV+u+PeSYMy}8&1OYc<}!$Gp9j*DvTnv;Re#pswZNK$v3lzuBSfj3)AC75VEPRv!} zKBzT!!A`>Y4Nvw73PB>H+rKkaZqUaWp{y<(aOyYW7Z3i!W}GiuM2wt~X5&z0YmkZnGbI4?4`yHXb z>9Brt@JIL`is#Djr0bs4nkg?e2Zs5zV3$r168UK2u+r7Nu?hqS^+f$?LB$mg4ZWS{W3GFb|1Y>N{P~cm6;~0(NOI6%$nn`7X@c^_IQ~BZ;Zsmxbr(HanI%@%?bfw;b~>!sHA79&fE=UkdA_RHumW)+Pf@# zpOZ=vbXF0693)CpftwjD(#PI(5}!xEpmWX@z?Hu;=jfLlwv5%&T%DZi+FClTs45N` z4*g@ltW_$8MXoqk__aVU+cN=R8>ULKTP|y7Wu>i`JwG`k;u0VL<3Z8VD%Diqa;D`0VPI{i-hN*asq_JdfQox%x0M^V0swS8|jqWJfgU%%ze5r$_zS z{zjP=bW+fuY8R@VOoNwD#~=X@PZ1DptE+5b*&=1hxlt{T9wLvndL3YulUwV^n?KND z$sk%SS1FO-okaytv6R$9Wi+O>!PhWYV8f(i{Q>)wG+5zoyW{QdR`p>$+!xk+Ig*-T zPaoEZYO2(ash+49fnPVeQ7LWzWHEdV1_hBBi^fRiz&=IQa0nreZpXY{a<5OA5_c@5 zUj;ui`7h2SG7NV&L*OyX>bFgV)^ZZ!Dsw4z+lc1=_0ieum$7sB0`D98%=)in9JV{K z-bNFXx{oou`3Ku1BK-SI*H}QW!YzD17^8bw8relZkp=#wWMb1e^mkP^mz*X zXueajTshAM`7yK9+as=3KrF~p-B@z+EcFvDTiC}iGB~DQFeMJ5CeWN#QBm;NGj}^I zj`AvElXE#mmnI|Vtn7ZGk_3}cV2UD86(7n@E$kc6WV-}G0(-VCTpdiM+g!YPXujgH z%CMtB0-Xr6@v25j!tyXo`%qfm9;=~RkQY8AyfA1RMl9M%G|JO*nVaLG>sUNQ{<2}f%I58^Kx047{8FylqEnm zboMcjkSxg?nuu^e{TR)(n)<*GFGgPmdpGz=*+M&+ZzY@F1>+GH*DL$=p=JD#Xl}mK zVL4Z3Jey8*dD~tm%&nOHPjdm!%hb!8vZZ-DewNA4?;r-jiW(CF7vKCGdOmykQHXv~ zBEM%GazX%2Iu{00WxrRav%!R>@JcY&rJeWEM?u!35h+Zmk~RN|LlF!xQ^kaE=okYN zGYn?G2=>w!U2oNdh@)o{Wq2=|GL$RP{QH2SKR6=!PutpGf`8;rpUNrO5op~zxk}=E z)I|^2Im)C&NEJ-l!$`~;`haOqC9ipRq0A%V6@z>(Ckei&ihN-8Llql&qQs)PC+Sjk9OCMm+fuHj z`F+RcY?>r12hSKQ!;(C0JNXsCjq0R?_Q%!NXL=C?W*up*P}3Tjjb)eA(xFxNF+uh!pM`ig21bY?9qi2%>3%vR$E}M(%ot` ze25%75w8p^qePdJ*h13KheV+Qrce$EMES*_0FMC{lcKQ<#c}h5&{>kxCI7^W=!sK1 z9JiuAEQPu6q$9uuZ4hBc$wloTi@{(+8%1$R-Oj?_c9^xazC`x%t7#U5F3gq4v!H&v z*`I!$CeX*Thrz)!IvpM!m}lKD?5#bf5BP5FRs66-#03@LM-Rn8M~cg~UU~5zMwQjL zIHO?DtP?T?I@T*0MX;>@$BaZ(oIPqQ;=XpvM^g4oTotm+e9x$R-@w z*&{pP#mk{(2yJa8(CC-{z{I`>2`BR(%AXVqEy(&Lt%NEiOCxt@J|<(p+Ys7oVu$s^ zWJvX|NdZMUy;6g}s$&5%aO!6N4rM{17|rxgiquH|?eEX^IC!*N_{RJ9XyxMU@e6xL z89R^%f$EuRWVOKU7k@DCIxZQU=S>g|!2oo$&VyyZsxLi>ct%m*fhGf*xhtC|!Z{!2^;#eB0~e%C!o2bVCuAmdt+*xfBMWE_-SBWMBfYD;3{6>3W(0?}MAZyRq)tzQak`<@*2W=M3=GhfE_vROrBj6bDXZTQRHeJJHpeSz{{SM zO*FK_){yE%OBqkONcd|cN(-UP98Pk#k%$tT(&my;z1!yG7XVR}|86d3ILlGN`k!(7 zFb#)t-}fxW_kLdgLDar#EW-Ks;qjD}DUa#rat;~*Wt3>N)t3Lf1PAx+XXx>46sfl+ zv(0-IGv9|HS?oLph&1ihoaLz>0tT3}QbEU&0v!zXw-?QP-;jaAzSmTs9RzQ>og?Ar zm}{4N)*Ddgt(wpR9+_`m^RY6s8PS<+;Gs|qtL6nW{`$p5tZ7_%M`{Yo{0=SG37r@) zq*nh@+Rr$Ws?vf11T-trW&i2M2>O1RYizgNe?;S)mktu8!GL_^OQ^BQ3HE+RMh1$M zyOC2!(f`|utK&imHA+;!_<CbMtG`t~Gjb1P!NCu%6{?z={kN}DM3BV;%jx2cIUKkw@U08ZDrGw4rHSlosCn6@+&^8xrAUN!RHk3M?yH9 zZX+hRfwv0e20`C5IQDdThLJz@>Y&~t|Ekc0z!Rl&YebjrJNI~8{61FgxEJ=d2;rxg zDp1Gg?=JTv>-x5K(Z}7nX#?jqYsB+<8SP2?rnux?mVDZ0iFg;Zsj8Q;)p?z(%Z*_c zg!U&dbW)*hKa+daM72+^H63qBo_`T2#HnSn4!P9O(!Lp{kH^{KF|y46Q7TSAI9-sD zDn%9dz332pY|EYdC)7X{)YVdtt?< zZ1B(IRHwfx+5r%3f6xW|q<<>qZq+HSS_Q-8xoTYBs*_SrPq9Kd;0= z3-u0HC!AFwr794A1mbl51_+d6z|dv^m*FNcL74#LA3!-|J^Y`)dl6x@w3Cv?n*NC2 z0YSA!)Of8nv;3&`fJTgVIJY~Ef~ol1y`ejyr=hC0laR)@^L`~Y-X=cOcQ3^md&?KC`i>{t(c>B$(MlqGYt zNxf%MW7-`jB&UjTlZdq6kuoT9UC2|dM>ktWwCMrEpoZQ?IDg` zOLZ8Yt6g|K&Vl*zR)2kJ7OU0SFJ|N@oHOMfrPPo42r+Gw3rRmqr=yntfDD$sEvdL2 zN`E(jLmt;aj}3)FZNRaXN;2G=T1oX5ztZ1d50_bU{f`x_XFs_+@5(fEedYS#zJ-LqAC!fM^{m=wMf5ll z{Zj#uum50(N4RoODjkPTLGM~@97pEyd8*tg-9)*J6=HTkB1%$5iOk`<@ek!Hot9J- zisDqk_j_zr5EL0qX8dTWgjm(zY0M-#>Lsa8TJFWY{0X<5k8KM4z6PE(m%l52wlpT+ z?rQjMe?EJ#uPLoiWJA~a$ip+Pv;BuZjUoZ#rwGaS2NBPU~+nf*eJs9aJD zUzTe<{LE{-fTLa=^rKWo%v^1OfzgVban=bZ#`OZ&-v^|=w#|t~h=edWbxfV1TN*ul zD~*=95P@#Hs zZ0cwt!X|+1S%Mmr%8zi&BT+z|Fuw*F<;#`Oz=vWL)gI*k^z@fqW-d9&MLd8(Z73undQQ=19C15K z9gsDU)#+!mhgeCPfztCaEnQO!Kbi^3TF@en15XC&J-E=B)-RyKkSeTm_9|;jGS!&{S4jC3XuDiubD=0(sBGA*SIuZawX>n)4++Ag5;6{V1TtK#(`DF9m4~nw zYP6f_a4VB*gN;7_8@?(x4uggxV`Q*z8*x!kdpFc zj4b4RO&yBWab(NR7&f17NOcqCJe8WVxZ9N+v?=UoQ*a%?4g4%*W&X~}k})}r>!CL1 zv4^!p@!G$OO1VCdDa)7j7DdA3ofWyXAB=qx$65F}R|7j1yP#_KK1NzKF0AuF4_qy4 zyGula(Oq4?tWn`H`LsCeL6mxU#Lq`7)8aRa4M+vxIY2!h*Y20zulqiqby)7bXKvl! zscJfO(dKU7jzg)kjVNDiJN-+j7qr>ry)`-7m%iR~7QBboXVB^^y5%V0;8a_o@?Ll` z1wov~ls&a6GbRYaL`AJ$5-;{M`6b}Z>+M&5%QgXQ)8HT4)~>WoQ07fCingP7V$5XD;KVHblM1>KqMtNOwK{@ih=kR~o1MC$m)KBPj?nUZc#PekN zX8cGqa_+2Qz5JZXqg!ZqXMmMbv7(R4Pr;jyO!2^0Og%q8Ma zt@$p4XsK>*^FZoP&bmNCRt+0nYgW{GB}u!L&EP6{ldDlSD}zmC`r+W>@BNVMzb!Lb z6t6CHWG@lAgU#4F7m^}d-P`0L4m>Tn60&V#>&=rcttF#jAVWY7MpXD1(?cN%reJEo z!W7-QPz=sS`rIFC9Dyw6LEa@7kSh9PP%pN2sf@xa81Z)a+0glLe{JtnLGG#|y^$%t zBJfA>N0BmC9ng1K8aM+_GeS@y&4+>h0X}{{mX`f3Nh-(3C((x1;kiDZ>@?Q5de*Y< zptE1vRBoI_kb9F1qtObj-Zvf?szY9}gnrS(>4-d6EaAxfMqPepg9U%y{mqqFUDY@# zU+d|!KND8}RG0tVUKVX&dl5yk5%;b@TmSA+W8MBHaU?gn+Rg9GOX#w2L&y^Q{dh#M znNOcu-%I~7nz6~a?6&-E5!pVqPN4mgPUo%n5!C0ei5a;Kyl0BqJCbV^4MmD0 zB+8O6)6{egItk~b+ktYeLKmA8!9B4{Obh1h*in_sm}PBwBMv6|@ye&NP(enF5Y7+8 z*GxM~C^D7v70W2XEZnLK6?7GsQ^Wktkx^pi2FAZ--;W(<$RNj>ZYk%6nzs0!PT0ET zbE7xV)ApQ38H$--iTnKOn^ZEc!H)i{RAS({&+yQ`zjCB^H~ijJk3iB05nR1(_0@!p zSCHN3{yb+>rN=4k-1T-pY3PbT8w@ZUIM;AkWizmE(o(UBEY3oKHvA<7Rz^InRFUu0 zlS9P<6LNEbj+8pJ)RI#r*eICdsF#?P?R({LRr6L(sr)M6eskK}5er6;Xw!Mdyq?<$ zsz&>98v6_JKQT)kO7>%&LY5gz#YwVDg6RP~nvmd{#d2_I9iUG$9mRkOS>4@@(|v-{ z9b(Y@wUUB^7XinzrkPZM3};&u%Rg7R^CUM+hb(qz315!}J%wiXz=Nb{GOa!*I&^gv@Us7mX9U^&Y8!);VKssV;c>dUEZF(lWlKZi^p63rP^D83%b=)FiaeJ7H)j(yc1gk5 z>QFS`_(!f{H#I1yIMSq2`+eDO>YS8gTVfPA^|ejT!|LiE(nrb~r`eJ~Im1t~;R~e= zN|~oIVje{P6iAKNXCy+2a9u15CRBNtiJV>Ppfpbq$@9YDzJBu$jUH3Tl$;l`k&Yb#K<;p9I!Y4G-J?~ywqURSz~^CiJ|~e* zFaQhLVC*J{rC?SyNGv*in@wnU&0|W08)$PyIUzUa?#oDyXGIhwVT{ClIQqV3sS|^o zC|Sb}Oqt+3UBM8(x}OQ@^RJi6kOXIa9|<30+29Cp!zT{`)V9=>`;_ z$i|)pBoNCP`YmICc(~43SrgsjW6R8x``f9lqSlz*RVOZ2Y8>n6I9L;%0_gSr=Im39TbQC93u!XQxx$^^p_jx}{$4=BQYzSFbYAWW@JVIRPR~H6`moS zh*9G1kW2G-Y)mT+wM=BaO<@Y=<(Gc$w%w4jD!w;F>RozF2z$pC3|8bN(ewo{_#a4! z`<`iNZ_um)U_fdd+?H->uF@|<=Z~uyFO4K6)l((P?uh#g<051L2VH0!p^SkG56a-n zVk;coII0ZL)D2RzwItuzM?rOhmCDaT(p^;kv~dd;?5o33`Ws&j)nuH~GbIT}C2*r- zD$ha45nzSveBbrlV-w0D>=PK|HPX|Rar}95QKsx6t4qdtdD=zqFhn9G6XJ&NPv28Q zyEbCCb)LVrx~}nP6nu!6;-O)n=X8orts4_?qt*ojRL5?u5H>vXit}ob-HW$L>Y^EN zY`F3Qe;*3Zx%J%GA^JCn8a;g12_<9TSfSbbJ(AFvhU(@T;Zj;EZ5ow3q1&rV>5xv! z&ojMmNS!)JKMR$eO4&jteoR&egU&D3pO&l@_NKpz^a^%q2C(liNYJ@DfBOOR4(ogE zb}+qEEu8v0*5J-;^KIG0m`y+LZEKzOKyEKz3rPjIVHM=1CJh#BzcuopcMBp((tR+Q zh@edVIhJ9pt%Fhn)b6vD+ArEbCpGewpTZcnm|&Bd(SqC|_F*+AwkMTJ1IOmMWxDi0 z2+#>d-<=_!#unC?eQwGSNMX3?6<3}m{FXw>LbPZj%Zqo`ByjJV7LgQT#lQdBl4lcs z1UlhavD8^lgV1u=CGYz;N~>xtVT>q5Eq({inrgc*do$0 zv~_#h`jU4!uYSl%6vC9m{>It?b`-URO=u$q_9;2?7mk+^31xgW9gi0WDJSUGMPds+1_apGS zG|S<-(RUNfGsTf%(p_rS;q*4fbgaOe_FA}WR6(zejaaKHZ<}*sPEQHOmXjZMx^JLV zIZabiagtb%i?v&PBF37VY7e1MQtiWMWt2Ld{vp$Hi*$I<7vmCVn09Qbfm1RJm)WOW z*CwG>$wivhh;l})&r?^O76b|OOv&Vn9WS&IO~45U!JMt2Tl9vBRCaL4dI8Z)qix2! z#8!p~>H~xoHi^4&4$(}?)4SV}@}an-IK)=Y^WzIPv-y~C0xS(*51MjjWrCO!@DSC&K8EjN*%$F6f zVXhzjyz!g2wbeGD;Ty5DlWS&Q5fN_Yc=oR$pMnymXpL_4H#F~U!sRx5_;>h-PvCyOgdvq?V4A^i z_yZ0E!BeGT7gk*Eej-P33o^abS#rIZN<(3*l?JLcpu(-`yLPvAq~d0eoiNW#GOxM@ zPj@R%{UpXviUTL<4sM3&Jj|XxzC}B4bH16Kw_a~}*5&p&k0a*)Cu}>k`cGn; z-PN*x7++n;D*0f4BAk~pULuM>+YIg-aAw$mX9tBlU(L<)#R_-GMGY0Gc~i4f2U~Ac zP=?-)Y}wDT7LFa%w6WS`;`9Bz?|4EdK5qS6pfOZbw$C})g$&s?mI+o2vRPPDr>qD2 zzfs^S+^sB5kQP-BEuZr4cd)kAhN4b2$d4tqZb8A!L^ApDW{$ChCSWmX!5FpgCchW4 z9IxP(x3G%Xd@poq;wyiWgU%xiXWz`zsH3uq8RG#7ni9hI7g?uS>csCW;6(S=u*m^H zUv3nJ7`6Va5Z&4<+9neO$tIVR0sz?p-)g<*Z0oHD zZuomNDSKG{=$(F4n#<*4|6#%h`nz6MGS8BNGA;!|JC8Mv@nZ|EiysxUhJ2zf- zHjXYvrDlE_&mQ7Z+gbiwLY)q@Z-^UC7Z+(8LAuvPY@06d54OE*z8rsiOupSrS?Lf@ zCmPzVlXsE}1qxr&mp{A7$L>QYovU{hIHpUp?Yx0&Q6Zt=f?KI|ec-=V$wOV)$bR0| z5J1=L`IzPR(j4>L=e6sTm=Dn`@Px(TNS772d}g-s+l_fy=hS#R7X*mZc$YK-CVaOT zv>UVDf;v6!=OYRj8?5%CPSMl3Z2$A;ESq2O{Au-TS;h^Vam_NC@>Hf76d?5U$GGn&<(TWPfoZQB<;MnV={LHH?2jy4nI z@)46cYyFC0!Ek7P4!^%r#_`#Oh?KY2>6Jz!TOk zh#=5lNzsG?XrmU4?P?`u^r;Tb4Q_<$cQelcK5p`vpi*053j@jd@@EEuzDri&eNa>{yN7jV8h9zJIa z3cj)KGb}j+Lj_2vWW7&>pk4bSOAd#q^`1d$*Qx5*dY?FNhwYS8CU~3ciM{`zuI_@! ztejWpV1ft=erKwg`W95o8nLY1|BVkLn&O8iqU|hfnRHHB1g{=9+IZed1i5G%S8}{( zD4pSt#(ysjfEj)L3pTIr6QsVEs|;3>7UXktB}zl=>TeP9F>{2ddsRN9xk(mpRIlu; zgau%sCSo?dXnKk&e;$2iW?6GwEqd9%+U!dHDB^Egz1?*1%)))8gK#|?XLxHS!j>8- zo(HNHKq?6-TKe}HJYirUP1G~xXVnw{SLjh8!chf-MCO5URyXtR;cXVt8_=&KU5+C| z+_T>xe@xZS)}D;%85~zp&a71GC9)I%a2Fy>7)W9k-cMmOye;Wk*~W^U*iQVkNHn+P z#NZ()%H!8_0O&SQynZt6(z$`*KA??pY!14b#li|K4Tql0d1zF`(|E>TKJ=Fgt<4p< zx*m-Y*U>lFx!+h-`i>+f>%L(iiV<|QUKPgyd3vg|yz+NXz$zB;>6G3;fuy%Y?!u#j zsUFrLQj;Ubw#%2Zg*M;VLJ%Mz(5i~4KED}zD5ZR&IU)ew#@4B?OusR^$&7nD{4q{Z zz%ibmBC%fl?QfLVjj;laqlt)?fgji?(3?KWC0uTrD=a6s@s`#t7hIxDx{qOl^ne_X zfMMlZQ0~Ya5*+0ll*_x7pI80qulHDjf`Xj5?*BlcBJ)Bx14~CoYwvfU5CzmXBCj<< zue0$cPy(gTva|buD-2=}0F4=o$H!TItw)uwkKsGh=cv`#Dcs*HovSza(Ix{gE?V6< zI~~RLkCAxM1`v;bc@m>8Ca9qYxU5kVe`OipzKS+RISpM(#{~O}p{p!!Nn~YPZwZ(N zw+yS_Bn!K1nll^AAj`csGmZMn63-|?yW0pMH$j9F-0)BtHBe*~!RG3tu_<$AIFpSwiTc96R-)%KbVKT~KF}^7Rps}m;Vp^oTu)C!lg)+B5*hZq z^*a^yduHPFn9Nap6s&dUgCfF`WUoYu*uj*RpI1xOVb;2%al$EUl$^rvrXdkN;1x&Ud4T1brf8il;xKopL6$ zjfW#!ERV#dP*ndY0N?8gF0VI~i{8Bs#kSHgN#x_YTj?l+&ZaCIBuXtd%d!)**0|z8 z5b@-SCoB#B3yo%~4nI&N|FTUa;_nqV6~wk&(_tK?mt_tQ`se%;^xTR=N$&06I$Cc! zk!j3&u-Evd=P~5LL&Fm6xQO`)ojs<@vD0HbxSXqwl8q~&B$lS2aBQaj01wHQ@O13@ z9;H)Ko|k3S;o(aYfW$m;`?(AVuDf5J+PzLFy#5I_M9XTl`I^hIV)X_8;B4)AT3hIb zJyz>!KdW7%t@LQCtOtmmjZS}=-$^m)&+?y z6sc{az89^(lo#BCL`yO61O(3&#OZm>HhdEH+6j?9WlVNO)LC=m9(Q0@A2;Rsz{_dp z#1{{a*Kz9#uGI)`)%LeRNj7pCNG}C|@Hi<=`LQWLtU;uaYs1#q+>XCx5iX7-Mx*4G z9_9o*EKv}G&u|enRH**{wE$0GP(rM|j;(%003^i4$ll_*MMLjwT!lewa`nba;ltQ< zWQhbd#K@b+iZR4R_J7BPvdV=LTDeMu1d7}#3k`D(4fFZOoA(Vi%N@R}A=74YIDouh zi?F}xioels*G@PRL>6TFU&U7!^0l08wz2o)*XTs}JX|f`MOrd204PNZ`G(~MVhHR( z$oDj^=ZMWLr@YguqJeZ1ER#fo8j&ss(elsa*j80jMFUPHU)Zx<95ug5QLW`1VrZ(< zk?+&!;&5t)i{nITdYBtgE%y?LZ`J0q0@}VWx%8iA3DmD1N+p3^$H3>3F3LBzk3*zR z5U|5Pr)&=kF`QAbVx|N9vQ-pMTV_7k)Tvzg(ysqa{bWYiS-aBlr;0}o%SFV5;cz6C zLz)Rn?lHY~US_zjj|0B4cp5Wia+@^V*F8;64lcW`I&SSJ^vHo67R!v58>%|@b8X~^ z4u5L=-LcE&-8uj3p^^WHhK_zMr|%@kHzMXIji~mpN;rsOg&k{@gA@!yKy^NMtXLSOsSnumq*!w3J#Y zrqf9pc<0RuK08ZgdUu1g)UwKwhRS>U9rv-X8)gI#wwqqyjx**~K!#;Buuqj^Y`61cP@Ym9ie2 ziLa&P(4}N9)$4a?cki9r`(FN_uRT_D$`?e5ZDEAyT@<2BxU2gEEo6R0=}_Z0$@G=E z0_NBEa_UG4BfVe{63aL?)AnoteZZmVw=HalryTKVo&E zy(Tf3T3B~Ysxjc9(sA5OL@EC#)W7o*_IxHF&4}FGCAPT{P(hbT8p3lR^`e`cs!$2f zjU$5phC+h@g+LDN;?o-8%LL>wRg8Im1#5Amd`xerkFI$cxP7Kb&)>6am!u;#``q(+ zO0r(k05v5EXDUy8_*~eAUXWxi*Qxy=bG_rP_4N#Cydofv{ghIp^YHK3p0h;W=90PB zhP|D+7amB~w72kdq8p7Ty&3y{X+85FmilyZyua@FYp zlf~V?xOZCFm)|H`BFp=?9a6u|o&( z7d;Nrg>R=61TMGj)LqI+1U$AbWh$Ev!!y5rrX2VWeNH93k7@=wio$^ac(($fq26;2 z*0FNS2l-*4;p1%+`wQOAAKPii+?YZDidZ-71^^JznZ^7;3@A@`fUWaRzvgU1kHvtc zEo+}KsI)G)&evAORpD-_a=a2~;2{RhKc@a;)hqy50GV1a+z>@TBCMb}P0kiGK}su% z-sodU5T?FZT&wbcy-sBd*iEHkCXyF`3G8)l2LUx^b2%!!P6b4i3PCON00Rjl&58uU zUoyQsI8}onR!R$1&2S&1#I+wrkq-g=8g>#?wsZ(@pwqKe`Pv2FRg?OXC-Jsrsg-{z z{aw@D%l@~25{B{PjTuVoKez5}GGFH%WD#gtJN?O+)xnpm!az?RFWVb)aWPp(Qa z@@gFu6<5A5vy_pXKyJ2x=05+!@x^99M5AuWV7P=5vCvODvtdP38*d|l zZ)sv^x-(-stIbbJZ^Vc32}ll(_u>7&`m}R3c6)|>SXzJDN)~>SVU|ubD#K#&u|1nX z@4UMo+&FaCXsL6O-(~m`^PxM_c8!UBXG-E$u-V+;r0{;?<*HFbzwu@8SAdh(8a|3m ziu?^V`v;L;y_dtAoia|ftwANqHD>B9;(u1Zr>(1_IcwVB;e?vk z{VUS@ebiIoW~L;I6xI+N*>+r`xb7da?WN8#iqdT2OleX|CAe`k5{?bPscuA$Gj7;V z*gSf<4m*fpQx zN_WF>Wr{Em7Pvkj5Kz9jc3Y$~J}n_(0ESIOgn$eX2HDHY#LJ)CY+namBQGB8)QmLu zzYh{~&Xqo%>sVIvbBkCY_e17vb zF5W|TR+}d2pU^ciO3=%-^XhAr&u*}%pqI|=uy!Ej*0uY%oVR)f3q$l^etC$_CPYLT zxuiAwHwI$gHSY`*1W56+E@M-jFw1^gD`{l$Q~c|G-opvrke-IdBH{-z5URNhjbN-a z7IW)WcYiS$>tYnElzRaRrk+oEf+LUUYNE2hl{~(Z%u^Ef+<0yyQJ+eD`~L$>DCl9gbETM(=#R`ur{H zb;m~mZ6af-*3^XqlhaK3&$Mx7SYG%)(V`q$OhE1YTE;A==x1sc+qVL40 zXyV!CMM&>N2}*Q*Yb|vxJQ>ZkbpTDx=|bSp{_NSP?R)39y8YGTKkCe>m}M|`qR;jB zB%x-J+jZk{mV4Zyx?xM!N)KlOuiuwu;!@o#+1Vr&XJND4SsGP7mDORDZGN%+fPt6z zJGQc_%Uh_@EI~ZVa7^YZUpy^{9>epQL5N~HsBmB5_%)FbiCEZmYi+f$-DmzSnEdsQ z-|t<+OK*g*@BERF@BYjm1Pzqfw21!jUQ?>zX@}2fc!6wCuyRPVbJ)zSMfs45CRh>c zPT2k|+9tX3|NIzk03!G_j^63G{%e39hL5q|z#U<)%7*uur`&JDKb4xP$MBy*AQ3q^ z-(pZhUj54eVY`K@D(t2(9-tcCi*kdh{j_!#1k!CqY$W1V`ATYC8XzKc;>&6o{IS9= z0w;Ft4vP$$Iay6?ZlcV_=F^CTfRw2b(jF$7e3+)^HDq$K^i~*(Q8MWT!@LfZj)s30 zOaOr!s8uUwm@wsvZ7Dae-8=HMs}f7dfKgBQ<$v-rs}BPnS@>0;z5fsAKp4M*p37|N3IquEUjmp^EPR-c#80viG!)=7RQ;0k?7>+bJumWB>>>Si@n`lYY!dojp(s|z5kzI zbLm_5op|&=9{c>p_Dd(Gr@s9UkG<-x>vp_k<1>%HSPBvO2_rKIAP{lilSkxqk8Qkcv#Iv0M^KVF^=LY;c66}3nR}-H;a~Os*G1=C@#IsFf9f+I@a`@l#8Sw&7n%o) z4ujq(h!z#xads6J03xJj%o+<^+bWC3f){Lz+)!2#i`)mYY1_=7Ne;NJOC=O-le@ed z01yH$qwUzjHqYdO-p^a%ycAdY7ZEE?XEl(TF>4c8f!3Lrf+-r+xRA zUj~4oi9-O;d+f0*&%fc+s4Ydu1Q*UM#+4AzBa-_*!izhO01lK9Dpg@=mrp0@GRFgZ z?mK_$rR&zN4=zQ30LwNhyYsHwzx35V@wb=&g0n~luV*dH#go17A2@LT1NXK@O>014 z1z3^j-QW9`cU{vcNzt`7q-fOJk9Ge{&zO!ax;I8Dm08LS3g^uSB$;4&UyBe0zu0h8 z_T%0*`#1q4sm%wsSKZn)3zxN&Q-*u*jWjHRc-x75@?B=4X>ZGwKMOmRuctkEK;vI^t z(5lpxKQ)zA>XBBpX)Mk~1%b6|=Z)`s?+4y~{qMF%d+NNwZHv!L>y!^o zJlr1M^l0DRlN0$4dF`IVKke?=Fg7*PH}GPNt$OCfb8=YE4#`g2$=~^%*Y_SC$qXPR zY{PYv>d>xzPxa)!b0-7Kt* z&%g`4hu5D=I#+i*e&E+m9>%9f|LH4V^xsz2(l`Mzsmuk#{ae+U7MA>EL^*v`xE zV*_C@B#=1VPsoKA$Q<&LaHsH+n~ba|@ z8qYlJz3(5Vy1IIh)Ust;ag()aqu;6Le{y++^W6l4r4i z1QiJ?^35gxs_B9#k){0&a1M-d#y}8}qzG$YF1lpPNMGOBBi$`KFEOl3cF8V4JJ#R# zu}>`zyg~phWUuX5{Q9t1LI}>^ZG3$&tV;mvl3ipL1z!EPFaGwqez0|2T$USSuWG)N z@3Lf8sfTaWr_q)X)KmG+YNE8bl8jKTC>wCj7%<9{S(%6p=`#&pd>F9#{OTD55xo*+ zd>%Di5@~5kz7+zDQMI_HNFO~Zq80VR&JcLjct68{$%@dp*d8&g)c_V+b#wob`xV^0 zx%W(Bu6y@B`RPCW$ZORy^|aK!Ua#ejESKhaDHuyq2o3oKRkS73qSmD2Rzp|O4&xjX z6e;(g6=SUgSW%+>4R3qYtA(8t zv(yZ+t&DC?zwN%qe%7`*K09pNWbAEQKhjrv*dgNsLn8%i*sg@-8NXTEcRgI9IkI7Xg( z?z^}=!~uZ%p(ba7&~8p{x4pTJ?A4N>(alfNP*n6Vvt^)@zcI5V{LcOV-9lrtg_HMu z=Mg{+ibEV;i51a^Ue%v){p%EsNXzohP(8`2wn{6C_;h7eSIwo3dPO2)*QShdaY1>F zb8Z{qYnVA0S*l4U0tSSlAgpKxFDY1!)j;0a`Od44uFm$3hzc>rV+rZ3uxX9MN>sA~ z0SMx1(pqaP1rfzQF9u=NbypA|gg5}B93ezVL-WK4IKl!FlaOkaX~<<&5LF_nBnl&K z*%YTf^K2SRiH!2bMkq*_b3k-s(?;7ahV^v9ctWbPRNmO@aA1r_p{btpnu)Sq?54%V zXAj>OlUlcIyrk)V$Ra+Ucrho>y&b@VW|vbbSaVWrCH!HMI+}? zdEj-xur2|tOLj5YOU@2!?T$$@sXNlB!L1f$vQk5*H0zXR-L)S-ium=(XHH*p3Tpz}4^jfRy(lPpMhiC2KYG1sKyuEvFBIfJVQUcrh8 zDpYe+7Nam07}iLCIo+(R1z;h7BSTO24-CESE$>=&1U=V$((`Uz8xsqJZb<;z%fVQ& zgt)SD)@x<)q_`-5vl_bM3xBbYOELk7Q0|#9)=Gc{3k6fQZ{3m2W)sQ82R?LbTG{aY zkv(fX&oE$)8J6c-IP?G+ZlM*STR4t>om`oKYNlCnK2DzzPW{>iQ# z`p{s1bERZgl?Cnk%B z(h0FAe*I53Cb!MFPwiNL+4JK+yKd))1Loax_{(#p%J}5qtbZi*_}Ij8B`z>4?5Aj` z9Og8f0p699XKg4}UMK~+n->9qb4rtQ;3}3on@jDOuN+g~bXZA+yEbpC@}qVoaO0CF z#-1hunm+EF+*@tXqXGb+0Xy&V?HEH;!eX&!Sf~^cOGr`oxV(*{Mc#|nOwyNik4jAN z9U6En`d*_Hyyk#Fiwm)&RB!o=Lf}!(K~Kw(>K_eR7_e6@eGILIUY$)7tImc(pK7{P zOWr(hX8MlfWS`-hBYdVbxAx1f+wPCtGP7#8+g9A>r zv=F$IhFndEzD>2Hs5eP=HFV8z{qAJwF&glCyXxMlm!~}>lq7{9fv3A9&Y^vq=9Fkd zFd$!a)j04dTMz+f;CruIG2>KL_T5)1Hx?66W8w?_k6&U~m+bu7vk(4LwJ=efpA<0D z61ht^WbL;1=_fz=`!^pMcxI`jNNuMs+>S63C44Dk`sLVpcLeTx~ybcbUTGeIQ>43mB*Mvx#TGS}6VL7@&t7HW&qgMa`jB~yu zkuZW{D;C~YcVMEu`O0wrz|iiUZ;=)Ru%ou|7k~AIpWb`>YuG;5Z%>IbLCcxj%feWk zgHiG-g$t#&dOD|IjLwX%>Ss;_ydVL#fU$Vp5ngPEEwHx_UZ8X;u+B@1y<3Y9d$$*3%MBpDCJ9>rkgfS0JVnQrG1Re7JjurR8e$|jB+C2di-_dSz$)ZVnBhVT4l)&6D=|pNomT}n=7>D8u(EY2XAlg*-!Fly>l!+?f92MndWr)F^Auq9n3ul;9L&mpY)qB8{G+O&6P zrdo7giSnkNLsMA=0Qx5OD7Kt z{_eJE_|aHq7?$q`flnn_d>veuZ5hSFd|ZEtkx+yEWl5n?8^}*t{YT~z_Vt8zy7vzs z+xzT8Uw!!D?>MEWo_*$lc)T_AJFm+Y16DXaqr4yV(}#<4jXx0a38uS(-Fv<`{z@d>|McVSulwi4u+{rL&@| z+9n6iKoA?{V9;t!5=M_#PCK(4@2|{zSB(aK83BrC#lo1YrNwlrbEJ6m z=nH*`tTb`VOt;GMtYpsnVZa%K>b&RpoXNO6#r@(*q~a{QS_PoQx~sgrt9#*#vOm$FMj zSTEZGpQ$n7<>(-MM&~NiqSiZl8uHn3%QpO)#4P1%Tx{uz%}>1|46E)grgJJ0 zR$tsctB!kHPdqyFNRj;<06x_KfyEx;Xxs2DVY?+*b>&ne%L|3&o&ln+S zSrFDT&9wO`$2QLdEQZJXkL@ppp1?!A^&6*9`#U7nceH#A)YNVZ>fbbf4FP_Ukr7=_tkn}xi{`c4iFxMt{C)G7y7(YGsM zbCdb9@M?;Q+K)X0VP7K#hy_xXUFN zYenN1MEnx62ro2i?ucQ$Y`{UB0}+rYEd*(D4jjUOQTnQ85uPi$T28M}M6ZA|zywFj zA*cJaV}(%<7KS|P3f3BmMR~M_w2CU$YV>MV?e^su3qfP(HRpg3EG>YDn9l3>n41G3o1D`btkrL_h!#2?eB@RkPx~Osq^Kl*dW~!ahnVsG3Uqbf1NVIPPe1a=-aD7BF`#9gf7IKn8WBXy8C=qFKVK$F`1}Ga02rMZ z7#W?o>P=V6(#6!~g-fmB0w1W}d)*g$a@UuPlU`6hexSz-ANlfMO_@$Udc*Mv@x^D} zx$n)=$3K;B?`XbwFH_fJD_@_Soc!`v|NfDufA-Q2+tjKGVwBUzQ7wUqM}AXCxoi2Z zP0xEtpoJ8|<*&O=sHg%5&O)9aG4axwxo!BVW|a_h-u;=zQ6^wD4a%$=3OtLp9& z-qj+$cRIL>p{eMV*6x^|mLf-J`9rV6(j}>COKyIxTIGT)kx}+v(LlVHLnxv!#wa&4>03&I zBwOUEeycS4QW7man|gLF!%kL7GOH+>AU8Bl4iFkVp=fp~Br-CKfgqFdK7$AdAw)#X zC^rj1A}cutr2&gKNsMyGpmrq)LoTZX5X5prP8EqVPPZvU!iAGIARr=|9kyL7jHN`* zAlKO^+GoK=$hW{7wDOyCSi#_i`ZA^eDM4Af{K?_BP z0U$)Etf)Z{NaK#1Q(8C1D>I&BgfwJ=EJ!Nph?CwX;ZBR@Y*wQ1!Ohyw`+0H7MF7p~ zG(kk=X-`Sut{r+jE$UgRGV9NeIH7wXwrR}U7|NfYLt%*M6$?397}2^nrzTHUoi$Y3 zOm#}-i6tF)vQwx`gqa>$(TSvy>3#Zr`-?r= zuYG3skAC_jA&I>Yo>J9gzw*h=0Pxu1yKcMbGXNmzi*3m;4J^RDzj&Tt<$wRQxR6)6nDkYx~Gd+lXuWo5}WhIgB?v*P0a7BSfe-Ia&6E0 zwvF2^;?C1D4a&fFDFE0G9UmFoxOw{;J%}HFe_y_MuqD0A@d^R8tM-H+7zB&0ncX|C zPVBy_nQ}9(FLBOY+el{CTSel!OjU3ga!JIUt#VAoeh8yOhc@rL_L37?x4vV2-~HY< z_Z++fVT4W>ABzAuM8Q@VBU!EGTR7IG(yQmq94k~b!L`q4DmtZn|Ixeu=1cHrpZoLI zyq7x%$K+B3)`e`cEP1Rnaa@@#A7(7DyqStM=7%Q1VvUw?=7mP8ZSt9CUQFtnJG#`1 z@iPDQTaW+i|H3aG8N`y&)m_7IQQ*}}P7O<^w~AV|k+U!gRy7EGHal(^CEu}L)k;-b zTofhjnBn+|s-)m$lW)!-o|3ce+Ii;}^)QD-lU!dgM@uID00``=e+IXqzI_NEx{OJjEggFB)q*+7;D*JNkcY0YQCEE>c(qsz3rpFb>M-J z`qY(csjQkV=ov+Bh%Q-uR9_N$wfrR-vTDhn9k=GEoC~(Xx}KJz7^O9$tJ*FDQ6dX5 zO*IKDzL-MmS(Pv2P^jPRI&!KiT)RLlA30gPC z5?N{VP__NCI0huhIP@8#Jet+13DGGBu1S5HVuD3aqr&Qp^25h z!TQgXGk)F)5g{1ihS00U_!oo_Xu1S^@dOru!cvU25E^q~mEAliQ#6ukRTq^O8!mW> z&f>!0?ONfhocV~>#;wjuuP{a&xF};mzzD5=yf9$PDlLW~7X$=ot)W<)gYPmxtA}Ep zRrG3U_!X)L{UOv48^<^zxbev_Kpr7BCz#WKfM-%QAu(O_6{=y`rtzG- zm9u9?Tv5WAb|r9`s1iZOdXvOC6enF8a?fPueDJCPEG0=okDrxWiT>p(yn)#5m~{x@ zdMb`!-o}ynGNw0zAYcTDGmsQQNUhN)GP0r(0skq z6HYlyX=+lCRJK-re-Gf`0Dvv%AIH_!XAb=Q z;d`IovNPA+-PU)kZ+v|0`m1lc{_2}HufKfv&bOxZwzI-4A-IB(X#hxMWLb+Oa!?pB z&k4)(UbX0X4n4oz`kZ_l+X!YS>{vpq!;X3ZE=IW|6Hy|XE>`Bx8<%PH6_@1?HfXpb z0OZ-H#d&&4Qey%_z$l;3I~b#yw$aLLzhzl;OVfnvCll2pU)0jB`M{_+<3?^zdCujG z%bHMMdv6>kJtrJGQhL?A+^_ugzy8@D{l)v<`~Kto6Z;+?^2IqSjzs^I>x{*d(lXy| z?HJ3dhSiccb;`7=!3AEN#dByFP$Di7y*UHAiuO1M4nPP3sJpBSHRb`051xaFm1i=i zOw*lm=l1y65ku95P~c^Eq%`FzqzUDwQf*46Q|a6lbL}wREM~gpc(ah*pvE!+ks#F} zJ5`Da;%jI%G~})w8YRCt<5*Qc@EH-YC}8Fz1jr9Vy-7;7%Hv0?xpgtlp}AYD%=uB_ zQG^f*nd>k)CIA8@MgRdOh%>0p`AS^yZK`J_IWE}M5CDjXw1nt8)HP{qZ_KWQ$(&rA zbOE6KviRJv%|b56ghW;BULQVp^{1(SN)?p zgKN}oUm}B5kHcEn=8OYG$H$F474h*>W5c8MSVXC0ay4DD?RJi5>26&YjoXGQ`pu=sK1nyInLZ zcO4H#deojEtPs>XgBU+D_8f#kI+r{-a$;Ra@7U;gb2c|!oc!OWelGviBZY7N!?X9_d1Q2~ zv}tQ%rLxl6t!T{Gq1be3qAAe~0Qu5*(`pLh&mP^|nd@PUeeyql*tE=jj}K860C3aI z2chkUrr}Kf$^ZE1t0P)JcB=28dw(*1@}N3DfF}}RWscA zrVnpeL#@ffhX>yI-kl%)m7Bi*&BtmZIP*<+Dx{9>&Ur!Aa;HE2e{X-+O;<1b;0p(y z-1CdiW|Bf%vrG`Q<>WBr9Kd#15c2EZ_dmt|*eQgDVH`NH|3kli{R5BQF)}%T5MYcN zOL?sNDc@tVLKfD!fibv1DyzJnEQ;y}rY;tSC77lWzjy-1{v!~p zD4Firr^X(-XYla{_j-ZRFqvE45xlU+P=w=exkkI`{T*+*YR9X5ww7ze6#eB~?9YDC z|NPSv9QbVc$QQr%aRA6;%Ui09=3l z4vuy_bM#SBD)=7tT>wL=~qy6un6@MxcuQ&}aJx?%r}uhWcT3&X1)8K)iE%Opr07T##^O z*3WHHm6(v~kP72Y=Z-{i+#w>K8MM@tKm%T#^ofX!dHUv$=L%zPEF+flo>dH7lLCOK zA%@>6x2l6|eUlU~`!nsTmKLXn zEZ3xMTVen(bJA+t6ej|jAF(mPsWv&55`2fLy5Ku(a9@dtC~#R6-sM!nz+;RdiEto{HCywY%vBML6f|-Bg z<)5m!^Y;z?%?)pU_=WlX+hF@&-*qbhbhmfE_1)cScj5TS7Ewb3Bh~cYqt{%!qyI!- z)hn&*Tz_n!Z)AS3HPQ9(b9a5{+S`r~_wRjR>f8T(FGBd&K7Hlz@X1PfOGiiRvWH?i zMqFK-7@r~c@WFj|e(3sN*Wm^;??c-xp+qQ37_MYkdB*E~) zzB?bj_a6|3%eTZ_<6X0Zf3<1%e{ElXm8>R2i!>LGt<`O+&`G`|kOh zFTrO&^@knp9Tz&lx-IzrfBI)10f78;9sq9tx4(OBI~_?O za2n~Tz-PWkC7Eo!s`=Rdx${D>>cdYWBdv7{>E!=jW*V=+tAk9 z)|{>77u3;JWP^jF0+B=N1>y?;(792U6e19`B(CU;7>kC?DEsAk*RwC;TEdj_YRR{Z zK$J;5DK3$xS&FV|e=rCGPJ~5;nh0aPwDeEv^T8)7scxw>>5hdDC)$F*qX;3R;3soZ zDeq1VSb~H@pJ^#^Zp3cc5R(+FH%XOg4lUei?o#!@al8QwI zyJnCks7uAj2mm0ZpcrG0%UhDd)U21t$#RU&oU#Ey*Y*TLKm*>fRnMQWlo*M0l3a^w zNkNGdIVOYwBO1XQdXeXsZwy zU;#CvtEll~j5y<{mNt4?j8!f9QRe1F`nwPWl*-D0P<`^w7cQ{Qv+8sHI>Qnr{Oadc zoS9!OV4<_qt7yZu0!fjhXSXWC8Lf!!YStXh-YH`tbnIK_Hc9kSS7&zmMau#w~BeF)y zc~_LMq>$pIE6R9&+@S&YOj;hP;T|Q0t@$M#exwx@04EZP`ZO#7^+8GDz~)+p1U?H) z-nL!M_c^QH3MGXF87na|f6B}DC}trDJVqpx>JX#GrKB*zD8gs0m#N7%Ie)ZvsECm@ zZ%~Y(H~?feR*K`SbyM?Dek$JOskzIPq&<6lIJ-&q%*E4AcgV(c(78*q%b}JM7=s94 zwQW}=6}NAXl}3FKxiJ$001KIAd!j@{2?2oKL8|#c?-aC_RR0sDM5oZbORr3Oo32ls zc%r)X-Kp}Fm+X){D;zsy?6^5y&ik1z1tD6EpA!)!a#9#D8ZyTSiHI;kaXlT& z>T{DEzy|=Fn(+_6McmfMotF5OBc7c>vGFjxOlf=8sRloO_Ak{qsm=ue(A?5|Y@n|= z<;FAO$8Pz%^p)jxJNokfepT0vNA^4=-t)DicRjx8E06q!UFiMJfBnIM=k`}%`kv>% zKUEkWpBnqjNB=FPE&y=OuDkwfDU6`zx^kXkR zy8q@u#lO0N|bP`S4mkvTggOy?YP#9T~g#-)5`!?8-MZC%4`C z-Qnl%YuR)~;g(;Pwr$@uIXOK(VpS`+WBty;B)G<~X;Do^VaRQVB7|=F_z$wV4)~8} zhG9JX$U}em_kYyrL@eoGm#qgZcmz>5UR$RGh*U4#OZ4iMF(RM^na%Te%!ZOC`}^*J z+u@dXec-KEUw1*zyDl|_3&bWTr+@bC!(LFyr7j;C{%UV;@0IV!{O%uoW_Wla!ZdYy z6-|h1RO`k!bo6K;E3PVn{xWSSe{5sh5>3cuOG)=Ve&;7Y^4Z04`WyqYy4Po(WJAC9 z>+b`ApM10b?(a>%@0W~~izKVsvAz@0ZE3XV77?$;v%m)cxa!JlqGSH^*T43fQ*(qG z%OEay9ZEBHOSkSh;d%P5#UpD8vG%2WHH-xyoJPkzo|2c*tC~B(xNU}E$TeM95>$p@ zWlG&jdKEdnt{v78SgljWiHuY&F44hL@OH*F^*0`1s`}Y(C32oS& zRCFP5sGgPcC(M@KSaHIQCDJp@Z)Xiz31hN2e#L*I2_lRL}29k_l{qjta#LP-`#bHr{ ze;K{P2%#193L(T8ry;8)r!Qq#M8L92&YbHV226<&*IH|Dz$mX2eL@fsv7!lrfJ7NL zkSwUHI@XtO>dAvEXx8GO6>Sm`clPQNrwq@goI&`MB|0@y9HXt#a4Hu|g;%MrI6 z#iV`&kZFqglk>#q3q#%3f))eP9+pXq~}BcXkM>WXM=dN(A1+;=K}!P zd~M1o1WF3GUZ#~N{Oo#_NT_2+Z0@8Z#jv2@SX!8$mr%^_yu56cf{8;QH4iCzGL$QV zj9a&=T1J>ZRSS}R%Wb*Ay_K#jVrI!NjRv`mTB=Q+I${Gr^LjOK83GL8Z+lm!|K1V; z01RzAw9wVqHoJjKO19=003z(V*N-uext42#Zhl| z>)7*yPT*3cK%!Nw%z6l+(C3+Ud31EFP??`9&0&mqm{c~F^q%J``6lXs?-s7Qvgc6x z=o8O9upxCz$EJ1wcyZ)uDTb!m-gfEQ0|U>5)a`ul>_+v9$A3DxcTfNIH*ZR%Y6*ad z0776nhGADZgQ=Ox_LdIQGU72E5isoP#PnEGHZw5X*VR@Ni9b0un9on`+6aSVea{!a z_W^zz06hHMUB9&R^HJE8Vc3uCeg5u8_KiR4?fC4ImC?(Go;cP|4vgKkN`j#um;hjV z^S`+B+wc3>@1}CX&mVepba?JhKmYNy!V7y60DKngeefgz1flifq5a+K^!AQyZ5i*# zlN-9!kn$lJPfU9qEs|MyC!3L;!C2;3qB9h^;Na zVx=$8Xmgcg0B~${d}O+L>+YMkZHJDI*5ToUcYH&6`$rBcGK2xll!8p0gaLCr-nI3& z!t>oFpRQ2Vh2()QFPXJUb_H5m%83JT9{7wg9<6yqvEEU=7~iG*^;~xKwFOw15ES}c zl<@hQzITvf001BWNklsgv|MjGGbW6BRR;i)v91%(h5h>r1e0suc52)9(+Xfs7baVq z&Urn-2ue#jxcp>7Pt-})6Z;>UwuT$uFf~8EsdJSgD3)t*4l7rI2u}RwZ+~ojYziSE zrsPDTjSZL10I&?x002F%?|o|j=Rf^{nLk^{^4s$uK*NHI32pG z&E|b(l)Q-(=OIN7Es6L=%kl@&YH5{%h?eP+w06gQkLE{CtL^H$lm<+$XLc;3SId;k z8*3LL007Sp1rawU5@uRd-(@R7RpTp)CP*p)07)iMp(_p`idYa4=OBo9XYV`TdF=GF`%3$TVw<%SEP%J6h z7235!FHgIbIlrk>sm%JR7CDiX0w;{6Burp-*h%E%nITJ#6G6oDV|J=dc8xF$dE2I# zT@CdDJ%puuR2dH@bLTCw*-nOCjCXfCLf0CiTUaF)XxDpm){StJBdd zgaIMsIaJee{V0tLOH{~N#R^@E5&>}zY|RyTDdm*X2!cm2D++^>6+(o?KrDoo4o7Ga zSfR#IvLQN-2)MIXH!FdZ1=k3hdK4@m*9a@KzB?FD%GHDr#TrN|nHjcSlXAwX$pK(J zhUaEN)DX%nsECDt1pojd0rf#nVnIe&02YFh!Yt%+lIU4UjN47!O6WOiQkWfdd4|WE zL;w&}tm;C+^xAf+=3KxTPxnYljLe;M*6mK{&EohGLy#3Ij+F#y>QXp!iG&aVJuBiJ z@wUwxrv|6Id9wltE`Lw<r!Q~&_Yy-F-4>V_ytj#CW+mjOWME-kk~D~vh5#U&k=Cf$xJw8-FjRQCEqRw##CeK;SVoA<~dn z=X|>o2qKDQr1?=>O^BTFct$h|zMjFcwhFTn;-+B`ZB}lRm6mGapa6j6llc<@aNd4d zd}?r(g^Hw-%8c8*PJ7$V-*~qFiS3&%|LP;ZQ=0N_xM4TD;n7l_NkUdgxsDMMC3yck z-uBZ2U#6uuO>O(uhC^E?f+vW9B#j)Odi2m-sk`&0M9<$odtVwroEo3|U;p+$c5lCF zlk(vR_00FG z_RfTwzHGzxBa{2w0y}ha|FM~U@9O$v!>ArRb?C79y+6MC$J6EUn34YYfBG-mJ~)Bn zJ+W;}lyTs2?Jb8g8%~tAq>bZZ<8Qa+I@dn9K4kt!KeO)pUpX>({N(rk^yJRVHVzKa zn4+&-iUxq`(j;}EQnb6e+aG=Sx&QYIcQ$ft0QlS&ZocuISC5ZPM*yqu#V3#M`Ta~% zm@W96LwimtltVM%BIjGXu6g^rKlJiDrC3~V@96&cC;rH+mN#wLzQ#`(#+sG}5yFmN zNHzs~_Z}P_$n;zWMPq2!o8Gf!YtPSr@K3J#F0Hk=+h6|WOidQP z|BcD5ZwymS?2&t>Z+`z(S6!340LQPrd!M}X?tec^wfDu&vp%ZvFyx`fqMo)^Xc%fm zr#a{6y`uUht3QgUwj&l$7_gO&+e@<=2y5`#4)on~pzoePhkvEk-1{GT;F+KQ;5Y5dZ$vGL|?&M=L&3$q;?=#!9=O)qx1&rLkKrDIpL{X*aV zygj_3b?c^uIvtbw$);p()#H!Oo+KiQ$xH6Q1JB;|)jxl1ZbaYrkckzORX0qRUSKSB z{f)i(*-6VY;%ef~dwDYHe)jNv9og+&9o=U*^Tq-|r?ZoD$3(6?`rLzed}9bVS=ruWm|#&R zf`nnU5QgZr`MhNr;p9-&tOVy}Xt}_RbMQUt*&!exxF$r?u=vIqgIbs#2iFSC(-a@v z+#(dLHMM?(z^$@)vnWWIb3hmcE{ml_yBY$5bertEG;k;(s50ZlGm@m@$pI_VuIO1Q z@EIZ4ssySo#8aYc(Q3g@w#j3CmM*=472^QVe6?Ne)2LE`fC!o(xx2)c{@D{w*RD9{ zAZx^_hM~t81G^H$6+(>AFhh)x<1wGZ3`21VxAbUL5f>-j`B7WZg~GTC06gSjz+x#e z^tfwMQO1G8T6$xEz?k!M8)8m1WQ-?sGBEHgs%NFCL93}#El+z&TXmL^0PqcD6et1dP$okdx6d@l3~Vc;AD0Y_8ndH`3n={ezAvPd|4>B$hB0}XlL zv8ZFQjllP4l(k9(+!%g^mTI@xNo&JX13-W=Ry2V#&Iq$g0THq9P`yd=ZOR#Vb{Hv< z%9;?)`-Jfpja<_qZ%UATvq4XsVvsFDO#9PKB zmBdow%-js$1m+mulzNH~#`;u$fXm6Q}tw=0rL>~auGi}9?81q2iVpEdWYfy=bC zm_K6c?Lx9e4qX;+5#=OyDq*5oa;?y}nNbx2ZAjXS+4W43!v}Ib};Rl5CbMa~?)WjthuTqAPAN+Pq=j z3rr-;GbA9P)Y_}rm5_7JXw;rjGAEa&TqQ1y&b~P99l!T z82tZRS}#{nY){|aamXE*|JL)v_gj4Yrptfx8~6Rsk(t4V`@b%srsoUad;b-m`Svrv z*Ol2#L|iQ!cOLlCoHYbko(i5!z=qzA%l`I`PY5zmOS``N)YtER9P_ z%1L{2@A~!EPh-JyiaBe1$&Ah#6a3I@>)HA{fAEgo*S0?L;Pd^@pA1SHHf%9FH|bbF znT6Vmkqr#@HK%iTKXLzG{O;ZDJ;}fSf9|>F-JKJsOo9czFe>bOeCYij-QC;UQ}br` z-lNFr0M=RNN!wwr&&LXZV^Oi|eLF7O-O*Wlo9V1Rty-hByd=qoj~!~wwZ-+dmNk@R z>7%z@yW@?m&+V~YzZ6q*BGCeBFD#Rb*SxFy@4ot}-~W>jZ`zUh{BQr@k$aC$orHh? z=>vu{dCl9mNFu%R>Kpg$dGO=6{r>RC*p=7Z*w)drWTNPteWJJ;y()e3!?({(8G|qI zCmt9&di20U_wH+M%WS@^{Q?=eB8~PB-gf{SsNfDL44Lmx7V;&d zTf_Dx;r3UM+7Kj&c;SX4&VijLeN$1wjf%sOJ-+W31II=bS?%uXxdgCYCsr?cdsZ9D zA6wVfyYhA4HONAT{-JmNx8Wn2TTBB&mN#?9kM@iW5U0NG8xX=F za|MzVyhKm#?UV%{`z^g|gLPov@U_=(m*vG#ZPuKK2CW0f_x5&fx%1$+cK5z@`Jm#R zc2IfX;LonydR-kz9UJH?mJ1uZwi>4K!-u}<$a6(H`i9&)nzK0oFihji&wRKyaa~kA zrSY)S#YvGX<#M@^g&iB{>pOaK`dC|`I*`!1PYsSx(Q%~FvR{GfWnI0LQ%LBE@BZ}m zL^c3MLAky*G%?WCyutT<&-ae@AA0uCQ}_IM90G!3J_L))ow&&Y3=j~~UIa$o`p)j2 z%d{WfzTb=WQ}WseDJYt-m}88VtolZY4`Ik%D}4F2Q5)!0ZML3mk3}h5t7xsGMT|xS z)JPVZ+q9YSwF*uJ9`oykqR^_O&a0)RP_^DTUl=&h*-|51tFql=1AU2DYT$T(Yg^8& zSgdoJdU+yXNg*qrBLL8lRg2!pv9fK1juHGv>k>JKz+;XTh5^GQa%g$YFXi1V9 z3*9(sWL0NiSapPgz<23u1@cfMZ^Csi1r|yTE~Qs^6?#>V*b?d`ZX5n|%-~fP@#PFc zzXr1^1V3mjy&5B)WdU8FNkAvO%lNdI%sY{DcW=R`6C8 z`ySnz6lSKqX^&smt+cgBCIB)i$%!EFD7BD>IW?7N*~rXN(77Wn$XL|{y;<~Z8gG); z?@rp)P*QL#C2__bBa{>(s#uV4;Iif(t&;aLU5aal9hb!f5eqWbl45bvk>kWJ2hHnL zLB^SOr8?(h5$D#c)p=i%1uZ4ekekK8DhI}VU>1UGk7^WrIVOZIW0X5qF}hcr0&s{o zNlrEJY-(3RB_U`DLD2;*DTF>t=4465<427|PT~wig*a6j%LryM5LJu`O14RuK%!Z) zib1MVo<3=5NkLR`;IP1Flrk+TGRgy&vXJ`@v&uo|HocU0B?U{Wz$o`@8cT`5dEhcR zM)W2T6L3vhne{}4IA&Ox@mhOhobkC+j+PYcYG_xikdOOrHQlBd#gZW8LQhI}+OEw) zkI{hV)@zA%l)h95Y1;CtKy&VLO?Vu00wS>Sz=2Sz3 zAk(Q(Ha~X65M`|D!rZ{7!n3Kk+D5428W!U;Exl3NH1ccj`_H?!y!X)bqlBvaC%*sU z`2ASGSGIgYB*_z}PP{mIhlR!k5uKPi*b~40)cDZEiDz4ywon^CwEr#xjrum5tDF)f zyrE+^^2De6?wvWF8!8Vt72BmKX@Bu1U|NvrqPRylnsgW)5{p&8|N$Enkx> z&pdMH?C}%Ck)bd$V>;8*BmUsH`ktFM07IVVN0S`GG=8-2E4$ZS|CJwpw{n80o#h)o z*s6=!!v`lgr`m=fC=p%j_}pK?}eUi|A)Qzj+5)E@BY8% zoZDya^qH+%Y1L)9+t|2)u_*~9m=ux_LK2=NkmMnakn#}nOMxdq3VBEf5D3OL5CXW# z4L4ccR<~B#)i!OP-skpm&iVZ@tJO+2V88}LIC{NSv$J>R-kE#vDev#+`}w|$%3Do8 zeXKlj`IevAe%TGT-279eM!s84adlnA)vft0o`0UmqG=8fZ}_h6dRdl^9UXh>vBLlm zgw_hZ0szk0;+fXEP3f5_uP`V4@^9Sy*h9}4P9dAP*mf&DYh+CsZkvl(Q7_qkxg*zAuJu;2A?uxQ{;VWKYn}17HK$7H{`9p?W9nVMeM>eQf0>}GU;JOMd*sP` zzuo9?Zn};brVZBOOBUqw8h)Bhe%oV~m!aG`p&2j9!!p)mfY7 z^Jev&^QH3S&I3EfPtRZbGOJGbKL}uzTluIGdm&H0pm%F8T@cgwR;_7QQ_<(y(zk2v z+9LC6rzfT!zW=lrbV6!})M*&g0N@4fwl%-9F-y-}f8DmCKmV@Zyl8}dDgU$^GS3U! ziRkc^w;4Zm;~RVXBZGs>$#<4-OixWml|)y8_0Z&}6T#XL{9JrsbtGYGX|y*rxcZPv z^*ka-5@f?PzA^r1Z@TPvy3ap;?7mvHzAm>}Rn;%<|43!2zWeA`qw5-P*!Esol1mljHu!pH7> zU%o!^sgHhg#C@_eCw2iAiufek=9Y?-05Fi=`RlLSFuXCbck;1zvqs6p=9}XPgJ-?S zii7W}Ur-~$^P#Kdps?>!*9jSYarOnP9BnmSjK(EciKVR8eXXW22oRu7W7%3;5V6tn zzk7Z`yA=OB&?|oS9|z8P;4zG`B;%FvLZj>gK$l)+`ZfFcU{Dya?)teG<-Z;q&O5g}+6+<1>Xf6@Q|BH~WPcRHaO6GRy+QPL>5-6fwK5j>l= zN}jBdcn{SQW_c{Dro+x0-}a6Prx~f8K_Q;gQ&M$go3$V*+YgIqec{=RSb2@r#OOQ&#}z?=EQ%b!_d@`1Iw5BuM~M{htCQkY19DG7Fq?s4QG}o; zD)eV10ii8vad+Nhj0-Z3r#7+n_IUBusQKwNYNz5;$|FfJniBJ477;NP5D%d`?+7v`BBlY4 z_sE_ZdN$QllBkeY$#XiP=g`n)n4nHQkQ5S0ibl?0?ioG(wtGBT$isu&a8B4drVQ)$kaO&;qjs4-uV1B`%C76g?@ zN-CXNLnSBLQx#PLNXl*>tsY(boUk4Df=;b8V;2Ki)PvCCz-+hn+P7>R%^#UB&Gx1S zBvGDSnx1K#{`7x+A)LHc(nY^-a(tpaGP3B`u|SmGo64~bp);EzeRERWU6Wfc3G#uX zdxzF+?KB!!zUGakM*gDBS8dsP#oONa-WzXx!_!Ch_vQwO1l^TXvAL8!yD~a-po|IV zy7b8YdwY^=#!eWfUC(3^-{ywR7xTGn?t54ykB`qhy=(fso^4fx`@pWrL;J?ZM+(n8 zwG>r*Ew^I36+-0G&o&P2Dh^!~ZrZppo5?+wUYWKbi}D2utZy%0FbwM>fBX3}6L~*0 z`qQs)gSPG0DRch%6K_%!lFg-mxajKPM;`i(_ucmG(baQ%(Qg5^U{%8QS?i!{ zrEH>z0ikYi_^cyAR}k?1zB49BR)yzuDqXWPSSn4rz`+ zy2Vl>pNeL7ow?_gTW{$u)CH_Am}6HCzUJ`Q-c3X2GX6xYtWIn!H}ean+2OuTmTP?F z8+TrF=}+fk1Ck&YtNB7H|HR_QU$ORQ9y_>W%6c%HSvN6yI+~K+a^>&ji~0Zi=+AWI zu?SliQDckw`LE6V(SUF<63N)i$WnQMU^3er-PC)jEXhmxMJys+i`{jMml$n-u5ZnD?aUjs*WE)TuRU_bzNtGFiW36SZru8d+!4NX?-#!O=*QKV z5PIyVZ}{bBYxh@A#vvfli;G9=x zoMgY!F8iH18+w)0aKw!WARyCai5{gqW95c5jFHm`I~Ct*1vF$v#it=x;{qngcbRL1 zk)%|avDR#lSlf?Fjo(W6Auk|<-qXz_5O|H?|M zic*^wC{BMGtd?2U5Y>5&~$bE)x? zo_CB<*VwKrymFn;>I9xc`3ty3G+p=+GIUSoR6QZD_6$eoC#Ibz`8hALu<{Z_1NK9= z$?MAHzBhWcGUAX`S%lqB*KT+(Vx8~rvoXpU<(@;$mfvZ3M$@-DKBF8k5RAI%X3trk zAp)3S9P;J-`oUf$?z1ET8gR;Ztr>L3TtDENg2RCMKD%r{p6sOj>h{R&&o&lXmRq*1 z8duF$INm;uW5S!o{v)m#MpIIHK=p0fsrfYEp~u^0-|hsltV9FmIm~W_L_qDTm*|sS zlZp}!eMUnrsU(sV1BZDQ4P2HR*6dD*F?7maqE|8Mfv8}k7Wg(b>OtVr)PQQ#{a98C zJsx;0nifTw_!e!Ky`J@vSVrO;8cVLz2~}N`Bcw8GE4oMo6u69Yh~?yV*+T%LN{W+K zqDPLTq~fF%2Hdk~EF;wx9X%xx35gQ!RQ*_1F{+*#6Y7f&^?A<*jRxGc!bZV$+Upu2 z2xWF00JiN>tz+7DhU;oa|a*G${dq)eIz+cqX-)L4DEb>a#cl z&Y4jS7~?GDk))XFR}ca1f zTO@+WzyeY@H`MOoh13Z`E3zT*8#u81Etl(p3iVDg9!=Jb>c_tEt4(K?$c;ux7=Gi? z@)U~?%^OR(5ZvhIww7^37&7>*A)CQE@A+;zmNN|N&M!Rvl}}9_c~U%my0*LYsl`2;|MTDO zdHOM9_KXiwA(@P?HazLJLOI`VwFdhKzn8n4(Hm~r^yI^*&OH^JrzN2*@Pdx*RYU4f z<^urdlrrD(>PHs$zUN)OQY%7@{(<~Fdd7;F92A!Z+siw!{NgtA$CU&7CC30 z-}FO^bNYM#=ep~zzkEex@PlvpeE!Q{x$Av@@y#{K^vpRfXIIWM|{(+0rHx;XS063oC^O^tt&{X*K6O)J5W;U-J-of&N z1APP2rLmRQJ~i?{Oimi6@wJEVdb;|B=_5-lfXRi?58wZ@|MZ`Ks%NF$r7s<8+_~9# z$MMm}wV1dK{mK*1-na9_4yO}hf|Mji08bv@(HSwCBY*O5pL%1ddh)@=50-0%Sna;a<3CGRFsgc;aiJof?E;aXX`Jhp^_s#D;H2UD% zU-O4&I!_L0n*iX@8hq20j6 zi%zd1F-cYgIGfgo&~pOst1uRRkvaoPdAs2`XKmNd(JKziy-hwq*pK8*+euzT4b#I?SZ6T&70KjxRhf81FHU7CUVEui4cRc<6 zM32&~fF1^{R&vG;*Jegr-^StoCruD>L>J>}xo0q9w0*}4S5IzUwOQUgq-ek*DT41DI2s0C_vl~1qLR`xw{f$T_&$aR1SMIOPJ7&YT+o5N(n}_6^ zljMEZ#(w{XGfA5HYgI6dv!ou1z9G+;(8z>vsZ zJ71k~!=U(5pLf>|8ReXD&!(M*XB*)QpVX#$)J&iHBXN00Vqz>Qug(cX=S}NZa=6bv zJlo~2a$-UVff^N87qa-Fux3hm;4{YId!ttf0b}R#g;z$tmk+&qZVP>2T%C8!MxZ6c%ADibv{`U5Msif>-x>`Z=Gl}}?idsc$g^p?;&q*s<2|y| z2`J@>URjW^5)mQ^vA*Oo3Zc(x3yz+atcFiRW;T6EB?H@Z8nDce8cm6=8TvM(lyeS& z%WCtE-3hyt(`tsTf@{`&;1ErTj4{umb|+9{B4A|J13^MY!zUs}7DhAw?(M!Yo}iU*NI8W9cCk0I-0RsNh=R>JXr3(Zy3n;IU+% zTo|{Sd9N^TsxhINca6HA9#lM=5(#(R4>{wpj1=#Yl_*gwZcoG8-Y1ig+3i47NW53+ z)O}=cQUeNSygKIy64D2iFfK641CO=Jp4spNkF^S}C=*o| zw79?+ROjr_=T0YVl|0W5X$ZMZH8mzM#_LNi7LZw4wo)QJbJB)K#nh?nC6)80f)T%a zKc=s1jh6Qp3WdX^yJ`jh?{5D~Q6aufjr{uP&_bt}=-Jjz4SB9(4BlA3?#4ArqR}ch za@+i#ZA&N0JHLMF&!0ZA2MK7VdTMTQc6{cfZS&9v;9z=f03a%;F`+-XW^8gwtXwW*cIPfXnv)y`Yrjn9mJ8+v8hMk*P<>Bg(h?rS-jaq@V2aiIVJ6LX_K_`c3C zj8?nV+uQe>@AyEsJoooCUab0$FaKONx%>&eddZOuL1*a|Kg*StzyGcR;QMJ|a85+A zyjFXjpM2lZ`~U3ke*Mq>^8NXI{wDzIC58t808p&v+u?<_-;+zDF*$jzV>EeY{MI!6x*pYw)jSr@U0cO!e&o#I{U>&;)1Nuv@QjS3 zN%3??S*YyE#LRN&m`zy6r8<$gc%h?ezq zF*{7UjyPZcj20K{PEFacBk<`7|IW;iy6@1gFWviv zYc~Ikq>|c#lZRdI@V@e>7`w#AX{%id)$FsSafuEc9y0(^^$$?#KVs~^V!*%*%n^7>zkieW5U5xySJ|2 zJ~lqOVD8cEo_sOC^VuD`lK9%w|5~c&pFFk$i#YI@(+LlsJkZYjp~Y)OySQNFmpYY2 z3x3kRZ9C`q1|W!d^JS^k$wUKjoYb-Bvr;X%@}g+>=J0&x2YhzPUE3?_+IKNF8RhWl zJIj%*$YhA+B!rP1C2CCQ-x8%EGwVS#DVlX3VQ7^+v+3KduvPL46J~MB;v8D#njb7? zwiQyF42E0jfj%S8hybn`0s`u@tCPZ8UJ<`^SlzNl>6F}K`x|j5+@#}wd~5d7D2b+| z?668C#6;{n)U!iI`TR*^U`w=9@j4aHHiB-g!+4ME8X>|!L{y!(IR`B!$ST(2!qREe zvnUae8W(8DtY)z3l}S;?vPMK1Q_2My2Of=QWvl5^+L04y>~<)}%WJMIdN$QFk`y6E z)sJSHnc0KOBw zLaXUj_tQR?Vf_&O>0juz%79To7&zmhPg^ywS#w%d$2NSk<@2+jNMJ%**CV>rq0nvz z>jspq>$Od5)vfDQ07&S9K#-~sMZ%P$AY%1xXz1IVo>x5)?K>-Ku1A-Otu zN!CcG>RHVIV;oIM?UEM+EIXt*oq!|Y90HdT0TBVoQ4-5YnogWf71u zq|jrCp!%Xi1Lhh5=MYVaPA633q99_|3ONT+CiNwE+fAuX)w4T+AfdSvZ9&4GLj?)9 zE56wX0-p&o4n0<$u|1pm4h0To!{?m0imuZMwYZQPRKkEU$`J;;9dZtwaa9-0M&Q{r zHK?+Xbt;~s6T2ORKJ#rF%gRJR?TXhfdyMjApUeSdjdY1y_j>bey6*Cr@6hf?>z1lu zj2kuIcPJ)^`iyfJxJa)rIV@bR1Ci*F!2;rx ziwdqSIsgz&Nzs&~Qm$DcVLT{%LfvPS`wk@pB$XI7pK~6#tc&(sgNia%b&-fDa2TVY zU%3?eplXRVw+e|XY~Z|Q&c?4UH@)M&&GfWnw*yMKq!EmPBM@cem?4pnYtl~57i7|@ zdH@jmTv9~fpr<9*3`3u#2GmButuMKpb5X&Kylb}u0C3H4?s%I~&KVE_?XnlRjD;K% z6nM-srqb7!Nq++?XQ-P|bs@oTJMY4_BxhFEHwV#y@{+gv$y1+mTH0qG{}2eXL_~o{ zU9SYC2y!rA|bEPMz z3y&ls!}^-Y>)w790{DXu-9ou_@Z`P~O|In{`C`89*5(#wme)|NylEMwM!rx!Z;`y3 zdF6}e{uGZVbUgxid5$6U?h^)1t{Yx+(@ocW;P20|DvU7aj9~G|{@OXzC7zp^JaPQK z)w|2->n;#C9GTt|QS=MYn`IiNV|b1+H~vI^?x}zMn@_C%Yvz^q1NVRF!+$th$XBoc z`}Q6AhyU-?53-ljb$$Cq+uwHE&;IUvfA1eY`cJzbI{CnV?Z4|Y4}Iv5|M`1ETF=X{ zew@q!UcLYeBhFwIy6VaTmdgsG?|a@9xD?JxyH=71VR;v;cM5wB-TTQ;{qw&4dw-a# zj346^!l|WEU0oJ`e*VdiB$LT)y;rZ^VCVQfS8Z7KDKEG30eDe)*}Q3TX|&#|rsFx& zF>3Xi9z93gKlk`YUa{d85tKr8;lbVCc->XEtJvDxfJ5YLN(vBh6yvA9GP`q@dA|=dD4FEW2TCgq? z-=>Ih(k<(6V(_TW~UKHMHr;pc;r#v$U%%s2KKF@6!F~Pq_i7Px z=l!1@zRDF<)VokXdn^NT&+c82} zBW5LY#oMQan9m^(z|{mZYwG43+X&*#=83CrlTSa<+IV9O5s)=fp0-;{{-)~_m08EE zhMYojofP5 z%{lfkLeL+%ObE5ZQ@f`MN2~@R0(olw-!4hNVW5BQ@wvSR7w-%MCaHu|n425#-59CY zEv#}SNvc!cPsY*j*kpwybLUBEvIAPRupE%QZnNB%7F8KEp(=m&5?^Ml19J z=7nH-Z1m8(igqKjnS^-USR4+j%iUmR?Pe4?-KkYXg+!BL;4&p50D{1!&63M0=ozV9 z@goVbUG}00Nz#a8(B6#^B`P3{tY+X@Ar??1E~+sh(WiQ5m>X7IBaEh{@)^5tV?@z~ z`hu(K0>Z!NRfCaw{xF~N7JXHh~Br=Ubhv*7tI?Fu|o{fh50Sta#FhlX5FOHL;Q zfOt+en?a&irXf%CDv2K1YKM}7iHOX45YNihdB<*toWbC>sND&hMK6*Nn?*0M84X#Y zS5czGGpX4O5o%ygk87w`jYD!VYh;?V}z-GrB(8}1cwk5O-V-0 zH|stNIl?H>rw{?TMwlE>nguuXm|6DY1JcIpl4c`NbRi6wq!FtTL=qwkxulYI#Y+t; zzQb;0w9yP0;}uP4L4dIH0YKHoSWdQ^fglq_Cq~_H+{Mc7 zD}xr}s>w;mFGT?$+OJ8yy95O*x_}UH%H;^*A(u1)fJ)OAr`&FbRx<#A>YRfRB>NT4 zxLFTcWe+&`HcbzywRwjIJkcvN3XVywMvxv4q_pGnbwO1T^4EG$aDH+9qdU)qO1yV1ion zDKWJaI7;W#n*QqyE!~kdvZ;4VJD5Wlg+4oWdY5a`3O$JsIzF*WkT7G=bY?fDZy_I-`SyjWU85ayQ{2A!mRSt3rGf|m z>)ueQ9*=dbg?InX8}^*uy)L!>zAr4^`qtiV66K2j{SR(#Cd;u{ESJq~+q&%)S6?&O zxBi=7Z3*Epp+f{^Fr*l&yl{O8|DJ~Xmva*Yl*lStRQ%x@I6nU(R6whySY0#W6_Usi z`o2#D23aA?&R6F{E4WaN1+z=1zq#|?>G4HX{o!O3{x~bJ7F$zY@#mqjeSyUT>%0?d zn8uj#)vj=~P|lk{`$S>SijFk2psQsqwHNcvb7_W0&+Mzff!^4fXC|IpXiiO$uP!bv zz*#lc;fZ|!u=C`OjNZ3oO<{sIZ`u6#(R-g>ygeREtZcTs^oeI%cb$B^S`v2qHq{d1 zewRNp=ji<<|I%-inpT4P;)4jGX3;ep!PXnoui5^;x*?0Zj=g_r%=qG=KYD!p zu21cIw;t6WeCl2ru$EuCXY|9IawQ^!9-BQ?INJGQ;4#;v2%)~Mdf?LiU&%)jf}WA0 zDUor$Fk-kCjU>dOOXHoYFUqJgV^0mLQ_nO#i;4=4XC=n?H$PA3Pw`&i27xF|Fcts@tb#6{vo->oIczX6l39Nf9#SfW3YItbMY;iD%)1v*zOG7!z>L zt#JifcA~&k4_l4lb0WF3Ynx zG|M)l3?ZaNzg-4dqwH#MQ_TMPYm@ifn0qwR{<(zpu59e>!!1FEyahfOji}G0Nu;{X~29!qgn$^IYB+y<$1vd33=q zRDD&!@tAPkmGL*eI+cnGshB8Bh!7+SXlm)Zw!=5dVSU~!O<6?5dPdR`0z%+Bl!jc< z1JUkE#^m!%P-Nd$w@Jl z9Gtcf9ctY-Vb7Ml(M7lBu(_glyb>HM`ASsqZQ89HD98vQAOaF3TwicRnb44HaUqtG zJd@IZMUxU15OCm(N7GVw-VsfSf`lUp!L>rpc;HgcqN0quAx%{$zD46XxioDB9%Gan zb>D0R2%}`L>^qbO-0e`K<|q3VEhczYs3jy(#zxhTrliUlr?v2MuZbxuxJ$3vHMd!D zU*<;}O^C6yB1jlk*|D!?Sg@L5p%n!#un;;eKR;tEOm^D!moEqB96X11ntrq5`W{=R zS6yO-zXiPl1OS{ZI~xLkXTR*_S7-m@jAM+tL2S-A4Hzb<8$=0w1_)tRBn4lQ6*m zpz4Ao<7i5pAL+P8Xtn&*pxSkLCnEA3>U5U7qj-=#c=SZmx6jSXRaa`3~*BG_vW&Bxfx2SZ1y2nzUJP z(`!`5pg3h>f)rga8~%F6#?IIw{FUE%D4(6i}^9ddWhB&sCvC?Uu-Lf>8< z&Wth59vKpa2tt^7Byd@7omM_$)t6iva#6xoEAXt4Q3e2NTm%3?!m2I+0K!O+uxo~x z006Wro}>}iTGr&!fJ+MQDwkL8pe|*zJE7HDF7m?}_Z`~xWayqmyB)-mJ>A3W*o!N9 zjsOrDZZr$7(+)Y~zRLi&V;R}$gn~k1St%0Fkj$i{V1jeKH@C8zm#kJ$nX?OYFBWjC zzyGoS_gjLW5}ZE9gBRX^{`hIG1OX*`R6)do zbgs12%WZV#jIV_M&vK=6I;`)fc{XKi)%&epsWA@AyFRBy01i8!zWWdU&#!*q&wmIR zg+I;!YuY&21yv6%{iV}nUYo-z0qWl4Ph67v<>ecA;sITWw_&0C>wh2k%$dcBd}FrM z$R9YiD}s`yV|3N3UwY;PzC}A$=ZS@XoNPYRD_&1jFfGG!JC7W=ckkGauik&>vD#hL zcJZErABiNzdZlsS@sG+HY1Uf+u>a%}j~}})a48Y6tdY!G6=9@ANor7a5|SFTH{HB& z`R||H_FKFAu9@vJtZwVSzK->iNT{?V95^)em>^@j6}Sd1PFr)&ws(yFeGk6jo)aI@ zGt$C{(Jp(ZW}dj{)#*f!%qUl)L=Sra;G28yPxi~HK_%I*JUjZt)#+c`@#sB|FMQlF z!h=h9${H~n{+df-G-QvDeWqRV%F|Y3$&FCsi@#&zmi?6E{=AFF4xm*<;7Em6h(kwd~YL` zlNUxhaK1g(Ip9sVT(1A;=Id`##I3}<9`n8nHxSXc2~emJaW!2+2x!PU4WGU=QTG*k z1pt~Zt{lg=!dR3tqvgHSt0_vk=ThIL&8pj}`>q|bkaZ2P*jXE_?ys&x3o`~nK*aBm z%xJ@2Q{8`R?#s3I7ytyJ#R}>8J&wsX=AU zr8*+Wv%*+L`kObT{`a-9o7c!W5ug)Z*(Y7wC(V}qd-DFB1^;8an)ggQRx60-WJMS1 zOAcq;H9}D#^}O3%V-N`gfT9bv1t&eE1}<~0P}K>r{@&LARV(l7A%9$(cbCQt8ZucW z16!l687BJV&}WqLNJ1ncvfGpcw8|cwHJeBes)B@wgspbq*;I=QT2jOUQgk7blIlw? zLg2g9Y6sNgoqYK6zgprMg;HKG+MVXhy^bfwAW1|&TiW%x4C`#RIIQ--q72NIH#gp@ z#lBaJGW6&U#?2qF3Dy%Nbv(&Jp}5)V1K869Hp_00G9p7{?e3 zB1RYy0Y{Uvq!3vlfB-QxKjKZ7DDx=*jLkcz&)BZVW(!`+2n{m?;C%Lm;;2^2UmVxg z0D#qM)H@Tdzq~-r(pRGS-|h06`hp|UYpO@D2oAiK9Qc<2@`H&U zxl4#5Ns$Q1ZUusbyDsvabBrO95?KhL&j0}t5DmGW78wKAq*`2z`0*^%!V(-R?9Ki@9;J_&NZ59R`I5%p3yW&TZ zq7or1uASMnsuma1Yt-7jQ=NB0j|mdC+u^`Pdgw70@UEMcAS2&lq0bowyA^b;17(eL zjsF0Eg`5b8Q6BG+OH=1;C4HNUGI2UVcCG5QsUTsi=>vc$LSx zXHmQDi!$kU;G3>Z4BXt3dIJDpoDwVvL=jS@M4y5Q8rTx`9je9z#|T_2G#i0Y3s&S3 zYcGp6@-85VB*emmDXG|QFZaowMKMOvq$nw*zUX)kQ)2=EFv`2H?VfaC;8`IdDDc?) ziOyO7W{^}Y$~f@3+d4Pea!W#Jd1cpkWyPra@g7-HNVDKBjhUVuI!3@5_iVVpZhv_6<2|{)L*u)@w)?}oPk$lw z=skNrdAR)G;#^^J>Eu}D=`-cs*<|m7BOmKctO0-{Q+w{-dAp#Z@iU{vYTj-KoWrr1 z2lK`J;i=sNJwp%eybl1H?FIlGsef@QKh|>3<_RVPKQMG{006eXXBq&)&<2FIU%KvV zPyI_&NIrh_zI`K4JTUfA9cO%p?HhRlA$V-$Gix)O0AT9O#AyC70PHIMlM)jXdg{=D zdncwIxc@7^{p^_OcnrDJ^O-Nfqpov&f5RfS3C8>Vt)fL(v+Oc=n{rev(T4TGP ze)Os7U7a(&<+}NNX<}})KQ&ZpoLl*qTNhG*3z8^b^!ApwzWSo=n=ZR-8xu@he}IyS z|FN@Hj3J&;x^%|(C=p*?gan}rtgql~Nv!3BzZZom(r~4~*7GM1KGz!yI6Qga?zjB% z4fo!6k6{=;urK7tIfd{-U_#V^F)IueV>qvLwm*V*WEbe|M|& zQ(HG}%NO&H%>Q*JxH2Tcw%)7r#r)kTKXmPe+vYo?i>=A3J!b};O}&@4{L1mU{RfXf zxmJHowOKiR<}iZ#3IQtRIq+MS?TaC6$AAZ;&Em_*GMjW5&izHWjy;tkzY_YjII_{vzTwH+tkZ)r>`o^F%`NeyLLoR`Lp^C|W6W7?;s6y-I)Qt+BO9 z!c|;pPynDIGg?0gHAHSOBCEoAbq3GJSY32goV9G@2eiKJGCLw*-($YV0-phJgb)W< zM*AE%EN8Do6H=y6tDVg_d;YZtGO66MS{~x0%djl3LYW5`%=MocFYPT_Bl*+DaPIQG zGhcYkruW>r=Yye36Mc%+45MlB-u{)#sGnV2=o_1eRhz}oxgxM{TPQo@ z`Qssj7g&h!!mENp;IhzT@m`q*yjuiN&q!KK3_RLR(~G91M&6M$(kytQgo%jcsL)t) zGiz1PVvKS@CR_UzsQc*{iA9O35J5m2ht!yg`;y}1q-7G^DtSiTcZ@K*RuyI3EP8>< zw7BTIRE-K+Otjl!=us^$2_lv>Vz-0LkjjHzH-GE&SCgGqIT2o>*_)w!ecvUUs?}!@ zMxu;uBeWWU)eKyd>S@WS2Wm`c7F^DtYX;n@dZEvi2%$c64QkZK8F_KUERDH85?4ziqg3UbCQ4Wk$$73`=h@YFJ9Pkr0-qT#CmbnCm=GkZBpR2Lh!9Ijv7{VJ z$!b)TH9?YzC=o%#grHS002t+z@-Ddp4z>f$fS{1Ogu5;y9BKh?c4$k)(ks(Sxds>M zjj83*gduggYW3VQ!!;) z^!81P|5|ZiLec$1uaX}(LyrN6@)HHDm-!Aw0CGf-R1$a$Bh>Yh@47yzF@XlWZ)2n~XPb?nXMLo$ z;9vxtfgt1jn29lHaWR?{U5g45Qez^*z&YqCseH!j-yCfgTpIFZpHiH()R-Vh7&tfU zLC=Orv*6Nzuh|}>A&+IH`l6dZ?c~<02p}`0R_C4Ww?{+-3?d1k>zq}ZvIn>8t)kZj zD+q({Fg+uQDyc0vzRfa2nqve+!fq!__A8ixYtmRoYUJH?R<=if!x}RjEouo*r0q z!!)y4-3w+hG%!6d&2(cHv;@LP2sz}X@|9UOedf#OU%dCiM_hl8ogepAW|om!1@fbB zz06#BBVNRf8|QxKeEaNgZ*%Wjgb6Y%oJSHHFdA~h#?(YCRe352MYc~Q*HQo}w8|G$ zxU3%d@ztw)OhnJ!KsRotM)_1Df7`IL+?iy9!A^aNEt>aze*5=C_j_eBm-7{oYhmxN zcAoGnwX6G|1sWt{oYI}+wflR6-uoW=)n2gXcvahUH&%8YKldrOO!GvdynIo=_nzhN z{ZD`XZ{Gd(fAO9V{PBrboOb+aJ8^#9N;2eCEv7d$UN~G5sBlEAZvu#A&4s6Te7f>$>X83;z4O-+kcGk8f{u9qX&qQTR;@ zU|n9jkiY0z@~pE*2r@^|0+Yt~}7y%}Add}L+gNm%U+)P>tBZ(k43KhpodRvsSD~U8ua&q%3R;C8!S;- zC>u+5e>3$PMiPkHtZjKXPh@8`p%yl5q$IFCviiiB8mK&FXsO?D;zvIAxxb6)hFhie zc^eVf-_FV{v%8T*1AgS5%HB#mb<}k$RB*kw68SZwJY^2s89;FHwo-p95xMGZCe%bq z0EFS(Nxyw5GF^fRtj^ixrkMtUnmCWd>Jww20X0zjQsh)9i1@<&UH9|BgY7q>4(TIr&12m+9W(ydXqVx$3|ztuNPB)J~8GfWXRkW8cziiJat z*)r@Bsn6Rim8OT%nAc{l>Erg!`N+xMHfO!#w&u_K@ZQmAGtTzIbjLKR1eurG@7td| zZt_`J;Ytrqy{Vc-A{`&pUDQD$JMcRE&O5B{duyFDO$nGeWH%tV+-5Hqy}|^VHX#Ng z26|aSzcb6;4L|ee!&oepdmGVUKmDpfS2u@J+OHTalZ9o8U`ldz{S1qon1tN+h-s0= ztkamW`+MmZ!?27H+Z0n%Gc05pB->+g)tVk?mH7>WXX;|-fl|vn^YlZuPbOVfoi-tc zPKjnQfgsBP;VnGH_dp&A%a?g+2d|^J+Vs|QzV%#wXAHy z4Vyp&2HV-}Nl!~{dRS!I^vPsDH(hM|c;m^id*vGgy)rF4>SbSVQcz!bht~GW#!U(J z#vgE#{1ecCGqt}Njr&=V?!Mte1Hn`r@OZ)yMy8Elj9wjJcN#zlf>EA*eQ1bOnpS`~Ce|hiB zQS;C^xLVHnM93Tf;FAS!_|}SZOVYvZ_LJjq&F8n)?N_9=2e3KDCKq5exqL#WMw0gj z!DXW@p!H3j3U;5>aS6SSw)IxYRU)9uv7NPn-RX6jK-uSYyE+ zY^L=EyStts0&8>j&c(23*>lQt{mjJlN$apvm<)z}mIguz0F-uX#-y7MwlgWT>EhNQ z7h#};ZY~S_vSzQbI!rh=G*Sc_I;l z!|hCPRhhLW`+0TN$|9*GP*PhSaVrEs$a94d81LovIV%liZO-DEq9(ff$hf)WSQV;9 zEKF2l<76!IMAqjlVj-tQqY;x#6BETFu7o~(PbKU#yF@TXc8Ty@m71njx)2c1qBS_@ zlCo3@wr|~sZqCWo%CyWPS(!G6+nE$v3BCA=Qg1UYwM=3lY9R=Lyorxoowi21#UA!S zt7IO_JdsKQL?BD0V47#LP*WDULIheaNhSgjs9xamrePL|Jdwmq6r!qkAhRp22`Xh% z_g)Tqlj$Q)!T$=nthMY&q2q~2Mm!HCX9_@|6_`2Zg?%QNb}I%;q}HInl@_;j(SwgL zOeUf_ZS7u(oC?iC;nj?yyr%{V`pj_f+MnMsS<|Cv^*Va>f=KdyKe*K0zXCcf$3NsB zKKI$rT%^g{^8E(6^g1$mLp6Vwu4RC3q;N+oAf?*vTvI~7=H&N3aqWQ)KL-)GZSGAU zc;r9cf9nr@`mw(?JuH|$xAN#Mvv1V`J^J(~?>u(@UqAF)sIfoXL~E1JQVZJ+Mw^U@ zNbWZP0IGF)^!RjfKEL@V|K!Q@kL~5pxM*%Q`v}iu*kh@Xk=jHA?r)~sdspB2=AZe{ zh5vUFj;1S%|M!P}ZvSdzSg4-V`>TK9(5+U@Kp0kh62y`cxHxM84G4h*17P4JnwNOo zwmG&GMADtQB$%olQPb?zthB%Xj9QJ)z4rd&MA#LtQTLk{FJGV@Iy`sm;BxWMvrBOr z4&!dkZ$?R22s+;!QTh@GU-tZK8bA7u-#Yi?0nZC+43&YTO?Z{?Dq$@nzvWGDcr^)l0u<(p=xZ^s!HW;M$e#TTk6qDt%?e-M%>ito>p8 z;_BJ;{<+`&{a>w2nMWG;ZpqJIy>g+vVB@?L^YME=_iIx}TsAIAD}M0YpHCfiW$M<* zJWthoKK<*&#CzRq)I|HM$)uNm-`&4-x&73~pZQPo&TB89yL9+fRYFlb=9s_L*#Ged z9()4XY_R@H7~Dq(?=-Ww32BYT=cbRkd8!KOoVUE{U11b{?ELR|HKTng@@hsBi0)ca znK2C$?Ou&-pA2{N+MLBQNlhe}GHr|ybSk8MxdYAa)DgG0)hkb#)I`Zh9J;%F_0f@F z+OHWvgK;M#CT5w;V>#K+=Wg+byBWgJs~gEgv<^F2D6T#=d}8%OUY%|{8_XQ@1XD_A zLSfKlh(Ia8{z^P|!XpOG64~EOkG{IPcO~YzL=dt}*5|DLb{da(W5G^Co`q6!%~EOm z#B?#sl;M(HQ@pp4w2nCEKGnwrRZs3_@jxjJG=vDU zM0Ph4CA1V8B3PTVM6QzwZ+5ctk#cV@Z#_C}=ejg!0}YPdSM9DQZjCk<9mBy&f$myz z^0l?SE79^DrPVVNt3(!V^Y^aCEK!XmCmOK1Q~vh3&~$NQ(S|$e_aCvh6WJMZuSSUh zubm!YimVdpuB69bSLuE3JC0V~jTALW`O@b50RRY*oQDQ+0nq*Y>CE}m!keSp?t6Qb zKD%>1;<+wBtI|A)yAl9kc<}BSe0b4@C3>hqS9kM#EKc3(KJ<714NMJG{4@?*fCI}R zri)Drn>Mz6V!6cesqK;C$158%%YLb5cD7!I^is8DIUcmpzIOn)<4|`-%h8Gx;#^*rcnrs*d=0lSTL2xa=4pA2pbDl8i=6Bn#<0pone9?0;PtL z1|sY;YGF*!l}}H;1xUTzXw117!t$BGze=D6pS4G2NdW0h$u>@zJv zecs-`mPn!3HZ!*1oZHPGcw&5EpI^1eW2t`VVw_C4$dv8VJQiAk@{}15J#5&!PXsz& z5F0c8!nDvkFj(*!w4`q5#@={8E7gw3({JtUU9zpZlq}5J-lCB(qg#1KOH^$lZrWuq};zhG1!;8*Yl)I#0AQBeGyn{8g9)X1a;RF zOp(ZyQaT!Nt-$m#7ebhZ!YL7iQ8Z*)fkNlL)G)M$wui?ZHrmgs%|rdC>t9;-ka5=a zUioa?YogOXx_r6l+q3Tikq7|S3dW|2bXRyhXcO4d6DO; zR5#Nw%F;c~mF&y|0HCFHXrp?3%m4UTxis@gCqM=G~_&2gPkllcMyT`h_76` z2qCcS^5yYI`qA3M&wkji)9yxky9KA*MoPEp7E(&@b=m56S})V(d7ClS8}U5Xi3Bo} zYrE6y)eOMYETsU--79^bRi}<7Klb{6^~l;E5Pyo6yRX0NH4k3;$eV6|he6CIt~@+9 zHD50sWP_`FXFXcIwEgVind1gAxB9CFwq5{NjpDv%y$~a~PTl$vBMjsB{LyD$aPYNn zTijl~vF?4>kH7BJsbid}kNw5!zx>5_zvazu{@I`S`G5LD|NNcr__6PP>pS1{n(unm z9k2g}L$weFh4dlIl@wp^E{gEE9h4UnufF`}t$|iRFvXc-xe{DSp)`QcIZlF`n+IR= z-PgA-{rTVgQLDN*KR0ih=2z&Nd=mm#Q5tfUfBf`cjjYFaE{4?^Gt)fMJMox*``thG z-Ut8P`Mpp24O1}XRjWCiTzvN8_q^q&FLgh1*VOl3+&k0b=L$n8gn&~fc_NS5_n!{_ zfZF)3`nxuxM-3Y}<;vg_KehESJX)VrlULJ?@1p%f{P4$vJw41H<6s-o?(|W&vz92S zm+mNk=CKbBCP7Aah=JM{qxypFmZ@7cESH!LUVmodH_SW{1($gGh?|C@I%D@X5{%)b zn>!`yRLF2Avr80Hq@=D)TPu%^AOwg&yF{{3>|Kp!j=7Uw&Qdvh+}k=AR_83sCA(K6 zgdwKr;)SzH>iWE`xH|Hx%6LC3%A`C|^?55Eal!P$ZT|Yxlj^hu0jSN{gPlw;4FF6g z{Mdc9{gs%dvNCN=daM}SS_9J~UX}JX(o)Ni0u)jUVV}8GLo0B{+gf`oaqGC7Cn_HC zLwA)opABrEOdY{YxuV>K2W+rvCp)Ix&kJdv27Xu#Ym#kpb^f>i^r_IT@% z!!i|(xYl6O$zS=MEkr8YXBJN3U)t_HSoM!)Y+QDi#?cxCkXA&h+brR^?w614?q3;} zTXR#Vy7eWieJ;@w7#>6vN(Qt9Q>W~TRQ!$2xqu53w|)AW88Z;NLDcpLXo8Nuu@v>W zA%dlbK}>`Vw0Sn1KI$q7oHEH{+22YLhQvVBB0N(pmCJXOy6cHyBGbXO zIoqw$&RXJC>9;xu|6x(Cn@VcKd*;-Ptzn(M zxG61fbr9=+`~Yjscpyi?IF~{NJ$B0*8g_|b0)rkCOj#vjI#@}ag|gH#rBGg#dNs;( z6?AgRH9}z0Wrl-$ea0*QGLNCCh}^A6dEA_AjB9BcQUt1d+P}?@nAcTdZPVo@(napW|n=| zr>;-^icx7;e#I=+Ot(xOk2pRxZJd4Gm;trsUCSlUEhnFkVF93l9_%H@mwDN@{8%2*J3+(olFcvrw5Z9kP8s^lFCRFc3ySgVAnQ%$P+B zn-tn_7(7?AC%n#Tl1zAY*5pj%=a8@QUT(SsAyA#Mf&pWhA`}UsmDD^_rj0pMr73gL z&C>}lEGDY6Ry1THR{#LhBl|0{;MytE?GN0G!+4{)2-4hl5Uko116b<2oM8>T?PIkNCo^rPU`U zc8MAmf(Z6D5^AFIOgx@kwP(zHuT;M?iJ~^dv0pa|s%#!hw?gAF2LL!_8jty4JEg_} z$L-+8fWUNcb;cU+=LL`i04TJ@XHR&OPOjt)7s$y5v#J`g>c=+792=PoQ z9gX>pR2n-FO?9EOf=M!ei`U;u3pZ-R#Azs4rb_kHbAt*IXY9eZ)!f(X%((=hX9+YH=0RUxp(X*!=vytWl z06@(@lClv103$lJbliE>gQK&D2Typ8)i`|Q4ZZQj@oqoPyIdsZtDc-(uz1HLTW^?L zJBemb`*ox6K}rKL-p>seE1`GcCo9J|9A!`_uu+<0Ko5k{wMF6`d-Je4QgJxcEKd} zx%D&8?0xq2r{4a^nFkNgortr*b8aA0yPbB)D;eYf9f;HL+0`?1jm3hx^`)mr(=_VS z_?bt?T;5nVTt~0|;-kNC_iL6u^Qk9)Of6#`8~n(IoX%+8fgv6f9IFwNl`vw|rg{U+Ip*uRVa(8Mj{yA^&4y z6!mw5jlcNFZ@=N>PdOTu~FTMAheQB~@kGymoqAY8YP4=x?Qd-I#Q8uS!Lx+$x=P^Fj+CkLA+srJ}h# z3x(FYI&IIM^j4o7x0apJZWayL>~S|wWVvNcI{DHoO9&&DE4xI)US4V#{moPgJ$=*# z02nsjzn1t-!*7^bD2DA!Da~_<5Sl&VZafpTmhCi>rj0F+WRU;>*go~D)Nh(vf>O)q ztS8h!(U2d0Rk^d8)aI>d$Pe9Ffe7TWj7OX^wRA_>snE`~c+z8-Aj8H%kJaWZt#uX( zgrQrZX&|%)*df!mm$FDmicFXAL{{gm_Qg=-y1rm%aY_Hz9C zYr7w2B2MydKe#vuuDDi<%S7cEaZi{7;*e8sAI1~TGPAZAo&WS8pQzc}9AtuYD6I;b zI%PK(owW`dT#On=+`s%}-*m~V=M2qM!u4H8Ee8Rwgvo-{yOcoy>PO7+4y!I1+2jDC zsvkD9v7EZi4!T?kJ?>{O%T&JFwA|7`hl>&_ny~h2^rgST;_(uM(6mVs@c(X850)ox z^Z&gPwM_S{iHkb6R5crOj$biuY?uQ80I(d=oO7yERyfLE z%+!!%TN?3{^@j4RA6PvzUc9}uzY@DuW71)!OS?775cb))lkc6&z_;S%hhH%)muL-MOu`EHPX^bj8mNqqZKJj~cp_na zArl1Au6kIfyL}$@<1bIcW^>Mk5K@Sp7V+xTDU)!(wA4u=;{+dbqcquuOS1gHU9bNI{ZK1A(D8IlllnF5i*l9ol-$ z7RzknZBH-FCGm)djvc;o(veBt2LK3}0sts=G|-~70#WSN*z9qSr7{|FgpuhICAD9t z2*P;G5r$5g5Q-{OrsP^MZTrNn(s01ND&0OG8V>eqMmiD1M3+A`ne2T*;UTMnM5b?+ z>ie39;}N%P+zbXG1QCLmAZlQ0VACdE#rS$qQ!;JboOKX_H_rAstHC7Vd+T91$OTgx z9PD07c|f`U<_?z0Xu^YGjxaQBQd||SK`>%pCji!U7)wdbbCpIS4tY3YNhkzY#paM! z;6|ppj%?`{?n?sz2!*DFOS1+k>6sJG%t_a&5Nct|Bc-OX`Ovh;0pQrGQ3&V4HR3z- zIS+^j6$4Y%JLZ4j{dw$Jj+^zXxeAR&r#xF8s3$0>Yi~$xQeNBv(hQ?~>b4ELM7A%4 zhwrLNuC>;Ng~t0CF>o^GlIv2_gb?~I11J#n8Nvu6VA?nuup%3XT#a@!w?gwsnl45d z9spPxAbhZ$ZhN@gvRJCd`x%6=x#T2)P(l|ek!Nb|l;7J(oC-B;ObDvYS%pj$03e=l z!@*f7iq30dq9hRUh!yR7N@{8#h=5;RNY1@I9i~#cc0%2FikfKD zW=HO+1U+WKd9Ejhjfd?VB53)zUReCmirXop89FF{VmQbF`bO=XiE3l_FQBL&5>8%~&jzX&{mb zM;KBQc{O9SQ3236^yc;9-mX@_tLl~P(solm4wCkR7~VLBFwz!y}o5CErQWRZYo7kM!(?ICvs08p8> zAcjGgVFJ@YG#2eiFPB{Bi7bG{=M8G5i2=uZS)pyB6)puk`! zYb-eZ?G!?&HE?_yPk21$AiHDpQ^)#`w+i$M0Fd)Znh!E|;6qiQR{#L5RW$Bb@tZxe zG#Twi>0U7E%+fax!)sD80QBt1NYZBpPuDK{653 zN8G`7YFPN{?&&NRwnySIFPb-5Du+8+xn-uIaI3U{4!v4~Clx%u1&yv!iC~IY2tkm? zveYmqojgwjrZ5Xd&}BSVc`S?S#xT+Lg~;}aTcOEBKm<^t=AniT$tOI^RTxWz;BYJ$ z*E{=cH&sX|W?^g5X;kmq?O#hK-10~==5~pi4vq&Fakr{-mQmfxBe@ek^OoCx?8xlN zKmEw>U*0?uqxki=yd41Wq0j!cgGzt-^snsq*1q@NpZWEV{F5KN?|(YIb|95i#NR#s z9^b0e%Lk0DQQX%8K6&L4&+}@2^JV46Kl!5%tzF%F$%hUfUtE}m7x2v-7QH>&yG%Ut^8^y;9DT)epTmuJ`i zTblQTjH9WKqvl_d^;2`b_o0XXupItkGO`@=?o!jpH(u+k{LAXBX}QEM5v@Sj=h2vD zp%A&+IvX^X9f;s?Cp+-&$s{q5QowH*hJ$N!7671_|J*9=@1%mMQTt#OqBU?zr09&L zHa0Ar1RNni2;`Yc0|5~%ct)+m4olU>(?M;{+PxT+8pht0*mN-f!1hTRipq@DS&c<5 z-3kr5`Tj~A^;mB;Eo3_hK-a|h(d&6JmH8S+amx1DKtXx z@ZFX6#YijA-%3TU>=GXBWz@vQI&$lL03q}n2GGE77?&R$v<|tLqUob9La{rF;EhSnd5GA*#;1lr%a##fS}T{5CXmRL@)(3Xe`Eo9I*GvzKR09Bz0W6PL6>K;NXplzY);Bedy{)-rV=`~| zu0-c1Qd4x-F?Xs;zWdeQ_beLkoF;Yy0it)#M*sk)PQi0+C{~$h04CjBOC1ON3%R*{ zp(xc&pg|h*ot0qy(xkidGPoE^C(G9{qvpK(#S({}d2REVo)RHq+dgr0~JMNtR z*T;-sr~J;Bn+KxFi>gx%Uf=+7y=Ei?9lgDF%RP;gcQ>XM-J41E5^kOkf1|se7&abm zr^V_y=;m7Kf_h{7BYM4ZBzjOVbb32KBR$GN(_Q4QP!#QH?Buo!M!inX>48|0RRv}a)^?l z=x?QzBCP>6QMqN-7wuBZ%oE{Njj+!Q8z&R4q+UHeGHsMh1SZg{QmwS@6Q@FnftK&8 zI2GztD7BDbV{E|I{H+!Ljfd{Bb!_0-A@vxZ9qyfJ$i%nn*~Z!ZG?Wl&{Tw^JQNCri zeh&bE@z}R#adzDHNqyc<1CdUI>0k(fSEc2a3HS44B9bw$&)b9|zhT4^ZnzjC(A!7^ z)5CV^R%l@H5?oG`G96^%D!=je}U#@LeR{z_cb5YQwwgv z1-Kd47)@B-%q@lPwUhM=<6$Rdxh#Azzs^6G6e+L4JcG7Dn<9?RLf-!Zo-q1~8mM+jAl>ovi&oltKI%Dxn4z@GNwKE-+P7MJ7 zSx0Ss0xB(YKJo3@mia0GK(hF0YU8l00O>n3J>*VATp900cB_pYKL6^N*0!iUaa;Si zc7|H$fPMnC(i#(_HEbPrMXq=*F@aeq>=H>Q0%8~rd1o!51}aaPES1e=8)Fy_SaZpC zDik7^g)$y-0Kn`?4;x4+U0<+gPk2%Sh(Lcc(HaP*C*3^g=Dm%iGGnXfNrBg4V% zOQBb#(U9SrvWF5{Fg@DMl+^V_TWe6AG0RO;Yv5FY#Dm9Jk-=pc0&T10& z`SoO#$D&X&NkSo*;<@auCc9T70Dxg5t$<_-01%DX-qjczXy>CX(Wmwj_m1=Dvo>Cs z{+jo9Orsp{CwvUb?h*hX%?H@k{{#4C~-3nGQ|@F@KBaR%jZE(QejQvQq%gndH(~JQk|;K3@w& zcg*(_`M^#d=5i(1+a<#fcsOJ|`jAt?2*Jhb zu`8Pw9^3tsXvAN!`0CEMeR=i5qq~3f==O&M)9-xMFF*YFgZC}`#OVtUu}EKcB;4z@ zPw)OIdd>s=(zOepe(LYE0w2Bn8-;0OXLQ56@aoQm7Z=etTOR@de)MO*?In}sZ~pJ^ z`-PwW>-WER%QC9Pk^lUEoVj#y3jok=@Biw*`OBa9+5hF|{_T%`Ytj3y_#*M?NB-u= z|Ha$?pa1-OUtW*GFKAVM?x_bW#$fjNTd?7O&7V+?Yk#DQAM5cil?quaDGwd?c!Aj|%&ko&Hu1uLw0K-C)-F)`AxBlov=6bT1 zLjuc9BkD8L!IwWjY#p(K9-}5QJxmSMS&J*vrq*EggcpxEHPOz+&~yk-rR|a4W-@ou z3%WVb8bVN;v!Wp{TxMpDyJ4TLKQ(bmR0u65e9~bv$K3jYU8rLwV_u!JE%vi5~=Gq?v0QQGZ z##t8vdv)|TXiN^(-~JEC1KsWTW?kePMZ*^@oDc%_X}dmsV0E{3WyGW`&um@z1e-o( zSEkMJeojq9Ei9NaEF>~jowLFL?{B4fBBG)48%BA?G??-%lt=RL-Q`E#w>#c(23;_%f1%;@~-v zH4Z%6CIEy(hAGMu$x_)_i!B#Z3!5%(9deusg#ZEs3TG>=b!EotZY0D+hhJ4GN}zNi z5QdhE9iIrUYqM6=ZuD2;*;neRH;(daxMbpa$0Kh#p z8ed&KGV>jat=DgL9}JUrBfn=_{T<5 zsurPu_&`P2t=7X~H+znZb8sVDK&r8>t+@UQP^Lpiap|KnS!3i?8r6d~V>?s8%4IaD*YxJTcOlOX&|YE=5O@}+i5%oN@T-C8VF1wB;6!%ifsVD zZVY#_%8VHexUf|`;t#Y7N|H~^r4DT#>y z06{mW){U;i@qUgeR1(-ex!%>7OgOlS*aacrOs9dM7E(e@x{O*#OKrI%4Fok20HBb# z%@din??g|%27q+{07Rg2B#Ew;zt{xiWI3DU?0KvO=rSD}0D>@She^9TJ_i6m5V!6* z-@ZJGCt&uZHQLP}ghfJiDs<6KhKc|HAOJ~3K~(2bX!}GQ<>;A`pVD!OHue{15xr;_8g`^vWZ%_OXwi`%});>1RGRd(xvmeE7nL z00hIWjT4nu$6^A&901^fl@Dd1=ywK3XTZlF|G-l7_-D@kS1rLi?)W9o_OEPQz$Tmm za|ifc{=A!RZ?rw-FWkH>@hkuCXEadn`GeCh{>rr0<7ngKAKq}Sse@Nb+Moa2qksOV zkAC8_A7thuUuzo7x8fTn{>yuRb8Tbo`@ZM$Csm7uN@CFdU8a(&JI<c5vL#O;%wJqL2bc;y+OEPUaI{muU&jhAEmx$2C?bA=ED2qt5W5Ogcla&Z<2 zo-3X!4OHotJ@fdL$*x-^Cp~M*G)kS(vx~2#uDej5Ss?RktY4eI{cz>p^ZodY+f>$a zn>d>QLZ?I+TCvMR+b4!YOoybQC{LN?mKhE?F_GnADRemCri0@ltIk-%cGg^Wx6TFS zDZ_FxB5>5syoP}Zy!5%T?W5&8%YNNhdvXF1bSkt|r_{pHfZ0BwHl91_?_G)P5}iBc zAp{3InG(wKh+n6iDZgoq_ws^|kjH}OYWkR4ZkcH$1XI;HYwgi-dD?6oav%WpdE2WQ z(U427%QI&C*?9IAckg_R5WM$CX2zXd3gFe~%rSSgpI2wCy{ob9lio&JnXwQ-qutE% zNPi=BtJL&J`(o5wcH%Lw%vgI@Uhc&;!;)md}p@o{U}344s^I_Tx2-R#usYM8?P zl>{LOG_ZX_Ewptu#1y&}icPe2HY_?W!#)f9OfY3wxH4ttiKHfW%4GeiNoCq(sWLn= z*iKE4*dE!v9Mu@n}sgM<4PsH7F#`;zPT1X*l*bwXU^NlXWo6phyBvqzmusdppp^*AnBN!SG8~xz5a4-ccswHS?8s; z{$HY`ebEyR9xOL()5EovlLwM>nT9f%@XEBACo&mx0AbK$l^LsG**GPlr6v^DX073s zs5EC8sa(4h)#vU0X14k*-K&2@U;_P`dHwrQQq$-3aU?H|uH7B3zmVMLT2qIn-dwhh zSn?IU{1XR@U4G~7^?%<@&uAEZiEmvr#}$oo*K2RXA^-p-01FjFhzsGAspVq7Zm?9A zn#QEV>=JD6c!%k&?~LkCm@2Qrdgf!)4ipvV*&uk{2JS<4T38*|JXQM*FYPxX0v(SKd$CJ zQf`@oX>uv#+i8%pJ8ga$7D#W3?hIH#8M@N0(>Ukv`BMel!*v10J?n7 zE^hR)?OL#+A*wFjH*A0OHZ=2ixU&T9%g0|`9d)pR9mB=-IV&3S?pm_+3O^c&>a? z5x;3fLmqUQUpMR$nRIf$VL%8cd%0jrNnMEW-#KHnN4z{`h665`3VO`)ND^>}VR_mr zKrR3PgfI(;S8;icrVm%;xSDkA`m&*Sk7|E^a^)3`J5%9r2%%MIu`~t%XniC35NuA( z-xc(%T&^|`In+RQi9|#0*WEN?N@yumJmvtxa?7+!w7->(_w%`1eT-o|;w)1ihxK&zen1+ia(?Oq66Dg%@v$kO&Op)I-?GhdC zWR+=4aaE-E;xx4aJUzhdnoG9GRk>vr?^~HMhdbHaNiQ04+ow*M5Ccs*d2`trwo|Wm zpkr0EkMTsYiEVR|^32(L;N9tj~lVVF}vwe2oV699=m+q$DkM?{~vpA9xd5@*9U%o z+ud*NRc~MV_1-OYYqu@S`vNuw3?3k{u?ZP+49PG96J|~(2XahK2%O0+9EVf3M!Fz3T4w{+9XUzJA@3TUa(4>hqT0+b?Y)ubqq^w0qlev9WiY3w13V@cgXVB}N!7 zPv}`JbIW)nc%8CsjodZN<%Swst^u& zv0*5sI%^S6WzJXFzU=pnv)hY-6skC;r^Yt$;@OqIv2Bp_a5raQJ@6O*^R`CaRNeL7pMGsXE8lu=c&M-i;fPv3QJ^TO9n>qy`Y!@}d~gctUFdwPVZ#fBfQFZ_OQGY*Ft z)kajqc182MX%cdTP_dzlOszaKJpSgY5(+bn5b#vyI7nl`&Y8)YN#<@Vo`1Ll0Fo=W zro}_0Tf{1|(QcYA^h;yfU?;IkOmL+;H1P#OC=JA*8IK*b03aN2W{^QMIe2&J%9H)E zgSL{8Mk2Rk7l|D1COj5aS?h1d^S8S}H(Pq5KYr9U3)Cty-NxIO{E1_ZZehJhM(q?~ z(26AQ()04HdQWy-kx)gIB%pcz-D zjmQ3Y>#iT2Xs?6^?=DFRnn{>Rj=#0sU5~ae`)*C&I6s;>>GqrP+-cYAX05BCS)f^h zq=c2TL!QYrk~!n1G@%oMm`SLCuRJlh=SRjdL4d&Pra_-$il$CDNKs(x2{`t#(G2q~f*W$p(9UJNy#>GoMo>i0SIRxcj=|JAc>n&W>6!kJRj4_W3V& z^SR$Fu-;b8bR3O%&`XCqN#lS;b?j_LPdwZ?IidgR*N5*rYF}DO-ZiNOshplR)+ja$ zL~}^c=98!G&PqgdAPg;jb@-i3#F#%`d>LkhuDJs?rtS5`mlzTusVSVs)}kPn0RRs_ zu(udZtEv8YTm2!B*RE%OGYRXZFBvryYyc1B#JsB)a59p?K*XNNeNW;*V1klBL}HGZ97w))kw{v)}`dXV({pjad5s9d<~1-z~8u@ zkJ-3$y>)gL0EWSuA2%DtTZwjKIS;wo{GFBm<4phWz1p4jH?X(X7e~kLs$z@*0AnmY zU^S|l7$HCyoU*1Q@I)q|2>O|B5vJqXtl3(N%9C>KxzWO1C8{B&xTqdKd{~C#u(UQnkZj77jDbB+S6fB)UWG zGNT$Eb&@nt+b@Jh2~!N%|W$ycTw=Y!H!9`U*)4X&{O)mj}M4?@v+m{25pHBnQUJgO1 zoLV((rCB240D_^)l6(jSLXqN%>4a){>bSdk!OId!8Fngc;m*?Ta^Ux}LPHxrWENtH zFytmsx=Ex|!*)`gHddbPB!ep?@x~)r zI3`rr*?f9)tn|kEv0-cFsi|Y`+6yDXklqn%y!k?*o8?es)#bJ1ga`W1t!g*I>rJ^VJZH-Nrw zlE6Z?zNtw2c=D(M0LV##Di*4Q5+iaQB(wOYbKy||(A2VpwCeES9}@^bL`GGDGM)L2 zc;x&X>9$597(j(qbBPykDHleb`~}Ckvy1{=WU9t^y`3@b6f5BrS*NlGkGbD`tc;=i zl5qlKhD->p41j^f?r-vf(+JViK3E7OW|$lJe6N0;K8_#S)eK&k`fi*^kwYHYA&0n} z*hga@wGW&d>fx`=86)RJd5BP7akV3O7$}(~&P%Dnlr4C)uiB7mftN7l3-C|~;4USY z)+IQU2cA+XS|&S@Cz_|M98YadY_l}4X-3_l`Y7c)n>>1`j%{v;B*82+@37MUhletT zQEkxri^v{l%)FyfvQ8;?clHjyK`BQeY(<%VkbevOJ#Jjn--T19QU4-q_+iUClQ1cX zxOE~!#)Z+DsEMK|_6=koWAD6pYF=4Fc_%mf-FMM{SExPLM%SMK z*YCW%y*5r2Wv+RK25%va@4Aa5{%@>+9o*oLkhc-hS5=X>k`$rOHxJf=fZeB$gY7ru z(3PZ5VYa>|-sWW03sL<>u%3ac9O8UkO+WyGMeK187YG-Q3IrFNm+ZR|tm~ z88;ArzFu`PhCCe?`F2>WcT90!ckaJ89<@6@=nmIvHo}{}Pi*@??mZu40B+mwfWB`x zBTyyVZ~s2!;ivYOu*6E#HWf`X6&UEFCU@(YCJF;z)<%l>2KjxCpD!0&Ub0L+tX6tZ z0Iy-~OIv|w=%4MPEkrcLKx~oE%4ks!Uq8#601||k_Fgp6LdyZVdfF1Dj9`pgCbXj) z5nwM9{e{@v^vlQa*nm*H@Q^i}kY)`;U}LjQj{14De4E`xm}zgjsPgP>=y<~KuueC7 zVD zWof3u%Ay~v=ZM@{HQ1zdVM6szFHysro&L6ad2LtlK6$mfk`0V+3tAI(mAx4l1X|MN z#L-I!i)tzmL*T8O8xfFg6LA-}FrH;3dCl&ourLCQ#3;)bD?S8izx5oELuccA7r%h| zUl=OHEd~>2e)Fz11fW^NdnnV7X$cGjCAGo>j3nRY66&<_mGQISq7+h)0$oM%>}mW|Tfx4jM7n?_CQx_HkqdkXIXy>f{3nRdnZfUySTT4*_H;J?zH6V`+ zP^;X1uZnY3-q|l8=yWXDg|Q8>Zn6J$hyvSI*rocIl{o)d-ES95BHwR{Z7N!VDiinp zc$;{o$WTOZQi9uiHvS9bR8!-OL1am81`DSg&uEp(vI$Z51G3e~#5(mQU8vMf`@%8) zF8BR4?x4?NuIzthjN$>@-PaMC3INWzNn(|~yUU4PAEX`$_@iWOj}>sX3+|l}wM>#7 zBk%lx{a)yYhv0wR6x9P|Z@GkF%oNGJG?*KTri>5na5yc|WyzCiX+$}z2F^P4C*OaU zh-E040jd)92c^lq=#);tQ@g~XY;AsjYNvDbnYswmGUzQBC$kv@ONj30nKB(zpSOiI zr`u~XI28CuM*HrZ1rM`5?B{bdmA{Coj|892|0l3RCAEG5Tw(+OzAbE5tMcgNr zxpXlL$Yq!k=T$gJ#OS@D82cTHf>6ygJ-;P$vD`{^Q0z`Eml{Y6D_NF##Cl&#Nl_Y#-6eHnxzYgcX7i7gCCxEdemgY{8r zX~wd@h#k{B_2L{))wa%oUT|d_W#E*t5f9W5Rbm`jx3ww z6oml{-B1N@bOay!Ni?qz>ZGLXg$}#^64AxGqM3`$9zh0^%TpyP9f_>X$sMqiF5zoh zVpx=C)=cIMg7Gk0J%-?5E8K)nY{F{`$Qm=p^}`gxwv|0HyvoEZQV3C?V7IKTbr3*& z1QkQkBmo5kzJI728aA+;Tx48?Ed!uLv2V)mhO>b8H{OTZ{oOSIX>`@m$k_-i5xp>g+EJcqKaHy92%QqpHU|B zzJ-&gV_2{zh@1Z{;x{P{FViJ&tb0{2E0cyEUI$H%-pI*$O9_I%8@2` z?dGvzK&Yn8&|5;yaU-irPOx~X$^ey&&edvUtxBI|>L1*w3rtIuxoT_k8qrkR6RUUM_5& zjQgq*L5$CN5U5xS>qw?MRMxMS&;Uv{s1fH*GD;&5>&xoCf_TF#p`h)xF|zxD zz#r@Z-=_Qnp{_vxIbsEF$85ce8`IQZKP1~hX5pnqDtH*VN|b&J@*@nhkKZkIa|{;z z4b)u(^8}4njZp6PyCL;P3BRY__xYkov@*VV@D`Jzd{;z%J4TnhzIB5H1D@xN=w zj_H!;+vDGuzOK+`8b&p^%p&rQvduw{mx!SQG-fQL>gj}8H{W-jHf70Gu*qDGpJki8 zS!JG(w=jn$el-?+9vtFkf6T!JyO|7Y)BWzdcW`-x%@(o~s#i?y|&<36`9*mSo{^iI`qrRTbr7wog0|Gz;dQKn47 zj8*1Zru%S-YdgU>(9GgATu)y=;J+5st6jYufv+JaEv!QK`eZrSj-OGSdyGXPLYQ-e z+rqCMuSM^FNP{<+D`|{>%)+h==$R-x_^i9a?_^O$=7CgIX0jBsME`A$Yf5H3F?=+g!*yrg~3*gn@ivA(-Tu>>V)0wPDQ{7@!-)Wslk4`W+ zVu&4lZKX8=PY&8u7gVN1KrD~EjTG6GKfj}y(GuE&6e474E5xFZ--_^vF>gD-3h?19 z3wvL-dNgf{VA*n&fKBrEIFNG1{iG=^IgG4G5ufEX3!Jm^H@IAF%VySasBA+!p0!Ra zxoQZs3EX{}zb$vW+Ev*PwZf)blH=Pc*20LL|D7fS4K)d5xL}DgIPTe%`EE3e+E>zj zFV!btp;F{3=&*ZHJ#hEb&IqSuztjB1yDxXqdP+k1E+F@G{uge~UJeNgXQb&%d6(Z7 zV-n#mS&IS_X`rSF*6`!4L+ygKn-c2F+A{36D+1kLPHdE)8{6AC9Tle8t4Dq_^{0MG z1J!I5rcD_+EW6c6F@Ya#1IyHXv$NvRG<*cshX_H3=Vb<4nhCOo?%aNhYkb%0$htPn zp#3S2t$${feZ(urb*uaGbW$KhZe|oI8%hE}Q|#e;an760>RmNz@>}2O8`Xfw>n zepfpi=9;NIA#F&cUOPOE?b&b4uS`NGuS6r5!W}GyvX= zb+e#hTX4l!k!FC+PBGVP01(Q~>n@rtgW)jldipOM2t#q~xoVXpr+r<)hXoh8D7)q? zU8@mDwg;Q7fG}>AO>&8S?w?`KZ$<_at;{xPkg)aFEuaZlCwz^%+~?tE0H>0P2Duyz z%kTvWfRwqZi$Ng<(4uUffz{Ph$u)(`s6BX`~%;FdN&J z>lS0BHsIgqS`i~h7BdbZzlhx87Wl~w#M?{7JcsA{|; zc7E%4qeROK5_NKb62HT=_}@sOU2|X(&jz;@lNQjwy@Q_QE^J_$gF9c&q^n=|e%{vo zkWSavvoc)|NH}Fv@JzDmz0DVj=V*~bFP@!H%62yXPZ2ZPZ0?UUw8kOBm(tz&-@QR= zx*FOvNvr$8tV>GiGUkga3CO~VaC!R4!qQ%SEjVU|^G2!&+?&d(+^vk#^$I(iUpxY( zu;|p{pQaMw5VdFqG6Srh{$tZiSP(DqO5uDroLAkKIvRDKSLhKd;Is9DM#p68m}fH2 z&RJ2mNMVd>V|gh9Ya!$aSRs&)psWLHZ<1^l=*;X*skMWx>ltqH%uNjKGF@2=Kt~S~ z)+UNo{P3KaNEOCZ)lW`axJrW_vI(yxRiS{AKs9lI7-r4{(n(%+e z9mfB!1%OWrv$klY2lUrqmX_|h=$AAOM3<^Lrt-#!ddp;WKK z$D;(HZ&*3YR}%Ev5i}b27l-D_wKN^=4e-@YpD+1=8`3)jHwT}x&@@}xJEA3PJU|9E z`V7OU8!Az2*r3ds8GU)Od9_xZf#L2$t+i$-5bctZz76r#e1wV!|a$G}ss6lXR3)T{9E`QuGgSt{GNnDqq zkal_43~yc>X}mS#Wt#>xo5YE-w!rCZEhI9dg59WHj^y+UAdZzLMSyVz={|fM9kWFa z5m^H$*#k6tHJl=%T>mSE!0nY!gY3 zlgp5NN}(-5r=)gqvtE}g!-028h1T&!D`@M?X{b}#Ga>oAJW5j@%LIl#kYhoQ>xj88 zTf0(ukOr8<_xSveoDk|iC2kZwaFXpKPJ0W98Ip>!WGEN05AVLYq#|WC)^Ba*N57!y z@mvu+^1%`V2#P%TxWpOJEa}ZR8E@fV(m)^A>TP&d>67SCL6Pqx&m`^}_)*@~OY~zn z5nTIci8f*w-TOW%YuP=gjKN#Jc1r)UVs;jd#`YFRmOhIb15k>>Tg# zgp#MvG=)Kq1fhM!In_0^ZR&5!cb9Wk6ecpFcjrI6mGIgolsM&ChA--5K@)64@^o~A z!K_{m-*FJEQ@3Oy@g?wJ-}rxdnR4X6q-VFKjwld zEz>-;!;UyxqM|uR=%`H>@+*LiQ|h1(t2u}SR#he`629Vdj24EBGnZJz|ghIk;Boc|ULoDuasdn;@FpoMKd ze%`tc-18BAYz!7Qsl3XdN0Y#_NMt9cl5N&Qv0#_+;8I*b8st)*Xmc9z`ZlyTE^~+Z zxtk*LF}Cf0KPTJw@2^Rm-t&Tu>bCd&)k@L7>Jaa9=g(*B>pG98+m0nsKkHM>27bSr zU0Q)`8}ZKb6r!u(UE+zSB7kXBnW7H+mGi?$3eqIBWHGz_!n3tsTQ;@E9h>yU?X2 z3sFbX8T+!$;=eQgN#oU`(lzE4el__%#NN{fJis!CQ3G;9fLtiDnJVbWH)94)ZGsiX zjISVgay)~k^>cMQ3DRGf5>IdCfPPOqf(asD2|$^5Ji@%=p4ZQ5f3D!scp(+9izm)n zDfS@^y27!u0tEPO5Drb2QUv&i%c^8l4_%xZks`TtmX>&A!on zbynH^jd=;O>DdSi`Mdc2&d*_)!q68r<=3v~1Bu?Pf%(u>;+BplxqiG~{#IKld^h|? ze&RHgQ#`ugH6b2c3`!QnCB6K$LQ#W0NFJ>yR&&;B#`m}B^e;M`nN|_^f}Eq#Eo};a zWT}Nq&AK!wJ!(o7{KKWOwUtLZ0O&=gsQ}tMM`DG~om$+sCEVADd)zVHHn=dk)SvnA zp86PjUWj5!$L(9LozBZCz8vcRVb5^Dv=^N{6n76e>WoVqQekDJE)6SbC>f(vA()^- z^JC*YuJPh7=$Qido;SKwgd`EgaQaS1DNn+ zm^2#!Vgs`8a~uh@&TnD^#Cc$qzjH2SoPXH5>|m9kMjakIC;yCN@kdE<YH*&NCe6gTWC*rc8j`m@S?R}$ z!&{N5cRXB!qC0Vv0-&M%G-FiP@M_=NRe_lQQ=#d#a3)Msz1k_1&?V&L`>`%ONeaB-j6sg-ohK}WLB z30ajShX)X<9*H*YGMPkf;tW!WlZOn7eML#%Pj5BLraXe1|9IkZetUk$0(@6oX`bFR z&B=>BqYH7&bS3CLxE%%FCSq*Sa^X`?GI?IIrwM)1kr7a=w-Xui@mQ#m_O4;T94fLL zV0{k5E+GG>&7?8rUV^D0DbHn@*}lN*Y8UtEY@pO^P}wiPo|Pri;A3ee3I86VuLjpWub&Ib>pq*F@|C8 z4s|^^-(k-(b61qT68Nl^`Aj*#9Jj_YrGt}Bc7Q`K;o7+zkh%AaM;pVJA;5s0Gj^|r zcK9*Jjam_fPAbz=<=%S)hzg%qv5{F=uHWIMGu3BN8W-eJK&}L|lV|$k_ z`YGV^=t-VXpZP5j1kx_Z%c)LyE*<~!7oT2& zAno#p0=+mRRi@dP_Qees)}Z%dH%877dQ&PvseAblWmGNHPt9^_$YPi*BLj8pNW47i ze-KC2GcdWkD&EE8U<%ze@#nGBMWD5h_?!nl_qNjxC!u2@Y84YwzB*21DOK>2zleCR zPN)5%+KHAFBt(~h;OWTOf1$G7XUaDj=Bd)N=r!qQmFA5TGNA$G_>ndo*=RbT#PtID zCswu4KxNYm310BG42SL(#@)wL3@?+CGtvfXr=p;JzhYmkez8fMM{Fwjn?u}-Ai}Y zAl)C7zV{#tm8hieb|H*^V9=w_J#?H=U9$BE;@1-q0E0Sv%dKyCNAn%4$4a#COFiRO z(-jPY-!PZDhR55JvR&Xpxi+-fDKmPgh~;xR?1>pZ<>vQJqBW?XEzck~+i{@>r6B(nwbeTz>lf=}TkDTlfMeD1U`Ef>a>G;iC{I zM1u5ly#V`FX#4pb2PzQ|%2Du@B0;K`4=!}fBH74%mn>go*V*WHL2s41&2Ma`f(>G> zoZLD)Vvq*Y81q_v9m@trOGX$ky9`SWc8szkTXF3PW#yPEsXI^;T~H0V0dx6&<76J_ zaHq)+f_khi`TjEfWJ*(@Z_NG zg#4R$3c1qUe#~}uc_<2WeBb_@KHd)4?pyVF&sG5R{}0+x6@4spNo?spMuro;p%r~C zN!hx~Ck@#7=zGBcy!E4kzu0nh|H$>;oqy(J715cU0H8^2MJXP~4E|yC+G!+x!J-I| z&)cRFHMRDC9J*ue&NEqZbb;zGn+Z7$5)In^e76ZnMw9UkLGQJ}2ty3Z)KD0*sb>OvjGOS42{!2OAvnpRz6Y-jRAD>SrANhX z#|sJkyFftrB8Lq z;X(Lv<({J%lAqA4QL{SRML2ihW^!8Z)3FM|`&zgA#T^lL5| zBU9@(&#;SIz||$Bcmm^fh!z&q9@{8jt9o#f1*)Ahs3s31W9@zSnvel`@}=k_Fn(ai zvq;9@6apl_7RFo6ewTNV$XCM;dB?P$AO@VUypH)3V<=`eqzh>f<5a@XHB7GGoD zbEl!XPzcuPdb%v#*iIZ{B)o4HoTgz9UF;fl=n!>f>sI#8%~BeXv2Egx0-yWPU7_BD z{@62+^(m9QC9w6})5PiXFbQxOsn8->MI3X+7)qCgCKoHQ_0j+z4`FCRTYGx4;e3Nr zsvSiO|L}G{9D@)A28<;u%K5m1%jSWa_LHBAgC-X1y>5-8V)#FVcp|o+{Eta{CW5x* z>#Z+(6zCXuk@8f|>Hx)9DuRRG)aRi9Q45o{6oT4(%sHI?zl&pJZM|QU&IWXc0O4JU zTc4Im!MmVFh0v)bbu4RdbwwcrfJzeo{tEW24ED+h(6XtWqMQdU5kPim=p(mN;T(ZI za&O_%;JsXCE=ijF&zUNLXYRT#RAQUK|G~a({Pmh$!S^#vZb?L|oPU(gOv&X#ozrJk zFgqeY=whl5WkJ{Kt5j(||EN?)yzA=8I%6USwErnS0u_i^Nh3FtQ#`fr&A zk|zrgJM|K@{F(g}W~!{vkgNDG{;VP@$mRr(0O7;R;jb_!m55>jR~6u;flIdUjsOho zVY~r6OwU);Whm2^NW%M{@4Ml7avrJHyFtbAd93KD&|)Me75powy5Y4#Kk{v3&thfg z>C8yzt;y4BTo6d|j9o9GC0)P7oDq&kuh12qU~gx#7E7m(owwU;k(NcWi&wL9!+i#v>|G>#BR^{8@OS_4nx&8 zo7Riuub@L*NuKg0CA_jid-1OH%JbXtSh~P6 zSyiu?i#2ye?LsaYAlJp+mQLVdT$uCjZ6-P#5ukwM+-2z5yiv$mN@NA8+iPw`dH#Ex zXM$-oTi96vI-Jmo*mDoli47cg6Wsuw*NY+i!^;L@;uZ5Iz4VuqE`STs%9dlBHhdGIy@FZ8mANALHDG{UU2kzG!c zDiG2^%$FyKK$q!mr;5O{IoH%Ut%~N+%UxLAj=Dw>7kXIW1KsU!>-6|K97 z^U4(It*>i$4m)zwbjhkyvYEUPRx@1;qfK$K94siBk@R1nv1$YPAl8@AKqd+FE z*6M^}C4-E_1$`J0l&SVF-O$L^-WiWPrCGMV3Mb^UBw1=TG@wPnGX}bU0BmKQ9?{51 znTVAAHG=6|c|Tc2IwTb8x{Nak_M2v_-yc;;^*lBK!V)z5{UJV*|4dWS!(-|#-#4p- z%;Xw!l996$y)nQ8ozfQ=6X017cJLy)LG(C1dwY!?&1v0Gmb@gd{OWPngqhQ_<=41C z5&KH-TzUxBPL^1%wqLoN+T#q9sU!q*@ zrpTIFRSxxsskxCHNPu7Z3k(Y%k0h{(_`Zt@2-2_9?-{bd9{YtgC_pC7{rh_Q0U{>W zJtuY6_Jq3&L^-d9L6f}RrD(>r2VpXbvyaZTK^BE$W`0eQ62@s>#n;#!S>hw zr77tRR}VBOK=4OIpPSpM5J2d0$V*^*GST`Z7}Oqg8j!K$Lw*x)pL2?5Aw@^So0+u# zU;fFV=uKtcEo0xKV&SLq&zjyFnWRqy|s zcnDjVLhdY3>mG1L?{}YqPRgFTpP7B$E<`^N`UkE-y!Kyp2V$&2HW8~ES561KKvKW$ z)grQ67H^0Y7&k<;&)fyt^tr@`65$-Va_e^XTha7xL*J>bIUp35x0l4F1K!L>=5pna zRs&EiouD|ALZxP@W%KpyJEnp{wPmtxn1&k3L9C9-#ynTOh{(r%#QDoI^L5X)$=lhC zXzNQ9q_PfeMUzqz{O!u(MS@ejN)6tH+_3XHays6G9Qf6SGg50~pnz2QAmN%8-duaeyuTRh1f1}A>>8t^mEi}UiPV5C z)~dL0g3Z?Gg>r=oU>YHG4T!d-3Zl%QxI}~v6%ytp)!q;7;-0z&g)_DfOMze@lSqpc zL#WW@0OVQ;B-uwJbcf-@=6}jN8Lg2B>zb~=uJRbJk^K#}oRx+ZWEUPSQhp5F8Gvvu zj9>f{*H*i+m1(XuOi#p<7`d-{2}*gpkbW%7U(-U zt?XJsrByi2depqM1P&^Kew@6ZJ^X+Ap%tw;kbI@mEG2k|*cw^Rz z-E}oUIu)#-VwjN`fbLQH$LJ_-ELl5<9@dyPNd`ivZI+d^V^4u~VuP-p7G4VcZstfr ze=<5gbdUoQN!$DwV!G(#hq7l-M8Ufu9Rwj~?*BITgK*scXa{gZ#Av4(R~O6;M)P$T z%qn>LOo9&TB{fN;w18q&Yd~sw1m7jt*UU#Yp;i!8THfZQ@rZER>^CSAjicK5MS7jE z5B%(#CLu42Dbe6OBta)Rq5w54XCb%ZwkrQ_+}V>ahfuuu*M3K9byYkcpD!WmR0B*A zF~#L0_%du{epZ`prq}t}K3>nP;{~u)GWbtpESY`mFLTs4#P{_g$Im&FUu~U%nHS(l z4T(N%i;64)lQ=(Ac_Vsk8%aqpx-%b6{;PpzMxjIFeFAK*)ytsh_aKdzdmE4rlHMs|v^aB1`#F_B-?1E^sD zT{0dYJ0t_t)PTqh3;+ji`yYK) zkLbbJSdj&j?)x2sNQZbjA3~rLnSVP1c)9}s*AuUbX?OR9Y-b5jJ{fBSt+5+xUQLh* zbJ_i+B8o}%9{QFvTBwe3(Qwk}{NRxc1FIH~B5FpfH3D zbDP2;mPZUjcH)>aC50#i2%H{MPxYkYU9&y_l&1buZ`YY5nPL-HH)~&+cVDW>3Fx1V@9;M_zev=u zN}OBw*6@TMPPN8RU?Q|Sl&2&>D3k-!oU6i7XfOFu65K2+gwm5C<&cf19*ooN_Mi>R z>Ho?miwoA=JW2V1+30@mlg3aM$qkoV(Id)U%SY;$hykLRC#vI@W9?lxi{X%J%z|lD z44s?e*MSeB%<=l-KZMCLG~oJHg6)_?=}i zr1JE%WJZy@jK^#}N>}Qqzu=q*>eC?}uXVl&Ds{|RYZ@-P!Ni|GT?!E9RUNs@OBt%X zSq$Dizr+L8Yg|)?AZ|;i;9ItNk%2T%@GOa_tvu}1MDO+ln~dLsfjoEcD9Hs4U{*s8 zuY8+rSOvR=lV&Lui-F)~bH%SI<3Pzhh`cF!s#Fip~ z<(JZAN4$Bi^*qlLkE8}eV%WDs*iGwLe_B>f)Z?m`{lYA4hcYH>$I@=Y$s}hrdJyu_Bj` z=;j5=fmO_P>lPv^0YU?4M$bXCTN+u2Y|>gIcKuOm-f?zc(=?WBrfgF?xRn*6*kYBA zEI(Z{D@rDvx?PGEuksg>DimP-ZI=s37Wj1~QSv1}bidrdP#X(Y5Lkb0R`7iEEDs@11#V^Jh z7;Uok(;)q&nKte^T1L*xq?N}5KiKg_#cSP@feC?s0W$Ww_P6NWYSEO4;Vq@)_SEZf zj@i<(BbM_yOBwTQ$`iEEaK`S8+cj<06JcU`a<+)EOIwG@6rS)}6psG6?M7@R>M7M^ zz1r4SpI07&pTj9FyjTZ_)#3wUB~7w5b;~CU_Wy|7dJ*dvUaZl+nAShGXVjXYW`!4U z|8U@Q->h#zKUC~BBx>O$=4lfx zGt&HG=OMI?2@8;#_;(;kxmSraj-<8M#x-|9`Bc?ggODdgu0)^HSfNeAoADl zF7%?Ff1%bp>FObSd+$9Dw(T1iu!5DUK*X4}qjB$KO`(@XU4R%PnLP#IA6WD?m+sZS zCS>O3tg9J4oQrZqLmj1$E#ksL?@#P@X0X@(XHm!f^XJ3%$JvnLvCGS|U{5{K$fnEZ zE@n#4`?Se(+4l39&hgmt&U41om9WdSjRqpDhC*7LE|*ZQ3z56gt0Zagc3egblqnyP zFE}%XAx3#6AVG==nT-a_xOz-61I~Y~tRzIv`{~l@dX;^owBJ|Cmz9 z0Wqwaz6`38lR9aIFpL^5XEkKpk%vJ23_`hch>Y$=%REsQxX8jz-%rn}ma5qdAWxH* za1}ANiep-AJ<1Z}MJSP@uQ;`26=?&h6EjvfMNdM5J9nfZ&1T3`C`2|)ZBZY!jC{oO z{s#m0bMzLbEIxD1WHX}@uRIGY@1`(!?x^JzVJAcY{dAbT3(>YlB2d7f$B$9>3(%P zZ%(jfVm-vjfbn)m-0KsMG~YRI6lkV1O_AZ{ ztvWQGAq+e|8GI^PZ1*aRJ9LZbvFE<9NS)LsF1TD5_SvNtAHqMB1H8N&s@t1y3tRskDP5|| zC{_PvoFNLlTinrL+-erUz1nygN4@BKlM>Qv`;}E(1Pt`C@)3q)Q`s)b5sa3t&K_i) zHU0M+lBlVna0W5hgsaCRXlR&0SNtGJ`HeNs?&?FU|9*DTwTqv-ZT95t%ZM6OjX1jV zpAa|hw}vabZsCxvIik$XW(RTthA9=Mf+|1MdXqoDo>?w7xZ!YjhD??%uq}QkOd2NA zRvt>y-iO?4{(>Csysg&Upk(w>Jq+%(=W5*4@2}uiOzTj!c~z)}UO-Pb@KB$t6vpdq zYx}gS-~$kar05#LG*R=AEDcc>Ck6&V*md z$dFu&Zv7}GG+!?8W#yOjQ`p6$B@qTylqs>COpqaFD6Gwmm(tUxpSC$m)=9RR=Q!%{ zw^~QlR9HzHc5^VxXN?7K{VIF{WJ|cmBCa=o;he$$E(XiK;Q+9#p&r&gmZt-Fo*wzK z3zZ{b#N_B#vt4IrEQ%Ca7Mh8!Dl>Ssaue6-=bEh39cCcjf>-;{Qy3Cv=aZ6DO&_-# z;BB|}{W30Tf?_#;P9B~nomLergH}@k*EdaKd@J|ZufZc`0qaJJ%k2@(SI{lVWcn`B zjqxkmY!iTfx{N)?1YCoHl3g>GWDdA@YL$!6(HKxh`_|N&#n#hf-5%Kpo-%9agv~?? zW5Z>07m6C9f545Ax6w(Gs@hh}v^_LHo-QZs$t4<=p~fInZ4sQa;k`=uR3JYEJ6lfzE&ot?=M2dV0<6p?0DdRe0Z*y4$QLW3zHDJ0Y`JgBp@&3o$q zx}H2*k!B#|BcaJPh>81+1H|@Kc$_PRG&RI$XD;J)>Qr>S7b2ukg2=Pxy;|AoKl?4H zD|R;BUX4)wA22Af+)5O1_?^?J(DeVdH@-+o{t^EQ?@J?1gB%k*xLMs?pAd{QrlB~~ z!cuA>CA04gntAy8DrtY17uCHVRCaJ@xQwd|rg#U#0C4Ol>+Pbf0=hp#n*(~AZ&cHr zvP}L3j8%OFfE1Zi4x6i{^3!W?Gg+ujnUVK=T82yc*HyXm$>K4JIEihV<%WqcEq&|M!UeUN5nyJhW~der$XBIKv{F^+ zv4=HQ*vjw#(z#gB-kv|_*dnFV)!4Ypu<&^3RnI$>OWl$IIVv)*^d(iB^Mm5Xsm^Fo zra8LSNNT28cw|y|(4iD@x2t6p=GSa%ECQ1aO+x756K;Zv&{t2K5@}fWXPN4S^Ys|u zZZ4Kz_h)q~dd+MM3nl4{(r4uq{DpuIL zIZr$C=S5};_goo@zOvk!=@USz4TeP|TYNMTW+qH`3r<+L8}FA;H(E_Z#N9%Jg*Mh? zhr6TybjB_C*A=-F0O3bJwe8P(E~yeCop)^uWXrm{@TUsA>p1d7PNm8M&(r&SgkeIX zUVA=tHifMDm&P!cnVN;tfDdxK@?Oh1!utZ)Uja!&V;e$5mVh0fmhn1uAUB|RbMaQ| zj3@3ovf+e>TM-EWFQZ~~mzTFw(^Szoi5E&Xb8wj*qcGqq`f#Rnz;R;JRr_aNu$#h? z5?RWH5yueaNpr9Qm$h%}dvhtfXvo!vWpUxgKO#Wg_2$Rff=Q?M`7LeVT!Ts>|Vxs4%xAFcEt>3NO#rW)vKtne|3>!J#uGDUPHN3GjiL@>xe#-?s8F~QgtTeWYavYDY-lP za#F;F$tZT7d+M_Cozpui&M=qcvQE}n(t>6Tga5%*P*IBDcIdUojTWM8M%>BeBB~LL zJp0{)bE6e+2=x1jSo}4>?mQ=o?I2F*H}(&LJdLKu@zGm7r|Dv(I757%5~LAG4pm<^ z_Fp5|*=_mm=pVEi3SQ??W^=oclP^6GT?7aMW_^b+)rx)Db~N4&1OP42L#gU~FFN+g z>!jU?XVvx;n>a|8T~eWx2|b5gBF#Bt_$NJVCM_PmCB(0Sf#hzD26AxUTzwlDSjIh) zY1H+yC#YAlsEGE@G;Qf?fHku7b9~B6K_AD|_bnYM>*jG$A#Hy*Zu@xoy*b~amqU#R zZw0APxfI!#8@u(mF+y2Uh6QX8mO4>=cA}l-C0cSm71v!t34P9$>p%f|K_2JZSQbW2 zhhr`^C_l%ZFF~qsv^2r}Z4MDo4z=AyVvgijBS08;s@|ofoDzJl`Fbp(R*6(ua^n2A z#il?JB0-`a&;J_KeP(a_{CjCTjz838wm5r4q>`X!CRe&I&Gt8sizm+>(@`+*el-;m zxge#C&)EkHz|wCv(AVYV9g}J8`!rOsYlE3r*hOLj7sPAdlg+cCdi`KR5_R5l>7$gT z-vR;}wpmx+`$s{AlFDzfF(I=@vx%pL-emgS=`4!KML2sOR&TvTHJfSDqm^JL;Fk$C zOVhP2L-NL#>c7%^=VN;An+3efX>1LO>XTks%7)b(j(`K^y>p_oXR;uZeEM8Z zd0+iBcBs=a7+D?9w$p(Hh_0{Mi&EN}!lV>9?T)AtG9tefVt4W>LhT&9DgXcy3p4M2 z2Z1bYA576b;H_^f?V~{E9#xv>T%3Ha$`wF7@J`{!hJg?1b0p3VM*lI-B)uql;33q!M!E#H-O#6 zu~>PQeB>ngQm{b%MCJUkXD5YptG9wiQxr?EJtx0$`n(@|<%#O7!II}TnPWzeG9m2u zh}fA*Q-4ClAD4}A<9nnx*YkW5Z^3Wb^^mwOZ&11aY3b+2Hc^Ox_#vG4SBGE^E1UCW z8GEn}-&{g&D44c(mxxTqv6gY6DeUwP19|zffJzZ_Yh@p7!6lMu7|#UwMSr zx8nrQ)#o-KC}Sx$zGbxZf*MvNB?J!zM&?GM5kWv-Ei={%%iT3NfSQ4v@BH5DBT%>v zCiF^Wi6cf_>q!!Qm_h;OIQ`2(E*3X2lxgHlaB=6y86JS-BMx*rzg~cjy+INR;n|Qo z)Q4lLH0Pv*r2^R`A29Q@sShj08Y0fBTt^w4g_q{Yk+_~&vFg^-mx-fK({y4YHS$F2 zTpow_Fwcb^Nwxse{5CzAuIYq7oQ4Eq!u~@RAUN?Xlqq2L)$H)c6*p}z&n}y)L<5yv zgTVQmttj$Wet=XN5!>JW0uCYP$~^gX2lds7f;^r47J`IjS5{_AWxO)Y>*|*t$D{HE z{giQLu!C*1Vx|T-sj3gyn!Evvi1}JzuP09@(aA0|Nj62@((HI^Xddp|!<8Y=l@k#ySr&KL> z&hVW?PWVp=#XDm-9n!l8dtfvz{p-AsFk~9m&d6Xik5S%K?6dVkXvOh5xa+GaIh+c# zY8;D4fTSLeTcSwIbnG&ZkeuBHhAZe$YxGEQpQ=$yu4!@Xaa%1@gWXh4;yWn~V)f`f zc3F7rxUfibDYZhm+R03qF{|ndW|1BFl2Y|)PFM~4lIX7LQ+2ge>iKIMkSsT5%KGUE z88Tdl_1<#)(zZMnooJS!INrp@tG-L-G2Z3l&m=kHb4xqgDf+z*4x{hJH(vR4V%}NQ zA}J$=oCu{+L2you(i&B#cWo>4nUQ~wqe}FwWOx<1P<%ax7`V9swk-N_tbl$N&YFE8 zY<&s`k7#Y{B?yBK$?j&&Q;D*}!S`ty_^eu790xk~{wf%2ZIme(r8TXRL_lvaS6;0CPc%zQkI`?ZQBvP&9qqW;(W9+IV=& zJ{bal3N<-$j%=ktLv>TDOC_*7&e$$#t<$NAlQK3_@8Un3MjtNNTkPy*QTwy)YZnch zAcXu*{;m(#?ZVqsL3MT_42(xS3Ao|V+JY&#@|xPM7l*}zb==8{RL3IpAd3aYX!#u_ zucb%B+$z(;9lzMv7ob%%$_*P2c49z~Mk3hHXU;lUN9X^u`t|36`iix4HOOL-B_bGP zn4r#jvE{Mh zelpxo0Klnh0C4=Va?y*@ZECu-zGwnWTsZSoZeJb)fM#IRrO_}qJqiSh1*gBA^mmf_ zf{73)sobh2xhg#A`@3m4;-hvdxVrJp;okM2GHVpM3WOo1;WQHe?rZR`rFJF7^lVAE603eKh?-L*WgMabK|Mq|SuUp5h|Iop{-yh!v zdc}0i^gBS+op#^hPYrYOqcq{)hJJPU?fBc0%{Dpt;8^8RE zAN$1bKLY@RY~L!eXTJ4yMB&P{%dcMhb0y(x7e4#!bI-hd>DeUUg^k@f834c^f9rRZ zg0DXPrN^iK_Mcw=^(+>JVD6c(YiAZnuh@fH9K`u*o$efl$>`OH86>@WP>hyJ&48xajiDc*QBET~oXVmkL&6zw4? zMe7}Ywb?2y$Bh$7+{Q{NL?w?%LBF~KV@b}!@|+MVQ%a>WC^%Z+sPI!iy?*V+U<>6U z%JbmCV?V1~)>`9lx0ipD%=D{|hACXb6iuHSdvmMxl^r4CQcEB08T048G~_&0Je9S1 z)2hZwK{(`uVUVDdvPx7*HGA5TT;++h%Pa}G$=Y%s>E=MzE*La2N!i1uw@xmD(6dr2M~-@j~2&LW?uAy-P3 zr}W`Ldj0u;mWBcVqA>>q!GL=WO)8bA za`v1nGO3xkx0MvQ4;M z|J~jp&krL)7hYt?UU>uY$p)R_<*m-MR_Uu{k0z;93J8XqoAJZvT+btsf-sVPBHNKf zLdrz;GnK~j=1arYij~K5=9G;9O4FKEBUXbHCCmLkQtjMI0N@=Ts^_twIx0*V3It*4 z0q-cFP;BN8zw^M4)YiUrx7v5*QEz6^oj+MZ2mv5(N&^I?MRq9Jk)R}#N`g+=ojT(V zmGq9pY;lTJN+gPf>rjkfZ7aEabN}Mas9wANw|?@IAG{C6?WS!sC)y3;3#s`vuJr)m z@_^qKXiT623II%o0Dx<|c6IW%GJRbg5kq5RvI4rthmJXY|A)?=p8rVzh_gORsy9A0 z0{}(^2mNgGlHc#dw=NA>NyTHXRUt|9Oy%us2>`fD1gJ_QA%(&SVS?K0Q5MSr=S_VP zcKEl4W4;Ymb?AEy08RSSZ^ecR1fjqb3J+|mBW58UD`sNN#XMCqS3JE#>$}rAK^Sg4 zJDk7YE%rhMNvdGZANAor#LEgS?Co;m?rES_;82>2C5J*pc9)Rw?QGYM3MZL^$eUR< z7(?TM>C_l!9@~ zwEUbI*sW_@SN!IRHG9U<9F#>uvxsKhQKkd7{q9I zs7Z%BCTE&Rp$dQW!>M&oC;sm^%5@!MM0NZ|adia7s!;izsaQpyEdS2v)ps0JN9X@q zt#MMXAJ@NM`~Le31^3>`OfP+pov_kGw6{XRWwCNv9;>#@x#Ql_nbP!<^HvP&9x_&h zG{Ukzf`m`hpqze0Md7MtSV> zLz^4Guzxe8I__`BH5h!^WdILwOo_z59TmPxCwEzcRp7fn;gc`m1$8X?HDN!cR^zz;bJ_{~T}$`&AgfGA2dUf8sD^g~ z5hY@G%pYE{b!A0qr#rry=E3RrEiL}|p3@8shk8xDI%jAmVJ1NciCl$)jB3bmC}kLw za%!5_)a(jNLy<&6N*Ry2>5@@9Z7dpDEV5YW776-!mPkwyVK^FcrsHVDXHGeV{gzS? z4ze^9@rWnBuu3c(ZIe=G$GWP_f<6m3$EO{rW8seA#&MSi;7xWb7(Zo z`#T9UFwbPx!R?HSfgLJEdB9xKNN*=$+X0R~Y~#!QzW{*~S#r7mUGPQZ)9chKGB})G@1IR2dGHLJhVP!y)l_@@OaodXpGRfT?4)UDl|M z1()S1UAKr+WlDnIO$%Fx)(z3ufT*lwLTvxi#kZ@&d_q>ssvd+0zcy zNvWytUk?|~y9H2%F{;fPiO)r*n#)!}F)Q-E0U%4HU16A@c+3Yo$zV6ZgcNq1wRw|J z)Z0$>ZUogi6A^?kN<*$&MC5AjtXqJy08pT2N+Q8vq;!pkjLjdrNFJ4){+5eq?{lfqIC!b40 z@%4>=T{EX{tgR0Ald0zPw|0K#^8OcIzxhSZ)yc*W?jG#i>R#GC*x5;*_QUa~UjJX8 zUi;|g#j(iMG4}_rT)T`h!hSpgfEO-5)Ao0+T)X_u3s3DIOtJ>{x;v}AZ~o4o|H{qw z#S<&1p1$$9mv4Qe*X=*M`Z<}ZE7vaPf%^1~U!oRTd9?iTr+(wvOJ5#$@&|rQld;Ci zLbAm72Qsmxlo>?C_9bVvlYaZEqokBlmQDw>I+Rit=#`XGDOEY&>8+upLzGgD$Gb?+ z?X$bN7+<*kdubjBkuEfzL)-0Kl5hNA5WG4&^T^5nWGzem&U$2(lRS}tQ0vSt z0!ZT?!BCww4TnS{zVc8h9CiR;>bTXu9cHO8J=Whz3Y6OPD4{4C<%uuifJ-5-Jk?WD z)#l9JMjQ=!ZO#aXdF=DXlC}2AD9>ckmuRk7GM8RMbL*O2p|Q`Ef-~=}Rc4IAUK0D< zDl^lih09f8;0*wFm0^lwpJReBMzd$#+b@m?L%L1UNRE5?+Dju$Q9R~$nIa71c4k*J zdpU)o~UHW|Avk4J)&RQic$wj3A5^Zfe?W zUkWg%M|1B?_~vw#orhp5=;xq7GfC^1jWG;%li1IXKU!u6>F>m8EWC!Er!weISY`-A zp~0@s7~^)j_R2_dSz9o(NRB(%^=JE1PNet%Kp4&vA-Kv@nZ_bdB~OIc(z8VP-7Jem zK}VlH;a~zv0e}L8sHC-mVk$p#6fB#>vUHiu1@K2xnU?m*zLrCKE50x+ddG9W=OmoT1 zMoQBOa}WZ^1s`l?QUTQq`81*~I4#;Zts8U#X}PnMU`&k3Z%9JPQvNOg03ZNKL_t(u zs%oEoHU7kF;U_j`|J^s6s~g&}1>=F!&is9@W09dRR;KqG@+W5MkEGV^eD>3VTnB(m zf37fbl0sQF&A1{O+E@(%K#OJ*_g*g|GRn!r0m02B4Bs}_4&3TjMl-r_ri5BZKR^j*eCO&VV zE|0|C?IcK5k}H|R?rQMBkMg65HWKam`KmCt5cS=M*9)+C;NPsm!@bq_MB5WcYwCm7 zG^fA#pcnUK!N#x7oAnia`ElniJD$pnzWPjm@xhW?*8m_-q!7v~G1HiA>YRCu0qY)S zB_M?4f~RBQ%#!UFqp7J9CB&&Ro=Rq7r^c>+qZbFFGOb6W+^Ml7;0xznrelP`Yid-- zK|jkPdHk`m$koYrRd}utAWTqUeO*u>cqRo`h$5@R!tp`l{Ttq+>xGYd!SP&OUFmdI z5_1V_I6g?!g0;1m;A2h}3%{FHX7m?7vu}Cqk)LdZ!#oQ`LHI2kRYb0eIa#o%j&i9A zD2nQ+fVu#HniEA~G53<8JUqTSXG9||)V;w_Ouj=Fq3KYBk!e$m->9vMLaQON7UmX# zDMP_`QWXBBpjU_76CosEH6ea}e|)zH*4s^q+LZY{$FO$Sf&xQ%qt<8G_SoX7($u0| zuIm8m9z3k0b1y@qn_M@k>CnPHLQSk&Ax}g>i13=4U1lOz1+;_^bT^~<``pCmnnki$ z6srv&IPuO(YsK2W5+tE0wRC0@uc6PJcKlwJ$I`89gkgkHcPkm}Bvy$^u10$aCa5-V zCIJTwgdwUEkxHsz!KLAnovZ%NwEzHSPCNabxDYXwT6)3FQ40KCUaSeTryY#(p$T2# z^)uYhM(wn4r{22cS7r>V5wEV92!e`sqtAm-7&;z|`OxR}3iCt3xk@vs6zCcz1O=hk z3xvp(aR>OeDs=fBrQtymk9joAb(4fco<{dC_eeuAZl`G^lvKJ+ z#_i1SWTlqY+fHC#a< zO#+?-e7K(yhGJig+NtSL&A@}*Wa_wGTu+?JwO2>o?YO>R4)@a=L%!C|f`jzMNR1Ul zb)B4bO{5S;jU}_Q5%Ww2{ai^X6sA(B!A_D!!tbW>m{T2BW^}7W1((%1L*&YBXjI2a zD9M#oV&iUx03{(02fP4rBv(@>?AD59c@zM=x{e8QDonRYscH0gV#yUVFwt<9NKDYe zeO{40WjM6>&g@yoDpB1g(J(JHbpViD@mv8?N~*$VDo@1R8Mn6;AHL-^lQtNr#`{gG#|ajUsxVUBbMJ2e*d^W{g&``2QkV*r>rvfg$K0L5G__LTroYUzWW1OU8-Ry5TRLS94Lxf%$rlmbFgXFV>i ziIULY%7*Ja8Hj>sZItoewctO7C)+9epB%S;wMsvP)%1$-E1G=puO{(|Qp9wE33@x| z>WzvEfoYKf?0#GN)mz3jI{gkK+xhEHAl+`s+A?>zIx^*0`sxxdqW{tJKd zxj5~aGwX-p31p^UdiM(gHf#64NcC-R?wVOe`?qeUXFi|iqfdYQrrK-NywhL*!YjAh zUmtE7nqJ2g@fg1K+Ov|YKYZbT(M+n_RCh?8h?coL91TIj%dfxS_p;yq#N*~_D+hjgRnOaZ{ny(=%j_QLIhr%O}%?EFlnR=#od z=BoI^=Wc&)KYRYv^0}{U{QfgHKj&1nKlsysnuff6E4Ql9+3eRBiOP`XsM&{M0;!aWNvEh}JZ=%|%l`(c>>Gq;f<+$R+CROG4TnUq}eTw#j(yNOw1 zUQ_pbS$jRoBB@)1YIxkuBv(8Y1%cBlF+y?B&+=4SWtzp(t!bu55k_{I6`sDedDHKv zN`hNskNoJAW|A}#Ze3$KPGcDdeC3f+ewYgQPw53s!)dT$`$08a zn=@xlIhZ2CkX>dqQ2%&hGSC0F6Ds?Zd9S=?2 z)v;4$EBff1Q`e#q=b3bCdhCncYr(-S=Jzr}@xiS~a6C4y^tN}nWih}D;T2%x9t~renMRw*sc7?nvP`Cenw>zH;c_Nb(LyU>l=0^4 zJ^ULM*G>({(on1ZR~HK)PJtOokSxpGBy98W0ly_!|v{CAV3fu_qGyg zh`n0@LXbv+=dutBbT^XPym|ZO;dq-f3+0g_8Y++=vrJ_EhFShy8}*|&4pLL)^k-Jm z|MNKeS(mH`nRkX4Pc(mg)_(Hg`Tw5e?y~redHfGgMIWET|3l#)R3KKEprD_bH9URF zD)1xC!f{VJWoFs5NajBN9xv$S)I>_D@m_9}aqF0c2;_-0$~X-sKHQo!(Q}z4Dmg@5 z@pf3-J@tmgFG+^dYLH@r9X(8QaY3-soQVqZ@IM~TE@zq?a>owYF4ROjSA(}UeIERw zYCBM`?TD>CG2F;2)8_T(`_0qF(W3-e1?vLNJg3wG0I5WKc=2F(p_06Jg2R^YbDP8| zYg5N9qCt6qjoO*%k->I0citVfGtEK8?K8?4VdOQnEEF5B1x6WHrghCCPK6D2QUH)r zjylQO>x1Bcn|0j271d@fMO1lKBNSH_G@Vi1B37B19!&y1chV|25kCPuK7#6?#ESZj-l2)Iw7EYC>mmEUS zT^QC;=MDr&;|y|i`=w#Afv?V)huEFh)c0|FMPUaq8Su2@OHvqVrGr=jTYB!m6LaOmo@{ji@Ysj@^wW4`|Sc(|X=opqUk zYYQd@hc#A(0I(}&bU04l;InHFb4{Ddf((C38GzV`E|n^w2oVqS;OyU zgyAd}@hG=StTJOLsiIMi2?_@pVJM3wWjGq;(I`h4<*CRsi817v)O76DG)zz-1z;L( zuSMZ7mqHbDX52}WfP+$!t7ycfge(!Gb{dWH857S-QB)cQcPWd-%#6`rv@9V7!PuqP zq_<4gT(Z1|9u4zxI}Q6;ILHx#!lbOWU=oJ%So*z;={So-xn)otGo2YPa^0tuMn#*!6}d2_`=2rxl}BDbamy<7nh4NI=PhUV5ZW@5X- z;&C30coJ})%QO~-P0Ley(9aL){FX=E`oxN>Kul&%+dPxyX}wUW<%ys=CItK4%<& zw<0B#QV@;v!YO~$-J4|T=0@{gsovh$4qE4)%?L zRPIm!n7!XlBY`R2yf`)-LMWJk~DaHs9U>Yv9^xC{3CFIcr?m-l#p|DD9)J_qAZj;`2oCbX7O3>R* zyoUbj=i5rD!uUVz<^7!`33)W+gZ;#7XikMqFtSt*50Zkr9S-thT@krzuSJGS3(;$5 zJ*v(c-Ho`wm1^^5*v~r~(f-YFZ#67z-4CC|nt}Ijgd$f;LY~Sb;NdV=N|_!-fDDge z1mQ4GLs3lo`n;LNqB3KwKGWAsY&bNHgxAn0!w91yY@y(GB>|s5=ki>}e!jaJWRZOJ zk9tu@6tz>ZCyL(c|L@gTUE7van&Y%1$PZUD1-hcYl)#m`VPUB{N++e#Qi zn(4Auq*ZmP_@T_we#iF0U+cC`^>4l~EW!liF?VY$Pvr0*OMG5nObA0X%&T(-CWz^n z894SuJmPa_-TqFZ8D!<*(zug#HsWx|5rRCChK;wc1O-Th2m(OG1CJTRD$$**0m6{S zVt9}m4&|9tN?9J&3<99iP}CPpjG(&_&z*6Uf{hDfrjsI+kT7I;)UIen6;his_HG7B zf#l#dG^Ld8P{EaElA?6VBB6>MCIXQQDWO>UsfGzdtz&jkhV`}*)1yT`tJl<`A;$zG zp_#5yO4Uy$;kK!iGN$$tp9?LtYaCP1-1OR?lo3V*GsCo+r|i*M4G~y-Wh8PLx6hYe z{iyfKZ)eZ{!!#)Oub=DOs-&SH;(U1X!>wDt>50FSN1o}jB5klBx973M1ZgJ56fi-T zzS12Yq%)@+-67>EBTpqlkR{S^h?2_h*4ir1|W}ceXDDnnj3)p8PvA`!_?Pq53fc02Ur_8gn+6vc70&4(3XZ+qpt2 z3uNo8K^)k5EwmdH0W?nP)fpq~=TfQ3@<>(lq?L_id0BI&X`E+{$DC=hcWbwo-u!$2 z&uF91pTA6A$7IH%p`39nvc1n-XH%#x-I_ZJpx9NG4CUfu&g!!Rql}jy^{9sH$BdQ7 zOFV29F7E)KQRkj(>f8tRN7w8(?MbM$+x^zHTc3@e`o+=4LZMtpV^NzkFhk)m@2o|g z{b2S1YwoNY^z#DT6uCkO1ee#I9z;C>0GfmK5@r^Xxtd6*Omyfx{cSet<>}IBymfQ< z$?Myndwu*%H`3qS?moZQf9dA#=U>15vG(wCr*or<@2A4TskJ=%C{?Em#?#z=g_j2| zc1?n-;DDPZH7#m3Nj8?tXUfMOFKu55Gz)h(lfulXbYUwez zeKU?a;+|fcg?jO=-;{THk3>U;hXLR&|E$8ai%@hFu{t!&ntW;DqhB%y)mv6+j`2|4 z)e-W8bo;gO^g~VolNn{ab1Cq5g=S--p_A|R4h?HCK~8-~X5%BL5q zU-za?nNR)hHUKo1&Eb9m3Ti9b{*4d;crD#)YIcKC6FD{3Trzc=bZ;ird41f;`df+N z(yi-b0KgTcJ4APAlH}naFU@MHFPsIOMxu32AKc1MyuVamFz3#AwK*dm3)7?HPP+EW z2mmV6Ml{SzP0jCSMSd$~I1NP5&xZR+9Ei==$3;2I^CP=s1jP!;Gdb>MMbZ`knAI59 z!eCQjOaUPAg0201Qtp;#jTm6&l(Tm|)Gg9pk4jSp!cdttc2`48kQ8ckkQO#r1wixd z4a;k@#=))d=y#HkAL3bW;8U!S7QShRAdY~TcUiL^9o3eBFv1v7Mh>-u8mNlMG|2(L zw3)_mL*psGyWW~yB2e+YT-(3<$`4PH5P}1~cRBh#4)yO_M<3SCM{XY>XnNWGo}XPB zi`}(vM;Tx`F4c6~V?37tVAe@41-d)O6jf$)4b!=EZb9UHgMFrygWPoJa4(s^Z(=FX zTCwv)0)owpn`{mQgHoF89X5m++FsP)!4X;a<9gl?$NzJlahPkA=cei85@JSe}ZYpYcp$ zf}~Wv?Kq1?o(N`;Q76q}84mJj%qQu70WZ(!m?EA@^V9$Uisu zh*#&#Qd6Hg?nntrK@#xtlu?~A%2UQ*H?hl1Peq$zgdtC5o=B&{!eJgt6%BK5+Q=&` zLXah*xolcxTF5nGUtofGCPXfYhI^Ya&m=~u$R%#VIoB$&g2_dvp3xurEUCU&s<+sQwaT$e657n#>pW8i0KFVYH8h*AJ5@GO z#zlhZ*ze{=jS>4?W@_q$EpnBo0;5So(XDI!oy4hVZe1(zS)R+rl4&^9@1@1l^C(%V zyAhYCCt?mv(C{D~?4_fFR0$RP+^Mm|=Z44Z5^Ei^oeJB(868#~l^Hz=xKm|-5oNeQ zFlWy?hC`K<7$dvPf?lSXBp4Jk6U6}s1;f2WcW8OaD4vpeEC3+!IWs2wM=6xy5|ODi zl7h>^@Fa_QeZegJk)5h$ml?uHcP6v6D65*wR(~fc1c~)|bL)~10O2q{xE=9S3=YzA zQ!koQNY_OCvz%V8pxyW6Nj97 zs!yZ?_iAFHzZBEh@8PiE$p_qjV}y@HQP0pSo;|nUe<_If2L7$x?hChfzF5PL)U%&u zaPoWp$fXo%CLt8xn|1YOKnoqIrZBKdJ{-OVJMoLjX>w68&scFn0oBOwl{t%%+HEcLUWQtJStWJ0Po!4)C z5mQu5;88m*mV#14|HvQx(ms0Ha480WuWbJQ%qi!o8~^50fA+5on>=*piB~tCxqSPp zYyGDTmr@OH4xb?mU)MgKMuKU03Lk&zwQp%A)-7tdtURS_21$mHX zCqA!C8{r@?H}#;O5sFNg{(tPfXRKstdLH(E>Eu(n>gL#Kx~C`fB<}3aa(BrkH!zwM zVF)lS81?31}~SQvCCa(zsa!?v$WTo?|Y%lv-nCVev^8$?qFCv{)f3#bc zsYD0_*ZEiwhKvENL2+Fsvc2rN5eXX17?X~~l`r({DpqD{a#*(v-?;TpJL7+H?-jy4Oepq3LMU2& zqV~p@kFkR_>@vwJ;Vf2JNbnH!QaRc=U@E=I=>3dzm> z?QD8fS-;`)KR0i*ncEBwZe`TLHlWTJa01epb4RB?)(LR z{$da`*xuXu*_UcggfK-LS85kO)n0$5Ha)JEo(!^yX=W z`ed9>#LFDDR%id^|90VPG^;Z8+h19E<@?V6@%ta!T-p6czg{=mZ^BP*6#wn2^Y_~8 zt`lL5vDd)ebx#)BiSY5Axy9)3b`Jil)hFUP^GogO=T5zWAKFU*0G#_&--dkx0LBae zgv|X554{z!b@%0U^|$NGY_wY{VX}!F?-v_S*M>WV-y*laJ%0Gc)T&M>!vMfbRnFAl zPIdOh6El$(#s;gOdaq9F0#7NS=Bo23HL&rqDD4{@&!GKXJ$GND1EgyJ(4SnJX4{n- zR$^LIgX>$r@%Dp%5%~*cHd8x~*=J}id6vZ^g5;_I03ZNKL_t)DnhpSH4lbn#fgiDr z7h?bjdRSE22{6J)R@#OcF&Ei=(ekD6!D}-MAZ%*Y+Ld^^F95(2WFJ9b6$StnF8Qa( zBWROT6QWyxx4T__P;2HjuoJzHq6#|X6zBw9aw_>bfjbU%JkmYulhedFWE0RS#i zovyecbp!I)r<=8|zp5#LnB7pNMAzasCs{pvC|| z6V+OA{FpZ9-MrvZXyzjlLX{~@kQ0!y5@jMEygp4QJUN!hF;7Rr&I}NOpuwn1?!7jR zJC5XL^SMSg;n|qCmb}iYAJpmIJ4vnQmYKp74@>p6Zz>pjON5MTS+V7y<7QjK`&)${)2dL#O!7jfLoT^7()8ASQK>3dPC#lM zH)=6as<`b+uBn5^`(@IvqLx$Us+h_$Rq0Sn4oh1>;{=2-G}tN@FGQe*P-=iR939Nf(i z0Abi@@at^r%~@;NUCr*OiCWbRv#A-mx&dN7eCE^hdlu5>lC?T+dR~ zcL)Vaq0^Bl61DyIjCoj#R=NA$u&Ud*9Nqg{)WykwXS+W#+AnK8#|cQ(a+rsWf!2~& z)!LPBP z;V=ig0olKmN~vunrQ;LkW9H!^RkNWuevofpodE*oV#gKDs!Z8O`ZbF12X($~oHRCX z4R>BWT$p)Iy@LsBO4_P^{Mv~M%r;Z4JRaBQ zz2R>0@Xe`}HQCovpK}Str+VjF*BKuaO6dBWYcvdZOUEaQ>+ZTgIjr1}96iXF9*crH zv*C0A5VhE&ukMs#v{f*Y8&RrkA}qYItJc})8>9Ua6VzGt0fDIWtY7&t^+HnRC!d

    `5+vd|yNUioeOZ*;hOAU@lW&)wbq!=``17;`v!ZTsj? zFlL?l#VWX8L|02^J1O>yVl3eH57{=zPHcl8s>6W~Yq8M#enWQSlT1z^=v?ssg>x*? z*0-~;&IH$0t_(nQP5{8t=cfkDSH86UnO}?$6|dZSlQqL5rmW)k?Q(aDvQFYTWYQSxug6TuU?6xHf!`;e|6Se^e_T1 zBJCAFZnOTwVs_-|s+AI4H3!780{r2qEw?_bA&BIEVook7WEJ=pKk4V&FofSW7JIw{p@o||-j1e!D z(Wbi|96v1l8f7jD>TK~sSQUD7Sh@k3?3aE_cdsSP!@D;UUa0n(KiDp+L~cA&Ck#uj z9iJEjlwm)jS{XYXI`cx)kEu~+@v+DlLm46r+YTCw4yDkxSP&4(6WLn!@|mplT*?pt zWMkn5#I|B#jP|Z2*+jHgLPA_bj8?{5%FCHAr7Y30-y9-j3wKnNDGX<}UpY_FlagyM zY(y<)eU$bKf8~q4jVrZ-+o|J|2d_^?dxg=OIq1&IIxqXx!(Z@M{#KHy+X~pS zm%cr1EqQ*&Q7+CVGH5ur_p9?SHXHM9W5LbFqA~C8-AIPp1sJ&g^go82XLhjvuVu{{9X6r9Xmy{z@xaKyTj9 zaC^9`{&3R#a#cy{B3`O2vZl?sHxLuJ7oc^X2%*Z0id=_G$v?vToDF4SJU~&Jz1%_P2UU2c)wbI zA&S?i+jxlDsEt+TPXtx~gmu^7D4|sFYTf7k35W2AC*nSTy zUm9)~grfF}Kiny+Tpd5i5kkpGh7GoGJ|qONg4qtw1~NJ1^1Zw;bh;~!=eK90{rK63 zWN}nK$9m^?=Facddv1N+VJ@i(H94wI^D#xK*PpIGT9cgpDKV?o)bJ<>wr$_)WH+0y*`1JSxjNRo;C#;J>rrBLvo>ZYR%H#NKqFPSwhS>$y11HO8p)+2KUq zoSvdD1PEy`l@v*pi;rTj8VlZE7y>G3@}c@bQrll0f3c&?Y(Xy6?fgen<;Z} zd)XJI;)Uj==9L0~xy`@;AdJEW?X3k~L>A76QH#~Ou0@{R^?)*Lg`BfK-@lc*0ckFH zahvf<`867MoWV{}pK}}Yt{0FpmD8ijXs9xoO~m2dEU43muTKG>z2dt8(Fza(KcWlg z!+O_^+KiXFzg>t@Aq=zQikE8nQmmwzI~$a#oDF!~aYUtX*LjFh^Kx7sly8=1Zz6Bp zed6t{+V)YkrD2?itjT0VjRr!o<74AuPLbIN3jjiKW8TfiqAHY4lI4Z6ti9cS*Lp6( z5Vcu05u(&prl^DFv_S+Bie^VuF_Y87D!uiz9aj0P0sxN3Z{N7~rTzoQ4ax9!OlLop z48+`K=y*6A3Fcx;(A(LGD0Qvp+DIlu5HEB#5{(5fpUEm$*+hg*hA>pQQry^%!s&6P zwc({k2&6nw%koS~u8;0!T0v{Y)5;Xe*r?4im4rgA>rfZ(ypuHMUFu@y5-+4y6=gY1 z>r+z-sDm*EE2;v3Vk%dktQi9cgXw%RBw3d8t^&6`nzm^QA7$YT3(&vpi_tK|YqS9bs{(J}+Bv;ep z%54&(OqDC60Ta|-4;u5H4J|DaScr$-f`Xs}g?QrrAE+tuiJB%4T^WD+)6GN}9-D`xWk_ovqLkxj(z zwS5uMuzM*C%z zsp(NQ>vJ&RM%1s-+2Ca1YA$+?PvY(gn6#V}yju|?xt83F4@&zjv*UbBQI#sK%<+R9 z3}h2w6htj29r3vB%=#Pv=FbF18dZR8GsG0iOloC5z(x@Vbv8X&eMGFPjimT%@+T+A@hirnJvcQmS`Gy37OSB^)hOa466)d$$C z=#c^B3+v8jHt3ISkdXb^@~ih@r^-D1PTId+8ePh_R5Tu}!(J{FbUIePHQ?cZ-Mc!Z);{v80?%a)mOqlP27!GE~*Ye)BTKoB-q z)N!;j?G>L;>_+tL^G&}-F~!y-2*x-bZY_D=dim@7@|%+DTG#1s73)vc+ROgx3kD%{ z=J^K3aCAp5Jgx{uVaqA=f;rgriB_i8bKQV=F>S3$$@Q$yeXrMirq5h#qDfI56N_z069kjvwYmgX586DtU1-`yv!og+d4p@8-1*^J|QGgy*Wc;JG249G2FW z2mqL3yKDh~C>0oU=GjJ-DLw0^OZEy-74-n=}63<^Y4DQAYsKz z6|PM4u}qR#bE7($>4BN{tLbr-j(Gjt*jt<^sd(QxdfDTnbMDRy2rwZo0J5@|tT@~s zypk3NclZ9Fk_pDN`Aoj?%dfRQHYxdJoIN<6y`cu51AxI+{_xFNbHP3TQd4m4#Z;7f z>G9~^E0gu->Q$!Bf2uj!E*H*6YfsjW?&oDD8}r`IwOKmiVV%ZpRwfctG+k9tn_brp z6`;k7yGxSBweiR2KO3UlPvMU@FTKyFPvgU#x3b}# z&l?F<#^h_h|2r?CI-Oh`Ciu8Z(M+atu5K5<3!tMefx>fs7h1-pz2-4pY(}YL2odG5WuBCm&6RymdLu} zXW&}ZvUB>a@(=?_b+&bt|4drm{DtM==kzVLDW??U4Y`7cu`*esx0m!q_fCe3Ii z{nvONYHq_K_Sl zb(G~o5i5^gG!e#QnE2Ioh{YN zR@yZf$`!QSrZq;AxjW7r)>6K+m{$5Ceo{K)mF=`-xBaDm!tJ}*{BP;r?X1l5v_YvO zv()u^-Re0x&x_}8RO`^QNR-2OK0!D!_-_8AUxQ}u{_I}*#Ym@!m=;IQ)3gxilgOrX z2PdM^ryke<%Ayih^L%1jwW}(HEv>dD9VAs=A^Ga_3)6T>ejCxuZFbYWvUiEC7G+FG zD<>#uUWFq5L`x!z#)4oXjHtkmf$7Vbtdm?1A1-t`faPrvvj%Fxfy6xcj4Xahl71LU zila6Hln@~bnKvL{p1DgEuWA&+5Yn!L^lD7C3K4fR>RN8q%S?{8hr^yb?ya*!k|6kC zFk3S{tac!+$)ekg9eXq4PIuBF5_x#}3}I~3NwN>*kOHNXim7=Uugv|JRm1~DX|jn^ zpsa}!5Ja>8QYLgp`o4`K%|}o#W-LG{=4T#--Fkh61oFZ$^snO+{G>w5t%Aa_pu6@P zbsd+z5+(NSjb>@+ySk}Ie*vgJ_7G7OJ-^7JLOOU+P#Qh{ecgbsmR@_jRe2LxNCN9` zX;iY*U$S~H{4%W;j@cpA<&dGJP(Uoe`B_RDzKOuY)O4Bh9iLv6LOWK zrL;qT7;N0F1Ff10Rs~n$zL5ii|2p`*EEuM^GAagAieuJ0wCIA=lmxHQoCxI4)y-gS zWd8RbcyY6(PTIL6mdZ|etlvoP+Nm&31w}s;s(H!xilf$5Z~%|`jU{t0gU9PuA3-*& zI{4A4(PXQ=#GHkKosk^9JGA1u&N=440=wlwOPZ%NPwilfE=M7cB?}`d$2r@M{SQ&W zLclSXx1DQYYQ;7+m+4h$Ualc0tK9YNbQS1K+Xc(BzGr1Q4owykuoG_A>=^G_GWk^f z$-mL}sc^(@ADj=3t>KYDqSnL!Z4R;g@dX;ne6Ic7sz7C##a0R z)WCPWXL-eC8XT#f0dck->-7}WQg2FaU$-*h3BhP||JbPI1ggE4!T_C@DcwW=w2sj+ zL=f8fXbK`NAh+5Fh~YGLy837?yS(z?xTsYtR??hvNmEIWHk$Kn;0sWKsgO}F`owV- zkKtVmT{eFzQBM{k{+5m4N_q-^%b;3Zx8M@i#^?wc>mQe%jJ1I(^3#n=>wJp^VL+nF z=Okjm>By#hB;4Xa!B;a1brJ%c5Z`5pEbPI5m2x#f`p ztPKF5w|pk?4K55gu|&PhWte1$w)o5`sy)cr^REP((uSucECoqO*XUc~eq&xl@N%rg zSB}wH3S`LjBuq0n)D9bcRQO8N*wT6>$bTYWBsGI`W40CA_rA0v;&LI_V#v|TQmeFf zIGLkke9AkpD4x?~ShjOOn|)9s%bSx_WNbUm94!LQ)7O7&Ie9X0?7xgAAIJi1T*FB< zpbbHlRws#>uAJ;eX3-$#gH1CK|8wZmAN@s`$gFcG<({Gva)Gsx-oiMZv9hI}t%$G| zx(avd;N5QV(PSls!j|eS`9wFHk^r{ z(SO-nSO2)tMZMhjtKy??CzyciHsa_AL;eYsy) zJ>}b(*BBje^y4CF{{WhO2OFJ`Nj)OJSfq&R7kch_d%rr9qsZiF5q~BO%2?|%`w7U2_Hza31~`V4#gTd{C49*!>mO&6J0tjqdjo-&g~~| zf**4$B0#ldP6D2tq$15#Su86;?nX~_BH$!<^p(Jz19auB!g4z?zfu26MydA0%Ar0I z@FF<9d3y{Qx5xvc69PUT6TUzC&f{Rk^#%QU zhp{AD0@jI=*i-Kp9^)4rxUT(j1#7Y-I+?hQ81G4T#)@zJ zpY)cr{h4?h=h+%p{HDxdwa|Afe$`Ic4cd=p44g9gGZiWe>v!7{=G_<>M?H*S?F^1} z_Kq|XORqc~w*D%5=Y{>TZcr)bsW<0w<=wEVyY^%KB>y?ggl+wo(1m?+OW!(Xun-HE z9zsA^$J$6Pj*@`rOV#!p-trJ9R-Xeo5ZCY1G2nm*?Eynda5Ya`kg15zNjFG%3D}%8S^Fmk1~-4S~sJW*G;syWfvBq zLFaF1{AV^m4<;|RjamQzU?@+zE*=2+mKd=|4if>4umP_J9tyDap!1a8GoyS_R)-%`rEx%)XQ6E%2JT$2v znz7Tx#jgboIV@{hYcsxV*WL1}`x8VBc)pNg4H&bPcdOqP6plL^zl>}`a6K*tbugcG zUarM|`!xpa`{I%^O@Xh4DkQ29R58F+;>MYWimgg$Z@X1p@9#*!M+BfwRu*!2X0A-p z)UxgvvX=GyX|@VM4uz7ZB@ogmS>O{|A-L<0ZLxIkDdFSFwww`ZoAUnI8|AVmk z&Gzv?df+2f4VTug&&BdU3t>j%ADNVuEBU~-gr2b+j1f(o?@@gV9<+nK18JL{w&)!3 z7P!=kyR2Rb6@-L_U8VJh!eUkw>B6`>8n(ORVB*iE^(2M&7sY0nA4(WYJkh*#_ z!eb{)MFMBvVUkwF+z|~r^X1$cU5v#t>nIX#Z$I3vXuw&F)3!sALHcrjBd7li7*R&{ z^fd?_J9vX3yQO;^pvt^I7MEtjTC#!$dV0O8cLm6SLnBh; z+QqKlI?qW24h8Bs`d;f1(O<1xxM+>+z4bf=CN1(Am8O=hw!xTzS-2@xjB(0F%4?MY zkMkuj*Ygv5*l%0Ml6Pdju`YxF=3pO2^q^dUuA{r|lH159PU8UO91TOSUyyA!a5ZXX}=aQ|JkP7nIL zt&xqo8no20@I3B*@RLdL)NB1M$$IP4u?yGEoz#xTPl%}DFFaC54jDzlf{F5tGzcr< zvhF{icN&1=GCE9|fJ~s%pjy9=>pu2id*PCU_B5)Gmk*Frxk#)Z*`6#!ji`C0O*l&N z8*OPSEgWjF;q0;58`YX^4Mjuh5QCgoLHOoKlC!WS@vR6PYF^MKFG=Bw4@#0PFH!L< z*Y=)2P2KFvUqgly_VsUrZvH;-m-(}omm!TaCbIxMIsM!F1o0o zbK0u6KjMjsfT;Js40Mog$d50ZAHqQYA$7`lm#qd7IVSU5BXIi~I-!HCjc&XWZyGpJ zk%-LSJ_7*Lp}u9@$zTwL5w`UM!3=H8B?dLFXKTa2fvs`a zx13**{TlSmz5})v-(_ntmoHqT-!hIaBGI0=`V&&qy)B%$-9_??e&!50)O;q*`@vvS z8}6*MKN-5_VeB%l$f^*_>0nScc@M>}8g!J^PXBbjEagD%e?E}a2Fyx{jyCaZt6aY= z>J@f^$?a{I9#f$gJaLuQ@1$vj9ToRu0LT?PY*cf?5jlifNewm>Yfbvl#8sqZzuen$ zNHQz)xkxWQVtd=YuPhknm4a_`77|F@4V@nvD5Mw) zBpHiFV}+avam|*KRaS#3wDL&6BZ)ZpR`Q9v-yrjAh;hN;njyBN$%Y+c*Fgm3+T;dr zNp1NQUttd63R{piM91`&A0$wj_a?0f2&Ws=`<_-w0 zU_gSREh+pfR4yclgYJD%(U~N;h|5V(8^kMEiYl#;ekS4lO_=mJB`v%1H#lS3sI1Tm z6Q_j$+9)y8eYRMcka@a55GxW*)EPZ^w_M^>sweq=8G;qBF|quZVM$LCC)j(J=}M2snv zBTnTpE$&9q9tYkYqrSJYh)l5Z7K1O4t)VZo$k{6|3Wi;DZcYN%TXmVqix2{QK{l2# z|J8P5I+e%}3opCUwq9GXI&c};@%N2OtGqKDD@?IEkhIX3aLhF5*cTHbj?#~tmib1` zmj>^w4N|&R6ejC`GrzyOE@Sd#qay-biv*IU=}6ntnAW?BK^lEpemjTu@m1Q9jsgig zUH*)b9M-9oOdwV2Z>l$H(a^~IppuMKW^&Z~XMA**wITe9UW;# zx^FLU;Xa+f`rbt_xkEo*vxy3cF*%w_3w;QX%81Th;1I2}D3UIdZIc%I)418xMge*? zQj4pqub5wCJJ#kT$01=FtWez@1hPsjGmheLQ=7`IN3y0s{(KPe;30%? z6E8mX^T2M>T`~!XU42|&B8?umCdr@bh|N`iGI{WQxDtfCSd}N2xoVxZv}*>h{SflH z@!9HkM^q6n{aaBG7K>bo*|&Q-@L6&NEB+##o(P38&0Pw(_>H+qlbiJ?wI}4OYZa%X zIn7xZDUs(0uz7yJT!-8Z44zujsv!g#XI`1owNOxMD-a>3>wBx+KgIA#NIj(?doU>M zhPvOWw+FK97WEJT;%|`(yh=VzK!E&g;QOK;nl{^FK7pcad(+A5pkqgJ2g1c)V(zcM zV>^h(r}D)n%M+hpwjeOs;qVq(s4Y`b>xE z<)6rFjx(YegP>Rj+T8I=Ld|lB&GdN-az8j{$BV^_X?0Oq;L!_BH0=kmhPIFF`D-45 zFWTi$TXq0JKshQ@2Ee2R-JWe;oX1rty=!&wKVRdT331r-U1lYSkisU)JI|ENT~+6O zl$~i+dm_R+MIbke6NN8J$=Lg;Cr`!k&5K@EGL!4S#h&-3Z^tX2U9~AxR{87uUrYm^ zJJ*-JTNXSJZkP;1L~dUEzuOWqA@3y@l%1@?jbX-qoLc1$&O=u2GDGbb9 ziWGHRJTXZBsoHHyx_@IS!X$AZBzObBV%ShslNEm_=Zx-R>q&2u)pmdyq6OfDfhOt^ zW`a0Wk{4ZKUSSD<%1hyZL~iOYNGJIk*VCzelsXCq#WI*|<@Pir?=J(Y?P{Q(iV*CrXB; z=WmUqZ9lYJp%A}b*1cSK%}z6j<;vfqt?gLgr>rFjmUM)@3c}swp6rZwUGZx)on$6= zRqBr902O}Obk&THoNZnbz{&7lDe5UpMpwQACX z#wMc~v+tieulu(N*;R^pueWC5p>C#*k={6l%|u5VL-!DcBfuYKKa8tR?ARV;^r&RN zP*bkd@3>%edFt;x;^+5X0C+T)5jl5Dk!~fB1?Nw#B~nmAwTE-UiEzpZfd~S*b~$Bp zlJA&5Tgzo}<0_vL1cqGw2&R_8vq-R1-X961uEr?XDYbp&=K){0Q zeK31`9fbuVG_r%I7=Q$Lsk&&XwMBGF(ABsS;*0BV_+AZ`0j`YT+W$_8D872MJ)nRAdgpg5d)_Gd~e=;oKl%F3I~Qg2CkSu*f$;G z1d*Vi@(;nsA0#_&d~k%jdth=dhF0%Q=M2UFLps*VArx}pe9d6PA)c?6fqy#FCVO)Z z^hqWqxtNWKln1(n=5ZW#8Y*gs{b={DUW|STbu=(kLJ7g@GiFeWxrm$yT6!QU`e1B_dWU273VE#w1J=m{wD+hcwZ&E=E*!QEm>-ES@->w|j{w$AF62YQ z#pu6}u+Q2;cEV1vF<2GueQ>@Y>`7=!7*`C^YEUcnPa{S9@6#iiz`#CR+j6DQuPL!1 zT8f%2tq&bP=|xq#ltvR*(Ho<3Wspp+&eBUSZ8{x3H6O^SqCgfN-TP+qOek=Q8cXcH zFp|Y5N4`IFZ`NnFbtwAmKT+i>D8_^%DY0E>@$d5CWRQp0waWydvB&54``H3Sa^W=R z`M)Axw)cZE6!UP*2pkt~PhKLn|K6!smhnzdM8`=k3uKMEIY4K}@zLFWxGDMztdoD` zXGtt7xWizygb_cyBrnCXT=@g*hFc^x$7e$_IBZPKF*Z`2QC36{Pc53*u~O#f*68GZ zN3FWg{?D-5m1#(T*X6{%MNW94{B}kj?x$M*OVeG8;*wH zhbH#wXZ62V6mX44Y^+hFCzHbwifG<;vB8P)Sr$><(ma$ldeBZ04H2)|A;*z$F3-`m zbepmnC5vUi(Wi$a@BQ96XzG)P*Dc!9alzyI{lYY`eQd+e>k{ss>?rDYwJ>oSLy3N2 z59bf)yhnMt?QC|t<;`YMJK)lA8I+fmbiw7*6~hO^rUPst*4Mvk0S5kOWcw8Ae@}JT zQGlXr&chXt4cCan}lJHsUlY&r&*?t#Uh$%ODL@J02U3su&$wh%rTK znFU)hIxV_su$~MCZV2%;Knf2-80-Y4X)KEfCPLwjxDaX^uHf7S5AB@Fw;n5kEOw%h z<1(L)eY-N_r;aZn)THlvrfzfl-taG+dgELn++8*M9ZQtnuxt8HaFhHHgZOi;u$*>q zEq5jfvBl|6jCQ&K$F#=Z@ei`Qt1cIz@yp888LFGhs_C3W?{QCj8EHc4F;iLRjs62X zjvK;vX@1zBY_fAt=TL{1V`FEDEfbO3JPv00wY|xlngusOROwZXJNZNW0E$h#I167z zQ^wU^XTdaB8&-a^>N5!=(*l#Im76i&>-X=}I@EZDR18s^4f2UL(X@5O;KEJZ) z-ov)3)|09Ts0ukIlk*)s$(LLrSOqhH_7QE5_m6xxzf#;%hT9v4c@_FQL=Kz=ZUQRW_>yZ zMU9*bp^AV&7Raj~lTy~>8yzquOy;Vu&a`r}-@Ppk%=~VkKc_u?<2`E_l|M&GDPxW< z2R(SC#5Rvhj1KhJ)Nkw?uWVZub4Y{Jglm+@C{rVOR+bdV_cj6Z=({gjS}zm!=AggT zcMDuo`e^IWX=0^>@p_(>%rN0>|2&u7lD(OCO$ge_`PI8W$Kpb9!kChu4OjI6*U)PBEy>%2nuRJ=JUu@3# z_omZ*XHYxjT#R?n);i~^Z`ruj{`r7X#Y0yc)7-rFQHXq%CFib%?J9A{XV=y5x@g6s zO|a?S!4=O;iHu2d&7d3vxy=(6!p-(-S|V)7R48$pP)sdiL;J& zxk6I)QQ1DnFl=V)l?v0t+yY_mRba%x5u+XC7iWerVP<|5kWeSREgc8t{yY*9l6QNx z3O-j(BH@rQ!ay<1rxzhv#XLps$hk*RAw^_@P#m{HO5r;=Ay74!K|w>N71H(RwKvoa zSJ##B9rF-h>+gH{`(YN}YAzA(C;2)VkoCI}Y+H*rpG5a>CT@olE(`=Yojx_o8}HKo zCwWr+HFk70Ex9O-EQN6#e}!y)I0|-Dd4HffhMXysM#xNl-mhrNwKG7Zf1ZHuU9}&A zVTI0t#ZPDey1cbsS=QXqpl;zKF=FbQG(a_SNPG@@nYcQ7kliZddx9|*#5WC@PcA-@ z=nGH+9r|~n`4K#BV))W!#7pNPG$7)LUoMtk@Atmv7H2q zAKj<}w_CB0U)GmfZ)jn9AE5+4$_YJmq^P#ee%(xnz6AbyA^pyWsCu|aYHj($W`qvs zLhXgtc$^al-Y(2#ZtDCS>1?tw^su7k6fMokO0e`9fypiyN7QpdULEn5?yQ)(dHN)) z^v?=^yci1A0bA0*g6ktug)4c#J*82sO^&o=k}n32nu_5YNdZa#=-+J?O#ND-cXE_6 z;9MbYZX#X`V-Hb%pO(ETL6q0=d-#GuuUFQ?_mBVilZbcNd;GFPHgD7%2_1rg{7d4u zSk&*WWY*r#es6xCMEplJf)P?Yf-|{K5wP-Jwn1sx6X-!bxoOEVo--ycMzMq03mt+BFqEQmB` zc;g_2#EB2Xq6;viedE5iRin`}8(IS7+OD1EMA6mk^oot`cLw-s&RuObg^rOD1IoN+ z@KRI^pJHmyJVK3c&q%5)IQBcUPQ~JO^ZqB}SiHq{)c~nc%|=WGeyTQFm;BA@H~dtV z493SC1+C5v)eN#7e#~Jv$`kb(l`Ok+?fBBhic;f&MjwZ}TE49eXFtI*HEro6}_$bJCqAU9XVfZqM^9q@z`Q{&BK|CP&`93&X|-{9BUB{wve_ z^h)?&^{{QWdaA^k6{0?o%&*dJ)23{BY}piAYq6jS^!5p|4M%o0h9BNiXjxz1m^RlR z?rU%gSHE41lcig=<-sC6tm@IZ$meLjav298pi$`K=0otN?{W^Kmf#x%* zQF-t~8NT5JCSo1|h>Al!p9#DH*WF!68}&h@R|riN2D_G!SZ^r(V!u)|lG=>!^;la#So5QmoC&CUC& zVHjQgI^bXyoL4586el}inEU0ypJ_JgJ(Fj_r)O@G^m(0Zev=_8knR$Cu?iv-aq?Km zrlF_eF-7a?nE5q~M^%OliyMpf4Ulh@cxXD$*i7`N?yn8W) zuhb`M$p)?&G-tXzjMVda-LY=P~dAr8l+2?Iw#!ngxHG-9SH-^j!2CWK4RR5khfXb>N_E zqn3CRN?tMzSxxw4fSM*-EbAeLzp%D?7C}07T;s7CA!RsdGi06Li8B`7&Sp_C2v$7# zqp)NoMC$sn3}GNBR)%)96CBdwe=H4%Dcf$jGniBQtce|D>vq zk1{}svXkG~mvf?o>qPkGm$35S<6#DQ)!1Py5%xbxVvJ>}f(1) zKYMcqPbVs*Xwb7fIy;VR%bwD%`M$5WqM&-NXRsS$20pe8UL=88X1zVLb!M0_=A?%c z^fQ8lk_K~j4k92r{vXjT(+EfGKBIoIqyahtErwtMjn%O@d!+>O5)@V$2R_PI^Z@sI z7D=jJ6th?k%B?>H1V}%@)~lNLQc%(lgS`j3QldZ%=z~ZE;eFc%X(eC4@!53e_(;LN zCXhvHm*-i!YWuuKd z;r}Xb+GPSZM-@c;$U&>~QsrNIusx>p za`*kyh@8ERBdj=F(nDm9*O1cg&=U>QZ6?~$kU%}BA%SE;APOT>zz?8q3aKmlBRd>7 zVW)usb7COB{)l|_s|p2vvgz<#lCR^hG<-UIBArzrjC+jmOx4sY25X5AAk8 zwjPGppq=#GaqQ3aryo$-#7>-%Z#wyZPOXo4UT$xQ#`#VFZ{fh&0_hY5>g#fdvtJnw zglstW$KE|VgjBSt?T}n-Xf*=#dDVlWlRI9>!BTjoGoxz5A;eKT+erBY7teKum}1qa zF19YKn?}fj&6C#dE23%RhzRM7IUpu*RYwI;us9gN_4GF+RixMzui2+i5GGx!!&!D8R z80;;fm(g&h_1fOcdHz!%lciWA5sNhN&21cZa(>-f5pzug2GX?WMWcYPVK3jlWLzQ| zkZ1tk*~XDK&YCxW*?zj9u6z=P<*GRlI&=Rn=6(CLtao)-AN)YeAyenZ zCb5T`Hhz){72_x*XHt3KlKV@Q+s1-QVogN4b!KY4VNa<8SeAT1QIv8aAgLAUz)4Vx z8B2U37*jAn^Pl?bux*t7Gb6Eeb}UK@wA9D-^q20_EFmPLCDdYB$z~J=h_-PKAN$cn zJi?D5Kkf^0I)%1Ex{wCy7oU;H;1MZi%ZBf3SQ?`o{X};-E+Xh8BU0d>@>z;iUtPi0 z=B9d={RWtgy)tY?JXs7EX03-?MQo0DJHd?fq+a@%BPR?&(*+Q#vEIS>_iBjTVJk+! zmRrFlNrVA8A3PnG_>xtz9_IWaY~JOV=+M(0#QATg#$!;W5P=J_!D?R*dl`-|_RJJp zit{RKwKuY!uaBB`*M2!A`hPD#-&)Wm|D!_>r$kWK53vPj9_?xw)Pj>%S;O`xG;$E$ z4Y}`#|J^BTh~xg5FgK{QezI2xjWD?5rot^MX;JDrA@DjzfC&&Eg7nga1@R}7^2%F2 zTIF=JC-b1hpS%5iPi@gu=VsL=rE8WckS%GWo-ylvg-y+p`O=eJ)pX`9qwPGt(U!H8 z)N3rT2fb&UuCOrfnXKtNsi+PRVvzfY`TV}HrBnW_zl8jkda+!eiiz%DG*fo5z_95i zP8B#GvT1_M)q?1EPLNzxX>^^&G)ePynTwwT^v}37WK&X?P(g9GIju$ay?KND;A+o% zFs#4oo2OBsd6zBYC8Ix~QbLPSrbot(C#_8-KPba5j4<^+z1AJD+0J%qzUzhg4l@+(3ICM5h(cs1I6plyV0Wb439Ts$7M%hv zoB$=m9KL&HvE2pCcOZ{NKgq;DtrK&^v2$J1y{k5~pY+lUmrPl_fOR*{clJfqFn zaKeHgV0Z%)FC~L;T^FdG;OTm569%RY_E7L+RX6X$pMZtL)&GsKJ!& zpt`w=UPa!V9tKXIhziFpM}x)+)_5#gwX4>t$G+vyiR4OjncNKhvAUy?s4Q?1;c@IP zQh8Mpj2D7qx+JubbA|s^+j0h@Y{#crgDI~{9|$|-tFQ5@D7vk8uUz&{&(@_W4${YF zvoISH0s#$e`uiPEb*s8S&LQg_nfJ`LUY1f-Rdbr(0KVrk%a4XEXNTJ~x^5#knlQLk zwLVE9nFJKoVskl}d>flx|BV`3ax&aw$t+)8CU{^|4E|c#Iy$*Yze5umr{Qm6vcVxv7PId{cShrv79ml`9*Zv1hH4EQ#iVhWv{Nif6 zc4PQsmw9}CIw42-Zc|r8AYoPslA}mB2KmJkkomgn;8B_N16jlXn)CLbS*v(t4W*K$ z-NJ{Ti(iElO?|*Rk$46M`=!h>il@q@}}7>P%|#wOUA5wqW^B+;J&Ga2zS4+wQb;2%Ydh@wW>log-@JsQK^lXLjL2>91Df+ zsS`fnJpEIVos$T^;RXnY2>sXbs_u{SC(_A_D`)bYscOH=(4>j#%C9=GW=Ct9-hHVz zjpbN*VG?c5;KIV9+()Ih-~Nh<$BlE71$6GaH4USh6swbUoH-P8T5M&(-bL4^R;Edu zSURwy>U-2F;MBy+Ij;eQ5^TwvSDJ>Vq$Y-YkQS}363;A|@MCX8M;M5ie98XW%o!%s z+_44RMGl_^eCPMZWrVf}jUB=9T_@=^A%bfkN&F$6>cV1o&o3VTHYszi`GO(O^DawP zNx>toz&tJXUn_p+-F}|xxKUA34jt>@^*HRV314~Z{@>n#)v;udwpcG%4aJa zV)B4~7>HlC=+rdWFOWF@{c<^T+X*I{j?aEX1KIqd!l8+|MfK<8ZP?Nn74qi$)o$AG zGq`)Ff#Nh(A_;&`T!~}7jTr{*M6F_H=I>GSF{6c)efx7LG~+k2u-H%}l9+A5iq(}@ z!^)gXai46>UX&FQ0xvgbw+|jw6v6SflyUU?tP zP)~oSu_Z5s)a@WJa29^j)8^sLtTn1^*ulD$#WRaHEoX1q&#Vm=&97S`}i-r4nGjRQz zv3=}6eR_Te3i--lANp?fzF>1J^p8ae4@r8ovi)$!L)On-q^fnBHyFsMK>IWTUjj__ ze8PSScbxr1{`)U}LV}efhWisau~h+6(QbYI{g|hp%a_{@jiue7Cz6TrP$o`_1WD*KNh|gNY(rL=&TM5+maV zGa?beL)z^#%(%VtoO?k6Qks=5*f~)+Wij-+zlwx)j(@kNLQ=+>=}v<+_9Z-IW! z5o@&&yAm0V*|b}>X+E^`E5c>F@1Lr**w6PKkQi zt(8ULdY~y^J8Cn@t^do4X{JYFPIV%jmIo&^BS;7qR&jHyxl$Czyl=Zg%{swXw>dO3 z`Wr5uS&YlpjG6JthLa=cT{56OdT*1iwN4Qj0YP)o@{H)}SV|JH3Gbp3Sr3?8r+kvy zSMnp|LPNw_q6yyos%DX0(0{>)?qelHIVVt$>IIbb{Ph;vyAkwb6sNl+n zV@dP-_35o?z@5Eg%=D`?L?6!ym@#-ub#n#WLT@E7hHT=Rc1&u!Y{PhAa-Mta2~THectp+Cp<>nW{~V@|A_Na6Lp z853EiinsNA>ZBy=Hv!{&pO*VW*cG)chT|nS$bCJnECiVG*E8|sjZ~hm{jaQ6K{0AP z!pNOaI}C&2ufBhx!0blvtp>I1hkJ=cqMMN}+25q3SiT$5KDD|LIy6I&OzWK$a>x+B zG2t)%ox)^b7b zl!E?iRaFOUpaW@HH+!hmN>c!HnEmwW7-K9}@#{#T8_ zQ*X)w6(DbrUP*GYYeM?#AFW9Z($Eo94DISeAojVVW-|%~%(#`KKLOg7cCMOL9oVUn zO0t2W8;W$G! zpFwHV8GJGZs&G>=_0^99f#^%Jd?Ef+fx)VFg2s@iocUe&H@8@`bCF2W zElZjuRUzDSvd29Foz-(vIpO`EikPvVxLHaApJe`ZI=+1&2XUMMwmh;)v97Qu`0(r3 zkEy+Wf9u;X*h8vQXdYu(j!ru$*gQ&+aKm~24F#`pVZI|IF}2|@RhNLQTa#-kC5VsSH$)Z92l5jC*86fc`YZVSHm0n->&n)le{< zp>A3w;ZWUW&OmLmIX+fL`5JG>8jIHoNXqmwq)O9UMY(Oj^qGp%UJe;2IV(mF*pRy> zZWJr5_kI%3O^;#b1V6Y68<);L_Fa0`oJ2HziHMCVBc0c#BsOIEsL%-Tnzi$z1TiOO z;n$25l78s=OispQ8%WzlL~MH~X&TnRvlvh&901mXl=Le~h~Zy9VMhU_Re^*tSB7*i zi7U}GdLdMOX0D~7=b#`QRtYDZu9cqU!~&1S%N3j&JS()pcjB%`CdvoV@Ec)2gihKH zq+)Iql)ee3CT}uB1A?jFcmNswxabVUYCNB({()Y~@w#`;Y%N;Mzbmq*2Z-wZc+;`$ zKmWZoMFNfL6!xBCC>xJVEK0@7DYKdi}|xqzhVP6G4ybNxnA*snsm zZ8(sN!|`2QR^9dn$w13Wu!XKs2FZo@xI2T%EpNEV;N-&0ndCa-^g40 zUU9{wU89ng+tK>t&Op1E59K_2>^tkmh7aNF&QD23+u&w;!xn$Xv%vQ`kF!>Yy%G5B z^l$Fhs{3^lyMOF-i)Jw1Npc96i9bIlr;fxgdv$(dkhD)yxl6ji9X0MJYC(!!nYej5 zeXV9U3{g_SqqI`~42WSZno~5WsCj^+%sRvJ zZ$awm-Mgh@$}wC8veE7c&NUIR@AmUS(#(gEawVW+oSyyB(p-PUOOUy&rZomIMoNjt zRz9R+Zt_AOWMJbNu?6vfxD0)tape256_mOXN6?Y5#|@O~cfCQMT^;fL`npX_Jk`Ca zhX?#zbvJhh+pOSBq!9WX>d zx-A6DHlru$Ocabxr+zou2=!?Ns4DGdeR; zT9DxU@BNoU;;$7(IMB|z!|%3=RNsAJ;xh?rv&7cu9A*fg-wI98Au*@3vjvgGzhT{j zbGUrt+v}4Uqebv<1Ba+_dB7eA^r;gYo6zt@hS3I>v9G@1@apCNXu8ILI{&wS!ZH_^ zYuWCXv9PdgTPH2MRxR7EW!uKmNlPbd*~_ly{=azMo;P)Hf4|rDp|J|?u;#ss_sT}~ z&6?0C3cPvXY1(DB9+7f5?+w zF%vniewO~yNecL?LsYQpU4LJf=d(r%#u6mDPjel5o}lBomnk<8GO>I!$hHYWl1et2 zsN11B`Q%VfEfL?1&PSyZ29xfpu2sI)o5g688Fl^u?9_n45B~EQ&-GY(zGy)DJKOu! zZc^~o>*`n-rgQORQm|Y$G~*BDj}+c@j4@QU-%?Z!9C0hLA3J6|h)}1hMFqYow(knq zHEt_%@RyYZr`3j5@Mbx3Ylpld?6o5V68A!@OFl*)RXxY#?hM_$tg>X!yW!Z z)@DJw9uL5nubbo$-B$edx=Ddb5f`Tv$a&`C=1msrxl<{SH0IzkR>{e;!qT07wxP({ z4P~|bd$@xZtujkrb3iAQm+dE5{lfz|uFh&@03GBv=K($-&TDJmvE`~fpKRlq{X^iH z(V@1ZZto?7>Ji^zjAPS9fa6AC+zH7bq(uKD&tWu(y&$>`JqXL0Xf!5#_vxRZ{~KxnFG5C{4C#@Ahu4xjL{k5G z==`Q`7Lt96Tez+|&uGU{IPFUq!>c=ZUQL}B@rX=*mSPpL0pew)4Yx6y;m{@ES|;)o z4;COJJHs=H()bA*Scu4P0_0$_=>J;}#Ek%+6LfMsq%W0H0ZyYXBK(v z%#2c`+2162@u4Qd$N$Afy#l81ie(iG3;5sS;uHI&YmRkoCsjTC)UgrJ^8-3?-1}DL z(MVMl-Q}(G{j|V(+P${&uYZ0J<($gLx)L<4cGUr80su722V%ZE!o*z^;h!2Fti)3;w#f_9|vY>-Nr8k(UX1!Xq@`3IyVIVluNcD2&-_ z?3mN_iDb8B^C^HDDj=@@;t0h04~7!nvl>gnB<+!dR0IMTW_MT6>xJ{Ktq5Nm>#(&u zNQhigKUukGorO<9&LbrmZPvo+P4)-9os~a)D@mcn{e}VI8WkHv3}DACRt0i{Dj1Uv zyzM3GQ)&65^5DjrIgII|fFQBHYR-%p_}ZI?d|3Dc=t>?=>~eOzt3JRG&Okuv&aBhA znsA^|6ymCpxB=PpU^qfA4s<~~fA!W> z{rz}n)~@i>a)q$28J7xmW_`4R8l0wOyU#boO|I;^cc-oRZp&NF+9jM>k&H<|0xded zwaW_yB1n+-H+(yGN^#G>V(IVnPgy-2f!GaGDIq5EL2w|xf`iwkPpd@YjjFG*q$Fvc z{W{Ly;Y>b)KohYQcMV#!17F2J|A7i&%tC~Mk(~z`WePjDb4R-VqZE+&Ih9lW!ioS= zNzYdbciE49;!^l#Q#G3}@9#_%g2iZ`NrbB36a1H2>X?RU-9rt2b zX#u^P;o*$BlS%Xs#iSb6b|%#G%daGPSA`iQibFz4V-D?HP;#`%xHw9j5=e0cbZ0x@ zjP#`xBo?7J8Qoe(AW3$4_n`8O8Vk3f_E&hw6$K<9^V)3OLWk97H@avPZ55V6%1sp# z&8adXj`V}$QDMG4n{46QWKv&sipJ%;L4_&ndf-%;o5!Swes-+Xyrug=71x5cQw)Ma zd>Id$n*e@bzZ^O{g2d&(Pl_xjz5;1DON={-4j-m+P8&GM^@cC4ZvdG>M-fBhB1 zYbcr9B}#{po1-os2Gh5%MKs3Xh@p=kzi`4aTsEbVA{PSFH=%eu)nK#-I4VAwc~?8BH>QF`ZU$S%Lg|?r~i%@4RR;Hq(QkHU@L^ zeO!0C@9bB+(rjEx4J+%rw2)WMnpaMlXZvNd;Zq(50h^PXgeZ1Qjf z6!aM6=F90}ECMe@4;$~kxNbUD%X2IL!Lf}uTJ-xM?< zQyEaWV}k$pMvgX}Tq^jJV3twKt%ep6Pl6q2H}g1NIH|{7VYIWNyY&)A%B-3yE)MF1 z`3`G}yo*A%^Y8`gGqUpXIV4ey6$}`q&hP;vUi;Pqhy6{?V;z38yO6#`L+iGcnc<%5 zcl)GhmY)XlX5VVPim~eVIT1iX_|=>d*cF@><@@e0&Q5GQ#m-+cV?NMo%TA&$=-rPz z-}2u$x#J48MsOIvev4|)N7F<4GT-5832)q}9xC|ZS2#N^_tE-A^iEAMC{nWPxmL*# zNExGZoX$jz#TBrgEkyMCW1a{=hw^$R?-F%R95-ewI+s=cb-mj_c_w=|dVsU?N?YDd zvJaDoJ}*U1>v}x15oWu8gNGoC+VUa)vxjQ0EP1b>=+46g4T#y{Lx|~WJ`fj|rKU*o zveCuhUhU=Ff(*Nj|Eui&%dfBtwBnQK@ zx;xzAUBaqKOXT6wkF93ah#!M3^3MsJ*z@ft&^(o&^Go&i>7bRHYH_2QZzwm@cO2tXm*|B*v;Kupz= z<#^g>_Bv07)0#)#v(d}Cs^(($38mvba6R$I6XyoCjN+`xi!PpV!WOy>OG#3K%KAS) z?-*b2lANhx@Q5T0LXnBiQsybyUgT<6{?GkeTIBq6rHCoH@cR~IQQVqFS>0HWTci#((@O4 zmX{w?Ka)n}i&rY}KE=j}X-$39`hP7zeJ;b%SM5%6!-{bud%a=kWAj@BB1q#`p2!5~ z)5wtKA3hOQGC!eZANJ{k<4a7`p=l(fgM@ImniaU(nRj&(lgroLkhuFc^0{qA6TX6O zJ=uA;S&m-di?pt7y1dJ?smLv~cqQq6BG$4}hW{t^DZ~ig?Qwfr`s>3_ZjNFF-kpDH z+kEhWTQ`0`uqeDke@@=DuS2I|@h5P(Xu#cVc(^*Q<;&7mbpJ&cEK2fJcKVTwv;^>9QZS9B31i>(dFLD=aabH1FRzeY7Ve{Wy`*KAi8{`89aDga&ssikv#+4hz%S zHF73I5)=OkW&bC!zI4N9MPg>n+Lr%=om;R5J1|io549SN&_I~AF8Cy+uWKoqEwq_q zuCStUpTLE(7+DXkXG zgK3%6ejrzH$_hs#GvXYzNjjSe)&rP|=2oaAldxcoSNT*-2n>ZS7bx5(_CpJnbYr2d zm!Lo+c@I&s8JP!3w2BB`V_`>n1kegEKZN?)rBlR_-#k|O*K3nXrLqulXeQX!T{}v3 zI`+h>5^bT_8FoeQ-m5%4>O>#f-Z0GHsL z`p49QHXTU%OgSqC&It>oT=~zWapAh)@)LBGZh9oX_<{ z$EKk{ACH7IkZV)xt!h19Ck-DNac*a8}*<)8% zFDFVz`ar@p&Qjz1)bw{+!Ngv<&9#*G10JZTij4HlMCY5S^HIh>Yy7R+8lU&7FTIcL z1fus5?@Wf>=og>xQ0uK!MY34@-)!=<7WezSH0?#J+vwUKt>d22B*>Y}Vn?VZ7uIFG zJ{J_0E2ChH_-2lI(Uz9Kl>JfSpNCWpuXsyPfU3XoUt`2>OpjB7zG|>N8Ql)Q_u=VP z=)Ma@8}iR^3YW&gh&?BMVd(!@+9@EIDEDdA>>1=|&MR>hXB0t{QTLynND@eTzN38? zzr5*(k1jD?pYA7}%KV{Y3C=iWME<83^LOWYljZbPOP?M2m>s1n0KN>W8(ItJCCJY2 zPY<&i;hCnvf3Z7bv;nmG88Y~-10C`1*~QH;7SWv2#D(AH-N@doBiR9Bdu3f*-tS&; z=g4I5rzF(74o|b43iopeSr?B5>zEbi@qd6Go87!grweO|a3}?wfP=+HvCh-m{nrYo z-j#tFCxU&KtKLUYr-z8=Nm1Z$h{<@t$}{^f3|fpDPK!^ygoWo71oul1HsvYepuwC0 zR9T;8xM--6-Pf86e-G!g$*Idh5}Xi@*;#s<9>8Q}sL&6h9i`v#{O$N>qa(mmRBcU? zl$LQwe_rqU;`Onu_mj2#6If)RPe^Em3CPJv)zhws~Zn`4Qi(S+5c3fL}h-=aGzfOsH zH%;{CoX*32qQAkn6=5O1FjiRIcIV%~`0K`2;6_=@E)B=#>M=B40*l4$DAP4BMOAun zJ@pN$hq@N-uH{!vanA2UPLpaIhQw@uBGu!3pI7UBsWW41_~@kFC8$E~#{tLG0BkUEA;gqvAn@Gak|J|=B*1!?qO=lva^0(?; zdEnpG1i@SflHSKQVd^}OE_Zx7aJLgj+aob*K8#r%FZ{%3#lSc+{DYiEym(H6FcuUf zn$Nl4B>%T*n*|-K+IP(_^`;eLhERi4Gv4G&k zG|bj)njVzM<@HW=@x16S_1?UOO2;Ifo z$l<(cz!-zD$mNL_G zPjUGI8s7osGjCvuvJ>0@)9c+uE_NG{s19L4a{Ja2mqoem3Hp?a8x%m8oL2@8OBZ^EfVLwAhqGB^W;#L007neu^?J7Ylop^rTPjQB26Es^?U8W2%je@OlB6c4_|I zf@|fvaJ9YL7aNK-ucimvn2B6IQ5Ms2<%{_{-Kx&^o!5X*#*KAEX}oNZHK19Fw5f}9 zkE{MobtgN@8ybK)`tNc%NqJBABW0WSlkwY5fX~%d_v4mryi%@>2`D>|*#KjjCh`u~ z9NpUUSI-kUD-XdM`CISE4qZcL)>K97wZpMg(Tq!^dZ>LS#^Y|jg3K&(c=Nc%Y|-bL z&3|zsW7Fj*qB6B_mOp-3=}zTI`u1Q==ytv|Vt@3nzlMP=R^Tl6hY0%KVM?&$7o|ri zy>6vgvvxeUHs;GfGPn^0h#f?*r5Nd+HGGCPyHozjF_BmpZzVE&Yaz~9%HKJ>9U zME>jWh*3qVov8j{dGt!>@D(%@b!sZRMyiCJQVXl0YcuZ`_6x@cO)U*TS^a&Wjt4qv z#hDk8pY+onpWC!lm=lkam*?1vQ^q5S}F)C#j*BecNhsYvLJ+6n_>b;5BLnrOvjmhlxeA6y(3 z7v*Bc(YJa#|4+z_?lRHKe-Q zP!dTT$V(+o%7qSt2+Q6A?lzc~8cu~UpS9K=cU>ILi3OCDln_F{Qp3a-(5EWQq2NoY zB#)<7+Ev;KFR?;uoKx~NSat4#CmSp}nd|NFWYeh>RH(&%e1)4ZwhW9A&UxNXnw#>W z5v^MFAnHpG(ZJ7Z%X8RVy8=~E98m2}ty5PA#Ka+?mH}yfV$N5t&X;YFZ488qRk?t0( zJ@eYJ6^vR^RF(QL0@wPERsS_6!Gaoo0nrXpdIU-VFe9PE*R7E za1E3S9O=VIq}leu(x*qK}p_;c!~DoN~gW->ydKAu92`yUC$J#51ja}l)sSF z&@YP64GR)}n(*q%x0J>1d7}<3R!0W8KC?PQ{ur3tOt8AM`v@|HTG6NM$P7j0Zgk#0?|`^@B- zu)sF-q&3B$MJrWHV6*TTDJ609@P*Vv1KX80o(nlZqpCki{qI*BH)?8WjH5~NlIy$f zk4do2%gNDK-RP`2=%tDW@vo23Oh$3W;E0rduIsUeTFhHc422Z*2ji-_x-#Y7k9+mH zN~q$aV6|aekZe9Zx%%rqU|V3s3cR$7ZhnBjo@=Q8dvj3?HF#dJ($%Pm`Egrm!db)Y zaxiQqD8-DPuG4#Z{xq)AOqe`3M`g`ELRU!uN5j2`gcZ4>pziIRIFb~pEQUnZ#SteE zyAb&~r07qSxYvy#8d7>NpxBwC(i`2;8-vgU?AQ{A^H8Jp-XeZJiHcxPlmImRa+y-SyJWlwcZSxx^1qTZ^6>p*G&0By^(al`fa1IUu)CvLFxA-Tes`pMVrH!-%HfG(WB9Bj265=o8Qf9+=d^H z->s;a(IcBwd35Od!HG=k->DD4fENV~WkOlkcUg~ryMBL3_+xo%y9G~8mXc#1_q=re z8!OZfpbdanF0zu{6#T}=M> zdDOf;KJ?SEixW6NMIMILH7)l{;}rnPA+_^xk#MI?Aw>$y4pBiK9dyP*U{X|6&*)l> z?!AUqkBeC=-7nUIbuDf)bfLb#tBf!Q!7UFOY=%nl6VIAhTw*6zmD23wsQ z*A4@p>U9LJS4>9O;x?! zZR+Y)EnDwMQRk|+UFNp_}2Sy;WRO2d~p^y%fZv+o%08|1_H&*6tjDeiFMIv!PG zi=(QQ*2_8v8y)8PQ>Y)=N|gs&l*>NURA&?&=M~bW_pj{z!H**RtXETQh(S*Wos-jA zsja_%w}u7jDJ^CPKA`W1?&gS+_)yy0w^3=WeZG`jl6jd>@?iNlLg;_Nlti3&h8yAf z#dckoyr*8fmqg#Q#1gFydrw4Tw(9hQM-R`nURCE#9JxiB$VT6|JDHI7>%7SeP!&U0 zZSqGJCclRZ)MK7To_cl0sfN$mehsN=-o9f+047iHVD)|5%&;&jHK(E&aN<8L)G6S( zeO)RX49kcS&do`6hxt~5hgnCj&RLx(yC=VrX_H9t#l*{eRU{&{CwGr}Mdpa6dR>Q$}L{MEYGn%c= z`H_M$B3mec8C_~S<)M)kgE z>0*rAv33Z)?b6q}wdH7I!4A~z;6w-VdvcT&;OA-oEDuhZm$ThBVfkjY+Nfd?WfB3} z55794%ZgPxi`F`E9w`NF!Mk!W5(GP66lWS0Hj|N)@A@askSJ})W=XQI?$ia2`FG2+?j27+=_|d_1bAL=ipd8 zX+jZFH%8Wz$)lCC-+{yZP@D!HE22VM(8}JcOHA1(YX*Y_@UCS7LJeQRGIf&00ic~X zYxa}NdaolT;=zH3FhcD^=1f!=Ym2wv6hoLC%(A};pVz)4;mE;=xlCfqnM7iJfCh1@ zW$_ib>W;~EV(YXMQiwt828XY*DTlyQl}7&ok`62IVA%50!q$vO+8y2&Sp?mJsdj4l zU)Cwhzc&ty&I{UZl@gPRS9@)^KlfR4@8!=;_7m+`Ul3eiIe`}OLcl6kO}u@6jUKJ+ zvR;hw3#}8lv&e)Y^drfidleghN+PvWav($_?3*emdyH7IPNf0zOl$iB{7Sd%BNY|P zisu)>v6uPvuQqiTP%EjONwV)4l8Yv#Ix9S9xE!yvKEgM*nvOw8GgaLi?L}T zf1yJ$YPU=^KIjAwP|Tg;>jLfT-)dYbs#7IQ1mU9qKM-kP_&A zd3S)2bR81JXtdTJvxhMQgXD-z;NR~H`Yw7W=MNN^t82B5cC5!tv75$H%&$ZSogbGl znN`PxIlYs=r_Fa}b5^AwXW8A*JKkh7&P{xVf**wBSBL_2m5pC*(?@2JzgmqjsY!jp zZ|5BzRUO#@3SH~Q#?@2GBRjH{*EVi~XsuXvmQgDdbg=jOJLP+)8njK(3?-9fQxqyW z)sED)f0%RPG|a1{nM9@rqnPaS9XgwHkx-Y622!FOji|=mrCRaRt{aepB!4AkH2n$H zDqN#6iIV+QSTjhHt-$nm>#ihAp`sZ;SWmn3U0{RQ8}4|Lw|xuBfBd8OU`Rv(^=&V0 zx0SgDs7Hj^fGl;a$7LENSWM>6<(m;Vb(G03SHegtH#A0C=(>6LMczd0Mguo#6-iyl z1!4N(@#J%|D_jh=dsncV2r(0Q^d4Z;Pd*0#}Pzf&yLsX9lQsGCto)g z57igqav!c~e2#@rH|T!LM*fIj#z_N%`c|7w%SuWMgwvcFG^twu|T>M2B6^Stc_lT*KhJL9WG_DI1mKQA;qp8tB* zR7$LivRcuQDKRyjX-UZ2>?0^LQNviuGjQ%KrY}-7qq}eKQDn){y`z~Y9JKrwRTbM% zW_dSoeTmsp?mCRodvo;lrE>#?F)i|;tnok_B>_e(_tV-`1eJP2T|aG-9BwA%U|t13 zWT|2)O50~pLxQOoc|`Zq2;GjB=>72K`!3=;qR`85;oJ=Iy;AQ(|2Bc;Ww%`eckRn+ zKVt9i%@>O|C|mb+uOXAwqD4=p=mYA|KdEXoTIC|noQS$H{NRr`k(2MvLm$-MsUQJj5eT#fz8bwXK$Hg|QqrB(^V0o?9?sNHiu4ELja0k01kc{X~@qo+;!v5b)K z8i!OG0B#bjioCAxvGX0z%~JqpaAax?Nj$}-(t#M^w%Cx39nTr97$ggKtd0bnK+b4YM?T6)us(cJHGXW*D4a1wKo0N>B3sS zmiABXzc;b^k05M*Cf^?ep2S|hfL#AgC3X-}{?;dngXE7jajx6fzKg3e(Bo0SHO@(( z06Q>}3J~J`>BGt5;BaOz2V{ilu|Xk}5>~y%kqtqpBi_%p8o z{6bSdF1xsKUsRdF2Yc@tH=_YG^34XFu##4SA{P~-@9g5dWP8ztSq#JVMy0`FUP2W> zJ^YD+Tw&2=*6Btiu*3EK$I=IwE+#b)(L(Gu)-UNtkO~*ZdvM}?8SsOHIzu=~lq!hx zPK2J$2QnF!U=;YL@Mr(7IqiGiQp!J)^l>UJ1vup;XEYqxaJzc=N-Bc~zrZi6hI%b| zFLS09sU;{do|{DXBbQAEl{=#&aik@;t4cVE>d|4CvRbkxNVK+grO1m5;8dms-S+?< zL|vbwU5a}N@1vbt+ZDqdHjnu@{-a5~-kJSaVxE%**g`bg-%yg^&QE(~Uz4>86~AJK zLQ6VHQjxL{9hn{cdtBac`7y(_3QeMT7PF~TE?&p${S?NUVBwGSZ`@y{dh6~KLZ~GE zZ26-Q;twYBx3%xH%B0Yg@Wb2^0n=d+M+jx_R0*AwKrOU3wD#Ry)UHt|RkHhZP{0`i zO;wI+w7`?OaOH&tF&#a{jID6Be!sy0+3BNB7fp(kqu9ftK-9f>Lb1Fbx*u0k;stik z*y2F>ttXgdMRPks$NviNcjVdlu793xejCIe#~&Do^$)(iD6uGc@|e@<6>87XhBKgv z;n?D%w*Z8X@|siJ}_?B(l$_0Wr1qqtqk@U>bENP(PN^(i;Gm<8SpR?~C&XahJ5vvJM` znW7IDOL{bza{(!sBk;>OIyL^ASfIBLj0Xou8miw*A4}1UF)z^&)tme+to##&#{0;8?oUpfTM~Rhx~nu2LfIt}*8T+-)y2Kf5AAo14N zDui}z|NlZd1pRxG&kO_v8SH($fN28g(Uc@bMBA0mVEJvTZTkz@9etI1uJS>Q8zwzj zd7C$LnC+ds_oETOi7Rr`=MCE-APUj<=MKG9(K4fUQb3l@VOm4CapYqMJ`RSV-@%Wv zCSb+FZ`}tEZgT$>U`(Z6b!A)Ix3#oeTRq#cLKK#NXYFUIS=!#J8lxU1t&W*$N9wm@ z=j7o_6+}u3d-`qjSZ7q)v1Z2)7eaIcqh@d1eIY6W1ehDzzvuq~%J7g-Tk((M=udD%XWk$!9;q;k46Ls$9KE50L($E#hPCTMsz zt3--`-g7EQ@7Xz#>~@@za%bBVZZW^FQIiNH|Ee-$fr2pEfks+qvbz)44YnALGxSAokQr>nynCv(5qeDzw?4hescH~|fHxbfnvGfo^P7eU>xXF+#yARiDy;)vTqUx>=TERsdb_gP zJk}hbG86#8!sitz<%8&(!G;84OH*fJNzxbKauDQU7Bw0vvkSAv{NNORo`Vja3`|-( zi8eoD>l}HiauDb($G$Es%c|h%f+ z!NmdEA^4PthGbywY?#Hb;6g|R{#8|KHSD;`7_do7A7T@P62WHV}3n%wNc5%9_mAF_uc29+R#vz>w-Y4pa9>|5omTz zgVN#tXx=oz=((O`0R5h`8t&m!b6xl`@(2p=D^`N;zs_hSUxbQ|$8o*&IXmc3-yItkf=n?=2O$(r_g$<9 zrM`*yzLfXAYC5qr$CKav96xdG8K+Zvygf55e<7=Jt`3QS>NLrDh>+31*~D{%-+2j?UL~J9-%Z0| zUJ$+@nM4yYvEC!Q#TVZyDmeqKwm}2xwk9sYN#&2i-D(UC;lzJfW*P^2SFTC5z`X%OOR5Le~mTqQ>aNc)n zCKe`^pN43RG?Rxap&WseK7ZRL@CJ+x3b3R#O3aJPgG*)F*Y7%E7FOo9*5_8o9wUr9KBXc2nDGSe z-7gO4j9vv{HGiT#+yHZpx2g_Q86ZO>siKj@bu-E)H(w?xVGqxq{9{amlG$%_ef~Lg zHJmV&6N4QRzV2@=e;4P!0yp&>>-(0goLq7yqzBTNOe&$889Qe`^YD@@3`PGWko95)^Kgi_5_GWfB%l=q!*Ztk)L-X~oF3;6_R^h+XzN=o_9tAwE zN45TRxp8EYTR;?^db^Y$AVk8N5A-7HFHm zmB=qbK$Ffo|1h2S84GsRg=-~{|Kw$vVYZBm2MeT3@ap7c_&c$#kul)ps7xV+bWBm~ z<>?dm=btU;tH4Za`Re?fp_@RjLJzWb^!B1!tc7Rt@fX0EptnugAiQ z^ff5WkLtL*o@PVBUJrNr8=7=15>wo+=6)!k=UNqfjr6~lCK#aqJ*9`Q>Ce=5*ZUoF z`W_?Ck3cZLQc=~-Q?pod2Xsf*mIjR$NPoGRNW+B_vl_3i6&O>{)=%^)Y8j~ZZEoK$ z;hI^!Z07te&Kn!(1ds3ubiDPpPHi+gR0a>f_BmE2v0S_RV{*A}Hwi>l^tSzu{Izg! z17Xz{@{0tM+`=%X1-j1my7DHIihB?$a~DN5vo;9OrQDi1KDATGL%N@iDLOU4jvZNx zRPbfp2TRr!x0RHjiRTX#${!1OTL+WBpDtRvOx{v;5T-&77ox;77}!jKv!sc)@O2Hn zTy3zE4N5!mc&MU@(FexS!wvm*H?P$6ieO*G53Dk<5I`syQea2l)97U|}|C5X%IwyeG$0SR5hXyJw1}^iy+qCb0ODY>w-N$}rUFUT@GQO;Z$6`7soLrjJq}Vum>cYB=1uqhuXu&EdTdfWe z+OJ2W^?AHM{@cpg+rPEmQ^jgp>K7c(mnH9MFS{o>PdYoWP4#akOp(so`)c^Ef3r_8 zQtELPlQmUcs|2$(5@0cTY2%ZYyYUUQbyXUaQt5jpH|p2$YL`5jf`bjRuHtX)Xyg; zaio&K<~m;xfWZFBK%t$w%uT*8ni%-+vficpt#rK4n6~@ z1Y14%wmR;!nLDoP!xPG(9NG-a2DI6-OD_Y#P7R$2(9p`1BRd};-OkNwL~7}8;p+qu zbSVaUi5PK4zgy3Z5dC96GihYDX5S=g54D^ThdYBH@vVElmWzo}3o;70XnJ1lShAuX z^KpM_rcB}J{GLUYO@QoobpFR;_eB@kY#TK487OFLqQBXtXXBFM=l5nSA-TOM*3Dce zAg)+DI!)H#hhy)8rls`54<#`gA@P~6efDB5#JHCb5N2#BcJ&RSg09~c{b3^TqiL$P zch9Q@YKCai%KwUdim9MVjnNpf=JHLa4D{;NMw1iEFD_S2VKZOaE@OP^>B*2yN>q)agG8`n-1aSw}C4~`&uabm}496Y>gt9y&k+c5*&rMJE- ztLGZswSRd?LJ9}MmG&O0jRm@@b+H23_+FVVnmhv?^9+IsZp%YbsT6#)S z(8OM(!Z*e&+NDVHq zkBCNwMVc_SR0Dh5RTHnC8p9Gp7HH2tVX{FJ!Dag%~zO zl@LO~5c3LN(9bSnT)I0o_Idez1l$SS>6`iKzDsuihY+PQMoRT_82+)jk*}_Pp9nND z6)IjmK3-ho|CP54&u$GVSA8M}Jxf&6#44DS1!!nhO`kINSoHhYf#MAh(yV>dB`l5g z48-CRWhSO3$-}e(1uiQUY)@Y$8DU(!TCFGbuIjxFQTV8^kfanEJm`(@bl8Y+x7kwX zu{V@PMg4~f+j?;2tr;5vA!Yk>s9p#ukD_~RTuQmO1)n01S8yGH&4L3&aVE2)NUTa} zP_Z$U9Y<1CzQ5=zdZFL zXSp>E7+lFvRSrE>DT6{W8~eMP0N#jWUp|8s-sRueSu%Sv+n%Yqt-ax6DP7~-K#aA^ z;3U5D2HQzxEIkkkC3m>rQCjqi)iAcQY_jUW2!EVWODv zX*93&i7P7>LJ0P+ubR4mMfNM1yqmPYS*(&3-3JQ#kNm<6)g#r+%`|^`0l5%1yK(Ze ze+_R}H%-r@BhAne)8^AfW+eX{7D3I|UOnfd%@A&>ar0VAJ!l@=l zs8X?Pqhhh*AP;EK1cY*vwM15}9lS4#bbIk>=PH`dpjvJ8%{a=7rBqt}Il!rz6E&27 zx;YLsMI}MJZ8|BFQZjOqkqUL=^n$+kB!_Ho7m`p?%f%oObt%Fa6K!_--As%8_foCn z9Du)>HN$r~rIp6iD+4X1FRLmgf)~DFLO6@e57i+HmO4C!?cP-(t4s8A8P@vI8BtQ@r-`EJ0jr;0{ww%0aCwv? znJlNNi=qa;mf6%JLchhc5~1IbO&I}HUF&z5CpE=zA*65V@UdqSvnx)+&+RkAHBK5e zSK2EX2FP?ErU&TuzVc!r=mp z+uh+U&}q)ADy*?38nn;s$`||c*%2g}fO;la`-$Z{pMM&S}=uH`+2!sP+0Lz7gv#O<0s3&LbZJ0aG zB4PBVPeYE_J{cR#Mt-F8?YOAt*!Q${yZiRQmQ++P+?5t%b8@jJ#3YJl4w4y)fX*w( zDzLhd^?o1dytaB9rOu<7Q+RKx@b9uZoxSdS9T-2>{eHbQzrT)B&FB(C>TX5qc*~wI zn6X2L>R{Oka%&c}NUFtgZJpSfS#8#aWG+U4*S=v~d+HiIN~%Sw3`w7e^2Eu+9cjhP zEy%;v1kmvrEvlMDLu*2Ab8+1MBTOgTBlq=#7-UZl9p@?`iL~c{@>9C|R{oEsuV8Ac zYugR9xEC$%?nNHlp#_S&yGsdBT#6T`5Tv+kaCa&0Uc9(F!R74t%zS?!nMw9u>%K1y zHw_{#kJZ}S+iy$k%WFA05!UuO#*ziTfWVKB*r6$)J=^$2<5QfBa4Ddw_VC>^KQalS z{Fptg>@DP<2I&7D)KrmJa-9QQBbjPz@XHBbdV-S#3o@8M|9H*R5%Tz)otiK2<(5Yq zJZz!+(O6f|;(Y4l2=O=nxXrikPVU1-0Bzj7f~c zj;54NTYnDC>Z78xNOfH;!4xaXF_oZJTzyxmvxI@)u9tj{c-fesZp zv2Y{PkDYu*k2e%zfRstsIAEf=Y|bN{_rau(5co@pU6_U?f0n?VFkC=R>s!&#o%3U$e7p8L+?sct&OMF)r7fC$(;U(>0G)mD7R&=Y{#%uN(=i_1Mh7xweT= zYdaR7S5GnJqP<#_aO9`>F~K<@rwml|t)Pd`^O(q4Mb{it@qyPvfu=nE)AC%Q#{?%!AwtF>nxd<=N=+G*P69U>c;C`bROwNk{$+&ogZaSO*znwwwK2sTUF zj+K=o(I)4TxRW+d(|J`7UYZhfzCcfcOt1P%T?4*9zr`7gbPj5k`fI@Dvi&jKdfZVy z7v^HL1-+m+oq92MV)aP|2veb%h6o?6zCCVj4HB`&*5gd{$mtJ#8w4`j6fwUqrW;M zlOR@kt43v}o-e~YWzlD1v#o{^!s?DQ+Q5?QeyfAdLL#C>c5+{!I5%+(qfSW8abRyJ zhN8N^2?4vLlt5+GMb7Z!-OO1d5^@kCiO84(^JeCDkQJri|%P^9nsT1=yjO#1)-ee@_G?FD@jKC#0=s-@UU3bj7OEOSff; zY=e@?-oB~DpMEf@jnK}b;tGonrO5#bHGAcgKAWzL1Q?U+w*;mU7eUN1Rf53s>IY}Rj zSbx`p7w5+1o((j40<@q0PO}3mEOXnQzD>g6AAs3WruNsKfu0S(Km6pHBNsYeS^sMe z3l!Lof(vvXLM3+iCgv0Uymf8#Th-c)Q`JuOz(P#~#h1~xqLR~CuaDlK2uO!s+bCDm zY%z*u-rLFu+7en&eEr3Z|=EIU?g%Rp(T0CTcXi0^m{C#b)X=Vx( zn^%9Nq>rgj{x`R_46An4``PWhx>J2D*0Tg^%@olET08+D%KORb^I#nKEKApd$dNRg z(X?3sL`kl>uObC0&zaC8Szl7I{!c%GI$1N9Ez=RKQ;=u}*1?WFW>JEUCzgJ;0@@oT zReff4(d9YvRtIGO@GcD@%%YGiJE=u}pW4SE#=|Mj{L2Wz|E%dkyO#7Xf^}FIA;RuTly*aS0ufc$LDaP-6XSCCRSqy z;Th{paGkyeBBArE6|_1j|M1rJW-vVhYa+i>Ms7nhl&^2kTg_s^KZ9L1gZ#u zQDRz?gxm+%it#a-mn(nJN)gI{YAE6X)xTCoG4+iGO+S3vI(J(bKB*dSdeN^5_Fxhr zOcRq)Sn&CALmHdj|3Og1;UT&k{*b?1S)OzVz4WAVL_**SX0mf`yY|Pg@ZXrN=Kd1> zk#6G5n*Zp)?iJd#$IC5ZjK=xmsazQcP|& zIzD%c>~tPWa<>zr2F;_x!}q)))hf2;`PiY{#NX1&O17mPvw(sUTqSYoN`NO+cWCQL zrRL8YZ2ASPrCr2`U#;#Y$1$1|E$24J=q&T3bJL<`OQ&XRFo2noN#Di}p`6ffFNYgq zuMMyJkxtQLut|3BvRSW%l(fB0v54A+djyz=AUvr#fV?!MrW`r*e?pp3?+>F3Hqh!TF=$&HZ^#W=g>bIjpOsIU|e{~-)n?y}(hyER8F+$2Q=*^;K? zP&NQq$Or`f^7ea?PI^!d&RMHcxtJf#rDy~@7P6Gx@@!PKjMLEdD*&VhcicX;g7!>2-%I-mV6vdr z@cBOk{tlR!Mn>xBd0f9VC6D!J=315>Pp)56AMp{!#KD;4B-eW0tH<7ndKp-be8z2f zxG6EYGbUdX3$1e#uweV!z&Bhk&(I5&cZ{*goIY8vQq>0r{682dxz;qr4Vx`EH8cx0i5!KDNhCA<&5G7RU|MjdA~OS}4+qbq$BY~G z1c71HDoOQsZ~siaritsy*wZxJF!aFbfhtvV;1(#FQ5z%0S}DrgPMq#*ui29(Gh!{o z#qP!KjS%$Q&C4DODQs3ZK419#e_DW8$W$swHlAbmz*LLXG7aD_?bl|BWuJ5faS{J* z-Vu!T{2Q24@D_S~oQG5o6PG(Zp=!zJ`{}ApITh?ndgGl_o-2^>`;Qa26j2 zJ*mg0+>579aDI9HcHZwT43&)ox2d>b?JKm9ri5$`5T6@d0NHOAMhF-SE7!sF_RzNB z0=o*qvYGwYSwxfiY^vxzz|gdkemA<=7Y%j@rUZbZDT|k<(v2P2;0hl1DJ0|cy&7rc z=@^fNEP>iD`91S^ZFg+LLwZWz;%;uA-Ke%)`bB&%oD2#^5PLB1KJn9znmz#RJ47S^ zoT{%_?AlY#{W6gv7vsJ^zai*Y(K^oSA;8?gtw#cyUB9U<6!sP?!ZZb>oaRAtcXc`A zsS2z?&a){=Qv*8lSv6F@0Ixt?A+Ac>yXg^|+!!8YIQq{Tf|)4x8)qL@bzej=M->8E zUi!)-NIsmIg>)~J@}c%UeiM5lY-{Qi?m^`~&aj|ePOl`edU{yiL>es_eGyz~$06&Y zV98C?onN~BZJ$M=2Bb|_pKdZh`-);EGoKT%~W`Lk~ZFvB$5y)|HiO|Gjgk)iHicXV__pLDuD6xE@ciX+#DUHZFt^AD$dz^%Xs#(OSm*OIv0q+ zFYfHUmi`)dMGYB99X1seVgpPPz>~DM1uzCwFYzx&*ehq;sP&x4x}yJOlH#v98l!$C zGHSt#n5huuok1ndrVPP`*FCb(3jNv$b7RYldhNh7=MfsdF02+sN6rV7!0T5f!I^fFLqc;-v~wt z*OY+=tK&|McG6F4Na0RW+Qi;W)I`~3u|6Isd0XDz9Cyp%&}3NG`fY6TF(o-DY5dRg zJ#&^2EBU!umU0&=Je(nVcTU8CYjIR9PDl&W*j9dU}7;T&7Yx`!;qx zs_tj~_?&Av??Z^SFE@1H=^@WJ)_Gsqsy(ZGU}8!C_P(zwQ4^G4&^H2T#N|03mALMn&XbG8Kjo3W@(D1r+U5YdAq=apV&Ai%`wD3c zBafF+YWfZ14{hg*X^i#LZ&*I(m*%?3>p%Sl*IZApIgHvb4(pg%M%}da8@JsOXGt+- zNhOHc-@8ysOvySih-2r3YRw#oVdum&UkP-m9jauXHH1JQqBMPS!p@Z< zT2Z(kA)0GaF7HdU+lOSr0?s?HCmuRC?mkhn04Z<%L`j@P@A4)Hha+Y@MQ3KD$*NLW zLR9Cjko&l`uO%#5fHT_kKuI4 ze^vM739k4z_$vk4ag)dU=1!0&nQr|EE$FMSzMqw58B?*3QV(I;{J_$g!RH2}QHFbyn=qm*C{U zIIe+nOCTxw;8*2F&uik@JPp;IT@@*bd5A$#|B~>^r=|cMLofTgohPKerrIl3dJ^C7 z0&Gg@>**{p+7k$=c@g{rF#jAy*`Llov7f7s?JGL3N{b!YR-d(8zw6;dauDf|RQ&;} z$V=LM{C(Noa9dP+-=j2uOf$`bYyv%lxFlS{cRxYCCJ}BI9ETd3C1Kdj>G&M73)VxIaa&@Sc}_&* zdfPMKf%Fp?KR{Bmzlv21t?9N3QJ}}I`{T-8&+}sqIERBM)w^H1{)2ULxRWdUmyfs! z#;5-HKrfDW*|&*@0Tq_Rq9JaMyuiK<(o}Trtu)eXIZ# zSY#;*^L0KZ;5ZGF0EB$G%H+_a1x`56ec5b}&idQ0^KNqsc3z2xCc}8;`@B=E-jpdIlgrDOu0ZEdqhgwXTgA_ z4vl#?f!O8+DRZNaX~eXzBWR8*H-J^i)y@8rvk>?|Aa3F9uZOQ-$chiEc73&n`Jsu6 zXcUyCvV>EbpbJw2ge`MS&4Qj7RjLX3*03thg3X-8TwmEt?aZOHjy+Cba@d1syEb|@ ze%{o>A&F0b0T;2wZnqwrW){Rc|KY{!J15Hekzao5MsQu1&Cm5GqCFK!%1O=Lj`dF+=(mf)IR*VP z1{{@>1Z{nMC|F5n77gxXObseIVO()GexYsMOl)88z(#Gb>pgpd3c8LKzM15Tg}%PH z-xlkJSY7kZe&nFuadW$>hv(}h4OpeLYU0{!qg${SYGXzen(jq{N# zNkTEIW!bCa`z@_{q5m5e5|Ca*R<*uuB4MAXR7jyZ;F5M!HU%m%U{HzHssKmh1knT#-HAhuA}xCmC*O~J_i%r>ovYQIcx3Zgw*FJpzeGe-P?=7h#^M-Q? z{_Vi5f9x-qaLhp`5d$fmusT{dj)hZ68!74UMI;kt$zbaKXB&%R2D5bxRgYcKm(|)^ z+bFKcx@w3%@%_hZ^5UjXso{bV13sRX|zQ}wTJgI-wSZ#m{5yxxoI8zVHe(_~j zpaF~cCL6o41Q+Yxsr@I)=qb+c)E{guKq>AvwTyT8Y;l~8?%m`HLMFK}%dvxdju?^* zMv&x^?3UsdVM;NV04T^ZZbK{P%r7B0l$^^(5ty8^YN>rbqnD2WTH@!p;U_xJlkJWD+2z)-7}_zsroSGiHM(zDlZ z=pddyfCEhr15^a4g`1^8A$jYF$Bvw!=GU0N2*kb%mUV!i*Q2p-Et_q%Gzj}-Lzk9J znZWAWb@*9t)pm**J4pm8TD<8z@=7dr9TfYEf_2hF+jnZmo>_5F(c+KX z6zW*+jX}FQ7ZH1|hl9Z3k+eCX6aloje^@B#W9bMSY5`=E>XEaBK&KoNx*pa=A>%31 z-@b-Q{$-9J!BN7a6I)RsCNIV7PzNYdU&kt=Jw{ULmG4PtK^txn?#HH&@9J?9%Jn5+ z?G4>T2}S(4eD+rlzbWQQv>Fu~c>k68M#JG)L|c+(3oCvc)LX7A))m#(?wlezO&QRk zb6mZ}?gq0~G%hJlAoV(WYzLbOe3;n%15dhcIHtrh@=Y)~*g6z9JsLBT(zIVvt3~$x z{KwmkEQ8XUfiGMJM{JHpMv=}{uByb=Xa0w-u$Yv@I)1`hnU)G4cWLL^G^wNyw7bLrqQbWZH_HOp^ zxhfiaKMq!6S(E=JPch9LkEO|HlQbDI@_Q4Dx_q=dzGl1Jdp1|}e-^7Cd!7_JeA82Z zo2$wUr!=IbMDm!R`I}Mo3G|=4muR9q(ZClzNd8OS(j8&&NW%gQNco37Yp7redG(l4 z*0%60E5%0k=gjm*0@83W`L9i*={1xQjZD$u-}ap(V)mAvipYJbfvN-J4xZ9sleON9 z=A=T22@fham0>QUeeZutI(Mp-bDs)-9YER*Et0S&X-MUrI(f3^-}0r`t{QyuAaIEi z*z6*i;C(be4aSbfiquQN4f^f(cHmzIks-Q_Ky+`s1lN-OT(ZUIW#p=wfeAsY$mAQ& z2Q9dg7bN)-t(CdUO?Sa1%)v}%qOp2odiF`SH-2;#AHq~Jl=_#P*4J+gOE;D<8*2O2 zV&X>3N~0SaDy?JYM`-1p2SdQVvp)>73o(|Xn0syXnOvRx%Gt0!3(V~ayw78yaXtN3 zs9;qqji4CJs%_bX0a6k!k&A2-P_-ef)R#zUTgizF59C= zLV7S}^|VD)Rv`5B*u8d75h#&gSwdk)_cr1Qq&RImgkNulFq*asZT4fI3BykgYF461 z%=Lv(=Q~1<(EMacPeYc%ra85#6Am=_(N=2pa`4;d|D4S zV%DO!|4q**#makx2xvOjXarJb%G;lAcFe&r%e5y%6;u<+Rt>cP(I?Add@C;Vq36Kg zVHW{W#^;dOIC=Ytge1MePs@!9&koGePWA8!hqqzpA!++X6rk<=84(u(-=Mu6v|S?K zN*wGK*-2;HnmJgOvWP<#2VdN_8?|+@rfW=;+USS{?hj5CtZ{h-siX$b#1ulcc>}k|FRAr$N#jH!HN4pv^bv0&2e^fer>VfC6uo zrq*xs5$8t+*uKM#8+LW-`CoFBUWhS|c^qn+<$^=hBH{eh+}q0Q$eQuz*DxWRFns?< z;Z&k&IOe9IX)zY^*NLsu05RjNbiqvL>T`wm>@~Jot}PF4(_n3i+F(S7KQZ0lsG3xR;JL>mXzyRa<}P4HVFHQB$e}aBo0nX4S(6AqkP1f_kANu8PyiPPNpXj>ucyEM zBNHgeOpv%MJW)vb?OUJU>%ckL1lEVf&P7ie5i0N??D4dp?y-p zAs6wKZtJ`nq2y$EO6l;R2K`W8J;Kf5@Dy2(&b*QNC7-G{=q?f>XnB;qo7Dqj@=QCk zX{v706iHh(3>(qf;N||5$sNHkkKz$7MolixNeV zt0;m~Sfot!wa&I-YIjVC^o6&@HwXufeRyZ@q0yhuZ)3;ktzrA%mPto^v)gg1mfL=j zX5V55Rhs-th6YsqxMse7Z8t{n$uu=T@bu)|Zs z@|qaMr&!?r&`mhjTP#;|Wb+igHP>UEKbjvRURgp73K2ZYAT$wYbl{X8&<=2IB5=HF zym8K0eT)kuX?oc;D>?4lzEmEJLaKTrtlQguE2Da=F~%B{>kk(rip50j9&K;d@4D%{ zJ5qj*X_9d&ctBn}v$5^b<0z;+Dg*B_xHanw`#F<09DrG$BN%N{82*vc^Kr56GXLmC>GFhOlzaZcV5Cgi3Y6O zYAiIU>g@P1>_E-lX4Qf|m4WcWQKB;kgv7oXXvbdbd65N>#d_F62P|7gpOJr9Wpl(z z`-B(QUAv_HLPS@=T5MfS82W{oO{QHZ!sV^v|ICn>DAa!_<#MCi0<)t=gNDN34aO`X zM~|r4ClFa(MV#J)t9_F4#k{rvQD*fHe;PrrBqq~}nz_EHTyf;BMr|uW;M%Vw_FLE4 z-9P<_K<7|5nJM=gQ^l7#TC}2^#N#8DEhO}|H$J^?Ox5U(9LOod07#RZ$mt6Vj=)U& zeQqy>_m|4W-oC@P6j{QGF=1xxrEz_NP_W_gRkad|6lU9di(1r32rKgA0;q!o7 z=ZV;}!u*#YZyh{u0fOjlWnvsOr3NbIIwI8kwXvzdhKU}YLr>Yh=Xx_ztUFZmiqU|n zndV{5xis&Xwisx5Y=sAx76zavFep;jWW}eC@J5kZA%W8RT6>@oM7P1826$>MBg6ipee(;oR%cT9%6Mdi znu#L?+^IUy*`2$pe#ll%iTBgK?QM&m1D~?V9idF;&)(thm8*$xLigRf3{}O zK`#TBu69omwLQphu`-aq_5&wAk^0zwx4vdcY$?leLts{5&%R1q?W+4WtFf=ITV%K2 zKn%}0B>naGq~)F3flaV}lRa|2wU|D7b`sP{M}O00kR|*(k5YPh`-o=UWMbn!eTi_< zwFG{X2-DbwF8Q2pjY?|HLQ(eQ{9_DbiE8h+1iNZ23u0E4u#8e@GQDlxbQC9}Zglcwt3!L$&{>FAOtrKNr6HYFK=7*&Uai zxr{w82HumIZt?bdypGW3jsXhc@wn{WC+qnb;zO{oLCK1CU;m5SsnyBDAHBc64SXW( zUZ3p@o$o6mh}Vzi?~hV`^9MjhMA)xGTdzXHDAXqh=LRWWY;Fdeq0O%}cAUCPw_4r* z;S|0;+=V6PbC=XvZN#M;+0X7%2|WJit`Nap`wBKVzb-zXnD~CZq$?vpjn0M`^gv{; zQ8e?z8`w>>i)!|Ytw#`yUteJ5ImVmHU#?y&CHy%IOnaxQLYS@LUMnNj-VgkBV7lS> z2Rlgdzwfmckv@O9tjN&SRxyROiaqS#p9R!ioftc0ygIu*=wBTye7l|Qxu{Yq7SrDg z=jVH~Whx5KZ=$z;V%a(Fs0;WZ_IfU}3=}_g92=&x7}m?OC;qWvK{d3LX93Pv(r|AV zEiMZ4NG=IP2c7(oJU1ZBg=d8C>D8vInjq{+V4K$XVBoj%$67>e5Ecp+P%1U$*-chG`2p(3Qp3G!A^HXtf>qd2eW{cKYm{NP)!L6yUq=)@%c%+ch$$PG^ zcJ34-yE)&O2$V_+Nz4bo^#Lop?&0odjkF`fpAq3QxuxOh$FJkg^;?LeR<#}izE@|_ za_~wJ-SVwOsC$Y1y7>GeY`{_J>*y>dEjB%`u&g^9q4*!> z#fP?Bjt^`%)o$jiS?ygKPs$b_-5YUv>H&>^iE_K^lky%JEkii_ved5QQZwt953a$d z4gk1A3NqMhctQu!`X!HN)tzML55P1#Uu92FHRw*jwBI`GwU%QB=V2ZoFK&J_CLzqOpQt=gdg~~HVU^2t(MMEwLKxIfG_=4xo{3wiN;BVAm zP64phZRdlz2vTW00%}WVW)OLgRyp;LUoV5_P{f`Vsf%6RwvXn^bGI#8FeyO2h-e>< z>^UgQYFSbw#iw*GN#8&#+8LLr{V8AYL(4d+@ABh{R!ofV3nx2e|SXuJJsDJ zv@%|9DOo`**#MKswDk zaS0&mFNV_g)18?vnhA8ls)oGM5h)+?&n(Z?O$@_MgFtWGNa0)tgk7I;{SGhcIwik_ ztLr{acikyr1=PK0>35nlRAissrr+kfVb}JbeT2ai&R0RB8S@a+@R}^q3D3`E23Y>L z^Cvek{fWjDFV8Dh=N_gH7<4fWQ;%B}or$hhu^z_DFI}w+=LdTOJN=8hzSQ8u9e78# z?}j}i#buZiN65J)Z2P0Mb?Gzw{FS_vrbP(@gYI(zhlqyUx0B*t&M4o*%_+IOCo1pGYIuzYlk-x8A2L(CsIt-fAMvIjIN0xuAM)9d==#qbBpDt3`HvDoQ3Lh=D5+11u?H7@$JSJ!nS z^;{X?E>9wsMoLh|ZDJ}wu&dU#d%Rwsvf&WoKH$3pZuV4U>hqVjH=HC&cWc)JWT2#Q zD-g0eV410RDG%dhv~A$-OZkkM{eN13m-YZ&`QjP0>N50!sWlWipU{eEtz;L{ruJcp zny1&*h+Cnz(cPCGj*Y5uq2vXXkn7y!=L zDf?)i}S1j@^IMAhW^{F{XrK2l@USm2lhWM(~L2o>ro2mzYGinM{@#b zeZQm^oTz`iH_G&k749&6MM1*?y`i%}8R@B#mX*JjX;8+-_%1)m*kHd}OEmy1T+c>& z-ygQQT9b5vX;}AePh7n2RXgvlE12B`aiFk&2Tp=ZEHCjymOw-l94@k%fpfyjh9fJY zStr9l+(_Kp_|9wg*Yme;t*>BVU+TzGc#!Tv^J%~1`L6T#-+oz2mVA(LUI5P(dq^2% z-wc%t;SNDAQeFEl!0N^?FsM+o4m<)po=*#w?o8C=x>OWpOAY zl=tXSNBZ(o2xHB~* zuBGM7PrSk+QX!lW#;-no*;q1jITDKHig#6m6wilK4}lBXo*Kn^OAoq-7c|<(JD)6* zGRaersW@nXG9PhPMEoMg3e|nDeFsZOb!A-Z<-8S8P?WR2Z5>xvGBHvJ%)o>+IDc+} z#mE3Q06^8qZY|jEar!6a`Wx5@LvPKGs-ppz(VJHuxTgmSSEjJlDFz+CUvavEmyI2c z_4NIDXFD(!4D&%3R~~kti)Aq<^sK!H16_M8v61r7#z{jHB;~8JIT*fN^;XjM>7rd+ zfS_UY9|%9mO4VXisNL-g_pEAS!@>(Nsp&Zg2u$kC_1f5y_;t0BHUDC_tIbhr;KKi) znad@6U02p|=tHI2E9`H5rdPWA+2AutWGFnEX=ZC8y!lQmM?!jETuQ7v8nO~aVX6rm zbXLqPl2EGWLm4+&=Q`(dq{dh48Df&#`${;{giL-rA}O8Xx;kdtx`p3Z1SR1lEW#Ca z+?s2dQ`f^w+lqLt0W^_PwOl2UX&D(w^7_&73*Vi@$3iHu7fgbS(-bI*(Lcq)QSmEI zSl4#on;=GSU;0n4VdB6`s_;SbfN_G24U|U?)?f8iF>LqMtmHs_G^1*ATKv9Y93e^Q zs>$Z=*q@%ML6pDyxdL`?6;6ljkUKeW^{-yuwIdl@mB`lQ-O{*=tz2FmzDcCkclhXk zM=8Wkn8wH6N!w;j07|O-*>zmZFUih!L<0e(VOgui>kdnqP-<98t-x+SMsMa8BmoRy zhcS->qhEab2H)?ZePOh_X-WRxZd}oYhl_>4yRiIEnATsBtEYi|pDHsO^1s(gVtEM# z>zqBac;%n2%iU9A*S^uq(OMOID=-JXVRh{AIk8!U*&hJ0G zi0Cnz*e28RX1~_=mJwIQv&om7@jHTa^-mop&{}|AL~)k&dg1vT+d$7Yfmnxy6-9AE z_BwtG;UZ3 zKKrh6e%0e7Dpbyiz(E@!4(xn>4TSLyMZYjdt$(?wvBO@&707=9$z+32_kiufon7a~ zV8IxDBZ#d%<)LQ-yK@ED`W%13rbfeG`d4g9y$JMVxNix$v=uRuSTp@O+VPqA3PX|TTQZI zKJuG^E{>D1d4#Y*fg(GUY}VfYZlAd|8>@-l_5Ne{<5H53s5yfj8N)5)ynuPep4s(l zo)R@P^NT~y^tLedzCl5Z$xET7gsHZ-y?Vz% zh3>I8ngd+aYxNBshsJIvAQg7a8V%D-LlZ|rkLHd|Wz13F6j)L$!u4X8MxJ!sGj6Z1 zU(n<4Wk7FQ@C`A!XFYd7kkyUu76c5(y;JKu3~}7is(}8JSAbmhP1en{gvUGiI%3Gc z-j=g}b{m*SMhb~f2x4DM*=!swEgAdzCCN6F2cHnAIagV*W%YiW<(4V(Yx%K#6(k5T zNakl`uwq)qp9P!0acWX|`&2+ppv5Yo|xxL42J;#%;O}C|sy{#O1K1fpV8s(|hyve6ty^o}C{26kHs#<(tCGQHb$)oStc%ZV8m;TniNk zBl&@Hc0&IQd`^`){Zyj0Zxu$pX(&L2fdYbL=-cP7qpbOdjB4oG16W~=grsJnrKN%P zKg8aCwK91^1v*qI0kvI*A)aj=0;{*aPzqJmqoprigRc*an;v2 z1L#HGV)XopZ?@jy@ZHe2Zwu5- zeEvQ+H*wzELiLxjm0xuuz8o|}QJIt9dSgL2#~8|Zpzd$m=U=ZSzh(pNeZVyJ23#__#g=+NBw{(oW#zI(*TS6O% zXvFfAH`0GfKH)GW9}NrDHIURGq-G`gOOxJ)Fl|wlRz22oXDOE%WJk4(dFh0#NbOle zJ~Zmc@9S^=O~^)fR{&@Ws+!4A&KTZ+Cm4|QHDq;FSk**7NQd>40$10L4SK8=-3Zfs zz3I3nP69~X5Bg1s52X<+tWGtzMO7gP=mg!2Z4cg(!fr34Y?7*T1qXGV@2g+EPu3}8 zzQ%GLIaW`|V$%cEEBI0b7E(6Xj2G3sOSbm4j~+MF$@u}$k%a%jaJSqPH?_Ha*!Gxs zM@N=!0#->@*!@j`He{pEI(N8T(ShShCEDJ0Vu+a*#}(|rDwCVyg~P`P67-KhZP#K^ zhlc2O5HDy8#6^4v^JX+Iq0F@`yE|j8uhk=x1_}a9qqq3-$rnbNwK0H)F1cz$@u~%! zfUGQcVJDF)^Zu#d`2AKR#bjVUZLfD~=h|9;F!H_<| zYe`8WV!jTqGWggK9tbCDAe``gi6ARB_gm2z@UM>quJ(fUgv?oM2sxg2fAmR ze=Zfh(8sN7HLWv8r#*E61&AtZ%0` z{W2>R&i38DTj1zg`aHM=Id@|S-_6ffWEixJSJC#t$lg7F+5EVj>O};%g#+Ye-&drP zr)cPlQ3)3ub1>L1=7UT3`s}zWEG)MPT)$Q^Vo*hd|4H`rr+p*WeuT_ai8@ZQk6cSH z2Q1p3g0EO=jvs|0h{d3Eiq`Woi!rZS-N&C69kgYs1h4!9YJHP5-zl~WwRMT8(Z@uIgUA-j?NN_r}T3Ak6#PObzmmo z6-7oRarhsU$SulBC}o-igU>7c%8=K2)KY*<*qk(}DTwnIWi#f~0cpaj-c7)MS)*lS zzqaEe9@;L#AG9wj`GMUwB~=&9+QDn9g+ueLS^Kzj(Z@%Cax;8`!l^^=ng%$-O2VNH zMuED*%7;J zfIU~o9-k<@Rd`$&p(0m@GYJ%gwzBHtRm8A+G;dR{&!;8e9AEN< zO^4yf9Ze*1tw|zZdX^TZE34HEFJ&ym^)&q}4J+EWj!Em{d6}Q~^}M}C_f!T?vSgsG zB9GhuSdy8~zUdN|uYSf7>ff~QS{t{DMA*67KbBp2L=CuDC}_Jz=|AaJIF^y5-rhOb zE;MI8I9jDbGjBHeo$-!~<+*q0i^B0lK3X00@JngIPhtmudeN_Ig4sX(2olwjA9V1R zzYrVeSV~;lmPCbH9DjGbd-1YnVI&wKPFJF(w1^RDP011-WB2RiTIL`P|6I`8h8uf} z=Fus1^&V^ZQK4o!a3~aUsR);eIha!o0?dM^-VSUA!bEK2H_c!d*%;A%9Np+YU`B)N zT2eHmPd_D#aa)Lxk4y)rJgN{F#gVNhne!d3`?@Guk+|3h_dBVPCDO{K{WsxD4dzgE zY$~pN=}W_-S}ZaE+uyHU>4;SnIdn>mW6y;_sSpE#G)8E`-+ylH#x|xz4D5N#cHH?; zw9tyG+L9h*83{>F3F^g(^-hDbl0((7mk3sdUg8M7G3p%h@95EIN<>W^IZC4~w`My9 zK?6EaRty!#7%w;%i63RPi(Tu@w=u-mF6VafZaS{x&dyhRh=dTPJ$byNn=gBho!s*i zw){>tls)9-NQ(glK&q#j$;+W1`8QW|p++lA-Ve%2)8BpX2k z4A=>LW;s6L^DjX-78CiR^zgd1S}LnN_0p*_eS_ZXwBb+M{-ofH`$$k z(*@g>pAMOin)|Op-D1O)&W=7DJri%kemPsmOe(LnNG--z+`x%{za_H?@@%-b8IPuc z%3Pz(zK+W2E#&}|>O%oe<=Qq*>0L8pee&%p#uPk==g|NK_s`D;t5#obg=~bca3EGu zBh26-V}a*jeUI03tn3WmNplns58vIDbrYO8$!1RZKuUHE%X!@?1$zzx_K2f=nh!PZ5x{K^36rA#E`5kRiQau>( zE&gXZ#Pn;c@y@r7FEww%Dv-1Fb$;P65goJ@7LJV_DU0OQqA}{iD^yC_B8y_54P}dOvq< z{GC-vr-u=#))cZmv^D~nP>=AaID7YKb{{M(8Fp|4o;^R#9WEt4@0hj%thT2BAeyqV zl*x^$(Id`3*&IClr<>*0(Nj0J%Vi#&(ZeSh!M(bK+AZnWU(QWNOG_5z#+-hf!F}>z z;msTr5{5xMSMuXWPg*QCyJOIs+ngQuxfoPfv6Vh%<+9d&yhFf zFPVPaGrjh|!@pMF=*63?!vx~9y)r&+^aIs z7?+MKF$0=eX~s(Tj)Jw;=Lgv|=H97SIR$bY-Lzo|)no7oC)TiM*Ehgud6yDZbK?si z7+o8U+s(PoF_E=5E}EU099wvTKwF}!y(Ijc{^jle(R7w!QFUJ*9zqyEWB_H5kdW?f zM23=(F6r*>ZV;su7*eFWySoG)8iwxf?t0Jv!~1Ezam{s@v-e(W-TQZYg>RlVz6ki zO;fP#v2;YjVPK;^ADxW3wnm7mI*!4vvO0e*s=St{xTSVY-^CJOp1ztap0l(n^%J`C z1YMhb7Mf}&P>3D`qFqV&M{g1GiU-c(kS#*P5c+3{Akmkt+e1frF(JVMkikJj?ONR9 zd14%`y}yyi_xBtV_ZVMkjl7hZqs5JbPkbvp_EK#{@+LQw86(&LHZ?egU`~8{bU>82 z9*>ngiPE}sqYWtl>nF#24|93z*3gcrsbW4t)BMNQ8?&3BIs}lLmB6#-AVL*s%v>^b z;OMHruCb+T7`BrSA4g=;zWKFIk%q%?L(VQyH5LC+BvX1puqn|fq)LDhU_?e9F32fx zmQ&~q5q5os!Ssf2PFUa-0Kl(mT2m#djRm|gPf0$v!D|5f5c&OEUVPOzyLdF)!$nvC z`M%fCl>s~6m6{#1&5~Qf=QsPvWd^eDNp><>yv>XtTC-o9%#+8* z)aJ!`Z}y$ybI5wb)*bHfPL(@1u(DR9y1G;L{UDp{to{QOA#b(5^$k2rVQF|+njSw} z+|Jv(32JAO;Z^(^&f%_W+vj~~OEBAV(%jN|yM60-KVdCxPv1P~1HA+eaZOx?z!X10 ztxPvse8LPdThS?$F7$X2`sBSoT~63>Z>p|nTIT1uySn1l>v|IO`r%~(MG~C(qOm^B zdT*Fp?N5wzVE>}@Yq#9{`<^s3}#;`qsT^dzsT15K8 z7+5)LL}9G~7Pe3^T<$s96$`;!0AQml7&j_hPe_cGm^cF#JoW3R3*P{bX+XRkPy%oJ^U{Rx8)f}@DuHl ztj(6wu1wq3XA4t0sV(JcuVpC_LhPHjrniTpf$VH#3Nf-FzZpR(zWy~D0;u_#bOeS3 ztJB(<2n1+Ky#?U%&Av~sD>7Z9l9Q8sjEt<~>HzJyZ7>QVT`5-niu;H}uufBrK*OfN z{Oa2yRz-sO@yJK@q{=gLLAZwV!CykzB@KZ_5F! zd-%hs5xI#a!cJT*PcPC46&2w(sQL`k&x01|{gM}X6JURhu+EZW=Hr%Bb~Oct4UC-!uru zmV`nhFKRvij&HWG)>dV)N%sRd0$oknf7R*3?2-|`ztF-MtKB$RIA4K2chJfD$`Pid zsU5o`G#b+tjY}rKAO~=U{(={}3VldVKNHF_V7?kNqN=I;PfRN~f`mD-sjjP7wO7~8 zNzsdBXyPpvJgRua)Fgh3o%9$Q5a8u;USngAdi7zH2IwZozLA~(08&lvLmhxcz*xiJ zbeB$aC7}p{e(=DA2L%Nxy``!toGqRrdo-$}1y!))Ext((f6M|W0xr!nvcy5yrpkS9}H=E4IX$%=PUHcOcq&FSFcQ|sD{V<~wm{x0QT;eFq| z%6L*@>u2rZAEgL%xDA5LzAwem;vfZ#cif~L&0h@_zc^I+yq)?stLs5wUBlb;R{=rO ziMfM)mTX!Q+WH)GO&b$u@#OQ-RPbXi)~Wei%fw*Tl?cW{H^;PSl$E8nMoYs$RpBLa zR)`_+5G*WP!R30+sK~!^u@5d^3{QrQsD_R?+pCwK`aZn>ZEdQCm|vP+qDr-4`5Fbb z%9Q+|@{58P1%;E%%-~^wgH7Rr4d=pu5Y6VlhmH>(wXS>h;aX|kqfJyFi1ch4&~4@@lYL2P{B=7moI9rnL$ zMr<`ej8ll=f_5?xY6~!qs6i`JM#Ig4J0de#k=9tuX6Z#9iILV69N>%4_(46{?d$~W zlwafbV19#6L=5bGZ^X{Thf=(@B`d&_RF!dDTJ)axJQK`$`jz+r1iCj5YX*VxMJjna zciOcyp;&uAuWRdTIJDlgQpyk(j)Vt?2Qx8z*RZ-Ssgm(>pOJ!;^!;azK=;4#JDGO6 z&3!jS0?G)ym|m+WpdBy1srSEvfVw5NKQL%TDE~hTz|@iy`Bx~6qF$zq{*TWgi~|Y8 zCrE7TM6ZX4h5PM)ZI9J{;UB2cJ)akY8WOth&UGV$R(T!a1IvHWk^UvZ z*latq2u?S{Q1P|p1KCBRzf%MR@4(hGt`o2*Ty$O|kYi5lO0SO9^^%VZ1m6F;PTZP?(;=z^RB z|J0Z$3JwqEDVMMdcuGPo_44F7J`~}64n8$|13DGCBj4xn^}w=cL7S;^e|A`xG`TMs zG<(d7PZR)y2hKIGF92;{Q<=r zxH>Gz`a~etFPtLZIG$0xwPpgxcz)x9@C8&e7Ho$xhrRu@3sXLb|LSQOQ^IZ2FRw z34H4(A0IE?l@`)4(m}?p-rH`42v z&J!nP`|V}=OE)6npjcnTdm}NkrIDmka%CK?=KJw8ZK^t78K>tK9I@*c$o^Kx7##?# zRo@^2NE-exG)#wlIC}cOoh|ovp8(W|BHY_<(Xs8JJ>95in-&hWZWmquD@$S$P$(gZ zve!U&%qK~#&R`ut`vw_e;%uh-9fC|z_})KRLXW zv1r!A%KJW(y&a}Plch7@T22=N5iRa5akoJ;K#oFETBtm!sUyO2sY%DL+kGskqEN>I zCYGMxPjcWfEy26U|Nqd`vPrO`1YY}f5s%sfd%+Klf_&S20w9>mrnMTgvbcm?nQnNY~=l1p!+y(}?#&bM5r%2>5r zK^6w=05BCkkDum$F$YhH#BO=aNq)D%xo=Z629-VfV=%S3@ay)p+eHeUYu%eGeHouu zQ!lnVJRi;0dB2>*u8??@272%1qA^bMv*Oq-MSh9E1Rb02Tc5mp0;l_F3V9iu`j<59 z&>51W1_7!KkFvilz!I2sIb+m*-{4FCZA#>-EnR7#=~3sP{1fb!^L@GBez#<@QLiVp zf5OSBqna$Ae~SBaqUmX^x%tXr&&(&hd}TM{jBNXad-h04D4Ed+KJ{yJFE>q7^F>S~ z9{$;-vp7z~QY|&wCqRk=)f}oLU2Vi&%T?B4RXCu;Rij~k-dhhNtg}pG#8MuB3Rwwm z$<%}$Uk}si|7=n$<}?$NE_SpXeE|hHQ8x?vRpO=Djw-JSF8no-#4OGI7WK`3R6pt< zL;8s4Guu}blT`Cy0^MlqaDz&`hjbf;%s5U-;mun<8l9GKN$th7szFqI5wJzE2DZE!-}oWa!M8AfL6NR>_r6@GN?#jt(owE9m>o6CDd6B}^(Thle*f1;>B9T<+f7Ue%mi^Jb3TZ)l{ z=yEmb*SNP>(bwBIDy+zBrA8Cu(RNJc!wb}`cd5TG#)Q+=E_BTXR_9N{N4X_R-Slm2 z+DR&PWXixn0Vuv7+^TK&!n5-2bFZO2Z^LY*94D8rE0IA#E`t<7g7xd!?p51k-jCVS z1FbF9I}1YNj|D_a#eNJF7Od8=-|QL92Wd;p7wqUDLi<)F(cS*PE1jYhLWW5lR`ip` ze?K_hIdV~;N~Uta$#B+)Y*{qFK<$s1d5`&{WBeGjECL$olB%0=^@=;;8TC60WdFtd zfEq5$^*Yr$GkRU?d5P8qfy+u9KLiLQMr{1_qD#e4FGP%0M{R-v`og+pxP7&%VA5s5 zH1sNGO3>LD*D@XH$`SOELTT_kdK?^x9La$faw_d$g20zv@;~S{8(Huyr6RA*FJLzL zk=7O|Tw9)+%1*lJA})F%KZ2QEp~e>D!be|6EkNupJ}rEu5~a0MJra}Vrq+{Dylf#I z7!JhIb1id~4?Kk%Ynvr*D5@n? zAsySiyl;>f_RS{WA@an9#anvLes6l6f8pYVE-AzhCt@Bg)20Dn8e|CNqmfc^lULQ9 z?5K@H>e;kVtN+RF%dziS$$zw>_2f~e$|Bp(`0c^4iXHn+SDG_~k?`Gu7MS}gD~Obr z=My_m_{u#xj$509|3TvDBI2!KgICj0&n!0k)$dJ#sQ%<5YA_A19RDXLF;w!J>c;{xB-907W9^rtersAJamA^@ z>muIojS1vlmahkT*lv*5Q9)pV1K`^5Xm~`CoO*E}u@SYL^{$({P^nznfHMy2*r37B zf{1c^MOgp%KIYWRy&P+7K+raFHYpiAM~(Dq5R7!%{H!=+hNryr)#wx>h)f@2qM5s z!%HqW%F7lQOAO8wc0dNFqU2W}A)%(AXfQ^RZq}b3A9-*CYCX3ykDK=D0Eo}N$a|93 zWKl2=3;Krls}SIcU5o#vif`ZDu3k(VHMn$kw{z0;V|atxvLq0yCt^g zNB0XWu9n|F-!DJG#VcBB-CcHY?yVJWOS9hT?(x{?#qbmj&^9%H>N~P7uRD6TUFSIK zS`qxM@VLFr!mc59&!vx8H@|s9id2SVYVHgY26zMR<>7=gtnbRA^!a3I;bXznM0+N3~rXrZHIvkUfs?$Gqf^Z(4q%p|ptY zy&a!)$7^@qe|?-`H{Q-2r!%wba=J%0cW5_8m6UOiZu=2g3q?bAas?-6%unv`gOdhv z0R7Z?Kj~*v%3!p@k{{#1@-Zi;$x*+t!GLQQ&Mc4B>6&|RUbEbA*#0c|F(iO`!tnJG zZnT;ew^@s_o2L0|wmz4-r%CTdbu(eV5E`3_t#FLI1#La2zKKEyUpZYWAj#62abLPj z>c)9L!)TzJfRrRejUft2jV2g7h+W8s_lmNM@oG~LgEB+&rxQJ#O^q^;Jv!zO7zq?M zBi7uef-??UaDen#0NPfP)WyURUaSFL<< znwmQn1K$jYMD_aLD_{6~WIm<-ojKHP=Y7B8@9=1U^5;3>V(!J=15B^{mJa{1PM zX+i&hR7lXP|2xQp)9*Sbvib5*)KC<|&Hq0}_#gIcIr9bYbF)}h&*Z`5=$BG|PZvWS zd+a6ilboCO`pBlY6b{!76(>HAeMPlf!ne;H76z~kDBc(mK4yArYQhgD{JCAh?1$@x z#_Q;2?%2EtKsSqb@MQtgTz`2cA|hlHGPr>KdENo`mF`!bm@Hb@=!4NJaVU-H@zu7 z_$Fz4nm%SgRvPI$co5hklUwQvCfO=;tQ?&eX0sX)=ca(F4`;BR|q z(oZg*laOiWyagF>7kMW>I#DxAtFpOX7t}~E8&T}TuyJ6lJ&?{$_~{vr#+QC!g2CHH+sG;wEv3+*s@; zM@|{GpBaumZ(R$9r|)qaUs`iX)jz%#)YeNIKo`-RLtzky5PnSJK&#N1_d;JtSVh}4 zdWiWoO!(aML0=aCCapjWXGQji(uS+ShyT_l{c}(al2&kuVsT7|xDfiaRy-@PscJijET`B%q>rlhL4Ak?|0$v-XGJbkjy-0C?@mllrg;p6n>Z_?nF&7&4>Se-z z-MF1O2P^-{&Eo)_@vbxU`__8)-Q)0N~%wUhO2BL|@ zq!MBm4*XlT3iO7s``>{ws*m)&3V(lXOz1m~0D%y1{QaJ9fOs#*?~=MZt16{;O4B3_ zcd;{}Su9$Arj~3+IrI(y_SEim#avm2bT`kpzliG+)0#CoRw=*+hzQ-+J690-?+L9k zNw&8ZSOMY1Dg-wqwxCQpe&fCPnMQHcgdbCbCY;MlSF{R@rI7`QrE<|YE8}?p7RD?^ zDtE1eD1HCC%nCts91VmJf(BIyeo%d=8h&R=SuAI_0&KeEXnP@IAePpt0**%SW+iiu z^ou2^Q8sqh=~+x{g|v8XS3)pbmDGBJ7<=Hx_ulPVhx{Eb_M8bJVKeDGBKAzwGS5xO zm)y{?xKKKVP{u3WD9yb4hctWlPbRD*ywKiQbvb7&C!EBUcY3mt<jh9oo-5fw(A^Q0|H^MvO-1GTY8?#DEOl+^KxB?VivQRa1r_ z8e8mEmo5@A6!0YH2e;FHeY|VcLn#jzR%obM@;Pj3SE;#LdE#(c&pZ$+4M0nR z6~9^N#GtWeqb`r<%TLm8=wMlnOEm0@gbybx^ ztqhfQ`ciss9@r1s#@(~as`&~%3k4QLomb~o44rpph2gPUQv%`P>K$0@Y>G~C!xCxq z`*Q{aPO!}opsIpVl&j8W^@!G0a_KwlXLU|zc=t*WYH9l>W9l6&m)U=Fo$BVHo+N65 z5I)FL2gdeANb?wLrQRvQM?Adx;>UV}tW80vT0qL$Pc1Rj9}z?1lEJ?Vx+?lBN0+u$ zvLoApWEK<5B`GzUxQBG<_N&2bR%%plsIDuQJQ4_$@Kl^kPjcr{E$<@m$Sk(30V|%2 zc0TIyJi96#m5bYZuV7Ewayr+*Kl?b?Y-p~Ph*kf*>2SI7&YU-wiKom{E3iVWSk4N& zhE0-K&r+S?z{lNZvzO`+Vr{Jm5M6mWXOvm+#^*V=?2}t;%G|wUFS~$Ro~XZ*bLTZ& zTB61Q<6#X2gQfyoZmBsTZv?s0*yP5}fuI_jNtgd+Npg9;>2h$OR-FKW&81vtskUT3 zzh(=))0xe9*K^Pf1sU9z2t1QB;=kwmK}<<4*WmdYM80r>1Pbt%n!>ba_ISs~+V%!y zp(l_aH+rnUJ|GGIB6oNJ9u$Y5v&dVAWX2M>qNj)@!UwU#UEz3(R5hklFhj~l`97tG zRU22WnQYNboHGQa1#Pj4|7q^D!e-Eo0?YN;u(rv2{Q8}b8 zh^1{2e6yASzFupz<;ndQsRfZHte`socbR&oWg^y+d04{!6{RAh7+ne0mPF3Dd$Zu* zR@}dfLm(jPqz`8Z(E(qi%SG2fwl?`^24fTxj+eVbT!q7bHih5MV*k_fdHySe>F^DvKIs8 zc6=Y~^v{@tcY5^?9@sr^B^~!JqC93W1Z!B}xdGffe_RGhaNOO6slN)C5+?==#Mz0v z=|xh{yls!y_*f=lvFvp{a^i{viaLt)NKP=jb2u`Zo%K?BLk7P(oL;##aemRQy|2<~ zTkWON|JnKVWlJAet{atdDXk_YS6Xk(Bepx3HH;3-xO~;OozG6ArpF(W5j4qc#;b_o zaQL7-&{w~5u-*-`wbI?vBJSlzH8=+@tvbEQHM0w$o*~e}AkScNLV3JA+Qe^1Ecg$< zOs%{(2s(^SlfOGYBAf{IKRQ@y?VTjMyy`nqFSK~GcorN4nVomB2pEFbFsQlDFeV`5 zyPPaUxOCNU?DzXNgOC-ess`iXLN>Ig|y5&zP3^ik9a>32K~`s(Z}s&d&)z^2S61D$mT$A_`fZU6tI{q`bQQZSQJ;j z@4vd)YgY8StcQJbEy9nCvnVKe3Pr=Izqw&zAfnWfYplx6lw7L|FApzX^m$D^l&OVy zU&qzQjq&zd``gqPlQy44n))bF2syzAS``}QKwc1+NNpau@VSep*29xg@} z1j98?WCPH&c`3^SSv@d;V@g)9<M=238OCA{cSBxn;v?B?TXFVAzi9$q}%a0ns z7k>L61~8V12A8QS?CE>c?<0Wyyc=E0vXXI`(1kt5{Nir9_eDppKPZ;M-6Y(Uo4xxY>&E=hp;}vPM$2aV|xEp)r-HVmTj+x2ewN2TQqefrl{;GH@;GeMiAp|ZQomp*ElO*1KI5Y zG|VIUcArF&dxiUteG7xtH?$Zzz18P_lqvVcR6^HEiIuEZJz04cSb2(mSwNXX_z|a@ zddux3Krl)4Wb@mAi*x$@Oa_(1k8_{F0qmchstK}3MH``hI}E?)G)dayMsbR_q|-(v zUX&d^ZHW!V%`^P#E3wX}L`I49c};>@&+|tcy>mHXCK4mSVAfd&o#Hh+G9k)OLxT?5 z`o%4J6o{3r77DM$*qmW4(X=ZKyF_VVF%>w)#7%SL4I?Y%$;&`V>k-hjKFnCA7SVQ4 zFW~qMG}2v_>_^E&nAjyom%kzfd_SSt_`WsbTsdK#@?1Mw7n_vTCQA}Rzkh=6IMaA> z)fmyat9O?DVy(_Rz4A}`C3BilJN62Cp!~?%Ves^@jroE}sCl{~)p{@e`%OU6uesPK z@jnp1LoAlIY8j!=5s){3N^&ONz7?$`s&3e+fYtFV4a8M7 zZ|peB3vY%rjKHsq2#qCgu&j~lIyZ+{c}d6;e{`Tmlf7*fPKWGDc{nP2Q+!LSl3bA< z<;$Z>tLO`}9tKCm5y3hbYXwZR5Uwn|<&ypG9L%-qW*1tTOrh*NQ51p;dSiJ(^a+e1 zfPOwfvW95JtsOg%x<_mwMtvt12x{iz18ZhB3F?he$?PM>Lc!p&C$wR+mO1wnl=^Y^ zTsFrUqz<4qp_iM@jF{8{jGL&C&yj#=Gej8khTVZKQj95nd|pVP1R2Np^$|;#^J#_@ z5{P?JI#<7Qdyw&~-ri+o`r<$nO4Wl;cI%eiQutx5I*^fR7B#c9Tx=c1)5z$3c+iY>z5!c+f(4`lGJ_9?8k1JB(ri|V z>RyN?($CO;W?dXPEO@m`!s%-Fb3m*1Rm+XCieqWcTmy;E%gZ0R4>Q`lSvLRG|BW$I zV01XXsn@ujzqWo=I22gm>NS`cqsg8y4MPUaFZ@;Sv;T$lQ1OH(LQ@tK$>Vl=iL0Gp zu5aC;@AQ^%|sE1W=CuvG~pwp*o6>--B*}+;~xETGA2ntxM9XtC??QN$Ull6uh z?NkP*EF`JJX7K#oPG}I?e9zPP!`v$q;bZ=RkdLU}iVg!#v+dPr3L=qwVT^SZ^X-JI?E8Oo4bar&!Em%ZcF6NexJy% z=$-B-mHL@ene6t4#+Bv(MsHbS{Z~U^UOIKn^cJyV7t+i{qtv`$yGW>a(bbuwRY!rE zke5S%>zcWmH}Vk#I*qa5``C%mt5ID3WIi&db|LlRaE6fGVi>)Z{_p=;fGLG%=krs1 z*Mugr$EUpem=x_YycB_OzVL=$Xqrx>t_65n93PX8Z5}!TfF^}NVjaq${O4Nsq|b-s z)>7}_=ahJ^q=M(bNIS#VD)aHLH0+4L~eKlC}5V@dl(h;+2OUA9q?xb zZgaaQaSBp&+aC`mn^FjVsA4u8(egkxJd*A;F}fLY;mKrbSrb{nNK=HSF0hjhx_;y;NUzaLCBD)@sY<@dCNSjd7~P}&8wqly`RbPZc1WGLXG9(mH%b8+Eiv5 z^C&h3>guK)Pm}&7%R`TZ456MiE0yDl=Nib8 zfHeqJEtx?hYcOZL58IJvBgU@*&xTpa@>L`cl$VMgo3(axK7wBJW{)uSwwQAd&BH~+ zJU3paTKU_);TR?quV zYeRxMY5tBaga4GNx^aXWmZ2kED);-JOsqujG=Zbm@|Lnz(;JTDyS6y%oZ&mJgkF10yiiY*c$BUS=8DfTJPyE z`?fN;9Xv~)2-xSzgMPw4gNeY0s3@Rc@{I_Z)bs5Q3Bu^(EnJ0t{iKI9W&0*P*xUPg&3kVD%-Q^9o6L3Gzxd=ad&}|&&EviXl?VimXXA+?toyTN zS^Dmj5|!K}v}!comyQX3J+L4>mAOP3)9?=j2&@|LfCP=_Hve=Pejb*A23QN1z~co}}sHSTQ72lZr=-18K1Y3AhCKXOyKbCLcvGORX}bJYy*tB=cA z8>0oMtdIbZk-;ozYY+j`zw|RwAVjI*f-uUGIcQzxqFH@$_5$Pz*%e>4#S+ypVXM6V z&X$-gVxxuvH!>wxI#IF9LW@2)_J-{7#S-VLdsz118@}Ml#9M4J<0}>vsG60_ZusY)^u~Z-0Erx4F5~#K_LkQy^~!V4$?K zUZ8i_G}R3Xw4o>o9Ql+VdjQxI7yfQ;2L;*GQj`u`sS?}%ZAspA{^0({i2BefoBI@& z)lm01FOUckg((SafI$6Xb$uT|6(sC(|9KYlEGFBAu z7*F)i+n*Nt{lq;A0dG74J>3o?Z%|wr$I=v4WlC&G*Z#z<#g)?vd&y*wBBa$<fkfA%WoJrTRklJV#nV)`Yb7XZ|x~|%Q}^H*qm5>&x%|8j5qzyF7JimRY^KG z&#mLt;B#XcO+3+~=VN*L^Fcp16Gwh&eT((V_v4sWVxSNv=bvXagx5&oXw!2x5G6PV zf)Dktsb{*24S#=mNOoM|zhh%n&uTy5<@s}`lnZAc1c47}a=0&9UNZ@@at(^lURj;z z7&S5_WXYLYuM#-p-uy8c1m@PrE$Yx$wh$!S&+sp-G>}do`axAhW6xVl!$I*=E$la4 zCWGrAOyL4|wI2d*soE9(2WhP_fdy$EAG(hjQG?IAjdQ1i8?(U<No!9VyZFDXUBGz(| zz(GxlqN!fExNx3%$WI#&eQ8}Leh~RS-xhG*v_Tuw!vVG%d_o@53tS2~yvcv{DlBKN z7s#z`TObio@K3U9h0qtmxsJY`?8>XNgl=q9NC5245N`D+a`B86@;KVuryVV^84Fu3 zNa2T-ErxNQGL}umNOV14*%D~zKIrgG3JMfOQ~p&5`5VVY$`BaJXXn*(lPAVe$=DrW z!1VRadv_a{KJ64^;KSQ4t~{G>_Cpg_WLynXfev4Pzg{qtLei6@VFcH` zT^mG=p&v&Uj~oR0v?8Z<)TRkuC=33lz$bNtk~{5%`U;fs$q1gsBG8yR7o){;dT;2d zZut5gZ;G|x8K&0Mg#3+OG%<>XqcNk`KJ42cA=Hi-49c;y%6CN*>?rD9f?(zffYW$4 zK!H5fZy1qK7}+%C2Pa-{IMMnD?gD*|8*Y3GJkXKOqX_bgV=#?JWFhw6YeyY?U(x60 zU2IaVQXhC4?Lu3|CFi9Vtc1le?U zyf^$LQuZxZ!<>oVI2@!dqt2j5zh71jhE8M_a5Lso+lis(E67q~U;UpYUWxD@;R0k0gd7Gs|K5_OJ@pZEE55$Av_eDua|LxDWG zhcsV{N8O%`>7rk*;)n@y}s zUoe`R&mXzu4HfOhMo;FqwRtQpFH5m=Yt*uoACF zbRfj=bsQ&+RcS6g9&QbN2)T_CZO4>o2&JIk?$Il|019NS_X&*P0Ah$Xl-x=}Cuc@V zzJbqF{Xgs!RKr;!z9?)d#*bFR)~14hv<*$)hbdP+pX9g6^FOuxGzSlbsV2?S;2BA@ zGR?wBp1H23=nCO~n)s5s0H+_tqm?4LQi`=zFBP#dk1gGbYH;~JZHb`P&ZYqb!itnS z^VWLL@_~nEG%Wp2X{VRhVFx>a7An4ag=ckh8d|j@xK06Vj((qYb(lPOw)*W8z7S6m zHSlOG?lw+|iN<{?(-za1N@)mJ8x%0G9VK=A{Z$tUC52eN?QIbKK&>(w4~PY1#izCY_?8U?;zW~x*C1!LSzOzWeSl9_PA0vM_uLe2&}l9hoPo`?+reFvrD zs39cA>084}NB*%1MRZ|5XX<3nd-W}D5wfRXb4HTf5QhjRgyh5au94L>->`j(H_L?KA+ z5~XTA>leWUwa))GBk3)>ScGFBM6v|!ryqbkoKQ8&Nermm%j(N}Z`|buqMusC#^<@8 z36YHvTfQKL$-~PpM_sjZrl)muoWyhP(DMzw)0g*`4OYQhI znHDSWxM}mz0l5ZKf{_2ER){}^)#P?q_Qa@-jo(O?0FkfxrJ5fcTfM(epL96OJY<)d@kuRavo%zvJhK?#tb0?GDNBQ>D-mE->s`uCvgaR5O zlN_%vuaQI6&TA0!vtxvmb>wIDQsdBc(^bf7js;`dSwePK6G>m|&D(WVs*t%K0^@z+!`1AZYl zo0)IjnK3dKIEBjs51a`g))Gq)?)$QWtL>|?nDEV}kxig+IEfK6Uju+Vmi&TD#KdLl zXz9)ffQ8_|rbr@F)A%&ra#I@G&hz@YCl%k2`oC3jK0gt%BHtb%U z%{G#BfpC9)I_W*OM{WT7&d*Zy2^&3Z3O2R8rkU(G9Oolr?U40bFvToMgT1e9?4Rjg zD^kpg#4`0f%~MyeS823J@It%+=WncPUjLoE?46^(SUoPEjQr#bWWW9K0uH~w9mi3J zc3;?Zt~@Sr{y1ws^>YA5=B4xcHftsgW$t~~a!5y;G;Vox4<-GW7me#_x?+-}9*;T8cnqNO} zf^gFAm*Gll8`l zX#Mj@G_RN9VH?ESQa!s#j=FqmS9F=MDf;`6I1jH*h{0@T)|7nYx6C4)G;jai!wRp{ z*52OV%Mt%hy()aJjYZQr)tI(?dLACy3b^ye2GvSb(`;klMFQru-*7Y*omr@+ihj+5 zn4`$DmT3aP|Mj1*x&Pd_8Df9~0my`+)L+dfizTb7 zj~L5RiCIEuEGDMu1zWqdx@!*@Y{nJI#)b}eY(LLcU)%wo3DIp4>Ocg&GJP^T%2mtoFe>KoED*VrvUiFYo8L`nc;lUcV&mgAVkSBwL+pV1GMF z{Zom^+v%rDb!P4HJIqrVal&|w*Qg-WLd0qCIeA{-l}Z_^qY@;}rmryO8~u>@HOs3O z(y&Q!yNnD`A`hyopI} z5huH#4!Ve%r{|r=H|o3W$#Uu^k)>Os`Q=fZ=VMvglc9(I}wZ;<=4W;0{b$j)L= zb!ys9&zZHuG((Z2dNc!%d)l_*^ZLd(nbU7swes_P^P&3mPmg|AOQS?6;-#pQeIQoK zp57h_;5><8kPPnpYToaRVx#}B50pKlBdK2YkO${Vpvuh+1T!gE(?{a}@)T-0%soOu@P~3MI#c3kUUC@@Y^fW}8mnAA?}GeuK2K^w zkx_rai&%2-&_LnzK_)?eK7s;P$a`UgYfFz0{lKR|K}5~iUc5$O&L>GQ5efk<+*WmT zd+|&$8Jt~%N3+jo7p`Gm%PuKxTZ5Y$*4#eR`V5E<=X(3?MXN-rcng>R>eD#6Y39a> z*sEG1>fQ}yRtvj6`K~Yo$RshuJ)xj0L3O!24KXP~rn-j%85`<$Jl9K_I|_nlod+Wnm+T+CGNmLIrVW>dW6B|9kn+atA*?;XdR`!_aJ-F17`|Fv zj}Ich8oO0u7b$wB(pvm{szsNy4%hoL72_XYbF(;H!dHSIaMIf#QC_ZOWX7(&JNhurg@ z7~Uqun{y*@ppiJ+>MWkAbk0Ed`l3zM-1K4Q_FA<0C-ZdSGJc$csUxewoOtrO$Bf|p z#G+4XJBzJ1S_cnpFE2Ok*M--i8brj2-H5vKTP-HHOZjD@3LlCGXm{`X`aVkJ{FtEv zF$H_5pLmg+D5|;C^m>WkUE;%2#M*j^TP5jUxH%^-&+e*Iyh{OIp3VSy-kc5$JgAEI za~*rUm2a^*x#g-CL#TCb38%IS(wTE$iXSED`7-Fl<8?4$zVfhdPn!Qxk0lo`EHp>+ zpWuqe!~#x{9BFInD-28Q*-k0E(f);*je@Tcp)Shh&%LK-+QkeiOG^P9n>s>J5yau) zeH1og>4Md-<~_Hxu9aTFiJzZpUJ;Axi_z@jCCzs=<8IQu6F zmj{xa{liaf>%%Jrckx2%ddY7<*2FJCi#Ie5w;4(4Q>Dz3z9vy(2WtW1y}|71ue8|tB()B->Wf{ z<**?Lq?FwErc4tUb*y0Ku;h`lm!;9@b332)(iP~k$E`GIRrw@NFsXdv-za_BHKvcn z=TiaMI6LyFRsq+$s~MjglA+U*@J;3?lDaNBxAQ>#L*eJIt0ynpk0(!03d?PHjs&HI zt&jdbo;z%h89C8jK4%L)1;Ted?a(gNw?RFnqt|Tgi?Au;3cwqsZJg?LvPv^tsFb$Y z_$3dHjjd8W`rC`0%pTmaJRGzcwByeGeo3zlIvBj7OWp>M1&8v^jSsP;z+DwTm*W5S zB%>)&E3`OqcfKWvh~- zQuYYEKoE$%{id~=V?N(FD_2L<5$iSfK93zi+)z2s#IM!BGE8Y9^|E*2{kw)mxgW7~ zFc+1M*HzC`9Iwl^d4B8!QMlt#q%94HMi<p^uF2^v!i+K0A1$WG)QR06>>l*n@d zL-X~QE*~Q|G#mZXnCn_VqSEQ*b6gi2^TaAU@^W1YWIX2MIkx^^8<%&*-OjzqX}hB< zrqQ%LH9EKrGuD)1yY-mNXi*fAaF2 zyt6+|5heQuLuc>g>G-=dR1yrTNslg3TzZ(MCbQ?AnZk%@ZF0XnI%IGB;xlqyLNV8P z-!5_6C3uxF5_+FB-gaM&Uhb`Uv)@ekSD~lj`DL8%hXnJdo=Dz-z!^iR`LKPfpih7B ziB`B|S>7u&5CB!s{8KbsvbHO}mOPC^wkmDpcF$ztp7MyOz|QXj_4;kC4x)7(nb@#o+Y)yPLUGuX1S7MVX0Na07d8 zy#44WUoi!IT1WnMnFS+8vV(RLen!Ld2FFT#D}7qj4Ox?f5+f=-9G38kSjuD9y%@nS z)rmZo?(tNjba#p%Fnu%zW5f@pN)Qcdb&5H*cJ)bRh&pp1_);Q1%2IU?*hdJy;afz@ zs{uw=LL=S|R)TEBgtw+j8E_>L!kl2~7m3};b=OXR)upKZtMCrfnTL)gquQ7ZPyP?X z--eYoX^d@H;Rp~-a;_8ja<@V_RI>+`-%l>{sYL z*8>C^hmkmxP@n>M%q{@Mx@zM@l6z;`Lq)O3*i@LPz@?I>0T`~S57 zrAHhncF-mbP=aKK6kAX5}p^2u#bv!WCBaiO0v);w+l?j6ProWy}M(hkyt2H zqVi+u7WYews$zS`j!3MnKC-e1%ZpzmeWu(n{Uf8`)__ zB-SkzPZc2_!_Ur(@)`#dD1Ou;-}*5?y}rvEBBuB&QAX~wm)b|+QFCUdoPaaq!#*kI z62z0vq^cy;uW)25niQ>N zrZ!1TZ62`|I6fW%v{DAuHJCL_faqGMGU>d8iYl&2*(v#ko<*XKOR-W`)5uaa69Brn zshM>rxAm&Na_xihQ>66G`ks+?6B_B6ioiN9(mquuWmbiDzmtQ6KW@-@L#_xx!twE) ze6lCgMM?m;jIL9vZ`ESnwILqntIFq+CI#C!U3tiY2ffLVG#Jmi^Bmp`T~Ide2X{f{ ztm&kRs89=Awj}#rJDQoGMpQ+nyFA+F=l&bNWDl~%Qy(NUrb3Mo*GbNmo$+R{1yaxY zKGKc7|044NRyf^W{wXgP8#38YE?v|`$NG8e_b(Hs$l5J6)u5ytVo(fD!z;=R1uDd5 zzGA}q{XYEy`^&nF0O8Zn+Nt**wZdZnD*6E7xFrdf+_*7YQb3@#0}3UnC=;S)>8Ty_ zyB+%%dg{IL9q+0GICfcToMX{W&Xg33vfFI749ehlqB_{^-15i|IlaQ%1H7QR@}6O( z>E){&o-2Gm#$t!SS(^Qh-k_PKD+_Otp~rJXO?_RxKCee(ZKev zYen6l;>hz0&r=!v4u&6ay9%X)--MZF41YZUAm?-F>5Gt8oK)oJ_-grY@pA(jE+XAr z*j-P19o#f2+TyOR{mP%GD>HBvS1r5Kf_gAxRBO2n!vBM@lE4(VwTKTfH%Oq1uX@Mz(?(gK}8P{}OnPy#B|Q{Za9&0tyItp@S(+ z7`OYKAx2u|pZi(A0^e_-cn&Txp$S{>FGNhrxq{0&C=s>shE{Mytq-H3Y^U&DueO2M zVxG&htM~J2TC_|WJpO*xyrkXOcBO!cgO`gL^N*A#g`P~4la;&XY_ zq)U;C$~qgtW-Zc&xEKP`4b+bkfK{KYX}vtuXEa)oAviDrMJ)asw*AbZ<%>s4TAVNH{w zXI`~2XM>&u=6Q4)q zNZwL?jvvM-)TGs~#%$it}YfeA3waNLT0YiN;Qp{opvuo z@Q037u*qjt7GN@t+j*h=b)Tm6?`0tq!CNuy{Qc{hnF~wUE&v|z5C=X7?Heo3czVqo z*AT$-vt4k%*v50n6B)NJ*|9BlEiW5}S2vElH%b0f=tYHK+|d`6u2c`#e%P zhpP^o40RLn+sL=IMH|&VL zc`SrI)%Q4okoM|-*~+Yel&40MbLhBtt1X(koiQ0P9b34d+tXpL+S*UGcyZFj0X1rK zToZ=AfgJKW0hzCS-M)Z-cra1uD;y&iCPXg4Ji^b^czK$eRvk+KywS;m~F+2K1pQh=+!>V zDwIx=gyj!vH~pYN0}1T(ug8ZE);GEzxF2S-)|N>hi(eS8`zg8D(FKcYf4~k2-j~ow z>3m0k`GL#ar4NuqKO}Wd=bzvhsHR%lBuS2hzxmT|`{|_icF*u*gT-|U0K_?%X<*VC zWYiCNt(UE=$H2?OMlha+9beJXLYV;uwJ#5MpH*D&@8pq-mNnzj3kwJqL-#{eHGy-D zptpKMhh^Hq*+x~%R=B*CNoX+F3}nHv-^8W_ivNb6lQ6}>NbHibyr7d{K1*UFN>+%7 zwx)V`+;G^)I&x|D4Pk+k%ZygEg56)vfF%M8?%m?CNbmy|t6E-s9x5HWZ8wob%===7 zt4uW(TFCrBj>C7>cY%AyuVfYkCbGx*d||%OFUPA6>MXgbt5x7&^qzN&t%(Em-dm?> zRfF%Y{>`N=e(jIr)q;oqM4(E#C>*v;@&y-)BwVjnC@nR3wPe?FfGAT#M#MQp%ZBpc znz7Q!9H>a^>aF1o{!U;^ER;iT+LC2(GM(_N<(#mnsu z8>weNg>nKiVSUFBY3j?xuP%#j3&>-O*ZFT0K<(R89LKIOKPu#&L&8y8FAKZ_gbC7cDboZ+9}1>big=3Vhp*7$f0#y3ue_r z_7$_*i5nK_Dw1?3F&XF}f;FJ@=DBa+^u)BzZhxbeGkd1~CuLgxNt$AtUijVj=cm3d zc2V-@Y9sC?(x;}UJN>RWeMUk#GhUUitYN8IorOv{1ZhG{NPekF5}3Z>MMxkqj5zF* zxf3F;&?Ys*IDr)1v?A-yqlvqTyO#zpVVqP{G2EMGCat9>U+IvbdLK@#-?Vd?+2b(Z zZ#MTy*+x_?AUpl&g#~Yqq1T|W@l$z8tRZzxW^QkFX|k^lWG+HUNUTiN&OcQg&k3yT zUZG8qOAZR60rPKm8T_(d5F9^oiKUjUhT(GH;X~G#MR&2{6^`Gxt_$PC`Bszs#}Fc8 zx3Y1(8ycfhRxLHmAxyo$f!vvF@$g9F7z9tsL2VsctAe~UP9Rxa8G*y4bjX>~ur2briM| zN2rNQgymtRz7rD@Qa6!Dr)dx$c=IO&m8#-*SlZ5p!`nZ+ek5KmLK%)561xNg7gKNX zh+I;t|2CbKP4VoFn`R^y#V=NXR~{S4<=xYNI0dq*5#FyISa8Ov1`8x6Z_@3#ezii` z`i9puN`I$vEJPShkpKb(gJ?zak(}i)NC-Pelvk^y_o3X4=_L4u$aq06ts-xXs)RNm z5G&t{D4Y`lP5Nj{lD-zStY{u?dr!t16cSH6gru|~p!i6`ntA z1|d<3tmk>3SVg;KZQwjD@5nZ*o4H&V6+sUnF}See%%9bvg`ZyGTHD;Ek!8T#g)PU| zp57XV;Ch}VSub7zMan>#v%PO(ZpSURLl0&AKv~ zWRRl03on>Bmo1*TGM-EMkJ~Z_9r-y)fa{pBYuVwy@xl3Ae9n3TLoBKQTNf;nZsN?q z6w%c!mCyzPg<-Aj^FH0`2X2Y)8xUNCxd=YYSMO{mP&Ui1y3gwo zRwlgc!PB!-pGg`D6=xx@*CoKh6d!DQeoL8#7384Qp;0x{Nr|DxSKu&vx31JfE;pTj zGCIUM0X^K^vz&1}GZxgeB?E4}t84&o9Z689Y_{SCeL*=}_mLH2sag2+%?gCO?gQQT z%S=>UhE`_fzAb%VYC2#Z*6OvX&#m-K6g)0VjE2_%~M{t!Y5x5i{Oq@aO>6;;g*S6npl?ix? zG@UmnfsPo@`<50ERfRpU*xzyP9p5*N_QlC+c!W2+vvIK%v@=i*;=$?sw`8=F!+911 zcWO|Z_8X$GV-H@0d_Vf{XjtLjMaEHSZ?<-^CoQF~YAV}^C9wfmd@}1!LIV7oB*K-! zc0%UHe=kh+`t)^4?gqa)G|kGGB^+JqbiQDIWM5FQ%sJyLff*^#;r4W}$^(e74;sbs zT#&i0y6Wk6mnwb5fByt^(u(#BO-h}x1?jJ?ab|bD*Fs`Jehwc~y|!ysb{hLV*+O3< zI3TlAQh+eN4AO<#V>23Qn7{=>O4{QWhU5CR3$$H8;&-G%PJC?8@OF=1J+O06a3(>k zaV4>y0$hkZ@ z)!TFj`dB&vB?;%qn`n~()QSc_CIG^oxP)nN!YbXKTl9*2T-j@?WZ`YQr;$VUds&}n zY?ezy)$!m8H40mU_xqzEZGJE3#M(acsp!u{nN!iO<(0LAJ)5~gZZVP3;d2$m4vh68 zE5zxlUQY~hRK5cwb~9}q1CjB8o5(#F#o(s(ZN`8qDu+ny>Ie+B4<;{7*U_y*v!B^k>GS zrrdLzQ>;f(OS7^%x>a2Z*nuExrv@Q@ja6*{nX3IJF=5tk3oYNIKg&M4Jd;b|;?n|b zUs|T4zHU2}z}2cDB7ZKroT7dV8>Hm?GEGzsoB9gWE?;rub~&jP3e@arSO_m$VDlv8 z_cVbdk-TAkbjjD3c>)tY>wngC**vA17}PPB%>r5=2*|oYU2dktVe1v&9%ox%4jpzX zE!l+;l@72!6CfB2LkRB&`*ghn00>{Ti^Jr3C!G`Rc|oGj=4n)NC)0n;W40^-9AEBP z$fi@ZBn*CXqT%npDy*YmArItOS|qi$1A;#6AXbQJdB(+68LLu_f@*ui3uBwJvrBQ= zZ6pBgaZ(`3W*G^NM-=_gW79Z+h!Oo3VzCI|5HG$rnA~@f6G@VpJ>F`c>l(EwhKC}d z?j^I2>}N_Zkq=4$II;!7R@KCy*-*p;XWRK6!PVKNYJxs;ZQ=v@AyyM)T9W80FdGA{CNTwEaX5!5NUqBX2i79E}5w$VG`|hS-fI;g-T4Q znRMDVewT%^9l11u(CDL$Fy{26+Go z1cX<~4KphVsqg&W*@r@3;wKHsj)qdSKp^uCf@K)N)ZQ7z*}z(y?1~$S*M=yRE$R*z zYjpWNU;?CkK5o4&-&~WfZWIghx!N3HHP(O#;XFMn5WXClx`IF|#lKBlP|EQuy<=d@ z3%8;E`kyo`%{M|h6F))AxKP{o5n%K0AB~XaXWu*pe6gU5mRJ2Sh}+GPiZOtQ%RHCR z#Vl60FmcTq=N!%d%4nQ&ZX7$Bw^<7*s#n-xb3$v$6dzLOFNslz1X|i78H!ugu0#b4Adjvx{kIoVSLX@%YROm(mQp6t>YmVSagv*y3W7B}7NP|&4{Z&9+FZ`P z=Es^Qu0G}+nBT&qq+;fP zoYs;F8Mq)ebk}acHorKBuusjNE_(kO%}wO_(%;DHQJZcLdr}uXb_L@V<_3b_zM;Yz zIga-~P&Mnz5M5KgFANxn1}uD&Y@B#%6fLJoO?zMJRU_W^GAxi+%-JguIXK%Vebg!4 zoSp(3nMWXj4i~>9O5#wi=AnHbR)_tWHcTb9p%0$gv`1$#pfcn{Cz-^wuZ&@P*^SFE zPr$S{9%`Ds`ZMDdmqkci|L@`v?aVWPgJV!Y{@-Dt^9OC!RPvTo))7ng?xA0&B%81G zf4>d#MI^y&q-_N1xhP%joSlcRfGDb?BVd?PtjI5QziRoePA-ixr?lkzIF;SWt)YL2 ze9O})-2}bHgF$Xy%Y6}#$?hSJ%?WEKL8&H_xk_-Q-J99~V2F zX&YePhSPfNz1l}>JF%Bj43#G^2$+^IQe53N957m3{1#qKEHSqGx%BUPZtuJIKUDt$ zoOuF+Bo>c7#I%c#OY)@K*-&z*NA@1itQj3T4pjHxtP^Vxf_^y1bJc^R}WEr$bah%!AmJi8EQLu;ghI4 zHkiE}ISdr?H-C+hOVr8_P@22L))GBp2s^obp{H@nGQWg50UbG+xoNFZ37l&tH^iWKk*8q^9Xl+XZ%6@w;RxVh)$zkV z?O;zeFVB#S6d@<@mV^*Rbx(FhF@yCP2^Ah1S?etYg#zp8wP(E2N9wVyp+EZY>`|-i#<38wfHnH(`RQfZ*b!+8u~lx>$?Q_rHW=fm?B0h0 zBukrzJ*mUR5PvkcH8XeH(RryUt49$gOm~MNVs|}JGzuQ zuy?dbJVwf40HlI_YzqOJz*0qsPaf<*m>Z#Bo;-=23b^AjcbN}d6um>weKt0YNWR}a zw8i7Guv%~tjk%zpIr}x$ORU1Sby`56$R&!r_gK`p zTp@(n*NG<>(f_)T@oJP=cxsc&AD%}d%ew`r7WN*SntobIW1kSdX>00!$7DOGju*xu z{hiL%%l^D`^!ga+GN?eqC+-&uHkc%N9iZ5EcYBep{b{Zucf7UI#V`ESc;MBEnY`#a zt~#(J{T7(`;9agY6KP*}OBB7In+g+%ib4K|&@YobD_cv8AceemJ$ozAn25VWTZo{# zgPw_{w>lDtnB=dVD!j4`o{jaIv*q?5ozwvjsT81byTL)`9rk#MHjBzSIIa}X3ZN=I z1SEt=vn?rKY}ca*X{8*1p<~P0Lfo7_xcpfoTffvvTQr+$^I7Vd!DA^}+6cWYF7bxF z?59(!(F-5Y#clA|S_Gsu9CR%0J@TfQoFZ(aO zxI|k1)S3wr$f?X9&E5gMzylfga9NR54++08P_8k(c=)mY)4V`EqA&t6_Wtv6hI4S? zvN#Cj>cIR8_ZIzwDBA>82AO8qLHz*|s4B3ZaQr=C8CELAt8n^-r~9@q=WR!gD3KyV zW>pZTQuw=k#rOGR?-?QUk^Z1GjoU)nltHWYmv{#JMYWT z{hiG^j|wy;ZwtdHtt<)k1zTDiD5_EzhCy`UK=q9^j8oG6iYJoDT4U%~?_$grzy#Oyg10J5g;qn4F8Pmb#6iqAWeIdMa&WuTD9?9RDxRZ+2*#C&K0F;&OFp^r=+z9Clw@`FrTS zFD|}zzPvh}Zb*e(0>{!4fRzC{dfEYN+j)g-PBAf#ED#hP!D5`1;x}#jY0Vnk57ylG znF>y9lMbnRm1BJ;@i{Kc^n=bK(G_yiMP_|ddq?nwEf1hw!_x2*Y;Hle{+SFT9RP%w z0Vo^;tWqGEg+UTHatAkS%d>Y&GeuV2K||Cs*d4QZV7_&BM#k_}Qv7a-KT)n$?fZ&D zkP9`z&ln)F_`#wPPVszO7PC0+yrI4K^(jI+E^J|Wv5R9MZk}Y!o*!ls9~JFH&F${O zNJ^(uR#oE!UQ=I<-IZb@f!YO9MxVp6fgrxfu%W3;M?zIrA&{De2>DO@)LQ@a4~I6AQ|icX(`-S+*Z z{YkIKR4)2h6~y9oAryo&N9!;L0fLIBemU3dA`T0s2e0jv4)TYDW2A@ZsZ&N-Kz}OhnZX zo{MgN;qYaJL*l}eI@iPUMA!#fy*H|x>pdV;uJ!;bm}LkhJ3>=4J|D4FhxYf?y9y!_ zlV2|er31(yP=ydaoBjyv1JJsmo%~Rc&7-FzmA3b&xHrG~L)8pJVt11)5}VypH2}%s zca7!8$SR>3xoB4;x_5>s&KY)602*p>-b8G!Q0^(f04tHE^$H3{@b^vT8GEm7E^3`?5_|M(F}A6Rjar_R)`6PwlBJ4W}JZ5(vpF@wuOx_nw^gq%ml+D=9Mc= zyL~G8;XOO%lNRFsrtDU9balmDBpdHJbz%AI-6=O(BLXM&a%GN|7rAC7drKZDdOX?8 z=rzVKV$;pyuZ*)TY2>|5f6<1Z0}i9HEfu~!_RJHd=o7)`s6xk-!C?i%G1|TpI7IjG zw&hPCU+R!G9cSQ>s@E1Gk?@y$UIbD$muf1{eR`s)yS6yUkM4sA-}HEy%pZ=+)kx{I zgWR1!8>YZY0x2>8q^_7ZL5c*zfmw>7zMqkSpo+J~#HI?&K$3O!|2W=s0z3cAOZ3Kc z;;2GglY+EQi{;dBZud2FYn3yRAfumgC}SuM?*22j)gDs({n1_Mn&&M55NPWf!!#r9>N z>aSCH!cW)b$gaPW7o^#{0KTw^`gv>eB`*SHXCT0v69ljM)Up!m=?@St@);l|uY#cWI&ttx`U~_LI zDw+fCP^za@!quy-v**A#0nkN}!BnWp?bE(@1ITx8VqPeBNl`#N8cso|I;uLupV2`&*0_NaT#@K&sm0z?Q)9trs)CI5 zE)9^QGFl`_F3+K#2Tl%BqgDZYCL?4j-z5bg)9Hj#$elfvVyestSWgab&0H|RhBs=b z=j=DBC_LWk65y~rfW>VBEV9s<2Jds{-nZ6VM9^^ehmN%c=2OLk!6yfgQq5lT)xPd% z`vgYOUT~KYW0S{E!C(3h>K@MORuUX84Ai zhsbyJQaRn)wcFn*i;U>@F5^J>ZUh7LeX9Tx(zz_IVuGQ%8mMiR6Of2#eYCW4hEieO z6LvXvn%HOun8|8bwMWz>iB1VLY4N4l&r-&c1Y`-$)Yf_Bu!3p_;{{C{#+A`?u))ON zI5%0SZ&tKHAoA7}3GheWY2Ua7{_v1@&Tg9JDfZ)kNB1k_C_G*ECi8Kr2=El~42e1s zXz78j-#c1&<+^Nf2+8sk)gCMyho{d^<IC%QFBAgf+?x{A?doT)C}O$1QSoSny$*Z}by0FmFHH*x2PU*~|EmMwu?5{Iwl zhww-~HAT@{)0Mts)brFYeev6OE>}6aT05nMpW;@()=hiu@(Kl2=YhVWusy$cS=fj! zw)=^;3SVtBYMlmq#fdAr>vmLA=sM5@GODGp_jsy*9UWXVtx z@cgi4@or4ynxE&^pD1knZ8Zn zp)12~@%bx>-SbSG;OJRO43fyW*z$16{CC>|Or0tBl%nj(L2W9<-&P|^kliy)gAdon zYGsoS{hU4CC^TT{B9900@f)Eas6x2=7v_aF-1OFry4TN-xlxdA^VBFe<1XDl=k*&2 z3VVTk$10<;wrB4Up-nXqxq^KDrnsacYrDHq(^3Nr1lN|j@BxL8?7xNw6@@NLn;Psl zL$F}jM1J*|rR<~oVisurF4br2u5?93p7EomF^te}1`7Vytdbx}0_%^M4$&z^aB4E= zB^X)G5Rq_!J5N{hWUPSEehes7-t50M<=9cbzb$mI$Oib|V_9QG1G5Tjm3y4JpDRtt4${eVM@GW*{(HdRXaX&aO1ihR;9imF7Ze zxHsu~MX=tly!t#WZl0DYDT6Suq__l7{LE z`86F%$2*8`;B3RMOlv%EvFe?}@osy_aG1mVZ!fR^c>9K?{_R~lvHjOU&XT&~{^>pp z-tNGuTqc~CYNa|IC++Q{LB_11;o16^!gNbcGYwvhU;V|%Q z7Cs0W>=!Iiy*ARLtq4iyj&&8#Q8Kiezj&b%=BAk4E<$`}!q~ zS(M6tfdm>^9eRoXmWMI?i$^$rGIyuJgS$0XvQU{HntiUpjG?3Hs~lEe74>}RV1>AA z(Nh4|1Ds7gVUT;!f-NqpAW$cY?=15IWc9JZ{E;WrT@#}MQQ=83seHB5bfL3%{H6-#CyOT&#sU8}h>qB_l@)QVp zYzebBdXVttT*gJz+P1=httgsAc=Y1mq5amSF=T$4POu^FLgGJ)ApmHTQ@iurkI7*& zYwoc(m9J{bjVCwb4@ScVnx(}qxMHaP^S@b${aKzRJ{xgxhBe zC8jHaOw7=1GnU2K-XgYqJ|3?V?t22sU?DLFg_|S<_{~q zF?4lq9Ku420K#LSYOx-C3fTN?!TnvE4UE*? zZm!F=rQ60!F2d0MxtDs!re;176Tt_!^D#UdNgAJ1abmx>Z5uGF8vJH8G`dse!w5Jb zfMK#)%{yK|u59k{q<_#j&SoC#^kn*T>KclXm2h-;Ulv@NaCH0%EDme50A>P|zy*f9 zh#t1+M0~SwPrrFun4?iXY%nvKhUqN{w+w&RJmzAIeM^XrB3?z+?)M7($+|z@%TS?} z!_oLchW8wKMJ}5PJy$B6qsNKwk5|4~epA6raar--LE-C=>I|Q&9*P7#VcKBHRKjM1 zY!^o@GpTgGorjeZuM90+(Lm1LS+xdr&6G(XhvvMY#`TLJZbowg$7|-R4&0SR=j8Ab z_4K774soX<*E|8;<;P|WU6u??fT^_x_UG)4g}$CKtMlPHI7amyo4*L2?9h}N8tS^f zdPt^3S#_-+oZQU>sBqYFCt;$V>S#*y%jd0k6l}$c1ehH}ur>l>Y;ew={YR^(XDzdw zE3IV9><4oj(LX|L*=5zp`zX*C^M})`Et8qs`C)_GLIV+7N3y5Q%+20e?6W=H zxl#%{v(MyCb4R0&@C=iihI|rLu}o}7o~3_X8eWPXLspl6zV){;2W|Bx`BUzn+&NK^ z2y0;&A6VeYM5Y_Z+oMPj4Q?ZY==w}j`dx>wQcI}6bvVr$c`J4$>%IKcOzH2b7$Kyd zH(g2v;vgRMQ#4Yrj0kFHM-+z7#0~igrzLqkwaxz*3Op(=l%}U|?|Qk9j30nY+LppL za=`0j7pusZ#i0L1=fIO{`DGqny_eApoRR4oDo+(q#)$c{rw0nR6V88QAz>^`+KnGa z`8=AwEpGseCFD13zutCre}*GbM!*337^KdrcM|6aRH?ex-z8@944wFeDUSO(hxi(L~9n-(}gR z^hX|aJi_;n-8J$TK?_Q0|HhiulZueBMASlRZm%Z$M#E9MME#`=KEQW?sgbe`!sKXudIH zcJAA4>p$9k)n|7zeOBYS$CPf9@F6|k|BA6|5uQJ7r_S_bt8t32G#+NU7-FnQm#OeDyoW6uLJFV;qk-YfZTxm_Y*lyds2)Vsb z$eg7U%xebtb3#7suOGY3T~$sSfC7F}bySn6GAemwOfYX`|Bk=1{zX9^-R5|*IWy!A znVyi{X?vJnD-XC45qx=iK_Xu2jWEM-98Ck#OFpNEHBRefg{ehLBz`+jCK--#O%4ax zC*pDUcp4H;JT0CBoB*Qbh?PCnB!e@6)xaJ?*qr2mlrcbVJhx=&^Fisb;T*?HJTMB(W% z*KJOcnpBR~)DI`yE(i1nx4TQ*;d2ie$I8!g*ZYZomul}x2GibQG6ky0Gcb~nK$!+4 zXcGRAeb39Sb(3IBwO_#WbL>3woIT`+q*Qd}a+EsF97oo;Gl|aTH;;Q3*?JdWT0#6C>Ji&q*N-z8jHLN6UAtiu=?oLvgMEMr z{Y~>Vx0o&qu2Sn!yH%3cq-O6R3bd)Ur-6TxV^HgahehaJ{*At=;TovFCUJa{VX$g( z6RcUj9$vsJM=Vf>S5}qA!~Dzi-c)_qX>gEy+s(2sz;lb%E2TF*cTTJqtP&q#DWPgN zLx`w-U1G$j85IEFt^W-Mu$tOoqG9zi?0aY8e?XB*8Bo<>`IevoDrDQ-J~H>#oGWP4 z?6uwC5WfvYTD%HP<3CC(tKOR9P9@tvL>3{tp#F8%PK6_%;hK*tQ9D>seH2Rn9x&20 zs+2mpIIHP=zTK+g2$`Fo;vk3jqN_4>s{B}m6eMtR%wk$!5>ZtYe93bZ`tF+NpG+N5 zRkWH=8{?pAK~k%dFf$k8RuqYrzHx6)5zCPlZ>Wz!g<6!a52LZkDxd<<_MDlY(dpkl zXIi2Onh3Yt)kQx&2UDL)BuaC)Ci^`2+rgOUnkm;h9&65Zs~tPhdo;3WXC}o#F%edZ zDxcQTDAU52lCFiJO~kWLKLfudgknMdYWrvXO!$>2JyV7jZ`d}FU4~zif)K3XftHIu zg{TEVF$ctbald38D4xm7l4+U@w##>6Kx!0o3IAovl|ZkYz1B0Ck~Em=j-{^8>#ybi z3`_kFi(^84lmdWv!18oL=D_+kGRho&Crf1VU#l7sHk`v*Evd*+(g;+nh^DmPH#z@U zqDX~Rz46IfwU6E~JR!x}rrtXaa#q>2rImuEt2i`eI8i3#Pf+@4tLJjOs?MIK2HJ2y zVZ)hpszz@-A{4<%WYye>)@~5iNsxmxLP$y#5XVWF2ZV$hh&i-))!}s?9>T7FWgJ_9 z1_6kV{O_meUR@U&l+0XPJ2&64Bp(y&BNRyLcKcH6#BBWs^44154@?4484&*i<8pBh z>4FoJ07EGipP6!px#df^~#);AH!n8m&X9~jqRt=w$Z+k)L3d8ZwKnf4S_TVlJDk@q+%*` zM)okRKnWs^z=+q%DT5WmiCvKI(nL5$rZdRiarc~YP{RlwyTBpCBVO>2%8j@^)lkO4 zZKIRG?Vc{`eSz92)(<~Gd`%e-O8YYLZnqu01mbaQBg_EsP-=fsMgXyaA3=3kaq${R zYI9d-V*{cVcjoA1z!9qBlMSDIe+$#^SBxaOIJ09eSo3ef{6~~an3B|X3pcb$Ti-Wq z?>Nnx#;^I?v6>aUCo&+XBGTRdLpa{yjq8-mfKa8|=jfxCk*q#p8!6dJHja?WYeADM zAO$gIE%^!{$@N|JJdxsa@iSdCR20t*EEK(BBf?g*?4!@Q8GOh{_5XRS!3(>nDiTZj zB^Kcf3oBHBKQmeBnN<0F1TQE8DrM_EqBJs}lh?mN6<40Lc{carGN_r)fHKHapV*=8%AkR`!yUc%*t}k`1clqYM8?%0*%ic?)yxvOFb1fDQJ_!> z2GspKYmGE$-{b2(p%PZAkvE}v+{1}BNX$LPZQ%f5<{rl~rkDUF9bl3N<_md|V&P_2 zZaAf|yE-pE%p3@i@%L>Om{d~*Q_xd3yOy5$d%iAL#d;K7;-#zu5zsPzb{ND#mq!B~ zUc}9d*|&C@tCZMDJbX>I5ntp;1QFCjoP1^uS`F{D==lPI8JW~b99nNFrw#5(^-=&Q z$D_(1BVNmu-gefc(y<<+S$S2dTnMIXN{Pqw09V$}qryg1B4yZpcYzPgtgvIv2+YupU8emH?UYq)Z6FAZCC=vx%O!Zs(;E3MDp=wE8vV!2 z7r|SX#yxuNuJlgtR3S{67ke2&9A3}TCP}!-Ue_^*j@4xE$GUBl4VaFMf~k+Hi~CmN zMLb-4^iFsgXoe;_Gn?|6)P{>Eihgt8H|V$zF32^(gjbs4*}o76qsq~*4#cy5x`0^- zTy2klR-YC2vo^Br*JCHn&GKh-CwY>1{DKxu{?XzR7p!MHpiigEB*@w|xVD8U(66Q> z8novCwKQL=B3G#v?iYBC(i4ut8>T-tjG$2!eSn5AkfN&+3WVh6?f-GbnKfaI2|cT< zYT!gF8U#Lj%}@zr4SSv_deU-V6IAuRRlMkWmUufC#(OT9tj7!xruza%DZ=zS0D%+2 zR-5y|#=KHBJ=Sy1STk_AXsc&|&}Jcsx+tYRl(AGbeSGJ*>x;`f6PpSKC=3#($?`Uu zK+}w{vLw~IQ8?D;TImB)FZ*EJIWfN9$@NyLfae$wR}9hl?W|Jl#1;{StXobp?Nt={ ztNl*Uc}&@1VPAf&2GaesvLVn9l9=OaFhZ$OCfP{VoSH45+hb}`b2-5{DYhE7ViSgN;iD? zx>?ABHII!BU*C%#Au&~!F$$tI2$x8xa(^ zA%ElkR%EwJD=6dCh^nE@h_rcDATGF;9LZgp#K&!VTq1uH5PA6zmSTZHDm>x|aJkA9 zXfc4f+0-<0f--3>gaD&zq94wip>sDiL`&1KS z@R>zpJDr%_Op{^4wFCbP)S{uqQa}vH46v;|cnS-%rOUJ<)tT<>IDQc=0UuXFQFpo5 zPgX_*4s#L*uObwNY@kw9Ix9_PGT)+*P@uJzhdhA&;INf9X6I-LR zmcxRBoyTx6`@}K5RouMm{Q5NxlEN>zAk_B&l!5eyTyXZED!~IH8v8Dp{#;_cklJJ0 z*8@3ckhX|k9sRAx`F}G54qN~muzn$TxLKN**E@EL^n*GJbh!ZsC#mEgX+LHOrx;1? z>n|cddup3;U_bb5oCyFVThjzS8n^=)#(503)i*XOb@H_>>b=TDQF7dIlEQ-YU79Nh<%{?Hntu_}n{KSZxw4rip6DO7BrT(t}lNyrD`M7EA?^|3ij zSll@=r_1(~sT0aC9dI1GbUv4&hoDL*r8G8@4yo?5r6Z+&B6c$z)p};s0hU{*fQ6t*A7&px_Y4x#$`9|MWdFiJf2lRrTaWHj_cZgkn<12X(A z#kZz7*2fdKPyjntl$-lo8(Uh!WXSVW=0IwTss`8QDduFt=#PqM&NLHrDaKT;O!QBh zYKbpG0CM3I03$szdO9@6%EwY1Xz1WJj`q?DyiJi|kOrmE>ev)~pK~O~jsnwfX9#>Y zaApx6*6gJ0NWPGu!?Q=#85kK^)-LEEdM}}3FkSSjZFUfuc5ESR#$?j?Ge5A4&Z9k^{U-*_tb%is)*y~|QxNnPuP1uG zzMAId|GKxylz)stsekdY@X+z0L1Ci|Q^`!E99McNn%{c@mUXZtZXo)LV=dn2uPJ_! zHp-`QU@~N7y4)Y?F0^{m0$73dmR_W}_L6A!;$23NpJ?&`TMsim%JR4PZog57`())>7Cv2+3D|+97#-zX%Op%`!kN{$+ zC#EV<0!K6_2e!k8ou1IpjdiNj|LAVu^z}-AKlVBgse(K?vx332sAD~A#6B5BS|g>3 zDC0Ho9g0+4f%S{D$Md+$ZE@>e+Z6y~M4%4L&vt%7UddN)SEc%F076=TZ_7PC^N={8 zHXk)!I}sGmTvALg9)Cu1eYeGPVI(RBD!99PU1xGI)Rwz$Jr3>XV*~}R?YGB}<=JW3 zxsWRWm64DZ7>HG4z5-W3sui`86k9f^`9*Lw(9J;Mbtc#0a-WE9?o~*n`)@8>7)~AL zXf*OqV)N^E36zWkF1zP@jUvmhNH~_83G`P-seHa{cs6nhGdu$4^@ZBKZa9STiurc$ ztL;-CM$Hd3NTb;wFof?P0bd}fdzC=4sbO=ODj08zDKSqQ@|#f-CQq0LwlI(^fRx7|`X@ZzSad@Us!znuAH1%mj}UeM zm36KM+d#kl4zlzY-0aBBgA|zd@ZI|1vXLXx3qVrg#RI2`8QF0mpPOV&0bCTCwnkPp z9Tvz&E+3Dz-B=X5!Kd1ZhH0Eet8_VC1}mOu>_{dpKG?py<)XR0m}g#X%g+y6gZOZt zF;DmpCY;9yGPs2+5cvJZqHDttD0m{En6wDPl0G~1Ps7FQ?Ib3F199^7{Q=z$YTg*} z5=u(Ctj{}*07EQ4S0e`=Ni!{FWn z?q?Bk1e$1%JooH~j|;l)`A{i}dJ<4HWol*0gO0G0=FmJffL}oum-X*1H^PE zCfAy^3%tNmg$GPh?A6`kJ;)wpxtRp+U2i;v*A()cg;@>mq52|=u(PAZ=%~fkGBfK@ z{%w&(CKam~W<7}rOZi;$oy1A>QCn^eoYk0O9F1uqM_im7^4Lb#=7tn0s6Bp>j;LVs z*&usTa?W`83)Mzde(Y@5)`|o<>vxNltIRoY7W>(LEo`i3HgUxA1EhwiVjFkMs9^Jw zEJFW%B-mj+wliwc78hyM_&W+;E!F&j9Q>>ty{U-bQCj)zel+=Kkse}CtO4Gn54^rz zUU#B?%0^7+m>@waE5A#_-zLcVZyqZKm5Nbgan?^!4NdJmd^Qz=9r{$khi9|WVW0Yz z342WBbj}3pX>$#Sr zu}1~83?Gx#+T;Lm=2PF=p^DXHD<6CHivoN+P1y%N@~*7qrqRpc=ki*iz4@-O>X#&q zmUr-pPr6r84wKhiFY+A+?8~XUihemW^N?z_RHu27ix(^HR1CPMhTky%SP_H4)$O_2E2OHNTCOH06!Z3-PRVXD-|}b5 z#!RHlq;w&+ldt^=oO}Dc5EQ(*jjJ`jn(G&*MlUIrfmDN6Sm-`~@msTpSzkxT<^b{1 z%Lr1)O&Zc`&`ahUp1FlY5xc<~d-OD8hkL$%!IG&23QcoUhxYH$Oi_)J{w1%Pl;jlE zc)D}Z0!Tswcd2SgQu^?L38Id^I7NXu~&;W4<} zhE1zVxbB#0eRF(tQC5vyo(Rk@_nW1CV^gU;yB!<-IP%RE9=|mA7hoC=}MdluzyPr>SNfb9RC=rBLUK8 zV|RxOCy08jvuXjdVB3m_vm+l~>SJ?^@AaJzC@m|gQDU?0Ok%DFOm>B^p|d-au~trB z)^toHe|i0G+v-CyqVbB0qWcOwy!3H3v^Ij_kE%_d{QQXk@is7cP=IZ9x5g@(`A^=# z*7+}zk}bgAlwPQjBd@wXX)fnB)0j44JeFV$O->l#TdtyAxzgk{xmmr}`eOvl;9Y$Jv6FLSOp^8~Sre4#N9s2?LGVd?K1 zV9V4P29mf)ZR^hPft*M7-ettfOzAQpoU0mF*5nA=iZ+99$s9%iY>)lp%Zr%fEZ7|t zI`^TG;D?`qaUh3OuyH}&v}>6j38ox)7Go>q?DYOnp`0%YGehC1Raqsofxlx|5RcNN01jKFD1nW9I8e(2GU`g6*}FHxFe zfZ49T2BEuE{dNdw{s5NADq7HW6~ZZNoEA{}0;i3Vs98t-)c;jQmx_n3#Z+qS`DxTg zChQ+IXwCl+7!?K&pon{~IJjhS{fennV?zueIYI90qor)Vx*Ea!HfL4~19kz5)sruB z2TWS3q{lUqD5dJHH0jxzZVo}58RP^SMJF_v7<#^pDH3F+`GhN-E6OwNH!ZU5dmtpn zvAqfuJeLmf_lWc;tQ0;TJst5z!QCK<16OI%r_G!1RqsPNRtIsu-2YUE512Jkg?FCP zQaozkUwu0o(+tu|KRQP=&OGfPmZ8{xsbVdTLhVc1eDIW_0O+)4?+xFynbUtlFzCWl zYa7hj)rcwZ=b-)KT86PDK_lu+dFf&FG9j?C{|YAN*QgHnoIBm-`AKWPG)1l-dh0A2 z1FCUsSR(4=o}RoKL{-)ly)kJnCVLy9e>s9vyu$UaCFg*uv$H+{Seoyf>u2`!L>7(No1r0jTOKsdpr+PCR*7gcjnALcs4kb8MB;i+v4Zf@5OPQdJr_T zSyP+A2|dZS2G)SjhT?4e4$=mRe8^|hnW(*gLw`7`Ab&Rp9Vy7!m#QOimT@t*a2cUU zRk%9rKkWSrRAS$`mM|~L5G_v)^Kk@%I8&gKq^1mC*Laup|Kz+125t7~eSF+Zz3TB3 zqflkr-K!Y#!o-nwt)%p)Z+VnM$H2G^8mwX!eT>Q~-X{0qwQ}$Z$gSIk2jzFSH2Ta6 zB)XB?SF{oOh%x*lOR_Aq9v2G4VKDX*d_5^&ZpPJ&c%Mu+7Q2T;>OOQ*X})5FfW!m$|uac*J2jdcAH}bV#|3YaIOz7n`U5*QJ}P- zzJNuu+=hxGHNR&~6D@<=MtiMC@l2f+EC~>bY~JLVnMPwR(F5j)o~>^Bs5;O(3rd>? z{ZX?gyHng4Pm2pmOD?G;z*~y8DUqt6$l>wAGW#5E^%f~8T2&miZ=u15XVkqV)e-(r z4uUrgb_QC2CX7Wg^RH2teGX%@jQh!rk=(t-01`q~EtIOO#sywTgoU*N4{z>7@TH^M zl3Rd*?<{!KSf9xH4q8N5)O4=fy}x%F{^fq;DrPr4N`gRMg+&rL$cA_&Xii<#l}@`R z&DcEsmmodIbR>WRclEP<&!w@wcy!M~qkXTH#?hx&C^}p2L1%v6l9-AxRtZdYwv}JW zmCi2ZJuB$T{{cU_goT@t$u1f$=;Vi?S?!X$1X0jCF`U+Z_D|utT)$4gS9Kkqcj1dZ?*$S)K6j|@pwS#7h1Gne&M(@}pfhdr z(>c}&k_|Pd$;#4{OY8CbdHV%Wzb4`q4ZqCECh-Bc*7_?Ft#+4+&-!3v zqWiK_5ehx@zdYOzy}p%d9Vj`*l5l{MwkBF-7#<6p2>8epUu6Hh7UlrCz|Y6VkLg7o zI)$YQiTP>H*|gLZmQ@>GjkaCB_qUnjw+%jQX<^&{nI`>8ZvE%u?5MK#G!xCCKmj~O zkr1FMw=&5WhJEF+R-)SC$jsurv~(SqM)!fTAE@zwbY|NsuaW%5f*2Kv$;qr?mQ4QjFlc>dhrd>5u(J~EM^lCZV-3pwB*n$+Ua^*03EMi`Bap6ZtI zFq-+IB`}@|C?>&Bo#g1|Vi$*nrjeT+ROIDKCAN+9(J4H-AxpLW_W?{AWCd|u%e+f+ z3EvEl;R3!Ecn`j<6H7%j-Hhn=@!MDEV-F$&f#pwznIVT0+I+dsPyNt1dMbHyM*pdD0Db;97~`RHz$XiLrO<-qvtu1b$DTHAl;+b$zYJb{FQ zvIO>my?ttdiNK&YsW6jdMMwNMD;QXv2+h|5(B)ay1_*^YvDM-{Xb|BwYfRVxd&V}e z765mXvRSK;Z*b#P?==c6l|iP^4(>u9yBXcEVMa-`}13ydf66n8v z33oAc}(d4RYgrWk)R8FFsnoL95dj)xm* z*P}k??3QiEl^Xngz&Qlx+8w^)d;3|EyyxzNxkHfsh8-Zzf`i0km1@&3Oy%^)^nQ;w zQ>k#|Hk3FG>zS-{v?G-`>l6V_zXOdVE|P^M1@#DofQprACw2BvUSn+-RgyTP)rrRD z{f}xY^>nViAQ5He5)eSbBgT}jI6G=wZRyxlR2nJnOXBcL6!C>`Y7;iaV4r&~Z`@F_ z7@Z{rk`hUJ8pi6!#$VBEp#Kp?6jJUfHNYE37t2Jd8<>b~cRGKe;96iU- z3KP`Mq~-1wH-@`=i#EDpDkx{k87%Ntxo689CS9pUsFocu?F7~Sre7+dat2LFKTLL= zu0FEDw6gZbZyNSNxi2+RPMbhh#CWV>2lrc_Z&=9k^QFc|;N!l{bBp;4`}6bKh1c7y zV^Q-RYFkbq3%_)!U?pbSf1cG}7A9cL{geV0GO645Qx;$ckl7GAd~PC}lD^nJbO;dh zF|HTQi60R!aRmmni+)?qE!Pq+!A{Nr&3b+>EV|;6AAluHZdgu*$TTpYt;|`9JZTbw zzYKQalpcdZRka^9P}jij3ApFy4~hcA7PPp9mq3nFyRvR265YxR2%L43qy~H77ysF%x2M{)lk3^U@zuT zLZ(k|StGshaMM(~3`Lc4&a)_)8{zRSuWxbJdx2GD;i1Wvn5RpE9u(R&`py-0uL~bx zo-d&sC?EDr_;dH~oPz`Q<O>58WT)_cBce~+r=O6kgpAUM5Z1(z6bDX1`h z!l3hbZmu3AIQkn_#YUdv^I(_*=Cr@h1;L-XHciYY6PW}9lDZ5rB4?fDDb%yUja3YR z*K1-czn3_Kla~}odz@5cCVK^U;byIk5)o-Enz&Zhk`OgmJ9rI;>n2xByVJ$V57HY1 zy$=m4;$1Udpid=m^-FAotD^!fwNtYok4AqUv3j! z8#mAI*uK6Cl3vKe(!px!7@^;Ha$*zY7b+M78ZFHTWM{kSTmy407#S|l)hL4XY;z{s zGWv8a*%S+nL(-@*I9$s~^0*B;TzhgE0*SF<5m6|8+kLc|XjS6-76f$R$~;00(Ok2$ zBbU`X%jnXmuyk?cl7jw)x*1a9=7^*@wz8UY#nzuN!#Ty3q9gG3&3ZnFZuWg^6e z*RD-sMxy3pJh76xrWem$7ccuYa(X45`{(PJsiJ;hg7*CG)H)L)yHv$RR>IQyL`T*{ z+ZG~5%=;L-w|6uMJ{Z1OUB8azn}Y(LXpVOX4-&+fP}RBg*81I*y^(6@NtLIphMvLC zqb;t)tE!=Ip^!Y0#Nl}gV5vOp4&;Y&{f?726j{ZW>6=Q`%}dBuSJCw?=i zecJg*FJf6+e*2`p7eNKt)xEuMAysoYD+`D=y%hg1`>*+^`f^-C7F{18SQcO!)ANkp)Dtxf7uO0usoUI;pn|-X9@sGyXzY_GGS(KazD?bxJB#x z;cowuIg3p#U;GOJ{5jd}nZR-F;HI99U?3cEXClt6o@32-1FP|9c)OMDhrg($+uDyY zKo?FIBW_1R45+)~ipHTUZadY%ES`2Qw*aC;s(WU9Xn=xu2GtPjVYwk!J5tNfk2U=8 zr2fd(d!Sn|Cnr))qr~UU##t;kmTH9nQGf?Ng0rY?+fZmMdCE<7dL&%+51t|g5X+Nh(j{yA*M_s);*V?H z`HsBGM_OBMm4g^TV;r^asr7#+LYqj1+L6V_Shqp1enx$v#|vKtFTTgh8I->I#VdMd zjZ|2W&TiK>9c!hNQV^!3DH5NZ1Lll+F4Z)bUVaBjr8r5ypitIESLSyC!;VmZ%AwuZ z3v3k{@KA{XVfrj54x`OfP0T-7eq-bNN~H^*9#iR`wYt8)HoaX@`S0JnxpMAaNs5Tr zxtkESYIiiznFZnFi-6B*QKGeF0SDj+ckwT@`CLAj4P^a;(Q>_i;gvl(oTk z^Y-4f2_L9Rvr9&EUv;~9+1P(Ljah`<>|92Q?DhN^tLbIupIj7!_x!!+4&)usH4uoLW zC{zg-z*~bj3+g_lIvS(WQj`S!eKv?CaT0o7C$g{)ilxMlmFXoUqe?N3Vl-Z+AmnH0 z{bpkt?fKTxUbF9T_TV#0MuBfXxk;I)x-!^=xK+b}KxkqUWuo;q~JGq&hPPdF*^W-;nQk+?Fa6eM}`TXol`y z8~(o+U_10X4C9tqguEMwIqIKq6AGO{= z#<%kKlI`u9V=7Hk*Tbq<8T;DRjiWTu!CjP^fElo!O`WSUhHo4b8HY(tg9Xt!VtWgC zNsse)S{pX?Ju9sou&_I87F$-XX~AsuE(wpm?|VHa5zp#FBD%OY=v4 z4RTCbReb^{6>wk#CJjj84Z7B8~NHj#((+DE7@`X zg-VbHv?{l&4#%7N;$@dg5Uv)g>99gdZ(v!{E-DRbxXL_+Xs=1i;h=ZeO6FVZJxdn; z_IW(?X}j~DgT6EePCCjJH|ufpSrnlqUgy|HuXQEGN%0cMj5cv`U3tNEJ3{gUKKI3o z?If;^FV$aP(pW=zZ>oK5*eSFX6;Ar5i4(_z^KuK*$>%#LM03zHmFtAf4ugSn4p(vo zuac~=Fe7RopPdl~2lj^m>980qGzrH!v$;OwOw39ol%A7{71enS;RUcTBo0S$vg+-G zUvj(ig+A(Jy6^ zhnI{6#-Oou@Z$Hc2Rf*wlGY{SnI30 zYerSts3-S(my79TAjQ0{)u$-0f3IjUK_?;$^*Jt|FwKSnE8%kM4wux@wvD5IaSo8? zjwmo0KYIV?`*VdZc+^zNfxX(PZn~NnW=1CkL3--xu^Ba?k*eqx0~kd;=LyBfJLomd z#dRd^KE3k1q7`i`uUmyF5_o9FiTY?ueu;bAloW5YW1>N*mL*Y=u#oy!_GmcnAME$? zlxJU&tFtE+3OR2Q~dEDtTjJ%E#FvQ8uh2>ZM8kz%x2qL{ituT0*c8IOo{C?ZtOPLSYR>*WqpRs z9~dUmB(?vYO{B!3&?4BLjqri_ykoZ$r^PpU56+x1ZK7-(yo{&~oEiFJZ`4FnlfjiZTP;8o#mXTA=&}XdMi^4G=}It%;7GC~lR^3=y?aa`(5ap) z%g(_|^&PdYi;>mZY+`BK;8y3cR6lwNzSoy>GU36fp}p~HIYeU=d4Pngian`VwjOJN zL5;B8*9&e*;ABs6@=#W9`IpI){?jy?EWwBA)-cwyMC@z29Q{YI6?(6n|*;59!%FbL!snUbSD zvzYg`s<(e|E9y&7jM+%(+v=EI^pni3U5-k=N9In|9)E9Kj2?nBLe%?>wI!Q8`9XrG zb>hC7gA`U7@}P%=TT}T-GJvBzxrUJD$VfDQywdr8*=gI$5(6;ZsHC1^p8s8u2Vx(y zNfF|sJ=|BYbx&Tk_Nrd?z8z~E2ak^yswpy5*3HZKzCnmh5s(U}?7w-pb%scxUeJSbnA5;78VASiPVVr1r&dc zP!~ZZXb~2rg33BMk+{jL+WLF)H38$W#M;ZD{bE08s_i{~2|~cQt_t72D_!!Gc;L@vR^LbCAU5OZ%ZJHXubjE>LOncH)IvK485|lal-{x$s{0}%BtbU(5**c^t9tqB zB%N6?C5)~|P}!MYE{>yMjq>`xqwn{)r>~nM8<#rRCv)B+>>GI6CVAa+Y{nFslB=Yd zqa+qajH27)ncj^-<!x%A&T8h(jB+Z#D8G!!Su!6v${ zaU3J&fu6+OL;q`Q|7$@31735#Yw7&t67>0lFNf+M3my+n5omx*rfK$w*X7%ssEdJ0 zo$>>n64P#n+N(S6;9peJ4^npe4z+VvL8T3Q=G?eL!&FFg#U{sT!{-;d;? z#Vn$uQQ-}Bu#kVWCKwz<*tbFJm0jc-FiwGH(vvQHcJ`y)>N9)q#_%vNK)?rn@aS(( zb{q)ssm{MWy;F0!^rLhmC*%G>DLc@h (7h29)vE*LJ0a!W~pLU$o+h~viILsgP zP%67_$i5Et#Z(sXDp00A=wVbM1sk(d10I;Q%Z-=bInug15>ZcneT=f0OkCpaN9MSd z>*i}(6CMttoQ=tC-i3&8m^2!`_+S0!DxH_3vyZU86`>oE$f8%^# zUY~_Y!)ydSf>YVht&cAAchXo-%BA}8XAp1>IUO9f%*9e&rN)q1NDQJHi;`@Fbug)o zi7%;t#hkx2I|8z1edZ4#<*6E5cDeRx^44$50xN--wh6*&R%8?lh_GyTb-R42d;*H zt8CyAq^ers;~Av4|5hsbK5{uz1f-xeG7$MEIFIcef^OUbFw_*!pR#6E^)8@zIEf49 zEhxfR5+wF@(S*KfW_RuHiM{4=>y`NKegC(*7j;%LbekzLVjXUF^oWWVCwLzpZVK`p z8?AhZb5D;TcbD{))0XWu#(R0H^AExGd=CoEyzhu9IfkSHrkP zV~v3v&Zn-Ku#KO*Z++2glrf+GE{uliNTKPhBmA?C>eX{mL!E5imnWT48Z1xDyA~dL z_i8E}HINu19WyX#9{#D^PmVYv3+;oz_SX#qL#h!CTj7N|%U{Mm&&gR`m*!8L7CWzr zw(ClRCRgC!iop@Zl42+sn4Yn}v52>=ZYl7iS7smW6C5VO15tYv0tjPpA9bh&(0HH+k0UAiXH z{qe0hDk2IbE&?8p6VW2?^3Zu(D}LsEyWf!V@)c15DNiVTQJqygL;UgEhV^^X1e@(s zL;T_(%(><~VOU{;n>9IaXXMOtovh1K;8h&0X@OD@pAnjEU(PBm7c8+)F5=f^t52|R zpj@f+qq516q1?ZJIfsG@8%zEuS0_hFQO;Y_(=xrEii^g&WG$Y-cnb-NKOUyRwP%p& zch5*lNjL`urcMDENQwhCL^C`>5X)6oBsooD)iEs!aUpoqmMPMEQ%PI?>zwcHkfY<2 zoan#s66=gJ3d~OL{T&<1@(INPF5PeuGrFvR``y^h=4P3tOn=r>c6xwfScAnEEUqbF z%c1bod43zh#653t*A1iuXOGz44|JlA^$m!5uUM?pvMA|C<0Pdg^!@-$vX`{^1Q&W) ztKW$JTq6>wD|&@M$Ffd$QF_AU^JhYe1-kd8xuj z*NAQQ#(w72uOFK^5K&Gvqd zy3c~+9bJakIkH}4voGi`naqI3Q5g{>djkNw{L_Bbvs0<{uR^21-uQ86sZz8rq!sLK zb=fI9-=+j(ocV8pLJZd(N=*0#JHefIkfAnPu0M5xcpe{n{(J3aa2g6xvrj?i zH-8)k<(=tsrD$XLmb&?+$);d+RlGy0+*C5(i;`=W4Od-Hm1u0abOZbK@cFXN8mof$ zAhi;a?~6u0_WqSdh=zmDi^)jIXpuzwZo7Ek6wJYL9{QjME;doNFr%daWM8#VRB0)__J8F^Gxl1wimVUyati_SoW(5r`!50`$-s=LgUH|ZIr|t7Uhvos46gw^SaZ$L z8=q2Ca|Hg2&aTe2WmXy};QTcZ)!OdBqi`?JBh%bJ9}VMFa+{1%Z$OJ9ZD#+_E0 z64sW{w#|#`q5XHpJA>DMPd!(`dfw6hL9WF8*}ENb6U*s^b!B;#+QI`1=&RaSJ?G3mV_tht99;}kiItIaA?;QR)x zI?*%8RnL8KxfAcPGk>=<$==qcam|gozI+gewZj9LMC|9I-`@Pet8N{aM*9>v{Wdgb zvj4t0dU*odkW}$3H8#$!mbdtqRh0>4Yz7aBI^P*tBRNNrKf47MmhQ>=@$6oP_df$9 zQSRdaP;2UQ1M@Fde@C+Zn+S$vLON^iXdKszC4*STMv6~h7CE110fOWK{06?~y38d! z!=v}Xe3ep@uX2KCpVvt|I)1wdmyRMf&v9iJmt(Ick66xh$OZ)3Kk8F)yMh5cT=85;c`)^(LxOABj^+tZ*D6;x@O9KrV+uPORx;B*g zmY)0{@o(uUZH&4#ua@O;%|4%f9^L;6m>T!iSPj+D)PiwKT`9Vx>msz5F#Ydm zs$2HXgmjyZUjKzmS#p0KYnZ#D>3WUX+~dA{)#X0Q-7EbQEE_6hUGsysItW%JE&bJb zT#ER{-mHP|sz7Q62aiXvOtQp!)c#!4>o9S=oj!$s@$r+^M}cw`n;}SgfMsS>{htIUa?CjqRL}gw=0Y*qFIWaL2-x}V zf1J+b^9*Kpw5O?H+ZdM@*u7XQkkncZFsT76&t%Ka0K>sKL5#*E>Nnq|@jta=bN7A` zoXcK9DapeB!2z=<0`2OfZFy9)IyuO$e5V>fc0;^EEORvO73Vt!?n9{`uqqbRbpbRp zNO{HM%oQuB`Ckd_zS*|idyrpk>aWz!ZP{${TKDZa3=kl!GQ%1K-JRFWMCkBUd?Kj) z{2u9v&MEz0);iuG{C-y*cR>Z->=T144qdlxZzn59d(&DQ%`c)DNayJeFTzYBQu;!I zWvxWdw?$fGyM37teWqLGlivJltkFqG#*!4adCC98^?gmD-gi0JI^W8Xn(E2wVM6ky z5}@GxqX|gg-MU7G+Lr&l5Rc;7fl6BJ{O?r(;*P=;EY?y}7l-)dKTma{&lk1MhfqS0 ztuUDyl{=p=dQgr~cT<&N6btcIdRJ%d-3SH<24HWf3ovdtuYURtV`h%US$U5x^s;1O z_tK4ezXP3hWvXKHYY7hw%}>@Bq~P&c`VN1>P*NIQ?E#su@7MX6eeY-Y-|a6-X3gfd ztuE;99vDR|hO&M@fg=7IPR7BS!DFxX+y%Xuek>u}7ZEzYAPi_H*hXD3LJvNLY zCm{5-!}h_4m@jP`S3$*Qe3ahAM~@5pe^cMf+Lx>GT*xccT@))q^|vb_?z`O?;1ko8t%tIX1-D3E~=bo*>9UFw2_wV&EruHquNxl3b z$GqSQ+OctJAh3!2M(KOJkow!u^l);w%Ad49zYscr1P5x^s7ZinUL#g{i1&HiKvS#T zweU+}t}_uvYO=+eq|s%+09}#WE4aBBBChMu22XI|Q+q3i&?uFn`w|Dzi>R~m6GHG1Z zF)0-$>=~Qoy(jG^MkM_2J)e$uUsJ)zUa6KDlRfvAiNrLp=z|O~T&E4F(d!;6S&a2hr*~M8+>TAQ_f%Aqx{)5@8k|pMV==eOqBB(5_ zo}Myu&kHtmsvzsbii=Wjrs=r$;VzzT-lmRb=o^FHnEe?^(xfB#DMpR<2@TO)WoZu~ zjU#DtXShPD@9e%g5*#ZvWv*sSq6)a9rYPqI2O%lajxXEtvoO=kI2N0m%7TU(vni_E z%17QKnWTNWBsm*y0j6it26Jm>EN}qVJN!8vf$9RwMbBElXTLxk>OfoWz8SZRDVB}( zThaC-*T(1Ep0p4;XW=i5+p+K{N27}AOcKA|XS6O>sjzOYUNvz2V(IsLEPEjHpY_@9 zYP%Hm3+=j!*sR#>Sm(E=dfQyuL2f#G1O6jJQlHZ!uQ&I}nAfwGrSs`)Xco-jUZ$&s z>$Qn3VxxoOEob<8lxj^-`AG=u594X-Ru!?mXFP?6$&;;D@oQ?Qt26Al{E>kTEVeN# z!G6)_pOT%-P&y_AQaz8JGWKlC*ngW5|C9Ar$vL&yEyc?;@=F6|tM+f0W5_m00F>H?N62!@R$ zMU=CDAxyQkDVnK4(N$bDBL2WwZ-?|1;nN32;+bV3+sZ<$+tZ&W^Eb5M-4QP?j5Mx9 zx#fz;LQ{if;u6ka6BWxnQ;>EG@q{9i%|82H0>`ShD+Li5BA7JOQKy5P&{>>9fx^d) z-J!zMJ|GCG;l+se9kVluaAhdFAp1-H-Kd}^xMqLo*kp(|FY08p+5^%r*5RzD!W1Bl_9 z46_)_YSVxEIK7&>7Hs~_de|#ySa|!Z;I!72DqGSgP&ejZpc%o-7FLs*s1gOgOV*>@gf~4Uks@=Xw5@T(A?-g){e?Ld!%0V~ewa6j8 zW+!T27d6T2-NbEBtkvmc!rScGRqC46FuHlG)-bJNd|U~P4Dp_yC=NI`II?1qmDin8 zb>%Qs)|H@;mNU7`nFRHj9O`i_vX7{H;X3X4=b;j6?B6PNH zgmyqGk3*bq-lT(|eab)*2Z@Z#XNUVV$Q|z!4{-sc#5LRmkFw zxl5KqN)sI~nGH`|Z*^mo^1THM|8$kwkz@Rd2usQY;v7_( z1U)7(S#Ba2cv-082mo=PPSsmuivdg}e`(#fz@Vg_!F-N?`Vw@bLl=#^{n|3}kV zu*K1I-Fk2c5Zr?YcMmSXCAhmgJh)rX;5JBb4eo%LX)!qYX~%>8)~N%bP# zlWak1orI0J<>OGLWbdgYuhQ*C4gva#7aeEH<~k*jHppqm@5Pmg2F(?IcfS2P74;(X zqLxZ_v!$qC(_!d^MNYkNr%2>AOi9YKLdeA%Zl|o5BgmDr{OLPe`@jE$2(_gDQqjH9 zoOAWe6ECu3D()vmkMzoWP20svKq-H&(>0$tuLBhF_ia4?58>r=2jic`7j`$%m4-1%7=J!vhRzJ!KGf9=U#Dxe zV9QjcdVCL=Zl7fF%Xhl%&7ng(o`QtFIr4L3Ekgx+?^XHAwj?xM?^|nakSd z!^p}}bb0jvBWZY|k%e9Y|DHl;tO(ME>oTw94rYClxA?V0D6fNYr_t7 zGt=5PaRC8FR`^94#De>1v+UY#p|I-49mu-9A+IaJEe0B3P`OC@Ep`Fw9FcTqkI9VrxU>dC< zX*95<$XoBc=`Lt76r~ZKPigN$u}DgO5-E3=5J`cRzm;krUC=! zYuR#Tdykvtix_VU3{OwHxNdBdpFQtXk`?+dOQvQjgfZL5Tb??GM?$AYU{@#S(V;@} z8h0svCUeTBPb+JGy*^y`T5|&WygSG9E-vH@6cnSM+@zIsMQ4;<5Bn8kfZkFNRXDu(Olcl7=3FL~o(u@*Tl2MHQd-tuNOUp7w`4 z^1$o|xrSdF{b!3dKL}z~c=%I4KbBk5t;7lss^gycA#^?H@U9|kPsBXc3=YTgRt6s)w_H6-P(! zx$Yw^aVE=?T2D`i5<%GesPBSb|M{>JO%tYjWu>v$=~yXy}pbXKksP7FJ&|8RljXFZe5iVL}^p>9M2xFUrgO8uNt5N?_mrF|D!aR#pfV?Pnx&MU=0Lcr?BF(i?mTW62j)xLU4SJ7OK@UgaGd zFf`%zkrRw%#DXLmA)>eOrQUfAM zA{_O$Xb{UI+g^(fA6|0ltqI?W`kgsomnJ|}jxxt0rx)aBz&JB)qKR!w+KuIg4n!Yg zEp8vAW~rWA*N;XN3&Hs4E&=Tf-QVZG+ZJVJuy(kzJ#Fs(3$?2$fc!Q`2wuLk_Qq>a zL{yn+SP+z-zO12D?Pv1n=^Y6Cr$a~C0v*T>j$Abjro+_!DrQUT@(b7@J&rT)9X(dk zVd_FSb!x$H6dC_jMjKk<79hb3x*BQg@`>fzA?ki;RlE!`<|2|u<$5=pR2xLE1+t<6 zm(QtPdUcYwAw%8k(;?jI^ax&kF|_@Yvx)z< z`1R$KB2MpUTHjPy069d0qC2pRmD{2AUQi@=_{H^w+qy$ivl9kXf~XVs*_Od;XKkEb zRif(!i`#r`O6tYqdvz43r2-yw7I(0&xc@b6eDjg##qg>8?rGNi!ul&vc872Yf5P|t zmtMNxibe>`TbsU$#S_I3lnv??hR|W*aHkU`+EEl+f{Ba@@;Xni#PD2(krimg@VPYf zqkJ5yTA$=q0PD~S5s6FfojgWlNmPo0z0d`fyUn(Mafm_5z3of1YQqC~-qMCA_XCq1~Jpl5$H>;;Zx zF6%L@Gi0@&1~0KeO!tQTONH~&YVNgWd}3ScOSo&a6~K5 znMf^SMGcZZ$cjxbm^yJ|#F#Ix9OP5On6?K>8|&qGlJk06cKUOP;iE(ElU0g3?}Q~E zATx4;7|+5QW4@KtPaEeY4<9&t@yv~6Zj4omPP@0tIV7{jDmIdo&!=XxV>J2;Wqp#L z>fo`^5d||0($HM|QBDGvw%;!AkASBZLVn4v24&+8=tyGx^rc3U80#PFR;RWlUfh^D z`;7x39;8XZ?Q;RgJk55s1IJL$JoBOsLdcrD7%O#}Qbm!q`|uuKM&t>-YS!6b=2=C zg|Zghdhiy>w?tbI0(dZuqKhbve~!riQUT^*R9xg%HL2BlpV=TfXj;ZpHhf;dgGT1YS8+oBIY}{TjG1#|m=}Y{LvlT6AQ|N)w?3PM zP+|`TfHD_Ykl$C*n)j5#@M!#^zvN*5isp|cX2py&FY5lg0zP~uMI-&~f96-+xvf)3 zW!(2y%nl;6>dJWD$-VAfp z?vqa*23aeeV$tzkDiS>0pM|gqH_b=S%%jC+>Ram9GDpdPc+Z0>URY53JHjDBzynW zlsLOR{;2a}qQ)NoA(wHBLX_;~>8&%4@I@5`KZOO(K-^v?lD0u3j2-wLvq(IIW%4o( z74FrA2>`jt;%(%o#4N_-fXPgG@*FNaxg1q<`W*ugg=EHloySqAhBNi+XYCH`&O3wpe@seg=DjQoHG#8oS?)xc8WoJwv&}*qSiJ=kj(EZm#o_`QRI7~) zg0bN28dv9@j1{_Pa1^{>bZiuU6Z-VDd`rBW(}JPg!>OUq@FpN|BU4(Lv`I38BBY7~M5RofA{%&9OKRJV;}bSNBBt;Ld-qz|0a9xMz8DI?)qZ4SyC) zdY(QeIy?CCLW6$3NB_g6K4Iq`} z#q@5qTK@Ne{_(aQ1!G5kTGT?TV++2{(XfoUef@=RLD!XQ!;_f;gDHwQK<*hCRm0`5 zW=rku?YWZX#x2;Hv8wmxm6h^+OIWI&Ztfp=kSh>nhzC0`w$0W%->F!6_#Tt(o9O;_ zKYA)IlYj8drT2SJhj(M`2?VultM+V8E|Y%j#aF$?bGI23?DV4^Og>4$vGw9NJRyHI zdQ-bQ{?0c)d2a$G!d?{}hQ?VDigrRH&gn1d`C%A}!;p2|?Igs!NXrzrR3C)6HnDBK3ezxk!^grNN7-x0-%pB>W)8Cs^LV zU5?jNb3|)g5{x0)Xs@p(iyf&X{zY%Eu4SJ~Lm-=h4&~;*H75(pqTS!w{24kWU4k2QQvX@Y~iFIcn5vdd*kuB{X8rcu#{?v@1li)#x42c!w zy!p}T-NIzOCLX_g@`(z2w^}n!gAy}FJGb9N=#|malAq4P3KyJ8g3%?H)sjmyA40dE zcjx1x0Hb$9ikJmh+HSp2ZBIaWMiR)6X7bm=JZkG@6sw>M|w(o$5Ng7kOVL@ zhc#y*WkO6}#bByOaJ>(&*bwc`Vj5hqxV;pTs^NWIZOul)-g;n*nXleL>p4YxvAo~# z9mO`h_@|vOZwTWa{?*_Q`+}9HuZdvyf7;P}_ZlT!UpA$)0$Dw3%|3s=w)!PgRW5F2 z4&0E=&eG=~4Wmlly&l3bP{91%IFi#|{upW{at7f~Y`}oXqhy@_@c8>VUP^KJt-hxy z!KG>^u6KD{VhXlO!gtxleF;vQebz~j73an=4!%*W2U+lW_G5sv~hbT zy^4xR?dhqNT-t{nrNWR$wWywV1|c@Ks$zxLaLMp5y*2GZ=V901~xxcjdFR zF3gBrs6HtmClL)k6ELV&IU3x(z8SwS7A94Tp~6E)Z;X _y+!x}jhfV&>22ENLK} zrARQ(e`zuTW~)NXURC*x^>5<#&MJhc57ji>>ac-j@~u!{F<=gs27t8E@}F{L!+iI| zB9QRmoJL!&IP#Hz9lvA03f3j+sS%?O*z%T8Bj8Z3^t9KL`LtwARf{#YmGy|= z029L;AT%o%qoPbu6kjrOTIKci=ycs+*;jF@_olmso@vYKyu0)FTSh$@LmE1bwoHO6 z*<@ZgLk;ll0>OIan-wvgj8tii9`vpx5^){c{Vhn@kq}pV9{How8~pk&s|D;MQC5jG zYE{!h9-{0s+x9ZRc-|}-gdK*S94o=To1E7??#;syk_$QdgN4DJ)qJv4%tVFaf+U8h zYDUGRi=>GEIio@vOv`msqw$-);Uidk&izZA)+hYpA$(9s3QLF%Q4cx`*zk`EzKDpv zSsO<$JfsmiTA2^mKgPx!U94TnK)Otg0;PQ_B6kbW>0%buy#$5w_XOMEbgQFt7#!1U z=8_X5!=OFxjc{t{u@pNE)(V~{676plWz~!oj`#6GLH=_ha&5i7Q3wf;^+q>(Xt4m7 z)2qrTHltE}f-_&d`*6#$&CSV0#@ojMT zrl}8I@G#7ww@$7(a57@{-;P>G7DmfS-c4}aZJdoA!b$aB3(eMwppd+YS$dBwRu3c_A8!xKh~hhc zcfPnQjd_rBpr)ZRwmR~?eCLq@{k8FQAF)-~4maD;(KB=hb7sUXjELjI$l~Xtnjbm} z5N65sgOj%RrSW0xdRR2B|78_I_Lnhig>V+87nX0ScuwNPZBv0WhI-x?(%_)xvx(=| ztrAqM+rK?wo~7Hks%w1;gI6->%KQVT4ljTlqrdHgd#B}^LY5Z26C2j}ATqjvPa zfIwLIr@+IrqYjz!7atsySaP*XS&J(r))=%ehLB?~_wul)f$2_;Zfw;)0jQjAMV_ys z!PceqzYf>O!d_Z-cJ`3-%Az$XL;jWQxiD9HB_|LHh_bHi=S+^DQraQd4z z@Ox3q&3^A>SB=UqThWik4+_NCt6p~fokz~a^PUN2|9SNQZqdtsu%c6018dmlVN;g+ zVYFu0vnm>N%IHugpb9dI836?@Z{J2Bis4_0U5RVcPA;$Ofm=I{QqyfJU&eZ8tnmFh zliok4pIKd*I*ai0zgg@A6FKf%VR+ zm0UZhJ$h6q6x)4Er-|4SZ&iNs>{QO@6y5&V#jf6RHDTqzS|j#}RxFhJT;s zM7I3^)9r8BQKU>F_{-al8Yr30^((LPdipRkthebyL$4N<7jA8gM!uR`5#3U*oO<6i zo;>%_@5eqI(2w4TeF6nIQG^_RcXIU_!?$nc7fm0rqtIlL!Z%e0IO=73S?lBI zVZEdiZ+zo_W{?m;6xcC7{l`UCLKW!nO!7Gm<2Xxs5-y0A#p~l-lZWJ_=cOw>`kPoFQsdcb zjQV03$B8B-2vNUXV25=#P(+$C;B?1EtjyAc6K5w~dZ4`@eAl(qmh*Os_W9bCkyZ3b zehI_PXOt+Qyb&nMgKgqY!X2te=P|!`@sA_ENgcEB9AmP@SpX->>&5zCTc$E&LlhUX9Hoo;uzmmbYV2%FJUGK{TT8x!uFR+6b(0{)-t}ybioxIi04rf#@ z9|*q&@LCNMy}3VKZ;~&5FuYF$^u0_%0iV4+J&K>Kk_O@hu?4_}nYltLZeDPYRFkb@ z%HBjSJ)1NZLdqCZiNp<{vQFl#W2fPn&6PZ1a4_xXBJ|87p%4OdF0{UH89Imu>;^9` ze`ZAOy+SOq@;9UwZ1LxU4IGxyHgrns0Out8XAziRvpH6@K52o%awT`FP8JUvG$rl- z)E>Jv`RYPJimOLSo&O$cDfyqW|FMyt-d(+opiCicSjKwY@U<6W$TaGOWB+D zL*NW;Qz;A%_sgQ#Mh+rbcfC@#UpK>s51tJ_W=;Y=riU}S6b;@{nYYhCh@Bzg?HK{$6rv%iwLN!1glXXePaGO&^wP3fL+F8c9p%*a^W`Hi$ zQvIGXA8H-$$NqHTK#=9A@;_TJG#x^!s|B1)pAvk0w`rLMhO-*J`5pdEEW>6G_%<6~ z_Pc9Q{=ye}F+}2;7|jraUe1BN4T`gA-0s7g&1>Q6_plOrWd3Itn7TTmPgNL_KSa`` zB3l|HRSIk1OnJB9_@$BkBTOJ;#Dp0N#SQ&t%2(-$ zO}7KvZ4#k<&b$m=G|=eDWC&Tkh(0UAHs_=UA=;wna^?y2mkb3LGZm%f1WUIuO(CR6 z%M2^1TyH)lQ>OZsLgnl6>c^~~K}nLXc6yl|buabF#okc_AOSoA8%U=G2Zxz*uKAb} zdSpI)n5lhb2U4c8)Hyb3F}=20!gjWXWeB*_@RWJXlt+OvV&huh&&X)_3_Dp#3Y)s8 z_-bLyKa|EO;`SCOc6u@4FT8G3x`r34I7%Ay$KUeRl%vL1M-`b)uV26T zJUv4Q-IOh9E}^$!3q3f@NyxDsg$O4Rz_kC%8kbe~872CHqnv??7Ma@}*&@)Iy`+vq zUh|8_G`A~N*HF@LxOP~oAHs&ty}Y4Y4`@EDREx_xw*CMa01Z4HW?v&)^j45w(`-yx zCDSN|75Fe?)X}gS?mX>h7?Lom-Sne{hfa8fI&Xb%P7QFI@Ow%!qngM6f_lhW{CDfK zByy@aH#a`SFZrvl1bXM-uqte5@ z^6XmV*{~XSL>OYwu{n4zoIr>+b0iSJ0pZ40+$@cqSJHW!QkuLLp)zQXpgO1J!X~M_ zT1%%PAFnY$OW9J&jsy?NL(Z|z+!)D>@6#W|@72pxl&Cz3kk$27=f-gm@or)lbK*;p zB|QGO5Ju{uZ{f#j#YQ_(ET%SsY16=|oW!Ns@f3*QrcpGb64b!mSexH+PW|0rZzSrd z-4FwhC~%+-0VH<-6M~+b6Hl_{$rsrs@8oiO{sr_~m&E+>zFf5^nh0GS-Pm)X8lVtZ zh2+w!%{j;V$7co9zNi-Rzll?p%b>L0} zj;WtNf7-|Rsf53i`@^S6WpZ#Xw?uRo=CDnZM!hPsbj`oae~15Q$M78b?|l+*{FMLX za(O={#>rFFFF{fH(=m%W@x&{jdwJZluH|?IkOH1|kR2xG8r&z2o z?8Mf)3N>`V-fMq*u*-VdeeCF4aOTlmb7hPUVqj^wZs~(1fB|klh)^XnatA8>_Gh9h zS2we@y7w;EpUOWpCl`1X6}>2^lb8Na3t%~FD9Dhhch(xQfBc-~n>}n?CZsr)nqlT1 zuX}TkaCU?^QwnI%+tt*o#Lf39W9j%hl3<{LYfdNQre5u?I`$O(Z461#U>u-VC-|=4 zWX_`FpVip(`W)%=vM1v)h*y-dmTYPljnp=Cf_op9cFd8`LT^pn^$YzcJzEQ5IB|L` zZx7JmGB(3bnQX9r8#+S~Ccb(%=pL0Atu{1uTAiLLr1W>^*$KTiwXrq-lJk|)!Myv* z2?;SWT^unid{69L^q<6BoHaKPso~l;Oa4H?C&WzprWekd8U5{G#R|(cVkhaGHwSNq zP|Q9iaC~Ujg`nvREA{y|i86G_GdIVZ1kaiB{Le}7iM_`I0Ut-bsd4_hQh6LsH}f77{Amb`bvQ3kVcK!5YX$xHgKm z$%wW|7u9l0>3!3-^CT{*KppDt%P1Su2aXx|^XI5jZBMF#s?Q5w|LL;2nP7m35~S7I zyu5sm(N=I*iZem-!k~{EUo)PpwD}<$Cor|xx++vWbfHp!f?r6#uI1sCw_{FIGF=bU zEHEOuRu>^(o`&X!I8rs$7`ujT9&AmIFe|8+GvhE zdUpQT-l`Q<;4h3Qx`>GQ2OKO5I{MoZIut%dE}MO;Q`>r--Do0}HWgSciJsw)kK_J0 zf0oyz?Y{APd%Akc9{H}w7SWxOS2_DlrptqYPvynM%bV{`m1WGjFS!IZafhMn!Yi2J zYPf^`oVDQe=xroQIzGNc0m5lSE?q*3C3X1U@AcPcfSfNF=RKrorCPGb;FQHsZtv4S z2&)Xupt*e|>ei^qq#ya?VWe5Aj-&RQJxPZ;r^^eENNXhK3Nd_T)dk${@DVDjq;e19 z6N7g|T6mW0-q?h2@qIaIWZN@GGP4qZ!>C&js-@JQ!|ai&IS<%VypT#`o*U6<(TRS# zZ6F|3udi>VFMN&QJ)yj3cu{@<`c@nwp;`4M0=mhW?=U+1FI%r9M zT=Ngk@?<2GoPS*JuBzD@aMGNC=_9Opu?(bthIq3%86g}gBp*8Sd8W}g$oI1t$}`^cpcgDXTBv7lASb`eWB?=9x9LL7DY-OOI|gc>*QI?m>qkq=S# z@w^sNy}KYe$%JIS%dlZ9rr*uSxA_%!4PVv;x{EoftUVH2VlESIt997GqH<(qsjO6n zg8K8jCad_J+pGzjf4`?A(-AT2@HZWqo)ow~W1bq8EePMEV>B#9dFT9ItOv9bm%tud z>)(hG`~U~U!mHMCyWKK`_gx!2Q=fcMDEJtsi>sSnzcadTCdY2c3Rp9iiK8OQbKr;! z#QFX2j|V~#?I*+mqqyU!lY*L|hNbNvztDdRIplN0AGmF%TXvf_UF$lQ9i%Fr5_=PL!oTONYhcWh_s+9pj2!`lT@0;bv#$AqZ z$8*0UlGohJ*ik)2gi<;YWx@v0TyMyu%3`v>8!OFnR=8!rt$gunj(-P_e^QR`h38dv z2*RrKnzPke@m$$-Qm=*g+#~ru_(ynW$(?8QCzanZ;#{dAWXdPG68iYUR?35c9}(VF zA-E7~A@}!L8)o9?m6k`S+_Xr`06EKk58YDBu5?!`RV%7WOu)uKK!J_QB4LSE=FFI( z_rf+l@r|4o@t0L}ZEn#XB%7FfK`coQ?{^+B>!wDTj3c6o&hp#vc_3vxU(|5{1=4@} z@>ZK3dgp)n-Yx9+-{qdcy&>Pfgp9*)IvN2SN;6s_ZUDuvx&D>rliV5hvpu%i(=$c3BLQ3R5Aa?=Kx& zbIUkeDffF4Y6p(@XagL zTWc3y|DFnf{x%~x`d!<+XzEUft=f>pb{^H<7$C0Madkbw-S~6~b=Ip}&JbRT&1`5?*481TyUA{tJnTx21* zmSPO5K#yUEO6#EYU-snqM6ABmAVi;e5W;sUma2L*XHZ#zS)4h_ zmt-LQr49zg%u?W7>6m;GtTwLh$nhU)`vSDZP+n0Ylx-P}tVCWz9Z(;JD^H5l)|waS zUN6_zjtp+F3@oqva|kYFiOjVEF`x<-a+^su~n^p2Sd}ZvLEs*5o zBf7Hdn+;mjMK&vlfmXH^rdBA94kaso3VGmxu_e!m?5Fd<`D4B5v(pqi+c^pS#iOGb zAodWLHv;_kc*PI~Exi`p&6lL70uT26oswRl*5e}=RAg{8Kb-7?;x<`&aPP2mCcv{R zD-7?qHNRGqy_-9BNjnW)HGD-PG{e}%1qFC3c9>^ZA_t<;j>(FoNU;}mluz!b7>b?m zYy|wZ;gOnR5<_26!E4Zp}fkK(w+C>nlqZ_#4tz~|EO~bb%1>vxG;OTAtzF1A8 z9Hj%Jp?jR?JGMgtXX;}cWCH*ZTM}foCuxj=*l!Oz^6U3iNon-=rGR)+{%=3w(80w* z3z*{Ok%J?gxS+&N1f$?IHJ9`_*gR>Zap*+X(v$tUnTAvWgOZZ*b6?Zq=5E+MtSxVv zQ6PI~S2Yi8UF~^>lM}jRb0XDumR7{td#1!az!cE0rj}lZs}({MM;|gt)IERzt|z4g z2^Zg}ZtTj=QStZ#}IZsUD0hH2Oj6YnyRs@=F!KdYq0NhFo~GRD-!T6a9` zZ|@oqu+$bFJh2s#sPybok`vzCr%EE`CHeesHTYa=q+~^o<{aKGyiUlH5pnoy`H&m5 z5FVI9f#fvvS-V9u`t&U@oFkwfAlG67Yronf>^gq$oBAj8YjtAN8Rv5|70*B-Z+U+D zGM2=l!{2PNQ!g6+VohA*47Fi-av<8O*_-f3RGcG7^_>``$Qik>8x&A8AF*Gc>s1ba zW^>w`a{SmpWUSbfM%&OK10i^bBMz^i|6Cmvx~m}yTzj+N_F3CC#b_8B?ogRqL94;G zXeMUM$y_U~W1Ezuu&X~y)v=CSe_v@xi<~Za-r`S}`=w*gVxhVx|BR89a|t0D-pGhL zm7hx&!>1012v`Q?IaAZb*$%sbOY1vEq@xIA!?P3Ik0ftL@KOtsdD{q(Yx&BW1OmnK z3gG9T#~-eHcZvrNZ`wpd{)zXxNBIkh<+1*V5ku6drm75*qP>Q8HjptDkz=qS_RwC+ z2OMwt0iEs5VgF>4T=aE^+9CDV&o-}-Oesj;jsBt`-Tdbz-)h@^+AM=$;0M2A)usRA zp&P$IzW$A4(BtE;+QSSm3@}%~UA z;9m`eDXt4N`bpB6C1adibMY}9;=M%YJr5+W+=y|tB(C{7@ifon460NatJ zTe)hO<(lG0Rf*+3D`d;^q_YG$8QxXaj}})gd2bDHu3mdNH@OJ~=#3=AbG>IJ6A)6Y zkRYYg5;Gu8QmiagyDL3HCr7ZPJ)YK~mBByBT3pGI>(o93!O`-ql1yHErY-?-;ukgs^63pKq0U`O2<&4|3vCbO1aR#h8sbNzi`K$1}p zE7fE94(ic-!z)_O0QkuqLr3oY8vISVWcGQsbI`YI%t7=F1J+Nvqfyc$ny9@?-Yi)=k|{0WXs;drk6?}>Yo94)Sy z{V{4x$Agz^YoVe?EX}5v&6Lh{X&iq~-_WySB;3isVZ7wPdmlrkXjB~yFlsljldTMz zPT=!x+D_+QiR}5tgG=$RuIfibHzH2KpT4X6x&SAB%q~!8Jwt5K0yJ)rbQ`(| z>OjIL_o$f13k9r2^J1ZN-LS2z+4JtsN}){0EAcA~K`-&ZVs0A2-R_4*mmUG-Ufi3OmFYNWBypWiqQRJ!Adsl+3lUT`7g>WdR~4SD9RCu^ zlvH= z=;=(C(7S(!=TO{cS?mU#zFi5|Evsa|eCMs~OAET;F&1es9i&M!AA>Zm@8zLR`6NsAJny=R-b1psKR=ZCz>3`_|whTo|u{3z0lpTA4Jie)Yy=a!-AIZB7d?R#HVd zqS~_I(%-0x3a)K_dX2bU=(Whx0bEfcv@QZ2J#2G=N*RzMPMD=Vip z7O2nbo{$c}%$A98A$U5;zrC06L9jn!v5N)}xr%yVuT-e~s_BwR6X;cqqX^7LTU_J$ zL&zc!2Zj_xJxldP1&k4~cD1hEihFR~(wK&ssD~unqw7S)yh;(ji$)p$Y>$v9UG$g# z3o9i>xk5M^#EZeJ2Nk{;VSm8`>XvYTjjfXl>`01sMu(FAM9^E<*+)AX%g>tZrpgh_}LdQ7dH{I zm@@Y^;y=6Ud=ktUc-x#i7oc5;S5dZBJ~_!bqH~ZasHmG4!;EAVRWI&IW+hcb%YYEc zxC4MxxN29`V`u8N^6q5=3H)Lbq37KHUZNKgFPg=oR6FlX2>W2m;}&UhNE}#<*G`f? zPJIAWjrc45%~gSi3!V%P!~wNqOT+a(w*mK=2nscRT0?E6Tj5LU*E1hxeRZa}`%xx& z0EPoNdXUX({FhH=CLE&`Sz#hsV zqw;ZN28r4p8b`*|wyUM(myDBir23Exb*c^x7)96B9@@kDi;EYnj&|aqD-)4fxhlP| zxn)H!1X@K;FCa%)xvG}b^rK5YiGTImpIB<23smAW3eK|f@5v(D`)^TF_kc(oU!$7( zNsEs|XXfh11z1!pnboKp*~x%mjH{WN?72(ELXJ6T-FLEXSQGRbwQR<2PnYB4TNnxG(pmKm@39A>@`? zE>hyk0Qcf(eqv_6WP*xJ96ulB2}34D!1QlA(`fA_e;=WA>xSn0pKv^uMEK^8eFUcG z`-@ly-^PHCj2qi(nj|SVkA9DFQ3nBv78!38<32em`ru2i%4B5E*1ewHTE&ZL$Y3tr6yF)&?rxzxojVqQJ4TyTvW+{(?l+CQX{$nyL{W`j}{ zVa=_coaOxlgi2D}^WS*zl*8vk<)6pg=7$Gdb#7Nq1jCPAA4azxTx?GdbNM`JZ0Y-< z?UM7b)zh8hp1L)f-&97kK4nHjzVUi=>bf3Us}NlQY$LMt!pC44DR^k7Mh=_MIn!e5D?Ezj1V;f)2#xgn_9fY;;H*zCfl--Bc-mwbkW^9 z<;{Z^_GD26S3GS^VHs?9=*UCs)yUO@rQu-KGHS6Qcnd@r;m?p6$&A-%_(t1k<}rkY zrTlE>uJ{A2gcyl570s{5{3w~>GzgwMPYc`8a>khyr-$UmQSfw3mNPn0NQrA8Eh>e% zJcYain#|M@RLiiQ*Xy!};nC@U$J$+&)$W49_OqSE>cJD@`%>Njd!Ey$LkQQ$N}aIZ z+G*!Z=fi;BLU9|eo>!&Mt^c&{LlQ~GCezr9mk$M@F%d#een}f9(9O6WW(k#ma_L+> z<_%j2bA(EIaGB5yG6Gnz;aU0EB=zk0VlYrYR0ob{=l< zeg}|G9=;!?UJ$?i=y)xjQRtV-=&At)F1XNlkVBDO=S)O~^Ax4`X%q!3&bJ2w%W0L_ zwJG>4RX1*9ydu<@KGmHPp~C58zM!ezyU@)1nMhQXb~|s&y(EO-Jft8TjH|)v{oL%- z_zmHmV`kU1wgKx(<$?RB3AK*ghKsP^Qs+E9^-l?Lr&)vhgFn7cDxAW=>>%?@vwU&e z_iHk%Lg_m7e3UgLKKA~b@D{MI+N_v-*5`9|BBl-C5RHGnrl}#P-wLQN_t$#9d}O_k zlNq>$2a!%A_iy`Vzl!&YA%+IfuU+A(Mg5F`7Ev8J(!SX-|Nn2hrqT1qTw{|tHNv+uM`pl zM|iZ|U?VzBpcq)r))6HHLZP0#%fw=hVkymA&CDS8@6A9`F>&>s;S8Ho3 z9{jv|1RSkJDjUzra=lhm<9HRSvF8}GW+Hf`O5}CI=Y^jbjhW>Wbr*x2q@(wV)rI6J z{eqK#NqaPV)dD^8E#$tb_X%V3Sxb%~DK3-?*K|(%?nEza)bQh9&K{`dI?2tlO$49L z7(tT+dMPHunm1Lh4FmeH3VzT-j>&$_+$sE*j)#V?I6eQXDNEmfTk9sZozmUh}7fM8x(iXFy`N&KH;%b&Be9Gg5lJ5t9zNm8Y z+j!=I$c}1V56=P|ot|?)sqig*Mv_?2nbi|jG~0NrQ`>y$KYWDz@qT7KwR3ao60d~~ zyoOrkf4d$&J!ukt*5#ldquDAaS!NzZ59}aLXNzv5zM+4y7B^4R zhi1=NZm&0b`>of%)?@J-M|6-SN{_H4GMr-2+u!`PcYh0Z{~DoDE2ih!!GZ&g_e_xf zx)v{+K_}%m9#t1;!GTv*`!W9Hf*Uki)|4W+jBjhVWIUi#Fn-!xyRxsk75de#{>jNj zXv4Na16MU<$oH-v;l!|cy^~F%*>wwqYh+rSk<%KGrv@FU{k6D79>4Y91B}R_8^JFS zSqF1L%nQrgpyS7pkD>K>iF|~-e#?QE39^VB#~P9%X)WuaAecnAFv8NDi*x!OD-Rd(!bmq6m*;iv<>>1~FLwyqMadXhn=&R`=iBU6;#J zO>NDByT&W+#mj2Cf`x2?;1=1VmeTiBONR&AF)m51!b7F)0Q*>MwIXNa*a6gdj+SDySCg(@(sq&A)f1quR^ z6E$G9Rw(_V@&(I^9S;64g+U3u>bZ!5-x$MLs1^e9Tv4je@c=XB&yD?sluSK|jgTynp?KsI`^JjFlm8}mv{}nm^ zASCd5*k2$?o&Fem@4IwCjDz(lAZXqRmN2`mp`D6d6-wkfc8KV9`cI_LSltQ^dm2>EO> zqmP>XQ7X!oK*Td+LQSj;M?R;0zxfjU>$`otjAeT(hyK-Qw! zUhg}dc3<9XfwB{^vo0_s)z4P%?-HNR6GYK1sdEu~1>cJ01+ifErAS$XmVG6R=~xQZ z7+c(o4O3LshbXA`u_dZkhjqnw=R-gi!5=IWVr)&r*J9XG3Y?GedvBeRZmlerwr9oP{ zyPo^|!}BNXb=~isnKQ3BC*{}y<#Qa;JZ>j%$2nxq3Pz-3T3IWtSRSHypKaxmJ{3cf z=)>TZnfvj#o}I4L5BN^D@*7p{CS9EC>T%Y;4y5b4-oF5oZ%RZ%-~WjH@6uS z{Mp5GMJ4-1B`O&Z0>_zc@~b2gz6kMlFM%Se&X zkimur2KDQWf#2zH<8}cZXLDb}YfNrGod=9Phfvipx!rU#3V4Q1wvFvlHQb|g<^H{m z??ZY2n18;cNQrjU`%#4?h22oVJMA6y3zh&HOL(|q@fDE*YJ0o)-#&Aur8bk7cEkqK8ZgUgXdmSUMq>EVj9^&GPut;*Bb z_?~w3FUIii|7lgpGJhEtvhe$qm<^WfZTG z_;ZT4XlJi-b;P6aKzoFZ^V-PtUm~6#3o|RVtjGVIJb*yJ{T_nOjr`2LZo-WQt{t#{ zui3BfqDNn|nc7Ma13w${EJI@HT^-E$rKfnQy77$5FzPXAxaEa0&Ia(8R+nVVf3n%O z@j2Dnfk>P#kZ2Kid3j!4MBK;>QSV&kTQw#41DR7imoAz&2;Q7LpUn6z*j zde7KIVTU2FiB zzSIn;TNn*ViYU8Dl@59D2Xa89^3=hUUJB^XN+NoErPtZM)eA0K+Ni(3z{}d)eb?8I z%Z6w8(rJcv6UujIS-mZ#z}m_H<437HRvCD}fXf9(8k1azP_k&d^so}m@KZ(YO_%tI zL#Q;ETP`Z0hWI?9gm-(82w#K4Oyp7?4Gza+)Zq8JQqs zWaGkBGaa>K%oJ zz1n`|tcVyL@P#PK!*3Yl8dvecO3?J$4PxyEnV@Kf?BIj+tPBseC;k~dK_j!y-xLcZ zMj~>%vJjV#CcFR6J`xl~r!C@IXR#R`*s?>EcI`>H80|X`7&!JfS=EDceOP;w15s7? z3bWAJfzftOnTyQXr9sma~~L+$1^iuu7x~HqdLqfxTZRdc3J;z$?HlM8OnfY4E;y^w{xmH zt}A&(t+^g%_21bouTJ2%=?1(NYM+r0QcdkjDs+avqDw{%kb6!B2lF`HM0xwM1x(4D zW~}B-WxZW<{2^OOT-@HV^;WlnU@(XTYzRdzzp{-UK z=1!WLTXyM>%n3svUKUwu#$r6kgyVFe@xiQFJ`BbmUW4x@fgo}Fs+xlqyMg0u&V|rv z;`xY@$|>iV`3{QF?lo=0fjoqSHC}%EW~6j*`?PX-?sTKYVWFlCGTyP9 zjNb4Qe{{KeC7YyEQ|=7`!rDUWr_`xUBO^=E34X)`3;bC_uV`fN{;$tZR)kFgaAE$( zhx^{3sQL2)mDkR@+``Ezu>c)-tYh#*<+D_MiUuc(XgWI|x*K(u}i#=yvYjKqP8|L#Wv$?~VN2fKVk* zSJ~G-r$eRL^M~ zbc0pZZ3ZvV^}sVCsih zU~c}FZZI86)>~?5i8ESXm=h<<$9~z@7-w{WAiTgz61AE?TQ)U>NILJM*Q!>ZEAP}^ zAnN~2=r(Y?AC&UAFh_E`Z-O@poH7WF9~Cw`{;F0u*AkFF*|$aA(#CH%DVwR~J&_S}f*+VM?#D4CfW=9iF&H|VZj%c$p0=!%#8MPYqr{JzW;no;PBVc!dx`ydNVDDT2+js`Q+8^zznHKYDxqCESzQ? zC#>r1w`>Ik!n?Bu(QcOyeeG&*26vr4So|@-3`{1oJCJdm3*6frSa?Z~!|0QLg;_&A z-Ks(gEKQCjSc>Yp-a_msy?@8CTz&KB`#pa9jY;O;vKcdLN>)V87rDZqa2>nSFraho z_>)Iv|E3?At_2wRAwkpT8#sL^(GBB-b6aKNmm+LE3r_?fKxjTYUBAJUWE@8d0|ln* zfK*{zbm@5}j2nWpQ-UovPH!1BBAKEL!YEcGjGTjTK6^*ciHL3*S8RFRscp&Tlzhol zg93-2^f%TX^KnC4HJ`l<1qtdV?Rl$1whP^?&D{GHt3*du$14$!!E-HdmS*-$zT_t2 z0K3{*@X&zxR>1uS8&yoV8s}_Y^oIt4ONf$RhYHXOXk!Y`7p=^KOf|;;TQG!saroYh z(91Y3TLk}FaCF{=SDCJ~{7Dk{#y*`M- z(v`WT*?U%Ir37~lrMEZ84L`}6Q<&m_h?;;rhwsz?>$jkTGIZDY`z@-y#F`WSTv}I+ z%Z>8Rtjv4y#+Ma2;j}7`9;+py{VcAyYTwp_K{LnUpkR4B$ap~&2W-9IB<5H<=e9{J zg&P=FlEUDVzkH%GL&(Ill%m(q5qza;f%3qoY*v`fsnIt!*m`+aX?zeeW2Fa1?FDR~ zT+_WnF7gME!MFz|tl8J!bh)QYA~^*;)9DO1hCGsO$19Log1h`0KWqa==G=6H>AGnS z)kRuK_xs8VXW8*;tSl*Nmbex-C(9C9VlE$B;F+D12>QOU%%CD*IS{j(I0UT>#*e|# zi&puME$bTCuxQ$O6jpa4un8jZoO-61)&-KU#k7Mhu~n$qpsS=9m^JQiHet9 z2hPrWzm^+m{5cVnaM9JXmGggY2`=xhYToM-MY*w8Hfx!0b@uBSxir2a%; zVhNfA{(VTPS=m}tXrffY#SipaeH8%EA&2Q{d<#UZd)^2TsTFkjH5iY~J}f5b9OM4^ zL^(Alic>HvO>*H{CJ>`Y;@XD-{+TBwiV&)-HEgk!fa2h@%Tl$mUFKfe{#ak{0)xbk zzpwm8ljMp4+EaO*HA9@WXBhq!AwK)oHHE_WYqGBp={NSWSz!M&Oerh8$ETU8?Qd>= zLwK~eDbL^9Mx4x7nnEdA(NMehho0z4P=?qz-_C*0<$iDAq7)U~B(LxcSxm&Lj!$C# zjlrVtwqhVU5Y>WRu?7Yh{Y*MQ&`IX+hyj5@mnOGr+z>7@wd7Q0n-{$ch(D%Cdk(=- zNv~zwJ_OIYCy=GnV5{SL`_dAYLnc4TEj>LYZ!N!CV zJ#Whq22c8Ew5$I6 zQrHn+gO}zkENS1H48+wpr2j#`Gwf^)%QoLx9 zmER0{6~2sX)v```Iy#uUmxgT&c7*yLW`r{W292%-k~!zHQo2c(AQ%+9ScJ07WfpY; zrx-{a>jTx)h7Y|@g=y5Xl=9*lU*DgNpH)=8$0gia)Xoz$McOGm`#7oua6mjMhG632 zFRf?3l61z<#vJUbHA-95>Aq08+Id{*mPf+F>Ft=p!;ww;0Q8o`lF!b(&kg$Q;hvo_u4{V2pqYIGEgW z$CNfim^u)-25&B-2PL$6qTHwTvc*%pXn@)6j=zHwiN-f~_+axi%RdL(Rj>?+WSb0pwsqZNa*07Os0)xGK6W>5(@1M7w&W+=JtkZu%=oe~dYQoELwqUplgw#~(bK6C& zTNca0zmkuhrJ$a}U;sqPEt-IDGQo;?fDXrd=G>CVhu)5q5T-vG-+COsCqcQC)CF$ik*Y^QNVx$zzG&;xGi*uwqQ>Uc>9`fBw*6q`gCCP;~O@G7FSrWk40|~tiq1lMWpPy?~ELn4gH-boZ zwp&KY4DNnqcufRX=02Sfy6xSDu@^rny$2bOO3=|rJdC7_OkS?vwGW;oVpDf5G8#_g z$KbHJir_2I`>B%4jJAwSSb6)X!0ePKZau0Hf_*W9cM-73gONkb2__D^{2o=WBOeLh zt2y}tBahoxMo{6W64gZ=RFKf~s`LvyPGYccmH$%-oEXaex|i4-X=+ii3Mk&l!O*lD zr#q~CyZCsUDq?^qG)?YDiIBIn?0x&q8t57bmp?#odTDIN*zyG^R#=wLy2LLlk`_d-pJ|WJ6;6D4qi9jG)pu*W=eso%qBV? z3qr!IA(9ttO^+O};|jqc=*6UTf9GztK5&a)`(`aOoHN&zTI$SUKfGVqq6Qs2E58dZR$r8!BAZ|}U&u?~C)2$j{r9U#0@##0 z&K)?QD9!@|1@4kkrxpUcyAqW+vA+}U_HdLQ)(M&Gk!-S~@=tz+fI$aqJub-cUc7!D7BwGzm71!kHIUp--37yu^y3*F4&kB3~ zumqTlp^7};eMS%T-2%$C4I+kp zrhzPdK}S}Oy-|Z|n$#PP62P$Xo?q za`l(^X&6|sfg27an%~99<88q`9U#kG{l%E;wc+-76bwg}-0cz7`J#3W_W!=*?l66U z4JE+`h_0G~dbDl<;6McC2OI0d!sZOiN&#*!s(6Qdd`=GP3)yl>{x%P$x@|t4n6C)< z`}OjK#OxBhAAKxv^pefm8_Hi4KiR}7=W|U6SM9yW_<}~o)lh#v3w-(eKPC?e?-h8G zzEq_v-|MY=cL~X3@le;t6Y=fI*aRKnaRVrNcm(|Kw@j!P70H#%@)CL>x8;Mt+36vV zL-k#F_udmLc@&AC#p%kLgh5B@s504pRutM2HH@-7OZbLe=b(A>xTVdHPq;;oef$IF zxNiFR(Lb34zfX}FVuSov2af{jdA1B%RRcgDHJDM-H~6@XxoCoS$+;jhbD7>Jr)`=w89dm2;%cmS)0K4o?-Uv{Pp;wxt8@Bze=HrQi+=QJs17p~^TzukrR7 zw(jk3OZE0DGe3*|2My>8u*GR#NoJ(A020y9)aHmfJgX}TJZ%$nu;cU&MVUhfEx0~ zVB}rNCu1OE^GBnE>L+(;@RHK%Rt+PToL%FMJWCwBf+J0f-{L__G$(x3>vUQ98eX%+ z)l}q-tz)G)4LN^IZ$?Ep+B^mG*N@n@mOP4`x@r4gFY7fuPMI3&66gKuCpr0ff^MGg z?r>CP^2Z`vMRef3EQirNVmkm2|I_MR9>N{z&2BsSY*F)J zyPj}0`5yRhWA9dIiYib#>EJ0RRs?PnFoIR%|Ijez@dA@xo8Jv0aZVRwnPb4`r;DyX zeK)$C-45!!vX#i`%hrp8HFn1;L}g5tpGJ)tVt^Y-61Wk<{Qz#iZBu<#I?hpk>Dw-Z z^&G=K2S{w5O{m=Qrf^9nvk`DBZV-sC_H_`&W=(GqVfj^5X6x zeD3~v?dCxvqr|qN8#(v)`X{{CXr|^=jwezd5Q|pkc=9v!d4G;H0^GRTEyq=85HcwmMc?C(WBo_r+`;Hhb}i7Ph~CSS?I_V) z)%aNCR>%5|os0M_KI=(n<%oeP*~J+}Yh;h&fm{KFd~oPSfx(IAXr^~zxxP34=dfNC zA|D%CSt-U|op?C)lR+NHfhr;?b&$GT^anVh#DyWM6qu^!Ua4Afd{N2wK4F04G%X@X znwh^;jwF3w_G|5VRo6_}sPza*Q;*fAB0n$DZ*LV9{wgTx!|k1hBn1=I^SI||_0%YL zpQwIDwJS@B!`d|FYmc94+<7&3)Wtu1EPpf8e3rY(>aYtMQlWtAkNG8wsxb~&&D98Y z>3tDSH#ku?qK~i*Em$)7T*Ma%*e@No9S;26|#F@l*=Hk0xj4-w*ezisekKs?DLVDf|eh69W7!c1!3 z7%(L^-9yFU&I=@?JlvKJ8nDZbeM?89=nm4_)4{%p`p{ZtUpW$_Q>I_`IN6%=&C~sK zYT(L9PuvrOagS25eXL)(0cP2j>m9Z z5o!~nZoyf{S~Gq2q(+Q&s}~Io0OprHjMihfvh*fM1ilz50C_87GiBZ7l)*mtXM^}N zQ;`sHhm%L{Z6EI4qc1v9518Cq5}if%kl&{EdLh4gEHWcO zGtUHJP8}%&9v*jHjcco&SyZ!B!wc?>7lmI-&G2riH;KHJH8@4!e%#f(!d5&IF?( zCIHXJmDb;z1U7KjP1(O%)5VN#Oh>-@CPGm8cFpc<123o>IWKr}%1nK`!PwMzTP7M0 zxh4SbqDDXpy$(ST$UIobtEdA!x6L1DXx_r050+G$zblU%GryyzQL_`I#BBfc<4YI< z(w0pmCcS_{jaqnk*-*yyjUId8w=Ug)LJIvKm^DNx`?tXMha6@u#^Vf$c{T+F^O*vz zk0L~xRlTp-_zGFo8HUq^#k;end5WwY+4O~}XT7O#hkCW}no9YC)p51oaaK9VQ=0J` z2fn_+l=`dlwT^o_Y1lxwsjv@)2R96R=g|T^U&!yIAzcy84C5df?R0)(KPfY17OzRS zW27AXfWPAFtp(%DKRnd971+S>0M^M(&ahngMjYtNJP30}I?fkFf7B;0U zWlah7{~7c;{e1BXv$jqh551G6S^=z{=0YFjuDUJf4RAdI%u9i2@5*`|;5*y14(a}? zT;6|VbyHd3U;VG*K95&52}x!f++rbABUr)5MJHrPfgfpBN@);xr^EK~-QF5oWQJ3T zfo0a%fRm33qP63!$K@=4fxqKs{K-g?qLa=w*TwJPpZi(Af5S^((4KT=$p!lNK1u4% z^TYnbms>~hT1fz)ve1A&%Svm2 zMUus6%FshcXBYJc#iXVMY#snn19F+zp=O+vFiDN==Bf_d5InEk-K z$n#TRIOD5a)_NZa#Bi`{D9_YlE9)PhvR=k43T?j_wNP!Y{!w5zFCDY3Zr%WY%`Gj~ zZC=)9`FI9>+tlI0yoob6#T$o$O$^T<*tu_#x1_4JG;OJQN3}Lwrr%~`$Z@o{qR*xW zt2bj_roPA5OpzwdYh+?`cA?i>#wnMD21fHLlI_s$B+*Smvj~n8OKTh}*Ewa}*_inZ z3dsohMVRrWuc&q<5_;Kf!|Hf3^`L^Oeqtnwy{{=Li5$ba?oy;X4pd_u+CTXDZ{^ua zXjV1s&0)2tnfQ)W_>4CFLi3nJ_8m-JbDR6TH_BH*F{&bn(9 zI>Lt)`Eq8wS8Zvot4S<#U@QKn7BSc+8#U7Dzs4b;fMM{J;K$=lA-{b83mARa_lDOV z0W5N95{nD|Oc6^J&Wzz?woo<~Tw53vO8@C~FSLMC6_dTfs8oogW9akVbFj*PVikq& zD3cw-UI8doWo3+V`h2j2s^O;w?(n?kF>~u5BiWOP9+e`d zLevkP8N!p5i1k4sK85C=6r#KNs=aOqE6s;ywhfd#PM)XzgFjLIb) zc{)4vcq5UFT_-VLsl{P{tX?fb%xwcE2MZ0EXYNzHOeaSMrsAw#{Em5l8|OB?YXucm zMdJ?`K=bW*HE=0)G>hcy+mwmuKIWBa`273yO@5JAb6!XuQ`M>xEF5xe5rQ|>tEj4( z$9hgdyEUGr;|k0{A_VBtx{T5>%^z>J3T!Ix$K6I=i7k(G#H)m&_m8A)AnJt3(Fe{B z8zRXX6t8}wzGkkdKZ7n9V*iBUsy9q+QbTTXL^q={d~S4z3ip&5rnIb2#VKwJrVDG?+8>K4g_{>Sd@A3-(2zssdM0kVQnKzZcisRCq5I zV8zSMXq>NSXo%V=~V$tEpb*YN2uycTcQQ zd@La7^>b)p9UR|Vslx?PeE*P=-ij{&Bn--09e-S|x$5s&s0CYu(O=J2wDY_>lBm5H z;kZz$xoaa+G`%u=@JBm2ayw{2L`oiLYkkzP3|JpcA-fp5{nh?BG(I_I>!Ko(XQ^VD zYznTe7gLXY?TwoI!QOdyly|`J2^@#UV9Wb{bW6uL5Eyg4IX;Euwfq*U7MM!-^g8g~ z>|p4%IS{tXs~IbDxGK$-852yR%5m5+S2Si`-G*;vUic??V|LJ{zVlQjFy3_tF*_o# zW19bWzt}q7caRJMK!hAm-W=YMYoVeLtbhWma`=kAI&W4>!7X z@@+9PZ|xuskgNMcH)jm3(Y7*wrx2X$!oaLBB-Jp1BCl78g#V3S zal>szj3}O7Qd%jsbX}uns)iD|C|MIM^P)&uHfW@*YN-Be6DNpP2B$hUdPTqdkL{=g z9%J}h%{68{2G$&wVW7%u1;Kx%Ob*YqiRCaiEqr6w7_MapTMB@pHi-F#M{D&5&S@$+ zPRL%-&0S?H+_hh@+0;V9NYvF%W~J&2kKi_BMxN_Fwwzqm_H!awps)7k@*gvpb$@uJ zp$U|IEekVp{ZaB#9_Nj{6f$Vjx{HAc)X`d2J~`4iKn-s0{EHuH;j4P$w7-6zX9)+o z!9ALXO;eN9 zGeU;+Z1l@R$)oe*Uc_HG~HE6KnPwn9}3<~I2(p_)r9hulJ?Gh|M@1qOwF0CIHlsCBibva-40fvbQ%TG zqn}sx30p|`A&e;Rp!m|zpf9nkx<5=9Tf%t04>_V%f!Q_3TSG8NO*54`sgwHaRa0z^ zlgyYSGpLTzMnA?Ts}-?kGQ(`AssWo1Y}E?|^lkWva4&tV)^$;JpO-w{f_0;2<=`f*N8rsSVuAAbXZp4qGG6|kTe;E8xi2X09BL11NcP5!#uE?p z{?0mxX)OC0#9J;?k62po=jpLEJu}_yeZe!=7PZ{lnPRH4eMXD3d+wb&^9S08k*Det zF`^c$TO=gdUTrSC=FumX?tAOWG@sqT7&mX*Q?D zK%->Z--nJAI4|w+ZdK=Myy_u_Om#7~$SHNtx-3!On_>=j35nwvEfA1uPnykHHJ_w} z<&sT&H+R_vO{!0kBTGH>`stL553A766Y@ffEl*x>hF14F;}Q?euHf!)e#pDwgiTUp zDZmIA{FW~S&&gaddEJL`y7m_ZVdStzTE?npV`<3j6yz1oJ0ijP3ZtRn0{Znl$!YZ- z9}|3yQm0il;=g7zd9UkV|5R8tU`F{>=(^g$I(}R%$xaXf8DksQue)X0*-m**iJw! zqcb~+E*Xck7NeEQ`-k9#jIUmcYZj_c?3S5j$k4?zO)KKpBXIYi;KbtwnU%!@- z_&?RO916>uzStWY{S8>(xf%G{{lniIA1@NXJeuQDxa+5ft(FY0luzD@PBg4ODjH$% zNwBuW!TB9CDfN}%{Po}e;&T+)K=~++(_m>ElYZ9x%~BLMwbS$fps)ZRIa~L(cHm<` zS$Tf`kMuXwl(i?&9U>vWA00aSc~`*d!lU{1&Mmz`*N7(A%z6WdnmPpn3C52*y)D^7 z%BF7xHPj4AFFHgL!gB?=?FHD{GT;r-2NYvGa(TMMhug zcZex3{0K+|IC+|qVq-A(0PQAHlxw?Epv%AO&oCVdx$?|K1grYktI<~`4TV&kYB4Om zMC7Oe%io4tXP7{zjM5$wT98h_^aNizkGt}rr(QA@n=dz5h}6M z-{T7f5p*bkigCfD2wSZ`p0n~^m>Z6b9lrkIzgbvY>$VA5A(H|nZPs;cP_}2bniseH zLv^(vasdR844NY8q@gK1T&}Dbi{iYNe=Tn!#(8&XTb`bV_WN)Db~Lp7Q;jWZn_b*q zylqYnIkpQuR>A?{dXM4BvojpM^><|2pv7$_I5M@F!WEEt+~=RE;39XFEtkHbcN(}>VkI09wKbFsFaHYSePp^0yOJvtxxFeH_d}Q`Qd!BJTmA51}C6=(F~}B{NH)%_*gT%>3ni~ z|Sn@^yCny*y3N5=aZJ3qd@Zgu9Mos=aKc^4USR5A>oBOZ{+utq^2U^FNorUiw%VOp7&}ZM(%2Bfc!lEnaC+Y|>d;cRirA zS<>Gg|GW41uvV$lu9N{s$>yhr($vXbi*JwOz1A^Fe8ttN*MDqaZSV=2U_E#iUk7zD zg9rQb1X}%p?o(^qDbfjNGS^R^JCX}W8caTq+8N?E=9uO=5B=kJadJwQ^fIcu(Q7)V ziQnhFTC*o+HggUdCT@dik2gz(xI=koJC6RuMUYIUz}hB5Ds-0svlkno=jojcB2en0 zvVfMtn39o1XEvDtwWOf-e;K&uEj}IYdsZ*5dbmQtKjFi;rd7<>6PFTo7rkuqdW3!* z!x{)9y?LDJ1Q04TNj20gH>MHzk~r)Yf*ydUDVLkaDB69~xr zlTmA;cTe(T$kAzU_SN}UgD@R473>V(wkpCC8TT+@AiSTeV@TaLG!#O_;t4SAqjncg z8T1(3;p?(BJ>1Ark@jpPyIcv}L%-@qD6|SlzRLf4l1Wowf^9aH>+$vMg)=hPOZ48qT%d7mZ}i z8w_3+Fk_7J7T$cBklonez27UJtj=z^OgQ%J^y!y;sl5jpX8n7Yi(zFr)l2F1@Fvtd zX%Mraemg|m=}bL_F3AsU23@_aT+jJkz76FnIAL0OP7gJg`~}q|X@9!7tRprvPv%EF zvlO!NS6|Hl`?+qr%{2uRT^I+^LQXB(5%ln8y?XDZi^=pUg56=OV_}lkoOBB(vdiei zF*t$wi+4X7R({YF5N2d3uUuMixwI1Je`i*ma8Ph3Jp+Um1E)x7f zp>EPh4No3mqE6bh@lq3^E1vx3B+7&}G{ucOG<8esh_=V8=_gxX%WMHWBgS6RZUBi^ zKHgdxlhR_$`~*z?baxuiH}Xqo(07RRgCZI%dXRQpRqzlaGPGtuCDuH*Bb_+HN!&60 zSIcE6g#ZN%T3>ruaVN6Jo)Z-#eKjjaonUNkCJ^eOb>casVnL`|q?kJ3XxJWpxH4RT z`t(Vln6TDXYI#E8b*@Md>KZ1-MZ{(~!$&0I<#vX5ioJL@S*2qWOuQw0rtI6{+=r1X zJ-y$$j3qdM#`<*)a+jE>A?)bqI1cQq`YB}k*W&d$-|-x2v3u|C8u`kln_q>n1S@{^ z_|xdv^YP?BlKG+o>X?3(x3x*n7iv|XwSHXf>e!A8g`+I({QC3Bfb=!=$8n$Kx^_1- zQ!{KD6!h=+G#Sj3Ziw~ieAay@4)&;1dL%Xskn&@pA#BY3B6=bB8-=@+l<$8Z^-rA8 z`u6QYAd59UQ@OthUA?MR3eV{FujPQn^mi3m;XJCH9tv5V1MYo7j!F`fV3mxLb-(qw z-?zUi+*=3+@EM}N+p;q$n43;24JN8+yban(s^0u6524oi_DMw-b29ePbd{ea>6%*g zr$K!TTcx6b(yf~nze;3X>CCW6pn(>RRSm0opi1sP+WT`oi{j?ku0S z=YHy&3q6*|l*Ka6B2_tRyX#JIQC#A?)(PExTGpJ`pk92&5(_)S4EY%QYELC`g!L3e z7G8VwdgKk|?Yt@T&?WnHw8>f@)gbA2RFz>IrgOuQ2j8f!T>PuEt!6BdrlbT0BD=@i zWzPVZ0}`let?P7TP1XZNLyX8Lg(b@7)8_!d;$E*jYlVF|@hYlKkxW7+)m5(peE(j}=wQZc$}08SJ`G#Xm4lr<$JE z+|S%s$LrBxWG}u@gW$}HDFefxKrUVHCm?8eD8({5mk`Cc!S&V*_T4EtHkhDsbrZc? zAp1kL$MSly`$b#zR|?nn@6d;N=t@?%7c}HKM8py7#8*{wkn`m$R`s{=cSX0eTv__h zR)Z;5I-(>m=zZuDrW5i@J9S0}yu*`L)mEJ6J@$_4^mbeYGxQym@ec*ylvF`VjGgte zKf$?>v_S*E6L=|seCp2Qg&i<3BR3JFOQ%V$N~6P5eUD95|Cum)2J|tuU7i0IWu=lY zMpO4^Pvyf)=2GV_;kKNMml~?;8}z`}eON8!TZf3zzA!+lU4lQ8wthSu}3HuU>7wfNfrW^~yVKdTG3$^RM>4aOh}y$((k% z>Am-V@;FObSk+~T#&`2#@VmX5^yZ4imru%143Yh;zU}1((WD=v7PFqJl|^UQF$F9N zC{{V--AA%^$(WjU3^xYIgcf5TBHh1PuFOrDL|Z()A>5Msi@Wf-zVq9P4amwzMJ?8{ z`0bUWL;^Yz)WeH4Qq~pms`t-+KXWFt>c4}vcRaXy*v7QvnE91U3*q`)$Fh0cfJW+~ zB1qC^BN4l3TVrG#*w7H0 zE-K8Lg+xI6r?&v;CCx+<70J>9@+F+`*WgT>$F2T%rdehT=cQW`!mSCOwC|{i;W!s2 zt!|~MSSS~tH2={}qSNmr?9@>sN>ve#8@pXgiAD#G?%gm>Zv~vjv zD4Kaf$$g-9VcF_-eo$RK&_HgZkE#C|QsKt+-_4=sPiuE!s0e|Ck=sSemdcn$Rv^hF zXr(&2JZwjlVd0`*I9B#)amu@QO1?*VC54ydHL>JXxBlitQ-G_DXW%>@=O%I>4-L`z zyxm!bwH+LylOq3STIZY@xKNpRo!7B{;%iB&$23e})+FPoWXJC11c_P-tH(9#M{8-39}wFG z{~eue)f!UwsEW zjj1?FRMShwO}WeSgU@>-4~+b4GdHf=Wrv6<8Wd<&ENs%QiW;oQ$=uTl$r zJ`3&v;&)4ZbVTVS`BI(hAsMr z5=P?BkL4X9SfJ=xblSj`fFCrnuj}0{@3Pg*oBa0n$Ne=*7kd7_x1>nlZcDnfhftWi zr&huT=8v_w547P_03(%!opal5x-5Ed)9Bk3%hHFL3FT40F?uFMGRKfs4VoCzmXzu9 z0`+?t^&taR65Nk1-ohsNi37bkpIT*bU%XF~5L%I*>?@=X3h_F3hZ8#8Uh`__3WhJ# z$+hST^PGgS+-MxRW%gF)JpFZlph2;5iowPR5|E&+BfZ`7jv<(lY4)~+D8y;=bFgaV zW(%FQDjDF{(9_UR-&x|GB{1NH6d?+zD#I?Yg_Dz=%D2?CzbHhh0tpy%-srwd*yEk7 z0{gn?Xq6_WIDSgjHL?|(I=~4mgFO65N^cWP0M98Cf zrwucC>&wtQ8{Tir&?vra2ofeH!*7RNmBu4*P5;fG^iLyYo+X%!5hRK$hH zb|DKo1h|B6`Zdl1u-u|%m1^PfICAsGWxVJ+StH4&)@WjhYD9kEGTv=yDHy+cEZTF+ z;&u4aXtgR#n&>`M9+jq90}a$bK&svCURVWk!Yn2(2%%CK9fXj-w-rp}Ec_%~M4=i= zF)$YwUJ*_3+Vs!VJ$VbCA&w8=RsHi7JG>c|`01&`S0G(Hysizn z!ctBvwb9R<0rE+C2TvwXhd$v%53XWRA@^p6lZqHWSM_UDJmhADm#MGmINNt|O&7Ju z0U=RP!T7BDP9o==@36%^dldUF1EcfyfMy|xf6=iVkaN}&&vJvoOPqU?@}p%5C;ni@ zLZXVxqrMY8lYI}fCO#&mjK8R4G?`@Dg*}rk`y;Y2Y7IEW8KXtlTO=_YXJKGYOY&~a zc=JhMFy2~!?a=TU)NQpFf&n6OU-I7yb>(D2kz&rqW&l;_hqEX^e$;#=3=3tyx-6LL zmH%SX;5zn-ZaVLeSOKn*q+pIMsi}Ek5SePqyAwsKM7R>%y-Of^Nq`Xw#%Xmz|0 zkNZknoyFk?d`9@7A}AbU=XEbsCTjF^jRir>H>-2nP4^z0@Z0I8Z`OY6vN~lVx@h6p z@1?)Z;hBc(!P@b|*s_GBHv(vZ!qI3;47&y$H{~?%nRX>umV)#6C zRX-8B9hN5X;5(+E#0Bn_Iy&Rp&M(A%*{zy=*^7Lc*(5Ugn(A#xn)nb#H^z_ruW>;= z&2+5~A*1@k3+zj+9>^>gZLAo7Vwz(r7Z2|S@Jl~AaWU~yMkdV+>zY)r=FYmN%OOIy zV@}Ywr^8;swwwEgHmdOHTcnq-@5FzT~cTp|dhPj)jpxGKFWu9?BBi4MRIVl;HK z@=NPay{$3)@_;|JEn(gaL{ErME2RgW7Nw4t(+|h(IU`bLPDEb`mi(S-)mJovESY;5 za@I%8R-^_yxK!VnI0)8b>jX%eFEeIh4E^9Qu}ZpozXtS~sAL4mhsI%zfA2-z}P-P;sJ1 ziPF*pb2}BHkE>#oq`EHe4GBOxsS0JfFQT-OS_)hM{MQrEDr1qo8{58*U|CFhcN0}UEHr&r zJIN30j>qIKm7O zuwgf}QaklrxY7T#>6KQ;O9*fp-c|9*R}S+!n)4#Y%GD8_H}Hf7H{nlMmv}CL`a*g! zjC>Yg5ZoqgX3g*Q!+=^08r+{59{kgQ9-6x_rcJ12mr94FRDWc099g1*kLAjb)5?!! zp#H{ruQ`0 z)ybIX@x~BYDPx$1lJds{-N~g|U8xb+ic&i zD`wfBd=)Q~7HN&N93p~nLb;Rq$+z_=4-ase02Q>8tEtOc{z~aojJ7y%+>!GG`pT(o z@nax!zTHEDriu69V~uG-PX=}r(76ALDOYnDMzOLahGjNeoP8^i-dwcvSax9bt=r_P zXbx~0kISs`61;FrtK4h4S&ye3#@X$FU8QmoguWI$K8>vHx9w^m9=|WjU@B&V#Ben< z;PVsg4KKPp!;kmoR3pB%wzc(NRL;W7EHlfmsog3Sv{(0Bg1s7E)V?PH=I{HbWaN0E z{ph2g+d1LKJt??P-$@|D8xC%==>+I}$h|^n;O}^7R9}gc%;Uj7wUZXB2Q8%@$@h{LB zMF4=0pFe}dji+VGwsp2s-Ca1)h>2q5WBfPqFf@d4?cA3|I%AwvP9gZom^XF7(X!I_ z@K3A0P_H+%_s-08@CBGaZ@UT)Y54J^2`&P;~Y+IX_dM_!ryM>;^DJoR= zgF{oVdfz+ZK)=K?IWdwDJ0cVnm;qj5^UiaiFjn_fuqOxpwYhC(doDuk0y4cydb|f5 za|+X?cT9sBlOydqWp**pN*J4N>HUuPGwMm%%fG7~Rr8R2>*v0n+#bx|k)OzY>S3Er zyzRXL6vqTW+&9uke%^)TpEviH|C&|HCuP{Y{o8F>{War%n$|NfGWaBApXqi5Ppql%&NYOz^A-&hP8M$3654SkZBkOn)hY{bt&uku|3V{|;=x!78pXj13ET$?ta+GL zRs`My%!}K_pVnPO62nb{6pLKCgP!!RpnZV$G$wJ_aLYR%65jTVpO&ZoD+^A^otiF%r|@S>XoB}Q*X4%k4aL6wP1>%NvjUiS#X z6^>x1#*jnr9ypN`5)o#i&Zph&o$Hyu55+q@A2v|Ym1`Lm{V9V5(Kv>_d|w;VvBiv7 zFq50>Q;-iyvz8c}SGVwr^^?H^Y(5t9_m}x~4?-vtTav#$oS`z$tgL$Eajs64dJz$ilJFotn&qY= z8$xgCRT+GDmhF4jSkSAqveMo9izB4$YMkS;O&rf>@|;IKYC;vhS`xp{E<48|GshwN zd|+dbsJ%Z|a!NiHHS#gKfHm#=`}%C;2;m43gLMwL7g&MIctVW@$fzb^Qdug2g?^XQ zDeK&kRn5Ar7EKOL{5`9k$^IUg1?R^$RXDHwfWdp|@k`!VGz{Gdc zADAoVJQ;_hbu4G<0a^9W0f*_?_eqakW`?1lmNs#g&39ECx9N#@Uk}% z;Ds8XBT4p*!jHb{70WFdri&y!WLCG{(;PWQwZ4-Ng|7f~T(=}ieBR37yl{8x76Wpl zcd43~vGvc^o!C$6>aX<`)U1MjRlDzAW*I^rxcK0wAgw6+5gnjBqXHxy0=)1R-SF$U zK6i2NU4~!`bfhf5)|)0YCu3ySc>WbgNN5ayh-}rcj(c#{2S*eZNVc}< zRQ-`e$|>I9&iCb#1tGkm&;~H>_=Lro!-b8OlDb1vW2(q3%?!fq37} z;yE+Ed@<$a+=gJEvBQEwxngw&O{jl_biS?S$v=Yn?zDfDdYT{Yan1xOl6G8+nv9j5 zQrl$hA{ykD#gOmr3|qHIEoBR>?3$845>bQbR68z{n$2<_b`X)d_74Zc$7B1|&k)~N zG?z$AJ$(H63YtWEn%rVI?jNmAbr2U}GMg615MX3Jllj~o8#Q}OwMKQ(U7gj^V~+LeXceDRKlz1-q@m5YaXO38yK zi-8UOp!2=6Q5GLau!Lbx9!8`YZM?|(tlzO(8Z1mJIVzyEW}L^&*#9@ew*KxwK_luZ zgEPrNEO@uPYlt>ngCb=Pd3pVua4O2GiYrrI(;C_CSJJg|IanhpvF(#SV8ol{iUQ^% z=t=4FoBv`})ylmM2rx)mbOY&F&13F9*ftzna|$z}$?6nl%I9RmAu;cNaOS9%P^Jt6 z__MnN4NTvFWDl24m7jp9cvF(t=XUdo*RcuEIKT`Wo_*IySRxN{&{iefx9xM?Ytk_7 zOB(-BzZ%l!#!^pGmdI;&kz?D7{^DC6(-r8ck+(kTm%?aQ7ZNbPeqH^Ea$}rP-l{6K zK`E4WVda2@rHw{Q6?fU%#-%#XuZm7@hy(ivGgD%R>VggcygLaEfbbPNc-QqXfRUf)nUY) zZ=ik^RFM3?T^0uuesN|iyP`K9_CwD{v4GRILZ*X>A)wp;$CeLS#aJczgXGrfknrsX zP(RlNHg!GwA^;Xfl$V|gT{8vHX~z+Jd;N}}iTDgO8rLDtAa-|5FisqB(l8+7!0dEv z=~zJ+H|Q#jmL8z~0dE<`cZaEW9bJ1^H)D>hNHvfq!^R7wd`OYa z*h%KdkMFPgM&@o8KqPlRn3<%#@C00i=!@P{-d);c<+6YZSdPwL4_fkxYQiR2UNWLn zzG@6Oi%FL=;F~X@+uE>oybRA9#N-;S5c|j$wr03+HNHHX&K)_&Atv!#gja>b!N3)!&@{_JK*Vi_hIk=IBMvPh^!N$&6TFN(D{2 zy_eW?3ZbWUoKOCMQ_11q#BH8}Kl<1ad|ZFogT3r%xj8$*t@F8-RfP-4uBOD!!j#FZ zG=%JH9e5X^o>IEr-6S9NK4Q_Eu3`}z!>L})QsMCzZVpRByQ z9<#^&l#|XoQ|l)ESn?{5=?bGlD^&<4@ejf%q!l6}(*#0O66E@x^MPUT>100!9LbcM;uxSU(l*W1vHA zkC&Gie@UW^Wh~4nf<$XmPBr8NToc?J5dZjoZ6`R`SB!;fxLkIBNpytkQJr5K*QAcG zf4z(`#(vi%apShqcXjqi6z}%$MTQCU(|hmHQ@IW=mLxp|?hj{g6&Hb*w{Vv_<68^= z?G*%KYQ!w~YseEx&-vYLTF4Ulm(xy{R*sNP{HwncE?(Q>%YJ<5Mjuq%eB$NV-nZH= z6{XV3P?5T-U~f^j_FWgl2q~i1MoMlhWv03jK5p!D?1Lz29z(QSH#mmyHNBNN+OM3U z;lg@XQtfY68OH?aQDQ&wB*|J4?7O!tqM)^sd~qr!m>6jy8l$4G;!@tvZIJ7_%iN(B z3eu08JtZm^^S;+KP}w;*1pH~IAB}I($#K50?a-!Ob!zfcj>1CoC91%ZI=$M!)O_jp zVN|l#sINA9Iy}2%11L-f57JU7{XKHF(QPWzJTvXUVe3(|RN0;Zx{j!TA{=2H4GXtKN? z^-PaEVFSyR3O{R_2}(@lgye|$P04WiOYt@ytzWJw$yuv{Kz}zX2HH}Y+jWt{9I;p4 zp{D~T$D#+2R~ZrC>M@|RC`?QY%qxF(Wm@@#K&KIo-Kkc{!%`@q#oqNnJlmLo41W_K z#;t}h%YBvP97duy>n$MNH;_J1V+u*3aBxQkRW%~g`V9rd48rOz8vi-Hi73A2Y#@-a zI*h!oPi~ody!`P-Ut3q39ty?0HUi_G@8tT;S~c;D(iF`6Fc72W71tQ$SNUXQr2!lRL2y-=vm`Q=AKfmD{)J`lgUtP5wSae70PceY5Ot@y%EV z^vzh4MKAq8_={!JvvN6181_6GX@uY`t~KwcWp&8CzT0wTa{Khtd1tkSf=^Z4G;pav z;=djV*GanojrL$pG6MN?M+x(XR=#};?z!fHf8_CV&|~s=&i;g=R-}zJFwU!C4O&Oj ztRn96)-S$p&_hDBi~Y)gn60L{u9@T( zt&B0z#l%Q@Qft-#y{fYfmc~h(s(?hy@GZFvSq{@LcU=97{xJThQewkneN*nIY7 zMp{r^4l^)w#7TUzxPBJO*#s3vRVa}@H|)BbeN-%Zea7D}yf_SZuM*Y#59<@G?t?Y4 z{>ik*inz=-K6a?>?Dpiq?xOH>YHKW>@6u433O7+(YPcGeP$~|3?{)#Sw4!Yx2e9L76EKcdr&o>Kg9@7TsuzI?T zf;c_g<12i`Y$QP!?s7!&0uM+dJ}ra}#ZXBPNy3f2$~Suq z2%38xkr%Pjv@1#9J>l`5ghOpUc^_rp84oIQ~Ku6r)>I%@h`PkSJl}YL2mmJ zJi?>aFTW=B_>CM=E>IVS$Lvx_H_${-6|>DTwgc0U12%@N{lTflkq8(03m(l$Z5N&dkrum6oQSt5Qr(mCoH#ae{?}QNShsZ-$FBZ-NZ}Q* zEe@|0m_$S#o1jJLW}CPE#qNggp*u~v?QZp*ZV28h#$lD0{%dJ`CD5i z&OPeRmq8|)zki)KStg&=WElO=k76rQq|w8_uL#Lmsg?w{oro$GqAmW3Be18uG_eZ<`!}4xQixJnqJMT)Y%Z9CCEt7+ z?`MWWNYzD5&A;JYZF&>a|7CGrGPt{ls03hOGulDKS+i#y`%)*=ht?5+Kqj0owVKGd zLYH7lJWr!Ple0TzX~eHzzJ2fBH+k_W2LN(=dd_a5F({)s4oFVURyp;OhPn_#NGI*ska3-fjH@Pld zC8D9K>4N8ljnx;zm%ZFT-aZy>il%G-6OS9n^J#d`M(4%Oi(qaK%OqyimgDsu%;;r) z((KHMvaq60?!mzmVJ(x6Mxx7NlXz5vnipeUYt;86RcmSpG=P1Dw<2D@N22wG6az$B zABZvg^HRrsKVW+(^OQspE7k$ak56yGxDsw_m%<)!xfkfho-H+logb{7rqwE#E~(Vg zB%Z$ZaQ#$iv|rXbFjjfahE%4In#J(p5SQe$!4ix_o@g>(+b#Z8*b)aDS&fPEPg2bQ zqSJ3wAA1s~Nqn9=*vkP0GU(61qLfvkkSKKk+j18=}0ED_nRKsyO@ zn&m|^;K;g7Fpbbzwl?h}S~Qvz$k3>m6_XRI0ZYjL;YO`T6bYBn#(%$5CAF*_hbBT! z-G2N0%4LdRchK&s_*m{QnPafqT$a#oN0vZDk@c+KL6=UN14@HndQYMTdU(nmbkW+} zrVfZ~GIyY>@CbS=NPu4k)>|W8k8g*Iyq5ao@gL3`iY?A!z20eaGV;|?oHx~L{}^N7 z`$e3Za>;8kC(qG@!L86Kt5xez5Sg~+T*ZOX!)~IH=gk6Pv_RhHHOT#qfdYm2trn%% z)WJJYsKMQ%gkiO{7z;nB-yU@`SE6z-l`7%QO7f37BISr*i^8efgIMlRoU-4-izMeA zs_GQlLo#ws{?`@uN<8<9Cw`8ngyKB00|DtA-4B!@Ht@;60a!`+-FgI%a}VRDN#AFh zPaXGHYkUI*?>9#;5k=zu&tlv0%v(L@j=J+BvO&hN7jkN?mAhON$HsIhe!d>TRahI< z&q>=@P%f;|=H+!!wZoV`SWwla*F6L6rztrV~jUve-F!r!1*uR6Wp+l z{bBvjxnuir-}0LsRp;+dZu5c@_*RvoRz_V#4r=9|7Al%2O>gDeyNDy$Rt>Gp(JzP? z#GsZIwHE=?(@WCv^jbP1 zZ#!;3H@ER9DC9aU5anT0B$o^dJ0M{-NF<#%j^Ed0RS$J$NNUp-#wan>#QTl0FICwB**zeDDkT5IMmInN&IDm6e1jLQBh>8mEj;2AMTeiJo(S6|ENK zkSsD;t1VZuuFwWn02VrWL$pwiL|v;pFr>yhf_epC@N{Rye#4gdp1}Nr(oqd9p55*i z|HVPv1@5K+d`N%D$@{vZ1t!bJOnOA-tI`ETyb-ww#qz-Lh8ZE4{5=y5Vi+wggUYe> z8#!KX@k7$=C9*7JL;tOWP5Vcbs`5qtzZQVgovW5M3@t`U1a(*CH4{#nqA)Mw;@O*5 z1Ya@Qe~bw7TkCBG31VS6lyZ%Yzpi}y=_iv{%2CGzqqJiBSZ)%Ei}{a@ zA6`9}z-af7E(Kb;pCr?yc7F$I%?S;6Y%Pg=1F|9u{`sYf{G%M(h|dA~)Y! zgk0SJ<2<+uX`FkKl@e9m7=@n`jW|_BIMu#>SI|Wvj4n#ADF?)?9+~s$89?NTi!tQc z4At;3Inlwp747)e$m<(PoRaZ8vBY`#aV;Y`k#zpD2F0w_9ZanYZDJVuGTFl8{0d2Cl6VZY%iJ4z7u>%0L3(2tzkLYiBotiixi15Q$t6F49?( zP~(KHWoGQu`%OI9XOrA?NZ;PvE>ytmcM$>F`?sLxl(Gy3m!{*|XkIG2{1I|?mOU!80HxJ9+g($9|_wM1BxNwe8KO%{w`X z+y6B46#O@d=-eCTIs>1^!p)YDQRU@buD+iX+~d3c$?dj-@I|)4mxt;EEkM&R=d23$ z!P_&#KG#LPhartpM6;V1pjlh7y80opuh?--!F0jvg5me}3nBd;Tr5KHq^uH$c3qKTM{HcI15#6^ny z4DGB7MtFRYNT^=yA1LL!nip>OKtaLV_CDUssSUMAs3@B8!l)EVxc_}|XMN;p$f>q* z&%Cz($Y@{x+5ke_oT~LD=!a)U)x@JV>tu-l{wpfiNgF?6L{;Yb=>sr_hRkN%GYt-P z$7@aRy@Djhy^D)IPc~?3>d2{T8L=6mIp&N=KAngPUr>(SXkWcGoFZazs4g|p<(#A= zCn(c~4IA2G3hj=4Ju4R2pZwXPjAI}tD~w7i@F_tfb@pjRND4%tui&eoZ8=G)cciBk zqF8Pshy0ICdGc$r^F`$N-(8n=gP0XvKmD(z(M&P{$p55GaF;H+8#=w;XFMk+jlr{I4Q{qhVcFd+O@8z#BAj6L%Jjxav3k zrpuNZT_jfBHph;R+vLqB_E>QGN=SwiRAZu66$yhjelvcNbJ^b|fB+eihF~rKTk|_; zJzVek?56JVp1e}rxF>^Xw`y;2JxYbWdwpGyXU0-4C6VLhOUQMA%lb?0R!PpwaY)Fw z7qmE!>b1kPj&@?h-I~{+>49N#LzVfR0;FgeEAU|P2p`B(U~oD1^c9_^txEEbB>69w zz6M(^>nbA;_z`~u+!s`aocPyW!ZKu>n3a)14vX)hr}7~p~3Z6ClpTEh7mn)#(;WnyXgpzeZ@?uR9LwUO)J_QwEl` z(vqEYr!IJqmuaW^yRqAb%367wIkiShe)~27418xqXSkz)^SV=fVA2GCc15{pbd6M! z)tj<&!8)XDJ(n}1P*0x$SSXN5W|4DEOb^EWl8bIJy9VZx6RB?jk0?gR&qgrOkqJba zQwxQBx@x1L^mR#njR7uPj{SIR$ITQ~GMLb$wB%kFmU{bJEkOfri7=;fP-e`_M!s^}sLl^rrdWz(j8ApB>4AdPdM`VP>|#?3pQojwiSE zbIZmp^b;DbgEUbdxuR<*b{y{P3Rw8)S2(3AaCKdN1bx&ZiTE5$Q%rDXCV|ei8-sd# zDV^!fM8zxQ=o>0)*Z-?WA{*Ly<6@MLawZz~K}BJ9SAE?8*coQ8%T0!*xFv9#+Kv{# z&!l8UcJ$$sAfETyAuTP-p}0{AZqFE!L^Gg#@u~#(L1nj$PXymnQ0dA-(Y~j#?FTo7 zI=|c*td_A-6BWbk8;C|n%`M5X;|vr6EoQcT_EqZ=n|cc_1>!auHKKq{)}z6j?%FQ~ zcegi$mB+O?lASHJ)z5v2>aR|s4t!$Ikd&dM+8(_w9j8UG)D}_v*eICW>%kkm{pEhI z8yDch6lSGd|7yzvUK{izR`;=4+^d;c_Lk>9s6O8pl4>k>J5 zbT-MtW@1P}wUAK;WcEG1+n+J=Ao#AEzj3z?{GQNZP)Ey%wxtb&s)=pL<2_|?t+9vg zQKh|mu4m?Vdgo?_c0#$1Qhxy&SwEj;@AIVQG1an45Vg$jAL+kt+KcV!L(X3UQ}tfp zo%!JH5;vT|Ny9>u(zP@fx{bRN?^z0w`vxLPm?nf`b@U>+0zKDrne^r8Y#DX;tY_;N zmNlp%uNt9eBqyYTz4;}WS(k(1`E542fW+N}+qc9O!u4F3#QF7eZhEt4D>a@S!WWJm zRei`xPLVIhn*FI6B+q7#`RCs?Z2!jS2v-xnR)6f5+vm(GSHZIrER9>nt1|je<}`-! zpeoZH1lhFVrO6RtIesy!X_=@T@NbgxO~A}cp5xP%ZT)#g6K5&qbG5zOUHi#$ z$n~GZ5roS#0s8N|odCnmy~k?VCrRv-XqU+cz2gbWAZIS-iOclsJ|DXmb#|nF=>7hz zII3$#SaezJCzrnY^DKFnO%8fyO63K8SE{#K2@5+7Z$RpUofiz%yFEM07moscB7N?g zjP;0R{pW+DW(j{wAZYP0s8NZ7Ok!-o)Y(>#(uV`Q$}Y~u%Qf-E&E@5>Ug9f!O_{}Q zz2bm3#FsxLq`O0ag)(iT@|y>(@UDsh@?GVm`sGH@BhJI0SMA2~Pc_6pU~R?~Lo!L~ zhZgKFq&B^|WK4~MHUCah>Adm0K6hC$1+shea;~9RO|l*I#QI;)#57TPsTYuKz4dMg zBi7%ps{xiPR>LV*)%X<>0h?5)PFt9@x3Y4QF|ToN#+4NEo+L&*qNr*Q8=QVkkxURd zG8ccZS_qUyVHqk(B%0YJgH@g4-A2FRL{>dBw@^Z1$a)@f|9xvohLXVwa928FfO1wj zdhSXM87Y#fsJ)!Aqf$^yb<~svM4WSwKPE*+xEqhpUn&sUSy?^4pOLp$fkY6}gI+m& zWGN@vUh@_$Ox?Dx@{OqV1{#7_yDGINs=g`-p1-MGs&Ud9;UtJz@tZDzddCH*tzES- zZX9U(vw(g58=%5R%(z!!Q?aq4H=-JvWZU-r?HeNxEOF!(SYxZiYY(jxMK9$da9)k+n1M?VvG&T5qrHO*e~iLo}7|h zHMh$jgSNCO0af-tNtgJG0!)xndMzO-9sQevI7V8)Sw3It=qQq4Ad9{jFWTT>{G*QJ z=NIL>!43T`9G75%^#@B8!O1sBpf7`;gXd42BO;0zi|z97M8%gWsNUVfI=Lp_@aqY&+1OgaG zEfa(3_cnhfwXTG66woAPdbH2jehueuTNa=~XBuemqfKi~9`N1xI9~*NzLa+K6M_w^ zbBODUn zH=rU-DH4xDJe>WBWxU$itV>~G5lJS*JX;dcJp7f;+;>e8SoumfMw7c+hp?yb=AYXQ`UH(w|{O6GV3BHY<}8{ zP!Kmvie%M#{0R_XGf8ovw8k%!;V;W#a+p;=`Kb_^pKVTD4GOLMAxaaT``ZAFyR|)* z;GI!mQS?S6`9!5>Pg{F$`ENl^)h};tmDJ`xrS(;9O^xqBxDhePp|EcNbF*JCd3D*r z1-&;`rubYhaASn3?s5H-fi~B}*^T+}tJwtp@Nav0Mhoiegg=gv<;Z)DQp(D|I;Y{U z!VV4`Zg+ibaF)Vu`55e(x9Py*skopbM<$d_oHKvg1PvRp0=x?% z+&B>j0N_+L=Ny7{E+{Kb5nN80(Cq} zaP<@|1_&m!;d!Uz+Cbi>2jtpN6^>xV*%!99_0(#hvp96QiPi2iOQg%KoIG714>UL? zOiA*<=}q=nZ2 zZW)cB+xrg+v8`%&aQl(LUF|6%(8smJ&n;#FsprM*`$IB9`>740G`b=vpA(1FJEZ_X zmBfN07G>(UF|RzDgVMRQB6oU@Rr?9GEJS+q zwf#5m<+~L7Cx5u%=8(3@)2Bs3R0f~)R&5`i9C9cX9W2z|k#BK16!0vUnY!x)g(3)f zYFVk4dNcVV>zBc%~}7Q+UTA7eP$`4DM(;yDy<|W#+%t%DDb=)MpSi~zH_+R^xxstwuwiB@6YijtMtpu*Wf(;EqHt*8FR)Pnd`OVw? zI7w*I;`jjQy;VJaW;#LJz9{#9WHHbkOZ?U!e+589#^~XxO`y5Zz{|bayt2sFVI2?IS1Lqr zP>eX*&SUR?^@*-_;K(>-VG7bHC>wEHZd0WAaT|mDl#Crz1QnGuO(? zlhthX92funESpUiUl9)ga9%!%l$4+i7Y!Rp-Mv#aw^LIbpTC>AqKHQOG90;GZS%PG zr|kiO79gIJnI9cK}W)>=cyS4WMu5?^-bsTpk!e?j(Yb>96+*h zfSjadb6CeGZ^U+vHZqoTt5n+8>@yo8;u^_JV{|O5Bc)IdjmO}_Y;7;Wz5YUZ;>%#e zhO1JaxY(@xSpT}QN@jVZHl8HC`7|>z`z1=;u!~p>k@AS5?XEj$DVg~^U_tBc-!0Vr z;pX{skI3Dw@=6~VwEf@~^pKBN>^!>}o@;wql9#Wv|0nz;5l2##ezKE_UNIV#>kJ<< zm1x-Y9Xo0u!J-$Vy2n*=twZ;D0og-h{AMyz`?!GLMTHlXF~j%d`(#kZue7sQzcI8q zcz3%#Y!d>VS0p{F3}H55G10R~)r;Q0$WPewk-rexejJ<&kmI}lyXNn9dGk4fffzaB zkI+_{$5iHPa!{zP3Rilwhi1CrbN8L<%L}QcqLJSH33uPcO#$DjN`#Ks!smOG()>ka z>dTtCrvTOZyx>CDM^lrj#QMH`Kx)PZq?P&}kOp}OvFQ!i@?08lEvQf@0J`bzGBJ#S zR1_Rwvk~uJZ;Xk_!KNgCd`gPZ2-EYnq^#R9d7)X%y>j)Ysmin_Lk{IBh`0!U?@-u7 zAiVu(sLAIY%$)nxg7s;=9l(gDpqZ~e!UQFBbqB`!@zKwKSb)j1h@cSW(!){cQ4>$)tzrp4Lg6SF*+2NVDfBbnt=zQ z&NU^kQHErwfd`AZh=U~8kI=7geEsJeKzH1&Sxg(S`)|%0gb`@uhy}ggr}al|x!fWq z&-sb3WIp`ao~3^sRkba>EWv{S!<`^gx=n!oUWw>B1s$544C|6EA}A)~P%HKM;0X)! z9{`M%aM+s?Q8%FhmjiCT+qdT&8$QE21Yyc(oq5aKQD$SdN~7M6?c2;&L#U{*pCw}% zD@lPF3;&_ox8Gxc!ct-AiLnfd<_1O-$-v2Of|b?~j`(eBq*lT=8D9o` zvYA9b5meAap$7CrL=J_`1mo&50K`MRI4g!LDlC>m-qwr=!e2G*#10S$#WIruGY+MO z2y0#s)DqCx+J)+{+s(~Im;TU&d3&#xm=Msn^t>nAU_p}P(&_Ek;yR<2YH9?)XuF_B zgn8?7D6&+MVX#hwIW)Z=u#U!i+{k^cNu&v!8sQmlxEkLHA8lTk6;XCbyqwy^drafO zNk)*#+6}nUo?BHI;epiTrU}8Y&Y0$vnB3NTrr_{0_x3b(yrL^tBW))Y*gi=3 zhm21U6bqIG*muxCLft>P+J#W}Zozcb zLRqW4xAr;thcqC{vSf(W>Sj!6a~G6`OAAxDu54L({o}=*JP~QoWfr{4mryw03I{P`iHx5ocyj&`=6}5dD zKBkkt5wccINIrkQSczu61@W6Ih=rb>I&VIm^7ebxtw{HdTQv7e54>V!Q6@U9c>@zP zAkOdm4U{6O(FCu#4qPGwPWI&~3GyUnO|bMo4n&9}mjYs}jYUQWJ*|ito-aY)z6G-4 zymFn)+Fc*MXwH_ph{3~+Idh4u?I|7_f>%De2VqXVEOevlY_s;4I9 z)XW;{RQNf*jo)`mdc@k_Y$=JnRo+&_IVos{M!vxzR#?U~eyz;rk|Iguv@xC&IfuFn z2?;;}c@;LXBfEl;F&mO~m9rtcmkQ%k5rjzimYv>wl0*xgx`_zW&YR4QKq}dx?+0Tq z6SRo9&j=2VXE-FR!x8iLvw-kZgTL-CKZTK<27^v)Rfz1j>AOq}izYX**C;Gqje#WR zd?I#51PcR`Sin-cw|jz(9)mWQn1RjCqP0BBll(4`807$ftcUX=MDiy}nG|VRFek7-k#*+5eOgA*tjm#&5Fl7ur3sP0j>QLsA zG!kgGFZ5G5Z*;^$K6xG_(zblmW~Wqyau$Lurw773p1-pUpO?C{=Y$_Lek78y0)5r_ zgBY2Rx(oEzBq6|t1hUXG=PN8PiG=X+L-|V4v`9*JW>zjNXj)qK)$I*Pp&F~!iV)!E z^i@%#NPU`cbz{#{b8+KJZsK2ldn4)&J=^x#Q?;vclM^u@by(eLK%;r}F2NI62Fw0+ zOd|p97i0BaU}@g}a<2gR85S;Jox0t%k$;+Tk6ts`%0*zggOzSklqAlIEho@BgZh!8 z7BS|NPs%A|`}qF$=_R10iS$k!7X)AF?!u2^B1SCc>hucY+%ioN;QaUMU-G8~W0503 zMR3??j$>boVy;Aw+WP(-$Tx~u-rn8@Ybb@1l~G!r63<+&-E8tv@&^Qe8#q%ZwF7>0 z$)Wn3a~9j$S>X3FeL=b=Enm|!RIQt1zv1dhm)Hn?yrzLNmJ;F00K_5m=QQ|h1uHsQ zVT`;C?2VS^kzN#duym>|*Q06HtF9cC2EnD7)f|mqRxzm)%>KhoR0834;!@W82T%;$ zH=JjM5Pw5H@RUiKl9}K3E1Y7(E5#WAE(f2JZjp2wEA`+L7w6J5gYt*iF1Gq4wX%~{ ziN~PIc$*)=po~4NH0HjJ2Z=zZ{Sb=$zk0zzr_cG2@0f;a_<{@$(#YREmjSR9>Og+t z@9d5s1BG$YN~(Z|c>hZ&F5?5&cu8h|FyZgUGdc)+7rS!l5_0mNP=z(rhVb(%R;l2- zlU)-#$YNv}87&Gc&6N~RlKw|*L97YczuRhqW(=Y<%_+kMzuyG9(F3R6G}Nyg84GM3 z;~se3k@V@O;5RuT10w@C>@8twk83sg2W7~|6jGO!K$!Wx93wfWl_Z&gLB?HdMt&S8 zomXA>yMr3k+=b7I+ZLf*ts;;IvygEgn||g#lI7=C20qdEeorhh*7kk-g52xQ z^j0elZ2z{nWUXi6oMlxcMBEx>0cvuqas`lgwKD^wq9O^UOfto3AEJ}y`23zdICV`KqQ>@1MY?)qz*d9 zc^*lE{iaG!@$X7MDW8r~5*=a(A&Y%MZ$S`B9=xIjU{E%P&UW)pKfAIEcgKyR=MV>_ zOVECRQT^oj4qtgR1LbpS$H&yH;eWUPuLV$&=;*#B-IuVEvCvu0Q9DQV^Xl;Jw}D)3 zIGp}MR$=rPuD(ZUUHdvWJD--9!#|`Fd%tnhxlq2O|0$zv_GM$1VZS@xwR5Hs7F%9; z-o*cRf1kERy*T(8QCyvWrZ}|vrXP*fPvALdELIBatMJ8AIaKMcfhPuzr{%dDPhM;S zNc=K^V}Lj9b!dFPgM(8pvdna(kyBqY3d#zHP4Uy=a{I}H5d|*v+d`82sv+j%g<7hA zF!LTm(I}rjhj-ihl6zpEMq;c8Fnur%-d(z&l&$RX5vNq7Q*oia4BWD)ssT*<%6RP{ z>PhxkOK;x;Z@(-JhVQ#&8=}W28~5bQN9K{ENBkQ3p$Zu~wV2&_8-(StsrxW^qTaI` z!Ks~q4;oh=+A^jm=NEH+{M4LPIg?_jZQX#&Hd*q57Qtkapp$`ZkiBfsBbZ*qz1~f$ zWHNPiTuWe;!TBYXj%=USAR(t?vjA9ZWm**n#jk72m7&`BCut`%$ABTp^?pl1|I=-Lkz3hki~~uw<2CiDber4 zLV&uv9IN`;@Xra}|Iu`oQBk#D8y`X#KuVB&=vEr(4k?H3ZV*Je(*OY(dgzkw?p9)u zA*5qqK*S-WyWu_m5ASEzV%C~D=f3y8uHU}4g3h!}jR8IDph*;o`aHw?6`ELt*e)!m zFkrgtLZ-BXTx8!<6T?EyHM>Fx18kgN_vy$*u8pOpn!b@7rmk$0biUs)6j(kneUixd$yko_3B~%5u|v-{ zVQVe2l<(qgUQGSuuc@>1@hN`Ky^KktASql8AhmX4IyhlZmocf!;xfrD)>s~}uBWy6 z)VaI<=WYXyTj&&>*V0KzB0U)@#Ac&A_e^V@sfd5>6~9 zxhtN*w4b>R~9$T+d!q+zq1#{B6 zhdijx!)d5O9*CjaEww!pDF}JzmRRI9!Q-4H&OY!6HKE>U1$>fDw$jHT(^gR7nw$Q! zcX7biy}T?9xcD`(htFArSKVRF^NU`U2xLy^EcWuTv?d~&A~gy1Jwa=5W-UwLz`S#4 zW*jkF(0~P!d$+!={}ayXEbv+_eU89FbMEwcMR`q{-@f{@mhuF-I8%N7raj$A0p1ro`8P!g+NA$OO{Cs+mCcE{P<_QTl*9=|y6xu#sXlv>!-<;)R^3UPMCK}5- z^RBFl9i7ko#_#W)ck*3F4@-tgylOBO5Z596xSIOP`ZQ$vyyX307VxuYZO-!>%Cd12 zD`1T8;(sIIpv3dEMIZW^lF>;J=vB#uN-gE9D~9;TYvbMeN(~ZHCpuuqEO&^&u)4h`CT|Vrsti{W#-{E%LbrAJ$|NboH z)^weDWYV-Xy7^p?>3GWMq} zhL{N`JRuiC`%q2luaeb02!Z2D$IA(Z1g!(3-@jiz?!e~>c6L6$pgo!jBb<<)Q2<=P z0qE-OkK*u{!|rLp>F0Xr|FB7u;?_w$L3JU)4)wIY3j?M6@b-4a0a%`FEnsLxG5n2S zF0w#!?22x(W|%+B=lQx_q7C&j2D%uw1_KE#MSh=~1Jqrq>0ttFMYi#M6c zhK8+86#uPofd@D))A@#exV@4g0eau%w_8qv2Z9M$*|}d+V?BjuKBE?e+-{fG_l&jU zM=NyuOQkhAbz6?L#CAp^` zc1blyE(N(wrbu9^n-F<_v{aar8y$f2xC6B6iqyM><*(mAR>uj59PlHOntnSkc}C^R zaB3Z-%R`6`|DyG;#hc5auF&CjMojQ$PQuuqH*@y&bf}vN61_p&KU{;hv0BOqItTtmp786?Am;g&J{KLi;aYhPGm8z5H<-qjfM%uas8{tUFLHroUMC|#Y(eQn*0L+ z8p|JUJH?g`YEjZb!Cy$OBqeD*_})G0U&fMDTgKDwH+!BcUQcD8HV-$3c?7hn2I-TR zB3ibRze-Y)GFO{nqi*F9=P6Y_yF6PU8?n2GV4$O+-Hq@}^?O%$1O+1DM*CWA|1-Y| z`YD;PS;isSx72r$npeGl&!9>C&{%u1H?Wq!<&?~?B<=^gr#-8B42X;zJhXQH&?6h< zx1z)&fqaLkkhqsez4hN`aO|DfcJH2Di$P?b@M-|Wp0$qjU+C{uUr1rDz63q z>UcaQ{Bdv5nkNnZcP!JaNgd5rM*lj+|>q9y3Hq9wT$rtK`d9G+4UO$wK1f1Uw5UaDl)mwD2 z(ceeRRB1ehCwNo%FRHBNrV0%_@to>ZaCbMcWaw!M83+%__X770LIVNw?+MZsR91@g;lu4XukJVLt zbWIi2Vrv4+T7~nvJ<69$B6+%ky8pLSu7swDn45NV!n401f%^01b$~rw3m$xZN_IIIEhk z|MfI=K4D}f>LSi3fQzUocS8HDweUO6!&$7^p4*7Wb{0chr&k0h$b*8E332t;lMLN# zS^c_vq7)lc)X+xvn#=tSC2SY99N6<}Zu%d*2Hu&IUHtM7w55db5AtSyeUkd=xtQ8S zc8NxCzsX8?0U1QOvRMa#`D?LRbI>QSw)=QUNkCL9bjKxCFAd@bo2Kx#v^LNGjPoFSv&sQMl2sXIc>4>nqqe#S=B49!+wl2a! zvC(3Iv)l6pxa@Du+HGAh)gcCMKEimT$Up5hMuu~4o=8NrAkmNHIu}YqUyy3>pT8-U zCYdeiACp5E5fv1q=R`qfI?1QjE{ol1g~QDp-MC6mr5Y1`86%80ilCz~9pyhz+^@BX z*kIHB%x^Hv4VX5FQ7y^|icKCdla1iU-Jg>@;#-5pu_pJ@kS3W zsUGO5S%yx$t}Y+6_P>Iovn6(JpVIUFC%K5CS_|>HxqkXk?JqH0j1jHvVp|XrcDz49 zD+e`3Eq&M5t4k<#(LB#&pNLvIhX|72pVIWmCY;YkUd%1WU%1unkBv6qbFq;&JZR?l zTwmGn=sB8Fem4eSUkcV4lWystYZc5}r59G+5#Z6|WYs5NS9fLRp$kV?a;KO^u&oc9 ze1sSp_mF%Xp(LIlq}e1YVK(FFP$REyb8_rf=3kTH@(sxE*~m#BRWmbI_-QT56q4yT zbp09WqQ&WnW3Vq$S2kpPD3!gBLIf%uhWRJCgAp;&JAc~eT4-h6kZkd_$_@^`8!L!0 zaP9?LkSmD`wm%EOZGcU|_8XAcF}7%tqE;z*ubs&*lD?CLnwNZ3&o`*8_b9A6l~7&V zi8be3zMVXI_T}f}{F8SaAyoR$LYXe`GF?OW8H3?IR_)mrO2{qw!Z`2w>S~CIb}6sy zLd9k&PtJ@?^hBpGhO^*eY=W%iBYrYh)e*T%x*#d zTXnV2IW$@VM@>nTcQ^K+bPPCO|1oZx?c;q=eGBMd;tPOYSOVjh-ykCPLsoMjrws^Z z)?%_s_M!ITLeL-cO{7fqQbx`RWzwEU7cOD5pK#yR^SG8TTJ}Z32F3k}ZX|Vnsu&3{G&V3fB3Z16CMn5LiO@C9;gb9L1=BirkBGCu%kk5W*zW1kwP{Kqsn156yW{Qy z2|9Z^a+f%$SO;#fPx28YP_seWb8ITRB2LYcTfn`!$*d55&vA2(P{xxCae7{uYOagA zX>H6+%K7ir4?75$)xt4utvjz4F7cLuIK2Iz>(A3*VbFRq4O(doPE2#CBbuk%=*t3( z?Ia-UP5eaJ9PC3Tn@iqPh=_GeZk#~8)w&hSdW7huUzHFt_ax2+PqtuTSM|7s!UW)| zGBCc!Kbui&S?7MtPIp)GsI{0W8?#02=C)G^oXsMS3p-IDm6~us8W9aKX{vYf-(|$` z((F4T_FH>w(=+HGQ3i(PhKzAfmvi&!fkRIS2X?m--XSaLg4;E9XUz0TwLH;B*zi6# z+AH}Sz`e|qn@63Z0L>l^ao-!B_>-GYJwa^tZFn3Z6Lk32N8^7Wr;Rhu-qS5{c9Q6l=HCL2r@{n7XGs*Oifk%M$SXT`;_c-&aF=*tq}ceMD|7rOtGSs5uZB*{ zOQbz-%f7fj?4JIxlnR@rAlq+du+*IH1u5}5^BX%TQhzft{~#>0649dwSIba1Yh|Ix ziYa4P&uo!F7}tw%|1xz-B1s0I+x-&%RqC~6sL$>n*mFG#zOg^%(wC`B7}_m%pIGTg zv*@OIiPg$W>wmBrjkiQEUdhu9^0^C41R^))R)V4muG>wkZ!;$gqTjCAn2G8hCJ8cP zPcY1XMgfP{genCYnc!Uy4|NH2QdrNiK0RZ;?>z3*m9byro8^))FDaw?;y*|n@xP|q zxx4l!5j|$td*yh4XBlOykh(ahcF(20%wN5$^UM6^-`5BF@Zh_Ig3XN$YNg85M_cBs zWHLHyZ6lv-G9);YBsG1UZ6Q{%R9BNAm-~&NluTH)Amn|`Tv&HEZ3y$EZW{gN-#x6o z#~-NQcjV3DgvC9ttDg6`L^vbil!QOM9FIwoC3tc)Uefe1pB|+%v5Y`tap_(BXe$-8 z`EWG+ILu@-*qrC}=RZH?X-RNS^*v>0S-yV3YCu>udjbtLQJ@QML{eB{U85UWa%niRmJu(P|H4#!DZa64u?0)7EjX3)F@Dn9~pw@2mm5ytR_Owoz6zMh1Ab#-BUD4xM ztLeQ47O+0{X%4TsB1fX%8z9O5AVh_(3DU#=;ezTrw@9ovOl|i*UY2vag)>b&xsK^; zbNDY=x|62r-e`v8(o*B>uAPVDX55N_A*|@xQ<8>;c5lg->=-m(t#0N}Rr$O8%9^qj z!IH-*63?FnHO5v*gp}!1(8h|&uJzsaT%&)fbXkS`t>%cpF4XYgJk6*?M*15lk%L2S zMH6xci2J19r?KyNpn}f$WnFG1lOT&bC<)r=po;V|by0at?~9m;=kr>q_Q`=*FmvHK zV)o4db|ziR4+J^%seJkP7u#JCN34#^4&2o%S4KGTKkajAahdU`{y>K4#UK|lNMB)4Xbu$OB)FYfaLh2 zucN>oG`Ad(3T{Sn6r&dJdX}S_YQ{-_KdfkW2{zN8$5 z(ov#b{}h2tJCc8Ac(F-&b7^S>>VG(;^VuEVM!xLP>Xlpz?-dF&j#6Jca`1OYZxOqY zP6gNT@w!gk^7%|Eaw_2yzM$m$D46UM82<8Ea!fRwj+e|7a(3jkM^`yr96G_8OV<*` zK+atF85Q7L3o77&lAImgGasCI3{xEpQTFaF>AZ_m8RRGbZx1erXT+$>S8WjHSqa&V zjlp3oJwCN-@#n~wa{KVXAgrEji6iw%4{BS@yL&m1eYraedkZ;#{wkxdU*`E9)5N!E z=N>`*M6c4_k{U|CL(RPN!N1>_u$9J=iC91dBT*!i2n@NNdbRZI`5mMwy1iJ?A!S$t z=K0+hUwEt;vvEFnwk4IC1!SH$c_1oYuK31UkE&+HrEscfrkr*mZJu*0jspbt25~j) zY9S;;kJZnJFQ+bg##P-@dAgsXp=6np#iLvt=&>`u+0n;stg3}p0;i>wbFpSx4;n)^M^y2bLW%uYUZ$@hkRZ`}l^7J%; ztn=3y$W6s53cp+BuhGCd><$Pg<TN{aP5JapCm`Rlb%@C4_vZxBlugP`vR(0nejC>C zLnw3Ri2D#XEhq%#oB$1Fdb(U(-== zI~FvXiuO{ytm=VeK$ebG9Hs$d1YN=Wv@=^EJwm0~#N?eo%+lMaL#dSUcvGi(Oyje` zi7#)#9R#zwn72DYU!{_d4Y5JM9Fc7$#9zVS2p^6>6{p=fnuWCQNP@NB&FywkIZ<+(A* zz^G>nzf|G-eelO1XZ`&}vMF!RPCxJ_7Ipk2D(MxnB=ms0wS?&vgy@f>L(h<$_bFH| zx{WGtM6T?aK%6&RtRx3`AQ^$8D7vNWsuNo1wEVx z@pmRa<>NRVXce2Hz4iRLT7-)Y!&4j_s(7*GSWh{c@eE%F{sF|aXgFb}l(2TcHS9TY zaq!n%ms+nV1lADb09-(ASHH&{%p|RB6ZwIAVJ4yKKvgrrw5*|v3y;afid$>$?3;LS z+iGXp4ZeT=n+H8S=Sn2Y7s2qw-sEbza^nocnQax-&Y@A?ESiQE}3szqoLpwT$>L#Ws z8z;r&@0rieVkYhE5w$%?U$~y;NdY$IID*+$hCJ9`Liu{tj~tASCfPD?vozwJ2yCg} zz-01`=obRn4qQ3JQ_5~2d~0+>Ckq_+nk2)Wn0P5aDv+!kMB2c z-bo8x0>gU(bN4-0cVTqJg-32uVRck{@X>}7itK(OzTu_~5roN4L6~0dd7zk%MR*Nm zXB+XV`8+|>qwUt6JP)%n*mysab=9VwDxw8_LXhimgj`JE`uw12&i5Wx-`cqD;kR>r zcU9DAB8E_-O0Y7=>HqPGDz@Qi2LInCMemG9`YKL_#XL7zcT=7ez$wU7h-qmE*c+wfflUvg-Hy`BcKP zCKuO!K8M{P8j?KG@WvSl)(_(i9hWz@m)G3^e=8f@oB3M!n%e@Hd3&(Jg)Wr-p9KK* zpq>YB916dz8d^v8(+Od}qHm5e)*iuoK6v(<%DooRV6tLx-jEs6b^mv50{D5T z6XK2|`=@_zR_U@s=F;$9xC=IyyHIZJtrMpU7TR=M)wxoYwnS$46tzS-^`>3;7jbS$ z`Zof`HI+%6Fc~Z8Gv3E_%m37|K)?TObu#&o!S$T2_%#i;Uf9Q<5bjhv%&Q{O%W+jp6>7TbqA*nq9g#Z^hk7Kac6A@^bSzWSs(oLI#w}9(PukWb?wV zXh5n{JEga3%_98qo&MIRyD6WE!_0eFM#O>zeWnlwkz8q|?{oaGM6+hCzJGP7F^VHR zU(X-EG&!3H-fi*1o_DDJxQL{^o6D+y(ET^(^s2geAa~#;pYQ6;4HaqQNAP53Rh^F{ zt)S9{{=U+fvQdi1PfdyLnt8ith>;VBLn!Hq%8*jj7p`+9+Hujpd*yR+-awk}BG5Nb z`d4z=n3EWEH3g@-nTNk|TN|?u?q6iZr+Y0fU4M;ejju2)b9qk|`)d)6M;vVxYRUtI{ z74a5UU1Kwjm?v0Xg3|YOA#Q8~xOmIhx6QAC=);xC_HX-$0~8Rrf#)SlHb}#;x1XLr z`g#2cX>3f4WJmxP-kF(FGfj>1)?~BHt|z>rt(S{i`|X=uZsYyz{(0}u^!EK*D({c1 z%szMeI$gd{U_`Y0ClcEmw^twQz#S8oIl965f4faHnt!D`AzaKggzX~U^ou>gtZaqo z7Ma%%_=r9MMTmz^I~26X5V#2Is^=W%>dcb!f_ViUOOIEJpwtP*AH2o)6*C5?u`x@1 z<Rs=rCAYap`kr~|L+C?My=BAvM|x)<9jfPKOH^Hk(z6;Qgv#t{-5cprl*ntG$3 zDRVl%)0BG`=bRx&2i#y!Gt;uroTiZ?_8l-B zFU6;xG73klO5lTA|I!!FXBkSA1a^9+@9rYsFNx3AaA04!q2+(JGcvQ$#nbEW>u-Dx ztE62(Mf+^{>>?4KYIs&gg%*2yOJBg$4eKRWwmiG8IEGMs)$Ie-Eco)gEFrJd?b`%< zy=i`|3N>8d}EK27u-4|;|SOaIl+zP8W-&UuI ziGienL{{$>cP+aqJ5;cI6HX&5?fRYUFhqFfbi>a_Sf@o8vG8V;l?}8c7oiku$a`?& z)vM`1gErVfc97AjbB-mL9eN_Ka+d?8r=mUuCN#x^lb$@NuWd@9V$Pd#lk50mVpF9- zopRf5>ZmJ6hwT27vbXoq?`%{Dn|Yu!y*zXYoCWs6hOM0+{i<$$Z_TP?YYp@#uU1-S zwKmHYv^|gX72dCln#5-G2_n}cD}flyJ0D787wM@kSHmlXV4y^Iuu~{0iV9>DmPu}wnx&Is;Ymzpo*mLpHyG&QFLI2UXc1iRe46G$%?L%VToha6+H z??z>0K~6bxXH7T3vKy2@;0zvcK9e2$Qao9kBsvMZ@^Np(Pp0(Q{o2o0hvM~5M@Cs?GNEHU)$ ztOZH@460j+Qo`n2r2Ei8GF>hhWy>ZQ*lT=oj}n`0ey%695_|elDqNdS%V)&~W6k$a zvT80P6Bs1I&h^y ziZYkLO5jN}ThLQb%@LXjf^!9d#gl-$$O$;lECM?Q@~l6z<7yzu?omHqg!{EU6G!!= z>S!`NSc``j*Y?fx!8TX4vd#91*Z8oA>T@z% zn>B3e`jC=cR#suXrvs0-AwFy};o9!z@o^^@%Epj5XVm&_33TUtA;>)ObDJUU?eSSX zQ0p}fkEe(Gx`(aw-T`p(DpzUL`*044>-M0FH&{N4unR;i>RQbX_UoqKEM)U#D5(9x z#otc00iG^o0rmAK7m#0`7J0dx#>?4G4NpSS)pxi0VjqElN#^5QS{Q-zCC52e zXb~o&o>7Y$?Q6gO9W^?kT{t{>>>1Qo3N`*L#q2pTwed$^K=ZXy>`oR1wd&()f!lxe ztw7ITS=YNls00NBT}hXXoLyu#JSO^?!ZbZ`gZd#8Lv&HX8}+G zfj$#bWF>aDWGRq6g)5t`1!F(+A_AJ(#J>{T{dq!FSH3GdNku<(-}Ptx_%O8)qVKAO z)Zy>yZY-w_(*h279ve54jl47=tF_*9Vu80i0`sG-OCi*NU{q|K6mR)o$@2BRtObt! zfRNRmJ4&^x!`V=THTaa!ndd?T{ik|dMCm7e_Plh6_lVezyUIr&5``$~zN z_=b|1^-jHu40~)K5A=|xnfT1j#24edsvu_t5Pvbz=aytI1+LjQO`7=3BL=72+RN5b79jdFl!Z_V$sSp>f)sZPPzbl|$2r(d)NQD3#cKgy%=SpBtv4 zJ17JQ?*0^9fdP71SG&x z60__D2qP&MEO+7=<|9Z*r%Ic(lz6pM=?;d6evF1?#r+Bt=fnAB0IE0dnQg@c882gf z7^lPlQ4EQymF~|=-XZZomN#g&P<%+vdq2PM3mMSj-$naNbXDI5w_n@vlJ}{~VRu_* zh;Q?#sDGfuZw!xkkiS*_E_|6|CG^F}`LD~q$7K%lNsnB)1QV^0s~QtC644!|xx2tDy%MF~2Aw4&aZ-`I>36uY68p~)4uhswz}GBRs^Q#&d)Q!t zJT?nD;cz+e^FDElp$A^~dfGs2biMRN>9K~*l7p!kt75XHgJ^HsNDijt+C${$_L-1? zM}OkSp}H$i29VqRJ-yvv;3QG_!9r`SUW&{xsm-lpv!}Sps@~jfX%j~pN2%~b$K%_L ztD;K5a_PbBzg3Ut6Y#L7pp+=W4b}txnh@bOL5Ed4Ky-4bxv27f?sRw5^JhEmg*L+} z;f{3o*(r;`A|S7hRa<(8z=?N{en{GV3FRw4A zB&%#)KKU*LGh%n2qcpgff#mC-HL)4bG;x9(gnBJaXRb&*e)caF3P>lhj3%As|6-I>YlU)8O44tid@Aa>4NWKHqb9s-g?<@ zL?yysW2W6Ud@~AQloih;BXJcU z=A-ltYP`!Qn@^zTOGg7LFj;c3sreCPLtQpu-6R-jm4m7(f|24g7s8TB-fWS2;?!Kg zlFVeqIoVypRwQC?`Fyidg|(DbB9c$=(4tZx!Gdu_;c(pjVsqF@ITLo!a*~S_qqaO? z@tGk<`Ft>G*Ab&AbY?43ayR$bIe|sN{iSY85mcLTn=x8_ZYAPVYutT6*fgdIC0jQ9 zHMLVtJi}~m(%F0zG*xJEIi}`Zex~E5qgE%Zo)VWnt+J+;CxJ74_EkJdq06E4f8qK} zn0A02ge6xW;JU}LJ;|8>0wm>LCa{Ior%z5I6PZmvSzKVdu0OqMNtwFkW`c^Og6fgM zK*8DSg~3T`{vwx9X9DWBV!ABxj&vP(s?Z(C?z|ytp_&vt;`j$3MexDRm5^5x7G2)- z)|7+wb%JIvDuDVg555D{GnH9!B{?`=!S9>|FOhcg1@gaWY>?)m0Wk8Fq-~qphK!A_ zK;V3TLKb3x1AoXKA$jbR&S1*}cXnX?qtG>G?7;M{RT z{Qi&lTo6M^k#j1Jz_{(h2UZxUP$i01K+EIGd!fQx=BW61aoL5I=bO+Owv*@tH^;A zOQxpC_!FF$s=p|Uz1X95EC*+)u?M{>Ki5*SHRn(}3Do~vo^CD4&2MJ5?ewf{E*LK5 zfqWCLK$^xW+ldR^=Nd0q8ce*94P3;&{Om0z>$Vy79yqXU%*z{(cYmgj?L7InDmfOk za<*_-0a>)>!`Bby1v^;ZGOs4)Z%RlbBA(cNbPly1v8X=B&{O1G|MWG&8Qn9qnl>9( zMd26zu;%*Ty{T5{L=mC8&KdIX!oQFt%a6ig>|aR|Ue%_fXJunASX`b|hkoi>?Hx?C zrp|~$ng;!)%TwE2q^?8@2fo7M(^f?Cb}sJFZREqcN(6w8*bvsGeetHLRh_T_V`9l^ z^MhF?{_NE=ft%^1LbM8kV5; zP$I$GJsc8rEWp45Rl`9K@A6AuGLn;7@IdCtFs}b_S0Y2sN$Rl2G(XxN4{bXe9<$t7GDhyaxQ{ZAOQU&?}mE&1j3_f<^)_r zwuK*`v8x$xPV*Y2?#8j&)jxJjAWzLrQDW?P30y(V2;4eE&jRI+TmUicty&I&fjIq? z)`LC$S5`c^a8V*^YbE2{mll$9VoViH?cPG8ILwQ35v)D?oIA&>hCX3+?BwA+ z0cLTi8qR$@b$Q`hq2yINBpKlD{|Dk?>GT7XM$80f36iD(5yVwgxD*!V`83c~`))jL z=gS~_lQyxIy2vBFFGjkaKc7Uw!gm=Ci2RseY_o0ryERBYEg#K)jEsv~vwGMI_Y`M1 z`eB(v99e5&w#aFhGEC^ey7P6U2uJ$WOK+fba+j3ovWm^13pWSemN{b%3q#2Hem;Fr zlp!F4u3m*Cym2w@^JPJGC+TWx%2Xu7#5at#zP?chmaO^2uhszy)4NeZ zU}EECU!(A1%&nx34EZpFVYU$&oax}GnFGu+GfbFX%=KP;<{nkvMTdbIwC9SSH%-|q zBGF@Z*;-V;DG}T0Tl7**Z?WysdQ6NB_7nDReptK+nzL3nW#g^~P(^~8l^scVHR+qF zeLc@9^b|&1sy|OjxV~An6)Oph^?$UN7tdvAbG8~3C%`I4ci^W=OkB0{J6oBDw=7V^ z^J9X4K(c+r3hHUzAr{t?<;-3>;b8QGUMynYNG3If`K=ho0iXYqn_oWioAPy#b8Yvm z^h5ho{=QXBa$ESdHi<&N{8tjMbM(YsdG3F+;QC-mtGt(T;QgNks1)yM*cWZUc+5z| zmTWe7_?z-V-8e_!e?@+RwgTsW;o3pFmsWc?q(OJ}L{X_zVJm3|l6}4qYU;hAoSEuYHn(;K3B#~NvW!1X;F(kAsb*xUXQhZYYTS?2S|4|3KX;Oo=wNTUng4Q zRd}Y&de;9jQp>`glf_7Ofye2KO1?TjCHdHI4u7O5!ye{$xK{4?!xi!<3*$qAOs7uj zGmv?=QrBF&=+&Ioq}#}HpO)ldqK~p*&uzcYU06_qz=6fX%86@5XP@1Md(*gRNAXzC z-Mo9ZV5h_1H*4-c`&h7VjF{QWfi_8oig>hx$c_+mvhP`>00@BDGFJ^Fz*RA=a3g{N zGQ_;jk8^?@*XU9o`I^PfBtf+)H&TU3w<-T{lcT%2)$mLFdj=G0G%imd-O&TR^si4# z_JLy+cqh(Ui#(oo-gK-=#L9@S7R~_Tsp`OK5xiL|Q8es6RQ5bDb+<7&@eMKjcWblx zbgKtavBJ}HbL|#|4(=1bU9Zb$=(Xg>jC*3|dE6io;C+p@LUo+BodQ_GzLQ;ML;Jv# z;;Z(qRrm$N5iNr*CaqC&YyJFZ`v~u6zHea-jt&9p8#z4mNZq2=Fwadh+~r@6;G;c0 z`?fHF;LS2g6i+6wm@mvn_?X@S(f|G8PF|6k6t9NTF>DrxWvgWC3P z`rLNuG&QbXwfg+X7-8dqXX&a2E40J*QE{ zg^^ZCGyVNHYSI5ISaRqO=V7lomRy6FMJ>H(mCLEALInP6Dd+sCy2I+jLpYE;Y8W^d zaPznNKekt#vp=BL&3)StP7+?teOQuNC-dbEu9oxuiAA^)oYwtG0U+xE? zzt1Xn&uX5BZSYZuR^gka8@_xL?VquVg3irrjTnP5xG|%lGs5FrBOT4WV^(vQ_nvV^ z;b9>S;+MH$|H+K1slfC;gE3Su$I@{M%(?YByw%dmT(&Z~84xJ5rR)37HaZ8ahEO4) zxJ!z!75Kc42sI}?M=XKGI8qxsS)iL-OFU7Lq^{~9glF117Q#kggnmUXj=LpXaD3?? z0_K7yJ2V}f&aw_-tx2lzuLOA8Dm#|iVcTWN_3NLdIFqf@jM?tus;6IO>JueLK3siy z`pF@rNf4z|{36}w3P{()l>Frwo6^dY3w0KlTat^8j?7kDSwEkyhW{%Z)fIjCyD{wo z6*S~&X_A2*F@9(&`1loi4By^+W+0pjO;oKIjW(45)H zss$ICWVQn6CljFx)iF^AI3NPMZZT}(ihBo>0kIRA=W_*yGMs$Y=qHe-KP9ru#S6P9!%gwy!RkXGyArKAG>C3|d zS0B_D)l>pj90#>^K9EUg@?&~C}5-d0QYK4jcE z;vZ@TbV0JM9BsKioRp$rFGmGB@q!4DkBEa<$d_>e^-OQ7Ec2eb;@V#`y#5rq$FQU& zn_apuAE_mxL`o!90OkP4EOGmnpd3zD?*u%F;lQ>A? zoYKy`_~(f4E+P|dMj&gMj`$kThlyO1RtFHs0Gpl2t??Vrg+DWsGi>VnrRz&AYCQCZ zh-pr{_s%`1L$g%q8im8}oNZz{FddXcSx@xR>vy;$M-u=G#5yJ!m2TJn{Vl^*HIIdW zKvfLUki354gWpqnM9gX^R|>V6j1DV6h5t?4Y#7tF0cO{9>08g_)D9e;I8_?BEXyYk)~V zkr%mec(wMbn7>&-_(Ez<1nstU=H307$^SYb(t6l5;aZ_hr9NV^UY z*U+ed?3D&MoC3rhKT+seOlZtHP?mpe^`I{hO16>NlUC+($l;eSifD-($F=p+E|ZoC zoQ=--GHbwSSUB**%|5lxh<%^HBA9(=6$pMh292?h-`t*D{Ce6mT+O$7vtS2mKeO!> z34*o=JxqJ&{x-9Lng{U`_Y8g56`??=BDXM1P~3zL#ilgsBgZOe55C@84)4sy5Y8{@ zf8y>V)RPIZ3;v#MAS73UWvuclyh_#fzphD7xpUVJogJ!%IGTNp?mc?LLOLTF9-i~J zJL4?^^MKB1>qT=;PMEIr=}?%NSY`ttjOp?bG9?nDo2+QCYnK7nntFz~S9l-#_b;$1 z1UnrtsX6lX-|zg%al%@c-a{P}OFwMq8i+3_Ot!OFUZZP{<@am&wk|f)yUZs6mAnlg z0WTj>vu4c_V*Kxc+OWIn1$)q`X=m2`^w9AjmK?$}YZaU3)W zfZ%rP&b!Z{&lG;{)sNpWe;@`P(H)y6i3LdFj?E|=Pg!SHc6wMC>`VznZ8_Ku*;PEU zR5hIdxGeYkJ0%k|dqUQIx`g?&iIFqUCNZ7&fI)51#pzJ6Dh2_;apNFdzdMgeNhWQ~ zI@e1wJPYw9W!)Ucz#oC23`e-Leu+kxxe+f!BlmpNyG6`EXF}%sU`4X~*ffEFM(WWs zN=UQtm5*xngsPi4kiA?&?&pr48)H;}O{ZwRaPkzNXLe)=@m2;?AF%1bTixwV06-NO zrbvdS5|Hs`W-rWe7I?zHR?Np)<+Q+_DSQ)3zW&0B4Q6WEpuiYFB@0f*h40I*%7oNG zf^7p!0d2_tUDfMerkp2EA=A(0d@=EnGR@h7a#YHx5+4_;$BF7odS_1l-T9?s<~cuKciR_GHs3 z*~rP0b-h{E5txejylwew~jBI2v$RBsSmX z3B|X3_#7^PT)yf*&&{_A6Wi+%sbgsldI{^*VCV~OKe?f*rI6ar8nEF2K=<&MCs zg?mksvO>*T-(E*wZ64-Fg@eW8r&{a@uWgwq)$o`ioUsSAK>ee8$B8S_=g(d z`Q2tU^tGa1398_uzk1hvXC$JL!ueBAq5o;UpaAUs2@fNj|7QWd2^!N#g*9o2 zjXYV0>62+Cgnqhcan*WJ+erjZ`+Pk1WlWIC8FVbziv{Y$n2%Z3mPBZ~tA#=T}R zTvcES&`KM2ibVJ`QZxit5|j{G{k0P<-tS)es^as@-!AKj3!!JlHi|Oduc=a&?O#6D zrNoVTx|;!=W=fZVc9bu={ackcih=^;YfJ@YDbL=YVpM0|7Xl}b*#w5!_1Gwuy%Nd5 ztL(D<6v5I?OUXPS(#n}Gz1or*9wTH76(;#9YTwfs+~%#obXNE~C9N1}O-_n20yVG1 zH4d7l7-n3ruW~Vi)-H$^mgeT8wEU;nM}?m2$NY(Tr=|3i6nbJ4_@hjz%Hz#lGqghR z$1Qc*4}wtf1KB^M*WN?yFJ7yBop73~nm9DM_+bUvyMn&nc7M2Q88PPloksGV=9iem zUQ=~tsi0Bb{sX#iW9CV?tefkR?3t6NRo{6R*<8CTpeeqm91r;XLqIuB~Z2@25f6TnLt+l8VWvd9`k(Rz%ig zwAQC{LvG3&@D=?}|LUO9G#w$&MS__%W1?Fl37)9TtvtOj+!Lf#|b!UCe zn229~a0@w_e_LDOy8XRCZaXUl&3)0zY$54B zW%Be`OTng|vS|20lUxFSdHR{c*9x6fGJ)mJJYG$Gm>}w*Z?9)0#bL*n!LRpt!hIs$ zdtA@oS9DSX@*it7wi-5%*2`c!o@S4Lb&rSvqFdR99uMPI`NUIHAJ2;|)FHyI--eFs!#tNVxm+hkiFpCpN zNAXX`>6RLATHkg9w|cUGBWC++{Q^B1Wm;;qQ5k}IEiLU$&_i=0QuO6+cRHS4TnV-& zgTVl*oa?FGpm;)0kho~6Z^k~lyUvjPAjZXklf{sQ6Y|OaeMS6rOgT?Ks`B#pp2R7E zEFC*|gEjvJDL;VinvI!}He7qgZO1hImOg9!Kbo#8EULEc4xw}--AGA;bcaZHr|{C9 zlG4o((nxoAw}7;aY(+gi`LYkD&ooE$+k0zDKn; zb773i6;-u->KrW|2|W7k9#l2%QiJf(c+`XAhUK1jHZpdtI~1hCC5E=;xn2L{J4;xw zZlsaFS^joyouiDh^`b*O%$el3v|&ZX7ng8mVKScm6W|5*#{Lf(PrukWlk2a_Ex!yr z1m%k7nUVahE!Qm_H!`{Qg8tR&eEcPLjoWAHG|c>S>C0g3TY7E9I!1I6Zscd~2d={l zVFCI49?u^bTIp&Zx3Twix|}V#2g&L`kX!fgCPRMCM13+c#KSErU&Y<7!TM@u%)e>nMeVs#H_>XtMJawv1!F zJvIzY5Jk_gX z{QwM=j;*tIY)nWRyKn1c`P_S1F@TtI)4&g6DIX6oIOI)8Y@SM~NpJM>50xJgJFUCC z!Uwlo5I|o~qOq0!Z7Pk|Q(o2zeE;|X@v!F1>1{JyWq!-a=_rlVB*q%$`X+b&1ND1H zw^donLI-bO+|qA&UdYlX2a;c6&AfRxL;Y~%M5-z2HkS%NkrF4zM%UteluquOk8hp8 zP{GY_Gr&}bTqUFon_?cCT9 z@PQVk}ovdpzf@ z2mibW^C&)NjWO;c`SlI`c7aZtwrp8DGs+_56SlrmZ z2*yPprOuF~As;_kVJWq|poq6agN64#q-kWH(^#8NbkG>%o|#`-^DLoxpOyjM$+Z2I z{>L0Ne5-&C>Nngw2+#W>%_W?f1#@t$UD-&_$5uhgF&gW*IsQY}L3#0o14(7PI=;NqXPIe!Ql6d`_}@(f~tx2pLwi$!Lpaf$1ZgcfO+?CZ*Jq6QvosD`C2* zG*r>nA~`EG&9pDfD0kvdrYmuBDh5|i_~0nd?x-ow3FpN6O78SkV1&JhyQ$?!RCds8 zJ|FhviaNk1+JHm$-rT3f@sIkU--7NTkR#*{_PS3zNVwoK=K6!#35m~zW!p^wZW zY`b!J!K0rGd)OA0&Tb|`8EtDCTR;iU^*=bQQF)MN1m2cy?O_vya6$qGX}`!MpdmU`(_p+gEtmRT z6+xS-e-@UBb2C^m^oL5%Py`(Ja*(frY9K?N@spKDc!%Q;&cb2Ix9?&QWCR@esC6fo zfW+eCzbSxCuOW`aP$b1eP`i|0neTccg4C#OTyi@;zasF`j#w7sj?|<_iTT}d9_>|wY$C7pl zB4(2MZ>Y~G`^-Qg6+@Smbm5q{MUz%DHswuDuG-kjdzfj>*eAO=WBWP zkO;;18mM&PH>aMa7v5K?p!2UH_kp}Y>qTcj}rzaEV#Kjf#=>+dw zXV+37QaptFp%mUig_e(AzVLPeHkU>5l}e%!5nIKueJ8;AN$#fg!@W-89`bax;>Eq7 zp!ZQJY$b#2M3sfqB(5xK>V-Ir)#Vq@9{77e6}H60%B*phs^Jck+EH1H?P?kMB2*Xo zYVb`C_=etwA{h}?Qp=#=?=c|%llqX}N_Aq#&ynof=pY(oSWJTZDIhn#pjUpZ&v=MO zf$7hO7FnrQFMx5I_$4MTVb`#Yc_Xb@*i6g4hIma=%sR7oy;d#(jylOn6r8ww>fueXK~A)55e*@8 zl6BvU>t{XsJTdgIFX&|0r=q>ywWbfmnSrW=Iya9&82HceA&vG&lr?h$uOIep15M3> zI&U#v>hkeIUS2~?w{FokzbDD}kR69h{RX}wl0i^-INA^&5Sf@m$!|Q})+F^i332&v z8zf%C`BJV))G2$_c^w>=rTR!0t)F=jC84h_clrzifi@$Uei|fFFeo#}@-&L-*nZwT zh8=XWv*Ds@)sg$Zw9Ll$-ehs0H%>;7n#9jsT#P3|!&Xn%K2j=z)LRu$iZUJM!#=aP zDEialh6oF&n5!EETw;hV0OdIO{rQP?a==k$c(`S%Ux!JI%~@m%x6vEei}Y;j-E+_C*D=E;w^CMd07WUwZDRZnaAO^!iKiZqURuYm}?mH!a+SPqp|TGPacBgU?Fp^gR2*Jo@G56}W+ zBY;}cLCi;%0{0N{Y%YYk%#e>izio1kKfj`xi2*m0Qah~I)o*%}hw%XIECemK$o+lt z4qD>MDA(@2Y@z(bhitWXrC(CBsoR${GNEvS2)S^cl9cjRZ%H9HC;_&Lvz%VhLZ{+m zk)iFCy)8OGa_M%rwNy2BXk?4IbQBCLdyR%TQ;HWT?nYEQ%F(C{O%iKv^dyvlOkrX)?b>R#R zr$1rNx2LgmtLnLAd*SkbPDBWfjy(At8eSLlUyq+x?N5PILnx~@F4V4R@_r*wKgtImoNKC}JpAh5Y(|a)}Ew#sKi^5Bx!tj*7&E&1t zK}RgoMo44;cNhNz7jLRRd`1Qrw6w`C9bCeC4>M~RFj{gMH7PVAwhHhq%ee#$ARqo9 zvzJv>vRS<+MZe->Y%nGLIx_G@;Mn<%ysb2`-qVSwrE*foQ2Y&0_rlD`W0HJ;iU45| zF7*^B1?y{N(wNKnN*CrFjZ104M{MD>)W?zgqM27h2o>pXXDsnF9cg+|TmoRk24)s2 zosP{bgMB`>x9u{DA?}96k+>FVD;-3&j2|e`dt`lZYcX`Kyd1Jug^#?BICipoZ&mEF z3cTuiFRR)hh&vyZm-iL5*})pvC*wU~2bXdJP$O!uaNa!kLBW`=OdW>WuSW|SJ4smI zmeG(vt+0ho1Vo504i$ozrE-C5Z{~-IU^n$vv4;vzsmH4- zr1Zdl_At}BBto;v!oXuu)n+~dgGHcyZf}cs0IqSq3DVu7gbKY#6z%ZiFc+1xfXaNe zcfx%95x!5ld_9n`a2uq9UKb&RU?a0*;A&JwixCzjkA~>?y-wNjqt{&9b~wl9Q}Q1~ z9y>+3yqp#~8}lcx)o%WI84dd^Vcc^;Ud*+1FFTcZl$+61oQNT9e$zv`A%B==9*T@6 z@l9PNPZzG{pjZe2z{}$;uQck!_I6%{N3(}OZTg7aC^Dd}ESH!vdp?u{Y>B(;QZB6O zX;wKtC~H{vPvyhiuNP12^;p(_jyhPaqvCnRPh%E*F{qkC^mEz{ziRbc^9YVTH`XUgiZEn&P~Qt;ENpJo#L$pu}96@m8WZv0nrp%JIht zPxFlScjj%wts+!6UA>`pE}r~2(nhVSgh|_~IJNk_`0u;J9zNK$x6GN?`a2b8W+pG^ zhEkG^Xq^*L1ZfbZm=X9phZAt{l}+O{_Y(kWb_Otk15`-M%RJ7`i2b9_zSEoioQ$h* z=bSo67;*0jS2QWQv+qx4hUeUWPj0)Ep8QDhGvN_Zm4@6}BHk&&0>HuZh0|CCW^dPX zz40{q=PbzTZ!es7I4&Kl6r72YDCxiY4)|XDn*{BaBUn@H*2cr|MWd6<>$dl<@Aikb zC#si+sM-9Cws88sN;3=js+(hjh&=vRWGCIDRTUXFV?8o=QLh{0Jx8#Hpt-dV7 zt4B%92nskuf+StZKqopJ#t$w8-EjucRA*!YV(I29<(PCIO(Dxkeq&AR_Bpx!V2+!9B|IW{FV6nmx3ddv(cO4^z-PM zw##erxZ2CIu>tk9kGKvM4e8jhMx5n-*+=twzvi)#nj5&;2NeGoLpwv zyNCU!!>xDkdnC45F4{#jY;wMT!a!s=!eUjz9uG96=Co3Aw_eYULVs0^H_I*Pc1&4b zm;PKOJC589P+_4kGwXf}lC*grw_FYtk{SeVmP@}-1XScNM{@4Z@#{d=ED;kHg6qiH zhFWzgsi_kYAno}z$195Shgxr$Il9|o$G*hg`{?o;9AtCtNYluAcqYerNDr0lyoLHn z%k$vU-4RY(9?!WT;Z!w78xWwE8K)eQmO~*2H!IsW|G5DjN0ZdXuQ(DfrLWuHm!D!d zcZXFfz_rY~pf7)G5?=RR8VmdJf^heUlJU`V=K499)LEkvApO&4MMvzA{zn^1MRv8lE1{h$6JaoxICLN0T~L}V)eaIOlNFyo$EoZ^wMNys~@o`g>!D6Pk`pC zf^N}W%K-WWe?$ct`H%szPWv3bJO*MvBURkavYhDPw=Dg?fBg*Ve=yWrtYg6%3CM`M z)}JLsSu{PfmNBSr(c#FqEpUKIdsBcA!e^S}e;VZ9yot=`Qcbt1)d=jMHVL#}m?%No z%KZ%2m0jTeS=Ud%Bj-BVA!w&pegcy+(EJZtjd9hPf_Diq3+jz~SIFWtOS~-ahXc9a zwd?lh9Fia1a&8gTx|e18h8O-@Bp;Y*9_EL6sy;rmnW<6HuqpzJehK7HGaRSF{$7^jFsxLlGfckR%@j zsZzJh)J`$P4gdCy`7b24gcX{-Y7ZTF8GB9h%U^Q_8N>SDuAHJln&v!gZ!sz+fLJVr z96-^xF!4nW7nepd=UT;lvU8*;4DZr-I-tr&GGtRyUcK?OhRJh^KZ!P1tX{{d_fome zE5a>f$FJCwl;&4UoiQ^!V1A3o+AYH$C9Zgc6pr9$G_YMVyvkHf3F(#RNx~}*JskOD zf*{FE?_?Jiy}vu!_c$5T#Y1=rc-qq8h(Pp zk82DH=Bp1ysj`(zUGd$d1A?s+8meAL!FVmZ((Pp(tkX8VhCjNv*2AhOgyrczN2(8! zs7rnNSryUuBF7ocJlGwycE9~x4k@H7sQS8(cg&`(MBt4~@auzsn4|i;=)}UV1``~* zNTP%CMA#(``3LzRrhq5icV#s!Dw(kmeJCrzFHH7o&;Pufs!IoQu2#&Beb4Ziuc%=5 z?AZm&{sR!EgMvYGsnq}@WK47Cp2#jY;5xVI(cn0AFImD+$Tcux9Hv}f!Opo}YedF5 zko3cOJ}Jm?pqVCw8qG^USaI>HGvsvIc$4M)bD&3QCV5q1x4KnL zsmbeKlhg>ysOSk$P+7|Sa(#xzfoi7?YE5jZ!B3L4?wO|LAL42?GP%Mfim?07<%qwF zgMZ5elaHbx7X09A*8G)k-!6jBa zA-1C8YP>?^%h8(iUFAZo7F}$YcL9~422qFlz_OJMbgm2>(2d!+_J6tO2kNIAf2JoW zIoY-)GJ=H3@rOgAGb*7@#!A{JBuo$~8yOA~sLek$Y|%2LlANGC;%Uwdf_FNOD1AWi9=^b{U0?wG z1Ib^=cuN8G0bXf5h#%ez%^o;qLH4?R$leau?{6r+bj{8BeQo#nm2bQq;h%LQ1*uz8 z?AR>2@QRVP(oaQ{K3p&+F%Id&kY6V2luAGzfStHqh>y18X-_I$@6F2VS5aQQaB^=E@~{c+?y<@kc{H( zp3ld_W{sADI-7q~2?X8#yUBQ{Zia?^hUj@yts<@)Z5JO&^_3J%n36y82$j9&GjO)S9CfsvlIK-jbwEFeRt-xiw zGVzHNpwyX52TWxJz6Q=a8pml|K-1Ilw<$?ZwmEPJIOyg6H`^81uaPDWM9>wi%gpZr zq^TwyVr-%(KW^%Gi#jv}Oamnpi@@3FXlLWN^zsQIPQ*iYHr4F1mTZBP;>6gBp`mam zQ?)V_ucfW_zNI)};BrElT+3+ceKg?KQqU898UTKAE^`3q(Jtmc9Uvp2;8K!rL}N?* z-oZX|R+NRdJC`b`UA2Wy87X8ooR-bUPnFxd&3X##9)vYz9>OI|vY;ocN{jwu!F7!G zo(%3#4+VrT9mH!77G}uW?GD?{tM5|rN95BRwk1Q}oCO4lbbyS5aYK_tXBT(sxLUKR z`9x{lqVfYYJx4=s*GXU3sq=Xi+RjQc)03UX0*ZvmlL1$(l)b|&!5o}#=RGB=G|&=U zXfLu92hapGdzoz>aJ{!)&Rs?!yz4@V&2>62X&a=u;#HP_FDV|iqRJ^{#pPuuOlcO6 zp=0H$%!_#B^66$jYMT=rYaTm4*2ex zi;Hv39_&o05rVbpm!H3QiAxn-`*qPgae6a7bF#_GCrU881oZh|6g&x`=?Gdv?(faR zM!$&bNCH)b;2*PBZAcE^X5am9hV*8Sz%vvjk^KQM`>C=D+AtL>Z9es;4*jKC8TP>s{%Ue7}H&Ah~O%Htf8 z3MuWA@+Y|H^tIxD1tOrHj^36DGzBa9nXb?`CBJh~S$2_83q5<0XoKuBf3<<^47%LH zax0AYxy*SA!h@Rw&jKHeUKeiQuLCqNntjV*k63&inEnuzZ#YZ*XZ?@cm!kwEKU(h#h|!L=mDhg*NQ!TNMVNFg^syxU zcED@ZZk3|VC;WdcK&?m06*9tRG6!D6+kfk3))nNto<}(b#p#drmZ^9yw5Kr@thzSr zz`oc&PGasq`8AMeyb_B5R7O4?Y$IuWrR#E?zJ-$4NUZH9UYFi_#? z$IVQbr18t&5498B?X>sJADzi*jQC~qoW|U1$dJq{0fKz~ROO^)a{{ZLc82^HAFq3* zLL-St-I~{biSVh}%?-3F6Ou;QfA5*s9Y?8&0Z5uZdo1>&cX36G z$~2cS&W6qSc@?yoGqdGJ{(P{3C=+ z@F_+wXra9gLr>IW#ak0#?tU=uq)H1d?n+N)`nD5cz2Tm+F=Wh9qN9tITYJ211~f>$ z4~9_~7V#OhI`NNx{o|hXc#!8<=-2&PeghcpUyUS;??)lv-8Mcf?70MZ7AD5XOfS5$DzBYFe@3}40zZ6`m@$OOpJ2hyKpU+y{3nnG_NLqJI zu|DL=Nrw#nYCP*_)$!iT-0SFYl@5O}9UeuI* z(L`rmI$5oCu1SV`4|qYk9>NFn_LQ6bpjYoHuF)K39XLzFj;Pfi79JJ_VgC1ZO8B!Y zt%P2R4IjfVp=jZroTG{%?qEl^*@9Q?)@jLt%nvjLY4pgkmC3Z99^ZVtLgP(25r-$2ab?bzq@hU1 zW)-FGkCY)HtaGZ7D=OgfB1hYdPPs~KBOpkV(332g{BA{M`A-(vv4I$|#>Cz7S0)Wq za6wVKV7ZGnJscu zB@dcPP;7$Bd-n9B2UDdHR`*xYRW z-l8dw?Z==XMw!Xyf=%INvJJvWH$XuH>S^w)RmSIDF75ittZ?Lr%wy?fu5HyDcI4uz zm%<F-MBBDYd|n&n!zj_wqx;#6;z>H#+!U6 z+`Ur(nJQJIwtAmmlYa%gy*9C$gUGeI!tz4F8(nF?v9lqOj_7kWVQDeWIaL%dsnMAW zfj2!YW$2tu(V2CW9OL2dy_{jNn4~t=xixgRP#Kb5!_2KfSrQuT)^8%?Iu zFA=`&(QCaXN~Yr6^Mk9}w{XH4$tPMklS5pIU=tSIyuk96;QzD+{&8KWtw#$#V#E?CwxJG#&A7RP@9LEWpAA1K0nWyKz5-%y4l?>}LDEINH?q&j-0Guvop1Ho&d#^x&~pv13Le)w+^2$Y}{Dp!w2D zevAxHJSvyauS-}_!eI-*;VA*O*avaTQeu5nJEa1(myn%?wRHa9B)CgKLdAqNrsXpl za_W)}E%kbGd>j)U&b_jnB}s<6J+}+9SM5loz*ZK0O|Y60ckm5&t=EW+OpK;EY16QV zLoFvUBbbHYeRL=0^4?S?np|+tB`2h=2Zn|Z-N5d-l^Wc}4%*o`b1{zh0f3;K2;+<-}2l5H7tiN$ zeK*0ncf>Xf@R0c-;w8?Df7%B$a$Sjk-=};cy4;{aJ zICRJz_}U@tkpE;`X;1DAMCAqEPs$i$1YGnE-x-3X!i}eC%yl0ZfQNqeI%4Y!`$gFY zEDIQWZrl5(gDy@F|Ao;V!~)!<3wp|xFMpDPSvVS}HHMY^$u4!%j1 zoW;ABU0^+-_@dMI3WyN^7Pkl+5bBW2|NWZoAtvHDUBe--pWv&1-ZFDbT)WUa_cFJ}X-X7h&AA7z9q3)j=v>HBPnI?Y zWtnk%odEXw1DweRP9WW+fm=p_s!_Ty;j|VTm*w}b_e~qNK>yO?rcv|w9C}aCNxQ)5 z%LItYN&7!wa+Eklm5$Njpp53)T~NIB9)zF4H)-Wbt#4zKfFK@1kNDQVR~ic(PJDA? z$O?Y$eoL0cAl8pHyAm(muaAYOW7TG)pC}UsT0mSqc!)n)`^60N+I9zPRNp}%_vZh( zw=5ZVlkb(IqkaTL0=ZNl<%9?^{v?pWLCb2?0S+T?#9m5BOk!rgv+WtaZDCP%VFem{ z0YS%Yvqc&3RCg&|75ZQOM{}{v$!<3v<4#r-gchGqrfr#|`6cW_B#pAy{0+QiCX#Z+ zDjO(C%@P|XM~mO`g5!8gjo>*LZHXtf%spq-p% z;nYT79;9GKlbxm%yQQMnKkcMz4L2>a&%k0R#0AoVfC1#2xX!{Lmn!&T>Abj;oX(ph zxJl62?0#bZ9Ou%#h&sR};f>%4j>N-8Q&_W$nBYU$=TWoQnVr{{gJprWD{=CkPargMdV7T%bnSICO+&Y(6^+`y9N%18CRAhb6!vUZ^C(A zo5C*MoHqBNWzUw#n1cmIjJg?@j-chtSAh%;fuso%O&^RpxB7^a^kM6$~+i8Cwn{Sgsm)+@HROD|V3GN6DHF`bltdj~X@>g`~>F4}rQ524PciP@`c)Yk?=G?G0i zyAvIwL`?B0OC40jX(ESK95Q`LX}Fd(?8h(9jt@11i*1kY)`qXOK^GKJ`2&IPWx53I z%Kwlviu0lOzWCi13&71M0x#k#b=R4Rf7P%kd-G}oJxM4K>DKw@HC*=gK%$!WJSFBM z?Ji6e5dr7?1;og`O8>nl9K)l^k|kQba10+hfZcsZ@4IaOIlV!6 z`ffM;@|Af1a9in@?S}T=2-u!YgzKM^)tj#&0Q|WI}Hx%%J~l!`2%%K1YVC@POF4(pxLJ`1PVD4+xy|T9&u( zO`s^u*}P8dM%2pVcliYjpmg7C6L%Ew*QzEJJK3>xID3lcLr+<%C4ClVxDJ*1 zGL6-9ZW1oZaU}dtm3txg;Rj0jkBUP_E{0LvbuX&>6csQcUP`aKr;@EuKNK6aLz=xQ zL!#z3i-wUb=nv?4be>opsAs`+fe3-{Z*m2!3VPiZx*JoaYu(Fmy>6R-69Ha=G3H1c zb(b~dHXbLGI#U+P%KdK9T_oxx7c4gASm#Ux03u$7SJO2yD*_wv>%S`OeR1cqONd4s6H z`>_Iw;|S(1uqG9dK05WqDfe=+`Ri2dETr4Z)W$}pt#nvk3T%XytQJEn0XOhv;jc+2 zGx7s6sFUusD`Cb>BhccOb0@%wv@A*Y0gw*C#cEL7~m!ru|- zaLgYnyD1c>wwG3>cjX*#?G&?`d$Y>o$VL`grVU%pwzVur$JnyJzryyBEC!D!`Jp_Y zxOPyxDf|Nurq}nsiw)Lg4HNPqPImQwXo&4L=4UQ7P2I525P1}&LKq}r~K{G9$bVNRT=dQ6pr<7?n znABdH8(ImOG9=qDufF6bS6Eo;m_+gaZch=Jv`xn!EtFAWxX)Z_E*teoyQR(nz@#d- z1K0T8GO-vf2}nPoD2SG>#1Oq7m=1~?e!2VE&u8rn0DFHw`?$#TWSzY0K(Ha z8z41P*2#2V=zz#czOh56mw}}d!AmC**8T7PiSSlGkF=tq4&WhXDefG(Et!jWYh4}E zr)pz_wL8vc@K~hc<7vA7M4pPgIOwkSWacJo&as0(rBK&~h7-flbAvS^$x5HHU;ol5 zcY+OO-{r<{_PQuX`frU7xd$$Z`g5XefBMP%2Et->buKb#U#O7{TR~T&)&Ylk(;&ju zFag%eeVY=zq_lQ+GeGn!v&*D(Qi!Wd0jHW2^ldo>Vc^?o!T#GwDf_Qs?tJWiY?1U`7$BF1Yj7 zf94D4(+qW9Dbo2&zFMujTT}*y$?xlnmfpu|q>=IQF#86A8}CpW>*^Tyk@mD)YW~zD z0DlwwvK0}lu=$hCwHrqe;dTMN8@8Ji0E$V|b~7U5uxtGYP$G~!oIWunKe_{Ss_6k|8hSt$qoU0}_*c8vpL19%@KTPBJ~j(! zEK|L7t%nqVBO~%jP1*TJVh>yRER(Q8%}neWSQLNWTbra2i+`TmeQ>2g-_52hhP93^}dqt++Z&sIc5bBZ>BM*E8y1N6MsFo9KyJp5bl;PxMOSY4uWyM4qB9P+-Ex3W!QY69IrJx2Q04BBVP}@=p%SdE z#Jhx%(kB|!4+|2?4XUpd=ei&Ddo&e>;T*+iLE4FmI5_u&$;UBb`PKqW=ng0!RZBF0 z{+Ni~jJYA4SU!9>!fn^sPs7L5d*WqkDv!RSRsEC0K_8T`wImcmZpM~>`nm1H+QVWY z?^1AiV2PPDxmYnrD4?YdBKCwHlL(87T0SV5u(*@^j$XIaZ%g^bgK$uGJO011dxL`i@*KYU0qK` z;tsDgtI$hum)Yp|p8W?HvYVPE}EN8hp?mEx@YF0GUQXs0;P(9pwD)45|` zJfU|Mbu*&KkIDh%z{D-hj;XtwqR>(92J+TzBv-%b3Z=S>jh&Kzr8+G~8BLuIP{VtDH59N*) zrCEQpD3cxIuamo%by)}3es#;>Ojv0>w-{L&q>(~HsM#`oPX}1s?F(zqp@I&^Mh5VJ z*_{Q=%iy-wR+zUO5BWq1XH}^bL|Qo6$;#gdA@XNz@F5KQR%Q+6Ug+i2NLSENIDT@U z0{hS}tk*kL@FTlol9TC`7%#TTy?On1iMz65bfNv^RY?5$0qioO9t~s}klb!mu z=aU9$85mceLLgj{drnR$^}hP66VV9CfD<68TYYyuf%{fYh*XpCsxVWj6|j5@>kS(N zwToyBq6JVNhumh8KJ(ghIT1y)^iIE0jp;8f-q_a$W4eqQ8O5Hg6CE0=?du|HEK*+B z=ExpL4SBj4#UC=TBlsY8QB+28J6{{f4`6S(hltzU#H@2FCJax)!i)cXP!_UI6*-Cn zkOJK)8fmjvG7>^@06(smbJZ%Y;^FEc%rGp$P+N{|1vNCh6e(s_JAeqtA5zZXjb|6m zXvtxjgS9ou`6_du6O@rtd&#!Wg8I5iEeI(&>`)QTp!u9{FB0lxtNgfexPJ<57*y=N z?fI-KCq7f{5rI2yr4_QNH@|gC7r;(-&b1?20G>NdsPF(z0JMlUKvTyO*1`$MV6-y* zTGu^*rW>9>GS3 zx2aBBGi~-Nz~5CxByk;)7Tdp7i(UNcX z`zRRF^0RP_C_thV_t|t6&vspfWqwl4iS%u^Ij)B6U$h8dMfrs_Ldh6Uo#smmFOW;H z0LaLgr5asliNht6TuC+m1hHimvx8b98lifuVylT4mDpO=@weDb=E0D*pyl(1ah2Tc7u9H$ z<`M8Q)ZpabnTp+Zon*PZ&hn*=S0>NDFR7oOGL#gB8ew|8Dj@Bn(D34O&t|AueLlw7 zw_I||YN4Y_lzzZOfl=)cRZJNAtE){?Ql9MgP3Rm%cmxfD8F&9I!eNx+=qSw~uT8=1 zY14rTddIc9RtxHE0%&*|G^7zUo|5$P+N2T|OnmCh0;phdk9|(n8bcOV?l1z)sj+2T zq;@zVDG=89?3L!x_AhS#b2_D5atq&a50I=TM7j_8E6=epFIrVnzFrfKb%1D2$ z%ai%ByAUNbAzN}YS3=bPHW32a93eNEkmpb4v6j0pYZ!XwIzWfhkjFmBBS_k4T?8l8 zj~-noTmlP@dj*e2rRN3N@uc1>@2Kn95~NC_*Yel>EIuk!OM1Lg3a^7*WA9OXkmc{o z7{4dT1pvau{XC#6m`PT(WJeT$yjz#?Aa3q+8rZ;_7u1BUxs{B4Gbr%7SX`UkICBc& z#F3S4{+>xKkUB7f^2VybUSu^+{840w`gOe1j*>WBU30grpWtQlRt;NX45;lnd40ru z`k_eV{i$_6C9JERR5=f-p!P8>mueo^QT=Op)NJ#X$ff3k_)sMcI7fqk)cbu$G_N6*w;z=JD`kNFq7om@B7cPL4R62>HO?lx5&Nt|}@m z${8^rX*@t*>nh`NOC&(|sw+-t7_p(}7IB2+X+t}>fC_}w*9m6waSL-@jLWQg=Xq8S zVBZ_GtIRwy~4-C)ee-79=apfFO=g;X5I_VUyg7(`4X&o0-_pVCpAWu+vpa zyfaCl7Lr{1mQjLw+%wYK{itvB9}G&6jrPLcaH%uD zFXAbtb6NF(^e^^9+q=5WTc-_wROh>hb$3S_vSp9$0R~Jnm7%wDvziHAA_z1-4-jRC zm3e-jokVZxe~AV>$2m1XZIwu=D0Nrq6%zeX*Pawb@)c0l zKEmoYzzAP1OFMpRd$Z!+yK6Q2(WiIXIr%zoVG~3niW#$W(Ix2She!&ayD>mV+DtZr8@@ud?p~LZCpfR}gk>$wq?ma`b^qpP zj&wOb->zpOV;yeZ7EPxVe;}W17+-(tS2bZA6f;3Zpu+v#IHQ{`hw&ew5uR6+x~m;8q8>)jfg!+0H8m z7rwSU-TRW()7!RhMvZ>f2$Fp3GF#om=RZeciM?2?GTnRp_=N8T{l#acg-)GOYQ4-@ zl}L&(2@)3TM~Ah&+5)DbyR5`EUN%EG_+1~kf(@DE|ORvIDm1$g1#6jB~>!v_4 z@xJ^=+T{S+KzJfV{LvwI+?=wtVu8qP#4Cqvmaj$m0rq_rjDGhE-7p4HD`*&hubrb4_FhD zw?w_DZxa%$*7Ne~&U+U%4eZL9`5snjl`NfNJHdvSxW|379e4hfm;7(bPfb3e|L3w5!6*n^A1At(u#C_tJD`(dbKc(T)ndTq% zkXBsRuEf;DXOCN2<(c81_QLiZ@8pc6r~fucqJkTrd({=_|LhJg9BXav{l6BVdggBf z*?M(sqbJ{Qm*)Wkz6G%;rj=0*KRKUaH@bt!ZSM%<;_kN<()!kT4?WmS`)}1!LPsH1t zR3JRKQ8AOIv^RHpjki9a&VbFF8cv+ha^m$mk^%E7L@2Z`w6roL59G&R;VfIL{lbmE ztj}!6C1beU>M--S!@d?}E%#?4>h9kI5f9{o(y0+TM@<2wIK^&IU-3WFpXHDK=D92= zoM(=20+mg`U-&EV%Etgi>~Yj+p6B9&$*VJP0y(xkf*Kqp)H$tsmAo~oWVo=Z3|$)DC- zyb|N&eKHLl_CjjQvW0#Ih7|$@`sZ;5_iVo<9aBNgj%;27$=IwbdcOhAZr4i_Hmcal z8jKULJSx3L)^HXx{Dbpl3)~>MWi*9@(>j(%lzRTMQ2(L_(~^L}Aw{i}T8q9GpV9f! zqHI;B$GC!~u$!~|-t#_~sPt=nOx4s~1MCzJpGu95QXNdtqve+!7>RLcAuu zFuaovlOQ&yw`c}l9Hy!CA8-byc~rKt!)KWtYI|Mh$(+`v>%!d-=p1U1Y%OAAJK2b5 zF%S1FxD5VCzBMyLJvpC(7@j2s3M(S-82B5&V3HY~djLz7QWOiv{N zS2VErpO%~uN7-!aG;ZQA_BImqVkd8=%v`9sG@hYhQGz(6oavqP80|?4HeCFxdtT$0 zk7I`ZcnlQ0iIxOXB(XngAg$B{aC=XVyLD&V0Wv4bzqF3iX-eNyXdyyrlR~nrBGe1> zLtbSRPkmqGHS@QTpt@-E5iy32Zj7c6rFq1fR7qQN_@Hf~Y7Y~3ZSn6?%6M{YKX;`` zk=(L7Tf)id5hT+`m>saLypb9D%B{H5+~Q)SyBj*GzdN$UMtm40 z1AUdq-lW!^$l*9%`bSKe0SXq$9@wibshj^KB6#gKUy%AA*d*x}1LK#YuZY212zlEB zL%ZMIA613LYR&HKqj)IFe!r=mtApq6O#i4h2Cnpyi8Nw7y(n3dynM7n^Ki)pXd)`@ zn2Ebv_CiG9zmXC{W_%hV+-fKBv_NU5&uKMRFKeBX-v@jVp!*F)|3}kRMYYv-O(+g+ z(c(^vTX3gP++BjZ1lQsecWCkA?w%Ac1qu}R0Ks00I~4c-d>8*^F0xkEIZvLw_sr}W z%BGYyZ5pJ6x2z-Q_C3<1NvAeq@8_k3>1Z86ebcF}cJ(BlXUw=1e8=v-pFre5O<6vA zK1_v<*8RZk5p}5lcbDzP=U>N;THNitK!M8y+oRmPC1dTRdC;^p^Y`UgqU0zFE%_ z3$pupp>=Kn}Oa_4Ad z_q$>y*I;u9%OwNBd#{Jc(&?Mep}XP!4{C9s8AQG~=Y3}p&Fr>le$hs%<>`F6=8w^@ z{+{>SNI_SS?xjL>oTohVhk>mU*F>xV_nb15;6TaF`#bpX(+YWKFt6!r*>;WD+57uU z5x@=U@~B%jU{<|z?TQOl6Zsd}rS87uiIoE97qes2iQa!RBEf)cG>svm_iHI<58U{* zY|2a^d!|r$%5Ud#*ayn8pa$d0X{l`&%6a2qghJ8k1f5f}CFic)-@VP(wc^WMnfc2q zclbq=osP>bOl6wamlh{U=a}K3#$a(h7&2-i^$^i&fYo$iRPaq%$}V-jq_ z%NefAXmxB~pCBJ!I!FsCw%Xajhh&V1yV4LARGgS!mhV^5W|rUJ%b6woy0XU#<`r{JejmbUry zRduWNd7&SHxb7%W-wveB5A@ZW^b*$Yl0qCx&FloL7_(3(Hr9JXCVjnoz!Z? zIZ|ce2|4=xfBTBt{?x|$@rS(NPT~M$GAbSRUz2M&yaj)h1ogV_3{A##AgdvdJ7YMC zu1xlI_r+80LnV|I;;v9LJ)8js9tl?bC?Iy@&5vLXi2&mmtp`vY&T$g)+dM`)+iMje z0@m^v?lh=hFs=I9`1*ZauW!iaZLc6BiLWR_-Pmg+uj{b%(XUP161Df88wYimNCt76 z#3r58D8IG~95S+%I>a1-c*o?M^_-q3CRbD}G@P8)Z_(=o$B&OtFC|%W|c~`#zB{rgr0|GCjFkpX3TL6{tGNzEZQ^r z<_C}d)qn~nZ_m}9Hhv6{g#!6@uIK(2TR(*Y8|tGa`!Wh4R@I{}ZG4D(d@0Q8NRglvlwT)oiScN(wC`C}nF-SG zPFxeYe)jG6OJjNZ)S^fKOP!_+^|N;PYL9KcW$aDZS6iMKVIJOy**S)s~FRpqq0n>X3KH%>Gxgi>?IA!Ty=}~a!ak^$4B55x`Rv`ty|KuglI~D@c5X4h zjFrPCA#H!#^iAt1$keuiXTdJ5WS=hOIxN~+qH=YzrjyWkZpl3EF~(_4O^s$Jt9V#3 z5%aG^5hbMEx=fzKHj$rzSvGOr=Dqy8@{n=;bm3d`qKGnTms)>JDU(WW8+f0658%x0 zUEdql`BExQ&2JEJL5R%er1insj+gW}(80+0 zQuI(|u15|EELmq`ue~8+ipQ__8L}4@2YdZv>K~*UX*{iy7@<4Wrz3a?JQ0QeYf)(nm^BZg z*Yn72sDedZT4v>CXMD~o z7S=<8{<;tatKgyIG?L;ltqf7sN3xWUoYNoy4wt3ls~Q*Ep)621FX(yLC?Xd&Vv z%z3;2!*mm^A>##3o!O03E7a_EOj>% zzWc5b9Rd8Y{yQ0Kt1ozIyf&|C6Ub|VJ;!-xpzxrfU+|fGEO$)?-|+dq=FmSQLODo% zczl(5KXTa)iqy-FxF`)4ZN5YK2Q`xNDn4RsXM(Z9@!GIZ3HgMpG5eWt|7|a&(=%ll zLhLHMflHfSrV4~U#LNCFTT?CRlsTGnWY!=X44#y>aYcRY12HK4IQJ1k` zIQ2oeNFfc34RmFo)GXSPT4km-k+*dTuwN+Ol4a5%cFH7WoV!XygQNl1r81<}b)(s1 zgMIdHWna=ZELrnTCs~!nYfHTa1Odz6I5`Yigmv?@>}4K^H(W zy6`#WTD-#YsB7!=XRcnhM+UQ|gDwOIvz8wne7JUINap)FokibbpW2jj-?%N^-T+hrBx%wCLAj&Iy)=F z+1jtw4Rdy?^)nIbRr8@B$GZCnI%`)TTI;R<*rwV1J@0tQ8=e13ot4C|YYHz>eqF!Jw+6Y$aKIIKdcE5cY zuzgHl9gwu#fzg)fUE!m1Bxb`#){az}f^sg299}$cWq=8L7b-yC%}H{*hYVkWzYvNsU48NWZIbJcPpk7x?MVTnMX40HrQMuK>_ClVU zSdy=eQr#)J;vBV6z(FHm-1lgGhedD@`Tp2L9zHjsm+jLgg+aF*02@Z(`E1O+-kXJq ztGHr&V_IPRRHc{hK)jJ-wvSY}W*UKa4|k<}^=r-UdqmMrb!&)k5=%X=D%rJ_76+6B zzvRoq@2~&KKYZA(oJc20O~uH*P*1{T)ja4;^|(n#-?sPA0pYGcOuVPS8cCUVyMsm1 zXi74Q{bIUl5qzH9gnuV_e-zLYV2PX{z&Wx2zG^P=vT;Ug3}&FF(s}SD0h1b%9c%#i zuO803(xZo-0RLM}VgbPOskxKt7Ie4s;&B!k;@aJQvdcS+GPC@)D~qvgEk+?L#cbo6 zzw9M^Qt(p2Sl{tNj|b6k&+8{%G}d3Q2{Q&vJ7iaO<`^_{Fz~M|$y?i};mP}m`L<4~ zF$`&l=h^e$ZL@=(iwe5|mE*3gL5?Kku(W18CaMf|)a}n6#wdkwf49xiW1#WINtC3%1*zj~eRo#QvQ2NVrP_mv_K6$%E_D`LAQaAEpYmU*Oe( zBFr|iJD2j7@Zn~9bAhC;?pWeHXAR7XII-bF&MQjj z>T%Fh)uhp9(>>YCvyudEN?-v_XA&a}W9w>NM5|BeeFe(T;tSr!0z6a=JA^orfSJN~ zwzUc^Wy!~0EfwK!>HDXV@-%ka#)DMon5MUPC)3@J|8=9$E(XBduS@q%(Mz6`^lW`t zv!c1>wxzuVf^>7-wi%RpkqX&%so8M20%16q%<@YH=va9`AW)UWU1ite`453dAlg+P zjTR}>yNs01EqEXPU4Ja?8>3TW>1d6yu$Sf}3IkNO$jtIui%W_@x19~9_0JbBn>#J*?JFns$|A=5>nC;E2-2ssQLT6~ zPC-t+u+S8Kx9tkB5?ETouma^3>VNXT!EQOaa$g^Y-%{&Nt^t|Oqfw) zcvQ&VYVEMMW))XYO)``jgaXw($mO{KTUFR6puN(&X_=3tly{8#21~jyO%}-_TsTLt zY}CFB1XtC3i)Ri!K8*wp%Xy4eQaWETk7D$j0!P5nST{|*kQv*a%J9uVXsfGrL}7fl zUcf9#*~xJfkOx))_O2qaE1tNzZ1dR`O?)>=E-GAo8WeCuL_czVStv~kub1bZ$hAE8J_Qag)W-#Ds1kL3qCeHyR_9) zqG6#FWu?SJ{x+!MJS#k5BHKF};${udreqfJ68g&He8z)|kFiG6GB42GBr>$c1yzC-{71HOavJ)1s*rURs?lZrC1 zQK&-vRo{QIUN`AcG+ZPo%{<=q6hV`{`BmzSOfX2@u?w0xox;*q<-sxfodFmn{;S(h zkIZm6%yIO;mJ3>A?{WVe7aWUB5zyM#VN?qg^Id!~=qA7qtA)kKzNc&tXG6NY?%QP> z!y1xX+J0Z25I;s4lG|DGdBxULB`X;p`2)K&w|G^auN+QI*_Gu1t8d+x4vi%lpH>vX zHBx6Ao4*1Tz_WN)=HPleFO9)cLP;3)6r-YE4ey|V86vjf2Gr(U#ZrB_lsmR+T(n^F z%!+F(dI%dUhesloPIjE=N>-UB-#&ZYNwD;xu`Gve8VK=9&bw;#u9+m~K}L_0x(MG)McqpQk`XaDYs3zjg2i6Y}V|XfTUlFdJ^ja z{tbA(tezN~aIS~a!9msn+I&J=mwtR4ky7gILP zN;A7-PI1BNH43dHy}49|?UP<@IslXkms3jj~fXuE(TmT;Y>AO zpFiXn;5ehPucmodxK@Ac2nYeFq@8A#Ri6}P@DJI1H~{Q3*ezR78+KEcnJ|vf6w2`w z@ac(R{5m;7l{2FL7Ff;cNU7H#H{dC^GoX;>$)ZH{`|{r|d4!d2j>rNS+#`kcDRmRf zW~4F?fL55>giFR(xsO{S*igO`z6iWmsEU~npy9zjd z*&ZKm9)>3sVPVkmvdR~S=d;D`_!>#hB2|RU7iu=5WtN4&3!AS2@G@J@?{WAsN&(2o zjSk73tpykTgU-|f+5B)^MUy?bNru;Sui0r8qY2~iq%XewA_91;)}JPw#Jn_{7YJ;9 zi>4dLl3cb5ymsUKfb;K%!Rd-twUw_gKu9wHTNpoUoD`Sqa7tv zln!hTZvy4iGK^cwyl?^vhx@s&Y)o*F$VaEMnbIzzeX)1~AITEc4xkQeF^S{S(Nf}L z2g@YFlngz88mRcM7zCX4N-J;5yz5H=(L$_V*P6s5ePrnj7XM+3<)tKIthk9MF1MVn zOo#O6E-&>o*zo7gfc)h1Q8-i2UGMD6)7qwFEw2B4_{*j3wYuGn1XrX(-cx_hK@XVh zv2`MMTmCosp}be1f$WS%O%%J6tw)c^8M8OUgrkYwe>IK<6%!7VpApVQU8i`7F)b6i&?THU1+!;9(#wS~8@9373Bs zsI2=^Iq8@wpN;KMf9jwp)T%toSa^27U>D&<;kTzOT*GFEpCZD@|5D)S5TK$bu!nElnqLCH*N#1qx<(6yc%0MgtteI3IV3c{UNB8nPU)ZuO zsMp3m4&(X}pS=T3)BJ}tGh{03LjSR<(xHVc@V8Vc*1ew?A6w9^_ctK-{0 zv#joY)yJIkM=rVN#_kix8w&&FfO}@&`JALm0zUha$r|G~)bA>iaeR%PF1zhcIYt2N ze(iQ2elV|~oa!ZX6GOnLQbjPBj9IjpKAME9}9R*3HZnD~I5T{s{%SERLKu47H z+a<(Pmga=q;2(+``%!?)vb_qte1L z9Fgn4SkdJQ z>SYS4l?~h;-k>Xeqv9zF!R~JT?{Z5UB~%6c@%Mah;WZu;&B~=N7Xws!!N>B~vs~4i ze@wd@zd1O(l?0!Krdj#j2m5JiZOWta0(i~oldM3H&W#``gV1uO!@>pV#I=!DnnKX3 z?5KCu(!)SK`QWb5w3}QoAfMt=60N+67>Z^?+bz3WL4U*@@zF7bJmQD6VNqR3HeOWz zqb|NN-B^FTwzdL=NricD`c<35zrTFj9aP^0JeAW5qwn>D8h)A*|{7VOsFf=e&5fKfOY6?FY^nNO*$TfB3cyGO&?;n9>(R1;DqlV?axp zw(tkJ_i2F%!#93owxeZ3R1k!8OXpC3KbwkekyS7sinp2NE++b}elq_~$fj_c-Af4Ik$5>cz6 zPd#}6{<(G>OF}ZMq5aqtu2n3QJGI2$LjxtOP!U;b&dxoW#B;llz(w%$b*Wnn&EWY~ zBej?a_uefNVru;z8V=!Zw={|4+!J~g;s0v^UfA}rgTC==$StoLg(wqdh<<+jY!x0d zZud1hYgj`d!^I^H=AJt=ta!{VIMy#uvwKn0h;%0-aGyVYeQwm^#4O-CsAr@}4)jGu zot-PZg7>B&Tw;DH0UKyGWOw-Pt0l=lCB2`i40GCmOtX!%@PXUHOL}tt?2>4x;N!l- zI7%~Ve1}H&@l;+IWvvn%Jn#R!@^{Go5Kdb6t|6BdLx|mOrpUUwov6(H=2Po~7kcVO z%fG+F1Tcea2NDZviJGkFGVcDT=2nUw!hM1DYJoe0s5g#@c?DRFp?FFiwOPu(yz-b6 z`9$$WUOdK&<`EkwdgdIzop=5j2dmr%XiDH~rgkL4zWI0J!+Mt2v0jvH6 z?-$UBoU&sbbK=(wZc13&VFEF18e68SJ7!D!U8$Eur3rtWrT_(wjD`Sy_i74{6RfVe zjN6U_kV&BLY>F(%8IEMeJV7V(w6tx>@wjO^^}{tPc~*_jcTg-iEG2wkMXPm%BT!8r zf2~ZMZSEPx9ImM1>CO7#32z)BGap}3w_mOi8YaxGQPX`Hz@~(59)x6)D3V;P+P~96 zfLKZiUy8H&B6dz$Gho&??_2%yIVC|fH~Pmv{H_u&8)}ZBUuk%6IKi(Wf9W7d>_Vxq zO0PNVdhxM%W?DCsGw=FcyFPc1Jn1x%mJNdr(Hx^QGZp*#_HP)Ay@YAp_1zeBi$7D_ zP)}s3iu431uy!^q%fHu1BvVRbSl3m_WA-=mjSZnJu|AyyQI|r$vq3VmJgo{RuI>{TuPE9~l<>3{ zPDo&+MOkP<4qOfjqzosUgK>hN!AIQ)W@07f&6Kxt%cY~WQIh;OutG#`FO#Lx*NL_4}9|zW)zPCyB()c};gXFlUnPQ{`%j z^oKDlTA4Y&GND>EV3h$CVw2c>QDiRR;*9DdqS`@eG1VucHC7=IJr}~~s+`TC-VH=R_y;nlq_?Rjg z9j^UV5gOSTeiCzPtQ;n0(43eb*;XI|Mg-dtLz^3kb#r9De9}E872<-$$8FE<{wxn7 zfxT!TwxuJFPhZGj3&}%?9D=MJfppNGUjQE)0;b$<6l>>(7q4ZU;ofMn;y*Z8(v|Ih z9c-Q==wE}g0*kv+936gvODvw`oDyY8@uD^{gc&i}|BRTwj_A9sB#5*{o*n_lVsmQF zau0V#W4Cagt;=TL=dCe-Mbqk=!}-9*D_o0dB!M~mQ_x?JJEQZIkw0cQz{xzms!Or+HQ z>h6sSleKjm$;TZ4B8_Chp{O;k1Oz#2Pb79q-!~r&VN+uC13J#DYPL*QEjK%AYn--@ zZDvWh)x+-Z_!duU-cYBkxp4byJy+|sE_8+Wg~Aqm!*8&%Y4m5?|B(fEkx>Ta4sZ-c zoU`1M`0`4Y(*#@RTq~RHNR3ENpH*06w{L z=~aQOH7be8)mIRZG+dpD$F90}>h3$1^NAMi8WY5uKmyiBI66M#kS0BN4{#tAnGUu@* zDm9vXVjC^ndMy@EXJn>sz0=r=sd zF9^OI@2Z=_vYZRe+R|T4FaPWDRk!@Wj(heHB2kd!wPMqqSJ=K|XZP>2AMjV7SvTkO z{`+0%A9!0B@> zen>jm5JPhbXxAx4${5(%wfFhpv|^iD5~raeoG(@xeN(-OJK9?Us9Yg73$DL)%aOjc zI1=;f+H}D7kzZMP9adu-wdIm+z00EKD0Hv#0tfny)nq%@a`(BdY{Y+Udt5@l;x4j( zc}nomA|Xe<#qw6@Z5z){?p#JTK#DhrxG{w!;Es6I$3hCo#P3*xHyYPmUv6Qos9IpS5YE2d$+wQT|l7_F=9_ zt_c?;L7G~6i&WT6(bl2_S#9tlNFf8y+MDaBVJIbTwXC z5@JkOZ-7cdk}%@$bid<;+QHk$<8fM=(d#HK$R}orptR2ZV_BW0r={K!%WLBSyP56K zkMrf7+gx&e^U!T=vQiza{!cu@^&QK-8`0UCaP>dHtxYm$VVIq+ys;^0x9dRle)NNe z>$Xw^mIvL>CE%yQJM_0Za%&QEnnblMU#}kj+PH)9#23}_B!ZZWfC|<*Hh0?yMXI>* z{4m!1C72BfbxGz`m`9Pdb20G+A(#YFG_=avM`|=y%KxMN;5;VHa|wKb^hGZ!x-?5M z)BLZ50Qw64G$|&*!QNbirDPFMQ6lJKs&M|Ld7=^fix%2U@^;5zg$lvzgn7=>5-KbK4(81P`rNT{N#xeCj$Py~BbH!Uw)-sF4bc z#2|D4e)6vWl)i$+_`T_9WDSlyXX*)4ng^e7y=)OyfBi7Nb|#{Qb5Dm;C-8)lrF;e) zExRz`@`-s66(y{NX`AOp=BuWj@}W}wG&w2gHVSz$| ztvhB60|tkavq2ajo))|A$+9=iRtf*AMwmvPsM5I;B?=1W;fo>*iqY{}!nBu1rR7BP zkr`!reG#gxN+pi7YnZt<{plIEATk;~IU~(IU4nEHpNa&+t@$4*87cpQkz|AOIJ~c5T^{r?SB7Vnfwq?WaQX!n@{kA z(+i}n8UF>1TEw@#@I-bXb~5wv!>g z_MzN5$^(|&#j8CvQXl*U+M&tGZTukf9Mv|+86m}U z|FaU2th2E}9R4JBNsx;FngW|1`GY`f`DG6wGHA3ZUoBr(jnXX-5VerNS1WHFGzt3C z8&d@o3F=s{afR)00!w-afd+Jr#T29Oyk;PR|Yg_XqwC$t}Zrz+Eq&@^#O}-j=#h zJaQ=BY1M5WF3s~>(c7hg)P~wZ&wtc zTzTRQ*XamjN@-+dKThn>#2?+qzmgpg=gdQ3vIJzh%AM-0s)d(|lFkrrklGl)f-I4y5I(wa^nwF6AZOw77`LaGa)t!%@@2IVj8E9`%9MZOBg** z)$Edfp%Q<>7jQ^FZ0v1rDtztQlLmBovTuk>FMBCw+s6Gxk^4T9a@xjmd)-V%NBqU@ z5#~W?sUd~R|0ab1ofjHyBYIz&NPSAUc%B3+60Hie?d_4n7c7x`AvW6?T-GR9;o^TUP7PFYu`oYo{v1j!Dfs(ic{=iFI&2xJ>Db8inJZKy)2lS5Poey>l90}D< zi#rbM6cQ{eXXp2>G!5$sMu$I12)XD@Bg`HJ?+2Ybpj2Wkj6+ukS7%2GCU^UcNO7W% zm$559Q*({#y@d7e6zEZH$}6KQn9@a?liw-8X;2L`0hwh#1H+sMq%%_={SDG$aFgirc2uO!xTBuv4iohWGndl3Du9Z5H<~0$+#zw|1C18|~-I zC4+f=%K1G=9V<0)doWR`;16w4POG-Ou}2F7($UY{SD{s$Jqa(JqW=ogUM?C=RbR4) zT@RyQnr`%8xbH^S#mIW@Ci-8_!=rmR)S7OeUTUBID_DKW%*?E*j*Sr&qZqC1Z%dw} zCTWp6{`v2=@LPH|B~YFyP&PM5k{wc}p3xs>LfWX`LqmkgkM#j4Z1rbe;HCcN=_8GN zPHXD(_Su$c63bg7r-CP)R0E(9;C5=S8#<&}Z-iWm9`)xo&K(G7I%+U}<3YY)-&%yj3 zQfA(F~yM&5l*MuSxwY6WaJ6hkD7uhuRpFgdrCc2pV&W|cBO=L9iYa~%^0Zj_W z9BvF3CVDbXU4rJ$yqW3U9@mfyTs>gruBVjSMSd%z29u6ShW>RZpkQD4;`}-kE#eCS z(dR4_Y5w2NfL6SYUp-Auv7~fEVnVKuAIM1X*d9eCOiO+fj{`Zn40R2X(^6~xk~#Sr z3D}&7n10kj`na+)pp$g1%!Ino4j0>nEjLgs15&VgGtJOgoOIwuM zuLK{|lf z5yP5g*cT4`Qltz{FLG^A2*1K&A^TvWgs<>aWAB0SxY_~q)W%BKk3F%ux$&aqKzlwz z^6vJf#6J>=PzJO3wJ_747s9Fe^)`1Tq)Ikl=t*CC z05SWY0&+Cc%fKFK?<7Jqetc49s<4@@i$QW z*ri1?K7=053%$vX`o`!8+QGM~1-NuOkB1lA)A8W#; zSYp$n5c1S}!+6}mtzZ0j9wkY+AOB-o4kh`_7fNgRBQzWIA<;?c(^q=g=Bl;KgR<)t zULJU7{wi+IpIXaQ0_IS3>yKaLBxUTFcz935Z*oshAD#lufIu|OM9;yiAAL_Zo~Mu2 zJ!Hqf&FkF}cFq%+;3Qq)=?DwFgzqb3xD*k1<)6Ly8Hv>M;oPPib{#FmrU5Wd%`+vI z^02d%P_nI&(PJo+*QSh&6k|BCpOAf-$w{}F6kOSe!z)GO4+W1@*HwRBn<=>psP?Y8 zx%*fHaNADOc%|XCg)eP7KS7R>raRK)TM7O?5R2*)0Ghqae)W*!iD~8K(Ze^Wt6WzK zX~1aagWoQ>qwK0HydvKZ9Yp&J?w(RfDR+|$=72>b4^EmJG%kqrMB*VC<@AN>pc+N) z`o+U>EstLX&3=Hgn4jv9x&Ag&&13TJ@lM-;~d=@+j z>n{WN_RH%$mH8iFN5f^tR#h9U0lcQkNg_stFovVTSg=ZjSMd8fA6=KiOFTav&Py~M z(Xp%;<}qW@!!I%R+KW!4q28e$wT>87e2mP55s~jz$Z!=9@3Q{8I#h)3>WL+gx}pUFc5I@acR9Cc*yXf;V*fQ}GsiJuej@U|UPFWs}GApK+{lTEt7p&gd zaPsFr9q!atjBWz|0d_yR`Y>;}=&r27NOpNHU%PD>ZSqKV81`G0lo)%&rkse9{>LVH zSC0E-{7TKxxEvY*Jz+zzZiD}EAu0BvXJ{#sS$d0$uwF;gb|1Uid&bZH2A_WD@N@3- zSW#Mh_AdR0S7+`v!hlK`rRyLoGnjmkco@d>`cTV`!#Y=Jv-fS_b?+#x{`P!ti^gBH zP_11|y4|9zKddIS5h~oLF5Zh*53CIr;UAS-DV0A%!>f8)@aN*~@^B|H_ytTAWMt}s z829O+#rh`9U6Z@bvD42KFSDt@8Z}`O)__AaLxPP>&WMK;w{#vyQ?NEF76XwgwSJE8 z%w1F9hW>p^IC@vZU3SNfK4A&vppb&Y3?VJArrI~oo3)Cdx7`69hVvG`CXe%O);y&W ze7t|&2VoAdaWDJj%%e3OT{RT^I+2pm;r{_9uQ0*W29&tR_Dm9f8Y2iEDH)mku5Np5 zigNZ5p+TVe1Y#d8C@o4UOcINZ3Wwj+GHAwoFN9T&pY{mIWBMI--_W91CA{n;zg?&w zkQ&1rD9Ixgk(%KgLdBQ+EaSClZ6hnKPOZ~f;2cdhKxz?&>~2$*Lj^#(;dwIrK0pT7 z6@6(lRPg6q_e;2;oj9h}K>`r?lvOw!+~OxX04z4Hni68rY+Fdfyu{v*&ukIuPQdtG z+6b)@!Xrjz_7L?Z%9sNIryO5C=%}R6zeR}8a^h;su{>`D@YV#Sf#w${{HMs{AZB}A zH#C#h4yl|*o#gB5kO@{u-pkHcOXO8eTi04AnU|Jz>b1q#pZXoNMGGPIvqa^bV`k)Y zfr#j8X9~2l^-TyowK8vM6`961-g+DK|Gh+6x zS5*X0b}~Evlq`Mq8hm*?b&)#cU?jB?TXik$eZT+jszxzw8t}~Gwi&vKKi{m*V!>ST z+qGj-)kY{6IH=wn(w52jQEL*XoNvbQyt27=A4JzLZef}~Q&JHIjRYKKR`4j;pK3va zIn+9i{xkimu9MXW=Z@jYc=LNOackr7Vj$M(%>Zyo2y0LMy6WS)>bbzcpfAU~11uL} z_MR4Yvi@>g&=;?cPZ_Q+Vah51=la=4XBX}$*+%5DqNG-!L%P{E-q5vDPb@;=mY|8) z4j%>KD8Nb97)GY@8m?zK6Ttpl6G4joj%{*@wg0)(NmUD?#;qHCHm4^@GcGRmEx|mv4Ur z+-ltv$3THo>tq`5G?;$`J&YTW=1ISsE1MjI2=+OVY9zG;Baywq6AFts7@Svb2^I$p zhF86*pBy)05i{dVc|&S7FJxk52S2GK1Vt@lvo#T!zC-MNI|$Eu)}Sgb*dk-q}G2;oD370y!_9KLn` zApOm&>Za0|&s+f{C$bCk*j8cDwu}Hnkmc44CEF-DCUsI8Q!(D9jCTE_mE{<6Ja+Ur zT_(iWP5{Zg>oDqlY?GqKk2+kTO@`NhP+uSS``Afgfv}QN%DWnE`bYi2L?T#gh-#3u zY6snlsFk#D@5o)1We1gs>g};kOMiLmJ9P0OC6LVjYXLfLTv}dCz3&^5Z^bEd5xab? zYw2#m?6Y6Z!+?a2w(w)`?!;vViqNbKfOqvnfBsG68uXDxWZMy zc{VY#g|cO0`#~RYE83Usgfa_0TppZ;j53p4d=%(#O3>nj}v*6%$v$@NO53dc*Fn>QRMmYnD3t$rCm=FWn!hv=k?JnjfEV9us_< z=g`fU!VAu4g^DZ(5Nkk;Q@Dj5ba1+>%PxW+O9f`W2>zD3V`%#Z!5O%o)Xps=P?7<< zN06L~`7Q0|kAQ_JqsFt#X!al}vbGbHVwW&oJx!O>sRdr6%nqKrfmzMebI80-Fa}g{|C->- zr+=5>-`!VMvE!?v{(ChCJovF>n>kC(!M+F|ct1|3o-c1PhuZuWSJ79z66b<2v#WHHgsC}epV=y+ z?zLgwm4*zoh4^*DZ%jJFc6Hsp4<>5Du{`K$HQNRv(FPxL-8FbZLDGLNLZNbD8oBC3 zIE^jL1=Y~e#B2Iuy@$#HE^N<_IiWsOBUqR?6G9`Enl8uwufE!m63UTb2*k0apD#D*p`=+AT?=3*+vMw^C%jep`jWkIR`kOQBrn(%sCka)8bz9-3hTj4SFz z=$>Z;C0!O4a0{i}==tdy>MoV`voLsD)Lvc9AT>p6bcvO*#!sx$$^L#@1sK!#2B+fOHkD0i(W?>P8SANE zu5U&2cCQ~NiAydc|7kCLYr9JG;g|lCX?b5*diA4e{LIspZns;0?Jls^8nDSPBpRLJ zma=xBJ#qU2>FTLumBvi;u^K!dSQ8!FyHKXbr)$4Pl z;uG?76^vv55mO4&;!wy$P&cuUNE( zG+{(dZX0~LOW}UZlN7=vh-#`x*wX$W?Fd6bdqcp7S~8!f&W-bDX_h=cWOdvv_`N7( z!!FpSkOJpulG{p*_P==3cb#y!p*opiE^CPxp|v}`D5NNZ*sX$|7H~~x&bb;edfB*~ zUpM3`{~m4qSSk?!*7roY{B2oWci#L1=w>fc$d7fb3_c=}kD%}%V$GiNyh~R1`{S@Y zh87P&!Vz<7Cpo>X0qfhSlZ9B+sEFIGdsQ42$hl9m~wa!EHCF;Mu z6>Zbsvg4tMdAhlPEAT~98^=oAUR&>`!~e=q1?p(1xrCHuUf%B1vG2PvJSq1GIC+?i ztEQbhmWxts46PSv#sO|%sT8_PnITqf)jL%t?Nh)_Z!tpM-HufG8%XAC?LoM*hI6xK z+P;|L+tl*ECaxgRe$?-2%~aR%=0Enc)Z6u9x?4#g>2++B(V2oOBD z6n7}@y!(I8dA>l-CcB&8%v^KL_>UBpPl!rCQ4wZHq!4JC?B8a;9nY@x&f(#FUOw5e zX!c~P&e$t4qk^Hoz=8ya5NUQKUSG!@TJO#-Ew3nAAO0y=+kXBd`8%g_jH_k+q48fC zl`|q=xEq+L(Y7V4Z?_y0SCbpXeE;!^cXzVYL9_sPLQA>VA9sJy;_H3Wn!p&O{bJ2! z6YLrq6@?oS^W&@v@?SJ;ccDc)r~Yy73fa`}MNC zQ}`d_vo3ivsPLf6GaR+wHGlVAtiH!Cu&A7%yu3{dEIP<3kNqS>4IdzuwsWKPl`KjX z+NQRpk@mZ+!`OfGyv5EXt!4@)#IH+bC~9X0#ze!-No8wn-p z@b`Jipgehkjmp2{BdS@Q6hEG5SSc(xiD2xMyN)~Zvoa< zP8N?u^!68lBl#7?z?#3EtA>?DFg8QCGo8lOQsw^K)g};Sx4IQdr0<{6fK3;++}YGg z(sk>SKvU3h=KQKUd}v46Ip^^zcRUv19H0oOy$u%nR(;OybN%VV#a+&AsX|LppZ) z@n+FMLM+vAncKp3G*_&;(uz*_Ys2B}Zm=Hn?_8Wv+eq z>2i$2Q9V&ZP{uMguPgWM0&7^|e9rwZwlpo>#45u(fDSW-A5gX5MSmD4hOhfKsnp@u z5>%~MvaEOR#mV|72trhaA@S{Ce&a3OfqkGUoADDi1oAPQrL2Pwje5uZp`;2(jGTT} zb~27xs3`*#0V)O6cWutwFScS+Gp2#{^P&s138Ed(nw2?+mKC-NlY>Rf)+)|T9s{}M zd>|j$B!#POfZect2C&?G9394acSh*1NET_(+N+X_*Q!rK%h{KkevBGfIMff2`On{; z3&tPGb>%qpQlQ)xprXEAW@X~y#XmQ}+!15}rw$+dS$T%!+vAK-$Mb0R<=z1)C|--y zu@=qRKrZxH6&I9kr&~jJ0hX2KUy}2CBHO;3duUu;J|y)=SafCtNfAB@>bsWI^msH) zuJ<%i>dGYc35bk7O=MEv


    h9yDm3zuA88=5C~0N@WvJnb{?B1~U4HcenY~{K&Ns zNsw?fqM$mwT2MU_watDH0h#k|5tl=XQ!w;VEp1di+E=mQN~2Ouq^^Uku{!2R}Rqr0~3AwE}0lSgMH+@AJ8YidZnX2H&jwwxo7qwG&2@9 zbY=@d{r@}}l*=`s1}Ib=>70{(f->ZQ%c4G@bQr*P&|eJbj@8WEwg{t75A|0=xPvUNVc8y4Fa1v>C9 zFmBgeO%rhf;X0LYL(^ zj*0cK+F@;T1A`*tz|zEFVyjB>a%7ACWx8oYbZU84+Grk|5c60deSD234)<5ixsx2Q zk%s!tGZQ5YeI}JZin&2?P+K?s!}z3@Ms?w0SBex?K@#Vw8{`71jpOj*mRY@-!Z zu%x&8VEzLw>RRPnGV>1yU=39eT_$drdg2GcUkKu4cvWdS!Ncx(AIMt`QXCxCzkk9;v;D#KR*ef|Ue{;6B@<7Hm(S@~SvQo|r z{kVpa?H;X~N4Ncf{p|b|ih@MmrYCc$!yR_gGc)7KSQr>jqOcl`gBX@}b zzc2*C*Me%Jjg)2a(h-#-w-&#u}y-6NiwNvS;AMuB`$=? zh3mf=IpR|MGBGI<=l6(FzZ-ycYE#kg0{N!`AUegbG+m?`6%f;x02EhN*gZ@g5p{m% z2rPAw(4e!jJKd$SxdGYyfA2V4f^*;29g_9D^3Q7a_oMk^kom>{!EBc$(mRat=`zV2V z^Tr2TtFF5nus2u{;5j7NbG7JwwaEi0!3OcL)2kkpUgCVvGwfFYDU`Pd1XMfe6~D(b-cPcM#UN-3-ap-6#JpMN8S<8ssr^%oMN_mkbUo6 zRHUW^xmfr2^=FQ!(gs)w>g9Frt}9bWS9g>h-@;W9vX=|2t<>XqA!Pt7rZ0`zzOk=F zaj=O~c^NN~ia_@%vX%=pASJ!=5Cm3Etm5LYVd|(qZN9jdA{o5?mpx|rYX%c#Lmfs` zXV(4tE!VNu>-L;Ld9!>dlNu{f(5yFI^5Ew5%^%~bkh&!I<|5^Mvg_{8Dh^IsvzWhO zDBX3q*^!v9qtNOPiF;VFVb)S%Sb}EQb*PI<@Dnu~ZyWyTOpQq#0Me@57EDj8n18Hu zsah}NJ?Q%;P?N=AL*xJ@1qHHx#%m=3YT^#chd_N{znZu%c?oPWLYz5wwb{HwrlU?%fuR=OSJd24g?y8X5$Y%(_-bIHR1Uo_o*$kInl z#>O;;MaEa8_iFe#<92X~PU}c4;7nJ4$(K6>#C=kj>nTd#(BPIGlj+6Z&nQ40WBjCP z>st|$DLqDpRi~p0kQQB18|A@|Bp2mFiY=tZb-8p2&rNL-T$Cm&_nuJP#li)L7UsM3 z8!I(TlUuRnr@zlrw0Joj>-l?kY`zgVoJVx>10UZ4qI#zQhnd?zwuV+Fnc1Q77okRY z1&~Gj7yATpb_>kL2POA_UfI{B0G~QC4W*o`Z8g$LV{EPY#dWVbFFJB#>x^FF)fdAB z5syROrQD!AT_6VW+$o&s%hct%H=N;9d-B4Xz3 zd)#+*9Lu%e(Me*sU50{NwG4YK9E3QLJ_*T`ca$o(Spn=g^0W-{LIpmuK$|bhWbtWb<#>VN;<4F@sIQZK6W1O; zM4u-u7LP7BY7y)8;C>X#otsd9H|}~$Kw|Yrym-~?C;CT)8dKol3?JXzKnv=sw%oXeDM zQk*KsR>8DIt1uoKK?h!9I20VG_lWFL8equpGnYttk)*_%;~xr9k%I;aUA+%iCg(}) zy7;b@6h7UdQD7(MrcP`CeZfoH38hzSn5Uu(H}z7ap;O2cU@qD^ceA1tdY_eh~}8uIYuR&l(|p(u`lrP_^IxlAT!Ra`{NiVDo}yvWL& zIz~I)-sR1VU+m4}D9&Vwi>95c96I|ik-xkcZm}bLz6?*t_ZHk?)lEF1`fe@rpJ=qm ziNXz=EXnl#@6_EN4KR{js71`kHr30~x9OvH`{>!32~4s!@i^lWr_HiUSoYQE)D_91 z?ES+ zdDrQhd`036=R~NQGuhd}i-uT6*NsdBZT5fajG;}_Z2maR!C{t^Gu&3yg>X$J>`u#g zjRRnRDx0QEhf1JzIB$Ky#1I# z=QGQikXZYz2yJBr<6pZFk_DoS<$2;XrSIGdMrbO$-R_L-2Lq$>Xy_z2nqEDlYn>46kW%@of=AwGtDSa#}fWu348T4<~6B-Ax;gs@F${69l@^}jG&!Q zxpGp6-NT8&sQ5Xu9;J0VrIpA6GWI`rZ(ij<3|>1L z>>&-gTU2Y;c;KvQlmnRI<9k&@X>Gr!WH)i;+;RWdfwzE9DyiPfLfgt&n5c*kMVT|& zSi)8|XH-meqoYU|S$3XVLCf`Iryd$G^SOA+UwNASTgFA)|85lu*3mi^;Skr4B7@XrVr?N$yK zRGV=2mOD6>w@wOMx|pT9*_03S*GRU&EKEHrv*+dJ->#nF!;k3Yu0|5vkR}iBo@I1g zhq!!7rMAvk_t3HF>0!B44NB~t?{mLqUu>S7TW+Lvm2d9dOrTB8raCa@+7hF@AnD*z zva>;=BE49>V|O0j)Ee-1#+gm#W+Rj5DvoPG2)C0kw!HrZqVDIbX>Z#hZG-J!U&GyF zHIet!*4l0j{|NHW%I7@x5w@^+5MMM<7!`^quCp|N6S1?qJ2S+ z14u+W6aGWJfm55E9B%6pq>R^RTv(Jn;sC}1!bg{S$r(%nFAMtdy%$0wUD!=uZ>C2> zmDuuchX4ssO8O~-_WT)0cVeV4<>0gM37lhB-94?nP7vo5c9dEs(xtm7;w$mQlAdL?)4<8F`-7<^%8`lSme)s;t-SM^@0Gzn!{*MK?G!`M|A@Smz zzLFtfXMsK6FYCJQa#<{Vj#Y(49DWhTtQhNfxe6hW!}Z&pzlf4WK@Ed>&b}g|Q0)NK za}I?-=2?!CvIgMW0VGGl*%=@is=fUsX3g?ft{n09!w(G0BZ`?g{}(mYWyk;Sh%HtP z@KOQo^nHFqlznRbX(tIaG3VL@w|tD&C*mc42`Y)2|Kh^2mwii4W6LlGB&3u(vn}}X zhh+T|v`@XvoUB3~SEdI9_COX1>Mpz(mZXEJD2T@NsatIm`%E9~X1NO+8mL|-v|;=X zJhe&bfdO`46q^8ZY=c}G>Uz&Y;Y09xkdy8{;rLENll)^$t{9d*3`>{tV^_tt35~W` z|IW`<(+L%z4Pi29&eCw1nz5m2q^NEvg@2_hE$?)mmOgCz)r(oyDeNGXpd%)wWepD9grw)8_w#D?C_8M^$iq6Q(3qtG+x`bizC z<g*>85^ZCmV3)hp$k(t z$j=$y@N>Q2&p!!z@wwgmcYX6qeEIMVe0tIgk^jYVYA)c8T)m;hJai?tw2p5P`Gf!8 zx>d9d%6nx@UDgNEg_(@cOc_AOt%w7!%Xg9PD)+402c&E*RwA!O@Wh=W*G1ewE=aWaK{k@565Xmf!Dy8gYZiYoRdN~w48pIstY|s^lJbJ= z5Sv2DRf4H{nekL6Kr?Ye7dXhdmfCGktJQHZ;s558Zks#PV^o*bU~^+KoJJ_ z=kdw8XZc@Km*Dn9^_2DXpQs<(`i&|FH=CCeVr97??$r zBM_)NRT+dW@tLnBv-(J->q<(t+HFZ)8~wd#R{79!k$E63j`a3$v$OGsO&~EQLn6>o zNFw>JM~rXABE(1Xs3a*3X>sI)oFyDJqU;S2L3T2*Gm!>G&J$}1v$&;MYW9|enr@^! zh{w1s04MU|B!;(T?9|dW(1qq+;kn(VAO(rN#NG=@AQn8{_r;S4G_EyR>+u7eDGn!3h!`!5i{=$Qa$xgpG@wxxD`9CkfKqeHE zp^aNICJ9ItiWa2}Bi`opqVTN20l$oC2+hj3`&rmTHfs=CoaB8jWTe34pkg~x?|;lF zvMjZ>r^!#c30GJbY4uShkOnb`VIr3RZVE-|KOCoD!#0)pC2YnnF@J+`V{>l|JKTTs zfDOfmwP_|X6^P$*7wm*)Q*o5*B+Lw}|78}$oGf0=n`}bgS)gN@g;`dUSIv7m!=ccy ziHO*(ev^8dCz4<;_eCuA$Znl^@fWgVsAw=0rlat<*Wd2zKmd!`Cf${f zs_@Lqi=c$!?f3Of84#&h@JM+&Yj>mhL}&iTF``(>3gp(t2Gd)lqT}jvVO)Z&w4wMV zUmDEtLYglhv=6~F30bR*6oHR*4a+2_%XCTa2cKnW6RK{PBz=yvXQ&r-{pL*3ndveM zEGuv>H!ro~1}ZhbPST+@!&Ni@O~MA9B+jdGp<&YBXt91offO+^3!sK|ZfvJ!(Oq{? zS{(zzvT2>AN6C5uwU8*vj2@zK&nBv zN(Fp&u~z#5*u0hGnH<>C@(*njK9W_Jbw|>b!O4VR3{h(N_Fa9kvO{y*T!j&ld`~3l zbrP4<&mH88w+&4l^`88H zwo8G_^QnUzkNq?6$~jmqs3hBj%G313dLc+Q-@QZQn>&A_q-QvUCGsF5Dj13P7(YDqis)^D?_^4nUfE@3GzhT%IYA)e*Re%dg< z3>n+5yVoNkVc6rXq2w3)s@rvcX#kZQ8WwedMjubxpm7dg`SI6%l`jqlaLMa-l|#cl zfg0}bg~36DQ`{xo!tsVpS&k5HQH|Kk4zGqLUH>&f*HozlNgj>ME-{=2;`JgjiG}J6 zzvi#hh{adlJv_)_mAw@6?f*b-J<-v`yA|!2ysV#BNP$)=_Zpr)+R{vOIuotsrZLo^ z*#XAmt7+#;aDE0jki4m z?AbH?&PMQK+@e4vV*gi%oOpxZ^od}w5{v`0P-JF*DuF%!LEA8ho%Lb#pKw2LO;YVF|6;XV~(*-in3N zhS~$ui~8VBx!YJhJ)#WF$ceslZz2b{f#u||h!w~$Zp$HqxVeag`Q%1{3fsCFB`cvo z*vh4rXv>GmUxEZ_lp3U;LXed_``oJbY_og0>E6rEt@ag_l^tNa$cNS zaA>+lifo^thrSy-Ost3g4ZwpBS8GE*R((sHijSQUK@TuMInBq5X#CHv7D-pcz<_aN zQ}Zint0$XD4r}?Jm6xyCc~3;~;w+8-`TWz1XemI-${cwAkRS)`c z*T+xY8y0f@k{_92HlCR@`fK)-qIRUY)lSdj*hiStItv(U|_oB|DQPBdNUk|Ij z`Z0#u^JgcY=9fT>{wj|2fUaPE;RWoKhc2aM80k1at|WneOrJqMR}WyJ<7iM$Em<_W z(E+&!e_I(rG&srAgponq@|n~i1Y?l?)YeH=8__hviz`7A0 z{T$!-vfp=@lG%p8pQzT@Ds}W{=xUoaw{V{O{tJy7)=S2`TTiF~lL;h0D_5JTrCS+r zsANu$n$D7cAMJTd+n&9nqzrn8-vy&M?XJwKzl(3WNib&-CG`aA0|d_B;H(gvJ5{?> z4)Awy?@1{&vClbSj{S92Cw5GJ+iF07ROb6I&>;-{@I>)4F<6g8OBPg-0Z5YX5%K6H zW{K$xga#{PmiBh@vuVPLp?AX@^Lq-v4h_0;<;k+wxO&WAhZVn*&=jjU<<7L+uIq$) zmpu$O=dfRj<(f4^uA(@h^zxbNIo1FE-n3;M8JPjy={VNoxuFCi+3?Z_yuHGk@bRHH zr>Bl!C24iyvW1!eFYYcHT7D6SOI|UNM7Kx;>5^_jN$OvXID;Hu8HA6zl7+eARUu&! zBqEP(T_e@l(J?=kJ5nrT`%~k*EIF#v(@~m&SgHs~!H2ubbRht1N&vb8HL}z2);2ID z9?!JX2%(Bbt+UMA>ec8QL2k5n>n2{DKd7y{tN*8M`$(R>ncoTo`It8=5U<^bQ{olp z{2cx9>G2om+8L1%6V?1fAv8fdusA*P=sFO{C=b|`o`v=uuvz8 zh}7oOmDSeu@}jrsS?}D-V|Z~MfK}w)-hqys{ck=$ zE3#xKA)@6~BIf<;Akl7^VKjDhsQJSm8WoT2Qk1wPRknp*d@1;F`_<`4xw)bOF&*>? zBq<-hg~O`w?rIRi^kic?*F{HXzT-xaQx7>CWYn_i5A}BJLL54t@M_%MIRW$$5E4Pm z{eew*lL_>)q;c-*mOlUfH_B#-{YHsNoN569S+p4v?`UZ02S<7H_ct*m-X*3Sm_;+G zIg;Y;Ol`XFtg@OSmZ__w0mMs@ciCQX^>?!4>> zOAp<8u8P41E-wmejLr#p&ecTsUam&*o?bwB#&SrwA{-Y)s&h*rGk z_V|Mp`XIH>K{>c$IrW3y3-T+6pF*G_Vtp-o|ZZkRO`8{ZQjg znM`fDYwW)h^E-M)nV?1VF=@AhfB zwrf#hXR>7P@3~7H%Fxl)A`(g>f#Pxdvk1L(-gl#xknKN9Wl&FX4HXOSp`o7+N>40* z$dR(<`z7Z9C+%~>0y(v9!1Df0zj=t~c0t+k!+9twKSV~NlrJ7Vz_qsRAX5e?>>U6( zZH#X5o8>7n+GRGB)+wt?_8oyOLPEkgCU-X7@ohZZSUpc0^8O(5_B8B~?8bQw$r1tU z9!!V?05Ad)`std;*^0U=avBvssSoFP_dq%RwvATbQ9=+OS7-`}qn~x9cq3G-ENqST zfrdFmjhXdFC9bHY<+wI~mTM>q>cpclU%cj4t^%bT2PZA*pf(|)MKNg%DkDa#0=#q- zIs(4-#gaiNFsRuAhI8a>jLah}o)!gaqQ_UI#{Yo<<6;s?Ni4TAu?<2bs@2wPr9RJm z(HcMsgawGo#)>Bz{~KXqRW83OhpGt8s;_Z(kX{9U?M)nVLdF)x(OT1I;Ly)6;FuOV zf2rWX`;#@K9mz5axk|ill~(4qA`TOhp1R@klH4jJ*F#qkss~#{SF956R(XY47-T&p zg(0ZNYWQ;mvxy$Ma!}NH8_Mu>keWRzvjG?PQG~0Nr>}!QQ9QjlCEPwC#Nl_G*G+%U zyQtOcIw|5GVSeY;|HuS@_FA}hJdpK3>}d$gSrZD~J}b#^-8|-3DPZ|dkV}nVst?k> z7orbLE%=JH{?^9v%*2`WCIufbq7TR{n zUBFj&YWwG^S5FdBCDK9rj1&Gb2JzU@@{MO_4V@&K|Iu7^`m%*HjQDfWlG=Q2BYWp} zzBNyZdfuJn%%kh+oYjBp{foP#qNSr@s6Jx93b0Ec_8YHS(jU54QiSn8W&9d;;ec26 zf691*KDs+(LH^+SUKUt}u&ZXx4trv2*uG>3c>zOl(Qky~fv-kyHfHnuvG$2|4)#8Z ze+!OdwcdN62_8Hf#yQk7NI|}wa;~aTnrtx@P0ZwCg#T5jTV?p#o&=N z`vqeS>oC>6Sj~;D5%aUjWvQSfv8( zyo^l)mMGr`fr#CHS(eU6ho@^dg5s)99Lm)(rYBE+?1D@TZ`uO{$M=Jy187|s!*`zz zmW2hvEJr@a0GS?Eaog~Lmr%{mk*I)h-hDdapX%Y`Ph1!5vG6W-8az?lO&D;8g|*3h z>LP~~BuI5O=;=&-*&Zl19p?!(^DVhq7nlV6|DeJcKO)!9-Iv)ij28zE<8*#+%|EMF z0qa<|f}X_2kCiSyP}S{P^~I1G#SWh5wHwXnN>aUvW{ny?G{blC*g&0-JjoCuhw3hq zMCL;KOVE;k0`*wKwdje&?ee~vpH|v#$Fi!o)iVZ99W4myQ&Qp}l6B~pMD3`VcrrQW z5fDq$tUUT@lcplIWH2=j0!V<`7Ma(nw6pBHw@${GQvPJGW5WDa&_hLqKU^#Zh@G*B zU+3q;QMdoO(EeNR8}ItSUlfvU4-fUIMA%OtGTB~%8qf2}hE=-5i($I?xGJ*DJ34ni zYeh}q2%&kH((3-GKLWM)ZSSOUerD#%(;#QxP`9=1@^z{FF>X8i;NgCM0T0KVzr8-SUbFXz&vyQx&ZDYrPcxblub$>uiyY;M zh~s~r9SSpay|+j&R#V$>FsR%g>Z9+yn;tMDVmEaO=uR%JmZ&z zcte}0*uFN&$J6T8Ud#K*C9vB+uvgzym~-TyE(BenYpLCDTR^P{`TSgdNnZ#>$EH8E zvcLNwD3_+EH;^xne4%Kdp%srn>%CuJQ}k?;zi$t-vP#Vao^X|t8nldRJo??#NyUTz zJ7SluMhZ@g z(_Y1qZ!aIE62UCTFz^>EPQ_M={(a^gnJGR%kBVEPq_=PLF0@0m*u*Wc_T*fCAksRB zOUeHdsO|!{*_avb3LE_mP`BzjaW`#vTMsyu{}7w@*cs=XX)?dBqf~>Q?gkAxTK$!!MbI8ixJ5n4$zU z<;A`nmi}NK&58Gh0}(7#6gpCn=$}je?MQHB0yBs9awLAEPie>h9@D;f)u``(5Yc<& z={tw)`go{2ttl&@r18G~ed3ii2i$z(HIQ-8r@FTb=jlc+-!_d-O~6rQzOIxRxxozR_W8 zKHm^;$z3}57#(znvc}h8oUovJeZ73?TF^sdL=88@^)L(xuF1x+Urm=BiyI*$Q zo4)9Bj57dlcMF1Km@)w;S>;|dF=eW@`o+`=>Qy~sm^s{BQQp+OHLXa= zpxq>cN+*I8!{8=!nMTa$7%AYNA9zWZ{Oi~lBut1-uFN0lIv$K9T?xG@k zZZVGAOfoA=s7K@S?@g6IK44&#LaU*x{fzy-T0)GdGEX$3eOwO6{ggCXV~0a@Um&5J z93`@d9_^ZIRCp8ZRWh5jmCn9Z&!A+K8_=EuHdfcxs6GMP4eMHa1sMNJ3}FIV zC!igc6=UP-XdMm2N7bLlkc6JOQ+OP!k);M>z2pr@G$Aa)x%0pbl+jR8IA9gO!@Z-0 zwqQ0zDGlb35vRSlxsGs~43*3!10U`bC*$Pi!A|3_Lod3n6k%k*<31h>_$D32`u@XX z7}AdkZV?FW3!GoV81D~K;VgH+ujmJJnC?b=_#jm6`j{Pe4KZa$@Vj=4xP1=8!O?V8 zSLQ?h1W!{vAI#k^la=t123vOAV8IltY?xqOf&M)^k8BeiHGbFCTD9w`Lzm=+duIb# zI8Wt=PA`T)a%8?Vy08M5(D|Nr+Q=sYI1hn$I5XVVF>vI&Aoy#Xve+iryQZ&sx%2D) zHTOWq@5@`3n*|WgyI8;S2`Fpo7@Wg<4;{AmTUp;IvCBksaJz{5sE6-{fK_n#iLo`U zZ32v~+^uJD?h9ole^Pfe!5%FgrYyg@8;?Z+A0w@pW>g&iL3N5&B_bC6D5rI~XbNTE zJ#ncMPzxWo_pT%@`+b^sfs%+&b*|e%y&?$CBc%bso`5EJalsqdzWXPTFA<7qov)> zvhTGm{|o(CjQdlSmqv<}SJ_=++%4+Mgb zE%HT`_YJQ!Oyo2{TR11E67Pa1_MxQ5wvuq4GS;PCm@u>=oZIi)VYk23PD!Qub8kKE zV}8_pphH+b`HWBu;W+zGw9o?Ld1?r-w;lNhn4ctkK@O?(<|~%XhvH90vMPa3^E@zraFl zd>T3KW(a#cI=1AHe}pW(ZTECfH%>IR!7*j)5N323FFIw#>Xv4ox~9kWen>$VVQt&* zTvqasB-s7e;+5mRmsZ=)mbW2Qf4jT`g{pjBZJ)YN%R31uH=ruk?dGjLB6(Qa-}t!I z+L-*n_CmZ@g&o(@-`dPHIuaQW;K3}`#jO-K-n8d`f7f~-KkYu=3>r!Rxok#%U3=ZZ zbP`CQV3eZgp(A(7=iAx$ICXu2K)$NSvq_#Xd~V+S%H&579Ml0BOQ|xzM6hc~pcgij z`>#F!knS4?)v;dS4M>f`m{@rR>ZJ{xIH;2+29d;OnA+{pF<1!;{f3?qj$Qki2yq@B zw6Xs0x7mK_cuj*og!T(b_SCn5nvsIfUm!F@vJ0;}&Z;apG)~pXONs)12=8M(tpVE~ zw_ZS$FGM>p_mB{DZA;cQQCrO>`c+732D+vF^0M;IY>9$Hv=$6wmz7oU-bX zWkpfx{TUb4FY&vz4T**372ldZ#P?*+XJoTwJ+L+ZcF)I8uUlpYa;h7-=W6W*C{$3r zyDh3`s1O`JuZePO&Du_}xK9uzpHN0|PWG9X&$V06lQgfr8&=(mGDPr`@Ty5F7tGH@ zL_yRVowMWa57Llrf~I?43lhfCM@TC_!i6Nsl5b0&;96iQPHT8#Dhj?zNL_UQWeMcu zz8q6)-7xL6`420AlsIi3|NX7g)lEYd-OO8G0+E?mr1~EVOr}r1UG=uPKlyKiZ-;uS zbnVJ7%^Tb(W(TOx;&Wq!hXje|)eA7ZVKLj3F$T)vgSMGp;g8x`KPX%ly;i38fl@}Dzl`Md8 z^lrK^eph9#GLBbs27(rY){_d%bJQ`7XAFrfylc>k*nD2wYXuBN+>Dw8q~|Vd>6-7{ zk8jz4SwYNi=W4~dGTSPDP?=frMgN_y;Ms(ILr`U6HC9*IODfW^2OaZB0QdamvmCpXb0rz;v-@=qDhgvVvwuw`ub zg?^y2kLAZA`)WVDvWBrIGjIIa&k#B_R5^!L9wPUL%iLVVPlg8Kn&~je10k6^SFfABlK&N`30Yd z)J(cW!~68x*GZIaL*4t*Tf6^=+@(ZyfK5~!CHY7lA-=2s8enD*0iDf+U+CiOdRVKu zjXEc5#-eCdF16@f7!Uk|xb+Q*JOyNIO=j>t?KO}H1&B)!8CL#3q^00P!e+LW4{Msn zquhKB9DS!d;j~J)c6tDa_z!S+4PU+4r2UD;Q+UAs=sGraALV$dai+e01wc3ul}r;y zn&Ym-Tu-D|`uoTjs51gmgOARm1v~ z19G7@QSWYUDtRL2KR#*7e+|&4*&}Xl^G0vFk5wW$LdzZRE)9wb20LL&ZnXpt&tR~a2x@YW45}&G<=Q6uwMG@a zq}syD;H!p-^%n=*ndCwQ5zGdOI+&`KP?6foztjyE=A&+0Kn0#I`&PceMTL|J+`g6R zzIf*zO*#jilD=@6>A#^Y%uCqszD-q%)z;A81x^PZ_fD$jNk!>~&6(tk0niBjgD`u0 zF|E0$bN5Y$myS)$Z}5JAhd!U)7h5`G5L2^Db@-zE-)y~b3JP623T%2~FuSw6&NBDz z!=iaWKoM6xN^vUpr{kFdIJ*F2JZVV#d%Or6$hy?epMX>7W=Wq{wd%&xIW!FZ-?~hY z04deHaw2sp9Jg>)(%jc-F54{iNj zD<2A-YmlH1OYIG?qN0|HoM~0?N9Fe46vC&t2q`IOD>9I%n(n*250*`Ln4H~HcD0cp zsAck3A>MUg+hDg3WOK0ldA8Am@`?}dBq6`$F@}VwQ)96zEi2?C{a0|-dth0JN>#VJ z+UGq}>S-mZwAx|Uv~ypmpKTo?5%d}DikQ@#_d8lBsg;FpS>zuqOM#bD_1RtxnWqtE zv>V$nzeed3H-j(CUfWUQxPzRn!M2&V99jSM!Q8ej1IyKA5P=JGTLxLOn z{?Fi2=XmH@K?tP?Sxuzhfs3wG={RRU*;?k^I@u`+6BG_xb7Eqf-Riung52=t=Q7_y zaZOI_PYq70$_kHv6>xCuL~dj55G|$A>ncuLn;WHZh9sK#X2;sd)Yq_B8Cpv_ z=J-M;V@)VaNWj4t{za~`GKhhMctsIm?-LmRr&1fA4~m$bb6T^DPg1#t>EZ zkN77q&{k;BX+-(Fod`!`T1K%f87{jK|F zY$of;NmtKJ_djslb;<(M&|vwD$&;l>)KWk>>GvNpv8UPg0Cpxjxe4;U92f9g4{e+> zOhbhGz3?yxL`lE^Lk8UqT(yqdelsf8!6=jO4B_c~K|5|vpk@L7^;M9Q7};U9E$PsB zlR&?B;CT+*4j#qe$-P%kAjfD#MK?*_DrY~kM36f92E<1aRy(BQ?EKy3q
    s6!u3 z`<%oVcwVB*Bd~vmHlA?qtdKd{%$^#FH3s#|jJrNu+bVLwvfXdi$wTpY@xyH$I;jF* zK#Vph{-!UigQ&WAGkBg3M2d24$?VmtOjORg#E06I66>1Sx*~zanB)bx%{{Xt8@le7 zuSK0Cm{jQ^lLB89YXj@6l_GJWTrV@=zY0r`k|;OQ(yB%r>YC{E#Ms%U0UYxZ{HfT7 z%b4o&zUAY-ohIiR#ACgbGu_ODxzN@!;~B2!n;UsEC{%kjxtx1qc-dj)VC>cpz-Lw- z+RXy}Z9}s)B0j4BhL;YZ zzBp6!Y@fa{fN;I;r$wEwX4TxKKP}@Sf*|+se^@irREX8-zbmUc;P7D8H4vTm$|bC0 z#+w=RzRtvrx-~xq@GAOY~9N(BbU#!ar5$!3birKaphc61|(Tk1)szOr%U=K&i z)^F77$?H@z^3QFTqrgSLvR2Q`Swl*fb68ghN0Y`b)4lTLCf}F%JfOeR?-u8?F6Fhe zsLwBHPdYLx-_owTv@DELD)RScVkEtM&@)O*v+skGS&A9Fy;nVjF8tonJ~yGl-n+mq zDCDPU5GVXa!%#!vFGN67Ge%R7qNESlZ;$X^7t!7GU9B#&g^;*72!wa8sFi)#gS>ah z5YP+hsIzETEM=yX8qcbnnWLQVaSO#mh|3F(>H3y4B&VXW3x2m_^)7XgBPs4<3y-eI z$A~%z())-KHE$7G4Dhh$+|KNk@FCDC9G^WDq|x^e=mZD}`UDsSW45e8hc z&a^33*G*aL<({D=GYexW)ajcF?$&e(uw+jjXd*&V50wWY^5?6T+1?z~(c=gINvmy{ zJR=(M8GbD4B;W{LT&QJCNqM~7H}p9xHu-N#D2v>iKjg_pt^V&nxO+Q}Cn^$+=W147 zx0D3T$^ZxTjx({3PkpcndMYj-6xu*~`y`yJbt_!#v@hGgJ?hLDP3i*~{wBv$=|Z*6 zKb5DM-9Ne#-!Q_A;qs#ctc)megy+pH!~-4PQOa z74UG=+h4Ysncgs`DjDL{_rQj=am}z_A)}-MV!s>fTb4z3V}7doTcW(bR>@mboN%5u5=yPW>N-8QV9fW~`N{^j-?G!Xm zu!!&%#VomH$^*Ik>(T0Hl)>p9od*u1@eK7IrMb9zrhio4s$2H)vM2vLoyEU_EOffo zrQJB2Jw$wMjq1A*pCRuIRXzCx1XD>*GEQ&m#!nvSWlhw_L6Vu5C;hM&=|-D{T80OG zE{yvoz@uFdSl3R--j%=7&niGwF*FsAb4~Ai?aHdB9LF1@))e+5Bks!wvLIXxw#S*%TDaPe$?!2?ad{(b?aK` zb~)pD&C%D>@OP5ysNv03lAo{VrFXKcN&@KN)y$0QEkUD$UrdMA5)QjKU{{k~nqQ
    ro^vUAHhLUAyNmfk6%>t99*FN%4|S86f6$QZtidDY*dWY%quYp z+M<5c?;~aby;UkCWrX0>+bY47KR*@qR+3F|ZF}_KMp660*7i?>$FkMJngi#ij=UZl4I@Tl;fA_=jCf{59&hl@92EL-Mn z1)`_PLSS2>aEukd2y!A1M zV`YAltUkj4ln#f71Cjrb%(^HW~wOoD-_xk@09-|B-;m-igc`;5c*ZRUl-FHKftCSD20GV zk=i=G!yRW`riAJA;Ais6$dz2Alk&Jp9<$A~7O4MvmPK2(dYoO`9%FMHUFd7-Z)jg5 zf#6EM6mtn(K@x`z13%EZlOj9-t>!zl1G@Ax<{e+;!kPBHs#Cybb9gq@CYGin( zZ|OjqnfgTf(FyEL)?w~+$i{oumoB|$x^&-rnZlwarIFk_FP_3Z22hCbIQSw4uWKyq z_6TN8{~JIH-6^2vGW@Vk&~}QDt!BkWKiy~0pi-G%ZCMBpDz3XGq10udH?~GI!s_(d z85h6ddun0RI3cW@jr&dK@R~8UxzW4%?4QP!^{-Du#b``~yYzb2#OW6H2LJl_09*OuBx9@U4wn+{-J|Fgwg2MD@4BLxu#FD zU0np$^gZB}(|#10UrsOifb`VXlx*IW(|zywvlB>di@0$#_^2axvY8$l(jCI^HJ6g> z_i;0X+j8Od*r($G%4q({Ohf~h*Fp|lXZkhIec$%)8#ftj$*jP=MAsde@oK33<=?v= zzbl%G%o*;NE4|9edpA8r0}F2;Cw ztF`QW2DPs{W~21&co;E(zF+XvlR6ZvdsQ4owMaoubrN z&&u?%ob`7f;YYc6R$@sS_lS}PXP(&$o%9y@l~mN31@H$|jTz#r)equ6lKSP>|J#wD z*;gTJ9^-2N^ea3o^cIoq$t_x09Y>Tx)hiVmgeyT&4G=U8!o2UYY3e3uV#&4%iQ@C? z8uN_CE1$feTqN44Jzl0FhwZ~qG0<_8 zO|WoSPo=~BZ~#Vb!9kjoy&J(|dT;7!sY3MqT7g@nE+P^RKXj_pI3Y$rlF+?E>T9pd zeJaNWM_wJRSZ`3grCd`@>fjO6>F}(c+5N~suR=QdlN=(_*|kOAo*7m>^A(%zwDIl{ z8Fy&8_2&5!{)e^hUsUyD3kM!=V^%30gDO6d_9m5*IH-t z)NmT(#gm2J$xSML(IlnP7k1SMoMELFfP$H448vpXciiB3Z?V8YiH3B)$Vm$m$nG)I ztL%pAoqhkiY~V%kU)%YwuVL3f51gWbnpK2VM+^~?bDd=IN!c4bL6lwJk9t#v$(ArT zE{Jx>cSreULrmrGYSPVr4@T*meawu~2y)7L(##q&GC~k{h9-zbm$&(K+_Bly*fK93 zE|O!8v7J~O_`42e0HfY@X?3(ku^jXv14JyS_+EY3g0 zp&DvN@u2R8k-21R7);*vd}+|a?5aY_*7YU-_sfM;H~%B`^}o=w&C88d$;XMoA8a6Q zuCHGeHl#>{Zu~BvQqN4Dovi(QT+Jyxh`n+bZ6ki{PfV(9JTqW(Q8?>a!p6DPr*>XF zt%&9p%>&As*BlY;#Lv!Y5^1C#k|)90MrI~>e2yf=N`HreRql#H1uTgi)m>W-M5F7+3AUwAqh-JXF8J_(akonnGoKreus684_(J|X^U|aL zOi@`%($aJg5@6-&Gf-$xABBI|vJs-kApKnf9eZ|wNl~>a58skT)c`rd8{zZKc`nMV zC*?zEHQQ0`yP^I$?9h%pM;fZ{CkIA7?({O-*R1WzimK{I3L0`O@1QsYgk@CwkeynC z^#2HU6ELl8Ag=W&mJu40gdVg!Jw-XW^F4kSHZYV?rkwZ1tW2`Tdx8#Do#eXEqO?kw zezsAmAJPX*9qW-fL27{2%cgk_cZqvn*hFb!*0xYtk(!8S`D-zoOtb9WH zq}%e_HQ|uy=ao$3c%5|4g=bqW`-Q5_nS_s zKV9HcPa2vs{g2!^!z+c)^eHcLkW4rfyhw1;7j7`^nGCQP&i)czq9y)x&9n1%b!#>!9ylSnHY=7>?{c|$z- zeMJ26&KVhMbXHND``+E|Wj8UcKSD@7?`&!C;|Izel=x@3!e(tnI2LtAriGI~dc#XR zfjBFec7AoiQ)iMRm0#6A{kLyu=qdc6WmpX_v6h0DON zKH1}SHlCUEUUW91#8$8N2vwMJ5{~iOEGxY_^LDw}$ls#-lt;+7X8hmb>iVrm1^mB{ z{0Ok^6Yz$5^4+`)qj~sRbHB|E>q@;evuUN4q%!<*`4vBMRF;lOaExSrHxF!#xszx3 zSkDlV>dJw=+DjHx0Gmg%Oui4Q4~w^bLvU5_smy{APTob0K?)$Q;vFaQ+DwFefRG>| zgR!1?OwEh3ES79B3ila;}s12PG-M~_vU{Tk4fv{^ECnW^Eco@GR&x6q*2MuAuRAoC93@MtAJ z4QpEnuN*Zw`VqK6S!*6Q80p(CySIt{azDPP^x^J3Wk+P7uD+dMIA-Uc`tiH#!-hBX+$aE7 znGNCZ#1RbekeowY73Spzy22w12cPi4x>2dLCIOUSWejOE5wCM(oCM_E#z^7$ZbM#@ z1Vg21fKkyS-OkNz; zYR}qq2a5+iJ)yrirLFab-cJmz0yS{MFMj!&9zN~BCq#~c%F=aycO6veg>XWwKd*U` z0lTlikC2-BJ4){i$6~8zM7JgH;YxClR30jsj2cN>V!T2_5wh74n?6;C6{7!Bs z!GhYGKSV+Ugci$E@f=-dn!8Y~*oNsCHMT(!9&`j58vNBCrnbfH-B&-9M4zsgKzB#; zk?%^Y8|}tKC97xa{cexNm6o2URZWhNw)bg3CX?j~cV&dwlk6(WbDP4s-$%Bc{C7Ow z%I?;R_38W)j5o>S{S{4Km!A>p_o$?23wedp=Cet=Mrf*Cv$k(Z){+G_;+aKUeF!k7 z*vY8QSoaxXcte#2I33bFXN}XBEQ*|2i!`knUA_QJZws2^HAA@Xo#u^?tZW>snWMze z$75jbTASz>lM-h)scFi}t{jGz0);DQ>tcHt{%I(z$PVeblm<%FhU(M#5p}s$`Yv9Y zu%s_Z^%f9}U^*7k>}smQW}-YPW>ThRAOuyk!vg;Gs)?v}R|AVELa?S`4i>aj ze1K*m{Hyfx=dWptBrf)!EP<-bwPAC6e8f5>=NEiNra7 zxf~P2A=ak)OsfEOaH%Q_=Tl%I=oila#svZnB`Ik4of`NI&V`{ic9WYZ;6efrm3d?% zzb;#@L2C$Hl7B1nD1+|;f752Rz}4n9m*vEcw9-JJk`fqe#rqg~^SneW8Z0|4>%cXTs7>0ddd(Nk6y@>=N!)|lb)&{lbJi!)mfH6<6N z{nc4pd(A?>tkk;jO3#>VW^1tNJHBpqaNZ&in00UxJr?@oue%GSCRGsU3d!= zf9QCom<{0L+dDBgn^W-_lHqDS=sI1%_>1;%o2UT4xB39Mh9f~K(P3d#PfZdbl%{|1 zhS#Waf3&bApJRbE9}aqkiFQ*qtM1>ujYRR2zW83h%Se5o;duXiy9aG2(0<0JotVGLE0@v-eZ2mlH(x=l)QfVuW)p%dFyfE zZI>7s)$aVkkIg`8#LLR)e%<_nr@`M)uTz*2&wTkcs1(k=jWQUNced_NrjpqwBG1(Sh+eaFqnAi9yrpJYE_|xt$-zsc%CI-sUoqOr12ACCI5`61p^EE;hZF`( z`r7Iph0UHjwInG4M|z0rfx?U_G9hZ#lGRJqt%k*@bRNfgG+FJxDS@DYskqe|7&#&u zoq@IYXq6ms(j&0eovaU?Pfx|G;bnVgGx3M#RT$i7Kd*r|A{$g${^fVLW_V+WqrA2X zb3`daR;jlQ3j?o>C9EkK=%r%XkwjoC<|Ngr!0nv}~dTofkNC1F{1X zmhS4Ftzx#c3Jo&CS~x$KcY51%zZio0j|~#9`^Y5P+|6#c%;!NgekkaWjij63?R9%{i`C^v{RknGOGr{ocDUq0scEHy`0##8 zBapQ`Elk5RS-QC`Q%NoUEk!$JjPvb2AoG2|4TL4Lw3RWl{4M5MQ~0v7nJuHeyPM>} zmuX9)^6tD`?yZtR{D&9CQwAhZ;yY3p^S6feSK*kX-((L6VskyIx~1-gFTQarfC0Bn zQ?gBXz{yw@^m^DQ>)aspiB!D%^yF#~tp+pxRq8@cf=Tyus`TcdD+EkGJdQ<`K{{?^ zyO18NzWV=O0P?;7fsnl$IL7CglS!m7cjoe4KyxJ0$!|fm8nFwsn3!EhAx=_j8M#4=3>E zWbG(5(c)I(NEY9P6UoKO*N!cL_Y@K^pc9hPa9aXojbflQw|Vlo4rS%Yy!;`?$I0?B z&3$I=OF!_NxANway!}8W=;sOW(cKr8up4t1>fk&*s6?P9`@d|AY#e}@ie{lt0}NE= zFObxp%-__(fp#qg`BgN(48 zRU5k2k=%QK^i$6T4ZSROiK!uRTAPWw=5J|JRF7x9=$r311RQBUUDi}37lpXh!3dli?k4Af78WWh*`%tfC9v`hYRt3qS#O1MOGw}352*B;()->O?{ ze%zTkB(OYc-lgL736wSw(lVfwR|t^yOGCCzmOZe3(ZOB?Tx$6|B#zi?1Z`7aYPb{- z@8}-D41*7j3af#SuAVROAc~Qd=R1>8S4QDQu&_3oV?jQ z`J#Vb6pJ^4Aho~!{T3ioA zo-)RSWyj?_=7$DTy?uPnZC=-(GsbMP1pd%T@H`YV<}1KPrJw!9cy*TkJ~Ac0yZgo> zbSFEM@{7-reS7{hVOr*3B)u!)d|H~!oE6~UL1(n%;gg-Ya>T%{?H?@TYN^g{T?xLd zqfI4*R^BPaCz(A3ndkwa+<))8K+0AzzYwfMKOZF0WAZCY`?aNQhzFA|^J$(P&D#RI zlcFp;} zeM*kR?DQfP42Nq*62M|vS5IZ4UdJEUOHfx@l|yOrbSSTfoWH&r9Z}(ysI%PzBB_b1 z){$sSr&I6b$PkgGhT(t{!m66*tP_fFh^Y0k9Dtt?)m$Um#+s`O8MdkW;2UXaz)5@tG^hX25 zv*@x*xf%?eZGh+fJh98MB!ygT9;p980(AL^7;9U4ejtBoI3+L{?h>5DeG;72=;88x zN?tpxxi^QaJA{-;6?X&!|GoFlRCoZC;BcjS<&XVQkLz`5^Ez|P>(+}v)Z!Pop9%&e zHb+73j)3ABrZvC^!S9`Fi;4R-^LX`gTG)t1g#k2VIZ!=59^)XXtLLI;nQUgF4gpst z*x~Y#@n$!cvR!;9MoOjS*!zN^4fhIVI$!q{EE!c^+lb351?nPxFxe8>2yxhAY3Xd< zb-B~Gj@TM*1U4RTzrylES(9A;rEfIacUK1RPe&PG2WDnV}r_8^=k zTJJP9CeyTz7kqh3R)Y%9G@7~Mrz`9&eER^Alflfgm5Xs#W9c>M+o@f}WgO9$^wVuq zkVRa#s8m63sCWQ9m&Qr{^N-^djTv2wyV2>)mo8sBu0Cl$=Q>+ZKNod{g`a@`*%mZp zdpjaDJzcS9_rK*Jl8?AmhWrTl{dEBFD+VLkQf4%%;@Sq6FikI$QUg-4McWu1V6{TPv0DEwSC3!fwwN*IUrc3ph09`M}h3WD?qnDw)u)d4H zS5%s%cKa}ipiuL1tmr=ac+-*EEHd#DZ$xbqsn@YYS~j2wkRDzKNP}t90KbY#T>HAo zB+BT|-HX1Kg=H+iep34FR0qkq{f5YISj%96bZl@@q+h(2u3h%u!&R$F%Az4LiwP3C zKUOw*ugr|}NNe5{b3{rz3P^j>j<6KTWeQR_UM9{0s|keGLv!naQWABkZCQzF^Xk#M z3YXVxAOG^RE3fMNug2?IQ%D@-CE`a%x-(*A%0-SF+d3#R=iG?xb=Ny(FFUy4qBDV% zPBUqT|0AA%pQi=VgvzVZJGr4`lEAq4j#m9nmEvVWn0aSQ7!`%l&LCy-8X|m{Dbw;J z;b7+T5blAdJ_4=Rsi|LZ4TUq4Cp}m>QtG^R@^1F!mB6)T8sDB3Tmy{h!>l2WUh=EN zzuNI>ardxcIe1>luWqCfM<7{Gx zqXn~nch!{>NhC!jk&AZnsrPawqo*rhj}S0d3cqXK8CRWjc)jUc;95BVho^y!W>WWs z*xxa}i)Pffgbk+I@2o%Ue)!%X(N?0<+qm7d;vZI$$hSJR-DY>q0Qx8XTWO^`i)=M0 zJ`M^ngk-J|PvQdbQXo{1B*R0N%rvA5nl?7f@q-h2y8GRIx?XxS$+h0Pe<%;Xl9+7z z0vR=Jhy0k?hFqzv$OF88G`4K#ydsvGtTYn7Y$;wk_|w z2FPCsLcI|`aBQB|elaVuXsZ0lSPJ!BH^wBFhzoDCCQ% z6_FHzneShZ#bQ(Ivt<@jKVBcen8j@A%x{yM%;a|59mO4qsH4FPF16LStP5gU?6PLZ7+OJ=z% zX8uqHm(!rqAMYducUD`327zPdR&W&Gm8bcOBZxDpyPB@ySU7 z_Lx`$VcRtVLWB5KO0Ovg(HI~B$}F1HftB{vP)AWQgM`$&iWk@G^|wkh7vcngeTWUu zNtkiq#*|$c2(|u?l~&0_hQc=th%KjQj)>}z+>)el&?#lm&9pBy8m_o_4iQZyP`cc8leVt^t(egZpQn3yD!GN56NlA4l>&y7dL+?%Sx~+Yf zcjmeiXY|#+dm}So4{fEJh4j_zl^+@47=@p|YrMNQ~> zf)D6JhD7i(+L#Esi|g&r_&*;iUUrPtA$mYG&RJLHy;N?{QE2NyS>rIyv2D4Bfz&Lr zp|%08=HF8uW)8OX(w~Q$CadxUkESWOY;rZ9kQKS0|IF1NVyVuTCfAjyMe>7= zU8+|guK|^N^QldJ5l0Y+Gq_V8oJ}=C{JHL_knnoP<1h zBhfIM6Ox2f=u3M^FDO#mq0tlOA@h}bM=8_Ldq8A?OCqpIJWh?2(6Wu?P^$d|1=E0T9xlyDE-Z$eDiFjXK}@Kqmde1oup}0CW^(_ zuuMn6MzM*rrI~x3D^te{`3@!ylz;yksDy!#wsfR+X9r(*X_l;Aeu#TEfXX}oAz3~y zLi#!6Z^7&nrJ~4+D?ON7Duqn4)#(?-)^mxTnmakX)vWQ_RiZ*Q$N3(w;iEIi3~8yr ziwSDLMX(A%Gy4g)0Rc4PkIw69j6c1xMlLlY>LY}0m|0N6W-P9Fa6buFL6CN>YD*p z*XZMthm4JZ`koJ5%koCnllTP~|6A09e|3P{^XPRjhI5+W+3=v{U>Z-VQF0g4h|Me~ zb4CaBvb9?%f1!U`2KtDyr}=7Z^(UQ^+#aktYXs`&Kc*#L2WalxcaJ`exw%ajH$f_Mq)k{b^5*mItf2&>8CPyKjb$uF1|~$mXhC#HKz~8%ecY@piD$mr z+~30S^4Gs++?9#TRlVo_EEODYnBc1DT9+{XY#js^)53Ye7cq}Tf=%=o-@sT6K%2u@ zMCMKWkk78InE30Iw{(REjrudiMv)mA{-toWRXo4f1YwuDBX989{nG7^we+$(=!@Ij zMrdn+@^ib1XkLlhl3JhCh}U5#7(yda7?UF&+v$EjrZq5jg{EH**JlqX9D3> z+&3)M%DAzKV&>`DBRP9{^l53HQNav!i*T8x&HDtAr45YY4C!6rkTlG6uby<&ifQ8_COE*=k?(q2F7RdW$`sH zf89kKU-j=aP;y2igO(N|hq#V_hz?oPoHj`@UIoT21tzF*&yDrPrG?$WpRZuLZxgyp zf7cL&#``o|aHwA4VL|Ao^LCUfTTD4I-6urd2W6rbX_n;l2}WMA^vgk4HPQ<4!js3{ z@6E>#FEUH!7K0MX~ z*MGOZf5-(iYSYRsW^fM#lM4!`?1SkI$-LUaS!eH5jS!?v)KANoL2ndUSZ125kMi8b ztRr##I0cxnodxhTD?N2c6#V!l>LAE^zdh=OT!zw8I=Lr$N%;L)9+^uLzrpdU2`PfNkW75#C%SS?PI3CvZuAftxJ&20T;U+Qfu&;Z)7t z&G$xGH<&uu^g{wN`^5QZ^Nlvwr-vKjSZ$&E_1`bg9h|DGc-2j+Ne~M6WY!XnoBgZF zR6v03^HNC59bj&jp00w4#|DK^*EklVnDCVtX6@}X6u zUlsVE@K|~0Z)$`e-zxbn$x&(UP2bq2MrbRu$!0*Tmp0)YS2fdr3yTxdvKg^HS%X1k zrOjkCn~;jdg$WczhSiD)w&~-wmT4k{cL6SM2mYI&tShca>c_36&mZ$HeFgwCVt-4^ zqU7(4sMe9u6*)DkR=L%!I)M%2c6W|r3oNnU&&O+*hZ?P?s6pE#=oj0pE*HE1yXC+t zqE^`|+tkqR?b{4-NSQJ{)qDnGB7<&gfrh>6D7fwYt))7dQ6I6lU@&7Wc*!?(I~KQ+ z?;Z2q++>5=b&XSPch+%eBbfZ(?xb%M6lE_u5fjvLm3|CB1N56_oENw5oB=I`>-G0z zI{Apv<>u<(GMU}%UsSMT65|0#OE13Ouv^iZk-^IwWXzBLe7I}TMZT*;)HZ}@xayAV zx#_A%OD>(rF?+6gIsEfj$cQFt^5c086-NB0O|z^hkN<&c=d!f`5qcs;`3kptYrC!R zzyNGL86Dc>d$0JlL;GtwociC(u4hEbNUOYmV_xfF(CJQD32hw1Q0s>+pO<)lZ(bwu zO1)|?!AT!6h-1$Jn>L3z&U3|O?#uRrh13MlolKNx5KA)(rk5OK)cDyXa2nHP-F&jO z*_p*!n?xSWW#=YU9Oyesv!$#EE`UYJ*OZJH3*KtWn2Td4q?hG|VS%J`!?i-SsLJp7 z9KDUjF+=Yaab8aS(n2cDjK>9pXVx&FlVKozC+q6)NHXh-IF$f8hx5kaD2*qKsJi@b>IXp6lZj}#5PlD#{gn)e@DYj{&932FO-zt}yW z4X!d{Nfas@pkNeGF5Kz*kmYW|%Kn$C|DY7Js$Hk#IytjQ8H+HoK2a9IIJPEo}&{>EouYgU%6rc_{N zSI0Wd8@qb^ua4e$Ycuwd&q$o-*VjuuUEC|hUZ|9AG8$AQHPz9eD$j`Hfexm`Yn75b zR!B9+$oKZe;JnDu|8>qOQrk5D^j_NByGA$cBgaEFm;NkWa#FYY>ie<$JIB0fhl9tg z>J#b?a((6)X(!LX7W!ej8uw30Z--%BzLK!W9bY4}^y zR-J@e3LNTW(}11Jyo+#Ly}IM54%-5zyh^+v?6_*BD~4%o%)Zj~yB918)aGD6-dRGH zGy|FXI~j5-D_OXm(J0>QWe+QT_N;D;*EwL&UG%vs^6-2fX2Az=UWB44<{tRqj^wNYCZuE zrtHd;MYRyB%vAME85Y(3k9B@95q4lMAy!*4d3ffcOy(YdJ2febx5;b{6hccL3RpnT zEPz5v&-PH~mouS;paIdfp3mx2kvK?&m5Rj@)2${sg7{6M-&b;F<_L|AjL1vYf`DKY zUiGH$DCqA$x`KcrU1KR5J)6t;U-{I0dIt&{V~i^Af3Lj`&!YWd>tp)U*|Oz=F53H} zSx)KR=**v*95p>jJ;U!EW$|C-Q{veZ*qsISn@e6}sF+UC*dYF+=7aG_CumzG=%jxi zDdGc2a_*Ho+QBj981Gf0)sjt9TQM3?nnb3jwn|e~(@0#Hm9NftYb}=Lki&asQhT0{ zmfH&9=jO7?`SwPJC7JAFyZ!Vir%b*nnzmMS2h?@~UU49097$y3aFq&ObWEF8NsU{t~SvGpBs zw?3x>=AN|jHl^@(b(B4}IJ+PBhtE8J;B)#<`M6`7*X4;1Z&_bwCS*7FXLE1qcX=67 zI2-U0>pEssG4A2wKZ>VV)_LFQE<{=8)vtUGsyslYq6c*yAkHL{Ffl2Z) z@(ynsxy-&)$=i%nmrE4%@dud!r&qfDM^n#DdX@DqT&v~+NZB+tl9iUEj2X?)q{*ZM*sv+{2+gnD_12i@mzW zH5JR-5javS4+^4Bh!=>T^Y?X zRqUuUd`UGou4N=HX&##WZ*jb$rRTr^icKNz;BI7exl-vd7%UoOs)`Nc-U8;QvF*Ee zIpXN!U;@Ihf87hrHmojzn;#I`ONJM-I?xN1aHF*aVK=w?Qc_b43|inaxL{?D;k2fH zo-Mobdq*g@Q!tAc8)QC2TA}pY#Hx}Qj5L0&kmjK5*A_OKg93JeDJ9I!D5zON92?Lh z&%Ko9ij%2ZVm403kFPEi*X|-*pnYhm@oTppPi}m{4T=}UOh~k8+A1tX3A`iFO;hle z|F^w|&wJ>-xZlv-XPg+7`LMRR?f945DAv8Or&eKh6^;+rp~3+-?HcF!C-Zjs!ZPiv4LluEiR;R`!Q5VQZO3;)*o^Ti|A6%5vF5AA&sbnwsM(AsOP-nWD zuI=m|P>4Lgjuk*c2UA}9Br{<1Q$YK79@2;sa5Jk0_DLQ#sN<4EkEVF=KxhWr3Kj|1 zu%9R6nu5&8Xpt>wy{)){P?9E(B6;b)7Zaw;bvt8c76$6)v)dKh-{$>c9m9s&Xy*Oc z$F`kqmZ=sGs=0wff>c>s#ML~(G?;R}K1VfZ@9(A7;!}eEt&*$q48iD_I2t?!LDUS86r?2B_ ze*J&gjCF8+4?p=$aVcnj{o#X9=Hx!ub*dd}n$t_Z8jbZ2K2jb15( z^yQB1JV}m=?11~@ZYbj?O8{Xn%Mn!>_mQ83Hg1OFDm2F(A|iJNhR{(1(~v-XaN|>v z?3dl-rPE<$Z{_9C`y0^$oL^-^xl2c|nO_4f3lSygMst5VUS(jetr_!f%SlVUB({Ia z&heb#y!n4G!0{sDYBT=j({Cg!YGR>2T)xD}|9V3hf=*tt3xafu&5r5{j;jZ9W{~?$ z`r6L^q6281IV#_P!WhbQG7hA4BJqmUx&(dKv5t=1RCIbsf9rIrun~B9ou*kxxIz&U zxW;8u9-3}n_vdTJefGlHATr1$sAyXe>pfD*oAvoL{DC+-&Amd-%V+d>xKE=u8_$lX zy`?YH(nCnV_Lwsefg4r_+#+RCW7H(q8=^JN8-F}TZkJj=q<`|*96jlIUfBsfjC*^& zXtO-qvebSZRnIbU1Ah;$O$TiX47avg1Un-N%qSm8(#~72^WE>Yy4>?|$|L`bx~wW-Kw}1*+mV)YD9%rOWaLR{#!S_NoZrfzo!4X->9{~EF@Ni!7#`q zZ$_@74CMxCvhxpEBL3?$wv+vE@`QRG!{!;e9e~%^NZX<4Zu$<4kxQ9s_!Mh7*GaFzvRd5cBc-yjPPV!p&-G_vTq{ zwr^6XZJDmFYyOjs)2fHHf|-$ogN=dsh=>&YKkTt#g6QU}yUZLI6sC)U4wz{aG~{}F zBZ-F4Deoc{hAv-#8auFu;8DkaKmS-?c10Jx7%RWEvcrAwT35Mp#UqhZVdk4>Iu^y_ z)^8mttB4vNkZ!hu=l6LwpZiMDTg&O?Gw|nmjr1Z6;R>_+iyX-@~gjcxSus?>tzSyI+ zeYLKRdKQgcb1|!ljWIFW_r~4+K}*}D(<6(0)tjTS0@wO1UKe{@B}Vjgfkqz@2d^Hh zB7IRj%IKnCUhBxfA9i8;c$kwlca<_!rg9DLb+l(#B_xK=EF$&W-;!a^nty^rQUxtOq1@tPN_o(U8Vy~ z*s(fy2W3Op@O+xxkv_6*_&-Mrb5S0#J(#Y&J%;p408NkzGe9LbZ^P^iNNjjAekT5% z^@VK*&i~0a7S~x$meiQVMY^D8d>{Xf*5Ba>7RA#(QZ+D#nfh&RetgJQMq=-*X5lN4 zxdsAOkP6tBO(+(vL>8a^Ti@7J{*{s>gTdI2MtPqqx(B8ug(c@l{gIHO#8AaKx|I7y zuZXK!k{Xr!?_eKJFNr;DgcieB=$VR^0ZB(F?Y*cM?LtJH3BapbW8%+bp$XVftT z{d+Kp+`cc||2da38XEcx49!gRE13`xgE~##;~>$$AsAwgA4uNqw@4tOqfa0>*5W69 zBf(}d)sD<9^B7xa5nmBQl!Bi6tq~+&o#aN?b_=`jH`*Kb`0myIN~$>Z2`1A1_DWb7 z{iBExSqVpR{Y5HkZe>tCm|LeHI;aU)zw zJ^;;RdCY4!3~|74RQJUK0(w5U$3vC|`{`CWBwRfIWQ(IpQh8eJd`JjQFqM0ZRup0!=Xhw!nrF;DH3X zvEy0PE5E3cm5gb|-e_Q5Y-(98fy+Xtq@~&RhF3*F$bj5pobc9YW~vgn2gNiwn(hwR zO4AguwP5upE+1Xw~nI-q{zc#uDP;AIDE8B!l_$G!8z1!Q4{7 zoOAr(>5$8fe^xgSu6LIC z|AhmW-q>kkaAANEpdy!SQLVk;J&n9r6$H@-op!N@?$(H)huPH3Q`BB{nRFY*+esCw zDWH_SZvjWV=)Vm1>BzE_MKpuJW!;5lPgf_zK^X=^;5_5=AC_qU#~D5^{M5Nl?uPfxRA7DrP4 zzP;XTXR@6SCAzo#vDww*3ln}P5#!{UmqVZWys!o9^R#zyFRzMC5CbjCfuw?C3zG(#A806iShBL$((s6oenGA;~gENRA{Jd=_HJG-wl7I zo`&0;p81xS*p^LSZ=Z~FuV5jF9U#^SBc2o-te~R6Ix<&+v;or5zLCfZ z8@a^G@0a`2(_@c?fCI>`UHhdKV-WGkzX=PnA+sU}lkv0yH`wS^gIDCwndG2T#PSF# zUKG2OuFOz}hB`G7h$e^M1yePp_cS0LBSr16Nnhvs`gy^#8HNqrLA2`xV z8rCPW9q#nssPv8&x7WHbxqyPQKZ<=u-RCu&1*~|DOdGQiY{{pi0M=-DXdYZ40}4_& zbs$sDdsh7@&X?VnEu1!o`!a0-ERt7jjz6h)+Cz&LSFo-(OuFyJA|f8hh&h{Dlof@K zavYxvo{!#9Rw4CoI$TaK`l|1pIHtZ&x8C`#8!zwf_x#s#{NZ2S%QNhLW829nL`@PO zC3f_KaL|k2{qfcb^ix{L4dy3A65UhlCvvY zzp#C$k#t2imh;6((k!q}0f`nC>x%Wq7=iFi>`xnCF zkMpq0g-@*kFJNJ_T7Px_%m4G!;MFIez+#vP0Pwbp#)W8-KFn_Xn|J?RZ~cvuwp6=w z+5GTd-P-w=vG+@|G+w|?pA%7yN3 z2kA&rO0;%bzTm!*O%&rKYH<`%Cs!3wea*u>C#Hyqf4s=sjr_dnM`< z^OIg|S_2PX!1c?~u<mr}S~Knn#PXK$EXLKjJ?qQ~Rw^stH)t~ekcG7djB#~p z7l+Gw7d?!B^7y-Y#DnL`1rgC`gZ?K%SAP{W_2W>kUixkV%SgKyo^VtAwJs3ZSjW3r zHkW^+=+z7ALGlTB7Nx}J!psQ@7QBFZXIcRi7JTAQ#SJz{crjN9rl1vZqvy%W$jU@5 zp(>-LaTew$H4{|Tn6P9~yGJP&!x{}@R!&>iz zd?w3O&Bgv<_oGSpxC&~e6Wt(f>`n5=wX7g53 zEHvZf;BGDF#tRs7-WMZz{d4VNrf?XH#@Nj@-x^ovhH>KgtXMn`X|)=V)v{8=<6ky! zC5+SQvkL7g@I=6$`SeGrk*>WH5C+vk8*Q<5GRmsV^wxQAoyTW}x!K&XfTI6Bsy+!N zm?h;UOe@!H({iNKr!qg%=`%V0xZ1iC6ZQ#fX!}kwd{_X1AYs`^EhQb|dHzCO+0n7a zkLj^Nf0cZyim@yvnmR%>P)1fU)&O8ick#7`n%ftMB*qa3Nt5+9I6`Cn^-JobtAS`) zYXHDn1prcIpxS!p-#F`vxmM+07{Z{>zC^=HT>F7@rvL<%n^mS!qK@<9IybU5lwn_E zjB<^xm>pLbsh0G-`B0Ab%I2C!2*GcDPBINymFcAGVbS6&e#ThskW@|x(aK`NqqETH zdaAb5qbg|fup#O~=QAa%b4EpO36Y~>vCg&dDEFzBMtBqld$O{GkaSqrndx5)wRW@b|tk3LD&67k4~x@c5lMj(jL3nAg-A_+f)Hj|7P*<|q&& zh!bG|djCQwOM`WVRu&=A*-2gH8Y3E~N0l{BYggwwpDR4LWo3-AT3Q^s!I`%gV`OQX zuB@tUK38>N%7v~L+K)H}n=TPp2kNYH3lfe6Low6&OgRgY(iiaevOER4|(2*h2_IaKTlEu9yz)7?S@)HzpW8XRcl7$>OB zj9Ox}SCXaV!l8?K)Dmz;q@oOvTv9G{(h;4lK$fQ2_xzaQTRgZDtt<({IOM+#@Qw2ZH$YWLIgBDi}GNClykLu0nbA#S{Xu!Dvee~ zONYdla;`0Uj&o8jG$DjAN(f*FDl3CfJI(`SX_=rvz>k?9G2}I-BZ*g`X5Hm7d^uhM zTH8ZsU71zM;4~Xvq^&G!3FeS0CN}=MP9f zi`S-gW?uPHx0>s8SoVbE+Fkx^W993OSOl885keYk9vWS3-i+%^i-7uLnPhr+ zQ2C{~6wqJt;dSmdIH6ivF37vTGepP`ui4sVTAy zTdhv7*B`8}Z*J{eywq$plcX614Msc)^lVdF79ixz$AG+8pSUw)z$GsXlTKGKm-gH2 z>S~W$Jx^>uR=4%4#KA0HYn&|1Xt#Wx&PxDej8R917}j|^FvjW1&#OGu`H`CL*ZEl0 zxdsbC%tz14sO?$fM8ITjjvnNTvFz>y!YAozO$hwy|9P%KJHsW_oPf11YI36;VGuRBQEq-*RSUgyJGuX@iK+J-? z$3;HXT3RpShaY9Sc432K`@{t~_%O4^?cH5yWeJ7T-4Zh_ikX@ZWoIksZU@;|0wEaM z)xQ*~(tPuOe-^d)gKtl&Tw@5!!Tn6ucJpR3d|G%RHOd+7(ot=+J${f=260FH;I~iw zggNJuu9)ms)>v8SxZ_QaYFXK^A?i{ig5X8;^l53eBaGCU`N40W;BJDHx7%Oog$>>u zcn{y6#ci>9GvPiJA)}NCpQfkMD0}6t*7Tsl@@wOIe7ak9x5L|C>D7f9JuC13$)wp6 zM!RyMxktT#bT@-4H(J_!A{S%XUiag+@MHG)omqKru@kX;qSVvkyq{=USxA-EE@}#L zHL*Tj+s*Iv#AKnzl{L!tE(BY*k}5Mn!WL8IJcR0!uq6&3WZkV`@4a+#RQm~!+oHD< z96iXqfZqAJzVI0LNz~*|zB6BPC}KLe9zA_GogdUd;H_WVKoi8~nrDRatgpK4AItE-=Dai87#Qa3%72lq2o*@xeqB^_^iP-^9R7eeaUu%)iP)oS!S zV*Tw`8$bHJ)BO(?gR2o{?hdZRSlID^ppRao?{~L@r00F`d&{9gvMIV-!F(iJ8-AFG z-49YfW_Yq{>8gchf;i_^R&-cTH~W6IAD8ubo<9q`W#FFlWe4tt^fzjBU;(%VKsbO0wIf$Oh@wSTW#S} z$_e*KotxIc@9hNKr;D*{Z~E4{$w7&)f7mQ*dDOk}aN}#U7pC{UJXzNO(EHp62X`L_ zjd=aj-|k(VQo?xN$=>ac@6BcKakTYEMrJ3Kstn@^ODI{4WYFZ*La$$q#``6qFgvM@vVO#Nf0P1QZtr-w6scZD z82}jNu)t!B$kJq|OJg9UMXTE6v*j3ha5Y|br;OmRu{rRb-CG0=hIEGZhQA77q?8Z< z#;K~zDmp!AaHFgU828!9qnvRvKCFy7-@~}}mS-)-U@tRtR*>b&O^Grf6wv3DdS~>j zbJRv7mmZEmlX?khU*;dN5Op=&EbS{Ej63tidPj;GFoO*@-D=A3#FjT$0s@N%wK zz?|@x?S^w8i=_cY5HluddMdHkLUSae-1@b6KCJVZqKpI$j&jIsyfovBnmj$N>)fc? zqK9`jRw(K40*V%~vNYWdPJ#FdJKZf*Wk-8uW6iH}P5CmkMAatg3Zw1mZlR?cA5?I* z6Bct7wRqeWtBD29F9%nnAY!wV+BxW6@wrEkz-x_Tf{yn}uR)_0r<~?9g7%<7 zOrBJOTM;3U^p9n+r zQ~qLF9OX;%BTS`l4g50I+#}#zXEX48T9;;eSO-ncI5o=3%Bae2-b`8ppL-N@nX|E+ zpVauS$--E(6dNH)ig^?WRH^o32H*$*&!>a}@(i?GhAkT9gwM)_Mpu3$Mg<9@oXWzY zu_-v9jOJ6ND|4Rur)!I$ja#>p`LK4*A=8ryY8@zP2_>lAlcg!t4Bm9(-j1R!qlvw^516tan0s+u$+JI*PKe6+R8QIN2(!5z44qMTU@Kcg1MXSI1V zb{4F4+@pk&#+tVr8FJFu3UEVit$9nf8bNcaRDL#)SWSIl*_ z&~;%}RjxBm*Cy%+aNx%r)0vjWe_H_n(B>`x(Do4kuyc`5@vYo%pBUv@7v{1wr}q=u zKDzzY?#0)eh&(zySb4fTXZ$U+jh9LnRro!ZU(BDrG5Gv@jvg*1(vMj-Q^j0a=Ztn> zoiXoF@~yOwGgZx%^Wt$|%zCypYX~Ys$#sgIrY> zh4HGg*+i+za*tvI^YPoWy}PL@?5BQt%?s$!gY4)*=0}VNw3w-nzdbR_VK@PBPku13 zGJVd#97M>-QrW)LyLPt%faftNloCJYcmvh*Fh3NWbIWXN*~E zEgI!nN8F44UeBR+y)6Li;*l-9kqoYvbD>hbI@M* znV{D{+m2d-(q+-s8u;s1uradHTU;hp_8t6^dQ41`t4T|Ss3P#xGfkblu*U6wm?Ka7(L1w7&rf>ZlP6`6Yx9Rg{c)yW97ofps0ftC4d0oL_RHZ! zrrHH9G2SZ&m!tVfEeo^#O7hT)z>|4y!kRY4GIT`D;JhKiw_7fSx?g zHDVt1|t=uMeXZM_OMo*B9_*rSRi#r0J8x>^x^@ghL+U4-*+gfkb?ty>A!@y4oI_PCNW09gC!f-_&6YS6vYZ`~fH_aE&4$KBx{cN*7{ zVDqPL|8w)KcX06CwAiOMccKmh=WWm%6W>4RzZaJqP?x9<-d|M6t@Zd&Yj z8`q284{h|r)|&5}L%$3xeVCwisj;jP9<6humBq@iz3Dp#>(?U6h^p+}-yh*FKRd3y zh}MPa?u16!*>N4U1V%m$9~WLk39DZ?0=vWZg)F?R`q$F3p5&Wf4-y_U7sGqL)LBuF zPo{Te_&bb~(O!u;cUoEOGzcLVUTgF(hR(Vw({*WNX>rJb%3s8wnMa#_KWs8ALs8pe zj9s1ITDj#`0}v#9VvQxzn9aVou-Q%*!cML;pP z@#5_DnqbB`h+V*P3qwfKW?Py3fbE@-3Y8RZ04?a#3_Xs&tF!x|L<&reAU!Y2U0 zLjnL;=p#!v>@5ondyZq`CC?98uR#}wrkdHGAWDCm5ARIZ`7#j0z-tr2|H6d9zph~L z$AYfNbLi@&&&t}q1UFcTd4`Nnl zCTwsoWX^%CEaP-Bl7xVBE}O`(B>*7qi1w!6T=UL*CbqYH0O(%`Wn~fZ?_Y_k!mONJ zxJR6JVVC3mz8KYIX0RV|*2&xg0a;tEobYLHgUf|!uW__kZC&uVpwq)j*LHqV`w36_ z%le$M=V_qrO@F#uzjW&jUWrhGgn>C|KCp2ovc|mta}gi_ao0n2WSMFLz&yfynx5+8 zN3wS@{ODWrYHmzzO>KQ3n>XS(WTXOHI5{=>u^QelvXe7JPk*te{$b>n=2p|}F(DMr zd9;^L#ql@R^P|_D`3o~TR@jz31CRWOTWzaMmkV8&nsUN8b=FmxG0IuvCi@llsVt3k z&KjpG!x&|PRGCKN_Tp3;<(zdZJv6E`upT}u!02KmagfG1an`M<;z5H~nYP+>wt^}* z)1x{_m@I9z(5pmU1T>yoDm&1XQ^+^eBo0j=*Eq>&W$rr(MV+^{i z^e=>UZgg#110N+{Sfo)-lAiFMCz(3u9OuMn+u8IFKgv+Fs4BAxa;22uyX;5odEO`i zaxVG0Iq>0JUNi0+Oq@jooIg@15K64J-K{`XMg&Z2H-1+7F+)L*)$a0}O+tVPl1-JW zEeb8qQzpHLq5M`=#tW&I%e||)?gIefL$)=c!6N|DiZ6w?mag2*%Ok7Z@M#gYPpon2 zgBTls;gdSk*;Lx}()p)aAByC)X?$@306dzjNx$;`ortDYrmM`L+5i=4*w7JxxZ~kd z?Q8|ByJ&DZ!~+R$(Z-sG*6Poc8#|cBoW0c-^w%~osRPYz0S@zB!V`clUaX`?H?`x{405F_nqw~)EH z^ywC2idx#Z%hOZocUX5T5FzVd3=i&SaYtzBD5s}S>o)C?42L$czA?#0!}h zvF>&N1e^t9T-*_qLNU{D7CYme2@~q6$2n)5Gsfuo2O*3x=KzRX0&)&RTk%il;M{*0 zpozHA(%fXpaX&+}taZzzHbQ7fx(u4jgb4sb2|BQ>k`d@xR?ACD%&0-rBU4N@p+ren zXQsOqI^(8?)nX*m<2oCuIy1Q85<;45zSE8nXmweCgHw+p_ys_cu87)#3p#vUaGy2@ zLDUx9r-YL9L{^zbCr&~LIC7rh^~Nu*A*4OH98HfaN`ZUi_+gH8gBQ*o2ZRwXWDa0@ zRB2_A_yzzxpf|tNVU$b{tJc5+=O~5kSCh$p<;QHaR~~$rIpdBW=Bs;96 z!lU2)zmB3NUyNmUI~?tmUckQpTgP0`+429!-kUv1mYw%uXTAH)J!`M-s@|r1dKSzA z%m6Sz1EL|43dv?jRye{AKREp0M@RV8e)3=7M@LxUu)I*FOesi{5(Sbl0AZiOVAh_c zx9YCFvU0uqS^eXQ1`+iGlEo!d1ev^Ige?KtV zb~Zgi(6|1{<2V24wuh&15Kgmwj7b>d0v8dIYw;WGH6mqPOi)PSTM)xRY3mp7~PS@d-db zjh@R~(pYixiKL7WhG*xJJLLRvp_MHY88kVj$Zzt_rhj}l3tG%rgb8v(_QT&lazobH z^pat<`E0DEx&DQ=tn~Dx+HO#sDfa0EY)yo*nX(AEoEU@rgS@w&duNpwGw#yE4^u?Y z>|7i_6h)!euZ0BT$!X=q%nex3;*Ljy7LU8m{`*O5-L(b{_lv<^(b@FB{ZAfuu6PKc zo!6V|&qP6k8DZO7-m|~iTfY`1Be8ZZ+8ZH(g;syZ58K?2*?Zp{)GDy6UjK41J*~2_Z1$aeBG;~mev^eQzH%iHgLS0YV5Fl+R>m%iDi{#xCDQ2xa9NywvQ-2Ht8nzR^O@4QC&(cV3Y?Z-tj< z#r`zgyZ7kNDw${_?;if~qtkB}`RrQt--dPvA+++cE~?Qe`Q&8$vxC78X5+!l-?>-p z{>6jif8($ibK$qAveL+)<~)-T0D2|t@SyZ#hAB>l!f&u-C;+SKUk)I{RF(!T|J;xk ziQ+Cz&P8X#9qbj%CA7}G$CHz4Whd}DlV$o9;yIz@+BZg42RIbBzH#{ezwR`8Ew6KudqLz5tev|t#AMF=V#WDv| zO1zMb4oleSz->fH1A{xaMHhy?w|~1EwRt)ceuFDvD8s!i9~sL%Qd68PLI~v(Rizq& zSAb|{ls(@sF+nh1mZb(AE_9NV;qikiA4yT_MdJs1jx4p7c6d-i?79@%kC~PhvI{9E zo42B>)RdClmzzP0MLj1O3dS+$eToS{ab{to@OpxJfM{U0q>JMtl*da>`I!G{p{#rBCEeK^R-`)e)WVl zut2fr2aby@GQv6@W)wRf`FYoH%84wr$PM(6S{jT|W5qe!%fV8|@oAN5FQgSX))}jm zUA-E>M8q1~=sDaY4}Lm%`c%w2OpGo%D90xt?1h0PWq4s-47$H6*W4#o+rv*Xzrpgc zg4Ocz`!k~~_sQ%`AZ)oiH>N=dA(V}!wcx%)podAvG8u@$ULLl%o(q3~7+Xx0tW2Ir z?qXQS2*XvTxl0(w!-G0I*Tb-wdjW5Lw8 z{P_#7vE}<@?M7G&rdr$@>x2{|6tsCV5I@h=YHhk+mjV!pa6MG;e9~QItu-$SXf;yl zkxY-|)+?*=MKH+al(4OJcfl+cxrQ0r z?n}*;D*23)CW255EJ9J5nkI=6jV^5o8BcqIhO!jLfKiSs+cK4>te69?t$->EKPqW06VZeQL;4FTB|LXVjp~vaE~Zy zi&TLSk}{;Fk)>&_x}wlfbcsTP?3z$)Ap!woOwsO3O%M)iWy_g%JPK@vh4rTv786`0 z3se*nikU;a23xS&F+sK2leKWRwY0P0lW9Wi00r$)^%R4-O0-Pt~J$X8Z3axwZpg z9~r1RYY#$1D8>|v%4AbD=dfX;Q8tkTW4sh*4}Yq;>aO1i2YWf?xXfxb0j8L_G;DKV zSBk=%?-eUo13zZ6)LNV7s_VGaX#2|FU*#Uz{~)O{4Jx53Q%2d(|3@p?R8o#*X@Eg3 zE3?R>z!+hQFh;F)FP}(+tko7QDyOH_{5crd1iExh>MfuvFtl3OlweFSCe~nN=h$4G z0YCrO@?p$^dsW-`&6zp%!+>=mj4@`!i|q|EcSHrKURDMIUu&kEwF`>)0>cVp(%)cm zqR&3a-}x73Klq;yzxzM#@4uPszmeSk?xZ}|Ix+c)JiU`o_RIS}oV@#ogXB;ywiNDT zgb|_`!e6|Iv|J{TzEK9R_GrIcumgCbq z-#)K$?E%P*aXyi~OMcvQlr)qRH)Q!#w%5HXSNTMF5z9uh%JtiSdKUMb&Xx}W&#g6Y z`?(kdhLe-h_2}fd$|mykein6|vjdrfTo)Y1rc3ZC~U%Z1cN68jDH7=fl>DOUV8nt_Q8kAW<)Ik=M`dC>*YjgcNUvhw77_EC}_25v7Y4y`rg^!{*m_s-*gKFc4& zqCp5fpMH>6gXws`!*6%{S4B}Ggp{r-F_pS#TsaNfJluG<^Oc8o_a5#1$n|M5ltG6r zPuCeI*IsKOgj(w!G6*BIaU%-b9ER0lhr2#0rqWuADQd5K2xA}>x7R&P@%Xrefe&*C zm;=hvw70|}PXxQw`t4(k?dmg!B6Zoup~$tIHKj1;?`6Kz+4_5@!Nv(fc<=3*m4C*-{qsEU;oK zLE^or+`*a7YcPb7taSgfZ;g#woKTz&CHIKYw#xNvD7Z(8L|JPGkBabW*rw=krY`sR zmn}#-81i#~+G?U5g*lpvkJn2yGfPm@lk~khVF3z3Dv4|f~~R0T0$`<$Qm>|6G4L=f07}D;*J9$s#=@r zSq0vre$1k-GdmSkqPSl-lf(T2AvD;_;bpZncfLC`+6GOQPbHxU_73I{gwfp}jo$fJ zqs5%OyX_}KIe3&W`&%u@>O3G`i$DQqv`t4+S9Vz#sD))NW-fLD0;pCwGqVHrYl;B{ zeY!l5|MfbSt*<@{!{RLj7}no9boKPpid;QK!U`MCuXqNuvL}zT>3OO3uMD34b?8^i z&mkCl+-U|8QWzmrW=1HZ)zj}M8_P1iI0MB@DPh7kXPgu>Ws#koRdJ68O{PShFz83D zyXA9_AcVO`8Y?a|e)dVoZqa2~WZB#@$?++3Nz`@D9^?q4g$3Th`#H2C$Dd?i64Y9C znM000tPnz1Uu}WkljGBeKby+Z%m%_*B$s%a$YS7g!HU;fbs;gZv*j6W!#1}t+(qc| zdkL~A8Hk|4NBac`v}I+qGO{w`!?K>cS4K<29Rh3x@V6=wg(*6JR9IAdiR2UMg|xNm z8f}k0PMv^ppAd?;PmQ)B(}0C_x4be@-EF_K=|M|8KCBn~{*F&5Zm+wLW;i{qf-bYx zPEV^vRmNPxTmtJe5-HrlGnPEG~r;|zohYFlO+Xd^Jqq6|Z43wA4Iu7f6XL$-ig5JFyfvC3r= znT_SnOUu8UL?h9UcFdM5Iz0?%ne@Mo6@Fi$Un8m6eqaTh44KmV+1D8(z?2v!PIxsd8Ji;S`3qY@~SlhYC*)aW`OMFdZM zjBz%Vy=~8Lu;#kwH>fJL$m$$bt*oq!DD>L3aB@-^W#hgB;1OjQI$QvKtVXJ`l;iG} zpPY%K56YF@09jO}7q*O1muF+S2oSW!YGs&17XF5?E!6RA7P$en#wvLc*?|d07L~J$ z<$d$n7(|P4-vM9td?LHszA@Hn0S-vx$nk z4)-Wz7Ufe3=CF%%0ngxuG3D(kJj0wYp;5tA= z)wA>~uQZuM4(=qN-33CH)%NUR?#G-GY%S8-1RV|<4J~bz>i7Tr+-gK9HpcofOU}i^ zpG^@)N|-XycYi$Ix*dZ%?7|`rJh0$hftC8oP5}OtU`?`lGt$zCLND^d0P!t{KBbfp zN(jNE_NhV$n?=o1$Nw$BDWFILelfMi z2$^3&Frf-FJrL*j3cO?(QRYS|ixHv>&jzB=cdbDucQY@f$DgE_;GoH=gSE0s+9FYl zy~^gQX`C4S5?MnRJw z-_7DKCj|fS_m2=lpnoP5m6>j>LV2gp_lri~p&akOH=B2l$kY*>*7d0uv9)VqK2ue0 zyqIm@j$~z~gQ~gWjE;)1$sW8lnVpNMv7I>9}NcP#)jQRyRHQ(=pHW_L}R>{cA8r=IIU+Nso>Z z%KPr!qw2v?Sx0DFbmu!mjPd5};MuQrA>79e2xa)j7u(j@_PRSe7m!)2rF8>V%+zyV z?^U@z-z%e4e)AjM)BD-#)lf^jdNtU*9bJE|b^ndY`i*dMQnl7xEo{(agU5yI*CzL6 zszwK;7gIN&QI~rG9UYcss(Y7w%5ZblHQMGgK_{~2l#Uw3G z0G5&}TVfp=W3)D^sD^{?KYw)k?K1wzjV_8s_j0!NxpO~a+#{{+`=jK2jIpXrIux6? z;^F>pPQFzz~?O;1Z}k;N1TE#6-DdON=3ksxLW;cO~r=Ymiiv=||XGR!!30wM}+ zlwH{kpa?4yr7ClBFS97=ed!(2%@9H)oQ5qYT0N{X_24IB_uqTeTy@>f0Cv+tjN*+G zgC9a26Sn!IcW3>}fl&r>UMM3*T4RhTb$i28!T?h;?mD8-kcqRh8)#)6pBjtc5dg4S zYwl-oA1uZgjHTv#`+O{cP?c#&#xxcwVe*-Td0IJBql1!hGC8e8X}Ci^d{}(`viG}v z)*$FV`*Qog{#qMiPi1MmkTOnWWs0e6^c`!h)d;3Zen=YY6mq!Mu7`t11#Io$Uf0_R zxJSK+oj)qHFk0JeDha__8f)#G-7Ub3QWiR&spr1lJAYKba2R2%Dx*rnIPoGj zJ*l8%A3VxMt|t#f)V=5d)Uu21(>**U9Jx(Wf2d4Vxt2oHr3+yh%re@RGxO`4KS&+y zHOQ|iaV+T5PZbY7ZNNma)56sG{|LHzvg2PQ+5PH5!sTN&7H0>)Dvb3@(65#sr5LYl z#J$a^$nEfKl5@wSM%k(`YuCbJruN>RE$|WUf=#Mj zyA~FS8XgpcVY4Knh7sLD699bz_}gk_H*bd7L=u7*M3U}$eJPwjF52s^D0OGcJH4NE zcb~A;XAU6*bB~-qDhR0~s22NYIueTy##~Zmdi!<^(|A$njT=#KCs0)_Pu9{-&#E%j zZa~wK^g=p#R1`A>f|P|OCGI<_suPycJi0d-2(Lp|uLWS0<;R>bJUT2JeFr>S5ymj$ zDiRfScrjJ0*FuYs8&E%H;0v;_ObVJDA=JCXY7HZV(Y4=b4esR#A-~56#Z{(dsR_m4;JLCJZap8zU7nr^j8MGJ{g{=n6oB<{+|%!M8pkgkvzS+ZavrF0pUIsr7orlA++&A=r_5_ z%+|}%@^lUOca#0<=P%ox*BkYRFrHKy>1JjamSPh5Ys*iY=KIs^(KLHF%^nz|G)+JC zCWvlG|HJ>zs+GEY3MqF9bX|+l2pIRsN^^%4iSio^TsVQe>_yCIn~fwyk(AI)U>vr& zJJ)}enaaj8Y;iwkgc4a8QJIC4H(W(!s*9O|FL8WSLEta4XzNy7?_UvH_P|=ECBp9l z>I5k_grekJYGv1MM9EN4inTOGSudi{r51Dm03ZNKL_t*3Gf`z4=s$3sQ&uPIX=!As zAw7IST6aU5jb$-Y+$CCBYtYI43=_0KcHDq6myE%!a{i9GTfkAWAZnA9aeM+6yWLw(`wO(c@gy+3}WDnLDpLCQPAjJz;+Vg9%3z8rlhUx283ad7M7_5nmOF& za}R5@dNquD4wS*ObHRO5<;n?InQEXw!iWwo0LQ0AdJ!L2n|>DBi&;LEve5AThF!;t z>UcYmYh&zeAkwi+M>6j4Y^+3SKxiG2CKO4OLuTPnay@<-nxM0(GE3-=da>Qc9bW&85hl35i_Me`GZC+;T@WX^Mj1YSBk50g!BJS}<&w2k_=iH;RG-ay%m;=)1h7?mgIjy1& zzx}nYC`~$+qBLQfgT$3^e70A(A(e%hor%*2S~wPN1b#!ukzfLvpGl07 z)@J2KprnXxa-1j)jrBQZM@!~G)aaK|TQrq-^7_uiPa*1ZqEJM?0fP2{)!r^ivx zp$wlr%%iR|I~O-zZ-4x~k>eA;!FreclY7}SU+!$&2s>LoLg>cp?a66{F$NH1^;&r8 zxkhp>I-B10*V_+&Hf^rD@BHaNmlh#JU2Kf;B04%OU7zMt=|;?p+1Bkio2YCeU7w!Z z%VeoLTYh)b3nI4rQuD*_4Pl#UefdsfCAj<#rjGBbqS=jaz%apD^QwRc%-`=U78`to7e;&1%n33Et$V}-=;AdJ9DqrL7ucypGXOQ6eU z6UiLXTy=;0h2P*tS%Bxjrqo(g720pGxa;&T`B9sT!URordOve~S|%DQ8^-bMtjZ?x z=2tqS!;*2V&3SnJegCd6OWrJtJiBZRiEH-7aKqJ#k$E1im8m41ajn|_6!re7`pG0I4zAl0&gaeP|kI&89q7G}}LYiWyA*`-KvP?jxz^`G%& zsdrv(%#H;@h=;`SKs9 zYbEKzb^sFuv^#`QG7^AmC}E62z)cHVJe$ZOQG}8rQMIMFv6PcVk!+NerS5KfgS|YT z$$X}gfxzTKq^yJ~5(#bqvd~%@$ETt)*+j;D2fkui>TDvHNyp1yx~z1Wf=RYf!cd36 zdezRs}afv9qg z2`Uo>bOg$9Ig_=#PFXF@^sH+1U0E7gny6Eo!C8Z}GU-G`UB~fhK2v3)+8Z7r$XJw5 z!BX7>P1fi;anG$X-QMuZM9I=XDk~(UiBcP7&i4z1P;1TA${J-cM&qN(Xv;mKRUJ}< z2{y)HjQTr%(4&}Ot?d%Es?HolWRWR1cjK~%&)Eh*m4b>6ki=xkSr68KqwB40>)99# zL;AY`DB(cd21(pn884!$($KtDxoPwqt1VQ;3v$Vlts$WdE1{Gy=~z&X;l;g(j`mB0 z5cW?oJ6mkHHgym}1`S1JL}98-rz2s8Po$=p5^Tq(ecOWf)3JLbs@?FD#^I(aF| zI%qL#ER0(SrS(k?W_V8z3J{W|QOYV=pB2}q*4m)S!!|d@e(>k#2XCei{_V6#RBO$x zGRR6m=~!NRzEP%Xa$I>43z{q+ON>#_WSHQy2f4_#8?qn#-XXylSUlERj1Z=^Ko6j# zrEMF7M4J*k*aMXrmPTmW8#VpI8q&^jP+zI9k@wbDwdIoz~N zv8vH3AY>U+|9Ae=#d8;=tvPdR!P;8j-xy;;t*cIVVFTkXA#>7Z%{#E@DGA}vAFXZo zuT@A9iZQ~nG|VHi(BqQ|1c2+$MBpQU5E>npAl?S}2_x)=6cePiUA-EP4obK`7t=Xl z;W3X?nOdMGwHJf3U{s`q(aHd-J$RIV?zj4c;JCwqvf($GEQ~RzwdQh%sLF7Mz4a%jlw)g*B2ht;5rX%AHsuas zj4+4fQ`Oz}`#V0GJO0F7?gsR&KR(@gxj7q%y|<^3VNs^)-ER&WedqAQG-$FSQNZv7 z4tYM6*I#cNZQuHnQ)?|I2qWZ0bob@v^rR}L$|&nc3}ZAM2tsjd&0W71jtn{l)6 zmZ|Dp@`r>dk0ONbJ}U4Wo&5R3rpi3ul(!neEA4zLJDdLLgWU0HIuw{-?vP8*H--mg zciW#0gdelh2YF}1&n7AzOCwEH=ql4*$TpsdZhob6^l|1mYk7;||{qY|h zGl!f#%)N*KX@zin_0?7})7+!CzS6j>bVuV*csGxC|IvQXIUOC8?G4ur>G}Q{?DR#dZhf^&7`C}R`B;cT zKlhux>1oAX(%$gWkqDbi3X@M&I+9@NRTawhiBZ;%S=i#-r&X@pm?a}=4T`%QArv&2 zA2TmzqA-n~gAh9UIPGqFLZ0%@ov1hVV}>y*5}8kwwHEPQ8I97BfI7*G7;^~5C>z)HWpmXf81tCr+rj_&PWqD% zk{{hkhZwgvJXl5`B3%?3V^pTnXuEMUDrWM=m!keUYxn32ztc~L!tqI&>#*a1Lzd%H z=8(y0)mn3b+NOlrdM@s5`zyP___*{VcJN-Z^GdVIv=_6LU7s*aIi4JpjgDiCO^5QE z|HI+xwU9X^YVo>V#0V~LQ5s067NxEeIWVG2+yyUUev9!4QvC2@_zws^A=n}$=A~r+ zvR|bdlD4nC)?y5osZNIi3OFT zRqg}?lBa&XNLYWl_0?x#Sj5FF{>zA0pUpD*m7uGqR9D5%k+7Z$1^X3YtnpcS@+kf5 z!dOqhRQR*$SNN}DZDB+i*|^f|Z^cic!%tJsUT*pgR;0R0wHLE0*Nl^FDv_ys>8YfXfNbcm>}kobRw%N`>|2Dv+9_!9sOyyJh5etk zNC`_QA`HvQSc_%@QDqvo8yHSYyGz z93hkr1(e@TKwY1%T?<97-GDY%9m23yc6w4>f30CM8#Xy}Nj6c0;9{oE9~Ev)RcRow z^}?6R*0MEO>3kv=$~bH7Q;xSQSAyoMEArY}kx+~X!UQpnt+h(l^C9k$Y#t2K-S$91 zgD`4scxU%>giz3D7$aHg{swEUx=<|}ZNnbd8gv6_^QAiY`1bGg{FtBJ&w(^8GP8Os zXskGsg9;(kTKAT(ht1p3Q}#xSqp>m%qEQju7(s+tQJtSo-p;FY-|2ih;@`mW+TrE@ z;Dh*fPB%v3&1~l%zvb+VtTjSrrI;egL-#9;6H%CSeo6@imYfxZhCLeSfnYdLKk_Qolap#e)aY*cqR^r+aQ3os?Og!X7YvmV zLK`=uC)kTiuim>H$kK>HA&aCiMp;>CLUCuqvj~k2ite_rrMdJ%!;k2brv)5>>_U)O zCR!94C^=DwLp=l03SdQAWx7bz;;wA1xsFH6M7aS4ngV>-WGJ}DjJ8qN(ZU*Kl{9WZ zp&4S_rlu(pS zRGD4q?A(xAgCMjaY;g!}V4Te9av0(I3^d@aYMW1#8&K|&bR-r|4j`N04%R{&WksRS z9~W_#Yh}HVg3^-^%s44iO-OBmo=v4J^~N)ik_OE3z*-?2D{HM6u_{rN6JwB)2FUop z+2kInG6lT;-fqAHVv*HL*)@QdF-AuF)%bBWI})S&oRn~(*2E)>t+x48c_9;pc6{mv^oc}8 zgN#AhM0z1hh7yWZGLIC5t-@$&J4^Vw2BL1A4^nSVj!&B_4#xQ8UY4IJxE~0`fWI#4 zx!xszxLbAUkKdhLto|716A7js$Rb&oWv!{v7KkTd zgIBqZ*T~Vw;^CY5?XUL;LENVh1zMXX%uM>2zsDTt5>TV+@>@C(y6CqHvjnWri)P`-EcV5>&^#BaAR2=;yJ*r;e*%X?-e#_cIIY zCWXxsPJ*mVIuwMU@lgq0(UcRdY>{ZFW1z#7m7yGCj4!>=@FJF+SF+SVAFXnYF?g>a z?h--?{|x=AR0|VzdD!NU-kHI5 zn4DMZHzKXf?SH>Z8HOcb<3{9#ET5@spKrM#-Ftfmd786`XA10L(`S0s-BR|KNE0b}TZTj%1lCC!pzAIzEj%e0*HSJ%=8bPGyo*3u$akdq8*1cfNV1D#I9YJn9D24JiciPL8YAx*PYLe5z*W)vd2|AH6&6YjN2k$2cA?}jirGPU08~?@TyWbpek7!|9Yn~tNzVcrk9Ddh-{&xmu8dkG{ zss7~8UtHD+cWOUic_@{+r#K@2}oG>|Y9)L%fK^ zJ*P|+tU$~qqoXoC7yT>V=YG5O+~4WtV+ny!Kw1Wj8zCFDd6}vQZ%$x6WG(Q{^}l@n070Kzt>oM4QLM8f9hhIDjP?!MI2!g8Myh9}3BmbSI#uHT4=ci&os z`6tfS_uYt<`H(Vl=Q~4$kQVi%D;dhsP>vzT7wileCvHf+h!u%Cy_Yq5PCAl61?3)bTnaH* zK>rS!OdC5n6%XHYTc6{Y#>UGjrA?`(RGPpN~QkgQz^WNEUI+`JVlVa^{F*|A!= z8ca?rt?cvPXd;ZPvHh#TqClxKH9RO_wV|*n)r4TocwNr+cY|bD0W1rPvnVdo?kUGm z$`?tU1?I&}>zWcwiY+y_%^6Q%ZiEoEcoX-@-7$(NkK}9(x z1Q}x|=lc9u<+HjN)yj;HswXv}W-+k=^5C*PR(JOati)dgT|IS(Pa|RdjR*-Za2a97XXWwUFAQV-b?H~= zQ|MRA4^mDWU2o@hH|}_!bvk5e-v8D)CMakz@Q4|ol;AoHTL9y@v+0hHis@P9h179L zk*K<^{ zm{2@?T);xQ`%)9Ip6O}Tz3hq7fKLi&&w-9AOI;=sBfAK^w#FKR+<>?~&Bj6rqon~l z2JARq%s|?c4uv%+8%vDP__*p^a<*^B+`&a6+v_f2#2Op4xiv@$1CA(Ri_1!{UJYhv z)#|lC$~tyL9TR%UQNZ*O>%kz^o}vF>bolXJcErDo7#m>|Nj62=Yb>7Kmw zQe(JZltUGCS{OW58I)R!;p~%2C7-_XbV-q@ zpp~t@@?*C4JswK&ga7gt`EOp>{m&cWc3K__IX(GVGJCYc@Hq@RO)C=nU)= z@o1<_6%RS)<97$NS}0G3vk61+G?jlPR4nw(Z!x8rOq*XD(XA9I8)1XW34AmR`q z>^Ir)s93!kB7_=!C!b2_fH1~x#EiE2Od^Dhv2`vs!BwfBLcIyY2%};q7ubZcsJrE3 zij=gn#=k7os4%#~2(4TRvWWyV(AwI{2Hbvt_31`*bX1Dc6sckkE>k5-6L$DA*3;;_ zAh&{w*BT@%qm>n1_EJp)yfbrll}mL>VW>SWIx-b)2Bi#f!R}d35t; zR3-`|luu+jmZC7g;DZpMB2kc>sDycnZV7xYB9SSrOieP>#KTHit!$ZUaE}$Ko*b7V z(?%mv=ql3>f0|Y^BQh;AU1fTDT){N)`fDu^3SS%pp$* zp{=EifWaXc+$86sx#ChzM5*t6e*&^Rw+$7u;XZxuF9ryqTVL%`4svB4wH?Z^8_@H| zC9(*hbncPCUT(D&S&f&A(h!1fe6fA_Q93WIYZB1L%}5s7Xp1b8mGNSlPbIOqvqCp+ zxFvj!T2Ylh{hUsUMy4(DhsK6FvY-228 z1o9(9sgrX7fs$3KVD1D1tJSLk#<&ci-1@9o)ezlb_cIuebZ>qS&6TgR)*+CLsy3=}8mjzInja}{eW zVOUkhk6F~=&}C_DqYl@q_9JtA(p+`V9~Tgc>;^QO$Pd0f)XKOa`{;WkkZuu%S9Sv} zY?-R@QRT==4E8J*^hJ$KGY%4e7y8ugSA7yCHr5Tj#_5B5d>Hw_kqv-J2Mr zsKd8z#X*awV-aL7_uiRdjPt4TB8DsqJ5D}RpZl%;$-OM>I45_r?dRg;To8;_b_2?AciRtI93#|R zbsxVsD>Hrj>piVZbH#Oh>!Lx6001BWNklP3t&eD_CV?vXeC@MQf)ICzwEm!u<^ zjg%55Jr_}nUwR=PAD3=OH*Q9bPp`bvYOT6w5A&+fqA-{s!ig-+y`PL_X_BFcy3YQ4 zNqf@^8XP7h6558Md9~iu2&DDME-cw0b=dxh_++ z|6VdWDy^|$lVgk@zBw&ZwRtN_&c$pXzVN&2O4|O8pG~9}vE5giC-?H}uebHyKW=SQ zT6(0J&W<*1=3s${>LrBe|^kSx@x%XM1&W*(f|OyA>!8JzFx0`#RX3lg)|xvx ztNaFoAasN>v_*93Jv3Gz^5o9BGV!_lws!nztp{1jHT&$9`=6gzn#7I>aOnU>F(*_ zY+Q#FNr|Rui6N8)vf?Z^31AyA0tiTuJ0o|wGjbanND$ZvVi*Rj1XgU>rb3CLL{h_L zIGlZYdS7Zkb@qSz_FTNDPM_}S8B!7@*=GuaT25D;^Dp1`zR&wCiws$y6foZBv5P^_ zd}x|0Vzgh&2A!NJXTs*y>`c>?lw*VJ^8Cb39_XwiI-4<)N(h0d$&o=L6N;|$0f0~t z5!1D=bBAQ!1)+d(+TD(iZ=CV38k6z`IZkG*3tfaPvpwle<-O zEdqf4{c8PE>YbkrGy-#!K{2vPgFEY^l&iw7?IytoLcl6t7xPj%Zm?ox7^nF_mt$KO z4o#!ewpj3FlO~T+wstW=b=cOk4MbJeE+$XRa(b8JC}mvIYGSW`waX&fT9d`d$e0lV zv%bb?#SnlCVk!#&Nn21xOy!Ui95wjPXPfQqSj4o>Z8fs%&!w$3iQo!oJ`&v=6nQ4@ZWJzFeo1dq`q8H<|fHULcjpM2+J@=jUz z36ODdZ!Q0N4e2z4anA(}zFT9dv zOmRAxw)lmYS~6uPcgrfb%@xU?3=k9xKPeQxc{gu=nk#aF(I7GT9P+T1(W{NfDDNGp zYHn?wk92TBL^L=U?$t??Pfrzw2|Tf7G*{(gtQmm0Kf3Y&uz5Kp6m;!Zb`pGfRbi{C zrGg;35v43?GUvkS{nERzwwuU=!#u}~dKcOoQP$=nqDe=Hh#KYUnH7>D^xRsDROu)q z1i)xtO^l3bom-4c_BJp<5z&64!(^PO+@VuDz6(`aAOVR&xTN4a6*2QJSmQfeF*3z) zt<#ma%3D3Ro516*OLzL9%m>NAp>-DqJx#(^HLny77^k>v9;N2qOd-?WyUp zu4dL77$4W=)F8WPHdNjPdZw#bT*e^)NsiaQ@fu%!Ctwbyp7RR_?|+)4!zbP{jc+e@ zC1-r2Cn$r?W?W9J)!th~O2DBPegKDa){IR~v{fD@-V`HuBZ@9kSyx!)C?(SqWon0A>xu&Gv|!gGpDAmJhl0W0UMD;Dh!#E0*p1r zXk)Zisw#`Ru9Q+*DPy!nda?HoO`4r^&N}Dj{Huk=a1LI1fA%B)q}RJY%OnH>Jyw*F0Dyfp-WaBIYT`PZ zv3FthVj^RD`$yw)Xjw$jxqmTQXPjLATnC-?7q9uOT_G4N(AtQyHoy1!gfXHkhXEq( z&B!XxIBl&M77n-=Dz5DF}A>_h~ zO)lu*)Mii&L^sLhd1)}T9l8>?H`RfC)>|8xFEAr%_U7* zJW83GIpnD}Rzznb;t^fg&Z*i(8SmdKd)u*$+1`6IXZ+@sY;89=yixSdCo*Nnw@Mzf zYUzeud^pF2ZGyaORp?vVw;)C-q(*G&>$v?~o3Hm$a zLlb4ZwHDoeZGzE_Z+)x3kug3{$AlbEvY;yyLMQ>Z)JEz+Za88AnllsKE%TvfoQjCH z*QF|~Oz6&w&DNUy$-h40g6_Yc%a}4jL`;uv7S0AFC|>(=@8+wcxW&_!@E(E>$9D={ z`@vp){`uzq`!lQj#g|)2lk3X0)}qZT4Ws<}r6dVqEuq=Sy#4Lda$;pj76$c*}BQjyZZC?EKe;c>TxBl7?If*@sG3<_x~*$-OVrM09JhEeGR;+acs*~P zmz}LBcxbN5d|*%|oprd?etMz_B~i*KC5^6Nl1@)l(&DOcB4!~3Ch5`5B5e!Ci1T6V z*$fklFd*jiVRhl9W}Um87h9(C0MOoykYX97EJ_$|T6N)6;Y7spk(r(9=8DAQIXSM= zHm8D2PZZXRloBQ=j$!M?B$GluGH9h|O_-e;#tCIam%gC`W3X3Uex;*IclmSee4u;VF*1Y5S<}+qjO(eHr@;c8f1&w*+^XIf*p-V( zT{tEQp`;j_$+3zvX0@*i8v@9Ln#yHevHn~NgiuP1@{O)kxuX<@`!%LjI2+=Oi-^vT zQcO{+e|R(Jf?DObo@=PmF;0>eSEXZuSnYX2Ab^M{c?^afOQ$KQ%KlniHy;Bwg^O2oA z0bBd&Lp|A7qkT2nSF=-t#%flD1@Y>UWa(q=+dp1e|CcGad*aJK4*>L6{9fEOUVg<5 zU-7e-{Ol!PU&fC=-7iTA&%&S9?&{-cRX;m}@UfqH>x=1=Ed*tMAt%M2v9YSc{sQS& zAIC9UdKRT5iR4PNnIrbyoJH-`oT}92X9w5zn@?ELT7rS%Au`i zRz|d#*lJ>mvloB>1m!U8EAL_Ntvv0B(Lw#rw@*b(0ienq;`K?32M<|?GeO!LQ8_i6 zms2Jv<@3OC6pxe>g9pRAph}CBhemga=h)!LreU0*!lAblqY5c)3oK(y?TVppu13Ys zSRKlVS-+g>%B`G_s~NI6441SR8k8jl4`^1c3Tus5g(m(}O_ zo=ab9FGHD^e(h$u^*#V}p7}^}-)i$(JKM$2i?=uXA6&I2_}NP#1Z8I9{O-~4_4~)) zspxSmdjO=?qv7oR>HYaVUQ7&94t3?K{L#U8F3bkHcP@5kkP{B!k`_l!Q`}&6?ogQ4 z-i%~QDI>%Ex}MoOx68NQ?x$MQ6Gb^COR|Q^k@7C|&c$3(tZLv)CZB$YSkT*!XG3kZ zLk$y_PXQq72y|pm+X8?@>6}QubYZh6nF<8Bq)32ju1X+)OsITh5G-&y=-NS;yX#~< zfo)yV5>dvRD-jBSaCjL!WL?1|4L(FE3n2s-kWi^BmvsaaB)E`vgmX~m7UMF}zzC_G zNs~dCR}{+ygVEk7A3{I|M%>_|gSyd`&IYuOS{$@SS0IqFaz6GhO!_K#;1P`yhWsWj zsWSmJZo2Xz%oz-nkz!=p8xd0N@Z79jOd&uyHNEpO5D+noQdSpE#uUpNLIb{Q2vAP! z_^1xyk2#6AD&&gmLCCHNdC7v5x4Zi0I%!B_ax8UUK(#;&Nip zw@yf^N?#Y&*)Vum$&?}2Y_U~(4{4hNfnsbPd5C)-fI!^fBBsT_5Dh*L)v;Y@@zCQL z$oytwf+Bvo_x5aIQGkme1XzST zDMAQg47_`kBJ6GOE~FjNI~O0nTlTM4<*D7cno&juw<`d6_G{hEXB#r1rw>Y1xP>Gk zm{me3Kp^l4hOuUjUKwqC2z6Z*d0tm#RaJFe*JWAE@}kJ=veZgjYdvN#d`M#$mhh~w z?1T0A7dWCJgiywK-7{r|N}}blWZd8%X>;(U_Vh&mZ0KtF!iwmkD#F+f%1NDDLPGs~8S?y&)-}!@6$_QbQ z4~&Rel(DqK2e)fI_U*L@uZzxRl(xihzfL<`M6|goFTB*6oG2O7d#}$`W0b(@gNjR9 zjLh($MwOGdA
    &<-SdAJ;{{>XRk@r2fRUCu zb7EU57ctn?S3^00r5FqATVYx0Wc;5LV7?$Ae1k=THe}_Bwl8O6wVYYn%0M2&a5`oX zV6~A}7!NKYmlEpGBreUKCr_d3$}BsQ!(1s&pwp(|uH{(t-*)>{bM1)n7NQ z7AS1NpMw~zfV9>z6+457ks`}vlpR;fz$*KMTCY#7i3hsQG}kjMY*3VTg^OaAH1@+{ zbK96=d_*CboI0f@k zpI~L9YTqvyyodK#`IE?fiDxmh+$X8jg zy;GQ2RPlDCO(qhn0HS|(`df@{SSOACEyg+Q8!2a1er+q?YZDV4e`pr@ORY9DOUeh? z?(L1uu^;Fg6~xt5#33tA$0bdf;uk1(X9ZR3H@fay6@8C+X+~+)Z^fhx@X`l7^}2I8QlbWr?}O^uy!YIE?JMeuRogK+QuY-t zk1R&iocw~1wQC=&y??lW|FEZg78MHA>;55w#|1m$#|J9M?DMu%Zwy4r&%I z%XHi-TWMQt_SbN1PvZKS(t|pGV#N4$FbQRjjfgI}Nwvk+`-iYk&PB8WGzSf~Wvo4Mm@8HqbMZ<;1X7)*yG zQ@!W(`{ld+t!1|90=D1-X|%q~AB@#f;-L~kpmZKo))q+NzoW^7&IFrAizDP~24191 z5>l)m2h}qnDMSfM7OE9}TbyrX3-25$q64S2Co4|#8M;c$_1+JF0^<`kIAcaaw8x9N){;l)j#zeXI6*~JGBu1EFQFI@`AVR=8oO4P=c za_TTpk757dQWwT+L9zN>d_7YzMRxz0bbMc)Z&eN^%{Z4&VzZlu!bJ=O+^~|XubpBxpGuhKBF7mje?zVrNRS>-#ivRy|w%f>I%igL(DKc z646`SvnI7dr>WH<{J9&2uJ{eDEF_Y<4t`su#kdPkSS@dV9e?uc(CP?U6K8U zssMpZdVv@U!Z(ldyi-_mwzY-3#4Gok=8w~5E=o6e;0e5n^yZhbbdE~6c=MZvVEz<% z*0NtD$|bkkt=DBOm<%p4O~pE#%c9zY_p--8H?9nj29GVijk%nJ<1;IM2Mz;L=x$B= zjr@?<9>eOV1qB;~GwC~!?B&N00QSGdGn{K7v=%8%EN;4gW)0jXFEo1YzQsK83JYew<;bQbqn;xkJQ1hQz{1IQ{LCT)B9AdY@g5y@ z)d69}Dpzrcut?3heMBOmpp8K*b?>Ro7mwuZ;5?%22R6p&7X!vrj=TN?`&^W6r&H@= zyUaYvuY`$y>X$9M0HifbCg^GDiEP0Z!S1Xh8RW}y%ETp0mq`DuZR=$IP`=|M{HkZN zNuoz19t@~tiW6(1XC9;9q8sTd^(nYozl5WblWe4F3Z6Xtqe#VKuVf5Znf z`5x?i%Vroa*6>2K+`s?%Zacu}3*j4@3&0IE&W?6dFV_0}!lR6);4fC4_KcQt+Q{{Z zezbI4NMB~i^g=~=?|cynitnu}G_ud;PyN8cLtO@6W-v23ms zY0xv|5+0d0&deLfOt}6mR+bPn7kERMk>@#)BKGWMc2VVV6XoJzolrZqr({~4)bJHG z=w9L#NI^>?30d2UfZq44-}^yfl(i!<_MV8CFJ*$y>VV<)%6vjg?u*{T-r~>>%W+Mv zji2{g&dN{NY|hKSmGPJDo7~q^3>0@7rF~dTWiO#g9K8J`@FxE8jOC?EC%>k0TFkHX zVN1)a`SQlesmkc&nuZA}(!A?8`)S%WmgsQ_BR&XNeiuMYLe#~LE@rd3sTs)C4VQ6R zwL!nZ{rO`$d6ekbK~^I_niJ{I_YKYb&KH%@B(wU)4W{AyO+*l{la*xW#)MRHI+>P` zm%(V``}m51yglxA0Oeuvc^BW&$MNwySLg68*TTU zg6amozSKk@BWone2`Mo9pFxK_WI6>=hqv0NX8~y@;n!@1oP8fzb!JtuA-}~q39Xqg zT-~<&j|Lx6^PKxWS{mTHnfRR7;eKz_gY=RiT_5=AEZ!A&YVC}{K%`mMXI9x&q7G{j||H$1Rk2q%( zqnbCLfe^-s9S3s&m_+Yk8d|uDEp_$Bf?k;tTticd-u1UJfPRUdywIZSB;{$J(9P@0 zbSSc<#_Vu9HWEWj*O&Br%SRBPtpWvu#f+xV7(O6G5~@b?1qC!Vej*D!B-cW_Jqq2f z!6ca6Y;M8+=y$UCI`FeWQ>mOuc;I(9Xu3PaO;!s2eZ_NWIaY1sJd_M&<$if=-i8g2 zneE$$FK>)HBb|3iMX1eO4Z%jp!0V6OR|piGxo%~HKI%1S2qr4P;*k+j(Y(%7bZlAE zazYlakr)q#<8(BnJ~f>l_Xz?<|1)2dEWQF6*5?;d4%e`rT=opl-ht-mtn}m=D*gEK z2^s}y(P|}aI@SBB%n2bSn%Nr25 zp|LQC^fL;OI0ZUlQ9H2Usg06Tnk%{fi;CrzHw?_^6rXbz`)K()P4t+VI&*e~LaIE( z3ite-+m?3Kz2 ze)?nF;>@sXDHhdIfkZcE=%ox1E;^r(PjEK1wbt+Ra5cn(J7Hr>*Ir4CDIA7ac4OGH z56lF!3D&1kY&T3;SU{%cfgN>lWLR)tQ*oL~nfrMcHtL|DZ=kVB1c&EI{YA0SBxeSJ z=I+X3FbZ=LM=KI4+4;MXj1FO+A*oDgmC~_v?0s+5tA&7ab1~L!2$D=6~>gZg4o$KMjUO)91Zc74}hgnX(itqW<}{Dwn?d9)px=q+L?nY z^gKjoDDmXQ+3e6;Wj@_w;B4KQC>{HP7PaiYIFdr`B3Q z+Ak-GyZ(+jY{UV~(x)lc$DbcYn=ceN*CRo`Le*2|0@a4nbIig;0r#VXEMyF_b;aE` z&>7z&uQqfm+-XLLjgH7uX$IC_?f}wbi;EFI^?8?9e;NMTSU22Vb;ZE{O*fs{Ee;qX>@d4S=2+g=<3C=JPso^#$@Ah!o-f-yrVLAQk3;E~ZwUGM->frdoSR|Uc z;YGnReE$`kMb8#yciyXM0eb`xug+BWi{pDx-)Q>qTh7Vzt&OLxjf=gfjWhEL?|S|m zj)WLj?PP8X7K<%US|G*j|78TQ?3Q27%$4vqp$T;Pq(%bu$nA!puPy(bJ?~KjNHZ}+oP=-lk9_g86bBCDP>>|6w#bi`?G))4JDrsz$MtL=7zD!S4?_C#m6i&}x^E`Gx`yB&_Z@8ZX4qUXR!v92KBC%QU zc%PX++yZIke%IieHn$Aux7%vLJ1W)ztE#lQ1veobLQzL18h*n{bG8?d^u){=qQn^ z;!#ZzQb{mZvvTJSc-j<5@G-vk?f()^&##)#w7%)|ShOn5-QyeG&`}YNS9B^7fF1C( zY`LU;#3S1AX)@PA_~|xO^`&DS7F5G`Z~}d?zFL0uxr4siG`8FiuiQYF<62sJTF$So zA!1E!PlqiHPOTn~YcJ((4UVS)`~5GZBN30w2gjs+f=d!(VOTO_7#7#W(2CIUx&$*G&EFwe0fvzZr9Ty1NV=>|t+oE< zh~{Tq^PM0X2KL!-4pEExXhgM7OxHm3f{VYi`#pixAiNefH#cZ7+^j)|gRt;FX0Oy_>xa|6p{d=8PX6>u`%pMY+%mbjR-JcVWLJtXS3X z8FPTrWh)y@r!Bn{6G19A-d{j<44xDRBD9=@cvBL%_E~w3uBJx}O+31~;dX4)>ywml zK>4rc8jM}VbN4S|qC_Svi_y8Q4c3@6U>jGBL)|lcn^IF$6D6qOx|-NS(71OmUZF;j zt1``R*CL(tox3U$iUN-lroVSKOi12}02iDfYM6>vMAPNVVi3_c=R8cxa5`5K<+(A@ z(Lt(6_e<78wEB6uu?9O=l+}BTA2-aperr#rX5kubs_R#?q-GNjIO3;(+t~&h!j1fsq zpQvIssuk@xM5dSdR)f06nj;4f&@kaL6HG!faeEonM5_f;)oIc-i7dI0nA0jc$cv1a z@CdjWcwQo2k8S+$`ihalhUCYZt%}3q!^?$HTm3Z>i{LT^=839G$#OrDFUfVuhT}|v zgpx=E%;p8m9d(ii_vNAPcpXpkdgvgb%DVKx!Y|b>Lgi>_?zD*Bl$x|*cz5c# z#aBQpG&w5OVx1W(mz2~^;Qh~|A)ipVsKQzsAxv_GX}Yck5Wc^wDwjl|{Xku(TSy(s z9S3D$sOw|XQ*yBT9ds1|w)$0k-KDs@ zyR=AgcXxLv1a~d&ZpE#*?fDP(Q4W*LHS^9RYu$@+Pk3!UP-Qj5qVhxa{Q)F(>gBPH z71I`4ZlEjyXK0T^`X@0@|94}-B)_e8&FizR{fCIb1b)tZL0YVu&eaTqISfgXu&FK7 z=FdF|x?Dz%RT%~a-Y7krj6sT!xi||~Q-2Yp7FG9L?ho_$WgC*W9CL;$QEottC7xZy z+Yf1;_!LRVHWTB*4*WCAt}L;82_X~a(7aE?xOTt9GF=K zmKwzu>o=ZDQhaICAMIhLkPsh|6XCi90`=|ulE||{)(EZ~zR|)maNi&9r2gYzYwq|~ z%GD1HuzM=_l=<4fZ__thlUS^;e+Q!;VmL3rAb;4AJ@}4p^Zls3_1mg@JrhF%am z&N+LO$-QfStj3|}+nD>?s{To`0P*8hd*y;jw+v9oJul3QkL^TNy{!svSLwXZufD$5 zz5TVmyT-SFd#asZOenB|QUXqqmp%F{ALXyC>*;`|Y`k)gPWk1qts(Sam*||5H)7Sl zp>O7>kinIVD=7%i-^v?lFR7;w@v=o4mR!gNYnwjF`NGyPhFariR7RP+sCTIvnJ|fc z*i`pPx34!wS(rcG0rn3~@2e&uk9O?W11eNqwlYz_CXa;`rWILXk_*y5?^A0TuaaJ- z?#72}`#Rqzp!II*Y>QMn>*^H}>CInfmICOzuRE5AR%>4k`|f!0zHa>|@U;Ac_=Ok; zXZSK>kZAd%`0m0d?J7$)F=aV7>=9$Nx^kzfrLHr(A>_lz;o(Xfb_SvNV9`3wG)!F7 z&DV3jLw7&K3ERs+A2JD*`?7edI4KQgkt+RG8ha#tF34D--`fa3iTcD}rp1q&o6j6} z_Wu6v4^{IhriXrmi9T77)y5weB?@$;)2e~PY8^Wd8SydvqC92E2Mpx=0Q1cyK%BqjYt>p2UsA%^$KJ~QAFv=rZe)VDrB=lVM zb{cP&N+*i^Xq;2Z;(rSv#g{epg&g)J+^8o8(%0-6-dUcbV%Kc=p`AFZ-Vzm5(}{j3 zcJW9_hMX9SeiS0;z?$Mg24X_DiJ|}HU-V?Q#xKs)QFGs_gk%_eUP&bSlARQsWFpOu zmg+lSTvAlnzVL&74rdiF^AUFJFpb3WBgcfjs>$JbeUfo`IdeLz0hLUB$Nd-0kHwt$ ziNhu9ubUHX7Y%6$l;O79*`z zgtfxf+Y9~`l204+=>eIg`D-x7&Qxhg^WGKXKm6|K%lozbnapsf|Mf!xF>;B_>He0B z_06#0TQTm33X@(=3)riRFx>GJfHvS%ex9ore%~(JTP8$JY%qI&W)jZjOxT~sI{Z|8 zZ>F@6+dY^go@Rn3#MM9_sFj&kSz}8W5CE?pmiwKwi3FtL&3?K?5xOM>`qxYj;Gs4h zLe}<5uh=1>^Pk>w-lzBR&s_a4Hj^w3G6kH&mX@R0FM4*yzb0>w=~J&AAH8OG*0n*Q zb!~7ZJi*)IH3Fx%&rtoY*%MbUsC-L?`)|*UksJB!L(dH<;OqTfAKl^$rQ$^$D+?qo z^=8skQ}-eugE@t=MS}~8LI6!ARvF>TK6Dc}eKLJv-tXU4``b+Rs*_IiJ28VwoXqZt z4zvuUC}lD88=G2obYTLljSZGr(oWWWa+Ly5IK7lUG+`n0+_Us_wy_fkFeV9;Dh??_ zU}2Q=eub(IdtYVQ-zjdL_SX_9&_IY39jt7i=^sgQQHEC`4JlP^zvt`srMc=l;uj6Q zAbDbU1*%SdcM-e;(I0iA8~QLRMijRqV-7n)ujw3+^7=RA$NfXod`||^g-HwadIIGg z-)}!JCQ30@wBer)C=020sd$nAQ!+8(Atxu*3W!D}9noJd^q>-eoPSC=`N!C##jZp+ zcV_s%!6WSbGxy)hHb53RL0M1e{T-{Cd4PR z!jJfci4s`0DAUXpN!W}&a<{4XojL5hdfyoFR1&?V*cB0DptVSpD>Bt3M+lgpe z1}B*Pi5qi564$3=>hr4cX?=Av0=2{h&^?wV(&yAQ znctuEMB%_@3e?0$i-wbSKjbdA5% zP1F9Pr|#YCr~5~p|J0Eh`jsI#(9-6MB5qVtV4wb_1R!{U=MYnnR9C(qGhv|jouaD1 zRY&hs=YtaZez#+C$q2)5Se}&4rk&b}^}V*Hw z>t-Pl4xA~WfGOK36v7m-{hsxIfMrqBd!?d^5!OHoG59K8olmDkqq@NwfjC8CZ0^GO z(xN)JAFmk|a|;Vl95D$xHwK;aiMyz@CB(t)aQ~5!0D|{WVG?6(9KUk6S`0}^8<_nj z^3oQ<1|_PWgZwWWx#=q?E48SJ*!b61yH5iOW5F?FS2x;dHWw99dPOzU$j$q9d^Z?> z4>AZpliN*;2kC5{g1aZJxjZ%11^@tT;$Ma&))eGhOwj<$bWrzn)R~s^vd)JA0}UY> z%7~Lc1X(g#~~`wZ6Bidq<5c( zM8?TEnOdh4Y1xbTE7Vy1+HebjRQ$c)0D^DX5o^#blmELvc5bKqTTRm3$&xHT`3o7v zat^Pm#B+P`s)7Q`llCXy5ic8+CiX8R)BO*=a1^kE%C4-hjh}8`ZJb!wJ9C0Sljkl` zheq5g*EJq!fY7wtz@PdfNN08d`U%zGIm+)uzva$I;{vYDA&IT%~DDZ%wM|#}pN} z;;%Py>XISkrF=P7ExD)J=xw}iegXS{8`YTqNM#%{pZl_ICdOf zyH1^T?_aTr9Z~bX^3us>OlrF^wzSyu@WO(ytrt%*nDiMn*44yl9>>mGb~{SRs(oI3 zgG)u*bsD2&`%&Ai)X6EdBxV9 z=^!n7;P6c&Bwh&kx)g;?-d>jj3TnvXY?Bb%do`HpsLa_!6{eoPoSd}pykGJE?dcxu zYx7uD4=VxVqo#T5&PDp1h_>{sHS@7%dHEadjb?Yffdre^+1u`S7Pi$GmP zY%eN$l27eN7xP9A#)_HWaspG-7_WjTHE@tLPWZc-YXMx>X zJ9%Fa;R>;ulUi6&=_|03$+cEI$LTD>@R5LPFCI|&ezhL3gbMP-L#P+p@bgq)jY8%Qb(&p1T{N8nCI-;K98N) zN2)GZW1A#~ooa_MF5E=EfRnaWZ)jht!NM#7?0Johh9gxa1aH3AadN=Q=g@Y^H}ynw zeCm|DC&SmL`N9;oewCRuWxhEt4kSRckO0<2G)|_b)%6PW#JDpp4y#1r; zjyQI;Nf6*Fq|vGP^COuy6~Pa+*1RTm*o!Q4_fATAF*@^=1p@xcZ$GO16lv+FzLWgz zVm@rl#gwRUZb(Kr`CfN5sY%ch0xg{p(VKJAM5FS{{6a$fj?0k{N zr?weU_1kr${RURT50_I6kx({TSlpkhuJ&kD`ikRt{p&Uu2VAFixz~ydt$gNTCI{cH zp~lY{7ZDRcOM}UE{%fW$J2*cSAV9j0|9!dn;McD(u%D|neE*J(BDK`I{RQoraxT?LS)pEit$5bv^-Mu zQG_r1??RN}87I!C8|17|6P=4mu0}0Nk(2J$z;FU4&N5Vw&lS~MHK zQ`uAkHd-`C#sXM@=h+d2-V0ziD>#EKvd&e(h>5!1#srUIrYOaLf zbXCRgP*Il0a>+_8234>>Y-`8f_-g{DxA62zDmc zj2p}BZm}9KOYjJ+%8x=iR|>_(TvlR^#>!@BQDx0Xj-ASqiZn!`^0q^QLDQY*-i5&F z-^G_XuScoiLf=rd*=Vx-$7`!%-+`A_V;c^8%1G7|KF98a2(hNi-QcIwF{{>`C8}?s z0$#d_tU$KYUbx=jvW+p9mRe;sA@SUPf9K;XQrXqf&j!j_%$-U&<(7-0;B`&OZ*l+> zXpI8dZ5J>R=I=!2FnC0aIfmFwG9+#Bp`adzDmdX1R8^z;ziA1i6MU;2lxv@9%O$JB z(J2y}QKLV5*^8NSrI5u811c`IqDa>L${6QxNQ^&A6?QaVctqUUML%recV;dtSL4Uh0=GpexH2}qqSar_QHU5%B%n`1tg~eKY462zUO5U9ktX12q-OBx9=)0In!S>}@0EjF_FTrf zh-~|~Tf4m2VZUFMb;u}D?r2vx89fFq%z~NSr!HRCiD^`+T)DYXZsF2?O*W)=I#OD) zQBJW=Fr=|0UN-78p16a@2VOs2aK0kvQY4pr_=g76ICBLEMw66363GH06J=1qmL)Tb zU~XgU?F8eq)YaQfx$=oLfz>4n0i1;JRz%19vE)QX_cJY=_U2&O#F??q2Q;)o;R~sO z-ZT`j6eZxl{IigkxpJ=l?_ub>rnegY^T=so9uRsNj6br`w>B4O+os)N{|Jriw`07K z4QdmNOx?Y+61pJF+X>Lye&lZ}6xkTrg+B<%x6^q@Or4S^Rcg(tt@g&hB!;(sR38cbdG^#R4bkU@m6s2H*=cXyZ2$eZ%0Gc615WdP`Oje3#FmI&f^}Vm-(iBtp!Boqv&%$ZR zW>ZdXevl)fq;WMHPnXAeXqa>o``fszmxOM@CBD()*@Sz0*jN5i9p-OjWaWsLh#L79 zX4{&3^ND_rcEmpJioT{U-)EE>oWINAoKx;eSs4KkdCQP~*FXhxkrLnAe|@+eXqiQg zhCf>ynCRSeQ4u_?G-Wfbdz*-uYR5_SJngFURWso;V}~b$$G!i4!o=R#XD&au01Kuz zmkOaFc^_!R_r2@-z4?M-p9|`_UMaCH8e;JUI{Tqdds#Aig*DjoJsxi!>ijuLQ`C`6 zShq@rJgTAxv(FRHT|@61@Bhtu`E5^_pBjIAfAM(P9@z_?ewp=j{WEnD>3?PLveo5( zae9+caeuBi#)eP4AS+ZK)#BnzL`EeT#w1 z8TIGHLJ`5Z6HFj?u1EB4p)z02{$4+^%)P0&qZ{Rtep#o6sN z3G?GHfenBhE(!g_wpQ-1jU{+eq0rFsM1J%RVp&tfERXyvB6cV_3}=8$UUVTT!`th- z#@X83>ND_Zds<#ep47V#{t+dORZJ9if9||%8n>%*c{&4Xs)sInlrh7BNS*Yxh#IUf zHr`Txs6P~BpLy24j0wdnAh=yqii}cp*poA)7@9NkvjR$oPclt!7HCWqT7e!`#uV>&DYNqS>%%P!#5|;KzEK($B5Ko+Mm+?adXkw0^A#{F6C6Cs zkyZ!I7sX&^PQk!|C2(xjYqF>f-t@^^o!N<~KUDTDuPCrk`C`St!Ffd~I)@ z2G8C!i&6AYP-$2syW3ZgHoLr-0R~+8Z z)b-s@7}xva>glM|buSJ1m=n$XbZ`+-*)pJGcMH5$ee!$32sn z$M`}mz**8ggC7W%Jvt;W_-=GU!d9*+AA?WCJnxL{UMOG4YE+9IV=yf7t_stA|CV5J z%>wFnf8P!3c-edZH6<{f&pFxq_R<#ZT!x`u;PTWnSzn0iG17Z6kKhbX+48QHAi?y` z(;@-z5sqlft{(d2D9QZvNkdRtgNB1xveu=kgTNE~6Y&$CeD3?>EQuugLPKG>Y0uD~ zZ7r~2yM1OyVKJ>Q99|y1~Ae!O@o|U!?gm44EmPT7J8(IGY zWO@=)oSFIn@_B(yOl|5c-E{+88?J5{m}EQNO;>GArQLe(I#P^WIDG zHTsvUU19N{Z9Sd;e%yUtG;0PXTUnz$`ns~Z{E7($KNw>x+$N|#v_0) zFo~?*Z>B})xL}4!Ie!jDYIPbHcHUtn{P>5!!z>KW}p&3-S5`x`;6SvQKvk(WB zQ=8CVXUlWPCn;(fFk=#+3cM9GOctBPJoe~!IFiE$X8V3Su^o~fHpe2hevvzp#e87B zu#>0+%X?e#vxqwE-V(qRir?|Nv40DVL6Z_KzIzlT=G89b6C*;|IvrCM%TI56EE5WB zzV4ZRj2um?b)-WD%bv|vqakGU#vK|u8A|}JbSVjL8Kn2BLp5`pyzU!p*BLe5&$z@3 zuh3MO6srSS%z7b{<8E?6v+Ms9IuO-aGhFr_Q|2dwWhE;Q7$@hZ3yi(a<@HyLu|Qk5 zT|9frqYHtqow@;c?zVYaEIfTD3=kM31cWzv zJXNmwHvp4%STsWwuZz<3w!#9pbJKx-$8vfUjZz$5Q15A>5gSUogj}?>=+f^jG}8Y9 zu1gD$*r*+nLj*5+A9BTE7efk5G+{ZoOGR=g6&o<2b3we44EY)#Ysb&`deh-Kb#a}B zcW=ccNy_4qq+K0HUQ)rpHhYzBDfX6a*F`wjx-^qJi;44n+O=o%*`#A8+GRV6Bnr0!B ziPw0@Ni%#V#&q2tNs!;4-rcFkkf|*;%CdJYQp&qr{A8i$_vAsdytwSGo%49XKdwd* zQKvT`s3F#Rqt68E@pknhOd1Elk{3_2L71v@2}pIph{^NjFmacWnXgU;W{9zpe~5PI zJ>auZgdkhHmhVxYbu1d(y^&(A;;bpiF3L)w_oUIHB$DV?RUABOgm~!s1Z+|8q}?6| zkO25wGce0Eah&W|7W=8YqCky9VakMU0uvBU22M-q9 zxuvLJwjXAlz7XcRPU`VAz({h}>w9#mTDTWSUIl8&i$V z+e7#s0&+zyFD+r@r69q%>cTjveKh8G5 z@^AKsPi{q<1nfnb58BWHDM%5OIZ}G;pV{HF&{SWBKaRl5x1+(wV3c)wIO#6{obx^c zyM2j%?|imKf0}=3MRxSSMxW@{Va$|yPWFT!R`2MEiX^W4>?@R`VPvXBKki4;?qkAX zi2yI}`_<#=;UMPy@2*IuPUs3us)5f_swp6 z%^9JJAR~0|3Qv%cQTze$q%dA3En7J+FHv7P7Lga{k5qMxF-zOJXqo3KUL``DurNHM6=%jYBmlpsf?8*^s8 z0HfGbdFKUWG##N?gO^zZP(Fi8lD>;-cyXTXvE18l*^14t6&Mc&>yax@$d-phd&VQ9?j+w{XEFcCVlw- zK!y_LI3P2q%`zUYEeQ!2Y|F5=moBlRVieT-cFID?K{_vv@!)bAM-y2 zx=^_S-hU*zjG$n^J3L#%X=)E_bO8zJtnIoq&gwpVc2(a(RR|%SDn)4jE;Xg6@w1z` z2v?I$R)Sm8mk-|=WuO0}V7Eew{=tDZnGX(`Eh&oic&q34)_06LA&iQ#T7=Dut@!PB zW6cdT%qW3md`A{^9)?r|Ur5*8~&Pbzpv&=j-7kYV`wLQALYZ+e# zTrI{q_4}UYaPy;4wXp*Q2LH2#cy@6~lsrX7r}JIT{oGRugZVJEg7nAf&qNFlb2`u( z0K@~IxP%Y|$2j<7g4mTT6imkbQn>|>g363a!9Z(3B@C~@JCKNnP zazfj>hA1J9j*yM)ivd;BP8=Gi#6gQS0GD;5^ z8+%3?L5(h5HU=|-CMi&CHl#uVmZcJq8|91GNKcv$T$HGSONuXn>^G?ym1=mMmRaC9 z{RZ@!Z=XDWTG}70qXXn^b(IrB+YR|8%c3$c!oTd}P#x6VXnwkn&m(;opIhOK?ev)I zHk1^l5(2v4suIB)FIDpPbUQx(iXCi* zK7&@>l{@)d$?5|SMs^+}wP_Ni34HZ|!ahV;2d+$%tFDp<5{UJ^z_>@l%4dn9O&K8+ zbbakrfR` zM!>5Li7LKUE{Fz3=mcyVaX=U@dIP3!hOHN2A(^YUdUHtw`Ni-m`}alFH|_t3iO88p zWmCKb#Q)&Dnyau9c`g*O7GcW}zE+P7t@<==E1yt_H9tzlSaRJ1d zzSxeMsNk{2yXexB)yD9qiPrG;FI&dh^iQ@oW@x-^RI-z6#ygQ|T~~H1n^BqY`~6jH zw5>Zme4hTJ{%E}WANY7!`)r{%D@Ff4U>2aX9%nuAFq5gWjXS&BDJ@VI(opy%!*xQuFi+j#L@Fju1AoO4iyC(E~>k zeNghFA~m7flpb3{-)o2zGp${MPDXDI?_+4^%CDG8*^>u7=cFbU7i4}1GV?@fpp2+b zFz3Mijd1$`)NKO`x;Zwi_o&Z#!zxElUB{dvj_A|5`U}j3nnuUY1ZFSZzIwfeck=YE zg-z_tCvv+rJkgd_h6Q#%egqZ%QT~fEzO`s}bRYqpy#O>b&wc0CPX3LIG8706*8@F| zUEBn(ChGiCZgUZaJ*M*!IH+JQk!tvA_>(qngR8$be*u)nO3-#x>cn&hB271Y_65r- z?COIT?m_Ld_JVQGpJML6*@i74(~;@cT;??gG8;Y(B6D6+4RKr~A0;ZpD!%tPiBZMP zBi4Ku3M4_95O-bdCHAly2rAHG>CV3W_T zPWOmpN*7-)QH^Ks85GDM@iK63lL8U7`$9@l;^w^Y{=VW7#@Ql z2?fOsdCQD#kJom$4+1pe@SxWC8C?_KtXs7b>Uv!Wd`1hpC;{<8Cb`Cxo;}lb_KxnW zf3nGXOc92SWtStXsk5?M@+Z;e&vM%*Gbt)#6cokwH$}_8vsPB0@J5JY` z-0*DhF6a6_dJBfU$%h08<{CTRRN49SxQ*q9LR44eqiY^2Dv$c|8%sPseXw@3bXd;6 zQhU2?LbKE!?57kdQ?aDmr1#-!$`poR*AwUST-@Rq@4b9K$3ZPi=eqbH^7bew!$1>j z4TfR#;f;~(Llh^=J7=(omAs;Z9q@B#SDhL6x4{_ zLrJZ{3Z(h6EczL@s(kLj_;vCjEqfYzSc3jcSm392M~6UL3C9s6E#}xz;Wx*tRadd`~0jg3<4*skj|OX1LwwJkcm$?w#;m=e68`8$L&WEai}dZt?=$BF`Nto1m?~v791Dg zGre0R@CXDUCcHEm7{Jsq+T5)A&%9oPr@=Jq9w+!w(V_C9TupU<8~@JZIT8ZQ;q*HCL}*MMV4|68%0=-CyH_Rifgd9 z8mX}HiV`^QOXio}pYMzCp#f+iy~}0Hp$P!V4??Mn&Td~ciAq*WjS9rbl*PqeGJf5C zT8X=EDiWC5UVi(PY#qg#V8yMN=$-LXH}5^K~>k z07MzCC115t=z5+wH#T7`W`mqi@{B!&h>C+a?2Dur0VT)3);NT$JeoM+tp;TCmyr9; zb?>|BPo-=Qu0QS!E(-aUG2TXU6ma<~%%ZivE3%Y^%;CbQ3?9|(Xj~JJmoF*5+ zMORwG!}&ubILz(bT)0unc_Xxhcv76nS`a0y8NT>m0XF7$EKsay+gR5q)#ae17|OHJ6_9FAQHGO83j=Q5*^&qI9g$4Z7NdyX<;TF zVK20QtEa8Da4GJ7ZZ+D4q7q)gZ|0adEpbm463zK7Vv`W7~2^7M0#W z{2&(RUE}jtZ1AD^!Qcs@yh5b%^!hK<+%H+mt*M&XxPDg&M`GsjGM)9bXpuL`e!$_L zDWlRP7x#yTe9ezR#@owh>91A`jo2tqag+}pZ77|hzH&#Xqn%Q)=Knd_OOz*D9Hy-&Z;kqRcD;n3!+AyBw~+Gs+X{SNLv zJ5juO)VS&BW$o*u0R1`+ijt&Z<|5DW*`RdG*S|g!;w>%I_MP*#RmH`VX@54uQ#U7q z`X7hQ_=*}G=kk-fVeP|`;n+N8v5e-sh9U)dYQoMYh+EkJ2|#S8 zB15ai*1g6ixNtJwXlr)0;e*l#jSpaL#f5*0fFLO1Ixp#0Pad$?M1ePkd=cU&3 zsbHCDj^;Ip*NQY?w-0J*&)CmimHOKC7~QIVn36MHfU}CoXpUUb5s z3t^~30aL|exG556!h@N)_)yT4BdO957=@;LZ|Q4DBWDXRvn%<0)8IxziYX0;e~;1C zOk;f$#Dkx1*?bzVgnd5g4XqKc(QeNH2^*@wVn#MFRnVaG;%F*(nCC_aM9&|uw5EXq z%0!?Jmezd~sa>a^ptO+R2u7aTw{^;7WDAIg<8X0-;9ODCuSYa)O5-imqC!gqHXlKB z>zk1c0#c4Y*P^XoI(Rcv{)>DnZQiv&?;p&`<&JyJ8T8J95B;UD)HdDm?tL(Qq1%C% z;UkuqcawxHZi6K|dEEn1_TXwAPx22B=9-*QRuLmr+J>5wauVdJH+WoQCiG2s|IX7jo6y!?;vaqHO_9Opz_s=3OhAgKU)$s3MexZkzD9J?oBdkodw!IG6Z*J z9v^2S^}r2=hmqim22^F70a(Wt{MjOgoa;RO_1*0x7?l+zEdw6>h^8>ls;j40l?LQR zJddY|NiW+!+V*6hE{dz+=X;q3-5kxt=&s1ObaBYSlzZS38i2Hljd4DSrBrT*W*7cB zADViLWL}gwRg05atO$Bl`laP;FoT-RpUs%XeLui|FLsng@r=tEB6I7JJHWfP*qt?l>zu^84Ct{%E zCQ2)@eM^!mv}^@&sFjqC&5Vh=qEHxQF?X~jUe98U9G%W$b9eU?oEJNz_cag(Wvp#B z+;9^;n$lR_cx86a=)_Jtrd?2QrF=3qv~_;GCtZk#g!k>r)8`K)EM_&X*vdEO1KLwnb_CnB=xiM3niS7qJnID23ci$o4K+HHJ55S@^L zV9R5cxlM=fOW3KXreptqsWZlwAAMXsGx;jq492*wYqTB~xJ=Kmc95M1{^&APcyFGk zjn?T0gr$NfE<+;V5a>&yV_WT1w7($|gQJk~NfoU~VF8iM?|5B6X7dU6vL><)*uv>( z|2ivLGw#?^2;Z4`zjn1Rxrgjv)_9o_d_^ZhfvZo$xU%4r7Ii?;m29^<^wXEMUD4PL zPVXU{jITJft4+D|0Dpn(;Xkb8`=06vu95D8kA-w)t3em^&&nv#E3eg#_96UZE z05xA@w|%Qt_Q6Mp4jrkx=1-@tR#- z;1%UaRqQ;c+DVz>x$|R|{_(x%CN4%xVbiO<0=*}9i8g{$T1O)YMUpl%E8Ptlql)I> z#gqXSOy-FK_Ir5#FQaAVO`cbPl}2$WD62Q5e|y5Mb^*igUp>)=WJrJUB?B`q>DiG_ zZe%$0Q62EsmrSbaTcMif>pzSr?a~(!j@;-F*+_?;-6ZPM^7<>?=vW|yQ+!lldiQ~m zxv${aJVgknRv4Yg2%ob+$l04we;ZLK)&-@`02e-kBVkJzlGl#w82u9v30u^6eiYT; zklTjO{Q^~7`Ua359@BvG$&HeesZ>AK2d$1*PZU0(&87$@G}l zNQbrQFJXYxxNU7EZGbHgfU{a@;sh130sq7V&li$~&Jb(sWgx~r%{T+NQOZR!8p zk81oU(W8=C_WQCLet*0vC<`=;&bk%@rF0A1eR6eMseHoKZ~UMCF3-~@7$W&6G28l| zlbzg=($-kc1nxE(f-5bkM+=WoRd@$Lbq(3Bd}!DXPe!&z~*)v4v+WVazkJR|194=31utqiRew(@`o+$N08gKeM$za(RRQWU$0M; zwqSk;D(kQo&K#3TUg|0}LiZ4JY>O848Q8tuB#O>n@E0S^)2G|DoWL}>X!-;PP@L*} z%kPK|R%`YK(aLftkw-`b9as}m%G#&Kh*UzmV zjcvY%$b~oueL#*O@Y{9_pwRou4un*tbsIqJp^M+}Uot?1faAf8Heg>w!)e#K`d7HEBS@2|o$0G}_2^v$ zjYoZZF^E=gMFZKaOO1uQQq3Vsz)taJ=7Ydk>5pF9Pu^D=cZdPjN+0MoldVi=5R?%& ziWLLoVV@~H62PEuqcLvPyxS!TZ}(@*0@t%Pu2F?y$7cetASa%KBYUQ|f8Ks8`8fn^ zl42%Aubmd=kn{!KI<|U8$v!G9d=#y;eIV#h2*_j@ z#v3Ut2ob~#|9xqxK%MrBWdtrJ5eNL}Pml02}KG`UA6l9a5|+QS;o--^VVW#;w{^w_32Ml^%R5eb)8okN^Gu< zhclbRYwWkZDFr7nfmP376tj}~jQ6|E#_(qiUj1iVuRHVPWX}*$lPpuR1q9JRHfH=L z#*sNsMRBc2ovA4-8$~pNd2`Jq(+hPGqD)HBOd^i;EKSS3A8R}_WnV+J1HXSB^|4QM zRf9TIB{T-yzdOdew?p4ZB8&sA^bpeT**G4H|FzNw*oY|6c0Jr!#(&YV0L?s?&?XCq zp=j%K$6$x__9;X*mZZ*}{4bjFTB8V!1#K@cmGe&J^b@)0@YAT4@p3LJ4CFKal{a#d zBF?BJgfxl!Q7{~F^Gje@!gL$+!9td|Wpa!7n&<{k>%&(anO8*X`a3cdT@oESj5xQq z+udUlEhFtvd|UoXPT~ojbRVDR8NQ}}eoQ+|Gub2p5Ww}) zWb=69=gT657k?hl*Uns}jP|Vi;ty&K|Jcke$&z)-2V` z4dApl2ytgP;`0y&@_Q{IK=f?(v#Ec4ot`l8G^j$V%(*K<)NMc2WEM;zG}{=W5rcSN z&IPT$6>WBAOv>ZSV`v%8iK2l2Mr-Yf3()`yxQ-&dEo|7h4~&G<>D;N05DxdtUl)z}(fj<9o^Kzq|O~;S}8h1kobSK-Hv`$my0UEG5Ud-#nH9kO0L(T4cit^c>_pK#q@XA5U8KAIJhqCoNoDsNU-B_~Gs;R}K9fYvvldj2)83?l7L z13dk|D$8CS1W?hMuw)0Xe#}&Jd+P(Cr*d1dvsoFB}|f|0pM@Izh1O zCCj#h$j#Hx)7;~~p}eq|Ng4o_#RO7*+1!<8Mw5B)pB@sNo{P_sOq(g&Gt%oQ%!T>f zp=Xj1&d0)2`<6k4Pg-QgY_1q#xVGG=r&$CgXmIqCa$^rSswsXB_CsA$~JH z-C#5%h>|o;X6i9bNRSL?Elg?aF*4$UQa@jL`*GIH(U{$i;!%-<^&Z>bK|R~Et|L?= z_qPjuE=j&YVP&2m{qBCkKTKe`0;<-4k`p3Ym!|&aOfgP-J+$HURKAW)Lf!KzRiglg z6=M1AxG-A}xkmdW1>466C6?hj+x0V@3!un%7JNi@(=cbxmsX5;+eIlWr3pQIYGq|k znSrHj-m2?7Gd7fxf@(V`;@pLk!=ENIBOu;&VAStggZ^EWc456${SaV@N~D`F%A&t$8??`8}Ej#3y|-Bt$F=amOHN zT{#i`rN02wP1)@~wnSo>z}YDMkQy0j)Xb8>c<07nc)yLmgNJ!ZNSYU3wGl?M9$q}N z+>#voGX#0QW@smdh0&r(G0N@ls**MHE7BUDrXlHfM5}mGBZdm@OM`p+u{v>&-#6T0Rq9*F)o0 z(q3u~KC(p2S2+XTs)1~hg0HB73}0Rl$MwEJV?RNI z=AFK@BiZE1N~O(_)rhB=Qw3TTCigFh5+E0GsXQfJ&>}}%^AR4_Gy1T(Gx>KKb}QY( zk|e8Wyc@^7Z@7JeR9~rWbIznA8J)DX-%gmQsWU5Vs`3*bH&$qZ6=34+tmo^07qsi3 zR-kHFm!-FDsE_yX51?_)hkIOBd{D2RM+B^MV=;&L&+yKdY9ZWMq`D6dc~Aan-U&pj z)pT+;RqL7Ochl}Q`{ZAg^G&3_e8DGGDk=|bK+|IUK;&VJQ%g;RciI2m?cd!O1k-M1 zj57>&GAuonZShcQ4YD+gS4>g9k#`!a$H)lZkY$*$i0^j2v8Z>6x_hIcH#(&J)koCXbP!Visii9K=2`Zi*CCL>fBCWuw3pl=L zZ68#wogQ^vUlrMnLlysH$1f1t15);OU_e0X+zfdhhs4qndqWgyFzlaXj=kOG7XRG{Z8+%=$r_$MMBSp`e*`L=r$AWfa2r&)UaGF|LkjGdeC z8se9S0=xwAVFX0fMf*KM;V!DQ%xzxKh&~by0GVr{2$ompDgVRT z{;D7UyM0cE=l*!&Z@H~fDbuN7H9UocsvOOiAr)jVrP_L2mjeAP#`n3H5q{FE%hSm? z5r~4qfm+{;E=A`=%5{ePS0&r4L;q93leaF(!XIXldHq+GkxY%sHD3zxKq^|<_f40q zh9Qc^<62h(2UVHrvPHRaJ`Us#5?OLn?YL1@d#NfQmv?`5Glb*)Fc=#gd9SMDRe;n3 zQ+51)hv=f@*W4AJhH%qu{9^3>90$;lm`ikN^!NLR0L(bsk@wcS-4R@4knxX^#S{;+ zg1F@SW$&6@>NGuUk^9H72@Xk!zkipEO??Mfn7zJ%fo^U^6=+z&Q~O-m@_@9lwO{xP z^|J@}eH9lJz4aQT$O0RRLg0`y5}Buo4-fk6zrZ4NWT(m~6E`>+BY(Q>$yJPfOn*K5 zGenENHo+=Tr=*R61UX%CJ7N&&fDlQ6P_1YdB6}}Qm>@0;?LUgX+3(e25p|rXY?p9?BvNkYzcTz!HrL+?92V zBs3jJ-$~hF6N5*3I%00*sUd|EjgU1eTI$!$3OIvg0bT!GG;ZL)tU@SwCw#!i0QX+b zZ;=fTIwPz>Ekh!AGabDyN>3<2YW*v4R$*}ykmZ!2au!l~LCZ_yAxahef^~W|pPFfX zf)KHn5+qcEESiOZvDXR~P}%j*M*>hj`TKR<=?$-INm+%lQ-L@3queUc11~0>nH(o2 z4o9aO>PLGonn~li;=oI)Day1ag1dG+84~Ql)iBHEwk4LS%i*YlWD~_KTRn3OlRuMA z_QMc6*i3dA21E$Kc1R0JeN^phfaIU=wP*FiMtMkN=g+?iF>P56R3}=iT~1_Yb5ubI ztt{TjeC1oCjngyAM4_F7f;G38GI6BY`wo;keDwv~({?+W=M7wfq$(&emCGO?0eJe; zX6)bBb3+))&26WbS4fO-fm|=uZyC(~_4w<6P6s~;#K=c=MhgsiHd?8Tb%MZ) z%*Z80GM0F@7d^`?Gs!)0I)F>17|&!334DdxO?WHlQ4L2ppwf)tPFK*d1IHmJD8&-WMh_@xaRG@#nnX= z)p{J*#(=9xOTfg242sxd$$u%{ADnl0#~lF)EGb>E%J|*ZvYOJeeM*yNZ?u|h8Yk~C zYnZc+N$VZuB`O0caRX*Yn1>K}-LMwzYcN5w5yw|72U?w#}k zRmsp5T6mM@_PV|Fi5N?mXO$BqKu(e#PZ@L9>vk)EW+t8+#k%dyYvQ8rxC)BVYoUyX zXZ~FDX+i+yA1_vSN5GRoB(bo!Gg`R}9dK`L^)ttq-wCF<7z?A7IBaV~udr_><)*cJ z83LiGR9>09Udfl~7J~m-v5+mrvgGp4g!E`OR1~i&xuF|fSP!~oV!6o(xWstigq5Pw zWJM^3rXfGTCM12cfO^`e*v6~Cc&8K)FR?EOZb*F7FTvLVM}}Vc(@923O_xEWqdLN(Fm#zKQ}`eKKyKXe8{7IqDJ8oax{5L8L$q`d(_zjMt_}lCob_5 zr8C@fI)2NehQO<{6qzjVz7hav{&lK`@O3J`j_RoY7|vE(>UaoHr|j_3b!s}Zo##!y z=dH&%e_yLp_rwF!|H6X+u@$%6z<&{V^S=v z8Q$hiE1Oh3LbZvInbvc^7YRjbgKY?us_IwR#YZl_jQuD2k^Exl&HO^DlMP9n1&i;) zA$PcgPz=xnPAxM>cFgZ@f}`@(o6dO-i5sbTXn8ADvojrbq1u^n6dAPw?}$@IYM3*= zXNF*2B^48391cKYw&B=wx>5_V?GxasO-}Wk?{P)jwthv)(Oi{eaQgM6qZ|*fQ+Igz zU^J5|vB(QB-6>F8{Xhcin?$LU%@fckNmr@BPJX~JGp$VeZMBSzYsm=)O6b#EXgaWr z`McA9T>=gyC);cNd7rnxzz&|#jXoU_^;4jZkJ^KOxsT7NttmS1GR&^MU=p-z_)`6g z8l~ICZ~4=M8f6NFVzPNTPgSly775iBamyk)isopCmYnU({P7jWkAsfGd^{XeG!o3+ zP)$d7%ZgvlZ_P5c9DE;>VLSVVFBz+pC<=Uyk=uF7{>c#TaVTP9 zDl+qM1Cj#2CQtt`_sD%shAymZgl{cD#E@ALM^nz6LZzI}6S zg3Xed7wPo2Kq={?M6V(@7KCQxW;a(uR^WV^-pZs;vevTHI#IqJ)IvQnYH!M}sc^V! zOrY=|TyWtChz=RmsF$*onx+=VgAu{X#_}z9o^o+3`VSzF#9`M?%~fI;@co>KfXgz) zG`$0oquE175NMlV>kkhVK=DvS_J8MTvAgI z;kkV_McstVz^D1GcENHcI?II;V98w|5f2yaML^Yoj~)dplbZ^*EPKsZc*)~*%}Fsn zd^TkJ+>(5%t>DaDv_sC3{agG zcFfWI32}j&a5M}Leg~|bZea!p# zP>gOdB3?S;mG97;=^kmt+3Ho} zQlRDk=)c6=F10|P+C;MMna0oVc(U_S4!h-Ems^{!FJo(`)DspFG2h&H;fYbPmjG+o z*!G?S-)lvXC&UY-ezI3vn#d9W)x0IL{i)prZ%08En2YOOrj$sKJR+rk$(zv(Pf6F{ zSMh7YHxt^uZgC<%U|D7axfxjVi1Q!ItXrn>FupNgm|KD)Tl0x$!f?e(_v?KeEtbZ$ z;Zwx9EIhX;Bc}yf{ygu6B(nE5u*r^i5C3po1J&Fms;;S(doiJnJgS#di>sl4priPJ zKSTl&T0#mYXmA0+CEjok)Pv#IsXUc^B(!h|Qw3X}yIa*#wFQo@)a*exB5tgMhs$bf zA8@3z{k>#8uAA3POQJNN%;Z^5$uXTBY zc&Xd8nq^(-NC!Ds(N*K*ne|xt)PS`vugmSprPcDKBgsX~k*1>w0*Vd2N1D}Z+t03m zFZQm>KRVs-?UqA0V?pIWvG>WhCGr=c?FJU_DfbgcQ8r<|&ygm7@1%_B}e05)a zce*KWWXPZa_-aO?Mh1%o4MCx#g@W|vi`mPoL!xdM<(@R){45Ma;w%_N+ggojNK7C; zqb5wrP=!~JDEvjre)WqniyFd`pg=J$NL_t-YRi+r%i2#4ZN-c@5S`$OOcGtU zcL-KQWb<$Q9?v1aisrcLs25bGq*CzSi*U={g5Kbz`1H$Ov5&t@Lm z#ZzhvT!q4d9y#laT215%QJ29-umZCYj=PePo}P{iD8~^~CO?O@m1c z)5zTqAbCVGXzGXxs)z8M=r_a~SIK3S=Sor}g36W{4bB(AA9%=of>lBdfi`G$t^B0Z zGO`P;dEn4m%+C$n0fUzJUGSIl&~&%g3L3|RybA;3Rfv_A#F&V`116_qVVcI3KXZzj z5m9B|cPxhh%-otrv|B59-@leqtKTl+9D3M}b&(#8*XKAbz|Awto6NBlbg`_Z2nLyw zp;82`Aay&DnhJ0UP{6f#H&1D9C%}=^C?rclMYkaE0L1%CjrTkICBcjsjFJ0EZ;`wyEFf(i%26G1E_av_OwLvW;g2*UCXQ4@C#@K#M{S`x>7ioWWOW&>%3S07f_no zR&SwB`Ck&He0gyL{R(OBG0r}y&KxjfD1o!?H%On?3Wh%5dn zk9B)ADW&g66St9B890P?Y<5}9!%9m>W1&0Og0}tl8x7yNAjZUk9eFxS>)#9d_M*1alZC+nq{%PN_c;m;3LJ9EIU7xd9~@B3*;4&4go0pdnV^93^t+1q zfw~8NOoW_dW{BaDmFRgrA0OQr{+tpC{tdmc4l5U}yue1BVmQ)B`VJkF@-f{c{e(V4 ztqLKrZ2)VoW()aBmUCC;1LcJzKKL@X3rJ}pUuKHV5XBJs!Exj_@>TptCWmC90IeAU zm=*F7=Hp)e-aoT&OdnQ)%(vatrzq^CvsaQuEBg@V))t5yJu)JQEYDOekZO7LXna@< zkOky)8*5E%%GQ1lCR8FC%Y`fwp}2!w!#XtUEv)5?@|lbTgupE2A@tr73(0E%tm{&m06j~_p8T?xIgz# z`G%srwXaI-+%9G$hA8**-C5UMtAEO^;ij8`(bho&v-`ixv9)as0ct@Ivmt>nV^Fl> zEN&hfA}EJ=!5p5cf9!{)gRSJWEIssy-GPc0WDN1ohbl74le-4L2q;$0^XBwv=Rkx$ zCA3A|%^$xQZXfQ#6im(hD|yDv)pjUGvqGg+b?|Ci#?r^WArr7mNS&&?$xQ_&U!fN> zT&zlQ<8iivi(ho9mV}J|zZPJ2tgX#}h3*6~bitoOZVEzHu=RtLhg$2K&O~NJV8lSZ zYq8bYr8MQ8C34^f>D|W7O|xfs?c$A!V-xTI<;eUf-^;j9^FHY zTevnTCI$;P7X)#@5wd$TYCV6c)+={rE7J|_@nDHh=}f--$^1E#9sVHtwBzL=1YDpG zm>_xC>aFD$#e!to%)6|zjrPQfl=ZUXbSF5laW4T)6^*SNJ(y4hYU>{yH>#qBY(L9o z_!h%ck!C%?!O?SBfGxZWH@Jw__pREi2!9htgQKXLlGUVMG`}-xEjOh=oLfcj(u!j1 zA03tOxlYun!KxEpN*G+I!RZOfHNOp-ONoi*R&D?jnr4Cnket=kHZ~!PIng~qH zeomF(F@$$c4xiL#cYTswQW+*$J!&F?1k3N60-k_4d3)pzi!7`^j)}^#^$PX4PTxhfgGR7TuZ$%AY5y3${tNJpOW?PF0 zX>Ouc`H9}}L}La2vn{m3(3>LIXy~xUEJq@`*5Ekmqk?KC)s@(o+!rx+Rp1&*ty<9G zqUNgRfV@#e{uHpDqksh!pa@eS1St}x|LxW7JGSBTETq3`O6gc!mS%7z&+z{JY$}qO zD&HZ~GvAFjNwM#9zr9)OwDn@9De3jH1rD0y0||5(%;7^~`jZ?rRd_!<)^zJ(Le)E> zZty2~lhxmzuO4uJnLI;vP3^$IKOTm6w>35*BfDEhJWbX2`I(iWVZ#{kQ2xNbt@6GN z60tS62a`QiEcH49a@m1{GQIM$q9Pb{@o0nIsH2h?{*v)SH?iY)wRx_*n1ADco0BUm zeOUVybmKg3+qgJQ|Ir48*OiaaKwM|3ub`8GhiphIJm#g=$}vc9C`vB-Cve1DzA>@0 z9d59riblDVnQ4sMZ9I5}E{sGIJ6cfoJf4+C4ep_AaI_{pE(@qh5kVeH)6(5qLeL24 z^JjiX}4n5O5 zF8hz-fe{>ZrS)Xgj^ZL-EPHN=hUf~9ebKehlC~3u=AAVPN}lowbkKm8)i4FRXAFry z6)*CNhb*)&VKqArnrf3t1uBXfJLc6$!d6<(vy>0FO%vXbWz`Dr>ll25+;4=O+90#m zhOnA;gad@gmw$}A!Azk z*vP(-tPpM8JVm;xvRgat9!Z``5vyL;~V%>}Lt`2T)O z;8740#atEDlafIA??+>3Mb`sXcw=5`a=Fb(HyBUk%~K5Zq3IS3l2Du{r9xzg5@qsK zT>PX5?VC0Kzybk{%q`LMSeJTk{CF`%l!!3Lf2mC$e)=*Zl*Ik6p)$>@Eek($7jP zF7wfS{9aZNT=psB4<`U{0ex9PVap*)&~oTOQfYVkLepO1{-cDbkmw%f*K*;E`jn1c z&waVWC9pGce42WMo%)WE?a&ihPn6x#_yLiOlzSNl$WzBX-PB?Is$ee~p^?H$J+HpH zepid3^=Qr20<^AC^Tr3tc-Ty`VLwAqaW?IWYN&!YdN@*wtf&yUWmoWDl{KZJ`RP4wv!*2_X)^5aMy`^Z>OOg{hqp?YEn{U7`K+ zXM{oKl7J)U$bv(WO)adEmnIe665^c0k&v%PutA3`X}|8BRKFFKO{b=%roJ`jKkFFS zyHFGFr=bAavy)M&Z=jQ+z0M$_5wFvwM^s%S39&j`Cuk&-yd^{rl#u>>W=S&sS$lH# z{?c}lvS>QLf6@R00&?na(r`COUK)2D#=d_?dc~^;f>#VIgG^0<$yug)e0ga*(hM`W zbG;DAEcBv0?wVbTuQut91Z$FwArh|=!#OLNy*s7Z*2D2OoziO=Evz16TuIn|4-kxZ z&m);g(%9!QZW1kV6vCUN*EMIGKrsAdn-&L&%f}|5tS&P{q-Egf9@I!fpoXA5=kykk zxu5@Bk#ZA;$r=(f*>o1Z`0ut%ySq^gMwru;?ZP`q1jFpMK3j&3pvYVe*#2;E`PP#R zpnz0rAw&SRV~&zScsPHylu*y~6)TA5>p|G3nHh1*E#>pieL%HuryI?V-M69(E53=8 z1NFl$&F7O=FyGIrp~863+s!&N1mYG@238RFPL8mDz4)eLUa-hw9^j?+&>h>V(FXj42rH!IW@^wP3=b2;=KHEZ%%{^!_8+Rr%sZdS5&9Mhips+lKB% zHVw|sWCQ3(O|?}o!fMWx`;JB{wD3xWS6kcJ?$OV`_#pto7fY>^j?vI#{8bkmq!nFP zP$)0J>DqK(bgeDoE>?8?xRgoe`_a5Me^<7sR@sH0t!yq94B84ZG#qcWeR$}scJ6>b zdzzz6tSJ0vC88k*c5K90XwPzL^D90c78>A_k8patF2}bN7GT`v#!7;a%A;RKy{;px zq6X)E=HK?%(?SxYHAhwZbJbT1McLbztvCDQGv%^BLqf)~t6h)3c=M4AW=ZnqqA(9N z6yRyNg+sTLuCI64Jy^*@a!`Jlg;A(?2;Sh9cm9AB^V%ZQS?ngb>b#TmO2=#_=6c73L(E`Oa%h(ti?cQu}S*t^Xfd0R}~P8kjE?9caMP9Stt3&f#UUS&JJf;EyqVI#nmb z13y}iBrT-JYyFMu*O|}E8P5wI5$To$6p24l5-F`-d`$(DNvxJp$DITNW@FOp7V-&WTL*4`HrJcXpZNi zY#ECD-NWB*=9M?{*J0N1r-TNi6?x$TJ z1%o2#H}-=AwMzo~bxMsYB^X(M-7frOJvB$xTyv6^CjoS!&tvla)t6Y`nO?cb84~3) zc4}Gc9@Ue>6V$Ati5a9jtvQYSV- za7pR*ICJ~MK9yEEE=f@=a5ts!wDh5q$M1@23VDyReP``(_3|pD@`Qv#GV_Ho^^0y& zA`nW?UVCAsIx0$2Q!;Bxl#F8{oOcT3{!p;2dp-76_T*E1lkrVL1I0evqp#F0b}tnv zJe5V$lkXFC5{yuD&9BrP9`_fz>abvGxx-t4i_C6!Yh5ST&f9!)qZlvIWwCc1ZwS(f z_}8$?l1gu^tccx#j(T@CZ0Iln15#{l8RA!e42h^Z?WnMF6l$F0%AD&GiESxhF)1Og zFJ;g}i~OFYu&?qS;>Y+&qZU+9S?6b3_l;8sCc^=Gd?w8PQAa`Y zcQ@E%OiNg!&0~$nO)R|j!e)?XX`i@fU0!-a9}spHqTNYZ-u68EyC%q0#t{Ng?<)i-z0ln4Tk6`X!-`{h^ZJ@AuWE4ZOtK8Gf?{uj{Dv|4pOHxT+x zxh!mkw3MZ1;^=;};@Lhui+np7>P!&b{!1_sfY__xLm>#XO(r^%^^8beOenOrcs{N%wfQQzc1iEwS~k`E0x*-x{AodxhKZ zm5%PuwtC*U(ejQ2rC*2wwO~%O@*%!SP`;xxZO%9pbxU}V2}sKr}cg}kFH!6Xe4vr|MNR-sQ@KAmmz zeR_8z8&&Z>qcmMI_od5Y3uKH^?uw6jeBK{4zf$hp*4#&FYtY1LTE^MJ?k7@Xn91Gc zBOVKZ5t{N2YKwwaeA-D!tN0Z|fTt>bK*bLPk=N{Jw$9UCUnu4~ICc@<#TwGhEf0be zM2I1t!Gyr#D?Y>dy`z30R(X!-LPK{Osa_$*GZ?Dailx!~^8z6&E=s7vd~>q4??-iS zJeAO#0tEpbrTmhTBGK7xoOH!i*@dUan*e*t!ur>5Jfy9+`S8WF*008>Iky|2TRWLP z%moQtfK?OkN+SXJT?}SX45rS#cML^lN3-nh6HKirpeYehTRIg(0YA zrL~1!yShO#9cfAHEX^zKA2ev|vOYrK0Gb^)lfn&#q!uYhS+tI^$C!&$uBfTcQJx~sJKY`5ynt;Bs9We zg^VCWO(H(-XR>QG_6hjTl^6~Zc+V+Duyqm$#O8G+PfGWC!0z{)}nx_`XV$;0JaEyS*lFkQj!CjoYmd@J?Jvwt?6uG?L%i8UOuG7JAosY*$Fy(EPpQys&0 zdheX+x=QZY8RNhOMQT({O55PbUfd=NXKwbV)J^%9qo~+&NT~${xs{vBgl_4d^^;S* zi5OTBv?|>rlfqC6(*^^DAd1c3uHZe%cMx|ByA0u9q|wdp6%t9X{C`wGNp!byc;^3eBLg zK0VkEigCNCNWn{+B78lVCZ9i~i22W0$qC$F_TbQfiuF`nJo4&m)r7_U%w`DGv*_r` zje;V^Fg{qi?o-aoSrylmmVpJEW7K;zKc$#KrSu(dyjNCQqzM}EbvEvs(}AEBSY|uO z^hwOXw&pAW5muH8&eI%rlF&VUgk1SrAnQUcYq_#U6KOzUuBR=xB5Yv=$+{_KlZ#s? z-^t|Cp~a@O2&J9#zNjC(BDwLOHX7&kK)9BVqxmtkPlnHH4j|HKX+*lU%}uoeBW+@y zN%T6ZW!m^eW@%YNE;?%5ly(WEeg;J)Tn<9xA>8}dVhrNlpjHtk1oSW6DUHiNm!CSc zWp?A6ED#%zRyL#l{)Mdeg7qSgb5%a->c(V2<{;3zqO_(V0!C{2v6=Aw`I4gkof&Kd z1@my@HMHU5D{BN`NBNp{li?81Lw^&;L;z0=6N|5Ju@WxNvGwz6H}AUlhGCmX!kDUF zGF(r0d@dgcIb;&|vER;^3@YvEEDt6ggw1 z0fo!X<<+eT)Z|fSI3fiNCH>MRE(U+sj-dk(#Rw+yrH=sgU)*&5iAm%6%?P&x09dcg zI=X{~cB=c?s;6kRqS4JdV=hNGRF%TjWZSHQbxvwhpAHFhl)(8bs?h*%lp;r~^PWL7 z5Y>g>Qc94lLW!4l(8_B-0(af|ZOtdi{}TRkJuyjPP(!uc40x2O$fII=M+-648W5bC zmMR(l+)n+wX~<8058@`wx^xk7#wA@F^TZiTWeGagjI52*KRa_xJRXoPGC67aJkUX3 zDbKan1Z3f|GjLdKEW`i%)V-9YvRO_o9s$7pvXPO@Sf@9_PqgRjo!^Fo&kt=ODwE6_R zXe-#iw_dJ%^22@aq=fy>Zy(ZeJ+>|u$CyL36alg;o;M?uFOaM}r9GEK>DM}~Xu#y^ z#kfkXjye~`EJ|s{CmAIFyxKlrqBe<*stLf~Ok_hNjQL1ZDt7Iw3tk`Wra9Lm4Y#C;9NA)j@Ic z<=)CJb45oxvNK!Wda&eHob18<0&w!wOkDfsPTRo0bqFp}Cs~>ivVDBzytn=5nAwacVE&bMi3VScFNE?M+9?7X5bzX9Q~tCno?*OEq6fx4zf3pf;QQ zeqseOJoG&L;;H(FJ{q*2D~f@sUqx|fh&7X{kz8TlCcCDezKi(^3n>Rm2r%$`M9Gqt zn<}du)_^|1V{*RPxrkDJK9Ba$E7L)z>|kFy2K7wpcWP|<)ZRrB%LkMPkM6C$92_U6 zPJFs3DQ|0{mviZ1vkO<;SwH`HilX$D3=E6$d!TlOM=Lk-6UWT1aT9WN&7(x`40vT# z6Ae<3a$x+4oKvEeNEypB1Iu^cWEh-*jgBq3Kk4y=z2jii1g4dnDGU{%H!NhL zX6=}}n5XyZTgO@oEvc}w$$>JCt<9Mnq}_KmU)C~Ox0)nKivSs}6dFaGzPb6BBRk=j_}_R%smY$hqN(cTSDyfnU$H1{=+qB$yP$zRTY z)qOFAL)(brk1Jz)4f}!jP4I~=4SMK}A{B7=y%jVN`g?i&4Zhj&9612Eu!g6aydR>t z8(Qtv?=*>(9pQF$tll5|j~`-s*gb7u)(NoNZ_U~4-uGMVHkZAgL_tqgWo0F5Ffjim z!iGXqqJI|)hf|ik_#;JuXBgIdLIFptFN6W|H8esJ0i|HGH7l$i?zD%I&R6Mh=&$G4U*7 zR)OqinMhtqaeHq-xxXtAGH*S&8L3WL;V^wm3{m0WbL-gYlrH+ahK3xm9>oPx99-Q) zuhJNie$YQcXAyddRk)(&wR`4|ClMOGY(C9BwLGrN!LHh*23m;MH4ia~x@euvM?H_h zi;Z#R<1Zh~J8!xoxQU+A3m+L~gVT2ngz@=>gs!np*+cj*Dv*5Y^U#$oS?YnO!Wk6Z zVum81#tc&;2^rg1pF0z|jU8pHRUE(kRe;8YIx@dHAG9#?!A8MpcPUaoxZMKYbOGgS zm9vWNr4rjq+B@Xp^k%;_0g;lpBOQ6QtH|B&)yYK!M`R;GHJgTH=1`M<4RtP!m8r~y zp+M|TBH1npjfJ1I{W;w8CHsbpGQB3*; zTlVOd!qkEk!wd5Bl6c;JniVQun4^TMq0d<^CP{3{f;(n-wAg!r_nTP|gZ$0;SoB zIA+wND^1r)U==WzSh4*(AQxW~7Ck35DfqIeKm=f)9^y0bha_5z2S&rcrOK;u$i7|$ zB}L-n>t;#VlQ(yqtm46-fgAVty$(8yiO!;Kbg-Do+9J(=n7|hwIo!q*8kPFb`#^qCh4Sjs+O{-dTChkM<90oU zhA@QYH0V-~BT{Q&k+lWChM8=_wuz z83>FFK!y<2YI0~nnm(0?570^Y4Goip3t1k^6j)s>Y9hRSQx59Jr`8$Y4jD&hpNIF8Ry%jR+pSTWD{TzvZUI=81%0$9`B#SEpl{CG_zgMzOnQt zlY!1Vl0-{!GZT1{j?u;!a~a&%eCjuS6N~NvB@NhXf4188E9N&M4t-@J0U!3P%=8^| zZ}S#xLkww8-dnZ;9Z27De5Q8Wh9BONK9<&A=4vLsgUO-R9SUi#z8GTY#UHvn3{722 z3bpds;iXEkK-6QQd0W<_$ACER{J^havSKrB1F)w#>L*E~PCh(N)S_XPc8YdO3nMj? zkG3P9=SqAe+^^F#iUqZ=oA3L%$J4iZ{kU58sA`(HK0nQDt+uMq$2?eqo`Ms4mb>PK zA+%m7W7(mjHLl7~Tc2c)n`RH_66iK&x@sB2G?3rnY)7@IF{6BTHzyO{-^~uk^$r+( zVv~)ICFiR7P5xGF`Y_ABwKD9Sj1n|=y`A(P**4E#&}{YiaG7IR-aqg|Ws2#2IezTO z@kM9Up$@0g7BzL_ux#gQa?HNC-yb0+_Yqo{erviXN9x>1#nmjcm;8oNu`5-nn=xmY?r%XE4TIo5E;;`fSlm(3mHZLhQr_sCHpv z2@RUBOAfVF|CzV6X;hlMxPuVyVabeHz?{+^MZz|_o z8I#TEUag{zd{o;$X(p)7Q6Bus&x7;j#m0#tcD3PwhuSDV#EwQAe za*`(TYfj;C16ezN=US4c$Yme!o+xvA9;O{sDw=DrOQpb$i5(kSDJ)rbrM-PLbA|Lw z9l>vx5t&EHb<%als7uq)@2k5(o+^`Dhx#gztMM`=k#L2qhxwq$5}VST_UcYl9ReP> zuC5CR;fu&ZZeGuBu-MU$>l%^3e#9dMsj{<9F(X4>z+iaspI-)9NUY69 z*M0JJKKd>lhg!$Po0U!7*4xM0+k7txaJ4)LEb2~DCPDlKwqE55)m9Cwj5YFvZ@7O2 ze37*ECm#WEP|>xer};%AQId46KtN}My%3dN;;L7AMB9&CV{Qu%^u4Yp)3aNXUI+eI zTBzIVbdGr1IgOJo;Y@&72D*4tLinkT?>({}U;Ue@$y}}8Sng?KDBX2gy6wtki)!n+ zQ!U5#!q6E$(J^`Y2<%dQPa%0}tL=?t7LV&$leDpfK5rTm-}5RZ@Gzr(2t@&R(0&;v zwBxmdq+XnX-zK{w8Sm3gN$h5co8$+~(w_xeOc)Vb)26322+JNR6oobwkHH z8*=fWH`~U$#J{RkLGnuNL49S{jdz+Co(NmhN zZYn8$Lo*2%Qtr3?VXa+PBlSD_5^>PX{REQyg=%>q64oH|+Wfans)h4iidx|{Uc^U$hwJ-{OZccm3caCYK+I?hJ7^n?NHc=O4KFXo7Eg0(02 z+iy;SmNNP`#j$zRPn+EeNIDV$Lo=q7r1C~wWaK6M_DoSE@W_JCSH)q+HyK`O;f1dT zmBMKoUVgi&&r{_@Q1`rG|4Uib6IX7bO|?4&DqgKywbwQm#K#Iy=Pj_g5B(2A9o5aw zHBoZJ1=ICwyjh0ODaH7V)7@`MVZNYD|m2352dOUDp%>7fB_kAgZkLt(;T;GYn-mC875-{dqpdRxw#dLb}PZrZZGq(SX z9QNUKwHmpwx=tcLUK|RDuwLX4)^|~epQ?K0B}loe!&)62`IVZW$;ddF&uyrgD#CWX zXD0w5;nF$6U;FmePK~+20{XN@72T#Qx z_p(MRF%lFxo(==xAp*8EC@7&w&;=;27T~H+g*%i4t>MwPv%`hifgH#o)dg6cHvzpT zVrrxbAGS@%XSwE{GLuu2`&Umk>3e#@h(1PxvZDT}o<5fU#?z3OP_Jizbb!jx-_qPV zxvAFyNls|CiCoC`Qs91Jkbgy)Tl!IqKpf8&YSgt@t4KN8Zscc>Vz?z{)YV1?s!1ZY zG&YE6B8Im$temAwgNqj_Gn3bXPZkcUg4aLwzqyURt=bEG%lSV53PJV0G-Jv^Dr~Q5 z%SjOu8DG2V5?iu4yvl{!e%!hd)z@D8e<*v?AIY-oPVAh!ye;;KTq|qey4WO}i%3eA zC~Bm^7y<-ifcY|p?J?l5hW`WqB?kP(Fbub+qX0O#%l~uXN z9&fwL@rU!`#gbXgR-)Ictcb|>-o5vn-}x>2)1QvZ%$eLz&dT{!S*AW{%534zkBw8+ z#NyydBWlPZb&TPz57eWk^p3dwdCQ}C?LlG_@uhcgnK{3C^UK`b{$7)-oyFL0H9JRN zYo=>p&EP0r3^$<9$yv!~$9liERSB@*orhi(V8M&D^hN60yTMkXpGn=|Ks90+0G@wZ zo_+Gd>0j!5e;vH{cisD65LM>x&BNjG#ZTth*$Tk=!%r_itki#~&PDVYTVH+2wc2}- zkcX3x7ww&Z0KD69mmE#THi*2L#%GbFn09fQ+ zW*aUC{iBH62VPcO1JfFJxW4TD+tI<}#=2=y|0rtqHG}D$y?|N3>BO4Cm$`fN{Vrdc z+wZpKL$khEL_H{K{NIlog zW#;F@k_jaFxEH85|{1KGk%J=qNb z>0oj8SKpj{ZbH@Ec=F9`k)JtlAP+V|#{t-BkF6D|IjbY@h?5Y!qkLwWEXI{KQH4?L zKTD(%K_n2sEVtRZ($Gy|DrY(j8UF{|v#TvD`%4G^X z0L-pTyrf@kfu|cYjD?MwDr#2jfplU_?m13@Gm&2ZI&bf4@_-5ni1mGqt|m`A_YwfG zmb!+6|%u0>x_T?O4UH$Bl$mcen+so(0=YN;(J#LKN6kG$a zYI5rwlu8H&4(cY2cj5Wiy!hobj74h@Y_}Xlh?q?bcf`(kPGa&zGC&>3%JJEe$^F5j z#?^85`e*ac|90Z850MDA(koWQn_8^Gcifu}XV04m4 z*YZA?JMrQh4-6S@g4?n!wr1QZKy$;2j-~R4l zo%i0D(i&q->6}Bva4(mE5dx7wM=~9%H~-h*D{M%%|9JinllD%Kj>^Vv9b>NmXz907jk#*2J=Z|f^8yg1 zMsI0We##G?cVtU4xp$5obD+o^D?Si$c$~#;WlP`a1+_wf99cs`Vbs>GB_X^zCJCJN zlh?tj3Z+$~v-jS6Pu1U?Ip}Lr6;$Dam2o?4CJwIs%dg@Gmz1pNP7x$l2wb{iRd`p8 zUagtL(>io@GY_l!t%||MYp?Ae1Q*{F<6S`PJ-cAnBxk5h9Y=2QpuT$;n$mB%;i^PD z{i9ykkSK9>x#U?mny)3QMlDtQ?(zJer+Hy4k9ad`4GPTb5 zGIwmQ1UFHz*wg*d_qxN^IrA~MiV4A4aspK#f>18qjw&A|?w8nw6b0}TGF(<~QdS2ZBUYk?=;*J`Ap2tn$i|UgLfrC2<3tiok z4EXua#{kgXk7k$U;gja_VAD}^skuYw-;UU>JD*u0QHSCe|Jyk)vF<^bFKiGAp^zM1 zy~^7Ap-^ZG|HUsRxW@cvd)>7H3{XHeHhcFISx4#+aIWy%I0%gVGHIE86Ic+JP7H^m zGm}e5ME(l^5aOMU9Ft1CjceeP0AI^K1+Wn;Ab1bi#9W{J)DS@2kukqfq@EqkoT(a?d}d$H``@eIWf7ClooMIanRE2 zqF~Mi5uANC7gCsl2%t!9y&F4ALIRVX*tDqG50*NG*n60q6+$6X_f1Lp+}1JD%#3UF zG`R|u781x)Hn+3OQYrz6XP>9FgaKH%fz{|TpV`I4RF~9xTl&^+P@CmdZHc9*DTPLX zoXo|PejpF5S>}Ld=ZLqC*=4y*85dDgPEHFI;q7-@w(v`yCbV_}Aw`hL@maC-_=jw2 zt85&Ob1D4vqHJ~*0A*7{1g`XTx)Yyb-jbB40z`qFZ_U^-BDiu%FLGo{A9pmLs*}?k z1xk$wptPtFE1^U_x7A_fSdhX=(@#uCi3tznN98D!W2_CeOcOx2ZvvRTdf;kY!FPA!~chW z)Ir4I^ZfQVTBn~ZzT_2>p5}gdI<)66&GGxii=Sl|pX7^6Q+sbkP08*~+0^nlP-+Ck z>3LBp%Ka*LwRaQ|!GquHPA`kuRoUzZh!{kyAFS+qdPfl;6se0_YWIFzrjAu+>DX|_ z7A>F5Y+@NFdh=05GueNXq!XLXZ0{&4Q+Krlp{AQh(p(Av*fI@sM=Qq`zP+z}b&-pg zY5ZP0YALCOHU98PGaXwYkt
    S%&%MRk?d394X)l`Eyax*hbX__-j%fX=ZCgg10NnQBj82TH+tfkf&QHEG9AMU<@fWV(hY}r0UsVOTfqxBVn3N~3v61S z*U=gM^4LHrC%jbO7_DC@f0!55^1f|_!H37oKJWsL*iT5Km3mk)tM`!fQ-wsUXgqOjM(fWn* zlNZ(A*IxS@GUwLx3;YP=#fCqj)j#g1`IFYXu+Z_-WtG-k`63E0FE)L=(3hmQK~EfC z8O;mjpDnGqleP_fkQcUz4UTwhx~+<7eO`x5eO+F%^6M&IB+d6sPI#G!;f3=1^^0nA zzyIZt!(`qKKjhbA{57q9QgbW5C0=TwRCZqKZ~80k-}w8j`qB4#>;GHV6soJP3vcK9 zyv{>^cf0FQJ9Je$1o;-<*h;?rcc0wGmbz!u-Kk2hw{U%h>n*i6;F$-+HOg0=SGL=) zC0=IXWyrO=+pqmHZoTCh%*%g;^4VaiueW$Vj1MKmGqQa9`xfrqwtdx9r?+1V>9bwC z_FBttm$icz7p+36XqDu+Cdb+{zmJ!|Pb>YR;)!T?#l;iR zUS&zWV}mp5ZrZoBXKCM-uE4W=h%4enOdS4E{dt|Ck;_LDZ!qj|yng8VZ7HATQ}%5| z-oJ>mZ>`sVPi?ztvs{SdMQ*9vx3!PFKd?<_4fZWd`-=Z+4F1lkV&85XIH2)FlOK}! zq4&$!EB0-DZPD5&$2;X%d)ddjagE;i1G(qYC#LqPY5kTMcwXoFlf3QyHjHk1TX}rV z$mr0xoJPVCT3?>~lWMo>iN#u%>62PYdu0Os&xTPPIC0RBKWN`NejWL$&%VX|L0)X! zC;UB@Jv;uWd(2v0oa{1Q*e^-T!VAK2(25tzKil}@*tg(=yzu-sIO6dIBikxNJV;TR z)^D8>+dF3ECm(#cVOc+#YUYHO=@?!pKlKaS+wUh=_6o<*ID3Wm2TOh2_S-AAIOjNC zD-RiccB%}%sw-dd<`1q=e_Maot5@=^^xm>%pIhO6-|rW!u3Ylu?JIDuz`Ra=LLIBu zp}!w$2Qo14c%VH``m$K&*<>pundmd%&q&1GcPq}u_ z*W4WTf5`Lq(_(A9RGz;-Q=Y&7fjob&j)SjIZVt$)kGH{EmSvh-!?ZrHC-dAKs?7?o zF3$MITb`>I%edSelz*<=9OR$5InI?qjkxQ{be9*R9KT>qVeM%QRPjo|{%=bk%Slv_BDmE$`0#jn9(d98hs#UvZnfT@V_wuVhm?OpCd6t^Jm*&H z;KbwRNN@w5c(1wKB+tdg`iR-@zwDapBumRHth8HacWSHkQjWP%dWP~x>6yS*>)^xV z~R=KEIb6(2A3XHoWEE;%ky{-Cc={BL^BF!15=ax{1WM{FyXm)_lK zy_R!cD1VTbU<|gi76CpyUNG;o!BLQx-rZ`w>GOHzO}{9+h4M2qdTXn706{OSG~-=oF`XESm^&VcGb{W@Bdcs}6h+_r9O(wQl<_adb(tY8B)%A;;6|IQVLw zr3JY_e%{yi3tjnxwIs>o(8!Lm{>KEzruAE=a)VqlOZKPQt-hi-*=2@8>HKs-mV?V< zf)*gZW+;RWOYq_G!utjsv7em&PM?d`m^WTW<_`}mUJ7Ryn?7C+Z=J07KAj!S3*`^; zQe6?6h=33B!Uody40%cGQq4}klw`D6U}dIXAn;61c$tXdh4Ke^kw6fA;)?NC=Y`y` zH0^KG`n(QV63jL!q%(%EF52I3IpBMFB2qw-e6}YY9h6_=CGhaD3W}oL6&DmmdzGb4 zdk>tkZPj^q%M6J2EbZIUTM@*K1zuifXBKvoo4JV>cKcx8o`!M``6Z@sn_O0s(JG8JH)0|!VXO9E)yT`#v z;2(TYK$nBGR>(YF*j4vV{n%o^Z(O0wc_=xqQ2wX|m;DlP>+u3UJYG%)FPi>vdFkDS z-BONuQ4712f1=%mU2x)Y(+_UI6Yn*bo8Dd6t>l;+wXjS1qx4K*VHbROyu1>;fTJKU zy}Phm^YKEPoU-?F$#IGD2j@Ex3%lUMD`6hM{~ZgOZmeK zy8wcK5C|LK@VI9ecGbkFaA;wdjxIXB>}{?Ck`6I)Fg+IDiP(*1PUccY1hi905*Q@5 zgq7p#0ojT8*KrHGOEEAOP_9CGxht2gIli9pDF`L2{WI(~it;mmd&=ICcf7yj3%hJ* zuYBY;9<(N&BaW}5WMTL8qBSYUO*z(Hm3`Vy#E_r&wSBrPzgEp!JKXLb@_J48*t9-> zb%7WPneK*CKT;OzPG~fJhC)v-)cqv96S11WQhrWg-S)1^lh^Ls|CF)gFa;+bH)r6! z0Z;6&wL?4kF;!_=pC|1IH}z$WnVfJl5yK7T*SL|Vs;bUA#0@y{xH%KtXnIHVg+W+= zWvs8rP3F5s-gdN1Ocpone{U_^^|HPxJQ>zE&XY5cKR7X|HbT6B5097S-~}A9pF~fX z@nWc_cpV+#rT*MTe@=Lrj^Ty!YrGUgynqjnmvg`iIATA!`X&7WPFD8JV(eyITlCk? zE_IiVZZ5monB@6zUTli8loMX6KaJKelwWtO4&M0e{)t;;Z&xn-f)9_E^S}!@V$-|& z#ekQL^h>9BspN#0zNeyjq5OVcHcRJ+cmW?CFDt+cI3h3W#zwChx@LG}c>G5GDN$)! zzjZR~mY!9%H~erdC%n{Sc%l3pkKkTF<|1FVH}K){LO%mIVn1CZ*0RaVv_8+h*m8Fp z&1^hUeu?^vij!T&OKC;Q!0Dew>le!J*Dq-EY9OEhe2^FRiw%x=yrEoH>M8Zhv_4O) zvd=hyuvytJikHH%#b%fBVyEQAdODgH%CGaX@6rAHk37ZAFyr`P;IAYvcF`S=*gq_j zd0knnRhri4FNx*lEcDq&==N^P{gRc>(|TobrptI?dn7HVe;(#V`R^!y&=1r4_0T*C zoOs-*JC%PtcA5ALNBx+2DxB zvzZXXaj0 zo;WAmW!>oZ;RM^W^Xq9=tJV3{iuD6E>< z-}#mUzheDOvGhMF)?57y*-z?%qIItvKNMcEF5U43$201A>>#JES#;Uh5BlHRJvOb+ z^JH%Esy3@GFP3~G5pM>bvzN+g^gm@%94L#I^0#C0Dm}pao_e6R9T6UgVBzm)pQkt7 z*rxPAqCCBqKo79g^nm^HO9FX&DKE=&Ubbv+@wK-ccs(#Fk7(^wk8GVNk8DX=f~p)( zgdf=o<>`f-bLj!oJiDg#*}j?Q=~Zo3Kebr#=>eXr7t6Rjy_A18i*%7R2>EB8-u?17 z+6dGI)D5K_u5O^tV0(6APo6Z|LFtBB_vE=0x`5?69Ir>I>xR36d-9YJ&BpSo1^?Z6 z8=l$h&tt9>WTqynE@Xo|LY^rGEo#O6G|9HQ$=eNi^b`SZ> zVYhEYd6iab_B`cdS%W>#@}TV@U$taz|0}UIlszwd$ZwS6eR8b5LVL(VevY^H8(sOe zYQ4LMylOY=)Z&b9ygghOzK4$E_K>IiL3`fO%Obrm>I!^#yzssOM{Fv`o=>-pmh%&) z^?4nc?+LDWsh(W4|HIXL>O8a|c+UA)HdF2i9=C@)<@ee19K)sb@d7@`3)@E5Gfsb} zUD}o(HLcI<>Ig5^iN*ddb$UjSUUa9gA}D{eV$VB;zUCn ztFLaSJcBcauPm0jj2E^?(lTxjdCKqOCGgYA9#!){+Ffz;KiaD-sdsE}M%_*Omi8>| z+vZMJ&$B)+qVT1=oi*(Zm7&e$F}0%YM%g7zvhCLDLzeC2>1C9CJ1*~E#jI)DZ-za4 z4a&_ZuSGeBecOb6%d+ye7w!uIw`Jq<26@wgep{Q{m?&+Yg0VVv`to5IVBH6J(KFfXd54$OKTl_Hk_yjwSyx6ekTK(gGGSw5N z^?5y+$Lcw@;Mv6)A1}1!dCs0HSA=;{b`9l^(=-0{GRGbUC*+20WP>Ljn?`?|*5`F( z{&Wg{*#2R6`R`iok?hk%1UJspDUd&?XM*Vq)%=?CzPR}{=gVHn`6hVcJ<0hs=hK{D z*WT{-1M5?|!GG50*O!-fUOGCwJ>lTzROyqt<2%O6r!8HY)Z9|@>yOC$f8yrX70e69 zP>!R#0i`y-w)d@@HCA-#)4#R1e#6asEbE8?Y5i5Qv#q=j!0S7QJ!sv#K%Nkl3};rQ zXnkIezbVJst8(e*f-&QepZdhU&XrrMHjn1l?o-&AJte8y&AO!6-(~v5UV7`y-8bpI z)W-2;ZvXR}>b_Rv5an-s90DgEHzT-Tz!QJ}3Vujgn$~Zfwlmujm3-WE!~D9{9?3pU zL~x_VA?*FT2VuSXtB=47Xr34ST@`q5G)^Gh>C-lpi z#b!=;>02Mo3*{#-ZhO}Yq45awLh@o`e%R_C_mk;!FQ)Zd*Hc`WX;u(tZh3Wa#>dOT z*2#MAQ$2m(>@@-iQ7D{F3#aK`8i}E4u-}w8j`qB4# z>;GHV6soJnUc8;}V=U(1RC(y{ZW|qHhxy+Qs*m_qw&f)&`Ic+aPRe)G~h zT)jwtIx7x-Ey8bp#n252-R736;&Yq7mcQR_sr=@5$UD|=z7zBDn^E3^vW8Okn?E(X z-~4y4J96*FJ$Fo5*0BQz)NlTb_+=)PpZu!>R{hmQ>k&C_hW+OD<*t7B=9`e8+^afV}|3;%FJ)B+O2SSvA@g4_h#DXsL}syPsM@bH;4QaG2?b<{T7^f z+`I$#3wYx1oBA+?F~Nic_-%;H28H`V^CpGA=)ma{Qh}_j3eiV=AGcf z;;MbkH?eg@O}o#o}Jfl5wznU3Lw^80zQtiD2s7x3ZnQUx#Ii2Y>h_cpE1>*$Pr z`Okq`PI#%lFT{6d=E=Qjr*9xv|#FW`v%S4vSKCh!QynJ_HGAF$B zT@lR-m%+^^P`{f@7nmOU69>WXeCoi%2 zgTM!QVZYemh{x+HL)*)JmtA}9_HwGteN5}~I><}5_HJ`vCMUcMZj9D1l%Kq`+FM)q zhaZ8w*zhN`zVCkOS--jCi+Fj_p2>&b+`2NF7s@}I-`rVe0UzXroY>%q$ENFQruBIp zl36j^bveaL^@L)7PI#G!;f3<+`o-^mc|@GDHvEuZkMY;E`iVYX*JeJn&SGH=N0m;S zsAKgy^!G#UKn618K{3X6{5p%=#+F)}RO>CO?^%Rhi}LMyfP7X1S3r?DG5%6~oozQ%1|eBA||eojI4PvG^)<9n@b zKiX?qua`Ukzb`qh<+!engRfAYE6C4r-oDk9KUmA^-8@&S-Rf5tOTKZwm;L5(d9Elw z$9ea5amFJ-!57~LK0ID{-+&`>3Hvt$*2qj)J?RjlNMm$*Dvls|eN;o}8- zkQefy>lufaqz|F-$D}l^&!5UX&y}NJE-%)6yr}VXzQ39&^F_qvxuX0&UTE7m_K3Is zkMURMMQ^Y9_?WS@j#~a zc^#R@6RCD9EGjm;OrMm_Nw*vFL`*yp+?D~ zqhB5zsO5y0xOgJUPhMK>t=TW|Bajyx{)E=|-B0t!PnYp?xQ;L4q~fHH7y6R)Ht31t znD`LNKbxPk!rW9?3?Es=X==?8W&GQ`8m$V#uI@Lj~CuI;E3Ef z^N4v7Pvq`HQ_CuzNbzEwQnVjy`OUjw9??8I-TGWyJQ3yh%_9Qix)&b;KFACC(DjUI zJdkO9URUPvM2>!uee=4Emr~aI=0W~BdBOOr^TPgNIe+{V8OIYjW4P>_*JZr0Uy_z_ z@kEs0$4lU+8BavJD=wah_9{#29UGiccQc-d_AKq&(z{(f&-%Ow`<#=P+;fv)2Z9%RFGsWgj$|fz*5@ex_dk8nO1^o$EbTADzWqD5Y`!8G zPsH!Vm6LycN2CAc_wMO*ynN{Vg`-wm){9nK)uDz}y{utP%kkg~ z(e|y=16MDN{;@XxdSQ9=`ttbLjct5&)~_tFR=N9d9vc{ww6t2hh)ef^hRbDeD5`HIv(BO`!o zhuFvHytt8$8?U@7;g5^1Eo^Mma?Fd$YexAQhxp=%RupVn+<+60n+CW6Pps~8lisg| zH~?dCI-_TPXJ9hN+$cRm`J?pAZ^-|9dIo%WygUeAz)_HwFbw> z#BC!(o66Uhx294!uum!{dG_yy(M@kFkFOaS9ZEAYsd4GBfu@fa+T^_UUM@K zJ{uebd3jCh36QgYeBXxaM@Ppi{LM7wBHF!6bUS9%=;%nAUsU?#Gpmk!`6b?SGkMc5 z>e+M3|8dy83%mgcKoAf%u?=u|eD&3`_h5PJ=BuyfUk*;We}BQ5AloPDfV^>dY<$O1 zaz@0^t-nP!>B{Fzaj;vUpreb9FZ(^NiBzG_(5W%;om+|Z~mIQ6Rs-0?Md z!fLCpUmRU;Xjt|0gwsB8f}Ij_eAOPjKe(YKK&d;>+?Dm zhymbm@S7q1E*_H6vBc*oY%a>ZGhjd7TCnB0da<1N+b{>pkwN+C$T&t?+5hqf^f>{b z;KbvGdQ{UR>qp1aLn9YpTAwm_+&n*;o7Fo;%47U;JEg+BV_N8<8>VSS?#gwWoO zThQk`g{5cbgC9=rIj`Y7hVz={Ev_BF`n>MJe~X&e3=eJHvO}z*GQT!wdHGoKI{qJB zc;W(UM&>o&i<{T{5cb<+D1RI*{l69UxruoV%S(QA-s*2&dzNr_gg8o?t7Hpwc^`n+ z^m(hTiPbWX*(3}4a{lW1@>v}RU-rW;C!ReE`Kc%D8CU*bEz4S4-frZGGOf?+$$Va; z+O2ST*XfDoi{9Wl;Mg|pl!ZSE>j}p`MZbF-@O}Uv{Ot|p5t%m(k8b535|*a*dAdbb z-LW%jSvfWp2lXo@7^mgfJe()%!Eyq6fTAgVpk^?XKkV295Cnu3b%n8ZcJFf40 zV_CL0-c(M!A+~9KUe{s^85^>S_;3`()s0G*8KP{Dq-Ejn!-~R*_<;QWmDok{yvOcf70}-YC=|rV^Vk%KY=@T$Of9007S0#%mJ$lzi8f*SzX3qgPKnoki z*c_5U^sVApzeFNR<#=!~WPq~qJOdQ+Qcu|Xq76`Y1wQqHs4inhx%!^uxq5MI|D2Z{)Ktw4x@wj;!+<+(6bh+uph*HJP zF$2vUbEEVO<&V-cfrwJ@;qmeecmYR2UV1U2RPplcsu>?Iw8<%ZFP9vbD1R_QFe0K9 ze0aS461;#Tww0@2dNHC@@$!vT_K#Zu0(sfcrUvEATd4-1-9iW*U37ev z-sdVgv6gG=rTMU-wRk2?|NNdn5HPM=8_x{4^hYS98~I&S6lSqzK|*E=g&_M%`p zm*dO+Ikp}{Ir4|^Y*YvP4!q-Q-=@{peIw%ddcCZ=p53r++q~L3QjWD(?F?<@74q}G zwk=nFt(vjpD$59sOe0EFyH!hFcVE|1MwD9b4m-%5l~?q;#{usL@If9-S58gq^Ewt; zd$L`5t)43eg;iZQlCV9J zmi35{L@l+_B8ppTr3J~-rUeFmcvI2hq=iX~)4tWUI9Z?9T{~Y(-gDWG@if_c+~hqe zE6c^K>XW!*8JoTvXK^lug=t4yT9l{V^1KsoUcLG2=L&ZRIM%Q4X0e=VVsWmOrB*rr zHaT7@$1yL}pN^#g`Kc%Dn09b`;Of-r2D8)?nOdAqyA``mPn0f77fY_=;BkO{CkOnV z4L*20pF9fAGX+^aqpCQtF77%G*e|9f^*i-B^?UOVUHwkI&-3)%JmGj0*6i5ognp`L zR2}zq!rV#n_41bT*lA0brBf{`l%^pbg|?HkErGsAS$cIal&0b{C@HJIeCl7`I(6h( z{l$Zz-y2q;EZ&6s2dwIM2dwFLiJspQ;SQa`5r+Oj0dvQvQgg%_>7E7RmR>{}VF(R5Q^1VgOP%P!~`) z)IR9y2I>s9X9vRUPFs4qvSyRL5{KCx0p0LIx72mRTxb8m^f`^=&iT27Z5?3SZ(?u5 z>ifKKJ|Mc`Jpe#E-nZ2AvdFjP4JJB2UyNZ<@^PI+I_=Fp4SFx63Zj_#({84%)5M~EHJYJ3kFW@N1OD~4mDf{G(;-rrk`eP}3FP9vb zD1R_)Dk97de0aPZ2VTGt+sf51y%=UEyi`9_Z04L7${*w|4FY_VH z4vAs2T12&!9rMBBPM^;!Z~8^~I4FO35fwlX5CUNX93Ianr?^U(l3C(LXJWKI*UzEt z7DDLgqT{RdM+mcnbDSJZue`@`iaSvgW6C8yFnawp!&}PR)?zvL9}HN9W94|C z90y;`t3De{+z9!3U)wKnN=Czy^6Q2|C?h!d@Oa^U1CIE+SMo#3(zJf-w4LDPRRi{axq7d4p85UB zzAPOt)|;bwq5O050zSwKTS?b5N%srk@31tj&)<lfuvrTi0csA|>334fFF!#g|SELY!$9TpqhhXq>NuQu&I@W#oW8V`5NIce9@&b2@6 z>U-Ab^<*FXk#2D@aq!1UuyaxBc5cl#5vHvEQU!n5AAawFw{!b$c7s2xMdCm{Z&lmD zACPk{y%@T!$a%;>mcfeQ{>#g*M49a=z`@a&p}yoA5YbF!){GC)L@sfv>Gqm^Q%1J{Q2lgClDS7o0TGz$5t8|+uQ@@v&B$;+w#DbcZMeV%NARdVL9c2@Hd zwW-O($BL6V(GAv5!a<{IK0^8Z^O0rCmaXL5KOb=dgTRT$&8fI=z!Upx?a)qsOjVlJ z=Se%l&EW0DW=^=7h~b9v`?;~KSvDpBCmuJafg4Tlh`zWw&3Xv?J1c!-S;!-tmA_2s z>FU1^%;bcd!joZrqXL5{zu#Z>FTZtBJ)~#AhsVoO@B)s!{vO(C#*3kz;&pU}mq!Qe zC%VfY-)fI!pQdAYq5K*zg%B^`!{g<2@B)r_HLiY1Y)-Peu|32eS`2%p78&5oZzU*| zJu~=;Vt-C}ss1!tzfgYvTu1pp2XB0K|HLig)#gL7;KSqP4DbSu*z#hBh<-8PB_sXP z5nd)fUM%H=m%gW>d7=D%UJi@m1$=nCoC#jQ5qViRHhRs_HNzvr<2Uk8iAvM@t&?HC zbbaIw<7C!{dd125`g%zeqd=CNISF5{)SHeEcy;LoD<3+4Cg7qq$Omv`pX;DfxdUu#_$$eaeV#iW zv42=5^SZKDt2C|8Us8S;CvG(}|6RY#r~kaz^zkC@>YjZ~|2)i#^50SZpdY5y454`v zIPthy0Xqgfv8L1S1~codxKVLS&IXa0`C*i=+$zraxS`CwSXQ42bL047AV2LG${ykc ze0aQIeMHwcKXgLTYi{c)-!#-h~|az>*JDe6SQN%2YDe^ zHaOxjc}e>SXjZ%|A}^UeaN|lib5cGw6s$+^q8_-R{CwcXalEL2HZGXP1+;OYnI#Qi zDjem^Q7<*oQYYfV?BfWiTf!ARz*npb66sb|DSO^MWm#v+``z-nqDJMwE0pF4a_X8TP)QC< zBh^gn^LjFmbaUG5%Bg`I{T{lp^xbmB8&u!FhSS0u60gh&wmNZ9$D$UWOa_-Mh zSrZM3(r6>i5#*(Au-CY9>+-peg{O-|R=<^9ic37^o7J}W>M`F#X^t%RyT?HZ_W}4I z4=x93=PH(k=rm(z+U#RQiZn;+-l^`LD&=I1V1Key`d!U#DSyNmVFl70fe(+Di@}Sg zKU`kY*>&pLHf$OiDfjhXcFlFNi~1{gwaLo`R@S=-s`LPo<|xO!C@&i2rx$I`G)LgX zUO18GwfAz#af$K=y{-{yj=+b< z%R2A^j@VYNe(B*fM>*%E3HgJ(M5H+aA0985_u1em$V>00IeOIR^U9lkQO;1xPp|6& zrFfk10suik2!suAc-*sTj+}|nBjQxZ=ZlUnI=bliYToTSzUUBR>vSN^5q~;Ssdf{b zHO-M7#yyMII9dUa7c*?3iE$9A{l#=Gi`bmh_ zP?{si&->bbqbtAO$Q$)PBs?~)-#T5!X-J%Q`{$_{pP|q?*ZlotUy?G+EH2GajG+)p za|Av-UU=VtBes}nnj+KsybhTHi|aeXv^5SdKbW!~aUb(+oo9Z3Dy8HlHq8;_*A2@M zFW`f`u$6Q@W16POv_7w^GrauwRDYN8QcKB8Y?`BXdBOOr^U~@c_mgRwBGdZ3p3Ku6 zIb--kQ>8BBh3%2Fj7@U{`RP#Af7c&orlLYt!5gOa*~YUk?D1O(N)`N3|D8r9Cwe6=_=ECCINZH3#6{Aq_XF~7Q#U})TCN@2ySLga|BL2ZmtD4n%?QzG)GELTc=LV7e&nj^^XpX(?eXeiAQ`0#ic0WaXl&>?hMSMW*$69hs*&a_pClQ?)MR#lARY{7GDzqX_+iHuwDU&b%6YkQerg z4UTwh`ec=9eO`xJ$H_F!k;BW@smU(mrIwPH*fd8myoAym!Cy&U>~VKIV*ju-O$T9G zpV!f`G)F#OdO7__Y?>p;-%dP%qi4X0$IT6}W55&pi)l#G&aAWIM#U{2#wnj^?hJBG4{=GEZC;|1#@y1pSVX&)WVikFV1Ir>J+57WzfCN|9xr=h9HoEVHgyza1m>`%vDBa;IDB zE7r@k73&gKtXZlR>xtigovaui;8Z5c(sxGT@5|F1@0V5UHdm}6KQ)W}4p(mWBTLg2 zXVdz;j*hH6%8GTrZzSTmda{h!V1@GgE#6sItig%L%{y`5fG4({>58*yeO^aLxRDj> zQck#uTd}76er{%6u?8m|H&t+>>7AZlv95k`s*)3K;#RCFzkj9_xnd1IJYL=fUceFW z@19<IpHO4#hUW_d5K)H1|J?TH-i^&*&ZvE3z@qWKMXA zTd}76{+V^;iZ%G~c)10ypB$-SkL5ym$(&c%FppAcEuWec)ZZh0FKyCrYp{-^?4l~S+SOrc_CLeIN~vR>D3i$+qYiW%e=&`SX2JciZvHZ<5sM>(Cn3*Xk*~g zSFE`(8(OjE3N=@(YoA1J7CdWB5(oe7&ZE?4Zn|*k=;rd}W5YvRx9k`h8ZYx}bC$k3 zr!8HYeB4yeSkD}`!1^VolfmdOB(dv7D(XuwnYWZWUton|kHT_;W4!-P%-7Uhr+@g@5n#KNzD}S(- zcxcPpEBfD(9GlkXxt1`dH>=GzRJ&PLfxq7^W%IIhGwQ-0g|~=vVlL6|9tXT1zz5r9 zLwQ7YK^Pw0%0DD5P3!Y?i>$iDqDXGRthRo0IGFfqDJLV$1oQygQ|SX0szmuY!nBeQ z0|)}bin_v(rRL%5cU<51#`4(s@TT&1ey`oqv_8+1xhus1q<_z(&t&Df=5twFmr_yu zeOOVbT@xt3-(+1Re^>9o9>*9+bzbzgG94I9>+^clz~TgPXEm@mgYhR<@%MYa{7{$| zl^l?UQJiH;gOa6Zkbxh+Wx8856b()qprubC0T@Cj+0LEW{Vn+}LWy^Oy9Wm7r`>Wc z1C;WzJbd8U;;#4J+HnJv=WCT8DO%M(6Ju)ES1s%ERaW7Ti&o)N%D9Src?KxtrJk@q z7HxpKyJaMfSoO}$iHP@ylpmIGca^O4#NabUYvQ5Uc1n4fT~p2D0R8T9FoF93d{7{l zgR~B@EO&pyE<2HXRj1kgO*okT+hViJ>;6>9P zE-%UTHqSY4cYjlQqwoJK&g7Vvw;KSnu^FA9K1$pVg-QOHL=F7#6KF4d`^ow%5QvR^x6+jRW z0$~Fj9{23-Z;ruIty9jtm1+RmErig~MaP#tiR{)`fn~eYp9rtKZrE|n=HVNLx68WC zh8<(q%GR>{c6{lp(}zm30^7bptX5vHU9`aZMcm5ky%-qpL;2ZYsXM+ZJ_Vt!x`~xn zmQTH8$!hD7Z;0dTSa~+7Xy{nqcTa#rdy%ko(L=PAp2aG>VnrI%yD`Ywv*h4OQP;TvY9 z>8mR}UNEleytMkq{bV{$nAYd@WWEsVjLj#AO^}aQ^?hMpoL$;rFU2jy(!OMA(>?<~ z)J2Lb^_lkAGh&;n2~2Ar7FwpXRGWW}tTtGxb-pbBWWPs~k~8@$@g7Z|hoy>Aw^Vm( zma2Y5XDz(7c;5+2_jEc&P(QC_eNgU#f0XxqqCso&zFj^)BJbd<`It+Pr$Hd+TpGl5 z|25P4ltNi3PAEsD%bedzQc9au@0^O z>OrxzTT1Ez>W121AbuFLS+-SY!Z(t;TN8(G+z;K*a7$e`P`6t+I2KexJse>1A#Qt`9>A~;~$3D5E*ze{Z zD|1Bn2KexJ*#lm{5!=e;CHZ`U_2+H)hT^6Ap<*fLyiooiFA?Dz;KSnu^FA9KvAOTf8|?O;zRSQ zv>(L4_;)BD3YK#@zU*IMb8?iAzve5&ec#%%>cBg`UMbF-wGy)N0b%qoN%wxLe7-p3 z&}p9a+2`CNo2h#a56I8^+HSh?Yt3kxreHCx-?|=bhE+LfiIPK+wPAGA+sfl>Mn;Fy zOhi<>-7r=0849g)&EHR@l;InL%iaE`WHc-(f6!2<7OcYY56XLu#|!xIc;S5mj`+Jw z;gUSnh5HNH@sjao!It9XmZ@5o@xp#dT%H}x3+11a7w|z|cz#{ake9SB)$Dk2H}kAz zre9o%Cv(EfL<}#KKgf%TBiP=QgZ$J0(o|rqzM( z$U*-Lw4e{jJ(oUVKkC2N?y+foo+tD0WYuog#nNWo^=g*V<$I~me8HLDP+HG!1@GO& zL8f_JoO@@W>o{OPCM~P~8RkHZ7t~{M;|29UOIy>M`gpIwUsuH5?XyN>Yr5C{bOGpjrQ%0z3<9IAqfQ@>I*7{6sF&NO zcQZ8zJd87ELs<3~ThWg-fKALPDk@Be>)tX-?S_g=fwUA0pW#j4$@ReQZ_{r0=w zwcfSf^}}==mn%kxcJ97*WON6=w170sBddY(47XJrm&fD;jbEA^CErKKIE(bLWIEr( zR|Ad`rq8U{IpDnP!@|j--U0W-2FLkRx$jBB>7DY~k+`QCDMzu+C15U^dtJ(!my!HcF^CCxTo1eENH}0C&++20_ zTlv)mriz<~zt-$9Zkjp!of!i+l%L!LJ1AvBLt+4_cZwU>XF4}}rQ6yYw)t6}!s7w? zHr}h0eOHdx`_uYHIrM37n;iNar!aMC=YyZ+s692Ywoke^j$=5kseBO|9N^ezWzUR` z`wPG>+_Td^NX%aVHnelw$c}7F3pe?Bdi+eM^sURhURpWy@0A5$zc!6)o`C)KE2PgO z{XmfF*T9; zAmAi)ONaLIW3JRTKX2L=ZU#R% z;C{0l4&8ABHf-GvEarv7G|_l4qto_=TeM%PQD2jiRC$Dtl(|;{&yl@KXP2YyCp` z;|oUASZ46X=MRp*OJ*r#Jmb&Hfsc@vXTb|N3VHGMiv=$Q>6fN^SE;H^X>oN6QW27Y->WK=kDW zf0`%>FOvpdC_nonOfSe>oO;FLa)XbM7tS+)qu~3FbMXK_W}<+ zi7PH>b{H>>OY`{+2cK@OUnqZEzo5?RiG|YOgS@a^TyVte&DH8Qe$JEH=I1?&KPN(s zkIubdw!?U-T$Ya)=b6^LP=1}41CJa$m^gqP^OfYqJ$m!^?vTJA`YYS4tDf6&Z1eLM z)jW*axL4f#U9Ze@{`Ud*k!T(!=~3gIyCa?Xd72kBe@FR~^DvRjsc{lG3As5Y;Kl_{ z%;~qg#mKrSZi){iAamvQJ1^*saYLEAF|9wF=Ek3gf&8>%D0_+*@DcI?|A?+{$V=Xl zQc=99aZ;hD155^brV`_&oApf3bFF!y{CdA6+$8N7@IhY4l?#q|O08`<_9nv6Wt&vLYd8}V2-O2UoFV@>(v z+^88lzEj+QlaQO^!HuSO0*_MW1xjpg>lHTP54FW(y=}upNw_h2tSNtdq}0-54L(9% zeh0jOBes+135#*HtjH?JqtqUc^-&v|CE>;7v8MbQFKLf8_y~FF0WaVv!ru^}dbxV&m_y~FVUGM^q*iM0dvEZd3{n8d*#AEG#E1L18 z%-xupJl2#y&Pz*=HTVd5ISIUgBi5O%$JsVN%OOGNWB@NKd<*ti_m+eglgFC!vp+I= ztieaf3+EZY5!=bu<7}Is)B#GLdf<(-Ksikr50teqchn22#hnY%GHd8{cv?HJ0Q znzsWVAusTc==z4d|UH661lk2O8i^jJ6lZv;)pUTc!rCXe-* z{QZTd^LniN&{Ov#-GHA2)nZEippBR|=+5ahC<3sJSJ|JH5->8v8Md-kALpf|egPjLFK2-la1`>=HRVsv!?4y{c&x!m$jybYW55%0(xa4jWL*?DYUQ23XSS$V zcay&<^DvhU^p=DhlgFC!(~e=gr{-b6N5~8OBf7pJFWu^~u9SoqlgFC!$Hz%vCTYij z5As5;TyVr|^0N3IYaGT~*dA-;i+k_XtmZGI+})O%Jl2#y<*}y2)a0?Iqd81D&<0q# z$C{2=daO_59&382>9KD7Jx)8qUTd~Qn>^N;&-tF$WBms7)Ne)l`$$g-Qr%;{_LY|; zqV6={v1U5{moMKx``sI-4!Os=E_lJqQjCtoR#HRPveaW4tv zPUf=TQ?%4Q*0oqqq|4q_*9MO@<&Rsub9$`7NyyD*cy7QG>&({UY@46uXqU&jQ4(%U z9&5@U=VnfiH8=^m*$8ely|Z*Y)&)le_x1E|dJ`q##^kZ4{PB^}|M>K$(;jQ^5%RJL zynrJ<-%H11-3DHqW4&fccrkgbDSw=omL6;H5%O{ccmYQtFJ11jo-GM4CXY4ckB_Wd zdaS`m$jg=B1ssLEbh*dceKeZ!rOe%!nmpE&KhDbwqykb==AZGM)caF4a(#d(=m>o8v2oTq@AJl2$7=OyK_#(X7t zasM#rkJvs;Z9Rv!`B{#3d8`{TUdrgPru@ly7}k0Vk2N?6xfz5V1D=?Z9;LNQpV@>&K$58f^#~OTuyud%A>l^aYtsd)UjF)cKGbWEU<=6Wq z;U;OvfDiIQu3T`$Yx1)A9&4OXNZ5>dth<>PlgFC!r##kln3_D+bTl)i0ZfIX zd#vf0rN=sq3Qi9-J=T@4;2dl0wI+#;GhVU!PB~A-Kfk&VgTh}c5_b=YLYtNYe#|+oD`FX45 z&VaP$GN*Bze%`MQ5>lAOep`yY3B0gAY*X?=`RC%rKdu7$(bO@qKVcf` zV{pd0<%%ixH|&4h{|Bd1VC59$>;K9f$EeSnYeUXPl)F-Bb+K54!#U;k4-J7|B_r{X}J!$$eXTlPQlh5qC3 zllO%oH{c}XW;>o2@WkH_S|xwL_?)fE+lOgexalA8Dlu+4VMJ6}pO2fKb6Rsl`4`L$ zI0?C--qrL@$W6|vm*Tj2L$Ue>MAkZtoA5!(_+iq(4dq`jH{gWauoy0Q;`QdOL)-I> zbc0{8&ChZ;PQXp0s2N`TaHAyL48A_CZ`3%6@+W6_C7QTqg+Z1sd~ zewIh|PlcW@>)V2T-b9QS+VZ?-SEc8sc~N!^lxF~(kQ>&K3!Zpw>p`^5&vGa| zQ|R7D{BW}*+>E#2M(G*KpVTu+&!ZZRa{Ol+Uvs?7)a7^+Jn@<2_?qKsj<1{dB8DdB zdD-s$ciireuP>^O?5K{7-l#^{{v6-Nk=?^%!y`NS#d%VGT?W^gPkdBAt;W}!A6e$?miKc8J>cGe=l<st=2pLQnxS?1YZE%R*0dd|LYPCL)awf1VhF0ec#Q(lnAvMVURW>=)gFW@8O zh0hH*VmtZmoqu}Gnm3k%vBU}+?lyNrb6TxHUJ8zd3V|yn;bq*w3+0dVB2|;tFX(@DUdRno+y2BhKg&`0sWg5c zeu7tv@sjH6qnmg9r+)bTD2TF4RDVSIHC~+fyoeg-((W>ib7`+K4edQ}#=7M=m-Z~} z+sb~dW5Rfs+*te?sa0{{)frF{S(-;??igD zmd<0}HelZ}{m$#}@^1P2H=f__$Q!A(CU^bQw6pO+>3feBAM)3yoI$xBmuu}cdyHn^ zLVoHKx8B;my>Mu&_Dk6=ZSzNW3wAaa7W-7yTYZ_=i0PAVwpZ#eYHhDje(ICpaZ#t# zt5<9t6Zi;u;d29yg6}(yzpBh)RBD@_d{4rhUp~F+>|5JDf6M!YY40=BPV*-+7kQD) z->&nVN1mQ`);^W8Z<~+Zll0?2&iV8S+9AAM)(^J%c|Wz2+4l>t(AP<31dBhY>a2c_ z=l-u~{+9pLjp^XyLHkoSj+ZI_Tsy{ANG9_Cq}VQMjP+;orf#4vpl)bR!^ev;Fz-3O z@~<`Dj?AW9F_L-o>-SNchIZ`AsU4J$w9O}e?)AM;`F3_)a47fiIJeA9J4b&@bi+X4+v%6+`qostxfXM{1ity5)vq*Q5u zl%M*A^{vmkdsiFEONS)USL*2l#*J!-$qAYb4N%JsOqPQFsU zEXdFP*1aW=KbgyMZ0&K|{84#|_GL*uIg{r%V*TyP=w@B_$>__1{OoUyzAW$&^1|l^ z9I?WDd%P=sS&A2@eUZ3xP~6w}5z`Nn@e2HynbZ*9-V#(&_0ys&O`J>&DzmA)*+ z%lOxt9mb3MvNz8e3xMsYr$%2EG=oM7q@(=_VnkIATRZads}P!)^C9=eJy`$ zA%EoFw1s?kuJ5dNFrRe1?#s$~hrt&~9i1R^O67co9H8Ap4sOSD06thd0SEaFkxfH8 zw~g%Ru@2Haw@-6q^s1}h$|5f;RnLxd>y+!X=6_*7(z)MK9Qb=uAb$&=rmO=#cvHv= z_y~Eq6TE2pBjDwX+!f=;VCd<+{F>_}WYo#Ie@1$MKySEfbiEPm+Rx03uQz(V-V*b& zR+@wIkIUq(n!i1vMH2}&5jWr@%D;zt27H9PjDr_&l;kDt{}#wBJ|sQX3-}0m`8aq1N35$r zzvK#Y;Qz#>!`rr3Z>WlfS%SPc>%2zEd7=DCUXn38{P7R?2zkM{&jm+GUQW$D0P-=3H-mY>j5w^oz1vC_kflFAF;$06{?55H7&s^_DHw zy<^p#+qP`sUlu1lc(6YR9(7X6&>bEf+cUI1Yq9)+(Z^&$qnt0r!9F2`6J4D6a=(s6 z+;H%+cG|E|GnadJ-i4ZdpCssfi9V6q-35FQ$c> zl%IwI)?Hd@uUHt>eTtKTA@$326uJ}_6HQ8U!w@~x;4}bXFpiIdHnYVxVC5IPe`U_VNFF*|z@ODQ%(4MFLPJ6!j z05)F1q0Q%X@KOEniYuynFWs~Iy3wH|=XItK!YhwERoi^S8=R~zSCz_R>NXZn#Dwejk>3l8bVEB7nY&Q^3EH3kuAXbFL#3%P2boa9$=e4YPeuQcyYlP zm7Y0ws!|eO#tpns{x~lWKJb9d8)&?MkC2xyf){Yab_yKUyvm;1=8x{!4qmR9s+EM7 z{%x)G3+0dV;y69$2lc+|{7}DukC2ypzzaBHI}HrWf`;7-5AM!X{ zY9qcK=fMXqIgf9jcKlBsV@Exi^s~^fLO)C6Aq2$0`YGmZ%OT-?ujS7#I8}a@IS&cH z7vn1r>3v9>L8|*%^cy#@Zi?yR9TGk%hlI;qUj0wS&*I2iuKT|#eOL08IwTzOvwwFd z1G$sAoF(LE!Mdr!4hfffa(;iRSL@$(`Ip*t<#+OJST`OL4*ADT{kFa^ADo2T?8kEh zo>*Uje=YwhM#cH(+QH4}R3*mEN(#M%(`HU?jE970 zZ4W=Q&ChbQ?U3-2aAQ0qyrrH=&UdNsH5~Vu*791^asldsev z;gFwtzYb=QrtQqsW<2Q``s5rag?}88V!V1#$40*{ptyUl}MX&1!B(9W%7vmw}3)L^^e|28S4O83x#5O<6 zQT!p{s?WY_e=WvKC-g^AePsJ&JS4m|FR4SqX?K~%xwKcAy0rJe8S9qgT-vj=Z=3&& z{dyShQo5PZ^dX8t(8+9MAyB2CN%rbxjx46ex%bK;ioZ7P*ZUXPvsYZ!N zI0?CV1kVw8VtZXWw3i=qrMCHb)3$IUhm}s0gqv{#H{-zjduNyyE&!HuSO zMBiA9j_manxhdQqc+0V3zpV0_CE=$3skFXP`#dRse0-#IO^O%r5%TgVcmYRjC(#pj zyjbcfmZL4aOdjdYmV}oX122?c<7FVl3-}0m`7U??M{K7+zvLZF7pGrVIl(%WM$5p) zEN%AGT@lEwa(1&lQ~zme{X+Tmz{Z0&K7VlhUE;NuI0b&(0q_y>vJv(_IAYBQ`o)5m zg7izfcwNyh891^1^uraKv`HSgd86mu-IDdllm06xJW9d5QXarfMC= zOCx7|%fY8x>lex&*Dt8^dg4G2@IhYKE-pCYwe86*w)t5ObpVXNFSscC#pmVLsYZwK zQpw4S^Gs`AD8J6jfkzG=Jo=TfgBdViNnYHmg8qo@!!+BhD|1DuZGQez;p-*+bt->2 zHPKm@fHDgDxu zQ_YfaQ-3zijXw_q`Dw?n-BY}PkB}GmM|6EdUh((_zv zUMRobFG=+z?HKSuUdWXTj(AO8@*Xi&6fY|zzKPFEQ3rZJKsV+u?B;ox$rik*J;;=w z2YUDuFKPic9j7M8G#$-h%7HdIsJLTV-H49a$FUKzj~;7!sOhn8{7>wB#>z}Il+$x_ z+GFh>PjvClOz|S*>(%S3qj{Xweo>Ui+7plUf{#l5L-gE8b&qu|Mj&O4r}w@1<NDCw|MP;cZS(U+ zb03k(Z)HeTojF%bxhta?-VC`r?yG~3x9*83|6D!M3XzulKMBR49%kwW>H_M9$~UoV z1FKqCS?!8G&EH>Ws&vDg(WeKY3w9#il}sC_U6_dS>)!IF#I;_Izx+36dfa(~JfDX; z`t&UlefmA38$KxazFk&pzh72w%eD4OMW2TJ)D7-6f&5ywB@`9G^Jh=oqM{6Zvi8ZY1@?Ng1C@M4NSP5G0&IHF(FD;9kk ze1yDQ4_?4g@O`mkyEgi?;^j}LCQ8DKDf%?!kMpu_-EKrMj79qdA0aQ>!3#JdFSgO6 zZS%7n?a?pqoobeZ7gO|U${**&agOc}>OIB__y~F7co7`2ow_#qv~Ta;w|}-IyqKa- zQ~o3`s`WMd1$>Yf^5KFbUfV{Gw$0CSv}b(u)P8qWH0RdM<0Dh_Y097EMMWc3ub6(p zypzsL@V)5&w$Y<)^G78qI{LJltD4#08{eoA zv}*NO9Au0}hvFiKk)&GS%k5TF7+R(P@ z=w&0@s+SJ$-E`3g^|vf9$tC{RylYTYwE1Pub@Kj+Y1i;5##c8W-J48xKZ{=W3U&)K z{m$#}@^1P2H_ALfdv^_s3oQBC_+O`;TXsrcwPL^HtiHgx>xOBkZ$z$>ui0bnPM-1! z`Psj_V}bn1T#jSgKilSy$`j0g7Pbmr)tmG1`IT7zzB0O5*L|wLC}@8Qrk-oHdW`b3 ze-9oPr61I*eqQLa2Ol9Xd~U!|@O{U*U}XEqXr}XcnKMXj^Yho1b5-+kpZB>}nrQRL z*0)v1{5$Y#3r~Gs>ixACFP-3*Yo7Do**k7pxS0HA&#|p}q5K~cMU>J-abCa&dExKs zdd6>!{Axbn%_2X`)gE4M`C6mXcsV|wA9vEg3+0dTlCTRy{eu2i=Y{RVH0RUH>;W&~ zRsIi(7k{;3QToO2!yno((P6ygt---Ht@R7#kMWYYh2ljmKBV1cT6{=*l_~X(3(ly! z)$i>SMMis;_HFaqh>C;tL@Y$XQ6JCX?`BWuiTe0<*t36vw4O}ovu_))Z<#J$)W>&D zI~)HdpD?{$_{i zlS)phda9;eOULhkwWiS7KWZT?7#z`iYP{?@OzZBvyF(*UAL{;W^+ zT>JC4ke~X*7{vt72YGSvobdOUcJ2I%|BQWRf33rKVY_5a`(NC8eueVSHNWCV)dC;n zh4**C5wFkRzNZMtM%J)d&PZ$M6*SIt-?hsKZCLdTKOB+ty>rRsv^I3;NQmg6Z6gTQ~180;@{Nw z5C1)=zr*#gl7tzmUir|pGaKxEaGdA&JI{V_+FAd9rR@3CY2c8b{jK}%KyJ#%)b`X% z+x#qtiUL(=6n9l`&hJf4bXb4u=A5rKod!<%$EEX1_jgkJ`f01+B;@A3cy7QG+bd}I z{9&M$HaGvrR5QlSN(#M%(?(8iOs9cU{snUbPC{;|cQw5ea+7lcyEtyza~k+;hjEh^ zY13)olz+k8fD>}V^0?rM*S7nfZS%7njGkNAX?pl!*DZ(N!*m)r8&-`rnHk<~Y%hFQg>(jHuockcg2}pH+8Ravji+39M?Q$CUtuj_TP5fn!oRTKj zyVP~^l{yU^a_agdnX8*m16Or);#939`owe^IOShRKeSH<;C$|>2b$jt^Z@k(`DxQ> ziJ5hQ(gSmzmUt_k`%fXAK>GVZs_TJ<7JIS+J_9+=~_L~s&vb32|J@WgW2 zo_1)PpXF%VX^AD_#&}v{Yi{K1m%9H>jbp$`$jzPLM$Fxam=>oc zf{&1wkAN3&#OJ%~PfIKbFUHdnTl11WEfIW#yo`eva1`?5pT?TmoMiUGPJeFK>38l6 z%P}8oJS`FO>#?*`r{95(ke82x7jVP|@A}gcOTvrsw8R#?Y?H=M@d7?VUOoX{z!7<| zJ?+poKg&UXPhsnf@xzsp@M1hI5%SZ1F|IQPA0aQCX8=cRC)?8wZS%7ng`bwF<|Q0C zEwRIRspMRjZagiqg?>SuCr=pyALNDY;({Yy+n#o4o1f(<{Io=$7db7l!+3FX@?tzK z(ZEaUv_#BTk{9>WL4U;dVQTBwv(3+P6z)$}bDqv0OigqcFRYKOsqwT#$e*0Qi+(*d z4+Bm@ZaxD$20SsR-|qRB$vH)FQ@B5wrzMtz8{=t-ke_x8+dah#_y~D{e?-?eJDKwQ!TPW55S_Ay+Oq;x&26zJfmZg`#+A*J+8Bn7^=_{Ys|O z5-ES`v_v{gO$$`$Xbw{jw9!Gu7pSO(;dIQVPfLV{njY)MzXvm8{9%$<{Ar2#bfEHB zXF4tMF7(_;b&vIJF#;)TJYBrg636AV#5=@#yGcCOuaVOdKPn#VJLNk0N}ZMnId#pF z%+<}OC8|2xH07?2W_WekyXo3^S|a41t0!6^6+!-aTH+66HzilKQ5R4*RDKxLDOa_y z9^JEEvHH%N97jdXyl8Y}&o2KMRsQS3Q$KHypIPESWDj^L8q>Mcnhp;wCH zKt%(g{4M$ji7<5VrjQr#5%RJRylDC(;3d1>X8HVGJUzXaUvqtR>)6TsYxY#FW>V2s z-8H)22=;ws=Ec_=y2sRNn;3VYc%isn)F?+yG-Z8G&E7h@~ z;q4JPTdO;&J97ZEiv7(Bof~x|e5OO;1JM*W^;dhf5_6;U4CQa7XI?1(9_ktJ5%Tg? z@B)sKyr@_o`CgmHMyoro8>{v74h-+!wS6crFAjMrD(aoj%X+U7F~Dg)f=j!VU{2-&N^?RctYR17@OsOZ>fW*H&TU(^@Gpy#9z56|7`i9vfLu8|I<{vh zGb8@MXj~>V%K1_p>=Qyb(Zz``_s7A+7bnD6JH=0m=Nmj_o)q7YjuL6*^b5ZiKlWu` zOhHiAc)Dnl;%jB%Yo83>Col4x$#tI7l!-4lJ@J*A6o;Jpa~+pSeHJsndR=u?|MP;c zZS(U+b5D5iTNzSSXZ3TuX3S8?kh|l)YMKLbch=85%R+41|0FeT)NS9M}H_@`cL-UBO?dvN($YLsp04k z${*+D{rmT%kNyB3lyNr*WFT_ereCqAH5~v#dP!s<&X0sETr`d`d^(Fa>LZN zy>0We9I8L^kG3mn64dX*Pw*-+UOJ&ais~cVC)3d%lwadT9CJ4*-<66Oq^Bu)&I{Jh1Q=b^OJ0ddBJ}c#RI@MQ@*lUYm~o zp#1Y5{Q*A63-9ZKBVOAc-C>)bKE3xZm+N(HQ6h)KbX2& zza6(%)X^X8ucM)ZqLtCTxZcjlkSqO|3|Bkgs01bwHTA~k4qS1<(Drkv@v_yFogi9&iuh2q2`3b_CFRIm+e{ zIRdD^;yLwKdd{pI0o1#IBY+@3^?>`Yf!u6IrnaH(ZS%7ng&zT=>aBjRH``%)ppw&X zWjX?g@|*NP>WBq!5_0nho*VGQ_6piPe{6##&5bkQxkq)D|Eigj8`BX$lz+k8fRm6L z>RnCmgxutGWEICvdyW9=?J#cmJZDW!M*va&1#<&V$PLTkf+t?v9^qq~pXFdkxWd*~ z;D;+E;l^|X5amzK57pEDPuOwf#f3c=wNLQLR!`XGXL$-A-}ts*pI3|V!Z|PAv#V0W z5kQpRq-Wye8-H;>I3YKzBNsgJ+Sc!Fo1f(rOh*7w{-mBsZU*s>0K&M> zG!M=3GE+9tG|C!c>&R|^d1EfDnrt^)jE2v+l-+BFA-YtLs#`D`9EFm=)()VBG z$e*3!13p^D*Y{63x7;A}ZX>C6p|i)_?a#BQ_Vo1$qgfzerx0$ORL|s&ChbRg_r)Lyx9)p#a)+g-T9<}7s?;wCE-U5^$Yr6ofozb z)0|H)vj@C{SNT6EUi@{TMd=s64}WyZ{f%het`qc2-WnWS(^|h!{unQbTPR+XeM`H` zWZ%+W4O8@AE;wV|s^8luMiuQ@+P96L1nt25EJSuX+7Pv#@8MM0x<}Q%KK9 z?updz-hh3}bkY1r8z-lo178t)R{Tf(;y-fay8o+b`}Qo&zJ>hMC+=f`+`62$^CY(U zS)RiEN2=cX&-HpcOrN-Cs+?f1Flz+k8fRm6L>RnCmgxut`d5hCG?eQPgI*c1W&skHG|A_K0 zm>Y0HZdeW%Jn`Dr|6`k<+nnY90i<37{)n&V}rF2|eTiO(d**BnoCd|mlzFurDfwtE}aX=h)YDTPtv>rCsk ze}-`a(|N|%l$YtEtnn)LI|8@OK^2~oun3nz5b=iO2C)XS0T6?+2Y4dE5dpj$>YABhpf7b?t;tm*kQkQW!vNz^{Ur>^z$sAsJI z1h2Qlc+uNuq1UGU*OY%QKaamo1$>Yf-q!_3ytdsxZJVFvXxIMhN=bMz?Z2k{)Gw^> z_&8U2(b$ig#x1lzn7UfO9Ur%-{nzZT5AVNTTKj*csT1o6aILU7{C8CgZLSB7>uJB! zo^L)A*g<^0f})6LZt?_`^wqgfzetYK~_{xvk=4ZLu!i(&QtaKPJ&75;< zrah6AKgLVKXQAv1-}j0BSLcQ8!_;qYUgSt^^YfO4?}_yL@JFX=9mWgmBWr5f6G{1F zyd-{F@#61^g#Be2`_f)zO1Ix3p(z-@3mF>;mRzA&MXSX5SB~%A)MsOk>~Q zgnf&&`MTtu$VZmy*mvzSa!%w=Wb9j)vrJE&a+*)eIgwAL?Az2ik&tsfePTOywarhi z3LpEbI&-d=YQ*#j@70Z|Y3xh+=NtQye~x|oWjzFS19bs)L-W^xZlKO!eY$78Vzr9z zt0DniG&-_pmmhSS|GMzh&)ef?7WZ#<<4Ea-Bjo+OVeG4y#Jy`{;QzfhNOj$ye_y|T z?!=c*pR#7ZJfBBhAgfX~NDORwAA(n?8z!cl`prh&z>9AtkEnSayJ z&TS(*dNx<9+xVwk>D+z9$mms9zct(M`hCQ$QxhfWBlOBq9QbjeAb*QKLVPX<{qx!U zF$(wydASF?X!;}ICC>?HK?(i+t3AD!UvqtR>)6S9sTY2|40^*|qw9@e$75z*e7(`@ zHA~FPTB&}@KaMyHC$wl1!6xDcoP^x$12^D_*#mCY@iKEdP#qf@-X4LowYsCaGY3Gc z*x#(sxe;quBKc>2DQ@bo_GU}WjnXrezm=YOq5ON;FM*GcmoI}CaK!o#cu}i$^Sw5Y zjaGMFH&*NE9T?udYx_`MUW#7_u6SARxeo_&E9p31&nIbTO;E2)(yyW+(T{^sNd-aB@XqY9)i?hz_EjcfgKgmmSzq4=0fRB(DjQd=0l;q{q z+yfv#E^g1}9U~)oRzI^8jHb2W%_@WP=m+`MPI*ga*>BR=Zru;EpS}*!Q|Eu%D_F-zf zXu~!?%Tf5E55Et;f5SwF@xuDZnwl1UQ2rP%iJw;XsIm%acbOJ_&|YOqz2ky2>TcS% zv}bAGR+a@DK$)L~Xh(paJXWr;9bjz7ae~sBIcs|IBi|2&D$JDm}u+7hM6yE>% z&)E3>*$(4{^^r9-1?ZvtbM-&|#3}e7FTB4Cj(BYwV8=E;%Tc^z<{?=$^5ZG@pQ3pK z_Nmc5yXTWBKo8}oexbyv06p_9QpJ24?GRV%w^_GJuc-h%?60E$J!*Tu{;Hq%-~*Su zKKQFRi$veW-scA2PyFq?)lYr!T-+;Rr^|1sYxO$(_rvu-29_KTwC8ER)1G%<5ZLp4 zzJexnoWV!$I7WSr4sN`ny7$sOyRRD^x}nN1Eg)r<9?3qoXS6D(IA&TUrtJCKu;Mm?fJoLg7#r$9cQhv2PzxeEGb9kC2xifEP{Q*d8omn?Gu} zf&)AGdgi>TT1j{rH}FFFf1DT5I_C%VzU%x@zkrXBms#)vj@V8E!?Iv^_wdM0{vl&(n?Jf;J9v59 z)I>>mnKAG}`IEeiV~ic^kHAOB%VXdL9I>4)8QQvM=g{cz*p2*4w$wI%bhkF}A{#!N zCE=xBZLMD@f0CD(G%w&Iez+bM}~3~aQ$D(g7JZY*^=?w!$YAu%;Cu0F^?4!RW%9G!g5Wr}BE1di?Ln&hSrR`k7w&(;_mMuc<;dy3dhn0L z*KvpgVyu6B+Ii$h;xl-s+dpCssfyOW^L|S;b#t!Ut)CsVKjosIh4PP^`tAPX?~@?+7l!j%;3VYc zgLn?W6MsKw_xvX!ENyOfPt{`Fbiz2Ik&~OAb6Rsl`4`L$I0?C--qrL@$W11%I;peQ zSNx@A&Kru=H~8U3hjGLD$eKl@|QrTocpsMxW3{{%aZytuIEqV@?s+4e8C`B|RA4{r8t!IP$%F1 z!IaY@*MsUh`KsUm`EZ;BIdy%K%;h+22mS90y|&HI`xM>}`E~Y+Dfgcve+!xCJ-aEL zLHkoCj;|^ILi(Y7G6v^!Pd!j^u|E;>ZT$U$4;;-o+ES&N=fKgA;JN=e(oZDQ`Sd^q z^J`2O?ZD9k-<)=C`Dc0V*NPsvV!tyk*E8xm`AQu)3i+uA-0?vEWG)%E4sG94)&H2` z+BSc5t6-k3Fh9MjH|P8Ndpk@IRC3Ojm<}AJ{F+^n9>0K(kQY8T;E3(yw|D;OHEZ5j z4#z2Y9gxq<5mS{IFDs*)b>An$fuoc^&ddAvKmFCzco%$-7gmt2XUI!lMPHnLDR>T-vKlUD|u#jCIR#F6~*`x9)1}*TZ<1?LIR)?vHaX+_Q7*m@JQ0($B$e*A88AdoM}s*K5GOWqQuNYo=fI z&N~kMIJYL_T35!k^^eHC&zW-8%Jo(0ac=E^cHk)Fr#^8fTHCjm+AS+|Z1a;V6(GG( zKl0?!a;V_Tyos1T>1uoBCqetOJ~_^%{K;`{UG`iB@6>!NI0?D=G@cvq#NWSkXfHqJ zN^SG=rfuP7a-G*K2{+>gZYaOT&46&@zf;_RlaQOwfE!Kkh`z8G9XW;Ro5KBpw;U_u z=~dorNx12MDy?t)d3wm7v|s98iWl$^^71+G0*?56i=MFK#ZphP9Btuc@<`A9muMcg zoBO93122?c<7FVl3-}0mxeL62BeqkZU-FKoi_f1Hf-7r_fSA}w0 zFJNy;EM6h_2zlW=12|$kT`bnJ&C51F@4X7~a2iGRM`~WedGA!C!+5FWjfeAeYyCp` z=?{{GpFC~79;DTxG8+STmHKMw=> zX~(eLQ@ntWkQewzbbUi!@{W{>;zf;<{Pnd(^-HK2_kWgS9;WBH*1S-Dyv*7Q)*W8FM5@a*!3(NInsR%XAJznvvj9_vgi zvnSDWBW;{{VZuW_-@O-YWp;gf+Ufb4tj7L`=k(m>Iel`yORlw7YGpR$)HREit$SBy zt2(RS>Gj5XB0day9dyIBX=OI$Ux>xKPm}_md+LG4Zv=XP`hj&-?8@vMp$}LP(F42X z{hVp#%6>fe_aSX2)A{s36DwDkF51d$_p{T^#DuKIzTI=`@AI5}pP6=^m22&lTA2;` zsRvvykYCGYy;8O)3q!4hD|Bb6syF9WuhL<9pxKx21K=6F|5p{{Bd4x|L})jpIVs>KFACC(De*?S?m#S z;Su*BaHAx=m{w*}{x~mEHEI2V{#WOP+%UD(54QPPj>1=F`+fKayoneu-E5bdR%TOv zjhEEQY}#F>0Wj@VrY`M0aK^gjIG6S;?c2(4VFfeByKMKKo6{?^{T;{`@5~ezQNCWi zt~x43uJL`Shx@Z$0!YvwOcj?KJNbTW!K~ z92x6Aa=)CE_z!9O_OW2bEnJxbIp@{u_On|B5#Hbsn3#c31{}kv3>I~Lrn|5tvRuJ><+IRrE;8CRC zMS5?L>bhaQrW@R2@O`9yEY&{b%Xm*AP?J- zsqL-{+x#p?TUOu8u8rB4Zs_WH^7aice;JoMsG>DG40x*{K>IRi(MPwBjn{@ zzzaCy^WE*cHYz3I#k6aK@@u@LcWr==ke7c2FW@NT#orZ{ccyLW@7k!9gcsAU4a%>N zbyBPF!AHo;Bj5!bg}nH?!Yp`M;=48)CE>-iYlHH~dD$k7pW+34guHwkynrL}V!P|Y zHb2YJu3Z}wCE>-iYlHH$KQivx03RVQoM!+>Y$w}Y7q30ssCkLWPkYS{lf5{adlB+>&xs(Y;U z8&}||X1ZwS)m0{^o!PHQ%sg4mGV@oS^X&gS?X3T5YBfvhygJBF&En1ma_e&1p37pJ zpXE^&Z=rDpRlN=VjaQ5HM0^-{&!w1Fa<0}komWTsO%`uz6)rdlxp@rF4R~Um1?`^S zR`u_7Z>(i z)IPx{TRmZ$pXDihCeOD8@APJ4ymW$H!}`dawm5f8#b2TPCOwmynE@x{hUIX<6R&M& zR&4XL9EHbU!4JESL^HtM%#G>1I?A8aGs&4>6)u6}KGVRPE4ss!<4y3yy5)*+j;A@k zZXAo<&=_~K-QBZZvHH%N97o0Pzi4!1&n|zf2>*5Ash_vU&n!De@|_2Ngp=XCx~DKs zaIW;DAvS$CG-!0N7yG0(Boewjgm+`e4W6N%lp7d@JmN(oj0(q%V z+@G}`U;8bvrH|P&r#!bXb4D%0YKi0T?-n`!^GA@c%_CdiRvpWEhrt)g9K;E-!={|C zkOQ=P$iXvs4!{R%C*UCGphtcL=WG%|YC)o*2y7nZ7Lr~k8FZ>(QgSjO)7 zmf}Fg^`iVOX8dI*;=!9jUcg7l%d_A`(;opZ+2=)BtNwVWr}y$}uCHz#JDGpYo~j)I zN^iJpbiEN+$eDTZ^+vB(DKRg~ex>}hUr%V!G=fdU4LAw8`31NEPs|>0lh;oqJJ_mY zL&Mu6aJE)=RCne8XchaLmhs>+ZF~(xQ{2>F?bS-mjnXrezm=YOq5ONOXTV3u%dfx- zI7;$zIxjP)o5x10JFgq7_4E!5@7}e2C@(J#d8xIGo1M8_j?c?_uMy*gHhK0R>%1K7 zmneU7ywhS{1$>0OJP%&L5o;jOFR$Ze=Je9xZQH9iR7JxqL0+77-bBfHq5Mf+lH+54 zWfb@bdBM2P1xExU;N{fZ1E9^dp>5Tk%{xX$#%lb{Jn0JRm!jfL`gY8@UM05ExorAH zEhwP;T)D6;?0^6S0b!%L0EgFGwp90yRd;UNvW0(Hob=$q{=m>ZDP`ymkB;pb+Mcyo zYGCBtRq6rqJ|Tn?U7Yx;9EUI|SYX0x9sJfE$EeT#13#*!zpkk6y=-K7ca`5*Sn6l# zk-TGjMyoRQl{KuGT3B+cynks51Gqex;Bt>b`kP3PZawkk-u9+B!-H;ohco^2>tA!| zC%zu}^0c$}9vQswweDLeAIKl6*=s>nV0^JX+5KOq5Mf+2K!UIfRB)u z)!+pjv7LemE?#9%ZSzNWYy&SdAM<)k!pn?-7s{XHWxPMA_g&|Q`UQN1ywIKlM{K7} zBYUo^?X2$J%|B#JZSzOB3wSB)U^%5<#y{azO2SM1O|A6{Te}O|)F-J!JSEzb`uu<&adq9cS5c$?U(>-}G1Bzw!5@{H>q$=-;C47LGFS_{zW5=FMdZ z@)aYSF519vEG+f4_NJj7yK)8?SM%mIdH=#RZ+;BM<4ljm^>IO}FBomy{hrx7Zi>p@ zz=lkw7yZTK-Vfj1H|03HE|A$sk+wIZ#L;hO`c(gt%#nXi`l?R_$LI9P^+vhYUhZ*s zC+E!}x8A>N*&JJY&NhEk9&E@g>L7DfZ!+F&c3A)Jo|Z4f(Ky+<;?61{QLNQ0S)0XZoGj-{sx%_isGkagJ)MJr5njV#p~$pPF_m zAD4A7@AaI?9iDTQT;C?w+H3Y0&7Oz+>~Gzd2J&m!mXJLk_yY>_AE|nqx!LQD^|#&Z zpRT{CwS7kU+200_i$8BAD8&3n;3MRP&kZ;tH@-ceb{rAr@N3o?~0{Lit&|oPl^I4ZKkP7%#MqB#rTc{#WOP?Zeb>Z(ig`ZS(V%iWlGCSd@NIeR%x_ zuhC(=us*V;gKJvr7s?;wCGpeB9#!K%+FhpcAMMpJMgQf3GwN>Ix3p(z-!^_50S+*4 z%|aA^9A>`GQrWkej>GJOeT%em_JxUc-B-mnf>73Yx@gB?_BS6ES^~A$P}p)pQ&te0o8Zg=62xO=I8FpbO4Gx;~lex`FaB zbzg+dl}HzD>^uHXGVXma8vAaP>s#bnd!@#{ke|B2Jw1?L%htVPUsZ21_HD*=Lm9`u zlz-l_FZc*~;d29y$c=AX=6`IL?$}rHB4gj#7%#M+DEm@O8wHPjDSvC*G&Yt2ALNB~ zqw5*lv8!!T4%wYWqJ;-&ka)DzIE?OuGOl*u4Q`VWsiF&-gw5LU#nG{k>L4{ zh<*FFa@_m-J!h?4um4uczD=#wg52}z6Wg^`w)x4GjI?AnW0_N!Z%5VJ;3vIGhv}2b zx_teQX{{FJPujQs`UI)^n7xAMgS@zSPNMb+KH2skw)t6}!uucfjE(=LSL-ldSRYwa z(^@UcKUe?buhjw{}`3e&&l`UwOaA|aT4PasW8;r;lKO%bjX@M z+ViyEY0o!%uvQE6){x0*Pq6OS^5++vDtkUtuj6<=2KCt|@Lb&hE#E&_TW(d7Cy~nux{`X@^T?~ z(ey{aOZNurZkCuAKh_!K9~Yxn*}d}y>jozwHx+OLp7^W<+;nfS?%5J^qx1~rZ>47v z!Medm$jckR3ph&h(!IgD-A6mi-^F&ZP1!F|{^Wdsj5GU>zfay5hIS122zj{#ynrK? zC(tk58?3vx|3vhV7rCWn_tASC^;b7gI=;Fjz<9D%$8xC!9(4JG^vk$n{#Mhjsz;8sycqP)S zkiIoYbw@VkW7>cto9UvR0^k3*EI9m;II?jH{DH@&oxUHZ9NDQ;;2}SsYj;y1H|1k$ z8*JM)Kg&`0De$V^j#QXF3I*@-LVha1wGuy{qY+kelo(-$$=Febb&(;2Ryr4WH+% zsp%AW%D-T4zzMlwIb86>YujM$w)t6(cAWx0Q4(%Ur@&MGBvGr~D>86JJQ8w)t5eb(*ukP`s$auqKa|If<8f?sp=` zO(%?#SRa|wp9JmCeCoMY4r0om?1$>INGW)y`XO)n#a4;|6XhzsAjgaO1yI+<=pin^AD1=^fD*`6p$h(TmbIg^!bNIaYM?Dz8!! zZu*}}>l?MOfbu8pm%5kY1$>0OjDZ($#OGV|gdH!IdWz*}3onyLdbN`9GGpL{@@u>d zq<8@zAul(87jVRO3iM0P$vgRxqV&ruCz!u$tk4f3k+3o>Y>u>15?<;*ZLMD@zrJv3 z@W$s4j=xK0GsN!k$J5{=>JS9{aI+-5Od5Eh{Ope~y%26T z3-t^52zlW=12|$kT`bnJ&C51F@4X6#O&8W5sdp=AE!(z!P)&?QSu$E{dDN{YV>+l)3UJrz$1krv7Z2 z8-E@K^3#rCyQg>oA0aRBkLdb_yyP7z6~&7hC;7pd3m#Y3O2SLebFF!y{CdA6+$8N7 z@IhY4l?#q|O5A?Tz^hyV%aQ%xZU?y za|^ukSo_*oy~>!7sJ|J`??=SHe~tfOzX{&dy@ zYo=fF$#)!jkM&*|8Lk!UZSW)Ft-j53dgZ#7_E=Xw^rfW78glBIMVF54p#OcL*S7h2 zpTaF(RcG}(y+*7j;={muc2hco_NPqrSX2ImSiJj0Bk;MW9%#N2AyKe`g}>i_PwM!p zp|KkOb>ZoylFRD+D$xVG<^7yN54a6H_wPmezGOO|9&nFE2ydjveEJ`~6R%ar(YANx zN}5#_dhMTOmgx52INH0uIqe*fYwgv1opyW`5wz|A>RGPu6=aUqmn8^NTv9D|RL7d|)Oi0wp+G*4Jk^&7?U5*&BdD3X`S z+q`Csmu|L5oikhWLisgb?oDk`2Os2xeCT?Hye#&JSJqTWZy__Wh4B(dJX;c8#tpns zevOy3enJ1M^FnTz+Uf_}{49qGx$Do66vd0*hkw9x|5r3~pYH3UyLbAh{Mp(z_h&ZRv|`?hg1c0Oag%laPt)*b#hcXMrM zTXj^8a<8cFy=-K7ca`5*Sn6l#k-TGjMyojtT{X_VRo=fe*|)dAp1mFEok%|tq`H0U z-ub4)aaOt%8{gqf|NQ#bwB5ed@9RAL!)a&N_hgl^g!>zOpV+u^Jt^1Pt9IEJlH**+ zPkrKkAdp+j=GgA=vCYr&$YErD|Kk?5GF#Q#;GJG?hv}1M&YjQBlNQ42u?z7K8WWAJTc!}_#tO%n?Jg3!FJ2cGxCf%UM0p&H`}@6Ex7SLJCI-R zhaBhap1cPXUp_D3Bjn{)@S^D(+nuMj`6FHm9v3M+)ALcURuW$NH>UNB;)U`jd6|?I zO&TxYBjn{a@B)t5P6O4kp_%Ql@@X7Y5BHR2?c?OmjI`5*!mXjawW@Ef?ZXmj6_k5Z( z@Iv`@UQ**D@IhW!GcGvdwe3+ww)t6(arfJN3HI^Qs(o{@SHxm z-j!Y-mWpTs`Psj_9}nbaJ2JK1!E2kJM3YKMxG_aEq5K**vOm)h(FB}?+6f-es3-|9ridmJkYC?d|X1)_S zOc6~ee_X$y&XYTV!3TL^ySU(p*R~N!Z1b}mg-0||yf~Y^-VWoXxjr8+ridn#U*{zi z(FF6A%EGURWPlQ&U6}%AcHviGDrh*99jb zH}}Af0Z+{7w|f^yG^v$@8&gCR%1=9n?VjQVe1yEvKceXy@{)I?RFs}+S45LWNq8|u zG@<-@za-ow?HKSuUdWXTj(AO8x;3K7-k86z6YO5LOV-pB(S-7+BAU=)YTD36M>A6z zz%Du{F62;-X%)eQj@fiX6L_fUv36gLh$h(aMM>SWUa|Vln;b{&@w#YqWX~=?oC*JR z;i;du$IpC9-)Y%B7|LUPguE9V(d5hMxtmBekM(>df9}MWPoJ`8|DoUM)%VP_^RS%5 zI{AB^GkLM+%sed~?5D)~Z~Y2aNJCy~7Wb>IE#BZT?7r4Nwt&Afvdsd%I_Fnb%NZR0 z3dZC0SV=kWF!&;=qZ4FTN;zL42Wa<@gL}b0_+ae>9OSh}90zCWSPz)hNZA}?ZDjPS ztKZ5ZFDzBhPJNR%5wl1Zma#j&r8rPKaVUQai$r!2AM|$+`#ZP5N65=0c+vDnz{?rA zE6Lxv)zf?VHP=_Sj-8zQXQT%R^oF}e*Bike)Xcp2dZX8CmY5e6`;+o>qMF` ze=9xnLizWwUjiQ?FCKUSM@e2z=Vj(}^Vn#0=XGPXo?h9TvupcMUS1sXQdDFMpO^KX zdrcs>5{$-rW+6K;1N$Y)pPX5dRk!-t+u$SQ!=@&KOLHRkevMlU?00aSHQ@8+!*ITwoG@9zpZCkeRFN>2NJlO9K zjNFq_hVJm_*q))xyW-Wr$hoT21LS=|2q(HY@zp#9Av`f5#@24j#8(czlX>Fnesq+N z1Zm~;#JXG#}s;%n{rw6pIHF{)+at1c5?&5usYzPb4)z9283YxjZ3z>3QlDE{1f z-^n>G6)%GS`S8S7s!FW>5bAfdd&t2E4O2 zX32S>{7GI~OniZlkQa>mTyT`+CC301Kd{s%zM3VU_@eyji7x;_KnR2jaCqId6JKgz zH2Id&PkeErixXdsKE(FM$}e&-_+X3J-ftPYp~^2TFjZL?+IxXn5?@mjUmudUF}C-& z(J}rA=`7O6f>fXQa(jZmCvFnEm^yLU^t*Q-B`dy;yFmQm8|2(Ec^`t;+FRtzs`to5 z*VVG(>qwdSdcRDBsq5s+y&{M~6;60Sem>Xkqpjt$jm>SFpHdVa+gsIJ|LNXrhZzdZ zbyp{1=dga}OUKdv{GQ@K4PYrh2eABirl~dS;3VYcyLfKE6Z6@|TDHy4augnWS8+3W zrsr;ro|l!;&ARSW|CmYyJz`XX_A4x1#EjA|j2zi+SFPgrwjfHBPKWeywW2yRj z<~*;rB)rTRc%l4pUV_-W8ZY1@<)16Ix4-ffe2^Emiwll;Z5#XF zHb2WDYx0XdJHVg2dZ{;C5?;m)yik5!zr^QX9+tq-oQM3U!?EDiSO9N-T!66w|EAKz ze-G;Da6KIQdQf%Fx8pDlyhw#DvF!WBIE8 zYEMk~zRWAu=8Xye1jgmRLi#+?eL<@GTV`VpStV!#G2xjmT1@!b?Xs}=RZO2veS{Osr5Cj+^)Y_g+hr~ao**S7h2v$n+cmYDGFwn*-7o;Nqegs1#T zf6E*(;lWAB%>g_&;EC;J8`Ir3Kg-b;ZX_mrZ%Mc@#e}E)8aD&d$N2BKo#>A%z)8r> zQ{YC^JKY`=zEToyOflgpe{x*WA|^ce2zmJ#cmYRzzPmjpe61wBm}0_HevOxOOnC4S z^70IL0Y@P(T^T^;9(;tnaGn7iv7KyVy4&Vw zISP*nujVECFZE_SjF(2v^^B&N@RUEUUr^`CSgPQIys%wdaKvld5OucsS&qVE!Yf`T zH+gO~(5vb`oiHC$$;pc;COqZWc}c~D$9yGuahD)(T=|nz zm6C8{iV08oX~(eLQ@ntWkQewzbbUi!@`j=)ikEi9gs+u^7gJ1l%CGlJ!cEeS0UzXr zT)E(g*W@K{NP(hwS>aRy{ZdrqG6;BE%wO0Eb`0AkYif!KPx-ll(|07VmtUvD)EE;U z8~NyPrUA?jii@|DV_G??>6lH&golTk9&7h>#DvEUC~2EK)|vOR&+D;Xg`WC2q-&9` zKzc?pG?shvB?*hL36C|?Me|tKrzHmb*JN}k9&1ND)_rolORlw7%3}@rsaae%kXy^v z^&aa+NqQoa$C~mdE#5gi*5D-MW;LD{@I-!WJCQyxh05%O{jcmYQ&PoQ7&&cn#5_e=Z~ z^WKv1V)9s1{x~l!J=WkO++pSZSq)C{dn{Ue&bAuoAHN=50Jc6qF4OTvrEV@>(>eo44V+A-jRypSsw9PygGbgReuk&=6? zDSygiO^2z;W6iD5OlbhS=%93uH661lk2O8i^jJ4vi^H7Y$tH>Ih-rIDUti{qbKaP? zJ?N=lh4d7peMohW^-0l8AZ3lGix$(i?<->I-y_zW95_~&n6@)tmQ&5;T6?8p+CqM6 z7Wa1pxwUMLZA@C*{47u5F>O`7Ij4K>by2(WVc}?%}ID( zz!U2%ckn>`fNg%3qwpAC{_}RG*Bj$zWpuNy`(%n~OZnp#@9iIciNx#BVtj#*ke640 z7fs*T#-z2)A2nRTF>QT4bDmcz2`{FYwv<24i^O+H$3O-jAuqk)1st)Rf|!xK%AVTh zkM7t8Ug`s0tt7mdV%k#vI4?nrAXW3Rn6}^}NV-k{4C$T7LvSLSAV9gCn*R+PnK=+WPj(<=#X|crnGarTpZ@7}FMfkQegd zf+Jqr#-z2)&vLX!zr5LNmV_5mOk2uNUZVQe^b6(@$cu~lgy{RhC)=2`w)t6}!eiR1 zxrqK_z1bKqoiMIuePm8eF-jr-yfJOT2YKQBU2w!}+nBVr`B{#_W7_(2S1yFlPRVx<=6E~+=JxDw8cE+;h46LiVcdliXG~IR*k{Wk{MvFDxR$#)0X}f`db>W!x@6uDX8+PmwVPLR^NG(<6Jhft$NYu$evyPY1qNPW%<9K zx5v+XO5drO-7ON2cbRj9yr0JsK6USZ|Kx9<$G2V<_cV;t`;lt?7XADB^>Zh_eEO6% z`==b|s0$A18G?OZ7yrtAV&nXt#I(Iw{4Mv(j=_IO`CC}t@C-r7%YNQHJ&>EuHY&M{|X^s1}h$|5f;RnLyI z$?J{Tdkf3h9p6$Ms6)yre~T3$&OtHyLSDc}$jf^0qUn!-m&~Ea!%FohMtgcMzvlYt z*0GbrKWF}+c8Dro+%-BcfhRaKFTURB^(rOiMV&oL`RS)Up+(CGHW4@AB;@8S_Or=; zC*UUUx*-`2R>y{hw@2V?t?sDq%mL6U_BSo{Opars6gTx(d$kgCqx1~rZ>48mDE}Vn z8SoMEat?R_N5n1Q<#b+VPB)K@R(D=ER_o~%kL|AQLwR{|$V=^{(EbhVlMAdn$9>?44Ic1vYVHBh=GxGj+^ot6KMESXrby=uT00aSHqqzWw*ITw!_l{L}Zriej ze_5RL;KBaD&^;+-=njvL?HSshwODFkRDVmU2gv)>VNRIn;>1_wOdRHf1;?z`HZ3&H z+*8fF(0Btn#>n>EeaPQg8jId(93r6e?%t+q!F7XiWJzfYsYSWiWt~kedtfynrX> z&%L4xKVX}mW-@rZ*eoW@U7M##O~iQV>IqfDLSxE5??PknL0;G{E;!<~?LuMO{47WD3ysxW)l0o*Nq8|WG^YHz zeu>Y&_zR6O4|#Z@u_FsP`Bn=${m%+hewOs`--G%%Tn~r79#oz4ZC+@soNwx_FEplq zh5i=zY#c=bKa6DYUu{`v+?RcUW9Eg%+b~WaMf&=rzlHLd(nVWn+%qoYr#q&dna_)_ zWx{hF{^+!G^qnbx3(Fn)Q6Vq;dH32tZhntx;Aqe7XLoWg1Lp0+^zcICuqq1q5ORQa z4>_oTfAGPZ1sr654w-++E;LrpPXA}U*_ge@GM6D$9H<3=l)u#iz{Emh@DcKIJ$TXd zN5D(>E;M$pkNhWP;DjnB={v+R6Ccf@nvCR3kVTZjthK})Or0+ud zJ4m&OuS!fosB*Y#-t3>r%XHDs;N5k*Omy8UgZIDloSu)$TdoJ?T6?9=;D!8ruH72~ zxwUNFe+F;NP*|x8-%Zy)xyO%8K#@3rZ9skwV1s|3;|yMK5^}Q_&kK0s@7ta|XPckp zXxkaQCE><+25)O_2E@7IzvB+l1L8?>!AZ!?+rf>dce?%z-jZ-*JcAeVCkG}i&fo=Afk`T5Z@eS=sW%bZ40JFIUxRvcPKdb1_r#drp9YhKc4@Pdz! zmp=h7;E0VI=$HHs9Ldk0vP#uiK|U`nBRJ&$Y4>f>gnT#KGsZJ`A-_JcnmU6QeEk3H zy$zUTS9KkFC1mAB!Hyzh8Doscn2$Gf95NaSN&JbH5TXP^2#qWYgsG|SuI?_TyQ`?G z?)ixwkFkO)GQkQ4jQPtL1D+6q3C2Xm#F;>eS9S!CIDUQ(A$|&W$OQWlk~oAA9%Svk z*Sb}8>y|WKRU=PNGv7CT?m2bOI)Cfzv(G+1H{;83@`XH73xs@`f-mR#H+XjmU&ele zw}3B8X#5erkRKUeUQ51^N8-!0-_V^lzVdO_zQMao_%ikzyez-;7n&Dra~u90f1b^& zT;C->GQP;pKpw^WNiyv>bf=B4e9ZhCyk?g;@&4}W4&zJd`@^oIdO1^f>^FD|yG^fFUvn{zw4uq*kQ<%j5qgEk0GBF zQ{Tv(bY?v(-k2Wa2VrJ4ufFZCfHz!cbD*G>^FE>{`|ZeycyPG$Pe*Fyh_O<`Nfw>x46xUFBc`HkT0{kxr_z; z+AjYFugb3t1%7qrwWu5|n2!4fuNIm!R}*axP}==v6D>QTp@rFzZ}4h`S}WF_>v$(T zk8FsEd+s@LnLXdMxv|);)i>;Jc;D_~S2l0sA6~DnRGZs~G5o5nSa-2vea3gfzkwsS z+}w)wUAYzO;nb4kQ{VeT4_y50w>y0yeedH~Z4XgP7^>Mpd?xQS_`$qcTL^mfJI=}gIr{Dfl{bWkq%_8^C zTmQ8C!$+@%Y-l{X--|eSFXX~&@r?+`hCM&uO)iCh-_MNfW=SvquhQbBF&8UMHXHGF=-$rizw~hbb7^ly_g?jrt=)Q~YrFX@y^PE1f^2zN`pO^d9@?Ux2 z7eD>C9{sug{F|ZA-v@mjS2CRX#cuMIH$k8O`y=}N>1XBid6r+}ZTi+Izse^!+CjeU zyVJ&3inhAt`ut<_*L6*pg4NsnuXH;*Y`pD#-(>py@n?_fXLh_=kt#Rs*=y#v%;I?ech7-yx9r606R~Zj5m9pQ_LHc|BQJ< zo@Bg{+|9|Ij5qtUCfwG;?06HqN7Gr!873ebsi>(l6t@TJ9svuk#5$ z>%s4N;QQYDlaK!V`UrN-KHg4$zYF%+w|0}g@UM=Z{w}@wH-^{CSkAmW$(L)|c9=H4 z@-y>s$m;CiJG!M^B2OM-`>Q^!U)wmO@}J2#bU!BG>i3cZofmLV4ef2hpa1APa(1@u zTG#@K2DZuXwSpXI;s5^}XJ>mH`~BnTJ|X8mf*k14&L;P=_y11!hnM%AbvYpUtolyA z_S3Md{VkjreOos<_=awB68_J^pZnLlCiD?&f7dHme#wFK@+f~US~9I(Fm3#Pe!|W+ zv-ykF+e2^euI?~7P@2$Qa`4(webn>{l|QFfjLu)kkBl$sH{_Ap$=iE!^V-yWQ$A+? z*$v~%iMMt;1AN&D_O*U}Z1d@v#e7lu2l?{p2OoUy$b6Ul5MPvfUe1Uw6Pnd#$d?jE ziy5BcXMs=d626=m!xxo*kT0m3QTf90H_sRGM((uZ$+Yp659}zM?dcRB!{6BL4e(`T ztnVkj+o+sz`#j5^Bx_aFVg48qj*0_CjKri z0j7Mr5S@s}0L7nNUpF}43~zhs|lw|@h-50M|@OZ<-Uj69P6 z###%zU$?O^r-*c?jo*hm3**uJuXa1TgfDw;FXoHNFTV8aJNJ29&I`qtl=H*>`|&jG z`L}7~_w#dOd>(gJ=UZ%UdE$-TlLLH_ZJ?j#`SWyY3}00KJYPoUN92e2qMAv`Bl)L2 z|2A!W(AOZal|K(TyL`5*55T<fZO8FTOrW9{YT(THJsSz~TSw|3SPC|C>LIdD8~$=C6l6 zZ@rtG*uryt#BP52vfRE9mS5w0`t&IOFgWhasVwG$w&kBTem}98Kg?{tY4vvMp6=;^ z@%?UFjqrY`!wzg`z`3W*Fm?vW<S4ZqN1kN7DY4&> zPin7ezg{Qxk zJC#3wH}c5W%*c<7FSn5|arw+_cKA17-z7gX zzR1o%9>x3T@z?K+FMEEcTiRiKNe@i69x(3fcPjs&d|}%Ue>H~u5MRWPlsuAu+OOA5 z8(;aD`Pc7^FAx38?&=QXOYio{_%iP6cPf9LFC$;SqrFmmN$-mBNbMtc+H;=M##cVf z4r5<2o7sJR$1AXPe&v&$9mW^c$9COuU%ylNhwU(Z^btD@d6Mzw71U$MC&l!3KPT=l z;Mb{Uwa=AbzdN~0cr)(ncPhX17`6KdU&xP)FI*qV%Ny}!(wX(F8CzWl|1{f_q+%a_k9_@33#Q{1rnS(VxteH`Sc41GmXH=^_4T{`TCvs&wN|VVJp@Tdn5js0CWC*16?6EHKMkuR!~aHZ#Ao>>S<-`1?%`O;Idqf3jBmuZdOP*;?&*P% zNSz^H2j`N%GvN$r+>Q7u|2U0zC1MOrMGj(WHak=H{z@OXUrS&B;$?bZcgrGyqQq-ogHt^&W-qccNlNfpSSCdyAfaI zKV#mIC*qCrk&;jHPkWQawDFaXvvnhWX_xS3+>Q7u|L_bOCkOI3;!}?kUsCFG{q~8c zY30PU@s*#M-$d-X;BRzS2l%oR^cvO2w%vl8&Fv;)m4BR^8L`ZeC*qCrk&;jHPitA3 zHoo$4wr<4l>=NFLyAfaIAC@x(H{x^tH*Vss`Lf(p^G)(eeNyvl&8IcLF5SwT0=Y9> z?VdjCsh7Otr||V@d^`Gu&H84;KP|6c&)oI6dpz>f_w9e?nMdTCHoyK$_00sp+FPK!PtmvS>dOe*j+l#ZNy0C@J~98rxd~G^_}!?ZA3%HU&VLyX*zOq* zHrNly57kcaV8TfcKyI&WEY;WdOuZm&E79XE{`KZvFMoxyd}glo9qe2 zE#raR%$J_P%uC)%alP(-kVs*W`F#&-t)_7C6ve;I3&)hZM9RC~L)4P~ACTCRsB02My@p~p`$d8OKZSsXY zQpE>fCjVf{fp)XHvC>}Mvln-}HP$MV@+A>pX0>y{`EqSHy}fV8l}@g*pU_YIk?Jb=a*e#(c3)CkTB~kVAz{uzz9d(6_wI7OsQklx8J-{e{D=I= z_`-Q#N*;+A!I$lyNLKs|EGw^2Ih3 zsQlWwa6vWzkq{z?8X_fe%El%_br$f5Ai~+v0c;-V^`73|U|U#$z!{k!+AGkZkDva>xeB3{}>wKNCBt za4^}ht^wr0+M407os-Q+%8lXB_k zH7O&XiDfw-Nj6OTnb&FKtG;KxIBRuw@c!=VfNVIQmBMkKiB9YOtG za-j1oAqONM6mN#tfkFh>#ZQy{GdW<_fqs45b)bKn{rhf95d{ zeD&Agf7a!|2v;xtp$C%N9uH1KKSUI%LR zmVCI|8IS|tkuUstNn((s>-k1n{dOaVN4re`I!0jj>eZ$ zAL*VP;LAu~RO085Tbl6r@3`wgRsMnN`iif2BtOI#RY_jXczaL2=6dd42Wosd{!hET z9mbd5gqxJdT?eZ2KO$c^{^t22-pHNyI?rk2D<3nz4%El+likxhj4!H>?YiTx16BD4 z_%Z}-^HS3arFV_p{Ka{y^j688lsuE{);w4Gtn}N`dqclfd}ZS7Z2sE*=A&(I{(2qt z+c$;#NcyeHEBC~kuX^AK|LM2Rx_+zlGI!7I&~44`g@aWGPvVID%b>TxE;i<0W&>k+ zB~Q{$v3?tiAKR~gB|qWTEJe@UZ*Ts}s$wP&84uX*84vDdKOjGpSnyzSMdX~_{AGRT z)Caohfskh^?{0C82WAUZ`3r2J!<)azkBl#`Ctq^%BlvRuZvNW4i}_-kzf^wN#~yL> z7kQHL<_+Wx`K109yg7e2f0cGIZ+y*#%0qA}(M20RI zzS3WfiJ}Z*s-3g*9h`mJ)`ZRQ^|0T;c?$=|_t8Bm#fk>K+;?z#0|LUzntm_8^GNrP z|K`&kxctsHKl+BRQ#ZlLg-so&K8SBTz6;;Nf&YYk3upM>$aip9e)a40tx^8rSoXcm zjeO9y{L{u)Vs?6IrnkfJJ2)o?6ov0lV&|hf<~uklzb3Fz^oRKl4tbLC=56dZ)_1 zeFsP7&+%pSJ2>P=#+MW13wf0B<(&Br4*61es#dw(zPopq@MYY0a8&-hVRhuYCgexP zmv@sdezVeJE>6x4UrM`#FXO(0qw){(WeJTx!WZ%*gsw}qa&Hl@0{It4D_%iN0I4Zx!qp{z?AwM#{ z$j(3>slsoD#yrixY2z#Hi*atv=GUEBjYnpe*z^8wXNU16o$%J)ao@pF`3L0->pVML z<)^U85Aj9ql9EUAPkU|9wDFaXnSTez`0~&Px+ixSUwSW_?6%%<-@#G&^L!ck4i4>= z;!FDe7?0FGa;Lq;aN79F$IK6Cnawl#m2Pi`@kRBqU3c7fa8&+bJ4_#a@PL-f8S*6K z%?GH*kWY%~?LLJiW>&nJ`R$qf4$kRa!kcm5!BP38$Ee*$_(FbUe0hD?Bl7Y_e3^8n zG%LQ?JZb!`cq--g-SkIyhaG0zcW_kx{J4ag9M)sV5Aj7cosviLi!a+=*dxHK_;QiH zn>4H2WSGBe2i6PEXS?0F@8GEX+ECy(1=xuUEu4-!k)efVxl({r4p7>iVGGl?b3qHU z`VP)MtypV?S}WGQlhK0(%!W#4eqG7-7ppxhwqm`l>qS3bl3mx zRS*2v@4D~NU$MRvM>TGu$(Il&*&taU+0c1EwHoefQ9aK7x{}F+gUN<% zU03p9$_Bc5*`V@`bN~HwpZ36?-SV18Up9OeR)9-wHw)y#@n7sF`{4i3=x&yg>q=P8 zN0JTGUN9^zC1L+NPZwxmt2hx4<{yKeAOT{KD6cq zv->)<)!V7Jbys(o94Jj_bw9!OSA7}}>{yn{e*%5nCJFg}BUTRbB;(Ef>__C2;!peS zscGXYA4xLryqVc<6Yp>D>~;otb3V^n=YKThhU(LJW5=>o{z0qQryqRqxk+-Yi~l!f za)$iK`0_FGB`0riGcuN0?Gj9-v^{s)`2Ez*0$=7&bWiRQzC1LBFDm~aUy|f2^CNsA zKQg|2oO~gV)J}0{zkJ(wr;XoF@htGgR%><%Uyk2dEMHXqVZNN6k9u!hpUD^UBjd|& zlP~0v+KJzIn0Q#3Hoo$4R>q@K@9m!6C4AZQW5s+?`3L#(=?8DQZbZJ29~oby|C2{* zC${(P_05&ljcTi<@H2I%jo(iv^1#%!j%_^{wK)=7b3F%v#|WXNyCKSk6+x^`@i?|G!obH#sB`k^7-xXXs&P9 z!;Y$lVSZyS@;vjTj<_O_p>oy&#$+rd~!>?JwWa||J9QoSlg_B z@=^bG^1#nDsjZa2gHL~7v`dJ?yUT&KrR?XUW@er@Y5D*uUbk_sO>*pVPcK{@(7%0p9F{^_J3vryce@r|| z!XC_<9dF{)X8PFtJaoDgdOM6a>d)JCPmSS?%74bZAy32`sMzxZXPx4QDdSTl5%E!!4R}pyc zF5%6I0^XRMQTd1E%<%P_b{InQzOjcPxF1pT=2Y`d@=1MC^J~qgHNWotTJ&GVSG&*j z^J|lBY4)tx{MtUhc6!|W`uDi*{RedaaM*pM`E`f$Yq|gKxgYA@_nR-i{%p^$W&cop zCkOu&pJn|wxSj9sVLxLX?w9cY-(pYE@V}AIud)1+C+Y7;`G;fSQ@iJk9eu{@x>j$e z{!X_vAWwF}JSpEkXX+pK`8Aba@?`9~F8Pu1Mg4|6Qa*eY?0o$En(^g$r@K197s*JK z{akd@2|uSb?(=IZfAKoq@#kfB81h4WQQhR_jPqr}xwK(U8(;aF`RDqKFY`aw?d&kV zbSAXJjQjkW%0IxDp>>&zFC2gKd{O(zop6<1(St9UZ}Nwke}2uz@cAR%lRJzrlh)w4 z&#$Tc1AG}u!uVqPt@N&O`mOZU%;or%l4p|L(r=~DO26&=lhAJ!Uzs@Z9q+u%p8Mx@ zFk`x-e)|h=&>LswI*)I!tT%92XOffZrr)mO|Nk7P-+qqztlZDj|3~5G_1pBH{hXic zQSN)xZ{^;3>z{Ui_~_MGKWaSxQ9ZA-@4FvJ_FaTCI{5V3p8N2b@yi}aJ_~>DUwV1W zvom?ZazBzhId}A1t{=_nRyC`)`S*2uJ4~K*Cj4CN3AVpzVLY(;vdTZK-}=4@{5qho zuz!dzDf@}=X99QH`28erh}&yswGZv!XJBLakDpBM+8uV>hsN+l<(GU>eGl4iO<&PCI!<4a z{vkKbjoX9zN{Y=d8n5lcTxJt`4E`b*{|5Kb*mKdp1R->!$hzlLo5vXPpKnZ(Z{q*(zjXgchxdcA{2Fi5FGTr= zVaGlTV7AGhNRG-EJ z(_2)2-2!((Mi3GrBZvfMPGC$UtSvLs##ezZAVFrgk;@2j`}6ni62*M}%27dK8!S}* z6JSdyx~lPT2NiUm(2*zNjowblC;2BovKR={##cVH;kfgi`2i-j{@l^5Y_!%YXD$M5 zfJuI|TiRi~DSclkHma91bsrkT8wQQF&t%d@0!DCit3=$W5itlRuhtYXYMQizYDXZ^Q&f@s;oS zkG>{^V_&@xwcTH|Vg5{T-NdGL#KO74iH!EwK z)qLPK{L{woClw14GutTa_4bq9)g3mz^d?-8ICyQbfm!9x84O1^3X>lhU(|2NBej#a z_vGhTrskXSfunfn{g~*?%D`-VIr!7v&JN>C`n<^|yvZ|*`J(a<^92Uk{Kj(fLwr%Y z6!xxo*m@hEW=lR0%H_sRGM((ujJ#BpD!{m$W zt+SFZHipmFy1fCujEwdD#CQDDJP+8aAf{*f0y)c{<4ZC)&oTX0de=DpR{E;kRQeuy zrn;4WD}7e_ZSSL@-zvWHc@_?A3woPw9N7Moar*6lr9S&Lx?iXJjc^}HzwJ=JmHX81 zdu8`Ge(S-ruHRlVQVahYy6vB!Z(uX|@jJW8{O{xWk4N;|kptT-zvM~!=TYuF{Imy? zrj4)s$bK?AyBq2)S?-?RVe+Iiq5Wjsfo+xl#2CBV$T&ovWW4z*`wjV|_KJ3&T+y8! zZ)SY(b{;o1C-41a`ttrpit|}-8Fye?r#`i=}iD{Fe~5#4RRK7wcKN7rBj+&9O}uk#Vo zZ*rbM_mSq;`S_oI+dbXAhyM9lpI_(GO^$yY^Tf|!46Z@%|8X2b{%6<>_aMTC|D|vG zjo}S&EN5Px497~6Y1?7i_{z`B$04h;Q`PRt-6Bue{;E&2o7p&|@}J2#bU)_c>i3cZ zrH_RikbDsSEZ32RIf<)vHggRb>h*N z11BH{_JGp||1NB7Yq-P#a^Rs+IWV%0%<@YPq!&i{^L0I~UNCL^etu@WE@<_3{GM)a zhslA?r1O_C>&Pm9POlhU=OI5bzNp`jM`|Z;@5#+;=k7YP@n!yJyQg;;UrH15W!yTl z%KwObAwR?y@gpy1#Fq)pYBS`^*;z+UU$Hyvu_wl?Bdh$6$QO>kdA^7@a;F_nrj4(B z%zPc$#_(jbyLW&unv3<*Jb#|Xts|@aIlhdnBTMfZH_w&6DmT;j$TQWg){&*pO217% z9{pDFRrBeyo_dLW(9;fhy|7u|Z1^Nszn;14arby+T-~t!?UJV7{w4fB<9TjM{r2*3 zA4$K>m*mFkhq`}u!E62k^xONO-@Y4td7q+h+nwEhY96ef)qd(zuj(er6K~jdfzFc%84uX*84n)Ien5VxxWR)-wGf?Bjd|=kuN#<5q!CN;>z)LvORlWy6|e8FMQg>Fc<-XFX{K>`4THZ zlkw%msnuP~7hk7g`DGvbfr2IiZTh?+Pcq(IO5Tu9iXOa~LW(pq(^x^_1eDd%K)3D*rHFhS!08{zHCbeBrz=C67dm;L8;gPk{Ua z!#xMq>-Ft@_)6)^y-0fRtS&h4@#tfp_}ah)2fIza*m-r8fAoR_5<&z~L!=~*{N-}> zNV~eRR4yyzFUI}Wx90ueM*5TyMYq;$Z*F6Y0rPK0g+2FTlDs?r*#LAu7$QTL3}31Z z8N}qD<-#s3UK5W{mtx9e2ZX;iZejQF92lQS_esNU{>D<3Pj1SM>~b%A|L=5vczNF^ z&-M*RBf{z6g}8b1zhPs?+q=oZpND$^ZdUyB5x$Nr?6Umo*Xa|Y{3@T^X$|4i##cUO zzA@G6?V-1HPwy~AA)WBX>~RN#RsNi!FuJfyeq?-6zafv*PTt<<#KLZT!C__xgpDsJ zeyN+@y*n1_#x3ls{DXXX+b@0Jbt4CD$Pe*F{K(50@nuqz>g?pp*;&}#yG!^oZedsD zALI+TFe+a-{^t22-pHM{y{C<@e9YX?;bZtObV~z#85!&QiSPKQaSOXDe~vFB3%k<0 z#x3khU(H~h+Q_U6akQ~M=D7dXA=6Yq`0dtBgMOh&6c6km8f;+2H^?7&ez)7KI2t>NbJ6kmAh_p|;~ zZsx1>Lgw!YtiSo<{3*WhO2kt-rDqa{`AnCYzk9+RsXxXSUWb0A(|b-1?+wIzZ84tW z3$I7KlJfbwmpWfMop95yzbrPoUU<8^`TQxq@X{x;{)GE8#Q8gP|Acs73^$Lb_`)j@ zPwABYi23_G@!rJpcf!r%DZcPJ#8W!G&k^U}(7lIv$BOY3UwA#@m4y4yfv7*_?)tMiZ8q#@k%N;>#g&Dv%L2a?_e>W;tMZ*66;TR#L3#ZLA=)%<0-!IO2kt- zl6#U{>0Zi%`=Y<)<%{AAuR}bg)A>x4v-cp&`@5{q-wrp=XT=v@k9Z}yzY{p6&l2w> z@g6M3Q+(m2Kgjx1K7TKlzdKofr;70uUw9?rDIMjj_W<+vd(7V(i}4g+cpc&?ozDL$ z9J+5M-W|p5tN6m}5wE0t{_7mxt61LKi}4g+clRKSjI`6yqtr@H)g(I_V`W-(RD9D%wB&Vz?vxV|?ND=vO)^aXOD9-j|7Y z;hn|fM-DH&g7qid%LAwPSBUqxz)3$*oIk}^{z}Bl^7&VZqw@X{^LM%!Pw|D=jDR^7@GxGTNSdYIS?g;-FUwA$Gl}_(8asDIS z&k(O$jHmd*ORr@85x281;$`{!Cd>N=#dwM@yb|%0PO5x;nfd!&=I>96@f2Tp9pWjS z^lwBw=E#Q2Y)`wsH?zG6NrzVJH4Q#ze*vAh=(?{{wtefM3(c#1E)9`Qiz%Z%X^5|jeO?&hvEybL_DRFej{*7%IAk!-j5dNPw|D< zA)eAHeLaWwUCiG{it!X*cs=5k4C=%d7apORr}ADWBv?iMZ)onZM5z z<0-!IO2kt-=@V{te)PUS-1M_A3BLSZxcT-_eBpJ7r*t|$5ICjB6YnA7^@{NnUwA#@ zm6XrN@}g;ye;(&=5tc6ct`FEW3hD{c?P7hZ>WN~d>C;FNA4-p7e|Vd$-SJ}bWP zdc-TK-1E8oeVurpFV3Ih3om^p>rc4MSLd0;O{t%Ei}4g+cqQT~o%H2_(@{Pzp*`Yj z#dwM@ybke{PU**Tco!4ztHpSVFT5V{O2TEkmY&V>ej#wuUNN5H3om^Z>rc4E>HQSz z?GK6f(J}TH#ur|Rex)NE@h1Hk%lon7{3*WhI>b{xQ}Ot3Gk+@YyNmOu_`>TEucUn5 z67^QPjrDgYabFQ`p3jOey!6?uKjL+MG;n$^Al`*6?-Psh6km8H;whc<#ku_5%KW{u z7*Fwq*CC$LQNB7aWd5E^yuHPEiZ8q#@k(-UCJytNKAm{C6yqtr@Y3h7{)pGPHHUW> z@m^Gnr})Av5l`u4?Rq0|7l?OBF`nWJuR}bglM<(QfOt7)(j=P=zDkcrIT{p(72R- zn0WUW=TGs4*CSp@xa?<{JoqZh{f%%(#*bY7QXZIBI=v$iFDq}G`Ma|?e~PdC=>Wd+ znX)~Eo2orl18=1Mm>=PF=vO-0r>BFe+Tg2$_WANEzVLd)E6L>-4l_J`V1pMuE4G&?zVOohtUuxjr}uvl?=IrqSB$6l z!YdI^>6CteI8UYf9O89~@f2Tp9pWjS&XWU2`Aq*d@oq21Q+(m|h*uIW^VRu&=I;%} zySf-p@r9RO$@&xC4+f6%nchIWpD4yteBqUdr*wMXm&4mfyko_9iZ8ql@sy6*HEWl5 z5bs&Vc#1E)9`Q;l_fukg>-=?&!+p%_o`g;ye;(&_w{uy^+U zGwrc|PC0Wr-28Z?_`>TDPwABY8*%HI;whcpGa?@)<}i#TQk+S{d@^61Q_SB_ zFn_Nt##4OZrO#yj3HPr@{*=%3k=7vm|u@H)g(Iz8sA^H-U_O_`>TDPwA-M zvi{Z~-tpjJe!ivn!s`*Qq;j+0X7c_X@;NP*_lhsP^f|0Q;c48^diP@~pT7|OWkmil zzVJ%)E1i@$nSS*}_Pa}?{_^EjeBpJ7r+lVd*UHvc9~(I7Ct`gtkEi&;>k+S{d~%&O z+u!slu3z34^_VZO;tMZ*F6&Qt+$WXo|9cbLqdlhn7+-iL`jw7w#GCX8>+hc6O}@N} zFT4)%luxbeXZtR`MEU$+;O6lZUwA#@m4wT2H`9yug&a-4T8yXo!b`7X{Shyd%N#e; z1>$vz`-kESuS7hhll5E5)$}C!(jHTPj4!+n{Yt0ziko~LwQ~XG!SXG!o;+8Kr})C_ z5w9fNm*?;nh_^TJM);S@pFSL@bd;~sj|Fb}BY~6N6}Wjk#aI4H{19Q5&yPj@>jPWq zrD1Q>2LkhaQGDTbh^KVY7c*bC)BW92)Zf11{3*Whdc-Ty?YxjU-z3hb=zhHzPw|D9 z&Xa$_`_aHFJ%;UjC)?wO;`UH{;gyJ|bkq)=|HgbBB;H5E9jQOY7hZ>crPKQ_fm6DH z<^Blqz8d~~`zpThdc-RU_bY)X-1LLQ`*65}MI?)hzF&#dwM@ybke{PvNCEvb@6k z`WXJ@^4FtZ=?JH!`n&LjArHPhrv7qx>GN5C!o4~2(L2EW^~l2)6}PYAtGp%RDWAg0 z>hCtz-($zrAL9$JL%-6IT*>fW#P+?o7*Fwq*CSp@F6*uI4VLpD<<=L9%d7apOK)WT z5wCYK<9`R;S2BOM73WX!g;ye;(&^mF_PB-Z@kQqIbK#E2KgJhchkm6~dKGche>-fC z_Z62{@rBnTUWu;cN+wS~M!W%eY8PwhJd@%JFMR>)k9a+nGi%>3u)OJ*`eS_ImFQPG zy%*%_FJ=GueBkEgi{cBfLp~zlVtTnPNP}7hZ{YN+-klAH@3u;(ekR zPw|DyLQCDg9%X^P)J1n0_YQygX2R;gyJ|bTYZD@#t%m z|F;&)Q^glvhj>ay`6}JZ{C$@BySVtgq~Z&&N4%2q`S!r+{Zrz-l6ZHGu^%v=@X{Bt z{uthQCvkq6?yHE`DbAnb3$H{x<+Jmaz$yI$;@v>Jjbc2-7hZ>WN~iN4;=PY}?{ zi}4g+cs=5kS$|(5-kXZ^r})Av5l`s| zr=;=nZN&RPF`nWJuR}bglTxm9{t@$6V*P!p7*Fwq*CSp@* z%#=>=B<;l?pxyq%)K72foPIk#q>+~giZ8s<%c4D$PVd)#;eCjB?BiDCkv=r zsNQ@4&Pw|D^(?qU8uSB$6l!b|U9{SmM8n;}=S^`2$QmoF9L zDZcPZ#8W!iK3nyV8<@Y}FUC`R;dO|obW-9dpXnbGZz=Mbmj{Y3ydLpN!X-~K{=JfT z2aEHk_`=f#UP?zeS^F*%@3o_NesS}jkQcfyEq!wMg)28MZl3tw=45ssuDKq!v0jjL zX7%A36>zt?W>m&Mvnx9f*zOq*p2Bg2{D`-cBzQ3CEsL}Ka1HO}oYjYGSiseRd-GK0 z^V%KYfqhUy_;Ag`$(ad0T*CsM+{L^xIivCq%9)E; zH$xw;AwM#{%#knT(J)`mg%8(|FRM?*N`9Li};a}NAjOLAFd%^X7%A3 z7BHQQ^>3B;ymtrmUVBveM?YNi^bjCX1l!oPwNtBmJ{S}{nZPtFJM+IJ_(+y*{cl*~1n)vaW1snV__ zbIY}63qflY{5_H!O^zi;)@vL1Q-RN(j@r{}HY@GBuln(%-K=c1?4h+-S*zk9doCZY z)>c-5v{Y>^HfxP`t-g^oH!9`U=0f{uqneZ(l_h(7q0*|_Tg#QrwRXAEY*vmYL%#A_ zbtAEqE#X#uxm`9-JXlD(+Q=eoRn|7E3CgorYgvLBZu~IUsMj{y)n>9{pQKI@X#e*o zo*`vyd9AXNY*f~(cVBGy2u&;-zaNo|S6f-TQw$ znFCy{U0p9XtIJh8w3Ub!m+-TR3MJq%33UA4F zrM=loT8C-GvRKDUs1OA$)lk>%%!@omK(o4DX&Ao_*OtJh+Cnl{X|<~DsI#cu ztA9KJcx|!1QN~NasjMy1DQ}_-_3|b@7F=#@wpJBfSw`y(1h=X!Yv=OjrX@32%KBEd z*{m&9%Sao=J(|qbo3#~7Xs&UzT-#{1D`*qXn*9vARu1*sDp6h7`^&YpsyDS~`-*-0 zK?@7BRw!2%T6ag#T%&?^w(eAc+Pq|ML{;v)8zlu58c5cf6*;p^`wM8|K`%2~7CfO9 zTw8L&+CBXc-cB~r3PUbANx#ebk-O%l2 zOy*CCl~2%~pA-Mj9@o6E-XmA_39`A0owT8?AaXX+q$H>@+9Y*jz6! ztW_XXlU2yqG6eBjt$j3cu?EbwO0$oOo`uRrIUszpqy_`mt<4*?Er@|eeGP49Z&wgN-_~kA79^Fm#%cv(8dcymXyvW@XPlFY z$s+Ku9L3JOSy}rbUg*rrk}ow6mlx~J4fG?VhX%1!EwJ6JRV;+wrD~(?J;Z+V8b>SI z>u5p?+OTF_8whJ3Ng5`m(32tNE&ojxdzB%z zz2VA7LG9Wy5ZyVNy!@u}QhnK)0llEUjJinBBP}ek{|k^!>kz|`wh@217KFR|8q_GH zUKKUpTC9SO%S{X<8_jT$8?X4Jh2UiI=;9i>(i%EVt$MgzJ&NWPvhiZQ4}SZVQ7a zqysu2XkmYk`d^oy=8XjK;6(M`7VB&Era@L(jU)EwXyQRFBvCD+gSBfLE3N2UW$(V$ z#+F_S40kD2fdt#CViZ6pjseFWTk(<&_r|3wm-ITSf3XfB-$2*)zZ=yRh)C2=C=u+l zbJk3oTQPE5k(>2bqqpGiQU80)A~%q^WTA-xy9{6CFT5dBJj3syfp2@=w0?pYqhdeKWtCOsvDc08Xgd|VPVb! zd#KnDX+ynJf^K;gsy0dqq37*tqT%i3+E2U$4>!sZt13pTZ4 zeV8spOivj@;lkz``i)PRFg}Af7$sWJy*aaR#;kag*dJ(zV3EgNUn!Ro{J|H?H#aIx zQw89wFSaplY58M}4hUSSVA^EkPr0&gT70sB0eQ0>+1}bHAHE{7zx(~~mHziC`@3E} zf~gXO6r!%%gE8A?a9#le71j@on)2WMaesob&81z-Us}X;#HW?^;IqmIF-6fs@PL+# zawe5!)9a2jtBop@u%mS2bGxCFLG`Ud=WhDwx>13e;Nd=pncILU@rH*m#*lBS6ZBq+ z9&`E%05r)6IAV^sn)iWVrGgW+Pw^iNx^-gWf`|0=)q}%d%8m za<4yG(=BW+M{Bo+_RZN<%p9j3qY>x8#a~F8_Ret^Y|1L zRkG1WDvU^v7hJ!zB46^hF@79!$+J{L6WcOO_B_9 zeW`}ZVC80B%FoR2{n#|1eu(Lxu7E|&_nXI+?<@ivraYj`F+v?$hlv!u(Wo79DrHFo z_mNo^gn34_tZYC>g{j777=3T1;rr0&6XwOEAOL2K=!KA582sFDW9@;igum!Y_`6^u zFy@raCivoJ)?g1n(Y6p; z4qd+i0f}l3^~qJm2w7YM8$(sZfaDL-z}lzqXimNQsjey1tz5< z2}YWY$v;nZ0g}Wn_%8Y!#$TVthG_Dh@qtbIq(c zn`^6K0zQK2?NR)#U+=oWsm~~0y9f5 z)waruCRejZbn`asP9Ubus4$I$I$PgZgINhGqDo|tpmp@aK@Y5zD6wlan+q+dCzz)W zm}QZS2S$H%Tb6=g-L*2%5Cav4uOgu}n5TV?o&}ovhVo*NU9%CofysFG8}jeO76ANJ z81M#vhbe35eM{I(v5*^X1~O|LOq*s1JDLmHJ2&{=)Al|s*^5a;|1}G-iuGcGS+KUD zKCv8Na@g~QhPLd?t$Qx!);)1$60QfsjZC?*IZV!G4yhz-{&#N4vFs0KIc^2@84jlQ zgF#@w&HqEe$P|{A2DS)~ENnvhd0tHXd#{7G4{Q6}x^>Jj`tk{=rjeiwNF0Vwd(FG4 zjTj-T(7>w+=;ni4>*zX$KiJ)|5?~|`1=$&AtpW~W9FHnCL;G)Dqakp79LW zK738fj29TQ=9Uhd;38OvTZ@D&MEYS6!YjslNDu3#d*{s4a^_(eg%Kdx!kq0Yw22$? zu{vcs#Rgkr4vQgBoX`k07y*zbH9E933VP*PkDD zKDrR+VH)?Qy22OzjzIcFbwjF}**r{1E{v?T=U^hJG-2Y;6g7+r7M&X&G-W)5ecVSrm}f&0GJ=yhrY0y_UzM&{4%@I0A!DHT0_+XwN&W1Y zRD&(sR%sw=%_fQEEKkR(h~SHuB^w#$LIJkiLH;2JZdS8t2uv~Pe)iH}>oCfY*odJQU|5kE8x z>#H^}+mfGgw~m#7EB3)AgXNKakl9c1quWv8Lj2n*H7xSxK+;#SGyx^UN(eHcl3;R| z+$wv+MNwD=RFdV)>nd6rkEnJxOMqyW5d#F8a|{U?)s80AgJ7R&y3S?9G~*ti+(PDs zwWfxOv|Npn`!MX1)Xnzj@FwIz71Od%#_E>!eRMJ;v4V9MTdVf@6b!^JyWqFXm?W8V znGfv>G9<)5#(0ypnAx;fUmCsNrmv{hrp*l?^q``~b6Cqlt8cX3#T%=YTGOSnJzy-t z$|Q{^0|6B`qx1v7P|Hp~U=fRCF2U!Zs-t`u@>^KENanC2a0JRC{@UEi^euG#b~(Z_ zU;hV;V-U5854N_{V1hSX=xZ>(Tb)L1Xf$Y*Hs*+?G=)LXMnNCDYzYOit)^KEXi}r! zQhgKll!0y=`Art0UvU7A`jyepDkTcHfJ)Ddi2yc#^lW+-G2|>lWk&nhqot2w;pm1z z_`_gqghvMXf~SFJt4y{5eW7eyYUu7Zo`Dmdc#Jhl90~9B;N{JYMITYz+8WBK>vmB; zeO1uLqEKx7$#ollvc6$UxHYden)UPk%m@I6p&?MOG)QLts2mtpuv{LCE`0&w!Y&^O z+v*}#?YK53SceLf7Hw=bI5A^^k27DK2_U zz(dkN84cOfT1A7xo-iywo9LzaFpd%?jrxz}trhte*G$-K)Hl|#I<|}+rE$fTvcd3d z4EA3_rQtw8PmBcgATwdNf#|XsIF@$G9_H)F1EZdaZpbbW7d_jC6g_I8;XBb+=>r zWEy)T%7C_3;8WX3SK`)a80*9pynkG-c68nI@zTgf}c8 zuZH#ZFw_fJe3}i+^)Nmh$^sWEhir2OI=DUAzp!gVd-Ir&w2iok$)gl;vHZbHvM@7T|jWv8W zO*hpwkSx-W0;@>bY(5K+CY#moKrYG^FZ*D~f<}GP#fT7=+$Pw8BlVdG}^iXR8F^5ZmhWa>Ccw3jWo4ITQb37=MrY3 z?qHf=s;bRGs%!0vPeUM6V_1r0LNP?QguyiSfW#O>4aSBU8<^G^>hMy?BkVbI zxwMQuAMpelm^k)GzA?ab2XtLNn;Mz8-Npmr(bcyI4B>8dk0s3^Ef|#rO+D(%6+2&q z=avX8b;8KY31zmA5{zI)n%?Er3w_@x@7c5ccJYJ_EqrQZPyWDV7N3V$fLYYpxofR8 z%oSa)ZHhc?RT~trGck1KLu^W12LvSqtks zwqe5@&PLH^GKm%ima7$HS;J1$Jxvg?zUu2avBnf@L|Aet zFW8(sv)P)Jdnn9S^UZYOQ`{@FdAeksDK!*?9^_4*1waY+Ns@^g1-8tlj`gTmZFfaI zlY3?@Ka72(ZZvlXcJc@`k+t7(Fu&XM4YII|&-5cxu*q)5_&gizjF%sFd7-rSvqeaF-i$+p2WJHk9b}0fP z#0ux3o}j7fQD6^Su+0b-veJNp<@oj#G1(m|EsSGWzwzmYB$WbV1f_8~R2}pa@Vj3> ztui)Qn!3K&tQ{GSt58`Ih zu{wi^(^Y9}n3(lfnpc=-zx}z={+K}zyDe=liustW==hKZI@`#0l>Lbw-(WZg8EF$N z*i+H0woTX`ybhDf7W(_T$${t&`)tt{__j><{Ll?rNf-=lH1>_;=n!t~YY) z7HhDpXTjJ@V0tF@y?_?WrYhO~XDmY7$Zcz4Uctx}Dm__3{aelWJT4wg=KB+-817>9 z^sVslUyspBzvjKdUk@xW@$w|+RVlc175@a zgq=ISaJLqlEL`6}$ApOp8;&4gwy+z1p=KLJLjYS<4Lk+QOqULNAz3z+J$a`^vR*?z zLGaecPiwx(9?Ad=cOHhFw_rC?G0u2M-y73Z-(!Rm0TmM?CNSVwllblhFN8Hnv&JI& zHU!v6-SwaQ6o7;`$%3;5*b7^)AA-$`^GOb%a}7+MeOJUB>O$nh^xWp<>jxy&8;ckk zz%*OuSX!tr9pwl#7}8JGcCy$6#m#ZC3pUD#aG2BbH9h!S%r^!@yhPSo*ZNcklaSSR z98G{Mz}SV^lJyUtt1P=g9$kI0>if8&PE5`RcWsxLZxsvGa3O z9X6M3>x;RMAB%Idq5&?_s4F;e+XAwKUnGYOxOR_tLzk)vn( z>;2#`am}FyL&^0rEJjJ^qA6p7aQ78J#h!%)$a5$lzCIB<(L&NgBXmof*(NaGGc6rk z@a?z?Tn4PSu+a-!_7i&uqpztc=%DBeFt9G&`NHx`;Bf(LiNIjJRI5a8nukJ3Ypfn^ z)fS=I*#@;_rC!0NNKeil<5d*aJVpd}(a!GLcoAh%Y6s9N_LHZ$ym{={QQwDw;}wAk zrOXMCz3;*07yJ7zcF^(7@@G8(ebAQ3-3;a>xAk(E%j;150?yY%wt3{}F$@L1&lvL3e25mN)RoN|j8rzod5H~a zVe}ddfrx@SfU)3CUpC0R{(9znf%ae-k1Tt(vHF0|e(dQ5=u&3Dh!A_S5HHV5W5?l& zO_i+fZ->0XuJzhR?au1j5xRC_!TiTy!fyKd-few-e__F4Emb^1G})64CpS4uV#VNA zXnKp-Ma^AYH*eJ1clcTa27v>Z!A0rtf*sGQ-T`gI_Pxn}n}!NcAHN;&?G`>cwheX& z@I}i0pmOuZvSlS3WZ=Kvj|ePRnm5_TTL0CJrYM)$o9wjJVxx5jY|l|m^jJ;d@nt-^ zVN0|&3Yug;AaOkyczfvXpov?thF=^C<(o$9m3nmw4u8k4_eqnmsFrjVQyWib5mpJkG2@I*0{+gWRO^E z4OB2z5*8O2vbYcd%ZrQNN^ncQtp_VFhhJPhdXt@LcmV_fHc1{<%`6?h;b^QJEZ6E?svRqLkV7$Nw}un$w& zf#2*r73@#g>*XMv$*sT&=))zbU0#STY}=T_tc8gdOfec)m)9HB6Pm?ndB`5hM}QdziL}vbT1$fo*2ibA8VhHZpUoS8d%x@ixX3RPegh zBNYB4O|~btB2{6na#%j&kN}#N9&7`~SV_-HWgWXSU)|Ur@7qJL!bT51=8r}|%0qb` zn3B3;ZM(HxSI+DLDpM8^oArQ-_%TV#ezKL==p^e{Ww5=yrZ(EV__r_wF~165{h{!Ryo*Td}6nZW1Z+A{%qSA zZCNp7N5fAQH9XK2T<>zvr*xMf{9`eG5CG9 zC6G2s@Z1DHI)=@tj$lbRIck3x69yT~H&-f~pcdPE1p~89r!d)vZPil`ql^u6QL+By zFU3Iq*a0fosjtk`Z#5MM z0htkNZpW|@-uB?ee!*51OGbWpK;nk`IbayVViwdv7@|!lGb23ux!G5cPunAH-QLYD zmK&f)2ZDsN|Ae;@{>MHvef>P4hP!`O=a-`8tQUnLn8Tj;dfy z*y$^@n|G%$4tfQfwa#PNWDXqya>rdqB(uy)FD_JH%qAV|`xQKk6?D?}F2pGx9r*%)qD#tnZ+Jc(6q&Gc!aEv`5EI zNN;XnXt$j$u-96R;K&xvHn^y8oy<0DF~IG-P4q>hM&{ujCHKP`VTU6yb%iLyC}pds zW}>jb%HratS9C5sZXCd28$VWv*_0PL=Z!JI7h3Ejmg(tX2yUo3oC85IOyIIK!?zEJhL(a&bJHZEsBhU3w)fQ<=|F>3fh) zCgwc@1HPf(B-yOH+tR_LSb!3IHS3^=xAV<0vQ${i4aw#(8?ZAbMkl};wh-3XU_}M1Fr^y|^eN#`2vjE<--g1LoxwH+9fBs*#EBT2 zCgZS9Oh~K+qQ8U&pIzkP6&&ptbcYPX#!|PUnP!D~ve-Akndn=_@nDH?}vkD{0jb} zE26!z)54y7gG4-Gk;2SoHUxP9l@-g?Yc?TIVwXnfRBbHy`gj*SvBBSi%CQ&L{PD{` zfUk7)bthLR{3tqfaI^WFVhsbR-`Rm2Vpk*tY75GBCZY!eVJySx_0S6j!!=Tv;_th} zDizv8%XqRh%-*+xi=1Es01cnS$5ro|uertf$2rg5?wsu#=jLzX5!0?~3=H>Sf;Z3u4 z(X8ME=)I$WSe#D>@RF<7?Jvy%UMC5 zY3jIDP*TOdU&u4xi2>`0+Xk{`!3s2lH41Izwv>i_{Y?=Via-gyX}Mus*q$dV z5mws$uQ!n=+C;-RiYaBfz|Jo!@&J3$9&8A}HYx1XHlL5yhi!~;)zQ~sv27mjDlco1 zj)%oBQASVBn)_NawnDYwWY3?t5k?A!r3vnAK$=;#XTjA?ELvDCWFc0P;Q-$}ll|`c zGN#8=&9f)$XTS=UlRA`k7b>s}E*>)7QU*_&(_AgI7$L7C25xJzwIYv*V|p;uLM|U# zLQ(@kp0B-PQ8>To5#1?$Fie~9x z(duX{$>5e0J+el^$OJnAZ0oXxuol2POlLSe_H)zEzp1OC1P;C04<3ePSMl4jD)p`Y z!3mp##MCQh2Y&p~)KhsgTbb?uhmkQxVYHpMk#3;~z1exnxrINY@4KQJKl?ODF=E~j zlk}Lk>6e&%6#YW2-f>Kl;>>Yef-(35Dh;Edoh;R_0~K$(j$`YwXFp~HZh4GH3+0?M z8|3<70@O69VRs2+$tct}a^_$4G+ZWUlc=E@(EBkSnWp7Z+86I&y})`klsR4o3gKW= zX^eul?_dQz*B45Bg!JwM3Lc6^T|oDeipOUYDE?OVK<-+g78_kQnO-hp5B(U^KR+#E z6AAQg@{8*_Fr!B}^i-Z%jXb+V^b0}5k8Z-n^&n4MyRVH*3&haMlJ_h?(ne*n=JO3G)(Efg`xcV&iCn z!%6N5*Df3K^=;3Jo7iHduWT8?wz1H4V3mq*;)c*k^S-dHyz3@rA0W5wx�k9cfw5SpL;wO(Q-Cc8!#eZ+PT`6@R<+E`I! z5;n2Nw$^Of-8oOIkAZlKjAqZaV6%ZaRcyP*;({GxkJUv^9j!|uZQCD&DX7iBLbmEo zC#(|2c($^NtCwQs2s(>xDl!9&S&*nP+r|_=-U;2%E!yo>?3&-Og$~n{O~V5Q1qJLQ z+0TA%3&b@OqHU6ZT5G!%&4dtRlTBc#v}4`CHkD|)YExW`WkuM)y>mF7k~k;Gw8*_r zd%bp|lN!yiZ>fQ9!B+G-H7zqsR8%#sWWTQxIaeLZrIAu_EyCWq()L}30ppn%@KN7b zdwnJj5}TnBob!>-U#8Y!QNn(GTx1+sGE#E->8rM(=+>4gC zi8dC7?a8ViW^uJiST;>!#%hw?(qo*#5)|e@Hdl;8(pI#qtj2t!FRY{$sI9Q`U{8sz z5(f1cf>k8k(uEC$nQa4_X9OXuSmre&yI0==jxWPX;ULS;V3il54>ZtC~jtFg_5`ZtrX*2jegBn9@@habd17qpte z;DH^)3()0k!e^U_-6)nlVEo8_ic7z^*9CQjwP#D)48}h-_b6aT6 z))#yjS!$PYwTAyi54A&qX1kQ|c7uoy;Lso&ZaU+k_y`P%AM}K_>`I8w8hN2k8J9jS z`VkU)Vl~7Vt*Pg5Acs;f4pxY9539N~+!Z@e;FAL%a~QLMO-Ojnq9_HMGBjM=;}+)% zW?g;j9(&RK0h3W% zctsE{hs3Q+@#vgxLfOIAQfL77b8ORHvYpG;0bS>@TEH##vA@i(0FMA{@Q94qwo$x* zEw>w+;MN?{fPlsj2eutV4_HBcIlvL^!~~^mUu~YV?zaK^cpR*?4c#{Q#DNH_ z5+9K44`fOPV}9?gXc<3ZVbc_Bm9UGhqj9~Q(WU(ER_xf1B4DT0$|ja%eS3w8pD^v& zliBnr(HuOUU94eq?cyQ3;)!mIv=~igghseaZ;+xtjfXJ<=mP;TRkdMB;BuDqTsz(u z(#&eetQ(%Z-+qEF?v;g&Z9LvVZ&t51Ap{K|AkCQU;@7w88EJuvQJ-b*Cqr zK~W6hJ`6(V#Fr8LmS($I3@73TpX0?)^{{YgcR6DuM>mE#7;lG{)gGJDpaI(gUi2bd z&&3Dtg8qC2S5I1hbPpJ5nTePD5n>zyp8AxT5By@1?7?&;_uycaxz@IF^_zErsFAA4 zs_>io;p!##tYfDzY#231@ig2gj0iz5?xzgT@UMQmy_-1V?eGu3W1LwEwh#jSdjB z>kKh*9#OEKQIE&if37GicACjwfr!r@{L+6VP+5p@lZElr*u;)~t8kBK;hw<(??4`q zzc%hk^H=RYH-8A(70-|pFe+llp8tYlNZ1>f6`@gsijpN9{WHi}uC6cO(nzZz&p~tn zU(Xoy`_Ss=-C^t>;GNrvDb0D|Ec5`ZOE;YpML);sg@=2=v|;}QM)XR59Ju+H8Fzt2 zMHsn1;$|{D9M!`yJ;c;=wPuBk=YcG8UaE~d{dauM>~pbxnBQL-G0c=2x%8=W<^#1j zwa$V)4mO2SBBAwVUamv+4P!1Au$l?GgLhq{x@}DJj^Z<;EW`(o zeP&S%EgwmET}A~(&w-?_Zd6`(;VQ=@)J<2c3#kH#k5k3;UwV{%KT=tlItp(c|zB;Cz}C!NUVa`qZ>o)Aq*Av)UQ1s zc`V2u2CG^7E9}QGg!G?G6k^4EAfS&J@0NZ2eBcGBXWCWg<+A-9_OtKv=)=)l@$n!$ zwzDXE(`PrE2e4C~bzyt$W25_drF%eNB23R|q(>g0NA>952O7aS1Q!8PcQS?!Q3IwKoj}vrvJf45T;do z)2tIg0ecu|DIAc)wAo&<*_x@w!vQeE4TjkvK0j9w^=5pZ^9fp(a(B5f{h(4Mjl|oO&E`MC!N_gG1K=|+IaNVi$@=(j52l?3``V` zXjOK#jovn;1JALorC(|NFwRDiLO+cAsD{F9=!bpYveJLi2R~1JAk63T!|!3fXlt0m zfnjDE4%0kxI5e9@S}^ES^KAHouSi=cEbI2GZ;H2vOxyAkXciLJ9oUnrn|{xl`LJ2T zCH((p>^d?_PVF z49CpawntBq+FK#is_zGCKes)Skc@bf&F zMvL4RGJURbPJvMwMRVIWGGDVHJgM0<6V!>MAi!Y|d0{T+mQPiyfE(t(2!gM<8Cs zm@3RT=N1*`EjYK^TFRFeA1DQFgYS@`>Oy*r%(A-IMK5>j_UT|phuzm>R2W@WQnN@gD=RBF z0&$?ms81JvWz5Nk%yl;_3l)!9b12Ix(ErIJqpa*}2w!uia1!{&QKC*;rw1;t+LH_B z0NLK@NiJ0+_9iM(VFm{K$7AiKByH;qpY?mP-~&Ge(djMTqYPn{Qz?kbTkOzlYC(Xm zSLc+6Ix@(Fu&Pgq`}&=;Vk`M(_6){!FMEr7Su%032|e_*mx+L5kUF=5dN6ucdLkt4 zrGXNAauz0kK3JXn}FDshH=2;l`%A_;+|D2jR)VIzD5)5)W!+@wu83Z;=6;y^rU-#Iu&6 z?3CBhDiT-fx`lN7B;O*jzi-#hNyegC;$>sL0{48b*Xqq?Jwy?EORNEWm6LZn5t(?M z8U&+~in}&Y^UE?>s$xWUn3!o{-?47xumd?mIDj(G;P$?)2bt{K8?a_&5guvhSN`;5 z9*Pg{_bh}(gyNx64U5p$BY5Dv$tkv|XUSP>Hm-T}irytFH?G*wyL!cj6^@KMYx9n4 zh>n$jaAx|^0v;aEo3nD*hDoH@Oa<>Pc9lS{zN1c&^Zbi!*XU(I!N66xFjgZ*( z)B$5H++bszFO>Qr*}aSMzKS*oByB&)yozP67>T*St?G+%pZDa+`|}VUk6}pK1yzLUVoWFgd#7b!VGl?GzUh8 z5@2yB3Y5LY>>W%ew2uLZf^-~6GlwiDN{7_VY$66m(vM`d(#>7aXy8jjLFoQCu6KMv!L6zyQS9ItvnBnP%m1%0uUVwzh_eEh2#EI&Dz^ z6kDM4GVSKTIJZlb#~V#~P)oErIBXhSe}~Tzz)9*1O7Gw}4LiWyvlW6@+1QA{sZwE8 zLoQe(Y8X5C-q>zixhqqO#9F^($*Y>PZG@0pPUk~ZalvX`39-^Y92?;rI(<)}_w}RR zy?YP_S;jo)xI<`=WEYHe7mDuP+I#_!q+hUa7P)A9l7pR<_NGf@`5)^)C&)LyOc#6U z+DD_dvkt5}E*GqC=h;Jc060aeX%MkFr`RQD@h~vOtxiRV9_lGUe`&Lr^T%v;>Xt)# z(#T43I?PzJ7alxztup})L3>;q{6Gz@EI7B$G-G~@Q^mt%D(?bHkjn|{-af{J#=P!7 zX{(&m8T7PeMprKu>e6o7-khNCZ!&@_RM2jmgr?^V9FiiSJ(&&+Z`T7aY;Bao3PGNN z^2YI{?Yq3bHuoV)6*63hR`cc~A6)iS$#uooK7f}4^?{Y~XVjIZxh z(rb6+veAx{Ov3yZGa0o5Lx6H@uh*gGhKb0i_6b<6hHJHtHVJ#0UWSbi zWg1;aF}>^=&Unq6dgw8zV{|u;rZH{j^+t#*v?avpRTF8A9NEi(+%jf_Ygc(4>%Ae9 z7Ts!=cbCdx=*nIZMLo>EC)D;luPc8Z2kPAqkhFzqzEZ%jOP=(K27qxIW_gP5^xW3r z$A3AArTH)OYt^~1nsd25g*6RJwsLT+=0QW9$wC8oN_Tg`whL?{*EvE5$MqOW*#x3a z;gqF1$aK#wfTkbrw+`;n?W;LdHj#OcYL~X+uwy47Ki2s9ROMyeE@#B zSV4gUQ5g@ial^hoeycMC(fIJ*aqDv~k6U9a+e8C&-&E5;@orRJQ-pjh`oHmc8`oyo zEA)o6dn@6%_BU#_sI;M?q0xV^DhoY8qDwCZoV8Lb4kAvJOKe#pwQEb1so;1UAv%t9 zQQ{0n>4`bdv@O%b0T}JPQc(@XfpQy|9DKk?YZkHS8V9u0B49DvY;g73 zhHC6B+C4XL?j`h7E{E_%fzj<<&oN8JJvIzt%`9lnp{F;vU0jWI_ZSzti=y26f1nuj z=$s{DsuboncGkJT5s&I2`sUENr#VmFXwaZ4_bB+WJe7?GL`5G?E_zJtBZ`fX)&_ig zug-V88&6E66Tx(S;XJ}MP*E|moWspUMo-F0b5vw`C+!ar*7zph?F?>uw zG6rKVeUzH9=0I2B(3wjRMxW+Vi<=gCLNkd`$3g?!?ZE5o<8*UTa|ono5vYc)A2eDg zxXxVw&mq#}UK*6xMz6AU8*q`l%b5F>(VPimw+&Il?u65hy@}`Y#`InuJeFmzQt^`v z7UgJNQ5t&J!7gx9PjHvI+{%+Pv`JrXl|iu(gKzYdp;{pAMLo#bcCU_N24ZjMUXdNU zhf_Ha05gszppJSXFQkXF5)Ff2*^6h&xRqGynO-btWg_|}W)S|u*DB1{+fj}~r6UG? zcB4lqEkn%?i^5g&pq%|h8A31DhX7Da+2G(#yg}A!Wa%86r9uo_E|?MX6thTV4Si8I zJ6Pz``%yIx2|BAFbY>*XV3>zlC#s>i{4Vq_nHjvmQ%AM3iZg&E!nk^EMAB1re`RX8 zAF2~6xOa-wvu32$R8-q?v0=(Mlw|HLj72*%sthGsHp$U4$t7W%gu6?Q61?daga z1+=|nu7GI*B|;Mp-IN;!ZTW`DBwI{nmi$9@EQ1l(%@AYtC1u|7lt#bGR=6CI1#(I+ z()_;JFJIEpbcH`OZ6x#_x2n_YGzLk??taA6+otrJWUyb&Hhe0^3#fxR08ujy*OwtA0Wu87n8`DHX!eC>)Olrgz!-X{lo!>ngo+$>>bp!kWG z8Y;E}vv(`MqA6aaW0exwV zV%6haEMBeW5xqpy5Hy~Y*RZYLmN%Ubt^W{-%`Z&@5uyW_TiqU;K5;|2NQ7!d zk}9g1yTC*|iY+FgV)IZe0%G;Wa&jz`(IeWB9ad`*?y0r{HpH?v#kyoEBM zE4uWxK1-WH9NL2bMyq^J#3tHE{h7uil*}ch%+Zc&QQ4fpfsnx+iVv!44y>MclW zMnw$2;B6V)E@qFZ-z68P7Gpo`5+B#?CgC-&HM_mq&I8r(4CeY^Ky9`dS|->0e3^Xw zoiqEK)AH;iT$qHz95M!X&oDB}=n8zgYu^C`_tg~#aho<=lcw7sr5eB46x1;HGsG0g zr>r}eL-is|BbR=`TD`59vtG3i+0&8OH#SMM$wSg6?>2_B`k0Gv2i;8AwvBBIKkPJx zD-V?`N=6{mL9@z$#IHImof~4Tv`el)*dOhI(@>>$QOfE-T%hF zc|~>)pzt-U1y!IB!sY|w80-#Rstqrxq}8nAZ6;cM>0Wz4Iz$<_wv>Tu;Ri%b$%Hvh z?Zf46+orA}hoPO~JjL)0?Ie@=#;zf*R^OA&%+4?tJ|Pp!Oh5J3J0c#^$KImr%Nkvu zDy2;ENHmcna<1LaD8>k(We`+lfR;l)A67C%3brX%zSEqC9(S7Up2L843__+JXfBt zfYq!iR+*U))+ko%^f>rw9hjt$o`J%_ovUq>xI>fH8ngB~v}m4BlK9LIX9iXmDDtKq zUe8^`<}2!AUT|wWHVjNRk`d*pCM+xjaWBth4zfe6EUG)G7iiMSw|COE*`#*?H8JbP zhPbK%xAlJg3K!~CDH5a3Ug*jsdaaI|=pk~bh~~!10;xgfOmzBoWGjq!>{}x21`_9qNqaoN^ zfOCLHYl*&A@`i960g<47iknA^BXo!I~T6=SV?jJ zSUvxGnM&ExKBhL*!a|U?B?y$FFPC*@<`wmt>?vq{5GPD&mdFo;YtKiN1YMk0`Z>`-_bf*v1{hI{vQf zJc9|0Ykzo7SVTzLoVxFp?QRl@%NjF9(&++?e`-^t$5X5f8tHsQpS1jCl#12$YJ%MP z3x|=N>S-uM9NbrmP(o`y%7A}X9zN^ksdh|S#le{)Z_`W2G(SU)oBp6WFfHC{c5zI$ z={V96WSPXik(EGbeNGn+qX$5~*{Y3+FU(FNlN9MUvDKt|XLX*LT%hyFTQxe?r};@W zsYkB-4q&Cu7iZ3(KRI67FA|97Ka_orQR{IQ2m`^3NACSPdgvRUOz0yL}*yOJJkJ-?}tt zLH>&KlzmbDE>=}Q1x9(QJ~1~^K{LIPc7*su6cTfoa;lxX@#8=a=f4}-RH1J6ICAO@9pOqtdUWE#s>Hq=f_6^ zMMc6u_Y6ZwXX4~xNb_SWCb)@EK4sO-2$cX4q6#m7EX>+{>P`c+88u$1^kts9a$wX~ zW@ZBT1fRuGW$WZP=f>EY;20vbU@Y$Q^P>ULG&WZ2Qs|duBAO1u5N~#?Et#3h8{KTj z#=XhxS?I2|d~Y;EJvx5uq+-pI)vVnN9}0n>`55{-tnGuyV?*0{!pZ9aI9Qp3VX&aa z`w)2_dsGJktCH>DiFNUA$SJFb3B|L+t3v^GN;yavE0w%WTQ2$+MxC(OeLp`JVn-K@ z1&*1Ry$jObg=z1iv<+Gs(jnd-;$nM=NxYogg|wer>3JM7=yf`?Cfp;EXN+t|*y+m#DQ#`SipHbwIKf{ncXA;sZ|e3&BDQzh*{0%F;d5k+u!S{WDHO!*TbxUc1!p zx|AsVn6XWIg%aXZs)n5hZkwyw?UUSD>chZ5TB{{Bdlbb2GZsp1na`Jq%x`(e?Fziw z75qBNCG8tDH4z29)uo<)n1skrg2CM|-7phogT%}(L|Z-6 zvR1QB=8JV%FYHG}`*fDuN@ZFI26s_V+OEmH!R>|ewOC(ON(e!!NTT{B_1Dc`neFEK z9_S4+CL)$1mF5VJ*&uY636jVKhs>qWE;dV%-?Fj@>IKms@MIq=vfwnB&w|HxR(#rs zjc-3g!_^sDxY*xz=8%xGDiQC!&;u!Rz8pEayosc{V`-#VKWUtKzmb%)u-rGl2V>t3 z1tEv)$sHQPqQffASKA8_>;05mfx$+V6ss!o1}9HtTMs!BLHSeH?JyIC&J5%+43d7u zzMD+U^WJ3f3o8?hF^Ab~ zW5b17_QrNLs|h58Ah*)5wTxGSPkLQtiJ7Z79b_V^oboJ9Z}F8r`A|`1&CWCgO+fLK z4`0Jl36p!-sB_E`nz3D1nHM4D&9O#m@}Qfiv=ip>VbdIs;1$ZFXl&HUCHKew%F9KIAj< z0|n)7a!Ev-k01!HdfVGQKZa6u$6WYkHit5E5vfOwaem|FpyH1Rl!)VtF;&#nbl0{s zoF89s1jsz3%4zSJ56aR7Ty(I=d`$1QBx@yh#jf+((vGYf{i-CnyXppK3Lh`zIJ z!Ge(~pqJN?#@RAtPz~*d+~=7hN>MC+#6_2>YE8fiDw$Zo>Ba|^CgV&d^L;_V&~ER* zl_u0SG(Wz@nsP0^v_uZ6E*26)ylWQ(My?QBh7s_;5 zBPA~LXKCWWp`OOVpv)FkP%9qddxz1du$H zUfneyn;BT<4j+hg*9l`8C`EnJ!myb7gNJK(dQFC6&`K4S{JW1644+&!p;U!ef?xwKUau-jBB@f09Ts^@ODAI{c zxU+FqxRx)KYk|roUNE;>ZZ4gBs1cB$w$ci#dH3EM_!ZL-wCHbb{D+;_?-aCU?52)r*up8eDo0xg(^v zI_gmwk$a`hx$N4q}qgvFjhj!#8tyWg{a3|m8^75XT8GaG&u{y&R0ELU@VfS zapKus2Mq_N1syY?j6OLP83-rplop8y;Z-!QsxVopwQbK)XCJg1l*8>WJ#Rn%ToK}2 zCG|{}rAr|&enP6V0rEpQ*#~`|DR6H-70Mbip2?Y9+ZKmKuVdY#m#Olg-p#H_M@9Ln zoeoUtp+!|YSTB#@P87L8ZL-{)SPpah!JM}KvKKa;3n`;wj%O-ic`0cGd`M*!+2qnl zdWe`cQ&Ftd(o{%ir?_N~9k>qPJgyT_R);NOf~&|!h4*5&+7YuY^$+@eTxI43&A6(GXxud_xz3iOzUsOq#mGdk*T5lNL#F+d1aFITi3iX59r5oj|N6RhDpS0?b`GdrR_(G`icBW=!#Cu+ zvLz_YGj_G=cA-?ulEAa5^K7c!sZf64qd52LXWO{X;&00XaiB0i^kTghB)Kr^A6z!a zmM_JINwe;c)`$afj)XPXjw0poD|)#~bypv55+?Lgz93d`Mik77;d|3TOK)S!thtvZ zd^i^yYN_#1aW98=w)aU*HQW2yMx&GEjakyFnSE<740T%&(?33Z5WN)10G&1OhOqoq z@gz~!gYcr^l6CVqwrLKvAMD~F9U?9c6c3phaLI|yQfem9j<~}x&N-T=VUbg?7doW& zG^tq>cwAdHA<@%q%iyf;lm~m5VKHMxO-1RR+u^+yz4UYUknZL{H-PIUk&bb8NoI-l z^)({z70d2}gM7_$7E83cdWu3&kZff4H&jwU%j^wN4<@XBtu_>obd(w)5S<31mghAX zG$vSSRw8krw1SM*r*XGMhwCV!BAa*Tv|n-`LC z;O=H}r-31jFA#Q@LFuWcva!N5zK~Dj=wZo{Re@=l?eeJu7EVbX3Ky&fjqJE>d-wFy z2DD(?W|QNysfs<@5Pc~Q#vm(v*5D)Ucj|>={@+Q_xgJ+;VTDe3xulst+}Uv}%dIMa z5|W;<9&M4fkUk;Wx0%gzp%&IraUv%ie2b&K$dtFcIQ?op#Qe?vO<2U0tBNJs!_3m5 zZPs2g*@5Bm#1X?mVgdChYqdy%j8s?(E|OXUp>*7| zTJ^4>$Q?UTVnR<-zRgre)9>9cjZwLrE}|(#Eo(T)pmQ4fh9G;sz2*Wazyqz8D>c?E z6D3#Ldt%c^m-6^Ls`hy1<6-ZPe2;2q)`X=(v&zZ@#tybpU%V4<3e8l;#RFQEnXVvO z%GNAWQ_1OYaFLQjYqKI$Qdpoe-gE_1>fg7cW^=cN-(%y2d2AeYEmZ>>iMszUE z<=hTJmz5#h!-%4YU$m!&I6<);62v>ZF{dzyLQ_TR7&hhJA)**vGJ1>b1TLKiuGYf8 zUftLUW%CQ~`3WiJa&IdXGFz-wc_7bHjA74Jw}6ZL7v&zvEb!P4YL7)cqqZ0sv_*fp zEV3hWS&5}LRumSX_(&wfUo((vnl9w*WL?s>5TgvtlJLG^U5UJP5IL@Cq-Hri;=a;7 zj)bidN##b}sp>+1DR}z)8lqbun@z*BIX6hLxsWk%>35QVY9~s`h%d*2#KOUz>FL;^jZW-??W)h4S$+aR;(aD54bs4=U?Y9V{dnlqzXQy&PoR<%- z?MB5C(`J$YK9(mP~Dnn^hITx?o zxl9AQSDSB=(l0d+GGg&vazW{9#!~Y{B%UZ+(MFNYsmIpBe6IDEssq{`2f_feqj^a3 zMoSq{)E^qgnr{+6u~wR>rEf8j<%0%i*iP-#6$6Di|^Lvb&PDE*o(CS)xv|=t`>22 zrVJ66S1#>(kAqy&lUGA}>nAo%AhI08ENx#-&q%uOma8_%vY;v?TgBUUbKd@C{^4$n z?T$$_ZJ+qVY?YI&TBAjW@H!LG4(m7iV$>uaoFwR?uNL+W6}I_fOy54pmJOO()P1aU z%zjxoyUr)#=tEjg=}j>5vX^=&`*0!;vn5DvHv7VV3H50r~XyT)*Vr`>ri@{-C9O!d-Td{_13nFUB zj`xJ~>*&=fO~tGPp2-wow6#CDV}Iv$2-i{N7IHA2yKy|l{% z#K%;l19x_^B57~;y6u%QvZ2;4DjmvkdoM&P8ba`{Fq#==cg;kEIj_>AL-}c?OuIzf zV?M6!sz4>PbA?Ph#@waN^J*y$wPYQNf~WQ0t)HVljwGb4)v}EaUK~s&VkB@0!3gwP z%sm_d`HC%G-;NcGPy6g>R@%`k-xSh{BQ|7)abLZXr1vbLxXz8Ys|svYk~W@$uR0p1 z4a=MpMNhYO>{=k;R~Z!A)(*E^rxJ~^=PTwCZ!tX-9w*B@A&Kxl-V)G+8WOqr12Eu{ z{i8!Q5|aNMBj@b$If`P?tk2|TY(5j4$*fl`s7paVp_PcKS=xlQQn6J9FNi|D;#j40 zIQ*+4b5%wn3e;&(Z2S*%$PyIARl`Q~Wtpi6;T)H8OgvfW+Y(|FEErsT1B(Dd%< zj71jhQ+9(iDmW2oZaB!a+bm=wUd7hP3#%sNGO>SDQx6eZtr1FPHUB)eT}03#yHblY z1@E9LwOXkzoyt|EPN+^NJz1Y%blt)p6kK_2Fi!Mgt_qae-Y7a^W3P*3|NP;0AhLRPcN&tL(9fQmD7~ zTh0Wq} zIi6^Ks4%0NI;dS~=V~mSKisdA^5mRp5YEX80`xhiB*dxQlf;C~qF&0#vLme4g-Ky# zw2s>3!r{@oYh*AAJKtG^LL&P>%H%Oa7l`}5D8zh(3Oa?y(fcu86hsECr=%!3rV&=l zYzpi47ayyRn`L5ps-`@>(wd*))=pGD6&w3Dh|ZxAaRi@T05ouhxs@VUtEJDHWuwff zs`6@SHnS_*pN$mNSC2`fiKQ!qGxjyg)g2btMtvf+8${_!$7m40>jjt&yaa)_fR3v? zs19B65+OC-q)Lr&djgIu!zC+vs#Oy72w;XGw3Mh;i8(!I)$$QV3@@~Cb=e4A4=!Mr zxUMK0?M~H+Tyqtn2KR_}`86q;NLCmIr?h&v?j2?0pYx-`V+2*VF$XY2XD1$04pv$; zZYYMu0}ARyVbYV>HbLc>mIvWE<7x&m{rlCY^KBVBck^8J0J1IA#CC=1vP_b(NsXT4 zP?mMItsF8$q+9isD3|%_Fsj5-Lw8N(LF#J)MmeE3JmOmgkfIE2)rcn?FK>q)I>{bn zP2rO(k{ZWlOGwEnvZ+LojYq}hIU7x8>?{#k&ss7F8@!E4Bve{5IxY#!4%s68GPNF( z#F)k*F3@L-Jbc`%t?B29Y8j2pn$|TR1bs|gxb{`D74>Zvg{XfbB0pdOjTdTq=7^1? zkx|Pcve8;H-0Q@VVn`-03s-8$)S}ti%x84oz7^G#owV9P!irchPXI>bdZAwpvFzYB zC7=4T)uO66)$$d!{l=BW9l1?66nN--TC{RH$ zXBktwJ-|0g1A(K2K8-+x)?pT3m^JXxXco8IX=CRk{D}{S>`L!hDl@|&=F<5KCD!XJ zJ|n2@?U*X7qH0@+%a*AklLiE@jQW_K%S5AvFjDf;Y}}1f5K~g%-NP6oEVaF=%65EI z@=INykk>&r?$==aS~wR!T{5yjy=NdSm0VT0xNgE-N>-2G+}S(}^llRx-kZWP zDTLJ()s|HhYw!Ldz3?#y7Uv4fMfT$ikVb z#At8dk^!_{M7L5s0D*XkDeMgISm}mUo!bX~Ya!c- z<<)#y&4v|rCrjPJE|x5|aFs9PR99v1C~tRp~|nSxvA|z zi^qI+hRGtxO6=t6O$CYfGOi*{V&YXxJPO4IiaID&4CSE;oK#IeCm%G_Uf5zC?`&_} zhhm}}PSY}>Xu}ktb=#x5U@e>ueCk0q?i=Ow0~C=bthwTM1e(!_Vu4XmRSt969W>}5 zo4GVYgsd>yhYCLyzu3q_xH{C!+Ng@nG`F&4`RSg43bVIwTmzGtH*=JSce@RPJ2hSlyu`h7mw61BizNn5lpB+ zuI0L8mitZNQYb}7Tpn9#fmF0R{C)rW<<>F^_)U@QHt2zr@2H&$m$`v4voso?@#)^W2`V7zMeIr@_L<% zF7lPJRjFNu%t%z3jD1)n6f9}nk_*gI=#J8T1Jd8CHZf6Ei5EG1fvFtb$wHE$KCobc z-c;5OOIu13Qd9R9^^lRhHhQxvx{wmc9V-ikD!audxobN9MSin6PmA#0){vLf4-r{x zkH?aZ3ftv%i}dO+O2Ug;jEq}{SpaJO+%}G_=ofJ%hse0%%Q~}_oHy%ZR?}QHjJ%G6 zbqm#B?WGh;9-4Urv&7WTRW|#Em??@k_klu)yrjr!i-r~>1hyn?+FDt31DXVzx?_yv zP9eoaoYB5?D`FkFMQD-cOY-ney$T`I-8b3xjLW`&W4fVXJnzIXdZw%(l?5(+OSS9>kTDg z^8@n`;JOV~UPHD|M6(#@dwylTE|G?rK_y=srwM<;;%`T#YtIV((2 zwA^l_oK-dUm2=DyMV=UxX@s*O#Ledhn54O!qN6aVO?fBZ?M-FZEMzx?_GPEUi{aeb zSy)O-)^bvi6LM70Q{}9f9OzC3%Vl9zHWfiO|IOo^qBHN)) zWhsv?%wZ%V;y^H~8n!>E2NPl5gOPx@^k_JCZX1dmLGWb>PCr{>48&$lTQI?#pT#M7 z&L-j5ZmQwiHYi+7$td(yKF}3p=s4-3Zj?K1h`+4d!FWZ=5|@+7KzM!Jj`;#lKI)cX zLzhDIh;D!kArl=b{?w~PT)o8EaS~Gb&Kq*poGE7WHKk^@4UIyAkj$$NOiwaB3J;|3 z9Nn6St&%h8Dm!aE+CpL zQHiSUHN?ZvEvEN)oo0TVe+wxHqC6%B#;w&YC>b}RBUQ^|M$>VgjYE3U%i}uQ=3rdv z7T20rxa_iVuMH*Xch!7~XM~CpFi$1n<~@Q+>^s1zkyxxp?6S8-0I{Q%j~XkVMZCr& zBE?Iu@*^NhWNlR5{|a}6dwPvarzSB-=u`>tGRGJzlWfr$QdpiiKVnNnW21RiuM4va z18TcZnC1;cFVHjb@eMX`G}S#3Ov<`VvnqVezR<$^`6Fy8=hbi}+`ta$%OVdQQR@@} z#KIN&&G2py)qE6>7G|3zm?KP@qeYYv#>B}QcEx>0I*O2M*F}p;X9QO=EcOM*Iiw_E zZfG!QQg>@gEN`QTNM)u!BIl0&0y{;Ii(Oofi`1-Pv<^^AL++ZH)CW2yuW@(q@%`wL z>@RmAn4QW~M6kp5Gkmd3c!trDW+ z(rBrABivtQ7Jdw|F=N*!dvy~>CxY2hLoiR&@0 zo?dhnEk>zhLe|p8aFBk2pMzN*)An;{lAl8zew6dhv;tF4OPJ2I0yEK1XIk=8(#mCQ z9}&^jsT#g?=yHOjIvdhP9h&URxtkh2MFh@6@tx@khemVS1yKboh$`KJ=t#AWoD?)t zgkOMKs~z*a3Kg(gv3M|C)81^B%^`R9tSXiMVsS-p>)BJ z_8%B<7$j2hEgb4%+SWp?A2Cf0rMt1{_EJA%<*i9cqy^<`zl^4%8wa=QBqX`6m^3QU zFXCj$(!kEq-lChD&w^4&B6QT!1P+ZE7K+fq*!_dED<+m>Ap{UEo4{eSR%omnRRh`z z%Qn?+rM4-znhm!|9%il=CK&Ak(j_l3VPq-E@YcOdI8u|0>y)|K2u4P?1{O_W9W~CL zInBTU7G+NN1>|C9TUHv%wh~Fc*kU|?%S9JxYn5z^lh0aP6)NPrQa9Dr6wKk|S){Q# zaHdMhc~Ys1#K)R6q468ur5?2)2SrP&7=>QgMi-;di`r<6th)3(6f-vO2{>0&xOf#< z3ei}rT`iCT7K*Jfo)%*n0$yHp%#<+hEb#}abtlB@T`J4 z;5NREt7i7dRo)BEvwgGN0dlR7r3Oo(kzX+Z z);xGpa(Pb^0j&0WYl31pTnU%Bn4sSiNK`WPnR$#82r{U}C@4d6o4>BV;IZ8zzP6dr z((iIK3Ym?ejAL&$a_$h)B*vZNhS{VG4n>M2QreMIMBZmT8Q-~Olc`G7rH!;+CM-d4 zY>zRJ@7t3HlJIg^b=nRV)2t=#qFmOMKqV6*m*w!mS2*#!-J@MhF(t7&J3|7n$aP2u zsv4zoMBuq4gh{;3FnfEzA{OVfo-HGgS5*0Q5*q&yeI^0NHyoFEp~qCGVV%}qsb%58 z$!KU7sSfKE_FMz+)a)Z;Ymq<4t-8DSw#{1{r_61R%Yx zU=vL7GwV^5%taxxIYhrj9_LPC)gkX9WGS6zxWL+2W?Cp*$l*zD>#!42S3{7IZ(Fst z)6h2E-o-4~o)>v}0DoRyRmQY;+9m~mb$*)?gpn9TFLL(J<0QvjN?oFj?X>c!1PG z_yiwIg76UNa53eC9KoCfYVeZqp>4sxyT=GD(~HO5*dn59-e7~Hy$CnovTJycs4A&X=v>StS8 z&NcnKC9^jzM@>_~6soeMHOsq$KRI~z8b>-2v4*@(#H|#inS||;0)Py8( zSx@uP8wb}$4VK)j_b!-biCgqC*#*pG zu3W#yZblTbq1xhF$*f`5Zk9lU1G1*>*e+VbHtAqm)qVEHydk(|WO%u?_R@L_Kof{% z(osxHyCwHYO9u~aMBqmhxTHr89$c!PDnnYr2DH;rWHk9;l0mUAU%#@4Tc)Y&v9!!$ z*d8`728Smgm#&KZ)PB!qJfwBQY;7%LZfTp0kEkX`UTQ6;#q&dYhs?1mkG`ontedpY zWrtebY%o*Z!;Lp7j2pO59#voa+eqz|_;aP%=Oo9r_b`<}sav`|eY?)~v8@d}$i|9m zv=dt^wbU8XGOe@L_3fdt25h#{a8-LznTrNihQ`7=@};Uz%a*!19AYVSC%Fli=Yvgd z)^+)g*Z#90F&p*l1OW>&CmT--t<~xt$8L${T;z3qWSo+$>h@hSJ(e;Qq}qQ8grnHg zrj>eA$-mB(`s@n5hO<*}GM>kvn#SVA%O2(df zB4HiBJ&mPxYq|Y^e%jlEOlGjMk^~A)Wq8Sw6jBD~Y3Zib%Ut0-KJ}p+Mx8t8WYnZd zr;NP{vkvj>SnBbGfyIY{Q_WOAOnP2t>n2 zms8tz;HgLPDY{78y9hjB6G+{Dkx$kqW#;bkNX!|=cE3#H?g;jO$qRBfVJbM$(p}naN z?DD~_LoB#Dz4rL z)_Cx1FtAD6;YZPDDUJpx-83Ijlx-QxxF#YoR5}8huCwXe!zD+9yKluQXgxmH_}-=o z?YrW@$S!DcNBDI*8whXMfpjl|@tYD^RV;mAXJ=$>+SU=0_F-0^qFgRXgqF2STct0 zRENV^;yZRtYAY|8$2oIAv{Hnm$M;(;Cf_7icT>& z5P6u8EiN%Hn5qTE=v3I4kjUr8;Z4ZYc6T;dpr)k4;k0pBWh_ZJvOF)DuaG(QNA_3w z%A|fxi?COjyRKM~RfAl@ws-U(xlH}5x(BpY@@(b`%DxLr)#DpJGqaKUmsp08`n!?j zV1vQkG<2vcZvQ$f0x2A%$;jC4uOjpqY@Igz}Xt13n>Ru=ZFM`A14IIpi2TVQQ9mIDJ_b^I#$#g7& zZYq0en}pNLO_aN6iK! zr%t7EH7P;%w+S_2NQ&oGmo||ccPEGO&HX*XD>UB<_#~MsIR#!JvWv9I^ zTwaTL;qq8H*^8H9HZ9dgi%nV+#2!&Q0kz(G-8#2)?HUxQQL|=^B4*5Sd9mlP>&wCI zvJx|PmFRhAWD+s-FDId%9fMFtdpm1aU%LxrF-9qIyK7J#yI6r%4$2y?9SLG@$JE2y zSIG3VJa95Db1ZOJ@y7~`;nlZ$ENSMl*rfw&OqR;DWiS0+3@XG*l&l9wSF_sJlk#nh zgj=~zg|v$WUi){4M2U_g2S^*+Tu}$IPpBygaym+D5<=g0v79Uu=I#iuC3R(FeAbunFr0eEjx8cdvYlp zXyfq6Qe>1it2d92g;o2p*2-fHjql#W5}cW)6W56e{pt=+MrFa*WQQ`(PZ3SK#I;~K zkL_GkHBs}lVR%2SDGAW{kR%u(MHwF|-_1iTJ@=YAa$aF5tSa|lh3nQ{e70@e0fTz> zn&hwRD2!t9>?N!i^CG8)l&C=Kd^%je!^2JJ)&p1zxQAsNHDEeV{c5OnY-+YmYqXV7 z;brSxKQaL^IYh5WNcgIc9oPq!7G^%u=DuA!&+6MZ6jygAr40X4Rb#QcoSpy+MgwFr zmZcQ}D{U{LE0DdWetP;K`*%x%;3jA(WDD&OSF*;0W=4H2;NYuSLp+@8y~>O^oWaoz zXDy+bLMYl#2Zte|O(le~_xRnYot^QaJfx%jXi=V@I!LOBQ*o2bJ3hrX7#1c|PB{3? zq)-`MwTm+?yOd2=O3reX(|#2Y5+$$l6#dkxNbh;woMK7ekN8&@v z4x{Rz>Y5Bi{ShHr^H=N;^X|m3h}?E^jVS?QS{L=v>$8twmwYqt-EZQt(?rSk+fZfK zHg{5IIjmBdRco_78o@YvHpWtKDYvdfaQcA_4#W~R!sTKV(&F~2*F>j-FAL~EtsZAs zd+FGLUdr8XJD?h5XrjP};s*OPNfNes2YZsa1v+A@f^0;8YIk4fa(&Hi`axa{B+J`a z7|_i}_m-~?vNDwS4GK}Q0}^Uy8k8w+8?nsqATK2~NKlqXnR^OUdr9M=$p(YI$_B=z zUQ~EBl-s}R&B&rT+@W<+=^1rP*=d-~-W1C#tXRRBs>G73inoRf+C^s?-bvRfsi*$6(gB!+?cs#dM4vrfWO2>KGE< z>0H*4%h_$1goK4+G{$7q&Nu`@qjo|W%c}Mf+O?|3yo{6QBb}bz-PUib`*LZd;9N&` z5A7T7h>NVRmEw2Z6SX@D7qvLSBP)(6d{!F|^*E#8ljKH`E3;q~^>WRLm2IiteL_901G|I`@Flx=3WiFnyfWAIu!&#AFUF&7vyA)}P|+jp zci9ev|9v)Y+&{eKoUvkb+lNiF$skmVok+?i`5ihFHp4NoLRzkeJms{C9v)f9Go!I< z*^x}C zpxdp4Wtr~iVu4YDaGiCu5^gK@>>C;#-Xos4xU&xT(_zJamTt`~mQBO>9v&*zb@>I% zV%IER%DFmC`%~MG#%^sp3(*PcxkcPxDlp2L zrO~j;?OTxy1Xmk@($J!?SWVG zRdFjytA=;9=mb=)OfEO5Kz6`{PQ2-w?Mrx+kjt8>Ez@J;*61;B5y`eq#8v6oDbvZy z?!Ml3&ZJS!MGU?I?JW*6Na|;Q1s~+nqM5pPca^as!tV${TA9h59I9*=bp)sj_B$M6 zFWMWAd0(Q#S$SPHG%8lNo;9Nn!m3Hrc#?w{+)gBSbuK+9;^Adbr`y;Lrq?`rxZ?oP zdEMRH1;G_ovumk0sD_634?>i`I6BX^&NpL z*Qy9pJELC2g>pS{rR(JKRnbgQ)y`z)0R^&w$>G^TmSSdStvety2cq}MAvRL1DX_!Q z=O(+r98Zit2;4*hSjxX4PT)+ANjd7ksxNJvD&dNf!Z5Hh-oL>bVOtIH@F(TIW%; za(s_>y^2uEnS*e-Rbm4{#MV0_=o2t%Y|JwIYAYbzU9i~9s9e1L;8@e%yeVU{wYp~$ zYg=#91Q~04ENLU)^^6fzcu9HWs;Ye?lWip+C|$f@C4~n`RJCx{f?4LJ=usBCEuNtY z1|gzYN-tgtt_q%4lLfzA%@Mmel@~|W)4kgJZ?%F)`V~T%s4U$ZEh>>frHaQGWjAkq z*5=GdE*JaVy9mv*T&!x5t(AhhskS?pZw<-Gh&2p_7_+gOvf3znhmQ!|bm6%OLR)5A zLvGndM8s;_xM96*w`nXc7cMd(r(l#_t>N2|d}s;F+b*BNF-O+6*5k1UMKd5pvEq{Z zp2ZU(ZxSh_TEdc*=t3(nP{d%Z=Nz)E&N7<7df{3BDQ9qjYU1NKOih!ecFMLT(<+!J;b{@9hePhta;^9%g%&AJsfc845SrMN2m?HaXRnlZHa~N{@q(f zGhJ{&x4`lEhU|*a?%%x`o^g18DE*EiaSuBNNG+lp={1~?N1| z%itlcuCagj3SFK|;5F-3I7LUp6zQ#-Vp-0C?G6N2L&DY9l9Y%Xd)b&Yqq(vWrnE99 zOd)z#Rd@T@S|;oodfB?((i5B|`zx4a+p>eqglxDf!jOxG*#fqVkL9Vopa;#Jg##QF zfDIkZQ(#z-wo9W}+W}d>oz0-p?t>Co_A)u?X^)jLgR{Xbo`5(=yy z8{#(Tr5eLB#xl>{_3X_PF*Uo5=0hP#Y&j}yu%(sOmz7V7rdEYr-(OIbLbqlGb^T6+ zb^a?9Jhr zA%)5AlarY2r!3H`VPYAD=y{dQBrhR{iTV7Nef13O8JDP=nQyC?`L_}y!fhRUn$Vh) z67EKKZD@~uEvR+QTl0tF+AU{sDHFJ^{eZq`mk{~EE&JU#G=hG&$o8#x(pjGEx|Y3M zA$H60Ni&jamWQ!hi4hKVP;2>G$C^~!h09~baVya*WU(#fYy{S~;wvv|%A*QZ<|lWg zWqmLxRZRPbA==}_7R$kp2{Qv2&=hAJ2MKh zl(rVcT9;J}5`b5hwrVn(N}6-_-z@L64FFh zbKo`KS#!5^i3!%cjL5a_q!DR6WCd44$#7O6yI5C07$^; zsoO4d(?#i2{!dR=8b2#tKl7rryd^(pf;pTnpEi54S3u_Mh(GaGXWyCa=B zeO|imHZ#-QbZzQx&b{Lt{CBtJw6^e_L!1}!8-Hh#{^^aY8gtUjuFKO!jhW5E>C~?G zH0GsCaT#e`OL{x_U)|V(eO4N2CQ>91UCRAcX~&F+XC5E9AI1O7bhAwa#XOhXw$iaK ze`=^cfzdSnD2qcfpi`I zXEj!*k!ctRp})(3!{k&oJkq#4UEWlvi}=5`bs=G|C8ZtUcQ{OHUeUO|aYf^BI*%CV`)oPHiM`Gs)-Wq;*}o5c?MXm3lYzqIR9z zxCp?`UNtaOr^Z1_$C|~;DLAb+wuLq~Nuk1QNt`+Y3Wn0pmE+_-> zTuRvP)|vQIKIY-?xkkYyP95p*0AV$PE~h?~hxqGmt!~UoN71k5 zrj2P%>!L2&tub%fsrXhq>F+4#Pd;X*EltWr``_HSxxr0V^oGOuQ2s9>wKIu-4*!=o z=3-NgsXX)s>b6Ci2Z*7Ya2l(Z6Z#5rJBO6I{f`@FbS3%M=-fdJhpCG#>CVJ|XTEc& z-&vG@*38v}KQ-M*DysD>_}2e4ZW{QWm1ee7NAcgnu6U2-cTQSPe(p@!^xr*g%e0Yc z_XRtXGR(!_T>h0G`VBG71SkUyab?#vT{m}K#s4)KR^$7sR*P_FlA{Y#lb%Se62CAl z+KHY_O!MfYO~=$EwiZ}&he>o#zwK|^B#Ibroxkc45hCIWUy4ofuBIH<6Z5Mj!pAseYrsd1{-+%tm+P zsx*h+?#2$_Mn(=J16nbwaS`?_aT{rzhiP@=aD$Nq%xUZ(v_{C4#CZ)hauxIe3Iz5> z`pETNmrv_%T<%on`u7TQdJU#6z=h;XEvHtT>EB~1&v|J}m*Sp9Ki@%FuWP7mr&A8m z361az37Z--yELL02aPj{aWyf{!{toZ)}^=~ASHZEr#Go>8rR`|7@X3b)0|5>id}vF zfO8@`cp#gF4SewKo_;M~jTZg&Y}~NyZe1xIO^-Pm`_c4;+omoc0gZGd_+x-0!5v92 znT5HTrUBE_?f9L6c?Ra$xEJ#bOt;6c=H6Di4R8c-Bz4}xWhQVN;0WNzbO+;(!hAGv zTi}><9Pu7ce8=N9hp*bGMQVvuP9WSI$FA7!U|fq3t?avnk5;-Pa3_9`wBMOdIsDGB z+nve9alr9_`osyqo%nCse@b^@1c(mY9+Pr@S8{bXOml&|V-qF;4Sr7qP9o&VeD8t# zJqdF!zVm>46UTf)9swjkBlJG@+f4Tbb3fn|;QshM6<9zDGk^pr?uDeg2>{_o(`Nr>JP$A=|7lX)%!z$hXM}+9!{GQACCndhkGw@9_Btm_VZndJ<5JR`q(LHEA|0k5I7M~ znYU4UcK}q24Qg>awJ2IW1e{;q23~`o z*8-Q(^W^7s!0XB18-O?Fd@cs}Cg9EV%%gw=H0Yggp=VxB&wMLA^KH1l9e4+zc;D%; z&GasM>`dDF-Qbk|dw}->?<39kSMi@|y7K|>9|S%Gd>FWbUVTDUr%_)YahMtDqqu(z z_&D$h;FG|ofGdGd1D^pt3w+M?eoFd0qw5Rg<%_h%Rg~aMz}1xb%Z#LM%5gNK=PTst ztH9TQuLGj7-vGWzn%~0yZNA?Dz6*R0IGNGbL1_t=v#?t zB{+>E;WQdoVOo{_txiAi$ZVw_;_@Tl$G}e*sSWTyWwcHQ63_rAT0a~2>-heRQ7l^i zb4Kzn7|Fk+UGD8V)A(JVe#MCUHD&${qyKuoza`(l1Ab5Vlli_2I1%$7fd9k%N8kqF zM&M7xf0OfkO!_lp`!D$UEAThq@3`Fz`~!dgq@Mo;{2TZWx%)5p{{cS&RKP}~m70xX zQWwx_JSt6Vti{&`YMgne!K?$!1a8wfB^}Y|Nk0_Fkt2Id3z z0qzUj4>$$5KX59r09Xht0u}?O0S^Ek2%HX_0XztJFz^uIp}@m{hXZEYgDeD^G5x^q}x3;m#Go9LU9bwJ_*5mhG_*I>B zV}2C%zrl6eNmR<*Z~Xy=L0((c1GHTc{i{J7zRdw3xH8z4A={d1N(seA*Aa^Gx7bz(v5b!D;?(kLwxfIrx7r zdAqnF8nz`}(hz+XO;b75*P*qzU(HM>Ugr7uKMWj8T$*b-`(`Vhh@ThW{zBkI)b&PXnI;J_~#f_&o3h;ES$j z)%|1W|1qCjMLb^ut|t7Kfv+?k%N+3F^woykXQZzY?(4ucq^W-J4Zhz5z6I{vz;}S} z684t!1sY406zqN1pJtIF9m*r`KNrZgxZ1Z!}7uQ(v2r{s`^{;6~t2 zz)irP38Oaq3-DLWe*^vw+zkAKI{PQ|^k3A^zsdW58s{;GDzBpZebkKRn)&I!jehvv zez5(J;;rd_#9Mf+*`yo%zIgl@%(DdJgV5 z;CNs?<=joK=QJDX1mKRqoq#(N=Usri;^%I_T;T55PXtbCo@zekWN;CW!ojPNpSyrl zoU`FLj{_1Q9$xivPrC>!?Jlim>D^9i#P*ahsyzNfh>4PzbwE^t5DO=?^V-{d7k zr`1Y(o5QTeM$$O$`+)txf#wD2VD^8gIhr2d97|7V?oCf@j;ALP?#aY=A@CI7sld~k z`_j|-J_C3r@GRgW{5>0Z4)9#yVsLM1KvVfXkGwq}I1K&;%@H{8(v}(rrQP3m*967xqm6&mjRbHAD>4c)R;SO7Fn@PT*a@yPHo*?`b|Y zy|?+a^uFfP)B8#D1H|`1;`$KqVa!(mAHna%@CF~HUb|Vv%!I%E815g(?Gw1EPk)m5 zFKsl<6Mw3?pHe~Vv)iZnE~ZyZ1N#}md=~rXfKL@^LrF-&vCe~ zk?-TF*Dh9AUnh=hfRkBWN!IZVo1bX&H*J0ru_owyf_F^B1=rrVnD}O-Z#6H$jWq!N zzC)bf<@>$n^N3g6nQ)>P&&RLo=WzZ$9oJF^t#mD6zMsqd1N@)NDp7HNoc2(uQ6ZdcV{toy({ublw4~(b(YrZVU zFJ4_~Gk4)feL{Y2XkI$OojEPL&$j!^nd_C_jPxhqCc81$k+;7zwK|pCDe14Isg_Y6 z6D|82Y2VO%B{HRO|2uwe2L1v3lX(6G{M+%d1|hEh0{;UJt7f~H)4E<&m9yCuadv@k zbv4p7gcv6gwt;*`;`1gM2CMx50h{aj1@tg*qaB~TFchXk7oY?ioT=rAaNx0ucot%uHdjR(Y?gh*PAALmq z_)XbAYa!y8kK28K`{M6@d=>vGj$7^1O84)2Gh;gH=2W{YUFO8Dx4;8OdmRC-I+bwi z`M!)iosh#v*)Gp@drM_IB`vJtRX=0xMO=%4(*VtL58(Si;B?>&;6cEH2@`bet+{TS z=^>>1Q1CY)lTe->=6K)6%DCh+rH6x4y@_W&k$BDomH=mTiI--crEZsDUyi?fxNY9f z*i`s;Kza0iXIjzquC%i2-Dy?Vd(!HzW73+g_ohb>=8?c!!ms0dR@eK|`mXoqwD+g( zuKnpzzy_cP*a)26^?|er|C@m=ggFOzH0hoTT#dBkF3(~ zysj&t-=%CHNqvOxC+vMF-&VdV=Rns-X)Wet+>UR4%x1|ywsn0RKBYI+zri7=XPW62lp)CBH-D;a{$TO7L%T6p=hG$;aeJ?$@Jl~>A6nhbJ?!( zDjCk_bDXE7i=io(5YO{S^ZBHI81oB&7h-=A-xmWf0Tv^niaI$Zy%f9rzYMq(vuHk3 ze0n)>visZ@bDz5kX{O4i_DSg#z$*#!bxQmyzOM#e15V*}TlZyv=+NuHzaDr4b*;L5 zBl&t0_BR7>>H1QY_semAEATd8K5lOZ?g#uQ({$zO9WMXXlw0}ua(ZXiSJJ!i|8C$t zzM(&Pyx(jP!m^+Q0b!je~V7etzY$NLKWXOvAsKe%&fE>0OdjbO8x1##Pz$b?^N@^@3Z?K_%23b8uNqt8gfSB z{v&Wh*Y^midY!?(AN&A*FDAY+H!SG7)_Y4g;rGwD%g;M#^9AHtY5xWPe+5qL`hM=O za3BM2)w_P_bQnmOV>xc!&<{2yPk&Y09Z`NQ15 zq7GC~4cs6viR9VsO=%kN70q?{pN?5$^J?Oq(PGaGxD9Xwa3pTurv`&YLyri2G_Zj5 zZ`(RD9n&gv_>c2k8vV3BzGvBw#<1G!Cl!D7pG*_fMkkZU#YmE)AD@zLM;fz%+XKe} zcL0tfKgR=efD_2q#T4p};O_+dnEZU(Z6jVt{K|C|%{+nnxtRJ3UajeVtT|fpm^%~K zzsN`Q{h#G>{yg1<`0onb4G`}&xAlv3cg!cYeo6jY=_JxTkIIxB>}2A&2XN2Uub{EN zO!vZV9&qp0uaV8E|NJJ+Zz&JIO83Fv8HBrU4u3zshsld%bANPwXgpt^>nPeK>IeBT z`Iz1OEp%1;W53INc1t>?_1koR+Tv8;hUV`p+IR%@vw-w|OL_~*`y${v>S-~!(|`wH zzlpkfVCxU$K=}-MbUJxD19#Dy2l0Jy>;EdcFP=o>?03Yeu~Lu!Ax{5~SPiTJ9sxYEb!uAMD(hCQLB)HQb*S3z zhO~~fk8R#ao!m%Ix{*4Hb;rqkAJ+U6c~&&Dh@pTn_H7z(0^hzKt@z9e4-u&ep%vyITKA?{0l0 zy{Glr^j>i9YyCI9zxBWL0pk5&>mlhwg!?dX1@IBzqb9Q?TYVByDG>Eq-_ZTSh}U*7d^c45`;n(33^KLwltjk=QWr-9D^p9MaL z-_HYI0KN!ZMLsSeoiAa&8u&8s72vDD*MP4B*8txDz6pE__%`qz;Jd*0fNO#813v(M z2>b~6G4K=Mr@(bB?Qu05Kg0ZU+D*L6FEIZS_!a42O!_btKa=hTZZ3Jan9{55?@pX20w>}BWWM(R?uq$ceCGl8 z#ylUm4{%??-VZnhxIb}d&)`(d3vgQqECLpTKaKALfCo+!jclgV!JPp-2;775{}8?p z1s;a^;eg~7XJTIhEG56o!0iIJ9Qz7jC9n!u4Xgnkf%_x*uAO#7qfOgIpVSv)uVo$X zX94ShZs1YC2B3#BY5tO|bR+h&fla_>U<+^#?kCgkkIs27do{CJ0sh7NUK(rKM>w)^ zG;`It(~eA!AwQ1=9tZRS=K*~{Kd==T00t@lY~tNE?Wl&dgS6(^4t@tP1e_1-1a^^! z-F)`|!+_*5BYZCaMu9P4FE9@5BkdcSM>nKHvY&7VfP=sx+#a9HA->`XqiTFEApMMhHCj%D(PXV3^JdJpsKJBjQ8PkqwJagKt#&qu}&&pw0^WoB{tn=sz`KBV zJMJc92b~Pyz2M#l?)|_A0Lf@R2<}6`hk+}AkAS}fxES~-pt66A^goWb{?KL&mR{1o@=fS&A9+PCJhNC=G+-+*fV@eB#91Nk>h;8{u{oC+ zKGL}@_+x-s_`lusBhzf+y*=?rLVhgq-vKxdIDWcxY9wbnCC!J1@1Qelr(qxiPVkCbyEJGOx?+@yr^9FsM%GPdrq+5Yl3|qWmWhXvnRoG z-EsQ8$xljm2X`WHlD^nA2S~ngGI`Pd*FDJ3J*UraXb)s|PXAuG&BOm}_SWw`eRG;m zT=$uNAM(06-FNzZq2bcKA|Cu{KUnLEQ!wA(;hAGFFTlKz?;^g7`JM(m0P_R+o=)6n z01pBl3_JwfLvec;--iQd0!x6Uz%pPtuwwfC8Y`!t0u4v2h%ll}tNE@09sy`i?~(Xh z3#wWA=$k&T(NEhCwN7emoqlp-VER28gVXQX*f#xMjqSAa4&oUC&L{qz zz%JleU^lP_7zRdw3-B{a8e^FE0^`6wKsuNE!5_eU5I96zJ)X9B!t}c|o;dxkjVDc? z+jufzF9e=~zo+8oX~5HgX8_Lxo&{V4JR5in@EqW|z+-`nflGkr0nY~x11|tx2)qb* zG4K-LrNGO8OM#aIuK->Nyb5?V@EYK?z-8p&b=1%6$Z_@O9uC;2Xd3=4<(WANT?AL*Pfi zkAa^6KLxG>eg^y;_yzDw;8(z}3Hux1df>Of@4)>Y_ygwu1O5oyF#Yt#jliEM(@nVj z8TiZeGobG9z2Ih}rPZQ*;$8lRU3L4g=F-|;u4wlWjlV<3Zk~P&GM@)G{sFzaq4|); z|JT`BfJc#Z4YzwbFq84j;7$k*!F>tt?(XjH?v~*0?(V_e7T3jXadvUH|J?4GzzX|* z&kxT@b(h?_Rb5?GT{a()FMW+qB3rK)DI?UYAM|w{dDYL9|1bFc8a=D}EqY8fp2~_L zvrAFIWX`Q>X4YRrG>8snu$aTtK&p4EnN`a8vzs%k4zqk;${NcosuMphb7#d3LFVuM z2ah?Q>NQJ$&ZWdKM=CMR`PBwmA|)37W1F+7am+c?xaM4HJaYk6zPIC>=}SXGNCb%? z2_%JJNCqM1MoM!0r!W^(Q<@8@smz7d)Yzwiw2%(cLnvebS%;JnGZSP6FZWqUOIFAR z7s=b~m^mOP$Dfo} zS&=RER|)P*LMhzjd6wq743vd(AZt;|V^)BQ$fyLBp$b%mYET_&KuxFxwV@8wg?dn* z=hJ}j4b9S@l(DcPY8>CY(g^p)&;**|uNgGwx&^d^R?r&SKwD^s9QodB&vggr2%Vra zbb+pf?}i@_v%|7>y*u}ku5h)O+QVF2&8@EnEJ54DxC8!rL2r;TWdC#N!+l@q2OlV- zXVJAkat4q`+2EqyM+sF1nqw$~keLF1gRviiDSg0C)H_4D-$CDH80K&o0a7>EY1?G| z?MQST1>xW&j#3ao_|Y&1#=>hW&JyVU~KRh&t0; zl(wX#8jqQdVydj&_A0Z?US&4S!QWh%2lHV8au>oPSPV;GDabg$GR)<$0#?E*SWTR3 zU@Zh|rF`YQ1nruvvi!GvElpqGXKvKT$T`OBK+K=|DXFd}-VLx3Ho<1tLOA(GkY~G< z_coH}vkkVJgOwfJ?=+X?S(j5||EFA+vddgv-Hoh0<_hXw;3#g#%oUMeiGGuz!!gR!uja~pm;5ZPl8!3sal%T!{{-@+pLmjIaEfcmR}b>a z>#IzECPTs*@2Q6ssmIMCvl`NjG9JOo)bH0dRM{7KnmY0f^3M{_Ide@l!GG%KU#Dc` z^?BmD02h6_UP4Eymwv;%3{qZYP23f|Ox9AbqRTaNb@e*-XYqH#T!Zw~W*nxDdeax? z7UpfZW3Eg2WZfXwzr#JaPh1Z$J=9DOd4@Rx6y*{3kIh!)2|7H5Kj2SzhTrG7$zB5) z$B^gt0=qcay@Ud^HHW!>#r12mtjevczA@KV-(vR;yI`$>`kw0#T(>bbr2ICb{5GOq zU~U6Dd7htWQ$Cv;qvy|_hv8S&%6&nnucYZ4aVZw5_dg|-Vc2(UC&qge{8(ZOtK zrdlkl-v%q#z;0NDOpqC}kWX1L zFGOoYxoU@AGOlk^vXS4}AqV7yT*#E~zufrE1HV|>qutM*VLLT1a%F8w7=9%k`79l% zvpSG#9Vid7?zE$tA2%uM1uzRjAxkIRB;Pv!N1EmR3|0zTg4xGnythRNJB4TEUk`YR zGFH@5T`2|;#8@2NOQ26lD5XEwPCNtYGj*YS$ZGGd`0A?1-I?#QRFv0I=pp^9U{-=V zf0|DG61VKFDNT7S!*y9GM||a>f~7ls=bz<~jK9$SwTW{Hl0=Klx z4oUl#o_uPFeyvDTuow2hemDRJ;Sd~#BXAUs!LM)}PQXdzoPyI_zohoLOByA8 zXW%THgYzJHc>yH-7vU282AAOqT!m|J9d5u)xCOW24%~&`;U3(#j8q?BK7>c`7@ojW z_yhigXYd?ez)N@qui*{6g?I2CKEOx#1fSsxe1&ho1iV6}qL@H~0EhcO z;V=S5!YBxb2pA1xU@VM-@h|}X2L9(4Rc^F%!B!`02aa`SPV;G zDJ+BKumV=XDp(yDLEn|{9j@hlcujp^)W@UsI`f=qjL#fPA7Cu09jo6zi#AGK8yK#x zgY~chHo_*@3|n9;M8Y=M4m)5c?1J5}2lm1~bl4v_T0IarMm-qFdhft-)Pv)QYn&d} z;XwJO9*>^mu^X@39YJ5wGt4xBc5VXp6LkBd*h?FCERb)Nz=?#Jh}%Tn?Kp1I)`giS z>GmhMKdH-RZb1(>nYM1CD)y%Xr$qTV!~I$GI)@oSPg6#lrN_x1B{`fAoQ4iY|MCKU zE>gaBQh#2;3^7etWe@FdTwjJOa22k>^*|%9Z)!7$mpYBGVWye-_ts6WC4D!wS*px^ z-6H_eb;DBlcsu)7;Lo9{B}Kf>LE`|toB!XtPLPv9y10e`|Xcn&Y% zCG3edN1a7nHK3-R9@bc4{~F%FTX+ZW;RAexPw*MOz*qPNEL>4kYk*?1GWP%h5DlVZ zFLk{cHw)K+U`5O~0AWeo&oOo+vGY={GKxsL~>kr|)xnJBvnkdY7) zai7@gQj$PY2!>=30?8o-q=Z!XOO5|Dm_0~yTI8nVK0Sm&2FNI~t<%)ZxMks5z6rBp zW`jF?UuDNn4#)|)AUEVeuU{Z9VZ!j254-$O0184OC=5k#D+MThAQ~2id!|P&V3EcL5$4|gqnn}1+}rS19h!clzN!;p#k;{p%FBO zCeRd`A+I^^Es)a^T0v`Q18t!lw1*D(?FceH+zGQYbRle4=!ScD=z*M`*!P0o&p&}Gu8gqS?U1mY;~Y@2H!bz87q_T9G5bPXEGRuKu@#G70Ek7KMZ-p2tOP~z(^Pc z;Sd3%VGN9gQtCW)oVBnz-fB}OSm&z~tuhX}fOm8Ouj~Te+Xd<*t6Q0jOp(3Rw2&VC zLfjVWZd0ra)Ty}bWo%2{LDs(WPX4IdV(NwfWg2mL=($g~E>&k(m#Gu1%NdDUj-2Jl zS)tCfuH+k-dK!PT$(K1W7v{lySO5!&XOT~j#rO+mZfyyAFD3oUtc%H;Rm8mtnXB~r zX1R5>8pMuFYHse=5C`=+a#n(jy{*Dr4QpU6ZtF0c(Enb~^#<5zm33@u)lJrQq+uO$ z*6DI(&&FolJ?!p`1`6;;*@AA__-3i2ZXo|ycffrlYy%lPll;lbPEd`VpxX(*1Hw$3 z)wt{mRY3CE$j=4pPV#k^b*{SG>gC)9V_b3%a`u8T21nnL@T0hw=dz#ctn4hEY2Bb6 zAU_W3Wx}N#!aQuo)ZYuk+k)Shu3r z4!(1!yOD7VZo?higSENpU28$*ck52|9)6$kZF?V`A5aNC#QhOGw(cS?ccJ?(beHo3 zcB=u%dV;^F@CWbIpVmFt8RHDkuuIAFeQuQ^2v%!Ta;|Zn7MX<6I?dNfFKBDPSay!4H5P+Ag1kr8p|eYbc}iD*f#k_ zm$5oI|A2OcFmY{%)OZjd64+cyLP%sgtR_aEB)Ipc@0t`d7?NQZg52bg0#ag^%4Szm zlU6z3;5F@W8thMVO`=%8C}$h!YfM=8caXAig!kwOE=O>7DQSr-9r30oOsMTB<@qRX zMOIo@3-@VkC)B*QKqbs}44tGbo+Kvbl1Wc`)|uod4-42%p)2z(*cF1pP=v5W zp_uKo-mfW+T?r@&rJyu!sj0)tV3xJXDnaIy(Z|D%Y$>1R@lyde8M~^;bzGR{GIwv^jtw8^qxb)|LzIm|cXHbuKg znZHO@UL^mF@+5wxeAP#81MjwAm<^p!fZ|a!JMoRogL?GY&X=l&<@%| z2k2<)%E*XS>14Z!pPQuNCUJcq2kuNf>6KeNgIl=W`WH9KCGnnCZZp4k8$Y-I=0`?* zWE~&lC+O1^x;(_U48)8e>}VK6*f9Zj)Uh^M(|DKu>|OM}`!9Oa4@#>D?-6b$rp({YvfU$&d+2`;{pIY3``q8>{yz7z z=PHtLMxSRk@9#3J^ikLs!ZVxW(={FP=aMh;U_J!%UZ%$H0$2!(Y%-_2Q(bI(pl0NR z0ebw%mb&Hv>%Lsd62eHkz7&0z!E#u^vz2#XC2q3!U=?<&VGXPWnX{F(DeJg?iMbwg z18js%uokU z$qzY0gl{(+?KpY)jJ?k%a6f5#q@E(Ii+B8-KAy-3CjAfDyC-vEr;&My{5wN@XKjyp zrszPs5yB}nHcnhPhx<$J&tqP|&qeVMA)LhUo9(H38LklDRoh4WbG8axL%-{A18%}C z;+HdaZWHbf+=bt5e~@F+mc>-=aev?Tr}_XM!XsNu<+1IVT8L8|_}cP48(9-A&&4Q@ zPmn8XvY#UR5BL+F!E=bDCEm}ZdoV!8T&8r6~2M26K7F@qJjxD2!Lo19nA3m_uQZHT%Yk=S;Js|t_Iql zsaE?Rv^5{tW8+e6_Au3sox|?$L!vACIf>6@cPVZ=-+$n-+Y~Rvu*-V-7v!PXy<}`v zOx7%rk1>%Ei|g1BhwDa^37PAO%Y8hE4+-qAcusP9#w%n<`!3I(`5p#olQS!k$o`)E zGTz6;#BYNnpi;KPUs7}l#;=Uso5{0ec6nc`Q2z!iA-exaB{}XX@Rt%&frLwKe@$8R zk5#;(@BXv#bLpqbK7uN08uU%;%NPH=)(IX{I^@?;Uz3M#iT5pOc}rSesp;*~zmYu# z5~tC=4Y$6d?vs;2-r>hsqbzQr_V?7Q@3DW6y_9r+o5FY?@-q_eRrXJ3;yN=({gDNI zvg&cLCXMUt_78ObWYxe2WP~a?@RyG|Hz#3@{l$jNT=XJmRg7@*yi4mkt3TM$|IzJC*cs(Oo~f~BS!3C}Kdd1$8Tpk@3o!Y0DUYtQ z?^fc)p8jn#lS2<V`_-LZI9v3-6;KS{HdeJK_6_@hVZG?8*rQMWVyVCPS( z#TU2HZ<$G)mB>G1&q$!j8l`W5Qkguef__!uuX!uFT1`&fZ>aK;cP$v*s^PCX)PR~$ z3u;3hs0;Pq zApT=hj{N)g?)vuZ#X*-ilx8`p=X)K~k1&nUyD|DD;$7`e_(q)M6APH>(ES?eVLpz0 z9H`ejQihGa`Eovll=VT#84N>UD9GMOnO_~o^>ETL0!C8D^a+T^DG@Rb>wiCtI&T!R z!yy7j!x$J#7!RijB>_eh(M9SjMxn8nJ^i_&(!qLu{7C+*JFCL?Am;8~s&qV%Rz{f(uEYibDzs993Cf!TyiA`1TRan*vAZICd%h1u#lW#fl zL(WN9j@=4a39Dc=a@OejvU7-Ztix_SY``v@Uh+nJ3}qAcn_&xV#eM{3FVdbA{X5bg za2~9dkg}W*{S%^HV$(Ks*-lz_z)s{#S=(i=uB1diqrVsIOJ6e6Zo9G0qX6^Bd(e5W zJ;bz+Fu{Bc$@thU>ZAQW84HO20LYlbLCiyN7`G#E6g`g--pGsOreD$RIQA#(DNHAM z2B+XO_h&HA!Z|n(7vQ4awx^^_v+hGrkN^DHR6aZ2dGgMvZ&Q;-#nK0{NW~R0=-tVjSEWCfld3CaX zV?6!CYvlcP$jZr5@}1s{_e#DmYtd;h$|!c_#E>E_iM<=mxOJ>^L)j#d2P>QlDhQ`?r&i_>5_H$@3_81-(Sukd5`~V zoQNf37ay?yh#axc%IR3L&s5eCe8T>-JxssNnz-d|pob%7$XnU4SypJ`e{_gnJESZ|eC#@yom~_e<1*y1vmI9QPLJHZ8R+=IXaUWnn49Y6l_!HQ5G&amhO;>jPsER`NDBVdSKo zIGAxk>cUz0Wlbn@Y)U+bO^NR)PMgdaBX4FfrsR{XM-f@Fwkb-boIZaI3$nWEf?7PEW+VJn=kfq6Y z_TmvHHS*FxT1W@!9c9p;ek)-zILhkzkV`A4m$NFAld87zy4_T@0(Lc&jE(MmU4I9ls& z(wDl-ib)LetSxr*8PT{e=Bh)?Xg;?HpF>gcB1 zb#rvbWX#UdL)WQ?qo;13GxfqG&m6rmRq~~eZuWBY)n#M~P?g?}em=YYy4lAuKsPf5 z4AlKR;_iuQkZ#x4G1zAg@tH$)bE-N__bapE{T#z}yZ(+5x;elx(&uNC?q?wBnW~2W za2?@uAMG>8_{_0BbDYl{?=vU(%!xj8lFyv%Gvx$5JNaZ+y6SPsT;NnaKizyGN}dkF zez0Sj&;N9vIRl;i;b#7DJqvfSm(%xDYBE(BLijS6LmhK;e_b7R(ll51*VQr4XU@mX zUso*9?dn?Oq&~Zn))$YIu~Mp>+~=?3jdp&RV=?aw?IdG1GKNu!GBlhrGy+D#D90jG zI7Gl`?#IAbM>U!#qhHkpa~x%Byd#D(0VX1E5`HGb6qpLrsAs2Bu7b7J%-;m)V<9uJ zp9!;IHq3#!AnmX8m}Nb;^xLE#FwfD7u{!23iDv;U#NQ&!#h6QADc8#|mt(HLTCHqpWEf6U~ZbQnOt z$-x|eoXfHbI}fwCQV(n)>{f_`ZLl47z)sjjx_84K*bDox+mCsGXLyi!<&14Rk`JNV zVJOP|5&RtG`WXDm^>H`>C%KpBbBgQJa0bp|cMi_O1>|0YOW6Mgm*EOr#qAo;>pI+k zn{W$m!yUK_zr#I8J>|Y*8QL&ENEnIhA>ki6;;CJ!#Ve2pkMS4osHi-Fr`Z4DxS{^( z(8r~eXO88j=cMTcVP3*3beYMw$UE{?zSiU%czK?Z-q*-~gP*sU@8CU@$NmF$AK??o zUPalr_?hc3@D;v6cE%DEC*y};f(-c6oM;WvxQ~u$rqf}8K(K-hdpo8BoZtdC1c3*< z5CdXDEQk$p2oo3LL3~I62_X?Ah9n?mGb!-}bDaz`1Y}QXa?BLirNm4Hsku&rnHJJP zdI*IK*k{Dd1eqZV_gNtuWQQD(6Z>44xgihNzhLIY41;`-9|}N0>}9WKA+8HU5$^Ys zUqvyCL2)PnC83masj0McnW>C(1?`KG*YbUlomL|n95SusX{@A)SV>*tcTb>7Yc6Xh z$|AoUdF0_#PfkKo$|JLab2(weeU(YZzANIVl5;iR!eVQjWiQWvC(o}kZdITv^w!@m zdE?iZsyWvZpUg@3Vw_{OsXFd8^mtew#C0vG?JTd>!CzfxXZFZjm3mIAQXd*XLulk& zN1H8U@jNTi6dMhfk`j4W8#~wQ>DApRmrc;SDJ0T1U>~Y9b8a-H#NT@Iu{rTZa4M01zQOK9cXj8x7O;JOX8C2Tur4;^&>TjFC^wjIH?D z>hr^;K7K4`oX8woBz>awrV-ZlrcR`#Gdhp8Z7_8qzG3JhGV(xI?nRGoQSlpRk9GIu zR}T(kmGAbR&TS?+(^$?t?1kSJ&>Q+dU+4$@VE_z-K`Xdb41R^B2ymh*icktf1Qu*L)uY810#QoX1 z+w=uf<{k6!kt*{BV~D37&*&@hd?OvNsgXFmOfSdsJXNkupg{o0oLe*|_@V>LGxW8! z7On%q3Jh&g?)_)Muou>~$>boM6I`x6Cbvt@zT9gHa`7DvUYDFtwM&WN;@nM69lnQ7 za)wPz++u;$D|5M*G7+15Inz20W?YB|@gV^ughY@S;afw1kqDGK?E$;65YzX98Ihkr^`!?pYxlWQQD(6LLXr$m5dtoVgON z^AbJ`@%UDvPk~Rd5_Z9sYSfCp$^p5<2b-~(jn?-z7t)C@p+hv`mo+U)yI#l4QYTr zQtt(8M`&}7;C=*mX&+f59_4nFap_D-L&6wwa()eZ{ac(KPL-AurW@nl#1}p*r!O3hsry`0N63|Vby4_d--{EdK-*o{ILSvM7q-v}6u z{TLXFTR1a;<8U9(wUjH_-#r00ImdY-<|ORnSx%$>S>_CE%4FA5bqY)+|ED2qI?RBX z_>=X#vye5La6MoS%;kO_%!dVf9Q#cRUGdaKu5+fvuJfiPt_!B6u8ZW2jHMGV_16mW zLG}-h)AQrCk|e6#m2Z5bK3j(D<*>rVS!XaCeOGb68rBfkS{Q;}e@!oKl}pZj<6IS} zNnO1jo!U_9HsD{r0XGt66W5zzj_IOlr1>mqzr;A>C7#D6o`=z&lkdrYp8x%u$%CKk z{9eF)z6G`*dn-gD>oMb-Qs(6>*=^{!9d^J@*o7bYzLVcr+l}AXtb^L)y3Bj?cUgWp za@M){mHvjje^>a1{kz}4#=94}ZDF?_S2bmy>#9$_=xM|&{T&%gv(QJCaUEkkR&=}e zFY^7m&`u-s0LYmxB0rqpsM+JXPM!1LI?1`5-^07`Tz&d^_stxoL{=m-vlw@~yfXeE`autV{V7IsWs{<(vCBd3wTS z%zd52?G$mG#ykUOUAL$Se$>q$=U?+$&H&%-+HE@Lx=mm9$2{=onYg0^T!4#k34Vji z=qK&Alm%msk$wsGSK*rL4*hFs>+hPb*e};Ui;JYV;Fh<_k88r|4d{))bICu+KsX$I?&ege%zw0=Lh4QK-x#n$6c)6 z|Ce&%k5AqYW9-9t7mPJgg=nj$+a55+{9|7J^WBoQIC5U2)Lq}ph>@SWT@U}I41d?% zcsKp;puY@1LXyO3tb58!IlRVqjsMK@NY`V=aR088KP|>PC4G$Fc}6mqBJb8cuJ6MG z*AwPzB<%M*{d;{Ob%DH-^6ez`hCJs`eNV2uCsmY(uBX0t<>&RyBjV}?kKqYCMW)mn za$bOH-g{TlABIa;c&pbhhMf5LHR6%Jg$nwkh!h0@$<-K4$)8{`i{*#c>q>zMgNx3)9hyHu`ufF^+!b^V0dn0qM!MZNr zeEIQrd7_tJ2StlcKQ@`<2P79$cPp%>aI2JNla^c2w3O}uEw0`-iKeA;N7GWfT}m3t zOj<|>=^+%m43N>SXqhlGLl(#i+1$~!?2rR;a-YjxSk3J=Yk4SNzrZnm;XE(#g&{kY z{tFq=_@xZa5^&p;{Mc1dWQ~16r2u{lx&yUB?nP>0_gu9I`pW*DqQqYej5%TUJK=99 zeVmWH`z5e138k==0A`TWYB!=~uEoU}G0Y;&$#_++(oyR=r&8r|Bs-NUsb`nth*n#Nf#{gH2!{rGy^GL|FXjY*Jmitrl= zF~FTbk9(kQ=kHrdxP;`ftcj7|-DRIHaSY}e73YKQ7-8kz9O6!dpG4$SBKRICdk*_mS=-+9=}ch%PDUs~YJ~ioSf~MCt3*Vvz5QZX;LLY$nz^ zA)`-#{FZG}Edqb?dl{p3IY#*#&XXQP9MX>+i?)Md>k-sPzoak)&ol*LQV_;3PuAgNWA4j1e|tXZUf@oqEhJwSalIIpxV_p^ zUs~k1+m<1BIr*`|osyCw4%-yfT-+FgCJ)V`=Zvgqts2s!^L2F>hGWum3 z-5Yu0j9cPo8{dSR(Rr#G%KICN?@&F@wve{15J`SL;~TUB`pNUyMwsnUIvRTya%nqE zvMy9~*n#^_khzjwn6jrq;@J)I9xY-VN9G*&aK9J!!G1UZ2jLJLh9htkj-kV^?zxNz z&EeeT4BBvK2JJZI<%By@ISF?epFHJGr<{f}a2C$NdAI-<;S&4?m*EOrg=^&bb*e`> z>-h%p+=N?j8}7he(jwnpzjJ*LWUNunKEKcP1Kb|MBX|r?;3@Whz)JGrPt0f7J%<-u zzr=h6ui*_yUro+Ud`rH|_pF?wEOTG)aC?vc5Ac!ePne(K3w(udz#)8!3MSAXAc%P| z*h$|o9^=B%xi*6Z0&%y34ea0mC-$x&)&m70ihB>H7c&OL#4Q$PY={GKxsM0&Apv0$ z;#baQOT>L*+>=032!>=30?Bbp0V%mo1*stoq{S{Bq(??5WB?hT%!pkk+%sclA&#ur zXX83M4X6pVpf=Qjx=;`5Lj!0?*d)}|jW8Q? z-vpWxXEV%v*0oCWAeYjD`dX81* z(_8V!{XNcZ$dPY4nXi$uD!`#WLFpBt$--nicrdhRn?5OA(kWC8@vMCY7HJY?ZohExgW#7)2AlW;b zMJvx4OLFe;eCD*r;%A)XB}@p)u1yTOp-zIy$ex03Q(+oz(}Qwo?ECS+4QpU6 ztV1X1BdzCp18js%=yQVjL#X}Z=`BDGy-kz$dNb}@qWsC&Bj;@6{~Et$7K!~fn8m&1 z%XZ8i++So4ZYO%m+2Fe{cVoW?`@KQNT3Xr9wJ#_)X{Ij6&4@b>ZLs_rS{`5AIkW?~ z9VD%sfl6FPydl1I7KgY$9Q2D8lYBoy97mCV4D(kw4kzFwoPyK1ouG9+!*vcy##zFi zgY$3!x7lida*^vxT>l1_gYs%_JwF1JE7)I!Yj7R68$7q0T;JmQHrxSO+jtlAcesb! zVfN_EcZ5+kC0~sExsUw=p7X;Xb|UDbL-~B^H2kcjzx0TA{Bcm2_5{C%j`?*zPlF23 zpD94z6yRRUjpT{+PZ*QMuZ&myiTMnk!;7GTJmZ4+FNlBknPF$_Gm~)gt8k(p;|k56JuopMvshpMwf%UxEs2 z85qIh#2w<4-)Aa9jz=nAgQU&$&yjI9IB`fH{~L3_Qm^o1Hi`-+&^$)n(Tn;efa_@B z-yavp0lhi zKBFY?u!k9462VyV7$@3@b9@tso7Ay}j){@;<8LfWdz=J2X+M)<279U~$shzd$)P0q zodRLkD~f>3&lQ||MJa{0eKmbkqI(; zis|oD7Ou1D;}FFue=@HmVL87W_iUb`S{r8xjWg$XP9=CwM!lLHIXRG<(^FhKXA?ig zwOk(gCBTySD~Uh)56H-kA2~B#^f|__1Ui9LW4OyRWuBG1`^8g2%Zr>a^pJH>a*o)0 zJmkXXG43Vol7Q0a>Ms*~uY2OwuJ4-KFpG=j#^1e!uK zXbvr)CA5Op&<5IiY)U&%S@OCpIat=0*G3s^kB%MCN#>P0k{_L*Gjzf3r9LNGPV4F^ zPdO-0*z$yxZ&%Kx!#!AYvChq;=7fmVG=GC<7G;TOlf5**7KM zl+wn}v{d9Bub^FLXGdR8CEg6VmNj7FF3+zr_0W%YwD-vFPyC#v>hmvQY5!rMr|Lia z8}{PA8s9U2m1Vg7D6=|g6+bd|`J-IrP(+3C*S5g zo7biWf63or#Bt5l@E>vvdx@jbzv^hX`*m#m!}D(PFVDN_Kja%}6Zy@4(8thmxJQ1S z^T%h(@0)m9{6mIOX2h)}^@jLo?p7~Dt)lK{>1|i*sJs|SdSyH`3E!h0e(lpJ7lxgD zbB)r=ds|<*U|huKU&cYjP4YclZTCOi+egJ8q3hEj>VC9--!bam(63X}{VDzZ=y(P@Q@^2%CQ?)_)0$X=8Q$e0L|^!U3)#m5Et&^=0? z@mwe~dj6Et(nqyH|7_P}UUV`tr=XM6uTwFnf#^FO{AFYY*E6x7MZGi|=D=K-2lHV8 zZVO=%{uXmD>%aWJ^&@8qEWvImEQ95+0#@RGl}FYW$yu!~Wi|EE8dwYKJUvKO4^q}c zubTQ{Eg%jk6fWjQ#PTO^yOaDPK?pZ zlhHoPcg$w|$^M!x=(80fxi3JNZJ66Vy|hVuZtU>%)^>XGpk*FfygZDF(*Gq5GM2d; za}Vsre;s~nM8@vrZ2o=NHDJuSKtLXKKXv_8TOZQUhnV`1hQ8VX>~irfaM06_eq%rE z`(ZEVHRM+h`D8C`6h}F8ZYt;6l;YQOb1Q>+q=QM@VA3Yz z{n9@fLVD%bbcguTJCr`PlnKsHLYK>M1+JpM^p~!YHmOIibAQ7lXIKxTUK&RDVT8A_ zp2Ws}IOdmezvYo%+a9Xj_6*kUc!p|sF@N_A_sxCCc%G4t5X^h{zfU=P01rWa2YNeY zZU;Q#{xLj(mh{J;qQf8XCt<=VGtWG-#ynDaj{6IEiTx|j2qaKuxfi)_;2vDynY_h( z=NZX2w|rC5XGWIHv3|h*BYc9-@CClYH;}XK6)$5(U;@oMigc&rx8Rs7BtHVYj9t*D zi-wt1$w|M>C{NM7#yF)J(*l8D1sneC$Z&uYT;36y+dEPV@`h7~`PW<-@0sk*jZ2;F zAzm-xIFDP2;cdw(Ud~kTa%L6v&^Sl97HJOGA~5BDNHd`N&@LP!Kl7?((lT@rK@8U6WY8(@y0jL5GbN9biFsdqH*+-UAc`^pT@ z(aXFS;X=?SIdY^wpMv|8-Z6w7gWoZ_-&EeQjIYa%=ds_z^8DqD^VEb(<4vTb^)6A< zAtybALI%i)TPEaXhAfa3yKLB9;J2T$d&luCwXH*2QT22wTcse7_Tw%NzUOd zsK+7eff$Rk^ipQf=a>tRdFTByn(#Z5F-()tcd}N9I9^jv6h_Y?P!x)Jr_kS!@hJ9@ z;a&ntLKVI#tMUz17L&a)yjP4RLQ+b(%%3z4nx@5$(qHOuIUmQU$4ens`od;pmPXbX zWXQ8El#6>&xN4iC%|O4t)BS=hvyDMah>oM`TD@oPqre@_q(+Z_Ds{2s QZ*y;vvV{wB^N)Z34{wLQ+W-In literal 0 HcmV?d00001 diff --git a/tutorials/files/blender_procedural_datasets/woodland.blend b/tutorials/files/blender_procedural_datasets/woodland.blend new file mode 100644 index 0000000000000000000000000000000000000000..7e2ba8f689fc82f5f93e3d52c4bc6dec985b451d GIT binary patch literal 336259 zcmV*1KzP3>wJ-f(^p7?C0BTUBK~`YeiSnOOby5%;2#d@;JctHteJ~bJ*bSz@`!G2Y zF!Xm6%G!0jj9!-q`_nkm2ob74KAI+pQpc8cP!wM$?l$^PCF_w?9fF`N%WBl9(RH2l2$D)lN=iyfN=iyh)1;!U zB@c!@48!w0Pfku+T3R@clO(Au%hOuxWx4|Dw}AShRe_r7uxL@8%${^u+|)&@x>ZG= z?VcEi>0d{1}mj%>kW^dBrf0>Ts=;Gq?^78VQmKGHim9FbZk~}S{iZs8jOBBWL z`$&?^vP=}kDd$WwGD0#kGD0#kk|7xx$Fb5{cbGoA)2^Z_+MJ`=msfRSwWC=R3oYv9 zRqticqQ2ef8WNISrH{LsSbcd_pQa!Po{Fw5r9c{zNR#;lWi}a-Q<3JQIbwTEG-(QHOW$Xz|t5)NNgI)|s9beNObpILoq zRqtr_kxQaR5P1VJp37-LEDZmo?XiQ~ADEUPGcmN>U0 zlarH^bDVdQB(a1sju9h9j2JO4L&o%xk&%0E7>1wEhl=*Ibl#Fqj$s-}lFzgaOXF`u zUZdGWkYug(JTDBxoU_*2TB~W>tExK3aXII0+c3s^Z>@FC`MNHxHO0TI>Dg5!n%{Y( zwl0kmf1andu)Dapu&}VCq@+A1Cgvq2B?m$9olYm`97RzSU6Q0}k|gO61X-44Sr*4} zd+%B+$8lMfS!;h?*S2jK<67%=T~QQW*QK?-_hwnfaonq_zU#Vg+xETpHBGZD>-#?1IL?~nEd;`qoAPt^ZDeQAqbMDDT*TLwo31i^&b;|qO4z8_<`p+9M0$S z`Nh^@;{h@yCp$8!#c^Kl%1p6554%`{CTBO?$5 zQ50oa*0t6cBG5Iyycb z9UT*3K@=iLFzM)6f&esPJTy9T2$5rln2wH)EdbCV0WU}=TQERJM~6v=#RGF$*aI+( zr^Dh=IRoAGKKzAxEb~4+`4h+TmEIm`nVkHIIUK8v9g?Qsdoh3k3@CvKOLz@KB;X-r zJqQLJWX1YNH$5bz4svY{1B))Qp-UU}7_8=3rmwW>FLLG{S@RD|^GuYvcHyt6n0y8W zLpJF! zG;|nx^O35#7;^tW37Gg5S6p$5qOR+@_tsDL(u+khhosdwn{62s&FXTU9?i>nHrp&x zv$48Ny40mxeX`W)tv==Imfp8Gf711ntt$1&R;RZ*$J41%qs9$4+(0SC7~6~Dc+)gZ z)4Z-LilQsixN2W@V-!X0)gpO$OrAl}B26k=7I}gql{N0bnr&8j-pZ~=)6!@(k|d#^ zppYbaa&oe5TUAw26m2$}sAe-hFiPnR zGt3}K6216tU1eRbn1<=ack8akVK&n?P;_0_X0wT+h{_s!peE0HW!GYv#qyi;p|bUg zX%>0vv81$q4#{t`gT3%n)?L@7q@u^M z(P~@Yp1GGsj4nf%1+k4X4+}i&*7NE@z?`TajvS0 zgoI=q$C#KHQ4~QCj35Y_YNhtR+E-bY9*^hbH%$|UVbNBI;2T<(z4huQYy&a9Nh)I8M`jrMyQ`gtK*y<0_TS^86^4Q3z?ITb30Q z6JtaUF~`v|P4t>ZzT-TO>uy!#aWqB{MT+6YFpQ$8vUUbViu3Qrebv757gpN37RhH& z#NB7JZK~?6(Yzi_N?Wh?wM)(~k^COZXJ_ZTJWs2938D@`P)kb-4H`6#00bc5C@3hB zBvtg{eRi%#^H--EBJwe0~(D8fbH zf)hLjP1N8u;6V;fL=s1Qq}-1@+cTkl#K~NIsNpTh!3@f>#DN0`$8nub$283-iYS%! zMd?jxE1GJiRolc5c<>k~+heG~P33)t)SoftL!Rv<=XDKfJtc>Y$1DJc51|M|IM1_I z8-`&NMff(;D4eT(RV>>&dNH;4a^F;Op0+BzwT)g}u`m2)18qTzEt~@>VB(sX@RW1? zW32vR+S9Fih>5PEz6QkKTsW@*#0?j5teoT_<~^VR4X%Y2TIhS53rUh5kEg<%mz}6s zqlvjMha+j3oNnuI2kOzRtgYE_!37r&!VrXTlOS$vI{G3k*F!$~A?N)E1|6iE4pP>G zc+<5pd-u{g3{3jQV#3&{cb|1kL+3&`0uky%^L}U5wbo@>Qmn13#7a`I56W$}RoDYN z860s3=JR%+#k9QHAVGo+JfwsF@lAi>P5n~IPGBy7xLjBBlz(pF{d$=ZtZWbbtGRMkpvit`t~@P#XZf)IR$i63H; z?*Y=k2K~tbkxhE_xgLW{c9E6qASQW+iRHmbp8-+_S=smKq<@grMN;;khyn_V zqN>I3bUZjyI8#|u7gKvLruJ&Ou*DWf0Ss1fkdk~6&OJrq!w@Tvkvd67e`H68u}K$k z@nodzgP`bph}1<~utOf}85Qg^xauPweUQ^01f;(L3oJ~S9*!;S7=~q8W;L#6TBcEJ zJ&>yxR#{g@FaAW_ffjjIOe;AQ&d;EDJZ>N;3s+e28UR5DUn$~-$6)5NdJLw0jE{QA z%D%@*J}s?-jMYCtDq=I=aP=>==rC~6VTkoG#(EeX^#kP0Uv$zxM(QM^y%eH=!UrFG zxS3+(nKMOEv@GiwhD}!1_I95p&n%Ml!t`ifozE}l;SL0IIA$-rtrw=*Krsas&I!WC zWys*2MCJMfT8Cj;?Xv&KpnGW0Uu4ifLi!LhWN$#MO$?(ww(h;o_ZM6A7+LfgA9WA2 zek!jc0SG~`)}9>CbIv(Sl7wY&>^{rn)GISPCZ}H6-MS2l+w^SC2Y;AJiZo5N)-Jl} z;x`C_4^9ITL0sgM4?@<9aPUP+^rx=+2hMze^dEb37@BlVc@HC#4#G)?IO#I+7&yrY;^Wvtu`|vi9Y?432s%zc4#l z$)Fz1yLDFMu1<*_O^H%XaN-HyVTd0NvZ05RO&X1cgoGrM$v_Z9LPAnim9@6kN>S7_P50h=DN1WCNfM=W zv)NEealiqG@4Yd`nM|hZx>{|p!G@NWmJ_nO5ncd-FTjTc+yh7W@Ff&b!w4gcc#Rr0 zmRMqmH-G^Q_zOCK#38_g3bqlSm>7O>1dsSy@?GSy|z5I4CG6B_$;omg%5_ z4&Qs%P(uyZH0{QX8#HLp$T^>!oP0hX&+}MVSU#T*hG85I2V;DmXO?9cV;VGQ)LO4i z`nFN$EPP67XI^(4t#w76rR3gm+fR_Y>0ur)ySMKtrL|UyqO7$ThF#Z{bEfpWwb^sd zrfJ5+#K6G7z`($~yu4)Hc9fJ96ciK|7M7QmmFG}{e$PEiEk=W9y=RZT+^l zZOeK;U!1k})_O6%#dX(c@-rFgGiJ=#d#k9Z^w2{OLI@$mg9svsV_?@q4?P?RAb=>M zh$2435JP+f9mv3Oa0JYK5Q2z1Ac+e6haY~hVZ+8(R#w6=te@xoJWmdX({an`zosRrm|5y;!RkRyQ_L)n*fc2t>dJJ80sy)BOofK;ctNF@+RT zNI?Y^RQ!o2p2#7G9PZ-cVqwy^FuF>}aa=Z@{2E!TwN~ROYhRp_Pm3j%ZL@Q?j$RCk zSH~oWAE-%FK?^Ocu)+$D$Ae+m_kEt{y}Z0w zZNoBLX=`Kqsuxx_R#`U7vaDVimGx%h1Sg^kYW^lAz z_Y8`dNs1Q9FT`F*o;JfCcz&R1ia`@L_!1^y;x~H0;W9#el^txngG0=nh{6-!_obwy zWF7r>;fop8jkh)uV;qi`>#jvIXR>11SaP<`X4|GoGl!%_p4rJtM5)(WuTVu5_f|UJ zlyHZ}{S0Xx1_&GO;sXsQ!3$JSqecx$k}{Cw9abH~`;_6-)s)^-we;d@scL7DtQU4Q zPTRn-UV1F+5CVpCsMF<`bj27>WG)byupmh~V-Y~1P%sb$2`Cg=s}B=EfmsESnh4<_ zLKGo{7(xsY5JHH62njJ{W@K*K0r{Z-oO~g+QJ2qDZVjW+0TkjOqxskmfzG=<;nt0R zncHs@N1@{B))Z!mJ%hJ4P%nOqn8Tb&QJyN4KmgGzOZhSBBtG=}G@PJXhjrZ!C|C z2IcqqAxjT(zgxZqI(G5Iot{{N>$lwUvD`x!jVpU^*m%Y38?iAizKtSW*aTC2`KqUN zfP0CJ_i|kR9>2)iRb-Iao4&owiC_rt8fJ@1FB#N{ClPae-C>A87F6>+xn{FBv-ZP% z-gN^e`n@EMqc`Q-Ta@|Wm&Cbvdt9mfOiF;@O_fF}(6 z-zw&#jOGW(g|3o4D7%f)Ha&~zbJ)|X+>3?!MF0DmA4u^*Yu6KU!6;$z<_vZlvE$F0X*f}>l`}x1C{cdhJ{K=rQ-u)W@cJDh} zez55?>o;YJcz#f7wf#8y(5CzHZ$_C0?EM_PTAtsHKf{?&?0LfsMD!AyPW=9f{|Cu? z|LwgwKo}pg(T81@tv+@842%X5PPaW44S?r>KA|vBMT9Eo==iBtWI$Ko11#4A{zK1w z-tQR)#GNd1Jq-cV5AkcD{tmczgQVvZ*1vG@1c%r6?SFim2G6UD^^*G+_&r>$zG=2j z?t1kGNM7DltIPSmVg&Td)@IZq8@8Q4H1|XvYuyu@roS@*1IZhx~ z53y8lUrvYO^8DXzcA0;6OaAr-tGV8WBdFZBd7cd~d_S4D$NhZ0tR}?HT5$Ip!2KVE zZ-O}e_jv=(H})^a2jT#Q$pc1wAoHaZX4w<F4SE6i=%Ul^=NFd-Advb8)r}Nq9B&T# z2X4(lRxbe0h`wLbSJa;r2h)+yyP(~s;esi2eGQp!!QvX1H9c8t0C-?q=(98v9T27S z!F1)o-0i<97rNOEx332H;EwZuaR>bYXSVd`Ab8H(M;x&YQU91k9n5K}b#|695N+6C>jJlb0edp{sbU+y^( zH!S3TfVr1H^gdt2e<2)m$o>xp1~{w;_XO#=oHDI{#{-slaUU>ra>wl#$nLD{wcx$Ny-7wFC!<^?w0B?$$Xj~ag-(26S}_#jo<6Pw9R0w zTA_;7IgXdr{LyiV`_%dMs%hc-e?Y30CnWP-!Yr%D_!Uulivp&_-oN~fQ;1z zXvs}x1nLO=BOX&i%J&oNd-kH`DbpL2vx(kDUlG>+Zcm?0PN?1R>W^_Z3p?PYZN!Mr ze_+7UfCC*44~X2}R$UO`&6e@O%JP3pV1aDFqt%ViHWB=R$@eCMveG%L; zW)F0e1abxsr>OG7ot6NQYkz-xp0oHM|HNKy&R3-S9^QP~4Kv2ec|GQz-T(9+ulWOz z2j~uwW}11T3nI_{&!_W&4~RZ*^HTZZJpeYfJ>fszKsKmp=yuXtwqNgZ^;% zJ+Avnc!G4%_$N4Jd=SNZ^#gbwpjD!vu&Ga%H}X6;FaYKSh{@gmXBf#b1MvLK9ti)Q zcf;)6>)|E4uj$W&v5f0H*V*qv4KT373v{o=A9VDcFDz5NQF=Wt&xrwT$($(Pen&8T zF**R7Gs2gCh9%AJi}C>T-#NWM;BPx49%o2iU;vyAyA+1^es$l2bAEudi5vZ+e>Whb zf4}Sl;^qk>#XOkL7Z1oh;NR{y2D#)uZh+g8*>?@H%|nwD!tVt9;;=uM{rbuG=3zJB z)d}DJM)PAbxIE;a&By?8JOCVf0lH`h=kK9;G`RH)!hpE7)BAe;LU$qbF2FhM47pM~ zpYMRoeB5`WeZ=b9(u|0#C0G_9TCagixnRGLo`JJi-vvA`x|q?Euy<>^;Xpkd(BoXo ziE7w}yyMvq7<*29oYejd#C`+#I#KQjBCeAoF#CTm;I~VEtLYlpt!_v9zq=30h`-y& z`aHwL(a(Schb>@4R||O60gZwWtNmf;f#cI%12znhIsW0s9cMft+=wBT8&q72HQx#T z!i%2gWpmrM0=Z$w#}95gmHs~Ns~yLs-P82|ySHy!eYKkHOd{Oz0I1)z`+tGc%AI07 zuhN|UFS>OKk6-@~9P?!uqKp8+BmD0%O8~4l_u03@^!FTqG(ck=5W)l82@85yU1YTZ z$%s4OLWoa1rx84WHL#J~uf;v|JmKMfa=*R=vpK1AVn@^RQ0`M0)(8J*7pLK^SiT3( zd!WOzz;s|d9S5+`EsCnWynjP_idr2Gxd@A}WpQNi5G{kHCIIuZ(PtUZK47|yan?-k zk8%zPpMz%%5AFy*0zfw;7L1rN|K|;%8^XI|zC)T(?E>s30^&Yw1ULZyT;zbpKRHks z^ur;aHK`BtwlMCX`NJd+&_BKHB|op9{8k-sgb!Fe1jiCTKe&A3bEe*Bk3eu{ey+^) zpK5!fK=|QmeR`{Z;`|TC zvSQPZVEF67QUAHluIO6b+24H^tj7&{+Ff4J07orrc0MEy2KK=4M=6&KcmDHvc|tuW z+a24_$-eX+-p!j&MCScHAR|2k{)^W+4ODdN`}e@#m)BV_?bEc0BjhUnxV$NSPfKKbz6xzfjR zc->(D6w3pe*tUG?jqAyfusr7hh<9&Gg!d{(hbXou@eIh(UpQGg zpd<%SFH4L*HxTyv1A8)u<>I0hKz)OL8!7Hj7?9p}2EeuI%k+&IA9xz+96KOq{zP6k z3=t(z@fY~dS$h6;fVgD_z-#3(hTHyT*vPx?`Tbu&j0`s`%j$+-1IEaW0sXuuz7sLK+~bUTVh8r{zsG>fc?P)XIqHe9K-;{}-@rN` z+v*?fbBK2e$eA4iBlV|nPJ7=7we%({Qo7aN(Lo=}dusf=kW*)VEZUv{ffv(qlg8oocD{@9F-p-(o-LtQqQ+rWPPPR2dS4>*waAB_hIpSKqS3=P1p zZ4AIT2YBUw9nbmx{dfH!GXT}40sr#kkn@$(`^xsSw4D#w9(b}3s{Zl+Ztpi%X8@NA z10}DkGXE>7uz^|3_#_GQ; z$lu{si{OMe-WmU^95nv=h5Tppo+4eA<}W9L1|%agz~=4!fIL>xe$;ON0M~Z_q?$G# zn|~tjQQj+a^2y`CN9F$U>+>wDXUKygHGo_^Sb2R9eSUmEq|SkgZYAgo_+HqxoWdCocqF=L6q2IlxN!OK=W!!SE;_Z#>|U0f5jM zfTP^BPuRroJHg-q=Vj1#_gCdi&yxn&KA@x*mJ=!jZ&Ur=M#3j7Tu|OCsR8jcCv33; zRRbs~Y!2x7QmhE6-pOqt>J0UeoE!NCIQjV()=vkFcKa{L|6uU`KTUA&qXY2W+&6ph z$Vp@IZ#`Fa45)nT@~7)uFNfpl^*wR7E2urUZ&*kv;~h9) zJO9zEPp$umDTlAw4gA9S|8hXEBG)+LtrxKK?&g7MfX||@cEJZtk3(m_#p*-6A&2N8 zC2QgE)&k(SFz0|}#~~Ns1vcO2wQl|G4ESLe=yUuOxMtSnTA#oG^#|Jl_!q=70^^1I672{8V^vHg%a(IEz?`O-M#?SO^>IXT5- zrkn#nZdm^uiSg}t#Bo&4w^O1EC9rm0NB@uzzPC1=>Tm#I-sm|+yX(h42Tbd>bazZ= zz5wD_u-^OMvBR8UAao`cd)WpwgtP&w?@cj$6wOUG0HNst&S-Ur-}o+|zwx!PU7ijEW|T|*>o?9Tepl>ABxYkc9I*?y zmD7@3r*6luqw zwjQrmMVg4*G6h)xSO8c6D=054Eh_fICqn2KF|3;6P4K=C!w=yA4bcCR5)p+GQF3IU zYJ&j3wWo!SN0m)%96+HD?vYXW>}UTCSe|o4Kf_&CR4y$m)#~-nUj9~zSPB;YHS$-j z0%I7SxYL4nTgx=bi+<9?O7qq#O{Me_NXvW6szAR5*3oH)AKGR*SjUWryrnqvoE2cN zj1HKwLIqi?eRf;xEwG8#bx9s*S3YBGbO^{{lc~`hCGY|ZOsN=R>PD;qLqH0W*sU}K z)1f6Cj01C8&q4RU);{z0f0E)dX*@m_6uehz=L2?7Np1uHh#kZ6khM(LX(BuLkHyYy z;y)T)jpU_ik}z$ZD5f%dShtB$G}CsDAyWY zW*aObk^YBRqq?CId}J-#P~-;wz1b$7sQj3GKPLCYAAQY~a>9(l;lk`EFA`(ZEW|#w1$A>%1 zML_4hqux=py4>WODE^qR{xnwr#rq)6R*%MN+!=JYc?ACsbxcBK zX-YVLai-8K6J@GlmbRY?8hiXVCsdtkfNP6`k+D0EPYCSPC4~NG&uLkhlVr`1=q@L#&!wCIK+s?ph<|)3`KbphyvQLYwx5@n*fZ`efH;jILR zGTu^KLt~@99pV8X-aE2EF^|H0Q7T@b6gakouw=^V7YEqWRSZOgOj!^rTxGYlC$ z6*UCTLDm?M7_{7B=v%zSr-xgw*Gb|u_$He67+YwKq<&WR|6cmmoZV&(caNJTXV?x* zXPS>S*B@t*xwRcYj#amWxz-@JcfAKp|31()z4pQ+q)kN!RVcMD{a~;PtquS}4mLJm zZPEc(6Nn@9eE|ay;0#a*qHx$x#i8!K9rqIIi?#_laxUY2V+x63Z0e5il^yW%!pO(5 zQ&p=|iN{1Gei`g_9oB$yuSEjFL)oM8$xlUMe+;$JOwzP4XTy|&g>itm_r?lkh_8vv z^|)o7S@Y~iWk)C@gIcnv=^RZALdp-;e}UghOF+_y+W&#Op8|TAej4j}kUfgM>M_wM z9d`@GY6PgM(!vCA^3H{Gp|)+?NEjSb2uQ&d`LOmCpM611Wh7~fU^i6O-5>D(VxyEX zlKEZbudIBiL8_c3r3Ix7bKn9YnXx(&fKez$NGOgm0;2?k2#rBRKo}7aCJ-5#KuQ)H zam_bh(%m#jm3n26xpFHPNl)(Sa>aNsL4yU_p1osbt9mGOp(&G8nBlq09SXgBpgPDk ze^ZrL?mS};5+Q}VJSz!~o>Zx?ESeKrIgT>+H$w!a8JB{SK{7eZyJ{%;lD@O)Wm!h{ zW3>E(4GU&ryXDFeyzKe8l#JOrw_(^em5x?C1Y4x4;D>?VMgHyfVfb4>o8XdjFC}A ztyWt5b`eH&T|*7TSfqQ_Ws@VFXk{YIOFOx8(bdvvClDGlnSQ$9W~|Wvx=FT!u`)K!F#ruA zdrqrD1(EV!A7dZJq!VVsTXc3Cor81xud7PXYDBaR0}OF9{MS3Un#`mN8(%FLc0yhF z7&GIj$)V%a+`03Cx0tWf3EaWQ*vGGgnXeUmjD5)2aUKAKwTJ#o{g=-3yg_jXyfTiV zF5H!b8ed_Rk2q~t%Y}p@_etSNYk~|%=OQ55TARPKHh}Ln#wh$g^{(}gRG^uS13C8BO(1O22%g8j;G#r z7Oh-iRSzSr@1!LF)zThLIH{F9#!I(oF>Wz4@=7a1!c-o3Ybs7i`APrn`)x zPcCDQNGQ-A+9PE5b&REU$K+P>>Zo+aN!+hve8fE_w~|gFnS~aLn}Koi$o1xSbLVd2 zzb5V)fS>LbGx-H0VOtpN5sfcsvg>u~cp8(>FJyDoPV}0))f1Xz0!cEtoLrUxwb<(a zAio-Ao@XTgH4$dQ#;04fa;JPu1&Q-k|G|G1ze+aG^PM2n3x+adV_X{t-Eq&TlQu1! ze$_Izj9T_3DwzkBXoW##aW*Je0@$E6TEZSI;Row5r->H*U(kOP^E`u)+WBz4M_gu{ zguYwJu9xW+tz6>Nj^fpnRn?VMlX_qgC~VRI8R_hGaC8=1<|x=QNAaQD|A8gC`V)mk z{r|CK{u61-GzYp}U9(OzC<4ud;Mhvp<*n***V5{JQzqLJ{=SrPAGd!_smJ-kUu3_9nme#*j$4 zt%r<~*y*;Vwl?bJg>2p0UYm3&$<2+YBzbxEvlQNULd?&?0`j}@I(JqGI%5y(~?Lb-AY(LSOx3{; zQtBgBqMg`jnXC~E7#rvW)WPcGCjgcNs{7@NKdnyAkic||Y%r^wD zfZcF~!-*42vsJ6-C2`5wX@HxNE^>2%fQ{!5TLSdjQ`g?wz>w8HG-K@@#oAk+I{bNB zR9WDSYIiB({a_u;U35B$0^O#ECe-0NG@%Y(lrw68%knMSqgHzKB3)?SrlJDlBBX=> zyJ2$D>9!%KwkQ!;)GH_Sd$mMhEr|q@+{92@y?SPs(F^q4 zR7l;xWHdFw*kUH3&7{*v#IdK-ExKu%mZrgeFHINewwB$b>1E1Rqwq8z5mG7^><;#$ zcpXZPF|;f+Sr-NQL@v^84x%)ltm&&(DqymkXee8X7TXg%(N6XXR;aJ?Q~|JIz#>qH z)N_%5MWFCXhlr!2XAwZNg47mR1Pa+c>QXgRm#W!^az?)p6jk|~{puJrHasnaJ$S*- z<-sUnD`W+3I8n`hmSy{_B#w>*7JswE16Q&(0*6xx@St!Dm{m91G`MppLUN^t3e zKe+T1`+!yYuVuofuq8Q{m2*wxvYMhw$hlftTEF|` z$Wi+r6_w}zMg4|y)PBn6p-Qe-3l{!YS2YIG&$7M}Sh7G3<*2PlBvc^*{v1qoimK>8 zcXjm*<*2D{LQ%jXP^g{_TMedeC2UOFJW{?eYD!e~tcM#bXCX%9d|%KsZ=lgr6y+t# zpedk0L(?j8T$tt|0mtvjS466PoZ!+6U(hxeGspvOM$<97S+jcwNj-VtXH5fZ6^t;Y zh?x~>@R@OufX~be5k59@n0^|hI6C`5W_I?Ytc0^3FckQCcq1mN2M^~N z2v<-=|qvHb9|C?=4 zr|V~7kIqK={KU99!2+8Bum}{&(IT*Vu1u)8=d_d>J+psfp5wSEw6}jvl|RU(gRloJ2zw!gYmbl}qJ8KL zVPK_&r>6$ENI9Z+Xa@ER845~cP=S6Mb@;RFPr74R>N{0lEQXq@D}LRs_;rUs-nO3U zzeeJWg(Tl)5NJhg;HpZ92K&Qdap{b;p3K(?b<4C{tHN_tGj^dy*nuOlA1(UR|9_21 zWs~dZ`q8VB5(=x5QVBk8YkM{eZBI#wj|^w4kVm;!6(D$WN|QQ|3QsDLpdKv%7j%2% z-5^jEG!O{c3eYLYHt@6_bkQm%_G1k0w-eCrHhn_{64%<<)CdSm%0@^6- z&DQ1+6Wa)o*CiB;FtKQZv+2lt&c>k7tR#?6n6x!baxXb$mtm5oVL1 zRrnA5_^+>yOxXEFUkE>wF%v$z9_%vvKiq;yWiI+mOQr?DRj0U~OPm@8hXl5sE41I>t1^7?g!OLV3X@tT~=+lLlNvPN6u#bjuORjeC@^w}>t7sf=1UFPJ))^{fY}0`8pf@kJ85;ujAK1_tLM2t%RoGKMz4oW?h+3KePp^^_6T z(t`DFqtz2mP=`eAkVeze67*jSht6!BoRe2GH;nnOt)9=f>8|?#9fwVXeZ$FrJ>0=x zuW|@*C}e6!5Oxo$p{2(T%7mBj*2{dCt}|A~#N+a1uMUxPZ)M;ZB@&#XWWGU z+G+{C5kdw;Y2am`!Kh$X(Qsq9HfYe$ zf}f7CQO1!b8}RXHv@xT}=v1Rd@7Q#lF#~>SG#zO&zQ?B3gAmKI`njtr3)~GV(wj5w zgG7gKub{-iqHKeJjA05W5Ie0BN6<763BBKw&&V(AKQLsN0AmwU0F_;q+O{aRi%bIp z9}9fMc;Gx!Zat}qO-QkB395+V25rm&Iiug6VbKt*PPyDFLmDCk9W~@c$^WRcBmC?b_RG&o`Pl~itPKB&tc-MU>lhv_ z4j@aA7{C}6&7xsvH0;cxVdod+RI@8_IsiC>mz_{rg9^bET+9$EiTYoGRu5xHMp5pw zOOlf`8w*14i30QYaNM{Wn`IJhml699lwC#7?99$L!Op_9G;Ev@ERFCf%?;gU>;nz8 zcdx~ff&%@|GYbPd|2o~D%gOlH8Bv+V3I$Z`mO^we8oG*KRk5~5U*%v62RfY&DX*>7 zs8Iu%Wyg*kEH*YaEmFdSL7M8)($cPz>T=}Bp<7#9+rj|{NFA9Xovx@zCnZ;;dn?lE z0u||Wee&cf(#>PMY-pdzrqeCcv;}%os4!`A79l{Op`ppL?8S>03y@RT*x1a>%*c=- zQ$~i=h9pJz95rgxfKsEWsR>Gx9XocO*kNO1)3L3st?6VmG&D0aGcshzgbDK`Oi@uT zF7E9uh8O|`>eFXL9yoB|q@|@zr_(J`X$U$mT(pP`PK8Pq6|7US(#R-SQLJ=tOA~LG zgcL2mHwbE< zrKg9i!-i=4Bg*GZ79oq!T+pCl`qwQq>hNfwn5{%JrGL#aOvxX7@fkH*xbbic(Sq0m z*sO|25H>-W2hu3-ud!#yzWq8Z)W2?N5_FEJg*WZlu|LQjqA6%DtJBJ|m(hXKzqSaj zNF$|ZAh{fCm?7lmLQgSR@ROPp3dI z7zhsp8Hj-Zio+0up)iDlPO+&5V8yF&wjE71=zPO>+2$IZ*R4Y;wLaGv7s*>SK9*T@ zo21SCEDuTW@}Zth__%F_1`o6&Ivd}@UW*c%GwjISv+=Nc+L%N;p72Hn4@3ON_6Ou~ zv2A-b9UoeZK)=jpj=jPaH_mJv!Ay-#qRn-Js$S2znw|#>UZbIc#m^)WHo6Rl#0Pw4XyjCOo&w7&Qv9Orae7z|?8g%HLo0%Kw z*B>{fknz~k-NigjMal6~koCUDFCR}@34Sr(p*P3AWHGPf*+u8+Z_EdyR(GTSo9Soo z>LUG$d}+osDKjvw3CXCA=?w3)E z@yKm`3fGzqvQES3e6zN<#oo|5o8N2HZD#9YBH&ne4CgCPzC{wU0l;l!B4F9u5g)xe zj^2#x(l*(yMOnhLGo!`Yb7qSl{u^)LrtE~4`exn4?rxF?sWR}O)Tpck{^7xL-+*6$ z8Pug{QiBHTIn)$82~vY@++EbYT!g|8iXX!dJeN0jb&0e&r3Z6$Y4wl{2#qf`i3ioi zJw*~*MTWCx1dnYCj=PSHhvj?pyvH!@b)FcpDBaa!$2hUSsqRT95`!xEfgc$Tl#<#qM^3a!<`AFFOu*GF$fJ4$hfQcL3cCcMn&ISzh85oBA{zB8PpG zT$yxJnU&Ue6ad5ZYw6Y@+A6B0cE?w}#qb*%E&RW7yB1QX;PCF@yT}Mmd6F;rvrZ%h z&=j{-Lq=>d`3G70$jv==-Wb!ou5%sVxvcqEU=MlUQ+^mk^76R17+VOlgBwdD*}51N z{(aDt%8DVBjszz0;TvH{9gFj-d4P2HnHIchy1>?cn62IXW7y92XM8%zNiX%xmx&l&yuHkuWm z&RxwT7Ly)JC&-=2b%d>WlHjy?AYXlkvi`A5<@!xGxX zAiXj=qFoQ2!DEB=*&OeQ8`lO0Zt1w$%^g0NwtV2M#>O`kTE)jYXoBnwcq*bHVrynR%o-kc(}&0X$6~^EI95&*}Y>m_MkF2H~^n`tQH2Peb$|& zBZGr62KD1P&X~%6UJFl?u@jEVD5cpct?*aD&pEsFVcoAg6%o6}>S7!N$X-KfF#r4_ zn$Mmx_wfIi9_|h0tnlfVYyiQG&WNG%Y6r?(jq(6o;^yOd z*zu2O%$=A(kqD6R{d00 zesm#SRf}Qy2nOZzbLG)T$LBuEyT^y#92s|Z(9Gk*f$WuObiWRwtcg921jFj)p-}AM zNVC!+lPxuur3Y&^mJ3WW4aOa{s&U^SE*j)K2MG+MoVi=tNZ2^mM`lHX!ciL@+Jb5L zViq$F&zuDJ+B4 zNKAt)CtTOKlmnDc(Wm}={bz8)de9htpU+_Lb`oRXhfJn-9dg9LFHJ9PM{aK>B%9ue z($^`f7Dg=;Wob!raF$4mmxWI4jJaqt{PJdZ65v8P8~Df}qKwTL-$ zcoB29Y+>V_=Icf-z0{57Tze3q^toO(UHI#5q99u8zpJ?s7R%m}T^ z&GIi*ScL^s0nqMtkR8$Qm;?<9U+mk@o_%lmYiUt<2CT9?D1W{`X>H_>1lSvUF2&|w z(><+<75DdSBt`bz?+m;Yb!wX@3JB4Gb=1mL69b9~3=O-Ff^|D(eAHt{c)F8u8wt-y zcLXu% zI|aZSWWT1SoC)NoPK4ijp^mNT#*$|55RXP!R`V?vsc+^1&U8`?>o!88Kf~oy;W0cN z=XPv69uZ$EAweprzLTw#BrDi3dx4w_S{%BLU^}OwF{yl*f2Nz!b8=2)@%X$duXQlz zJUDB#>oh%8zFweh1IlgaIxXA&29j!N&Av(U1n{!CUmoEEPKMT{QdRA)!qCO$_uQrM zP{~ozv%F?zw-5FPs*=T&N+@KnheoP0JKUN9Mn{jKt*LQ8+#fG|sJ>Nf+h)e(A-fZ< zyOlKo?rqJ_V^c{K!dB!>@=3cPoM_5C$Ndfs(AkynO%wvsYATcoq6HnMy>8xTmJY7(CTHy-RzO0Ib;HeTfUzYU~-%8ZYh*5ZZ&<=^g1(AAym*Z zM@~jRo=nxjZoe}NzOG60y29t-+})spYe>WfrzvGBzYm50_nvWT-k%a`wrRdHup^pw z#x1H&G_>Sk%@gCj%zl{>wZIsJd^?r41ev3zD{m#3MN|z+_uPVSZ94=V-VkMy1^F8< zh>p4al*f=q^WHlg`7C;07f@Ba<~HhUUAtI&<|A{l_B)#i#5X|fO&0en%R|2>W0PnX z*h^ops2T}0zTk|HB(O1DXj^j7#mF2j#Y}Rj%ih6#&+lF8|MPtJL5qJ5wx^=4;$Ws{ z_E&hOfEHIJxUc&1(oDFGZlfc<5rsMM)olx8$e;fJ?sp~zedGF>h^m?CpeJDZ{)ab!r2<07odqrlo^DE+r0oa2kj1Jv z9HtX0Tz+`EDj0ny-jA_Rf_*B5v&(UmDS6{%Z8`40KQ&ycz<&7Pj+GU2XVq}8*2|>j zGqLsO@uo^nh}&moCYhTa2t{Ya+!Sv(x#hTJos3g>n_BG2@1jM#&*4m(gT2yO zjwzGofzdc^Q8ojg}QnY0NwGvWZ^LTL5 zReQeH#BR=k2k$2ZBkvVGV-7C0-fn)8h5-HQ0sh4ze%D-x>cM_i3l&9{vlfL;5|BBPa$Wu+>yGm*5tN&!@SIN0)33BP0sc9rt->e zCza&lAO=i;G7NO(L2F1gOq3}klnWI0z;&**mxbW!d;h@c+7Ej%v-VTSKZBchOItsr z{yG>6EdWy>ldyM z-g`|54{>tZi92yIe;ZuNV@>c0qupn2UP1Kq0?to#cV1SN*s$Da*HSEz&KNKUHZlbEg#asA!F#7kcG8{y)Mi6WE<_0}SPE49La0ObD2>q5`t+%DXoL?DZ9D?_JLjG57X=>}>BBvq=f zZrpO!6=Do!|*viK;|RV{tk!Qdxz6b>Zs5pIMsAsw&EKT+I!Rj!zkcxsyu=Qd3;lDIQ$=(AWbU?NZeWspVx%nUF= zW7R@BrJtS{?#AJM%O#?oa*Es0TFa^@$40_Vc4$Cs(CPIQv#bZ6_E)dkP8tp@O9Kz6o+g-do{b!X(Adw1_KR% zOWaBH^jY^e&9b69S&!}KIZEUX-?E>O4X?X7(-@EsP&ga30M8WiwF($B!jSh#P&i9C z4YeU(IP5Fbvqe%;_f~p-hM$|*J`TCCHjl`@KrjFKQgj8!al#^mk3o>p`)Y)b*j5JC z&QsN(=>q$+nJ&4awD=;9r`*YOy&1cOiWqA`hU4IHc(GB+sdQI;hHZ8a^SG*6svSB7 z*dmm@C_53jss`UIQ?(lmB@V%a*Dmt zCFWfXYQ(WVdX8W48gBPJBOzqkUL=CQM6joZ?MLUk9&x1wp6Hp;tV&Mg!r72XA`frIICbA86H7>#jCCJj0t zcwxjy=zRcps?8Ib%o#RHlIZDs?M+5w?&a!mvZy~6v6E#;`@<1ni&r9egCO$OjNYr7~kDSnnUhujXpiUTSxn_ z1vU8(Z1OP#_-}HLzfUY#v4DnrD5mKV_&}XC(3h!Hm}Lst)&sG$F4rf?+XSfj-)}Kc zmwe6~DYw3U9li5EC6nRp_PhSJi{6MbZ;b9ct~&G*9x{G(!vLA)FN=C>n1nU&!XpH5t&hzc;Pxv>zXMsgHQ?01!`Lerwaz?tNfU@+A* zMZ@`<@7e_y8GbZo!j|||mR$T77s-f2@g!97C~`*<^UNM8!O-+U*mynzc>FfSR@pzz zx!jq6i5Sx!M##>|jBJ(#j^jKez?YaS`HBKlx#7cFK{Tfa5nw@0n;T2Re8Mpv`Zr5H zqp>Vq`Ab7j&<7%-_|R~#|5887{mv$1cy*_KNj)?sk{flwkv1JTHkYktRabd|(7?$>UO46^1}<#^Owl})CS&)noZW^x?Y?4TG&&rZ+G2$a$9rV{JL+$Df%a-z-O4S zwt)?8)7<)O_BHk9n`R#ZE)kU_l?fs;tgWR?CR<@`0{ZW^@z~7{4 zg)Gi%lSM9C8B~RSHJs+K!lH|2MJ`+yrOV2;2Ock;VY42dQIAXXUd0zbH?=If7M@W* z?alcM-U{S8mTVwN=&XqI+7z=hyD84MQ0k@I@saEfzx*cRs^+8jN=MH{xD--VY=xl! z`dc3>_g#IlkEyu~YV~ec$-u=F0F#w(uF@HAU-$HZaU!xu3x9vJS2c-#spU;%ojcc$Zp03QU+G${mfsq~nC)`VZ& zdeUDFVr%BDkAN^5agu8?L1`Ag+gxz9#iHq3LR_WtZ}yd9@b6~>p31IJR37U^?bwn6 zlqE03%!C7>Mfed{tc*>hyi4yIBXIn>B#l2M9u7*yP3stQ98l#4s~`8r6bMrlnvcfX z!t@o>-DiX8uL`p`v>DmC>L4064^JPVMN_sKN%jRKnS7yRyHlaA1mOMV2*jJYaN_i) z2_T`T%uFlRlQ#?Rm)lAYT6pX$)?_noH-Fhw@WjNy6EAhvLkG)3bF1NWHnxxuKUa!K zIYY{)m&GIZlii;~D=#riAnQx({}E~?n8?;L81g2^wXT+52$Zh4mFf+W)@{0N`OAL! z9!Xom=+m0sQN83T27ieL;S~lDeSGnv(|tAzOB&SEC~_5oR!uq6+`QD!o#&P3KiF@1 zWXj!v$*P|}CEI>KXM|LTwLMo|CmGMo9lT$Tgaj?O8|XMGnZO2Yi&Egg@VyBYUIh$f zSOCXuV8=hs@gJyNEMj>acWvL&Ub3)syviCC>~0N>xuf1EMZJxIflC-cK-6sj`}XP) zl%WWV+&eM5MI#i6&)>3V(NHklo|qb42=Hwdco2u~NBja^$f@rxMGlaoO)V0?&;XbV zqq(4@spk#1=lsQ$c#Bnkmwh+_^ZXbB7|a2^+3>Vlsu}|}YFojQNtB~<7kkmxH5pF6 zZi^H2n|j0k@DX<$#OJ1iO_1rE+ALs{_Y*Hhd^N5x-5G43}%^mOO-0CQ1#K zluC`8G?T@Jp^Jsec}7;ZUuA#uU*Odn``yXy`LI5E1~Cj-@$2DDNV(^PqSvLZ%^*qB zShi9-kTcXgB-v!4&!LQ^mIy13Gizhg2la7{c+Z|L=^n)51k0PrF%Atg^R5FMHFO6< z$B;ViH8Qxh)&m!h_%f0{0|$>fInnUdo2c#}ACL7~z`cg_`7N)-?g;Pn$>`DFv;#RQ zMc0o8gW*l#OD{Wb*P^5k)LT{{$7h!w_V#Dxaj_#GWbC8_NT)V)k##RW;1g*eK>V@MSzvM;bHRT+V ztEqEd|KXog)TmZs>tci;yS8BtwAwlGHuGRlkPIGSzPH3EbKITVmwz(_Stscy6kSrUyRrVqaSc-Adnr&Uqpyh znRP66EM5JOt&>>cW$#Ldz^S5*-Xco}G|DiM&C{5Rp$|?n+LVDv8Uj-0ChTxsmX)?s zdWWB#oz^TT$TpNc6O+w`Xy*X8Ec(Tz>{f83FJX8NEiWFXeWe1+W0(Bu;Gryzk+vhm7KD8UG)JO6TKW-Z)O+`Qwj0@k!M?f!YdjC@PBMsr2e3BSJl`Ct zJBQsNmV_4c)6CebTu~v@Ew^Ste*!u*4})M~4EQinf6EY)ds%5;&9phbfUdMgXFa?omQ~(DMAHq#IQgXo_QW?F7$-Y4FK` zL*dqlsRf8=F4n@SHXGCx(L_JFB^I_GBR}RI^M!3c1(MYh_CLJYUq44ZK8T|*xG=yw zKgb0CJNWDxpteYe*@LIDIM^sxF#GDAmQ-cWHOm&?$L~H+W?p!OePFyb|C;}`GRVGb zaQ*wYb5B!D5lR=a1Lu*NKz)UoE*IE^;;1WV3WR#V6D@sI@wDLRvC>``Kw+y!sByCI zZ?l5kU7o;k-n-CNtby0hxTdf6?6!6EwTeOes|oAc1(xyrK~saZRRnfpLIQC37D7Aw zmxSnH)*;h=n-_titKO{?&me4aibA>dEUZl25E)#KEV|#@&b(co1XXA{qI#WW(B2j$ zEqDlrvD_%b=EJ?gq1CFiG_&bT{7s&p8b4hQiV2bE7s1obdHZYA6gkH+RBcLPy68Ru z7$JX2@hI`L^N)D=uVZM5o44nQ-~OANZ@?KJ;{xJowSp;XK#1pzL#Z=zsOAOnUrvu;zGVV#m4G4r zFIgzq!oVQ(|9tWSwiz>T2M1eEg8}^8FM|?^ zDq5H>?>B%~t!=;v+G%t!*VI}FGX-B&X|!O^yzEAC6 z0&PvoOEsJr@gI=H1dd|}Idk$*c3=c#h@(Z!r{8`7FN{KoMjoWkp?n6t@%m;xHKzt4 zTh5+KHWj!ZYqTe$DOFtB4C#qWa7xw`DpPPz!*3b&SA6&1dU2PZ;|4w;e_=6T6mCl7 zB!^!o_cdsCHiC~v+=9j?eta_k{b<|e?uDkfK_f7HE;}#c9=Qgc%TDyd$@poq$oQ@P zwH-{xOCNq)WQk))GTvW)i(nrGPI|lSr>MV=d>AsyG?;FB-s}@UzM%=7FW1d#H{DJT>$Tm;Tt1otzTlyiP9` z2MGmTdGxLgj*Wq`>ftx}OYEy+7@_MIRy-2a=n(V+F%$tGeu?Wu2r>O6v*>z{_F=p_ zRh2Z$twClSoCmuwEsAMzEyL{X8bXAZaLAQk35vqFC8e7l!w@EqHuUaakuV!taY7 zdIr};8N)wt2iN&vZY4g2Y$h1Dl(113Jcm~4MlNDZB1|ja@Td2MJ<#J0J!hJqw0=*h zLM^-H^H2FjFL-F@&+40OdTIsIPH>Kw)J(CrLXK#u%9*5fI3cw z5>TU(=sFhpS;r4@p~<_)*xn6~o0kVN**oKPJwXIvZ|GNvXmK>)q$fRh54A#gu02RO zX6A19g?IRIG(CG}AXv!quTy1&c9^A4@lWpc_8lEu+VToE^W)$7e!HMpz+Kt@ zLIcpY_EAe`Qwbgz*cMt-am!Sz&q~@9XV(Ks*I^=>wd&chDc44QGe>I5{&+cR!XEVp8bortHuZy{TSaKOEH}*W!NL z4U47?0RWobJs?7IkU?!jl0&IRBEfK2d3bmIflpnRp8^9(7yOKp7u2qosvB{qv8q;$ zNTiDB*4k&Br2nmuFP3Xe_f|Cd6{*|B9;&52j6O8!E?B1Qd z=b@NDf;G>NCGy72A63hWudd3_l$cYdRETGLsp8dA;0}B_4m|6=Cg;qS-otrff?ROP zJ(By&gR)RUEi;cR)X#aBwDvxOF?Q(eP?X<`?&x&B%4P7Zk&VL?rd&U45JPdwSe6&d z!bM>c(0<|rar}{jgoFUZ9UiFu0Rf_7rvZ$BUJ$B&qF^i$0C6yq@V|03fY4C(&q*v9 zT2n5MAA;KTAzW1y$(KjJZ1}(7k7~VxGP6ukH|17TNLt$mFA*`d`+{&r;Mfsy)~j~2 z_&B5`Xqp_BR%U{%> zLoQD*TJDFy&Td7O>qdIK`wsFn%1w;Zw^`VHVcZ&H{*N($gIC`PHcnOXI*yn zNR)Zzxo%bQg@8k(z_4j}G0QcD6+1g#VwPQX?#SN9%MhdrUqTdTIVt1LU%}P#w$+pZ zK)r{K*q5#b&%$svDrD8{jv1oVxRT{~+ab|b^J;gUl|1I=*kJ**N z2#USO=7|whY31npdAoKr9J>%fXi4?1qz}8o{-QLZ$P!uda@Z%*)FU{JginU5)5$|l z1FFmEffgkx>LU7siR@3`z3`&&_^|zm;w^Hh2yN6c^0*s#C+;pIHzA2}(0G&^_sUM1 zuLON;5uNs^$%+`Iohfg^8I!#ndK3skqy$K1OgCNP z{~0i3mwyCj>)tUo5}AA)!uP)hV3lK3k&KIAO6jk71C|R<r^DjAg8UH9&B*Rt=g*jGhe= z{I3CNm9QlVhb^$>>ek*x$3Sn1=_Tre6*uBWzSwBDYNrWOp4i?fhFW-7Ulb1e*r)>O zbWQGOegCsTz`h(+;o82(1Ar25PLY!$zbrYOzY~S?H2S@`>= zOJkZ^33tzlD(>)4!1Zt(VB%U!JS~r&;AA^MDs!W+d<$&D5at?bfgdnNw(m0_e|BsX zU@P7{nfCRT;ZwSKfMq*dcG_K?>U;_a5-zzSPDxrFougUDtn%GO{&?{s>aj=c6cn=I zrN>|oFuIk%r{t~V`praHj&}DZf|gcip5|pZXz!87<~$U#{ADd4249sR{ZaIp~UylWf7ri z!fcq-ge-e2PaMnhKq|(sEIKMR>RERSu?u|ssdyTN$2#6hz#s5Wo_Kf*!#1MO(d>!s zXr;i>ro<>PYSu877GYZJpnztK!?KhP<#jJPuBGCSC!Vo}aWFe2{S3Fg%*bR+Y}h|B z7byY@d@$ELEg9qucSyN;?^5j5bA)%B4_#%DD!!ulmNBwjAQrwJ&n7g@9yG_@$|1qP!P$Rx(0Kw)ux_rL|IdZK)tX7p*Ez4TesF7aWI#A$>r`A@tMauX;VtZdA0D$Wu#jmhWyKCjNn zu1raVtl@c(PLTyTr6cI~)*Q9^_AJ$PNHG93ygWzD`UAMW#zWeB^b*jV0jD7``2?RtE6a*wZIDD(v4+P|2 zwK)hVh=h`op_{Oyp)Jtd#OYryZXgJNChYrLR7gb#3&apmf_?}H6}Pr?GjVhRVF{v? zqy*$i0_wxV6pSoQfX+@JtVF@)Bj!fofQWFTvhc{Vk&y@`JD`;lh%E>cQOF4;?FoQ3 zIy?ptr{ZYxZvk5(mQcwubHGA`xnVe9ExZiC7+D5jkEWM3bTl&w8=<5dIT-^0b}#@( zlzqPDY4g0SuB1lz=G)z=$NEj|e2r+#J9g`QHr-Kr8G0l^uu%Gj4hd8HzNp zpvs3LsL04G3yv&GJ06Tm;!Q#sjOCcr4=UV0nQE{I-vQk`w(3BHlOyl0hhd! z3Mf3lT8P{Pf-Ki%iuFUe!epclg`U_pct|5c!<$7F0pJsajFFxWg@Z_1&Ws_b#QU79 zqt2OD`|xXVXcXnN)M*YFfX7q`9`(dMQ%247+p6>9RDX3REr`Ez`BMCpG(L;h2+#@n zORN7PIzb``N-UIN+m^yj~CdWA&ZOwd$ow#Ycpm9oA-B<}A37l3;_ zIK0^KESaSfaOvW}$VWOui;~*yY(MdRFY8Py|9IAwKHm#fk^!<#gjOU10CT&5kjj35 z>@eNJUv|G^yBx1IDWCfw&-At~l`6@MJ3-y9=RXXQMBvqE#B%EOF!vCSbH8VlF&j>= zd!vKf44*eU%cugrW5P8;;E4Kp`_UddN>8s~!JEu%urln+#=3-6cxHIR<~e#OuX0Rj zSRD5CrhuScz^P-h=k8{w!8NvB6P+NOw5H@yL>0h;-K4RP72Glk_5?w}$uaRV(TvKo zp{j%a7sene0tQk^0($o6hD?DdjrmMpWm|3O2lQc&+_KL0??psZWjp4J4{cbq8Tc2y zQJAu8|L_OQPXLaJ;SWOOn@rKUzdBDT3n=mu?aykzv%X>oeh+@IGNzOk+c0Z_$%FBO zeFIfgL`7u^PWGcMFTa&x_=}ybO-(}+hn~Q^a<$i%3&##8cGCCGFyML^i6Sh7 zDR_V#`twmI0g1zo8Nh3^m8HqtzpEDRKoXc4$>Q0uE@^jc1#IZNX`ht1`ckke%qGt|9+-XHj)NVH(Ejv|;MEyH=4>)(KtR zocSqCg{38!Oam)va|{7Heq|%+2{=EfmkRpD?|w9q&45IU_4&ejL8+TD3bDh)zjM}c zO#(|=KbZz&gB`2>lm)8t?aZMg(zu&6p$&kMaO24tbECl2c&?$^R6$lG?qR4`+^ThBU9(f%+CM?^U*BGm6K5lnV9V3g)U1EJ!lf5oX)aHy$oYsmyy7?}Zk z`(R8-e`lgA%G{~8FrBz)w|=b@ARZls06iY3+dRLP@?vgetISE9+O>#;zQHi6$mH7f zG%3^fFee9vZAe1p4te=lryt98plSX=0`qHj(T-Q@894atc}uOAwXRr`Ii79cXSB=a zBfm=nX@{bo2x#8bY2zcnz}_`a7t}y$I6xV1dinv^UZi=-+4q93E4p}RNf2HVBz~89 zH1qGB5KrZ1ju0_)k$FUk8A@+(@DC8tqbvDPQpSz6kW>zCg7G=)dN&(lVq-v4WyzuHv#7bb3)_z} z^X>_&$D@@E=8hAKp9XbHV_KSQkbc&cCkZmhNzFb#bVyzE>;|Z1;kJnIj2LpEIbK%E zQ)Lft34K<(f_e?wm--pG)6tv;?Wcx~akcJ9>$0N7r>_%r+SC5N__AA40s3vj5nVK%FwRh4F;(N)pWQAtZ{D>dg_*;~oj!6zqKi&ULeGMA8OvMjmi zKBmb(2j|YYTzXy(%GQOG?^>`@Pk7}@f2q{ZJ3~#8y}0YlrJIv%nCcPgXWl#pbyE9G zj@C$Bof%_l^354iWSoz+irBm@9}$AE58op9x2&uSHq~gMBA7`t)-6d z&;@0Mmn5rcQcC;bC5Ns74ZLxcU9`d%+kUIBYps(}|B;f021JPdqKG+~U4I|lH)ALq zeesf-Z;^`zy=Ka7zaGz}XNd1fP6rR+W~?#DWP~fLnm_ekP8A94pk2_m63KHwh53c^ z8SbQYj??l(z!tYnqw|)7{RbA*7OuqfzZY^&TUl!ne6==y_!EA+@NMx_%j%4RwCco< z=L^3?i-&k#x6d%xUbkZM>c&4PZ72>+d)b3r5YRJ4$M!CdVQEpC>nDfeJcw}M*oZH+ z=v`gfw{m!46D5uABa3xl+p>n{b41Q>z@guDBg`lEWK&21ESAgg`=Od!RLS-oz!7oKkwi931x{A+1AW* z{gCw~)NqmC)0Mt|-ok>OJsh35?x8vI4+t{h_m?B@ByE$bLbzsF3)F^@L((b5l=F{c?%5M^y=@!*@+?Q3(L{6<_5^kYU0 zJTC$b6Q`c#&6az`ooj#;>5YZ&`14ZP#{wkV9vd1x4Hdj7SP}FCG{*@u(mJH#H&W}H{ z=}S@D%6<1$q-K|p>-9KK)v@=QM_=QFI(0{m_TYcHOqe#ve2iBBd^X!BOH*ZPNNg?FZ`?RH&?1=D}UKETe=y^*xmYc{B;-g zMd-i=p2~f2G<6yDd3D|HG38*xW`0)>mDkeRg0HCPi8CC=5+$X#rF-jLzGRG}an{tI zN8z_zrnTHc49R-UQ7`tbZshkT=J`hwM7?Uqe4G|DN4l4;o8Rn?kezAk!=KX|3ZiSiC^tUrc6dWO?YZ z=4zW!w{MdLf9(UIo0}MQH2cAI@RY0Mje_8Q(VjEa19HT%ZAS zqQ|y2os{||Gba)?sqyoli^^kj<-yS7YM+ZQnC+JNR9we-=i=P;+XwlET6qa$Q1p$b zrVoOuX%>>kXyP2mQ?7JELBf;a#fOKp`oC}v7OE`czUZderM@|3u5hDgaqLcy zz&no$-Nb28G(noa@#B7PJe4e~=W)d!+opk<``%($U2Kx{-6(?3p)L`$)z(L>{YqEq z;xD!erWn^9%VdHWdDcv!B6;n2KQ>6(y5naGw8mCHsu3T3yeyCmN`bc;Q4 z&ITht$*Z^v^NurBfqNK>Xg{^Ksu4%cgwzqTS>*) zf55x}I7ATp!}LybjO(w{v+dIha`$g>|L12>_90@zDT8QkAMrLk#@cZm zUW+cBsAK(Hj2*QtCG%lX7K`?_;&ZMiPT)nBhyqx-(CxKJL*#%> zNe4)}JgTYe&}0(qWg2+guSEsYrqLjl=tT(YIU=Ea`kPt1J)u?CIOxLXyYISu-+TH4 zHAKC~M2^3;{Ji0m>elCpcSC7q&oD5nn|qEF zM``W4=dtd-=I(D8#%m21Xn(D4ZO-2Iv`Lylk)|*nu3@S%+A&SY1$70*Prt78ot5xf zJ`ntdD29TGw+|oKzdAWw-V9ETE!jlAvO*)9CBkf7^DC;i_0n*GNID2(0UZn3@$mr> z+YvlAh=&#dAiyjQD0Cq2yHN}0^In`;?`u+y5{q#*312cXY_q6W?78 zs4;p#?ydT|UqwyCWyeBrhTEh}R;4f3ow2`HJRy)63kn)`%ZVDZ?;G_ZR3IUXcS^Ad zoc|kjbySt7UQcG;7BCk z#2lx7ikNVjzXc9 zBr^>#6~0X}&_5|K?jP(O-7cd`#-qv*r)f93k+*{M70Z?0DlxMYtGB6KNTeKXQmQD1 zM8VKeFnbIC@pZMj2J$*e8D`Wxq?gNdm@%a6qnq9}s|KsPPW0%yQ^45ficK_?IDBfk z;}-kpZs;weM18~xWLsTy|yGdm-(`csFmVIJY$Pk1FBX86%I=-y;2H0bQ)u;r!LoR!nW^mB~e_7bpo2Lnp{5eDfIVyT-59 zl)i9RC6Ue*u&ro>@@lYVOgVw@T__Y~$7cs#s?TnFF@mULfsL}2Rb1#eX|u1y?jgmc zmOmcbuO{qQ z_FVMhHB+v62Cd=Z_un&uEvqwHZ&1s%u8)MvQ`(@lB5*eoUn`mLfAF^l;4)~R9LUV1 z?e^Bji#%T>W-F3?-o2!9qSYt&;VvqD`x)yz4T^eOB`#d|CNjF1AN9I(TfVU%-C7Dq zTU+9VO5fXgj$t^S&Mv)Ntk?FT7V2rp$d!Av%fMsc7iD*UHK?a;MSV;!aar9~;~UR; zHYiRreQ{3FuG~XEjOIk|Yu=Q@uXg^1|Hp=FV5r#tT6904YZdhRkP0%)s1c=?dYvzh z>P(RH=sElZL=*CjiCVK;-^v|gwZ>|`m(kE(wlUm=dr@8xl2v~EK4oJ`@JnyoXebN)oPjWb$?&NQp3&((fT>GOt+HFGM(YAZIQnelqsiRR^o<1srF zoE*E2*@o|w3_f8`*HlmCPRR#E`8bnwV6r5DT>5~Y&l*+##v^4ge&#~c_Ef;ZY%WKH zL+v%SFdkar+j_hc^&e=5=q>=I$(W328K(P<9f9e(Z8+$hvg5@k^Aq)tt=`Q?jtPsoH`$%&V3xpA;^2u%Trr-y zM|UHpp&(p_B^&X@4WNNd7=ENMhE(_W6(Lz?^Re$1Y~g3L#Td)V)LYD9#9R<*+g=yp zXpx0&OtoYZCN$w8LjNY8?wTi*whaY`)Y-4Lkbtfh9;ebH@{TU@WtS0H?7bhnHCdZO zZ1K)R!X@6c-2`IVlphIlu6}_vLJHBTStD{zb7M>Lo1RK3C719(P}6xgT1bVO<`gHx z(<(eBh+69)!zU;d{gb_0Ul06p9x9el8oad|3WOIM&#MOv-e@Jr22Yjk4t(QY9gF_M zF2&Ajwqw{}UsHJ1%)6u;2M9d(7x|0jBz=cOv=yd=#K+clU$olV>zRp{Bv~AB7BTlA*(Wv}@HpxF`Ck zIC2F^1f>&&S~?OLiP$rbplpme%3OoXZ{M; z&WidrrNJb{3!eDNyW3=R`JyfDBfhE~sp6INc5 zJFg#A8Eb?)Qf7)SQ$uiiu~Ndo*Yq3ZdA9d39so>kR1?h~<)iDQHRiOV%oFZmioR-Z zUHDI2K^)C{lGJ{2^^HW1`eEaJj!47Llgsk?p-F)3eCj`M5~t^1{2$#v)Bj=~dX!wX zcgGvmXLHTnG%1+R?^JwHx<;0>j3ncE(;d?G^jOOz!d^CRP&jc&?65t(6%jkfDLr=e zRotpCl5^r7HV5M0)a52+f`2)+)>#?|<*l=_pSF?UpDmBJgi#fCSd_V(ZcR-c7e=98 zT!f4+-u~JmIGUVTjM6g(h|Ea4;wAdYc<-X&e~(`?+Am3=o6LQAIh==ckbP5iQnd*6 z5jgEJem+fGq)Hvr-(#ARe_xn{5})ozGTF$YcFY|Ocigm7akK4?WS(OZ3*C7uujK8Y zW>9tG2C}_NE$y{T*2yv@%NEFequp7yHM}wibnu2YIml8^J9k`hR4a@nw6QD$yuYA= zy5J_!@&o-aBZS$}tr5gBkQlor{ZvNYhx#0wi^%55$?R*Y>rZu2# zn3p1%F6O(NFFQpSnrR7vD@)7qR~+3;LKpsK{kJ zywI#>KAY(Zr$hR)8|~@Rr@`_PM<%gEUz{4+>&2F0s4|_#?ECQB+ACJGmIp5kMJ8JA)`-Bo6b(Gr8CDXU-pLUl`e+7WBlJ zdUjMiI3?N^0KUNv*N?>unTLOzm_JMD>s{|ZER2Zzb7l$B2MF^vwQIQ={s(42nZKO% zF}E&|?fly^DYSY?e!nt1>IPK^&!}jbcl&eH#3+s75k^tkbJusD8JxcTDPh8!IM;u= z*X97r_{3f54tw7TWpkoE%(whKd5@C?#lNRlcIy}AjF*!crNVcfHIqcC zB_r0Hz4z(rh;0Vx>F|JPKN&|BlG41oVP1T`;j{j-+ksA4xlmpz*Bv&^WGwwYQ;vM>u-m6I zfUfok)(Ws5dmKQtHuMv z!FGu}qEj?{akzQ~USss6xX9jlWSAu6#*J8W?)lvra!|p|ne=Lw_BS5i<<_)GP5xiB z3b~!r3(jPb(r(04vG;O^hwsk5W)~#pod3VSD_+6<$??lSh>CqFLar)yl3F{tD!uIu zYXJ(AJI!*Y)EsZ0}6ly<{{(H#f5{^kuacCf}m=($oK7jyrP z{r`RRzwB}FuZcSN71p)G2C`p7`oAj8O?oEWINq1XgpEZB$~o2P0ah|m81L>1<_r&OFGTxjXWk1<0P;iZd z!3T=`P-Zh8yDUEy$sh}V{H|C}59ykcy}U`lH#x_ySv6tHKhCU2h-I4g?%?@RP$vAc zwl^F07zVhBEswr7S-r42Q>}&dik-aWMD+g=HGQu{xWm;%Y%G6L*EmlM z0?OK|Hwx^4f!*YY`E-QOtVc*~HutXFcLjQ%H>o-?Ali7N2jv;;>JfM?)Xr7MY%1q> z4WpAPsqrKI0(<(Qe>Mgj^~xqiGV*7*<72dX0%uqMozmGGypqNt))z|s+F7G78|=>L zHsO%p-CMEH^SQtns@=W%Pm(sSG*>s=Z){&(cx#^l$&3m2!D6T~tEtqLak=k<<%IH} zU!!S6*Y(tMVNYsN-&6k|b#Q2#oPuGpDnARz_%r}I{|iSiKS4Jp=v|3T`R@VRyd@Y? z>^Zl~*xq)lokLh%@LEgki{gEO+vRuiCf_7KuX3B3=e`MZBRjWtnuYDvo8&T*8@AEh zKZ{FaFIdY1q-(WbNcb0(+mkb{!1?$0CBA^RsUB)aZjHoS7=GP2j50~(+jZ9;AD(2h zOPNISZSj$L4+Yp`X)E>+HIdhLNe`9#(hI^WJECb!Qox*Acrr%IGdq|R#j_Aq%A4lr z%;tZl&}Q|@JaT4?>9#Vlq8m*ZDR%w4M-6e}k5}ELaW~J;c#9VhiH@(f^G(e!-nuXM+E7*-2A4u!% znv-5UE8HKL2qK%_*A1J_munvTO~}E@_Boq=mG z5$qK$6hK61a@ru!soy)(3hH>!K={8D}8{6!V2Gx>tRBZ zO;4ANe0S{avp$WqvKjIIB^xq4}?j&wdJi43=B^KXYi4FAu_ZrthNlG5ES4 zW2%ZV`G}D}`Kf?;>FqGdc#g5c&m@$1tuK zNV!W~b#yOc?}B+DlaWQcbk3w5*}3a>2gvA&w49Cf(>U*~O>*pESlc{b4^GL`K?CMY z+XVaemAQxgvCqyu8T^#J<+}BE+@HeEvw*mpSvE1$-)=Wa^ohNy5xv%&dL&+9TM8C9 z-XTIJa#9Hkm^_ItpdpMo_P(sMJiQ{w&TVYzTO$5{1##7+zF;NqGFTAq1iemZ@(xGP zGVHOJiebN8b1tY;M1kKKy*3rSDCOrUk-huJm>|pUr%NOEsQqbvm8|EHv8XT2WE2Z) zyY4vO-*$uF9?H7{(h#o3vU(&$8qvGO^#seS;|B1n(0|aIf^(CK5SZ7@4=08239;{_ z6sya{&J~#SxodKQ*A~1Y$H^=v${kW|=}_cJ2-o?m-mfH;O>JA1PM&ZwdxQ-)_W!{< zVt3{?dXvQb4FFiFO)=lm)GaIu$J)G8_>@t2s${JBnKF{mGKld5HUwMi>g?5Pdu{Gf zb-#6*v+w5Tq-6p6e%i$5vX9sUK;!b{h`-ys`eR+u+Lq2U`ybg1arz*s%&i%+f6P@P zOR~J_Xn9vVekD_(i$4JA=f1|xS3d{+WAJ2++-gxjjF7Inmzq!Ljhx%a-nFnlCu$n| zI9VQs?37J5F0aOV?ORz^%Jy>5J3mnTah#A(SctNPd=om;CXlbYy z2nYxlXcky$$Q39RUynja#7Jo$HZ-YX2x!P-$Z~K&aKR{JAc!LXB1mBQwW$SLS)C@HQ-;l;&>DCj5H zX-Fps2&g6qCdg@MCCDTxTo1*?xVQkFpCLSR0IG9%j&yXGsA`A^0dxf-!-(+!D98aQ z@`)NK0q6tB$cO-n=>N#bNHYM4R;d1oGYCjCxM*noi8sjni8+XhD9FNy`{??ps7NwC zXlVNR`uX|#m}vR<`AAmy_xbmTXefyGGYFFi!bp?$_4oDl_IPMI$aeMg^~jQ_!Dy58 z^!4=f^k`_vH7Jru!6=jR^7HcYSZDwM0D>H-BE_}`0u2Z;jHo50X>$@lFjyEUffx*- zIF1O3fDj@egb0d|5CI{Cp{tz(V7B41SEWb<$EVNO(|C91?7Mm513cy%7s?M;Zp90&rA$aSP#Sg` z>;9a1H#hMiKCqkkW^?$(P#>>9Sbl|^g+>|sw28f+&@HoYH>ESmgmeSd4l^riKEnI+ zZHD`7XNVsm)rct*AJ`_KT!~ketHf|-xVHMmzXJUbsW{+VvdfyB&@MSL`q+E6X9eiQ z@u}Co%!6(A(m87^@=oe%VkYEoIhrA@(b`Q3)uar1E$v6LHw@*<0BSEF>%DDX^$y82 zx=vzCm$fh@T4N7<^GxmjAjcpSatuSba`EGPvHD4le#EJY9rt;Hy5NGq3>b$PJ_(R! zR$$cQCW?qMw-)1g)IF7s`bEJx4ThTh)1`ph=19nlVeF+J>u5z5e_?RC`ILhvGuWYz zbwo-RCySL{P2Wy;Xzj@xTHJ80WT%Hrlz=m`pdQ4DcW3FJiKY1?>;x_nWpl|Tn7%X_L#k8U&*dqYC?8#K`m>%!AV5(#kAQgx%QPb zcDLpivXgY05M3Nm0ow15ax~yJR~YRVDQ$1uue2*SoseBLqR6t}4YepD+u^F@dhs%B znUytmxT^{33=2cgF}rM&5d&%NYGQdgJNBH33cK9s1nmL~qR(+#vXdQyXnu8Iy}TXw z+++p2oYVyAf(4PwxLq=ni;rAXo($jks+qR|IO zMxeHjd+#>GDY!tG4!bhagzxQYD0|6}>>$eucKN9Z+64<@pK&WE5zQCVX0PPhSJK$s znqSCH(rH3;aYO}ZzikL3T32S%>&EA0TeCOzE7_GyO-L7wD5dVV&84{OScaY0f;G{c zk_on&?IG}f*FNa0=P@d4cN?<_Q5>-(0VuUE{h*Ep2LNPc1TH>CHWxDxfKEF6uWu2= zNs6V_1|_+6&?cmG_RZ8YIC#dSHwu&O39w4Y5<$B>VX%Ao3aGvJ-YF{>_!r+6Na!lc z6j2mmJSE&K9mFao4IzII8%=bLqc<{fun(k$pRODn39xJ^FGRwPUG`{+FrLp-%Wfv7 zzrwcD|3P=r!U-WIMG2qJAt**CdAF`4ZGXk0k@n68icKo4FPrnE;ghsQW)q7y1H-1K zz@$rMrt>Yth`M69a8q27p6n@zb}7jpCLb8D;wy`m5%en0&+B`*IYP5yj))-`^gQB} z(RCFjH#UsEorBR;1WD+}xe~F6gY#sbe|%jIQ1YfSRq40M;g5U@tXD=L(Ka4N}tRjYwG5j2HZbXrVq0 z2-BZt67YGocp?dN+an-kcrc{=5|}aD24qWb72doFBF1e42ah{Ew?51RC!Go=Gv$KP|K*AlANt8JJc~8MZ9|hY!cyq5DEeaI=y6CFI6v%s4Pucwl~hDy0jb1cNB6 zKWb1&gZ6=MoTs?;$rI~?Nu;y~mYt1)6q@iUZ=vHywU!f;~c8@g63^-}OmLd(k#A~U7 zj4*E&A%!;5#nlssF8|izjxG?u0);1+e@6h6=Hfy{j0=Acx1|Ejxn`;bhv-$*pwc4l z*2BQOKM*Ha1IbbGWNFSXiPfoHy@q0>IQkY4iqK?GSz5z{Co{94Win?8fsHpGW1FCp z=$OgSxZvqTN6=U32*F5E;@u=Tp)G>|d!!+I4pv%dpK`DXj%~h$Ego8~B17c5LVOZA zRIM0Z1h_o`{!lG|_6UWvTFx)laiEL1K&^Na@q|lw=qg*<ROjfw{?Jmd(HITye6OVwrx89{~A z?Ojlk*cSCz!{@~8*G>%4qu9bJU}(Qag32}t<!#|2d{8*e1Zf@zJ30b*4<)sV-DN z1{}Uy4k`K!7Y`LmIA10OZ3~0~&j}O8KQM*is*J2e6fV&(J%Om5)VUgT9P%t^Y-ufU zGG!gGe-S6PE!v8L5~}nye#y2#*_2-u`Fq&e+7b{o+$#(G8Bt`=s$dEX11CDdHZa0!Gk;eC9t zq5!RhcV=(j2mXbmUSbq!{IU!NvTq!C4pJSpBsmnr&^6^dO56<^p#hQ55%tD7U@ z=>+f4n_4p$#2WW z>d$i0=paz5TdjsK>jFbNWWtmoNc0Oa<=GZ-QA0#Z=!rDBY?0CyGy<9YBQoGXj~uiTx~$2P;2SnI(t%T^+s3XJikqYRPB}BMrg=3ULRuyh zAmp_n{h=olTO~NWzC*4@vf{aY3em?&=9nJ@Q-glA;W`<5=FRYc*(#NYLHT3zXH+%W z7P*PAqb|Z9LPlw!M8GnG496!qQqtm~23dd=e2OT9+EYFsJYc}{GK3*oaRVz7H39GV zW=2mLv@rEV^PxgpX(&ibRCn30l}IrhOrAe=3WI+4%&;{oS5s-V~xPFMG6t$ZS8#8Wh2dM=qE^=>+`q_qDiMh@KAvD zcSQWql%aEs32i=Z^$R`u#>Se^->2y?L63G|AcIBfqreeGi*{KPQ8oE{Rr1h!Kjs;M zR-Ok^4EjleEV~>7evtB!j&vZz&dQ0mYht9QP%sM=5cNZbmW^ki$p^n@aU5ca)j&E1oMTkg*07|x5KOFvk;4+Mf7AdgpKlz>h3nc zwvC9511|tg$~H(e1mh72Z)C|C`tQz+N-}{@#-VBpWC975)zmk;!a@USUHK4<4}d# zV}+u+-Lf-G%FOu%rgb%xoVW;e_z;|0yIQ&^IVnB*1%0vA2O$v{!B+f~m8>g3B3UB2 zHy$Z-MU6qlepspYZjB-cN^pb>PQ4a7d#qVT1ES_%>2B(G@`C z2)qJ)E;JG7Fuaifc%Uw?#(1G+C1kPG#~1L?R!2U-2Y;`;kC%m7-& zFU37GmtW*Xx+Myn)0d;`kH~y$w3@&Pm5UGbVMGho!A?Ot{IVu?+oCFCm0zt718mPW zh|QfIMN;1o5KF7bRNH8P^o2>VRxeM?7R%SC5be@lN*M@&HS+)-aMDE<#4&_PzlmcN z?a1ioU=Qe@a{QqW@%|o^a{dl2mfAQ!l5%Vz@<&^Uwp1CE`j!kl0X}cG5}ZU>j2}PA z*CCB6wxf~s%DdPSvBf54Mz#Vy-6EZBQVqa4z7gL9%aW#=!6kcx@Ji+)S~o;DvRR_P z;tiG7;5nHEC;38FWi)9WI(;u#yow@jwh83q86<7-Lcl<`@P$yjEt6l^r-z<=@;YLW z>i5R5XuMT1R*>9J@j?xq#le9Ub&B79VA>M3(SsKT#IK;Fq}Nm!a^~*mI!$TPEogOk z=pK(uD-B8Foxxzh=Lr3y5j|u{Y&yQlgHqn18>#Hs*Mnbji3S2uaczH>af%- zEHd~EfIhWX+C)!96!~{gSa&Ny23EF@|4_Rgwj|fs_;^BF*Y1gFH0KBJXgrT`w)vUyy%C2zHIW4ow@KJj{K7$@=BU^s~>$Ra0G|0k3Wuein?; zC3_=d4)f*GwXUORp3)NBk6|j^EO9PMk<|PP!K)jIh07Q{?`#LUYfMhSjLQAXKmn$i z%ne}lxIWw`4CWdeR;d=m%cC4Hx!iFjHFEO-@DO(Il;DsWSbG4bPF*sOFyerCSxT#h zgXoMn{c8r-MRQ><3x3}w>F%-F;UMqdGAYa~AB?`VSbW)u&gBxuD_Fdf^E03;s|77kf{=!Tg(0)QJ^ zfKDF(t7|<1Dlv3!?O_$$nu3>AHagyU(CC7}5d{=V*~4gUU3o+a&@~|*K%FtmAC0J? zIqDyxBf@MAp=Gl7NDD}GUmt|^+3-bSr0Nr8ik_bx9%#i|_b37AsUXb5tWfF|80_K_ zygxqH^K8Va#>0D3yB6xW=BjVn;DB`z1ir!YdF7MF#Pw7d2%BJ6 z9w{qU+gX~~q)_IArbwv?aiC$bJMwW@WQ`Z2%*liIOt1PtV;(98ALH25rJiR+0+i8Na*_uGJv0^w?{_d|Z?0LYeZlSHFHpDy;i7g2o%B`6L*q-6z`*m>`mV z0G(SM7lT3<4E2@deAbwFOmz3$eke(5P0B(Klho+rw7wd14vR}dBJWUZ>Npi&mPM|7 z?C95J14YvE#DpLEBiE%{LcJ^k{G|(^T{c+?r;u*`Qw2M9;GY}Y&1bqYt;O^(Qn?A{ zhwiA=ciys0asdBZURn zGxg1>34~pUG;8osUu9~_1P4Gwc&0jI^&h$)liNN&)ET;q_Ua^~IQTcywbp~6Gg404 z=5ymg4GFjiC4kw(Oa$rn>Nrmzoh+jHr66hc6w&GvvB?j*5@tX6T6_XG zxBsB%+XG6OoU}39cH;P{$83;VT>PpUk;CJV$~DQc~j)D9+D1@TKkd=oJySu!g6N33FY1u_AR ztv~m5Hz^Pr6oVscAhM!wG<~;NuG>&05wrvsOQu0 zReq#yn|jj+55fsmFCg&AZW2m?MD{1zGiK8vh@7!{m=w+aP@+we$q?I>!Gv95$Bns|!ou#Tei(Lc4uCA9QAk|Q8&=}OA;fv&?s7>V{0fy*&qZ6#V02#I; zK!YFTxnOrdl16Y%lKtA`ZiBJl92{NTZU(Jvtrpnews5olZP@}8SsbC$vf)VaP@8Je z1Z1-L?}(vVv%~vGrG6nWG3r(xbBK76c_B7RTLHGq4^NT@kY=~N!Z;W)Roi-K0sF+M z*WZ__od(H>y&=x(--#O=wab?M6sD~RB;{UHDyL@SrAj2Ub@xd_Q;%*S?GrWd0q#cY zK1z#1z79WtS)5%(I%2PN!ozJY>@XZMUnkvmMU>oSR*>{@aowqBrMv6Ns!#304il=j zsRZjGpNboe<(OJetC5g5Cbk_nM{3m)s(P$wUS`U$0g(8DCnM_PQ@wqm4gny0e*alL z+A4fVkT06sO#rT)#$>98rf7>%kYa;Xy6OcPvA=B3y}-*>ULMFzM#$%uv77>#da~oF z0oHU_NZ|<}dsocbMn-Ty>fF4uRoL{LmbwmnJ5K@;yTzN;0gRjVaBR1AS;JePxJd_~ z?y*cHccw`87E&ZT0*@kgCgfd8N4bfB;^^pFH=6*C`%OT{2dbF8#}B)iGE~7a%DMNX zpxPVCu;x11_8c!_J1v8Z9%Vr`Y7#!XhMFBedRT5QYd1ETgGe7~KDVcb)O`Uk#17X4 z+e??oozyKLw*qLZ#z7lM=m>}Qbl1tyx1+L@sUb(%b>`+aS7Fp!tK@dm)VSG58E??= z++r+L*l}WYa@0-PTD+jPnH@(QZrnDOttneuWFrnhjSbqEx1B`UxY?c9W%l@NBQQf6 zHDqi!Hk3A%Br6P5E;~+ByuD;lwPAwUX~qz38bDk$*0MI38;M(vf~p&qcV}q=veEFI zxv{;wiiyyTRmeJn$e!Klmt_<1Q-v+nZ=c$Uu$8_TfB}TdW@946R$#OkR-wZ#Vjn{}aD@e=eTjm{ zUT{P-R)){k0-C0j z1?;;$tQS&}&^rW?M$ocBLeSO?8G&YXO|S zIVQn#By7TJX^H2bivaZl9+N_dj8A*GD&3MsY-tOePEFSHx1Q*sJW zZTHa$Hk=kJf&yyxj!n$X0|~AHsNH_C$hp_zG9h^Q+AKzu>g@=D zADkV8?ZF<9$YV-1Yy;+5+zz-BiVooIxx3EI!7Xb92gFtzg0Rt&d{|NewmsaTHw_Yg zP+B0nO2@oaq+$tRAM6HjTI>stlu=_aHdigrUiv{~%hcLpv)IwPg+95qNI?$vjXYDk zfVPs>)4BJDu`hc9Ya6@Gb@S>!KZ51KZjcvpk;40QQbtZ8ctW3?kEsvTZ)WPm^e`O zJd@ZoY8*6UOw^owr+X`|#~W4wHDIFMp78gl&Jn}fuK=A*l-h;PyII#x2Gn6N$+R{} z)vpK6)SgAMpc0wwrvQevoG>euOEl^=Kk~L5XR?xwLyf8RVIL?^U^g<>Xjop`L7)>S zVBMwDG`5>uwQN~&pnIl^RlRx$W($C?dIVZj&A6dY7EU*H1k}BZ+S^D?8^aeztd?B8s9j%BCdO`7YP1*X z#x*PyjgWNthyc_mOi3tF16Z#pa;&qcFdhK}P%pl%)k8dQfT&cgdwdzyNt~eRfCaT4 zfTOB5-74tn`lCUrg`PUK0FV<#LsxF>(rPJATxWnb9w?w+ z_(|=)YB9TijFt4*)tB1F489sc3oxZK0@Nm;T$I` z1R)^|fkEv7CDxjS0XA{~TxzS@aCH4HH@v!yxFVuiUn%I~)cy&3>OLW}b0xN6*1j1_ zPq^M6C320OEA<%w&aR$~D;(WCg*<8scv`zKaClnj8L_3-fO@8D;1N!{6yi&_ z2_7U77}eCY1$Okf(zBs8chzDR)l$GC2L=w$ZfDz`Rs$*;clRp;k8U*z)2OQ^c$9dE zGEFTLS{;f2rP*+i2FF1S?nc;)8(~;?F91Jy!L&?hbyxy~2;}ZBl9mar4skXhK(G-< z!-WjDEfGLkKvghku)(Fp#kn}M(E=_lM-3Tj5p2+4a{&jJ7S}?C3%DC-X=gRy+*-h; zq0vZ_@gjnaxHKC!Ttu*uBSKpm92yN55z=PVSc~8!chEAS)nPIb#1(h`z+eR>4+er+eTOAUJY@Gl|u`}0*Y#B7&>+9<)s{ux!Ay~bo4@e+@+>2m$cMrk^ zbRc$jhu_!N*H<%og?jExr|z?y`_K#b*$tlvpgtwNA%H-8Qa-rNX= ze{>5HBvj2v^EtS7$hV6>1SBke`n4H+-CMEL9OAl!c}n#o%Oau2ZPz9k}*^qRaP zDSROInIb#7P6RDA1wHx+0-hFw8yqKzRoy!>a>pIYF3qnK3v!jPO9`oEsmYL6j{3F>f+^4DBjIS+)a2BymRapx2yO>8HTADQ-e^ zPsOw}9YYzFd_r0^aU@*@hox$R&MPoozE9}6Xd|PkTbGD#JP6r1RYV^ta?8yoJmMQxAXtt2+9xdg`Wz+CC zx0M6UiKCU1$Bf+uI!V(2f;UPOV&ma*f>x4LUCRZaMJzR)K_c+)T%Z=Q4-{#< zU}tuK)Mk;Aa@n=0-EGXeZch+wUJCgOA<$^I^sp)wt+VrdPT3hC2`3jcZ8?x{XfLj7 zQJlE#)dFAWQUH;bQB+#Z?&y`*8#F`^m0d|GLK;(mCE|!9m|9k3XeoFsMkTFkMmW0N z#}xEMwW|gLb!HdAb|}^B{C5xIMleW(CCK$H?0srq)5zcxMcZOlztovI&iG|W+ho?f zZ27B!AEJZ}YNT&V@e%ApB;A-?$c<#!XUGM*ZK;V_o1)0tr8yZHb|?e0&A@E0$AHzng~W)xb;goz$!d>5``RPe(th-n*lR|t*mMmyJI*j} zH413#DL7d^GoiMc89`TGBn1BL)eJM;!7IlVLadrjVT_uB3K>(dcHj{bwG=EOD3K^_ zAamN#J>u}7Vro@)S&~XS06J6a=8Ub2L<@4FIq@2{7wsBX(lAXpY(GLpn_hrH%F&7K zs&z_}d0)xxw$+>>pi?I^FKLKr;}n*;QXwSjnmsx` zgJ!afsMbz6L6@ORl@f-gP2wSwmZaBEKUitVo3gb}kZIF&5Uue@M%X{v7-4fH<%_1~ z+7r^fs6c%SLk(y<11#k5?JNzbbQwH2I{Os3s)Mse)A-UfrjHy0fdaR6 z=;_r%L|>#4;$XjNb?uxjZ;Bz_tFB(?$4?cVSe7=BK4xe(%hz+jlwITm4SfJd8BxH$ z-88g9TOte(n9e#INEjyC1Di@|0Vey=h9CWIkgx>{g#8J~&|EiDl2{0_6)R8a2`;`Y zsk_=vTN1S%^Zt++- zo!`D(3+o0#SW@T&wiSnf)g0`gl2G98#S?t>W`bPu2xix0>RL>gktGGP+Y2a`S_$`n zVbR>?LI+Ph`*1*I3y5zqXX|||nqta;dNe=U$2*|Sz78N)KltixoIu~mo7fLIbs=Xo z?(1$CeHWDlOuP77ggE**NeebCAN$$2?~1r>Q1C-cZZ=VZCL^m~OLOwvIuMstuDlr> zCC_8Sk|rkB+kgY${gebzLpb_=T5d1IgbOx)NS`Ce=YQFG+^J;WVQTQ9z92%F`wLgJ zcIFt5G&{I986*-fBT5mQIt*LY3xU63<;;$r;QQ+1_nig3g;772IQV&2-r$MRIt)iS|E4P}ULk@h@Vay;qq8Fm>fKtx)j;h-^UxT=)iSGxi4K z+J$dKX3Z}VKs1_D=aV4ReN>1wRr;rvkoXL!Vv-a@JsguiZ}y-KhmQa8=J2_1N`yS@ z`6W59Pf|M~zj!AqV0Kv)FhLnFkAdqjtnu9WUSf0J$x{K*0JTrL)bdPSM@nd@eyVcy zBVfT9A>(H(VLpm6L&DVjjTC8rwcrk%I#52!GjNMWvWh0){0B+}HX~T6fIVh!N5)~h zMHN!u@Ic<|Y#>xVocLIM-`n0%SU`dv{ShNvz5&&S*FhQRoUcsQd0^>kWv_8Sks zO{c&&umxgs573FJPc$b=?F7>9Mf@9VaCVy@YG{1C9gm`o#~S&__j_8R_LC(-S6}{b zNSw$1X(M9scq0@%c9KY(vLs(ZgWlG`NktUH-&+a2ZX;%*P+E5QD206wbp@dtBFRe$ z#CodD3Y(Ip|3`4pB2)#urvkd^*S&kHyQ%2S-5Gxp-O}OM30@DC-PBJJng(JteO0jK#CjiivvFz zw4dce*4F&nQZ0E&EDZm^mBt>o0pFJ<%r~%nY6BwsPbN=nzPt`qPQdvGM5wlw>X<)v zehG?44FyY>HgS#Lr^IQulA)pzeJC~I=F0}qqsa9S$8Yb4jJcy987Idh=n-eD$3xT` zK{53NhBTEr(R(^0t{bn35NHa~?=V+k2P#cSO2hg)B+PgORZPa(JYEDiUsWaS$><}3 z8S+6^&qqY|`_#}rfrGIwJATqF^d-QtaaF?lMqFI|1O|Uj&j@%VQS3Yn4t-S*Ue5*O zZ}rVslWF#3j`~1|@SV}|HwNuKtVf&zXRjSH@@I5SfBKa9wJ^rtfFh_2=^?FXH;@=a z7>w*Pef~U*#3~}bpjVRN;*lEZU~18MGA{OeC{xS8?j_aic3+wvdmD`rj;GN=Z;Ze{Dfm|keBG~-PbQ?x<0bXDlpypp z6v%zum>4%*5T0^D-%k9Bh1`84otRg!!;UrZr|5mXQ##L-w2>Ivz*jn;Bd_b1ue)GU$IDHXTB;2SR25lnNMMWr^ge zk_7lfwD2xaNgv6f=?^gby%b0PxAKverh=bMq0SQRAldrcW$>q3?qS1UhOM&<1k2)UWt z@obP*A2y_cJB!%z8AvO?MWTd0hViqgkl;69v2T=Gyb~08oA2&Uo65~5fz-1=1F+!V zsZESO3h*QgnP1^q;%yv`Vm6`jXP{L64Zt2YhC%+xg2XMjx?{>6s&_n6=AHb8RBjM` zNIVyxggS(4M8m%>NadzsHvxi}-+{+$>$ux;gAiE$(jkLyI`X569ouq%p5Da+BKyXU zkJ6H}fsAFaqNnbg0F`VTV1S!j7N3CGZHZlg>;clI3ZU_5QZBq4p0d{fThgyTprv?F6Xb;jW0bY0~8gz4FY&RS}e+@0GHS8_jAlQ&> zR{1`W_EPaGTu2Lol)WQLT5Kdknt}0-84>#kICE_CO{zfA6)2j}fmagv36b znydoF?IY7jU+adHmKy=StH;4d-ATYz8sXprvj;XJl-B^)rl-rKu`{7`$lLNwGdBE& z#WOW?uU~|^`FeD`lqx28B`#Lq&8mxyjuanB8THw;Q!Y>w`I&r*y-X&Fi)4uRafu~< z%8v{;0MOlc$r1fFN-u3%_q>{u$x>FckI08{mGmTl&|uO5{R=K1UZ_W_XV`+jOS;=o z+6=N1bv+Hcxea5E1Ud-3yoDmb&E$fP)h`o|WaY)jEf{p>3Hb$HsE-|yB8$Y+cE;?= zGfACZ3V+KDz*fRGg-f0KSYKppKf)oS0kX5o{51o+XXZpfPQ&+OYMLyo#wcC!N!+5+R<+eO);s=zjvU~ zCRUvJbY1P|fU;Ew=X*i%x+eC46I5VBQ5L^Ei_Kh#bQ&1DKF6eTsj z_RFKik#*rmZyF;9_DJIzMMxM8g59Qjx&m zRjhi^0ttH=Cf;And+O$?bg)*&^p964x}_EjL2v{~eg6k^@Hofr>Y&OJ4z zn2CE9cz9TG6(1Lu2LEz1Zo4WO*sAeWAb8lW9?TSzKzx@bUR#ak97wVWpXx=<4$y*5 zC9B$Nrs<-+lAwXn$lX(xK(SfzR_h6H{(^}+b=;WZwiNR~nn&uxS0E`csJx?@)>_Wl zGa~tUOadD=n%b$!k(d7r^V(-JOhFFzc`=40Hq+JsN)P{;b9k78O1P6yNW2~p-z+N2 zXu7^xUWR%?;T))yU(|p|e;D#t$Lt~fBx$a$L8B^Pg`Ps6P|~6<@jaL;Li7j^U|IBd ze5OC3fxaYG0ewVKPnyG40xXJSzCu))m5^33EEGa~00(wmH=zx{2)@7gCDTD{Y*Lh- z(Xavi0fnim+gtjnL9a;iJ5vetUSK5ADZofU!)Si@i2!XRBdrV<>Fd4}YE^5v0zM0` z7}_IH*H$xWUP=h0jfkPJjVRn>W?-_Jl%9zL2K7ZFYwW~0aicfxeChzD`mU`*6<5l) zLI;laLENWiNXun^~iWaH|`rJ|Pomy@g;P#Fdpwx?awy^Oa z;-yr5*hpNB+?1*QXPll*SY*i;Che2a097|(3$dwI_Ek=yFojTEeaTDwAn&%Hs$i|4 zF?%x{Y27kV@(4SW`B6Ke+D%rF$-A}3g2_M&Bn1M?E7*ToGh%b$7*ZvLh_@n}US;`` zLKW%Bi=x%hRsdt`oRWM^Dk!v+FQXX1IFF@u)0JGHSS&MqO#upB0t=3#jKJSP80kJL ztSH@(KBi+IjfeH7M+)LK!_a6sGh!;g)^k8Vi2}?L1Y6jik{D8@y9mX zHF^Vw{!2fw%@?NlXyP5^5YTLDt=#y*gntCJK~Gtc;0Pw;GmQwhs~C_&yC(k&WNg;C zw~f=^@yCX%KEM-sPcVP5h-eEyLy>A2FhBa&VsB>2tx3TjiKPv#Ck7iAgI#_z>O(yz zX~K4c@|Ae#Y_X_lhynZamorFgD_A|rbK}o@0jk_a+m zXh{uANY)W}FLWk092|cHG3z{+S8$KUp&Vlq`Bg#>XiWnI3Xx&vA&-D=4eTIAeM0)r zIiNJ>V`Hg~59Olf$_WnA3K$>{MvIAUBJ)dd6vuZ#1gb&nWFTTh|EHKRnvd_$kqz%T zx75&i@ZzpmhJG!h3ysz7?EF;mRgChqGzw*4LP`A<$ur#}d6JNAGQLU;RBhgn9+XEW zuUTkC)0tNy3A-MXj|(jWj1eIOEx)DDf%shf#9!^2<}U5uy78ANQn)e$Qbv56K&fa;TmPVIKY9eXx2I<0I?P_7VCH zkWx8c1cVV96@#7~LI_{6%~j0=1&(Ki>=*LTvTf?HBJ|CcFB}86T>`_Q=EL4cVtVc% zb0qxq_J|)o&|jQOkb;j0DoRtRfuT`#`%{u+?bX+*iJBNcC4-r5#)v#ei28~Qnl1zJ zP!Qs^_I{~ibel^hwF(R`A&RQD!D1p69VLE38n;5i_;$&_!&_+Us_C_)Ov}!{5czf7 zqzWv9MBYMLR=2iOwX&wePiQ^7S}jzwVg~O4WVq~3(6V7^kmG@*lGGtaPpinl^FaW1 z)J&q*x@UI}G?b&>8xn>&!0!Ph2<)~&P_@Az{Y+O{4yK56oAQbr5YX8{^@qqtLSwikYq zN|No@rHK*`&p5SdGCn?BII``XAnBnOX#F`Z_1>`Hjbne(`Y+(QS;_O&!o?y?PWpVQ5+yyArhd{^$9g~4Nz&d_=h0YY-_ z`cFL{TlF0jN)Enf)dLkS8`E{9X<2FAIN9 z_$%hG2!FNwt>7<&09k+am+DTRJbL(K{rq`_?oDUq^qH_-o|NW*zJ9?+brX z_&etB2!A>F>y`&k)?fY2rg5`|O`Gf+IC1K@zjEfdy3(=Z?-PHM_*=wZOMj`v!NPHW zUHF^Ajr$ws@0Y(D{MF&_oSIjE4Vab*BZf@Y3~DMGRn=8ie--@|^motS$}_20cYn?N zRpGA*e?Rz3`zsgbH0!Va9_ZYnCaL zDeA@jUE|{Zl5KH+ON6?=U7+qS_tX82)8hWx@N|D4bh^I@E;GCJXRByh!LqrTh0|X~ ze+&KX^LL8BQmkOz{cYjz3V%uX8^T{Ke{uMG1M}5i1YIEfZL;>rMg>uZ1Sxng1v^VW ze0^n9RNebF-6=?SgEUBYBOOwb(nt(BAe}==OGtwtC=KEeQUeS~3>`X1H;nXpr{I-uJ$*$QMT=V`q6YYV(D?Qup=ijpUM%ob>8yiErb#yv~6J zf}=Q4atcJ-dnUA1vB;YZg61aXd+e46OxdiU-PkkG9iiIU2aM%C6kU%#!-^fJ5QRF@ zT-bN|f%D?WC*a+f=_pM ztX>lj$7j?DL`WpzhlvMb<;n?0g^G2Qm9~GR$uxXb$`$eNn`4(0)qHa#10lV%*=#f5 zzUquRzToa%pWSn3gb+sLs4ZCdUGu<$K&WL#2Sl9@zRJh@L_^I3UzOyB+bKHV_Nf(k z|Mw3tBK@z&`t0aYGS_~QlEHZEsJGEcfXMH*jpT2b!JSIM9S~J}#6SOzUMD$luU9+V zPJyvO0^BRp*3tyGWAH`@;Yvv(^Log3QGP!VJ_-Cli<;QGuJ4F{`7e+^=6^k`i0z^d zYC6|Z8yRT*5A`R;Q)?u+4o{LIL^RS6B82Frkmj)b{G_I56mYv|lyCL6N{p)C3?Wwh@>-ewK;)o2a1p}j_eDYb^Or2|CjwIY1z zV7K4ybhc4{`#XEF2*`NWP!i;T$SOQFZS{^`Ln8x214QHOY!okYadh-S-Q%r?U*v~; z_$nt?6(=WBQd?Uo3k^xF-8cPo#UFjZ7WIonr|jqz%e;F*+R^K4hR3rv@<0s0+Cs@l z++mFLh)LZ2T3TAU=|lAFUM{X&I$=67rc9ttvoB*OuKHbW>@Saefs1nQ;o&4D=0I3B zZpy^p=IrmW6AS$=`}Vuw&d_f~(uhee5+-0C`_s#T(VqTx-&ilNSm)UTgxf-sFH+27 z1AO=CrG+OQP%_*3wark4(NKx->h`Vvv{DS7CVFLK7SK*Xu(?XW#0(HA*A zD~u5INIpP(`C{Q&+vPtR!y1Sb`dn$(R8fgQ?W@nNd=C%_1Pa;0S17vTQ@Z>Uyzv8p zQ&R?pb-4z>-i_L!mHL1nU!Z{jaB(XDInIwjE$i_kBCu0FzA%H^%)a`l4_urJK#q;W z279{9y@6lG7xHa%fxUxmbsLDhJcOWjRTe>R%QKyQM8-02wsBK7LQtA^Xl8|zbLFQ9 zJw7KPHsL-(uO-=1({qyosF}Kf(612hl%?>@^%dz#oRH{udEUIN#!sOJ6bjftfb{dh zvaAwaYT9P_5`|cWF9%&R?ePg$Rz}LZNSU5>hLU@looHR*Nzf-wV7zUOTw>FJ+l-WT z-4Q<#iOPHCYT31u7H&gaK=!Sn7V@kJ+udD+^8E$8n51w5GYdOrV#A>oxKziO+c3GZ z8w0*eX9++Ef+lYFGLNGt&iY({_N_8IJ57EFM8d?z$lpGf%_d9wC4TrHdI?ZhS4YPk zT@cQPBO*^ToOS`6+9z} z0AXR^;|b@+*ou5`5&&6G_Lr5uVr)e@;0Bk>njQWC!3Dz3nzs8_IvCrV7~#b`Ylz=R z3H$>5d0no~4y}kZ)~@-Pr5E*G=1rY`Kmxia_G=X!e&Avmddkom;`K7&bAEeX(>`MW z5}%SwH!-7sg;NWF#9rb98f3(u^sO+;xvio7>05cCa{|l0UZ4icQl+pcQz=tLM`K!I zF7Z?5{#q%mrgSQ9!ur&L^%*Yzihz&c4r?2st#5!3wC~I5l9hheKDzSM?0)j-Fv9r>m^N9KZ(Mqs0ig)YyyF!Z?f8pSF$Q}t9W_0zUr?n_qB4^mG zTd~x(5O{B|mB0R{lz_=$;I=QVpsOdX)_^dBv{^_S)Ey;COat7}P46&GbW_aO7W@K- zQfoUtlTZIWVDpZmacEgl5I(P{%GR_{d(-xv&pvpYdycc3JH6p3yHkjzHkK7v?b~{P z;Cb6R8{D@oywgo)yK13#i~BwY&4M!u?rZ&fCLB-2CxVxp@zj5NE!LXaM*2f1-xJ>+mI;1^ zTbzfFxNU80PL*<$`U=O6m1M>uk5zI|0hP>EvHf%g(O1E5WH#@NhD$|sB^k;ZZWGP& zf8i^%GnRMIjl2-%AuSA-g8qmV5NG4Z6n@!ZQOoLdO&^u>mGj_L?df0B(FAljOI_G< zKvh@|$5N34Mo^Lno^`FU}S7W|z|G9p-7O3ntGO)lQNcJa{svsiZ zR9oqFzr@QjE!mLbn6g^0Z|liX+Mwn-e3IyT?zF+`ReP%9zTe;UUb%C8lU7PEy3QkM zjF<|JCU_PD!d33V@(@uAXptzE;rvdKA*gBUNdLhM$I2IdJsTueI8Id{;W=x>=_6^y z)DX?0H zr9g|DCTTHr-9tSzcPKeV(iZj0+s{X=zbMZ3-e_lu%CAz~QMOQjM`pOev8edq?sDs|-U`OT7DcJe3tQ0Id|Y_p~}EWA(nCyx%zW$5}uV zZ&dKJ#fKp*cEpa(bN)7WfTTk&?*E)^X+!@;dbKvpZ z*VGq0CZ6Hbq*5;#<6bI-NBTr7e|+Hh4$6pQ@!6Gj>B0%(GKvaiu{2T0jS}cH-BoTf zY+6oiUtin!qNIi3aZUyt$n`p4m99ua2DVZSJk}iP$;dPeRvZmVC0SfmC-3WsslO{I z=gm}z5(hqGlj<3uBjT;AIff>zC1DYNj5GBTE3FQl^?xNa7h};URJNJyoGiaf;4-0! zn<}19|76$YK@*IlMAF8%tusCuvyCpR^cDLjf2oJAX(CAj1wA|j=iBQNKJ}xnW=usa zNx(pp>hl_eK55_!Lhh~%% z?lbG4;<0)#jnWAjP5D|15laY`L27P09+R8+0IE)8cW47Q(f$2#f$C(b`>;USH$6~R zscTyeXSVfZq_G`GpL_2O+UAPKd+uJyZr>nCQ72QG&%{|BgWyn zEUohE1Hw}^*RvqEqxk?!d%IJ%T~arBqxTr?tKBNg71mfd01^aVl|%dPG;@`>Q4p1= z!<}#%UbMi1*Pv(ZVGV0dt3fX!1()g%yn*C9zyvMr^4Q&ye9Z9#i-f<;-?Q?)>)Lh3Xay=rtn=?n@#xT$f(E z_m8rv>mjrGbKW6*JxZpZLzn9)Za6})fB{h)q|7k&S(F&NfZK4SEe>QQ*=Z<~j50Fl zMtzK9WSoa6J^bKnyjfcX-4CO)W%h7X>>;C^j0B^Ct9WIRA_jqPcOf~+aRxbqW_VO5 zD^Kda?Ov3NQ^@8)avbAJ_K)LOn;#OCZpf5*wkIVo8E~0|wsBtyV%7E9^PG@waj3qr zjFiNN;R00t*o0Gs6R!cfZax;D~M{`Y}Ap5x3e*ON7k|3{eRr zrZE_}C7%zY|G_V;sCf=5B%5p1u}>S!Vwz*xMlBnr#2E{rBEAYIEVv(JYol*7f4K1~ zSHrNCT&uL&grUWgy7@@?d)(qJT26D!cP+J=m3*T2n6Ur`+gnODi_poOnLq_T9rSQ2 z+EQG9<`TDsciSzCNO7n-e zIKp->MSDVR%+MLFOY+s!YfY(ND(Wr|Xm49Ot*zM`?3cq_gaec03|~AOSTDZH*l(D$ z5GZS}Wgs&KDM7?5L&9(^pI`AkasSwVf}V-B&OQ-e@vwhC7k=TXw4gzI4oJC)cHZ~-14Er)`&TXzQwH}0@}m7HO1WB_5g;D#ysrY=ym)V#iO zG9wQP7n(LLeK`>2@J^oN4bq5sre?kb^oB`!KbD1;y~Mk<@2-$LK;z`!^-{aX=aNc} zbRQR9rBG^@**$WfOH52S&QZ{Bw6LHb_63otG;|6E^V!}gqbEnZe@OkcjMomFx+)di{bIQ0xHsk|pOA2xhjowr+T9B`WUl*pF}0Q< zUKptWBP_tRI%jJL*SC`qhe#rs;KZC~xl*s596Cy}n{f0(<$Tnmgb!_5DL6x7FTS3G zhn1eNeV^D#-|Z{i30=|DPZMn38vQy&^Z}^gS@qHs6Y0>F8a2S{9Uo>6WB$JBBFkOo z#p@qkE;&bvD%X3kb=y|1c9Tjr>{LWJI_;_8%U6s|NSqDbWBFI_m6GU~(G&HV1 z^*L5!T>nsl?_lklkIYZ14h}>-b37TLX{5N{KPMApz49-dM3cDqG^kuI57PTkeLkFs z4auBH$eJ)y%E*y^({z}n5pO*mFBCv+$rg`89>{YO^n+f?pw0bomaM;8UPiOYyXcuR zh~K#s-LMn)x+W$B-`+f?zjCbUK0mB9s7PI|%_BcbmlgaI2lf{uN;H5Eb67*g0aK6b z1aK+e)7C<`vStx*9f}@n;cVGU;i6+j{{$HgF#6=2fEunvO z2^(Qp-uunf9N>gMGotv-szbt}+Ar-Y6YG2Kj26}N)`p2&t0#)DT+Vmh?cDMG@3TQ@vs(Dy?I$|0 zk-{14Qxzx&4sUu(4Al==Pg;5}ePH+=1LZn%Rc3j33$s_J7?O6^JX}8%IMxb%j*>GpCme#&$t81YazsW8d_De4@BS|WeW!0~*Y9z|P zngFnu{c3cq(!b7q3o{itXW9$jkNK`sm*!zWc3gbiF~u4h`-zg%<|ku3nuX2R;7?06 zgTDaoB=y==i&_r*za|KEeALT}1FSD-L=7wLaSoUZwZyBENXtEH3%`AP^=>F7 z@%ghZY>d7#fkyz6rZ&ih4fNa3Big!rkt&?Mxyrg2e*9v<#Oj^scWwHZF+F3dfE_gM zQC5HR{K}BMX$FrseC%_fAUpAocm^^s79b9@;U0P98qHT;FEK_(x0_c~X$c|wDWeOwbMuIb1twP+vK<9 zj+M{oEW!l$7y?y8mts^2fuG`ZX~L_Lk>cp}ywqw4oZqS{cU9=0xb)wIF61uQCKYI< z@_4J=)Cl@HclGx>bupqnC^u?T~oR`=-`%aL94ZH-_Ou+by*8_} zHoDKb#2aWLuT1|oVo4?vn{YLoB8zV`^!4DWS-kc?=<-!t7rx}?TUre}b`tc@f3z4q z_Er*^H6virt_!t(I!UoVCP*jo(&k$NG0jE)+^}tN!Js{9$x;Hoz`eAQo1>fGSc~h0 z6^EZ&CHIR0bCrv%g6{}wJm?fYz@Tf$eZ8zi#AIrJFLCla<5X_0D0_-|sr ztB~5Fe~0Qhd;$j!S)qTYX7v=pdybgma%Ox(y$~zhR>AH~AsDV?uZ^7nu{ntzOTtJr zqac2VokLb8kxAGcWnUllti>LW-1{4~0=>(ggGkh-`VcqtrRv$Q4CkyjiDr(fwEV}p zlD6f#M|&dtWH?lSk+L{!T+4b@$mT*VV&7gVL5EYwYd6&)3GYm0kv4(TbTjANcbuIK zXp&SYETcJ0dD>>DGV7_#w<6WBmT1%WYh7?ZGm7wo>k?jDJMCsSY6xUx!V+m z&aX?%IP=*fbwYkTcfAoO7GGpAfGh^Ou!o^WC~4F{0mX((2xK)ThFfR|#?*9tb)daL zcRJ-DPjP9%dH14^U@QfHf?z_ej?7uGgQp_5W{dMVnrF@03H0@;=3okaBz(f8QeO}g zh}$%=)s*nf%8|(Ym@G3TVJB;ctLa&{NX19;4SlOJzfg$HV2sIP&?vTe%d8<|bCZ_J zew~GbcC_=1*ZV$WQNn004Wb2t8hO1J7B9-;<{s7|d`4?I@$uXZwvr7{Jgo*|?VpUH z*?+1wzA1A6CyQ8Dsz?!Zbm;-c8Q`iATQ`Hx_P$c+l@>8WA7T&25A1CKQRup<&JOc& zU$`Wjevy3;#m&=5!f|&WZ_42@)DDHjy^Lh5p1v78^9#p}tr^~kiD|AG+o&!JZ(3`q zmiXeQW7+ENngymG&!ktz&c&uPh0_W&RcNe>dPYN>b;R<@FVOQ|*=~?wf!^_fT`>y` z8XVE_Oa+(hUtePf1T`@zRWv*It4!s)>X3d@;VLgu_GT&K{4*wQ-N5pLST)L?_oqF5 z$&&9mzZ<+{qJJZKviif_kCK|ww{4OS<#(~qz6#I{ag?)+JGc}gzZB|^p`S>dJudH}zq;-u9E;vzS zzO7drEPK&-gVjk-l}j4Wo0_(a4gjAu=S7e>3gFRi2AO>?j$hN~OZEk#St!d<0SqX3 zqcNJ2PGT_Yt>iy zWywy%dTPI9de;A5Iye_m4A0-K?+@xT07Zt;UrT(n&`Qqv<}L_sbem*Q&GCK8Kf{yl zdRpaZX$UT<&LG3r#G#G9_%gqi20N{?hLe^E>I6me+%j?jkU6sAe)QpDHpa|+kGQ8Y zbjYH4XTNNKQ~qW5(UXuXTKHyy%y z>Ja{)#1XA@rHggGrSmnurLSMF?9PiJ{0mHx%c-z z<$m_y7L?56gtg1ea>`yFe}2cDcq)yE#Uc@{U(b`O3TX1-#nS$7Au7Dhvm+0Bn2Wne(ho^xQ3^l-Hf>Y zPIg(avq=!sG0qgN5`8Ca_jVyPvKr>A(0HS}(^?D*%wN($(#F8>YQQiP1y!TlqyF9c zkhA%1DX|KQA+FR9=M4G@_0Vq`+)6M9B1-&r+3@8mB z=MR|bfH|@UgJC@SU>Juf820uT+*MHoNt=w13;}h($^sFsD4GA zU2Y;Xguf{k0pffHixA&;k)u!2>(rV z&WHWC#U*pXZiBD34#BT~Y#km$>aNZ18wZ0rRINqSY|tj)9^BR;h*X z&p<<*v!Nji{DMlG$KN1YaRrbev2e|WO~GCl*X3}k%Oj#LSV&2+9kL_Ib(dFcF}x?M zYC!*a#se6Jg#tevG6utxuEDV6P`E4a`9gR*+n<6>!OhI=kp@4;8$Bju#~34WIqj}! zZ&?O$&cTSZoShHfVS|SEq--j%5BQdHu7Y8&8A7*PoN~1C%9Rup+ye%{OB_lIb`%qJ z)g?wY&L3xM9ApTIlZof0Gph3qG=K<$oBh%ybR(A|1 zq3f5UT5NIg07B}#Q|nxR%Y?B=LHg;K%YeKef_7^GdF)_#-!_I|dIvw(n~=-vz!^UR z&gWw~;|LV2Zli@XZ{6C=ze8(fsIyDAE4AMlUyvEFJnBqg^4V#{*}&7YWlwE-n>#Jt zkd3`k>s9AifDwEftOX1qPVO4Vz1b5425$(ya|_7(Rs{X1n7txV||jz_F0B3j%ui`lpMIuMWq3a z3|CzMr_A}CeMdJ=5IaF=pEI?AI8(R#_mem4f?YH%)LWA_lMc9pHYI=7AvOtz%DaNl zj(bd)P41@AuHfoOtAF0gR>xSPJbar^4(=={3*Q#?L$nb6pht)nrZFJ=h#34|uKnHc zTm$6&*#qPiba#vucq7ho=@6o{bZ(;X?Oqx$PlPDBJTPR~mKn%)uo zF$2gWorP~}`sb;_;M*b^@NGrP@TZTTbHkmfoP^-c5-y0dEGopApnsk+67DSGggB#n zj%dlEMEHFeut8C72!hDTqIq=jW2O@u@l{yCaAzDQCGZ$YlLUASw@v0r^42>i{Wjhi z-?s%{?47L%e%trU%XaG+Tj2*<66SV=9av~W-^wh^HT%&)>152VE|${AEP=F;k6rhj zbp{5Ftdf2oYyh*uaj~m@aD%e3$PTv)g2XP(e_KT$kLyHX1Q} z8^aPC;WvkggAk3zCaEEz(TcK-a=QL+MWlKBU0sEX}?(oqmU zGaSD>Bl#DYfILk37cfK%CG1yAm*-GxbJr1eP~OByR3qYSiy3G+o8AQw?Lc>t3#ab!V{dprdTMZ}2$Q1;w`^`Kz;~Sg0k_o0H&ZsGCK@ zQ?492c=K{T=9fp1Exa>Pao#26t2lMKn7VhmOZj$_t)DQXm{L{JR&+SDKxcG z;~COI5EOb}4Uzx536W3pd%8c{Wy)?|XZoQWkWR6f1BUASwg*GSoccPT@8R&x5jun~ z4>2;B=ou3HIw7>^%Y=Nwzz$PvLkILN!HT1VsfDpCPCK?$j=OTb)H>6f4^@El@9eL@ z(5K^DfOL^yhJ*q69t;Zqbg>#5|Mb%uKsu{77+PwN@XaSjoYFyq7{3iQdoYATo72v<~NKoJU?`7lbmD6HUn5Dmm{kN!qV5(Fdv9S9e4+ zT@E4gI({xYRPOa!RHz*HA(NPK2ei-vd970rn(7j3Mn#nu71}MZ#x$1cmrh*?cjPxj zobo&cBFaWX2BR6z7-wdOGJF}8_a4|{va|F{SN{m#oZ~>!kYt6{1#dCE5%Ej^IjD{h z`Re#u>Zpp48uTMB#^dy8YrLhF<*?DbMG%S__LV4cMDvZ3;-N~8-zd)?aZm^0I=mQR{d5Uh=*f=w&#P+Wr&`LOGY)6J6#2#G9wuZaT0 zDCoZw2jOHOSr^WQi0+I$&BP(t#z8x;n}6ecuf^-7Quj{CLGe-y z`@)oeYjS6h ztTl4)X$HZ_6h}e5vaSN*M4Xg9<3a$+ARs-s!vIGj;)Hxy4Vj-f&DdTs$f%*WK>`s8 z06ma(Lc-M3zz~%TqRuBZyMC2kMfT{Z7{n>rGoZz6qO50iqU`-Jj1i%Vl@4Rf6?HO5 zlx0}nBSA{P>V$+SvaC2fwS2%zNhrVCAY%i@AfsUHE=gC1Kj=oc6Joqo28LwH_<R-TMX-NKFOX~$`j&%MY0I6P|lMbU+LQ>dG}KZ40&^{idRpx8maQ13-2ZU`P%ge0>@daYBoUXez3cy~jNyF(~i@ zsS|=BwOH_VsS`Ay1woo0sGQ-=jt}oXb)=^HPr&jsg4=??jLSuR8Z=!jOzeJDOE8{9 zOnNTdfx`l=2#dS_m2h_N2Nd0aHfo_?OVfh1jJPIF$B_IPI1!U3SDFtMyBTsHm{Pz z({67GZ^0s5#{VdGe;HX0jQy4vhvs140vf%!((!Gy*@!b#fA-a)>TX^cvWRiBndQNiTG9DWM9$d5 zTPpTuyEAAVpW@jEV8&_g`Q7mcx$k&Pr#4pyosr6pe{lglC*ViAI#S1hFQDHa|8#?f z<^%>-|KTn(@+pp#hBcppKN?5Oa*H~e1OrCah^!F?6&(D-j-SZCgsrSziO6Ti$sGnb z?3?KH8SrkTIpWDq@B@_bFT}nu`!_4>{k?N^rBZst+dOx(967LH0q?QWnVJ)Zm)>iZ z1V9gIwy>4>0oT&0$6~26s}E>Fmm07{M8*p90X2B^af7O1<`VnXa_>5$4RI2-e$TS9 zn!3XnBUH!yYJFQ0VbyalZ#vf-d3bx%R`LmDPh2xAPAMs7uKSnX zAJHM&6B5GSdDu9S*6Z+CeiN8;>hOXL{V#t3+6e(uo1`|EeH%tBs(KIKleboC>itS8 z((wp)CsZiir0fcBjN1A>a-(I_jteea?=h)e2wL>%ycyZ53pXHc#D65*>pAOr)8lxb zk~qeK;sf;GKF&&NU-R4sk(9n%B)aC5__+-8-i-LFXh1=Ei4yE#U1grXdRv9Wek5$O zBlJyz+Qp&v^+`QX6s7Rg;Z*A+cy>7v*pYUnCJmY{4`auZ*NWJ3C3o0AVGpwv(5%J@ zEXRn;yD*pN_)knE-AszyepCUVnSTpkCR>_+UgbyH&qB>*6H&rN*Lp?*}3CFy{V( ziHY?ZmawD^SFff+x&8L*N}nE2nCo83qL1X29gDY(}>siJdts}XiGYMv%8jGBblupm)AK~jjlJY{{6lY zzYH7Aq92Sney)lA)&!G@c8@zjdFpq(!S2!Z&Q-}b!I#xO_wPCFIJP~0N6#vhvQxsOl z-Eu8bk-ASVx{U(7>7gIG42+zrdK7QmRa)+?KGgYl`&^bgBS>lM*i*Wn6w`}X^!kJS zw!ZcGYy+}j?rK>ha%;c?(U@NZ={Pm#jxQQ7b$HACT(PL-jP~1u&(zJ>al|#3!Rzbm zmAhEhyTl$G;8MUffKK?I70|zI!@!L`FSfHcgrTu}$c`xN^X`REdU#6PBHf#NXeS&Y zlwYFg7NzKhuq%H7On&H=5lautA{_~H?hUJ8;H{7`pxWe{Gn>)WA=R%VGp*g$+Wk`hJNfZmHNN1 zK5xCfN!-8nYJc&gR`hFhB96I4tm;xuVin)HTY=swyrZmh{LU=$dLi>=8lKEy&8Kvp z4}qpb>^%!I#v$yju8dKh>~}kNPD$Qd0NFzxJo;(lf2B1aE=WJ$JT%8HYg{9NHBZIh zXgR|zF!|N1eoktkf5=>b78!L$(!X04E`Mvkgr|B(Hy?dNyVv_h!SQYa@}GmJ5uWq29Z13|JnwJN23C+}k=~ z^_8rT5RWw5GhtbzymQ{{iT?L?75%Ovbu1|ILl4VNz{HDkJaRG_V zR9*{r_h1S8Bv^F|>8RgfvZHwwJTU5SHMs5=f7KonR&gTHbxmg9xVTshgY;A1?aC42 zLg{*Pg8HNxU3?j?LlkJ|eJ>8I$=u7yZ)?jX*)<8jwXU|VHs!C3{2=t{<`FH^R}Ye7 zcWeS!1a!3WFgl4>o1_=@6ENhfBZQ52QQ^)x@)~}qiyTaTtRen_&6=o+gciFEDGjU! z;0`Ro|9H04Qh`#>r>M;y zs&Ab_!$UjH=261)-1MvcxwkSYuLDMQN`Ir%0)VaDH;n&`Qg1=`cxOu+%sqTw_GgpQ zjg(hBVs6i0w*Ky~$Sq$t$d*|%&#RYS9h4d2pO35n<{U{eHK$4D z=o2*v>6aPY#GVYq5D!(B%`q=4Mz1UR9^TiX>}$pV*Izy}-p-E&rTH{5I8nY-+?ReO zJDFa#De#K|*F1&$#AK4C+pRx#qXz%0W>D$dfHEnWNMl8s3sLcV_ZiUrL5n<+-U65Q z`)}AqdKTj@``&fJOj7^l5dI0TBblv5Q+Y6D&Mo^Lw=e^bckxp@A_}A>dCX~3?R~#I zc}kocn_98MEwAYgy&(_iRu9=&^Ekzd_(dB>Ef8$T@KX751Ywd&LaDiHaDW?Yn~}c2|HhYS|3KVq7(p5drr|p({8O4G;)XC14KKpSRw| zmJ34GOS6KO&R-U7zu0VVef~mzOD41Avuw4d@D+U=rnY}dAr&Z8c|m1I=a%UeD&$Ct|W@GXT(waL1r z@16Npnw-$(A=eCl+b00D**3JO-=v3>ddeBnH!A{V!IyqS7lbCboAcYONM>7ZTJa^= zDd`N!Ci|y*s+s7)%OOR8fV;4mb=Ewf?d4b{N=UARhySP)!dMhWi*Yx95gR;oHgcMd z%+|%&*#*Z2fKC&2dx(9}Hr}5yS?kb`6A8MzF?eNO*8HPR=k~z7+I7Iyv`vVPa5%8< z?v&d?K@K@$aqgs1%D)}L)UsDqWHP`#*SHOw#4ZUsEp%z^E+KP|@lcBR_y>P*Y_^c9 zeeb6TvPKIgY1C;%mUiDg126+2%#=C$gOxKPbV#yE*~~d)x7#p zaz|?;W5QEHx{Rsjc_4UXaIw>ry&_amOExv#?d**f?z2Ve$G-2M`^N#=W{~Lx{`A}4 zli-S`rpTvNgfnNnBlB5O4d+^OlwYKb)_+MF`qf_8NGh%bZKS^|^vTB^`d7WM`@BbY zg_%ZvhQF6tSrI(*B-f<+SXxX2wfjwbPVXZ8U_l3# zGy#`=X{7E*#ETY#yBC;v{7Sf{Ih;o%z7A6*@jAUL>hfksYw{c3eoh-KK|wzR1i#GC z4_A!|e!@$OS~_*RJ|zYz*Grl~F8=HCUxVt)Ma(ApK-D1^(>oBy9&ZJ*@om!;enK?lq@7G`cv zl4K!Ovlc+azN?Lm?&o~{m{ghhN$5|{>Mg$e5Q=7{e=H9(!=Rmc@I~%%s*jem6PW|^ zknCVkM*8*ehg|NnhTOX~!vp*N74}Yjko>Rg{Ks7Mzg^%x+Gdjh=%;{x7pZC~0hez+ zgZAP(13OR(2)AH^y$6p-vx#5rAsAe>G#G|;nC2~tzXr}6HTY+G(jpOs&8e*0U%Z1Y zb^y2B;*ZcFnc3oNsPkp#CGR!ESO|azD6BM(vIX=#zc7d}NR!H6#b6YqW7rbz728N; z2_@6I?%x%Q#<}}B5(|@+OHW;Q1!!{WQdKlI;*my-+Tc)j8`Akqy&rbq=~n-WmcTB| z)yPJt0cofsRl*}y+>3kKKBelE7eTD-QAAkJ(v9gH4-%Q#Zy*GJe(Ii-veLE4HqY0vT&H`<4-kGO5_4PP4=lB=( z_9Sgs%QlBruwCZj=9NJKrhL;|hhfG0};IA&I6OnPShoF{7EzxhWHz@A9=23g~YtorF%P^NPk9hPZFhwdyi( zHXg69_Ad|p@?-02#t4`1bV*kZR1n@pHU9|BS1LOftE4=i7rbOw{s*^qy(qJV+7sk^ zDTSChpNdd=Dc1O;6ZKqlocP-KKbE3!VcpM~|E(_77w64=cmC_G$p7V-X`S#f=d_yi zYXq}L>UMotx$oa6z=a5ek<`rM3`j2QYXbb(7a|zr#yxA53HE#&8e^PNLZ#iB2A}~eO zhP@Dx8O8W9tk%zHyLsnc@e3(mSm3wS-k!ol>PEu6<=NbpYg8zvCaOwy3VGWEOT`V@ zXMhs_WE@XPkIng!HBv|%GWf@=X=085nM-YdhhOin3vhJwnIvtz@V}kJXz-v1AjVE5 zx!7rmz4~TDm7kTQEW9!f8S{aLutb>e@(D*Y9IRk3fsK>GopV8WGrN!^g|mNj_I;+< zk5*2L*KmH(($@8+gfAL}YcC#CVw%@Erjm2dyGWQ_5=C`ejco$GLf)CG~eC|al{>lahc|`jP44mmN^E;z` zd_OIEZ7m{S#H1UF(BDs2$kObQJGbKUy104c5g-ZouZG2Mn0l#y%6ECR3hQO)P?UH+J$#UcEX{oMi?`@X5ZeMv$$fJsy7v-b{K9W#d+e`o?VV)j&%+ z`wN!lb}gVW@Wy&y{c;`SkEKV1CTyPMphq^M;&HCgSgZxtz7gNX{zJhGof3SZjLOQ9 zr@h+Yagy;&OC=QRp{*6uu^v`%_Gl^~t})OXP~?3sU37X)b%Y}A7`N6?5Hkp(ll(=TEoD? z2XzOkhQNr^?vu@fUDW$q=KD2*U84UZ z?X80%3)1aD+}+*X-Jy_fv~g|R-Q8UqcQ34Qr*W6Y-Jx-JDBNLt=DnFWvGHQ}x3T|K zMcvBCbG~yj?!A%U$$)H~WY*Q?aIfKyCRfCDSj;Pp*%FV}_SL1Afs;l=^|yd@!t z%c+>EB2pG}Bq-GuaMKosv$z7hS257YW$|@bsb*&K1V5s9l}I_r!^!25+V>)(Wi>#q zzK>FOSD0G+POL~U;s;t6HY4v;Evr%fOnczpsLyjjZTCw(%_UNlKhKzk7?z}~U0m&; zyHl6o_fOom7yEae_NG^i&gSWk^OghschdyaBTCfVezbGS$!=Jq%&J}^dN@0U?UnO5 ziTU$I!IT^NqaZkwzNKQ0|EyG?6~Z+Tw*`0XCUuU_N~ECGVy)h`_9Z;1f~bGj3-GqRJ!CZV*#9ET{cGwe(cq$)faE@+{g+0 zEK>th0Y9&lxXNZX40aRg-1Z6GH%Cf|^Z2pxi(}lT?sL4R6RK6YhoWCT1NIw&&kZ%e zZs-_=+4tWJI0Q!(OsN}^rg`O2Fvjz2KN)?wTw>wEO$BT3)1Otp=p>#Q0be@`p(}+IG zuQ>1F1;o@Bq$+gUzUSk`1|MfteCG8S0>Du5U_%1h~veIF1U*FGfrVRmi z>`xY?aBqnL;$B*DPEno7ZN4dw5a+x7s#EnZzlFg1v3cJEJYGNVefTp&42;I{&tBhZ zwisfrHzG5x5FN&0&z_%JpI<^F?D(p`Q>^4>=Sq?;tl%M$*+KTYt1l5tBtC@9B)-dq zAWqi^cwEmvZx?7-hX+*Z{9?Ucp6XonZ=L8OA;;dK-?>E167($#J*+kyb&~Wdh7^W9 zIOii;BMgrf$JFJj|KxS=5&#r|1$6fFe_S|Jckk;~-m<)Ys#JS$ zoIgMNrz?U>KPP%$iv^A@;d5udR`GPqoLMbdD&VB}_D%Pns0SEVYS(3LC|yNdq1GH-RlzbDd@6fZGHdhq;^?+{`DO;lk+2ouPkA) z`orL!<{^4I%;v#nTrYHZvp3kY9R8?F)Yn3xPdDqgyM!0)u=}3pVAapP&2TcKX6`E9 zrjg78ZqESmcOqJ%>lM!B2+b#cJBy%7ZJ3-_=g!zsDG9;tQGLhh;?d%B=FEemptqVK zb+YGGYfs!K*`|k}1n+O$dlT7GZkm@I&xw$BmL{L4q#j0VyVETNY(K3 zS?g53XfuO7d9%aP^)&QT8+JR65yuQ{|LrU6&36q}7A#!-%gYPmd$5?Nvcx~;_U9+f z+H1B_lOcfgF?EMhu9I%I>@+DKZ~{UkXhAZdI1LFFceSBB(a)Tmvg{` zl+qF%|L>C9#{mAE{ut~f(hril8rRp}SETuTcn;pMS|78Vo%qHq6+QT9|494c&j-~` z+L{jOOI3m6zN7%}%}kMLHB%sgPwq6fffgwX8*uO_VpZ%SpJW)2H>d74^nozL9a~u& zM@P?l^a4N%U(Oby7#{jU-tNdsIY*#i}6e zK~*@Mk;nP8h~M5A+V^}4eBv9Hq&xnyfzJV%8W{ZD(MlRKF044ThTc2Ah`6pGGCWAT z1ddjnaq^kH)>E4|enK>Xpc99;e&o@iLrt@REceuHn1`A)=6B|W>a%Tx-D!iu*m`^Q za@@y35)wRN7uZu{tuXAE`R?ckb?8pmg^ZV) z(Djv#oDVVWCuXSjX4JCDAzn7juh~WvMDcF83cg$qN~-$QWBVkK4<4q3`+Kk9nR`yO zMY{=(RLzF-+0(LR5Wv#H--zu&PX|O=1^EWtt3q|YN(bHL7bY9AF?HTddaY;c1x|9o zU(*oU{@PY`^j^-xt4IZ`7!mJu^-leoQjM@1jm2`lbT~Md`_N{;YBosMRS0Qc1j1Y=dGjGH(v5Wt=r0+ z<4C7C%SE;O6%y|=oXDmNPjwzXgxws5n5VsUa3Chm@q48HYev!FV9X@RU0qFHy9ddB z#aLjGew>TR;Vc_WXA`dLU7Ky$N*A?`H%Zx*wE=WeUUi8_P?eewDPP-_MA7Xb8!5U^ zH8Q9Ap@GLmd-u|F4jRgq->LX^sBO4`G(q;h{TEnqd8mivj)1t#(5~yv@nxH)w0ai? z0(;nL#)3mV`&qE~5q&!s{D8gtz2#N=T;7&kh?Bh6;(d(w*f!3SE%ZZF)kNPV?Ld$9 zL{CUI3zl}YsT*cd=k{d9*vW$UkiKs2k9E9^*J|krP{V3zpkrZ67Xj_hF%HZ{29ScTt#gC8A z*m&dmFetNp9w{Ky;dJv8f%6%aYI(K;@6#{RCT4oHH0kv>7;c+?>o|#amZC5JYUxhQ zrD~u4MO#+%<2A&sj3>^Y)1>HW!<3rb~`lEifwPlXV-p z_{WJwW6q%nAuW(5%+v6Ls+7``ZyTH`=uylaT>FAu_YwM4+^8Nu1@mWpT>J$obrm%! zXv=dxJ^hF`Kdya-EP(t($&A<*IajLW2WtYG?LMP`+V4`6GJdmFyzL+B>q_z8(TuUxNdE0Jwdz)Yg)mvPIutZ=!Nv$moty9d^)0=E6oQ+0K zYchUz_@4<}hjrp3IqvvddFnpDY3Q{x^i8ZBYqB|%?>se)u42cH85vfQg?WbTW_w5P z+1HRg`{i`dqNRUOe0=SSt6NZ1!M)YOA@!{1P=4eYE^W97jMeon3_xnhz)bM`b-@~n zJZS{V{9>aID?*REv~`X-iesV$GEfK=v(;BUKaUe$pFgCvJasp7!Q^!Gc!>?q*4|wx z$@vcZ_9~K;smO=sfj-e=G3iFe;z+q!+Us5uyX`XvX#P9AsOMe@Za?z7t>?S`)RCda zinAembe>HBeBC=b{aAId-LxBH*X=UHG**hY{p7E4#`pvxVS`peG(>KQK@yl#DRb5h zmbb2#bsfd{5L)eerq4tBi*D1}gTME=cKo~se~$X0!J=xEs~%E%*JA3cV75EyfN8u= zw!ZMiLE=<|mo0N~Vx!_A1cJ63q41KA(J|f>aIf#;;foU zTQbCt`%>pt;YfgiH(zDG3jcC9<CImYW_4(*k+y zA)Xy7&{r4f4oUPawr6qsj*w23JdC?TsV@rw&@F9id#A7BY9{1YNrZ9ryt%UzXZpF% z+JP-&3PjlgW0`I71CG0k7LN8T$!)V$pc5M79d0T46Rf^^qqyWF)Uyqcd zK!Yl(S3M_?a{N~iWcWv<`8JW72;&HfIr)03bKD(_kfeC6kU;(X3z1DvyTs|?Ro*Oq z;=1#JM6$yH%vM9wy0$HAi&5-WNahi*cbfrX4)kVl{5t=pD@UYq!1+tS_3R*lxqidt z+dHdNDVt%~#lRXQ_)^#v@iEXbi&LV%>6eE;%UqO2QN^|DRGNd z-~xR7Hq(Iim1^Qx1p7QyShH12krgcOZ0wDdi3(@#`sw8as#DfHMX|4w#%+LGpp?6C zrTRLn9j0tDtD%orB!@B;VIPi|#=~MrJC8G~MIqzmug__yF?1SSBRv}5E#5j24J2(T zw`X4;-uMP|Bh=&zHTXZTUj#Z|O&%LxkNsTp9{i=F{ZV&|s=XfHTbf7igaS&0=L}>v zpFy+_t{Zvx?I`=d)#4vU`zAglyL%NOihtKb`=Ik=|?x`;vM_q)M$l@@cI0p0`nzx9O> zdw(gf@iwlrc5wm5bSzg|vb4WKZ2$=aNYxby=PxBl<$;|dmk!ycIziI{5qsZ$k9A3O z=b3Chg;gr9=nyU6VrHZa>%{MbC~RsPEN#YjzP71+WD>zY@s(So~-uz5goUSP7k_CT7^ZvBBi ze7J;4!sh;sqn4~y%2w~8kGS=Gryex|Ae4wA7Ev@RR{Nzx#fv$Yhubk_nUhpyqqbyr z=Q>hDsU#b1fC_S7N`Kv&+t@=o)N&t;UOI1@HCDq$JJz@r^DZt(LtRRU{SbF zz)j0(gm8>h?kash0@l;d3oXYECH|;{|MgqwD?G}R4lzpS1NuW)Z@`S7iTp&zaa}IT zE8nh%wkwjuYODr7%t=sAWRvrC%<|C)uk+p|rZ?eLcYvC3C8UW++=pd&+RoPf48tc` zK=1ILhCR^zCFfRtv*RsveY0|!)NOiS3p5P>ftK%y*P~lECY*tKs+5yzbF?7>+Z_~r zlxNv;zxycFW+8<6>?AskX-TBuVo-I1JQX5$B7;r!1m?S8ZF=L_8fK5^7* zYgNmHYef3-P-RZYo2cTjcAM|ip34GZhub53Tdc4^YNnd^9to*AcB)?ZrPGw`_Y;7wg^Iac-VS=rQ7=sjQ!wC^>EFr zeYbl950`r&O(b3d5zbk=8LG7G3f({EIH#JDG6SM9jkfsSp8K>)$s=~Zz0*D3_^Y=W zN_hYB;6}IEjhq_BwBBps!Z2XSt4o*HKnT*jpFjlR1=wFB3_p|V8UIPg@pY~^}+bP8CoovjW|tvCqPk!7^mBRnut_d*?`)qR%( z#p@h!Nak3)svH8hP3y`xCT%^c^4kcj1TV~9PeH)yucOCDoTQ4YiLzT~N{)j`E%Q}m z9mp}?>^*g-7bG6N-+Sz)x2(=@X`6-VXB{?^tL7Wm!(9#U zA7Xdj-}cX#kFdD{w&&-M2HN>9fZwMy5fnucy4CB~W#iA7LJ}DD$cr;~rRvVc>0q|@btX)Sx%s472A&tiBw3KtPjg@zhk=rOk&BCe z)uHHQu_o104g76Vm^C{-BR?RAXD41k_~}N<+~{05)o0(vp26Ys%+y*$TA`!CTg9#f zg@Jr6P$KQRt;3C}b2sI9hTMw$n`yH5L@noTx3D%4YdL zR=$au1B6@Y{(RFZ2POsMa+3G8$keM`tADk326ro05sR9{X5f#Cx6=7tsI+z-6{})s zeq`m|$%6%;r>(CLf_k8F*TGnkKxKiiA=1;c9!$aN%s@Wtw`KJ>R@JB9CoxWxt3ab zGpdt>gD*fBsN(e{2q<FHH2UdXy?@5-wfG1$C#$upr2T3mW768g3TAA3?m}btI5JqF+)^ z9T6qU4R!}l-?u*LEZ&gsh6OEWfdXHGMBa7^k5!S0!lxDKNv#jEb^`30 zWWNQB!ouz8B4my1UhtU_g9qslct^E8tiJ($@OVGL=f z|Dl%Kr^H2HpAtfd;gr`E* zBs=VAg<3`Q*#Q!YaRw#%<5DV6dTuM3<#QbrcOI4*1wxapd^l`C(CMktZ3AH;ls=E6 z^4d+o>NcbscsWEpcZOM@FLxs80u&dsiWtJhECC=Y9zkcYaPCayi)$U~aWjG%?F&8p zlNlvT8ON-eRYcj$0IL?3-*InF9ifUp-}$wPp#9A@{R3){QiO*AF-QhRViT_~RWIY**|`nie^nRYg*Y3L14umh}9&K1FGeor-rs`;S6ce$lVd zx^oOcI(JFHBWm~7&*m{!XNii%%>2*?%h_V@77_cS9%GK&Fh;kjKYh_+qJwc zMpyZG*K8o}IW21k$tBu%#oayd!7A3OBgSI1O}QDF14rh0_s{n*6hk0lgO>aD_s73a z%$9}KlQCq?>yXtkO|?iLV}BkTFK+<{yj$6k;hQ1_aXna)u9sSz{!I&gwQL3&dGrnj z7b-3ZN^y$-7}`z{73 zcEJifC*QH!p*-$Y0s!8HZbOPa73)q`*%ihdBH#51F6T6vQNbxeD57?h-_ z$kG?5Kxn~V!o9&|u(Bct-3A`72!K$#{+^TdsK2!OFhb}t@}zJW6R?g-cKl~QG~Xy- zg`aQTG_sWww0_|fMMRDc`2`n`ngx6PVb>kMQ@CzDW8hpTM_PFsa|Iefluo;sx*=tB z7pEPVuDU)+^lR6-pU9q+rz5qOB@4A+WJinK3deCKyw2kRq`yIr z*d%S67iK87@IzQv+LHm6@Njl-YzHaO5ek#A?g#cV%F>Gg3mbvypJebLRr_2uXrd)Y zoo$4Gx-bdu7@EoAkomei$M4%50K5T`s%=y%%90uOw?maO11%O) zDM4v&$Z1&D1uA>?77wU;V5p+^fz?nGks&M8(lLe68_D3A$csLqHm{&!6M0G*(fec! zBZqmE^;xpe#o$G#>nienrI75*0O8~C4R(d@@YEkxhf+fKr(;~ILd&%!IbxA|4#$Sx zUy?|Apy|7ivO18j?>^M0{7$_iYERTcBb7);!H>A!kF-cmHZ&%JL3hPTXkNl+-A@J^N z^)eVFqC~=hiPTDmpxZnKPXw`9Ex{XNR7m-0Brh*(+skgh5DJ5I#35D?&I~U%s?cDq z5n615UkxL;Tk@!b(i{qH2KdgkX3lI!5$$A1!8euL;YD8;Be-{}6~sH+8a)thA7cX> z(V~mr5{_UC6|l*Vr*;t5;V5d@U%C4SJ?NdSOb#Nx-`W1hD+LtLNmCcsK0}o#8r^dW z*=d8VkE>>_*rlj-K9Wx!RDie(bPR6OMSr}27YPPzpsrwEIxpL=4F=-Z{xR#oW!qSE z6xQWBZ!3_1i8(IOLwP*cmKL@wGdu*(a&I-qRB1*rrHAE#JApwlIr#%qrzX*^Q8`GF zkgpBh9N5(WXA2?MtNoohI)6znh_OGE(dZ0(H8w#MsoyXEp4)w}p`T^touRik2pmEW znFX>ETEE365Td3d5TS2L9c^1QI9e1z?u-O&!b5!Q z-ta?xyyG1x(PV3X)#RRT)2Y#GWu?#LifYbD4U@RPDwd&eZ2ZS}RQ8I*Q?u%yx@!3N zS!!yy>asH9+SrSu+H}fIRY{>}i&$t z6g2u+!+DUfSq;zAMOng@B3N0S&dt5SRDgPRdB=+(}# z0CYhbvWc|HOex)T`FeXtRR4r#1txpR`3tOK`%aI!lCU^?&tCO zzX)Sgcbe51t`?ru#+lhUI&5yV1O;{p;D0m)T{QKviOReozqkm~=p>H(5$cbVI3EzSB z&^W;nd@oEVCkGLYS?l+|X<)Xslg1Xs|VYFV~WQqF#zViGch5S8CC~_#gO796R5KNgH5b|39%nJeLI0EGBKbEPW${H9X7$(qZmP&7vD1w+egJJI##G4v;MK`1xeCwDB7#9!$ zRIF0tch&Slk70GWP&1)hpnN;7t%SEwKDfA=IaKy+#!P2qXa)W7QyAW@n5XwOvE1}) zwR_p>PK~QOqmgkar94JbjP_z7wRKY-dBq}1@&4`v{*)|6YIf@GAK&_UnKFeWhYOAz zG018w33~xip#k7NA>Z-0086A@<_AI&6Z_H?KX)S{J`Q~>4_wU9nM0c=ik7HY3lFh% zof#O2qiPgf5giB7*I|^D_ot^{*PFi{Ct_B-d5nM^x922lv(--HxppU@GD_p=Rc)TV zO{a%AW?IB4_XfOv`7~bd1@oe17#rG48XM7bE+5Cr*+QP(rTSScHca7p_sHTHl&0bH zPWkX&p7n3PeOC-0Qi;QHcl>-1Nhv~xSHANh!RGW0^>>L}tsxxQ`VQ3ebKA=KxF{C< z7IZ{jgEv@9=P4%MNNz3Ydt3c`HW z9k_3#)w5sVy3Ma}KB0e@%58stQj5PB3UZ`kaEIFrUbed6=^h+BeduLJb!=YsgxPE+ zwp&TG9*k_d{3bMxv!}+FnzoMB8q6+lneK$c&2@mX2S_>|6^600nG55AiW?GhY((Bb z_KZZfQd}|UNd7F#whg%kOc_h9Ahjab7y?#Mo*-Ea$9Q_dD}Np<2_b}D6uU*PUDQB@ zwhYuzF_hn+Hfz@GZg%j!x!&2=mVk_8m!r6ctZ9!MBLUE z>L+O`}1%BB*E8!@Y}f zS4^BfTFZw;9HqEJ)kr-lBlriHrRs4iB~-zF@{It4wSd?T!^g&FF24CkS0L|f!b8;L z;I%8Iyp_i_ynw3QAN?FK*oE{r_|kk-t8dJsTdu_#KM^k!2@=hJ(zYdQUsK0~!7fzL zd;Kkq*`PWen7QjC=)}>z+Z36+vk^=0nCc3I5xM-uV^q-Eaz^(d?wBDAK&J@U$Ik{;# z1xYV=6uB!iYVtQ7CyrWxwbV+OT7c@fr*j8c;dVyGHBN|1_!Jbk-`RoeFA{!C`UfsS z9Qh|)UY4L;q$!&}(W`Sd`KmJP2=v{WUKAFMPhy`#ROY1>f z#-RLM<mFo-ah(DK@X_5>5Z)H;X)HUZqzT{v_@aI{MVBlC-))8tvPHiKBqV}wO zczy@2-Y-}?^|NZ{%yrIoZ$!$gypFxXHY=8R9gm)M!SuNT1(O$-Srq{k)t1`zZ>`qy1z->X5NaiOzAsN$NlHxgDEA+I=1R3u$f;E z#~@vkvi2G@tCtaPOE%CRXD2)HE+f2gS#!KObb2iMaduBFSktvpnUz3f{L;- z$2m**HJ43?Y4;~w{A|hBbePNazc12EtQ+o<%4bu*WYpmH3r~2B*2x@!ilxfo-$pQg z0umU$sx&@Z-pXz&q>v=`B@1}f?+8R5Gu6A$#T%Ox=Ms7#aS!#TXtKf~tC`=ZY1N;~CZu5->MHdQ;z>;L0Em2)g_Hwl&xCl8V!_OA1=E zeby3L?Ac{~zXbTn#-I3nKEL~x)cTdBjOn~A`@Ccc9o3R7#3y^d!_kLK56Zoub{21) z(EGsyZ^y5beQ5(u2ye3elZWr(pJW$pZZcKCPrw6cpVB!!5Q9XeBST* zvRiUgF>k5QL&_I`5J}I|=bWBjQGBwtpUh^Q$E~0rH!v>Z_T-KA1j2!4@x@35nnX5h zd-?iDByV@AL-LTM_rWS?!;jiO7L5pysCfSCHNJb|>XsRRs(AP}7HIBl@FyQNi1e9_ zbnfwP`iYhFdhJ=IGoAFQ&-ZJ0)Ue7v=e6QnzJYcxq<0_XXL9@t{TKftkKJOt=WwfF zZSI;yixM~yI>p}xH%}hci{VY)l=?1L(K6_sWGBHrBe>Uc-fv}(w*ew5OaZ?spRe(s zN&FKP-{d<{QAcab)p^UgCvO10l+%X+-X#8!4ypj4wp)hwI}mjj`!hpr{Hz$(pCn-5 z3gr4ZxAsf~9P-$8@+9tN;oiQoo&+|%2pQ}}-0%ni^L8}JeiU)t;V7sbLw9DvH}YFJ zm=h)RDDB1wCT%CDB?$e2b12YkLCR%_Jmy|7johq!BY;CT(U({YZ$u{%xof~@6mmuF zk}yaNjlPB%YoK_BRDymVvrz`Ywvxsh1}|IRVLXw2`Jo>~%Q<5gT0PB#+UHDgM}`Q} z^Ph;G@`+;aB{P=D2<68zB)rj-x(-P{DX0_afKcx4ZQ>lmL>q*B_U1l~YuOED;e5YW z7fvYy_na>UV?n?ouc%S&dB>u?6%y6t>;vx&#c@<2nnPI*OKyW2JVrk(m4YMi>feu# z6C!jH%Jn4IA1wjwF0j6CK%HO~ZF&hJTK!Q?;*f914vm__hvQK|U{ldGUQ1Ki-Zmk^ zJ#hLdrJPqKoTi7mHBd_X=kM;~E<~`XE=9opic>M^G;kPgY60+@Zr?~$0ipt2nj-<4 zA0R~+?!i7X9d^yi;E9*?R+rqzSwhO!86sW!%>=L?FtKuC<_Xk~kYll4Ko`taFvp@K zs40&>ae1OsOmc2jjQIuApY@f;l3JiQXsFzCKBzJq!)O&&O;Bn8rU71 z-c$lDgexV*!BH@x)Iw0CQqluU7c?ngAu)93Ragt_X3QT}Jo3uGn~0=kzRQ(^Xp3p$}fa(>{`vqm!^(763{707fS6&?ndp4tUZ4xx=%QDlb>62i; zi66_k(Vz6`^Occi*ScMi9-u|^JNk{w$TSo}KOv3?80O&MD&&W%%b&|DdqDzeHRez@ zGPziy8?uULnq-2hNa`PVbi}d4>Jf7%Ku5s4%hAh&bFfk^jQ;&6y1o3C3|j3gmg-G_yfIQ^}-!ySnp+phiD2&Rt?~8R6aa#Hy?TR z>VH}8fqNR*99A~vfw~4x>|S&%_5hwJxuIKVhlH-Y)A=qBlO%jFpM{DK&|NjWAd{}jtz!dW)uU7Nc1XZt z*GmY>(w-|!Q}jI>YJbr-urtPf#N=2*e=1U= z(1TkqF1?TY8K)}=Gx#)7pe;?wKPX~`I$063ug&#=%MWF%f7F7t*WzQ8c`@sG;S~0c z>kaehJVvD2Sut+3;~BaWvv!~IPTCiV$$+dNY_0zV$#pFQ*uSmhQ5|Dj*jspDREK+-4N07U0!7fVn@d} z^BFzEFmPRI?Sr6d>)KY~?8SU`?MdaL4Yn!9+{4iDNJPcd@f`TA^R0iUWgK>IRYZLFpUX z8sNzdy8nrQ7K*7%a0zm|;G27Fx~dU%s(YOyu%$D+D^!FaTnJLqTneSDB$kaPP;c@w z3}hf~q-lY8I2sal8x@teLo$-A`>DwRo8RHc+~fv#(-$A6c^wkfnkwWUCU+tynTJ!* zdY4kpYvg??w_Y|sw2;q3OAi6V!D}bECVo`J+-zynKqkhJoCPEQEy-GXH>YtpbcDLI zmo6=`O#O%RF~dxfBStMrh_rqR;g@W{pgux<#sj0V7p=hA4=AGX8Z( zb6M&|6qnH0a6d~}g1=D&GtHP>VMB`O34)#Rk%w4Td+fc<>ykr`o#@w>_a%Ck%PW}l zW@cH!DqJedp{n7~Vd6i;PvZ+y9q5#l^Fd`6lANza+3Y3AnQJkD57!%4$VRh!nl|CRjfk2WtiCo3}} zH6=MIF+Of(wK_Zc^-NuYqY@h$Xu9@~_UqHb9q9b{aDR7ubN$cC(#%A@sfmHUj<%MD znu@T_qT;l|l>Fp`+_>zh^oZ23y{{IHhWL^1{ zv$9!(ZgnO7zj4$y{}I}r|CQ{b%6U82pn`Ez|3{mc5FZyC6CD*95gr<{vKpK1(p;&5y|&ugX0gAaFzNKW==A<1Y#IthLO{OpFZWK=6hC*K+3RH#P14gM|O#;NKLa{RajATRH!V z(b{I?e@OVX*s!WS`#*we)~467Q8+8Lpgk%vKP)c(S&e-&Tc7Bp{0~hg%q%hB!QuUj z$Hlo-?SubSlbHo_Utz{XJo|anDe02XY!2ec=RcpIy72($xtICUi zE1|JTM1Y5bg@J~Gga8Kv1px*^^7HNGe|JT*HglD=P19dBwJraXNqL=%;_4<94vc@{ zn4MXY{f}wPzf@PJO~axRd-7VZ2+`ugJ{~R&HHVwSP!s-Jt^EH*(Eq2E$S~!tvOvn-yJZa=#<>trw=Md0G z^08<{6GU;yo5;wy<%U^)&Mb&CqydXj=NeqaE5N?BFG63%%OXb_rz}|;6NEYk0wojoP75&S$dk}OTaN7$&JsA zWjT}@-3%|)h>yQmN}>>B?pO@!T1~5p2nXj zb2UsS%X(wI(XxcT;cf;eq+Y5-#&I@5c_`kKJf#t zXs>-Q(J0WlBCkl{clqDR{KcKY!6e^~G=eF>I>{*D?LFB^VS;$ah>#pT2d>-~jc>O6 zScOOr2fn){*q&9~8g^?hMvC_g9ckYh_(y`9hq5u%-G=1_2O@`j#P&en|4n$g!XNN? z#xHaJ`IaqR4E97FP%|HYc60r)P^$zzY=~34KM%@L1FJuy+~o$q!c%{I#K`Ae(gNGO z_L6=1x1J%ChzrC?Mm-8n#-Eafba(IKMWVHv614&NaCy(nUknM~%=}@}Y73@~J}^o9 zrEWF-W2OPR{urnlTFA8b$o(Y1PN&kX+E`NySCCUion@w+B`P zBvWERumMjnFeorIaVAkH@KA_AxUXQuEl+bi{R@4^Wi-7LU`-A?_Pq}zJq#tOQ2C*Ny8}nWKEgm(SuGDDVydun3o$G5UJyR3+*{+yRnF+_~8?& zx61|aa?-2I)<61*u)+XWB%EzSip<>c;_&A zk^2w+LO){_4~lpndEOm>z!#Un(D!P_=D))|Oiuc>I~+b_l=6OuA9x&^ez5RMAvxK) z6Th|JQ5=WY^YmjOO$oSU{rINmV0-rCMt`Pt1eKJP&=By(UbNL>f>LB?Z-~>2J zDSNx<5W&@&M7n>RZVvx^zp^0i=w&4xLZlHc0}q@Z2+OX6?$&yb@B{P`gYq*=)!=Ek zF#_dxhLec90&0vT59z6FpM~$?+FrKMg`+?A3KDEGcn1;+KVU(4pT5E}s;zyqwVe&m z-$@?eF-_}Sv3+1cAh`VP{F(tsFbgtO${&4~ z@|qq%No5tPY!Zul%lIRxr;>)aZQpzv%C?>gy|1B{(7vjH+iL|~tw)bn6e!mrjx~g* zZeB_kgWY&J3Z`&nJKo!uIn`lhDo;}6_eG`OgL0OLOc%@9r&LCpzi8rEB?qkpy=tjf z`5R-|VTO2u)B?w%1^JgEb!#WF41-sK&Qi1?rrlHMfF-r9#G!2LQyg85?5STv&UvUr z0tTKMHhmO=*G0UT)?4&*E%*efjXdQ^9CB>6}akYlo*UYbkeN0lE5MQURD&znHy~X@X}7N86COu zBbPRTmUA#n8H$v32}c{nY&r}jBgWC4p#ZWk*knVK5x+@l24etyC>N<%FPh4l>U6t6 zJxtqJU!&Cbmhsm$vNt<>Q%ka;TP1xI(u1PQ^_mbGY--n%qsPUqWZxKVyMn|rBrPYozfxU>7Ehnc zPI=g=$rGsx*UDKNJ;FYP8bL1-W7?9}r{IQ}H!p@cYKw78Aq+8X&&6Sxs-dJnA-pCP z^YC%mEVh;3u7?XG4r*0MXddi8#?Atlhpk#mMl@)SheN zgbzppr*-m=$BA|7j(16`J_gi)I1ynMeC&oZ&Swk!ohDJPApNw#x@J|^Z8*dEw!pvZ zl2%?c^rBWTNW+LmTU`LVwNw|S;e>=gA_~(8Wp@IcrV(0mr6CJCwC+eDOjk(k5#ntN z#w5q%b>JOzD%Pl_5_g4h-V?L^#%HCRKw#E0{g*f0XG;8>E~)B7Ll=5+QJO|*n;XG2 ztkAk64N-1m3wssjGhR2E=|?L%D&Yg&tl>tEzxzeCSKAttmX@`f&fPhZ17VVRb+%C9 zG-)dx9NkzuM@R-Co{A>I7>giCQ93L@n-k*GDd5Kmva-3hcNBEf`;JN6n~Z2MP9dDN zFe{piF`z*=z3-UBJuPX)31PD}`l2vK(3&R$c$%nmCq=_7VC#+u!Z4%C*b#p#7_B-( zWb{&AkcJ7i*5D`&6P4~7F_0%}%@sj9m$HPHfD9ENS^M41&R>ZA+r5V|MQNCzY|dS$ z@F2HXbOEPQy%3sp^Y@Nw)O9XuB#+MI;y|+4W+(zAe{hB(K(hX3C;}vhZ-yd3GV*39 z0wnKoh9W>R7-uK~B=>Noe4ht}yE%gsz}u5EI03vfIfE0x+p04-0larQgA>3Tqcb=G zyz4oG6Tq8`GdKaflR1MEz}s#!I03u|JA)Iz8>}-p0ledP81&@#jUyoA`~S1mVpLxt z5O7W9xh^To1#mN4@uHaS(n4~pE=b*2iwoeeg3^u`6hGCTg1#z%-2z zHtqka(($w@Q4!ymw(r=isu!d-Znc477@;*s8nPsVYOWN-aD>EOA&6l_ZMzYeh7}D} zonY!huP#W#2xW64n5Gd*bA=%bI;!qSAx%e2?3IETMo_yGz%jkLaQ}bSRSYJ^(~(N} z8!(MnI4i*=sha@6>M{J0q+LGj6+?i)mi%XArP{3Z|LnUj*ectv{dbNXUXz|NymSov z0leDw`ZQViXe-@TFYp^#bsITWQNwO6I)*iBxa_67ea3`gQ2!7RD7^HWMa(eLE)3d) zt;KT-_*cIs&0txrdCON-9}jn1Fgs_`(EcrACI1UuBhqlm>z6M1+qm@f(3Jy2dZ&`T zV}>O&HY{gJw^YPdRp!Xtq;i<4Tq41w^{M5nZZ+t>7`9}y#TkmzVwWS|3E!Yvi*y_6 zb?~+#Oj}m5{CUILS^1ln`_Kucix`kn9GX;mrTyNR-g`(qt+Q5?iK;^x% zS*y5WJ`lmo8IzZ`X8*svV?EPCYTEb&1{3CkCv7HNagEd)bO+cuWG# z9kPGkpk6_;x&wf2fSx{v6-OI|CZet>?-OaAXxStyX4=Na82WYICG+CL5*BN%&U1HBcMxv)$}u7bJ+>_ngyU)_J_ zj+<=oSr^lWlV;S;B=rhNbK;Hh(-Pxh+4DhoDOTSw- zCw^Cbt>RWqH@tdoH`DtB!9I9va;1NnMp+vbQ#<;y$}O$gDr-_Z@+;a|owo|p-ICqV z!Sd~T_Q#=sHLu0Fa5ao-5^m+2f$5#PnVu{(#x66$&V^aF+Br1GyHsn(ZnEnw`7>P; z*6qs0{?Dczg+20HlU-`XGm4oBTB3RVDLd9@Cs{QO9~Y|IEWFyE1#*Je8u5EO zlQQjZtWTI)SQDNtd}h4*D|;KdvxJQd)8zU1b?gJNyR_3`$qV?**QYY<^u}4`q=bw3 zJ%TmLK+h8TZTM>JQhkfT{os7eKF4+B2K8Ja-ZUo#7qr>D*cjzoV((L23SQwa^SWi7 zjI-0b(!Rr;=>4}>$swj~%$E^{s4PKuy6bo^&ld{r7-tgNi?4NWAnP-&Dgi8^)6+daXSy$x&^WXTYxvvHILZ8 z?t7?(67zQ4D~JWafv|bV```6_uauL%?R{5hh7HX+&Cy)?v{+{N+Ic#P!5PH8E$9+l zx*9@11KT;cJb6rJ%5#Fps`?VgMEQSx$87dnwbpu5d6)iHyBr;T1!5HK0&n=NT1W> zUt_YVFTv!`nVWk-mPTe}8)JpR?ntx*{W!!pgzak@@;dC%n8|hwtkH=F-u_4vRrUVTEVm7}xHxANbltnvcg5PMZbVu5g zU2f~O8H}1Lw)w8$p`M9$w(M4BpmLf3%U5U^72r$R39>t5;lx;+-)pA%%3O0Gt~Pri zJ-*&j*Bt3u>6NrizOe9D!l};FdP}?>t=HNqlO63cucF?aU;VfDH2>N+L>C?$8ZkgFVf_qD2fzBQ$tqLpZ>@AZpl*1&>SJUA|{(to^No>l-p+dqbzLIF>D|RbPw=o`><>t`c4m z-Uk?t3ALMLijU`edy!SW#9xjd!J7LOzdxy`s#4c} zJ}aXaNbCiXs>b5!H2u}@lVoIh$>>eVrKCY=~<2g#FDO^m%RVV?Afp~>EB@a#f_ z4OctEViLj%sQc>;D!bTuS-NgOIQgQg6|3{pL}c$5?(Z$)|3zD7g&kBoPEUN6kf&NaS$SmF}gtiJXmZFu3xa;hB*?B!K<+K&r$?mp2( zv{`r)6xXQs1~#dCfA;$P)Ydi0Y|~A30cu4A_=hH;snPIOGu zGdGn@%A&8m^V)Nu#1eCxf0;R;wZ(J)oDcavyUu%qy};SFyZ08un^22zi{cXcKD2k?)r+%fl!@j~@C7d#S&27@lkV7;}Ja^iau8p*X>O0e!pnG9!(JlTZ=H6h) z)1keQyinUuOr-uUdk|~v;XP~2!3whj?+gx9=TX_8xv#9NQ^#G(bR>X`-en7530}Z* zATm#I|FMU_74Qr0*j6YD*azZy;`@*F`70lj_V!FG^elu~-yFZChsCEE_|Dhn;mGqf z+nQY(FRdGb&k)&pTApVqPWjv2XN%-$G}&X*E6Rm;yZqa}<-00!9cQY!Dak&5m@!Lr zKX5~^;5rALmY0Js-ofn+=>gCUa&KxZ&F16;qaObMNaqs%amKjYZO=6II?U1NWN#)vzBf^$JNddf zAODF4Zg}#gVR8N1*!mUj4P%+W81oop>v{^l2HQwvqRZOCr%*TCQ<+@|>qVuxahfi{ z<*zBgMYXOlqPVm+Y;|!qG_Rl>?l1e!b+)w{9H@)mv)nB3tl;=OlGy{@1B+hl*RuBzB^{jI;p>p4<3@*AW3`*r2MF3WHIhFBRo3+TQb zcC(VIul3%J+t}f@*(m|n#N%pqR3obhz%4#O)sCFp>aDc}4@t2jg~4iyZOIc;c9hOo zkrNYevI0IyU;&E8Wx=koec!^%#I;go<9)yIYr~b~)!=>Kx{GeDFWrHyWPN`)v-1_f zt$fMBEvm&|-1x~_Ic_i%w_;hdNvxy`9`Y1-(rY8!RerrORk+dInvZTJJIJ{Mx8&Q^ z-MpKfh`+_FReiRq_=I)4vEBw;U;6pXSnpZfX|R;;D_0z#(@xG(lZt!s&yJn^rCuoR z>3vPzc`xE-;?lnv@}9GZ7>P?g68L-0qFh~=Tc*7VxvqOA$c^So>qvXD>$bc$gK<*@ zH~$JA>NU}R%W!1}YSRRG=@lPF3d1Eb|L{D070AMMzB{6axpUiE5UvxqEJ)4qsA=>q z`9*3$szr;c`~ybR;bt~#qL`KJGFe64ow)k9ceUu6Hv|{l_foD+o1YgKc8V*}`7P~f@^e@Cy(Ri{dnjwJl(odC=H0lY4d?~PPgqNF%NsKmcD^ay z--~ZRSpaHK2?u!3#&bE%s&)tX_*Q0luYIY2mAm~dI{b9kid%1}T+lq#aUHIEBV-}e zu3kOfgV*$O(eQ56^3UD5@mfCLZ~y1k-^yLSywu{^J=)4zHWAfXh8r4d>t4HN^fsD(OZ+}je@?Zx@$_4bTNW4Z zH(v`AO`5U0uhMiGuS0#-sQtUDot~DqlCV(5k^9+b{oa9!HqKnQG$VRQ!cVrXLwHwIT39qVuOH9^QRmQzZG%X zWp!sEnaR&e?&i^c?|OZAX|+uEaet_BG49Xi%{N*1vWSJlVSj-(85>coj3OCLx(S?O$&Y z-)qX40q`3TCb_6San1Z}BJ%yh`~27G-^JB>y2j-g;)`MbS*5!#=vwg=0LG@{Qm;^2 z)VWit(;!(pu1J}$ySa)Bqna>!E-H&*?ng|6W-I8qsHVfP3OOw*6T#EM)x~#?cj<~x ztxa4OEQSNwIop4uWuwFhcmT9x)oo0V*65kQAB6WvW>vSFWgNQAL{dZ_)6YH+c zUIJo7Xk5B3u?3wCNnQ|YK0Yhqm5^tsvkb>1B{Qd%Ahyp~zOX~48OU3wOBc5+P0UVf zj7w}asbwoXx7enhpllzy_1(q1x=|_{k*O{^&2F8CpRK(qx1(`I>dw!dvNGoJ9okNY z;l0?DyYrp;Z8oSDreUs)Uo*iM0@&%@@286E{7e7s+Rq7n=Xj3DQtyuaHr*mxB7VYf zt;e2q<#(G1w+6ZKRcCZFySMV&%MB%q?olqK+Vjp3T|wM(SwgO*4nbT{yeoV+tjbek z3^%&Q_H(Y?_J0+ZU|b#TcWjA;cgt1p7~aK2c^SS?+w6F?!alRr*I3+}#?tp!*C$gG z)&$P>ZWgP(^4`$ez1A?z?&Dj-f%si&BWn$Vn$MbJoauo#y-kHhg1x|6vcpM9n#^!*KIP)(a^wBi8R0_gL1Ddnju# zd&cbKJLdz%d1m`R_Z#c|)O(`in%&8}jczfP_$=Tyke-LOf7ru(KX~Yldj-7!G!SMU zw*PzQx>8SiZ11`;Elg+CH>lc79zvag+&R(Wo7uP;Tg|2RrNFnS8dfz@RAN!o^_Eh1fWc$|ZsX}dP?ED#+$ z@xQg(nwCcUVO^Sr&dl3^)kaw$gXb!2E!GJ41fn^KUg0}b_TE%3svbt(C@W{LotwFf z7uoto;w7l#5XT|gSJUuy7^9K>ekS)Q+}LTu<{{8d-4wH{`9Fn+S?lw$A6D!e)G~)L znP{|JKwtkHD5@!-f`pL-!T9 z;o5LuhnlUe_Jq?e_gu5{VY#@0R%aVbT%_C5TrV_!w$$V%;irV>E4T;N*awFAx61cq zZFqd}4_EXaT4Oxxwn^6C1M8hb;{CH;`(Il}3F?updwg|y>Z2d!n`Y;BpqFH%$>OM4 ziXFF`-aqt*`}NAYWu8T|?WZn%_%?U1 z;!i)xvJLNx();seWvwjIg6d*WwZXFAC!6u|obTYRhDOP1HKm&Sa5Ld_3$M2UM@zqq zS<&wh?X*}*BW9_cRBY#QDW5P)c~a4x=cPozEd5VGciu0e9kH4}H5*?Xw0s+459~jd_KKI+{pg`&q>U$q)_o{2y zY|&+^CYi1sCz~=0@={K3%IQJ%%Q}An6*UTem(Ks#HI($e341?uQ!Sh2oYs=l(5`)z z`tEmi`5y6EIc%U7r0spymYanZV|Th&Zu|9~S$SXNy3<=LwA$Q7X;rfKy|%nZScBN< zuyUo%u70ntp7dM=ZL`$zojq1GIThw}_h)^qFiw{6 z#nymRl#k*?k-j~%;YN#vl7pHR%o;Z)3%jgPHd}VR5wOrJMZehCjN8|uw3IHXvGtn} z3r{m;{h4H&@Ing`rG{Cpjn+cr^Sk{c%m(BFUSY~BX2Voi@}C<&eVTxp$5ys{JcXSm zi_BKC{6(OyM>f;#x5%EoQ!LwhjwBy<_X@O)vKi+g@F)aa&JZSBcfU&dwKxDYh?5On zqklPQXNu~6L@)BS=o{4^gWJcqo}lp0ApB<2KG_~CEBDA^Pd)AbNUqiX)oDD};}?2x zr!WbpH73v1`ye^dE8_FfXU)Yb=VSq0mQoi_pl5Pkq)XZaqVLp6t(xz0PNZ(Cqkc~5 zUQOD!(|w(}TrL!k2+GERvdWUV!}pw?IHNNp?^NcQ6fIe^VaF_mrBb$vo}=P+x@@Mt zCCXbPPwlQYNA3H^K&Z7@xU8b)s%4;NYcFSq0R>!(C zIWda6LYtg&V(fJZpIe<6Tt$u+?t&Q0SDfK_64>0~`^N^gT~4_;0I>o3bc?DdZsxxy z!na@9CuE(^vT>_wYL1aH?CaR2^J0c2FWxD`D_{pGaH%VlM(_+!ZW_qi{E9Y<^4gc^ zOhtRr=Hgn6Y(MmAptqth7shl%tDv`lPXxXqSNGkypXwUB%n02zx@@rXH%Du!bH`$`X^YrQ@q~}H`g`We-E|_^8pKAcoYBqf z&dP4DH)TyO4A$A7Mj91Uf)`spZ zUje3x`S=X>1F?C+ZKjWgkv3nr8k@gOzunA}GWR~QM_eP`LM~s}MqP&46bIl+XOZ~? z`=skIJMb3xTVPAlsTDUXzj)t*FA?lB*7>&?mN~YFCgXNGR#H3EE2tH>Gix^7W?kmo zLYAoRq^(3Z3K!aTyw2p^Yg((?LM?&!+1_B;b)#;fu^&!;8G${~n)@DPjW^h64eL(d zKzp8({pIYWE!U}^f7)H_zwA^%oV^z&pcjsUqx;wac|<4Un1mOy1%;J)U1}Fh#N$3Y zH_c8&0{}NW@s*BAcYEu^RJ+kxzg@ZIX7gfl2HnoI5%=RlZ(EQhXz6+g)eL0kAY1NM z^_1xZWw)%OmC3*BWCgBe7of7;yxiEgt`k!oo4VbXt$TN?_G4{87r6IYyIFnj>kgwE z!h)l(e2*2}@-N+c4Zo4nM05-KTkR5uq&=i=-<5|^GC)?^-Ob8F82H48(fPFA(e7F0w^_W{t> z*1k)$pweX4Ew(l9h;HBqvl3m2Wj7^?&TXo-udwcRw|(iV%s1_w<)v=#TwDpHyGj>| z$kr1$n!3L%oJ(9io5cuSHz!I8AjH$rU}2P#jw`VN7`kQ1{ZBv zt;?U7n?p(0YZ%oE8cR)kN`Wg_lK= z;r6l0UfF7nZM$J5DWRV)@q%0157FNSBcnAYwg#o7A(9k)ce+~3|0EMSr9T7PS_`g! z?Vj&1XV33Eo^)m1a?xfL?rzuW(=9r+yZSev3+$@Un$>E)IbHlYTx{jqueko(SGrE# zjl0@}jz;aQhF4Kx?UHVKwXDLKC*N$29<&)}YKfSf$`&j1;#Ey$ENIPaTKlEd5zf}H zsL)HS6)VlF{?be_)b{0Mk||YxuU1D{qT)<1POBY%`Lob8rfbC-IV3LRI2?ha#e>*P zQC!v;Qv&4HgL88qKV2yBa} z_0x8EMI-$pj4v0ON7-ZcOh64p1l?jHW{TYzTyYg%XxqvshB2bJI#URs{4_Jt>{!6C z7O*<$xms%sV9o!_)qtcU%t!~6yY!Y~zTAqYDY~o9yKp8S%CwxdLO?Z`^`@sL37S%v zW{GCa>-niPtIX~N6lMTU2wxCtra>iI^}83LtdgqFbw9qFHAl1-*Z;vbySwSHZ41<@ z&dz4QT=b_*3G9hdt+b34XR;a|p8N&YvEEeHu~oA!;BCNPfis!Oa?2}b+8+Ce+jY1L zqu^{C)!uF1={*hN1JN-B{Y3mGfmSSKcIbes~$M5VSwyFWYbV+T`icw`9D1my$`b=OXvO zPgkx&nu6khSlfi$@1m{hN;P;;?6=HupIPl7lWJ+_{U?*$n#d=~Zdk8n@W+zru_)H-jp1b=hqY!%ugZ+f0?b4X)oyt%`Nx!U@Qi_!} z651-ue70r`B+Pp$A;8ff#)Zn)53qt$INprJFKO?!F++ENYaI(VMuoRO=mv{*jzbk+3ggseiYN%j@?0T zVAUSZQP86k=0sm zi7ZLr;j?%)pcuruLot#w6>W+tw6SW&N;21Zk9x<`nwX8G%#nscTO*ycuh)!<4NpvD z5OSz5cvmO317Ia}j45sOA2{?*XuPY%nn9=`=!W#84%LXj&V8lY+iA-&OR|H0=iED5 zzxxW0jIH6Ne@Tcz<(y?Z0xN#2JQH{}Y^>St{BF91Urf6YHCx(?JlQB&d;P>aN|wAK zcN;+&a_x+eSf^izH57n`q(cv4R1GddKc#p7TI*~&1*Nb8rq0h=)F(Rxm|-C zR`|)TcS*J3v+ymCwCc`Q?9QKhqQ(>*V`Z4$kwkehRTEuduw1ii83#8F-8qjYlZec;e`7<{BKM@m@qi&dT^lmGoxW?Fu&Xt`CsPXyR+03wbpy3 zzU!+jjaTAVC^y^{tHk1nEsAsL1f=C84p)bj*$sEC!oBkA1k>=rtEziiTr34ecITA=Adj(>i>R(6D1?&*8b|@L{=oU=Erl*6DuGZO7@a>eSjP@ov*BgjH4Qf7dw9^ZY-B{l6x;pU3wp@830aZU5n<_q;M0^!IeEZLW0dOIK-> zW4iCKqhMW(-(%X}aaiWGsnpz&YB#QW{|(6v)w|i(iMW^M`CPlb*z^4x!?!WHp0q3a zi^%`QZA`Ar<)v)&=h{YaC38!^S3!N4vh{v5bA_fBXRfa4d*O3Ahi^ZtT5`EGc-C&R z$1v@sd0VD#2~^D3A6Q!|lyT}dnlhhM`D42FR{DIdZD6T!&ciKxB_@?Zucr=M`MMpY zPT6Jl?fXgVDvf{Ab49Q90hE-AG|%#VKG6rvCzbh@O}S+T>+*q)L9|tYZ{oey$jX=K z(>%&G_h-S_4-mw`rW(we?b{ru2T?cRc^nucZ`} zaB6nWF{iVn)OR-eIa$hSbd-wj8-00*F1-<^H+r+F*c4`J+)!IlBZZSaHKk`w7>rN# zyXh-!sl-f_vi+=*fpnUBEMJjfbUP{1SQ-u`xf3oY#a5O2qw;e&881#L^+!MiQmQV} zms6UZB<-^l@O*YOO2-?p3;5Ht zn9}w}$U@Xe-h$GM4HO|sx)ODd4%ogIHRW=v9<6SI7j_&byAQoL{__16<&+LK;4R>4 zOFp19xY4}Oc3`%kQokHWtiJp?m05(Q*7kJ~H#$|4(zY*)NQm4t()vv)hg{Ef<4M^X zoN+DkJRp};6d^hBVF%l zD@o(-wMnmH0;9nI;X5~VT7cTqb~Vvz>AUoX@{NXOBPV+;mj?=a#!cY_G@Y2JK_Q<} zbu}uvgHrZlC{;|W8fgxr?b5&~PR$0Eo;b>w!WLE30wTv0H zX2FiO}|2$_tSO|4lns!ZR8m(nrHouU?WX`YT|T4JY<>U;@} zdqd-TBA6P`SOtxSJh3&Vk>oSZe#Xp1Zr7f*2}@7s-O$5##4khLgkIRiEgUw z#-~wKBbD@6=N{dts~g*(M?JvtCpRXW8}$>w$&K6-8RNCp(|Xqx-qxjI|Fz#6ni9LL za9mY1(oHIimlxuzLkDqTA`uT#x8@>~MNFv=m#n1Y5KGTT9cw zqgCFxpMo1-^Qn~S+t5-k9877uRx&?yo8BF)6d#JFijK4F4>i{Xro3%euM2L~o?Y#4v?%rH?%MQOuK6rWW8LswW*L(iC>1T#7(SQ!pu+ zmE&S6o6Jpsr*=K6kGmX2kfb~;Qin$7Igzn2l8B3Rm5<`7r9lF6B3EAI-6St&Q)0I( z-10u1b}wvFC_QyIT;e4|Q?i>C|iyW>^8W1FIh?Fo%Rq3bE!!Ya36x!U9Uj8N6| zZ)hnIq0AKD;;IRu-?Z3e1sA+dhusU14@ysc1D6sH%ACR!^nFwysv7q>ro!*6-U{Ep*Z++FRyqtDj z&^N(pbZe_RLCsTgmz7k4ZqswetGie`#T!{`9;iKywqC^tb<;5QK2RqRv`*P=tYBM~ zhW*#}Jz+}kV&z+%rt|I#tOBK{#)g-?RAfr+zS7s6)7h?tiUFmjc7i>iOc3Zcg#qt&@hpQ4Rf>lw7^-M~^W6He*ft^A7fbl!boy`SXNpCI;=9sIdW zaSK+p&C6|1>-&acid(pvo0QYD<5hh^pF$g1`yzzt-QXq95Kd{kue|SbnZ6mueQtrD z-861xRa<#E-@O3uYo@rdwY&v6{Tp0b&-ZlM!*woEox&}z;&ppk?P8^#&&Bl2;Klmm z^>o~Ifwsf4+GT~_7N&p4t8#;OiZA3#{q#0XEQlq(0NR(^KjnI#o$W#VC%gs^bJLOg z8T5C*K0f^$w$!b+#J9R^@7ih28F!W2lT&N|Yxit9-FsRK2Yag1yMZNgJ-I2k<(09X z@3fqy!t;YYx#_Xv)oh_9+``J4p6|5Wb)`tp<@9#A+9$o~zWqvpp8NFN(Mp~tX3A}2 zMV#k8J!YuxoPnNY8gG3yTWL9VwQ!avaq2c)LX;;rMO$2v^F56c0 z0%7`gc-0N=biLgQJ`kp7hW-_=BU7}IHEmJL*upCR|E6XGOSxT{mbv*G`#x1Ps<}-C0wA7PwTH0*|FA7t* zrK>peOx*^S{-8W9X8Cgka&l9!g;i|R<+6u$dKc4ekJm(2Xta`4rjDs5+^{@KxJV{eVDF^ zG?hNgHewnlMpKt!!c*PXD7kjMpDV&zO ztiT8PkDA>V_#ilnx3*;4=JVipxw2=!w;NcpYm+@iEhuesae4M23(-rhJB&=xG_XC4 zrcTjBi>A&*bI_`p7EPl^Q!;U*G;Nq>_Gv<o)M+ z#>PfUN|i>d4c1m}XtjY{1-OJ)goFzU&<8x!SWY|#Yc+bF=L7Q^xib?3S@!7gZN$kU zDQgmV`|qO!A_YV_0EqcvZ>D}&-S+s)$kU1mY%$YlUtw~+3mLX9kX&xj_RfD|DO3lP zAhJ>^*q2B&%+V9J?}BXn3ZYXJb&nk>ru0SA5LJJs$RI44Jf{^cwV{^eDi*B1gOn*V zQXkkLzC1oCSz&3p$4;6h{Kh{NFp|`^S^_Wcz*9!%2P>OJhn>$cven63WdjIf^;w4# zS~U~c0j5~J0K+CMyzXq)$jqOKl&EBlVk7989k%KA@~|xy1ncb2bkVT_b;eTinC(?; z8&&NH*a?nsbr2j5r|7HYS}n&i2UFBGMziKupM8%wcIb;}o_?xhVxj znpryjzycH>t)-;dG0XK1T;Z!E(7asH@;1jIu6omY0dnJi6J~g57BOQU3pgDJJ^twg z#aKxb4`nzs`kZPWf{-NBUjVf?cK<9i2unt`T#5u3nIZI z-=O8vw34^H8Y{{<jBpA@cl%nuY(9=)ZpUxw& zk1tkWY*k(GVZs`dMy#o=MAXBQRwkc~Jz=Z1Ao67AgvVMg zu~}_Yaf;%_%a*pblhzeTv|Ah&@`laitTU;L=C2Y!ZB-VyOr?Q*b$5#0LdO6Tl?Bcs zOp&cy>ZHg77+)cdVdIJc7&U?5s!w=r)fKlik})?iUSYRDkV)&M;HXO(>?olV^hh(foG@8FHPNS)e{GV ze#|F9b=WS*^n{{7xdteaHkM0M98F4|;fkPbWl%K06cLBqq_R~{UwuM(aK$J?Y%YDD zSAj=L33VSCSSz4MerSQP8%=1!;t}JAK)jSsuTTxx**ubtuk7jOBWgth4yl5dQMZUn zA-?hk1*DW?Z4eSLk;5Bo7!XUz^H_yj%OP!(#DY7_PPbtkgA;D7DB=8+LWvK~2#ckH zDJoS|%L(f@@*3M))LImdVQ!ZUp@|jEq>EojvLt)u?kv5);eb?YWS_U4r@)#6W)70G zm<@2+z{W3NKw*n1kBm%Iatb(LA!uHf6p{FzjUM*c16EoS2(N%e zXS3O+FgoRnWEJdN*2XP_lf)C85!nW4EFN`j;0ao1Y|1H5MhABIB5R<1DdqtfkQGxr|T=Fcaxm=%L zUbAL%tpR;dYJ}KDB71p&s~|CEwl)hanVc@%{1PX&sm%QF1AR(}#%v%oQMlTyXB+3j z=By!vC&@Wpaa3W`h1lT+(rBvmZrUqq`uJXmD+>yYbQoDsdHKiC1sR#0LtqLHf_64E zQmRXe8Nfk|IV{nc)5~EU{KcG&AETU0KIArj2vwl_VuzGG@>4Vqq*;7y@%GN##DzRk zu?uA%1!#_gCdq`FD_e05kiO~%iN99Y9 zH7>(R?uLYNq6Enyhe2y~W7wjBgpZ61$>qH<_?7O)K){Q*t=<*-n-vbpX{WN>6$mwf zjBeqwu7`J{;Rhc>rCi8?o4av_PZJ`ooXD()TY`wK+`bteg9^+o;p_z>e-f@YBGH8z zco2Ay(-}A7;f*6ZX?(UR^JehlfvxZ9T|+8#2h!k@L{;>jX?=0y?GWMJa&dDdh@gfQwZw7#7tSy3g3lOU}U#rjRm_lx2 zbbR0C+}TL9@wIS@JPs))O6C&es{BhE_0dW%)~Kzm}6 zgT~0b(f&q>#UXy_W9SBBokuCeaT8%TZZF!c%W&hTnSS>c1031eAAXs%dUG*9qK5;= zPy^}CauFqj7!N#zp@_SxhZfiob{y0NgImf=tP3`d0Y}Pxr6le%f)GwfDBzA7d*EU0 zlw&4s-AptyT(CLv%R41EjdSSgn1Ty7iEs-*BighKbG0I0cT(3l^X}r1Q1%@}nzVv8 z3&)TLcKcwUV$JD1jicR0Lq8m_lyIuA88^>dfXW<@oNyEAw!w>#sw;*I;%?qEJ+`Xb z9GB9}x^r%ZNJjDC0Pe;+?AvS7xXmIM{>#&dV+)XbYL@};5kU-ouyfo5^xV)VJba5gxml-aI?j@j`%NQLc(kE{u34+{4k2WEu zUhbvBKaQkIH1-M0jT9h|Cm|r%54_$)vlqV+n2CA=r48UbRw;FS=H5gI-gpxVeJnPZ z-9NjS+{t2;7O{=@P7NTu2bgQ^huIrP%o7)a0&)i7<;_Do;ZSf{QD?7ioDp1j6kVKD zF+q3DUlSj~n`F=Cd;BQKZEF;E07!Sub8+4Wb0k{0xW_)A+{&YuQ8B3emx36ML~y7T zmXLSZP{f<;)V6rAc+W;qe2Y}+r)L2=TI zD-&LMH#iIo_r3CGLg6N75^O_YUu z%){VB8Q?7=T671P)BPX{co8??^EG2=&IEh?L zeqa3@{FTj* zH;JT2CAByUxl$g6u&#_uV;585g z@?XO?8bMOrcMGog4HR5xyy4t^F?M-uIgAlT5jUTmEPqvHGctzX31%5yE5gj_mO}-@ zWj|377`g9i7ktH?uMpjx+m5x0r?3f!Fwnc>xFqm$W6vYeajyZ1!dv)Z__!RmoM8?x zF=XloS(O`(%Mcemt?*+<@2z&1g|A-ycyWWsUFJlJoA51tasS+FB*ge<9btzD)LTsn z2k*pfz@sj_$^KY*DU1-UC3f$-2ORQ`y{mjaIQZX3)3=zO5j-L_}~YS%cgogXp9m3>+y0ftBr zUWA4ZS*ETvFKMwH3f-P85?+lZSAO{Is+VjL5SNn;PB@R+CbIO;hb@H}xDF&?WRGYs zVCkXClhCM>4U*w>q{}52LZc_^!?=}X)QroZ^_3+8bz+4|4IX1hlWb5Hk1Aq490*UO z?9Puxu}?d|AMvxTHaQ9N5%0S@9hJ z{g`Dnnx&oZZwk%W@}W%8V=zL@G3~tmNUZu!hUYdjk=3Yp0pc=!WeMwJ33^I;!99P=2fe z%W+`V<2<4Cb(q2w(&c{d9LCGdIcL52cLv~X8>wZR_@|1~&VM>fBOPoTD{Qshj zNn&Zq4W!F6r0Wh+X2P$L0vMo(IS^CtNzFfvS(-`!FQIphc)sZ9k2)3wj~k*3#!Xz| z;i%F|GsV*@a?W!@mhJ~{IC8aiPmTAF%3<0|cpH>yxh90Z>jXSHW8iyDT3{j&t5vF= z(%6tqIDw3nQ{;KS3cjG%9+Q5b_HKLgzM0xl3oBHhRrVAHu6FfdVp80@?GJdPDV`d} z+ZuT#Gac33Ro|$&FO;5-J?cPTJmZ6NgXr|xq=&M4@$0DK8w7?r_lZUD*%Lj&ZmRxU z;N7KMP#Hhk^^kB1-rrTE&9av$r3#MQNph9DQ}s2pX&-Bzk%w=R@ZOmPQ=cx$!{la@ z%f&N>0QLL-d`0g2SYf08BN`oZF@|6k+9N0E) z$(sDoupvu(1MH&1>%3JRafeZ@Wr`P*A{?IV3IJ%Q^xb`VkDj;Sr z`3=nOV*UsNmvKE%eeDv{{|ZqnA4al)n#86V$=(fbUHf(HPV=yTdS!2H(gsYKhxq-E zZ6=4_UE@&H%UH}X#cxt4!|8;Kq?4AqR+|OuG(+rYiKtcrd$F6AscfOb7!dT^A{}cJ zZc_S}Vl}Chk4*kfCO*e+ixhaniim53*iwG9$C%9GE%j7Zr zgl)oZ^y*aYHe`3gRgdN~IqOkHr~imZm{b;v$jf37a|3monJmWQQwRk+Otw;QZAxd1 z*t$Nc96T3Fa12!)hagS5nPG;=e2g3imR;7xtavEAhVo$m?U^yMVw1!J=l^vBei#pL zJH~9BRk@p*DwMBHBUI{E{dI`79LEfInyfaAcJr@}bUua=VR z*cef6pv^16GXh3w19CdI=$pEn&@GqgrMQA3FM#P-5joHQGD$2sN+fTBN5Bi+08dDL1LB>ZDt?Pd}(Ie7xlw44mH4O9bBHf}6Dn#f{h{@f+mJX9?nbNfL4e zE>mEnkpA+5M;~gy3R+)?yLQSZe)L&fSYWYj8y1joWLz$g^G>Me_#=m@2;WZCOV8d? zxHz0M9OV)TYyO73cD6v( zBoBQfOn_qrG$UUkNR)MU{+1ex=OddE**1-`Bbh$aXuoE`-MK#!!mlt{5Bo^!HjVDLEG$K9gfU9}b~Hh3w95~2`ijo57JuIpZ7@*lSzC%|Q1?|rAG=dgl4F2p}QJx7LlGs9w zI_V)^PdKzr6r+Mbrd&wiK`7S7y7+CFVmti?o~vfbV7WVCU!y|4usq8F&umP0ZbrNo zL0c~G?lI3LO;WC3u_UJl=rTeZKhp%qHV_Ut&^?4v`IDHrni_WcFnPONzIEz5TdyBsyqhyX5zyI7lgx%XYXL$q5KGRdNZ6Tb1 zx0!c^7iDE7!=#&Ux| z;$WEjwy$Y5>Oju#FPf%vB#o!~?I#H`q+^`)QpyNXv+3c#yW&VRs!`CrxHP>U7PDID zDiO5X2`K_i&Cpe2)`??+#SzI^IbOR8Q%6kh~wtsk5eji#Kvzd&P(>MD(V98TZWA-*A%d+ z==?U{@cekVaCQ=)(R7dZDmD2Xyin2PQ)(|MwgAsM0z=S=*VV_3+t8AVD%E6X5J0QF zgJRp)bjxqG0xl{oo$~}d&0PMR%x)^_=7{K<*)@Xw?VUp)>x%0*2NLXJ^V3C%H&#fI zM^sKF9-8?#Z2jCXl?tV6UBhjGB`S<|&`xHxoe&?eLUc0dH%m}vrru$dfA7Z(nT$}e z7@a-*e5J-g82@}Z!|C*bKf9w@9oIdnhzFnd1v9Ui7k<(3B&GD12lw6>K0+&GX5-;4 z?BMmTfj_Uo@ZC-Thsv)04<3VN&j#Q|BYG|ke}z*iGL${<>Efi?}(V zm>0(Zi-}>ASy5WZj%y_19-?q49hCpF~F2h`r#F zTXsDfWUEej$(_VL8z*&B^~mWCws77Rmi=&?JlqKs)$0VSGH`qE37&JEa*V&pu+8^i zYQP<~_RFNmtnK*Mv42feHPqNG8d6V&GZ!x!248wjG=W>j_J@}}`}iHjnNcEjS@BEH z>Jj))ly#e`RlGC6vKG)#8-yysXLPVB`P~neRD35&ET)#l5)$#Y9zzX3^^z>@LRxc5 z6ZRq$eN^eI7$Eapcl6e+F`N8G3Sn~u?HA^==ACj``f2`+4>Xxu`J!zvsAu3}={7!} z)8A$InnWa4FG{$d>x25gT0(xGHbT9ld`Z}lF8LWhW;JFnhqQKL?PPPKF_Z8qjJnX? z&R~fcXpEk=EaZk#)CaiXcTYjdXUMj~V~gqz0a1iD`4BOw(K|&f=7VZea&d^|uSj7< zv}|W)r3E?W>>z7{y1o5Etypjv%7!C&`~lHY+Zyb~B6MnI!xjb1BuITp_go9u2?pZo zyf7nX&Eq}=OR&%pkmA9GgUbC+0+Bx6tQd$|U|Z z#l281Y9sQv1##d}P{qHCX=DtA=^TLa;C{}o%xtUVBp=XFf^ax$zS&K!@OUmZ+7e;b{Jbd{>oDBRHh8Y zEoftv%}sVuU?Y>((9uO37I8n)2Yl_R3;xvT#lhIUaprhHe6oN{={8uzffrB)`EIS& zv?E#?zBMs-3SLW>MHXWBksR+rkAmR3eSEd#2c*jLkF!QDg*u9={Cyvp(qoq0NQ}&3J zYBBla%RJGXPa8-jW=j!>I36D8CyT}*@h}E8`q~B=E2r=m!9%>G1xRvi|4QK5aMmV? zbNJ#npH;T9Ll%(HOBrWal)_Qo+Dcuucq=+e;l|VI4Ul_Ns#t2%}OR^4D9J?E?!Y>@M;xm4mTH?ig483>tmaIVy?uI z4xl+{&-HnVVOfx04KQfD7B2xQrHmO6i=|0vA+&uOS#7Y{FQMTP9*yXAo;zpOND4l6 z6^sd)V3QX24vmvV7KbkT5#uX~wh3MAHD@Mw6N{UTz3 zR;`StnRCzVcM&HUOC;U+0~A}#S_Wax0T z!u%+8|A4C4|Ih)GiMSnSmSEm!I9iLEc2-`Rt$2h8Bq8ojG&k!1ZMF)JXt=ZmvNtg% zJZHDEE*wi5+)h)b)55%$?@hCvr({m~lfz0|Zo!#ZjnDo!@>BmdJwQNvprx{Wwm8&0 zo@VzqiL;6nq<#(ggLt>JnRxnE>-OXWr@pyGizLt#kJy@Jl^$fYqqV&^xja4%)n0IF$Bd;(QP7-h zj(6=lB{3=X9P~jILVb+NshlgO^*oENJ*lCa#?$o=F1K9cT|O*A5V8ckz-1Re8*_)h6o#L_cK z=>DhzctjW@(JgTtJcrkPM4h+}vQXx?7a^*7aP|bW6~5RU)CA))u**I_ADY$3<%((ry6Ver@#f0FpOCy&FgAizzNMuwUp zSjR7X({Y*QnJmRHLWb23ve!{Qh{^jwOa)|&%E9^I`?4>Ee#_Ejp;8Q)=}ZH!CaEF| zNvfRb0>NSAg$JdGy^a*m{0?}We*VB|_K@YV=q zGzZU$zS@@1P}`}Gvy80&z@9Y*6+PBC>HxZZ9OY-#q&QW|6x^jnZe8m0NLn&+`OorW zx^vT zUor~l&fRprqI5W0ZK9X}EXW&MZzv2KEY5@_dKFm+<5$y%(!d3uZ^6qr!W z@(Wphd?W@vVlWn3fD;TngpEvG=PYq>EVEn%BwMERE6}EY&BBS~hp}_+dDwEFM5pTO zlZklmSCyy7dsu2F`^xb_{v0_iKcOfKmy(ni5gQul>*?-n=U{L8C4W^zcUi4O2Y)%$ zmE8pQ8FCO3?lp~0-O(-)bU&ynPmg~!T|@Sg<_=XAIVV3OD}xXp6BQ92^4-tN!{wW; zm03sTnx^JY^?VJCpQ&!_>gcb~BhUzUY1B%N-=ZN7f=e^BxYp7&B`;|&U{z3ZGc!_? zu<$TZkr1H&d%e9p+*+O;b!4vlQBzgPS4~qzeP$Iwb&U{#fVE4joVUG&1{elPGuAoO z(*KD0ss2xpNW{g=NKMMfK}Uv%1^@SEXLYQtJUe>FNKac+RoO#LRYiGzZdPFf8xfnK zSG|CztBn#e3?@NOZ&OEG3$wbij9f&}!AMU@OwUF`f`b9$>sQZ@SbKSP^q#)f`kIo0 z%d(Q9g1lVZ>_%oBCLQle0T)+$c_>&Eg0|M?rutesHDy`pAm5GN*1WLR#i}S99h$ce zFKz7g3@a*6KU+ghNx@ZFNl`&wZuX=9b%ewJWrTy=dj%cDzewb_JMk$q5>v^f!k*jz zN`i5q9bCx6C`yJgN_7fCGW-83f{T-*nPs=!Lz5C33!*(45IW(%88QZsNz9i5|fGJBqF{lZwH|;2?YBO$oK*Y<9v2rB=K&ui^&}QqVz!N z_)UB+o5{7R^d;NbC{+E5{4-}l1A|US@6b{rza7U$OLqx>^gSdWofNNrUKc;A;&zfamC4y$KjHQ zN7B+`2v{^S&b5P4IK?i*q(|PYOU@x?VW4PpI50dei4ci^JIUK%l4wz=ODMD)1Oki~ zb{rh01}+9vUOo-%*RLb|&yzoJ@t?Qjfdb}2JubxaIt|D}-chg@GBz~+7+ml$aJZOV zt5bDz2c(6C_bNJ76VfzM)Rizc)U)V9Bo$mr{6KydDg4YGV=Hsd%`Apldk2QsF-$HH zzFS>gZrs>}=Q^g(b(`fX=P91`NdlY=ZdPGj%eW47P8?EP!#I@l1oSDd0y~fh2s%Ol z#o_`BMuNt|Ce#$w&8u=~_CwL-*?7MSdX0l(TmwZvC-fA;s!>| zJKZ0UN-g7bX0aJe2i-6J99kkYU^3}?cGz^WQ6gZ`tJXhj`9Owe$~mSR(kfL&Rf?FB zQO4ZfpgsJ*a&~aZXJCayhO~e|CfXSt(BLR?0|teF_wOjb!~G!oRaRl%Ae+^!l42{%Ae)`}Vu-yp3(~y$EfSUVl>y#4Yd(-%JQ;sgj8HQnHX|b4y&Nv z#;AiO7ls0p;9&wR{up`|K2@7M5-SYm7)(@hf*5oZOx!3+94fRJa*iYxnh2Fihz9^^ zm^e%b3L-8PpH1UFN~3e56QDSxPgHbJ0Qyj5fWKE*h+o*H(1>u4X!oDbgmNB<(k=3k zJ|urP7nFyqy}O&Ut(}XbjkA-3mE$27CtG_P(A?JgUk@9#v7{Qcwlb%fo}`jcv2f5( zFi=Q?C}@Pu0E?m$901G?5w)Pm#gdX>55NQf27vz?1nO5%FewxZ*~a1!DNaZzXkXkJ z2r?0834ND=yB>7bl7r-SW}zkx#tp)sm60~9q|AW}QX>?Z4QowP$ERG95SNyd6_b>a z{ztSsBr7Z;EyyP>Cdnr%DufUa5`=K|bPyQhF(Y)Dhk1zSfl#X6kU|vkR~Iv2&v?gJ z3A5)LV`q=A&>8nSRb#+nml6PlqDFr2iyC^uVHz;qW6^7mdJmyQ%wp;@9yV&f_dGzG zZ`P-*J(*5pctUhE7w3nt(gzk62d@v>S(#h!x3aag0xc|I25t6P*;w%26t3+ZK)K=3 z!E@7t!-JM4Z1>nWn;UZjgJxRXI*0^P(CzR*pc@M&&KrV**PO7JNwXjVba3C`F)wV@ zj6LY%U>edZ_=b_G5via_d;)2Ufaer0lj;$tKKDw|6;0U%PYuX&c?Mcx!8m@nY#)Kd14 zkl@qTFW@OaStk$8QK4**Viu>ERn{97vNW;rFmwbCjev$~o*gH$!U}X01PHRW8H5<* zW;?)boYMh00P9ghCpb;;oOKj{1%S_x5tHnHJ9)u(z$d|f!-1wky#jmpMj^N&IIK_c zbBI>R=IT$-3&^)jqWQUoI70;bhFMHX-xP0eL=151Z>|}y+p(AsI-0^)yqjkAeH&)= ztr)d@tr^|0b~oiRaOKl!*_m}RbvF8-UoEY7Om8hAVrMl6f5^u|tYcxNYw^(gQ(8?2 zrSED6*JLw0NSf3z8%Sbips@_n5S&n8V*HbDOv9n*gml9R(=I{gBoz!RwW+FSMN`#e z4$F#(%SnsK%182ayyJK?s``66O}LC?hMzBPS>*1>v(I2jShv zD|(-D3q;zEn-8;_X0v47^Dq?jg^idt-Vt=l4WC38=29 zh25rHoVh|hn&>s}XBC(a)EYK5ZSrYn8?OMx0rzV}u&{6@K>{41;e!AxmV|mG?DR}V z_Iek#@@bq6NEXuDI1Em^V5?l{eFLo8gI<4S<}Lc_v6EUip}nH2{iH=R=uE+{62 zOocOigq#DIkv$~1UqaWVHn>m0g7yYm3spZPZ;}I_;)6YVj8SHbg@7Oo5EezMx*2n| z9511q>4oz0grv$H8XrDx)Xvh$B8c!Ta-c#84Ier6*=73=mJJ9{)(oy5gtTJ8M9YG} ziGhhDGJ!N{#Ne?5wbTWBRfkRWm^R~d#xpW_+UJfv<@~}Y*dZ`5AT-P)2{xwQ}))gs;hFof*uA$!$h0)ecCPD>z#mko8Ug13kV8^#{$p8Lm^<#w(JW`7CFD>i<%Q5 zQdo#|4vL0CKN;BY@Mj@dgZ_=A*)X?IU6+DJ834niG>;7IE4_h=s3<8;BOpr@*a+EJ z6spS@a;j5`uwh}&z9P6Nub5O!P&x|dK{PFl26j<( z8C*^Yq7dap0z)uC$MSFrQU=?VSn)N6@yYp;wMoEZ{GX;YV z86Jzp+u~i|VNliG-d!IQ5Dwj95}?W+>0!MHrjQDQ#iT^#i_MajTwUHi6hWtTCL`a!82B!BO$i8yuOjuycVr;|Onw5hLj5t+WamVgP!2ajL;#A!>%fW*X zAKsB5b^@m;pDZRl6&~^_VIZlwp#GHNOC-WwoV_S-L+OsjCmU~3@$G{ASs*liQPPg= z8SE>gxWWnkfVl}Ruy#i2mYxgU6}?(a4y|WJ$jZ0D^|(=3c}B$LU?dDJNG~tE{gdA2 z(FQ#y*Ru9}Y1bE`CHiC8MDr(xJ6%ACRJmdnPr0J)N)A(<{9@TN4Wrz`GprsIpq1ID+&`X02k++1Hqd*M?s zgm*5RGcICXL~4tOLqyEHh{eDYf{lrbPAL&p1S_QwMj|>4#7mC2FA}m4!RLeEw_za< z#zkC1fP?`++d>Bh2R!c)8-6bNdl2s_toZr066I$`a<8-RC`inVExA7v2vSS;ta1?i zky^2{b=OyHSZc$|m#R!(f|)%3h~r|5LE?IDF;xJNSVSzxeFVO8*zMztCIlYpp z_T9H7T{iVOYb7o4DyF8mEG#Qei2dD=*hM)3WtZ8J1trjns_saVC^jW9EK87fThRq) zR5{W07rxOIw&dMWQYDEtIsfu+Lz)9Rd@l~L>W;KV7TMca3pzvM>RO+*`tG#6`VZ7`lM;55*w>{fg^(neuXi%CU97Ykn^eck>qGc$F* zmX(>`dBa3jTWUG&rM9>rEG=$U#n{=vplq>IW*z-i@S-30JQ$3o1=@18^C3yr6pzc6H8pL3IH+f8*!wp#2&fj!o;Q>PwLXI? z6^fVDLnkC-4Yi%Gl##Umb$S!y@N+t5qtx!gV0!-JAuV>P8}NY$s?nGHPmoU=v0EPH&i};_Vl@0Z^aQa zF#Kf$Cf18DHdTqOF@x1^@%?%J%9wmicgt4}N6S86z59!KNVB$voJP%t8by0IMYrSe z;tH2si48!CBSwua;x9Wih(jktagN+=iv5uQ{#e-y&3zC}kC$R27+@UQHstp|ba)If zI$MaIJKa=a>+6vvU_H1wmiX7cx-pPNw6Pnyj#pwGW`1@=6s&=64_Sx`F@SV zF_Pm6Kfp3#(%?KDf(3pH&>-`J0-I~1-3CG;lAn;u$7m5`eT7UfJtFM&Knn6I;{bvU zp^6?aQ@?zBqCA7R5LF~T{(k$%n=7kbRSViMK8n7yfr5f9GJW@B%b4WMsFUqU{|+N5 zy{@;9eKPcNkw)^Zi$I;087!nY2>t00sidu2hC)w5x0Z^KE#{CT>>1l<;8{8Llp+C+AgMO4)XA-#$#WP+no2(|F-!fNk? zfNK*XK$4{EFI6|>{Y?dqhX`Rq_xJ-=_j0%C)xwfP@NfFdW#XGtDqvZ|6jo83W$EPY4E1+pW+)Cp=NO(TI;uGHe!!&bQACf=wg8LxmKM<4r+AmUx>B= z^5nsmYt5P^{HrLfG1o{UEK^gTj|GnH$NZa}geckz?^_|WkTHuXa3m;0OHE#rYU+4N zM*yd%k8mb6N)7P$w-FicWaV?U|h=A9^PTfN6 zzCF=dC79)8a|zH}@Cme`5-ipN6yaVmQ2%=@#Qqr22=^+D(!Q;-h~=V?b-dG%CjW z-acvDQzwVm^w>kDyj?!$YIx%MnQ=+EhcdQMjCY#%@EBD7FdR_OecK5oW#@nUh@N6fj0T2HOWamrK@0k7x z=Q%_fNjgD)Lq=PL=wrM_MK7PC`aj@sgvFy{gtPTZ5-&mta@c<3TSY%__p%Dr{b&G0 zCeM>QN-w3yVwZU=GwT8ZL?Q*s^3s`3q?2=|7S|=l-tlnx?YR7X7LXV|aEN&F3VJPy z>^g!eOeW=SfVU=B>5YryW{X zE&;T6YGxhWXDsj~d6FMF9PGI7?49t?X$Ul@^a7`97`l+nD z-IJ5HLpPmTq6k<8rZArUYbN1r?q%8eAn ziP#O5hh0d~kAgeFv;!*?*EE2+meu{;;W|ec+22Q(t$(E$X5Q~VeB@#Z1VE?BCNCbi z^F-3iGb-4uPQR(v6|-zVEI!`YY2^c@IhJH>r-_{jmb4)rLgYX7X|54EU#hyw{aZ=o zj4>&cY`O3MOA2zwEw7Yu((BUjSTUj_#@Lk(B^(Ork0)e`K8Nf6(n z*dNDI7+%ng9Xzp62dEt%%dML7U~-%!%7&Ch=LDxV1J~eL1t(B@G%5C^xQi1HH%K5l zzBHvc39*_rXjx}+RV`oS8G=+TC5Kwpk@Kx>~?#_Igi2b%x669q*Cb&lO`Cyj|)Sg4B9Q_6PGNM?vH-0Rp0g<^MVOa2etaAhE6XE!QiLBiy| zoJMNb0`JWdwV}l_JK8;;<_q*G1V! zJlHK0zb>HW{_rFP%I^%Ws@WQ7USdAqFC=L5(Tk~(uUa|0oJ5{T(kA=8u{;`p7V|v= zQu6nOAA6AZ@d(KjpJA;jCOD@9kJ_VaE~gx)R5_z%l^PRH;~~Mjfx+-&i58*0x)8g> zmJZ+5c9;_CgHN0HWQ%H!ma>@p1AfV4-*=Ib@4uOrHvOUoh2){XvJqn0m`!P~!M|+_ zeRgUm(^faa3%!iJIe8$5Vg?l^#DW+-r80h~-yBoJiY@b-pEK|VKR7AGd_;(lD~izc zhA=c0h_Yv#dOY~_CmBM9;z8<#2#~6)NCW#!F)gRg;x(U#nWHqLgq(=^GD0OLYi!HD zaJTfmRNSP(H;z#VSQ)eze>HLZ{>n@3iM7N{r7V5dfVZ1uhSZrPV?ECH7D&SE$}2PZ zGWL0(k*75=ST^--7Ru?DE*8~@nf`B?(I3!N7PE{+NgO%YX1|kB1?m4mt;G3RS(_Gw z@n0z#!(<aQnXzOauh%mILLk$`?YbHh5k_H%55Hb3OGWu?8c!gQgRQ*x%G1*ONMGK8f(H%Te7 zo%F~++wO*6D_)7%(yju11fiEWa?;8@JWZp=Bz}cbZzOTCgiVLD2?T)dQT%n_F&e)Y zn&nEHqlJ<9@WIFw^=qVywU=;N4duV}r!s7^aHn(J@=99fsPxAZ4@{s6ZnKnGTS1kBaOGxbls5 zQ-B&TaDna=cGPtpez^ag;0S9nHe>Gc&n zFA=};?%!@ODdZEoOdCCAHz_~gTDtVLI3D}258k7mv=yMKCTwfEl<@_im`*%pCBbc` zHf+gyoNSoXl|d$*&Z6i!Ix5mQmn+9g8w~TAEMaLjD?l&h$KCr4zY2E^A=VuHmaKDs zEuT%S=k>tM!PUf_sA7}y)xa{=+@J|Zy(*iyuPPTQ-(~>c_mIRLQy>GeDkFdSo@c{v zeuSg0c=$ad(zi1LR7q8Jhx=SUE2b(HKl+896eg~lELez8agEzl>q_%|WTj>7K$+8J(z!TI zNKt(^Wz3iX3*J+Lr%LE9D($aCR5$x>05Y8a3=`tBZ{S`=+}})3nxp+EL0H9PPABlH zGu+!etAqtZq0r^(LZ!;&hOm3503_S#OB(DaB#Jf%BGG^ju)U+bk=E60|BkNcbtv+%#f)>WOE9hUL;WzA;o}~K{v_cmodLX3{Y3vn5*k{-h8mxu2saDN!8$-O8{#O^LrE)j%|vgh@Uk<3CLsaR}D6p_7FQA3VEX&B|@b!#e>8(Jn8 z@$b$TvQA;XjiJ_0`0mDjiL^+CUMbkS zW4bXoSjY)jL6S4?Ush9zrT(5J^($4Dfq-ciIK~A0(E^Dt!u>oe-QT30;tHBW9?)^y z7@!FPQ#~A*IGmTKS(_X93t22499<&^oN7-~ys<7oY&CVMNEh8H@?DHJ&#+apOp zuG{=Wv{9961Dw8kADYSiJv2+%eE8|mjKqhqsD}@k|6h>RZ5RAV4j@F?v|`Xnl?(Fi z#c#Oi-P%(GN)h}AN}l+mGL8x$LMs4C{N?6rjPvsE?f^g-u6VFLa&yui^#-sPu*!zt zJ1f1+rl3*5LwyU^a&RZrvyvoB*}au&`u=#qAp8F4^Mm>$xrJC-`}J=Sqd7KfhUkU+ z`R6ojA=XjkG1NUV4al3Kf(_Ma1;)`PfK;1aBCFNuZ1bo3VqkTjf!TYkV+Vnt&mUbJ zto*jn9F*$K$`_Uo9s+qHVvK&r)xZwc9{zOqM6K{qAT1;OLs8_F{8eQ~w2%e;0%iB7 zSZsiVKArGCz^-&~m`r?TiZ$QJqY0vf`y-O{Jhs!%2aEj0RAL&5!^t1DDuK5#1hA|-K(u(ORf1b(}Z;0EyN;p>4`+0 z+~&vX`mDhVDqbuSSj#b6D24!EOwAC34~i3UP|4uKwv;U&=FJdfmem6`ysPBRUbHOV z7JJI}FEm~4s}Y@g8j>CVgFevx?jp2`wsWV8HWn3mkn6Lwq)QylGqmwZh3I9heo^)F z_2~U9nrRrOR2@gE(se};3wlP+waV||*vA!>pR6C5*d#ooK~!I)Rp&3WB=R2#6Xdd~ zDU{5N7iL#pnFGuQ&d8p#^vy-vF2DUpUx-i<0U4UlA1PVFm;1jlVn3x!+})Y+eTy@G z{#Bu~=*VZaxSukFbf1CMsz?gD_!Ixd-kGm5p!#u*x%1m3Bs*|WXbxTVj&s;MjN-|N z+WA>+D;5HREYLt>Gqg%YBZd8oQEpA>T@NxV=)8cpH-82wT}doW*gBk9sG1rQL-*jW z?(P>qwM0SmSV_z1x!7J;MaL{8N@^|48YLNN85p1OgLznWqXzX+wYnf*lUoK0oPv^a zylfqoQtmD|U~OBwun0vzh3L(Oyh=13Su(wLFG7XEe-TO~@7(cU`e>PaRx}O|!Eel_ z#J;f9nt$LYLJwN`%x|LPgASEmfYK`}4Z&opvVN_wlKCn9xAV=3R$7m#ytU6By6yAt z{syY%tO3mmRpRHZ1p6Xw=7T9)oUBziB%~L=5GOs*xTI4kemb>_Y%|6VBeFC|7O&5VZyD)KKG_O!6ezH2VHYHQk=^;NL18N6-te3 z75cGCMmt`1I1Kqx*um2=ee&~!xfeJiZ6#h0wZooU%Bj`jE%~Cr)1k=Kp`DLh(r|=j zWU@Snb_w+pf?OA7msJ;R-x^mK2u0KMtJ?cezS6ED*<>?(JqqX2>kt~#X2l?1{ImP> z?QA78QVJ?Z9xsr*Q{eN|ycsaFcP@iYQYcbk&`CEiZFvzo1$|igf3Pv5(Yofpr4DlR zN~F1xy5+nPb3imzD%q=l|7S^4*|;73Q&Ki##%l-b+&@*V!kMBM9iF%;qsK4}_UP~I zaGG}@7>MbRy+j9H6soK=(da}v>7wvUSDq@;l) zapB{}?u0l84n`j3klavkq&wejzN3CaTC z3!TdP5m5szM?Jc5I^4={;(YQ9I493aTB3%rOxkb|C_v3d&YICa0o=34iQFjmj>97+ zTmP)N)>IIvA_4mhw}MY_b9&1m#r85**Y5IIRZo5x9}}QmiQTe9tIpn;+FXHx3=pDx z3Wu3e6eoU(Lg*e&@Y;$A4gIbPTRT_^32~>M!BET;C%TtOM=XWdQ9VuUcpABqBtqlh ze67?+YLhRfDMY?f4$b+d+BZ!}YR`<#RZ&P|SgcX`?qe^=_anADXC(HHe`$j_V4qd+ z+^<`_t6*x2j21GTIPG{@_Ip&ZTj2NL*fygn3#mij2MO4cZUhQW-&WW+{-1Tf%>ESB zx&Ai?%-X=0T+om>zv@Exa~`P@sW`*kIkqIszg53YO;tR@sg{XYP8gu~D`FS_jm*&W zqpr2k2!7u~`Xvw&Rphx>io6h~aL?Upea_z?IPj^kU*m!kspu;UO-Kus-cpa3P9O)H z$RV%HAw00?DEhZSeYLgi!|letz|T7cZ1$K~i@m_hw(g1y>7veDn9`(GMN?>kF3UHd z-u-l^4@=71C3cp`YFjhM`xn5QpB~>ARMbU6^}V4orxe`>7uF2=@w+geyYf&G840a2 zEQ#0|rjae%;6fY3^8c`QPQjgYQM-@rWMbR4&51Ly|FLb`w(W^++jcUsZGQRc+?<>D z=G0leS9R6yuIgR8tE;+qujlvp8s*X2k9u~PZ6Y5;-(n#>SyUswhtsaYYt@B5vP5o7Zhr-n}v>_=YMDnSMn z*?nPFsp{R&1_!9W*5yrfo3v7j7Je8K20gHYMGLdd>sk#cgtGLKs}v1I8bB``p7aJ) ztbVGShSMKoQlXg)B;KAlx5~lk4f0~?EN>!XbGzZEE^r8v}?}whc zJhBm3*7_4XRV?hU+XOqAcCPA%=t`8js@wyj&^_>sWf2@-WMcRC&dw}Gr!euBQ5fxfyL0>15kqo=j4t-Ytcr?pkS`$BzOTW4!?lj(mCB(%2uYzb|N zZLQdL&dwB$WRCW>V>?U@)ri~;$n{IRpWiKw%p^)I zLnEbnj2SLG4}M;FOjKICnY*w+D6T@y?|(qC)*>+;!SjY=u}}%Sy-;><>Oh+GB-sqJ zz~ep-3$>195AgN)8Y2JSc`G0V-0PRB?jdYbtWyOS1Vs&{OFz87P_W*cc95YFThaWoxw)Mvh2wV+^p8 zd9JbEdgyV2W_=9~4Yf+cV6(Ow{G_s~cwS@ve1^LfJ=;iIVQ6Dpx>8nGxUHHO%vhP4 zC>_7q1;W4_cIq@vw|L(oKyLLT5is=(h(ZbCB)!7bW;ZibfBaQx;R7D$e$3%wV}rxP zga0GL!@Yxpz5gSFgPpv+o&F=ez0IAR%>N^uob=7j_5UNy%{BD(HU1-GHGVF5@3q4! z8~A@l{|pbYydtrnum4j*!J)@-@0A#_hg=m4k(uqCmEA>9T2yfI{)WwbP*-E?;__tg zlG9~s`i}qprlhP)U`k*Kd|4xWLNzTK(BXpDEW?5nm!Jn+hMnM&gi#RyAecb!W{()W~GFt8d|v! zoIN-^N@ag28ZM=htLRvMVYUAxD_;b3F(_SNcw%~vtYZ7AkSNO9Mt4L8mS#w?9#ZZ+C`?54T&Uq z;=DuVUL^eetPqj5sYZj^!_s?IV;^Ds|`?YD2X)C4ZJjgrfpFg&h=(ksx zewfgxjQgYvT4&@kCBwkO9IC^PY1k`LsMu0*Ofk`D$$E_YObeLiRz;*^FQq?@Htv-d z^wG(~qJUeB9sAV@%v-d&1X{&CVgL{zn+YwY&YBOMF(;lGp&n#tBo?24@JIeKY7eNk zU!3&^K)_?MSeP3dc(wg_N)NZUo6Q9{2S+ZURa7`fpi(PkWib8_aDQbF6_O4X5KBq~ zy}CZF}`cWw}R53^WOqmKh%(gU4o;6ko=|Cu34a(#j+3RxpUS@86@9)6O!j zGX#S|K|&&VnEOd6iR*} zv7nz%zzxzKXsM~`RQhT88gQZrq|D?E1iW)vJ%VLeRnj03md~I*(EvEiul{H>bUZB7 zU&pmUgHVq_P>$XwdF-@S3JjE_R)Uyic~6zc84NY@41GGQ)zt%;mS7H!_I9>xSy~&K z*+(TVAto-WF8b9I{e#`TR&vc9HVoC86N1ssKYoaiiy#?U7Qnw{oDxu!x`K>UR8XOp z#DxW#e&#AxPEHOFNboPq3a~{cc80w=?bqL-sB}vP=Tz(;$&g09`sr3NbFgbm42YN- z2FExmx!f696ADGsWjwK17+kqO8W!`4fY;)Wl4ewKqgAnR8aPF9VScy_&>NThsg8NL zj8R=hf3}qIC)gsJxJfnMBSJGXCuO;;xafx${K!Iy$mG7atG|6A>BS1UA?%&RT^P`3jVa@#ipCHr4x{GRo$E! z80lGgyuH49)&%+^!ZLNnT1(UL_O;h_z0K$h{$q5+HNl{$xB;;&aaX@}rYe)J_B1(U_?xHL6*@enS*S2- zh-NEA4ciZ4!pJ;uj)MLb2~s@wzhryd>_VRlqp?vLL?2;_DORZHv(^&T%Ked>B>fWc zlsq})`jJ+pX9uB?q|;IcaX4YB(1u!$%{!SfAm-sFU<3;^7v;X$&2F22CIY(+2VkhG zSYJrbY-96}UMzz`5s~v2iD0Xwk@|Ir#&o?h32jd9#tJ|WCKPMeCemQn$Y@Lx1YV{E zck5VvK9QF1IGR9w?TxB&Jws1KLR)+up;Yvqzf~Mmpy7U0GMQ#iV3)$SR`sQ^F zmlnxM1{$x8%_UYm-COljM;P?AtXj2@)gNXr!9wC;Isx~O_$VxK+LPo>@rAq#nBoTl zRuIJEV_b2RRE@c-h~zyFQUgd>!@A8@6mo5BR;m%6rt)hji#5_!8F3MYGUam`aY{qVp9CR+MtY2D`Hj2Y(DazKnm#*$1<{a8EpsE^| zuxGGDya*3i>!zJkgLZ8F4U{J*hRwZe)Zj01vA9N?69Whd&2XK+x`wUy`ca`)(oqU> ziTn?c5257mE$4ud4{ANTX%p^QDJIytc^}Be){+`sAwf+JEAals;c7mJFR$o<+iXJN zZT#!yTyKFwit{xMN}(9Zk#4lYQiUE@hPBg~NV3CQn0LUAXPyq6-ZxD6=b$AUhbKxD zALUB2LMClIthZAo+eS#O3Jnh`hJ)}LQZ%WSH)`Tgm~@dTN{3!4qXUe$If^Ou8iA7v ziHvfg1`);g0IFa~OTJR4biqWvdo`=PZzLi88I}t#*TuZi>{yx=2&5iK(~<=RE$bc` zi_b~e@-uBAT@Z=Ll1NxzY%~DWHk)pJlxzPRnV5Q`L{XUEo)DW9T@UTTg_*3^}uAePmqrJgLxpAYGK!{IK18N+U=V)!C*6 zshtDWpvT~u`|*tgR-no#-{YMlq+IMOH(y4jvtmH4_4)eZ2|c6Llq^yjpO^mq zu?OnsvbmL(`YK<*aDw#if}v`KD~Wlx!I_Vwtuid%LC9#Gf~eF+tUDvKYy%{?QU=Iw zHyM%4oB?$>u13UP)8%olyRwS4csU8RM=*9cJr-0Cxgo8vGqm^isUUV zy|WWn#(y4(Fj`8UXIQf{QA4{-Gs1`Gn=693syC z+Q^{leM!G9VL6Hf>G)?Ul#uH%W`AC#1KX(OR=6~0WSE1M5R;GbwP5ZMhXD9fs}jSCYg;X54`o7__#>3|v=Qh!a$qkh=_#>eL zw?yNkI2+-37Q)gq{`N5+GV5jpT0P~c)wQbVACUqT&`H6eS}d=fAOUlx>*PmvcDTGI zHW9biC7#3Nx}ugen9%qM*+JAQb1`p7!GRO9NcROd3bl23xLjZ$B2OU7dOc^A4fx!0 zHxu0$Xwm}{c!1ds zj}wLz6-X}&75H645sfnwsa~HNnB1YW&~4Nmg{|c!ZcsI9kx|#LTzGsx)Jr7RiwzXB zH91bq{GiSEwP8pC!wSJLwP!=%)|WJ<6p*=ZCc3pOUv|%0F7Bi%B_0)sfW5#jhWh;8 z7$rkEBH&1h{n-GHp@cPHIoAnSWa79(6D2wf-nZ}(m5!PcU=Z>(f(xzwL++2&ylOW5 z2l14^l;BIeda}0#XoY$tLZYi~#*gR_aF_hU!$3~ZnkFuj0df=lJmb@Mhu`k4B5Ta` z(Z;AeXl{6?;7UMZ@!NrPVcCl%%j|$lGS6T;S_1722xSA`#4!>_Bu6tx!&7%9N!jUg zR#GC_hMJSO{uIS$G0TjUKE!}uObYvX1FRAG2xz>0nvJ@Z$%-a@YoE&4FPBC12S*zL;g|b z`Y9MV@cL0a31sW%HC4fEUHj3rSo?LxzGR9*>VBr*|2XaTD=7p?8`xG|tpBV((2=^0 zvKfKcma#FM!4CSX@UB%F=JCRmNLB-j#_EVDA2SWOafZ{(+!`J;n;xJgIIx@Oq!IY5 z1^T{FqqKlM7jTN}{;+G)Q&D#OYmdo*Up8xYV;6A+LK$t>HI73ie|v**IV25z@s|dm zFaV?~Unag0jxN7p`bH+ag?fdvOoY zrnnVClD|IR=|u904g+(6{Teb`Y{wJ_@%rtgXKpspbE|)lc<_NIn#16zT%|St-dJBE zAu6P-27274dCu}vXSksM5)%XP0g4dFc_j&&`bY@C_u21q`xU6zqsq#`0l4HbrF{82 z_=mgS*Y;-bbNQ*(s`$f9Gc8t>*~JC2yO3nnG>zj#!+oV|$(I(#I(&;i7-{X?`xmIZ zux|!v9}W2_2z$;g4Rzf2(_jZT(p&zo5TAi)fIrkzsobwu@GJ!@LJ*Jk1Q5HKgg#@6 zQ(-L#0L$um$)Xhr(YVLVKaEgO08@lwQDg+wd6vRimbRkPuryg0ZSaJ7a?9i(d_@N% zZ9=-zyxIfQocmQmjMpVTwsGk|Z$pAA_X`lN(aE2am_ciZQ`Mjg-dGy^8|Q8RrzJ*7jDr!iGN!WUfxOAn83@ImP9E6bkLRB(K8Ed{4Nx% z78`$NGcP~yv246l6*>{D;^g(oGm>G8aG1`|4w)#9$b-9KU@qLH9Z%r|-660Kwp}`f zW0WA2@D&6lE|xAc(m#iw;@LA0j-TU&B50j zCbS*M9L4SSi)#9Y??Ask;ARzE@Zo*h>6Phl7NdRN0`BG6ik1~{-Fa)bOQWaKw?F?R zZ!kcR?`jF|S=Q(1B1qw7BT;pMrICG;a7bOviBh8nC(_rk=ve@$A-VOUJHOTr$}TJ( z*gjfwZLN5o1K)C>n0={ED54IEGR^SjM|jxT!0VXdXC3634#9pW9b*kj-X*am&d2PS z+WUXRR}ke?*m%8$ULju$u4SYMj?IDf!=|A zZ(vSeVdy&`jaSAa&60rm0JYzHvcnsC3%^Vavkpugs?WVrn&S{2)->#{ZMDPM-)vHe z?=UWdCHdb>@WVaA^$2oDHp}auR(f*6!U^Bq>9^GCfJW&6$*bf5$pz5A4PB6fM{xKJ z7e+Fod~s2Kk}~P=u}s*H4&UkMi|NcqGD|i*hPwsX0Mj^Eo;LLhp2kRP`lL+q#{~CO zn-@PRLmW9ax3-5uv-vVO32&~^7Evm3-)Wiz=*$Kr4RRzvpNUnPvh+N-QM-Mei?zv2nIQZMai^zrGrj|vCH6QPgYe}+ zoxzMZh^f(ZI-6HC6-P4~m0|i^&YCWaMMs|zCsAcbqpJwbkyWTbq@?Rb&41o^`883; zp%#=wxO18O*K}-|$5BJi6o6()BiAo-|L+*)*P!859A0PkAru2iX@^v&bFAya;tuw; z8}p*P8@CqwY~Pq-@yh$B{VBXA=4DlK7bq;^Xp?s-pIBB;FHM9MS#T56BBicVecc=Wz9Wr(*SCj+imM2vPp4;Z!gQGlr>B zcalYBr7l29qWS^yWXc&+hR){%f5%iTema83>Cw!c$-`_d7>L(IFDkeK=Ur$-I1Y=Z7c99k0C;q6qFrjs11zm&WXVqQ>`?m=MUGWA;nz2X)K4Ls>Dh4xq& zb&p>MA>`hW7+uvRgi;9z6{Sr^ROfJ9{@zW^dDB2FL-8P8*Vqeg;U;DgA8nZY*>Y&V zl@4bXx^<0cLYbwt?evVqgDwEK(Ed1PwmcP&4BY%B^j-3nghiHRbs~8}i4q+R=iJ2N zi&7rlHaAyZ-g?@$$_&BFm^dQRh}Bc$HO7+3u=XWTU}hino5jqDOi{m$5@t+*%P5F< zg@!C&90CiC73eeCOZxZMj9uFBt7wbKugQvK*o~uaNY7vob`J#G-~xJfokXxuPh;-B zpfSpl=vY(Or+o;sf@AcRq6Fn$X{_`c%so^zhITy%<;h)E%O0gd_Vg$Rsjf%!bk68> zYkbb^h}X^1b?f7*;X>FTJcMy{-?nLDP?P+Q?FKAaqF+#Fdrzp=$gL@nYn-7N^*d@4R5?2)EtrFB3kJCgd;mS6@Du8gj$}6NmjXtr6RdPdM)k^xvbPI8| zC`(2X8^!XQEV`oPB#6iJ^$>jTIC<2MeTxGKDwr;Hf~t=4f_q++mfxWsoltz~G_0qWJhCC+ej z!j)oW`Pf#Ry1p=BL=k!S(9rJ+M#m{6BL9+&8hREzjT_{6x6vVfJ4dGzU?|)EZGF-w zo%K3t^}>Phs;B9z%<`HGk;+YH0}k&SLR6VqA68gzeXHQe+fFr4vmBU{V+;~M&3%kX zDSWOv*!zI(Yx&1D_}JJv7(wVg6M$mvM_SM;7BRNea5L zZ2H_lt`GSkD)mpW2IPib_C35V0J!JrEQas)Y1YTtPvybdZ-30vtd{7k^HrY;-S zrfpb&rZ~vO4>{*1=+9oeb`paOJh7K)2t#Icd>ORGq^S*4)1@XJ?Wx=67QIIYzmz@}Y$})C@hs)cln$1ZWhLGU2kI61s692tl9-(H=r*Pz<0vNnT6{OnoRIKO|8gAS8GoBp^nhRw!2XS>B<}{U{EB zjthp53%*;QL_v&KvT@BfVsZ^&esTb-Wiy%?)lwP7Dh7lud@4+bVS)CTSDb16)e|dQ z(?nK)COW*;K9wQbpu_!u>X}FI%J(;jQ&v{!zWtxM%_56A9pdgR_dy9X=N0loWy16K z*H+}e&zxq|jr8R1dMaYO%U;49RMo_iMvcbJ(uS zdnny{`*pMS)g-=6fYroK$!90HR-V{lgLs7}r*3Dq#Y>zFGhk$G-+S=2$bCK(wB$Ir z8(fd3)j5osBI3S9{&WlT!IkvE5xw;j>eDOtd1g+u`r+ln_zEs(bh-Mxw_m2Az78)m zP(PP%1Kgz+VhvDqQ>ow^iEaHvP(NlB`fGn!anX8@{SuPd)KC;NiQao3$#)OiT?D-$ zQ&2oWWQc3c1W}PDRVwY%#2TZhxB+%HbI&5QFL*kfurinIeT(ep$k;09y#b7PaRgC2*CaE znSEZov9FXaCSsw2wwTCTO}4mBBpf8<(^2@{xUP$)tcunWVQ+(DZe}K7 zf84lik{{dve(??5OfV`r`pZxI4{`F2` zsMTM){@`_67~xF3{8u8vOfbyVeEo5da@j*b)hvi+^d(oHdnLOkQPskQTq>FFwq99cy6M2QPfHQy!H7X97zn^3jd24Py z1xuRtTNS4hb>uzj+V94;Ss$&L&n~*_mY{S_2ME z#2x5$%ruDMUoVBu*fGb86h%TlSfMSPAo%~^JM&_M5Zq*p$@O>ls3F=i!ObrT=3Q8Pu*X_A8k*0MrKgpho?(X@SmF7oGv}*5I}QwJ51kK zlMgjR7?36w-UiKltkZ`i8D+xqvsY)O%)mbNtwHFsoSvAFk^ zjD0>XHb_7=-RtAukMRj47UP_BgKs1G7R3@%cMB+RMrw94Sa^lCZ!>IoMetvx&e?^b zTnQ-hN-R!rDtN9O^50RnPio#6_CxZ9y2`6f$et6t1v4-dH%1KvtQu$#gtj;N$wK73_UE98jG1LEhK%!_k^%4t^#IR4+RHlTm?Sp6GGV#2~&WdSI<1 z(r8LVAjYury@WI-sdHT%R)1-f{i&s1Dd} zNM|^WJ8uB|>|j8$Rw*>z`^_ZDY+E}@U~R(f=vK*>~}$((@6 z#+VI~fb>M4NuICtA(vH(haVk&>H(wHRk7vs(0ZyiP{Cz~Op{9ufZ)f&%MOw~_t`IN zFp$S-HuaMKRjVTv^^n24!{Meg{>-Ft098Fx;!FN-ZP_(Q@`%n-q-j&yqR<36Lq~~t zsuz{9tcGihL-&-ZvMNOt+r+*rYfXeOsEoIVDAlpCOxR;UrA)C4_uXlTR(s#4EA|a2 z#@Rhl^B5GiQUCe+>r-{P&!x}Kr0ek--_so&|LK+(mX7vkqucanTZh}`>D&{`U1%$v z#G`dlNVdhts?c>qI_-PhxmJPy3zaik{N+ddVX4`vmwjQP+4;xmpor7im++vn)4@kW zk%$x83+;@MjErFK!K)$n1dsZ39Y}HgTmL3qySV=SP-JE^M;(k)M@+xxU-l{@vA+{u z8Cv54s+BXAK26`oxi7i(6koU1yzy*OG_@!$Zq;(9Z+7@rdy^uGU9rPNnPvTVdIdb# z=B*|mVCR^~gMZVF1bPs_+fIZ$r0VEdmjwEqlLB0IwJi{5jcz)p8IN<%2NL;0TX_e8XDK22I%J~=+7aKMxr$puBNgAwr)*q4Awu(=nc`_fP8$LSS~G?z zpOKBD>z-mun7{^x!d}kbHnPB?=l0VxnAR5t^Y}!wF^kZdM9~`_L+w@Z#ml*(!o@rz zcE1>7BvK1U>^x0PIQIfGZdmG~w-Unvw60O{aM+-H+EIvF6E)G%n@p1K{0dRDnf8EH z)(FK4Q~-4docYKV(*vJ(lz9?n!YSau!V~LCWTG*J+OFvJV3WxM88Dj@NaY$O(uet{ z*l;pss_(5w5e`|PBtQK8%JMN{aMuP6blTcz@Czl9YeTQiT{3dyrX|L|UEG4}BSBY2 zm4F*UX%_RDe_!kazh*OyL%s#jg!$ycG+t~7#}+|UhDxHEirK8hRDsW2!O%J2jhLaN zBQV_L9ObcqDMF_wS@I0TT$O6Nj&ar1AH(X#k!VIY$bwEUPOShp=x&6o%_V-Ti!#Q_ zWY>eO^`|5yN<lyOF^?ZcA5$iTn9;vqBqB9%tarDTOHBVTiG(Gx7LQkLT%S_8C~Y zxGQ3f$r!0t(g2>w8Q*H6DVyVkvXn!P_ve{$)gHBasBO)^&^m*d^{>u#j91@>!<11) zCgq(l-W!?kwlTFrx>uAS)(65iQA>(oF-T%RZx<>G-gq+C=`&OzY~e2hLb#DIcENYd zMN(m0lNAp~xJ&3%y20U{2g&ea+l|DG34P3EG0?X4Qn;g?W0w1$yv%=Qos$PvE~|?qew=h_WqEr(;3fFk0aUp!pS(-a2L%-nKxqXtpqTUze=K zU*3c&`x$?CToX8kylYm>nK1Hh!EsktIX}MmZJ7+>JC$J>*%fU>{jtL0U|x?3Y-WL} z;4aLH&q*h%GbZd-8OCa++Ksa3yM|Ll6=B%4fGC`VJ0oPV(%7G@ElyL671+mopE-F& z%JG8`2%I4_%_UNI7I*6UfZHiz3Cp=PB?X-ZGNW9HlIyf$FEF5HFMLTPGIRPM#bcXG z@;B?XQ)umaf@^AKiA$VbWjoHE!*qlgno3#swy`PHX~SbBlQlx2 zVLtCyDN%$Pi4q2O2pn5Q;#^t}?O+)Zw~Xby0z{erX5_G~-f+;sfC?*cwV zw&P{RX4>B?iw8|I_gdi^HmRUssg$l7=Yc1-g*^TKak5Nr zhFG5hF~kHSV3y*@`gX` zW>pYg;DlW&&@3J{0>x*blieEsnSLM=- z6KjC1m^saT6z9N;Ent=vtZ{lPIX5WAngi0JgFB0&U-}Hx1?uvnJt1)plUPHj*N~11 zkvo#%H%uE=IZpwFx(CC(nwzsS&+rU`hO9WB&*s}R66w=2cE_}Tl5k#|%_QZ$3~(;n zUlF;h=4n{(URtZjoBSO>*E#ErIM~Z9S+>G%pIA8zt?CCi51Gd7I3Rx6jJCASA$Zu> z1lBdfOB>-N^*nbOB&>)tokX+Kc#<$*!3QRBM2y)?Hgym=0G4suqiqPi={yTDP9Ta! zWNqUl+J0CRKnS*1I9a*Zo`rNk2>f^!9(nvUX{B@ zQvXmmqY}U*$lzkiuQ=@7t?kq$dK8(Q+XKHyyX)REnU^P*6hEo=2-&)bu0m8eoi+}+ zg6Z3!?VSWZjymxK>G7^cL)dz1e)?*r(g4{TWwO+Q+C7bi=LlykO-2I})SZ zjyojGQ-ZyZG_-_luykA=IZ)*rV?lw7D&-jFu^%RzG4SFT@0exUs~C|^@|Wj041sgt zWFgpbGjvvQG!vkT5UO2wb^kk5UK6b2)WT0i8(Ww5rD`O1=Ez zidwQsau`o@)nCOWM|i_4E%QYf=Ex~OzSw1NbuF1@?kdG$g*ZFfD9iMIQ^G%cr+A#A zqFXAiS^&?bUuxO;}Bhm70n%T z9KDqI$MZ3WU>P-V0A6l6w@1^LuW^9;%Lq@+_FNl1DJrB`EwM4wnc^x)CHGuhK(7T6 zbuK{X%Ub8l{QL1Q`1^3==TXL9X_)o*d2)*;A~Y{Kb00>>L2TG#m^ZKPYD?@zN9hF* zxbtRiJxyPtHo+yqOew(spPoy4gGnlmsFdAoOrzW#VD0NA_9?Y+ao}oqI|ftvDTBh> zVkc+9>T#F9{}r!gVkf*~UY4dX603bbX2YIf^OpPylm7~n#?{d`2;6&51+Vz@z`icGzj}p|4 z+|qIuIHfQD0tPXxh_92C=8Ce;eZ-~V(u+Oz8{7Ewm7CG@ER#Lvy@P1fx`=% z{8pBWe($k1h+#0^3ic*!ZNL$Jkc;13_4ZWgxOJ!p*?%O0E45Di?kYFZt2ljp#S&i+ z*&kBa&fb%VK_J1jHvsQMUzdAIXZ!ao-%+6YtD-PNbHVJis69Qi(T{zvW|W{vQ2spyM1XD$J_v6LJ}+>_`A_xp(+k_AV6EL+|Z zNPGx9x4iE;D~Wy9SA#Bz_@fBjJxGsy_lsK3s6QTs1PnR1-t!ofyP^EDJEsIvq z;e|n*XyxwK@BA#(0dldGZo2rESK;JYJP#0$#rL@C8eW!JW-h3PM96op zl!x4Iwzu*50?6+@MFcz_z0R&az6!%bpI0CHN8GmeFE8i5Mncf?8D8q|JzwRVDS>2R zy_BRVeR2F*`$x=v5mek4YDOPDPf_G-^?cOw9YlUhGe)|4MZ)nrcqQuLKYGUX@ZdR| zA=&bWbJTj>Miabx*vP}cxi);D?SGhz!tOYMzfPn=2YRg?W)AMW-fbTPW}lOCrx^t9 zjcr(luUTo4Cn4Wp9&R#DCN6hLS?3_FDKy&WeLtoN=AK1!ol|DY`N7Aj9h-g| zqu^sRUls`O=TA939)Pb3Dc{eVK|Q`BJ$Y;QP5EmcDTcMd?Fs^c0Gxp@kM37X7uV0B z!tdtTk7u~|=jl&@maf<`u15ENGZCo*12n;>+n-o5UsWW&C9b|t9HOBFb=d;vH3Clk zE$G|otxz9_vDfBntKnkX z-b0(xUz7%m0j~$wF7z_zWWH{H9wBGYpy;H(W^-*PfqMnejuqMjfZQ^kAsNO05opc8 z`x{Th)-zH4)41*JfN50rsNm!9R4@Ik6Rz>HdeLUe(xWGDZ!E(7oF zKajBD7|`lJ!R!B}iTqdqN@RjPF9hOhKx4$g;Q$FM0iLFTiM#OD?{OL)0Lmk3MS=x^ zf3eM&0W!RR%G%lz%j=LPNuG}Q`xf{F;m7ew%xKKnJ1j0(4T3aY2sFEwZ4zQV^HW<= zl_22%+a26b+kc;Ds1>rt`R_}j2=*25&rrbJbSA%4(G!6YXhOdN(GJFTpT8)8j~!7T zoifUtw^G^vbb(1u-+bqJ@{(J8iyx?Tf&7Mv@r~`%Mg)eY%Y)3r*m;k0kiU5O3LWeM z@SPfZQA<_D&SQ+FqVEHsnG9X$hrU$WR|)cJ5|YS=kLL};A7xPQMWE~Wh4rkwuJ3<3 z;G3VzN$Unf>c7hyPo?CowqsUz`KtLWb6aAs1E1zD_B{#uUGzN~p7LD=zv@&rS-qJC zzsk`zk?@!R$I-3Gdyi4G?^sY_6P(L$)*a!c(=`x-7f3+>9`u7^W8v8~YPO#O!l8h#r5e<@(Lh@WgG;SRxQMU=@uv1Kc#i9A%R+$@#*)e2bGW`# zLI-$|uU)dFL~Y4T$rEIb(+6UG_;uOtEV!1V+ z+slmIwRt(owi;}e0?Z>v*V(^s0^Kj;R)=VYe2dXxQfCR{fm?L*=aWdga*46caY~0J z5oYI$X!ab5Sc-LaIP>!&=iSu_$-m=i77En!%`s;ASJm@iCH}{(UsuRBFUQeo&X0r7 zp&Z<1g*F<=jjdJ<`o+{TH%XW<@9UJUCiAXl=uTY|)zd~TAv2L^R*Vsrt?c36c1BDX zs$`Db6lg2`#}xW2XF8fOzkhcip#>-v_hRt3qUm7cFO{R}=(+~m6j7Y?4+T-7tJm+e| zXXR{qe>~(Gn>1M}SGCd!Smb0#x$=p0UgUeZcqGF6@LpL=0W##iG#jpiQDatlT30s0 z`SQiY@QsvJncq6^)ku~p*!me^5|J)B)|<8D-mbiwi79IT82^yeT1LgWE=_RUEDOJ_ zW%z1R&yM1AGCg2;+$`5=dZ}J$urf$ax1CPowWyjehGW%=wLcYb6<$Sed93?2CD~BB zxv}9{k9SVtY%h!6fslO3+u4`FUX$IZp30J$QcpOFU1T>UPHHb*;%TfHRn@Yp$$tG^ zO_x&J+^o~mfn`pePd3`oOx=)N%VcXvZc@4BQbNF*NxrH{7nwgdbU`o2=jS;Hy#38T z;ijo?yOcAQR~nP_x+b(!y~()v#KcHfHtK3s(ZJ>vFIZ4MhrD82D)bLGu0Do;@DL`_ zTu@RobgmUO(D_IcmH^sa0y1YGD1K~Y6)(VG8<{J%=~f%$i~Lh+`+{U7AoF383h<~} z-MB)`Cvld6%TRSx7T@!0GzDuWXk$;a-2D84R3p;an|v8h3)01rP?FF+2My8S{RSuA zv)*R)E`&ZuW^^r?1F^fVq9!>*YkIVxjW*fW@UxGla9wlbr3u(JX$ zcEX`_N0>U%bWASw93_yJ{O>B(P5GhS4S2ecd^rFpk-;>X;qzg3SKNCyLq-(%7YR5S_q#PE0vn(Zhb!`Z7lK{Iki zZ160P$18JpEc;4<|3SU<>k0|LrLUcOuILtX*qE}0 z)Hs~MmV6hV^?MyZBXCqcJ-u7+bj-Vmw4$5~Vur_A4%V?jJ;VHMP|HkOM}6JI!>Yun zO!-ywx^tgf+5@QZ4!bp7X>N-90(9OF2yaA?%?5 zUB3!(Y@WX6K4IU_Y&(5_?4#h7FD$J(eHGX5VBzoC+!eH3_D&|UmK#->EMFVfIQQ(F z!Fp&N1D09hHei6Ul?BQ@cWChI99c$l7h(}bpmn-B0^9^ISm|}nrQDHqK6pw?()8AQ zZZIL83kCMntlVPdC!&-lIniY=2Xw&I+-SAVfVTU!Ea24G6K$Kt6}VDyt|8rq>pt8_ zhJ+qaO|1Ef+NKjuTNTL`3AR_veqLWS5C$z7n;yw7sS}Q9oG9MRvV)GP9%!rybB=yE zIWk&pkbK8w)N}H_Al#+1zGFfcOUL;XLO&eW)DK!6F(sdFWsW`kuhW+#MYi(LdrQrV z$NCEznRvQ4;t$wVr@GDyIqZil$9rx5DU6rsqh=z6TZZnx%ZkQ4uST{TLU*rUqLxv~ zwsk~4b0%G(whMjOTDGk)8-QmVYtz+|^3Vqg5OqV~ZvWCpZfdI#+xlU3MH_)>hKC@- zS5??unylsLSqC~r0ifTl@23(*21ZU8`0NgvCG+16{|48b=d>CdLxYA6uM9p%3O+%5 z9+rFWQIYN~4E|2Deq74=OdBWyt?w(^oa!G1Al_mfwBdc)n9M}QnReu85$He^Z$BJ; z?u({zP;aiZJj9Ye9D)s&qItIP+pQ!w@#NgsC*I-!`2AEoXNB>Ezq2z_Unf0-eT?6p zoidm_AL7{Q8LA!4@-^z#rSmT<^)WE=0@E-3y#w-PGkZA6F+bdq&P(sQOL}lmr0!4^ zaPDu41W;>=^R(_)i&|#-7By&_(zVDneZJvu3eOejJrLgrc)<8ybtAI%nS| z!+)h%z#sbHCUdZp*s`)i^nMUH6*=bEFbjak6 zBa*xF+X>)9R}kbl)_mghTsS@?-2&PX4UWgG~v8Zpe!JZQnIq_I%k~ zUlV7veK)@5o!OYSx?Ko$Z3x=!>pAHY2DEnwW?Al9)U^ypVU!nZFKAm0Nqk+Q8_?t5 z2xVSt9y!r(UNJGacCoESEC(!A4T3*h1y$(Kx{Lz1;R)>(P?*TElK_>FBULpm6YgA7 zg~`h&;_GOm5?;$QEQ}TnxH<@PGYH)6T--=$dSw(g;216p6tUfYBW8`_W}fVdxG;7I zWnIhTI@Evw>($81hrA>3u=Xq;x7ikCI2@ty@cZ9L@G#b_7QP%Tx-4fpJqKm6)~ts* zr0NPj_J6LOgj`@KMrc=mH=DBDCVIwFmTp8+7f56CThjYRM4Fm z?h~M9S`n=8m4bFtE6>pOYp_7ys-aTx)MoM3fBjM_$}IAE0i-G)wGx$hkbq2qeJII! zDO68+yYCxa+PGqUms}ZeR2ik86hDw zbV&Z2vpjj_JBE->dX}$r0Cf*sy0T{--Q@m^Zf=845@%HlVq)wDy!}>c`GqGhXhn#$ zUc^2b;qi_U_z1m32=0xeQKxbK3Ga5EC3lZ%iBh&ey`WhN-$uNCHI(&!A2KLoE_>uq z1=JT}`avt}A=pfIQ`M*1no@0ZXma??&w-=er-2pa*QUF`<~t6%#{r$S-Oz?@Dd-Z&!YZRJ>32b}tJ~Qy1oHK0c2(%4`}h(m;A zlg;Z3i**`B1;vgDM!WK~hK$j^{#ZbVL}+I@OE-nRLsH^7#64gr7iAIx{8K?ia%pLk zKqw+rl9^xuH94a(tOQV_~Io zBhPlN{ur!(zgoJ8J4C*WxV6`G1jZK<1ph(kSJvQoR}eV(+_qzYgTjn zw-deEu-JrcClwY)uTNuy2zT|If9u|~2DS?~eUIp9ec+*cenV1?zk$B?vN`E$h|u{I zs*Bxmf|I?~PdkHhig$7g27>b|BIKUOc1q<#vY+#rVw@ggRYExH*S)6qe7X~%UFRUZ z3-R$q7wwg+z70)lxLTj5#t7ESG~9QwhO%Ru`=9n_{u!3LEfqqne}t{wI9AbmGj};X z{?6c5`!rcYw*{OUn}d^F--@`7>ecKxxEpw^suj_zsv>vi39G`e`8X3WCFw`Yp~<(! z;ADDz*5S<^()$Z^c`=;W%{SOBa^-%A3`%+kKQnl_V@-UY!6+rT4;MM{3 zY$LID*+id8cy4;T3l5sG>6qWU8Q;L$c1Nqh7!q9^{KX>2z0RSW#vug#a{4GsoM7|I#p`J6yh@;e=)dGIK(>V8kABMJ0yPBC2f`>;~+$~|s za2R08!mi<~g>IHuPJ+4Q*PRP@Md-ekbvLeEkdKMkwc`HwR=qhu8l{2GWKHSm9{SbR zStmCwTByx!;NUm!7*0+RhYm00lxw7I`&HXeY6oh$(`igePX?63=RGofe>BOG<>9af zHq_SutKao{MzUA|jjL9aXP!}`Lip$%(f2kFe#56A`G1m3SP z{Q+G5^ZN=1GY3Ml0JFg7>r#uGh&dy?T!Cp1!u8!?Yy7&F&-@tPK(*^dom;yZ$Tu>h zvo@Lmcer;z7Q6{pp}k+H8O1Lv-MW@ze%hQsvD-Q_$=KT zo~s=Vq#K!mS+E5HoesgbG}gF2>1*V=I2Jtk9U9hQ)Lq&&ayR0J2&{D-7ln>?LKcn+ z+ZNz1=GN%C|7ohk*JkFmQ{rw{i#``8N{)f&MJ8kxSSRlOt?etY39SNqS%(?j$>6mV zYciLc9|&xCMrLIL1Tf!$!Xn@J;|>7UJDu~_ z?gn~EgJ3~7;VN)X>pG)b8a$T5n#|=iVs!6y-e>%l2FFB(WqTL2$2lwN_Ps6Nx4d49 z?R2$hA*b8pm5dG`jGmlG>a zrX$mACY+&uc^;r=@A2%LWInhqMl3kZ7ffSV(!Y8mzEi{JWhPc#Ob6aHy8&>S(r$+2 zeBBP60O*;Dy$Z=a_zt}Oc5tRXzWZz2oM2}des?jUAfBG!UeRo)u}*e6!)_|D+E*tE z?eu@*UX8^TnyDa6vlCoVn`jl->pCYZG)z}ZyVhw9#A(7N`x(;y#keNb;1}MOTyyrY zUh4;1)8*2xVKo8aG_~negJj=>V?r>!i??00f64HaJ(j>zqM2LrXxf8S#|S#`7U;0bH209d_9J5Nwl8Fz`AF%in$oWRu%a z;A>E<>y1C#fLTBw>=p&JF4zPTP|(6X8pEI|O^ zBT-_H^BF79*mbaq^ANbEaRrfl7rtE!sbvsnI5cf7SWMYT0$i;_qX~lh=ALts1n=vx z_vWsj@{`PjtP6L*`F>*VV&Eqr2+X$=V+R5OJhjhs&Te;N#!vqid}jxl?J5 z5YFMl?IM1hgMQ1bH)+bzK9L>tpUXXexDWX0jLgC)1^LBJ^c;*rfMkc9v-ZUR1ncZZ zSQ2xrLo^D(-FD{BCYBwnxBtDSIz-zZq+L}YXb^E)_Z#A_lN;%hk#(g zZ{kP-+;uLm`86VdVmFJJiz5JtH!>r$0KQkq<>&KZ_DR1S0U*5b6`nQ21TfaM-1FC8 zV&2l3v$@#eK(_5axV9T(G~-hoTss_gmUtts6dPJG zvoOQ~Yu)9Yzjrv$?{-q>eit|patx*wU}5HmK39iV_*!WB5#GJHfhC9Fz0e`|1==&c#3cxjI#kO(3hEwQdfxu?K2p<}i#OE|i%I!MJ(P z{ZW4)*?7&%pI@YU>og-+mt?EMzAR;mL!x2fGOxj(pD7M~Hzm(cdfRJsp<3bq-`>Ue z7yd$@;e94e0OT#h^Y}EF=4m)iK;dMp-O8Yxbtk=vPcI`rHz%5RWH{uTzB;ARnOKVp zQu%4P!TY#!0OksV#GD%biT#vWHf7>%xO(~4gKObFtQ@~Z-oAd#0%R{m$npm1MPIo_ zA5A&@2!ODkwQj&IdQQSG-oWR^(F(l3!@z%FY>rN};BmNk2(Dz|v)*%WxE>0|-HjzD z zJeAB3)hx!`_=M1HoA9;Gd<_%scQt8qE4SyhEbNwC^Y&afGw72X{FY*k=R%wMQFc3t zbGc^;v>n#lrCd{U>9Yy;vIYzKmUxfzG$VcNS-l`^?QHy&V|6QWR{LhaQm*k_ zjUY{A(69~ZLGhj~V@{dn9!U1~m zZjH5R*F~M%3mnKdx}vkbzybdQjAn8ETi&N$mJPikZ|CBhoBi-&OSeXIe}Mz>MrULe z@Vs$^LuCCo*c!cVCw+mpd>z}~>pIr5=ict@rEAXr-u{#`|8}nYrgr+U&#SW7bK^4r zG2KD50JGo)%;>6TCTEp4Z}wHDwC`u+t1QoF zg*xlF`5^lhB=*@auUOEuN9KNo@NxymOO`nAeNveLzL#p0oxl0eXK1m8X&UR!F09{d zj&u;vo^PGv41ajRsfn9~`V2phZ~S=I>&M?zD9dEypF-sFEiMgcd>Hz_G5b-_1SaR6L8emUeNjb0MKAC?o0q=e#GLT zVTP@&9{2erp>oyw!tX=fMSe$Da(RV2PU8S5+!K;g-Q7X6gXaS8jld}9ANSVfeoJ!R=qn=@VbHG zcHual=;T#@4XlmKiO+q|bs4zt0{2Uu319kIf5IR1lReNM-+qJ*27L~%y9M}6@U>90YVO9art!g|Qh@{RV3 z0pdGNJ+{=*+jD7)+v8I|J@}n}soR>Pw)YB(vjxpNc)x%BDx~Qs0P-K7eE`6uTP(fp zAmInBHfyOk+vn^<;X0Jw761(i<17e3F9zeU4nP-&ai#_^X?lTnC`eNj6!JZ|?PTVm z1K_8lyb=g=g>GD((^YD&^6&(oav1pkRvl~R`vjgx;!-!F<-wS;H+8l;NM;^D+ zGQW7#Xa^y1-eDu|xXEWpP9~W_fVQ~Y}!SVur z5hzAV=*J#{mUi(zagL|ytLH)&UG__E902quGCcdg3BtaUu^&4#mUOw-0n)1K-;`&R zPDWT~;LY}YM8v4yF2(%bHsZGyzjmvfs6DwSz7L{(N+85e$|7#c`f_D9<)lO+-vAH; z&D#-C%P8$|*n9OQ+gxj}2;}zDS=*>~rs@;g7hp>}M*Xu#j)ts^_`)Y|2!wgpqkQ*K z|00Bj5kRK{w5Ji7MqyNY2%h{}U-(+~jZ_~X+8fGVOo&b)RJ4r(chR)NJit}|>U0;o zoVUFjtVpX^8Q1{cqF&&iKka5Y9Zis{c|-qc%9wsZaO(TuhZovR{BDqXc$c@2KWGCd zI5@r*+HE{%5Blr}f?Dt(ohvMEI0+j&sISak{lP6PYQKV}km_M&Vf=;fy-HttT8Bc3t~@CzvNI z({8nb(G{G;z0yIUW&^W zq;o50duEJs5@{Imjarymddf>-u;Lg3Ji)YiJh` zJZBJ=7drpZk1a4CSjgRB-VGeLNYoV7%fD8Y2%L=eyTyjp}OI(=SpD)$DJ^^Ze=Jo!+qcai) z8$jrToNC!mE_&3b?f^i_7>>+1)eS7u`wS zre{`a8(x8&jqWoUuQqap{1=_(`d!5y^4I7sw2P<9t2g(+?Fm~SCGjKS6)gV5Z~-!J z?`LyiVS+37hC1Htp@l{79Ud?Sb)Uke#kLqfBb|Qf<;Ta<>wB|2Y+^XUGVb78{#!eQ ze)RQ3>x;(>U%kT;VW(VsPV>NDS*%i3NSK2vVbpSirhxT9- z-ZCf-bk)X#?UVz}jhduaWWs^>nuGn4-DfB(C_Y>CCl@RYH1@Wx89m#;cWF=BE4k(% ze!iTT?6Bb2)AvDZ!9h6AAVgnT!R&bb*sjIinlT2gR=={7GQt3C-Cr3G#PJ2N9R@VB zVVCM9y#;Zr;cdraq8Z0BFa6A|3XKimVIOMX?>s0(1+D4N7vi zI}H390&P%1zOA5W*v-xGp4QPtdq6?lq71% zT0pRRegePRZu`4%@Pi7~yYX=lfWV0v&&c)vatMI;(0foz^Zzi|sMl-k)#C$@lUn-0 zx?R_+wD*oeOK@A(-X@+SAt7uh!P4z%^@da7lH?NdUY&fwg?et1-OEPk;O04Rng+rs zJ5-DJcjNtDuGVio-d^n zAkGh6E6^8o!cM=;lOEldaHLm7X81Y4&?F1DPcs7a#lO(MZ2daH2iwhTHslT+otR=$Gv&Pq-)E(q?0$WdU-zUKDMQGpB2Gl)r^W-^*!f&$W9QJSd>&rLW zb|LBZmChM$m)T`ku-~SMDECVy@UMiS_WO;t?yuf#dPsBrBJX;V-veX(9)&*cv~57zRx9XHOa7}oh83;QzKVPQZpJX|AIh(iDW!jJhO=+< z!aQK5yXCK%*?!$tChD)zg5+AoNc+3B+&OUu*a`@m|qjn(q@9)8Z&(^dma94SOS0}5=FWL2UgPoIe)j4B-fF)o~p-`{3x3gAW?VYOAS*(&vx zA1$ZnD_iY<4^>FGaJWCF0;!mLJsrHhj*8(~w0&_wx9Y8<32-$||7ro?p8B-TRp#gI zv+%!CFtD@iL+Pj>9{Dc$C&fkl-p;L1y&cE3XIuK0js2@g!W$_9aN$mI`FBM))ldGr zd6YYn%fDnxT7b(ci#hEwe_MF%GU6;Y-;LRN z*&LQ!M_iK?YVF%qh{e^(&iqSeC}8=)(j)h7bn-o4nECDK`(OKC&(-y|&E8&g@~r_p zm~hp98%Me5xF{>zt$y=&IPmX_(!VFG9nQCNQF>K#C;#2ssDkT$E|^Za#@C+nw{OY5 zyj+;K-;=~1_t%A9^|-qR4fb2u>e}9pEm+#$7)S57{7v?Sh^!0Vp>tJ!aS_PB|31qP z7w_HtnIp|2%~$aSGxP7!dRN%(aUnZ8`vxz}d?x&Tt=5;qn9}}^EkzD?r(D{&wNdY@ zo6WK-{)(FGs_ps8c;w0AzEH0AyfpaowLjD>5%L$_u9ld@`xTlbdb@lzo*9;Tca3G% z{YBbuseW&2qWO2ysP>UIN?HyRYA`-bUP^_xsK15$~7yRkE8HiRZs0UbGV%>DORlg?`C2yY?si z1zb~#+d{v(O8+{&XoI-WZ_53C3%qE*Ec9!!>mv(PJN;f4?-%Mu8=4~hCW!Z2dY~Ql zBmHue`(2w!d=4ierF@;lxUyWHV}*Y6Sqfmj>095%S!aF!(EF~p!}nWOU1vM}nx1Jd zy0zYDcly0r#ovNEZ5N$>zr%5nsrVc5P+P@LzxFCZt>1<#{w^=K6V_C}1T_jh=kJkz z_wV#8`QE?wk$&B>)9-?*ezkI5ZY%!2{$B#qmcLMzp;ryOqs8Riz1c71?SDJy-0b(x z+j751E3w@+=kLQ>W&1VlR*SM{lk?YD{n>s$CDO~-L%gpX_;Z^;X!e@{@TI!wFX-KN ztegF+vFNYcV)-38f4ibzw%<>i^d6Il_p5P={vN3=*X>CIzE}#I{niXn?)OG@TfEKo z3w2z^AD$}y1}%T%oWHSlq~FHXeZMP3e_y#L=Py^A{c3rkUsb|$%lXT(*?#?dv>|f- zUIQ&PQH%bX5R3kn)$CXGoWJTf-03#^RrBTV<@~KD+b{dfZ}$6n(O_PUQP4xmLg%OATNItOOjZc?<Yv|`;Tmx8E6JQzNmAe6V ze)Z}F^?=U|Su1^gr6V#R@UE-`tP>De6rNcLm~lYD!v_QozoCGCcy#ui-jJbye-7&9 zs@;IV#xxNS7{^M$ins}|aD4(V5eNnR?V;L$z|vPT6!47(G+{}Vfc^Pq71q*swi8YS zd<_V^J8T8K`KdF~%?@~7OV86xuYb_Oz`Kj$gH;k37IVu8{4J4z#aopGo_vkoLybS*Kyu<+PZR> z(OBi|`NElj_><7)32m3m5ZWHu9QW&wcEn$9cO0q>9Kz1PWpl@^;J{eV8BXXB!Gl14 z&e2sXXQp7bF2PfgV9{h)-6&Xl#->IUslNwM*>>%epzK2A{h`A$$q{^c0a#(s^O&-pEeTy6HVhN(XGl z-O7eeT49D2@tcWdZG`ds^cIzg&%nY2>*$lRvdXbcse)$z>Dj)jZJr=C{k~yHkGD(p zSuFyVHk4^x%Xnmiht8*FTU$RE>(fI^u7=id)#19%pZnU%K6FC;4QOJ&1x)7H(q9^kNNW?4RQ zu~jRx;z0J*tz^@5E7Tm(R-IQOuCH-(;F5V)MHhlgHzI=ri@(0ULefBCC#_JW4ctWAT%};-{VvZe z)ou~cSvldXoOKxR-GdhNl}GV)utu)T4RyO^J-Kdmw(t!c`Of1P1xVjry@ju*h_CK* zH=c90m?F433m5|Ty?D+$-@G@C`s#ljT-hcQr`-hs=04%(k@oLJ(#Zd z;JEuz;afOpEq}W8u71x&+TFRKN_VHLcm*{fS z3gTXwqxR_h_>?J1wh-+@Azr|Wo75iv=2OYb<^CxK@3nDm(JWU_0eIE-dXBzzoKiVk zniaCvDlC_-JqLLzx1cQEtp9+z_-e1Pd3F`k4J@0O&V)NP7dzQ*{&ovS*nd>?+D-D{ zzXmEXJ+2yppw=4g)(U?rev-B-b&u4#1lm*i4yQu;=+P)+ls~IhHk?ckwd!*Yq-ml&jh&FnjIgN#`u3QQ^>)v z{|zQ=4Ca{;{!C{iCio)8Zyr|__fB2kmciwLM>od_<6nZw;<%%mcdAo$H2U+K9OJGp zV(j`9C#)uvy@emtq;m~?tMX37-A_;0t%dZnQg~0)AAD}qt(DQE zmkHfF6WeInxl>PkCHf2*`2{J_6a_)U0&(w2RWPDz&zW^5YlbCj>Ed^Vd@!CB-Bow& zxw&y>8ktMej7`ml75RH4-au;<271#ug!Z6)`Yo|LC}&t*Q>UFPG-@29L4IZa8ehASX>P)BS^Lj83_2P`ehwXFORde=%h6+A?P6_?qguMxRE!(+i zzW}=RZn>V<^>ljZ^w3qk#~}(nOSf8(LnRRrq3xgH>$5C-o|Wb^N6#sOfT7Rc!YEA( zQi|Q}UT0qb)G@WG%%-m!9`*~ptfSLIPkK1|NMA0HZ}1=YgB$_7nFF}6;p4ZAO;?`p zwZ~Z}tWrH;460J=Vs$R{q}S7&-p=X8-~;V{_xODt!no;5lKs;6l{^88_TV=;5Eyf% z1L2{y!J`Cuo-8xRfV3)k{vl;6X#*4FG(|5OyzMsBkS@3OB#DDV`+z}%1y~9YB(S2Yx(5_YNvQ@hp1N+qD11ej(3S$% zR+kq9Ez9Ngz(HHAtOlDXBPAy(RkDzjlm38T)NQG%3``xcRd2JD>e#;8mG-u%9%X2d zB~(bzqoXxs8y6Yd27)RAYD_ddMEpdr=ue`bJ$(A)(Syg2Wdo;4x9gjGZEU{6V7y%prNn`h8|LHb-M1%eiqBnGi&(Ig*dqRc&klMTKz_8a^fu~-a0gcw4_nyBPt~- za}ju)cuVX|6)|Gzw5ls(3t(+E#L{V1x3}ys$5zE2MJ^Zgk=tALmmszXtC|%>>zOLz zkcPYTqm=aU!OGHE78Vv~wq#=1Lo1Kf(s{)$x?F-Hgo?(c5-%e_mQE`=EDNUAHn1pL zVwbwsGgZWx%H?00)pTvDV^r3rIyPl(s$*+wvxPL(F{m|LTw6+0t73ZVnJU7rn6$2b z7a$B`t*xq2Rob|N z6O8IFKubYvTFd@YG;{^JwhDI0gW`I2<)NvLLBcDI9Fz&xvlD^NR1sDL@mU+fgtb+% zC7n!(OQ+S`63bQI5(fiy$l7X%C2H2jE9&~FOFs>CEF1}0I<4xa(r9!#l}4k{=wB15 zG+G&*N~cn3G#ZUcrGHXsG&+?|r_(>_pENp+N~O{0bn2u7SPsFp+(G+;EZ1V-3)&mB zU$tAg0%y>ERpnHUz!UhCAMmR71XAtqsvB_ZS;~O*>vz#cZL7vDTfAT3^P@_9~Ab)g5s4Mznq62coc1Az+Lhz}0JgO7QKpZ*2lhV{MB z7sCaB!Uek(u7xY1?}SU?TJXAE_v`wXceR5#7X&Te!piao?Og7FL4zv=3#=SCf~f-r zJb{{D>ZLd>+I^+2f$P^RN3~;7pTI}zwv{%N6=g@+%C?=_egbtj-AwlrrfccaRbcW` zO7_KcBPS^-Rcb3qDQRjaLAH%b8!bZMGE#KFP1NWjI`rrv6}pBlp^NAaa=e1>W1vRH zL3a_*g(@Q6#Cv!b4f|X__sS|KFKxeAz$Z{{lqUgB0RNZ_aGNMua-H|j?+B8cq{ubW=Xd#p47o&t+&w+M3&h8d zyt|8M*B8j`v7_$tn7edxw}*~qj<_2*u8qDrYRu>hMp(^Q&6N*8|AwbBkOluU9mV{Z6E96J z{#KqOWqhyviBq5t%b+rze3&_9$ZiY+uNXyR85j=d$-F?`ll?q}OeyQheO^Mwl=Eah zpOqWsIhjsQ^Hmv6-t-DQyZH;B;c;dI&6S_v6=cLW@HvahggN>M{!QF?(Q^ z&v5yrFrx&Gt4xZo45k}vz!^eTGA2UalDTB%9=QN5CGM_Zv669QDpjWF0F)A?#S)5tBEpcroHkH_o5{0lwg31(6|1@{)`uhcV)%8)v{% zj)@V5%V`u`-*DNqIm>3Tqc8$ZZ0-xlCFoH%N>5y*7D;q&QkJ?9F{ZWCiz5`kSAQ_ zzTA~_Ao-ECa+a(m=VdIhY?qB>B-uk2l7VC%d5c9ZlJ)Z0kj%g;E658FbY<%#Hn{hNQ=w!;YpK(DC<6vBjk8v;l#jzn=Xn|1O-o*obOS=Ky zC5vOnMa+m5u^O!r$6mxB$Mw zS$GQzSe;u5NbZ)`ZwWB)ZAy0v;}pnA%> zTA`NlL6R{;2m&$z&j88p0K6{-C{;-@~T|7Cd?G zypykEhYl1ubK>;DDSY!n-VNbkH|Em)NuEucHA@85EWgX5qTnAslS&{R+zuxjo?aFz zGM-X$n6YgMa_1w;lkp7@16}=^==eZ}V-k6M9uvQB{6sK{A7jXoI7h@VhHv+y$Ph67 zU(URm7xYjvh@a)LsGTwSC2yyq$oF;Q6;U3_AhzxVYJPxrZA- z$&Dv`BYZf%@ByDR`}4e%XYtH`@<)Ef%Xq$T@+v;YEBPt!;$gg#K9@AhUd=1n{SX0&|T>v=vO_-8f#%9D9BKjXdpmap<^Pvplum#_OT8PHn=kO!^F zgGRhz0IBRMA9_OuDb9l!v&w^iB|^??*pS=gQI8=*M)Ymr!z$!V5B3x$bovM{;cNO` z@5Pl9c&*=pkSjgbXZ-`pZ{Q%Sc~!)RXz(5KVW`K15(`Nd9^lA^GSmdBF->9a#y#*N zPnv%0rM^lmugQ@L2zs*TfZ#(ulo?ry{IdUWAVmHX3DPl)K&YgN)HSW58bQ$m0~G); z7*rI921Kb400?6r6aW_-mLg-tkc5B$0ssIY07w7;5E39X003ryq!a-acdY{E>am#H zMZW`o1E1rZMsFsKQnG=bDQ?NGxjSL@{>QNl_3zZLPP@R9s5}{?HJOwZr%LhQe;@;W zFL@vJZ)N~*>CvyziJ^BxrOEV)nVo#=1cnu%(dd7;>N&)p7e^Ig zpW#&E96{RkG1ITNSZCR{c-arcwyG`xS+0tX{oyBA4$YR z;1&bxmywSUGeZ&!u0{=p#zKOuIb*j&-qmyiY|0A)uD6k&$92c;9b(lzOhy|~({Lx( z@xgZ{UQ6UulLgR2Mr+R4Pxx~o%xhZwy?~l5*=Ur*cgnJAY)u?LgMwpbsV|_pR8etg znO+me#`lEv>ENYzZvvat7&FmNif`%BTbYYF=VrT+uY?1ifodzpL{G_{YUkbb>&`d0 z(>i8tnR`FoYJSXl_lWK_6Q5B1laeoNPiwSe7cn=dY#qkT@BSndw6BcFFKLVTLu8v` zU@sriec5A0k7iy!4}Al_>;q~ylf6W1ZAOi!4gBkyYR^OGmo#DFo&KN&8Fc*7?zrL6 zq}R)UlBqZDfe(FK*c-^Z!5RT&cF&A0GB3(J~6eq*K?f!^rFGh$NQxdTL0 z*WL#cOQgE5Ei;dvd-msbM_(f47HR0fyuvYFBcWxKjF`kyl~23^km{(Pox-H*nomE6 zsEc=hgYYn7(tm)_loA0)a*U%K$c-kw^q~9Vj0T0sFuI?<_!t#sL&UXdEUDZ>>>qu} zP$G4xD-yltv6W(mzATKYj)|3&-+1bSNbxBJQgvfxjW%}O-Vic92|+4#P^(j2{k17Y z=1xJ3C>*JkB;R}MrfA_)gcFKpVG(t9o!uNd`H6v4a#mDiP0h0_Ma+It6fGT6i#)UO zYX(v2QwY<_rfM1KZ2gTPJa`h3RN_=uW_s;oSHumSQV>y`QVTi1_0>m_(o+s3)P}+m z>umbHF>HDhB1!t7s3w})XIF^L-I5qtI3;UIX7|(#vC^XqCsobTBG&9X8#83^k|K%p ztgOn~n$K2_82W-BQaL47d3NX54r0Zx5J(jb#VXd=`&(0Z^dtr8#6hh{w7Soxj2nBU zFrsp#7m|GAsZC;quN+LNjfGXz+jMqA$nYfv()3YPO*M7Tz7R1x1tF?(NY~Qb?yZ?b zoVjq}z9QX6WEc#1e^9QIT|YkG&i<^+iEcaZW7c%*LymM9N>m%Ar_H^`p-p zKl=LhtFIqF`}*~-&CGu}PS5CB`>5*H*I2unS$QWCeaxhY%6XR#J5~8c8%_GOKKg-v zgj0^)Cl04{)AiH>PcWx%b1?N2dIqzb$+!}ok*aw%GZvz(jn=Vkur;;+Yq+haso1a= z#h~s@hp-BAuWq?xY)NWY3iWH;c9u(MAIZG`bv@iYh67KIn;|ZiyYcnZU<>~xzQ07+ zGv}IJysLaqD9$^Eo77ONj~#@T~+4d*=0Tw}2;2=}80 z+^N02HPrdJ_EY+|X)NSPPBUw#F}E~rq)Xk3huzuo(S{eB&w@5hJS)3Le}aM~xT6KD z#&=cAPBuqAkG(f*qtk-!rnHbJct0}Oo16>a4i<03S+k$D5c$xWN5gAByRi70>6_Pr znRPfhYFDmAOZqRycJX6lamC&H(QDGN^67K(ejM1h@|hz!{rxKR@bY!p)4^;FgAY0! zHsgDR)->lvQ^OU>XFKr~<6Z~yN^@Zky?%^3E#q+Ca|L97eEsT)%>78-{m8muga3lc zOVKyfTm)>i1G?jMCGbP+2hw!Mv?|=khvzWubb+6FiNvoet(7MHCsX*TEI63qMblsn zaQz%}=v3Og54XD+{xC0ZFwgHyyDyP<5y*Sx^uJkPKjNDVoUAj&xd~Wb@p&umL^IR# zv^f=S@vVc)v9*OP`k$o4*&F~@@c(lub_jloZ6cZH8=B97^HUa|NTWr!<>%6Q!Au`1 zi@ss%%Vfrt{2l>jlV<_3KK=T)O>NDrRUW9^|9ylv&4oC~wJH0r!gXJRJFcl-ybXlQ zdF;4a8h9(){`B?gzKS=?*JU%0#XgRgHMQE}*Akg0HG0T-c^APdYZEOi>vln~O77Hh zUE}ti$P=o0kPKLFTJ8+*lVZn{|Poh=u)cfyT2yyn(;F;v)Y}hMWE_n6s`s;JdFCcdBrn z%((d4*seJ3l{=p+A&(%Hkg=p^&im=^ExGdzfXhe^0BaJ~=~{S-XV2?26XZSQOHIz5 zz}HM&N6>!HjJCH}v(Hby0PFs8MRy;4y|DB*(%Am?I<`S^f$~zvQ-Jac&mGs@Oe-(%WpYxv{ZxH5MJjsHKl-MR>0PRrj*FZXQC$^PZ*=4$BK3X*<)^0yLV z4e#Zfxvrb?+SR%8g{uB6YpM+f<{eR=EgcdW=$8RWSsJ+Hz!XP=2zuzh`4O`M-Sa6;`+Sc-m+_O}n$ueZ`*2he0Q&SE|r z`=-#h;I)LqTl^h>m0e1%;-5gy_1q<6mF20{Db?-tTMMj6?mwUBn^TK5i<7OdPr66; z8v8v8bN$7zApFb|;ZEIKUBjlD;E(Ozvi;ChSCjNH{C+I z(6h02Hrs^$CEla!RwH+fmz6esf6Bt%^9}ui>&@qapCEp?kquzla9gc2<3ziMUa)^a z`Bxm@PcG~Sq__oIv=yyy66K6JaWbHX+Ixj$W+PSSvZmF1N+VAJB6;}j|=6$Lw_%P`&L*( zdv;lU66bS{$+nQ&<@Sf{A0)e*%x?Da@z2cEwN7#Z`w?>Td~ z2$?()|IA>WDIMZJb9$XwzR`E=cHJpIW*W~t9vv<@AMx`%7nzb1^*@tvpg9ih_t7Vs z`v|_7FcYjeo}4uMhJB}roMuXIn(p&`ttoqIa!32FMt%eFZl_t6nlE>mY4i2cV({-) z`mfD$ZUfJ3<+$yBXgk_(;)a>G9UsdrpSy;jI3wk|$gNIo%`e-{3$*2%+jQ18dIgs> zbUXZUEq}P13^iA?&2@BeWNr(luH9~Lw?IwZ+%LGgws^gE&tsa4!{&5|Z#Vrs+uQJ` ztxf04y?2uw)$9EZ2fmxq)u=Q1oZS80NIZ^uH|y0fzqXsczg-R|8=drT>euFv=AQBw z>b30`$7EP!0{-?r4S0X>=)~vE*xO=8b>8$$H^1@b>COBpIs}+HWcL{2>n44;+4$Lb z+B}-?aA4?lQ)Dz>YaWg1h|#8Z`kn2cGQ1p@|0Z_5dF(fH53|qAgmeFI5=Qgan*V0( z!Fl;@CNp>#MM6K*>^C!6emBeK`)J>Tb2n&?M*T5cXPo@WoM4MN-O$QQI)71jdV;oa zsFQBYrgypYqdII*ry16XUe9K~y7@}iw=M6wGp~aWo4WF2cYkKK@;^D%rcS@*W#0a= zBQNZjjUD9!+9jIG6~1-H{dMFAebza-*g5Ej&ibd$c@95LpZP8(IdnD+^Q*m?xg_{S zXK3P12ECZ-Ulcdb86`X4N@%d?&GpfkLB zmv8cXz2kkn z@S*p;|9CGP@wo#&)QYch+dJ)h1TSnfSoWE|dyMD8mpbtc-h1%yNsJ>=)uk~-+8r&xVW`x-*8>@>P6W4_MNA``^qBHxajVd zwtf4$kH7CDEig78e#Fy{_vs_-{@Kqy^*g@U_U3-t&M`8FPvxs(9;GqUvuhW<0mh2a zUOp{vWluh1mpV?)>a%n!=6J3?(PKqlewGfUI=vsD^S?R`?pejBpTaraJ)tdklFiG;ZLYR^(g9{%qszZNqIW|bR0@o7YPy-Eom;qGDz4w!Tz9S4HDk8lfpnVt{5*Nizs^g;9c_*RWYzw=G@ z{}c{n8xi$C_3t46S(+XPI!+`sY6tp%2XY>j+t6nEAeogIr8T;K9`yrFPUD>tOK8s# zjq3aSA4H?#A!?fMb*}&0xW`|`JEtG!hW~3?n6F1FemZo|q7c6+hWK+f+i8>r@)7-; z_it3k86O9udqRgB)&CjuFz9HMXbP~@`_cYyNIfT6fPX_G9UPK&B&&9FRZ`y^miC61 zJCbM~SBF3olH-j(^&KA%dw=%&t`EWWG=MCxqF@s?GkUSihd=(k&X9@NfWoguv8g}0 znQdxwAC}12W`A>Y*z9J$!_h1E$<*;dbhyiRBukpPwl(+fl33h4zss3b+nL)#J~o+1mF;<9_$8gMX_79P_-R+xr19UE<)vwqoH8k7{k^3Q1D@4Kqk+qpTBHGmn z@nN&HuPk{^ABDUdg{{!8z0<9WpWFuDQ)<($Pb0oYw_QjZo0R@rl)g1e_b8?JB&Dkl z5?d3LM&T%>+$2`cQ3B&Bv9Us#Iz$O%ir8ADZJC;bp4p?gM$%wx>O<9d(6lMm&syuaca&!K>@vGbIy`=F@*I-NJ(;dy z)+w{(&op*rDnHN#(Z~tf#WU&sz@TnsCy|{VypGa!(9T72kETwWp_gW~8GAbiyEW7U zv-y8g*B#Jy=XLD73Xf8pa(gAc7Tr%5+xLnC`BGfB7LFDfm&JaJ6`T07*t==z*ev!d zqE~nJy{McOj{P#s{}#V-w3zG`y{0VV8yl{R(euTry<42yb+NEqY&l}Q+^`hJnjUgt zxalDa!$o_+=<>#kcEV^Yl;Nb9LtUPjvD91NGKOeHH2Dzdf68*yENH@sZeU&w8e)uV z{xax4sHZR|PsdEorO)q4vcuT*#8T&=UD73lkUiyA@Ikhn*W;*Y#W$r_MXY=-I>gFR; z@L1-@6p_0rZ(16?{u}*oyn+9XPkd<{Z#lU*G7Mwdc;8t1IMx=9<;<~KHnwi(+&X^V z$Pt=Oj^(A}O-GK$QTEE&9;cntzn?yCGDZeWzE3mbj69o+{3%BA zRQYUuh8bOl=~-)h6ZGL`^nN>)r`|>D-|ee&823k;CPb&?^^{rJSic*O%Cw{E$QgQM zrzVHyr-Z|htBFresPaAOVJJ^M{tY~OcO6}ujy}`A`WUzKXf&&jYkRV6V~^~4NAlDT zKt6UKorgKpNYxmCR2q9!4Nx8P&KebYhSdA9W1q;$9I|;0Y|j(O-t9ahFMCMveC&4+ zIkyVDd}YTx1t#{8%5S8=d?Lj|q~sN;a$?8*%Z{@~74A{x)Sps^lT^xRpHdAwuHY!O zJ4OAzp-xV-miRQXdPlyl#V38kqYmw``}+M(n@HZbk;!|cdl{TQ#B@fH*N^10kUVY& zBL^|fMe;L{eBKbwK1a6hsLyFlQxQJu6h<~3d-WpqY z+g6nPTc53-P&RgW=3SpTQ#zdVeD);(8^beUQ=|E#TR@AoOz*KkcL@wqw7 zTI;e=V^p!7*`tZsmr=`w6WE4=BKd#px9qx1%uAB}yQjXgac zL+#brkVC;t&o7=xTaq-l2ar_@v5PaS%X7|$@!6xj*)N%&9oXn>%0b!p zok2sE+G*+WPOVoG%*u{?dV|`lWLaIB4O(YN#h;(8EF=l?dD(NS$1|Xa48a z>0j9`_0>;(Q>fWhFZlW|S^awHosl!T$;PI0b$C`aIOZ zo5Opyj4^q4vHySnv8m4rc`h!{zYgsquvfw3IQ*K!)o9;XpXTVS#hzl|0J4Yr)~y+T zy2m;NRw(!nJtQP=^>{eD0eRi!`I`rQk#$sVd=G3FT2(t(?l2pNtiG!LY<;PLKe_)g8XFKvox9wNdGBa&0cx{XfpER|7xG{FVsM?`7j8Z> z8$kaQ{a)(dRHkXsAN{rO5&gEyN!fas+~u#q()*rVV|g#S_fO*FGpOqg%AbRS+!1$N zPCxkhWIL2c=KV5thd)gG=e!9wc8lHATihtUy*JZ4!!*t}njQ-kHF7&=wcfbfiN|_4 z)(_dUOfa$bxy>-5zqmH5DzS?(7r z)Jyly6Zd7biBYyXgpV%6h}mVb%bwMsUL(%g?=NAAeIzdKAQU*o=1|m;TkH>(uDKI$ zBp1vy#kwJ4GPHY~5DGQz^a4(m)2i{7yVa_~0v%s@~4|T%<+L-nX(|4rtIaAJKQO>rWQ-nO-^GRrG~k{2I)6IJSpe+y#&&=h8Ocx>h7R_JwMdD;x4)}_ zZn{3k6C+>b)a@Bt8XV|uGBiW;k7W?wcTf|)zNd9VLW#tkUwj0}Tb@o@e#B_RdU0aS z-hp%Q9UVS6|HMTsqb|c?y`O#ycI+sa?(U{3a)k7uA%AbjLE0#PX|O)Lc{uP2rl`M* z=d01>I-3kH_s38peCFW$t)c)1K7`EK*0Eg1eOkGx1d{MFAESROud{wkDvg9ck(IHs zN*tL-&#w+s8zRcSYUp~XQSlhBJ^sC z(B%km;O0a@R6z&=oB>W$Q)ppiWpW@+Z)9b3a%E)%#|ZrG1g3ug08~hQ{^f{ZNMgua zi2^UwRQIt>aCLMbLjVB)eEBy>q+S7m8uXh_Ha;K%>~|Nnpg|Nnn~X8#WYfNwaPTmnED0f4rs@j0WC zB+14a;DQkmktuEx;6W@(W*lP(BT7I7gcxH4MEFENh+@pPc?lN{c;o%CLMdQf(u;`X z&DxE?p4N-nENhZtBmxK6422DW-)@f3-3~r<1IzabZlMA4a4qy`cn0biR$zE=J71Ep zHH`gI^$Z1Te%!M`zy^872gL&__kaYxgQIKoVeY(9Wx<9aO1i`umsy`053I+_Ju}AB z3+uDB(13rhl-u8~^Xp(*KptXTE*JsCWxQ5%k=9zEmaJhvmi--Z32ZDM)WnPY(s(pU z`{ja8*B;OEU7%tcGzAvyym|1;u3%J-MCHN@zRCfBhGWp~rm%d{0gE=G4WxPW?XnJT z2d!$r{|j?ZPY>)Kt6_Seg>K$-1n-(AsyQ7mpF9Q$Gl>CUrGft$=iyvtTyxb}ih2Jd zbk@3bgnqIW%wbpY>T&Fnwdx17q^?U)6+kN9K!6VaSf3k7uDSPK`i4xe02b@#QwRsJ zo_v%8eFECoXsRf+Fa4nOodE!S4+3feBeF&i5QMooQ!m8<7#xZNfW5&3pL^4NGmsGG zx}|fPcbA!P>7uS;yNj`z)kaw;!fi#$ZTEb$t=?>_8&FuZw6tVpZz-irDfS9E3;YV1 zpMXY>i^0*r$M7I>3UUPb7)l=>v%-LjalCOcjF}g+c$t9}LK#<4J3@PJFjQHbYuRwG zmCbpa&d?c+uzp#^b{}7JY<_1#f$&f;EdJAu#H)CKJeEHe-*On^T}V{^i;5cuL!-yT zRQkA>8VOuX3mz8(nd4$c6mT&jFds(I#s!}sS~MZ$@Lc2lBAL?WoU3MgEv?SgZhX>& zM7aAAHNJ1Y33}2so=W%eSNK$1i=c~hQKWG%C2U-R$QuWV6~w+zB~mqZ%>!dQ6;M%efSBQ6i7@$z6o*f^L(%Y#9z`~-%RL@+D(QRg_C z6Prg8l8vT@SKi&bQDTn$AR_s1;8}i0kaNI!uEG2afF|ABTfbH@mBOApT$q| zTLfRci{XrWIizt35+^SKBIPGIr2GVilb@h)@`EmeGYUIknZ57c@qRs>vNx}y$$3}J z_GmRdPb9KB<&=aY;C10a$T&O#2_L>WA@H0P4&ON!;!^BNyh@fn7T*Hs;#~w|+>4-$ z!5RM|IOAUgWl*r$!O;onW`}PprFx)sv-2yOoRi`7yhG2@RV;xW2iAlu03pMRn01e2 z&F@U$2LHrDA_vD?>7F;#>Aud<&oCwe(3+ zVPLM%2#5wJiVDYAqH1zLwQRT-+X9`A2k9k_wti{F2I5XA6duY2#d~UC{FFKpufpN+ zR`5>zN*BeibU^Vd9wIB)ylZ3&8)ACjog<}oiL%l8AS;LGTsGYM4MjZ#6W9y5a=QXw z89pS!-6N2&cTG3IH;E(s6AOv&%n;(98X7O9j>M3heMF2_atq8--Hvq6FI{_xsZ4$85YlQ zW>DOcfZHAgG9e~8eqo^K3rGH7wG>Ro^kn#co919OmU0qBz+^H0f->tPae&3~OET7@bR0~1YtOcf;9JM8y zoTeVD76%)Z%J6=-+gWcl&EcCQYjSc)lNvQNn=DzP2}q`4%{j@7CNGk_?IMwNiAPW* zsljQ42Z|sbn+SODvx_V80Ayng$j!{gArH(&YMcmDBX3hiV~`?48c%@LINOYDw95nJ z3j;DF2-;v#qlwHKNt=vXhXsM<4SMkF1`fgn{RjfYgsw4f>b((s0QpgdvCJl10zZ6k zHr8=&dI<{Z^$Ggf1;+L8kpNku1Cx|I9_x5)BJoI|M;8J#B_WeQZqfwp=)uD=h(?}f z0`3Csx_o0fcG{>DSXXB38iVOANT`Qr_ZFn01q;oY zn1pkTNRR^|TqFw>ou6Kg7H~koPJzH9F^I>QR!~>aPE184A|&8u5Us}&W&HvkIbtMI ziQf9f>+%8W-TCPSx^=)46tjVp#E*yV?CebM%md`u*8zHreejApo<-3*Y%Rvd|C0wl zy}<6^pxvDyU0~PnkFNuipr4*yU|@HUj?XTT5U+dp7YIlf*v0ef@^OF?9PA1T+Cd2# zLVf54;`!M@b^HGEptdpDA&>b>&BeVOiQqxFCZT}E;|zsEmyqvr-c+r(&ED`;@0Y6e zhT;9rZCE-9&)NfEs!eBn-DwhExkh9x&tz=XnS*Dn(~hN4y*DhmVJVkaiZugQb3kQm zj|~EBiY#NRj@FLnsNS!h-tQOvMnQMIvpiJ2UocT@eC1|;l(WqPZNsX05QMr(+exK9X}a-XPPd8*Y~gQ>z+ouH@<(WN&=P#DZQOhG%2UbWUpwvMNN zrC1;xuG6R7r!Uf*Bb)uklUi$88x*xEk}AzQOIxQ;xlo!?8zQaV?}Z(I%htcs8Z3{^ zoTKz9_vurv6JT7u>C{^Pm1Yl9Zw^;=WNgo)G(plEBc)4mlBU}xGINd+(T1a1*KM^w zm$g7PMUU1D%{fUqOP_U^KIp~6s;k;)TZdtn2dSN&{=XskGKowAN;{*4O&I{++c~?$4t%L6@~a zkJb!bYEyKnO%a$VP0-vcy+-xkT7}k{jMf@d>wW#o-%;$}ndWdc=dpGB7|U}x>vLHf z1RA9g(m>Y!OvY85s0~YDt#?#weWbN6p|wV$^(Lctd<{#@ywWV_JFU?Grs7l(TeqFD zbu0PK*|81FRK0hO);daSU8eP})BCN{Z#<^om}reR3PnnN(ivpf%a-3pE-GV{jB`U3yhNSJWEJTug1 zV;Hm!3$iQgo5Aut5dOV6k|-dlrm!w)3{dN^ATlrC-`EQhgq&fSL0X3e<%9)6nwVcS z&R;w_D9B!K?Wni5DIFmjjJ%b$fY(@#%%Y;S0;7L;}jI^`t9B6 z<;D3iGX7`$Gqu)R8?DBPQD%(nZ}6@w_hn9^_n=?5uX|_52PmjV_Q8)2OdSR=4eLHa zzCSs>4@m&E9-A@P-MjmP>*D>fX)A!#TW=j}_|C3FAR*j|4|5HzcLt0**+$eX`-bWo5D)mty>t;KW@pPgP{chGKa zkPvW?u&u_jLzqdecagBTFfz%y1RQCNBflu-<}N4RESAA%l(C~2DMAx@#C7rh*tBNc z5fcD(eiC=PfrDMVKenL2E}mT;TpZiBeCM#ZFfy(8R{*A1CYjIyxwY0BLT9I^)>?mk zHEO+uIdp`}@&p39(ALB>r>=^Mdg8Ow(|dt-Vqt4~YpuPsX4EkOq$Q-*8&K=8weplo zy#fHsWc4f6*JobgW`Qi$T-o998zBoKsnhF&!;JwayKSbF6RWxF+9ogxhPwn zp>xYGbaJ_zCzn(3+yFxpDs4hx5w_lY&fx*QLUo<$wDl_)+;jRG|6`)^MKX9e=>TGe z#Pe*LQ%-@2mCtcvxm^@3$Lr+sJI^ks`|R=zpIt8J8Ct=!OQn|x6Y?9!)c1vbP=}aq zl^Q!$D(u&^x$FFqI1pr|(&djS1&$mG$mY9~c8IE*QWm@vOR8a+0H9u1i?2LP0q7sq5CUx8wAYxKD{0CvuVFNj4UEQ;s253@8bE z;K|R9c-~EO$}cdnayw2e*Nd{{eV$y-_u1thKE1r|v&%1dc6pp2?i=M_%V z(+h90B0)`;u5J~3`%RwWdq%|gkc%8gvRWX?w}LD=m;;r^PPSGCSw zV>fu75Jxo-IMaH;gIIP^i@@>(eExQ>nnNt)Ta9A&Lj7 zDBwjh47d^|19#d%glkBXgFW!%5hCb(ni45*TT#B3~{lsqs8(4JX%dIk+}u-5LeX>uC2%qcyQYf!U7;oU}wod(oS12i7L7SDCO*r4oDA z&F)(ejt4R^nN+F3n{Ws@)Bz7%HL&@>lY>Rjc`+oPA4?+T5i}!gQhC{C70@#!QY4}N z3ZriB0`s8)06W6U>X}7TxJkO%!gH&AJh{gd|y8MBFkyribdf*Az5zmJq z`4mecF}=)hV!RC)|At==h(<8YgOj<4BVUd?^#iopca+R1XMFr>9>v3fPa$CBRz8kAYk?$Zv=%_J1*?V*3S2KS`Hf>CSUN{id4wpiDq)?uN_joo zcK0nG<9!%koJhsxkz(vPQ>6lb!u)Y5974`m)Rb`LMq&>nW>yOa8-*@jPcuH-Y zb$T|dM^FLCa-AUnr$XKbK7S+36oruFKv(4mz{9)yBc z&K-byKv^aM9&|v-xj_dBpyZ)J0yf}IQc^-@uz?0&lz9cvAOp&?0c21B$|MU4FaXNA z%m6HyEJMbEGLxJDC_`qF#~3mIn1l=ifH7TPbhf^#1=#VW*7-S^HzrIB;|4}en3_Gl zv(L#SD4(62olqcSD4d_1ViS&C(q8E11%D&M+AVo>N( ziiq2Q7w09mRK(*mOQX?u?C^l7S0Tj;NeK%0MBF&@lm=YE=5p9 zs1?T=9$=y50e~i#J8rNbOoV{t1SO5iGW@=LM%Wq&?1Y>`S45GW2LuZbQg-(U*7%-a zP`szzh*Q}^@hgWfz9j|bzufo{8YV~tWuzbgTBjPWjxHZH+rkBdQ|h?xl%aKJ~UVdKzG&UWv;V%OH$tv6r~^$N;m!#xC=?KkWk6@cY-2E^#x0MA+B zkb@&&i*q@gaW5n+KYO6x^(M=?EJ@cyV0kpg)Y5RK`m40w%Ia#-SA7*FZ|BESn8zggL6Q1Xxlk`8fr2>2^pC> z2~o~TKXvk!#tFVoqx#)j^1V*E#5^`;qDVcUSV$XO!=eOm1%tAjm438fEH%2}`2Di6 zQ_z^l1_P{FRfzehXS=0x{A!?+l`>JYl)|9060ktC60#JSLJ|4ARO!1lps7w3otl;8 z)pRAqnzf|!&e6R=bFxw;A1b3$wUoM;!lJHZX;@~oYg#X+PD0u($9rR^NApwA)auCk z<&;Ic(yAFCD*-D`=DB&_8|>qs8>!RQ($~|N<`u$I&O1l-)?_sN&hlRz>~xB#jq5aS zT?f#rX~{)Y5c9NKIW-;)M)3@B_HY)l2;ShHNsRj?P}}G6%5K|NB6#lu~VY$qe)pwRZVbQMIxHPR?O)JIfKa5VmFbA9Y{bGe9nsge&>5fuxGYw1-lr(eUO$fiKCWmHwD zR7OW{b>2G5yRT*VH`nM9&u6Eg>ef=#tLav-r(?^gjxD1aa|MGcgK4g?-g;{;dT%ot z-q-Q_jh!CW(OxFvK8nJG z(ha}w2G!B{+d3cS(p(P8xm3yLQl_6zrHDSQGCDOY3ADPkqyhB`$x>RhBlT8iSa0|x zqo?xU8mpPO#|Bg$($OG_#8biC1k^b%{Yc6^H)AhVI_vk{by|+=_8cACQkiPcQLTQz ze3`YPR!j;M)R1*KS6$gCGj&yEgR^Ri3#s~{EA;S07mUabHh4@$Wo2DOX&aDDPd4(F zo|=-HmX_uu7*8;g#smZH4j|$~g9gDs#+k|jHu4tW0vgKF^#P@lt`?6~rf57r!oM4k zZ#2HbQz;gv&eT^bM|TWwy|+}qdkChXYOq=rx!}@~2`LgW$7G3xo)f1ReMOog^(c!3 zE8y+0buCqecBZdX-g{|Nv_T;jR*aI+1 z6y?3?L~F3{UIA~f8_ZilLoYa7sQ|!3C7@XOvL|NDI4^xnsrVbB_T+56_q#D)oN5AM zq?^;!Y2D|9g~6%@9Md{)1i6Ai$enR$`1VywjS$qL?nsz^cj9rlB8HfR&m12}=)@tz z3DK?!Po-2l3dcw{$5N0wH-y`XWOT1|BXH_Rpm31( za+A(!@VfF6Q2Z1S5?L&y=m=e#Vt^(WCZkPMd(}=m3X_3-vU8WvZSubUgW|%CDD}>y zV-N_5Uky2dq{ZdhlpPyL;4Gkx8)mhyQBe3Ndsv93Z|ukhU)ht(9iePg45*A^>>$5# zOx1f2d2_0Vf3j4vBcT>`KeFUgV9~_b*Qgla`NiWzO*CuG@^Z1&v!v$;n(duw2NjSK zw;EzX3xXI;a9n~E9bcPbfB?)QsDWe+;_CPXIcU=sAIA_d#*tMwK7Fltb`O zJrFLFRGC@#lVPH1$p#J z0^?^yu1!hPlo32GZ??$p|=D*zN6we4aBn3j8s(})}A_Dd_&l{KUnZrvM5EeT#4$aO= z|MFnvB%EL2qP{&;yO0aJA6f35NeAJf5?K5c10-%G#KaZ^NL-vf?GpzPs~Ch-c#dA! zb8P0_x&Gz3J}#;`mF(y^e`E(zF?XZMJS!n4v>r(DEh8-6g~Y`nD1mXX&9NqwC*!ny z8I;SLMaevx=MB&^D4B&rbZYN@_uidc>(lmHx~%h*i2G0syeIK6e3TCnC!Y1CN#kNn zp4hk<6wIG>7C-@*5J{(NQO~BzX13PHMmD#yIXy?v>_93syoiPe$72Ku5<&$oen^})B=pJYQXVVL?EB#K#Frkz~Wv>UL1mEjDu~?c-WE} z7i%(E#!JYGwi_>~cfT8LPh&2-X8OUqwH^l2{u&o`9YVANtxq6%@}{XXgV6``l`k{72c zMtbFw0PTjX54eeJW`I;^;J}DRo&`yhd{U5BbYS7rP3y8M{Y>AeymR!{OZwer?^Rj> z&aqyQB5l*8MmkSYpPL)_I*m8{2H+XYFWpP`=5US~9@#h>DoPql3Mv}1F^@seLqUag zmSx7`v=-A0nt%GV7R#db7^K!?I$DnzYAvRD;(|9Z%?KGB!8n3Z1mh>j573fxr^k}V zwr6K&%ekF%VD!Mq0rWd#XbHs03FrqI2CDU#osJthrM$C^tpanI3EnRq0TKkTxUIF` zpIT7RF3_xidB5)zjz+KYbc&5qtJ7F2mEkzvd++_iL{e?d+>KP03nDo>AyR^jOu8If zG%1UmQ6%kAk}^#&5$}raZD~71G|N)y`!+?d*%&xmWL}8$5IJaytUNPCnZU7f2>BNR zMt%lF$te(N657EC6b}-UbOvCA5F|J793#DwsH|o=Dt+O2ui7&N0G+lCp+AC;p+zZd zT&YHnKNZlxr3`T3SU!&2tAWjz6>;)6BT>#l$!BOGlPaMpqGTx(dBlk$TwkD0*5>Ao z5cp(#$H-fR_OIAz{!2z};QjTGh%KMyLd1I#*Gm%iR_~=T`AiDAS z*?aE|$1|!xMjd3Uzx??!1->u&{T0z=#L!;&kssWugt|mPi%$WSx zr4jkra8`rM)`h2~LTZ|FZ>VoH)=pc7C8a_-U1-LlI^bpyI|I}=;b?IKq@I~36M6zz zV!XTIb0NYO6^J{(a=i84s`Sfj#0Axk`E-zQp+E{ZLY!-Y42@#(_bC^F7eJlZbL6IR z<;2$Mez)XXm1-dO)cne&^qjb^^KdwOP~QX<9!$9qRDcN2O-Op9#oSX_1DK|2qjm*& zq__cvq+pc{Lr|+3hC`70DsbhjRfa)d?EEOu&97TY$BFCu4qb$z!xVil1Zg08a76?@Vu4d$h(YRRC!#Sr$h*H(0xA&SM63&C5>IK-f;#h@FF6w;n$(DynYuBq0f zRehU5%ibG1vAv(3_j$u7yPv!6H91X(hT4OTdp#=!58HT^Afq1M* z#b;G6b~=T?tBI@AEYcwz9JnGw3{5BUq*?^NN=D%o4a8$jCO)fjF#uC30F9>G8}56Z zAN{#G)@w<_7|@>EiI74pmFPyX0F3dg$;4w(DiWZog&h-m<4dVeK-ZE*UB|)~VBCueFCd9Hp{Jrxss#wbSIH>6 z6^+BtD;kJini%nPWNcLm-&{W{@jMIW^c)Ia=Wd8_9}j8|`hz)tAEYEfP{EjC z7+NL6kjN3A9QD=kYi3iUuNLd5r<*1ycO%5PA1!Wp5~CfYp5NfBVidkgMj>bw3_?O3 zva7B4EPqp@-&QFV3g|RvQ`f2RrMGq=5OE(GtZ<~L;YuU!noQ(5MeZGH#owbO0Waku z@KY}YPX%Kz08oz~oTfWBJATbfqf(>ov0O^OY18@^L)d$|M1&Szbci9T@oven!<`^M zsOWnX3&2ZBg80-6!81}V0$udHg++G^?>%HoV^BTI-__{j9PF!7LZ>mCdXAjedF;&o zv)6VZ5EPb5bem4-{V4_Cp;q`kip5`O6pOzpNP-xQqBhxgXVKCaG)ukgV{_}3(QVYO zzRe)^o^INK_S!xaD3_?=NsM+^8gX}~#|~#Qk@u&_y+1|r{Ygci0G32>n1F2>dgGUi zmc}0Jsr(l^V<9jd=Z&ieFYQ2lZXXJiyHVoYkwVasz&q2Uhc}tX3uSurV8IgO9UV=T zQoP^2rDz#8qowiTn(AkyooBz8e&eQf?gp~^fx>;YW%ajwGV)N+a$< zl}6lsA^M|00oybr-7ySrGFlpgzBJWGgK&=ZTKWwe*0*zF@4-VmP~U_L0m7ZA@B*mO zVTKEa04ZQ@*SMObINEr_F9{95ntLjfk#}e~ph5+GkPUm{;D#-W1Dy(A73^$?;ABhT zOVTDxN=(YFp>8?eJHn2}6<(?|gN%bki*2q^vDRAiO64FyW?ey7P@6+cgq*{)fB`d4 z4ub{EGYfK!l3EBi69V9sIbVR8Bo{X~hanDgc6%$c%dowQc*#fQgW+6FW>2?F-bU^OCr!fp)qq2;RMx)d?j-xRA?s=A8=;7JU(7KW$BEd|I ziQJo-6ATpEh{(OE)hHW-(2a6hLc+PRp~|wnw|0tSm<3k{=ZltAlo>d-vrrIwc%h4h zer6O4{RA-h=i$bLwX-cB9_}p1@!ooGI!h(^>EVWQVNLyQt?U{sOz87K_rSi;5sHF0 z(P((VqTyc&vM?{5DwVn=r?d0`+Z>x$Ni|sz?CTCTCI&Kk@YramfQAckLpC)u8&evU zH^5%4UqT{cGwae>_=m2BuA>MPB@{tXlu#6cSBHU%#a`n$2CY)3RZ&e8+|W*kf$oE$ z-v~uP!=Eq{>9{E4tu5^umF4%{U}o!yf_&K0#*Tpkn_VIyABqx+89X)~zBw@|!SDM@ zqcUifI(-&v4fD#HtKh~V!}&VU6@oC)co@3k1mh-O9)}xiwfep<8R~S-xvBXR6Vl1R zwhqT;_6%}uzhguM5u$Me6po7%o|=?)9K)d0>3k}6J`XqNQcp^96VmQB$PohODMmgn ze#HsKOQINISs|`13d69pXGiB&Q%-Suc!z->5>K23WMik`UtSHBI?XcAQXih}ucn;h zK6DQSLmW0L20k_-nh5a~kc?zTEDjpw;M{Qc-c{=Soo&vorkv_Bz-mQ~czIB1Z2 z-d%>j4;(H?$oEA<5{QQ^kr*23xJcxV?gCYoWB7f|%(E1Gt)8oM^C%~!32J2>>@J+I z16?2=UZCD$q2Ea?3jUGN@Fzwf9+E`j2PZ}#7JhYQy?bx!bWS=NT0;|ig*OS;U}3`X z=q&VksQaIu9SFT23VygEVILzRh?fvS_{T=WpBQmS0pcLv(^e;E*TFDsMjDkL^t1CS zsiv2Sb=^%ugt)z~hX3i=UC^(?3I9CY5QN?p3HvVM5b%tMAU;A-@FYSE{*loT)KNsC zWSW_n48yR^-g`(?mO-Ua`O{f?8=CByl8XMtb#*nfu**$I`-Tf|$D_0Gyt@qV^H2yP z?}&qZS1k0qh{KOq6bvP?I7nr$1D#O~jTY>E-z?Fn40^Rz&(*;>R8!I;fNgz(T3KBN zxOcF_a6P=a`{~&o1RvgE;D;v;@;!v%-$ft-zA-V7%;2AgwxlDXyhwfGKF6wpdRm09!?m5+%~7}q4j9hYf$o5NcNgsI9#L@biG+NiiiLd_4E}kbi+W;$ z-}l{HN*u!;L}mF|to1@bJipthY$L7cp+fk8AA|y zT{_rdh)X&ulEN^&;(gyT(Wv|Z_FDZ<5BFG9Pmd7B^*1)NW1ztHyA2iIt-J8O4jaz+ z>Dg7_fkOsNv%M#<>l)FeRZXy}72tf>yn#JV_elMtZ-xd{@S zw53Im?9#Fl)5*D+#&Nv&-es~JTbRyL3^g=av>I*p35&JTM5A)N_l7w+XC0`iMc%Em zG)~U4vu!31va>Qsu`;qeGO;1nAevpSBxz}9VwYzSz%G-zz#wcv=sN3~w>Atg7+cv9 zV7xS(8J-bBjzM`b6ysn>5=2fbHi`h5y#mlx#jBIX0bU7s)&+_}sN@TehO|%;#wd&f z8HJcbh$$;O!xx}17zhpzOm`)+>;V*j2~A>HfFd3c34>&^Fcb=hf}&s;0D!^(3u4Qu{2d%Nq`2klRs(9pA2^3Ow5JY9MPqc_dNezz0iFu+;oK*Gz(COhjq z27mPG5mp9iABO(P$?&agZw@VD_LnwHW;g#Hdw_^VDH(7a+<^CL?~?(*%?D@)r<6jU zz?*~Kr~@3#{cB1Ije(LKJmxTa!`mR-Vyc00jo_h^f$_aQaR0EBfdJ%DDE}bY!2W)T=7zP(1x(C$BOyZD|17J1L zor}aDAZ4c49!{JXK#K>R22k+<=$Adfz;_N*wmJcan)K6%B_70T9?ENQ07GAu)Jly{Bf$l8&V!%Ot2V%yDgCzggP<9@e;|Duk>A&W1 z$Tyk}N_z!n&nGhSChR-vl84;RdxU>@F8qZ*Pe-YW2jn+7FmQ0(vc;z8KVuyZ4#3^> z>rpOGj>c|7|3K{?%I9CJTIUXr-e0YVT>|IF9xDl6he_4|%6)RaL*MnUL7LI)`dkQ) z>3+|S`n((Pv|q3Pc;fq;EyW1=_4hjY7|!kLX-u__in9IWe0|=zxO*)(v319)C&ZmS z79$l-<;qlv_5mW-VJ399v$?n)ov~wjw8|LKAg^eRZ+x$0=jz}=7%qS(aCT0TQe`>V z-J=e%1$1FwE(UV`f@@>x!<9$0=52)#1Pr~C3;RNU(TIOk9h|Z9QOoM57DJxVSM<$V z6Xg6->fh3eWmXl8ZW_4t)KXU0kMqWRKl>7yCZn^yK8sRJp_10lg3Nd|Tv z8;8LAkLdT1&B2s7VAEO-bfoREu(*JZ;y*Gtxa|X@4;uEvK=PqgwT)VM{MW}HdxNV% z1=RoXxD)@23AiUczHqSIk2#>qZWDwOL@>qb#~7}LI%-0 ztVN^)mJFL(?dZfe575-%Bd%!Gp=IX)Bz})tt{?14ut>_mq>V>?$A^070rB$tLWcz& z%HP9;(t`{RNm>A8Le3B5O5spACLTz8Tja1B_$uC^@PNhSs7D4pg#Y3r12A((gI!Go zcL&S?1iUQRL4 zT?~ou(Fg750KYoS)KVT7nkCx(hw6o6?srgdKZi3k=fL6e(zP#yY$-WYB<`|c)cOFP zWPTOTvf40Lm?&FG-=EeBKiuxr8Z2&bx2dKKh!8S)1|y-BMfkk(1LN?hC6hcO{g=(Z z0BS&$zX7E3510DDDK=`=CJ%u4+s7*zra!{m?f37+m3U0EHty)eg0cs$N9k5_Akx0Q z{!CS5*MbOd@Tg#FQLVYdUOTZ4%|c}}gpw^5BrCIJ&ENm^GpppOEXU8SkRK6*l^}Zl zz#`W0ts&3rz4nD{cTksSPY|;G#d!7N-ygY?N}vChhXz(Jp7;3uH?#moe&_*NWieRb zS1%OaM?4m@{wI4dN)O{5`et}!GT5sZ#r%c*17v>(|5v`K%VQ%Y=YbBL>kSkBes-{^ zbz%}NF7W%oJup-UJp0Ag>EH9bSBe83gRmW|Y@l)g-vip20S=N6b^ul{uK$FzuzwE+ zllRU8b{97O-9y6`vbb37Z~zTKQ|n~^GqXX7frHFVIvE7IkW1TuS)g6L_=9Xf!^Z{( z-0?u=7dkGu^w2*a*%%p2e_g%spE>AbpgQPt3#>l$Ii!jvjC^qEhcz(=)?36d1O0(k zO*Zy}kg@=&7yLs%53x5e^+NM~$kIks@xFudEH(>W?BNbNGoZ?asRp4zKSpBpVrG57 zoCiWoLX#Htcwid`pz`R#KaTtx#y@g$_2TCOt-*16jB}$mhn5dLF1C6=lY?N{IXK(_ z_%jf@SiN`>k_{LRIDAvQ&L01Ku-o?F2(wl%PA*Wh%mu}hb>@Kxd<);bu+9YNz~6_1 z%*!L}0@AR2wy3*iF3<-Rm0!Kk=i^cqI-qzGZp=P3v>Z$Y?$m03SlMMJHS0x}Cw#F0 z&-Jj%SiLZYY=b@@Rs}*oTmzMFPpuM8rZ++V7B(Ex9hh6!Di5kJ`ctdug-Ftc@n8_V z^Nd)Smzl#|IcNH6rWU{2+s)VS$@y`gS|#aD-5E;A1}yf}uC3QdDY^p(iGgu@M%U>L zZN?t_fZP5`Rxj?mrxv_s>#&!dSTX1lZt59V;b3=}-3MPjhc2hbYe7Tei_7v5Yl zFstnsu;HpLZ)nFV_v$H)MJ@aN2PAY)Y?u**0ExBQL~_;*0|q5T}(beR3o9;~paKG1L#ZG-YDdzz*13Rjp$F2s4$`|~z?vgFGCq|IFg^@NRQN`BxZu(_vA@&iRAI|n~ z(=az4ZM)UxGoBSNBNxU2>R#-2c8x27cU&hi04F55EnTTd{GIVJIN)dS<2IkTEp|Wc z^=)sj2sI6sFzA|5ow@#DR~+cw=f<`FzdA|}LfnPC(QnzWJOB!{3P+ePE(1?4(+`2@ z!WP>C6Xrh@k&O({_JD4eLsSrR$2G|TnEST-@)7j{*l%_Hd!FkcwO;-{dBhTx1wHks zSg^P`p6MX9UjF=OAzT>3s(JD}rp4{(Z$q=KAlWBxjvRu*60f{SZtnTyVG4vNAvubm zeGvx~0hrYt;H8T1Iw#@oic@d7%x2;w_7`JnZFcjRIOi1Re6=-ye=m?wd#v++5C<)SkWJpi-Xiz) zflFdmptRmP@H9X`wdhCYI)+$8i37VI@spRn39cudzhZS|A@!m3!(e?JQcMavKQ1P7 zNVY`X;L>AS4*oYnvazn-z7X^^;!2&_UNX*K1HbTn5?XSv4gYb4t64gPoH=spB+Pm@ zht%WcK5C2bz^^^qHLjcSS0Ab!Q_KcmhO{2U%p9U$+;UDGR{8GtYki0@ffbdZi2Jn#mb_DHp73B?&I;Rbm2NO!l3 z?F@|U12}sty3v1N%~+AIOamAGZC%Bfq{UAv;NBgqW>EV6(b>3To@>q6gFoQ5M_Bg; zz(;hvZu``lBS4$++auSCydlhLUtM1uht5I!c0JDT{h#)!b?+=`&E8+v`(SDAl)L-= zx;>uR`yKCR>uTr6_`Pqfe`hOg_ddDaXAk9@eRX~J8ZwRT+x0lN*L&QjtedmshRA(m z{hY7rJ^PgPI&;A0z=7|5KOdztvI~zFA0D>QqY7^;3;Hy^sX{{WfYpMUxn%&R}Bgw@VJO1uxas9MRfF28cHWj3uwq1pc`Igm=*m8Stc zrnwH?pNrcA?-!y#I9RxQdj9=*V^WxZ8#;ly(SaBmRtilxn-Kky_W5Vozj@BEJf}KS zs#@othYy>|k`ME?UBi50QSfRckKRjelmLO&V zn~U!af2zU%4)U`{Ea?`4=ydxsr;sJ2g+mtPJI^5&t=nALyW5c@R15m#CIgo`90Tq7 ztf>6FgQWUZakBUxAf7a`S%@6*?3hv0Vd?*%40wZ+GFn|$FgWl{|BkCKXH&aG9WGjt zJZUL5=OyCCHDhfpb}!esL+wj6UixV~9E{-kz&h+1TT!HR;L>9g_t})^p|gfj-X37* zcgM|#FO{{x?NCR-Gatyhkr`Fq1L$I9?A`U>Nyo=@D3S?Z1TFY|vWtev!lKOXm{dc} z9UdJ^Gcli~Upvs+kI6w7WgWC1_p{MhGaLxlCynm#oCLWjG473#z{LR2SvWd_4i70Q zm7R_}yO?1f^A6Z$?aaXZG$K3{X<(qJj++z1a4M7?wzxg+Nd8di6>%aaGVb;{hE6yD ztM|+JynnF+dEJJ#1I=EKBtF-iKOF}A3jdgEo0A5?i8+=n8oJy;BSjW8W`s~%hc~1# zFbP$7f6D&RPmxb9cT9SU@*SAFuhvqzdhqEI9Wipyro0aJ!zz^CI>Ya@M$VU!vo@0* zpwpVQHkj5qDw+3ZhS9$czJ9i|o2<3oz8&C~Eo1MRWvE-$(6JrGMa#pEksL^;rQ@zk zwi_H<(wVjO738blf$VTNPVQ`KHs9MXR6$~JXsuy~9b7gxMA?y*CBXh)>t?8;*`akq zwRwdXZI39EVk7gMI4fo=@9?@x#G}=2ZS`KwT3MLo*Ss@;$R$BO)x9Gw)hWV*#J-F3gh)JPH8UcY%sGmX9ULTb$Y&DyQtc+3X zmdYAmV^lKxfn2Q(9;Cm(x(|toN8|Kl>T%tVC_WvEP2gzvuXc(r_?!6CqpxeW70VHo(F=8f{;O%>vlW#Vg?l zLzuufusXob^bup>0|wTAK*^wGhiJL#S*V!@#NqF9Aa7Rw9Wu~g)(278VRaAs4=u)K zaF*HzCNuc4200xtkVQ`10RZ#ZX)O>Tw950>9YElui}A^l2fTa?=fLV(jIIO82)|JI z9M-x+sGCwe2y$SO1KkJx9-@aOk^z#19x@^r52ioTtG7TLpd}u;3SCHz8YE!bm=3)d zxyA;TYbT@rT8CI101ysB&UA2tRe6Bv7h+?N3LKBOB3v2`x={Q$RM3|kL6!%^sl&z= zc^nE1jt2`Ou6>wAjU3{C;CTExM0A<|_JD)-PbhrBa?z!HLHUzK?r;Mq=5zYT7rEH2 zreF4e2KC5^3j}VlO`z{Xj-(Ufki{J+@JLrr6yp|4Qx7y*fqWAP4~rFk00;~K?OqRK z%Y59$;L3$aUt~WhebC(p{G`o4h*e+=9aIgc+MZ#>+q27+_!ly4v2Cc+G z0{FMLJ~@C@qdi?93_C9b6dWlKl^E&hl|lUwji1icv^Z;bHi&enarGa=Zf<&hemrIS zHNP>l94d!dQSW6AufylO&+vACu3CvWF_B8{fUmqusvJ*&7TYv(knAF3gKUa@58IBQK1`9VMLl-!mGb2a{C>+D|F2;n8apBas~v4C8$`{cB*qoo>90G4tE2R zR$>QggBcz1QZ?3R#MxtZWB!MRymoV#JU}+JeALSjpy2E9vYWw-qBx=hkds{QzylU! z<+-H$4~x0C-aIhkk!Hluv=JoNL^e`%vRhK6(ljPD*OD0P9kF-@`W+m402TbkJ6a`d zlr?Ii4>2me9jsvLm{7?n(Io0K7=lz=kkJ`9NTh0|V*M4NBdR3eI*8?9-&j=n1<XJ!9*yvFa4mX*aHA$2m=~rW`I->K573WAfMSOcI1NFZqC;;QCPewGIzmagGjg9dAbxX%XjpX0S0@7b8&tbDQfl})`om~z|A&-uSi+YQP z6tGCsqAPh3<#EMkQS_e38-+j;ZBB$KQI$mUZ=uQb(Dz)3LmbA$hjPmgS*RQynov9d zhv4m4-z!$=0s)06%$3_)D0(K1{f4=Ipc@-`On>dJ;2_DvNzBkJ|PNtnJf^^;en!m>H%WEUlD*)_Dv@_-l0<}7I2FEuKzg?Erow68C#D_ znN3;>?5+IMXY7w&!mkwjLu+i1pBSVB4-xwtE57B;=6x^>`_!T9BfsoD9|!H>M^@08 zXO9KK0_>SQNDutcqjVdsuamzN2}hw->?qN1?6<6&^I$08uOxWRBYz1zf3A6^+1>y` zu}OG`GO>mNJHDO9Qr*#crKdYOoRP@Io<7+g+W`hMf2xBR*07SnT2d87WX-% z25|!O?VRck$Sb3pP@62-Bw{8W*G&V<1Xp2y{Y)elD&Wq)Jm;X9+nGc5`2-BI16wV; zq zQJr%IOyZV6CP96A5|M`!5DDK&B=!+T0`uH*9*H`Uke?s%c{+LF5xgIf@e%fh9x*{s z!qG>-0Mr1Apzm-I=n%RtULNkL6jB7ycR92Xeu*2gu@Tq?ji}fN`Q*ia2 zn?1yrxgF*Z9EP(6f`_oJI>hWl!0v_Uofksq;6hv@Ed=F4#2{d#-$Q;7n+Jh^>e)ef#x0}6A%P`%HJLY zxPB1S84d#Z@drNs0KeI4t3NRD2Ov@HJgmN*^?(OpI@ALcRy`0s<-u#n!_Fajz(Jdb z%3}tQ2TAkiMYaQc#?NePaIyoIhy$_DA-@CAhVRf_c?V5}-yFCDoqLDqvENv@4m#+N zV+pN;4mwyJDi5rKl=;J~)f^UeZh8XR*|K_44U0?;^w$mQ3*#KPm;;n@ARfVi8}Kl` zfnC#ar+*b=b2lJ=i{|iEh&(sJ+0q>B%jYm*Fqi}6UE6F8Xsm%-qkan?Y2*a8;m-|78@SE2A>&XR?2;R3!z@Cz4Y0%b?f3#33BAC*k?;Z( zhhHGpBK9yHpKgJjgDrq@=(j+H*+2_OUc-ms8aNVKLw5NZ?2Zvw!^G;kZim+ZCk9f1 zK4!=V9bj#31Ix|4V{4eM)c=LTyO?nb7#mr zIZRuFGfW;OUe|R&eg@cac-Kd;3_6F(aF@Ic)P`;uqL-4fr=kHG!*0@oc+8kFV}1WDrCP9yWcW;;~f}V;a>t( z#&QYB@51@(pgi+zgH$U71=;5Y5&_tOY8T1?)K|)0x}FNzr3eLwsN}0K0hKlnSHfSZ zI>Ab^)1Lz%Cvhk@+nBaYGw4aP!%2{K4S8tEhW($+MhKW5M#hadrE+_(3et(=TL}+@{x^!6tXn-DFz2!*R^6B3&9SADb}El zqyWf+bP)eVUK6DElmsBigQEA^ZyX$NY(raIWib6zY7Q%@$RqOvtNeKh^aUj#5XagA zpyyM%2snR=##G-Dtlida8&*%T)cjqkj+u2h^3{lbN=ch}6e*yi0S}5+?340%H zB>@uq+#;*Q1*#8)sx&T;+b8;)EV3wq3V`As>y4KX0C^AYqJv^jZ5q=89M<+o9Gdgz zMvhpS+43Cqb+$RUuIrv?6o6X*qu3f9jiz;#0+cyJxJ|2|rI#-)T)iN|u3gG?OWzZk9j0na0T?PLg1Nku)?z{0{ zb(lPu{L)BBX~^c!mEd49xQ++Y(E*Z?ao^4BWLOWTL&=!1teXP^NCpgI@`8HTO-Mr| zbU22FLFqBBQxXYL^cXZujt&zaBSJaZGW7x~hG)U^@vayfjK_k9#lW`PmFLB%G+FJ2 zxft@}&@jR%LO~3JFS$U5kzr53FzgWTVay>^hXH#B1HWBk2nHB7I)ZV%2ZK@$M)WZL zg%9Gt*f{tL9J624{e}GVdht&nz2M!8tV1pD6Ug=g_73x)52+dm2jrzZG!N(w%!9b& z1l)la!utagOf2O84r*t2AafUAa?7)i-$mA4SR1s9`6>bJ0(K*ui(Vvip?f|T_lm0p zkPE7};9?8Bh0j}TiCrw9TU40@z%8_>fj@6qEjSL?$fulfH-c~O+bBHTn86> zxRoEgAdWP9qu zIEX&hEW8g5$hvVB7|8$CW+CslK`qDOSmYgyg{6JsECI2A@&+9SOZ5x_;09;`RC_J_!N8zo+8UBY!5oc^m=Ow2*pd$ zqn1+KBMzmYOInI}0Eqo|;h^iLQD7f8imJo6qL3X75Q9zdVwmkQIEn29hTILh31rr!{qFiN5s!S?di2;KoKiu95#*bCov;0H3}O`^0tlr#zo5?@#kb>nGS}#nMFp zv1lgz(j^!Rg;6ZgyQY(`aR7AMHQfnIr>ccG$s7AjGK_I1JeG&hnC-Etg~VWP>NO3B zO&T{{Clkmf+VV}&A925_W!l{f5G$1cex{lPGfApHhtVrsX9Dm_ZhdR}m6?QJfikq~ zxb=nMdou&|v<6#=zE%BhG6P)NOZXCw4ERgc$LCA(i}85={D!nV&pZIAWWCb#VU-{W zXi~>XdM8~P?~^Ez-AU2!P$Yju2DtGDFph+wC}BkWNHqr|$^JP%;zww<{>aMcK9BGb zY< z+n`taBHD!%MU4FvA|?@$6Br==u>kn1s}spzqdzBdhjl&|G|3IGm4+%*+1q?3R` zcg73REEIh<4e~#KV^0AQ@6e!{=u<$g`b}kU0M8>OArn(VrV}C>)E;RzU0H_Bn(K zfdXMbK)ij2r&I5kI4U?I(T+-q?!9^(6uLtIRTj3V9;C!1>>JC)^2VZpAF2 zPNvY+PGG<30^WY52-!s2)C0l7qflcRpS3J|w!ky=1J#Q(at z$ZrH|`86Boxk%NLjSxU;u}E;&GJ|}GTHqCZJCRTm&!UTNmfM5OLVbFc_=HwZBsbHh zxc*vec$H0b0DltB^9`JB4*O*3)7($6KfxXM-K4&fV!1hho@Oku2NlrC*Y|>Hu6=TzV6Xi|OYcKJ}MlKVkOtmF| z$Rs}!`hEB-{D_BFavh>qEWa{gP&a)A_L^;_XDj+i2x#TTycJ3WTZ!85R$baa#Kx0B9@BNL5=br<$mcR6 z=K@>#_Ayu6;I)1WwE?%pDm;+bZ?8p*mLDNkixw^Q*CHYErA6Z4pVL^&vro^GCCdpq zi;aT&j57;-kpSLK^=;vLDX&z<*2tfHuUq5!pDGXfB<1H93zs08u@>6XB6cZGzi+(KMgl6~u2i{_lu7^d9-Wkt;3TUBO`1mfD+&Hoq)w5vlphf3 zZX}8Tj}%2%Vg--9KH30)xQemikLn5hNQ!U;uJT*BRrt@Yl6e)2gob;SsjI*R(A%{O zh9e@?x5pY8Wh2^Yqv(Tp>O;VSgAU}zPMl&(>!#8PE&4Wa5vSpqt&dn#R77(CiHeGD z(61s`Z>K>b&5151qLwJ$A#aB^9l}ura;Wm$A&CPn^liQn$3of3Qz3igyU=vPLa=t- z$spY+;XnpmnHn&N&M1STr+&LQl?^0Q!Sh#7Mb7a2d5sa)at@TAtet)e5Kt=%2n31D zu7wx@spjcZZV&Bg5;`RYbtyiE6ky#N<1eLll1q^v=g(2#KR-WBSm>XhpAqcO&rj?> zv*!Ll>eH#lmkuc+`uNBrz$mcu zbgge|U&@4g`ocW1Lh)VQGZ+fCfq@A5q14ugBI)OR@|b7dnL#^+PMCAr3A+=1JCONA z^C#E(CzJ_(5;t_>sgvEE;O(SRClU!a`As*FmS-6`v(!y2%)%y9H-R@qfJ}Oit95uL zH+v=&hck(M$J5OO@8EBU_;+e6`W^Y{lCPI=o1I(O?!@o~_W7!M3G5LDA>{2jw0zBfU^ngb;mKsRxkJL^ck)PlEDEo#x@vLubjd(M=1>hUVZ`VyQ)l}Xa)>A5@ zwDA*wHv3~55TH#(BLvY##{5t4MmP;Ol4rCL+qpoE%n`hiB0zT6J+QWymOzUX!TDg3 zXlpzc8o;`7ui-US$kxaYfc^SUIL|ZaY-h-J@{q6B2k-^4tK;x4&98RR$s@XA4#s{) z*In@o2>B~+Nu0m;J?>-$^|H0xn>@Jd!Jyl9ixSb2$c=eVZ8(vbhj=2kZaM_dU+rs% zG(igaGgOYnm~Q58>IZ0_u#m}Ag%kq2jPDu;)t3he5~K&AI!N>_3dAE>AiJADu!{=# z>kI}Wb^iAU_d$PTEZWW&3_ip@`|Af(LIr*FmekktKCY4NgLXY2V12|XDE35f-8AAU z{_Dh1%KZ7zj(GytnZh&s6D$r0z&@qq*9mZj(sWOwI|1NJXNaES@GqLUB!$Gj_SjA+ zo`OB<4Di)M^89Z&$2@ZPt>!Ut@OeNa^mb15k~QHvxuSrc%3u?s-{GYc+_5_!JxI)V zRJ%j|Kl63a8Gh^8ax44HY~|Ms?C}8DvA#9-PEWax=&_eVZ;fSmj*3ISa!4K!!2C(T zmfM-Bb%5+8Oqc^;39!RFj?T5dRANspj_3q?9<**6c?0iX`|F0(`Cl3SLkzt5LP1H;Jf4JGBYV2!UnImx{pP{@3ERN;+o&D4A-gW&7xRJ0GZTkd zMqAsb4h*5aU0(p`u3qb@(-RN?afq+sn{-`)zUAL!PW!V$bXDnE#4jouv8iSOG1UHfL_DxR`)_%#?f# z?A`AA3D&nL1|6^mcZc?X>K;Td)9{^CgG(+nu~zjl`yvIZ{W=TOUU z89B-=!@@xJSw?r20rl@qsDM=CfBC1>%|e`d?i5zo1a`7t!NTFMJaz;O=68xN~^-ViE4QloiMx>?4l*uQ$N09>@=P8o$YM zAUWF|It}~Nm^ck+(dc~Y8Du0nM-^M2UI42VK|2aNUgu)5%dHp*&bl zW}{VYX>uYWG7^e1Vj7A8B@Hk!@A|X zDkJYjHI8n`N|x9Vk`d8$(Q-Hxq-?pG?N;@Hk%e)2EqJa^M&ivG zI1lDg(PpyTN9CtxI5(O&GG|jv3CM^E2ul>vQWVn=l_V!6-|2Wh9*@w_P*YT_iOGn_ z^J0L%noTKJn{7cF5?V^yH*_~Hs+x>OWwV8Gc`z5w<-u+wRhX&V_az5sleL)*g&ZI6 zmcw~GOh!UcF()fArzI=i>*dFM&~-OC92N>xGAZP}UauP#kT**_*pBpkyc<}qHj_L` zOGZshLs+7Ul#Gs;mY$+wO+ZMU4%3p7QIZE^TB-t+ByS&>6mGUKR9_DF<-8nDhUC4z zTkN9^ecvtjVH=f|jVgy`bt{cVt2ueFk9LI>^I%IxFq&-1gXM5DBoFrGj67IwY9{2t zvT8tAS-I~jE0*+KW#w|RE1XT%;j(bNQ=y~Ha#$9pJFG%fhqGBLtlIbCZnCQ{w;IH# z(cNyJcjI}koSUYcFFBv|YPQ=9OwHwat}ll*_1({deK^@iv*NX=YFM@^FK4THHd$9v zHlEA#wW=SI>NO293S6wb{@>v(RY z42S!yyeryg!`N)ot`Sw^ep7mjhlAr~UFGC(JSg0iZA*>k-PC4O9~c=6Zfdrf zjSB0-T}dy8byb^rUZ}ng7v%*fo84q!aJO$(HS>b|sBB6_UOb#l&E`>kIGL1(n{_qv zheeZtxiTv&EUQ^$!59RSDV#rvmEa8re-;rl`V%Q^Ke&KINAs1qj@#kEQdw2CcUrrP2oP9^J+5>mz(-fkg`#I zxv7u#;XE2m=HWgZE@$NB&^|08&*o-fypJX|%gL^+Y*XHMlX*Fr&EaxbS2--3_jO!4 zT-D`x@#5h;nMYNV*`&S|WJTW1R^@q#imIZ*dGT^ z9s`k;Oye1qEOzlfjn@J_P;jogl zUXzA0!BBo(QXRy97e+m8;$O7h$llnA2@u;T0seY9mHaq=&vO^EtpK!7AHY7F^c1Aw zw^yno4CK{PwEI#K#{C9z$-29a;{WRoER!bK{JG_MW)Qq(@_jyGFOY_c={s1Aj#kX= zqKlz)i-{hnWA9`K48X<#z)5%js+BP^05W&8VHdu1f#ZNKRd<*5=|pt^-96hmubzmL+OEU<7xaZU0ou)u<6LG~4X)GP44LcS~5Cp2(hVV=NO zfSpEXb)2Om&AL#07S&l%U!U)uffsi&*jwq9E{OU2Fg(xvgoX@bdpsIub~ii>+#zo_ z;RXbwH<%kS7>dC}Cm73ftR1shxMI~HEs!~^+y_K{?nj>EH$lx^0jGz{i?y(hgN-B=@z%T z*ow}`K&x13zKdLLNy9Y#X|?9lWamHkIL|SskXue<&=hP;VcHa+l1HIy6!dGNa5)N8 z1rUYUXMO}4;B0p{dWMhitk#+IuKn8bAav#wL~Dz9JHLfVW5_T4wZG^Y{N)nCU#J-S zCDtnMt2VE~Ku{p7Dy@g!M`j%SX6A*C!6?^5%Mm4ZZI*H2$SnI3WiD7!OSMt^i! z#DTr|sJ(3M1#i(_Dhysw?nQo~9ra^AisPASXtg(L2BA^VcIh}M)h38tu8-|PbC(EZ zNQCl2Jk;(Uu(1yeRV$RlT)q$I!lf6ktf*w}mW&1j00000005I00001lP))zxsc-{f3A1j>6|S zuO^ZLoCw(ezqxOKIL;0hcaUeyipdu zG_P0Xz(~ipaFMIm0^@x)96O9Ce`6t%dVqO!eV_hJa<~bBJB%(DG(gdQ{#ri>SLr$< z`-PO$)KieBToq4oU7hIFKH`TY7;iejA4l){Hk&li{1e3{2Pauba>}6%n<@)se{%Im ze4}?@@rZCHoxkH1l74%*7v0!yw7K9Ll*)it^nPh9uw;+ZtYkZMr_X*5;G4jHHDF%d zB%cG+E7W1NvBUB>Q3)j@)_KHG<@$NgJ#@YMS!2gQ8MFmwUq!NU65q;C83{K|ErS8{ zzdP*1&~14~G0tXB{`7d@^ESEJE^sFxYytwr{6b?xACN~hC*`Sbc80z=E+M-(@e3cE zuaNUI=>1-!Jt7-?p70yM&9ZM@>`V6l{nMg5bnQPM9Iyu~A(n3`H$>*=-McDB-NQP1 zs^SY3=ubz(cCsrRt#2Fc{L+?Qoo~=}e(XixsitXy(2>3J`?{pmv!E+i;n+e+CugOT_^7Ev`5lAvXKUwy>AZKJ}U)>p;vw3 z)&P3vHxBzeQ|C_5J7cV^=FoSwlyoceGksnDj(~0|lx?aws%&&*`ZI&d;@G!TFnlMP z?WR}8;}1Q{|}_MC7)zkJ($;c6CJyCuqLn3I_JPSdkt%<`b++gJ+rutu3O9)&NfP; z;gWl^I|SG&HS6jbtLPo;9n0181B=uD;JfJhaT=oAOk;))hGK;$yJr)spQ~E+GW4aV z{l5(Nz2ar}kFKXjY8URgqI9KIHw%Zu+1R`Xe{F%U-gv@s_+T5%)7fYAE_{K39eeZR z%2zsIlK-@D#>m%^CHdzJ3d23mr0c8?Q;vr99)-qR#8PmOVRN38|BK;DtDr>xDLI%) zZ|TG&9KxT0+PQPO?vAAEpvN&Lnzky~(@c@;Z%Ayz{RajU>>tuQez#Ry^&f!@$){}4 zAGG39%>AQx_N&qBoXw%ex=S%iTP9cPB^0 z##rlnjY7cpCZ^E)T3Ul=Glw!%>gI>~GxbByF7FlA?KTx$Eg-Pvls|1VyZ zwJ?wWkc=A&wAb^gt88rz-JIS26+Ue{TCp>=w84)i*LD-Eyw{(*3#`)Gb$&{>DYp{S z=lb*mf~!g6uQ~^P;LI^>+j42&W{Z@?VmUbUZx=Xb4m!f;xvu%qnm*R*amijwM=$XC zUlqt2d7y2Pm&8N-%$@7sS2($8=Y`tS+@N=P|J!!+NA3#u($)L%=Fjw-k57jzZM12j z|1Ca8*07OFUjB>2XSZi(&MFL&b?b*E$lkX$l#FniuxB`m*FAz$=;LS38#`tqIBmu3 z3R?cFdS3^W-OP`RKeaXUGl%T3OoaYr3H~>ufAPW1s?7RLqk3U4&(r1|Y*+W7BK+BC zvIs|`>Ob=2&$x~MS2zD@-tabZ(%JqJh*9cC2Htn8be*Te7VKCv@25595|F%cjzJrG zmw(FrgoQ4e*>0yoFSnUUM$@48*~FT8-!2W!*-Hdkfu$ki27JJ1V{6B}OV22}QGfhl z+sEUnzGm}R*qv{BFCPAlnd|#=iW_Wu4clgo)?rS)q1k>IGT$|zF8 zX$H175VC3b!)x!LGRHq`76)c~ft=>3#H`tIP2LtRjh)ln8@gNx)YJ*|eMAJbhYvfhk#9E7&kBKV6GT+ z8+5`#%(QGf~6vbJt*2GmM#vhGQ^qpM%)+%21dk_i#EL z<)FIh%bb|$sfLx!19}=aXo4YYvnQXcV%WY-_|D=f7-+XIh3Tq>jF~OnA01RZ!>9@P zp(4#XsM~St$%Nr+2Ls#W=>%jbR1Lb#{y48Q#G*H(+fnIB7~aazB}0)duY3aHpyP?=6Ldp|1HC5d$$jo1-$0A3;WlT!hYV0%P{UB&ut76u z9dRFY0C0a0Zs~Y)W&`dAzj*+j41?7T+^tGzqJp7@t_FndHD^w}Vclow*k+TF;(dQk zngRVG#>BaSw|I(KKZl8!hSS#3H*a!)x9yos*F)#SW@9d%*JBucG2m>D4fFCIOx^H? z%yAehD+BH}R&g@uVaM@?d>g*WT)VOc%)@SGl(Xs{6!3t)IY~{U8w#c`e>j`E%YgfE z7;n!xa~cL1VuO@v%+QE-4djhF+dO#m5Q;WuF0 zaO=tBP+5n;ZQEx~qoK&|9+veFYWnvE>ZZ^dUI1i5T2jVu>Hxo9efoKkV%j=mXgHkrUwyo7!>qF9Qx@Ybh zkzs{+Kx{#~vlO{OH2OzM4C@BpFfTT&#U2jZOz(`t;pbUv!U~7A(In2R4+ss?AZ3n% z2J1Rd88E<**<6w4RX9jiGh=9N z1YEPk!B@lF&O@9`8;rCA?lu&8GHB@X558N4&_sm;ADM^LEuwFh{m>o#-^Y$i&iniOyTL;fRA<`)NRD&mRO!S9;Iv{P6 zyK~lt+K2(hX0R}g57G~aEr@)&sNoYA1IG5yGfVy;>$?Na2ERD3dLTp^^tLr>ve6)~ z8QHLFwkG)rPz_k^Lt-A9?GRuh-C_ON2JH5w!eq|jvgB}j!&E%S3`%9_wk6bAqlS6i z;jn$^%+iOF6Mt}En0(W`$wPbhbkG^t;BGuUu2l$kl12=X9>echIWfcoYg!eb`F5e zujE|n;j$P+w{HJAZ78DBVYOBB&e8@P41BZ9o$TQ*!`#M3Cz=`VoN@4NCBzeK4U#P< za{3$$5J$Trk>C+Buo0OcjE{D2>kI9E=3pJcH+J=K|fPa>9*zyj_M!GZsV~~m& zz%A*2mNS$W4ZH1Wq{+}w>owrsgiq(i7(_uGx^EF5vpgSU`ww%E}?Y@|d9$ftav#_a}fO;s5IHX|O!v^jF6#ah=tL-yjn=W{0PB)aBXz%1};4MRc zy9-S8d06oWu+2qHFAS%#h6&f<`P6ZTms&sE(!-=1r`P0tnDH63n>Nt|!ol07B+aT8 zhvH4_d;&Z)io@IlR%bO8_Q0ABWNQqkruT=d^r5~<`6mAk#vi!bSkXkp0Ur-5TY=Yn ziud4x2YDma+Va_4^4}NSX7WwJgpoM%mZryQ;$OF#q)os9_HirXH8=AMl)mcgn z`De~%sRy(LEX}_7gOTOnKywioGF)^RE{F&?259@*n{RlSw_O@f8f_?Uvput9hSD$) zx_u8PI1fKf7|PGZWk9oGpl$m@^BENlceK_(l0!7XZs=}B!V?u3HogpyPp9_4Zast( z(ZfD4L^e-v^5tRMJQL1QIPA80s*}lpSp)~%8(zRUqK6X4ANp^YrE{nblW(Vo3C<6i zK*N9gZauj()Hy)&MRXPt32C(-^7ss(=nc><3u@|Q81CQt%%(#R*~KuMU&X9GEIqJn zVj8JwYo!)04mIrkcMVx6VbWjX&-G;7VZZJgM3^+yuz#Nd?Fn+oeLu7h4 z6gU_Fwnwiy@euNdo2`g=5*QqPu%oSsbY9w_T{6&Mqxes=G_Y=N64PxPBsMSp$*)6a z`A~Na0L;Zcn3-UZ+fW0wbMzPt>+?Z=6R1p+0iZ$EnDX4hDi`7K05A>JQK=o)7KA+A z<=|U$=-D0zoK6@z=p+o|S3-V6ymg{ZZyX${7-np6J(E2{MdM+p>8cM-=$0W-5`)&* zz;a$@I72&tZmO1Mca1wx@$(_riIIcb{B~w34ubhW0Fa2C26+4Xo8>)_mg?}>?vk^f z4}7p;Z!ba#4s|HU5woiVO6qy;>ICbZz zaG=LpqA9-}S+6;=aTAiLVdwG=ziqtGAcG)%OzL{er#3BIUi37%BiI~cZGN5$v$ldz z_>9-?f)X)DO#_4Kkn+ncdPm(d8xquFwON*V9!zW6^qU-bVn6iTcu5aTIma$ecIBx#r^&2$78Y;sDZ` z6XkD&*rIvok@>)wm_E60KSPfQUUAQp8NgKzROfB)G%__8zD15{i^D*T+8e;Y3@Leu z)J%lj%xQ-@GJ!kn%H}=-Jar8;sbHL{#?#LBG9=Vi_Ce}B3L;4q%I^G;z}^EHZbO%A zr**We`Ci8b18(b0$(5X<$3^1ALX|iQlv5yJd!vbrK;l|*e{kg{+*9#S9M9$1SeK(4 zqERP&c(VRnen1&i))3@d^C$g_KtwIIK8D^>yQj&)k8t@fhCQhhMZWu@dsI^Z^^O}c zIKeioQEjUZ(Ot%snuj_IPsqMc;DKR?gFof`#b@Qg9nB)Q-JHM{pJfZE+Gawys!VU4 z(SN0VvE|oG7_Py8iVOxfbuo~P^Ow-f9(*zpL$7MjrjM9R0k6%c=qO60Ozo7p3-*L? zl_zXQrDJFINwPAq#~otK_bRF?4^74mk0$sJUsvUC?rxKzyDq4Ex(HgZZxGxR<08S0 z0Q28lG9$Qg!Xjz=_S*&oMgPKzVq&TaX5T}J!6ltKpnL)3&jmt-A1}o6G-fSi;a|52 za=JY*V(7o=$o+d+29%WF$naKGgmR|WpvY|!UC|7SU4r&V!uWll6pn?aF^>WwTf2&12HfBez>3?|dl!YtHttID#sJ0xxF zs~1aDVC|x>Wf;MLEKWeJMn>`{sK+1R1tR2Z*3W$6Yt`q8*=5kA&6>Jjw}I*B%u(-z zp3uHczDGM>UH0SAKbGP;3JI?zz!yyi)-q%(p5Sl%8=Y7Lx8Wb2xrRDJmOH{B6UA7| z6^672c8d!t;v_usPcelxzoOgNqUfPSr#M@*rDKlzXUj^=;}X}Bhb~HY`NSqNDZ*uOO#k?q1F~Sm1`8*B|b?;1OCuvZa=ab?f}hT z-2Ki8_`+N)AL)!+N01W=+j%~qZE}1J!FMdBPcuIo1MWV=J1k@g*rkHhh(W!z-6h(9 zDqZoeWU7$Nl;TR5pSr;fKut_`M;rICA#C0R>64&1V1)A}o+On+S-i#LLJZPBwWIhC z74s}`B|%1M&KQQV(|FP0lDmK|n{hQ4g0}Jwxnbw)v2ewoKdA=)a%&VKI@QqUMyD>w zt(E^mw?J-!W6LAUFv&gnHCTwcf5Al#mIU8@>dyP zk~Pl$2YiMZFu++10A$narn5%~Wsri7#P4z(F3WGvX88%s-=Oshu2ka!%%(Y?NIDXl z)B?Fg`ix$NpGSRV1(e5x>xJQ%3Bz17gC&@;R`#8q!3Mv#ZiCticqWq4=SJYLt%0J} zYwwDD+A)yAf-%1 zVrS;GRqb@CMm)VKYUKQ1S=fvEYw2Akg0A#_O|RaUeyPA_H)A*>ahgeIWA6h`$XhG!9RW7Xq9^4l(A=YE1^QW9M+jF>kzq>_b#95iw8==16R}PAqPp8q>IJy9<5)$906)Nbf2* zIgcPjj2o?jhwTwsiM=ySCkT7cL;~L(B3Bb7v5%_4M^OZS(;gcI7ZC5y&enj?OwAkc z)4dwS6@lQOp0b}_9gl&73gA#by<+G}j-TAE1-9)_a#jA4AGaw^9$u03cGea7Uig>j zwyd8w8-$QJgq@AHAT$oim(V{s`DT5mW;(*ZV$6*e9FQJCzjA+CZaFVkX0jS4VIWi4 z|1nm(5>EHHk;Gzf+RU^<*Z>c!dxSsV1m6BhO&x^g9KKd#;4Q#n1R4m+<705r&S7sM zm!4T%1E=I1kFXn1Ui$kkiNa}i@&9;HvL2eK)*7_$Bl%P$Vqh!_ zD!vfG6$g+`X`2Ql*Z5n^mWHeiZQ@z+3_ph32G;* zVA)n#j&v!3J9D^TS=CfU4TCJGX$dp%uV9p7@kHw+TUB*k=5f^+%59oL%55_a$RqsQ zuEF1|pGs(15W@7r4wh7a`h#F`KA~B;UG#c0{o7?i~rQa8Vq8>H?zypH(hmFu4eF$eD5t2>OYtNhe`P zmT}n_gFRDER6MW|72uHx81jfUF`;^@@7(!03+v9&!^b~IxjODAJy8Uw5LOgSWYD2J z;K^z?o3^y*6GXrhUXJc?1d}R!OVP5)?*J#Hz}%1jAWTnA&ZVQ4z(>U49g*a_faL%X zED__)t@3$_GV3bD%cEDO$VA_`GbDkrlNcPzgdGdHsVT)M$!C1`HTW28fYK6;O9_Xy;2xj!Jr?Z~AHBmc3$Hw`sQkD+6W>q5>yKsv|-sD0;o6(Lo^VCOhu zyknCHyw`OX1Su%wi%qrzE6IUNh`EDud?*IN9X`NcKSrRIpFx1({Sdtgx#*NBPRP3y z060~nW!Q;b6mu1oL;s9Z{fA3{Yt%6fL5q=W;TR7$n5T&71WRO+o58-1S3UUw6OXMIEDVkaecLCOs7>82^meb znlIKAm?9Df2TDK5JRp?@>S5X^geaJgDhM(!Hc~@JgMrvB)MI+sK=wpL!J-%L;Auku zbH|C)a@p0qmOX;fgCRg;v!r>#PD70{)OevqVfM&3V^!c?qB!AwDj^9%vskV{*{>WV zIR;0J=zYk6^S5Bw)5}4?Zb-7zIp`;wDc`u34zVdE)1P4Y_f@+LlXFkjWqDzV#Z=T3 z7prwIJ9iX!)6lo+hCYUkGt|%?CrhH8M#(BS1951%DjZwUx}p=LIHh2h?Z*W<#CQzM zIxz6QM?hdVej!Ip-4rrN*Zy|o19|y+=+PmxKN+{+55+>i;qQ$ZSy0oJp&%~uc2~+a z_8;aRDXNB5(ij#^!2t9}^prQ8)KQ8bDPwGVFkJNkk|&w^JN-N%N5jA!$k{Ql{|2=g z18spzhGWYQ6yhWV7E*A$Ja?i~3SYRUO$YIgZZboY!!=iG8!{g^O%2PSwzlsO-nH%+ zG@HgU>Vl|7p~&=iT!qhoc{XH}lIbOd=v0*rd=S~FpV9q^$CUrQA-vEJX#2d5=!S(x zhs-DcDT(8A-B#u`L_LtF4qjR=c1;AGlZ-XTO{c@v?Y!hoKRqO5PR)~I>OR)|$20!k2LL z*2^&oz!IJKy36gj>(OV+!now+d%nC=E?4K`>WvimFJOMX_sHWjPy#tDa6|BO!Y1r8 z$c~cB>fl#`7fqoIq>W}CgJE7aml(#wd{z+eUo2f!B30aVk%!vpt$v+YOr5&X#yG1s zP~zvSUm_S!195J@;UDN-XRJIRB^E+ofCk@$m}mJS+#hZn^aQI?dgq1dX;&ZghpVh+ zV;g1#3+SvfJA{C|eV!1*RHvkPwHoIqy zsBoB}{zS%GCn_Wc>UIh*wVJP0WuSlcqb4?#?Ohc%OOD{0DA0%!QV@K_HlAO^bborQ z`LfqKXdC3sYCG6aE)d-<{%;{3t{b1KL~dlH=M?Id@`jPdC#rHvf&b~LB9q7ATZSMy zDLlE^3i_7(#|6JMJ=_FzW|wqu_3TBLBV5PKIraYarQn9z%<&Ah1wL|S%mWB?eg3ba z-!{X-ZLKy?5>a(yX9%_5EGC%PIWCvp$AcilaDUl#KWg@poGk2JdnhgwZS0yoPUFs#kS8{lFNOf-=dp_bsge=3hiJd&$ay!tgnrp+9r zLZRbMQ`mX^`E;pFDujjGC4Q)=wK|_J*mG3%C4IU%13B)vN|bv0hhqgUfSpdP)i8JN zz+pSjt1T*Z*vtG@)M}faKvSv?62iA-WIgY`o#sL-4GScQb?_OHXZoWLu)e5d!DGmW zkS&YF?|@yhq!7t_fjfLGV_9?!sv*&=DV71~#7vpud)C_ zQe*2D)mO1Hd1~Qb?$}bU+btT+OEJmXkdUp!1E(aDJliT7{9R6Y_kd?|jDIQD2N{3b zd`i(6iN$tmh|^7XE1E>{GC@e|_TBDB(M_&*G(<82D3HH?h%Gox!NlvZ=C7t>2=lPi zk8LbKIeN7I@BERQbeNhaSv{k5Y#tvwDKuIfGG7jmP4QhM{Xho)b=`o0N$ndc9>AB* z5zdBYvK80)M>`$SQT{T}%EJ;&bbI-9fsGJtq+}$6&!+r_+&~v4@rbH_#Iq}$oA&VaZA05R-)|lH z2IWv7FMN=%(0iL(+b!!fJQWoU@P8d%y2`j?)U7DyW8OpE0cmc3gbAH5{bTOr_V`IB zxRq?SaqtV*bnlD#)@jMq-jUiyGg3W$hi_gtLJhlN@D_)4BpwmJD3~VTC`IdXolT78 zaV>_@H{fLuU?aL zb(x_p^o0UZRetb}#E3X+r5Ja>PRwuRPVbVkcDb5CKW5D2nMXA+N_}AT9E<3Cex_{Z z6{H3O*<)NeNAq65gR-9iosop_+f5@8v0~UxeuY1R72Nt5Y6axKTv@dT&RQBzCZVf* z^e@+keEK+9qPFkA5*iuRJwfMyE!ETG?irmbe4H2xJuqhBC*Qr-;I?^Hr_|5pc5Hsc zmueGwZD>O!k*Jt&en12J(G|uD%uYuXqarFepf+XIs?q~s9>*d7i6W#ZZ%VXt9)1G! zEW};P^})Znqi4DVooOcEq?sQJaW`qC0jfFhL;5>JAyan{${V zt>UT3{zl_AywNO+NcAy0rc>MYxx2dmQ<13Uu9m!Do`n&#GKt;gkfk<~np6w%ubuec z_rp-C9tVIb(JTO3;}OsBy_N#FqIQ2Bb!F6rfUc2AM|guO38x1Vp9~}HwV@vDQsKWyx%o1zVRY*#&X&=_I|5_>%S^yI%ym32B zQq!Rgt{_Jm-0t#M8E`6s<_HLKzXh&%cuK3)oiUKOSIkr~iF9xp)xtdJ-k7G%TEj*3 zo6{+Ji(hUrp;P;}T2W%O^tLoYv3F()Wgl+^y6KS(9Iz3u)J@Y-S6#)paP`xn3Gv)V zNR#=25{1n#eo?`p+;e?DGBE~Ah8d^hYlejz@BLCe0C&PGNs5h;wkRjdytJI)%A;dZjvu^D z_X_4hIe|l6*WfcZF#=H#OA*lUIqIeDOVIoe+<}!W$NFhtBR_*{m9qGOzuYiOR*z(N zt3>bLeyO!Qm3*(MOir#Up`_sxKLTN-6Pb}lA)zBpHn(e;0XZ%Ij`OiT9-7X#y|7aU zA5gfkXzz>ge=yQ>Bexfvu!r9#b-QXiiF-<&mKZ~SOJ>>Tv`&vs73WNYuCOV&)2LP3y>D&ZkjrVkD3`1&am7OdL zKLv#D;*;!vB1UJEn?vxPWCpbvX{Dcn5p<&MdL*`nM^e`ufgl0?xdKGbmL7zQ)Y44VYW=^ ziZBkcxOO!301%Ng^-*Wx0-mf*jSw4F5XnB}fmso;W6JTMhJRNhg3OF_e)889u6LH6 zp%Sn3PDB*21JrhKhG_CXpx@j5`kB!Xh{5Tn3vXkn z_Iq%6#Ha+P*dlDW7yUh-UB?{4#luiCDYt_srQYp&2|}q$5S^B46LI$7T1A%;r^^7Q z3l@BPIPsY8-)0uqjeOWV=4mqE4I%5eV$Zox|8bt+REt{8Gg+ol02l zPhk%NvjAf%@ivzUI(MlqIi!afSmHE0D&EWbnLP5%L@%RLILoZ-YfhUOH6)+@S^S{# z&V;y|SQY=TNY394$ga0 zvibvR)(WkiM=xp(0Sa-Mi}GPTvZrj;k3bb zY*`u|at$^>zwcJPFnv)qV$F9TYz@GKoos3c_}xS)RG>zaIdi!e0Fw3zX(5m{Z+<@+ z{+UtQernez*)ig?Cb@|Q`#DqSg13kC?y)ArnjPpUJZ$#qHeN@(jqyVR!>r4uv%MC( z2QVqd#p^I_x(D;oF5xA-Ahw={P&jR7$-}b4x9AHktvp?oC>ZgJOIaUfM2SZf2_vI> zTqd-hh;g4vvRc!iF*0G#KU@QzHc!fF;=c(`iarqg19HsEW^~3-9L!|)e+p!~_}8~S zLOIIbN>g;L}7fn znA2TWYS<3F2xjOwf7`Q$5jCSIwdj$FOXL-jt!OH#&P?if#O+Cj91{QhuH{db1(OZx zl<%VM3#`ry`EKE5HZm-6ElEy;Y)Kiap127OAZPzw+z+|2d0*)#(*iR(Gh>va%uE49 z3Tx1C1+0zJ1d$4i{!g<3a%k1IDLj_uXCuSo%eTK(5l3*TiA=HIHE?B5O$n8DatRm| zMS-P8>7H8a&iJ@=R*r^Fir05e6sA$p6M86bKz zzwU!^Z|+M+2*I!?CZO`94P9pfU=%Xt-&U+SlhdTCEHgZM2o~d2k0(*;52*OVH7RtT z9p42HXE7@MLy!#=vQ567#bW7{kO#4-OB@cX zQRZ+V!=B9ZsW`J8CcLh(=^Eq_r)QnHVsN#_&Il*0AJ?S+6DOM&<%UvHG7OK}!lq^vbFn6IikWZ5rwE<&Ocm=rqH!pq8B#UxgiJU-%B)ZBqROHk*&2dYw=n z@rTKC?ICBksV*y56MY>M-(T1DhqYRfAr0PP8ogr_g~(7v3cVNSk^aNOW*?DRK!HfU z3uKrmh>H}2NAwjCs z?Vhzd+k}P9m-coh_XnLmQcHBZt)kNAO6D@gj$_0o7VK5c$ILH@c9O8#V_&PJ58WvH zxBD6@UP|a_njO?i45TP z!$KIsv$#~OKE$T?O{?;sP#5`#IBtF^#hl-fI>RMO<)6UWwziffq#TEtCBVBMd%$_p ztomDohL$Jz8MyA^`;#*TfmM9qEJR+K ztlI1L_AN#~hYI@%ISC!c{RWPj01m<|6~#xT1m~aLwqjh>eW|{$sJGEdY}k992(ky< zBo>x|bWHBfWN&v6-V2YbfODZT`(LjS0Fx?TZN}B@NR!Sb0!420NUiH zuBaaGez5C2ATa*{JU%AC_b?^X>Gk7sXK2)#)zH`{*;&+&4^vAGe;2Jm0l3f<=W@p0 zwOz%t0gB7!Bla=ymW?v0AE}Q>8{y98qF;zx|KmE*<;(B{U?8|CsqaObLAUU$Ip3}I z)0wCEUghBLx><&BjaRq~?-SyAjcy@;?46Dzg_C%`=E+{k3#T zIIjLcRVRZ-bL^I8H*|_{7tmw% ztjok8)XLRhpUwkMX;*CSK&NAgqB=%t=KC6QFM?t?%0 zY0QP2<#|T(-19)Z1p6Ew7$scocBm%+3z1B0%4wubn*R~)GZnOAa0?~(%q@irm&|NV zd+Vl51-g>s-Wo4V&Eef~N2zMmlG^FKm@?nPW9$U}Y57EkKEeFvP}m(nK#&rdGqui#PehZ~D1Z|Qd?{0myUd+mLkx&C1c}Unjg*NT< zt*+caf&2c<4wt&Yv8%S)a6PD>M;#x%!A22Xm3w6&WX(CIxeLGTlwk7FN3di(L&fSH zJZ(Nz$>|VE%cR@++I%OpW9!*uVXj^ZZ5j7qGs&944ka4fMNx0ydFjOwnXg(jYy8x^ z>5va=wAel-M31PVxRW^3!VN(gy8+{%$x5yIYv;(?s_Ynj6I3_}IBxP?U3^;SmbX+}mkh1Mt zlE-^bkEI12<;b=f!tv|zg^CA0=xpuRwKMH`jFX)RlAPup_ z)uAl=OFRpnNKrq%&HRzdp<7x9y(Vt}MU_W3qbM>>Bh0Zmm@2fz=fA0AL7_e;arpH; z|0#6i4pN0`gVUd%wO>@g`o>DCuVMy6KhTbbdY^ z+T3ZuqRxd-0)p^m^VN*jJuY@h{+1EWZs4pm6}voFm>Tie&BkyJcop81cCq{;YC~ZZ ztS4*2-SqxEWSTNUX=2|rc#Qk6D9$%4Wm3oDcs^^@{jb>Wv84KKZ-32gj?Gvoc5inEVJH!4p#QQnugJmyD*Ln78xw>%Tp{g_84 zP8U|eW!C{te5O8Ixi}AuFPWz)nibeLU#9BEC-qs__eehx3B!k?NiFx1&W%?JcZd*# zTa}m{)hJ}m2mhR{_`(>xPalM)eEipF+=9V1Z3n4b2xD>tx}Km*{%AutVm>KKlFQJI zC7RP~Rjv~PGC?KBz%#=4f8m$6-F!)fH_D4)_Bl{xgBmM}lkTa

    U^W#Zpd2#{9?M=bxNy3E@NKy8=kxc&tg z@0v1Sqq)mu{Pj35ir#9(F{4 zF~>u!^0uAxx43>fxbf}wIgbIs>X%4Xbz`| z>5K|8J7I0uyH9%jWc?7Dpe`6Q(Gxo9J()CT&xS!wDXggyl!omnzpMC2wKfQ(!!FwUH5)7W3U_i;8#&Lz)CqnZyZ(p^&x! z4c-z=tE+owPyJ|;FM%yAp_G?-;|v3r$M%d*)TqJiZSb{K(%?&7^4y-D^0 zhuO6_QS`Q(fs%7mQhZ(dZF*mYpUYS&df<(ppYUnbo!rzF0*EyNql0hpN^h=>|6@>$ zJYEk-jNBc6@L&EJqUotC1K<$+L+4+bBg5MB7@z>Pw6`#~RE?Pt(mDT8(TfWD9&^cp zSNf^!3(`HpQX2)0n*iE=nk)X2mxJ(|+FTZ&pT>MSD31p<&I6Mc`sIYo{|gRP^c!#e zi!OnUbKXr7bUrK6Bhi)Nh-rb2KL^|2o3>h3 z+qV|-5ip~UPk7j9D>DHts8dC$p67~C8(oz0gIgUYuuoeQQbK{T&kL1Bg`f|9cL^io zs6RUAAVKYXNf87tg0sg=+IhekcKkt|=wIvsuHODOF;qIbS#vUlPb?yn)l#TLnzd^o zQVo=223qx=a43Ul3A88y2(tFKQBn$)Z>w^#``CX*)pEop2~7_+(O)-+M{S39a(Lc5 znvw;byFV>d?j1VF6A#h1H{*F)4n8*F8`hGGb_P{B|N7w}(^D%v7P=$W?K%+Z^6Fv# z2HQv2qR|H86~9`b0iH)ZxWB|XD+-H;2H)* z-*wG&-c9$jO~xAKVi_B!N(58Ou->Zs!SlU%I?t+#gvmSKnIRz-u=Rwd)9ag}>C*$D zPA)C|Zxo@ZKbqrX?DOgbT|aY^*8^WaD~Z#W(~;$%%0C(DJsC_lP`>n~#4o}>uuk=7 z{qscFC|qJXqo^tyXDgjCV66kNUpcmo#QG>H;Jb}aC>~10o(+k;&FN5k*gtbKj^B@g zHZ1=_cD6dR+h|GY6;B@o+)N#goCtM;?Q_&Y|Q-LEw}r z$_Pz2#o;yseI_wim%5I|tdHft&I1CL%6frP%6MYI^)IKrLvE zZ{2%QwSA0@tbR>zNKWGG)oWJ)?^7nEsi*p51jUOvLd%}lZX>B z$stWbXO8U2pmfWa$d2eYaMJ%rMVfooG#BnYNW0%#;{30i9v~ywA}wA3Nw!Z{ZpIsW z$GVuCAcN&O2Nbmjr^YyfMDGKqChqo8M$f&;**C*qRv)9I@AB<^!rE8k_i2l&KK`5Y zKKJoHSI?3Hf$dqrv?W%PRqEI?46R^MPP|JKXPUz ze_pqNEH}oYe#!9+csxIO`=65KQvDQg4Yr*DDEYbpoHbeao1($iA#G6VaGfX7m2GY>p2YC6K2dQT>WbM+jiFOwV+?xj~GyTsOhh7BRRvNcCr0-P}*zl@;(*>}m|u z_yUZNJ?wvFDKM%aB3)R+f%{`Kgm@O+T;gO>ELuL@^$i$mvMlBALljNXc!94FHqhnc z^w|HAdR>p~A@q42dIIb~^a6jDV~ea)hBOmhml8~=-HMJ8C3OhI7Ld$FRb$T4hQp^k9cayI1z8Q zGVz;DjevKrlhT*3%kseGQ%pqWJQMPPO-5m=Pi|l)GmhhQe3|D<{16Nl%rY4m--}OV zNxUKoQC&@kHTaKrzr&KV2mvh#?+}X?3_9Keq{ry8jB#M-mg7a3lkCexvZ|b<3N*UN zKCtW+;J8ihgfm=0-GMD|E!I27`^Pr&;onRRW~U!#@KQs7)#sW`Mo+3Y#DRW6Iq4-Z zqq7U6c)5I!;yW|PFj6g)$JY{k=y_AGon{a-ixH#iS zcntJvj$hMrV&c-eB@P1SFlg62fUTI}%<#061t=Ai7s%O;^ zABAAk@(POa8QhkL_bNL)BF_f$rkl=^Lqy5~B!A}TU18I_=611gF;xI-{4?sZK;Grb z4;grNk-TXwsDqN>I}IM1G~xU2Ly{-ks@dAkx1bIQ{s(&-L+{&Dqs}&F7JAbpyoAHg z@fP6B6ufGR-3%_1ZvB<}$-(grscrD`of*5Kt_ReLC0ynQ-*xv4t_LWz0&lXld+80A zrNHpqykgLcl=wik!Vm9%r3udJrM%mq8My>VMv2rHN0e79YX`nnIdQXuIu=j9FifBb z&K3)v?OklR4Q-#bcm`R&xH5hPafmzI&IFFOid}26@yBIO*NDDf{UA_hqkKPY_Bz`$ z3*qlDcj#kao!fg7l;_HbdgOrpM-CVTvG54AAS%wdXbIxtQvRI;x^e?c#S^htQoHk2xSyewK=Iyo}{D%>#SKb2M znLr{!iZQRZHAX!N*LR~hxBuSiVZ7AyH3+o+o~}}~#m{u5^*%@WeNPSY{yN57z$|=(wP3KlBig<#F<5L{fV(r1~oTSriOp-MJY;=uTjlwYo+tq*?&;{+1 z@+R(GdXW2W%$PtpZ$~aTD(Q=xr}5segRiNlid*YgKAvHlrA*N|*WA5@D^-nivT-A| z0u5_P<^rvx%X%U3gv`axSIubFQ;T0;lp4(%rrV4T6UH}ua-X|LggkG}2#N33 zciaQ4RdW7}O=j`SGY|H8@e}L+s<>epvsN~27Wj(arap#`Bcv!fA#l6%5BQXS$QNFf z{-gTC>w%7k);E6+{otMDm$w{`$`S zQS{|V2VJk)x32>xl~0~1!FvW+w~;5`*7XVw6H_vxJ)@YV-+V^hYyHKJ@^UjmY27h< zd^cmC_-d%?@E1Jzb%5lXm#o?oRag1T-(D-w<{`!Zdqq?PSUKbq23 zG=TC7S7t_3Zr#yQNn_)*OK_Y_ z#m1|XS7-P5jlTXV9^UZ%dnNKO!q)IfR4VJ=h0&LKqpy8-H`;nF6?>i48gQ+EpSM31 z*Q6ROPT?AX89*nYY|&52&))qy|1jdB;IPKE>%v$0{|oB-T^aOtNP@qkW<_PvY;#$knTD4%$8w1X>M!8>q=gUsTRd<6I;mPuu+!XPIq+Q37J(bsn(lx3`8E#5Nz|J%LW9{ketp-S4jmh%m@CyvMJOxr~w*VW^;-dejGm%gzyHac%;lKqLj>z$=x z$M?Gd;__E*o~trfXMzw7xLEbKXg%i247y5nQRBu$<%xGu)ZFyMZ~h) zs2X@8d;JBr2SGQDxZq76RE;&AO(M#5v`V$zv{z~)$TrfHLOKnWG#trTF&L`HNzJs<|);m7< ztzFGgzc-`0?I%=6f=OZ?gKoC^z}LGo%Q8gOFOja6kbfIXEJa(G+;_bAL8c5#30J>$ zdcq{;tCshFK#4*DB ze{$~

      )OGnjMH8~L$O0#$n|9Vz#}a%Ifft%?>v4PL%^{l373oHEdn8zkYkC-O=7 z+(*Z^$%c$yIBdP>`=bB6Sit-Go!L*PU}UbsQw=eI_(G#b>q5fi%Qp<}I6chl$>A6N zhjo-ly5V)E;`gGkJ7VOkuI45$PT4j4}XipRQz#C)SC&xO+tp3cfHA8r1S4^JQ?d@n>`ig<&%^deq zniiMbhL>XSaeI25d9eVaAT{U~k4I>okIC z$?dGBV1DUH$S13mT9BQUvQd@}QJiN+$lW!(uJ1W4wrFr}knfYjl+Ei-qLO=V0U}J} zsq0BZ1T^&kU+XHh)|1NVkel=X}c@n;>ck_lARj@vA^3bSA zUHHpe;bzbp~BOGNr(Z44b*W5vFMz7p&<@0nTooncO&v!4#^tt3?7qaJB zOqM_hkm*<7 z#k<PaLk`O|q%AuK;gC;1 z{%6cLhliePeI+_lv>aTz!re{^+EAe|m)SZP@x)^{6AOyE{g8a}>hW|yP`zd>M<>4& zm>o`{o7=dRo=d8^s`%{Tf$e5>^9I>xkPdc2B$_=Z`dXN8&f=MR^u-@=SuD%=5y^s2w39x|uJ z7Aa@@K5@W>*(03Ut;&*i*-<^=`^sE2@hTsm$Fet|gi>1rJsvOopEXEdQY^i@UVL+gK^>>{9g}`WWbl<;-tCa6%EeoDQ=8}e{WWD zdq!T}lA+#3h1{r_;wY`;_eWUZ;^gObYO;yzJ8|#tlqL$nm`h)puR8Hr)kP{JNBJiQ zFh}{{3f_2TaT~?xlD`l}kB;3&+izzk&(<`d8SjZ~rT#7xxc@?=x}xP- zY8ea!F0xr#RSFJ0e3+sC{T!e3R6{fC=rb>|g{=;T_F92&i;g9~4~}ZAu;sq3?+af; zjImmBgWj5#iiHm!SUKQsH`ijTD}Fu(98f5DWo3V3n2EHhzXLEpT7DqvLewKuSIIQb zdJ9R!GjQ%k6pC3dnkP-Xy#ix0Z(-bxhaq(h9Ft5XT$zoBPR1S=3fRl*ND18c9)Ek& zlQ~i1ynLpo+I6YR`}btBZMrrb(16E}1&E9A_&!m&Iw^7;RQpts_F0CIsQ2v;r=jel zu_)_lPm46?3ckDI(&w&RW4!UMFa%V!GLz8${Y7Ety<*k+Tigk4ZUbhkSL=;tTQGW~ zUp-9!_Ts1$nEHm2?A_8Y?-O~sV|f;$d4ytl=A(H8t@A%x8`m4e@+9)eYVZlp87BzC zE|)(YC0SgPNEreIJni=~9&|6A*f^2HW~9jCMvZK=6@`?h?u_)dk4DAtGPPcWj#8NF zkWc41GGUh`W-~uvMkjYK@V2m=yMyP`#`8V&88`a6lF@k~vEARn#>Z2QXwcifD*Ofe zjzD^#tqDlJ;Mdb`Aui@+{Pb6tdsn*y@4f+afp5@4`_|h?gd<0=Xd z&&Nk~n6>(KZv1?&rPtqn_@CX)`TG{FV7Dq=*x9bN6CKJ!mP{CfEbT+U@XxN>?Sy;M;wpGQ=W{5#p=zr4NP^TUQ$c~zu^ zIqm^3JU#d3o*x2ZZnj9cZ;1SHiA``|K(jQ?QW*KFUNlWfl2a+)V|2)A^hIjMEOrm6 zOtWDK>nm*H(0eBtbK^@2>)n~m`qwaFe8#6HpX>NB8?#Y+ckH@Qh{L_v8SgWtzzY|d zb`POS6ST#LwBT$%fAmDco71`w?%3sTbM#fILX{Q<`I=Ui@hkEk_hSx99t@yfUb-KF zzAJsBTU8dp#Fjsn#LusqXmh##eQyMm@eW3(7wb3OaF8l?IR^!tKyEh~`4735T+ht= z^lS1@p7%@7$YoaUtXI1I!Pg<*@4GxsXiVxBMvQbx+gD-Fr>`cgrsm$!I^5(j|g+$__bQXz*giL^J6`5ffaeD49|+ozm% zR$wIqc;=%h}K9_P8jtPcC#eeO-x?hC% zaqM<*28Svajpd`7#|i|&t%9RZ<#bE`2T4G-zYw;mQa!wsw#m^0iYr3185DS;9~=gt zI*C|R7Zs(7xV@kjb67>HmM_JuM)MK{#>8Kr80fBU9C0lRbN$h+mQ^jQe$<$$tu5Fp zTiULq4{Fc%x2$TZt@uJ=0psqk#iZD2v{6j;H8a>?PK#+YH6q}tnG9&O{mL|%^eaVy z1C3(#2b=M)(P(TP!0>A(vpIv%gNss8jYeZn7@SIKCd1)Df%=Ss0GN;!W7I9nvM9{b zxwC4PRV#PdQmI%d#t5?&Q^|fy4k${KL=bpTGZ|`PJB`;hn8tombdZX~TP_1MUt@iE zLZ?#}h-73W#j|-(R8@!6>BN_1RnD!J{Q*QW(m{c-!BAlZ&}cx7{h;uoN1lBqNmi@a zRV|OCTJuwDuWOywT2U>`28QmpRP(!IpLcFV+gn8d34p(m4rY zC5=X7zpk-1u95Gwbuvdbe%(n?hb5>vV~131CV_MN8jZ%@t?M%OVVF6sO7-edd?Y31 zXx=$Ux!GXkv=+;c6f1P3v?<5qALXb?KkCw6Z%@$xy16h@lRU*OD&|>-K>YYKnH1fC zfZTDH^u1e&M$MxCE~bCu_Bd2tikB+_n;uXmm)bQ|qcOSEYI5OlB%pOk%1qO^1&t|K)T`K3YUPkKR7B$7L@6&KjYCBEs$Eh3%YpbQUnnE5bEF_;@ zGLiuPQ*DNV5rVx)ZcZwW-L`GB+qPA2V^Z6BEo(Aye&D!Nz#6G#^1HLyhy+K%^04io zY%fSW8wgxzoRGCD+}~aOwfoS&T-FAPqr$fS++qq@tKt%3L1A7hRAA6<8?|Aao=~dl zK~Z(BrZX{vcdYXAGNjPy1vKAVG1hbp;EJs z>TPh-{mseBbIq8X`@sPY3b?jn6wB_0FV`_fEZFNZgBus-9+GI+FK=DpwjVR45&I+P z|8ISsfT6ieIVvaCEcvT_w6i#l`2KU2P2sM02q3H^wVs-nAFj{H9*m@ z!BI(ZA~&x|qm{JsgVlhVjZklrb27>u>R^DmSIMEiR51*O-+A_JAF1v|c#4eU+dRPgl zt4Vy9Mjg^01+_R-f2bUji;DGZHMv~X?fB-q)^a2gohFIzZEMNC)BgM;_j(kPyk>O^ zz-_?F^5AuqRh^i%0MM%5b^S&Af?4~KxVM|9;|W30U~Di_K5%kUf-zoUX{;62X7%xF z-oH=&>_4%Jg>ZH*F#V+c%NEf%FP9K>1gQ+S54V{UYNjsCB56R$IAL zL<0Z-D5Dc#02mY)3`Zm)p;Qy(0~7!?ARrVwAsiT_?UOQT8|C=CM5CHQ#m;c1gzTC2aj_Q_zS>6MBE8JOZ9l&sz5W5;!T z55yOzTrO6aszY4hI7!R1@d3OB9tL~Mx}*SCP6(8*N7y(#>SL|E9LAtHGLTK+_0z(! zl*~=?ZU>2_F}t^%RU`4i{mbwfiiZr~kwt)exO%I&3rYR65&*>gEy zM3;1%hzBwitdIMD2>MM4(FY*j0kD5Ed1f+IG3W5K*T#3s{mU%$?fV1E_1dSpgrgch zc=)Qp@zwi%tdt|-Z0%KWM=#=8YsBHxr}8I0nbS};tI|yVpF7!!_-5?+gV*($y$%7? zocD7(8YHz2j~WB@e_f*9#~9p&8oe(Xv-{Nv%pf;jBA{4Wn_T zSerIms!hF`%6Is?p;hlw`_B*_g4jHfn{&kV<{SLH*ryA2U@yrWTv92ULlNM>+SijE z$MC3jhFY0Sv=}4BsNp^Xzr8Nj=FuqpHEuvn zyM=$S*hq#gmgbL}p-q_`TF-UxMPlbqb%l=|OBk*nv96j)4@1!>FUod;FoAP3zUXJ+ zlWw3+mGYqFG*w>z`=_X4v0^j_ofNU!p3t7O1wu{1QDWY(xu21Kk z&Rlqx9eeB&?7!Eo8%R+31f}8k&LMsv8oi&JWgun$m!%`W(4uTeL{tb4TZ<7XlDw>SUip z&N-!Z>k;m!NVBt4&gu7zN6Xni#E1H);w>>_#h_!+)zI=g>d;PL-WgElk1q@~Y(MU9 z-_tlj945b0Sdoip<>s-w64VH>&3AU=LCSqz!|?lc3hYNpsf#pq=2FA&7imnbJmkd< zu58c1dk#x=Vlk@2{XA%3f02>P6tp`_tpC)tz@*@e0$@}N1d+3R4C2d(B$j@3*ZjHL zco=5?=NdlxER3b(r6)z+onZAt`4FYGd2bNz^r z@@CV|fPITly2b1KZZ$dBPJ=)U4yxaO$@TC(;XB(2WIOA=!Bfrj>O~(=E+5$8*JASk zGMT7?`Umg+5q!SehW)-OC{aya2e z#?A?AjAr;}@@G~TUwp?8n(C_t36^_{Da4DcchzrOjCB9C7k8q$Iei!(D|eNuScnpJ zNyV?%t)?_&nB?uX#A^(&1>0SEv4eT{U7#qei@i(zP2?*msyv4K-3x4n{v9+fx&wf# zTFX_Fu>C9XQ=1}a@9l;cHb@Q(aCse*H(I`rfZ>YaIp6LiqO$=S&$nQ~9J4)_nI7}| zN_PS?zl7Tu_rK{);?iFTC+Z^6;5YZf#l@Q+!#evhckxB8VQ+q42%3Gg2#g}sFSXk_ z>?zPtFO#3(#WtDa)14&D(`$l3``^JME7nU?%_Um~{4?asJVY>Mq*biY_@#0sGH3ETgpt39Pr{y6PfzW(nxA+x;MG04 zhUV(4%}n#e>kPh#h0FS_?O8iQPiGREHvt`^AlKwxC7(-S0FLvX=|9iO))pSiHI~}1 z`>MjZ@3lKc3x+}LdYew-YF;e2;?>j!V)kDBw7c97jX`JAah6J+cE2a~01a*Ny3gIu zD`)Fb@4MsfN&XxTgG=FWolLoxN zpWC-ER|o z&jVhKJ7eL)SvC6aGcfU#p0<0?oVpYTDgctl+-gFG}_29BawSqzYx0#gxP3S=#oL zt78&2DeKGVZEdB4-z)at?%n7l?u&%d%>&ix%Wi5}Mb`KUJs;j8Ya$0#^RwvK-JN^G zoumEgOWuv8u2=&<)Rd z81}$>?21L{BJLP>@4~y(PS4F=QG%}z;2q9ePeb@Um|SqI8|{sEqzS~$O;kOs+C|Gu z%SpQ*S#yi^$-8@%m^V!;19NSkWk>A@xjWbF@VsLsM-w}{{i}D(!bP<5-9WM{dN;mv}k6bgc;NEE(?Ue zA`jZHA~uCCHmP;x{Vwi_aD|@arU7W5+?7U(jh@0~vB8>UHP@5(%PjxWpt_o8uslJG zFAJ;t_0MTSad7ZE=OFtVEKlv*sa@izDw&HYjvTRj&Dpu@D2Z)qOO-{rw_ zFu%T$SDmo;l=j?{jiiB#Fgm;uHUblw%hHhPL!G%}cU&tk_ed{e(0mvyw>IARRU<;A z>SDvi#vNzlHlH zt(_*bp4RdcdHqGH<5b6FaIe9TIU;0c^L&Xk{g2U6Vvvh@E`eb+}t7;O)bF@9d$} zTg$Caqqc@FxmB{WL75~ocvgkZmU^sdqkzPSHJJ5)yWC&z2qIkni-Y&j0>_4E>70eO zj~CiLAtQV!9J}4lt&B`On+#h80`^W7ArJj{T!o&%1CeHCY>!pdpx6uh_vQLntEcU$ zP9Z-%N}h;3o_V~Frvy;+C+wx@DOcEXw>@?hgnuHGoILhbTb7kJjJF>*#26>-d%Jhq zc-78ns$Kkf2z&cvsygn6W1N4IdFo=kLj5FNVcn9fY)b8XWL?ZbfnphS4PN$oyPmI; zKg(GP#(X>c4|2Ws;i-C-|F_G8f0tro!5w@-;fY`e)7O*=Ho2O10~9e-FTy%7Q-fCP zD;d5F{(UI)^hVsZ;Vt%NKo1MC7^k>naK(N6@AgMO50P9japR6W=;@mXVLkqpLe_`e z6)tC<+_aP7*CWxJVrc{gOGMGOleP!l z#f?kBKc;nbLJDRgNdWG;H=>?LFy7vnMS6}2Zjd&Zuz`J4U1Q6(q zx%bIpU0aXt6u7BE-`-H+@T+)?L_h?eXyY?Yci>NVv_+8b0a?TDSYsp5{R24EU(3yg zVkZJ5SD=JZq>dTDJ8IU}V*-|D=HKc|?7FKb&fi|UN1picw@;^=O*A_5(A;r`FcS}O zjJLe(-hPVv+04BcrwNoNKNivnBX@Z&z{de8hirOJy{DfyZx8{c z^J+y|D(RS}p|DzH!<5bZxl8YdZBozpYMs59Uw)tUM|OUEzvYWUoxTcMKbagZ|I+!{ z`;+%j^9})?{tz0!%@IHLj(!ANFRaXEa!d|Qp>wI^8RM-1@&vJ{nNPltU-7#V;2iT$HIK9 z1PMfmF}Alq+MHqEq0=wk@1!dcroTuCqTf=m;a5+*Uyx7st3^La2nx~3d(%h6h5eQs zGw0ulpTVNLNqls*CiyJf z)EZ>Qox99Fy#TwLRbk@OBH@aTM#QrtZIWWmFQw}5OBWp$ftEn|f^G`D+F-KWlHCU3 zY-k&EPk2!&qOZM9V{#&RzPnDb9eV*t(+rk!b{=mL`+5C2f_C2{^UHb`3Vmf;hCvfc3-l& zH_ENIXHmf$Lq5yT#}b0x*XZIA-mTV_S_-=!}Cr-GHTlXO4gNeC@ivK^xWMixR$-@G8Ng4 zxr={bg~CXlcZR7QBC<%FsAb$?cx~$ks$1@&8&iDFERjbzZlc>K_wEHtMuUdjWCiIn z``k^kBj;2-!xl!pxu2F2*z}zPF?{@!I{0e5=>4Qk_XaC$dVjo&hRytzBrDTAXghe1 z(a5#MmCsDXRV_c(n)~fN;U8?*){9!8w-=ee_JN#y)7L!d#dB zxpnS%tTA9LlI(nUL3q$1cWxJ9mH_X=2g9ZDVkfKi59Kv?yFH*_F%a5!+&FX=xi|AI zZ|-;K-EQIj0+;g$)vQVQjEZm&P1**lS@7!~RE)2>M> z7+<-p;Dhr_ggk2AtP@Eng=7=JUTlLvqbYWse!%Y4#*usWJi!=_ zk8+5um2M!E3n5>pALxkOC)X$LZw&GS?H5kp?F-*hY+PW(weEoVSJ6wm{NUc4ZOh^Y zVI>D%O}ZBQj9%(LLFub|VKVuRTyGCZ=I8rignUc?^-jpI@#`zW0+O>?4i?)v%=)1w z@wfdt5mQgWCxeFQl03jD#zy+;OKS6%&eEiY`-o%k(voe6c3(zwKw23WCVyrGWU`%e z9geNi-Nb25p$;Oy*>Qx<`La36x8`%++pl$Cmfs2YbCdZ_7_q8ASKL8=hvBYm!zXtesQ~e= zkGYX|9okR83Y%Q7x(Ryrsp4+>fk`7Aw&%RMsHa^#ZtsmnDdT|WO2KPxAxy;|dbI}tAwuI+(cKEMMj;*~@f#vG$cN2!|F_w(3td-Ltu2Q&~q zAI#v>gC%emLT$jWYcUmNGo!)P>)o5Ck50flNfPVG5@V1S60n=OtE0Uw3H@P6UA&Y0 zxy|pa9eoZ-W}}^cYrmS?k%%l7(bS1{_5M7QQR%&uy<%Fgkr)PWh1BCrEbga$YzOuk zOwgiEifrY|(%wxvI5;o=<}ht^>Y}_1D5Euy2U7a&W*c+!S!<_!AmkXvEfgwpl(bry z8aT=XCc4t~fbp$%bT5!0mf6fhi?$x#O~qC_;-x%R<5S=8U-z7s7N#@2^44rWUZI{j z_c2v)pZMzfHqPp)Fz*AkF$54yvtb1rZLGz_U%7Z|e@{nV?Em4xEqfa7D6RBrk(tmL zf!HmTkQ(N)O1aTBBVD9_{%SAX!!GuGIl6@ZXH_3>VkX}DqC<)MWdb<^^+1ncw4-12 z_+RM!Eb)`FiwIqCf*>(nQ7y z5l@Hh{m1Yzs1Rkw^X-UPx^=%-Kc!aCf{i^$Rtm z?Ff}Q;;uEPINktW+_h~utIL}S{VaXz8+X`=-f{2bf?nL89D2sx86CABcZzLzv+Gj{ zYTOC;Czrl(&*W$i+%cJ$aBp#r4{tbRPoO&nvQ#*6qNf z_Dr17%kJv6;$ZviRv3NOwyvzoue&9$%VRf-$ZL{ccQdWT-{m9#%Cx)CRX6uNIsoSc zQQh=d9Fl(89edx)S>KO>0a_dxUpgH_>R10dwDWi6%kExZy*zUELK=Id%xCvV@%e-g z{A(5TwmU|q{NB{2>}bp{WxZ!97kba`&F;}}Arm_hsp!SqqX;l=n8X!eaeye{tGfzr zpxU121!VB+%C&B^3UYp>JI4=DG~-eq?)0lWqWKo=W(R=Qe0QfYJlhE6LI*D?)8YPh zpS82J#?c0ZqYH=oS9|58eW zJ>TwVk2S2ygndy4|J(iIqR3Lwg!dNh#qi-Ht-oB{Z4+ir+%eCt zb#OPXc51L&>P<%0XUT8m=a_A5;-ZU=a0q}&ko4fJAGSa#%0QA&NMiX&Ssj1%kLoYG zHr+`x`bZ^2I~M%iq>!Ys!2pxbE;&ViNXvrPZ2RW^A;d>_jB`|#xAj@czmnu*l*Sk= zoDp`tar`+4$d)xGwDI6sfMs>p)hXxo_HC4sMn(>-hb#;D0 z*m3_G%Ut?Yu+hSQ4Ep153vIGcdcXMst1Q-Ws9DpO0Jh(dk_NrFS2q!m!6|n(KNC`r zH+KbY&wPW{8%6>p>R;V3<-Wi_6A^)em?;X#jqt{`JL9D&F>!LpW|I zimPM^zWuvA;wHR%<{}+L_k%x=2RUYh(^+yq!IWgp{ee7#r~aix0^FE$kAve4=;Gh0 za(+z8dpvCw?lof;eI#4Y(QZGkFZbqt$o^7*#a_0|u(qoLH3W+5Yx;8MZHs3u?ZYrK zc=e|*2X}PPK>%~n{rb#zvyID?f=y)4ic3}5hhYNw_?UCaD#89%R>SJF&ylJJBcZOI@9V9S+08gICZ z9CuJlfi~TZ{>Yq!@%E^zIm8I-kqRVp@3H(tMr)LI>hYc0J(xwv=)3p3$*k7|>O|$< z7BOA}Y8=>n52OEi9pspd^k_R`5j;YR1xL(zW&}gTR zbp0V|*#WvXh;5cPDF(&Scc>Pgo%bg9y6YbgL0GODxbDxqo;)OAIx8Hv)}n5$U>U6f z|9UUCzyC=p`}cl6Th46^j{1an=4M?h>peYT@1t$xyQf|amojJJaKevHOi>-bYag0_ zec<<79sDeTDbvZg`1Nc0`-&rXGMugt4!35`NKkMwqqww$^8{TQCwSyDmR+ia?4kH3 zsXBjmbARYs1CBl7MFh(IzPqu-{nqsR>7c1eCcl~$S*b=3Bfls`-~0tvG<4tZ(1qN@ z$qDm&AbM8#cK+_ssmO*>I7NT6{H?!VZV+1Z8pIFq5xWNA3u}id~Y`~*+ZmG?SJfv3gzqCfi={s;r>356! ziD{Bq5_TuO)_Fc$lX4l#GvBwfD~p%lEx#Mu{kT&yxM*ki7-$3%`D3o>1FX!3@BygZ zT$LW+gC2l!qYc+Q!23?{>JmsZ?B^u8b?~*roVo55N?Z2e0?d4s$O#R)4$E!8-}cH` zyw4Eo1Kz$770wVmYThH`D6&vb>=_mE%!4qhXyKsKzRfXvm`m^|k#?HiE!64S!LLsI zqa+DA*=S8WM*Dny{BJY|I}y zeY55q=UxTbtHuo2mf}6%aRbr|?N_iT@cJV{;l=MFF-_s5!*OsjqcV8kOW^7_Nx{_Oqm z8cOJdZm{F0&<=*xPW@IV0Q>^Vnt=2Pjb9NxxUuc#{or4n_Nn*j$WP{AHxpY}?Pwq$ zZ||r4x@n?K!)xzdFyP>iCY0(oze-~c>iPsQ`M;OwyfPg(cX=47KNKO0?>IjaWZHec zBYj9YO??Hdkq!PoQ@>I;elPY+fnJsT`F^kN7m<(G6v10C?jLKG9Dffunkh@^4^KDq zo}^wTZRm-G9~QO)R>9edE|7C?U*f*ct?JzO5_xH`%uH~ID zPvkh%IDgr~fH{mL$LwESzhSpRVB)KZxPYI=ehAd`KQepZK_WfsYp3`C*e=v<4xT`Bd=XGUx#o0 zP9HodguV2U2W#+A*}pYirezCVlAnZ!RWL;b+%~;DbkS;-9KawYJfP3h1TVMlEj;Nx ze6<%1Q)UDU>fwhK27hq>l`D_oU_4D%n^$6bOKg~J?jHWw9f5XHl){?0~(oa_&z}W%XTO;?e)3Bt9EVQ?obP*!3UH9uFA0 zNu84->4k*kf8DRC`>n)hH?8bOIu2CX$ndf5V6R;g@NYG9kIB z(-caY;G59}pC(HE0ARqIz`736%aij5;MW_pcSJ6~*_h1Qs<8BrzmEJQ{&?C6|CIPD zY*h=6ufU^(^YF~nssN~rY`r7!HwT-g(Rbnz;waJo;pxrhAH}0{TzlZB1msS9ZMtA{ zki8sgrKXpADgOD2W|}?fPn(IS^ihiJnzxsH{bTXWl<_h$yNgHSfULSv&ACi) z*FBE54)c1tvFUZ+i@*7&l6Ej&{q5{nrj8ih_b;(ivR_m2)Tzy`tYV;jf^dk%k*kI# zgbaY{ffaS{tA^s`e;nl=HU3q+M1uOWdJh0}cb|uszn!FHn7V~TyC;>e8I^By26%%6 z&$It1{_>xVoNMui$HVv-ZbVGK!g%IA=I_tO+w~zjU*}W@FNaKmXoz2~;;FLhia|?Q z!_EcF#j(xTIsn(lTE{#(CUeBIL#N?NLNsBqL+dY8tcI=Dib>qiwBscn_Tj^wrTB8i z-^s!bC!)&@U2rTA?gk=}z#CWme8!gVWM@0aayL7+r+DYDVE3-dJJ~pU^IN=;_l(}F zP&pWqUy}>johcbzT}lVRI}-qFY+$y5t{ZZ1t>zL}{$G6Q#qiHi?_CQu$;R|DD`}_M7(j80r0S=rk0U@j`z-SiC?p zD^vr(c%13x~sD9_B_TzoS`r1Hi?Xhu~vg>&tlWAB^+qW&{eb}y4cDY?#oLkK&L`y!Y=(giEe%kEe$ls39?_h&4X4 zR%K#w7~e2y*8@p7b-Jzt$mh7boebG8Ql=Z^1pVizw!`?whm&@OMfkHi-q(~emK1`M z0znn3CuWcDU`SvdsM3#jaWK2asANrMsGld)fjEU#^(L+=a}_{>X6Fzol zFM{I~5FEZiO`eGd_JZ>O{C7Rq^AC!>ecFw9)Y~NHAlm*_tTjUM)TDMK9A9taL@4tb zi0}S-d9EXZY>7x&o86uy6eQL5JyLZu;Z}{M@gR*zsg?u{h zF@QOFvd1f$mt&Yu0av+9UM#S}O!~^Gx`t9todH%Lgo?Ga(3FeXnJ%w-2 zZ{@V}hp{Z2yMwGflxTm{8Q)4g*}8WhfjhFMoU1xKFju!qhjjR@-TI z&}qm;$_{}%rgYBK`d#vP4=-wnqg{aPNq0rkKYYN`mZOh|9j)8hSgwP$aew8J>hK`T z5%Plp>G3Ao`5QYW8VpT)Q=i}z1w<0@$^3t0_>bXt`(e9Bet6!m%Mo{uwYl)7fx#(Y zLR2)F3!AiE#CwHr;)^#4@EfL2S-Eg4?l%-KoYgdc;ZO192|rr&Ig5u47Q=OOzJ(_6 z&2s(D;wjr`5B$zz;r}Des{t|a1~uI2DFt66Cgbm+%ptj0rcbo5w;^f`xy zhW$a*NhqKyoA-Wi6)N5rz4+})%!lZD zBBu6}%M4_;+2DkB;p76i}(wFb!q$zs6XzKCcyA#_dQN10I9Zp1| z+G1a z^ltp$%LqdV-2&vkncsJW_e)Nk2VH};WVVe68cNNb*Zg+!{qV3(z5c7ljK10^)df?h zWPQFvbG82zt#2tZkp$-bxPJVO9Os2UhEUjdbaNc(k~SOS>AS}@*#0l_0lTboE#qr+ zc=yH1fH;^9CBKKp|u;UCBT1c6tO?GZPE~zlGOFR~e<=K(gmUNA2iSqn$*<@xqwDhkhZJSl|pt0>cdC2hF(1vAeb--mUT@kfv$(fqtdESiLHiVUzmY)o7K! z?nll=*2FrZ*rW}kP4|u^!NQ8Z%e&Rbf@R(g?VY>tu5oVy+vw||X_tI1sDfpkrs0P= zuU_n(Hapd}=qb{xxqkLb?%@`9!krhlo~J!nZ&M%U;=|Hro+ozzlf)C3BjBV1uAZip zEvS7}woc2O0vtVuQ_o4>k%xL?bYN0@y?DL$o9e3YdOANcmEI}sg z`1Ffsca9hT;C_S`?$-gKEO52G@pE-*qwlu^^zwo0Qs*f@9F8u*N4sCR2E{2|JxuO+ z`@;1QBGP1`81HYL=qz8iADi|RePvVe?-3Ww8F{ei4QJcWxuM%YBilJZ;rf+rEA|iD zrDq0XPS7fTHQ}W&^AtOCPWbzO5_u$zuE=*Nk>#$^J>X|D>5WQ0)8!IEOXuh zv?(Nq6M2tEub-E8@I98*N_zdLhE6}MWIzbgxA9ZT{{M_)0nfNAfhn`!(XGO>SObZ=Fu0 z_TkxAWPAE?MvItdhKKi8r#9L{K%DwW-hojQ52VpSdpqS(UbRk*Sf$0GNH*y?S!eHj zjaZb2Cmk!21;SU<8cRifeX|qvouMb-_WOQI=QlWL@1I@mpJF}4zIB5pJ7Y$dsC%Uz z-Oz+N*RGG~kF=9!9ecjg(Y)87A|!K`|5XJ`;TYIn5rxTsquUn_VBR z?9oZ_^mhQFdkw>%koUG8IJGlrIB}c3hqXGMiXlq41>ZG0{zWe-mItn}qH>aQ=%D>| z(>VoilW<2QRXRn|N0BXvXM49(J7|CSw!{W0g*#F@*f2QRg7(5PNT!;2K@FQ}4%&}T zDK|8N0G~>c-kHTppT>KMaqsN7`?2sm_E~`K>dMq&h3{#X!jA8-k+)kpw;X1_m`^C9 zV{|=UaYo-~<~YD$6d!r;-kb$u9Aw;=1#|gW2Kk=198s$FuzfD=txbo{<0^HIeoKZ=G1z83Z;#+ zXYtrLuFkM+_Os6jOw%An(PE%pIqc zv^93Fv3I2EH+z}(I^?0ZHfy93wlTtO_NObuxh%^gDLr##c>EfHT^900yXN-~wOb%1 zh-fuejZ&md_t{a`mT7oWhv0~E0RbB)pHWr=AmUH8(EEP~dG!uMh>cBYPyGYE9%T4# zzNFjiZhub|yaL+B+%-EF1ie5zZdfVVyGB`?Fkh0eJYvtsyDlQ@3u#HjEqm}eA!})i z*;O=nhVER!4FwO3h>4>k9sIHm`Z5g$___>17;BatdDy=T%d`G|*&!~ejUPR^mf5M_ zhZ%=G%-$9nGk^gZZg_lW|Kk7l@bY%q{G_A$p#p8DhT6yO)BqdMb>l~aj_4B< z0TY+v_N85vrv<_;a>tn+5iEf}(ypIof)4#Ik;AqKlQp+}TA#VF(eD3zpufQJa?k&l zc522(=5GfJk>ae~&)>85?1wkcJlQ@hUb(!+Tp`3?KI@f6#Q zbI-wY_wZSFLJhefnnaX}PHsYg*6HBZXV}FYynvHbBxPv4JDd_W!>)6_CI`iFV!dON zFnkys%g8MF@V+KWbf(Q;mo-jqrmP?r>aic(4q=6NYKM7XpV!5>rio+_6QMf1QBA4k z9ehyN;NW_K^LXb8vpl?M^(1Nc>zY=EE#%3l(kdkxLqelVQ~l&vF4)&QsLJQYNmb8n zgbs5YX?DU~7vdtFU<^Tn1sY1S2;>EC;oX9Gh}2_f*$?oW?sK1QKr?&RLi~E!!~aE& zUP@RqkVp+5sR`JezKx0Gt$@_?4r*WRPx*mW*y)uQG8Hs391fck@_q~UC_e; z8sJwe?b6h_q#k3jh4A*5dN9-O!*f0_{;TW}^o#Lt>+AIYF82=D_q6YX^{@Yd%AW=H zi!(6oK%~4viy-!;(x%_iv`hSff(pN8y&u>i6+Ri%afBUyEm1^jIO!3)Mqh4Z*j~4^ z!;X7yk5)FgE^}oe;q4s#_nk7Z58~!Blb;vay*y|cgzth78b2r5tV`^`N8A+hE_=g> zbU*C4*HR504_yD)vHSJ@|1|8v1&`G|d0o$J4w{N%t@Sr{EqL9;Vk2|xudcBlXHWIN z&t-yp&l-cBeVMZxcIDVO|b`laegJV(7mGk z$k@V54tk!GCvYe082fgIZ|rHcbjOb6v^8=E+0o}<`H}sU5c`MBDLX|^dT6o;%&oFt zrgdw@1b)g(^B=&q!#j>Pr#<*i-r7MsI!`IH0KL;Y`2xY2sHTT3idVJuA*6PZPmz;U6 zd%}M;tE+ypgF^-ZHzmT0S4`dZfWgjbeK+gu0UsIZ`BIZODbLw4R(Gl*v%M2%0qf4K zoyL^tm3pnpemSUED=S<}M7k^#GYh(TXGdFy9HHbf5yQmB>eR5AtS&g(=8k(@7J3*C z3&_^rI%jrbeqH|wpBhFxB7A9wDhotmTJg{L)!~c%es|IzywDl+e>d3t2?6BiEK215 zUc;yD^)&nS8hmV6I~_NCvv*!kDID$#aOycb(!(j2**tp`R|44w#k`ZhIoQ3*vgiVx zz;**&wRa<#ibLVoQ>vcaOFPqC<@~93+MbUo{?^VrPIl~$$4Bz`LQj{Hk|?=xQl=<( zd3_>lYwgfz<}cDZD?Cm7DIiMy|CGLG1=Wv}5UNoyW7~3!3>veB!|sZ_L;Pkr7flYa z`!v^{HGz%ne=^3c4rfQz`E07ei(#}qzfw`OtjYA~8^L0;J?iTwKn|PNTD*UoGO&=v zgMqx`8h83i`Hf!QUs*y1Wx0psqjc1?ey`F3nmwC|fN#`Xt4Lmjm>yx9h_wmCylmg_ zN`uO^J$vw~7TbXzMephXzCqx_G6@eUH5xt z!s|2FE_5LC-(~y58{Fmr>$h_<`>9rOj&NnN$O=b2O_BZQM~Dsm*~LHNsQn89(cccKOJ1aQ(W9*mKknf{X6m1)nKLadcX|+uj3v%WqWAeP2v+E zz9)m&mJwy^%JrqbSFa5b`4T>9Q~8_)(e;amXNmOiQhr#!xSQZH8Y%z=AIUp7#r$gU zUh?@_R%=Y*Y|*U5-aATLDDxbFFc-l3g>;hm5qJHYbLMDFEGLjzP4c7%ckdXR@qC5_ z58CF*UGPP*l6c@n8J6Y2bcTpw@*7g=2Tu6xeM;sDbl&bX`ZuN9-k>x@!~pkYDQ~y zb=qvR&!Z+KAUU!Z6UG+59Vm+X_Jsc=kNsPHn~~z*-XK%TUId~=R08s4C!fd7I}1(q z*X@)?Z|G0XEGPDx0U)t(BV%XQn9ga6wQE2Uyicv2Cq1+6*^HR|*me8w7uTn}`O4Y{ zm6i=EwXOb|Jb+p$CS4kNMtyZ&B&h@fD^gm?Mtx`?A> zKM12A5a=&$hC(mI3D~lmf*%DlG7p7Hc^ZLFEOXeq=!r5!2N8z{RHXy^Wr#>SUz{g zP@kKDxx+*#*XZ)s&iAX@Ai$(4Ubp7X!M&q_INK{m$?8)H=&T-?{BFlTpmOs)s(4`W z9Dr*EDb-lqL8_P^Rgq4doZJMM&H(Cjd%AJ>c>9r5#*ll=W2+HAMSMOoy^q(mL`uf+ z(7UG_yprF-Y|E+@20;#6Rz)jaKF+}`xZmVH$!G`LudXcK&C)^B3SDN{uS_p5-M~Lt z8neLLBj6=$JyNOwLHA~R<}K2nYUj7rcCkZGiow+atT}HT!Ub|Xf zO9?e`To>D$>R_VF^>bYqD&rNJx%k$5KbAAse&qx*<0#&TwD0HWoY%b`4A<*>B!`=4 zU^zV96mo%o$WelB>9qY~=Y|4cj&+3o6ZAT}!&FD7+)YFC-EG2)oNGVmS4dIh=AEDh zZVdf?PY40^7E9Xy(QobP$LQ}G8vNjX%-*cL?XJ^#{S8)4;Q4bNbKwU2`*?;H48o6( z%&z3dZZxSq!z<}NHd#Dru}@tezmr>Z3m=~*%?p_h*M?9L7!_wPM!~6Cd^d(@6PC3r zPVq}(PPPZ!Vc>VtYBbJvE7SgheAn)^Eq`2RlsN^E$wy}Nr#m?>fpXMtEYI=(ZX6GW zLc9P`K(4<#8P-b**Fw)avPgak17Dc^(~f5z*V8gMJqMAW>8Gupblemd2-GVh^p!VY|TjeSbO@98Q2S>k7x{Yl)h{L#Tem`_E1t9Z@eYh%eSA zD6oM^Tdfswz8V8M`Z3jOQJ*EC3zZaBJYEVwU&;P4JMcA(eL1a_hm;PpW9rdg&Z_QU z-Axg@ukVqWU=KabLDDx%B2^?EXY>@u?O!gQBM3cQRxRx@`(<-MMs_2Pv$Nt7)V6F&p>k3RCN5H8X!~TRdPR~C`Cn9F04(?E z)dl=ail2n>ciFM4s_CdTr?L4?uAP8+@UQ#HzH%YubP8qns|>@fCN`e_;`Lv2Eb%00 zB=;Q_nJel#RU4zrI! zF|5qK*)@7b_9)Y|1UP_g?9g03^I|=0zEJQQeTkZ=BpI()I)rvbYU zFPhEi=l=gaz=bXISYxzK46GD#BMkdy0+cr-QQGvyUkR4cMae+9SqOG~N7?bRb)>@l8!y{a7-%3F!@wQM;4wk?7oGwzOV&2Xet$HC z9zKP>&Jv+-Gt7QuERr3wi2oxaB$j{K`%GUf*53)`j^g|~7=Ps_>*VM>wV?{us@(x! zf<8u^9YZLI0&39(#W&}r?>-=T9Z6-k#*3OJo-*t7{5b@)MXs6wWJK_+ALx;rvlzI zK}vqU57jJY)HGBX(em93n5Ct|p3Tc~wxncAGOj~uB{&+M-d#pM?ABtg0(C*FiG zBmw(wluvF_DVbxhrUE#*4gfDnAh4A9$Wr%9@q5Ymwe@Ex{=O|UD3nIeQ%5&558rw1F{m>~h&^_ZxbZ29&# zeUf!l*Ull`8K$7UnSF{E4EDgf)K{OcOSH!cIIP5#M*j{yAPzD&K|(;0l(2jt|- z4iDIXx{4{nORS3aK2lU!AohWdV2)j2tF9l{40Ig5S-N&7dAXXCQfZWJLM~=d{Y^dM z-=^y@K%ByXR(=Rw>G3_FbG||*e-PU|!T88(Rtp1CrXR!4JE|yXHgh-e(=W-p=i+>% z%wUW0?%YaFHVC76avdF|>rKp%InNh@gK8MQ;OG*8CIryc4;J8#LVOZveP%dQ7G;w>uJx+az5{v z$E4|Vp@jhPE6!l=S*BBy=K;z z`a1!~8fTbr_;Cgy9?^Bi29o1ronS#;PuPb*MTRBf7d`Vu@Y+C*)MwO4!n2ATMMl&P z`8U;f(mGu-M9-B8-zNyrzxowD6dtdhj$$`p7hseXpu|+rFO92XeQxy}&#z2tid|u~ z1zD*r`NMf3VAJaCwb;*^&up5Q1Ah_Y8l}*XXf;(=Ne8PD%ceuHW?Q z{MNn1~WB6;6S$o=%D3HWU+U}`7TI4HI@EQ!rwF=Mr#)8%bxI&2@SMwI2h zAL%qrp+k)&4e$f!zn|&1V>_`+L^aaT$tfx)|C6|gq0hA1Yygsvw{+^Bk#*hp)P~0r z7=kqR4jwrq(`3Psj_q}lAtS?*@19VlW$VB?SkW}*D}twI(dd=n~2;JJu_<(&F^v!tE_y*?Wngd&i_OsMu$@wGC`#8w%YGmeI?D`t!hp0%X}4d(GJ^aJ*mATueZQBT!hr zPw4aP9qR6f$0xO`=)Vr6&UW>bij#cPEhIAA4{SQhb$%%g)t9q(t_&TzzrTg{r}3R_ zo_48;33I?lp&LJt?0@op2_4?$h=1l4fMoLzgsi`DXeY+t3_O^Os}zoAqdgz}hvmWX z7?+RzE9O?8*NpwO)K<0Al+X1WUyq2xPg(x$dCRTX5&1=b5_*m9y;j#p_;Ei3Sca58 zsDtxZcexbK(IIAG+2i-#9;M4)PUWoC-WQeQK-GBE?N?CNU(=cNtLX~s7Ag9xq;kLC z#qpj<7hP82doP6`7iQzphGM%U??XD`$Q{m|QvL9ep1)9-?&9!23Ve2=e3kCnMB{wc zq(CpY>Q9sz2>kd8r%rKhVr6)*SD8uI@Xn|o2cIrJ?(~Vv`Apcy_M(rLQ^BJLP6t`R zfA@u*64Pt@I_FQED=NTG@lb^q_wUt5J&`-b&8m6qr}V^4pKweQihwU*`_nNt2@#}= zA)Ie09sd#N%Dhx}D{&ueYk$(;4rcZeJ2^H^%s)TfN!JvLd3~4Y%%scYX9T`*5dBZm z(GP6k{+f=ZYXhoc8bP@4(xI3n8gYoct~C5}@@*;o3?%pgk)n*S#yh0GZ_=U5iQ2$yDoFP?ynqKU`CLY~T=k)DeCr$$ZykXI%R2+qNOx%+G>Rkd5TVgew2UsyaF3-T3PRng@LB0NFRt z{z3Zse7C+Dg`luzdTuHlAHYjrogU6OI`~WXL*dk7r@=hBbI``;6$G94kDX2Ni|{lr zUiPZG*xryd>li)jf5GuuqPe8JIJB_yoJ7r&A%E4d<_*4^=#nP_M5du2`%a{>V)`*P z4T?lvXXB>am91sQ(7W$}!QM^PNlr`7?Mklt7P>kqIxL2_#{_Bn_wbAxH@IQ)TsUr6 zA5R{Y`=vA<(Qk;JqDM`};1Aat^DaDpcFNT)vU&$!Y&gI+n(;^IC8#!r=U7Asp25(J zqATr3`AW*qp>T2F1RRd{oiJ@h>JL7}9J==W(p;hkyqf@BN8IC*W05n?d1O!RD7tUj z%Vh2HN8<&y-5y6^#!O~xTX4vo;WliT#l(NN#*ruL%qY}X^!LMgpOWm~*)=;bm%VfJ zjnfhNl8)^;BHQi?D=dANqLj+rL;bjo%3pDn=x9{Ee$gB92U4{6yLX(}f7+$fDREz; zlbZG#AR^yo%C-@!T}H2C902YU;t}SP@8?|e9cdOF{F9~TCzPG-kpK{jv)>}N7DrUh z=}gqR|75uFj3SjAj=#&hOZ1Z?q282snRlV0)rQqpWQKcAX5+p=^bI>e?6Bs00TEoE zN5wJv4Ta(%>`(MiYn-Yu`w*>T6b>CD;y8&h=;kn)@CU^MRXOS6V3GWxBZo}!bfJ32 z{9l@C&U*lV!09J7{N)I(IF7cA3mw9t?GpVhx4CI=fN1s^5&s~cuvHZu8TXuyQzy(F zv&6EUbKk`U=RV7yOn;iL=+y{z54bOm{nR0z;k{9LW|1QVX=oH`#Q-;yeMZ4=+b0FV@_jlswd zV2ns`8uBSY^6a4}j|5{5Jb3>+*u5*%=@lJPd|ql}ygHtN`y-k~=Pi%LeQ5PuT1CI! zjAMSd;O?T|wKP1mHZA+!qRV|q)IO19e|J4b_xsQaR2&KKmfPsqfy~rwLLP&Ng-^%A zp+86X1L^s^hA#PY`gUk|Sh0(l<5Sj4x1k+!lX6(N%=3eEuJ(SWR&oazzbXDn7i~2_ zq-(`vseh54If-~1eynSZ*L)ipZ&L@VRb3QkFILH45#c`!Va#8Zv7K97*wmeY}jeeRFQcP{-5`S#h3B5{yil9z4r)vgx(bvDzp55=>zm}L6KcL3+a zBCzl4y^{4tDuqkn*%(h3TF*<*H`%*SznPn|T~$Uq`gdL^oJn`1HoZkgzF|m(A^9Y| zk=N>I+!Mfu;Q|8}&J+nuExbDG08&Fs$d3PX%(;8o-9(HGKFFMBV~m@0{MY$pfrfg? z?YcQ#1tb2~98*?}N8hKakr=;ZI4)vk`M-31KH+Q6%~HvnJ<`3X$%d-X>(SdiZf8tT z{tnc0(}Pb)MTMEuyJkZ@zcA$UQI2h8c~Pgl^dj`N-?QOK$Dd;Oo&Q>Is=^f*x1o5R zUg=Q)jv;j+wDEN~^Z4kRY$+XriFOakbEl4->9`sX=CK>{eE{dlujv7!Sb^o8dNY0S zNNxB~{WxGzY*iim_Y_Gnup@neR14-x!?SPKGhOGk1 z^ZA1H50bJzIVfzhPj$RCI|9+PM!(v1FO0v@DWRYKDfV*UD!kjX&$oj|&4b=ts%QKo zZYD5wqV{$z*ZeVZU6-6^+4*2GQAo)bBj*}Q~*etTVVklT#S66yncMEYy7;Kb+3NAs&Wha zCGZ}R)$uj=(1-A1*xT3DnGmt|! z)OSPUk*58u5%qU-Jj}Uz#|hY_7<89n3r=?$F;D+WX`G(IhM?d!w|uv{C$)cq*1bA5 zL%bA}DJq-V8IFv;K_?8rdRqP^winI8&&>`4kz(@~n%w`CWBQE&cBkiO1qMH-FHi8e zbyuByZNN=)*(|*JuJ3$6!FjvdX+cUowM`AthX)z!T)RJ(USd=I0GsFdOWDTf4bx7O z+2h9q+2@Ep)6(v(#UK1dZU5U>@8RR@<*o&F9faZwMx<14lO!(nC!&C{^DU#*zRMfH z>5P1s@vy@>TzJAramFiJP2j zWf-uvRj7cxF-yl#ex%;-tRFfIQeyzL53LjLA+VWsG<)NsfE(~$5q!~k9i9S-uL*6^(EV*O@kOQp@A8$@q!aH@2jrPj%MVt~4V zvw+2HE7lK2FNrQD*2VYPIz5i&jD7wmch)-_vhmr(>+j>iHp^OqI42;g51uniB0eXH z&+z7}qi!S!j}7;sooMlib#@W#&Gf{}oCKIr60&T~RReG;nJ$}dx`<&aw6U+A_yW7d zPHu7_sF=#TvqSFiv&lrwTMF{;GXt?$Q8ru8>Q_8)wHpve8LA50vmf1A(GD$?uE5qG zz^D_zJJZgmI`*ulioZ)9o?-NaXHGv&Cm#tL?3jF={_l*O@0n{9(7ND-^kEtTXqR=_ zhkdYwx85>k?tg}HlACe$-lm0$9+R@4zv}gqUIL(?-Q0A=xw>$WkA?gT;2~bli5p(p z>IkeVP_`kv(GlH=LZNCvoH|x5HO@zCO^o%xl)z^4X;oLdv z*Ky66b)k$NXnZ1?PD;aic?s8e73TGf{V%QWR^U&L{_joa(mk!CLWl9UEm(g{|HG1w|mheOyKInc^*dcsl@&>@g z+9jp|O9zA@Psb#GTEDJiw_f=M{AFcax7Z~;jYurYMcBdsJ{3*C0)zs*?HZZ@X`d}1 zp5*}a2zVe~U4qqhH-mL&4;i1!>nt0>sbz$616-y+M8NrcU*2g~XcHMEJ9itjT@R)r z?}B6Nys>P5!P#~F9c?$EzK(+6e>pk~@MYI1d0$y2ysn>95lUz7e*5k4_g1mt?_9>2 zA98!^j>F)VmY|i+_aiZ4-ahIP-`6A4x-N|0heK3BEDMzD>rKw14FxPV#iCrCoUeE1 zX2tHB77eyk4r?E3q%%~dORFiFIyQsFtCQ__Fz9zagn{~fF@wYgXWA%H2umNM(ByIT ztEpin8j~cJhY8Mkdfm21@vtnkQeD^O_0FMq1b;xicp699Sr(@2Fnz#$Zgfz2GH-*V zy5w?i@A_%>)teI2IsSoT?|LOU#3ZOk!|PXKUr24eqRRv7Am|uH3__{w(`@@)zk6<0 zJ~h>dM&87~edp(;_VfDsxva!;RZR0_eZ1bSMaNXz!`k^+M+0l6&Iy|iWsmh`e;7ly zcH9*^-v0T7Az5Hiax^${v>@(%C@O6U~!=9f89RxRYEFF}+#n%o`s0vv|0z<{`I zJOahw^)K>dP*YU}-SsWEhu};N@rlsIIu}G~=PL@c>xgqxK)zSQd%*Kf9?==`TYC_f z$zK(2|LQI8txM0?>{vJfy3n-dPG3RGntrwp`kntAE@ZbD4!%jbzWIv+D7mPF2)^$h z2iQn>A+A`-%n{K3qymedL~0EM(}_S+pXufbBtxgwK9IJ`H$D_*JkN^?U*AyxL_d9W zv;c#~z2g{TXdP&6cTM0H+D%!iXCdQP9iPhdZbsk=6l&*&MY42JTSfcU9R8ba05@&D z1<^rlk4dgxQ>@lRL!|!aWi#a@&_e^z#rpN_gp7yR;+kzwQr*R#!)$$l@ea3R=IS^- z{m-33mlvJfQ^X4`keCq{wTHUHfVR(S`Cc71YYXTaeC@UCa$db@(gd3q%%y5D?a&EW zIv93uf$*RH9sfJq>bkm|$MOXlAZ>OTK~H>hURu5#xo)tLCXAyGpG)T-B}~}F$%Kw;~^c4=Xr^%UHh)Y-1w)i-Gmx<apx*?(B!?IBoN! zo99Mc>qj;LIb5fi8&J=V2>UVZ(r)X;R#0##C`?v2Dq5^3(NpWCYw?$0 zCj>aF(PG0Lh|77PQ=Z%KwJx-tmW7UG_tHU&Mm*5U6<;UQyE1tpP^r%*0}zfFjwmXg zofr!l2Pj|BEG2T%yWUu>TXF9RD6f^T{=X!}UZ;W&aJZ-gK;8 zdQdN3q!0eWASn>4(iPJn4$xA~-Rb&hRdXqrc7BlF>LwT}leFvr_l1C626p=wA!d#a zgj@nzn6^kfny>O^i+N;Pda6V(&%SfQIWM5_TNeDLnEEi`w$-(oXoc4Sa{0&5ua^z! zV;=LZ<4s3Rtf-gFrLEQ?wap~%5=L{tW~2>>m>m3vsVJZrndHctui@Qj&ePAEQpCWr zIDBq3X))E%LE7o`cC;d&RZr>2ZISEo^t~(>TzpLjUh&==z^(RCs=Zq~^-ne;G3y0R z$?65v`!qtTk9$SwrTw-!q+yYhtAOD>Xof__0T^AT|N99O0?CYa9d6y+e0ekD$8w@A z2dXtVl637^mr3y4APDJQ1j^uq`p%MjU3r;)J&3zdHq-4& z^UfGBFjqwy5cT)pE6h_ypQ>$rPRmc;SxT;?7k2Shu!P)E(vDb$6H0j4D(ag@)DF|# zV{Cb1q>KNAesdAFxKVebmadZ>k?btM9qF>!n|}*}jIca7*uZzW}JZ-WIA{D^b3Qa&`)R zBHK3X(FYAc-{;b+3lxuu_%M+!>&|T%K7?dPNG>4=y#<4LqyWv3odWLz;{)^qrFjhc zu%y_K?9UlEPX}DpsyeviF)C`Rm#$Z7R1^*DdK4w5hiI>LXs@-}YhQa!_UkxX>&(`1 zR2~gj3@=r%Mb3{ACy!5>xc?^5Y6X5^1@x&tn($!pYeH<-RorQz^V!SA2z8-uPH9>NdlNfwF$&+-_^jU#cy&vh6uc?X^6FBTu(XcRTE$Y5s(C%2(9U#_PWLO$thBRe2hHy^^1Ki z?Nh_fl^~cTt{TCrO;-K~1c+ zDoNFqPj#xYlshKHPL?cqZcsN}TDj5<>ZY;$Cx6JH+Jk-F73BGRI5_OfpX2p;c)(ve zgw^pv4nD#;tx!ApnT$l~`FK@7E2cN$5hix#v(wl)Cfj4rqw3ud(1dFV2@)he?4R9p z4ss!2206tUa5w}6v+&>^J_aQWQ}wFU^~s3Qo45^udWyPf1yLSy=-3q~S}xGq+IhbG z16$r6(=pj+${*l&Y7_HV@7KO@-_WiU?#YB?8%eYH!JM*lXPxSH~nvc&4%La^pxCn z0&>?-=k*5dbyx73%f!`w-23MfzlJKn4$Wm$40`9puu=pDi<_`;1TR&vMa~ZrCwan7 znx(36-FV4b^n= zC$IclTgIBqfd3NzP)z|-Jzb47iEmfqL_GQib<;6q;In~WXf_rHzcki}?P3nwm4wb| zfddik3%|MQTd(?7otpMiAHSbY^)UhVB-)WTq!mL;>kBlrg0!swB16lba)~!h8Tzti zsb&NO3}Q@Vhr`Q75nuj^8D~ub0|u813B~`)&w(NsV?x_!YZo zT|PH)(ggaS19xCc;3v+ovBhBfM0WQ~P$T~Q#1!_i{KVN$WL*&G5Lwk}2*q7Jc24r> zIBAwIpV-5GF5AyUexeKeL?Ct<2y}=*sJS8B#nV+T z5rUIEx|8Ow_d^3A98^Z8Ld8q=oPmAZRM|#@E9$2BU8=U~>V|}ni*pEpjW)ESz<45k>9nN-clw55eA^hpY%XLLN9_*dKz?AuFokcKkyrf0py- z{o|(oAy_F#h|X|}1>U!;3<)w2oaEU$X+dfJ)?S(<RRFy)bNSsECmE*cOJMvVh>Tmdcg^-W zhd)2rcYofEapFM7je)~r$ z&55B!AKJX_TOy6MDGr@6e?m>>Jd-X0iBlY-^JBBSpT&&D*_AoVosJ=QrXA*0I@S9D zC-_6#;P3LZ!;@~_)ZEwF^d#*!*v&~|t^q&F-t*Y7*`nA?akGa%jOOKL^JV-`8=6M_ z#XQpvGYuQO=0A}QxO{VzHCW98HVZae+0VJF!D)tCV~)U|OZc;!KeK-p^XHtKA6t%k zPxg%uap2%IOPu6MO*KXG>*-XebOn-7rLODE0mj^kpA)>{W zLS8VK_S%K^nrmN6wbx<44(?y8gDT`uRQSGThDV&_IlxJ?G_go9v2ZDsnhNoqC(u%; zY=xNiKCj*QwB&!Xh+b)`U%M@jRLV=A#*pE8qg#}>uibXc3MEh+er@L0T)}Ip^V-dM z?Y3MmwAu~Z2??<+CNrkaNuCc*ngLt23bUWZ{(S!Vi2V$K9f1uPAj2k?VS$Tfv$C$N zj!0sc2(^s%8HXclYV7M6f5zd@3^)^nmL;Hs>&THKq<4fO*5@o)pAmM!*$zcAvIGEU zm!O%5{dRXmqzDkkOKRE9e)}RsOuSiF@aGQv+2?Qn^6QEXw}2@p6dhp%BV9!PJNezJ z6LLk&xxrD56=Yw6b=iK{17&QL7&SgW{Hc0r5GSZ1D~2$Yyc$LO;jim41Usz|f*sa= zB8*=T?dLoH@IR48m+i#xOpONRbe?=^rb%?F&dJII#Tuv*B|=T~yE>X&9{a8cd&PNI z$L}8Dk|Kxe!Ryo1)pX}2(gtjhA~xu3j57#}9Z+tz;{loEus~>EEsE-(_W*)cpr*ns zqBTvlHQED+wpk@uyZH6b9(rj5e~KKuK%pP)E8UaVt-c{vVhC#R&TJ}5_AP4_RPe$O1io#0lFpMb9Md>q2!%PI z5C#ok&;v{$tAYL@7!5oF7zDO~JH6v~X5s3CA^>D$v<$P_JJ=B80 zT8ZRhN)IM5NXvmZ&)FwtnJ$7}$SJKx4dZuhY!^iqY!`Ac21S@f5EkL@9{n1~dEKJD zOWSvC*zrKowV(%μbT%D4ctP&)bYsR~@JbO!hgTqeSPX0y-4<2;iDbUN6;OnX&4 zt0!ER447^alg)>H&2(P-2tXVr8)T5O8fv8AJW~?dnR;B+rB+tAmI4@@c!tO}<<~{$ z^^}+_abqVKn1A^Bc;5cq+!4@XHV7;`F^SOqf37gkjSyf4VQ$5`fbE>CP z*C%~~2@w&_oHa>o9d(rbY$b&ov>2?_>u3`|incH;rYzC+`n2(P$MhpM0N+p}kD2Yz(QG;cHnky0@lzBWJk1ympe-7fm75|%2%Bw09n z0j^QMpH8K!!PE8BbiGQWcsdn0l}hZLpqYW&vp_tVw*EvZpLss?M?un`J% z(ABV6!?L-JPP0bM)~@SBqbALN{OTBQ8Z=vI-eF&NnL+bvqkY|VzGhfxuesW1BL1A_ z*ImC(Vb3UgL%hHlr8s7ia6R-^O$QC#Ev$*!>l%WsJ2ci19JYE)?%GT48iQZ|?CTnW z*ImpoFJOjR#By$Xq|q_&JBADsZG=f?%sXSk>K5%a4?!^+nC!&RAT~q8h>5{99)e=R z5K+ADp?IC+yk_xhBg|_af*W`-mb<7>=Y7eHp&<+iY~WZhElMUB1rvsXQ465GZgU+5 zW(O9ud^HT+ILSYa0~9bgo88iRd3++2j3O?ypjuRGY+F3#&VzaDO%%!Aet z*WO^VY#5j?LOV%3&Ltew@6N!1xqu%a_8(siN2Lf9RcgBGgxJUerUi@eKUoTKLpVG> zUy>&i=|~ICaz=onI5H|Mp3mv%D@$;OLM@}{p-P`jUX^Z5we9Fi@az2X!-1s|1)Q+} zs(fAH5hM);jK+)uST&^^V#Di7mG{jbXy7}lsuVSUKV8xhl`3Ai_e&_uDGqC``t?$c zV~Q6QA@_y<*ejoKAuyim0ez|x6+A^ti_I>6R|W@Brbu~aVc(sxaZ;kVwSBk8e!l%U zvfq{QyFZ3H{L0)LYN~)mxd|OhJhXOCpp+(FfEB z$wrpN5;uU-uo?N-1$Ve}h7pZ3e-@g{pLo*1Glo|`@y4Hz{6i@J(CH_h8dzx}2B}!n z0<#zF$bo0v(7}?sTFr*CpD03&sDOPUao>jh50!qR2tQE*`vw`th%NlkyIKv$Tasig z2$6+vZF*z`@#4Jxq3y?=_|M>&1#A4~^3$4?lN$`19BfbB=e(e~=fmSmq+fp-jmN#$&iK&kX*6SDPcg}}z z)tTSMKB0kGsf-X|TWYep0lrKJ7hbn$ksYhN2AaJ$U2|~<#WGY!4-7!v;>m6hEtaZ% z1N5stwBw-h$Bk96)Kqr+W4&-=+ZiBcg7tR?!u}4R3Cmug6W2g%E3>Q4zFmC!E!DR5 z3=@pg)lZjXNn^witfBLulFqO_<}=**z}Y4XRP-4}tPn_q+gD2=_T`D|u)H4A1ryL@ zN$te@(vpO})E#>XzVrbko;af+V_?a?Oj3<-?KQ$nu`d0am`iGC=!;1r>x7EiEr`$h zq5Ai%aPW*(!_qSvh9Y^CPVw_Y8;aM!<@a3A_9$gJ#+v5K(N;u<8LwLF_PNv^hFoi~ z16%m?ZU!(X{x;t)gafW};gnzPZ4HKthXNvgO=1Q;`4S@0YC_5O{Gotc-W99bfIoxA z9u|WK;N=kI2)+J`l+$;MF(qvRea3BrzeNaF@W02iO~JR=iu2s1}4+V2E_ z1Jrxf73>g6A9rMsHE=@7vO=t+XB6PSCl|kY0w_9+tz)Jw=;_R2M#j%T=e_T;Fh>c& zJ9=~tFy0^3`pd>0pfcfmAWtXD`rUx`ZG}De(gFDboFYQP4qB808#*!Cv3ws%Xy%S* zKa1w}l|H|Mn6z41#nT#<5X5LbHuqUr{BK77wHZ2ETm-eQQcbO|aAOT=>&!{{Q!zu9 zrS=?dyiw|=veRzBuSd4SJQOzPNu}xHlAm^8vvO05TUrlfz`EK^8RQxF@uQ7_kBARu zxOfiHNOoT@nUp>N({}TwlXsvN=cGXuWI-~QZ4@J6;FcQ({IkOE6B+9a*>MKAK7}P3 z$19}_hr`cVlC1tRF+yVNd+eHhbV%>LTZ=2YD9E{p4echFbyHP5&fZpXmSzW?tAo|rYD_g`GOD;>GHPHauO+XIV{|P; zBhBmlcSuuP&5Q0v+HD8(Y&Rnoi8tHchm+~7|v5TaEgW2%U%w{+vr3>Tq2 zsRey~zr)%+A`tmS&kDkNz07r%)x%m}sA*%Nt8}<36T}qlG40*g^&IZNdPiWh*}ZeE z7iy2V^a@t$Bqj0*NeRxJP2Fsda_R6S7%!b)Pux%(Eng;ZmL1l?q-s0s^)q~c7k!xq zeU;~CT=^2+O~sZD;Zp{}tTi-M1=mgfo3WNTuo%fpMP|^ug3$Lt-Vw^n^~1ZZp-;B{ zxE!K}?NQ(1={n}Z7sGLPD^J#;c^l6woWv`rJ0nVhmSg2*vgM2fXfj^9@fk9>G}W>W z{FuEbv1=p;*+~Pvb(roZjT$(IN8t$0kmY6cnRFoAFq)I7#GsIjn_|Vq4nQT3VUCsP z+SD){Z$Jn3))aovll6m0gupx}^X{6l@qLaVfU%?o;-tqPWgRFXzvGfFPpZeCHO7iJ zeHj$6@JN1KC%8&UBadF8uo;CJs~wpGC=kQ|w!UG(zSpPfIm^}0L{7+x*};FWh!o+Z z5-d$7{Cr39c)5`aVCkH}*%$vo+XUp;o&$EOI@>kokZdGtEw)Gl755SC8$_4>(t zCZ5>9C^z=RL|Sbyqx>(iZ*fM9f%+x)yh|vWXh)`^)b4nS)(#5y3{#=6`NRw!t&tqh zCT9e4jHFRR^dCs-?Xh(NT-EhWh|{q^ft&}*buiPL z1{QUi$x){Ic&jVZdr(0WA!U%?w_i-oaQ8UpqT3|s>-6sU?C9ak@Bg(9cvSiri~bs! zc*efe0raXRa(|85z!d1r@Oiu=!<^H+Hl2MPOn$#y0iamY0J{1gm4S~%XXB>laDbfj z9q#!?;O%8n?p7MLK@USFdZlTB@wtw+yJ3pns5SQE`TB*cdaNVFWw`y7Er36s9eW8y zfVX!)cGd^wE#I}nanWHnTLoh+TppZo)7CSL^uk$b-E$LL&CYWv_OD{K?a^_3Csb2A ze(1(0J-F&5__D)qoz{&7=Q}``upgn<2){K!hB9hUQ$Vy+matfX`0a4_po?L1i4vA% z_@vile4|4s0t-(4IIyPmY88y)jIdWgu_g7*u;zGxpXY0I|CYI8AjZZ7512q#w_ePp%CJCBg`@6h4bo{SHq7yE)jx zQ!#{G7>&6ka&T@?YYm*rSat@zvt5Ga`Ch~ypks7mD1g~($*g7u$a_4+n&xA62_S^g zoMFgAT#d8dT|=&~8YEAAPQJgRC9;yR2hQ08n1Rq3s@gRyQiTrXvBFp=ILl7~JzZq> z@pE=HuY;^h%g%&aJG&NuXyD4=%C2Q(D8YG16fZ>}7RKw7=UEvC-{u2w&kPBlu0{dg zq)4->!N@jll*nagV7biNq*IxTQV-W6$KX8O%9Th{#4) zge5g6bw;W{P2$@K^BnF45+q%NFur22MG-g3Rtsg`nS~$rCUu99c8_D5lOa{n<<11a zz{ThBXAifnxmVgM0>{J~y8s;n6YbRLb*b;V$Qt&9z9HG@2^@BG624J%z<-LrrQU1y zPA2P_dQi>W%Kw3dy!6cjAHtaeLv&D4^2bc1tkP!}R zxcoNNJ><^jyELAk^q=BVPPbFzIYUiVm;=P>K{$APlz z^sN>j-P{pPn&kI%idINQ5R=TDaOUZ#8+2^eT@Ye>W;#eS#9 z16pi3wBls~~<#Qo~zy6kD ziqlaq9t*6-$OANgzYCJ0Xh7pBrhIKy#sadmb42WZ_0pV|IbLf;+X|X`xCwO$5|*es z1{_t+zzZJZa+bSMyqBg%gLtHP;RBZh*HcuzdWD$k&2yJ&g9mCKDoPX~)U@42iB+qT ziPUhbhO<{YKu>RwoQe?8#0M!u0$M+rNRq=HpW_XsIntV<^d!ih>-Cd(-QU3` z)4XR;V2Jq{%3k$lvc<}qT0F;oaq9X#;wwscLq=6pnU#|#Vz7)^gWQ284MVPkm~nW8 z)4+7XhYM%x8~SUNMR|_7YLinQDyFG+Ag!x{ttQ^`TEW6#cxZmYNuFQk=9>H$oc-Eg z17|W_Q6Rc63qHsJn3Hb1DO$3NGe#3V$wlz?;a1*Ce3u-{d*3@oR5xrYPGO+Q+_Z|+Rn^^jOfvXj@6~>|b(BBfKv~wo2(N`e>-X4o9 zjB)&jVPCO2E`&j}yVot&18fY8cS}1c0xj6%hsn5&+fkxnK;TzcqRZMnXqZrGKUi)qv%-+)1AX}2y4O3{gxINTtvMNw!=P z(d)$=-a%$r#VG%5FOeN=P_6;T$QjbYJND%Gl}NTwFn%}Kp=jtJv+{Z}VnUK_`CFll zP;>bwT0r<9GwM(hJVnqaQHTj!LTzm)!%i%Y`2~>a4a4 zj4Lt2{mN9@3*k1YLTwir!D+Tlu-sg+DacG@V~BRa6elNhNMo3-Nm>m%5?L&BT-<4izT zXK~^EYr3w{PE63(n;V3(l<2B^pl~CelIIF*)qdBPHyr@S;++#T)%5=1TI_@bO-_O+ za>mx8Y>fZbh)psYajg>{h5p`3)4;fzNOk}cE#p!%61%G~OspD0jH!6an!h^q2}pmg zxI-(-GTMsx=2~B2;?2Q2SUM%a#m!unn&aNVE^k2wCN_Ta_zBt?fz(fy|8~>5y8|)> zEs_)B_G%T?!$9}ZtRrn}Z6?1}a5hm{8;|??D#Xt4GO<#L#b|jH$ETm7ICt>0eDCnA zFF)Iwq9?XRY_6fGH~oA(^3WiAl{iy9tHU@$D95>&5BH{eF$|nSd3Hv*GA9z*9@)8j z5x9SP0BdU*omv5JIFBsQft?R4^-EbO#6W{g4^b&E>7C|4rbU znH{8DQIc`l@He|Xbtps_I+==u>?DDSn2JY?=W?7d!6dBjYt*K|fj+U%&Y&qh=l$44 z?fAh)c=sL-;sZD4TR31yf1YjT09Vu=6rWds4S3@_W5AyWkhvv;HSaALbA%n@8+~iY zA06izz7-8An=J}w)(*Z{W71$&h6Feg&0-(QCA`+K#tp>uRt_-vK^IWa>XDG3GJ1Xn ztn6SnNyXSXVj(X8DN|M86yUKfopp zi`A&DLtr`~4Sd(}{47%=4G%na9wCgxc!77oB;VfnMqh21VSVgFhT;>Y4l)>?e`OA6 zW;7~-3_iq?huFL-%D^)eDrpvCIV^ERDqGjvbtz507@jcH(sXRj7QU*_kdRJ-Q&fxS zhH#pn6+kS6$m$ScjabYAE8(^gq#o z!}hHt-~iCou%#p!UQj*sP@)kSLKiIDkXe0G!t5}YdQ_?lQbCK(30l06v#Z6{tOe$& z#!4Q^DNVLvRwcoV#J&!&%2@yum@c%f;`m1rHw_&uFMIv&oRMHd6P4tl0V}B&@HV&a z+^l#lD)|_@V4mrKx2wurD7!mzGc&J}<+)Jv@o45d^e9ZYb#X4JyWKsu7XAJ3k^1aH zEGTFfAhcmTEbn_@?Bq+h+jqX*nxbUp1GKUpSm<XZKQQzM;8ySJOx`iJZAJqkioe| zhb*=%@NMC0$s>+kg7uK@G0`k>G_9rK_VE1!rrw^hGZoA^%c0HOr^5#Wl=rK9*dbCq z?8x*z5bvHNGj^Wt4ovQ#k9<1+X7K!ZK(SAiZpB2^ic)e0j(ON$F$|Q~b6`fs*e$;g zIP6h#uc-=1Iv+uI;C5UCEKd5Wfx9hk7GUq#AML|F_UYBPnijh>GEeQ$;Er^ro-lUH z%d~%UR(}#RkD40C{^O;WCr^{fJ2-}qX+pd-n2CsGD>xNVX(!W_f07pLIbR+ zo0W8!;qWZqW6~Wu@0j{|u_C2lBI&NvVvu)mEe-Kb!RcT&Q7=#4K~r zaaP{#JFU5RWHZIFaA|h9a^LJ@Q?N7brFp@DkayJjJp)wxPgrcE&E-aq*oU9@q)cW{ z)=Qyes`CMos~K2u1TaYo3<@*E&ZLh&NmDdm6YVb&iFlOKT*NPOeGRp+cApp2Y`!>C zoDQs^ZAt~_y0OO+r06oB#bh8rVTiChCZRdld|(N=JTyU8X6?kau zCrS{YJ;NxT3>q1B0L|fg1`|N)aRM48j^n%cLjxLZRe(|D0i1WkuY;4&Xb%n_kvnvR zC~5H^UJbx>Sd9xc4jdBD>*mlL!R)2#X0D1z@DP^PN`FV`k z1v=b=vhxjomss#Ss_&!&dBzi~mlr3%dkA*Oc0hJ>kUPOd>W#W_;~hHyRrmN;q{e&P zV6F_FhU(#Q#roH?n@t?Zw;Mm5Epf$1JES+er}v86-hz-XmdwgXtH-D}16XCOq?91n zjuj1)%b<@)10O-KTMjv5X|?}mIK=EY*Pe#*pQBy|Ow0oEj`Mvvg1ssfnO^wA$jAm{ z=^Fo5QfO|6Myy;=x&{bl7#4Q`bbx%@Y7BcNUcW=HVn3E3D~=;ML$EguPo4WQ{KKgt z>={r22wIQvMphNVh<4g3bqRL#$B-J=Noo_#qB2R8yd_r3CI&)m`~h*E zna{pNf?)5bm2W$rK3YKvRO=lEqVcKRSMISe-5O#5c5GZmF>qG&KM`9$)xLSn`*x)j zaF>8zIzPiQh;M<&E^@sc!gdlKD>5-_jG)=CZRHC*3)y<96}cl=eG^eUc~kC@eb@Mg z-2WZZo-puy^8pXUTQ6QAcNe4>4#u=|ekZ~l+^9-EZ@!+sMAmjsp z#EBOmhTPfsm2*6J7Uc{p8VCBb{ju(2&B@(c0485mTePPb-34J>p^-dJ^tr?w1I-Spmq9da#SGQNJ&nnE;85NPCJ~!!eP|K@P zq(gQA=d%j)0bLE9^*N{&t3e~HSf2$r-$Q=~kUpz0p9N^qmYf*znJrqxpu}iA5QOdF z5wUP^CLAl)Ja&)uxXm<)N|opiHK|s@PT{TKqJn$G(x?@cCh(vhcak=k}oK8^&p-0NIMan9#+tyen{qUfiCzBp?@U z;d$IbZ&{003N>q-xvH1l^(a5$8Lrl_WqTAbN5_{XTe3HmPOVPCDOG7?E3og%vd?={z=XeM=E%j+`7Bl2NFe z;N-;dAP4JP-%>ozg$qLRv15G8Ip0#N51#Wa#dVOF(*YD!LB&1??(I1p9M63Ph5W%R zD}WKGWs(RC?9CI^3=h(qGRd1aw0Y^f%iB#du{s|V>3b|?)22*vJGZ*EVS_}nabwrG zA&*FEkZaVoHELQlZA@utKcEe?zQ@wGR!myj57%|k`5sH#o94K_v8->W^S;o9!jKsc0e#3N&&{GCgb^kJe5jv!(V4>2s1=uLm+|YWsY& zru7iP(%lj^Q3rNs3vCY8=ccY6W_55fe_cZXKIcevz&zBg+e=n_#%dv3gFov4_L#G^ zOsGRJpPRbQ!mML-I7y#%0LO&M4gjBd>zjl#AFaWfPHxq$`V6a^D(;jNvz^Ed?K79U<)oQiRuMC5jX^3kgMylEprW0wwF1LV1#h8u$ zFESky8CjPJ7Sc!L&pJDl$ydoXkRO|Ud7)Ux{vmc@sSPyjB4P=*h(jz?INZY0VQmSq zuCE6bUaTO}Xa3nIiB@4<9fmlj!w?r_yXZV#OHbfcm6*d2C+0B31&`gd9vFmVZBYGR;cVluqCfHCQuR4LF+G(jL%URplkk|2=bnS~y)8jwC0ojG`XFmmZy zfb}`)W_W^3f14y7W}&T}t= zS6WQ8uBtE)BDGcpt$b$b(GH9+&1iR29(_U-9T{<5Uz^UT2ppCM>_Yt-z3&kwZks`ZWj*@5+$ zmpXBztCgh4VTC5Zd7}miiQ1+zwJ8xorD@MA$v~1lG;JCls1jW_S)YBhY0zXG=kwCq z8T^^aeD=|*2!jQTZ_bXYt*u4VlXQeN0_JYYl3>%rMnsSbQ^{>B=kw2G3o6rZA-nkJ zpV?!(XV~^^V_BbnrWMzZGiG=}x%0dZp?#)mmpHBczc*f8KWU$zewMgvYQLE&`Rt?X zO~rht>oe2u`RRuP7pzYX*$q!nD6hl*Zs6#X66oIzq))dy$ltrarT*4&zJKYvft1IA zWcT2K3;P4=wi_53MbEtSbZ1a{XNh#rc4t%jTz1{;=RYI!<2S}<6+dSyMCrmrriQ)S zgr=IYM?(V~ce zKMSD|{rLy@e1JI=fEykwLq%QMkweULFU=rPtI7f{Uyqgu!%XQ&N-bQ6kJ7glNjoK^ zmqM6+pZ-9PW_o>wHDc8GJsPcmqN8xFUwSP->-6gi1# z6&l42KSrwx(jDDhrxl0{S^$Xb@s1#Y!*SIgn=v9e5>$i57iY)Xp?@ybh5)6ZPXM3G z-Fs+$r{9m?n9rqJ0V+noRA4?xw^*b|RUC3$B1lkQWmNm#}a8%=8^Ts0=CEEdI=-_2m^DvV#``GAp&uOTagcROx(XdIDdV z1|w#$OFJ&_2JqZVQ@A9Glcd9+&V29}<6G1L3?yu*DiW=znE@!e&U(Kx=VcRdI4Y#r z7r8E8p*MPsrr0K^;EFP5Ex8AOhJFeH#s|``$=_#aYu0O2PClcsHP9p{|1d+0Tx!)*(&F7k|K??CK2j)s8A)F-x48P)RsAM6dI6|#RAYsR(5r@{q)7Iz1FRp@`F z?2X5LFWtka_rMxMri_FrG_OObei7H`eA{>aWHLEuq}WhPG$Ci8K89f`8K{~<`~-$f zC6BuiFGR<>q6xw{J@f5ar>p;zJXC+$Md+4VPI)&3@9z}Hrapjt?_>J7x7 z0rGKxyDQ)KC6X<1>18zj7VHbX68v|Cu+@RJt<|dr(F)0-2&-?oGF_0Dzr0x~lrUXFVOk}aR=<^&{I%YDU!W0sL|xH>Hr)y#Km z4pb@UyB%VO*tBdvw!UV^A}1db!`~|RZ@+Ey$x5W;Fo3%Q`v1H3cIdmYl0}^-VGP$G z|5=Oyeq&%przk8_$LMBz_;=Z}a$DJ<=hmf32Jg>W<;2t)`atE&z|>A>&8VAn2a8_V z;z5UDtEf#zIJ=wSVOs)Lt^o8#oLZjqzy~%Bg%sRu2`ulPVS;xUKB&_+lB?~M@Q=46 zRF|oK-g$~GqWHNCCS(@(I&6Q_Z9_1lzkqMGBb;2rc+t16UKE zhqYo4TqZaby4@Z0>U!r;^LtyjJ|gkN!6IKM{#47&rU&7jZ1^Kv0*kkNTH0R+YM?v}S+=eNSRmwX9FU zj)M+#)gBxZm!dQ_C)MEUM0Sc++U-70WWIzgWhQ%|3j1AKfGFR`06>Y04pUQVGPuG_ zZ1)UVO|mh_aqg8Iu6;1&6(INqiY{TN&(@f=;~c}g98MX9DNG?C=P#5YG^Q{%A&7_8 zgMd&bDo^+}HBZ^IUnYEqJG(z3R)YvMG0prJ7Zv@rLJN~7a&|LNj|8_pB(m2H<{cDZ zA;Q2W&pG0QxHV;|aGinIXB=*aJZp@t%-zqzwcC;3!*{HI(nWY^*e$OXPh5gV%t_bh z{LQayk7qXMzyn9o+v|)8a1fThl6K+EJ)u#p_=svR%Ui8WTyc@CAZ}H@Xv==;l|Cm? zCom}&+w218rML6>IHP-pWhxhA&PNtS7zu0AwDw*F#~Sw5!A=d zc1GJ_0PFkGl0YVX%nY`kc=IdGpkos1cQ$4;Tlq2(O8 zl(8HbaiE>!s9Ao~cZ3l;K-#p$f|j6T<8R=Oborh4J_U__2S6|bwM|F67DD^_JI`o-;Il2Qe1663bXn?XLL8&sp!`{e{Gga*O@c3RP>*~)lze7x- z@WWc40O4a|U9AgZHIh4uQBsX?(A~G@7|mm;)4X#w!kPa-wuz@+C&cCyPBcx^ABf&d z_lZW(@?}OMbAV`n=W^hqM>Ly(3=cTJr&~B&xC0N*MbZO=<}t~?tN^jGXNdWpID3~0 zfB34^Qhux^mIGX`jNMtPf*{XC_<-|N0O(vkzQ&XlifUKF2hLLoAm?zFuenxb7YSo| zrz0E?xR2eba#BoD`nz#p-7p66k_{?5w6HqFy!<6pPU*Hb?JYGBA3A=!@7MY0OFOjU z$~z~68HeQtf1g5R~x{`v56pY&A(Pfm#`=UOZSG=#(roe{Y|lP`LHcXa!q-;C$98L zxIzrNBj2!IQ*-)TU;Sn}NaZePJVcac=SACm1%PPQ3r0~GewLm`3EV+bSYDo)&?1tc93z{9QW-Q@w3@e7cYxEjK1 z#JY&>&9X$oR;`Y5XNQWaDPYF1xQK|pl>XvM@lH1&p-Ft%#;5J*$WgpGIkP&t{&m5} z)akAf8BhHhFQmj_UY4Lg+Yy3+It2a^z9mZ(uT6~%u@d?M&&WC=HfKXhc$CX!LkyD@ z6&x6GE#Lk1?0;be?ToXTecQCs@(cCfY=yZ!wE-s1E4C8(FkrH|I%PmvN81Q$6%Tt= zivN}ol?K>9Juumqr5X0;d2)6e>kySr4qR&uN_LO#-J+J#w=@tG(}Q!QoB05%R&bWf zoGg#$b_MQ$^5&BT>Q?vmN*y{=GJwGTT&_|>W(>p&vK#-OcEHhJ3S547(*wfUy39C8 zC0*6v{>bB4h?9u+KRsBGmU$T@T^c)+){F@I;9+V` z`}V>us~>uYaW#N>_C7RD8t5Mda&3T0 zTL%upAlo=-aNtEd2)IyfSTH7aprcf8(e{DIg*z%d874>bYRtVK%G0%~7PNVZj!`{# zJD3YJe}&<`DO&O{=sP2$TC>d`>pGi{2SQ?_48f>aIa6rM;86vFIMMy%35~M@uZ!&l zq7IRPZ9;1tX4)Bdd5cS(D!+BP3%1QaxG+gdG~Ey`|o=n&lB&x2Nmeps?G0tOs-S zc%ZkRTpBQ*;9-a2$N-5;GWQ)_rPPN)w+?iXlMHCv-|RD~`d+PPzW*IagSRDlvyYpq zp6Zkfb22Uy`>9RcPyJb=&NXG>n>5f(hy=U z2V$DrF|+R70~g*E7O+EfQIeDn@=GCb+`Z;e{SM>V=}`FsnP7T#1spRX3w!qEPo^=$ z%tTigOgerC`+(wfxZ@U?MP2ekd>up9L5A4!{T0oK4#*Vt<=>n^Ew!FWfnty$VC;;0 zh?Jo5Ab`cxwL0TbV8At6pqSfi@P8C)2fT*(E&)9>hm?;{DG&tDop=5j^u)&nfLJqT zrNT`7xCA+}1G|9|J6($-PFhHt;gR?iHCMUjSD!tbMPKnLpfHu{|rrGy2`1EOu`4yUdY`h7HH-0d*<>I1H)m~L?U8mv}n zX?;Sq^;}qK-_c8fbk~D-n)nbRq9D(P;^L3T*r*+PV`t(iw22;8z%~el=l7)VWh4(o zS|3*-wXTrXa1z%bv@4Wr2O#c*TJUVbVzKD~ zUtrQY!V>TTtNh8_dsB@H;mY219iCc;(H+4v>!iY*oC^rlmU>L_tZY2=eeRHUi6OH& zccyCoRK0A*P-n=%<(}D;mDN&MbwSOM{z&dQLj*fexmK12lXpa!fjcb(tA2B6;3`IT z>~T84>Kml>jK(Y4wEDuR14mt9@Ql9bfE8=&s;ukTx(u}$)zv`v_GzuP=*@Vy4qWX| zSN~s}fkqE-_LEBqTAVS}8j$vo%k&kVQC=E|FeTrEFrX|OGb*bj4ZPOMmh2QUyNpz} zzi+~lJ0QhA-ovKVDFFKqlAA~PK#62o^c2QceCHuyhq$PP<-@#+ z3Z^i8Ru*BPMu)B!P9h8ukF}3$S3eR%W~?2dYeS?gw5Nlw8^>z;#C7CGH?BV8R6%kho@VW!dZqe!EG@YMEqwG0@Z}V@<4-ch$96vO3UIKAY^yDw)azJd z4;RqkP7PSb*XTJ&JaL8@&hZ?oIM1P$d!4KlDu>?6v)q{Q9mdfNx3~+~XR%RS6K$2T zuFL!rW#^*9AWwa7elGjM*W&QHDDa7Th@=0?Fu%WI+OCz)s;OH4Gywyp`uy$-*<01j z{SEoiHd!2_x}yoFX-3GaJ1%7vmO4=`XXo89db1=?Vd2);{7$B7dKNFQJ;4~GOEM6Y zcZ?%>hBq6%X05W~2e2JB zn_0@}8MFOX9AtrR0o`)p;f!kYfY;h=)P(k{X0W!321F&s3@*q(C9vNN3S(bhIpkjr zXBa{Q{A}bIsO$PN&q$mHeA|#`WNw!xI|Erea1>!P0`eH?T`@6byxXzQ&ba@&WBsj{dzBP0Qp}1#@+JO@IO5TCWa>pQ__1SrAin;!d zQ{&8i*9VMgRz^LQl;uAP#&`$%^@g#?b7jYAZxrts>R`pEl#W21SQxZbK3O5C74*#( z2VYJksxJ}$2>dz(!e+jB26Ar>5|Gy%`bO=~6+C%kCmqj)2T5FVe3o=#;V_KF_8VOK zw#SfUzXh}m*!cD}+8CXzxvGx=joABfjJXEXT_CG#n0A zhZf7(_{t#3#<{RNW&VrUsNU9Jp$y3kKBlCl!vfp_%mTxrS`Bmm&Cj*Y6}6%a$^W`C z**rfh#Vb3^reTi;J?Sb}tR#~SM6^;Rw@{i^g;*^1?xaFYySEvbl18N`><7-HK|?eu zQ~sNAeI#WHTCXCvE}lqe_=o1-v>@1qnAdUBKiIHL|GRN)^mS1k$= z)di6UCC7<$9*y7#%99#K@LYETe31CauM!_4l15LCHqi5K`dcVH8o|-gq8|c1#|fYWGn6Mz zOeHtGj(nAUb?`M-_4KzPgg7JN?M>=TE@f-qa0qY*2KF_TpFchn4Nq<4jy#r=>_@n)J`pgAXy zA2nk3-wcYN7F&vdvLk3lNVJyVJjyk8qzp)oRnsFq%2hUIREs=0x{5Ts&Ta3w8M zh`FU@kM`)<(n70#wA#0h6Rjd1l>mtv!Q{Au5<^2%>&QsV%}V=6dUPu*Ye%ZaEVCNQ zj1E@av8&xb3S^jCVO^c@JApk4WO!v2)I%|Na`dX_on_y?^yt>nQ6R&f!5)>MUb9Rr zD>m2ZXkGVmSLOwz%nJxl&h|j2s`J0zeE=i)e_Ma|INwb6K&JoK`@7`))(BG_W|a>& z_rdIO+k;=Fy25_K4_G!xug#nrrQBOTZt|TMk}n{?8?#Le#j^OzD%*8{#HNiEc!pcS z20J;AV>sVk>02s2Zt~+aTLy}?Baux8kqb5oEOEvDMoNzY!M&G2@<0I6_$KKd^a(vm zbQNSlG#yFg8+IO;{M(KAjx#ejN@S&&IE_q1(;)bu)A_bU(VDx&L!)l1R98%i0b9Z&3TMR=i?`82rB@(}2v# z24Z6xba`zMHsnax5E_m}Oj7uPcIuQ#V}Lg44(URXhXTk7l*u$4@ePK64avT`E9?WY zHd9K8tTQsyxHD$%En_B5M<^r{R|blBgb1~cDMN66J{REs`-{jZY{BLExVLiY0{*rTS92kq;X=b*^3lk zu5z-_jC*9al*gu!+?s1z&3Aa0SP_M=hHia=dLp6bTPnF_mzC-C=bd*ZJ+aK4LEE}5*p34Rv;8@UUCu-*amm;(k3Oz zWNYh^nOs%m^6B;qA;DTc37Y_WOqFg0g*;U)AzM$p ztSzl46H6;AiDlTUEUX=;9DuD>SXcJ%V)y)*D!sD8_Q!U|>2{3tcmiu>R=F6q0rveO z3Z=N5=Z3-%aS;WHs;0PWge@aI=J`PWxQf4L*zhm z+`wKxHo?Asj=Ah{l9Y@NY^2V}>`8PZS$XyLkCf*VRvSfYs;@Q$CygQ-*T?G$P8&3u zM|#{#mA>=TZE3e3;0mq5E^ZCq1&*K<&$HYW6V~9x#lPNdQ9{1itLo=e7GE=c7 zIFEauA%r0~k9nN$31Zmeo-H*f+X4(uA)PRHyCESsOsGk7=3M8GST5rlPbunc9yZ8N z5CF+i2!@!2T|v-K1@l@P%LWPZV*pSZG48XI-i)_eJv8m2u z6oNdaiIeP(SJ+Kij6zU|2i_Uwb|9O`Fa|J9CTbfOY-~OC<0d&u7dpk}VUL^q)G6;Z zW+4Y3h*>eoDTP8Kl`p{|x|~{#!JQY`mzWPFE#$yi;u*~_udy;9NpQ3%m&~q!h}h1J z7IVpD2Wp%sd0pj%nzFKrL_?NDgCxuCbpH2qo3s@8>0t z51*qI9XQtsHE7PnDUr6A6DJDs_V2vZX(oz!Tm$l$3-Ud6sq;TdvBf*OIh!-1blrK< z&Np$kh#T|fO|ld=0_l5*jjLtO9bW%@L)mjo88T6o%DwJPqhpKvHkN#Y8_WGb`hIc3z1?EpXfbYMw`MmnJ7YDBm|SZ^ki%drdpxwf z^FTPBFE$kYe#GsPCfu7_m^V4zWF!8`0M4=R7io%(KeKnv_lwkvF&*P!BfqxP%b1D1 zeqFq@C2{b_*48CAPx^k5HkU4J#Ui%gTiCeVi+@-xT(+bMg_vq>i5+EB)PdV%ij$*E`O)lB^Z=J=}tbiYj$)0OVwiU=mwkkI@9n-^-iRGWSr~8w{Dc zN_=SScA$zFg!A|c#7yc*nUPS8!fXgeVNmhv*r~>;lpsR@fi{x*Z!jvznce) zoTwCWR$EXZ#|#1hzyR|YP!Iyp5K5yc$sDEl6o3Q~JjBeIKtM1chya-+2!?_oVPFsf z0002Mpl|>HfhY#TX{My;0d7+uVzAt17uJ1vMiCz5v1|GLbKpR3{FS+Gv&>g$UfH6_*#&}P_VdWDeL>aj9ZC408ATLXfq7P_jqB`lA;}O#t zcdb=qoLVb%7XUYH?T$ZizF>M8cbjcLfEJL6O# z(^3oYh&kuX9L6{EHp6~f{K-DDF5Gj*-ZN}In|fftDTLUx{MsGL^-LsamkJVl{C00E zZKd}`$Q#%N*c{)Kk#^mci`Zc@;8%vli%2}bJ{FbmK+cOjSyzTN*e$Ktk%cMcL(^H; z_VKzITBWisV0MZd$UsX(ygI_2bJ?HGtl-FHao14yi;V04&!7fz!)g;F8#7${48F%9thF_AEznnjIr5K2~o4K12LYy{-i{kD|Zh$MZt$B zpl$)Nkk{q!eDdCtS0!N*oo?VLfx2wHnMJB3|J@C-jnJG((C0J7g5gxw{dlZ!9<uL6k26?LX}3l@+ZqLl4Lwsa^{S0ML;sx9EO$YV{M{wZk98X|@(whDG9-6g=XKz; zLx&ktHaA+m+KFLcB>vy3aiJ&Z>qpzMtX^qh&-j3evpqL_t~WoJyn%hd=JsYM*Va|J zu^lD@e(lwYFJ<=0%&@kIWYxH`Ig_S3sl^&st>y3p zt#PhF41pO^#Q|AsqqdM-WtcdVCB+RhnAr@}R~wa3wgNIrKc$P6{Z#xF4s*-* zqZT)mu+5m>wEe@$NoDlJMz46M6y+J+KtZL;8uj8U^dhWQXJru7eA}aSxF( zw?!99bEctd@lRKVCBoicEkvU*gM!VX%ko#@eX5mS`XmMXEya~{nQ2_u{YjvzuTJU2 z${ncB=wI{2p$|EwRsSdS&FY9&`;GVQ!EK<3Ke7#wc+L}kKVT%_`z*_x4p{Hw37!T+ zh|evHQDCS+%NCIlQlT2%0PdE6mKPp0Po6Q$Xnj^AG5$aiD}_s3$KY75hOO-gQ+zV1~5Z(>KQjAv-B|e?aSnSlwE3*04OGtOJwcQOP?-w+8k^=P+VK zub(T!EQHk}=M%}TzfHmcq58!#eEu3(0QG(G5@UKAmLalTmb zS2aPjhvq(`6%*Q%6FYS1ekKr_p>t%<%fNLF?P%FM16b}AP9{4X_`!<<1^8mXb2o6G zIl5uhad34@kDWvO9YDMVDO-E0NFq9UpQEIhQH8ntV!pMxHfFCN5fe^XJp(B#N@w8w zVBAzl_Sp-ZvNO(s63qyjk$B-+E5?ihwPJ7d1j zu&FYZ8HP%$3g_4ZL-?;$S%g%R3l#8L=7=?tV`t3v9$0gYtMgOdkeB!3T0LClSda`{ z{xUo8s0ZYpkQ$UR;C#xV6gHSM!wPkp@r*TqYeMS7-3XT(#Ai2~jBmZ-*5QMhQ4KJ# z9xW~lHAwrZ*2|b|MrYrFug7=bKj442O|pHT>Apue)X(ZeOAYA*XT z6!UfCv z7?#YNz7@(~B@mj}L4eUrohf_$zYJaT#*x)9US_2yvR@&K0S!))ydztE84|LW9br@k zrUyF)Q`%xKg%9fr>MNqs@ps2{+-Y8eKs97ARA0UL9qMcT2N;DH%W zyg3F{RNUZ>ig*Kf_pA+OkXVqWwYMV?mMOT}c7TvH@X53GM%Qyzi8~gRh&gmaTC?u6 zwsXQKR9gcwGn#^pW?hx$`o_7W>{-P=HD+azcrTez)>UlBXTy5xQ#3=5Oc0z9KdI=F zxRF_*P+Esij;J>yBHO-(M2;L`*hqx|INiH})to@8pZack$^TS72P#mH4PVn#erW#y z2VjaBg|p;4^NgV<-ZY=|){rB&judn`Cr!Zsh3+{6Ym+>3#Jw#PBw8uW)C?ZRdg`{L;)`CM!Tq zvpl%^3qX>r7mM|j4VFC{c_wvvKOjfsJh-mPX)$PAoCW6-X!f%@%$RJ?hd=laX0UfD zW`*^BueNDlQ980A-5DPk^MI=X1lyH&`j_=85*Yh~z%{Ovws)>Wf4R@l>2J%!lK|Vn zHINc7d<^|X)M?@EU1ljs(|nlw_;ya~uosqITz=!@&+|csRcUFDc=2?+NthBWsZ@!b zC-e=KV@)p>_JW{lP5;C6e>bk=dw1BhSoCU-x~=({dD8jZJ8~M{pN;kB34!4-s@iPd zgJaw^9ZJ$zpns6Xv1$A`&&s3B7{@xmSNr*fuoNy!H8p*H3Li9(@UsXWV{D#=8%}m` zWARKuV;g36G@{rwkSna0vgQ}FCGm4+sHt$0Z5`-5F@m!Y5!MuX*pUs#tcn2Y0M<(( z-g;d{m`?#F)rOE+-`GEF(VZBN3)t4rUaigUH;+{>jJ?uqz2=(w5yvV0Xy7`}gTvdM zmULVjAb@;5m8%*)-dV|7Cpvw{frZ_ZvnTy$QJt{^JJ8udozc61tYN}%28qQ$t?^i~ zx@8A6A*(C-J;UnkqY*j_=E#}T5-!PR%$geWc{$*tJXZhvsPWD@`FP>?xE*e}1LB?1 z>FwPvJUmun1HQTD56~X=!Pjvw-@&OYV==(FVBMEbFxw9^6|qbE)O2Pc#LG2&TNCAJ1u)214=58S+xO-Lvm*lEk{)pfGA&1SSL z;}<(f!|{??&>4RWT{sU16HYk%T_CeEd4CMEDP*Z508!&D`A8EpFhQC51({_zV7yfg zDFnnyq*3kAI8)0^I&?r)dr%AmdtMFlM7G_f0Q(C@W@1u6ErBct z3PcSZrt15eq7N<%1}@i@%SZ@%1^z0s?xV z)BBb3@j`%#750P|nWTR=_xuZQ^#6LIf!=6x-}jL5KcD) zl1Z4=`GH*o`fj~{QIPy~*VCou=At6ys=FYt1L|w%w_otzagXlz;^w_6Q5WcGbgmaY zdAV7V-@DZzZK61EezX4ONPlXGWL*RSL2rwzE=i>GGRko7f}QO%SnpGf@2Oo%uO|QQ z>J@+LQHDNg=VI&@n;U=N&ulaJwq(&>E${ciurM(}-VpW!KMb1$*wrHMo>b1OwSzRn z`unjBzZGcjeavaw|H$-|yQi~r%07#l4Z07i=c)Q?%YKr>$gL^-Cj08sQUFA_kv;Y7 zH-^n>OfK{WWj`~-=*Jh8J2}=5etOePSp6ij+^E?vrO&oEPxU)AK4gaNshDm?4^~_E zyE>Fj)?S#8R2?4q^{S~?OC9L&y{2T`8X=a&1zcWRZ_L0jPCX=<{gw>?U_hV0YwM$M zo;?bB@aWfr4xg)@!YryryNBAv3vH4Wln4WA!s1CBh=Btgp2|T`0u~pDIBb#6UKiL1 zzY_FN{L-62-Bv;BBQ9lph2e^|e_7zA{Kc*?t1Krdk{l;~lkIXUb!L5b;}gxykSkb( z2vj-^G`6wVm&&LzSCem`G1Fn6zXbr8R4$Zw#drr~L201}GMh#b&%4gN84vG?qb-gj z%pl~=)E1Uf7SHQl$Swh-Zr>ocKRTk}0x^^_d5!7}`pgFdO?$3osBYD$wVqQ|9^CE? zAXd89>3nrs>hDz91!dK>BIJc+Wu_)g0NB!d<78g662l&j)f-Jy_n}Ni_Nj{ed#rA# zMW4sKJ>NzYf#Q@>C~iyu#Xj%0s#DtOfdFA@DA{KEH~5u!BSUps93Z`JWi3J^-BdClCLB!4j{SX5J2d&+zC+=1z_qW}7}snbD$9hJq=D zTn_!-9Nn<|E5ko(#SUk7EGP9Y!oqh7-g1+UJ>ZADt_Vz1a~hW0XxE5sS$9HJa=c%8 z8GM>D2^BdSDM;{4jcN{p;;L@KQz{$W+QG9v{pii zQ*~OZ&~d-wqST0mxP*-iqfCCGDk*>N8T@3pv^qAt+GZ%9fp!&;CRgv0*ZkmP8_hj+ zidd&o506Ft7+Kd5egHT>JXJ92`WB2zpndJNQu2lS@4zhYwB@ZgXl^ZmI&QRK2?Ejh z2mT0kJub0Nz`K1DX9W$73$;~>aR;if-j+)vdj>zE{;|rdeWI&4VL8Ql2k)8W<2bm* zX$^f58%={)Qyl+gRai2dWW5eBATct^T1h9UR`nz^H~_1p8`s`!W}bV9k4+)ZY}7Z2wf{U~ng&at7TqUQ=7vBp z4Q3~(L=Qi^Q#?o9mL?85Bty^Y01RPeWZi47bkwF3V!$AetIogY%c=7WM_l z4Zh{B?90N*TJ@gW+WyvqR2F5CSxURXTrNBtxuLs|G z_V$b~Q?sz&t<}x#gp0CX%2=nXPwv&2-EScq9eW@f4tq`@IW*G%nu!XUXy6R6wQe^I zf^_gEwB!yMtxC1 za32mr5LUw0LXG4L;^wTr^I>5r&NdQH!c_y?C+<}4F|V!^f(A{=$n*~K3IVvMPyN1j zP>c0E(AyMp-?%BAz2H8vMxpV`t_)kv=)0Pz%;{zB(J!$GVya3rQ$BdlVo4+u`B36( zY*Nx{@Ty1osP0up2ExLJv!Ml-x{jCa%sNhZf+wNr=<9*^pOss$qV^dGOmJz9GtgVG zjB7?-3vI`&0&{#ca{wR7JZDt28mNl41J8C;UNI)v0UzkE%b_u(Bn@15k{xRR4^&ui z$zYG&jy7&nXSoB`BGcMQ;aL!O2( zKu#4iEKPRdqG%ny2csWeXF;XmM! zx2-t|F0uCw`h({WsQd$W+7DbrFvwJ5GYb?yku3=vQYO@MyhBh=2R%tQ!&%qsvhD2~ zB0XvuzxZ32ns=c>90!JSfvKO!)xF^K#K{6-pJFG0B3g)9rza&~xvWbG2_c((>bZ0u zjls88CD)uu23*|JFR6&se6KTp_QnA6(FZX);Bi{dWsp6{&b18qiVxXt@~guGMs)lc zliorj&jvP)#NLy!RmM9!G~I!fEm4N(#@Rt3Po}J_fk^ki?NvCSV1JCg-thAM>3=E3 zSndYCXhQMsQ`*eWn+rKS_ONp4n~x;yZ3_r3o8j^X%ys13F42L#1hB)olCXA&ZYdAQ zm^%Pd$8nx&gyLYh0O4m}3vy{@toY2;k{#|?k|Klje~x;mtTi?G4)8@G%DlB!yfA#2 zhABN!(Ch$qsXT+ThwEBZD;$_laS$iVmiCkj3Ia#cPG-HMAfKA;$c*$L5Q%$^XkC++ zf6b73hgTV>9d7Gm&GWczI{ig~zNiffGA)B532MMKXjAx=A)V~O+dJHP z=^6Kc>Pl*?Pk30XvzZPZxb!wgz}X^AG(xgRKbSS&T1Fr9)IjyP6pP1NCA2k5R#pJ` zXXHPPK%)=w#{L+%Y1<*D zT0dUNZQ#V8jn9Bw1TG6u)}jt;LvGt7KA4H^(<5N7 z`Qb9jJtvOfPi%swOFbxkl z#7Kdz!~&AB3mE(ezaBiSy4(W%{yIEJ4jb>(Lpek#Fl<-Zf|LI}FLzq1W17EO(R5$s!>d05eZvs33wShQ$H^#-da;cN8)mvP~ke zkF+8KAJB$DZ(V+I^<{-Tw&>EsW#aZDIKI&Dkp>PMn?c$)47m(w+FvK>w_N zHDZv&yM5k+bWczkqb+nZ{Yq|YaES{$%8H&3239;0m&z4iK*~Qqi4iyhGA?4HrQ22m zSPdr4xbRAT{DOO0`udq6!fIg0bLfu`mj`tRE&Q?Ye4J$8@RYq=#c+=YsJVM%RcmLbmsf??Duk{ z^|?Zu__z(_V)jXM(##3hU25Tp$=gs;0hCF)6b4wc-i1lW@`{98)+xCM->qGf@0Zu^ zGnl`+!}7Pm1M&q^u2Tl&aM6KP9Rj$=_+yYnxpy~_(VAMKF_yhQAl^|)nG&=m?aG0QEh^2HF4@XQPUCy z(Sh}%%jR)jse+m!u*$cu|A@G+S{2~cvOvTzj(<%^=B_Dl0%rnj0_R>K3Im*lJF1)( zN?4<9ZV4pD?v!|X-z)xi3cCRvdfaS>t$>*dYqYt-8f`rV)`8;t-zfgM)cRb6Wg0|{ zHm<@3J)}cbZhaSp8f|KdU<_|S1#~nD7EDrLA?y-z35Ni125rJbHfVqjqF{FtIKA|=JeXABF>n}R1~c6K4NpaE_lbs|Bq ze$;U4qlC3^LNuZuwA+_y^>r9{amxAIZd4QbIp2w zn#{!VGnnOPsaDMSxd`OW(vjwBS;BStq*?mmGpWuv){oLbD$}HcRECU_wpz*HF;N3d zeUy&f+h{*(0KSjXK@yXLnp#2^o(4kbj8GY&F=1{rUYHI4FjJwQVJPb5u@SVN zVJLncelrco&u_@jL)zSzpJ6Ee2zBKSY~bsBLVQAdLhqR1cQ7yV12KAlTlmkBRv_l# zz<+-9X#YIL`W$IR8bYK80b!mpK{jW{$_nq~^uC?=<=|v;=iT5R%kCe{-;L48iT_GB z=GL-l>PC1zz7gRU47_nqim|Gnm(i_jTQfFak_>jp-5$5y|A- zQV1fJXmKe7M*w}!0Ll{>Lh~{#ohQT+3%$a8-!E6#yDMLme7RGi`HO#Eb%%KvvPy=W zs*4vTnB!>eymWcFbg}Doc3hH5E_H0LQ-aYcyXH-8r_*3VzJxyidOFN`5c-_Q8g$M0 z)(|4P=?V{CFgLS;b-^&#fj(c6?$_I{9RJHIK}Cn?HP9_M~Q%r;eO(ZKidMVt}LyssxwP#OJ{j|8Cn%@ z2>!Xvk*+K+BR0+djfl7$1v`{16M9XEETR@#j2&p%h5DO;PB8&=qu@DE)q zY)Q^zeeSjL@XxFM`PZXRqm6$MjDd_>8&0C>0lH{w@7tGxDQ!*d%`dDTS0P4_Y{5XP zrM<73B<4s%_U`&Pm!yz6{y1fQf=H3||Ai(b&7?}hd-*BlklG>uDur+GCd=n$%b!F3 zyKnz|MLs_}Qw)%R!c(ZbVePz;1Z3~{RSU=qy0(S{?fS1yfQm7}VKu-|X8-C0SxjwP z)4Tt<{`sxHdyz!|Mpft#=Ot6>{YlfMxTP19U?%M|}>7J2502*@efL{y1JlFEvz}*rM_H7qZXGDtt&91H5?kXDqwL}R?w{MN9t5@A1_T`;R!^J*5Dg%!;?Z}L_4$gV;!$NxxlC12 zWuW&3IS19$P<B3>O_4EqRAVMN2wS(Gaa6fFF|lhYpEwmaw~s_4(O}65*l!!uos& zE^G*1hNX%4cmg405)y?&NkJF5wfg5(E&wp{bBS?pus;7XvQ^~Bx!0~Y2LJr)47%@z z@xMLzAFdhK8bZ4`ad78r-aNO0*vK++?br%p!+0bM#}D+>LBu}XXX|sMA0T!K-W;sY zkyHTvnD18N^P}RyTCg3YM}I?x|$E7LvSU&}R9npW<^jQb`D$;)n{8a|3Gyoso>i1l5T^cfNF3^W_lJ@f}%{Pmo zpZ}G8`T4(NI==or<8XO0??7AbK1tQxz;2%Z9l~olx7GiojoE6AYvmfiI$wQ;lZ(s4 z9AtfUg*dpUUIY%mx&3D-=w}XN|93&|%TA^nb>1q;-bDKln(rLo$iVoK>`VVyOdu$rxF zv&|fHauVX^)U!|P*0usQ`_D1j&pvJT(P7H1%?T9>2UXatEP-7iSxGBw`&~0zawoAq z_i5d@=PS_l|M`j?Q&y52IK6Mz8XxXzu9xM}4YNFMy0sHFm$egIFw5gsuAQLunouo` z4HTW0bi4ekMQLmmWDNoQVB8PCPWh+g;LO*HcgtC$sIgflk56BZhd#m|4!h4fBo+{cTCdIo^!zM?Cgf=Yfc+4 zBwTKB#b$11I2y2Slz&x;l9kEO!00aUuPURIk!hgk`oF4V$)e<+7X4S1V^LVBd2~PVe4(q35GDcrju49shROQ+UO{|$&nUm8dc%=Vq9R`dH zs3h{XOJ@*sGy{MDgBU;%0MIBFh*1=jlDY#FfCCjipzN6_I4~Hv0BIl$14AJ}a2x;t z001x`AOJuh5CYLO)M4-gvsC2LTE!f*1LjywbU@zgv00ZaO(qqj32poD2&zV4$+bE* zxJ8VN;~&{^XJ&xKgN2gfXUjQg0eCtK4akvtY@(|9$68U?*p@YiBQx6RU2&KhnB0I{ z0UJML*fzoIv1upmFj*<5u+iDA7w)lz`>e<2j5O_$fjA!<+U`B*cT6!C_0&ohL)xH5 z#%p)bje2Y_FtjCE(zBqw4D}=->5wp&qgs7?$+vQ=%A>g@kH% z7{&)=s-mlVkqF)(K?yF5aZPGJkSkqj#vk2473af>PWs#oXf5_T16Yft8=yEvx5gk^ z1Xu&*o{@vSC>vfs1`fqeD%M?@s})`C^;9$Ji#ADuYy({@$|eRr7A_nX6^DTK4-m=k zBv4laETW>TsE-Nz8PiYQLA^U)GH*l#kOl3sqO0R%V?i#Bx$Ss;~)g0+!Ponj$vS6=l<5-fTSt@~9Cmh>0OEH;S^+LEHL?*53SQ zYfc64KEDFaTzF*q7RI${`!PohFD5*(Eix$f>*@AIT6<>gg>Gveysoy^poH#4yr}}u znmVjaI-%uowYBMn)YSoQ=qczJs|B|j(G!@al0Im(&Ou2IHGFdN;zio8)0b5&Et()# zAy93o7|3S-E=*Q0rOhDQxKIyf>~gZ2{pzHc+J9{2jG4A%tj&&&3*nAOyA0=r7A9=MsjDWbDUVSPAe zw6-dvgCyZ}+g@Nc@N(_9EOY@UdMGa>G==8mtWLn|QWHeFnyz&r*xE^tIG^{eBRi@K zs-45!Z=8~LIS`C{d{9Tkmk`gX+d&<@ScHX5siv2yrKXzXLH(@2448OSnBV)iLk9ZN zP4=AO(I+3y&20R&dWd)F+% zZ(SxI%#t##p>Z)RrBsLcyv}1*6%~6~-L3GWeMfA5u@-m}_oOtCG6)53=;+}L90!%r zpBNdCvvC8XGB#rvGQf^c{^&KU+@)XS|ZHvZX^y1?hO((Vf zk^<&aqenby3F%&Xga!sTH_b8@O>~B#$GbU+X6)h&q@wp|Bu#4EO}9qFD>KfK85}TZ z!`0K8&?{UNGXzZmX__U@6VBKT2SA@7kej(lvxqeSwjH2&fXU_WKLg4NAXBEuvY3 zmB$48=FNVx+vpt>tBYn565s5Y?53Iem$l#G03#G7X+I$Svk6e@($osBze(> z@kF=fWY8k27ThjkX>BOKDPvEp8R4q;_!O}D(AgcZGqo8&ipP`t6^F6V-DZ~6%lPw# zvA(Cu_c7>s!0|m=9)-2N3jwRry5&r4=RE+-f=+v^~0j6LB*Q{87 zuy@%fMecZIuHcLsGy{hUlmFp{aH8;ItaZgTTyLClFb@E_V*NJcPt#6YmPmA*@hCHJ zN5%SzorY|9PZ;E{UPL?S6y4NnPvMmkwqjl4(>fxHBApVLfH#(dQG+jpU~U@mUI|<% z``au%Td<7*_<@8ytd__Cy12`gf3*eC zBWo;KqTw_7#-uV+@mR73z`qfzVud~l9GL%Nr1&#hMQz%*8v(NHnr0}goqE+8fMBoo zg>}HelB+fZkf-Vhc^C^$3M&0rOAmA8M(C`E-BojPrMWPV<7M1I9bmxxtgWs3G<=Ow zEL#)rR|^ZoR^cAnj!ZgfwBAU*?k3C8J53sISQE-QOJ%=inS}~4gc(bt&Fz!JOKVk9 z#(oX9=KCuHdmiLBX^)P2&3>G0U>Gez{_!E@5!f{2xubPGZ^J-uN%NRpE#U*~trgoE zZ!eyF%a0p(TdamOA!oc9VoSP|t~TaW0HIF&*6^|3yBF=cjmc1=%>jVytWQ?BXV(PN zFG&-pTmtPkOU?&vrVr575lea6c(Eu9A8+hF~(u_`>dic2Q~sWXl*@dsi%WDj`0#j-e4Q zhL5mmrNR21=CgJBP9?~%)+0y+^mK&F&?e$pIQJ!xKJ7j0|50^DThdc2PqPe`XIfR^ zGtt5nk_!@3^G1waVI)6f8FuhDIW4vT4$ydvpK=TWdFx+d2W%XX)wykmZMWiCGroZ; z&ffsd_{eCBphnpu((r>KaEOzGwUpo6eYPMPa~1_^0IOC5jyS;y#wTlk`I579`G7Nei+$Y*u4OoVJAgbbKsmzSi=>YydeC&nDM`PfQNbUf}$$(wccqWZb zH|vEs4Q)l9GZ;J?eh-)!hq_JYtPi<$2?sNHtOhK2kF4bjsTrL)16F&~C0k3+;G_-Q z+$Wa=>vV>RZvglHx!rB68NVR|S9`=QM?9ZlnhqfBe=c9Yy5m=W_-N}u3UtY-b=3_W4Xf859ZkS{IM{NMD0~|eQ??o=cGkVD$JR{q2&K`ZmBAj(- z!!5;0MRR)%U*d*f)7O)Mqhgd5fX_1JLkYecGwzNrz=DrCj+$`|adRVpB<(%z{{dElRl;-x&cdvOrm|hd?>3sb#wU=7uhr)vUw3 zwnOmOI^Ce{ZOAJcI|q$Ox#x#>dt_RX52G~1NVr<3*bVj&d}Qi2iQ_JK1h5|~gRhIo z;R>E6zP_USw4LGjG@gupzi%*%Mk|hr3ewQ zbT7sc+ioD@cPLp*-$+wZ*<^R{P&kDd8X(btxe04}21G;KS)!S{g957F6!y;89u|n` zm1RJarnK*k&FUUcTb6jfvTaLhbTMAIZ#+~?t_JZVea}oa0-DwN-a!Gx0#4r)zCeGx z3%iWwJP5%LT_mgNK;vFtCj-CCoM1k{!07{=F-OpIv$9ea-7}=|m5-dbQAN1qG$5@R zryVLH2x@0ei)$Myj>(lUZUG=GOj^E_*S2T{Y~E(C2Wq9!n;5yz!^xZ?_AqntW9b+m%`F{D4wJx&C|IFKdjnqjPS@a2u=o&oX9hJm9<}V#tz27juYHi3^g;W zmW^Q5EgwuVklGO}+<~#PYArVQ$;U}|6h>W{-3p&G8p;P6Foh=P*o1bIrdca;>koYIlu zj-6a>S7_pZ47a>+6@HMDS()m>0i*Q}B9%>RJ@=kkIE7=fYN^hc50Yci8&@h8bX%{j zi$LSb8HMozI?^j1qAK1}_!)A+swL$C>2jxKVB=aw&L?#iI;$miFk@l{y1mzKI2{8I z8Q8Q}>c;wTU=5&k7(h-1Gt}&89>UD#%LoW~vOboaiJTEkKhV`!A82)Zb$3K2xIFEc zs=&ZAebfwuOloYbPhuzW4%BK8962|`NKN!cZeyKp;(~*hu`-KeeVrRRlA(>peSF;W z$Pjy(`WUf^QcyQo9UCIO)G?ZLOL-a~t}k^Z#$H|N^Er?FGk`( z+g$0Gz6!RCRS-qz)ROH8-+TbKhOdr0a=I*kEN2fEmOP_l(}8uuFoV1g{g*W(qzu@y zzyWoDseSLE>k{RdGo~{IgDoRI3hpI?1RR|~T|0)^d2+y|2DWTvL^PhNqx&s`Cb$A! zEyDtRnzrv~PUlTOqWtT;QveutF%J~2hQY(* zPIl}nphdGu+lUg63tpe~BMz)Hk13<$069cw_--A4$DpVr?-;jumaDC%kLk0IwfsO` zJ$*;3kB2xmw@%pJKGnEib{9nnAh=s>f$_6Ot;4^15FpzmX(#+{{_zai_kB|SjLTQ? zXDl+k`^gwa-$@g&!({L-F7w|>P)%2LI}zX<_*jyk%{q6&jlh3IUJ`ndIlxNuTwtlP z8DL_h)nU5YT@I=?L6NRaYe8Y@uztGH5ER^cGu&56t z=bCCJ3IuVuXCR9w0fLnVGY{FUw0jykLq#1u$i=YZWVszwNm8yh9}k9N;WTM$pL3DV zISO3WI0d<7*vTav@ZQ^>yAn9#ef^~1c#B>)sk61x{23dw8^+Cp zirjf3w<IYKxqHPKJ}Zn zdF2_2heova7HJuv)(tNL$(qp+hcns?0za5J9Py+OAe=IH)84k2HG@{nqD=s$Ggi1k ziU;or9Ho0rMTsHxY@XHil886KLlTpV*cnosz#?ubt{LrR@_~T{(%h+~wC1KD_k>)V zjvUrhF=m(J(ROV>nfP_+zE6-bFrYX~Fh2@FU(dtsZyJ`8Ayp9&KTQs=tsMy75+V2Kh#Y zX@=P6R3s^_HJe+it^rALa|_NzHE$^+qggsFJ|dQs%(t>KPH@v@Rq&pys8wxwRwZS& zs);O@6gLrklovO#Gx9PIW;>^dUbv@w@fx+kE2wSw6!W|QrFjxT$)O4;H_~tTT~MN^ z_8<|5F_al8)VNNs9>V#Ezwmd3o*%MS2ba+6epyBP)EDi-Bmz!V3~}%>Nh1yvF(lN5 zsmx3Bf@G0mqc&s|er2vX5*_>jAob{^)}Pg_r_q3YK_cvU0K8gVtY92d_YAV7cd*$l zFH4V5j=kWgw7Qrrwtnp5X+e95Q7v}h?3S0A0n?3dZ{b!KsB{Ye0_yu~Ur%J4 zC^5qG9BsnF*BY%Z(6>pvqqDYyXI(2RwLrSMIwz53D6pEE`_$~Mu$c^q_^U^Rtr`Ky zLVl3|J`OnNK6fpE^#|Py$2Zvoe=$TLeKW@~TGV18zAWH?27lw21oM$V1f*r-oYBJe zF|vFYIWH6%{(>>wLik=5PZ}Dym%UwLa1QW>2^L+S-wRHF+CTaXM{|{LLFm+?Nt-ay z;CPXTSi{Vi;SJFIo+BgotlYo9zrz|iviQ)bo|zFZhr=8&cnAA=H@+se4x1>=CZ_mQ z$rqz+qEbna4LFV|QhD*jRYtP{^oU>PaIOeq4X}&e+G%YoYE3}{Tn-ZW*aIViCq5yW zUIK*|?}nUSD&h`GF0IsiL@<&CzknxhZLf_{!5Y)pD{_#RcG~J0zp4)9Ra$vzTI7JP z;0Ac&7!ZNjQD(6~f4|jgb4(1nh4mX=T&EwK8+hWd9C#V$i15uQhC8{M|A4>HdwT&1 za9h+CoZZ+4Mr8-pZFND);f(Rzzaoi@*1<8OcdZ%WtK;u#rOY9}F;!P6I)L>aP1M|D zxco5K7-?yIVy5G%m-Y)#^8F$v-2BZfxjRym@2D4x2*l6s|Ln7Nycd=p9L)uS#2tiO z>a>V}r%2{Q7qX%xSxD?)2Zm_7b&wk`<(l;&SqFaU5`wRch#Ft8E!(X-P9Dfe_TQwq{P-2rp%f}IVa zJ7_82uB#-YPSuQ5KA`IEUTve9APGwWi~^qmkOEqXNt?DoDko`cb><{Ege|J5M)1<5 z&5dYLtfj452PFn7=+bDL)ES~{b`06zf*5Q~+Ui`?4cQI~*4o(UEK$FIF9G{fV_WOV zDa!Y6HLb3xwJq*hN>fwCOgSEL0BCAjQxgW#-%EsDUPscO5MbT&{sHY#k zA`Y77lM`Bp5m;)|wth`DsGOLbq`{{5AXOh2GM>_pSbCB%l))tAyQmUY2CYCIkLlwRd3>73D$Fqrny?C` zxzuPiT2rh+fK1w>e!4`DijRQEFw%iYFu7?FLqOtQbdEmCMITSe>8T$&RPKk~T4F7+ z0zFtMxR8ozP34c* z81t|k<*^USpJ~6{f6OO5USp&?;0F!@%w8&H&Fgy>wVlJ{#gPiGRh6T7>DOj4lV+%;aYeyrJ$)uZ$S+w4;uV8EL1(lnu z`*#Sxl;6J{cn3Rb2)%�QqdQ`G|4@a!*Et$4BL*gmp+Z&;niZdLo7i>WSwSKUM?g;|qvXp3)Eh5L~JJc*^|g z0_sHa2!j#o38oTSAs~CgzsQ-9EM!`tA6SGz7!K$} zw7(#^ND91L%P9JuBvV? zF?{Zb0E)#e#}pjllcrk*7(T%ghQs|9=oZ`}=;s(!rrQIV;GQ2)`quvj{Bw+|=cKkI zGXirA3(~j+1$JoxRlvKK=;x_0z~$2KuU%_@+D%92&+n)ncbtBv0p~|2XT4{rs_(Eo z74}R6ZkLTE<*5yBP*p&{KRSR+bC)l8M@_!@GY-C=JH-@^oHX59Z{)yHa)(<2IQLDy zL43BMeDe5jus`GYvkjB(gak4U0ZgPR-^#bjS>N1&v1Lozh7U=2=WeAOZI%w`~zegfnz>}&rZfClleqGJMHbg$fsQme7DVAmzND2y7xTz zhP9}2YEt+^exdh_RF%y7^HSKe18{a=W5(nqv9ll6ALQC#@eEp{Mp;J%PXD#Rzu`ua zMyclS@9wQX^Qh86O`4x&5-p7mX`58~vldZ@dnSA7=dJ%_%RPk8TEyTfWQq*A#|pi+ zU9+xPmFtLu1v+Y(TbUb~o7kNfU}gvt1_lO9abMAAjbTwiX_{^tfPh7XF@a{dlRv*%%YJOnLkA#5W@ z+EjerC$6OGRCG!~1tCoaHvKdu$u!B35{rVU#4*-;&LGKVLV$n)qZm*W0B{V8)Hn#4 zbm#*VfCCynoUmyiNGKr4;AkuigaYAEm>2*90YE?~AOL^?fiM_6o+>eX(HGBRcu{Hb zy)$3C1N@EP>>g`UL=la$RisJJ?}nf5dCUja+&7R?#XzIEN^Tgm!njvh5%*saO8=Y^ zO<+qlrqW-XB;-(~ovEOM-MueQ^(2BQ++fW8S6+uT3R)(nBVIM0_1M%y8yT`&jWZTZTW-BX?qPkVUV*5I_` ziQk8&ezQNFwZc2|Qa`l;*SgR z;pahoLG%!42iSovLbBN%tk$_K^F0K{l)$E>GnX?k1J3qEoukNR$jcR2K&kZLC_ z+(pc#&Em5pZhuH&LoAa(YV%-J)Zbq>G*BaEr>s>#!OI={G-53UaLsv$M~ zS+?YHh1fKv<`SC2r$DJKQE46^Hpez3p@U&eO?UM`*c_J`gqffU^6Kq<%V4@As|+{i z7P=^TdfhnUny9r{f}Q7>A7lqFQUf>K$ymWUx;es_?$A~GqGWFM(5G|=##r=$>kc6M zN;~if4}e{iY)Hvt9=@QWiIT@siFM!|a#S&L+>OvNUvL&g$uJGJhMdH-rn(!k7uq3J z{X#R#S|N)CAWBvyh%f@!bf+^jEH;MI-|rCo?`&Y>QYGDtKwgyc*#|Z*je1y5RIwB1rCi20 zEVAou`$PJChBKhsSGs3ygLF+0W|GYzZyDEuM?Tp!|3B;@yPb+VT;2Tzc=q9vWW~Ff zkvsS%!GQmPg$M1eoR-(eb+P7r(pfXBwQMhyf&=#^KTk98w^!FFoB4ZVa2D$sgbP(B zayYI`^>N`6t;26&O%d5nY}*dsxp9RUPP#bcAKAHu6-3d3O#UIhG=p?7Xv(2<)fuoQ2WlJQ7;KmC8a6X#q`w&tbmy`=g6d4m zs*vPI;H?@j!OEQR^o;pHZ;)vpBgO)g! zdB@Awh;V%zVSCe&G6U5q7&#R?nU+oWGMUP(F$`N^ ztcWeFq%9vY_BflGDHZSdJ2?iwfWunAqFdQGQ3*U?WuI1%1#@X350uJ=hQAh=0_(<* zxHkV3k=LEU$OSWi=WNbELg39E$djB-Wmf%>#^5hfGw^ z{K9a-tEQ}G?^KFMjz+<-aBtKptleym&J@X5#S0wr1*&ASBlJdAXLCkHP zZ<*lP^c%5%+NgsCJDTnCseswN#QSLYBH@4)k^(H2Am5w7eTv+|uTgcI{b( z;s7zg0sD(D$3DNTtx)63?Zu#~`8T5=H@)`1F%m45tsG82OZ=PhlK5~;pipKDKKbjb z9oO2_fjwPLD|9;HUrKGxC+Kvu5~cP6N;&*#g!UD^1^^ti(G*-sb}OII0C_-$zfqrm z2LxvFVyQj@B%=(r@_+_8j!Ap#A_S}{?z`hIW+zrY&blYp zmRB56Fv|V>)vrqmXlM-GZ6SQ#>3Qd~bLX?}r$sVF7)}P5Xyh1$8DNz4TwVh~3Zg*o zP$;0+HHs7|alJMsE1mH+TM$+JXiVM09J~1`;6ooMSZ#M59QrOZH#7=6bb|$zI6fT?P5HsV_9!SWFz))+ zeyqutF(wqYF(&k8uWzfE&`u^cPn+p?!*00&RGV*q?^Ywnfl|=`@XI4Ihl^gDu z;)u$O$vd31Q~tym-|LG}%|U0dSUEK!R)6KH`(krd4)nmyGe@nq`1W_;K|0SNFjkIt zL~DHg$sK3sh#Q`{>h7rz67Dv3ykI!kow!Sici>SCSi!t0eexX_`5mBuS^0%<6Ef6u zeoP(oe#szM2LYDCG>Eq4=PPu#S^42F<~Q~i`CZ+#d(0;$;&i1aM|(+N;;MTK4bHPp zOE2cPc^aO0Us|wpGI?70$aBpU6aI97D^4y>I726yE#Qt`jt1zySTD1IJv;W%zC)q7 zAiiS^fJl@hQs9h8?!>|12jpL9$Spy?dB!b2e?E=-aM5_&68SDQugC>G`2IQ0 zGs4d zIwH3N3$EP=xgHpg9{Su7hqEILMHoc4L;2*kLc=)35;X%@ZFg|3+~H=L+$F+F9^!UX zynWGGJ#dTi46)g^EU}=~)^Z8mTAYa;l+tKk9sU|){{i817;o=DUvNOsURZM=>X<_%JHnuRA28Q4KyGa}vQ_{&)jw%| zf=FqVC+IGbwZ(sN?Bz%EvVF!j@Y30GyVG1?itYQh#DGU)~ zvVxS--T;)wS;NRDtk?p09E$58JLIT;u(%tclYIdT9%i8-#PbE@u4T#3@ckBVQXbx6 z;!duB8oqpVwSaRPX41z^c(uZ%zzxAfgrsFHe^C-;A}XlfCZ&ay;Ne9QS;KcSV0%oO z{0*vep=FWX;UZ!38~8Jf&F4VV0Q6al}Q6*&bQs=qe2OCvN{%s}Fv*}u7DYU<8E zc0br{Y*i0vSGh{KFS-NLE9HBSzMSkxmYd7u=xqT;CGi1OKVkdc{vhH32)P-Y@7zsI z*G|^o9xnfuhJ-HqkcIq!Ey1)32cRP2`+U@w()&8p&ca}X72VYpb-Bbk>xmVWvpZOc z>HAn7IspG~)IO$&v@)^ALM8F8CAhY#Vh~9Dxg9CDRwkkyQdDnTw<^7yC3tugeD?cU z%th;e8P?%E{RCyt|4Zb-y~s)hV`S&E##pXha{poF?N~ORFs5e76xl%Wjt3E9Vh}sJ zG!c2623KKIk0!%L6w@97O_?Ibk*}OO9@Ix6`6zCS3W|N(!xz#UQQS{hfQpNO+PLfjwoOs-O-T;EeE!W0w!&!pY8LR7%-{CMf9c!5xX53Z#xcMG zq+@bN0@?*1*Y*lLWqBZ-$GA9S+XiFU-y+(AMNWpDK72^%Yyw8mlNoJJOpZ@PFlfWy4O~aZ> zbu8GHcLFqtHNL_;W8o>~UoD|F7Ua~LBFVs(((ZvQsq4c{!`Uy42M=lg(*8{PCc_MD zvy|w`2N$E-DW3%;5hs$<8aQ;{nwbNh4D6oE&<#X~xwe@ePX7epJKTVFdy&EH2+QZ; zK#Uh;*}#qxfIHZMP*=Cd?7a}DpOiq;6@t&QKtg;xQ%H0zvq%szP;ufErCZX@4Fx8_KpcJ zVFnYDBaN6-`2N)OOQ$_WV&YJoLD=311}>9{rVPPsL+<8yBo#A-Advvkorsw0^?Mq@ z5neF7KIDyMJ*eYF0u~MdtqS(`bubCC2DgVti%V?c#_H}0K|EFw9751CG50DM40)94 z?i3Z!vR8yT5@tkyPWGY&u2ZdokwlaE$9Rxkm`vhXSVeTP*aO;)b~GrTNXT>^a2@eu z90plv9(Rt4I`Cp+&OeMeonO#)S2=HsW#ZL1X)DF2TdklHrR3RzJgvPq`PqM;>GNHMb*%cE-XxMcUd8 z(N}xyr;gUK2^%tClu#X%iN1D(hhIbM0bG^tpk`%;_Htb`fN(0wGsG+bXYdpc7-0Gi zsz$6C{#Ep^xE9(~|20rY;~7vqpr?i#h}*{vc(B7Fg_MHNR7Sf5>*fsSkO5HrunfwQ z${?BDMmg~Bw7egA}7Vb!c@@Jz8ZnAg@?d|8auUwOW_!RRS3hz2Awc|QWK>7&!Ry_+ zaF%;<9epk?2Ws{pyS1L_Jr=jt!+x0vbKm|l4)X-8HhLh$EPGB5^vcb#pn5@-|2k1S z!)`l1izlc z=YjE5R?b@00^iKlT$pE6n~DT=$beQiJ3!=r+9C0nC1v7g|63?x?WWz*xUx<{5xW8N34^Ax469c}`YIZ~ZuS2Ks^l zLhoC-K6Y%C6L`+BMIHbgBhQFkkXF=;bE$y<7C&vjvjO89;`8u_i(uGuMW1*Mu%xFTXw!ej5j;5O_TQ= zp1fl+KnP_;P>ec}No*B(Q0~9?wHZv!4y83bPv8x6q{T{H|Kqes)=o{kG$v~!dVO@> zZw# zm(=BM)wBwc@RRm|9u-`KW!s>U=^r7hw`TqY7d)hb3-vIq?f=Sd78R*j_=W>KYw<6Mc)8J zIeU(OUV1S#gKEi8n?7AXeKZoL%2#>ku1tG7SVu?K3%UUwuv$u`3>A& z>W=yD(>2PtgP0WL7NTvbN2nBrf0dvprJt|3)gT3fm<79+q8uwK%MsZ()C z@#V!K#TRu3GGSaUtm}NDtg6z0N3@QvjkeC?kS?l&N|oG#_s?Un>s%C!3oN|aL}G1@ z0I&K5tsGv!%)J^sebNm-0=Runbs81b)s8tYR5=`}vhD&zoEJIZ2jE25_QtyIzw0n9 z56U1e?I04$y-hlFZ5l?UM-;to-byzV>7$%NIN|hr#yBx=P@W2mp5j9 z^NX%vl5pD>I0N0aEN7b5G3ILe~3`T{X6s|{pdm_3*Vj+El5-_ z0E=9e6m231rs4&#B|;Imt3nBPKl|OMii$GF9Bg&F)26&hy~2N=p-xFtkwn^kqThp> zEc@L@{XRog{ugsV@$j%DhG4kMI#y+D%2-;kFVXz6>M&@jwnK{|L`c?3u-|E@QSw=* z5&eGS_}c{gTJFEoP`@L6T#`F}hQSzGKKr3{ci8X3Ft;pD*I>L&Jb@DL{C;O)gz}^h z-Z|=b7RD#pZ0LJWnm+U2g<;=W7=c7A{)E5~?U*|TWz4M42e`TNEyw1|y>k0ivNE^^ zev2;4$Xf7g-=ZILHkQX6c`Z>u*&YJDJhlx?=Qlna#W8Y{2mncMHl@?`F+OF3lNlj#saaIs53wY z?p6!jqEV0c`%wL2vuF5y7;OR|)rWOOl-r{vQQk@ks5(&@>#Y96Cgn>yEY zG_6Fk6NR-&$5pJPW4(g+s&wTRmG)Ju?&4JvM^RmgLn@BuU!}#h|Gq+qBRkM{luo(- zj${13LU`lHfW897jwLeu@qf&TA(Em5o^!~URq(?BvTm4>;q$n zj5QT>=+nYmlr3DWNLP*axM+cFd0O-!lRG^;$W@1D2bl_YbdWhmM;P|6rp3i6!kn~! zHOvau3jFt}uw@R8@_Pk%ufN#ef(QLR6{f!^xaw0Vm;l3G%NrjTOPr!1+NB-mC)bAP zDc7``?7urjvrTf_0Btf&3$J=fFk7YC3IDUoearug_x}1|y}mtHU+w9&I>~?c(JZ59 z#`v#(vYFIud1lJA|4GeNAHjZ~I+n?UQomR5>Jt7tkLLHOV-5{4^eHI>+NG$cCCxH8 zmiGrFiV8s&Gy&{^P4yY}I}#MH>MdH8cg+~QyJr0VJ#R4*RK3e%7I?Q%{f-13lkHL- znyC(97(-65oX3uVEkg+m>zagrFn=(om{NU2TBQ3V!~T{MjrwX^o_l=dBoDF_P|yPk zUdfId>M2U|x0B{S=l(g0_qUYjZ?a<$IYL`XnFjW96f=t1gZZ??(?I4ZCpdL725IEy zp3y1R(FCteI$R|kYr9vaWKn6a>Mo{2MHL5&u_bdT^BHQ8DirfnhENd9VWdGawp{)~ z{q2JVl97VYZnb=X_qPu=1@ijeQbgMa`y`WwWgh|KgW)KnQxj0tY8Pz&l&$|Sr1{{= zcYa{7Dyw7SxRnBj?^bp(^ofJRcnhk9j|*7mRoE*?kBb&=vqsA;f+9xHqy$9kY6p<4 zEiNUV7CmRag?D;**uUdi)x|@HX9vg4ZGGXD?{^D#bW*=z%9GUJU&k$|935dFtCjhU z7e|=$A4h9qZltPNTU<&xID9JeYt4eW(EI!A$i%r(vFEPP{2fB`ISTbT)Bk1?{rzL|OrF>8-T{&y>A zJjQO#dh5Si8O7MeSXfze@ZYQO>S8gm{$jsZLFvTQ!LS~I{a%F^t)p{YodWya%2)(L z7j@FMT5B!}MmJ%nV_B{ioZkY(^85BXg3$R;T%+>}M6&1mp z9sbUta+oa%$4v*9A9;W0P@QaC{kGZiCC%SVFLx$+d;HDxuFkiL{k_DMu)mZ4JBJm~ zY9sS_@U<~Bzd@O=S8K$~l`QM(Y+K861$LGlsa;tEu0b^?m1<>8Ep_7TDr#10Cw1q2(wFsLz}K4Z-_6eTz37b!`Y@xhzqLjKFng z#39@|P1sP}BvDmeC}k_#uVzr580EB>|2Nq2Nj7W#R?>XE;@^4pzgvj@20Py5DX?3J z4{*=iY}S`Sew!`RC_gal0{L&`2P01{sgL&CQ#(k3|r|9Y$gE~Gw3dVz+XJ?JqZu?{-e zg0<8*P`!? zummPi*6fd%AOH6WR%)sS=2BA6ci86vig&2=ur-Vh8FVC31Po&tKo9_601dS)>X16S z0~CM*8#GR?77h{&1~f_%3WOn1Ko}$j000003?tZ z&S@)=b|*Mu%30NpSpDP*zdI1)0In89-n^jRS};w_XzLh8xfBq4Vs`XPwF&IEwi^3NP_X6WAj%V=h$K;Ph2L?sw%|K(#Xe&YZkYJeBlsnn_!u)@eD|POC zCQ8~CwALA@hk%m5n%IxtRBS~JPCKs&+$~b7e!Yi%!8hf?z^Ql3i_Cm*GN=J-!n+wX zI?273+^?(KizN}b#2g{6*n!S0OLCWYM}F01x-8LjN+O_5e@F4cgAPmUX?8Rsd`_L! zWQ>-zI3O2=aBH|$FowjGM4+D}v1(-ULw}4lBUXSZ^lHVbLobw7um-gUgP+s=%bL5$ zMNxp3orm(m9~1B$OU_x)K~rcs1k{?3YrSNJghVcCVaG(V$vggwYhEdjkz&5xnd5t6 zYu~!sMgzGhC^F0d)EZ`K$IQ1{I>fo*N9rZot~>}+8_P3v;V++dT=i~g3WPbl?RZcz zF#ZK8F+z--0jtStr5ybZB2@<}(HXXFY5A3eHA7WvxFnm3-iv|vI>Q#tTA5hY24Tjh7G{JN%NU4ug*iZn0X+o$XJyakltoBnZfKX(_A$YK?wY0tXk!0dkQACBMVO z2JIYx4G)QFy^X^h+WJjr|Lk)L8D&K&#T?8RM;UXSl?^BrmHdy z-6GC1nR$k*X>t#Gt{2fAv`o2$wd@D5eKBe-ub9ydKlW z5z|-=PLFz8B**3Pg-c~VhnZ(q?yGxI7(M_$*e1~#+H7$%4%z{8*RW=McY-xO%#N{n zG4S4yc{R`3>rm(xd4GIYb1V=XdQ;>8lqMUVb%PGpRq*?V0(eLH3Yj+>;aERu+H&Fb z*(+3;*!-sc!ooO-=omP_f8{GU=HeQOFqOBb>q2ytw%7BlXcsX2o*a3GZ^e5+IuLfRQ>9ng+Z^)n(`1O9nR zi&*imEpqQ{ke|{zg|tH)_93lBBxK>CMLY0QTFWM&Q@2?z(aB$P3G6Bv_fj zse0gSF!ZdVjv>~7YjCqULlfLz4oo-@&Um}-%_o-4obka+2v29Mzz4RwKm}LhMi{JX zw5q%K0K~cBW0q0XE2&!>q4tiKZv=C$@bMR#5zbu=x;&}q@iql2l69n{NGt?B3El|C z%K#8A0JF^PG5{fqj|c8Q@(i_p?baI@rj1asm*;2WQ}gQ~*|eXc2UIrlj&^Xu!#D>-+ToR5GKEMme zGu(9|r2Yej9gBT;p9Di7}v>#;d=0yyA zu`^pSwnw!#0tJE1Uz6uATN0|YvB^7`PFhY6$!`AK&3z+uHZeB!LNG6a;|0J5kN*B6 zSQiaLZ=pNPh|PW5*On>5&2%@?Zeom7kY^wb4GFvaF!(VpQEIZR8vyZm8E7dtL- zx&rZ$j8`Y=Km}!3nGTUC**Ls=bhH-#ra3bVY+&s%;yn&yaa-!G*J0m6$8L|;D%HAk z@HPWroR7x`{(^(Y(HjY>*K8H&Ns(<*JJ7zJk_3svOP|BkXz?VIu2N*XBIwmvz^K?M zcid}x);mz_ta%BT9Z{}Fae`W@oo=6Nfjek=hT#pkA~9`S9azQ2ROA_uz`#i!%vq2f znI;AEVWzh0fyd;r2)2i{C2-xi*&yB_OdXI7_m$tu)g}z<3?-b~!Qis&=l7=>hLTAL z3#sjsbC{{fGrr>CtSx>%wCaR0b!R$;941`?N)HHQIO9ra1K@WTk^^&Q`@u%%j6^Tc z)7btrXFKFoJ+yeZFx8TXrWuhNLJHJ4upM&i6#~I*NHZ`frq!}dF?rQ^xE*6za#&%WAe%H#&yx|%mnIX0ecotPj-m%=b z9!23Ssmx1>=bn=&&5zb;Fal0cnqjy@)EJa!@x0nNqOF&2Yine+qDDR-?IwR0INba2@lOc z_3ni-IRHKwJcG(wPD7U;dY^G1Qha}g*n)EGsWBdfUtpq`aYnJ;Q1~OJfr54Rj2^&x z6n}>DVjv#d?~q_@Nza10kK|8a&RQxa6XI;yr-lADx)Nlljv_IdE|+-D~pmjw%|O_I5zzeXhwf z7)xqsw4~+F$kz^#{Pf+cp=V*wXZ3Z-CqDT}Zdu7SXZuO08k$6;go>meICizP-Af?F zn)M1evS_6TmE?<@ypM*?+Z!q%%Ln%KGf-8w0TVM~Z&E@=uTf|>)eYVvjg?01t<(3- z`Nsz@=0rSEu@j<>)%oIh2#ZoTH`CBUD30v`W$0{P3`)}rfcS7-Lt=D5b6>Zsp@C}- z%p<9}LU=!|MdhmC061dCEdL7nu*Sgpo-liu_zWOhT+EU^Ly|{NybL58Gse33La1nk z$4U#i22|E)&)2`^5uv@XCeaHk@1ZsLjPHDpuD$MaI3TjG!PU?N3C0enz30Hg9$^2H z_wH2<&B>fH!`hKs<^6(RX8`PrjmzNT*TvZ3CbbEl8e_VS?F2A0#&oykIQ@>@#ZDzp4`}iC)fSvD}v85mQ zaqvXq@*<$F-kHGzkbC@c%s}=WYlgPK#`vY+@*BRh@}u?PjGx($4Fmo?YCrizXW10K z0rMkpF0PAh91^A}Z*NXzqaFp1J>K-wc%Mfc}2C z-C@;?8*RXH-`w44WyXneKz6Uet@R?=XUA#Vv;#F3JfQw2w~GUV%p2&TDNnf_RojZh z0UPX-`SqENp5uc2|HpU5KRMqnu_1LlQmyN@IM-uU>Q1_IjM?!~K(9LZl=NuK_5*K@ z$6il4_|q-}M9SurR*86q*Dklr%IpKr0YVW>p3x4DJ)c9l4~hSkvYlaD4|oDLe}4zu z91x1M27#^%3mUj1&K=!B4{U1Bik$Fi4ztDp$vp{di{UX*;1!oeuShiG>)24Xfd<4JY*3*7vS zn0DXP3 zonw%q)YfAMxM*_3-J#SDMAmeO?Gk<_vrf4<1AhG74Rnu@%)!$He8C5`_E7p|u- zc?Y3!!A|C(Zz6OLk(F}YlnJ+=ZW#KwRyGfTL*Kasj@^OEYRw1V-BDEt7T&yEjmr&h zQVr)FTznXccHCAl;Ieq!8;NjtxP^M6NGlGoCd{BE^JYjCqEdFaS@Kfpb}oRc(Z}`r z^LMl?N*b0gGM%wpZ?DUi4)HIQQ|#tA#^6Z-bQ& z+n(bNNPebc#d8VNeM1kE-s5)v!koO!>xKR8d4`c;MeU~ngO?@z+4tI*7+U3 zH6j4EEW1^QFm>_VBd_k7gJ9em;1-?+<0KB$+POQN#*k;Y;nZQrnz^hx1jxD;z55n^ zLGs8Uy++s%AbBSPB6|^&H0~{B$kXy1R_;E-9m5P>z}X?fWo|#h@=d(e6gdSQM?HSM zTYe`7{{Vnb*|pDmU@#X)=U(4nk$%j$+)Q`Rkil4@FO#?#oYV021vwPVoe7+q8cKVq zo4Fmxd5BLH&C4=i*8~0|?Ip;znR3grh)Y(`MrFN<708P35G?oyA$)%Bu#}u+=!o^e ztHQYyK$%5&79cXu1J2V@i_xxs*pzVmyn`5JAc+LV zt3jTTsL66pMwnTo#_!O>3X2!|B_c^P8lk8S46nd=n3ey7PUY_9j%uzBu~19Wa14oL z$O_LaFdl8pQP{sfj&>(FTzAeTUi@lrZC*#T-Vhj1LWXOK&ZLc8@?KzgvP>~qPa`N; zL=#94<6l(=?ilw_u|OLf*lq;Iv$aAybdnFL6V%s}PhG2nufMecZX5!c6PG^70)Tvn zUZ}8m)j8rPzo1YB#$&Jer8llL+!#=9L|?5xj(o%pnX)Pp1-9HmnZMwH0^?ybXzzdH zJ>>}26F*RlbKlp*qhPJ!@I0dezbr7`&*SKWhaQvOMbM+)jzRNfod|?HF@#rEhAquK z+}rKbgIgdxq}w*{YRo;cCv-U%Zl7z5D-QSBg~uzm`-?*z#KAlfF(E9TcNoe+U7)@k zE6ZAMkeJcC0iKPT26TX7)*jbk1?}B^hWUbdXksMfa7HAPfriKfN>;Vv7-nQU8;-`b zLx&wfBol=tmvtUcW=b)NH`aF}a^Y88_d_nu%qUjoCxxB#L*B9tflN+abe(;qlJeXv zF!5-OWpQ+4uuX>;js^|I zOedcb8GW{)q>RlqXDa#kr>=NZnXksopo`0PCsbSJ4t$k9Ej3}Vyfg5C<%2XbAm!~K>1 zwbEkZCyjKY@Tjs-qdFo+&_~>)1=e4r&n^R*63Pqc>|4rq(gRz=qe{&%v{grC(sZO< zaafo@LtCT}FDBA7w$iN&&BeLxpqRUZ7Q0E|i;Qo6P9l>4k%h>*in!iEkMt={)TaMy z7`|sz@-8R6zl9{pu%T~hb4~=UbO2gMP!LU!7IF^d44KDNK}KNMDTHI$a=0E9>%1&V zz}1BWFFGxn{QjC!c^g38sW|?5HSdMP685SSwbOjCOry(0hK1dj6yPOmq4y zJMx?mgG_T#gz9QyqW>nGT&DY6J6`3Q?eomX^91d42kqzD@$)REAS{_{ONx3}- z8A_*$PRy0sXKQc8(%NSSw9iRIu{DlFVF_DXKq6^H!)p0BKFt!FRT@=tb|prB)IQ5& zsgzW0&ZK+xC`wmRZ60s3@ofI7qt^U~^=y7Fb(}(xOi9tuIX^jEz-~V1NTdy^sy5Zg zW4h0{qwRsJJ~(Sz<#7n;jjC16X*M_L47E|!8k?DHR+H;|_A@myB2r!!HzS{EKjXw? zWHU1|GBFuv`;6n`d4Tr0gs9KB<7b?hfMrw0NxkU3XG0;~ntS8M=%6@ZZW_Mf0`tP- z9e8os?P4wmZfMJa*zF_`Ye{3476QG$vh^gulBPyDM*FOYXKyU$c>-wRrhiz+1HnQb z8!N&94;U8!lU~i0bn_OnXKDUdOs&(U`Ki+VWy%X%DpQ?QhNUQ2STa4ol3;PnSr|P_ z^Il+ItL@8+5C8cK-Lo|RJjp#C+@PqpL2I~xh7Cn1`g*OqA`Q9oJ+cyM*yZiC?udx8 z&)ewV-v5jBpNYNCJNAljA|&q^kR&1o2zCacp&D@vR|pys`v21i(}0A6dWtXt_9qCa zzhOEbpdaHqrGI?(esNsz(LCOJgrhG&;q>cryTJBz?73#9*k_-Ow_xKR?(m2T;fgw5^XP9rvTCl{|Pa;nZxsd}avhW`AtpGQH4QT+Ur@+hF$^a#*ewG3AtMY%{{bwljbFr^VCdpjnNms`W|Ns9g zM4kmF2w zVV|-}+By{uhg5rbcA-#c`fP2ra@A#0q)1`LY@O9#ycj!}?z>CbkL5dnp^sH2EZwxmg>IU^Y`2tkq~X%6EM zbQ0eafIxx+$52C15D19NK?uVz7z05FLXaQ`h6o8EMiGh(KlNs@g@x+D87*J4I~W^g zcO^TS9_RSns*j3-fV;@P{)bRee22uwJEpdi3Zzt*sGMXfebA1#xz<$6f{M(lJ8k(C zM=EE6LIHoK%dM3UDqvh|wsU~XemkJct7x8~_*9J<(8aC2W~tz%GH$m$!m43TPAvr$ z-?;^@Wn-?mpu>9f-RSi_;w>dVH~*c$a0z~bgHS`DS2kM3IJI+f;BJW4gRLCBM!tsf zWGPlCi8K$WGOJYMuwKjMOumNV-%0yBS>>4&u<)<;>!b`<#yxSQi;8RU;t*t1E(p@7 z=e(<0iRaEMm6u>L8{=e<68Cn4bvq+pJzj&X%~)DD4tfHQ4~UG~wj@}#iW2Hj3$wFV z>_$r_=m4fruWjq2+K1%}DEK?UzOQ`2lqp}?g!v^PF)MKF6bKIC#0l_k2$VN@_HD}P ziX-2^wA@sJ>)sDRZb*7zmQ$~hS+93EFRmm2e{D?}kXgfyz^S(g-_&L@Vq$CF*xg})&a)a ze%x;e!REAutwVVe)*6%3wg}F&n$*}w<>&S+8gxxA7Uo5tj_bARgD6!@T;hwM^R;=iUf@n4xMr2xlE_L-FMsPjo)f%9RF_6XgR_FJJ_E-;V7N{kPeZ+ za7raf5UaAGGQk~?%$aW-UdC}e)Mu+b#JJkm&&jP=974xr`KSnaUAdv>v|FEa+-CZ}?4hRRDs^M6 zihfcf_yH`z*l5po#ahvt6lU;)L3sW$Ye#8#G>xUD@hmFVc=P}R&WVcW(L+j!+cXF% zdtX~PeSH8Zf3Mt&Y3*@JB5e>h!PKWAXPiTJbf6tWE9%SN8wPHj|FxTf&8&7n9ZM^Z zCK9kU77=sV8#R7KzBB;I-Nw3pLJE$9Tjv$JX>pdJDW zABKmE={(s~eR3zm_7%383ISTiYOFeFHA>W~0U>zZCh;fb%5H)qKERmP-HF;Hh()@CVvsfa3H3D4kK;Qc2Ie`hbtS${1&OEmcyKD?2dbXknJi*_8`| zn@J5P zvssXCp_>c^%yn0>OiYiEnzTI(%aCB1_Cx_Rp#D69*Y0smde_c#%zD~^li&FgwdcSX z_CmN9;ZX0(YQbE4==?bZuJAlVA&{xHwM!HZzq;;O^+8buw zH9BOh>r{i3MpEV%_;<~&cHwxPL1M4U=&O&XLbik8*K?`l%ij6zy!gE(>C|}#&~DbL z@ZKiSd8F@28^agWpX($abgjrIQx}s9+y>*;a_vw_a6N*C>|{YH&CTw-#Sr`{s(&^E=j9Fl zAulqE;O9s;l3r#UUn}v`>B#K64kC!~`JW9OgY+HLQ2xL%WOlWJFFX6c6?!+LR5&al zvvSQDlUhaVys-5>x1RQY226|~GAndMCThbY89B0nUiWuJ96Qbs zgH^hjt_gp}uO|@i8gMy0o)MgJ>lW&f+8n6NOmVuAkTTj37Ag5dm#Lb0WLG{?*rU*PagVLrEhj8 z?kKMiG~X`tPyy5Fmg~i{NNuA}NvqvW~~dgMXlHDA34K1Qv)OpD#9c|Uj08CFW$4T1r!a?GAZKNv+2}xeHR^O zcotVM#I+p|@u&yJ4AT0FhzKnQRD9wASV_O)Dw?w^#a{`iyi~4X(c8a-DJXgs^kJ)Uy82`x? z+gR$m!5ZuMr+N&=4RSkG>%Q47)ZB+&wXC#UaK}{YxWs3)n)X1p*KQe?)>B8Cp2{Ae z8ix|)?Yb%SzG65BHj~LSXuq1#QYmEKVmSx%kt~nx14l!4@(v#UO6Sl_a^T%^8Eb}U z{Z2#~E}^)=Zw!ciDt} zGnC^2&-8vsGwJ-gkK*j+8waf-CH_8VeP!M3M#90F(N%si8gkeT%hYOgwY=}|^F$JKwY+anwG~#(-MZguQw?j;5P?KPoq}zxRj$+) zEd&p_*0xFwVE`&1ox%g$>})`WxJwi?N-&V`!Qk*Hath?(!_^hi%zfgb2-sIY8>qbe*>t#DMKT4hWlVcKgH zM{)$lh*o-_7xQR9@6)~w9KUVy86vd6T-eo6li)NoTu7oquqJ%+qv1A4ID}D(r_V3Zmh|TH3M^`bcNpiO0ML#!`A5Hv=B^%D48vTUTaGk zj<8J&%dl*PqpA!?jSD|b3(HW1-Di$yd4b+ro+Qx%daVfn+ol4xodvc{fR`su#mf`V z^76#h7=FPoe1+c^s!DD{!L}CYwI0SucVFWr@A&F-rDESMoU#Sha)Hkr*~ZoV!f`9_ z7mBDd497`w+(s$Na2)hL@S@(zYrd9`C0wazqROdZOa(^KcQoOLO_1zb2 zYjyXkU>oSQS}ySMmR`#RPUF#dC>n2ad*%q|eO!#|ys;$Lz>UR$8;cV)(EDh-k;bF( z$P2bUZ!1O8LjrCr&UL>nF_;D`H55tXje1;d-sB}iacgNMdB<;ab==0Ku8O4DQeT*Q zX&rbcFKoNJC3j1$yJ4!ks0)TE6lzonyI^Xv1aE6~wbB)qE-5t7(?BUOMlQMCsVH4i zlrAZ#$O1}%G4g%k*lpt$SZmz0*0^b{anoAkR(j)Qfu6UOmxY?_#!Xvoq)RKu?Z^uB zL=yFFd9bYodNmj9F6p`hz1B;6{nAz!gn``>cFS^Wg`8J@u2ySPl~?6`uv>0pIJc?F zaTCk%tt2l!E5=J|o#%43wsED2mwatCs8z0%_eZp7H};8lo(Kz5;x^X6!c^&LsxMW- z7$HK7CL?ZBP^~cpLvIh1Qify91Es+3w{bFyt&m9=MXKvA$uL}^Vxrmuy(y|IdNpIY ztL~m6L+*~_eT5~rmE2a6TX|ceizW;|?TSm1-4~)3FS(_uO@{(ZakzRK{Pn86`Vt8xRt|w~ZR%+LC zaVqVWF0mDIAsDta&!xS>)}^-E#tz(4AxFb)BRINB?TX&VeJkx-g%=FBbldGpFExgw zrV2Z7Pu#TfeyOeGJTV;0kn|i~1z3~c+g7@zTSA&K8l*!?7+nJf2n68>j#rWRe$8~n?rQYl8oG0(+e%{lA6pqE*OGs&eFvYEuZK|bq zZntvUE;yd;cIlrf^gUe@HeI(stg(K7gk1Ds}# z?KT!>25b;CuvQjy5$KE7;?6h64Wu6%y0`uqXP8+*q$7#;l%EMONt4zev84I%$tGzX z@;stI1pVA?AOD~(z;FE+EnOG*>6`P`cVkAde%rvjbOCv2t*6r2cC*yH37S6$=Dgh7 zIWR>bz{B1+mK{Sng2pF7 zEiw}7mNyz%)d5kw74wef0zRKe^UeJj_1>BwME?MKXHhCzC`B z-?^)E&fZ#k%JwS4nbvR}6ZD}b7M#T*|Jhc6^{}(Cg*~o#4=)UBy~47Co+Lc99N0hV zTc{luPnIsBNWd(#WoBJBj`%?`lVL_Qtz*Tf&srvxc^e>I5P4tktM7z0kEF!;_e6j%6bs z?~porW`ndtmPU9udJSeCX}@DljU z4qbpgvkP@nc4lPhkS{$-ayT?9=Fw&ghP|@|j6=v;>!9x3HFC9baBL=X#;p$4lz4Z^ zKa9V^33W5jAgDTJr4HYLg~DkOpk8+6NVY4DDWDrs=1aTGd*znQtm+$Z^sdksOyz%e zsRXc37jc}%5?z^#p3)ZE(XlHuX*VGf*iN`%x1+;yL;?G&%#FvMqDT_Yp;|qr=qiJH z5~-kJ2$Y?mA>-~T%5rpp{w(C(C!-MUHs0~oIqI`5>g`cddM$EQmsX#eku7M{pT_W{ zqx8E|TFa$f)j2G%AUapfUzb6^LBH;~@F;^r%#{CYk8+C3IR0zJ@>5K2Zi?PIxIh?( zJHt7^f;4@It-x$Gzi}Y=LtLjg{2_{O8Cf}cb5Cbstb?0fV7Ok;EaY?Pb-O!$#%{IE z=~6ZN@qR=>3@44U52!WC26fMiE+KV=y ztuFb;cA=7q0vIxJ=5`hy{6RV`%_v58cJ5GJxn=2tBK1%b ziOe>YqZcy>s4-rj69pN>ndy3Nd>it;JW0w!+i=AmNgkyU+z3IV$Q{fBCuhdM>qJ*t zFQj+s#!xEY?Zu}cc%`KUDp>7#q`d1ARlihVhxDLB2-|C9?ew=YyDVYjD40Fga(yWx z>+6v0_o~x_s^(NdgEVf#G{M@bhiR)ge}a(@i@@kP%ya$7f8!veCL?~fbAD%6^3bxX z)AXxtot6&)2k3d@YG0zDg5UO7Z43ItC8*2)0we!+zkMqQkSXYK8qdMZ5J)mMG^EZS zH2TRZqzLkkqn~qWJa9B4UT_#9hXS*Nbkvu{as>|xwPZoO6N}N0)+>m(YxQHwnVYrSM4=x{vaLtRp5bgQvT=RMXe1=i9_*Sj#7)Ot$tFA+bmFmL7zMj zOM&LbZC?F~67SCvLGeALBMdZf_orQ{OmX2NoV`g=?=QOh=zwsPG}J+C-6H6jXHdLB zdmn~8v}~BDr5;wZJamc<>Xb|(DCQ#P+_o_eiGY24Q?lREX~FHp9Y_6P3bd$oi7xOi zbDD`-*$RP$bl8IQy*}>+655E=If0n3%v)y-WtHh1G(O|KmUFLpK+1}je=6a39S!=AQwfOJ8`WIY2 z-rMHho8|sx?TLel&^Zs6q=Z%pCkaa~r$^N`0qTNl!d?ZH9NOw>j?NY`6th@Ezf z;;TB%5Fxsbexo4Cs#@zw_S8}eFbp4v?ItF5okA=dy2Cj74JH= ziGPL!nFzKn-NW}LAs>w*HQ~At1{;QINV|(fQo^ULhf8wOg6yG!!7yi$^WSd<63RKVbi{ZtoE|u zYD%dCKY=f%X+g}ejqkDGWWa=duT}J|!LL*ARar}3{uiVOU&m+ebiMORd_m*NX^1L0 z-gbe;Bd6U6t=|)`nFi}Sh;?e`TqKvsLcxh#Qc@uX7BHuVGRsUtrAfK`(gI^Y3;9=v z*43dIi09@>=c405AQlNEuKQiMMf8UYOi@N|?kOD&9wfKUeu-%iQgAW}LUc-rw6-Lg zxn0NRp2|=SS1FlhZdp1e{3tGn;XTR`++;;Pf1h^c05c2~Y)g!nDL{>PKVvc>Kyko8CgVkQ5Wvk zMa((lNSU2rJo3H&II?rYDRy1N%2rI>oGKW)8Wv@thIf0PVOVA<^Dh1cgy#Dii02?o z+bpmOA%ssWA5H9d;S-Swsu!jt{4!F24 zInk{;ua&2+Eworyo&oCVz<(VWv}z|vb!F#>PvnkmC-j{qZM}u25k%H?2B=dMT=C!9e!f|nPZ^QGlJ#k*0R6d;BQfm9 zY74a8bgAR4isji)yXEIWzPf=M^QU*~+TK+QGq+f>lt0YO zx@Wb+o>o;WIGpxX-^ROhD_Hdc#id;r*qX?B(2HBxuBFs7DXWqPUOZhWYTAS89u)ov zo%KHRnj^w8YGvVa!ObcAs5A3^iLk2Kwr&o_09|lw6^o?{tfDfU%a6I|*_Waq778~+ z@hT}tzP*pxxjR@}CXPqWpBSN@Z;ucFkK~MAxsGz=NP099#t#kXTHG&Fn|baDw?nVz`2;_0t`R`%;L5Q19>m@O<{?scMqcPtveGSj|VlYXBvD&D1IE9txwh(aV8I5G( zy0%>FwNpc3p#$W$ozidCI`?9G2Vh3BU zW&a3%C<-ivd(5Rgmof@S{0=8RaI2aLTE$%PpB;jf3<1YhQZKwN4chkvGMb>42pHt} zlr&Lv{G{eEJg}qP+xmlbhjqMy)Z)ifXfUmP~!jXA=pdP&#Wq^;2~a8jap4+n7; zOs$w7Yl}N9@WJ>pj&MwtmvNs3yxa#8ZvJQ6I#x6A5Ij!pSB%_m!Els zB$gqGN$V8AXMR30*D>{kWqBb#@9cK^cS_M-Ie>fvoMb|vMZ;S?NMona+KWbg6O@$i zw)t}~n5D$1ZnwA3;>F&>w7iw(xpJhQxb7b(`c*s5FBqY==@eK^;4qdjP&*j4OOqz( z&?6maH{{|F3=L{PGLJ5>R-g7f_rx)OLhI3XZnZUx4Aw@I=z!!|q0aN*#o$N$6)iY( zp=b%zNjEO{%)4gV=ra0qnCIOCZQ zj(k|W{?)w*jVp{7_~-mtC}`Z5`SZXyQal5#IU%6a0P0U8cBKmcVF_8|lG#c_jBxfNclRJUqmDWIN>h85h$v^o~y?qez+ zIZ&=&P`g%oOH%02>NtfDc zs%t`J%MtEa*-kS)OiSu~${|<;#RMs!9*^nK4bbyB2Qe!&a`mSO*i@h6I{h00hy93? zdnNB5_A1t1IjjeD48s6$Yj+65^J>uO6tl`QdXjTbzd6PBqu^oZg3Ez=G+Pws70!04 z*umAXT`5BeYu##9g;dV@o?#7?e9yOCRQ4dQQYn-cR`A)dQ>y(s*W_#;VaW6!Mx##YuN)%LNAQ1Loy z7#k_--WRWenht@GupNcqjtO{d>0)uTM4B@+dROkDGZui~#QHCD>Aq2TRTEMt>9t7` zSp9wGHPO7$5G^UhdZ@Gd?)yX8lM#}s5&QtGav3YM-)3$vU>Tq zWIAx5S9TRy=yhId(Q?G_YZXNgbepT$COKDRZij)RH?M2kVbPBfH@Y*&%|LEi#_pB% zY*52u^`Q)nCishEuGh0vF}9y;TVY&4pa_a1*y)50Ye>(v6F7C|PyU`BhdXd!RzOL! z&d#lgLSMY@ilE@MvhyKgtzKgU zK9hxld}tKvI{rsE_Nw&hc&C_7qAy1Te@(Ei%k%epBR<6iVH`yE_gQmbDvaiw#~@v9 zg^MfJSuT~F5XNt94Q-q!9Xq>inL9y-HtaB#KD$D1S!T_}HTDHHRF)oAE195snTqm@PZbi?h|FaG>wBbpl6zV?S;>R2cRyI* zZ?D4u?C{;<%tP7Vwr{o%TAG&>3mg(xSqvA4{fcc-VDM1th9U;=D;r}sinMzzE(Po$ zbrh3Mt#!zIpiCeX+=b$T0*KNFJHx)tg^I_JTK$um*Fa+1qQ=;=6!Q5yr$Y5=8|Ik$ zk$C3fv@cJM1pWk_N7d;f+IKpX%5_b{2sUiCp!twEkCeDfBe=AZIPI*V4g4TqP#3sh zuJ}2eDoPw`v}=^QZPTKd32LF}SnGP^<^R?4zZ~*Vagn9yI#ZC{A9$vi4l28GRnZbd zcr2O*jA7et(z7+;a$C5`@V(*s9mV;N3}9gOi2x)QP)^^?`yn0la{#jIL{Wm1YKhn` z+mwv&cu2nf9~?tqIiujhwOAACVMA^JAPS6~h0Exl4@`+4we~FD`+`g1j*zi@7g0CE z;w2bN+1|HMo>{s`8%i*OwT#>Vpu?PPExhbLswkeIft*)~!+9mP{%^LohGt#$sbT;$A_Q)a0({zbSlI)xeq8!vJ1+nl zbpq5deTNic^RU_)(6(w00Z9xi#wQ>zj$rL#vJ?>%e?WAG!JF7Hp}FD(yK*l(3XZxv z!8{>0>ujK|MMbQl-!AZ|uBms+?U>{3J;nLe@^)}t=VQE|VDN_&tF;Siywr|mEf|*= zkXOxh-}bNtYow6m?2WSWg9?5~;cCsrn+T;jvqc8vd96AJt8B}*I(0#C)td;^emKkqIfvZj07gIV57 zU<&|jesnZX3i0#4>t7E;8m_K2ttHxM2B`ZoOJAk0<-h^;sqr8A-nrtfBa-lk=Ci{0>Lms<*&#r0gE?5okBm2 z864DDLZGnmS=%Zb*H-Z_@>y*vEMC?1I!AL~x57FbyFY-^wVm4?hUFboB?2H)dMlwj1E>jQZT?_S+Yow^2|5q2 z9;_F%ajr;}l(aSpkXp{YkyO6l-uB@vt@6Y4V6m{&L0J0QA2k3fuY8j7RLl}pD+7c% zMc2h-XVqUFSEU;uR?)lvRn6%1?tEL@`qTqhLX7)y`1MkmSO={_QtQ|5#r*yDzz?wK z-Rs>S~VnRykor`H44p9fpr+hHN_H@^tZ@8Y>|YZEsko+Gt3p;d!O3D;}$ zE6L#-@qYhR=d4vb0DQaOhg;aib2$sl%<}N>5tPSurA0+J9sruK=2QxuSPDq2NuAEh9zYq`&I3be&oF)#?Ecw zl99RchB1@Q!irEbN@E6r>#x?8sy?|V3r`#TxTMHYLI9R(3=4tBs3@Y~V>iu&kZmBg zJeml=%S&H9yiD5$+i=A{i*;CvkOWI8Oqcn69$LGYnC(gVD(o~VC?;iys< zGR9%mA&8_at>fKdAYdB#E85>JI9Xgh9WjLBGxeJ>&`2!9Hzy?AF0FE0n!ANPo~!jD zRAO%D+t@|irfAa4fG_hCm*$lB{!A^j+!p;P^3cyiQJ;~>BDC^(5;V}DHV`7Ud(Q%} zrDBaMW5`ao$`Hx9jX&MBG~>NDYio=88m|OnF@%*KD4~LLkKp`2g7-8_Qq3?d(pj{m zXG%c*G-+$`8&c{5vr`X*?haK{qpmRTDR0_!GgVyTc6nx@x78ZmH=$Obl-&F*uQF`V zF2_H0g)He+F*I&{B(+t?snK@5cG@H5DgN_N>LlOvgGhp%#w%S29*G^E#jBR<&-(I=ERj-%Y1joeIN$T0A@yCdWn5lsxnatw14Bm^1~ z!WUw~q0(0^a$F8OK_cNqd&z_Q2ZC4=4JVgR*5>??P!Q4Zse7bHcZGfQ3Hy&PM1}S) zc_A0}q#DO=xfU*YCL3~+!fAmyF?8huZ6+c@|+qz4Is+Fve8qe6><#SjFA3HqWFOJyCO1v@-RHu+B zl0!6g=r8#FkG`-Bw~XV=pB<@g^H@;;^+=D<)MtO{`xVn&Rqqzw-e}^T{qi_BzdXk?H?y3>GdHn3 z=V@+KIfv+tqueA-(1s+|{z)E~>=WGFLnO@)x4b&Tqd`z>YX8)j5S{u7`Td(D_8ARS zJQ_sX&q@RP6$Sp*r~8ym_`yv!#ctnII$*!2!HC{$FIVD>WYDL+XUX8fK1>stX{d2; zQ3y>5bm_Eza#FXu$d+BVMmmPdDsDK#)HRgNN<2!e3vTpIy3A;#$49MYTa0}e0)ZdM&J3Ly?H*WnJV$C3j9+8QXfDh=f&55A9Dly9&o^%CU8%939 zVR9eI5OY(UQRI%g&|`}BiJO`&&|(Y={QmQ{=r`-}uC9@$dFuXLN4MBruk zhQt9o^e6&!(jzE7L|){YK)TywH$|I3I^SbwE{(m42Yu@Kc4j1V&Kep4pCjt8WLp%p zFJ)<)k;G*X!BiqD9DfULduD+$douMmjQD-a91Aoys)!3v7tOanh!Ph_Zd4H!cwNZf zhQ_^gl8=XkzBG&*6j)=tp`zl_^(LEMr0RBgv0U>lX!WiUrMVajEcY>_ z0dbfKZfPvD!C8Aist||FFwUkfqS?b>@xfWq0@Dzx!C8?46~8h|to&HUgJLt>+$cuT zRkjR*wFWL4%8ZQ<8O;ocm#C;5-Weqb#>Scp3O`8BrciK8W|eu&YSLJyi-0!2;Voy5 zjpM;vW{WAvmg(WFZ^4Y*joxHi@|VlUi0PS#(a)Nhy>axs6`swr^EZg2yU;(|lDA;x zoZ0gA_jCCXD;^y42K`O) zU+prhBda_i5KYlTgUe@E*79Y=Voy)N(Zz*^b8@k0;oBQYE8txOZ(~^=xE7X+6kD6Y zmlcL5xt@j`nf>wiigRTSBRCGy^pj<~04I;Q&Rq48W;^{@9yXKwz1n96Mu_m*XHTe? zGf~f04L{qH$%igY3~L+n8&|M+un4o@n37N4_MwejRnL}^B2NZx1sQr?2D}X77b;(o;*F;2k<=C-gN@ae* zr73d$)sH@aFvi+%EIHxN0g~zXoza8VcTwe+&UY;T3J?fi9LWGHcA3)Q&sAeur2;!JxPt@F06PG6L;p9fqj1Bn@ zabHK!eTa(G6N$!rq9xON1myuV6|mO`5iiwBEel*##DG!cm z1btecuY!0&M~Ll5uh-`*BA(FB8umY%kPeF}ltqZ#!hIb^cYmBUo1L67o0*(8o1UC9 zo09!1mwK2pG4X8WaL4$OY$iO~4OQT_U?`U-e;7DXvCZ2r6%D8BM@u9A^`WJV&-wy3 zf3ae{H&uAa{aA%hF5s^1JhNZ3!=nyu+nl4ksmiUhlZLOvjN9Qe7IrZwc5#n+V$#{E z3@(@o8kvgPD8HpMO&0zr%>K$G=PEXtA56KJ>6@Q)Y}j^hQ`9_M)ZoX@^nara;k<8u zo9?xZ1_&=3CrCRb9qMJ9zCQLd=IxVu9ZHWS-u!h3d$S=FZ@ZP9*GA3@$jzPb`@&tX za@rCT?Z}x%d(qs854~tE#1r^)THLJ54GnJGX7KEk_DHC3fslp|WNDf!%(n0CG#i;gj+%9%hDR%$i?}yx+v4-_wB!tu$mr#oG zS1vc?Nx=!nJZQ16Pc|ml+rlG`S(Qee-|kQu=ffXd+ZZpFb8Y-GrWg20eeTU6d%N69MtwX`Vi~HB z+~vhyj{mkM+Y+ObJ>X4Rep41aVnGu+rXB6Z6Yh2wz15y^Y=PCm|J`X%KYrkt_uH7R z2lCfdh&+Vum-auU5fh0W{2e*Ju-IebHtg$^^hyE0JG{X8wn`&<#ww%QxUbR-i>cf> z@-+0SDT$6!{!X_vQ~ww9D8`ds^|$KpkT({y()5eB-u7!cUT?C=cD>OY(OldN%zksM zg*}t@yzBpi^i4qUFWS$(`g;4#p7_wQ?24zY6NijvObgdMM@L*V@4xJ5h|rS5Z~K>ThZ2@EQVlod)Oq|lvi$CLTyP*9hi1>e zxasG}G{uRTa(cjrj3t}o%cNEN{aB7=;KJTRAF~bnQ6ICHbKcumXpgs9=lZG*mEDo{ zUMhx5(!S0t^Gjc2AJGX%4CqUg{*BkUJzQ2MO>3Y$S2cN@iJ`Oj#c_vnO}Ex0$r8RN z>l7cqI$+{h!WOm;jwS~%RF;~|@OgA(Gq%*|5bpsM_Me#BJD?!7#IrUX@vETeuKGJntLa#wxj z#PJbXL=v3LKh=H+vGwq777q~sqKkQpm`A@wOL3Wr^$w`%3Y{ z6bmL9drL9*FWBYATo41EG&|X|+4gjLKYyCg4B30!J@(6p`1qLUr>Yse@$GH}>*57_ zmJEB4$M%y{2yuuROTHwgk3^QM|AMSEhhb%vkBVFN( zaseEC#2t_`?)#CyIbr9FfCkJ<@}&O76oxxr*9wY=O`Q>b6a)F zvERvg;;wfZi5AWpA5oc=Udz^B#m9PPkL#6hPFi|a%4pIm-YS-vlu1!7P~qwGbX$<8 zaYysWdebQtTid7dOv%ZHv z^HuUS3N4f(O2*0>0=i!fj*{8V3@iY;?il?GSlBnBizlAS1yt9jM`2Y=Ysss76!DKVGb#o{g=6z>ooh!(~hWj0#P7~(r+b3ZcqJYtT2 z#B6pdsf?0YDZ40&8BDnMaWt8b*#U}c&2TL-aV63_?h`XB_$}CCw5!0-DrQ>#&~skN zbKaOK8Xog_ro~;))N}sz-KRq6!l(0UZl3cA_Cpf2xxnzJ8HDV%xN>xH0_Eb}4r!@! z;on6u>(@J|3;o4b66#FhdJ(rDYitKQNj5H<>{gM^nPv%9oze-73aMK-HO>jRO>9J3 zq?@T=-hh_jnjje!?Sc06-RaZ2HS!_%(1qtJA~tgGe(=lJamGuRL*l!CG|ooLW{_Ah_n~7X z9@1uENE7toax6t=H?zt$)x-^Q>P4b+7Vr1YV0}UXBQ0XtCsYO@DRX2S7AyAekfsvf zQY7s(af4H;xXLcCoH9-Y>H%y_)6yPPrc9@s-m2{e8S2qTaBDKjsPrD?Qmuc`2lk~} zOaJS*vJl@fmy<;lb&YyJdREOHYtt48L3L~W~Uz|(^4(tyVQua%duyh2c_I+ z)PlX#gLhl+Q0*(=O}bMk4fQbf3FQ@dc^=pTj;Z*q^E3qHzaQTS{d)e zPMQ$t*(cOW{q9yjA|F>f$ze9%k!4 zaiHFA8}cBIW8-9}vGdRr}XEOxA=RH!Vlw|)$)&WiCH4b+PWu`*h!1wM_?#$IZv_p83r4(NMI zP0{pi^llsv#;TY}MyGct4m2BqH5X=i6$Ss8Ht6dnzt!Bkd3-s<|X;9g!5eOQ`N=zD8KB$Gi_rU)3W#fa;{B&64 zI(YmBDf2&9yIrx?U7O-%%m6lsG;ZqH(a0A1_Hu_Zs3Rrz8W8A2ehf$!;+_<^$;fds z#+Wl&tgHPvS2`gr&21WO$}CEzBP=H7=G0dD)s`m{4!m1O$(q>hvdRgy40imt zaaB?rL!}v|l7o|jqkzUc0mgClyCA7hpgqdmn6k!^vZj7Swd@#`PIrZ=L^0)50qf*H znCY4tWW>B(+n5PUk0+&$@3g|&Esvck;-!4Qww*BD7p;EDlSsqDddQiTLZDvF_I36q zhMTy#tTT&32mJc`3@ri-Om_p<*~V5yux$x%X`u`sw4u(q*m{+KuW0WF;IKff;QNx%qoN)4RAvLR>b}=$=JE zP-~N;w(DX->>BvX%AH6aX4%5wi2Gz?8H`srz`ivutrWHWzeOo6m&X&g3PG}II&7lX z#H|XR8MJq-^dQIB!}*!S|0@?6eZ2l!Z7$Yt7H#zD8@5@^JoaPBwG4h8^!75?5M+*d z9n@JylP+Q@57>@fz$s?b!^(CejFQ$wFaxJd|0}s~yX>DeAmPdwXNlPoE*9Mt2TaQg zC=Bx7jSHS-MHAdk_tkT#KA{^ByZM&RY1Wrp3+>kOwXqphG|>gj<`1WJ$4pA!Yxzh# z#+^U6jI=DZiyZ_!^`UkHAWwjc_Q&JPe<(uJZG`ThX0Em!Q3O4zacR5BeZ6^_mUdMX z3~CjYFCrf-^U(d_@8tC`t<5=NGl()2J1*m%ik(#35R8r!uc_tMu{~TdUtxjo0!;#~ z)VFtp4JNk4 z7PFW1U8G_CUn%#E{L#-`-8Gkf|HLJs-dt?jyEr;?#iZ)=VW`x!H*L8iHv`N~8o8r2 zNdXq0I_~tdNpoH-HjM&)_(?CcZrH>+!kLoL?E@+aDLpo{grrLN!~amVLfg8I)aKmn z;u=!(NZcssE7_G3<{qAaorCbc%!WPy>sc>_TbW1zRRbH6OhoTc(8RB*_`x__Q(@$x z;OuzjuC!=^<*@#IYl|AtEL7J*)RJ1Bx7xO(Xo}9dYVHDcg1%$fX}TtbaB5RGwj1RD zhd*>2vxEW5EK#lE5V3ku^d!sB~xnxG~n^xlkm5DRi_lut9ReX z$VR4DTEPsxc7&tv8DjEc+}Q>0r3pyuKb5B+qDVx0I&J{h&d%2ixvozYA2h}C7=&}N zRX3mYsa*&tCzEtFkf_gzCPo7d9Rgi+&l(VIkju^11U*d_qiZ ziom$_HBlXV_~$>^5hU1mcmAn^$;gb-*{lYONH`2&j35VxQdY;1Oo?rE;|(1}Szb}x z!9c4T@=?WfsXQm}MSJB!u=Oe;C$w=c+M@Y5u#)U?0C(gft_0Fimq@IWv>KCbSduDZ zd8NTZ8O?+6P7M;&u|Pxs?fZz-l>?(NLEF%`(4@`yt9C==Yb5wG2}XV_{NX<~lehe* zIO`w4WW_(l9N=vMDLTR7%*uMbTw1?$pLZ*v0KVJJ$VJ?Bi{GkZDA2HG3*z*JAPZX` z$3x22CKb}0_C1@%d^+CWRMDN`##iKX&2JQacT)*AVVaATnXA#cZ@EWLh^6o*h)lhd z9zYi@zO}!re4tJoV8DR3ct_EZehopcw{;08PCW>H#T6er5+W32U}@E*Qm5eT10U=* zzfv+QYj=xL;l|fSiQ^N0pr9DWwj^Hb8r>J}n?th@;WA(qO3+ zRJJy+pT={N^99&D9tFVu^ZQ(kxyV4h&wlPj|cI;bJ8tHbHowZ7nn6 zuEaswP@$vnd&>YZ6ljjhqY^^ZblAR$M1pH+bTH9J&Pbqko^KnzRhbC`ajW{i*c(Yq z1x_yY{sz#?z|v-Kbz|=aKS`K+upY9@O3?7LbW9bje(mJ@t(v6kavWJ{)+yiWxM33u z${>#p;$Z-&F)K75$AwVqb|tLPN+7^-wMXGU?^hKlmyqg@kADNmI`tDB%ohAl^u%eD z=Yv|#;)1NhvaG`j4dSlTt~6+IEuE&XkYM0_46?pdR(!iFm2};QG<5s!pvZP2{~#

      ~DAntqtYC`0Or(JjREWfk@PAy~DTxLQAn^7oCDTV-#o9 z$`Fc6N=HDK9jyCQIzQV8;HfHj4N(XH~R#3{T2pL&1 zoZ};W*zWf#6)dcH2{;W@8tc0E`p}D61V26`aUNcWnXwva@75R!3L<$)6g(D4AknSVe46lb$oRK zH!3}yT9NoF3&0G~49f1_>p(FXAXibxafFf7ts!w6{;C$7DLj*(J(S0Ad-^p$q(h!d z$ty_Uth$4b-M@5k?Gp6~J)B6aZjs0T0Fp|LDijVaJIG9bl)X4J29ra*pDQi-2apEr9MWiU(@$OL%@>zpjDWq)1dPQ;l5%%ocU~@9_eN^sA_%lhUGr!gEVUjE+?EWw>1r&I(0=c`;+wD^00T5qK z{Q%&kWWt;R9uS} zzC=wWYZqr}7tboVw?`YLKPW{$WoG=O_MjNAOCf(a?WE-4z<-q!@>AV`MCyjNbrs`)Ui9UJAck36?2sO-{4OgUra z!?HtOHcO{c-B9ys2uCzZQ#KEOgoEVn(6jE{4Y=S_=gAm;g+1p3sZ~<(iT^mCCrQ8j zkuz-U!NaFUcIzqCS1LZSkD!;Q+0a{hn^cYPTT7m#^vu{I5l3y)w#Z!HS~!(kA9M3- zv4@ma^mk{Ajmb|)%^AreQlx8csr0=kdYWWND&VN?kI>d@i;VFtd+w<1XRJo{hg9+W z7Og8aV_zWfTVKZ$PQ}}cN(E^=%&(P6>FM|G7V#RFgwPQEbdkJ$)LS~6L3EH90xZB+ zI)I5aMOR*=h~>MhCQ5#%Pdi@|SHy+TR$Pi)T8i|lC!Kbo1}gA^ufU>YuqjSh3Mb5* z6Gl&iD`G=vOD;t^)RQ*2P(L7Ujs)l5em2Bf8VMF9h0#-KdAu~OC(Uu87Vl-XCW}ch zgyjSwaCUF@JGb}mvgHK5d?@`S1=&P7MIj74x`>iF(vXj@+&+aoVndrZc#3^C>bwUn z;0TeXoQp6tE7r%=4h86MK4G5lVBY)k!*h7KnOKlaG(npnLopDc>Us<5LOs*NNM{k@|C6nnJt3yW)|N!dtYSh()Oc$o{?pqMA~VrXB6DKz$tvRyUmHb$V~FnL z_PlD#wwz?1du*g*l|oWpL}9E=pB>p|tbHdtl3SV-DMPB@Lgm)O+WfMX2*(G;6_Fq+ zNVF)HA{&FP;c8%UAMk#3qBRFO_ig1Dkw@IebHzTAdpHs_@$Q@G+LzXwzFyQIRv z)to@JfmdUP4}_V*WnCxSiDG_#{Y}cb&!`3cDD-jwPhzf=b&Cl2wif?d*=k%HTjWDs za@)RvG=y&fBd$#eQrR;mVobVanHV*ptQACkv`1UXSkC=qmVys8@zS!1b_z{uBeQ#M ztlTJt4`z5>B!;ZV6r7p=X3nF+fuopyt3x zBWJka6TG7$OL&<>GIrbDow0JH^l>)vElQW~8_J*UDDEhxlk?q!PSH2frqHKrX}9&} zpt$7%&6|Qz1@~&U_eqMem^<|JZ?tr9MYkNaH667z9JL>iMT9OzMk2J;5ckQKB45%F zok$1WnsH?mePhVS?ZH*V<-x@Vyoxw+e4Mz?GF2pZZprtl@V=mM?V8kS=`BW%{GG$Iz?2R|Vli(tlz$nW7H^RtHut zc%?TsX8*Uj9d%McO)%pn++o8Nf>(P^H-1g`y-7Y1p(af75bm%d&ZoCmD0{x854U_J z<|+gsG;Q0$t9}2N7n7xvX?pr9dY<=gYg+wCX8!x)v@N{Ew=9I_*OJVW^N2o(hFLb; zUHk9$>%$7lS+l#dcbNW8XY|U*B~CJug=L)cs(8?77-pMjJk0ifk#wE|pBbh|*YG#~ z#q2us2DoxHR?zS>*3`)kZ_5t9C;jK8%dej=>C1VQ$_x37BhJV7$v@ZuRouy+5rw?L zZ+=E3-`Qg<N} zV@(8NP^ysgql|`pHvf;0F3}sLnvZ;Gzmh(S{Wr3qDU&U!ln4ItUgl4w%%9TUNae2_ z46}D=rhdc@<;4zB<3Pc3&~v|DwQZ4w&DqF*^&6T`9aXP?+4uf$qAlFo_fP4@FYVsp zgyVgZf0Xd*4P~oyInq22Dh*++UNh#mCd}M&hUa3ymn@bx5AT5jn|rFPLFUR)eGMs<(%xHz0cB3B}$=`j5lfFC?Y4fqyPaW@{R) zAo@!DHTK`L3tp<`0UF-D>dr zJLE3><;fF|8?m1MHUEBd%Zkic(;A^^U(PErJDGVrJoeq{@lEP-cqKy93ZW@8o6J0G z#ymTj@lUJakDA{fr3+rMf3cUmqW?lJc|~T;(huK^UNyP@vXK2FFY`zGqEHA|c-v9a z$WhbKSo5K=rh&1hzOkmBv8G}90_8vcEzO4-1~}gAs)*#&f6O`IB+`HAbHbyu!(T6j zN4D|Y-0}K#drMPCIE+a8@N0i*@||>z2f|^Y*;kaZhyDGfcTx-s@BV$)f0f>U^{T%a zzN2~n1$o@@aP)CS^vRp(lPA$92GPglw-zUpPxg0zDLZMFA6Gp4lY%Xrz7qIlcA#1G z@5SHkpJw~N8h9tJnsUOAuF_33uYTqH`>75OPG(iX(}N3!z? z_1Sda^B=)xtXPsZ)4@QQa&kpP=ab}XmreE1PLbqm$4zzHU^A9=ov7=LivqDu1FAFp zwz@@d^4+tDzDK!t&($`M{Q6$^1SZ#1P(o{l=dIqbb1-Go4>5+TD5uEuzI$E!CaG40 z5_X3XS0I2;4?vuKq&4SjuBB$L@E)~*=r*m32P%EqecCa zxwm4&+Za3O>E_iW=XZu)Bs@{-Ijh}K0yQ{tf)7|MxzEJn5j2A;xE0oA&9=i%uD1pggau6a?>OJGUB|FuCG4x z(s~;Lh+yVAJ^m(0+b2bK8s8t)-FHZO8q^4fmERzHQKOeG=Yr>uov8lHPHg2VMESIB7qS_3_tfc~ z$&bokm0uzMMcJONZQ6}QbzX9BLzGTs`lCAgQb|s$cOg!jiTe=8O^l25xpdwu-U(DR@(PUHL&NR-`z(DUOhS+D}a(TCJq=L3%-&ni^k4<(*{Q#Se6TPw*e3-0~Sn z(oLl-G^fsGusgpQ+KG{lJzBSMr2 z5h8?%5F)|@c1x&)?X3Ti#+d+E6vVYf>w(|te{}myfH9hym|Ehzf+3oke5Elr5tih1rSp~1=D0ehjW4m z(unm1_jPE0XJVYcROWHqEGdRu<1UOk6bqyNGDIG$y}cCO9~CWyCG=~kEY13@2U%$D zcN$n~dK_jPS0BgaTzyHxGj$U>v7z+%*)GC-^jOA;!E|Cocpoq};M_X^%+^6l-xGd! zZuaw<4Mg*D?N~Cb8(Og}zKGQIg6r02IQCD$`a^wL#YuGlffckz-d4}9a!4yHB$YA` z4g0Mqrb}od$ej2|GG`e(NH}Tnv(w_AG%3;Hoi3UbxbOxX)51hM0nu~Igzcc%{ES4y z@!lY>8@{cbU|-@IH+|RSK+`_VI43+mS+ss-)~Xv-pc5lz_p zjy+8?4U6fZS-IGIL0m_dCJz_(TNX{yR zwjN*49&2JOeefdw&8%2c+{$WnsPXp>C|dbh8=Jra^bFK|wU<4N4AWm?@?O7&X;%8w zD>({imW8TyK)saiRA@97T6~^|R;VkudRQMeu7P3Xcfl_H+?Zu*K2NU!&_t|T0ay3) z|H?~hn!8-l>)HpS$&DL>uLgbfI->h#2A98XJ3sB)_ylCM%S`t9(ky6KHumw}j&F0| zn>*dkvcKCR`YHxjMX8)*`1f)evj^dtoBBHhKrA1I^c7(9_Kv>*46XFglQgHq9w+hJ zAmU|G$;cwO4JQr*n&M*HO(HZ?S@+QEqA(z9Aey2z2t{CNai9sIr61F2Da?>xN*}2K zSF~!Q9lkJQz;*|AZ}f1^!l);R7*KPOCkH+e`XS$QUN_hA}L2ty+ z&a5zh8Z0LT{8xOlfQKLCER)c$;E;7c{EvtJ_1JBgR8EN%ihGGRHM?Xu7~!Yd`i2)5 za27#7idVq!;G7v?1WL>b*~51c@c1s*zPf%qZQuUxAzzOhI7 z7dMZzzj4H_Os+VrIhQooeGAX%0y|`M+4NO>Y3+M-KoY@ zX_fNp?W{95=S7-)AD4(A`Jp1@pzMb7E}(QJ95#F1a??zFC4f{<{NkC{oQS%e-x^v_ zQTWA9*&j`^o#iIFljg=E#jr#}%@9ITnAri_rsr3HNq7q;s=1<}zZKJ$#>~}R(9g3u zCEJrak~Q+@2g5aTx6j)4k#19KpVaT7jRP-;_|_fV61abNXR>jy*dQ55oh#=>=a|FZ zQm)xjE{#$TN2y!mf-771)!e3h28->+iieVbUbOHWHY~pewp<*gZi)-eY2BX=+UItg z%J-O(8GLGxBqx;v^rC_1uwePsu;s!ibzNL=Z0r6NV(NI{>G#p6Ly2-@*+4I9xFsJv zhY4HGk5X6b4h{(1$8DPp%O?zt!U`xKTQXJ}Bpyz0Pv#F40}_E=*+7$Qpj0;DIh2B$ z3O-AZ<>x}F19b-z&kyT2hp`35V$OascWQ#+^g!$!bZ9bsybUe}Ga) z!bk&6LFs|Upycf|#1!p7F?oXAA-UZw_uP4Zh{hQ|xDqfLqIOo!sAWRTs`E+xzLpgE z+(3WGtuualt+C8Q`)zestyHqPlKznH2+L=O(^@8EbLssdbZ7iDTB%bZf@l2HT3(rl z%G>G;5wm0%eoBI)wW6{&L{Gxgbb=G?V&% z7JQatj`cY}n>yO^L|v!yJ0$f$-2tV(Sv*v#r}mPEB**t}f6o%NrD}3u_nN^EN#^op z{=v0_JP!=3C5K~9_&)dcWJyUd9cW)Is6r_-uoI|0+8lWoJ=_J>jGwkUNQl)4?3Um9C3rDmyRG8s~%du>!mb2!1D@CiBP)4mT{3ob^f zn_O2mCiFL}YaWJRZ*qtLedn)f(CYNV4$rwREPQ@Uz7UX}@CzWTEJe-DZXPg#kNXTKA7y_xD=&w*&Y8Yu(2M?k}H} zXa#zs)0poKmh4RC?@W^RKmGnmgKO^bTCioJ8m5Q5UU@$cQ@&8798XitzYxlYc>=Cb zdbFM7kU*}Hz7;Wh_}Y$I$VI&pSl=;I6UfFN#l}yJ%nfQOpDD7dFGo#Qm#aUFP!3V^ zTs#w;d;FGXC`>E`^qYzy@%DZ0sZn}B>Ma-5m}y?)?5ECmkP9FJ&`h$^>Dm4`HfWxPbq< z1HxN3I@>mm5N{_2sHm4_7$yBtXSs}g9~uW9dRwb1bq65N%DCrec$X}m9j9a-8)u(L zW}i?|t`vfD?RKx;K$yp9SV#h4lwx%USAx#Yh{gl(3byttxWGNE7=#{=_qjFiMVRf+>k&Iwvl~ej8``^eR6= z4XSw##b39t^=tVnpYefWzmM2Wm&9)&wpF>VvMI5A3YaoFn5ygV6tWK`{dQWnT~NKh z6=49vjw;)g1w|}*{QYrumzFZ>X*RFo+f3-%8P1bdpZ@TnxD!v()oijBK4423g^Map z_sXr7GWnGQZ)Fo|TtI7g02Za%MxerOEW2F7SZ6%u55hLOTgtxmio7m6@9o*`WmVk? zBfqEGOgMNO;N8L}*TQ$&>*lKZ^1i3{iyNyCJ*yUvHUd{IKKHJ*l*zX65qiP>VM-wz z?1*{esVXCY@&{1kDB`b=K^!9o-lCX5H5DH6;B8y`hW*+i=f*fn)gD_WgDpc7j57$5 z83a!{Kb`|G@{#cG!(pF>!^IxFO>f`OT??p0sag`b0srA7W#R%=j8Zitwr;~*RLxPU zj$vA-Eepz@~z0OswuWi49_?n?y=V^)6Uu-X0X@GL;OSTZ)x4% z>iMhc!c+|~Wh5w79hj;%OjRFSCWt8$USecky7hrHc;m|%qp>2>ZHMp8kC{TQ&&$~4Mg$QR{_F3V=XGm>D-ggQDNmjqZYW&8BXSg6(>dn#|FVan!1$=3t4@!4K) zk5Nzh!#rN|&Auv|dH8v*WDEJB8b9-2K;;TJnq#Ol#SK2t+I%19pn&q@!oJD%-yg&V zxWV7FHb+O#3}U~6o9{M6!rdN;b%P({R>VD=HuxD{cP91HdbHU4v=KVbm-zO7jcH#_2}iVdU2ua9CsBj6#R zW;OH*AM7O~=4rN1_;BY6!r3Pf2|`+6!>AOyJuO%s&zgh?eiu}s`p%Qm1rnmRS-ol+ zT~&TRxP3zJP}7Tm!_T;7={XIIJZxPD)Ec~A8Q&RjYmnh);GisQ;wk)0D|rV1D|Nkc zPI&zQCdad6mLOB1Cos^NQI&##>$NruU1^NI9_@_W_M?8E0d97K$x&m%$d{VpeJDSj zaNSn|HFKj^=wUA@F&{I1nsvEW&EowlbobriZ&5EPuqtGDx_JM6TcOqpSJX>#Y*^+x zF^QWThwBMh6Il~yp)Z-_9ST^J6Re3EZQq8r?}9b8>2dtz@}0TY@cJ6f)YS6Udg@oh zUQ8CC(Ggag0chMY#46^~#rnIRJZe^6^)>o&p#K0!K4bXVH;QYiskHK4a^&kbZyf^Q zcK9ZwbC*xEJJ8lbC2E2zUeo% zjds!5*Rmt~s(oWF%hGD{s8KT4U9Ot3*JEWrs&uG6${d2Z6h^5VtX*og+nOy=FN^%M z+ncSiKPIpmJu8y;OQK!B-I-XG#5_&+adjuL(?FV$gFf!aNym@&# z4{n7Adnd(@vj5HB?v-bL5Z9MJqA;2vHbW3lMuc8p&c|B7UrB6Lws&QI>74a_0`^Bo zbEQ84^>X8{@qYBrk?@=ClLNm$r7?B)525J(RUN(|Lq%{jXG%H}G5)^w$Do&Mgg7!r z%fw+QWT({MEh5&>J4;(Z{7&qG2`qxU1e~WePTNhi1kmCHXi@3U|40m;Gw5Z01*3hw z&^A-hI+J&{#+uMS;uR9@ndB!q=4FI7HBNfauGX@~q74|lo#;_U=~hPSCcnn4CNy#*^daai*{D5a@XE z!+%eXH-Cb=p5IO7x^>e3oLqR+%f0-8dtYs(0{(kl#$jgoPxrWvXC)`)J@44Jji!Di zlbnhS7V@7d*#Bm+a(CBA&fC99*uM$hzj5EcvE9EB4cSN`8qj%G&v+EYp zMFG~%Fg*d%eZtW6C~@p5xyJ%HxY?om)|#!*Eg~_}MlruBDQCg(VC3+jxFUTYC@98h z_eL?UEyBiK{$4@%d*Ps?{WL-*>pkK|P+eMMJvGNRk|P4D=wp}kM8y3j0r@K!`HQS0 z2K-II2%|uTe$P_!o&g-g>RxcpHmuQC^_MaY`r-W1x!B3>0~$*07yVAg@y|$5_hWH4 zpcvNnm}9p^^E?#Ua}=3^R^T}gmlqG0f-Y7;v+w9kLH##96Q1ZrqHr6wSC_)Yi{-!V zSpaqVsW_x_4|$b3o+*iRHFQC`zT$P_vY|YpC&4_y?(UB{MBhAnMws$3_lqzi|ABP9 z2XmshXU0Qu&$NW%o-q-IMCkt`>wO>HqELBaet6@4U+sm@u<73i-v!8jo5v(@x?4)d zKSTY}?@|c)^({Pc?5A=H0m^{4r`mcc^k>x3P;~5 zFFuo!a5?UlbX%mQEwnU2hn9MP-Pj8#u1sBcJ$*= z;;}x=${2m?>No+iL@A{%S<(yg(Xce~-t_`Rc><(FrzI?drp0Cb7JX>e$Sn2Ip$TGk z{W3I#D8>>_DPh>+G4)C7guDMx+)HLmJyE`7#8qyNvjwgXh+A@bvPptq(o%x3$!PSz z98cCz`G9s`TnCC&pS^X09rV1r^1pd^>O$>`b+iSN_DY`gNjpV(DCkIxsv%~^+$yU#Uq*j~Q*5e*;RU6s1 z@+)8Nu3YS{L8HJ>{%AL=Ic2rf-q3#3XeBpzkF1fAy9l(d}Kq+PS=OeT2 zM30F=OD~v4BVtj8vQU!9aw=}JQtU2Po-ivZbR`S~d5VaX^@tSpD5X@-M?~=s{18t# zk)c=u&|vDBVOAb6D?xOn1_+WK1W9g#1Z{W57gDuIfm-gPta!Q$`b89FB5;H4uc*lJ zOO#kCdQ^u9=fIDBjmJTdJKK?;cO!S*qiS>?vy2CkIhJ>`46W_U2(7WW61@Uibe*5S zr$9z!^n0--Qjy{1J9dZnKUZ|SI7!`-`$*_!PtPG7lft>~cs~~$FaCyzD=DY5?gdeIZbe2e0`Lbsk^=l-9yaRgdYcw5cL&!RY>)JxINip8Z9ALBZJah{BJnR}T<(4_m~F$o^PiC-%A|3Xm~>Q&G#{G_R5R{o#^t?D#={1j?a z-^$x^(%4rye&VC$3WgY+JF(}sOIz+#0lFb?u=Nk4YSt=W5oZS>{SBlUEA{bbXjgqe z)GoGu`DdrU)g6@8`cGsW!N)U7miS^1qD1?D8WP{@LDXP7#Fcm_%IXeQss!*<$08`B zWE`52{$ zQ;0fizMi_s8q!9Z6~DwPErljbjQ_OXvm&DjhOj;k=G~2C+l{1iFYuZzx5fil@Jo3F z8IpP-jHnbwN(dt*0$2ah`qVCuke&+2BS@tNU4z9!J|}tqUMaH(y4H+R6g!ix(ovk0KnZY z3A^82+83x2=2p;{E1zCK(=G~g8K*+5>xUb1=wgOzvS@&LuxOa`_;OKlWaN^dxi(x; z3hq8Q__22EW6{{h&}6wrTE{|;mR~HMMp{Y|&t-UuWWaZ-X#pJV60iuEqJ>*QURJu* zXcCmJgcYONf{{kGOBf1wuM4!^`4HK0gziX>%H7XzTzi z7>p3iLK|Hg2~v62rgDz(4ffC=QIvpbc9*WRxZ8>u>@Jms2CD1}%Za927gI3hfi@84 zUZ6FEpZh1@rh#Qc@+Ah0usT+f$HfB7;^F7);b$vmt|;JW$ID3tw{u8hbYi6k_aOXy z2Udm?nrXAeF&rohFO-EWuGF?wr5fR<=;5a^u!2lzZlr+Q@xTGZLW{+)qAWx~$p~Mv zft8E+W*>$^Y7B;n!8zqinp1o;G|S&JNhYf~o!qH_*V71nJ5a@kc&Uf)jl17uze@rw zc?d0r9tnkU5=X1MRF*hkV2*gi6nHIvBrq$T%#nq)g&AxitmMAyp4Vt@Y#1{$7LGKn z{3Iz!OVrt?|3#2sX!yZ;2od7mNR1~*@|N8a`Rx+cLh`=@Y$2naBP+{s&FQ4@c`o=8 z8CH@KW#Npnpv5JGqcz7fV2YbbagEUbW=rz9Fs1Xt-I;#x?Cdy~>_934{YfK5w|BNa zS-`OvT=?F|M+$tYFBY@9vbSD3SvqVOVDV`sbYw+5phLC=6X-|wY~tRMuu^{w)06(? z$fZlk(w7q%FDJ^7?lGgO>8i~wk{`>ymi0ELzjY9X+kLjcmo-Hc{*)x|^Et4fj3_Kt zW!<*0?~|D-YwbIpEPK`0IJqL;p<=UEiownL%VE&X(2Qo8jAoz76^fCM7sDU-lAx0- z><|1B+#|n9Nua{_tH0~3vFoe2>nlra z2CJ~1ON!eq<-er$^ivF0;Q-TaTNrLC4}TON{>VPOlC)kLhbv7%S&(*@#&(xR<4TiI z77&z$9#&EiD=7?LVsb2G!ti4x`CBl2Es}gK7+$O-FBZc?WULlR5|o7w7V}KC0xP*x zW@ZOC_T}}rsA-nzREfu8=2rH4N;Mn{-<7K2iA-4bvN6D7ZN;z))1&eZnC%8<8^W@u z_|r1r7r9y_6j0`_xZ<1c;_g-fN_cnh{QTgX;juSG$$mb${~Nz0M7F;VHQtsFU%-T|<42jR z;fe!Vfoll3y8$r;CnHvZtH|5BbO0-!c*0;$wZ;m@5i=K925sz}OQ=XbT}0a_kmk>& zX-%fVK$to%n28_C{Fb*~Bc%a*Tb&WE_--q(M8uFb+mDvgah}Rd?g*(@G&`=yZkp-` zrChb8!%DEb97@_Mit#B*k?Wh@Miw$wJCT@4;fi4(;8TRN@lRV(58HH#LNl@Pgd)Sd zAJ%jOwQMwofc(c;o#>xKWnWU|$DeFF^L{cHJc?s}ejOE_FKOYaiBx$0?zdRfaXVxxf~ac>bxF`7 zbKemEip(3g z(&N^rZX$I+ye$fzFf&17-PBWjZ?(Yhm*lTD@Ibg4(U4M_)YxGD^V_uL^9sQSQc7m~ z_D{#5bzsd5y*fFnn89&a)AJ@1yE|;J>jG_Qqi4O!HF>-`jE*}NRpg#JCz{mT&+%=r`~Y5maPC!h)Q}f3RmolOKITBsdkoL2y`{&N-FZi6(f)4wTToKkGF2R zMEPQod2*~cxcWlB%UWXrSOg2DXP+k%vbx3@Tvt`wi^jumhQbo6jX6z&<{@Uaem?eW zF)|kt^Vo~)f!u~!pAt89J?}F8j^%t9;04^+S`g~Qm!4{o zOPlOoge_O)@)&PA{Y$;|K|@n#G);Q0j10ZqqM+5_VBrOttokw1z(ph%cuWVE%iE5S zQ;z>M+(`##K$m^~RtRKfIw^>!k;#4@O%j2bP) zmLk9O>1uhcK{O%@n!0?r9CUPB_MrH{-F8X5hVN*Sz;i*mS}7N(Wp_cTZiQ~sCtCU* z8*+9IMA(JIl?CP6@$`+Asvur{)} zTlPF1eZ*#}f%Ckd*1%?p%BrKP<=3L6hHGfYctx=w&Y;2@2zeEvULiL@C6bXOPt!={ z=$v$tDi}XJdRJP=(U#G>RbmEVUNBJ1o(S||)M^n|sVo{TM4Z(~zp|0A7K^S4u@=)( z85HzQ@;G8aQ8e%`lRGZbw}^AWpuh%kP8XjOs5i`n0-dm8N;L2XNmK+$G$PE+28xps zfW!z<1w4hOQn&(GtHjgo$V8~_!3(lgK-^wlqCFLmESCj*ZLCmaBlGl06{U*x=@lEF3`G1Rz6$IVU`A{=dJiZ9j+T;R4n68Z2&(_VM8C*1|Z zQpt~u6)Ed$SHf(23bfa$q?wu$rGDr!EmMbP>xuJzCNJP{EO;c*)>8Yixb_A}AU(bZ z-Qas}`rp%{^>LxeMA=wd)yiIQYOmh9>76gz$4uBzYVqc54{s(0;@F{}l(>SO=Wu(cBKf&yS;IxsyQ=tC?d zb_Hxp7K}<_5?~1tu!I0uf(Ic$^BHNCiU2iC{&zsc`%3t8(G`V+|Kg>#cM z2`=XVmy^{hFwrK!;if4%7|uQxuAD?LrNOiE<84^5V!|jB9b8UytH2M0W~7Ja?!b8V zi8nRghEGf&E4Wo)2cg+J5ROa)dQ;$8`BrThTLk!G4HHkisl<3tCSY973NB~a)I&32 zAp9bMFiwfLp~s4GqD;I|CUUr(SzL}i$ZQ}qDdA*1OKx06gZQWfLIVZfh6m3|EVRaA zxE#Y)fn$jC(jbc(t zvb*P1jG3zxTS>C@IFoYtLF?|CzWw3DaRhHtd_Eag42XR}fij`N<+S5+m|6uM<5@Y& zj(A@HUvQ&-ap6lB{9X=?8#$4DPN)IP9@80%8+{@t%@|d%XB0tNEk%@$7GuD?Qruxo zR90?*se{`Y1k?X=1_?BMInJvKk2V&$vbz-Gx*xRo8Z)}dY@hX3%?{msJaypa8y)v5FFmI+mrSC*&ebOXt1e(^~fiKA@G z3wdSAN29xmV?1K=_LNI{)ZIBPE+!5wFJxCW68%_ol_|waPSPeh*r|;M?9d41k#P2o zd>NyGdLd|#fD!muCJ^+(R>_+Ws%B_OTnWrU2?@pENO#R(cg=!!0i(5?DwK&8R+JxQ zV%hRSa+S4kq2R=HB5Zj$YygQGp~tby*ZJ>q)bI-j8cnM<*nJv=W(|Jfznu3g;&9@W6$PV=+;AEF z#I9--P)7G~8NGpZU`HDvM^>(u8X(HZxjW;EMc)e-&NMRclwIxzQU5uc(jJ#G30XMl)4>`p_d+{-Q`=pm?G>$g>jteYUQ4y3; zAj(LuK~xxJq=UKDvvbY!M?;Y_b8s6fj9|yeI zHj=-Z)v6BSXhz6sc*xlfI20u`(@=f~l(cbFY|APRIM^q=Y{+U(BNhtB1sbdQ=swDb2bTfT zg$nof>lkwW-<1Bcfo#<^b5!)RyIf7bgEFZG87o&PMa`{H3Q<~=5i2f3xRoPlEdbfX zfk~C7HDs<5qoEW@$RX7yAzL^huUX{=WEs>vqc&uUSd_6^;Iz6iq?Y6mV=z;1C1p(G zJ!1z8E1M&xrT&IBc*Gev-WXAV0!is3Y~pW8gGg`n!a$WZl%|LTR?>VjVd2GuOli_N z+EH>zZYCBH1U)MmudqG|xim**C>?!+F}v`jK0PZZEsMamQ?{^fk`X5$i#!dB(EEfF z%@{FcmuzZeeOFoZUNY=~XW#e__NQ}12U17pjB&2)J@7?_T#M+r(Pri#v^YmJP|nx? z|CVCo*SOTVhAZerG9Pb-H&#@xKgK&I={X`=G}m~zJ%QS4xT%K2yf$*-Pi||q921Ay zqqJTwC!2TsM*nft-9y#^{2gsL9P`6Dc(!Frdot)+IegYKXj(aJf;b+mWwfG<9I>g= zQtbunso6izYGm*9jb$QRL}l-nI0`C1Xi7LKa+fRJ%TaLfld8(Ou9%22Qv^(5R5nw5ZYQNPF-Pj8sGGrZSZ?I79Q zZdi+y^WBwo-;LyvTc}q2a9$&EPdTpHG`(3my_qJx`6#VHG(Z{Y6Q=^osG*rA zt&-G?sU`#Z;%}{D9-7%Hvi_7q4nGr770WuhpTp3(UXscCsrXP(tT(omk zU`3Z4>`OCD?H0Uc*}$yH7}0tAi?s|bxQz+2OLW$u(@Ak6!sgFBH)g^hY3_4`%}-Gc zj+tYDroE-i_bHd{`DjV06A^4TRICjwpyWlfiz2eFWJ9=9xr#NhS@L4KaC#G zh%$iVQaW2V3<_z^gBTy|(0$YHG@+r#=LuG8VXEblUV#|zxb?c}ri-%H45prSTOP9- zN8gM{iz+Ako6_Ou1@PAFEqtZo$g$fL$^J*Q?9g!{8vYNa3?!380xf=?4J-VSKLaT) zWILF86p_cZy0bkmCSvBMZ+bV%R!l@({(G$vv7Rl(p-V$6bzWeXB$+Z7^|{op-PU^eM0kR zoA=uQzX7C5J8AREB#nACk8hQDWV8ArReHDrfEC}kO`T2@Fol>UnKa9 zQ~slQvn|vym3p_8vAT`18NsXJ(UjmPO^Iir!-^wU^lfM+h|)$_Q)^>KMffzi3IZb`WtNBHtb+@YGZsX>w?S+E)%PHjOMIJ8vD zt}_2fLbi0;DIgkMPAJvv{xkW5A}FHtRLW#)%8t9~+N!yknmbb&XYyQRp1NyRcROel zShIh~10!L->*tI7XfouyGDM1oYe7ksxRi2SN-fI3#+znR`C@oNc^OHU;lWpmAQ2lz z@;SHPX=hY97m<`~A68b5Yh<%q{H-sY4iyn^fxj{sOU)$4RGn^R6wos;CWgG$wm0O` z?Vzs~$Fs1)#qsm`!0FU1Sdye0uk1GwQZ2#@HpS)pl`9Di2Q& zh6L;!a(;rf!+DdpRP&@k98KC`0{!ZF85;~xT}cH>{6cd6i&~oFR5$A zzXa63tkk(M)IEcgiG5l-6cVuN7RD{4JEiwmW_xW34Kha)!T`orPT{KJnd8$@|He!w z7rurpGh0Jk8nc@22iE*!>|Fe@FCztdeso-e_M8HAV1!}#4m{*@8eCOkL>iX%Y~?H@zy8Jgo3mH)7=Ov&2%n=XkH z>!t}V^WyJ5WL(cBJdb}OiGB37N-~dcZJ+2RY7+fe#T&pu*AXB8Jw@w&)!JZ6v!IsP zS?GTrFOne_`kDdn??Ij4o?LEapXIS|2AjtIY3U3$P?~Fx5H6pkQ3SO874)0AoBZob zch2T1pP1qnTC3?En%Cfw^?O=|*x{QP&csuh{qG$0A99x@ga#f)xITT5*fX(OV1C({ z17SM|S{2Y26d%I&`Q=ckI7$I&RHJEUAI$vg&+{y?$~7iPXvZ;Er4p4SQ6lk89ZK5F-0*P+ne z;bPtc1{OP`FV5@Xko#RxqhCTH6Nx9^+XXaEp6{20-rP*g9(bC<#`3|xRz8J4`@@W# z8IRwRw|4g${5s$t={+Nh5kN?A$4u5&#JbOjGs=9F{Akiw%rSXN1K2**1Tq*YD)rF2~ zNpx^Se%G^D<}xyMyDnD9`iD@tyDym>phJ)?G(B)A)wp%B{M`7RyeEah^ zxk6wl;$`xmIqFjWZ)*+`j(H9CUao(h-|4!fGVkMgQFPHihq*{_ZQbh0ceD@XeEs+` z`)uLEJiKOL2VQc{j%{eQvoE?NFvv>|?#Y5{3NIKCP#8*Lfg;?xf3y>p3J2L}K`wf69oO z+~^HYoevlJp4_`awSRxZ|ND1X`H$sD0NMWiGhf3|A;}nJ3AiTW*>xB8>7V6>;PjKj zs??dq+RV-6q3RQdB0rFnmBRP(U^6D2=JZ&k3#edlOEfDT0RIBJ){_+9R49Mu6;b-M z4Y}9#+$1J+wGE!Hzq?I(VhIS?r9_%Yy(_mVzdn>xl@j8I zWosV3{c08y8AwiD6{fy5|E^*RcHtM2oYs5GStvBqr2m#}k5q0f(X_mS^F56?-4=fR zh;yLAJOeCv`f7uR+0e>C{Q79LkTmB*l0TUl^M5}*$FBa)g+;@=FAr|BwktpWDwclD z>3UoUIMM2xa=N{#3g0jQKgwvG*$>a1`}PdUwj;B?-b(!`!X?q(Ef;o;5$x-StA@Uk zYNLKuakpwk*YO%zG71&=8^U~*{1Ca2diIuihiCzcJWSQmykh%#<2AdQ$@<}0rZPTX z$MSNXn^ykojdCwmMmRE-Re5Z5T;!9p=GWwXf6|01kHpL$2-B^?pzG7y64)N(jOUcJ zP6_r3*E7?eMT9+K=HQ!4o*DkQZIIb6M^n}TWD%5~^eDD8lhk(&YEpM>-t;LRXM#GUrwXf94Hbu# zF2C-+Z9`W5HeOp9w{3B9o-v?_oYDKNoq~IRcUO0kaJcOdBmVGb!leX<#nkzuld++M zy}xc>f9s@m99X`t*ZBL+<7WvSEmUyA7b5sd>8ShQ`&(#>WVPyf_5JTD%f}x&K2t%0 z>S8Nw;GxWYS8ALd|1_WO*v z+(NYJpF}FkjpvIG4vsO0n17()$Sz8RzlZ8T)bFb;z-a`5!%%6O9?#t~l=sZlb z7Uwtr(t8!b2#R*MygXQPyf!5IAXaEBo(`%n8Bk$?PhrZ4OX<~d<_?mNqRBq)tERaz zODH>MKi;FMhO(ht^Jx3oC8+u%j>P@Xw_>t0-U7Wc#9%fhg~tDswFXxY$zG3zsl&%ah#Q8z#o%U-9lj#hw# zU}t6Fj*^@AUvPPpsf!In(8>iJJ7RW)aw|BVBlie->k9D^)fVk}Y2jMOkc;twcmE7R zbiRFeFnY41{W!N;=7m!XNlen(KzLY0RF_8d!flb`ymImPIq&bCCw?3|M2sereAwkN zF1vR0=kP3i@%>!=A#W*J;4=BKTi}ytDV{17P9_;!G#7=rBkHnxq+N@DSHzgQ{97J1 zTrr63$kENjcIQ{i{2HN(%nhR4S&%-<#95I_Es%)$F^GS!h&udAFb0AA`}X?2U@1^y ztF$(iPrB^#V-E0rCBMhiKJx!)*rYFJPC5;7ft;VR-HZJMKJZJmj!%ywb z_So)r-wCBrt`9Qf{Gg?vRm5<`abpOP%{l+#Sp`sOG>TsIpUEl9* zLhz4wkDTtQsQy;kIpe5y(*G3Ky(;qNr%O@*2fgzLH&c6t(TT&ZXD;2V6>EA5kiG6# z(<$;i+0>OhRxa&ee4BdN5%jiI^fE+Pdrq|T4>%|@@LEEI2R>+7ymc?1Ei=p$5Y=^4rns?@ z=nUUmvv$dM>P{(_I;Ui8Co`sDDBRD9z(-bR{Rjk$Y7AGxQ8UC;h5=I54~o2)%t58$fg zaMRe>d+^;1fu1?lFBO*#lpco>+~2dHrx6?FVazjk=EySq_7VmArs<`>drM2XMyG`? zk=P#MUC9Cg{cDIzG&rlDo5+`!=8d*Wc-82m$M^PihIpD{@#U0zX^I?efi_M4etiOI zW+Z=@+%*K~{^7H>4M$;9Jjc(IGyZ+xFI&c32VY;3h7WcFen{s1|@{b9;EeY)g3(Ytpojgq5a$0guafw{GUFZM#t?#nE_Z;>}YOr@1gI@um7M- z|5b9LSl4nr;XK9BA={ zYV9T(QZ>9qn(mRsN6uMg?gJc|Ppyf~Ip-SB=40Nk%ze*$bYpu`peLrOGJgH%?%eL7 zn?fAvwQrXjgLv|Bv@SZu-*_3i>kR$Cm*3oZVDfS2W=gGayoygx0|V`iPurP(o|EN!JZ2H^N1srw;J3Jbi}i6qJlkJt z=Z9p?_NF%%8Y}CodK;cYSX^+?wrxL&u<^RWrAhY0kH4!K;H(#Y=2uCPoatj=F|_HL-!7A_472N2beFPc5{aZ$PC1+3H0NP>p3V> zXc-`PB;gkIeLtKHKYM}q#W-!$k#{a-1f>%d{zDkySH+FH~{j{LDJjSsz zJG$$PD+H_fGWxdi`#j~=75Eu>f@556>znsqbJ+6dS0uK7zsvYP=)I7*Dc~6WT3LD9 z#zE)4IvtkLChOJ*tkxUIlN(=@FFeP?MIWe77cu^8dRq#mFA3vl^*OBNgjD<~unzTG zE3ggyKMC{UTXqip#3&ECoQbTvDb^B^oCDws2O-poBkhNlb&Zn{0~K3rk1c%v&@(X3nv2m~r)$BzAoI)i zS%U0sLTh)~tn!(;_iQq6u@#c_G!=BamF7>YM(Zt=Ysf0?RhP243}M8nl(?n*SL1Kg zj}M`?@zE}g%5$DL#z!2FDY$mJoZYsJXDsQrvk_ZsZC0|g$QTVdYD&Av?OGJ;kt-`H1Jo)p=)o4!Bf z9~_Y0{C{YY+*J4bd9kYTjpjMHeg-@G8K&KkK9?nXe^1|o*xBC~mXT{*`lP^TJhme) zly%dg1)EuQs@Uy0yQ!IO-&g(LP-l-z%|Pfc+U>@6uZG6QlGUU|U$&gus5TY3hZ4T% zc~f!E|9)*_9lKzuHcq|?h_t0b?f(k{pC;rR^oxSoe~q3gzNXzt>90AD&&jjSn1LY_L{c`BL8atc;_EDpFHmi%9IO|jp)YHX$8m~EyGOS6`aB{to!*-@IQMQ_lH-3wl6(uhQghzAnLE8`iqBnN(I-Aptc-XC# z=`~M~l^_c!u6YU;pm_Fb8s@e4B(6{AENP7p89u7#uUHc3w{Olp`3$W(4Geu!DZbbg z0DemCoTKC&6ee$v?26ahakvx5z@q29sO6J0KH591?#Hw4xCr>SOH%{`?wXdo;I;** zfr(Nld{KG(N-T$HRxISVVZ;}%F2g9kL0iFZ!Rl-qXxJ>)=7b`x;Hnf>8ARy%AtGnl zMlm8t^!xOG*kD_*1~{TZ3t^rNh5x7$Q(n@wT~95`6ZwSe?B9#%$Ar-D8CfL+bE>#~ z4LM7vlk%sp@o^p^ZwGw2!F+ zZp`Oqup8x^?6n^W4os~?IhM#$oAT?kaBvgTOm7vqF?D0pAZNh4XVA%5Dc2n!ZdsdY zZZ_M*YyRgO+d=>BcYiO~cqA6-2XMblv4PZ)O%#6rNcsJZt)cvHyA+cCx?*9VbkjQq zFmar}W(EO+pt}phWq$<00}@K8EFk%K@1H<-GT$DaN`=XIFu~Sx@qnU?2*@cf3dCOL z>R6sEgL;YP@YEX^!7Sjw0#)R43~$KEl=`8$m9MoL;?S>=0izBXP9_p0=7xWuG|~3? zIxp6zP@`FF$al-rT`tx4UOv4I;##Q>Q;goQE&5~k7UDio2@lMn1_DL#DdZoDQLms^ z5M>xBPoon|d%e-li_9lzxsqX%XMRM<(#H)`Rz_6_D;tX#dyHpxXFX6=-1p(`s!gU@ zpf6$k(G8doiuWcmE(-w+gNL@*DSB^6xRGpHzZ>QMZb7Ij-sN8|%a1jXq9WSqGU@MU z+-TOIux3+yPFAFwa=Q-NUTE|W3%;qZl;Pzhp}%88c;#V+E@yaY8<>9DOd#_%6Jkq! z(ZM~gBZunLD1G#*y&b_L7@&*?t~|dF19$Mw=)3T)t4hKglp`jzvo7TU=;jQC7Ju_Q z-tN#Y2$Py)3(Wyj*n0xu)0<>d!SS>;sS7^tcaHNXc_qE=M!an>0mAD<0|4cRgK+ns zV)<}!S;dH?yU{d5Vn=q-*Su2)zHv(9CZWqo%MKTpxSQrx3c9h(CDu_TN&JNYfhZXx zhos-=J#Mewse0T@V`d^$4z2CZbIVX~S_aBOIxlp-+%asPD7^k7hNvrdp=!TGkxZ4@ z5~uNE1r_M!t5VKkXIFNX96;d%?;Z&MH@e8z$PZxPAH1*Zq^-($t<2Qsau7`r6z!BV zJkgtl^5S4Kf#nmn?u8Vn9SbZs5l_} zYQ~UU8s}OFeq7a-Eo3IfRTHyt@*V&;LBE@&NgVCA!{1RqNTr`^$`P}RgC}CeJWLD& zjksxgl*%5?IR&&o{QNMs4+(DWTGgfG%L4m9iw=j7pcW@y7krn!6U7O$u!$McL3o*i zXQQEb;pP+7`YI@AvpeHvByr^2HA}IZqZ%aV<&6bo6T28&JbHF`LGHUKU64@=kip#) zj5}(4oQvy}N{XIL!K|UDyHvQOiP57)2x$+)RaSDq0V!+HU#9FfC$qH$t>*!W+r^V= zfL$wnG?U>BkxVRdPR9AtXK6ZkULo!(7C32;md4V^0;BCxCeljHOGG0Pb0g3(?HKv3 zK3u^nYJixe%!Gw%btu#ef;(84qyz86&zc2j8xsS2bp#eYGMVLMoOuXbf_-`4cvdje zsC>ziD{ z0rObghIezF25c$O4vixn#8*%5_p`2IiajZS zR6DS)Zol*)%#~^{SH9;I*jq2wH4E^*a)uXhr-vPJ-6o8K z)I8r1C#gU$wrMQ|E6ma$gGUb%X;LgNtAVqjCY$3K;l@AMl$C^kUi{(rj;Xw+Hb5*N zdp}g)5XNvpwA$27C7ps|q~e3Zb1fbr<^PoH>WR@Xgpyr#35r!(Dyo0XEBA;nly+As zJ_~Iz+7!XCox6H+hYE5>XI6|a$GYGO_)jgZkviA7`9FyqC+WRM;>HAG`*OZpKqS9Pi=Qd z+>V42cKXt+iHJDXkVz04)0VoR z?Bfq?RWIOqY+gqnAA%y)5AeJIC3Sq`_ywwWt$78^o9sq>cr+|V*Vx~ z?op*Q-m9SdO2;8A`WM5&5R~!^R4@Lxm+&YoN6v5GU5aq>H&}F7%zT(T;+i`5kX$D! zLya+Dk3WWBH2WE#^(ny)N8WBcFZl9*W)FrdJA6kTPESe@W$81WO%(!3iH#Bd1LMzk)c z++#K3nxbs=`XA^jo!A^tDrym&Lf4yoFqn{&f|4O5d|Rl2km%{O-fAYsLCzjw$>B_7 zXjj@R2*&3FxqMqNV@eqg^<+?iVJ@WtO7E?9npcWV3CV6SQ$@ea6YiFwPDIdTplIAx z@g>t`!4Mpfxt})XsbwgZ0lA2ZEOe;x06cxH@nn#RR$KT(AnP7-SImpI++A7m9(x`{ zU_-u+oplf#SXRl8CYLB$RO2;qAe+#R7{c~MvpjVIE<~7bVPsQ&YlKmshKX5h2 zuPM?5DNPh}#%7h%K<)5}p$2SFadGWzT!b;EGh^9B8-)rW`$xFX>ak}c7ksz(<^^S)DY&{`Y!_d1pVyF<2`Ix;0V5tqP3;|JeP2;I}g*?i5J z=O9dx5jg!M!V=p7p^TlZLgj3_0^c(>2M{8>V)M(Hr`I`yDiC2vQy_UshyKO5E@q4_ zQrU?s1xG6J5{CAUVazxPl0#g@%(aa@M*!prY^(XDZ;WI&LBey8&$n~Tt~%{MLHjSp zzNUD|wqsUV~Pcx6hMuUV6`sSt`^mG@dkKL3&j%X z<{stLTKBi@3N*Bby5!8;Scw_HVWG73qz-rNDhcnuYIU=QKVg3WTo;ws+_W;YJS+ta zOzBT{5BUmG8=LMsaMi(9fMEQCuXeka&&I%E$y4gUTX$mrD=c+?R0{~oV&QmB z|AT$tNLsBq=hYSJL@72xOJ48b>@+KoK8(b6;0Xd_S7DCoLLlJnu}==d<90k50uDq; zs?y{@EwyJ7t*+{cs3JjgtL>tNEw4KovKI4qWMZ;0Hud%b>7XL>FUyR7!`e+e5+Jf28k-${h3*7Ze2-bj@eY=mN9z%OMGK_x$ zBFv6*Rb)RUNWSS~7z zBfFDzl?73YjOhe?g5qiXT_?s)|KO&KqV5&X&-w|iT3_^Krl;iu zUJhhuak>Kly3n(in?}0wfhCfCmkPPnq}KPMcu+SIbzVG|I2OKRvQ!n`2vl&sOsJst zIB$4d%gnZ}mq+Q}%57SS;)r&d)@~0tqe8e3)d8f-;H31WD{f&1Y$S<

      9fVwM%^EjW>Y3Cn;c)B`b0e23H6tY4qasNk9@^}G1$j$P22({G97IkvedV>KEPJ8+v%s(ZAk61%A)g`D~t*< zOpD`b9af`+aZ#rTn7KPjVITpYo_e|G*zPUNA&DM>*9@zH2^j{@6#Rph`KQ8l2~ia% zrH;hu8~oeRmenpwf@ajLJ0bH!HB|L>aAOtXA43Q@ztx2iI0lhQGY?QRt7`H)3Dz+J zJuK9Q%*$;_(3@{FJx9J->3tMW5roCy{=5qMr>OgY8M2s%Sd`efF~~SF^6H$)Vpy;t z4Th`pYlMNg$k{Km2zVk*IesO-5Ankd4>A)3eFb3T}%XPq?H$}K(M zIoD1N7?!Y+G9(k+>TP$oPKyXCm%T{BPlnK@>O@?ncxckb1}aD8BNplnRdjFk8DF+N z9Q&EjaLK=bF~~qe`LrIdtm?%~?9No{=S+H(2Tdy3FC`U`{SeTytpocgYxk~@D~b+? zvrm}ZXYI1AuAA+PG*bRPo;x~D@IOD)m+z_BY#~5-;@4>-I5zo~(;-flY=5o)9K+_hoka}KI_z;|@`i1W^0B+LokSEN0 zKYXQ^jFG`l5#1N?8~TIldDjHuLI!f8AJD-6Bit@RVnVIC`~sLhJER^IL4w%HENMTB5zv z6e;J2M%7rv?^88%pta3gFw3cJVG;xHbwt~K;f_0(Qm`j{q+*7 zp=EsRHVp~V=H*$KmF+55V8eH93b*vSJl3ilGg+Anc#tE;3zx8Yq7WyA7$Q0g-Y=~} zbtAzxz#~`a-PU^L_c;`D?Jk>gsLpVF}U@k~T(p${}89Nthb^!G;$3 z9C&2=Kto31{=9+s=I5mx7pk?)9k!cP;1u4Aso;o(XE@6^fPHQQ=iB}xm~`eP454IA zrme=W-=AyX&jLPZ4yX>5m&WqN7uHo+Hef9s<`a zPv^+-`ScNAv>=F;CuZpJg<{9Fp6h$>cXPT5=P z1U5d_A~3|D0nK3KEey}2gy1c&hn@o9{DziaN^UnIdUGY_)}UF3;z%r|J;fG zOhOGZs4F`eiR5;e8FKlI9$om zQV{cYo0BEis8{IcGT(_-Cpr-GSPlkd#`L*H7D6r>)V&3ED!riFIDFzE-G4U5oS4Fc zVhd|!91dh!Pmj-#l`^3dx@B$NtzyF-1xMG282V^VbN3G*{ zeG9Gw+8=WF$wF*A>$PPsGB@Vl&;w5isp2m>C_Ndtw=zN)x2aI(P>WahLJHmf^Oc-^ zLbh5r&;9~Kw<>%}fB*sAALaeUJlF_D1Q{K}+$!=9+WYlDnQ^hg z&}>)dhN39ykgMA`$U5$eee`ovLVVrQTSi_#Kbl`E0`tlm_jp0Mo%}>el)bL_H^Oy8 zmtm|>aela2u;L1G z*5Y1a-3ZIO3tk!pv>Z8_>%9soz%dFX9VI+zJ_#iR#96y=e|W@^HGXuIlduy zT|ui)G#3WVx|Kc7!v^>Ho^eFyWCaCOjf4vLuK2@3*XK65S1>UK)apb4B9gOFhu*hk zKJD-HE4x8yAG)S8B536t<0(33D>cI$OgMz_-nGwJV>G86MbxvE6GeOkFph_f%%XWq z4Hw}q?G#6PFA@XtFdIsmY6Hqw+V|*;nv+Wkp0*<3LB}M%K|wtayx5f_-k2RAOQ?k3 zP0wF>j+7<8L)xxukhtG8BS$5^xWV2izf3pBnS%*xFR;G9LurSi+#T5Qy4&aV5zXH zF5(m@N$c^wlJzd7r`lYLMKcSKR^rv-rev#SC;|hfe-Wi+EA_jGTommtsPfTT%N4DL z6EmED3X&XV9TaFNwLVD_Jwav;Ba-2P_N_?En+8NzI6gphcMzeNSHR4R%6Sm$q3-_*)Me88J*OnvLh>Ed zvxMtc%;+@(5x0Vi|L7iwphm-?1vmVE`gekx{P!UYiu(y68QSY&z6o7AZ~`~Tj8bv- z%8AzS4;D-`xeI)MIsi|j32vDtp_(()ALi?glLWHoCG!gZU{teL7pee=l^&xGmE!_R#|qGMyIJkY={XIYOsy0TKK z^Hh{pMzL@ELc%?NV_!G)2snnG4)s7ogMrc+bxz_q|x~bDh%&=xJBt*c` zxLBsd0eS)*lOiJp0=bNezx{Xy8$=n3`-C(zcxx76-3#2oUgDT)SgY!fvJ-GIGmxQ( zd_On|R8*LMh;p2WT>4!rIunY|kBK3cB=P1!!v;kkdeB+w4`m#xBZ)3GUd4LMM}Hrq zKD)ChMZS0N99D@0n3;qySbf9iEO`}8o@-Oh*bdqmHiDKWCkX4`%{;k8q?;-OrH{&X zyP{Flr~IYE^CExrmmhp)2^jOHB_b*XA_X!tcHwKOps?-==O-La?(x0STYEr0;kDpK z^D`9)esT0l2U*4o{to60Ou`UI=pjD@{@5Y?iU8uPZSiTl4UxRmh=HowoTMuV>X8Y) zf=3_kd_+{D$dW7OjSmb$P`NWab$em;uOBJjk?C`KQL0HiipI*ZVR zdjgAEOyH7WugtJ5^cmX0j46)N(JV5cp6SIZI*zjj1H5LDCS219*pkVTERZ~I5N?xi6KO3XzYFQ)!ha0d3 zrRf1xmdqR{Xky0y5+@7rGR5D~m@A&Wa^QnU7XoAckb97U<`y1U7GIdryx3kLeDkUz z&}F%*9dd#7&O`P~8d4$}p9nUKOHT*vY-X^8^$e;cUw*H*Qx-2489NV<>4cvFKbd+? z^HA)9jB*wcHLI=$?nj~cfua5NEv5^|-QbfVBeN=%M5~;rIX;B~tstkk3ec^)->}8TP9_%UFG>n2P}6-Z$wrn}`Prg=}AA zH5?PB>*KC*C()zS$l9>Lqxk}HY$fF(ZDL_6EQ}siWcC4I`3#CPn}kbFt(HVEQgtaG z-v)%$mHfIMM^I}XiNzFwaO$$L{l?mnd9CzxZv4}h-&8v#O}J)@3h`he;d(KohdBun zAamXM1uRH5R`vKpgsa`JQ<|e<7O`@Rwk>g_tD#-&WJth;f zR3z-Hhr(A+oJ1sk3+kcFsLJtP|=z~vz_X{2jMxnl!$Hxw%8gtl?yi$jef zE*Zu^>G9V6ZyR)BRWWNTT+dL+SzwM{WI}S)nbDyz6~P7`?pHL7U;I;aJzQ}u`5vfew&W;2z!N$IE;bCNklekE*uo5>(|A4kT0^pS7tFE6!b9EeSuP+ z!ri`GTv^MYQ8V00igzS1RGhBl+b>@o9f(bX5y~r^QPM%R8d&Bqv%= z@DVOnkpC4zX(!8oDd?9J`P0o{9=!pCDkka0Ce39@X4yi$XnuI4tQmKkSjWFCiA>}8 zkODHv3o+exA;9(+`VxkYi&qX{@VHPdhCXZDeiMtzM*}Z&ntgVUl=j~JZy&mm(l+JQX2}57aA|Mxaw5` zQ7ajc4Eqa_^v^A#nAD|>LjbMhV>6E>e+t>$cAKy=utda&2zRlj*mFFqhd$h9sczgz zJl%y4rEGAR=$D><$sk3u9OrFl3D({=&I)I_8O3P50yco0b(!E5i+Lt;+i6;33o?sT zvUO^aUl7gQHCa+A?L-Y~%L1coAvCStqa$GJwYu_h-|)@0F41B4zg;Su z6aG{kFu}kCiKYP2NkqUy>ch$FjaZUKP_5IYIe5XUwhiuHKY#=~L^>oaBgzVrZ-aeO zy%nHn0vJ-vc{HP|xIcl8Y@zsj|C8IN1OwSbSdtHfOh|BUq)yMSxA=E|;Bi3|*cK|# zg`tJ8r|cJ|gsHHQmR{hFM;!X}Lc>u!^OD@SQZP++yrlDv=pA>2l@C7o!gy%}pc`5@ zEO-FM&#bR<$J8;gwn4))StyI~W7qk(6TZ;R)Oo^m4y)`o0Mbi$1jqJ3dS38pxiKxR z2(?b~kyY)OY@h-*Mj9@`EHXMZZgF6ujjfloj5HTfslr#mbh+SfhH38oVq1Oc>Ztuvk& zvX_{C2nc4Py~is|=_2KIS>|dh>*FXfi}^=2?nE~cQ2|vU3JeF_qVMa&*2l_@7^%aE zC7qc_o0{*}yg|sk217)EF>>j=xjO!9Q2lBVU~eRRQjPz11(Vmh))K8YT#}5~B~H)? zMdIFM6QRRR5Jfgv-U70i-Ght&P42D!HqjI8p{{#AqwXhEd=v~bB%V&~0UJy+2%kL&po0ki_&j!ZOH%+=mt4wzL+40A zsKv1ImJ7VWn%POQ3d_ilxG704pp_KgXV7ofjHFN90!&@=k_@&SG$wS<`X%!U%3=~d zFUqeVgnv&hD%C9|jqPf^;eQCDAzy8|I^Bj6yMg0JV?V;;e}C3QQ6x%l$9;o{;utVA zzcx1m8=l!k0_&NHlB`50oDT;&G7Hz>R+mSJxz&vcN zq>_`9DwJTlG1&9ORf-cwSEw_Z#D5W7rFN~sTtS6f0~Kus?r7Oaoev$@+^m6F;CW*Zy&GDQ@Hry1}?tmDJ6H9^dy+@;IS?J5XDy zl;ek=4#z6XJeMtAzg`{q@;h1iT44)Fjx<8CHdpKU)=DCB*?+q2k^>#ZqIVO(q=wW- zFKIg0iii3~L3ax@U!*~e@p=(zRm4%u-z`7^la?;VJ&J$tY(*kUZ7q{#bOcQvKl;O- zn?L~-J=m2S$r#6O<^ZfOX-lw(sfm&{p~HO;^uTa)Z_xkw~Z$?e0X!ay-Tj#TkE^JCZx_>2Yb5bc052 zeZEpo!Gu4?HZi=VTGvJ^_N>=4&o;z!P_vyAas)EdI}MD8!z4pP`Bru>7QM0)bbspz zQK00ab4jGu7Z>zZcgw2qNtJz>8GjMccFn$#kct$iv9^>5WpE2Q3|Djf2OLbbzs?uW zIgdv*%%Q5O6EJ)Fk=v!)yM?Z#M+Q8AqS#DeR`BOGB}}C%=F9&KpL=rfgPysT_4l_4 znlHTVk7&38=c`@mQi;@kYAbtJu9#%z8{hZ?MNx z;Hm0kbDSHApvDAQpdJH>bU<|02>e+@ubv_L6#eNNDoXU6in+GnG5h-3^yz_ll>*MC z_yU(3hJ^+TrkK3rm{M4s09fH2EWlsjmzytsDX1wg)?E4^!UBZ_-@YY2(l4$pRi4AB znZ|R78vpW@W@&^ONVT*w90^Eo4I6=`Zmd5WD}=ezjQLPDMp*|k@bx2k*SV$yRi%UYv>>^c0_ zH?a%EqWOqdtC!>U1(A-3_GRcSA|S*YJSO<|?Fp0$O&qI!K_mCqSyH_J-p3ke1hlJPm zW7@ySHu=$rb$%e0l@f%nk>7_P8z+tbyf6<3?`$%5H;gkR?WS;5Uw>RB?R(jwJu@|c zqqSo=Aw#_JA_!^d8Z3~GtIJk074QxBEb>?q@ z;(EBXxkqrhzibK$X$cw6k##WgwHcrx*A0hz!O-EX5steBNx(uPdJye9CT{luDWWd7 z;Y#rxm5%r{ed1NY@$~!Zbc?1(;lC=|4^D+XaI2PKmKBO^Um%GUxjrde(VgRBxLh2) zIfF)LF){!Y2!9m4}X(0)*e0~S3?R&Asmy$ zVt8lS0tmKe-qe@sY?u9x;sgr1tpeW_=?qa=)&bXb(glhKHp-rJ6yJ}x|@%RI-gS74t|_)O2E9E z0KV^K*$N`CR2XRPvbdlw)8Ems4PjH5FBlVd{y2(Hwq}JrDTf-<^}fwFq~*G_=voT-m3{?+#aaxr02GGUggy-o5&!={ z29gywCh9N>!jUqBP(y8M#Ct+IlUS|>px^>!I3!3RU*fjn?sfF`s-1LI z$(aVtvXGC%5%%n`I}8nLv!sj;H~@X0!cN$eILg=2BTIiKmk4&1s!%qskwP6!#s3JT}aat~NxsiTQjBOoN>pmo7ghR3%$TC)e#;;FZpL<1X=E8Cy&Y2|V| zIr1lal3hqm<{sVPH7s5PUaJQl*cf?p-UJhWa<9k9XEm+dx>6t~a!vc}C56_1TnJU# z=3}Zoex+X&%Ii>*WP#G4lVJ4$YT|Rz!|zB0`R9{T>8nb6rN_*`3ONi*Wmv`{U3U5q z&UKd~U*xcwWD1S1XM{Vs&u|S7Q4;M0kZhj;GnN#VP=gG}bdEC$VHY5d4LSmFNH{7! z0}FalGrGwNF|Y*nX_Hb9t_lCPF103db7;}Pa)cSmEQvRWbrAiEUcU{5XG(K(rG^&4xmx!zJvRxxMw7_s z_U(5&kU&Tkwk9xcHZG>^h8C){yUAqbS_%;IwI&qnV|jF5{gQmey5*QRD4sm(@HQ>( z_tT|?T$^1Kzg{u#R=?o51tG(EoixNN1X)3#BK3lO(hr)UG9eR=O@RQ2C9t(1q3z>~8kVH4a)q$)jD2UMswMf(rJxeM1gz$N`+!3+S z%y>d^Xa6%2X4q{zXx1ThLWlk^q>~w>1sBu`8R7~*~ZLc+gYtvNhXih7*k}KC;gA)Nv);_2giCh-&Mp~s{z123&Gy_dhw{D;vvjNE! zt7~TDMtGr=G?Z`7JL~j_JXrSQq25dU6g!}icyj7cksDz(J9?<6faH?{Dt!upC^PPL9D?)CZCB199XU7f)zo8=RDYUzOzgjchC@j^aBAf(LS7zzx#2 zT6=0UFU(I-GI8fel3wkLl1*ji8OG95pZBT%nsky`Zi7+dBVZ?k_$|TujC^#~%URKY zC&ddF3>PF`LmmSP%?e9uimp&l`slfYuT@5NbQ6TiKj9a_RJ2#gp{<}KSvwP5e3KJ+ z1IG{O5d3djr$MJR6IEDTAXPH}q!ojk-7wfMOFMZfsL{Me4FzF&2_ z>}koaM}vOlQy^_hePsE8Ks^58Fm8TZa+~qOe;*b&q&0y+YsU{`3T~Ia@S|g1E<<+L zW`COl@?nbWxuGW10)khuAhvlbzg69;zP2@cJ$Z+zk29r7<9_l=DWNB)SRFPL5Pwu( zP8lJR2zumPBrt`9Iv+NhzAQbQnG9ds1B-?o11y~EsrRrGqYuanXQ-5OO&apv7u}4+ zrrtL?Ia+;`z81Xp?445h zph8+NFIJVbrPHgS*w3KTQL4?-NET2X%p7ZT2Dgo>YNew>Q36{?H-1BuwnPhdFM7~X+E{JfoIPCQbOOyoM z(fcW78^m1H`FCr9BSyF zs01j|dthl&=|{On3XJN#BG-F5H2syA?vF_mLeYH;gQdZQ4qNe}W@x6Si>mj0${Ki} zT@J3}3lL5&PAO&L~5Pq`fx{InHm1W=4L9gr1^j~xSMdP@a#2lR#N#eTss zEQN(HG^c^Z8z1Dogcmqo2On}@)i(5i*r#?Ts3g#40dhm^FcbG9(G=9W7Hr+R`_Yzs zpF{*sDJurw38(mnh#ex9=JbGeeyAKJdqUa2?DokaYK0>mD7(E}V*mt*Yft)(qh{!| z?a18M6X4cK(5!Y?`N=s03@PBleYjnwGZ_EgR|>~^%}>E z4(Dk@|B-8$ZCN4V#hZvCNTqyh*DnN}0<(+6)`3|$%XzVbegW0x3=iH`#(feQeVd)K zr^mTRH?u1sQP)-h2(1Xey?*+8;_4q-YTd88wt+5V+0Z+NGN+3xmkDwPWM4i{DcK`* z1(v`t8Qw%mfL}idFp8LWQa3l~;kPDI%25is`TjhSk54b46QI^!eSV=Fh|q#A29dg; z0{|!EVDU_W0QB3#JI&NB_^BFJ5-!Ug1`q}COZyBH5Jfe@u8vYlz!bE>Pf^Q4gXLc} z#4L$$;Cgn15JXXcxv--EiOpyGLdJ*aEpk9uqd$4k-iC7iK=5IPG20)%wy&$lLPE6X zxbh%vVQLT&4vSK^0WcBI?ih~wr@8Pf1hoMzBVc45W7>nc%#o~u`EAx@&So2gg%rcy zVn$(XLWFEoLYlVU4kUPS@yOAuQjk_FRXgTJYbP%^pw|cV6{76)_v&?iSZG3)fgzR* zNzhOli(@Bn18q)6L-rsM0gbf(xpAAEHB^s+DAiDj;$D^^l2(I+c6Y`wjuqS>P1P52 z1+DF6;nCY__DGamxfA)?MKGjlm1iNk>K3^Bee)~5W)e;KYlx8_QtKh1{*#T$@kR#5 zJYwjAY4Z&Gd-`qF-Zs~ zBN&+4Amzp-VRKk4Mv>v--7@Lzz=a-mMzFJ+KyD>Pcw{$FcQfXCk3SZ63AoFg&Ksak ztNei*C!}rwoQuT-)T9=r`6bYvsToxoOUGhi3to1%+6HRGU9Gbth!~%dutr|eWhhbi zo6>EJH;9R5Ke9-9sEmMrIH2++4@gkG5p|ic2|Uh6bsVW6ys@KH50ft5AHx?;T;|;k zHr1WOcTtp>k$~RI3V6ectUI9C#?|fOZHa%%oA4c|^O?e&$g{64wj_IALj& z_Ju~FCe#XtpfXsq=hP@SPVHak67B>2q&WOx1aGiVLTX$w6C8-j9e)OMR1{##n**5= z%|9Se|JF9z+74igqlBQob)r87I%XwA7Hp5^!(E8ba~Y^EydKGlIyI_KhrYnsS}%f( z#2%eGVsQf`J9TjXX*LZDl`bG27ge;>_+RHy&P217c_sVsgwmkPaa5pmct>{Eh6`U~ z)uI)cLLdY#aQG*=n5VXPiZI6{ATt_u2}11%kOeki(IMAk{1!kXd+6jWt8%+QdzLe& z1|z(r_p-PqqAighl5x`F0`O;<-zq|ofl)vpILFf%C>h7H)egRcgy(4#OW{Mr0^cz*A^G7pV!crN>d!aByxCrV(#aXh7_eZ0Z#pf;Po&rG zkNgxu7Qu*~mUAnzdm$#h4Q>np%d{E%WEHET54tiendH?ZY<9R6%Pc{rqc^KWTjUN& zJao1SI)PsqFY%+Ro;@gTN&pvjJ#0!k&OtIDv&fIVyuQ?3nmmLd>|d$gF52lw%Z|Yn z8)lrg@Y&bR6_4;s#}}NPW|mt!C72>aXO7HM3DY&g2jJ#@Bf)c|JpB4&(;=Vnm{cYM z42)QKJjAp~qGXV*2^>vf;V?3_^B8iauvZq<&krTP3?{$xkoQHQdH0`%WK|{iiObc}QmM`w6HzM=E0edQ0Am{ZjGNvQdnTJr8CV!9T^oV!R zEmtI+!^@y!T)6nKB*oBZ`eU;1H4QFHcSWmV#6~GXx~!h|!uMpq>+J>{?>(H!i#sDs ztdPcpvb}BG8?Nh1GAqKvPd{b{!S8to7s%`>NV6Je1gBuKmS-kzJ8%Gt2u|S?sV&K7 zyr0b4=6)mfJ<~vRF+R3FjFLyuniA7c1!wpR91?Yy(jMhfXQm-5fgpV8%2|eFW^ANV zTo=@}wWOc%xpa|8)C4AQA?CJ)n3TmTIi32uQ{rrMy|cTH)iEVUHDcK+2GoYB z!&i(91(LA=UQz0)lwHf8>jDH4Nv)nJ3#S3NPt-$8q`4sHr4%u_aM4gfN|E}0SA}sB z^x8BSJ+PJ_x-Ta6sx@BMEr!%pFZlQbMG;{vmzJZTaM7fuLDcl>2>T;Us@`W|we;%O zZ6Qo~q}@%oy>v-w?ztY3ID(wX)`r5K|IET%mb8NDas@7giZ9!b-$D{Nt_~$(2LaKQ zb}qzs4Xk#D_K$MHb>Ge73i$xmoXvI1u^F}x%rB>n7?^+cKMO!X6OipwfsL}_HZah{W z2YqKM-sPVP^O>ym8WB+!Ybt2cJZq2OipBYVRX6XnAG&v;6kfs4OD9Mh&bCJtk9aHs z;%PNs;&l(Vd;}GRiJame0Y-!>`n594F?KlfC3bFa&RA|?T~E&1%(nH0mIl!G($>t| zw5nXER*HI^#dtnOH#Rr!icjWkaJeYBt)Egz-T6G2PjeQu@OxamN|1w-XyN9 zzcTNJ5z8=hiH^ZuT{5tyZ?bBSiALKDi5}eaIOLsJeJB71gJ3QKz%rTBlT5uO=K?=j zq~;JffW0x|t3_1pd7MZh)96y#!CAF!Fe1J=cT!+O2{9=qOiz3cT7^?GM`Jg1l=E;4 zd>^_<$)Z$6%{|k_p~B2w;(!pY^69s0zIM+AYb-b{Hot^EGelCsAv!+V>zcTvieWqx zIPewW6L$y)8J?SpjOZ$6Vr|O9M^K@ErR*LZjo(^e7s@sm4O;dY_38wuT-tv5o|5M! zW@327E1ad3Dz(dqW}DHrkEFu&7gol!0%D1nJk`sMTAoC{|#EIQOg?! zRmM*lxpNe6)?eCeF$rKf?_awGkza?8{k5|Y2SQ>z&82$AGie0__+h%|AemAs?duv2 z>UX#-52h14@mP69fQj=!*b`Y^?Z}`>GQg6#SuXWCe8WZgz9pwU+0D;xkhE-Y10n`# z*3d3Edw5Tm!puIE%&I8VNLXHFocqH)l!gWU!wFo4%*YQPtpFi`Pr%Vuoq{S3QY2gT zHQ~AQb~Ibu;>qqy3Iv{3`>dtawuOH)XgPg2PQwk4kz~>6Bs?It(*q^#@617fm^ymx zJ3i-y6e^onv#I2346w18xmkRp$xK+F?EI&ZYtXx z?>(!!1E{5rQ zo!DZjewcBQWJ4Y8SD+xe49}V$BNXp!On|e_PXZDWggaHD6>JUz1PD3|Q(G5J#%$HC zb`E&6&B56cd*bd3tEtV@l7Rw(L-`E87gP|89^AyTs4rfr3<^Igv6uaRB`)N&(vu-% z?iAZfwEdQi9A1I*hpoyv!i3aq0#{1+Fl*?LkewtV3R97L;qTwoyvLa{ZJxl|>oztf zlp6t95r-cee8_j?T?h208}VXva(FrPnm@E=VI(qIo&<_Wj>UXE>+_dYpM5kR`<~i~ zPeXWotr&EL_YFvX*)Lm-cwl@MJRAfaElNLry+kRCQ0**lb4S~&{Jt%vG&pC3K`_o@ zr>%;Hilhc(%2elA#oVC_x9(;_@LyS|7Fw;a?&&q`0>Cc?{_3>D58S5uf4DyssCBx#oVu#>qmuejp!M|QaK?pi@Jtm@>%Rf%ue4|DK?24Z<4}C%6!_Bf$Q0< z(9C6KY?+*jM3Pj0BKT7(G8P-Wj0!GO{{(hj=I$M1Qj(8F-EqH#(y>Ov5QaA%`W!V- z5EOBg_giSu?;McpEYfgw`4_-b*Ft51>0pSkK6sdf#;jz5p1Q&pzq@7ml`&l($8ARq zoOancYUm_TVgBPu>8hKHDj}3SDu5-X{{N3d%Yo!{yEy>FvR&QTIUDeX6glQk^PlCL zAwJaM21kix(lmgZiAAXKp<3})=zJD+=>!~nqO*N^og7*Ia+@I?3R+q|uu;*pHb9?X z40j%m*AIx170;BvIaDtm{OaiNRx)F`k{-Vq-+nhCePqP^=0t*TgH-X1%E!>AhqXoy zQo%@}5k|RG0CEIK|4500-T1dUz+Y=q>2SWJQI?=uY@ z&s=gOP|JnTUh(X0|FyhB*l29Us4eKcB9x~9q|Mx9c9pe-m|n`^|H!ht3@n1MJv9c2i*Fv7 zG@8H`%hjwa<+q_m>i6-4+8ZW=Hjx}oLay%x;$K%%1EeK+^qT1RQ^~xSE?cetc_mFU zcTXTP4^ij9U6F{Z<0v;vCAc>-%55LD5^d$mGVdpMh9cS}5d2gc!s&5fThqo4WK|LQ z8|rGSlW|yBQPD8hH}%l%z+*Ut0h0qOU%7Kgq^gP+M$U<-;d> zagzdc9qXRwAtDU|F7;pVNm>x!fn*BOn~fs(!ByJKFYn#_{B)3nG`YP1#PrIVW!hM1 zgR@Nz&8$u+<;-hw}`mEjMTk61ebbF&k--Thtxe zftpx~S{Baaaxp8iG5h}_PoZ^vK29y?nTkvzlPHu+s;F@aj#I+NCTw=vHh~<~{W0)diO3(0vQR3nY=Isi0b4wK z(y)Uku=ioY3GqNNIAOU-rPOwvhZ{TY)5S;i;7fN2UMfu(aR2}SkRJd5^pF4m8Uz3U zs1yJI-vIysunPbHoi6|YxMKkTyAA*VIFbMWH3I+u02%-Q<0t?CL_-1qN5%mFjs^z+ zyaE6KfD`}#`#}Hz^qm0!aM1t&sMrGl0owoo0qYC^qS*idK*j+84FCWD0I}+lkB^lN A2LJ#7 literal 0 HcmV?d00001 From 36dda06bc24e7f2599cdf473a9d6c8a6b0db71b2 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Fri, 21 Oct 2022 05:06:33 -0700 Subject: [PATCH 19/28] Fix scene_broadcaster_system test (#1766) Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- test/worlds/shapes_scene_broadcaster_only.sdf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/worlds/shapes_scene_broadcaster_only.sdf b/test/worlds/shapes_scene_broadcaster_only.sdf index dff73115c5..dc2d4540eb 100644 --- a/test/worlds/shapes_scene_broadcaster_only.sdf +++ b/test/worlds/shapes_scene_broadcaster_only.sdf @@ -3,7 +3,7 @@ 0.001 - 0 + 1 Date: Fri, 21 Oct 2022 10:58:57 -0700 Subject: [PATCH 20/28] Fix thruster integration test (#1767) Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- test/integration/thruster.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/integration/thruster.cc b/test/integration/thruster.cc index d92b3f15c3..b6b0e589f1 100644 --- a/test/integration/thruster.cc +++ b/test/integration/thruster.cc @@ -245,7 +245,7 @@ void ThrusterTest::TestWorld(const std::string &_world, // linear_velocity) / (angular_velocity * propeller_diameter)) // omega = sqrt(thrust / // (fluid_density * thrust_coefficient * propeller_diameter ^ 4)) - if (_calculateCoefficient && gz::math::equal(angularVelocity, 0.0)) + if (_calculateCoefficient && !gz::math::equal(angularVelocity, 0.0)) { _thrustCoefficient = _alpha1 + _alpha2 * (((1 - _wakeFraction) * propellerLinVels[i].Length()) / (angularVelocity * _diameter)); From 132555a7635cd5cd1684810d9fbec768a35dc658 Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Fri, 28 Oct 2022 21:23:08 +0800 Subject: [PATCH 21/28] Some minor changes to hydrodynamic flags test (#1772) This commit changes the url to use the more recent url. It also removes the scene-broadcaster plugin as we don't need it in the test itself. Signed-off-by: Arjo Chakravarty --- test/worlds/hydrodynamics_flags.sdf | 34 ++--------------------------- 1 file changed, 2 insertions(+), 32 deletions(-) diff --git a/test/worlds/hydrodynamics_flags.sdf b/test/worlds/hydrodynamics_flags.sdf index 51ae7a93bd..a109f5f4a4 100644 --- a/test/worlds/hydrodynamics_flags.sdf +++ b/test/worlds/hydrodynamics_flags.sdf @@ -1,16 +1,7 @@ - - - - - 0.0 1.0 1.0 - 0.0 0.7 0.8 - - 0.001 1.0 @@ -19,14 +10,6 @@ filename="ignition-gazebo-physics-system" name="ignition::gazebo::systems::Physics"> - - - - @@ -54,7 +37,7 @@ 0 0 1 0 0 1.57 - https://fuel.ignitionrobotics.org/1.0/accurrent/models/MBARI Tethys LRAUV + https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV 5 0 1 0 0 1.57 - https://fuel.ignitionrobotics.org/1.0/accurrent/models/MBARI Tethys LRAUV + https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV triton @@ -335,18 +318,5 @@ true - - - - 0 0 -1 0 0 3.1415926 - https://fuel.ignitionrobotics.org/1.0/mabelzhang/models/ABCSign_5m - start_line - - - 0 -25 -1 0 0 3.1415926 - https://fuel.ignitionrobotics.org/1.0/mabelzhang/models/ABCSign_5m - finish_line - - From 61df2c3abe88bd8c428dde3e823227ff9a4671ed Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Thu, 3 Nov 2022 12:17:07 -0700 Subject: [PATCH 22/28] 3 to 6 20221013 (#1762) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * 🎈 3.14.0~pre1 (#1650) Signed-off-by: Louise Poubel * Remove redundant namespace references (#1635) Signed-off-by: methylDragon * 🎈 3.14.0 (#1657) Signed-off-by: Louise Poubel Signed-off-by: Louise Poubel * readd namespaces for Q_ARGS (#1670) * Remove actors from screen when they are supposed to (#1699) # 🦟 Bug fix Supercedes #1697. Note: When forward porting we will have to update the hashmaps to erase the new hashmaps created. Fixes # ## Summary Found that when actors are De-spawned the actor visuals are not destroyed. This commit addresses this bug by adding the missing remove logic in RenderUtils. ## Before ![bug](https://user-images.githubusercontent.com/542272/189558600-196d98c5-1dcf-4d6c-93d6-7493df38c0e4.gif) ## After ![no_bug](https://user-images.githubusercontent.com/542272/189558924-3f2e3c5d-68f3-4d80-aee4-3dc3ce6742a1.gif) ## Notes: Theres a lot of hashmaps being populated in RenderUtils whenever a new actor is spawned. I hope I've caught them all. Also while I need these working in garden (as all the projects Im working on use garden), should I backport these changes? Signed-off-by: Arjo Chakravarty * Update examples to use gazebosim.org Signed-off-by: Nate Koenig * Citadel: Removed warnings (#1753) Signed-off-by: ahcorde * Added collection name to About Dialog (#1756) Signed-off-by: ahcorde * Convert ignitionrobotics to gazebosim in tests directory (#1757) * Convert ignitionrobotics to gaazebosim in tests directory Signed-off-by: Nate Koenig * fix gz-gazebo Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig * Convert ignitionrobotics to gazebosim in sources and includes (#1758) Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig * Convert ignitionrobotics to gazebosim in tutorials (#1759) Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig * Final update of ignitionrobotics to gazebosim for citadel (#1760) Signed-off-by: Nate Koenig Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig * remove PlotIcon (#1658) Signed-off-by: youhy Signed-off-by: youhy * Fix UNIT_ign_TEST Signed-off-by: Nate Koenig Signed-off-by: Louise Poubel Signed-off-by: methylDragon Signed-off-by: Arjo Chakravarty Signed-off-by: Nate Koenig Signed-off-by: ahcorde Signed-off-by: youhy Co-authored-by: Louise Poubel Co-authored-by: methylDragon Co-authored-by: Jenn Nguyen Co-authored-by: Arjo Chakravarty Co-authored-by: Nate Koenig Co-authored-by: Alejandro Hernández Cordero Co-authored-by: AzulRadio <50132891+AzulRadio@users.noreply.github.com> --- CMakeLists.txt | 2 +- CODE_OF_CONDUCT.md | 2 +- CONTRIBUTING.md | 2 +- Changelog.md | 549 ++++++++++-------- NEWS | 2 +- docker/README.md | 2 +- docker/scripts/build_ign.sh | 6 +- docker/scripts/upload_json_benchmark.sh | 8 +- examples/standalone/joy_to_twist/README.md | 4 +- examples/standalone/joystick/README.md | 2 +- examples/worlds/actor.sdf | 6 +- examples/worlds/actors_population.sdf.erb | 4 +- examples/worlds/breadcrumbs.sdf | 2 +- examples/worlds/camera_sensor.sdf | 2 +- examples/worlds/depth_camera_sensor.sdf | 2 +- examples/worlds/elevator.sdf | 2 +- examples/worlds/fuel.sdf | 14 +- examples/worlds/fuel_textured_mesh.sdf | 4 +- examples/worlds/gpu_lidar_sensor.sdf | 2 +- examples/worlds/import_mesh.sdf | 2 +- examples/worlds/log_record_resources.sdf | 2 +- .../worlds/multicopter_velocity_control.sdf | 4 +- examples/worlds/plot_3d.sdf | 2 +- examples/worlds/quadcopter.sdf | 2 +- examples/worlds/sensors_demo.sdf | 2 +- examples/worlds/tracked_vehicle_simple.sdf | 2 +- examples/worlds/tunnel.sdf | 279 +++++---- include/ignition/gazebo/Entity.hh | 3 +- include/ignition/gazebo/ServerConfig.hh | 4 +- src/Component_TEST.cc | 4 +- src/Conversions.cc | 126 ++-- src/Conversions_TEST.cc | 28 +- src/EntityComponentManager.cc | 14 +- src/EntityComponentManager_TEST.cc | 66 +-- src/SdfEntityCreator_TEST.cc | 80 +-- src/SdfGenerator_TEST.cc | 12 +- src/ServerConfig.cc | 38 +- src/ServerConfig_TEST.cc | 8 +- src/ServerPrivate.cc | 8 +- src/Server_TEST.cc | 30 +- src/SimulationRunner.cc | 28 +- src/SimulationRunner_TEST.cc | 396 ++++++------- src/SystemLoader_TEST.cc | 2 +- src/TestFixture.cc | 6 +- src/Util_TEST.cc | 2 +- src/World.cc | 8 +- src/cmd/cmdgazebo.rb.in | 4 +- src/gui/AboutDialogHandler.cc | 9 +- src/gui/GuiFileHandler.cc | 2 +- src/gui/GuiRunner.cc | 2 +- src/gui/Gui_TEST.cc | 12 +- src/gui/plugins/align_tool/AlignTool.cc | 18 +- .../component_inspector/ComponentInspector.cc | 42 +- src/gui/plugins/entity_tree/EntityTree.cc | 6 +- .../JointPositionController.cc | 12 +- src/gui/plugins/modules/EntityContextMenu.cc | 18 +- .../playback_scrubber/PlaybackScrubber.cc | 2 +- src/gui/plugins/plot_3d/Plot3D.cc | 6 +- .../resource_spawner/ResourceSpawner.cc | 12 +- src/gui/plugins/scene3d/Scene3D.cc | 40 +- src/gui/plugins/shapes/Shapes.cc | 2 +- .../transform_control/TransformControl.cc | 10 +- .../plugins/video_recorder/VideoRecorder.cc | 16 +- src/gui/plugins/view_angle/ViewAngle.cc | 2 +- src/ign.cc | 54 +- src/ign.hh | 2 +- src/ign_TEST.cc | 13 +- src/network/NetworkManagerPrimary.cc | 2 +- src/network/PeerInfo.cc | 28 +- src/network/PeerTracker.cc | 2 +- src/rendering/MarkerManager.cc | 122 ++-- src/rendering/RenderUtil.cc | 12 +- src/rendering/SceneManager.cc | 28 +- .../ackermann_steering/AckermannSteering.cc | 34 +- src/systems/altimeter/Altimeter.cc | 1 - .../apply_joint_force/ApplyJointForce.cc | 8 +- .../battery_plugin/LinearBatteryPlugin.cc | 14 +- .../battery_plugin/LinearBatteryPlugin.hh | 2 +- src/systems/breadcrumbs/Breadcrumbs.cc | 6 +- src/systems/buoyancy/Buoyancy.cc | 10 +- .../CameraVideoRecorder.cc | 6 +- .../CameraVideoRecorder.hh | 2 +- .../ColladaWorldExporter.cc | 10 +- src/systems/contact/Contact.cc | 2 +- .../detachable_joint/DetachableJoint.cc | 6 +- src/systems/diff_drive/DiffDrive.cc | 36 +- src/systems/imu/Imu.cc | 2 +- .../joint_controller/JointController.cc | 10 +- .../JointPositionController.cc | 10 +- .../JointStatePublisher.cc | 6 +- src/systems/lift_drag/LiftDrag.cc | 32 +- src/systems/log/LogPlayback.cc | 6 +- src/systems/log/LogRecord.cc | 8 +- .../log_video_recorder/LogVideoRecorder.cc | 18 +- .../LogicalAudioSensorPlugin.cc | 26 +- src/systems/magnetometer/Magnetometer.cc | 2 +- .../MulticopterVelocityControl.cc | 8 +- .../MulticopterMotorModel.cc | 14 +- .../performer_detector/PerformerDetector.cc | 6 +- src/systems/physics/EntityFeatureMap_TEST.cc | 4 +- src/systems/physics/Physics.cc | 124 ++-- src/systems/pose_publisher/PosePublisher.cc | 14 +- .../scene_broadcaster/SceneBroadcaster.cc | 36 +- src/systems/sensors/Sensors.cc | 2 +- src/systems/thermal/Thermal.cc | 4 +- src/systems/touch_plugin/TouchPlugin.cc | 2 +- .../track_controller/TrackController.cc | 50 +- src/systems/tracked_vehicle/TrackedVehicle.cc | 50 +- .../triggered_publisher/TriggeredPublisher.cc | 2 +- .../velocity_control/VelocityControl.cc | 28 +- src/systems/wheel_slip/WheelSlip.cc | 2 +- src/systems/wind_effects/WindEffects.cc | 2 +- test/integration/ackermann_steering_system.cc | 16 +- test/integration/air_pressure_system.cc | 6 +- test/integration/altimeter_system.cc | 6 +- test/integration/apply_joint_force_system.cc | 2 +- test/integration/battery_plugin.cc | 16 +- test/integration/breadcrumbs.cc | 30 +- test/integration/buoyancy.cc | 16 +- .../integration/camera_video_record_system.cc | 6 +- test/integration/components.cc | 14 +- test/integration/depth_camera.cc | 4 +- test/integration/detachable_joint.cc | 8 +- test/integration/diff_drive_system.cc | 16 +- test/integration/each_new_removed.cc | 2 +- test/integration/elevator_system.cc | 2 +- test/integration/entity_erase.cc | 4 +- test/integration/examples_build.cc | 14 +- test/integration/gpu_lidar.cc | 4 +- test/integration/imu_system.cc | 8 +- test/integration/joint_controller_system.cc | 16 +- .../joint_position_controller_system.cc | 8 +- test/integration/level_manager.cc | 22 +- .../level_manager_runtime_performers.cc | 22 +- test/integration/lift_drag_system.cc | 8 +- test/integration/log_system.cc | 20 +- .../logical_audio_sensor_plugin.cc | 6 +- test/integration/logical_camera_system.cc | 22 +- test/integration/magnetometer_system.cc | 8 +- test/integration/multicopter.cc | 18 +- test/integration/network_handshake.cc | 10 +- test/integration/performer_detector.cc | 4 +- test/integration/physics_system.cc | 184 +++--- test/integration/play_pause.cc | 14 +- test/integration/pose_publisher_system.cc | 14 +- test/integration/rgbd_camera.cc | 4 +- test/integration/save_world.cc | 2 +- test/integration/scene_broadcaster_system.cc | 34 +- test/integration/sdf_frame_semantics.cc | 22 +- test/integration/sdf_include.cc | 6 +- test/integration/sensors_system.cc | 4 +- test/integration/thermal_system.cc | 6 +- test/integration/touch_plugin.cc | 4 +- test/integration/tracked_vehicle_system.cc | 22 +- test/integration/user_commands.cc | 20 +- test/integration/velocity_control_system.cc | 8 +- test/integration/wheel_slip.cc | 57 +- test/integration/wind_effects.cc | 6 +- test/performance/level_manager.cc | 10 +- test/performance/sdf_runner.cc | 18 +- test/plugins/TestSystem.cc | 2 +- test/worlds/breadcrumbs.sdf | 2 +- .../worlds/test%20world/2/test.sdf | 5 + .../worlds/test%20world/2/test.world | 5 + .../worlds/test%20world/2/thumbnails/1.png | Bin 0 -> 6279 bytes test/worlds/include.sdf | 2 +- test/worlds/log_record_resources.sdf | 2 +- test/worlds/save_world.sdf | 6 +- tutorials/battery.md | 2 +- tutorials/detachable_joints.md | 2 +- tutorials/distributed_simulation.md | 2 +- tutorials/erb_template.md | 8 +- tutorials/gui_config.md | 8 +- tutorials/levels.md | 12 +- tutorials/log.md | 2 +- tutorials/logical_audio_sensor.md | 6 +- tutorials/mesh_to_fuel.md | 18 +- tutorials/migrating_ardupilot_plugin.md | 6 +- tutorials/migration_link_api.md | 2 +- tutorials/migration_model_api.md | 2 +- tutorials/migration_sdf.md | 2 +- tutorials/migration_world_api.md | 2 +- tutorials/physics.md | 4 +- tutorials/point_cloud_to_mesh.md | 22 +- tutorials/rendering_plugins.md | 12 +- tutorials/resources.md | 24 +- tutorials/server_config.md | 8 +- tutorials/terminology.md | 2 +- tutorials/test_fixture.md | 2 +- tutorials/triggered_publisher.md | 4 +- tutorials/video_recorder.md | 2 +- 191 files changed, 1949 insertions(+), 1860 deletions(-) create mode 100644 test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf create mode 100644 test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world create mode 100644 test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/thumbnails/1.png diff --git a/CMakeLists.txt b/CMakeLists.txt index 38008583c9..c97405df04 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -235,7 +235,7 @@ configure_file(${CMAKE_SOURCE_DIR}/tools/desktop/ignition-gazebo.svg.in ${CMAKE_ # disable doxygen on macOS due to issues with doxygen 1.9.0 # there is an unreleased fix; revert this when 1.9.1 is released -# https://github.com/ignitionrobotics/ign-gazebo/issues/520 +# https://github.com/gazebosim/gz-sim/issues/520 if (NOT APPLE) ign_create_docs( API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md" diff --git a/CODE_OF_CONDUCT.md b/CODE_OF_CONDUCT.md index 820e43fdbb..65eec816ef 100644 --- a/CODE_OF_CONDUCT.md +++ b/CODE_OF_CONDUCT.md @@ -56,7 +56,7 @@ further defined and clarified by project maintainers. ## Enforcement Instances of abusive, harassing, or otherwise unacceptable behavior may be -reported by contacting the project team at [https://ignitionrobotics.org/support](https://ignitionrobotics.org/support). All +reported by contacting the project team at [https://gazebosim.org/support](https://gazebosim.org/support). All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 147239ce5f..fbcac678cf 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -1 +1 @@ -See the [Ignition Robotics contributing guide](https://ignitionrobotics.org/docs/all/contributing). +See [Gazebo's contribution guide](https://gazebosim.org/docs/all/contributing). diff --git a/Changelog.md b/Changelog.md index 2487f3b1ce..3e0257d495 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2122,7 +2122,56 @@ 1. Add window focus upon mouse entering the render window * [Github pull request 97](https://github.com/ignitionrobotics/ign-gazebo/pull/97) -## Ignition Gazebo 3.x +## Gazebo Sim 3.x + +### Gazebo Sim 3.14.0 (2022-08-17) + +1. Change `CODEOWNERS` and maintainer to Michael + * [Pull request #1644](https://github.com/gazebosim/gz-sim/pull/1644) + +1. Replace pose in `ViewAngle` with `GzPose` + * [Pull request #1641](https://github.com/gazebosim/gz-sim/pull/1641) + +1. Fix loading worlds from CLI + * [Pull request #1627](https://github.com/gazebosim/gz-sim/pull/1627) + +1. Quick start dialog + * [Pull request #1536](https://github.com/gazebosim/gz-sim/pull/1536) + +1. Quiet `libSDFormat` console on --verbose 0 + * [Pull request #1621](https://github.com/gazebosim/gz-sim/pull/1621) + +1. Add Ackermann Steering system (backport from Fortress) + * [Pull request #1613](https://github.com/gazebosim/gz-sim/pull/1613) + +1. New Apply Link Wrench system + * [Pull request #1593](https://github.com/gazebosim/gz-sim/pull/1593) + +1. Implement Component Inspector `Vector3` with common widget `Vector3` + * [Pull request #1569](https://github.com/gazebosim/gz-sim/pull/1569) + +1. Helper function to get an entity from an entity message + * [Pull request #1595](https://github.com/gazebosim/gz-sim/pull/1595) + +1. Ignition -> Gazebo + * [Pull request #1596](https://github.com/gazebosim/gz-sim/pull/1596) + +1. Add Model::CanonicalLink getter + * [Pull request #1594](https://github.com/gazebosim/gz-sim/pull/1594) + +1. Implement Pose3d with common widget pose + * [Pull request #1571](https://github.com/gazebosim/gz-sim/pull/1571) + +1. Test fixes and updates + * [Pull request #1545](https://github.com/gazebosim/gz-sim/pull/1545) + * [Pull request #1531](https://github.com/gazebosim/gz-sim/pull/1531) + * [Pull request #1599](https://github.com/gazebosim/gz-sim/pull/1599) + +1. Bash completion for flags + * [Pull request #1504](https://github.com/gazebosim/gz-sim/pull/1504) + +1. Add new `GZ_GUI_RESOURCE_PATH` to help message + * [Pull request #1470](https://github.com/gazebosim/gz-sim/pull/1470) ### Ignition Gazebo 3.13.0 (2022-06-01) @@ -2184,606 +2233,610 @@ ### Ignition Gazebo 3.12.0 (2021-11-11) 1. Prevent creation of spurious `` elements when saving worlds - * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + * [Pull request #1192](https://github.com/gazebosim/gz-sim/pull/1192) 1. Added support for tracked vehicles - * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + * [Pull request #869](https://github.com/gazebosim/gz-sim/pull/869) 1. Add components to dynamically set joint limits - * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + * [Pull request #847](https://github.com/gazebosim/gz-sim/pull/847) 1. Fix updating a component's data via SerializedState msg - * [Pull request #1149](https://github.com/ignitionrobotics/ign-gazebo/pull/1149) + * [Pull request #1149](https://github.com/gazebosim/gz-sim/pull/1149) 1. Sensor systems work if loaded after sensors - * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + * [Pull request #1104](https://github.com/gazebosim/gz-sim/pull/1104) 1. Fix generation of systems library symlinks in build directory - * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) 1. Backport gazebo::Util::validTopic() from ign-gazebo4. - * [Pull request #1153](https://github.com/ignitionrobotics/ign-gazebo/pull/1153) + * [Pull request #1153](https://github.com/gazebosim/gz-sim/pull/1153) 1. Support setting the background color for sensors - * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + * [Pull request #1147](https://github.com/gazebosim/gz-sim/pull/1147) 1. Use uint64_t for ComponentInspector Entity IDs - * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + * [Pull request #1144](https://github.com/gazebosim/gz-sim/pull/1144) 1. Fix integers and floats on component inspector - * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + * [Pull request #1143](https://github.com/gazebosim/gz-sim/pull/1143) ### Ignition Gazebo 3.11.0 (2021-10-21) 1. Updates to camera video record from subt. - * [Pull request #1117](https://github.com/ignitionrobotics/ign-gazebo/pull/1117) + * [Pull request #1117](https://github.com/gazebosim/gz-sim/pull/1117) 1. Fix performance level test flakiness. - * [Pull request #1129](https://github.com/ignitionrobotics/ign-gazebo/pull/1129) + * [Pull request #1129](https://github.com/gazebosim/gz-sim/pull/1129) ### Ignition Gazebo 3.10.0 (2021-10-15) 1. Performance: use std::unordered_map where possible in SceneManager - * [Pull request #1083](https://github.com/ignitionrobotics/ign-gazebo/pull/1083) + * [Pull request #1083](https://github.com/gazebosim/gz-sim/pull/1083) 1. Enable new CMake policy to fix protobuf compilation - * [Pull request #1059](https://github.com/ignitionrobotics/ign-gazebo/pull/1059) + * [Pull request #1059](https://github.com/gazebosim/gz-sim/pull/1059) 1. Fix setting cast_shadows for visuals without material - * [Pull request #1015](https://github.com/ignitionrobotics/ign-gazebo/pull/1015) + * [Pull request #1015](https://github.com/gazebosim/gz-sim/pull/1015) 1. Remove duplicate XML tag in pendulum_links example world - * [Pull request #1002](https://github.com/ignitionrobotics/ign-gazebo/pull/1002) + * [Pull request #1002](https://github.com/gazebosim/gz-sim/pull/1002) 1. Enable sensor metrics on example worlds - * [Pull request #982](https://github.com/ignitionrobotics/ign-gazebo/pull/982) + * [Pull request #982](https://github.com/gazebosim/gz-sim/pull/982) 1. Improved doxygen - * [Pull request #996](https://github.com/ignitionrobotics/ign-gazebo/pull/996) + * [Pull request #996](https://github.com/gazebosim/gz-sim/pull/996) 1. JointPositionController: Improve misleading error message - * [Pull request #1098](https://github.com/ignitionrobotics/ign-gazebo/pull/1098) + * [Pull request #1098](https://github.com/gazebosim/gz-sim/pull/1098) 1. Adjust pose decimals based on element width - * [Pull request #1089](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull request #1089](https://github.com/gazebosim/gz-sim/pull/1089) 1. Fixed IMU system plugin - * [Pull request #1043](https://github.com/ignitionrobotics/ign-gazebo/pull/1043) + * [Pull request #1043](https://github.com/gazebosim/gz-sim/pull/1043) 1. Use QTimer to update plugins in the Qt thread - * [Pull request #1095](https://github.com/ignitionrobotics/ign-gazebo/pull/1095) + * [Pull request #1095](https://github.com/gazebosim/gz-sim/pull/1095) ### Ignition Gazebo 3.9.0 (2021-08-16) 1. Entity tree: prevent creation of repeated entity items - * [Pull request #974](https://github.com/ignitionrobotics/ign-gazebo/pull/974) + * [Pull request #974](https://github.com/gazebosim/gz-sim/pull/974) 1. Don't use $HOME on most tests (InternalFixture) - * [Pull request #971](https://github.com/ignitionrobotics/ign-gazebo/pull/971) + * [Pull request #971](https://github.com/gazebosim/gz-sim/pull/971) 1. Be more specific when looking for physics plugins - * [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965) + * [Pull request #965](https://github.com/gazebosim/gz-sim/pull/965) 1. Drag and drop meshes into scene - * [Pull request #939](https://github.com/ignitionrobotics/ign-gazebo/pull/939) + * [Pull request #939](https://github.com/gazebosim/gz-sim/pull/939) 1. Set protobuf_MODULE_COMPATIBLE before any find_package call - * [Pull request #957](https://github.com/ignitionrobotics/ign-gazebo/pull/957) + * [Pull request #957](https://github.com/gazebosim/gz-sim/pull/957) 1. [DiffDrive] add enable/disable - * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + * [Pull request #772](https://github.com/gazebosim/gz-sim/pull/772) 1. Fix component inspector shutdown crash - * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + * [Pull request #724](https://github.com/gazebosim/gz-sim/pull/724) 1. Add UserCommands Plugin. - * [Pull request #719](https://github.com/ignitionrobotics/ign-gazebo/pull/719) + * [Pull request #719](https://github.com/gazebosim/gz-sim/pull/719) 1. Setting the intiial velocity for a model or joint - * [Pull request #693](https://github.com/ignitionrobotics/ign-gazebo/pull/693) + * [Pull request #693](https://github.com/gazebosim/gz-sim/pull/693) 1. Examples and tutorial on using rendering API from plugins - * [Pull request #596](https://github.com/ignitionrobotics/ign-gazebo/pull/596) + * [Pull request #596](https://github.com/gazebosim/gz-sim/pull/596) 1. Add missing IGNITION_GAZEBO_VISIBLE macros - * [Pull request #563](https://github.com/ignitionrobotics/ign-gazebo/pull/563) + * [Pull request #563](https://github.com/gazebosim/gz-sim/pull/563) 1. Fix visibility macro names when used by a different component (Windows) - * [Pull request #564](https://github.com/ignitionrobotics/ign-gazebo/pull/564) + * [Pull request #564](https://github.com/gazebosim/gz-sim/pull/564) 1. No install apt recommends and clear cache - * [Pull request #423](https://github.com/ignitionrobotics/ign-gazebo/pull/423) + * [Pull request #423](https://github.com/gazebosim/gz-sim/pull/423) 1. Add 25percent darker view angle icons - * [Pull request #426](https://github.com/ignitionrobotics/ign-gazebo/pull/426) + * [Pull request #426](https://github.com/gazebosim/gz-sim/pull/426) 1. Expose a test fixture helper class - * [Pull request #926](https://github.com/ignitionrobotics/ign-gazebo/pull/926) + * [Pull request #926](https://github.com/gazebosim/gz-sim/pull/926) 1. Fix logic to disable server default plugins loading - * [Pull request #953](https://github.com/ignitionrobotics/ign-gazebo/pull/953) + * [Pull request #953](https://github.com/gazebosim/gz-sim/pull/953) 1. removed unneeded plugin update - * [Pull request #944](https://github.com/ignitionrobotics/ign-gazebo/pull/944) + * [Pull request #944](https://github.com/gazebosim/gz-sim/pull/944) 1. Functions to enable velocity and acceleration checks on Link - * [Pull request #935](https://github.com/ignitionrobotics/ign-gazebo/pull/935) + * [Pull request #935](https://github.com/gazebosim/gz-sim/pull/935) 1. Support adding systems that don't come from a plugin - * [Pull request #936](https://github.com/ignitionrobotics/ign-gazebo/pull/936) + * [Pull request #936](https://github.com/gazebosim/gz-sim/pull/936) 1. 3D plot GUI plugin - * [Pull request #917](https://github.com/ignitionrobotics/ign-gazebo/pull/917) + * [Pull request #917](https://github.com/gazebosim/gz-sim/pull/917) 1. Add a convenience function for getting possibly non-existing components. - * [Pull request #629](https://github.com/ignitionrobotics/ign-gazebo/pull/629) + * [Pull request #629](https://github.com/gazebosim/gz-sim/pull/629) 1. Fix topLevelModel method - * [Pull request #600](https://github.com/ignitionrobotics/ign-gazebo/pull/600) + * [Pull request #600](https://github.com/gazebosim/gz-sim/pull/600) 1. World exporter - * [Pull request #474](https://github.com/ignitionrobotics/ign-gazebo/pull/474) + * [Pull request #474](https://github.com/gazebosim/gz-sim/pull/474) 1. Fix finding PBR materials - * [Pull request #575](https://github.com/ignitionrobotics/ign-gazebo/pull/575) + * [Pull request #575](https://github.com/gazebosim/gz-sim/pull/575) 1. Handle multiple logical cameras - * [Pull request #539](https://github.com/ignitionrobotics/ign-gazebo/pull/539) + * [Pull request #539](https://github.com/gazebosim/gz-sim/pull/539) 1. Make some tests more robust - * [Pull request #314](https://github.com/ignitionrobotics/ign-gazebo/pull/314) + * [Pull request #314](https://github.com/gazebosim/gz-sim/pull/314) 1. Fix codecheck - * [Pull request #887](https://github.com/ignitionrobotics/ign-gazebo/pull/887) + * [Pull request #887](https://github.com/gazebosim/gz-sim/pull/887) 1. Hello world plugin added - * [Pull request #699](https://github.com/ignitionrobotics/ign-gazebo/pull/699) + * [Pull request #699](https://github.com/gazebosim/gz-sim/pull/699) 1. Model info CLI `ign model` - * [Pull request #893](https://github.com/ignitionrobotics/ign-gazebo/pull/893) + * [Pull request #893](https://github.com/gazebosim/gz-sim/pull/893) 1. Don't create components for entities that don't exist - * [Pull request #927](https://github.com/ignitionrobotics/ign-gazebo/pull/927) + * [Pull request #927](https://github.com/gazebosim/gz-sim/pull/927) 1. Adds Mesh Tutorial - * [Pull request #915](https://github.com/ignitionrobotics/ign-gazebo/pull/915) + * [Pull request #915](https://github.com/gazebosim/gz-sim/pull/915) 1. Fix updating GUI plugin on load - * [Pull request #904](https://github.com/ignitionrobotics/ign-gazebo/pull/904) + * [Pull request #904](https://github.com/gazebosim/gz-sim/pull/904) 1. Fix documentation for the Sensor component - * [Pull request #898](https://github.com/ignitionrobotics/ign-gazebo/pull/898) + * [Pull request #898](https://github.com/gazebosim/gz-sim/pull/898) 1. Use UINT64_MAX for kComponentTpyeIDInvalid instead of relying on underflow - * [Pull request #889](https://github.com/ignitionrobotics/ign-gazebo/pull/889) + * [Pull request #889](https://github.com/gazebosim/gz-sim/pull/889) 1. Fix mouse view control target position - * [Pull request #879](https://github.com/ignitionrobotics/ign-gazebo/pull/879) + * [Pull request #879](https://github.com/gazebosim/gz-sim/pull/879) 1. Set GUI camera pose - * [Pull request #863](https://github.com/ignitionrobotics/ign-gazebo/pull/863) + * [Pull request #863](https://github.com/gazebosim/gz-sim/pull/863) 1. Enables confirmation dialog when closing Gazebo. - * [Pull request #850](https://github.com/ignitionrobotics/ign-gazebo/pull/850) + * [Pull request #850](https://github.com/gazebosim/gz-sim/pull/850) 1. Depend on ign-rendering 3.5 - * [Pull request #867](https://github.com/ignitionrobotics/ign-gazebo/pull/867) + * [Pull request #867](https://github.com/gazebosim/gz-sim/pull/867) 1. Using math::SpeedLimiter on the diff_drive controller. - * [Pull request #833](https://github.com/ignitionrobotics/ign-gazebo/pull/833) + * [Pull request #833](https://github.com/gazebosim/gz-sim/pull/833) 1. New example: get an ECM snapshot from an external program - * [Pull request #859](https://github.com/ignitionrobotics/ign-gazebo/pull/859) + * [Pull request #859](https://github.com/gazebosim/gz-sim/pull/859) 1. Fix WindEffects Plugin bug, not configuring new links - * [Pull request #844](https://github.com/ignitionrobotics/ign-gazebo/pull/844) + * [Pull request #844](https://github.com/gazebosim/gz-sim/pull/844) 1. Fix potentially flaky integration component test case - * [Pull request #848](https://github.com/ignitionrobotics/ign-gazebo/pull/848) + * [Pull request #848](https://github.com/gazebosim/gz-sim/pull/848) 1. Cleanup and alphabetize plugin headers - * [Pull request #838](https://github.com/ignitionrobotics/ign-gazebo/pull/838) + * [Pull request #838](https://github.com/gazebosim/gz-sim/pull/838) 1. Removed duplicated code with rendering::sceneFromFirstRenderEngine - * [Pull request #819](https://github.com/ignitionrobotics/ign-gazebo/pull/819) + * [Pull request #819](https://github.com/gazebosim/gz-sim/pull/819) 1. Remove unused headers in video_recoder plugin - * [Pull request #834](https://github.com/ignitionrobotics/ign-gazebo/pull/834) + * [Pull request #834](https://github.com/gazebosim/gz-sim/pull/834) 1. Use moveToHelper from ign-rendering - * [Pull request #825](https://github.com/ignitionrobotics/ign-gazebo/pull/825) + * [Pull request #825](https://github.com/gazebosim/gz-sim/pull/825) 1. Remove tools/code_check and update codecov - * [Pull request #814](https://github.com/ignitionrobotics/ign-gazebo/pull/814) + * [Pull request #814](https://github.com/gazebosim/gz-sim/pull/814) 1. Add service and GUI to configure physics parameters - * [Pull request #536](https://github.com/ignitionrobotics/ign-gazebo/pull/536) - * [Pull request #812](https://github.com/ignitionrobotics/ign-gazebo/pull/812) + * [Pull request #536](https://github.com/gazebosim/gz-sim/pull/536) + * [Pull request #812](https://github.com/gazebosim/gz-sim/pull/812) 1. Fix documentation for EntityComponentManager::EachNew - * [Pull request #795](https://github.com/ignitionrobotics/ign-gazebo/pull/795) + * [Pull request #795](https://github.com/gazebosim/gz-sim/pull/795) 1. Fix macOS build: components::Name in benchmark - * [Pull request #784](https://github.com/ignitionrobotics/ign-gazebo/pull/784) + * [Pull request #784](https://github.com/gazebosim/gz-sim/pull/784) 1. Don't store duplicate ComponentTypeId in ECM - * [Pull request #751](https://github.com/ignitionrobotics/ign-gazebo/pull/751) + * [Pull request #751](https://github.com/gazebosim/gz-sim/pull/751) 1. [TPE] Support setting individual link velocity - * [Pull request #427](https://github.com/ignitionrobotics/ign-gazebo/pull/427) + * [Pull request #427](https://github.com/gazebosim/gz-sim/pull/427) 1. 👩‍🌾 Enable Focal CI - * [Pull request #646](https://github.com/ignitionrobotics/ign-gazebo/pull/646) + * [Pull request #646](https://github.com/gazebosim/gz-sim/pull/646) 1. Update benchmark comparison instructions - * [Pull request #766](https://github.com/ignitionrobotics/ign-gazebo/pull/766) + * [Pull request #766](https://github.com/gazebosim/gz-sim/pull/766) 1. Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config - * [Pull request #715](https://github.com/ignitionrobotics/ign-gazebo/pull/715) + * [Pull request #715](https://github.com/gazebosim/gz-sim/pull/715) 1. Do not pass -Wno-unused-parameter to MSVC compiler - * [Pull request #716](https://github.com/ignitionrobotics/ign-gazebo/pull/716) + * [Pull request #716](https://github.com/gazebosim/gz-sim/pull/716) 1. Scenebroadcaster sensors - * [Pull request #698](https://github.com/ignitionrobotics/ign-gazebo/pull/698) + * [Pull request #698](https://github.com/gazebosim/gz-sim/pull/698) 1. Make it so joint state publisher is quieter - * [Pull request #696](https://github.com/ignitionrobotics/ign-gazebo/pull/696) + * [Pull request #696](https://github.com/gazebosim/gz-sim/pull/696) ### Ignition Gazebo 3.8.0 (2021-03-17) 1. Add joint position controller GUI, also enable tests for GUI plugins - * [Pull request #534](https://github.com/ignitionrobotics/ign-gazebo/pull/534) + * [Pull request #534](https://github.com/gazebosim/gz-sim/pull/534) 1. Remove visibility from headers that are not installed - * [Pull request #665](https://github.com/ignitionrobotics/ign-gazebo/pull/665) + * [Pull request #665](https://github.com/gazebosim/gz-sim/pull/665) 1. Added screenshot to toolbar - * [Pull request #588](https://github.com/ignitionrobotics/ign-gazebo/pull/588) + * [Pull request #588](https://github.com/gazebosim/gz-sim/pull/588) 1. Improve ign tool support on macOS - * [Pull request #477](https://github.com/ignitionrobotics/ign-gazebo/pull/477) + * [Pull request #477](https://github.com/gazebosim/gz-sim/pull/477) 1. change nullptr to a int ptr for qt 5.15.2 bug - * [Pull request #527](https://github.com/ignitionrobotics/ign-gazebo/pull/527) + * [Pull request #527](https://github.com/gazebosim/gz-sim/pull/527) 1. Kinetic energy monitor plugin - * [Pull request #492](https://github.com/ignitionrobotics/ign-gazebo/pull/492) + * [Pull request #492](https://github.com/gazebosim/gz-sim/pull/492) 1. Use a std::promise/std::future to avoid busy waiting the step ack messages in NetworkManagerPrimary - * [Pull request #470](https://github.com/ignitionrobotics/ign-gazebo/pull/470) + * [Pull request #470](https://github.com/gazebosim/gz-sim/pull/470) 1. clarified performer example - * [Pull request #390](https://github.com/ignitionrobotics/ign-gazebo/pull/390) + * [Pull request #390](https://github.com/gazebosim/gz-sim/pull/390) 1. Add tutorial tweaks - * [Pull request #380](https://github.com/ignitionrobotics/ign-gazebo/pull/380) + * [Pull request #380](https://github.com/gazebosim/gz-sim/pull/380) 1. Fix Qt5 warnings for using anchors - * [Pull request #363](https://github.com/ignitionrobotics/ign-gazebo/pull/363) + * [Pull request #363](https://github.com/gazebosim/gz-sim/pull/363) 1. Update codeowners - * [Pull request #305](https://github.com/ignitionrobotics/ign-gazebo/pull/305) + * [Pull request #305](https://github.com/gazebosim/gz-sim/pull/305) 1. Qt auto scale factor for HiDPI displays - * [Pull request #291](https://github.com/ignitionrobotics/ign-gazebo/pull/291) + * [Pull request #291](https://github.com/gazebosim/gz-sim/pull/291) 1. Fix yaw units - * [Pull request #238](https://github.com/ignitionrobotics/ign-gazebo/pull/238) + * [Pull request #238](https://github.com/gazebosim/gz-sim/pull/238) 1. Fixed docblock showGrid - * [Pull request #152](https://github.com/ignitionrobotics/ign-gazebo/pull/152) + * [Pull request #152](https://github.com/gazebosim/gz-sim/pull/152) 1. Fix entity tree for large worlds - * [Pull request #673](https://github.com/ignitionrobotics/ign-gazebo/pull/673) + * [Pull request #673](https://github.com/gazebosim/gz-sim/pull/673) 1. Master branch updates - * [Pull request #672](https://github.com/ignitionrobotics/ign-gazebo/pull/672) + * [Pull request #672](https://github.com/gazebosim/gz-sim/pull/672) 1. Backport #561: Use common::setenv - * [Pull request #666](https://github.com/ignitionrobotics/ign-gazebo/pull/666) + * [Pull request #666](https://github.com/gazebosim/gz-sim/pull/666) 1. Use a custom data structure to manage entity feature maps - * [Pull request #586](https://github.com/ignitionrobotics/ign-gazebo/pull/586) + * [Pull request #586](https://github.com/gazebosim/gz-sim/pull/586) 1. Limit scene broadcast publications when paused - * [Pull request #497](https://github.com/ignitionrobotics/ign-gazebo/pull/497) + * [Pull request #497](https://github.com/gazebosim/gz-sim/pull/497) 1. Fix flaky SceneBoradcaster test - * [Pull request #641](https://github.com/ignitionrobotics/ign-gazebo/pull/641) + * [Pull request #641](https://github.com/gazebosim/gz-sim/pull/641) 1. Add TF/Pose_V publisher in DiffDrive - * [Pull request #548](https://github.com/ignitionrobotics/ign-gazebo/pull/548) + * [Pull request #548](https://github.com/gazebosim/gz-sim/pull/548) 1. 👩‍🌾 Relax performance test - * [Pull request #640](https://github.com/ignitionrobotics/ign-gazebo/pull/640) + * [Pull request #640](https://github.com/gazebosim/gz-sim/pull/640) 1. 👩‍🌾 Improve velocity control test - * [Pull request #642](https://github.com/ignitionrobotics/ign-gazebo/pull/642) + * [Pull request #642](https://github.com/gazebosim/gz-sim/pull/642) 1. Add `laser_retro` support - * [Pull request #603](https://github.com/ignitionrobotics/ign-gazebo/pull/603) + * [Pull request #603](https://github.com/gazebosim/gz-sim/pull/603) 1. Fix pose of plane visual with non-default normal vector - * [Pull request #574](https://github.com/ignitionrobotics/ign-gazebo/pull/574) + * [Pull request #574](https://github.com/gazebosim/gz-sim/pull/574) 1. Add About dialog - * [Pull request #609](https://github.com/ignitionrobotics/ign-gazebo/pull/609) + * [Pull request #609](https://github.com/gazebosim/gz-sim/pull/609) 1. Make topics configurable for joint controllers - * [Pull request #584](https://github.com/ignitionrobotics/ign-gazebo/pull/584) + * [Pull request #584](https://github.com/gazebosim/gz-sim/pull/584) 1. Also use Ignition GUI render event - * [Pull request #598](https://github.com/ignitionrobotics/ign-gazebo/pull/598) + * [Pull request #598](https://github.com/gazebosim/gz-sim/pull/598) 1. Tutorial on migrating SDF files from Gazebo classic - * [Pull request #400](https://github.com/ignitionrobotics/ign-gazebo/pull/400) + * [Pull request #400](https://github.com/gazebosim/gz-sim/pull/400) 1. Visualize collisions - * [Pull request #531](https://github.com/ignitionrobotics/ign-gazebo/pull/531) + * [Pull request #531](https://github.com/gazebosim/gz-sim/pull/531) 1. Backport state update changes from pull request #486 - * [Pull request #583](https://github.com/ignitionrobotics/ign-gazebo/pull/583) + * [Pull request #583](https://github.com/gazebosim/gz-sim/pull/583) 1. Publish all periodic change components in Scene Broadcaster - * [Pull request #544](https://github.com/ignitionrobotics/ign-gazebo/pull/544) + * [Pull request #544](https://github.com/gazebosim/gz-sim/pull/544) 1. added size to `ground_plane` in examples - * [Pull request #573](https://github.com/ignitionrobotics/ign-gazebo/pull/573) + * [Pull request #573](https://github.com/gazebosim/gz-sim/pull/573) 1. Parallelize State call in ECM - * [Pull request #451](https://github.com/ignitionrobotics/ign-gazebo/pull/451) + * [Pull request #451](https://github.com/gazebosim/gz-sim/pull/451) 1. Non-blocking paths request - * [Pull request #555](https://github.com/ignitionrobotics/ign-gazebo/pull/555) + * [Pull request #555](https://github.com/gazebosim/gz-sim/pull/555) ### Ignition Gazebo 3.7.0 (2021-01-13) 1. Fix examples in migration plugins tutorial. - * [Pull Request 543](https://github.com/ignitionrobotics/ign-gazebo/pull/543) + * [Pull Request 543](https://github.com/gazebosim/gz-sim/pull/543) 1. Added missing namespace in `detail/EntityComponentManager.hh`. - * [Pull Request 541](https://github.com/ignitionrobotics/ign-gazebo/pull/541) + * [Pull Request 541](https://github.com/gazebosim/gz-sim/pull/541) 1. Automatically load a subset of world plugins. - * [Pull Request 281](https://github.com/ignitionrobotics/ign-gazebo/pull/281) + * [Pull Request 281](https://github.com/gazebosim/gz-sim/pull/281) 1. Update gtest to 1.10.0 for Windows compilation. - * [Pull Request 506](https://github.com/ignitionrobotics/ign-gazebo/pull/506) + * [Pull Request 506](https://github.com/gazebosim/gz-sim/pull/506) 1. Updates to ardupilot migration tutorial. - * [Pull Request 525](https://github.com/ignitionrobotics/ign-gazebo/pull/525) + * [Pull Request 525](https://github.com/gazebosim/gz-sim/pull/525) 1. Don't make docs on macOS. - * [Pull Request 528](https://github.com/ignitionrobotics/ign-gazebo/pull/528) + * [Pull Request 528](https://github.com/gazebosim/gz-sim/pull/528) ### Ignition Gazebo 3.6.0 (2020-12-30) 1. Fix pose msg conversion when msg is missing orientation - * [Pull Request 450](https://github.com/ignitionrobotics/ign-gazebo/pull/450) + * [Pull Request 450](https://github.com/gazebosim/gz-sim/pull/450) 1. Address code checker warnings - * [Pull Request 443](https://github.com/ignitionrobotics/ign-gazebo/pull/443) - * [Pull Request 491](https://github.com/ignitionrobotics/ign-gazebo/pull/491) - * [Pull Request 499](https://github.com/ignitionrobotics/ign-gazebo/pull/499) - * [Pull Request 502](https://github.com/ignitionrobotics/ign-gazebo/pull/502) + * [Pull Request 443](https://github.com/gazebosim/gz-sim/pull/443) + * [Pull Request 491](https://github.com/gazebosim/gz-sim/pull/491) + * [Pull Request 499](https://github.com/gazebosim/gz-sim/pull/499) + * [Pull Request 502](https://github.com/gazebosim/gz-sim/pull/502) 1. Test fixes - * [Pull Request 455](https://github.com/ignitionrobotics/ign-gazebo/pull/455) - * [Pull Request 463](https://github.com/ignitionrobotics/ign-gazebo/pull/463) - * [Pull Request 452](https://github.com/ignitionrobotics/ign-gazebo/pull/452) - * [Pull Request 480](https://github.com/ignitionrobotics/ign-gazebo/pull/480) + * [Pull Request 455](https://github.com/gazebosim/gz-sim/pull/455) + * [Pull Request 463](https://github.com/gazebosim/gz-sim/pull/463) + * [Pull Request 452](https://github.com/gazebosim/gz-sim/pull/452) + * [Pull Request 480](https://github.com/gazebosim/gz-sim/pull/480) 1. Documentation updates - * [Pull Request 472](https://github.com/ignitionrobotics/ign-gazebo/pull/472) + * [Pull Request 472](https://github.com/gazebosim/gz-sim/pull/472) 1. Fix segfault in the Breadcrumb system when associated model is unloaded - * [Pull Request 454](https://github.com/ignitionrobotics/ign-gazebo/pull/454) + * [Pull Request 454](https://github.com/gazebosim/gz-sim/pull/454) 1. Added user commands to example thermal camera world - * [Pull Request 442](https://github.com/ignitionrobotics/ign-gazebo/pull/442) + * [Pull Request 442](https://github.com/gazebosim/gz-sim/pull/442) 1. Helper function to set component data - * [Pull Request 436](https://github.com/ignitionrobotics/ign-gazebo/pull/436) + * [Pull Request 436](https://github.com/gazebosim/gz-sim/pull/436) 1. Remove unneeded if statement in EntityComponentManager - * [Pull Request 432](https://github.com/ignitionrobotics/ign-gazebo/pull/432) + * [Pull Request 432](https://github.com/gazebosim/gz-sim/pull/432) 1. Clarify how time is represented in each phase of a System step - * [Pull Request 467](https://github.com/ignitionrobotics/ign-gazebo/pull/467) + * [Pull Request 467](https://github.com/gazebosim/gz-sim/pull/467) 1. Switch to async state service request - * [Pull Request 461](https://github.com/ignitionrobotics/ign-gazebo/pull/461) + * [Pull Request 461](https://github.com/gazebosim/gz-sim/pull/461) 1. Update key event handling - * [Pull Request 466](https://github.com/ignitionrobotics/ign-gazebo/pull/466) + * [Pull Request 466](https://github.com/gazebosim/gz-sim/pull/466) 1. Tape Measure Plugin - * [Pull Request 456](https://github.com/ignitionrobotics/ign-gazebo/pull/456) + * [Pull Request 456](https://github.com/gazebosim/gz-sim/pull/456) 1. Move deselect and preview termination to render thread - * [Pull Request 493](https://github.com/ignitionrobotics/ign-gazebo/pull/493) + * [Pull Request 493](https://github.com/gazebosim/gz-sim/pull/493) 1. Logical audio sensor plugin - * [Pull Request 401](https://github.com/ignitionrobotics/ign-gazebo/pull/401) + * [Pull Request 401](https://github.com/gazebosim/gz-sim/pull/401) 1. add frame_id and child_frame_id attribute support for DiffDrive - * [Pull Request 361](https://github.com/ignitionrobotics/ign-gazebo/pull/361) + * [Pull Request 361](https://github.com/gazebosim/gz-sim/pull/361) 1. Add ability to record video based on sim time - * [Pull Request 414](https://github.com/ignitionrobotics/ign-gazebo/pull/414) + * [Pull Request 414](https://github.com/gazebosim/gz-sim/pull/414) 1. Add lockstep mode to video recording - * [Pull Request 419](https://github.com/ignitionrobotics/ign-gazebo/pull/419) + * [Pull Request 419](https://github.com/gazebosim/gz-sim/pull/419) 1. Disable right click menu when using measuring tool - * [Pull Request 458](https://github.com/ignitionrobotics/ign-gazebo/pull/458) + * [Pull Request 458](https://github.com/gazebosim/gz-sim/pull/458) ### Ignition Gazebo 3.5.0 (2020-11-03) 1. Updated source build instructions - * [Pull Request 403](https://github.com/ignitionrobotics/ign-gazebo/pull/403) + * [Pull Request 403](https://github.com/gazebosim/gz-sim/pull/403) 1. More world APIs, helper function ComponentData - * [Pull Request 378](https://github.com/ignitionrobotics/ign-gazebo/pull/378) + * [Pull Request 378](https://github.com/gazebosim/gz-sim/pull/378) 1. Improve fork experience - * [Pull Request 411](https://github.com/ignitionrobotics/ign-gazebo/pull/411) + * [Pull Request 411](https://github.com/gazebosim/gz-sim/pull/411) 1. Fix a crash in the grid config plugin, set grid material - * [Pull Request 412](https://github.com/ignitionrobotics/ign-gazebo/pull/412) + * [Pull Request 412](https://github.com/gazebosim/gz-sim/pull/412) 1. Document deprecation of log playback `` SDF param - * [Pull Request 424](https://github.com/ignitionrobotics/ign-gazebo/pull/424) - * [Pull Request 425](https://github.com/ignitionrobotics/ign-gazebo/pull/425) + * [Pull Request 424](https://github.com/gazebosim/gz-sim/pull/424) + * [Pull Request 425](https://github.com/gazebosim/gz-sim/pull/425) 1. Enable mouse highlighting selection on resource spawner - * [Pull Request 402](https://github.com/ignitionrobotics/ign-gazebo/pull/402) + * [Pull Request 402](https://github.com/gazebosim/gz-sim/pull/402) 1. Add support for custom render engines - * [Pull Request 373](https://github.com/ignitionrobotics/ign-gazebo/pull/373) + * [Pull Request 373](https://github.com/gazebosim/gz-sim/pull/373) 1. Component Vector -> Map ECM Optimization - * [Pull Request 416](https://github.com/ignitionrobotics/ign-gazebo/pull/416) + * [Pull Request 416](https://github.com/gazebosim/gz-sim/pull/416) ### Ignition Gazebo 3.4.0 (2020-10-14) 1. Fix gui sendEvent memory leaks - * [Pull Request 365](https://github.com/ignitionrobotics/ign-gazebo/pull/365) + * [Pull Request 365](https://github.com/gazebosim/gz-sim/pull/365) 1. Support nested models - * [Pull Request 258](https://github.com/ignitionrobotics/ign-gazebo/pull/258) + * [Pull Request 258](https://github.com/gazebosim/gz-sim/pull/258) 1. Generalize actor count and pose in actor population erb SDF - * [Pull Request 336](https://github.com/ignitionrobotics/ign-gazebo/pull/336) + * [Pull Request 336](https://github.com/gazebosim/gz-sim/pull/336) 1. Add more link APIs, with tutorial - * [Pull Request 375](https://github.com/ignitionrobotics/ign-gazebo/pull/375) + * [Pull Request 375](https://github.com/gazebosim/gz-sim/pull/375) 1. Add screenshots to GUI config tutorial - * [Pull Request 406](https://github.com/ignitionrobotics/ign-gazebo/pull/406) + * [Pull Request 406](https://github.com/gazebosim/gz-sim/pull/406) 1. Fix adding performers to entity tree - * [Pull Request 374](https://github.com/ignitionrobotics/ign-gazebo/pull/374) + * [Pull Request 374](https://github.com/gazebosim/gz-sim/pull/374) 1. Remove sidebar and put world control in bottom left for joint controller examples - * [Pull Request 384](https://github.com/ignitionrobotics/ign-gazebo/pull/384) + * [Pull Request 384](https://github.com/gazebosim/gz-sim/pull/384) 1. Allow executing a blocking single Server run in both paused and unpaused states - * [Pull Request 297](https://github.com/ignitionrobotics/ign-gazebo/pull/297) + * [Pull Request 297](https://github.com/gazebosim/gz-sim/pull/297) 1. Add camera video recorder system - * [Pull Request 316](https://github.com/ignitionrobotics/ign-gazebo/pull/316) + * [Pull Request 316](https://github.com/gazebosim/gz-sim/pull/316) 1. Decrease time step for quadcopter world - * [Pull Request 372](https://github.com/ignitionrobotics/ign-gazebo/pull/372) + * [Pull Request 372](https://github.com/gazebosim/gz-sim/pull/372) 1. Add support for moving the GUI camera to a pose - * [Pull Request 352](https://github.com/ignitionrobotics/ign-gazebo/pull/352) + * [Pull Request 352](https://github.com/gazebosim/gz-sim/pull/352) 1. Remove `lib`+`.so` from plugin's name - * [Pull Request 279](https://github.com/ignitionrobotics/ign-gazebo/pull/279) - * [Pull Request 335](https://github.com/ignitionrobotics/ign-gazebo/pull/335) + * [Pull Request 279](https://github.com/gazebosim/gz-sim/pull/279) + * [Pull Request 335](https://github.com/gazebosim/gz-sim/pull/335) 1. EntityComponentManager::EachRemoved documentation fix. - * [Pull Request 348](https://github.com/ignitionrobotics/ign-gazebo/pull/348) + * [Pull Request 348](https://github.com/gazebosim/gz-sim/pull/348) 1. Add more model APIs. - * [Pull Request 349](https://github.com/ignitionrobotics/ign-gazebo/pull/349) + * [Pull Request 349](https://github.com/gazebosim/gz-sim/pull/349) 1. Update dimensions of the grid config. - * [Pull Request 383](https://github.com/ignitionrobotics/ign-gazebo/pull/383) + * [Pull Request 383](https://github.com/gazebosim/gz-sim/pull/383) 1. Fix top-left toolbar layout so magnet shows. - * [Pull Request 381](https://github.com/ignitionrobotics/ign-gazebo/pull/381) + * [Pull Request 381](https://github.com/gazebosim/gz-sim/pull/381) 1. Add instructions to bitmask world. - * [Pull Request 377](https://github.com/ignitionrobotics/ign-gazebo/pull/377) + * [Pull Request 377](https://github.com/gazebosim/gz-sim/pull/377) 1. Add search and sort for resource spawner. - * [Pull Request 359](https://github.com/ignitionrobotics/ign-gazebo/pull/359) + * [Pull Request 359](https://github.com/gazebosim/gz-sim/pull/359) 1. Fix source build instructions for ign-gazebo3. - * [Pull Request 395](https://github.com/ignitionrobotics/ign-gazebo/pull/395) + * [Pull Request 395](https://github.com/gazebosim/gz-sim/pull/395) 1. Added playback scrubber GUI - * [Pull Request 299](https://github.com/ignitionrobotics/ign-gazebo/pull/299) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 299](https://github.com/gazebosim/gz-sim/pull/299) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Added wheel slip system plugin. - * [Pull Request 134](https://github.com/ignitionrobotics/ign-gazebo/pull/134) - * [Pull Request 357](https://github.com/ignitionrobotics/ign-gazebo/pull/357) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 134](https://github.com/gazebosim/gz-sim/pull/134) + * [Pull Request 357](https://github.com/gazebosim/gz-sim/pull/357) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Enhanced log playback performance. - * [Pull Request 351](https://github.com/ignitionrobotics/ign-gazebo/pull/351) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 351](https://github.com/gazebosim/gz-sim/pull/351) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, ign_TEST - * [Pull Request 327](https://github.com/ignitionrobotics/ign-gazebo/pull/327) + * [Pull Request 327](https://github.com/gazebosim/gz-sim/pull/327) 1. Added support for specifying topics to record. - * [Pull Request 315](https://github.com/ignitionrobotics/ign-gazebo/pull/315) + * [Pull Request 315](https://github.com/gazebosim/gz-sim/pull/315) 1. Make sure OpenGL core profile context is used by GzScene3D. - * [Pull Request 339](https://github.com/ignitionrobotics/ign-gazebo/pull/339) + * [Pull Request 339](https://github.com/gazebosim/gz-sim/pull/339) 1. Support relative paths for PBR materials - * [Pull Request 328](https://github.com/ignitionrobotics/ign-gazebo/pull/328) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 328](https://github.com/gazebosim/gz-sim/pull/328) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Add file extension automatically for record plugin. - * [Pull Request 303](https://github.com/ignitionrobotics/ign-gazebo/pull/303) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 303](https://github.com/gazebosim/gz-sim/pull/303) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Support spawning during log playback. - * [Pull Request 346](https://github.com/ignitionrobotics/ign-gazebo/pull/346) + * [Pull Request 346](https://github.com/gazebosim/gz-sim/pull/346) + +1. Added wheel slip system plugin. + * [Pull Request 134](https://github.com/gazebosim/gz-sim/pull/134) + * [Pull Request 357](https://github.com/gazebosim/gz-sim/pull/357) 1. Add Render Engine Cmd Line option - * [Pull Request 331](https://github.com/ignitionrobotics/ign-gazebo/pull/331) + * [Pull Request 331](https://github.com/gazebosim/gz-sim/pull/331) ### Ignition Gazebo 3.3.0 (2020-08-31) 1. Added marker array service. - * [pull request 302](https://github.com/ignitionrobotics/ign-gazebo/pull/302) + * [pull request 302](https://github.com/gazebosim/gz-sim/pull/302) 1. Introduced a new parameter in the scene3D plugin to launch in fullscreen. - * [pull request 254](https://github.com/ignitionrobotics/ign-gazebo/pull/254) + * [pull request 254](https://github.com/gazebosim/gz-sim/pull/254) 1. Fix issue #285 by adding checks for a marker's parent. - * [pull request 290](https://github.com/ignitionrobotics/ign-gazebo/pull/290) + * [pull request 290](https://github.com/gazebosim/gz-sim/pull/290) 1. Fix non-specified material error. - * [pull request 292](https://github.com/ignitionrobotics/ign-gazebo/pull/292) + * [pull request 292](https://github.com/gazebosim/gz-sim/pull/292) 1. Added simulation world with large number of entities. - * [pull request 283](https://github.com/ignitionrobotics/ign-gazebo/pull/283) + * [pull request 283](https://github.com/gazebosim/gz-sim/pull/283) 1. Fixed parsing of the touch plugin' enabled flag. - * [pull request 275](https://github.com/ignitionrobotics/ign-gazebo/pull/275) + * [pull request 275](https://github.com/gazebosim/gz-sim/pull/275) 1. Added buoyancy system plugin. - * [pull request 252](https://github.com/ignitionrobotics/ign-gazebo/pull/252) + * [pull request 252](https://github.com/gazebosim/gz-sim/pull/252) 1. Implemented shift + drag = rotate in the GUI. - * [pull request 247](https://github.com/ignitionrobotics/ign-gazebo/pull/247) + * [pull request 247](https://github.com/gazebosim/gz-sim/pull/247) 1. Backport collision bitmask changes - * [pull request 223](https://github.com/ignitionrobotics/ign-gazebo/pull/223) + * [pull request 223](https://github.com/gazebosim/gz-sim/pull/223) 1. Added velocity command to TPE. - * [pull request 169](https://github.com/ignitionrobotics/ign-gazebo/pull/169) + * [pull request 169](https://github.com/gazebosim/gz-sim/pull/169) 1. This version includes all features in Gazebo 2.23.0 ### Ignition Gazebo 3.2.0 (2020-05-20) 1. Merge ign-gazebo2 to ign-gazebo3 - * [pull request 149](https://github.com/ignitionrobotics/ign-gazebo/pull/149) + * [pull request 149](https://github.com/gazebosim/gz-sim/pull/149) ### Ignition Gazebo 3.1.0 (2020-05-19) 1. Port support for computing model bounding box in physics system - * [pull request 127](https://github.com/ignitionrobotics/ign-gazebo/pull/127) + * [pull request 127](https://github.com/gazebosim/gz-sim/pull/127) 1. Add DetachableJoint: A system that initially attaches two models via a fixed joint and allows for the models to get detached during simulation via a topic. * [BitBucket pull request 440](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/440) @@ -2812,7 +2865,7 @@ * [BitBucket pull request 514](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/514) 1. Add window focus upon mouse entering the render window - * [Github pull request 96](https://github.com/ignitionrobotics/ign-gazebo/pull/96) + * [Github pull request 96](https://github.com/gazebosim/gz-sim/pull/96) ### Ignition Gazebo 3.0.0 (2019-12-10) @@ -2853,154 +2906,154 @@ ### Ignition Gazebo 2.25.0 (2020-09-17) 1. Added wheel slip system plugin. - * [Pull Request 134](https://github.com/ignitionrobotics/ign-gazebo/pull/134) - * [Pull Request 357](https://github.com/ignitionrobotics/ign-gazebo/pull/357) + * [Pull Request 134](https://github.com/gazebosim/gz-sim/pull/134) + * [Pull Request 357](https://github.com/gazebosim/gz-sim/pull/357) 1. Enhanced log playback performance. - * [Pull Request 351](https://github.com/ignitionrobotics/ign-gazebo/pull/351) + * [Pull Request 351](https://github.com/gazebosim/gz-sim/pull/351) 1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, ign_TEST - * [Pull Request 327](https://github.com/ignitionrobotics/ign-gazebo/pull/327) + * [Pull Request 327](https://github.com/gazebosim/gz-sim/pull/327) 1. Added support for specifying topics to record. - * [Pull Request 315](https://github.com/ignitionrobotics/ign-gazebo/pull/315) + * [Pull Request 315](https://github.com/gazebosim/gz-sim/pull/315) 1. Make sure OpenGL core profile context is used by GzScene3D. - * [Pull Request 339](https://github.com/ignitionrobotics/ign-gazebo/pull/339) + * [Pull Request 339](https://github.com/gazebosim/gz-sim/pull/339) 1. Support relative paths for PBR materials - * [Pull Request 328](https://github.com/ignitionrobotics/ign-gazebo/pull/328) + * [Pull Request 328](https://github.com/gazebosim/gz-sim/pull/328) 1. Add file extension automatically for record plugin. - * [Pull Request 303](https://github.com/ignitionrobotics/ign-gazebo/pull/303) + * [Pull Request 303](https://github.com/gazebosim/gz-sim/pull/303) 1. Support spawning during log playback. - * [Pull Request 346](https://github.com/ignitionrobotics/ign-gazebo/pull/346) + * [Pull Request 346](https://github.com/gazebosim/gz-sim/pull/346) ### Ignition Gazebo 2.24.0 (2020-09-03) 1. Resource env var, with transport interface. - * [Pull Request 172](https://github.com/ignitionrobotics/ign-gazebo/pull/172) + * [Pull Request 172](https://github.com/gazebosim/gz-sim/pull/172) 1. Save http URIs (fix tests) - * [Pull Request 271](https://github.com/ignitionrobotics/ign-gazebo/pull/271) + * [Pull Request 271](https://github.com/gazebosim/gz-sim/pull/271) 1. Insert Local Models. - * [Pull Request 173](https://github.com/ignitionrobotics/ign-gazebo/pull/173) + * [Pull Request 173](https://github.com/gazebosim/gz-sim/pull/173) 1. Modernize actions CI. - * [Pull Request 269](https://github.com/ignitionrobotics/ign-gazebo/pull/269) + * [Pull Request 269](https://github.com/gazebosim/gz-sim/pull/269) 1. Sensor topics available through components and GUI. - * [Pull Request 266](https://github.com/ignitionrobotics/ign-gazebo/pull/266) + * [Pull Request 266](https://github.com/gazebosim/gz-sim/pull/266) 1. Customizable layouts - fully functional. - * [Pull Request 278](https://github.com/ignitionrobotics/ign-gazebo/pull/278) + * [Pull Request 278](https://github.com/gazebosim/gz-sim/pull/278) 1. Add Fuel World Support. - * [Pull Request 274](https://github.com/ignitionrobotics/ign-gazebo/pull/274) + * [Pull Request 274](https://github.com/gazebosim/gz-sim/pull/274) 1. Insert Fuel Models. - * [Pull Request 263](https://github.com/ignitionrobotics/ign-gazebo/pull/263) + * [Pull Request 263](https://github.com/gazebosim/gz-sim/pull/263) 1. Disable rendering tests on macOS that are known to fail. - * [Pull Request 209](https://github.com/ignitionrobotics/ign-gazebo/pull/209) + * [Pull Request 209](https://github.com/gazebosim/gz-sim/pull/209) 1. Fix tests on Blueprint. - * [Pull Request 295](https://github.com/ignitionrobotics/ign-gazebo/pull/295) + * [Pull Request 295](https://github.com/gazebosim/gz-sim/pull/295) 1. Publish remaining breadcrumb deployments. - * [Pull Request 308](https://github.com/ignitionrobotics/ign-gazebo/pull/308) + * [Pull Request 308](https://github.com/gazebosim/gz-sim/pull/308) ### Ignition Gazebo 2.23.0 (2020-07-28) 1. Deactivate PerformerDetector if its parent model gets removed. - * [Pull Request 260](https://github.com/ignitionrobotics/ign-gazebo/pull/260) + * [Pull Request 260](https://github.com/gazebosim/gz-sim/pull/260) 1. Backport support for s from Fuel #255 - * [Pull Request 255](https://github.com/ignitionrobotics/ign-gazebo/pull/255) + * [Pull Request 255](https://github.com/gazebosim/gz-sim/pull/255) ### Ignition Gazebo 2.22.0 (2020-07-22) 1. Allow zero or more key/value pairs to be added to detection header information. - * [Pull Request 257](https://github.com/ignitionrobotics/ign-gazebo/pull/257) + * [Pull Request 257](https://github.com/gazebosim/gz-sim/pull/257) ### Ignition Gazebo 2.21.0 (2020-07-16) 1. Added support for controlling which joints are published by the JointStatePublisher. - * [Pull Request 222](https://github.com/ignitionrobotics/ign-gazebo/pull/222) + * [Pull Request 222](https://github.com/gazebosim/gz-sim/pull/222) 1. Added an additional pose offset for the performer detector plugin. - * [Pull Request 236](https://github.com/ignitionrobotics/ign-gazebo/pull/236) + * [Pull Request 236](https://github.com/gazebosim/gz-sim/pull/236) 1. Fixed battery issues and updated tutorial. - * [Pull Request 230](https://github.com/ignitionrobotics/ign-gazebo/pull/230) + * [Pull Request 230](https://github.com/gazebosim/gz-sim/pull/230) ### Ignition Gazebo 2.20.1 (2020-06-18) 1. Properly add new models into the scenegraph. With this fix, when a model is spawned it will be added into the graph and resulting calls to the `scene/info` service will return a correct `msgs::Scene`. - * [Pull Request 212](https://github.com/ignitionrobotics/ign-gazebo/pull/212) + * [Pull Request 212](https://github.com/gazebosim/gz-sim/pull/212) ### Ignition Gazebo 2.20.0 (2020-06-09) 1. Updated battery model to stop battery drain when there is no joint velocity/force command, and added a recharging trigger. - * [Pull Request 183](https://github.com/ignitionrobotics/ign-gazebo/pull/183) + * [Pull Request 183](https://github.com/gazebosim/gz-sim/pull/183) 1. Fix segfault in the Breadcrumbs system - * [Pull Request 180](https://github.com/ignitionrobotics/ign-gazebo/pull/180) + * [Pull Request 180](https://github.com/gazebosim/gz-sim/pull/180) 1. Added an `` element to the DiffDrive system so that a custom odometry topic can be used. - * [Pull Request 179](https://github.com/ignitionrobotics/ign-gazebo/pull/179) + * [Pull Request 179](https://github.com/gazebosim/gz-sim/pull/179) ### Ignition Gazebo 2.19.0 (2020-06-02) 1. Use updated model names for spawned models when generating SDFormat - * [Pull Request 166](https://github.com/ignitionrobotics/ign-gazebo/pull/166) + * [Pull Request 166](https://github.com/gazebosim/gz-sim/pull/166) 1. Allow joint force commands (JointForceCmd) to dscharge a battery. - * [Pull Request 165](https://github.com/ignitionrobotics/ign-gazebo/pull/165) + * [Pull Request 165](https://github.com/gazebosim/gz-sim/pull/165) 1. Allow renaming breadcrumb models if there is a name conflict - * [Pull Request 155](https://github.com/ignitionrobotics/ign-gazebo/pull/155) + * [Pull Request 155](https://github.com/gazebosim/gz-sim/pull/155) 1. Add TriggeredPublisher system - * [Pull Request 139](https://github.com/ignitionrobotics/ign-gazebo/pull/139) + * [Pull Request 139](https://github.com/gazebosim/gz-sim/pull/139) 1. Add PerformerDetector, a system for detecting when performers enter a specified region - * [Pull Request 125](https://github.com/ignitionrobotics/ign-gazebo/pull/125) + * [Pull Request 125](https://github.com/gazebosim/gz-sim/pull/125) ### Ignition Gazebo 2.18.0 (2020-05-20) 1. Added a `/world//create_multiple` service that parallels the current `/world//create` service. The `create_multiple` service can handle an `ignition::msgs::EntityFactory_V` message that may contain one or more entities to spawn. - * [Pull Request 146](https://github.com/ignitionrobotics/ign-gazebo/pull/146) + * [Pull Request 146](https://github.com/gazebosim/gz-sim/pull/146) 1. DetachableJoint system: Add option to suppress warning about missing child model - * [Pull Request 132](https://github.com/ignitionrobotics/ign-gazebo/pull/132) + * [Pull Request 132](https://github.com/gazebosim/gz-sim/pull/132) ### Ignition Gazebo 2.17.0 (2020-05-13) 1. Allow battery plugin to work with joint force systems. - * [Pull Request 120](https://github.com/ignitionrobotics/ign-gazebo/pull/120) + * [Pull Request 120](https://github.com/gazebosim/gz-sim/pull/120) 1. Make breadcrumb static after specified time - * [Pull Request 90](https://github.com/ignitionrobotics/ign-gazebo/pull/90) + * [Pull Request 90](https://github.com/gazebosim/gz-sim/pull/90) 1. Disable breadcrumbs if the `max_deployments` == 0. - * [Pull Request 88](https://github.com/ignitionrobotics/ign-gazebo/pull/88) + * [Pull Request 88](https://github.com/gazebosim/gz-sim/pull/88) 1. Add static pose publisher and support pose\_v msg type in pose publisher system - * [Pull Request 65](https://github.com/ignitionrobotics/ign-gazebo/pull/65) + * [Pull Request 65](https://github.com/gazebosim/gz-sim/pull/65) 1. Refactor Gui.hh so that the Gazebo GUI can be ran from other packages - * [Pull Request 79](https://github.com/ignitionrobotics/ign-gazebo/pull/79) + * [Pull Request 79](https://github.com/gazebosim/gz-sim/pull/79) 1. Add ability to save worlds to SDFormat * [BitBucket pull request 545](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/545) 1. Add window focus upon mouse entering the render window - * [Github pull request 95](https://github.com/ignitionrobotics/ign-gazebo/pull/95) + * [Github pull request 95](https://github.com/gazebosim/gz-sim/pull/95) ### Ignition Gazebo 2.16.0 (2020-03-24) diff --git a/NEWS b/NEWS index 604eba6656..a73d9b7c1a 100644 --- a/NEWS +++ b/NEWS @@ -1 +1 @@ -http://ignitionrobotics.org +http://gazebosim.org diff --git a/docker/README.md b/docker/README.md index 052ad65f2b..8a9e390c72 100644 --- a/docker/README.md +++ b/docker/README.md @@ -10,7 +10,7 @@ section below for usage information about This section describes how to build and run a docker image based on nightly builds of downstream -[Ignition libraries](https://ignitionrobotics.org/libs). The Docker image will +[Ignition libraries](https://gazebosim.org/libs). The Docker image will use the Ignition Gazebo code found in the current source tree. **Requirements** diff --git a/docker/scripts/build_ign.sh b/docker/scripts/build_ign.sh index dd12c6479d..b98e5d6133 100755 --- a/docker/scripts/build_ign.sh +++ b/docker/scripts/build_ign.sh @@ -1,8 +1,8 @@ #!/bin/bash # Command line parameters: -# 1 - github organization name. For example ignitionrobotics or osrf. -# 2 - the name of the ignition repository. For example ign-math. -# 3 - the name of the branch. For example ign-math6 +# 1 - github organization name. For example gazebosim or osrf. +# 2 - the name of the ignition repository. For example gz-sim. +# 3 - the name of the branch. For example gz-math7 set -o errexit set -o verbose diff --git a/docker/scripts/upload_json_benchmark.sh b/docker/scripts/upload_json_benchmark.sh index 528b7afa95..9376494c56 100755 --- a/docker/scripts/upload_json_benchmark.sh +++ b/docker/scripts/upload_json_benchmark.sh @@ -1,12 +1,12 @@ #!/bin/bash # Command line parameters: -# 1 - github organization name. For example ignitionrobotics or osrf. -# 2 - the name of the ignition repository. For example ign-math. -# 3 - the name of the branch. For example ign-math6 +# 1 - github organization name. For example gazebosim or osrf. +# 2 - the name of the ignition repository. For example gz-math. +# 3 - the name of the branch. For example gz-math7 set -o errexit set -o verbose # todo(nkoenig) Update the database to handle templated names. # todo(nkoenig) Use application tokens instead of jwt, which can expire. -curl -k -X POST -d @$1 https://api.ignitionrobotics.org/1.0/benchmarks/gazebo --header 'authorization: Bearer '$AUTH0_JWT_TOKEN +curl -k -X POST -d @$1 https://api.gazebosim.org/1.0/benchmarks/gazebo --header 'authorization: Bearer '$AUTH0_JWT_TOKEN diff --git a/examples/standalone/joy_to_twist/README.md b/examples/standalone/joy_to_twist/README.md index 893bdeed1d..1dbc40f6a4 100644 --- a/examples/standalone/joy_to_twist/README.md +++ b/examples/standalone/joy_to_twist/README.md @@ -1,9 +1,9 @@ # Joy to Twist Standalone program that subscribes to -[ignition::msgs::Joy](https://ignitionrobotics.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) +[ignition::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) messages and converts publishes -[ignition::msgs::Twist](https://ignitionrobotics.org/api/msgs/5.6/classignition_1_1msgs_1_1Twist.html) +[ignition::msgs::Twist](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Twist.html) messages according to user-defined configuration. ## Build diff --git a/examples/standalone/joystick/README.md b/examples/standalone/joystick/README.md index 9e05e2e172..9292b6bd9e 100644 --- a/examples/standalone/joystick/README.md +++ b/examples/standalone/joystick/README.md @@ -1,7 +1,7 @@ # Joystick Standalone program that publishes -[ignition::msgs::Joy](https://ignitionrobotics.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) +[ignition::msgs::Joy](https://gazebosim.org/api/msgs/5.6/classignition_1_1msgs_1_1Joy.html) messages from a joystick device using Ignition Transport. The mapping of joystick buttons to fields in the message is the same as [this](http://wiki.ros.org/joy). diff --git a/examples/worlds/actor.sdf b/examples/worlds/actor.sdf index fc6af99daa..5c50c7b501 100644 --- a/examples/worlds/actor.sdf +++ b/examples/worlds/actor.sdf @@ -67,16 +67,16 @@ demo_actor 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + https://fuel.gazebosim.org/1.0/Mingfei/models/actor - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae + https://fuel.gazebosim.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae 1.0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae + https://fuel.gazebosim.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae 0.055 true diff --git a/examples/worlds/actors_population.sdf.erb b/examples/worlds/actors_population.sdf.erb index c885588bde..620677263d 100644 --- a/examples/worlds/actors_population.sdf.erb +++ b/examples/worlds/actors_population.sdf.erb @@ -84,11 +84,11 @@ - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae + https://fuel.gazebosim.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae 1.0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae + https://fuel.gazebosim.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae 0.055 true diff --git a/examples/worlds/breadcrumbs.sdf b/examples/worlds/breadcrumbs.sdf index b3ade84636..79cccff819 100644 --- a/examples/worlds/breadcrumbs.sdf +++ b/examples/worlds/breadcrumbs.sdf @@ -404,7 +404,7 @@ -2 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X2 Config 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X2 Config 1 diff --git a/examples/worlds/camera_sensor.sdf b/examples/worlds/camera_sensor.sdf index 8e8c090728..443321eebc 100644 --- a/examples/worlds/camera_sensor.sdf +++ b/examples/worlds/camera_sensor.sdf @@ -307,7 +307,7 @@ 0 1 3 0.0 0.0 1.57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Construction Cone diff --git a/examples/worlds/depth_camera_sensor.sdf b/examples/worlds/depth_camera_sensor.sdf index 80ce0abf93..2c0560063e 100644 --- a/examples/worlds/depth_camera_sensor.sdf +++ b/examples/worlds/depth_camera_sensor.sdf @@ -216,7 +216,7 @@ 0 1 3 0.0 0.0 1.57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Barrel + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Construction Barrel diff --git a/examples/worlds/elevator.sdf b/examples/worlds/elevator.sdf index d2b1238e6b..77d01899cb 100644 --- a/examples/worlds/elevator.sdf +++ b/examples/worlds/elevator.sdf @@ -73,7 +73,7 @@ - https://fuel.ignitionrobotics.org/1.0/nlamprian/models/Elevator + https://fuel.gazebosim.org/1.0/nlamprian/models/Elevator diff --git a/examples/worlds/fuel.sdf b/examples/worlds/fuel.sdf index 4d50302e1a..69e856b847 100644 --- a/examples/worlds/fuel.sdf +++ b/examples/worlds/fuel.sdf @@ -1,6 +1,6 @@ @@ -62,27 +62,27 @@ Double pendulum -3 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Double pendulum with base + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Double pendulum with base 3 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack Gazebo (relative paths) 2 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Gazebo - relative paths + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Gazebo - relative paths Actor Test 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/actor - relative paths + https://fuel.gazebosim.org/1.0/OpenRobotics/models/actor - relative paths @@ -93,14 +93,14 @@ - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Radio/4/files/meshes/Radio.dae diff --git a/examples/worlds/fuel_textured_mesh.sdf b/examples/worlds/fuel_textured_mesh.sdf index 2f42cf7608..b4955a4e52 100644 --- a/examples/worlds/fuel_textured_mesh.sdf +++ b/examples/worlds/fuel_textured_mesh.sdf @@ -202,7 +202,7 @@ true Rescue Randy 0 0 0 0 0 1.57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Rescue Randy + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Rescue Randy @@ -210,7 +210,7 @@ true Tube Light 1.5 0 3 0 0.78 0 - https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Tube Light + https://fuel.gazebosim.org/1.0/openrobotics/models/Tube Light diff --git a/examples/worlds/gpu_lidar_sensor.sdf b/examples/worlds/gpu_lidar_sensor.sdf index 07020dda9b..c8efaaefda 100644 --- a/examples/worlds/gpu_lidar_sensor.sdf +++ b/examples/worlds/gpu_lidar_sensor.sdf @@ -169,7 +169,7 @@ 0 0 0 0 0 1.57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Playground + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Playground diff --git a/examples/worlds/import_mesh.sdf b/examples/worlds/import_mesh.sdf index 685bace5d0..720f830789 100644 --- a/examples/worlds/import_mesh.sdf +++ b/examples/worlds/import_mesh.sdf @@ -75,7 +75,7 @@ true Electrical Box 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Electrical Box + https://fuel.gazebosim.org/1.0/openrobotics/models/Electrical Box diff --git a/examples/worlds/log_record_resources.sdf b/examples/worlds/log_record_resources.sdf index 222181127e..cd1d3f73aa 100644 --- a/examples/worlds/log_record_resources.sdf +++ b/examples/worlds/log_record_resources.sdf @@ -55,7 +55,7 @@ false staging_area 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X2 Config 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X2 Config 1 diff --git a/examples/worlds/multicopter_velocity_control.sdf b/examples/worlds/multicopter_velocity_control.sdf index 33d45db9d0..a238cce704 100644 --- a/examples/worlds/multicopter_velocity_control.sdf +++ b/examples/worlds/multicopter_velocity_control.sdf @@ -102,7 +102,7 @@ You can use the velocity controller and command linear velocity and yaw angular - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X3 UAV/4 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X3 UAV/4 0 3 1 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X4 UAV Config 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X4 UAV Config 1 Double_pendulum - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Double pendulum with base + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Double pendulum with base diff --git a/examples/worlds/quadcopter.sdf b/examples/worlds/quadcopter.sdf index 224a11cda9..89a507d1ff 100644 --- a/examples/worlds/quadcopter.sdf +++ b/examples/worlds/quadcopter.sdf @@ -78,7 +78,7 @@ - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X3 UAV/4 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X3 UAV/4 0 1 3 0.0 0.0 1.57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Construction Cone diff --git a/examples/worlds/tracked_vehicle_simple.sdf b/examples/worlds/tracked_vehicle_simple.sdf index cf9cd29acc..fbc77a7d0d 100644 --- a/examples/worlds/tracked_vehicle_simple.sdf +++ b/examples/worlds/tracked_vehicle_simple.sdf @@ -1719,7 +1719,7 @@ pallet 2 -2 0.1 0 0 0 - https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Euro pallet + https://fuel.gazebosim.org/1.0/openrobotics/models/Euro pallet diff --git a/examples/worlds/tunnel.sdf b/examples/worlds/tunnel.sdf index 583b313641..ffd0b99437 100644 --- a/examples/worlds/tunnel.sdf +++ b/examples/worlds/tunnel.sdf @@ -1,11 +1,6 @@ @@ -216,7 +211,7 @@ true staging_area 0 0 -0.005 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/subt_tunnel_staging_area + https://fuel.gazebosim.org/1.0/OpenRobotics/models/subt_tunnel_staging_area @@ -248,168 +243,168 @@ tile_0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 240.000000 240.000000 -15.000000 0 0 0.000000 tile_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 260.000000 240.000000 -15.000000 0 0 1.570796 tile_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Tall + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Tall 280.000000 240.000000 -15.000000 0 0 1.570796 tile_3 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 300.000000 240.000000 -15.000000 0 0 4.712389 tile_4 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 160.000000 211.000000 -15.000000 0 0 0.000000 tile_5 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 240.000000 220.000000 -15.000000 0 0 0.000000 radio_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Radio 241.500000 220.000000 -15.000000 0 0 0.000000 tile_6 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 300.000000 220.000000 -15.000000 0 0 0.000000 tile_7 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 69.000000 200.000000 -15.000000 0 0 0.000000 tile_8 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 200.000000 -15.000000 0 0 1.570796 tile_9 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 100.000000 200.000000 -15.000000 0 0 1.570796 tile_10 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 120.000000 200.000000 -15.000000 0 0 1.570796 tile_11 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 200.000000 -15.000000 0 0 1.570796 tile_12 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 160.000000 200.000000 -15.000000 0 0 0.000000 tile_13 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 180.000000 200.000000 -15.000000 0 0 1.570796 tile_14 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 200.000000 -15.000000 0 0 1.570796 tile_15 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 220.000000 200.000000 -15.000000 0 0 1.570796 tile_16 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 240.000000 200.000000 -15.000000 0 0 3.141593 tile_17 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 300.000000 200.000000 -15.000000 0 0 0.000000 tile_18 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 160.000000 180.000000 -15.000000 0 0 0.000000 backpack_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack 219.000000 202.000000 -15.000000 0 0 0.000000 tile_19 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 260.000000 180.000000 -15.000000 0 0 0.000000 tile_20 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 180.000000 -15.000000 0 0 1.570796 tile_21 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 300.000000 180.000000 -15.000000 0 0 0.000000 tile_22 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 320.000000 180.000000 -15.000000 0 0 1.570796 tile_23 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 340.000000 180.000000 -15.000000 0 0 4.712389 tile_24 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Tall + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Tall 160.000000 160.000000 -15.000000 0 0 0.000000 @@ -417,509 +412,509 @@ phone_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Phone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Phone 260.000000 160.000000 -14.996000 -1.570796 0 0.000000 tile_25 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 260.000000 160.000000 -15.000000 0 0 0.000000 tile_26 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 300.000000 169.000000 -15.000000 0 0 0.000000 tile_27 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 340.000000 160.000000 -15.000000 0 0 0.000000 toolbox_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Toolbox + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Toolbox 342.000000 160.000000 -15.000000 0 0 0.000000 tile_28 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 60.000000 131.000000 -15.000000 0 0 0.000000 tile_29 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 80.000000 131.000000 -15.000000 0 0 0.000000 tile_30 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 160.000000 140.000000 -15.000000 0 0 0.000000 extinguisher_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Extinguisher + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Extinguisher 158.000000 140.000000 -15.000000 0 0 0.000000 tile_31 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 260.000000 149.000000 -15.000000 0 0 0.000000 tile_32 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 340.000000 149.000000 -15.000000 0 0 0.000000 tile_33 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 60.000000 120.000000 -15.000000 0 0 1.570796 tile_34 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 80.000000 120.000000 -15.000000 0 0 0.000000 tile_35 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 100.000000 120.000000 -15.000000 0 0 1.570796 tile_36 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 120.000000 120.000000 -15.000000 0 0 1.570796 tile_37 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 120.000000 -15.000000 0 0 1.570796 tile_38 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 160.000000 120.000000 -15.000000 0 0 3.141593 tile_39 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 100.000000 -15.000000 0 0 0.000000 tile_40 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 200.000000 100.000000 -15.000000 0 0 0.000000 tile_41 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 220.000000 100.000000 -15.000000 0 0 1.570796 tile_42 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 240.000000 100.000000 -15.000000 0 0 1.570796 tile_43 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 260.000000 100.000000 -15.000000 0 0 4.712389 radio_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Radio + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Radio 260.000000 82.300000 -15.000000 0 0 0.000000 tile_44 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 80.000000 -15.000000 0 0 0.000000 tile_45 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 80.000000 -15.000000 0 0 0.000000 tile_46 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 260.000000 80.000000 -15.000000 0 0 1.570796 tile_47 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 280.000000 80.000000 -15.000000 0 0 4.712389 tile_48 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 6 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 6 80.000000 60.000000 -15.000000 0 0 3.141593 tile_49 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 60.000000 -15.000000 0 0 0.000000 tile_50 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 60.000000 -15.000000 0 0 0.000000 toolbox_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Toolbox + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Toolbox 278.000000 60.000000 -15.000000 0 0 0.000000 tile_51 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 40.000000 -10.000000 0 0 0.000000 tile_52 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 40.000000 -15.000000 0 0 0.000000 tile_53 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 40.000000 -15.000000 0 0 0.000000 tile_54 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 20.000000 -10.000000 0 0 0.000000 tile_55 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 20.000000 -15.000000 0 0 0.000000 phone_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Phone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Phone 201.800000 20.000000 -14.996000 -1.570796 0 0.000000 tile_56 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 20.000000 -15.000000 0 0 0.000000 tile_57 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 320.000000 20.000000 -20.000000 0 0 0.000000 tile_58 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 340.000000 20.000000 -20.000000 0 0 1.570796 tile_59 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 360.000000 20.000000 -20.000000 0 0 4.712389 electrical_box_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Electrical Box + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Electrical Box 400.000000 -1.000000 -20.000000 0 0 0.000000 tile_60 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 20.000000 0.000000 0.000000 0 0 1.570796 tile_61 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 6 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 6 40.000000 0.000000 -5.000000 0 0 1.570796 tile_62 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 6 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 6 60.000000 0.000000 -10.000000 0 0 1.570796 tile_63 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 80.000000 0.000000 -10.000000 0 0 0.000000 tile_64 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 100.000000 0.000000 -10.000000 0 0 1.570796 tile_65 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 120.000000 0.000000 -10.000000 0 0 1.570796 tile_66 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 0.000000 -10.000000 0 0 1.570796 tile_67 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 6 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 6 160.000000 0.000000 -15.000000 0 0 1.570796 tile_68 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 180.000000 0.000000 -15.000000 0 0 1.570796 tile_69 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 200.000000 0.000000 -15.000000 0 0 0.000000 tile_70 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 211.000000 0.000000 -15.000000 0 0 0.000000 tile_71 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 269.000000 0.000000 -15.000000 0 0 0.000000 tile_72 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 280.000000 0.000000 -15.000000 0 0 0.000000 tile_73 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 6 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 6 300.000000 0.000000 -20.000000 0 0 1.570796 tile_74 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 320.000000 0.000000 -20.000000 0 0 0.000000 tile_75 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 340.000000 0.000000 -20.000000 0 0 1.570796 tile_76 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 1 360.000000 0.000000 -20.000000 0 0 0.000000 tile_77 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 380.000000 0.000000 -20.000000 0 0 1.570796 tile_78 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 400.000000 0.000000 -20.000000 0 0 1.570796 tile_79 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 411.000000 0.000000 -20.000000 0 0 0.000000 tile_80 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 7 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 7 80.000000 -20.000000 -10.000000 0 0 3.141593 tile_81 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 -20.000000 -15.000000 0 0 0.000000 tile_82 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 -20.000000 -15.000000 0 0 0.000000 tile_83 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 320.000000 -20.000000 -20.000000 0 0 1.570796 tile_84 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 340.000000 -20.000000 -20.000000 0 0 1.570796 tile_85 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 360.000000 -20.000000 -20.000000 0 0 3.141593 tile_86 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 -40.000000 -5.000000 0 0 0.000000 tile_87 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 -40.000000 -15.000000 0 0 0.000000 tile_88 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 -40.000000 -15.000000 0 0 0.000000 backpack_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack 340.000000 -22.000000 -20.000000 0 0 0.000000 tile_89 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 80.000000 -60.000000 -5.000000 0 0 0.000000 tile_90 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 200.000000 -60.000000 -15.000000 0 0 1.570796 tile_91 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 220.000000 -60.000000 -15.000000 0 0 1.570796 tile_92 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 240.000000 -60.000000 -15.000000 0 0 1.570796 tile_93 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 260.000000 -60.000000 -15.000000 0 0 1.570796 tile_94 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 280.000000 -60.000000 -15.000000 0 0 3.141593 tile_95 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 80.000000 -80.000000 -5.000000 0 0 1.570796 tile_96 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 7 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 7 100.000000 -80.000000 -10.000000 0 0 1.570796 tile_97 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 120.000000 -80.000000 -10.000000 0 0 4.712389 phone_3 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Phone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Phone 120.800000 -98.400000 -9.996000 1.570796 0 0.000000 @@ -927,174 +922,174 @@ valve_1 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Valve + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Valve 240.000000 -58.000000 -15.000000 0 0 0.000000 tile_98 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 120.000000 -100.000000 -10.000000 0 0 1.570796 tile_99 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 140.000000 -100.000000 -10.000000 0 0 4.712389 tile_100 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 -120.000000 -10.000000 0 0 0.000000 valve_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Valve + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Valve 141.750000 -119.000000 -10.000000 0 0 0.000000 tile_101 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 -140.000000 -10.000000 0 0 0.000000 tile_102 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Short + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Constrained Tunnel Tile Short 140.000000 -160.000000 -10.000000 0 0 0.000000 tile_103 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile Blocker + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile Blocker 280.000000 -169.000000 -10.000000 0 0 0.000000 electrical_box_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Electrical Box + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Electrical Box 138.000000 -180.000000 -10.000000 0 0 0.000000 tile_104 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 -180.000000 -10.000000 0 0 0.000000 backpack_3 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack 180.000000 -198.000000 -10.000000 0 0 0.000000 tile_105 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 -180.000000 -10.000000 0 0 0.000000 tile_106 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 140.000000 -200.000000 -10.000000 0 0 0.000000 tile_107 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 160.000000 -200.000000 -10.000000 0 0 0.000000 tile_108 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 180.000000 -200.000000 -10.000000 0 0 1.570796 tile_109 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 200.000000 -200.000000 -10.000000 0 0 1.570796 tile_110 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 220.000000 -200.000000 -10.000000 0 0 4.712389 tile_111 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 -200.000000 -10.000000 0 0 0.000000 tile_112 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 140.000000 -220.000000 -10.000000 0 0 1.570796 tile_113 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 160.000000 -220.000000 -10.000000 0 0 3.141593 tile_114 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 220.000000 -220.000000 -10.000000 0 0 0.000000 tile_115 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 280.000000 -220.000000 -10.000000 0 0 0.000000 extinguisher_2 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Extinguisher + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Extinguisher 278.000000 -220.000000 -10.000000 0 0 0.000000 tile_116 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 220.000000 -240.000000 -10.000000 0 0 1.570796 tile_117 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 240.000000 -240.000000 -10.000000 0 0 1.570796 tile_118 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 5 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 5 260.000000 -240.000000 -10.000000 0 0 1.570796 tile_119 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Tunnel Tile 2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Tunnel Tile 2 280.000000 -240.000000 -10.000000 0 0 3.141593 diff --git a/include/ignition/gazebo/Entity.hh b/include/ignition/gazebo/Entity.hh index 4ac16e82de..0db6365417 100644 --- a/include/ignition/gazebo/Entity.hh +++ b/include/ignition/gazebo/Entity.hh @@ -21,8 +21,7 @@ #include #include -/// \brief This library is part of the [Ignition -/// Robotics](https://ignitionrobotics.org) project. +/// \brief This library is part of the [Gazebo](https://gazebosim.org) project. namespace ignition { /// \brief Gazebo is a leading open source robotics simulator, that diff --git a/include/ignition/gazebo/ServerConfig.hh b/include/ignition/gazebo/ServerConfig.hh index ff4941b41d..7116029009 100644 --- a/include/ignition/gazebo/ServerConfig.hh +++ b/include/ignition/gazebo/ServerConfig.hh @@ -374,14 +374,14 @@ namespace ignition UpdatePeriod() const; /// \brief Path to where simulation resources, such as models downloaded - /// from fuel.ignitionrobotics.org, should be stored. + /// from fuel.gazebosim.org, should be stored. /// \return Path to a location on disk. An empty string indicates that /// the default value will be used, which is currently /// ~/.ignition/fuel. public: const std::string &ResourceCache() const; /// \brief Set the path to where simulation resources, such as models - /// downloaded from fuel.ignitionrobotics.org, should be stored. + /// downloaded from fuel.gazebosim.org, should be stored. /// \param[in] _path Path to a location on disk. An empty string /// indicates that the default value will be used, which is currently /// ~/.ignition/fuel. diff --git a/src/Component_TEST.cc b/src/Component_TEST.cc index 7e6864710d..6d7a664a7f 100644 --- a/src/Component_TEST.cc +++ b/src/Component_TEST.cc @@ -332,7 +332,7 @@ TEST_F(ComponentTest, OStream) EXPECT_EQ("Mass: 0", ostr.str()); } - // Component with a ignition::msgs type that gets serialized by the default + // Component with a msgs type that gets serialized by the default // serializer { using Custom = components::ComponentMassMatrix().Mass()); } - // Component with a ignition::msgs type that gets deserialized by the message + // Component with a msgs type that gets deserialized by the message // deserializer { using Custom = components::Component IGNITION_GAZEBO_VISIBLE -msgs::Entity_Type ignition::gazebo::convert(const std::string &_in) +msgs::Entity_Type gazebo::convert(const std::string &_in) { msgs::Entity_Type out = msgs::Entity_Type_NONE; @@ -117,7 +117,7 @@ msgs::Entity_Type ignition::gazebo::convert(const std::string &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in) +math::Pose3d gazebo::convert(const msgs::Pose &_in) { math::Pose3d out(_in.position().x(), _in.position().y(), @@ -134,7 +134,7 @@ math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in) +msgs::Collision gazebo::convert(const sdf::Collision &_in) { msgs::Collision out; out.set_name(_in.Name()); @@ -147,7 +147,7 @@ msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in) +sdf::Collision gazebo::convert(const msgs::Collision &_in) { sdf::Collision out; out.SetName(_in.name()); @@ -159,7 +159,7 @@ sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in) +msgs::Geometry gazebo::convert(const sdf::Geometry &_in) { msgs::Geometry out; if (_in.Type() == sdf::GeometryType::BOX && _in.BoxShape()) @@ -268,7 +268,7 @@ msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in) +sdf::Geometry gazebo::convert(const msgs::Geometry &_in) { sdf::Geometry out; if (_in.type() == msgs::Geometry::BOX && _in.has_box()) @@ -405,7 +405,7 @@ sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Material ignition::gazebo::convert(const sdf::Material &_in) +msgs::Material gazebo::convert(const sdf::Material &_in) { msgs::Material out; msgs::Set(out.mutable_ambient(), _in.Ambient()); @@ -464,7 +464,7 @@ msgs::Material ignition::gazebo::convert(const sdf::Material &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Material ignition::gazebo::convert(const msgs::Material &_in) +sdf::Material gazebo::convert(const msgs::Material &_in) { sdf::Material out; out.SetAmbient(msgs::Convert(_in.ambient())); @@ -507,7 +507,7 @@ sdf::Material ignition::gazebo::convert(const msgs::Material &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in) +msgs::Actor gazebo::convert(const sdf::Actor &_in) { msgs::Actor out; out.mutable_entity()->set_name(_in.Name()); @@ -547,7 +547,7 @@ msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in) +sdf::Actor gazebo::convert(const msgs::Actor &_in) { sdf::Actor out; out.SetName(_in.entity().name()); @@ -590,7 +590,7 @@ sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Light ignition::gazebo::convert(const sdf::Light &_in) +msgs::Light gazebo::convert(const sdf::Light &_in) { msgs::Light out; out.set_name(_in.Name()); @@ -638,7 +638,7 @@ msgs::Light ignition::gazebo::convert(const sdf::Light &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Light ignition::gazebo::convert(const msgs::Light &_in) +sdf::Light gazebo::convert(const msgs::Light &_in) { sdf::Light out; out.SetName(_in.name()); @@ -704,7 +704,7 @@ sdf::Light ignition::gazebo::convert(const msgs::Light &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in) +msgs::GUI gazebo::convert(const sdf::Gui &_in) { msgs::GUI out; @@ -728,12 +728,12 @@ msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Time ignition::gazebo::convert( +msgs::Time gazebo::convert( const std::chrono::steady_clock::duration &_in) { msgs::Time out; - auto secNsec = ignition::math::durationToSecNsec(_in); + auto secNsec = math::durationToSecNsec(_in); out.set_sec(secNsec.first); out.set_nsec(secNsec.second); @@ -744,7 +744,7 @@ msgs::Time ignition::gazebo::convert( ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -std::chrono::steady_clock::duration ignition::gazebo::convert( +std::chrono::steady_clock::duration gazebo::convert( const msgs::Time &_in) { return std::chrono::seconds(_in.sec()) + std::chrono::nanoseconds(_in.nsec()); @@ -753,7 +753,7 @@ std::chrono::steady_clock::duration ignition::gazebo::convert( ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in) +msgs::Inertial gazebo::convert(const math::Inertiald &_in) { msgs::Inertial out; msgs::Set(out.mutable_pose(), _in.Pose()); @@ -770,7 +770,7 @@ msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in) +math::Inertiald gazebo::convert(const msgs::Inertial &_in) { math::MassMatrix3d massMatrix; massMatrix.SetMass(_in.mass()); @@ -790,7 +790,7 @@ math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in) +msgs::Axis gazebo::convert(const sdf::JointAxis &_in) { msgs::Axis out; msgs::Set(out.mutable_xyz(), _in.Xyz()); @@ -820,7 +820,7 @@ msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in) +sdf::JointAxis gazebo::convert(const msgs::Axis &_in) { sdf::JointAxis out; sdf::Errors errors = out.SetXyz(msgs::Convert(_in.xyz())); @@ -840,7 +840,7 @@ sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in) +msgs::Scene gazebo::convert(const sdf::Scene &_in) { msgs::Scene out; // todo(anyone) add Name to sdf::Scene? @@ -878,7 +878,7 @@ msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in) +sdf::Scene gazebo::convert(const msgs::Scene &_in) { sdf::Scene out; // todo(anyone) add SetName to sdf::Scene? @@ -918,7 +918,7 @@ sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in) +msgs::Atmosphere gazebo::convert(const sdf::Atmosphere &_in) { msgs::Atmosphere out; out.set_temperature(_in.Temperature().Kelvin()); @@ -936,7 +936,7 @@ msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Atmosphere ignition::gazebo::convert(const msgs::Atmosphere &_in) +sdf::Atmosphere gazebo::convert(const msgs::Atmosphere &_in) { sdf::Atmosphere out; out.SetTemperature(math::Temperature(_in.temperature())); @@ -952,16 +952,16 @@ sdf::Atmosphere ignition::gazebo::convert(const msgs::Atmosphere &_in) } ////////////////////////////////////////////////// -void ignition::gazebo::set(msgs::Time *_msg, +void gazebo::set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in) { - auto secNsec = ignition::math::durationToSecNsec(_in); + auto secNsec = math::durationToSecNsec(_in); _msg->set_sec(secNsec.first); _msg->set_nsec(secNsec.second); } ////////////////////////////////////////////////// -void ignition::gazebo::set(msgs::WorldStatistics *_msg, +void gazebo::set(msgs::WorldStatistics *_msg, const gazebo::UpdateInfo &_in) { set(_msg->mutable_sim_time(), _in.simTime); @@ -974,7 +974,7 @@ void ignition::gazebo::set(msgs::WorldStatistics *_msg, ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Physics ignition::gazebo::convert(const sdf::Physics &_in) +msgs::Physics gazebo::convert(const sdf::Physics &_in) { msgs::Physics out; out.set_max_step_size(_in.MaxStepSize()); @@ -985,7 +985,7 @@ msgs::Physics ignition::gazebo::convert(const sdf::Physics &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Physics ignition::gazebo::convert(const msgs::Physics &_in) +sdf::Physics gazebo::convert(const msgs::Physics &_in) { sdf::Physics out; out.SetRealTimeFactor(_in.real_time_factor()); @@ -994,7 +994,7 @@ sdf::Physics ignition::gazebo::convert(const msgs::Physics &_in) } ////////////////////////////////////////////////// -void ignition::gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf) +void gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf) { switch (_sdf.Type()) { @@ -1061,7 +1061,7 @@ sdf::LightType ignition::gazebo::convert(const std::string &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in) +sdf::Noise gazebo::convert(const msgs::SensorNoise &_in) { sdf::Noise out; @@ -1094,7 +1094,7 @@ sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) +msgs::Sensor gazebo::convert(const sdf::Sensor &_in) { msgs::Sensor out; out.set_name(_in.Name()); @@ -1110,17 +1110,17 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) msgs::MagnetometerSensor *sensor = out.mutable_magnetometer(); if (_in.MagnetometerSensor()->XNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_x_noise(), + gazebo::set(sensor->mutable_x_noise(), _in.MagnetometerSensor()->XNoise()); } if (_in.MagnetometerSensor()->YNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_y_noise(), + gazebo::set(sensor->mutable_y_noise(), _in.MagnetometerSensor()->YNoise()); } if (_in.MagnetometerSensor()->ZNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_z_noise(), + gazebo::set(sensor->mutable_z_noise(), _in.MagnetometerSensor()->ZNoise()); } } @@ -1208,13 +1208,13 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (_in.AltimeterSensor()->VerticalPositionNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_vertical_position_noise(), + gazebo::set(sensor->mutable_vertical_position_noise(), _in.AltimeterSensor()->VerticalPositionNoise()); } if (_in.AltimeterSensor()->VerticalVelocityNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_vertical_velocity_noise(), + gazebo::set(sensor->mutable_vertical_velocity_noise(), _in.AltimeterSensor()->VerticalVelocityNoise()); } } @@ -1233,7 +1233,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (_in.AirPressureSensor()->PressureNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_pressure_noise(), + gazebo::set(sensor->mutable_pressure_noise(), _in.AirPressureSensor()->PressureNoise()); } sensor->set_reference_altitude( @@ -1254,38 +1254,38 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (sdfImu->LinearAccelerationXNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_linear_acceleration()->mutable_x_noise(), sdfImu->LinearAccelerationXNoise()); } if (sdfImu->LinearAccelerationYNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_linear_acceleration()->mutable_y_noise(), sdfImu->LinearAccelerationYNoise()); } if (sdfImu->LinearAccelerationZNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_linear_acceleration()->mutable_z_noise(), sdfImu->LinearAccelerationZNoise()); } if (sdfImu->AngularVelocityXNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_angular_velocity()->mutable_x_noise(), sdfImu->AngularVelocityXNoise()); } if (sdfImu->AngularVelocityYNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_angular_velocity()->mutable_y_noise(), sdfImu->AngularVelocityYNoise()); } if (sdfImu->AngularVelocityZNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set( + gazebo::set( sensor->mutable_angular_velocity()->mutable_z_noise(), sdfImu->AngularVelocityZNoise()); } @@ -1319,7 +1319,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) if (sdfLidar->LidarNoise().Type() != sdf::NoiseType::NONE) { - ignition::gazebo::set(sensor->mutable_noise(), sdfLidar->LidarNoise()); + gazebo::set(sensor->mutable_noise(), sdfLidar->LidarNoise()); } sensor->set_horizontal_samples(sdfLidar->HorizontalScanSamples()); sensor->set_horizontal_resolution(sdfLidar->HorizontalScanResolution()); @@ -1349,7 +1349,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) +sdf::Sensor gazebo::convert(const msgs::Sensor &_in) { sdf::Sensor out; out.SetName(_in.name()); @@ -1366,17 +1366,17 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) { if (_in.magnetometer().has_x_noise()) { - sensor.SetXNoise(ignition::gazebo::convert( + sensor.SetXNoise(gazebo::convert( _in.magnetometer().x_noise())); } if (_in.magnetometer().has_y_noise()) { - sensor.SetYNoise(ignition::gazebo::convert( + sensor.SetYNoise(gazebo::convert( _in.magnetometer().y_noise())); } if (_in.magnetometer().has_z_noise()) { - sensor.SetZNoise(ignition::gazebo::convert( + sensor.SetZNoise(gazebo::convert( _in.magnetometer().z_noise())); } } @@ -1431,13 +1431,13 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) { if (_in.altimeter().has_vertical_position_noise()) { - sensor.SetVerticalPositionNoise(ignition::gazebo::convert( + sensor.SetVerticalPositionNoise(gazebo::convert( _in.altimeter().vertical_position_noise())); } if (_in.altimeter().has_vertical_velocity_noise()) { - sensor.SetVerticalVelocityNoise(ignition::gazebo::convert( + sensor.SetVerticalVelocityNoise(gazebo::convert( _in.altimeter().vertical_velocity_noise())); } } @@ -1456,7 +1456,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) { if (_in.air_pressure().has_pressure_noise()) { - sensor.SetPressureNoise(ignition::gazebo::convert( + sensor.SetPressureNoise(gazebo::convert( _in.air_pressure().pressure_noise())); } @@ -1480,19 +1480,19 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) if (_in.imu().linear_acceleration().has_x_noise()) { sensor.SetLinearAccelerationXNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().linear_acceleration().x_noise())); } if (_in.imu().linear_acceleration().has_y_noise()) { sensor.SetLinearAccelerationYNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().linear_acceleration().y_noise())); } if (_in.imu().linear_acceleration().has_z_noise()) { sensor.SetLinearAccelerationZNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().linear_acceleration().z_noise())); } } @@ -1502,19 +1502,19 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) if (_in.imu().angular_velocity().has_x_noise()) { sensor.SetAngularVelocityXNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().angular_velocity().x_noise())); } if (_in.imu().angular_velocity().has_y_noise()) { sensor.SetAngularVelocityYNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().angular_velocity().y_noise())); } if (_in.imu().angular_velocity().has_z_noise()) { sensor.SetAngularVelocityZNoise( - ignition::gazebo::convert( + gazebo::convert( _in.imu().angular_velocity().z_noise())); } } @@ -1571,7 +1571,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) if (_in.lidar().has_noise()) { - sensor.SetLidarNoise(ignition::gazebo::convert( + sensor.SetLidarNoise(gazebo::convert( _in.lidar().noise())); } } @@ -1589,7 +1589,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in) +msgs::WorldStatistics gazebo::convert(const gazebo::UpdateInfo &_in) { msgs::WorldStatistics out; set(&out, _in); @@ -1599,7 +1599,7 @@ msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in) +gazebo::UpdateInfo gazebo::convert(const msgs::WorldStatistics &_in) { gazebo::UpdateInfo out; out.iterations = _in.iterations(); @@ -1613,7 +1613,7 @@ gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in) +msgs::AxisAlignedBox gazebo::convert(const math::AxisAlignedBox &_in) { msgs::AxisAlignedBox out; msgs::Set(out.mutable_min_corner(), _in.Min()); @@ -1624,7 +1624,7 @@ msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in) ////////////////////////////////////////////////// template<> IGNITION_GAZEBO_VISIBLE -math::AxisAlignedBox ignition::gazebo::convert(const msgs::AxisAlignedBox &_in) +math::AxisAlignedBox gazebo::convert(const msgs::AxisAlignedBox &_in) { math::AxisAlignedBox out; out.Min() = msgs::Convert(_in.min_corner()); diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index 9033949c9d..f1a3809381 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -57,8 +57,8 @@ TEST(Conversions, Light) light.SetRawPose({3, 2, 1, 0, IGN_PI, 0}); light.SetPoseRelativeTo("world"); light.SetCastShadows(true); - light.SetDiffuse(ignition::math::Color(0.4f, 0.5f, 0.6f, 1.0)); - light.SetSpecular(ignition::math::Color(0.8f, 0.9f, 0.1f, 1.0)); + light.SetDiffuse(math::Color(0.4f, 0.5f, 0.6f, 1.0)); + light.SetSpecular(math::Color(0.8f, 0.9f, 0.1f, 1.0)); light.SetAttenuationRange(3.2); light.SetConstantAttenuationFactor(0.5); light.SetLinearAttenuationFactor(0.1); @@ -241,10 +241,10 @@ TEST(Conversions, Time) TEST(Conversions, Material) { sdf::Material material; - material.SetDiffuse(ignition::math::Color(0.1f, 0.2f, 0.3f, 0.4f)); - material.SetSpecular(ignition::math::Color(0.5f, 0.6f, 0.7f, 0.8f)); - material.SetAmbient(ignition::math::Color(0.9f, 1.0f, 1.1f, 1.2f)); - material.SetEmissive(ignition::math::Color(1.3f, 1.4f, 1.5f, 1.6f)); + material.SetDiffuse(math::Color(0.1f, 0.2f, 0.3f, 0.4f)); + material.SetSpecular(math::Color(0.5f, 0.6f, 0.7f, 0.8f)); + material.SetAmbient(math::Color(0.9f, 1.0f, 1.1f, 1.2f)); + material.SetEmissive(math::Color(1.3f, 1.4f, 1.5f, 1.6f)); material.SetLighting(true); material.SetRenderOrder(2.5); material.SetDoubleSided(true); @@ -336,7 +336,7 @@ TEST(Conversions, GeometryBox) geometry.SetType(sdf::GeometryType::BOX); sdf::Box boxShape; - boxShape.SetSize(ignition::math::Vector3d(1, 2, 3)); + boxShape.SetSize(math::Vector3d(1, 2, 3)); geometry.SetBoxShape(boxShape); auto geometryMsg = convert(geometry); @@ -450,7 +450,7 @@ TEST(Conversions, GeometryMesh) geometry.SetType(sdf::GeometryType::MESH); sdf::Mesh meshShape; - meshShape.SetScale(ignition::math::Vector3d(1, 2, 3)); + meshShape.SetScale(math::Vector3d(1, 2, 3)); meshShape.SetUri("file://watermelon"); meshShape.SetSubmesh("grape"); meshShape.SetCenterSubmesh(true); @@ -481,8 +481,8 @@ TEST(Conversions, GeometryPlane) geometry.SetType(sdf::GeometryType::PLANE); sdf::Plane planeShape; - planeShape.SetSize(ignition::math::Vector2d(1, 2)); - planeShape.SetNormal(ignition::math::Vector3d::UnitY); + planeShape.SetSize(math::Vector2d(1, 2)); + planeShape.SetNormal(math::Vector3d::UnitY); geometry.SetPlaneShape(planeShape); auto geometryMsg = convert(geometry); @@ -676,8 +676,8 @@ TEST(Conversions, JointAxis) TEST(Conversions, Scene) { sdf::Scene scene; - scene.SetAmbient(ignition::math::Color(0.1f, 0.2f, 0.3f, 0.4f)); - scene.SetBackground(ignition::math::Color(0.5f, 0.6f, 0.7f, 0.8f)); + scene.SetAmbient(math::Color(0.1f, 0.2f, 0.3f, 0.4f)); + scene.SetBackground(math::Color(0.5f, 0.6f, 0.7f, 0.8f)); scene.SetShadows(true); scene.SetGrid(true); scene.SetOriginVisual(true); @@ -769,7 +769,7 @@ TEST(Conversions, MagnetometerSensor) sensor.SetType(sdf::SensorType::MAGNETOMETER); sensor.SetUpdateRate(12.4); sensor.SetTopic("my_topic"); - sensor.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + sensor.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::Noise noise; noise.SetType(sdf::NoiseType::GAUSSIAN); @@ -809,7 +809,7 @@ TEST(Conversions, AltimeterSensor) sensor.SetType(sdf::SensorType::ALTIMETER); sensor.SetUpdateRate(12.4); sensor.SetTopic("my_topic"); - sensor.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + sensor.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::Noise noise; noise.SetType(sdf::NoiseType::GAUSSIAN); diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index b5f0eb8310..1695e89e01 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -1515,9 +1515,9 @@ void EntityComponentManager::AddEntityToMessage(msgs::SerializedStateMap &_msg, } ////////////////////////////////////////////////// -ignition::msgs::SerializedState EntityComponentManager::ChangedState() const +msgs::SerializedState EntityComponentManager::ChangedState() const { - ignition::msgs::SerializedState stateMsg; + msgs::SerializedState stateMsg; // New entities for (const auto &entity : this->dataPtr->newlyCreatedEntities) @@ -1542,7 +1542,7 @@ ignition::msgs::SerializedState EntityComponentManager::ChangedState() const ////////////////////////////////////////////////// void EntityComponentManager::ChangedState( - ignition::msgs::SerializedStateMap &_state) const + msgs::SerializedStateMap &_state) const { // New entities for (const auto &entity : this->dataPtr->newlyCreatedEntities) @@ -1610,11 +1610,11 @@ void EntityComponentManagerPrivate::CalculateStateThreadLoad() } ////////////////////////////////////////////////// -ignition::msgs::SerializedState EntityComponentManager::State( +msgs::SerializedState EntityComponentManager::State( const std::unordered_set &_entities, const std::unordered_set &_types) const { - ignition::msgs::SerializedState stateMsg; + msgs::SerializedState stateMsg; for (const auto &it : this->dataPtr->componentTypeIndex) { auto entity = it.first; @@ -1680,7 +1680,7 @@ void EntityComponentManager::State( ////////////////////////////////////////////////// void EntityComponentManager::SetState( - const ignition::msgs::SerializedState &_stateMsg) + const msgs::SerializedState &_stateMsg) { IGN_PROFILE("EntityComponentManager::SetState Non-map"); // Create / remove / update entities @@ -1778,7 +1778,7 @@ void EntityComponentManager::SetState( ////////////////////////////////////////////////// void EntityComponentManager::SetState( - const ignition::msgs::SerializedStateMap &_stateMsg) + const msgs::SerializedStateMap &_stateMsg) { IGN_PROFILE("EntityComponentManager::SetState Map"); // Create / remove / update entities diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index ac8cb416ab..c627d5d3e4 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -52,27 +52,27 @@ using IntComponent = components::Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.IntComponent", IntComponent) -using UIntComponent = components::Component; +using UIntComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.UIntComponent", UIntComponent) -using DoubleComponent = components::Component; +using DoubleComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DoubleComponent", DoubleComponent) using StringComponent = - components::Component; + Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.StringComponent", StringComponent) -using BoolComponent = components::Component; +using BoolComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.BoolComponent", BoolComponent) -using Even = components::Component; +using Even = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Even", Even) -using Odd = components::Component; +using Odd = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Odd", Odd) struct Custom @@ -80,7 +80,7 @@ struct Custom int dummy{123}; }; -using CustomComponent = components::Component; +using CustomComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.CustomComponent", CustomComponent) } @@ -394,19 +394,19 @@ TEST_P(EntityComponentManagerFixture, } { - const auto *value = manager.Component(ePose); + const auto *value = manager.Component(ePose); ASSERT_NE(nullptr, value); EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), value->Data()); - auto data = manager.ComponentData(ePose); + auto data = manager.ComponentData(ePose); EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), data); - EXPECT_TRUE(manager.SetComponentData(ePose, + EXPECT_TRUE(manager.SetComponentData(ePose, {4, 5, 6, 0, 0, 0})); - data = manager.ComponentData(ePose); + data = manager.ComponentData(ePose); EXPECT_EQ(math::Pose3d(4, 5, 6, 0, 0, 0), data); - EXPECT_FALSE(manager.SetComponentData(ePose, + EXPECT_FALSE(manager.SetComponentData(ePose, {4, 5, 6, 0, 0, 0})); } @@ -1533,11 +1533,11 @@ TEST_P(EntityComponentManagerFixture, EXPECT_TRUE(manager.SetParentEntity(e6, e2)); EXPECT_TRUE(manager.SetParentEntity(e7, e2)); - EXPECT_FALSE(manager.SetParentEntity(e1, gazebo::Entity(1000))); - EXPECT_FALSE(manager.SetParentEntity(gazebo::Entity(1000), e1)); + EXPECT_FALSE(manager.SetParentEntity(e1, Entity(1000))); + EXPECT_FALSE(manager.SetParentEntity(Entity(1000), e1)); // Check their parents - EXPECT_EQ(gazebo::kNullEntity, manager.ParentEntity(e1)); + EXPECT_EQ(kNullEntity, manager.ParentEntity(e1)); EXPECT_EQ(e1, manager.ParentEntity(e2)); EXPECT_EQ(e1, manager.ParentEntity(e3)); EXPECT_EQ(e2, manager.ParentEntity(e4)); @@ -1546,8 +1546,8 @@ TEST_P(EntityComponentManagerFixture, EXPECT_EQ(e2, manager.ParentEntity(e7)); // Detach from graph - EXPECT_TRUE(manager.SetParentEntity(e7, gazebo::kNullEntity)); - EXPECT_EQ(gazebo::kNullEntity, manager.ParentEntity(e7)); + EXPECT_TRUE(manager.SetParentEntity(e7, kNullEntity)); + EXPECT_EQ(kNullEntity, manager.ParentEntity(e7)); // Reparent EXPECT_TRUE(manager.SetParentEntity(e5, e3)); @@ -3082,11 +3082,11 @@ TEST_P(EntityComponentManagerFixture, // create an entity and component auto entity = originalECMStateMap.CreateEntity(); - originalECMStateMap.CreateComponent(entity, components::IntComponent(1)); + originalECMStateMap.CreateComponent(entity, IntComponent(1)); int foundEntities = 0; - otherECMStateMap.Each( - [&](const Entity &, const components::IntComponent *) + otherECMStateMap.Each( + [&](const Entity &, const IntComponent *) { foundEntities++; return true; @@ -3098,8 +3098,8 @@ TEST_P(EntityComponentManagerFixture, originalECMStateMap.State(stateMapMsg); otherECMStateMap.SetState(stateMapMsg); foundEntities = 0; - otherECMStateMap.Each( - [&](const Entity &, const components::IntComponent *_intComp) + otherECMStateMap.Each( + [&](const Entity &, const IntComponent *_intComp) { foundEntities++; EXPECT_EQ(1, _intComp->Data()); @@ -3109,12 +3109,12 @@ TEST_P(EntityComponentManagerFixture, // modify a component and then share the update with the other ECM stateMapMsg.Clear(); - originalECMStateMap.SetComponentData(entity, 2); + originalECMStateMap.SetComponentData(entity, 2); originalECMStateMap.State(stateMapMsg); otherECMStateMap.SetState(stateMapMsg); foundEntities = 0; - otherECMStateMap.Each( - [&](const Entity &, const components::IntComponent *_intComp) + otherECMStateMap.Each( + [&](const Entity &, const IntComponent *_intComp) { foundEntities++; EXPECT_EQ(2, _intComp->Data()); @@ -3128,8 +3128,8 @@ TEST_P(EntityComponentManagerFixture, EntityComponentManager otherECMState; foundEntities = 0; - otherECMState.Each( - [&](const Entity &, const components::IntComponent *) + otherECMState.Each( + [&](const Entity &, const IntComponent *) { foundEntities++; return true; @@ -3137,13 +3137,13 @@ TEST_P(EntityComponentManagerFixture, EXPECT_EQ(0, foundEntities); entity = originalECMState.CreateEntity(); - originalECMState.CreateComponent(entity, components::IntComponent(1)); + originalECMState.CreateComponent(entity, IntComponent(1)); auto stateMsg = originalECMState.State(); otherECMState.SetState(stateMsg); foundEntities = 0; - otherECMState.Each( - [&](const Entity &, const components::IntComponent *_intComp) + otherECMState.Each( + [&](const Entity &, const IntComponent *_intComp) { foundEntities++; EXPECT_EQ(1, _intComp->Data()); @@ -3152,12 +3152,12 @@ TEST_P(EntityComponentManagerFixture, EXPECT_EQ(1, foundEntities); stateMsg.Clear(); - originalECMState.SetComponentData(entity, 2); + originalECMState.SetComponentData(entity, 2); stateMsg = originalECMState.State(); otherECMState.SetState(stateMsg); foundEntities = 0; - otherECMState.Each( - [&](const Entity &, const components::IntComponent *_intComp) + otherECMState.Each( + [&](const Entity &, const IntComponent *_intComp) { foundEntities++; EXPECT_EQ(2, _intComp->Data()); diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 12554dbf7e..6c9c6247e7 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -59,7 +59,7 @@ using namespace ignition; using namespace gazebo; ///////////////////////////////////////////////// -class EntityCompMgrTest : public gazebo::EntityComponentManager +class EntityCompMgrTest : public EntityComponentManager { public: void ProcessEntityRemovals() { @@ -167,21 +167,21 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (modelCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 1), + EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 1), _pose->Data()); EXPECT_EQ("box", _name->Data()); boxModelEntity = _entity; } else if (modelCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(-1, -2, -3, 0, 0, 1), + EXPECT_EQ(math::Pose3d(-1, -2, -3, 0, 0, 1), _pose->Data()); EXPECT_EQ("cylinder", _name->Data()); cylModelEntity = _entity; } else if (modelCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 1), + EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 1), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; @@ -236,7 +236,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (linkCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_link", _name->Data()); @@ -247,7 +247,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (linkCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_link", _name->Data()); @@ -258,7 +258,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (linkCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); @@ -370,7 +370,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (collisionCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_collision", _name->Data()); @@ -385,7 +385,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (collisionCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_collision", _name->Data()); @@ -400,7 +400,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (collisionCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_collision", _name->Data()); @@ -485,7 +485,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) if (visualCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_visual", _name->Data()); @@ -511,7 +511,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (visualCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_visual", _name->Data()); @@ -537,7 +537,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) } else if (visualCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -636,7 +636,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) lightCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("sun", _name->Data()); @@ -646,19 +646,19 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_EQ("sun", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ("", _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(1000, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(-0.5, 0.1, -0.9), + EXPECT_EQ(math::Vector3d(-0.5, 0.1, -0.9), _light->Data().Direction()); return true; }); @@ -733,7 +733,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ(worldEntity, this->ecm.ParentEntity(_entity)); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; @@ -764,7 +764,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) linkCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); EXPECT_EQ(sphModelEntity, _parent->Data()); @@ -803,7 +803,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) visualCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -845,7 +845,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) // light attached to link if (lightCount == 1u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("link_light_point", _name->Data()); @@ -854,13 +854,13 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("link_light_point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 1, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 1, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 0.0f, 1.0f, 1), + EXPECT_EQ(math::Color(0.0f, 0.0f, 1.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(2, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.05, _light->Data().ConstantAttenuationFactor()); @@ -870,7 +870,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) // directional light in the world else if (lightCount == 2u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("directional", _name->Data()); @@ -879,25 +879,25 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("directional", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(100, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.5, 0.2, -0.9), + EXPECT_EQ(math::Vector3d(0.5, 0.2, -0.9), _light->Data().Direction()); } // point light in the world else if (lightCount == 3u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, -1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("point", _name->Data()); @@ -906,13 +906,13 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, -1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(1.0f, 0.0f, 0.0f, 1), + EXPECT_EQ(math::Color(1.0f, 0.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(4, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.2, _light->Data().ConstantAttenuationFactor()); @@ -922,7 +922,7 @@ TEST_F(SdfEntityCreatorTest, CreateLights) // spot light in the world else if (lightCount == 4u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("spot", _name->Data()); @@ -931,19 +931,19 @@ TEST_F(SdfEntityCreatorTest, CreateLights) EXPECT_EQ("spot", _light->Data().Name()); EXPECT_EQ(sdf::LightType::SPOT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 1.0f, 0.0f, 1), + EXPECT_EQ(math::Color(0.0f, 1.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(5, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.3, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.4, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.0, 0.0, -1.0), + EXPECT_EQ(math::Vector3d(0.0, 0.0, -1.0), _light->Data().Direction()); EXPECT_DOUBLE_EQ(0.1, _light->Data().SpotInnerAngle().Radian()); EXPECT_DOUBLE_EQ(0.5, _light->Data().SpotOuterAngle().Radian()); @@ -1218,7 +1218,7 @@ size_t removedCount(EntityCompMgrTest &_manager) { size_t count = 0; _manager.EachRemoved( - [&](const ignition::gazebo::Entity &, const Ts *...) -> bool + [&](const Entity &, const Ts *...) -> bool { ++count; return true; diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index 1478ff02b2..a299d45b7f 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -644,17 +644,17 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedNotExpanded) TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris) { const std::string goodUri = - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2"; + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/2"; // These are URIs that are potentially problematic. const std::vector fuelUris = { // Thes following two URIs are valid, but have a trailing '/' - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/", - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2/", + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/", + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/2/", // Thes following two URIs are invalid, and will not be saved - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/" + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/" "notInt", - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/" + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/" "notInt/", }; @@ -709,7 +709,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris) TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithNonFuelUris) { const std::vector includeUris = { - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack", + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack", std::string("file://") + PROJECT_SOURCE_PATH + "/test/worlds/models/sphere"}; diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index ba50a7369c..d5c6d027bb 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -315,7 +315,7 @@ class ignition::gazebo::ServerConfigPrivate public: std::string logRecordCompressPath = ""; /// \brief Path to where simulation resources, such as models downloaded - /// from fuel.ignitionrobotics.org, should be stored. + /// from fuel.gazebosim.org, should be stored. public: std::string resourceCache = ""; /// \brief File containing physics engine plugin. If empty, DART will be used. @@ -561,7 +561,7 @@ unsigned int ServerConfig::Seed() const void ServerConfig::SetSeed(unsigned int _seed) { this->dataPtr->seed = _seed; - ignition::math::Rand::Seed(_seed); + math::Rand::Seed(_seed); } ///////////////////////////////////////////////// @@ -902,7 +902,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) ///////////////////////////////////////////////// std::list -ignition::gazebo::parsePluginsFromFile(const std::string &_fname) +gazebo::parsePluginsFromFile(const std::string &_fname) { tinyxml2::XMLDocument doc; doc.LoadFile(_fname.c_str()); @@ -911,7 +911,7 @@ ignition::gazebo::parsePluginsFromFile(const std::string &_fname) ///////////////////////////////////////////////// std::list -ignition::gazebo::parsePluginsFromString(const std::string &_str) +gazebo::parsePluginsFromString(const std::string &_str) { tinyxml2::XMLDocument doc; doc.Parse(_str.c_str()); @@ -920,28 +920,28 @@ ignition::gazebo::parsePluginsFromString(const std::string &_str) ///////////////////////////////////////////////// std::list -ignition::gazebo::loadPluginInfo(bool _isPlayback) +gazebo::loadPluginInfo(bool _isPlayback) { std::list ret; // 1. Check contents of environment variable std::string envConfig; - bool configSet = ignition::common::env(gazebo::kServerConfigPathEnv, + bool configSet = common::env(kServerConfigPathEnv, envConfig, true); if (configSet) { - if (ignition::common::exists(envConfig)) + if (common::exists(envConfig)) { // Parse configuration stored in environment variable - ret = ignition::gazebo::parsePluginsFromFile(envConfig); + ret = gazebo::parsePluginsFromFile(envConfig); if (ret.empty()) { // This may be desired behavior, but warn just in case. // Some users may want to defer all loading until later // during runtime. - ignwarn << gazebo::kServerConfigPathEnv + ignwarn << kServerConfigPathEnv << " set but no plugins found\n"; } igndbg << "Loaded (" << ret.size() << ") plugins from file " << @@ -954,7 +954,7 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) // This may be desired behavior, but warn just in case. // Some users may want to defer all loading until late // during runtime. - ignwarn << gazebo::kServerConfigPathEnv + ignwarn << kServerConfigPathEnv << " set but no file found," << " no plugins loaded\n"; return ret; @@ -972,27 +972,27 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) } std::string defaultConfigDir; - ignition::common::env(IGN_HOMEDIR, defaultConfigDir); - defaultConfigDir = ignition::common::joinPaths(defaultConfigDir, ".ignition", + common::env(IGN_HOMEDIR, defaultConfigDir); + defaultConfigDir = common::joinPaths(defaultConfigDir, ".ignition", "gazebo", IGNITION_GAZEBO_MAJOR_VERSION_STR); - auto defaultConfig = ignition::common::joinPaths(defaultConfigDir, + auto defaultConfig = common::joinPaths(defaultConfigDir, configFilename); - if (!ignition::common::exists(defaultConfig)) + if (!common::exists(defaultConfig)) { - auto installedConfig = ignition::common::joinPaths( + auto installedConfig = common::joinPaths( IGNITION_GAZEBO_SERVER_CONFIG_PATH, configFilename); - if (!ignition::common::createDirectories(defaultConfigDir)) + if (!common::createDirectories(defaultConfigDir)) { ignerr << "Failed to create directory [" << defaultConfigDir << "]." << std::endl; return ret; } - if (!ignition::common::exists(installedConfig)) + if (!common::exists(installedConfig)) { ignerr << "Failed to copy installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." @@ -1000,7 +1000,7 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) << std::endl; return ret; } - else if (!ignition::common::copyFile(installedConfig, defaultConfig)) + else if (!common::copyFile(installedConfig, defaultConfig)) { ignerr << "Failed to copy installed config [" << installedConfig << "] to default config [" << defaultConfig << "]." @@ -1015,7 +1015,7 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) } } - ret = ignition::gazebo::parsePluginsFromFile(defaultConfig); + ret = gazebo::parsePluginsFromFile(defaultConfig); if (ret.empty()) { diff --git a/src/ServerConfig_TEST.cc b/src/ServerConfig_TEST.cc index 4e7b7c9aa4..351bf06410 100644 --- a/src/ServerConfig_TEST.cc +++ b/src/ServerConfig_TEST.cc @@ -191,11 +191,11 @@ TEST(ParsePluginsFromFile, PlaybackConfig) TEST(LoadPluginInfo, FromEmptyEnv) { // Set environment to something that doesn't exist - ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, "foo")); + ASSERT_TRUE(common::setenv(kServerConfigPathEnv, "foo")); auto plugins = loadPluginInfo(); EXPECT_EQ(0u, plugins.size()); - EXPECT_TRUE(common::unsetenv(gazebo::kServerConfigPathEnv)); + EXPECT_TRUE(common::unsetenv(kServerConfigPathEnv)); } ////////////////////////////////////////////////// @@ -204,7 +204,7 @@ TEST(LoadPluginInfo, FromValidEnv) auto validPath = common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "server_valid2.config"); - ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, validPath)); + ASSERT_TRUE(common::setenv(kServerConfigPathEnv, validPath)); auto plugins = loadPluginInfo(); ASSERT_EQ(2u, plugins.size()); @@ -226,7 +226,7 @@ TEST(LoadPluginInfo, FromValidEnv) EXPECT_EQ("ignition::gazebo::TestModelSystem", plugin->Name()); EXPECT_EQ("ignition::gazebo::TestModelSystem", plugin->Plugin().Name()); - EXPECT_TRUE(common::unsetenv(gazebo::kServerConfigPathEnv)); + EXPECT_TRUE(common::unsetenv(kServerConfigPathEnv)); } ////////////////////////////////////////////////// diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 6f1929b82e..fffbb62dba 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -381,7 +381,7 @@ void ServerPrivate::SetupTransport() } ////////////////////////////////////////////////// -bool ServerPrivate::WorldsService(ignition::msgs::StringMsg_V &_res) +bool ServerPrivate::WorldsService(msgs::StringMsg_V &_res) { std::lock_guard lock(this->worldsMutex); @@ -397,7 +397,7 @@ bool ServerPrivate::WorldsService(ignition::msgs::StringMsg_V &_res) ////////////////////////////////////////////////// bool ServerPrivate::ServerControlService( - const ignition::msgs::ServerControl &_req, msgs::Boolean &_res) + const msgs::ServerControl &_req, msgs::Boolean &_res) { _res.set_data(false); @@ -440,7 +440,7 @@ bool ServerPrivate::ServerControlService( ////////////////////////////////////////////////// void ServerPrivate::AddResourcePathsService( - const ignition::msgs::StringMsg_V &_req) + const msgs::StringMsg_V &_req) { std::vector paths; for (int i = 0; i < _req.data_size(); ++i) @@ -463,7 +463,7 @@ void ServerPrivate::AddResourcePathsService( ////////////////////////////////////////////////// bool ServerPrivate::ResourcePathsService( - ignition::msgs::StringMsg_V &_res) + msgs::StringMsg_V &_res) { _res.Clear(); diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 6023c036ea..59879223b5 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -54,7 +54,7 @@ class ServerFixture : public InternalFixture<::testing::TestWithParam> // See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultServerConfig)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; EXPECT_TRUE(serverConfig.SdfFile().empty()); EXPECT_TRUE(serverConfig.SdfString().empty()); EXPECT_FALSE(serverConfig.UpdateRate()); @@ -110,7 +110,7 @@ TEST_P(ServerFixture, ServerConfigPluginInfo) pluginInfo.SetName("interface"); pluginInfo.SetSdf(nullptr); - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.AddPlugin(pluginInfo); const std::list &plugins = serverConfig.Plugins(); @@ -331,7 +331,7 @@ TEST_P(ServerFixture, ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfServerConfig)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); EXPECT_TRUE(serverConfig.SdfFile().empty()); @@ -476,7 +476,7 @@ TEST_P(ServerFixture, ///////////////////////////////////////////////// TEST_P(ServerFixture, SdfStringServerConfig) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "shapes.sdf")); @@ -691,7 +691,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunOncePaused)) ///////////////////////////////////////////////// TEST_P(ServerFixture, RunNonBlockingMultiple) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); gazebo::Server server(serverConfig); @@ -792,7 +792,7 @@ TEST_P(ServerFixture, ServerControlStop) ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemWhileRunning)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "shapes.sdf")); @@ -840,7 +840,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemWhileRunning)) ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemAfterLoad)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "shapes.sdf")); @@ -903,18 +903,18 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemAfterLoad)) ///////////////////////////////////////////////// TEST_P(ServerFixture, Seed) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; EXPECT_EQ(0u, serverConfig.Seed()); unsigned int mySeed = 12345u; serverConfig.SetSeed(mySeed); EXPECT_EQ(mySeed, serverConfig.Seed()); - EXPECT_EQ(mySeed, ignition::math::Rand::Seed()); + EXPECT_EQ(mySeed, math::Rand::Seed()); } ///////////////////////////////////////////////// TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) { - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + common::setenv("IGN_GAZEBO_RESOURCE_PATH", (common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds:") + common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "models")).c_str()); @@ -974,7 +974,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) // Check physics system loaded meshes and got their BB correct eachCount = 0; _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::AxisAlignedBox *_box)->bool { auto box = _box->Data(); @@ -1003,7 +1003,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) ///////////////////////////////////////////////// TEST_P(ServerFixture, GetResourcePaths) { - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + common::setenv("IGN_GAZEBO_RESOURCE_PATH", std::string("/tmp/some/path") + common::SystemPaths::Delimiter() + std::string("/home/user/another_path")); @@ -1035,12 +1035,12 @@ TEST_P(ServerFixture, GetResourcePaths) ///////////////////////////////////////////////// TEST_P(ServerFixture, AddResourcePaths) { - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + common::setenv("IGN_GAZEBO_RESOURCE_PATH", std::string("/tmp/some/path") + common::SystemPaths::Delimiter() + std::string("/home/user/another_path")); - ignition::common::setenv("SDF_PATH", ""); - ignition::common::setenv("IGN_FILE_PATH", ""); + common::setenv("SDF_PATH", ""); + common::setenv("IGN_FILE_PATH", ""); ServerConfig serverConfig; gazebo::Server server(serverConfig); diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index 3f817dd1c5..3fdf7725d5 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -198,7 +198,7 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, { ignmsg << "No systems loaded from SDF, loading defaults" << std::endl; bool isPlayback = !this->serverConfig.LogPlaybackPath().empty(); - auto plugins = ignition::gazebo::loadPluginInfo(isPlayback); + auto plugins = gazebo::loadPluginInfo(isPlayback); this->LoadServerPlugins(plugins); } @@ -404,14 +404,14 @@ void SimulationRunner::PublishStats() IGN_PROFILE("SimulationRunner::PublishStats"); // Create the world statistics message. - ignition::msgs::WorldStatistics msg; + msgs::WorldStatistics msg; msg.set_real_time_factor(this->realTimeFactor); auto realTimeSecNsec = - ignition::math::durationToSecNsec(this->currentInfo.realTime); + math::durationToSecNsec(this->currentInfo.realTime); auto simTimeSecNsec = - ignition::math::durationToSecNsec(this->currentInfo.simTime); + math::durationToSecNsec(this->currentInfo.simTime); msg.mutable_real_time()->set_sec(realTimeSecNsec.first); msg.mutable_real_time()->set_nsec(realTimeSecNsec.second); @@ -437,7 +437,7 @@ void SimulationRunner::PublishStats() // Create and publish the clock message. The clock message is not // throttled. - ignition::msgs::Clock clockMsg; + msgs::Clock clockMsg; clockMsg.mutable_real()->set_sec(realTimeSecNsec.first); clockMsg.mutable_real()->set_nsec(realTimeSecNsec.second); clockMsg.mutable_sim()->set_sec(simTimeSecNsec.first); @@ -527,7 +527,7 @@ void SimulationRunner::UpdateSystems() { IGN_PROFILE("SimulationRunner::UpdateSystems"); // \todo(nkoenig) Systems used to be updated in parallel using - // an ignition::common::WorkerPool. There is overhead associated with + // an common::WorkerPool. There is overhead associated with // this, most notably the creation and destruction of WorkOrders (see // WorkerPool.cc). We could turn on parallel updates in the future, and/or // turn it on if there are sufficient systems. More testing is required. @@ -642,14 +642,14 @@ bool SimulationRunner::Run(const uint64_t _iterations) // https://github.com/ignitionrobotics/ign-gui/pull/306 and // https://github.com/ignitionrobotics/ign-gazebo/pull/1163) advertOpts.SetMsgsPerSec(10); - this->statsPub = this->node->Advertise( + this->statsPub = this->node->Advertise( "stats", advertOpts); } if (!this->rootStatsPub.Valid()) { // Check for the existence of other publishers on `/stats` - std::vector publishers; + std::vector publishers; this->node->TopicInfo("/stats", publishers); if (!publishers.empty()) @@ -676,13 +676,13 @@ bool SimulationRunner::Run(const uint64_t _iterations) // Create the clock publisher. if (!this->clockPub.Valid()) - this->clockPub = this->node->Advertise("clock"); + this->clockPub = this->node->Advertise("clock"); // Create the global clock publisher. if (!this->rootClockPub.Valid()) { // Check for the existence of other publishers on `/clock` - std::vector publishers; + std::vector publishers; this->node->TopicInfo("/clock", publishers); if (!publishers.empty()) @@ -702,7 +702,7 @@ bool SimulationRunner::Run(const uint64_t _iterations) { ignmsg << "Found no publishers on /clock, adding root clock topic" << std::endl; - this->rootClockPub = this->node->Advertise( + this->rootClockPub = this->node->Advertise( "/clock"); } } @@ -1332,13 +1332,13 @@ SimulationRunner::UpdatePeriod() const } ///////////////////////////////////////////////// -const ignition::math::clock::duration &SimulationRunner::StepSize() const +const math::clock::duration &SimulationRunner::StepSize() const { return this->stepSize; } ///////////////////////////////////////////////// -void SimulationRunner::SetStepSize(const ignition::math::clock::duration &_step) +void SimulationRunner::SetStepSize(const math::clock::duration &_step) { this->stepSize = _step; } @@ -1414,7 +1414,7 @@ bool SimulationRunner::RequestRemoveEntity(const Entity _entity, } ////////////////////////////////////////////////// -bool SimulationRunner::GuiInfoService(ignition::msgs::GUI &_res) +bool SimulationRunner::GuiInfoService(msgs::GUI &_res) { _res.Clear(); diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index 5f0e91e26c..4dbae0cd04 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -72,11 +72,11 @@ namespace gazebo inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { namespace components { -using IntComponent = components::Component; +using IntComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.IntComponent", IntComponent) -using DoubleComponent = components::Component; +using DoubleComponent = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DoubleComponent", DoubleComponent) } @@ -122,31 +122,31 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check component types EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::World::typeId)); + World::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Model::typeId)); + Model::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::CanonicalLink::typeId)); + CanonicalLink::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Link::typeId)); + Link::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Collision::typeId)); + Collision::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Visual::typeId)); + Visual::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Light::typeId)); + Light::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Name::typeId)); + Name::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::ParentEntity::typeId)); + ParentEntity::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Geometry::typeId)); + Geometry::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( components::Material::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Inertial::typeId)); + Inertial::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Wind::typeId)); + Wind::typeId)); // Check entities // 1 x world + 1 x (default) level + 1 x wind + 5 x model + 5 x link + 5 x @@ -156,10 +156,10 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check worlds unsigned int worldCount{0}; Entity worldEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::World *_world, + const World *_world, const components::Name *_name)->bool { EXPECT_NE(nullptr, _world); @@ -187,14 +187,14 @@ TEST_P(SimulationRunnerTest, CreateEntities) Entity sphModelEntity = kNullEntity; Entity capModelEntity = kNullEntity; Entity ellipModelEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::Model *_model, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Model *_model, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _model); @@ -207,21 +207,21 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ(worldEntity, _parent->Data()); if (modelCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 1), + EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 1), _pose->Data()); EXPECT_EQ("box", _name->Data()); boxModelEntity = _entity; } else if (modelCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(-1, -2, -3, 0, 0, 1), + EXPECT_EQ(math::Pose3d(-1, -2, -3, 0, 0, 1), _pose->Data()); EXPECT_EQ("cylinder", _name->Data()); cylModelEntity = _entity; } else if (modelCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 1), + EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 1), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; @@ -257,14 +257,14 @@ TEST_P(SimulationRunnerTest, CreateEntities) Entity sphLinkEntity = kNullEntity; Entity capLinkEntity = kNullEntity; Entity ellipLinkEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::Link *_link, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Link *_link, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _link); @@ -276,7 +276,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) if (linkCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.1, 0.1, 0.1, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_link", _name->Data()); EXPECT_EQ(boxModelEntity, _parent->Data()); @@ -284,7 +284,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (linkCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.2, 0.2, 0.2, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_link", _name->Data()); EXPECT_EQ(cylModelEntity, _parent->Data()); @@ -292,7 +292,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (linkCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.3, 0.3, 0.3, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); EXPECT_EQ(sphModelEntity, _parent->Data()); @@ -326,10 +326,10 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check inertials unsigned int inertialCount{0}; - runner.EntityCompMgr().Each( + runner.EntityCompMgr().Each( [&](const Entity & _entity, - const components::Link *_link, - const components::Inertial *_inertial)->bool + const Link *_link, + const Inertial *_inertial)->bool { EXPECT_NE(nullptr, _link); EXPECT_NE(nullptr, _inertial); @@ -373,16 +373,16 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check collisions unsigned int collisionCount{0}; - runner.EntityCompMgr().Each( [&](const Entity &/*_entity*/, - const components::Collision *_collision, - const components::Geometry *_geometry, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Collision *_collision, + const Geometry *_geometry, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _collision); @@ -395,7 +395,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) if (collisionCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.11, 0.11, 0.11, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_collision", _name->Data()); @@ -409,7 +409,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (collisionCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.21, 0.21, 0.21, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_collision", _name->Data()); @@ -423,7 +423,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (collisionCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.31, 0.31, 0.31, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_collision", _name->Data()); @@ -469,18 +469,18 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check visuals unsigned int visualCount{0}; - runner.EntityCompMgr().Each( [&](const Entity &/*_entity*/, - const components::Visual *_visual, - const components::Geometry *_geometry, + const Visual *_visual, + const Geometry *_geometry, const components::Material *_material, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _visual); @@ -494,7 +494,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) if (visualCount == 1) { - EXPECT_EQ(ignition::math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.12, 0.12, 0.12, 0, 0, 0), _pose->Data()); EXPECT_EQ("box_visual", _name->Data()); @@ -513,7 +513,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 2) { - EXPECT_EQ(ignition::math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.22, 0.22, 0.22, 0, 0, 0), _pose->Data()); EXPECT_EQ("cylinder_visual", _name->Data()); @@ -532,7 +532,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 3) { - EXPECT_EQ(ignition::math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.32, 0.32, 0.32, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -550,7 +550,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 4) { - EXPECT_EQ(ignition::math::Pose3d(0.52, 0.52, 0.52, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.52, 0.52, 0.52, 0, 0, 0), _pose->Data()); EXPECT_EQ("capsule_visual", _name->Data()); @@ -569,7 +569,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) } else if (visualCount == 5) { - EXPECT_EQ(ignition::math::Pose3d(0.82, 0.82, 0.82, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.82, 0.82, 0.82, 0, 0, 0), _pose->Data()); EXPECT_EQ("ellipsoid_visual", _name->Data()); @@ -578,7 +578,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ(sdf::GeometryType::ELLIPSOID, _geometry->Data().Type()); EXPECT_NE(nullptr, _geometry->Data().EllipsoidShape()); - EXPECT_EQ(ignition::math::Vector3d(0.4, 0.6, 1.6), + EXPECT_EQ(math::Vector3d(0.4, 0.6, 1.6), _geometry->Data().EllipsoidShape()->Radii()); EXPECT_EQ(math::Color(0.0f, 0.0f, 0.0f), _material->Data().Emissive()); @@ -593,14 +593,14 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check lights unsigned int lightCount{0}; - runner.EntityCompMgr().Each( [&](const Entity &/*_entity*/, - const components::Light *_light, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Light *_light, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _light); @@ -610,7 +610,7 @@ TEST_P(SimulationRunnerTest, CreateEntities) lightCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("sun", _name->Data()); @@ -619,20 +619,20 @@ TEST_P(SimulationRunnerTest, CreateEntities) EXPECT_EQ("sun", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ("", _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(1000, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); EXPECT_DOUBLE_EQ(1.0, _light->Data().Intensity()); - EXPECT_EQ(ignition::math::Vector3d(-0.5, 0.1, -0.9), + EXPECT_EQ(math::Vector3d(-0.5, 0.1, -0.9), _light->Data().Direction()); return true; }); @@ -662,10 +662,10 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check worlds unsigned int worldCount{0}; Entity worldEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::World *_world, + const World *_world, const components::Name *_name)->bool { EXPECT_NE(nullptr, _world); @@ -685,14 +685,14 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check model unsigned int modelCount{0}; Entity sphModelEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::Model *_model, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Model *_model, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _model); @@ -703,7 +703,7 @@ TEST_P(SimulationRunnerTest, CreateLights) modelCount++; EXPECT_EQ(worldEntity, _parent->Data()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere", _name->Data()); sphModelEntity = _entity; @@ -717,14 +717,14 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check link unsigned int linkCount{0}; Entity sphLinkEntity = kNullEntity; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::Link *_link, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Link *_link, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _link); @@ -734,7 +734,7 @@ TEST_P(SimulationRunnerTest, CreateLights) linkCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_link", _name->Data()); EXPECT_EQ(sphModelEntity, _parent->Data()); @@ -748,18 +748,18 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check visuals unsigned int visualCount{0}; - runner.EntityCompMgr().Each( [&](const Entity &/*_entity*/, - const components::Visual *_visual, - const components::Geometry *_geometry, + const Visual *_visual, + const Geometry *_geometry, const components::Material *_material, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _visual); @@ -771,7 +771,7 @@ TEST_P(SimulationRunnerTest, CreateLights) visualCount++; - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 0.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("sphere_visual", _name->Data()); @@ -792,14 +792,14 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check lights unsigned int lightCount{0}; - runner.EntityCompMgr().Each( [&](const Entity &/*_entity*/, - const components::Light *_light, - const components::Pose *_pose, - const components::ParentEntity *_parent, + const Light *_light, + const Pose *_pose, + const ParentEntity *_parent, const components::Name *_name)->bool { EXPECT_NE(nullptr, _light); @@ -812,19 +812,19 @@ TEST_P(SimulationRunnerTest, CreateLights) // light attached to link if (lightCount == 1u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 1.0, 0, 0, 0), _pose->Data()); EXPECT_EQ("link_light_point", _name->Data()); EXPECT_EQ(sphLinkEntity, _parent->Data()); EXPECT_EQ("link_light_point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 1, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 1, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 0.0f, 1.0f, 1), + EXPECT_EQ(math::Color(0.0f, 0.0f, 1.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(2, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.05, _light->Data().ConstantAttenuationFactor()); @@ -834,43 +834,43 @@ TEST_P(SimulationRunnerTest, CreateLights) // directional light in the world else if (lightCount == 2u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 0.0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 0.0, 10, 0, 0, 0), _pose->Data()); EXPECT_EQ("directional", _name->Data()); EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ("directional", _light->Data().Name()); EXPECT_EQ(sdf::LightType::DIRECTIONAL, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 0, 10, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 0, 10, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_TRUE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f, 1), + EXPECT_EQ(math::Color(0.8f, 0.8f, 0.8f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(100, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.9, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.01, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.5, 0.2, -0.9), + EXPECT_EQ(math::Vector3d(0.5, 0.2, -0.9), _light->Data().Direction()); } // point light in the world else if (lightCount == 3u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, -1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("point", _name->Data()); EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ("point", _light->Data().Name()); EXPECT_EQ(sdf::LightType::POINT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, -1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, -1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(1.0f, 0.0f, 0.0f, 1), + EXPECT_EQ(math::Color(1.0f, 0.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.1f, 0.1f, 0.1f, 1), + EXPECT_EQ(math::Color(0.1f, 0.1f, 0.1f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(4, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.2, _light->Data().ConstantAttenuationFactor()); @@ -880,25 +880,25 @@ TEST_P(SimulationRunnerTest, CreateLights) // spot light in the world else if (lightCount == 4u) { - EXPECT_EQ(ignition::math::Pose3d(0.0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0.0, 1.5, 3, 0, 0, 0), _pose->Data()); EXPECT_EQ("spot", _name->Data()); EXPECT_EQ(worldEntity, _parent->Data()); EXPECT_EQ("spot", _light->Data().Name()); EXPECT_EQ(sdf::LightType::SPOT, _light->Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(0, 1.5, 3, 0, 0, 0), + EXPECT_EQ(math::Pose3d(0, 1.5, 3, 0, 0, 0), _light->Data().RawPose()); EXPECT_EQ(std::string(), _light->Data().PoseRelativeTo()); EXPECT_FALSE(_light->Data().CastShadows()); - EXPECT_EQ(ignition::math::Color(0.0f, 1.0f, 0.0f, 1), + EXPECT_EQ(math::Color(0.0f, 1.0f, 0.0f, 1), _light->Data().Diffuse()); - EXPECT_EQ(ignition::math::Color(0.2f, 0.2f, 0.2f, 1), + EXPECT_EQ(math::Color(0.2f, 0.2f, 0.2f, 1), _light->Data().Specular()); EXPECT_DOUBLE_EQ(5, _light->Data().AttenuationRange()); EXPECT_DOUBLE_EQ(0.3, _light->Data().ConstantAttenuationFactor()); EXPECT_DOUBLE_EQ(0.4, _light->Data().LinearAttenuationFactor()); EXPECT_DOUBLE_EQ(0.001, _light->Data().QuadraticAttenuationFactor()); - EXPECT_EQ(ignition::math::Vector3d(0.0, 0.0, -1.0), + EXPECT_EQ(math::Vector3d(0.0, 0.0, -1.0), _light->Data().Direction()); EXPECT_DOUBLE_EQ(0.1, _light->Data().SpotInnerAngle().Radian()); EXPECT_DOUBLE_EQ(0.5, _light->Data().SpotOuterAngle().Radian()); @@ -926,34 +926,34 @@ TEST_P(SimulationRunnerTest, CreateJointEntities) // Check component types EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::World::typeId)); + World::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::CanonicalLink::typeId)); + CanonicalLink::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Link::typeId)); + Link::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Joint::typeId)); + Joint::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::JointAxis::typeId)); + JointAxis::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::JointType::typeId)); + JointType::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::ChildLinkName::typeId)); + ChildLinkName::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::ParentLinkName::typeId)); + ParentLinkName::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::ParentEntity::typeId)); + ParentEntity::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Pose::typeId)); + Pose::typeId)); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType( - components::Name::typeId)); + Name::typeId)); const sdf::Model *model = root.WorldByIndex(0)->ModelByIndex(1); // Check canonical links unsigned int canonicalLinkCount{0}; - runner.EntityCompMgr().Each( - [&](const Entity &, const components::CanonicalLink *)->bool + runner.EntityCompMgr().Each( + [&](const Entity &, const CanonicalLink *)->bool { canonicalLinkCount++; return true; @@ -973,11 +973,11 @@ TEST_P(SimulationRunnerTest, CreateJointEntities) }; auto testJoint = [&testAxis](const sdf::Joint *_joint, - const components::JointAxis *_axis, - const components::JointAxis2 *_axis2, - const components::ParentLinkName *_parentLinkName, - const components::ChildLinkName *_childLinkName, - const components::Pose *_pose, + const JointAxis *_axis, + const JointAxis2 *_axis2, + const ParentLinkName *_parentLinkName, + const ChildLinkName *_childLinkName, + const Pose *_pose, const components::Name *_name, bool _checkAxis = true, bool _checkAxis2 = false) @@ -1012,25 +1012,25 @@ TEST_P(SimulationRunnerTest, CreateJointEntities) }; std::set jointTypes; - runner.EntityCompMgr().Each( [&](const Entity &_entity, - const components::Joint * /*_joint*/, - const components::JointType *_jointType, - const components::ParentLinkName *_parentLinkName, - const components::ChildLinkName *_childLinkName, - const components::Pose *_pose, + const Joint * /*_joint*/, + const JointType *_jointType, + const ParentLinkName *_parentLinkName, + const ChildLinkName *_childLinkName, + const Pose *_pose, const components::Name *_name)->bool { jointTypes.insert(_jointType->Data()); auto axis = - runner.EntityCompMgr().Component(_entity); + runner.EntityCompMgr().Component(_entity); auto axis2 = - runner.EntityCompMgr().Component(_entity); + runner.EntityCompMgr().Component(_entity); const sdf::Joint *joint = model->JointByName(_name->Data()); @@ -1184,7 +1184,7 @@ TEST_P(SimulationRunnerTest, Time) } ///////////////////////////////////////////////// -// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +// See https://github.com/gazebosim/gz-sim/issues/1175 TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) { // Load SDF file @@ -1200,9 +1200,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get world entity Entity worldId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::World *_world)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const World *_world)->bool { EXPECT_NE(nullptr, _world); worldId = _entity; @@ -1212,9 +1212,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get model entity Entity modelId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Model *_model)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const Model *_model)->bool { EXPECT_NE(nullptr, _model); modelId = _entity; @@ -1224,9 +1224,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get sensor entity Entity sensorId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Sensor *_sensor)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const Sensor *_sensor)->bool { EXPECT_NE(nullptr, _sensor); sensorId = _entity; @@ -1236,9 +1236,9 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Get visual entity Entity visualId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Visual *_visual)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const components::Visual *_visual)->bool { EXPECT_NE(nullptr, _visual); visualId = _entity; @@ -1248,7 +1248,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by world plugin std::string worldComponentName{"WorldPluginComponent"}; - auto worldComponentId = ignition::common::hash64(worldComponentName); + auto worldComponentId = common::hash64(worldComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(worldComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(worldId, @@ -1256,7 +1256,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by model plugin std::string modelComponentName{"ModelPluginComponent"}; - auto modelComponentId = ignition::common::hash64(modelComponentName); + auto modelComponentId = common::hash64(modelComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(modelComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(modelId, @@ -1264,7 +1264,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by sensor plugin std::string sensorComponentName{"SensorPluginComponent"}; - auto sensorComponentId = ignition::common::hash64(sensorComponentName); + auto sensorComponentId = common::hash64(sensorComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(sensorComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(sensorId, @@ -1272,7 +1272,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // Check component registered by visual plugin std::string visualComponentName{"VisualPluginComponent"}; - auto visualComponentId = ignition::common::hash64(visualComponentName); + auto visualComponentId = common::hash64(visualComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(visualComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(visualId, @@ -1285,10 +1285,10 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) // reproduce? Maybe we need to test unloading plugins, but we have no API for // it yet. #if defined (__clang__) - components::Factory::Instance()->Unregister(worldComponentId); - components::Factory::Instance()->Unregister(modelComponentId); - components::Factory::Instance()->Unregister(sensorComponentId); - components::Factory::Instance()->Unregister(visualComponentId); + Factory::Instance()->Unregister(worldComponentId); + Factory::Instance()->Unregister(modelComponentId); + Factory::Instance()->Unregister(sensorComponentId); + Factory::Instance()->Unregister(visualComponentId); #endif } @@ -1304,7 +1304,7 @@ TEST_P(SimulationRunnerTest, // ServerConfig will fall back to environment variable auto config = common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "server_valid2.config"); - ASSERT_EQ(true, common::setenv(gazebo::kServerConfigPathEnv, config)); + ASSERT_EQ(true, common::setenv(kServerConfigPathEnv, config)); ServerConfig serverConfig; // Create simulation runner @@ -1345,9 +1345,9 @@ TEST_P(SimulationRunnerTest, // Get world entity Entity worldId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::World *_world)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const World *_world)->bool { EXPECT_NE(nullptr, _world); worldId = _entity; @@ -1357,9 +1357,9 @@ TEST_P(SimulationRunnerTest, // Get model entity Entity modelId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Model *_model)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const Model *_model)->bool { EXPECT_NE(nullptr, _model); modelId = _entity; @@ -1369,9 +1369,9 @@ TEST_P(SimulationRunnerTest, // Get sensor entity Entity sensorId{kNullEntity}; - runner.EntityCompMgr().Each([&]( - const ignition::gazebo::Entity &_entity, - const ignition::gazebo::components::Sensor *_sensor)->bool + runner.EntityCompMgr().Each([&]( + const Entity &_entity, + const Sensor *_sensor)->bool { EXPECT_NE(nullptr, _sensor); sensorId = _entity; @@ -1381,7 +1381,7 @@ TEST_P(SimulationRunnerTest, // Check component registered by world plugin std::string worldComponentName{"WorldPluginComponent"}; - auto worldComponentId = ignition::common::hash64(worldComponentName); + auto worldComponentId = common::hash64(worldComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(worldComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(worldId, @@ -1389,7 +1389,7 @@ TEST_P(SimulationRunnerTest, // Check component registered by model plugin std::string modelComponentName{"ModelPluginComponent"}; - auto modelComponentId = ignition::common::hash64(modelComponentName); + auto modelComponentId = common::hash64(modelComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(modelComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(modelId, @@ -1397,7 +1397,7 @@ TEST_P(SimulationRunnerTest, // Check component registered by sensor plugin std::string sensorComponentName{"SensorPluginComponent"}; - auto sensorComponentId = ignition::common::hash64(sensorComponentName); + auto sensorComponentId = common::hash64(sensorComponentName); EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(sensorComponentId)); EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(sensorId, @@ -1410,9 +1410,9 @@ TEST_P(SimulationRunnerTest, // reproduce? Maybe we need to test unloading plugins, but we have no API for // it yet. #if defined (__clang__) - components::Factory::Instance()->Unregister(worldComponentId); - components::Factory::Instance()->Unregister(modelComponentId); - components::Factory::Instance()->Unregister(sensorComponentId); + Factory::Instance()->Unregister(worldComponentId); + Factory::Instance()->Unregister(modelComponentId); + Factory::Instance()->Unregister(sensorComponentId); #endif } @@ -1429,13 +1429,13 @@ TEST_P(SimulationRunnerTest, // The user may have modified their local config. auto config = common::joinPaths(PROJECT_SOURCE_PATH, "include", "ignition", "gazebo", "server.config"); - ASSERT_TRUE(common::setenv(gazebo::kServerConfigPathEnv, config)); + ASSERT_TRUE(common::setenv(kServerConfigPathEnv, config)); // Create simulation runner auto systemLoader = std::make_shared(); SimulationRunner runner(rootWithout.WorldByIndex(0), systemLoader); ASSERT_EQ(3u, runner.SystemCount()); - common::unsetenv(gazebo::kServerConfigPathEnv); + common::unsetenv(kServerConfigPathEnv); } ///////////////////////////////////////////////// @@ -1455,24 +1455,24 @@ TEST_P(SimulationRunnerTest, // Get model entities auto boxEntity = runner.EntityCompMgr().EntityByComponents( - ignition::gazebo::components::Model(), - ignition::gazebo::components::Name("box")); + Model(), + components::Name("box")); EXPECT_NE(kNullEntity, boxEntity); auto sphereEntity = runner.EntityCompMgr().EntityByComponents( - ignition::gazebo::components::Model(), - ignition::gazebo::components::Name("sphere")); + Model(), + components::Name("sphere")); EXPECT_NE(kNullEntity, sphereEntity); auto cylinderEntity = runner.EntityCompMgr().EntityByComponents( - ignition::gazebo::components::Model(), - ignition::gazebo::components::Name("cylinder")); + Model(), + components::Name("cylinder")); EXPECT_NE(kNullEntity, cylinderEntity); // We can't access the type registered by the plugin unless we link against // it, but we know its name to check std::string componentName{"ModelPluginComponent"}; - auto componentId = ignition::common::hash64(componentName); + auto componentId = common::hash64(componentName); // Check there's no double component EXPECT_FALSE(runner.EntityCompMgr().HasComponentType(componentId)); diff --git a/src/SystemLoader_TEST.cc b/src/SystemLoader_TEST.cc index d1c8b38bd6..8d3882ec35 100644 --- a/src/SystemLoader_TEST.cc +++ b/src/SystemLoader_TEST.cc @@ -35,7 +35,7 @@ TEST(SystemLoader, Constructor) gazebo::SystemLoader sm; // Add test plugin to path (referenced in config) - auto testBuildPath = ignition::common::joinPaths( + auto testBuildPath = common::joinPaths( std::string(PROJECT_BINARY_PATH), "lib"); sm.AddSystemPluginPath(testBuildPath); diff --git a/src/TestFixture.cc b/src/TestFixture.cc index 8f1dffd9f5..e3a9479749 100644 --- a/src/TestFixture.cc +++ b/src/TestFixture.cc @@ -113,7 +113,7 @@ class ignition::gazebo::TestFixturePrivate public: void Init(const ServerConfig &_config); /// \brief Pointer to underlying server - public: std::shared_ptr server{nullptr}; + public: std::shared_ptr server{nullptr}; /// \brief Pointer to underlying Helper interface public: std::shared_ptr helperSystem{nullptr}; @@ -149,7 +149,7 @@ TestFixture::~TestFixture() void TestFixturePrivate::Init(const ServerConfig &_config) { this->helperSystem = std::make_shared(); - this->server = std::make_shared(_config); + this->server = std::make_shared(_config); } ////////////////////////////////////////////////// @@ -208,7 +208,7 @@ TestFixture &TestFixture::OnPostUpdate(std::function TestFixture::Server() const +std::shared_ptr TestFixture::Server() const { return this->dataPtr->server; } diff --git a/src/Util_TEST.cc b/src/Util_TEST.cc index 3a2ec1f081..6555cfcc7f 100644 --- a/src/Util_TEST.cc +++ b/src/Util_TEST.cc @@ -824,7 +824,7 @@ TEST_F(UtilTest, EntityFromMsg) ecm.CreateComponent(actorDEntity, components::ParentEntity(worldEntity)); // Check entities - auto createMsg = [&ecm](Entity _id, const std::string &_name = "", + auto createMsg = [&](Entity _id, const std::string &_name = "", msgs::Entity::Type _type = msgs::Entity::NONE) -> msgs::Entity { msgs::Entity msg; diff --git a/src/World.cc b/src/World.cc index 2d1514f79c..8f8ac5d5b6 100644 --- a/src/World.cc +++ b/src/World.cc @@ -140,7 +140,7 @@ Entity World::LightByName(const EntityComponentManager &_ecm, const std::string &_name) const { // Can't use components::Light in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id), components::Name(_name)); @@ -158,7 +158,7 @@ Entity World::ActorByName(const EntityComponentManager &_ecm, const std::string &_name) const { // Can't use components::Actor in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id), components::Name(_name)); @@ -185,7 +185,7 @@ Entity World::ModelByName(const EntityComponentManager &_ecm, std::vector World::Lights(const EntityComponentManager &_ecm) const { // Can't use components::Light in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id)); @@ -202,7 +202,7 @@ std::vector World::Lights(const EntityComponentManager &_ecm) const std::vector World::Actors(const EntityComponentManager &_ecm) const { // Can't use components::Actor in EntityByComponents, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/376 + // https://github.com/gazebosim/gz-sim/issues/376 auto entities = _ecm.EntitiesByComponents( components::ParentEntity(this->dataPtr->id)); diff --git a/src/cmd/cmdgazebo.rb.in b/src/cmd/cmdgazebo.rb.in index 023843ce1d..abf4aada61 100755 --- a/src/cmd/cmdgazebo.rb.in +++ b/src/cmd/cmdgazebo.rb.in @@ -465,7 +465,7 @@ has properly set the DYLD_LIBRARY_PATH environment variables." if plugin.end_with? ".dylib" puts "`ign gazebo` currently only works with the -s argument on macOS. -See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." +See https://github.com/gazebosim/gz-sim/issues/44 for more info." exit(-1) end @@ -530,7 +530,7 @@ See https://github.com/gazebosim/gz-sim/issues/168 for more info." else options['gui'] if plugin.end_with? ".dylib" puts "`ign gazebo` currently only works with the -s argument on macOS. -See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info." +See https://github.com/gazebosim/gz-sim/issues/44 for more info." exit(-1) end diff --git a/src/gui/AboutDialogHandler.cc b/src/gui/AboutDialogHandler.cc index 545f6fbb66..8e94a48e15 100644 --- a/src/gui/AboutDialogHandler.cc +++ b/src/gui/AboutDialogHandler.cc @@ -28,15 +28,16 @@ using namespace gazebo::gui; ///////////////////////////////////////////////// AboutDialogHandler::AboutDialogHandler() { + aboutText += "Gazebo " + std::string(GZ_DISTRIBUTION) + "
      "; aboutText += std::string(IGNITION_GAZEBO_VERSION_HEADER); aboutText += "" "" "" "" "" @@ -45,9 +46,9 @@ AboutDialogHandler::AboutDialogHandler() "Tutorials:" "" "" "" diff --git a/src/gui/GuiFileHandler.cc b/src/gui/GuiFileHandler.cc index 8572af744a..643ef2dd7b 100644 --- a/src/gui/GuiFileHandler.cc +++ b/src/gui/GuiFileHandler.cc @@ -45,7 +45,7 @@ void GuiFileHandler::SaveWorldAs(const QString &_fileUrl, std::string localPath = url.toLocalFile().toStdString() + suffix; std::string service{"/gazebo/worlds"}; - ignition::msgs::StringMsg_V worldsMsg; + msgs::StringMsg_V worldsMsg; bool result{false}; unsigned int timeout{5000}; diff --git a/src/gui/GuiRunner.cc b/src/gui/GuiRunner.cc index ab8a8d43e9..201b3f606d 100644 --- a/src/gui/GuiRunner.cc +++ b/src/gui/GuiRunner.cc @@ -255,7 +255,7 @@ void GuiRunner::RequestState() } } - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(reqSrv); // Subscribe to periodic updates. diff --git a/src/gui/Gui_TEST.cc b/src/gui/Gui_TEST.cc index 92a98a1dad..8f3d69e42d 100644 --- a/src/gui/Gui_TEST.cc +++ b/src/gui/Gui_TEST.cc @@ -44,17 +44,17 @@ class GuiTest : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -// https://github.com/ignitionrobotics/ign-gazebo/issues/8 +// https://github.com/gazebosim/gz-sim/issues/8 // See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) { common::Console::SetVerbosity(4); igndbg << "Start test" << std::endl; - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + common::setenv("IGN_GAZEBO_RESOURCE_PATH", "/from_env:/tmp/more_env"); - ignition::common::setenv("SDF_PATH", ""); - ignition::common::setenv("IGN_FILE_PATH", ""); + common::setenv("SDF_PATH", ""); + common::setenv("IGN_FILE_PATH", ""); igndbg << "Environment set" << std::endl; transport::Node node; @@ -94,8 +94,8 @@ TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) node.Advertise("/gazebo/resource_paths/get", pathsCb); igndbg << "Paths advertised" << std::endl; - auto app = ignition::gazebo::gui::createGui( - gg_argc, gg_argv, nullptr, nullptr, false, nullptr); + auto app = createGui(gg_argc, gg_argv, nullptr, + nullptr, false, nullptr); EXPECT_NE(nullptr, app); igndbg << "GUI created" << std::endl; diff --git a/src/gui/plugins/align_tool/AlignTool.cc b/src/gui/plugins/align_tool/AlignTool.cc index a2d965ef26..24e0815005 100644 --- a/src/gui/plugins/align_tool/AlignTool.cc +++ b/src/gui/plugins/align_tool/AlignTool.cc @@ -352,14 +352,14 @@ void AlignTool::Align() this->dataPtr->scene = rendering::sceneFromFirstRenderEngine(); // Get current list of selected entities - std::vector selectedList; - ignition::rendering::VisualPtr relativeVisual; + std::vector selectedList; + rendering::VisualPtr relativeVisual; for (const auto &entityId : this->dataPtr->selectedEntities) { for (auto i = 0u; i < this->dataPtr->scene->VisualCount(); ++i) { - ignition::rendering::VisualPtr vis = + rendering::VisualPtr vis = this->dataPtr->scene->VisualByIndex(i); if (!vis) continue; @@ -389,8 +389,8 @@ void AlignTool::Align() (relativeVisual = selectedList.back()); // Callback function for ignition node request - std::function cb = - [](const ignition::msgs::Boolean &/* _rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/* _rep*/, const bool _result) { if (!_result) ignerr << "Error setting pose" << std::endl; @@ -404,7 +404,7 @@ void AlignTool::Align() } int axisIndex = static_cast(this->dataPtr->axis); - ignition::msgs::Pose req; + msgs::Pose req; ignition::math::AxisAlignedBox targetBox = relativeVisual->BoundingBox(); ignition::math::Vector3d targetMin = targetBox.Min(); @@ -566,7 +566,7 @@ bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::EntitiesSelected::kType) + gui::events::EntitiesSelected::kType) { auto selectedEvent = reinterpret_cast( @@ -589,7 +589,7 @@ bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gui::events::DeselectAllEntities::kType) { this->dataPtr->selectedEntities.clear(); } @@ -597,5 +597,5 @@ bool AlignTool::eventFilter(QObject *_obj, QEvent *_event) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::AlignTool, +IGNITION_ADD_PLUGIN(AlignTool, ignition::gui::Plugin) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 0c9fe29d50..ad83a21d68 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -154,7 +154,7 @@ using namespace gazebo; ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) +void gazebo::setData(QStandardItem *_item, const msgs::Light &_data) { if (nullptr == _item) return; @@ -234,7 +234,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gazebo::setData(QStandardItem *_item, const math::Vector3d &_data) { if (nullptr == _item) @@ -251,7 +251,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const std::string &_data) +void gazebo::setData(QStandardItem *_item, const std::string &_data) { if (nullptr == _item) return; @@ -264,7 +264,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const std::string &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gazebo::setData(QStandardItem *_item, const std::ostringstream &_data) { if (nullptr == _item) @@ -278,7 +278,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) +void gazebo::setData(QStandardItem *_item, const bool &_data) { if (nullptr == _item) return; @@ -290,7 +290,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const bool &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const int &_data) +void gazebo::setData(QStandardItem *_item, const int &_data) { if (nullptr == _item) return; @@ -302,14 +302,14 @@ void ignition::gazebo::setData(QStandardItem *_item, const int &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const Entity &_data) +void gazebo::setData(QStandardItem *_item, const Entity &_data) { setData(_item, static_cast(_data)); } ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const double &_data) +void gazebo::setData(QStandardItem *_item, const double &_data) { if (nullptr == _item) return; @@ -321,7 +321,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const double &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) +void gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) { if (nullptr == _item) return; @@ -336,7 +336,7 @@ void ignition::gazebo::setData(QStandardItem *_item, const sdf::Physics &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gazebo::setData(QStandardItem *_item, const sdf::Material &_data) { if (nullptr == _item) @@ -369,7 +369,7 @@ void ignition::gazebo::setData(QStandardItem *_item, ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, +void gazebo::setData(QStandardItem *_item, const math::SphericalCoordinates &_data) { if (nullptr == _item) @@ -388,7 +388,7 @@ void ignition::gazebo::setData(QStandardItem *_item, } ////////////////////////////////////////////////// -void ignition::gazebo::setUnit(QStandardItem *_item, const std::string &_unit) +void gazebo::setUnit(QStandardItem *_item, const std::string &_unit) { if (nullptr == _item) return; @@ -417,7 +417,7 @@ ComponentsModel::ComponentsModel() : QStandardItemModel() ///////////////////////////////////////////////// QStandardItem *ComponentsModel::AddComponentType( - ignition::gazebo::ComponentTypeId _typeId) + ComponentTypeId _typeId) { IGN_PROFILE_THREAD_NAME("Qt thread"); IGN_PROFILE("ComponentsModel::AddComponentType"); @@ -448,7 +448,7 @@ QStandardItem *ComponentsModel::AddComponentType( ///////////////////////////////////////////////// void ComponentsModel::RemoveComponentType( - ignition::gazebo::ComponentTypeId _typeId) + ComponentTypeId _typeId) { IGN_PROFILE_THREAD_NAME("Qt thread"); IGN_PROFILE("ComponentsModel::RemoveComponentType"); @@ -485,7 +485,7 @@ QHash ComponentsModel::RoleNames() ComponentInspector::ComponentInspector() : GuiSystem(), dataPtr(std::make_unique()) { - qRegisterMetaType(); + qRegisterMetaType(); qRegisterMetaType("Entity"); } @@ -961,7 +961,7 @@ bool ComponentInspector::eventFilter(QObject *_obj, QEvent *_event) { if (!this->dataPtr->locked) { - if (_event->type() == gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == gui::events::EntitiesSelected::kType) { auto event = reinterpret_cast(_event); if (event && !event->Data().empty()) @@ -970,7 +970,7 @@ bool ComponentInspector::eventFilter(QObject *_obj, QEvent *_event) } } - if (_event->type() == gazebo::gui::events::DeselectAllEntities::kType) + if (_event->type() == gui::events::DeselectAllEntities::kType) { auto event = reinterpret_cast( _event); @@ -1127,14 +1127,14 @@ void ComponentInspector::OnLight( ///////////////////////////////////////////////// void ComponentInspector::OnPhysics(double _stepSize, double _realTimeFactor) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error setting physics parameters" << std::endl; }; - ignition::msgs::Physics req; + msgs::Physics req; req.set_max_step_size(_stepSize); req.set_real_time_factor(_realTimeFactor); auto physicsCmdService = "/world/" + this->dataPtr->worldName @@ -1344,5 +1344,5 @@ void ComponentInspector::OnAddSystem(const QString &_name, } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::ComponentInspector, +IGNITION_ADD_PLUGIN(ComponentInspector, ignition::gui::Plugin) diff --git a/src/gui/plugins/entity_tree/EntityTree.cc b/src/gui/plugins/entity_tree/EntityTree.cc index 38a80a9557..99fa75fcae 100644 --- a/src/gui/plugins/entity_tree/EntityTree.cc +++ b/src/gui/plugins/entity_tree/EntityTree.cc @@ -526,7 +526,7 @@ void EntityTree::OnLoadMesh(const QString &_mesh) ///////////////////////////////////////////////// bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gazebo::gui::events::EntitiesSelected::kType) + if (_event->type() == gui::events::EntitiesSelected::kType) { auto selectedEvent = reinterpret_cast(_event); @@ -544,7 +544,7 @@ bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gui::events::DeselectAllEntities::kType) { auto deselectAllEvent = reinterpret_cast(_event); @@ -577,5 +577,5 @@ bool EntityTree::eventFilter(QObject *_obj, QEvent *_event) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::EntityTree, +IGNITION_ADD_PLUGIN(EntityTree, ignition::gui::Plugin) diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.cc b/src/gui/plugins/joint_position_controller/JointPositionController.cc index c800f14aff..b233383f1f 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController.cc @@ -291,7 +291,7 @@ void JointPositionController::Update(const UpdateInfo &, QMetaObject::invokeMethod(&this->dataPtr->jointsModel, "RemoveJoint", Qt::QueuedConnection, - Q_ARG(Entity, jointEntity)); + Q_ARG(ignition::gazebo::Entity, jointEntity)); } } } @@ -374,7 +374,7 @@ void JointPositionController::OnCommand(const QString &_jointName, double _pos) { std::string jointName = _jointName.toStdString(); - ignition::msgs::Double msg; + msgs::Double msg; msg.set_data(_pos); auto topic = transport::TopicUtils::AsValidTopic("/model/" + this->dataPtr->modelName.toStdString() + "/joint/" + jointName + @@ -387,7 +387,7 @@ void JointPositionController::OnCommand(const QString &_jointName, double _pos) return; } - auto pub = this->dataPtr->node.Advertise(topic); + auto pub = this->dataPtr->node.Advertise(topic); pub.Publish(msg); } @@ -404,7 +404,7 @@ void JointPositionController::OnReset() continue; } - ignition::msgs::Double msg; + msgs::Double msg; msg.set_data(0); auto topic = transport::TopicUtils::AsValidTopic("/model/" + this->dataPtr->modelName.toStdString() + "/joint/" + jointName + @@ -417,11 +417,11 @@ void JointPositionController::OnReset() return; } - auto pub = this->dataPtr->node.Advertise(topic); + auto pub = this->dataPtr->node.Advertise(topic); pub.Publish(msg); } } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::gui::JointPositionController, +IGNITION_ADD_PLUGIN(JointPositionController, ignition::gui::Plugin) diff --git a/src/gui/plugins/modules/EntityContextMenu.cc b/src/gui/plugins/modules/EntityContextMenu.cc index d2282c4dc0..83141a634b 100644 --- a/src/gui/plugins/modules/EntityContextMenu.cc +++ b/src/gui/plugins/modules/EntityContextMenu.cc @@ -86,7 +86,7 @@ using namespace gazebo; void IgnGazeboPlugin::registerTypes(const char *_uri) { // Register our 'EntityContextMenuItem' in qml engine - qmlRegisterType(_uri, 1, 0, + qmlRegisterType(_uri, 1, 0, "EntityContextMenuItem"); } @@ -163,14 +163,14 @@ void EntityContextMenu::OnRemove( "/world/" + this->dataPtr->worldName + "/remove"; } - std::function cb = - [](const ignition::msgs::Boolean &_rep, const bool _result) + std::function cb = + [](const msgs::Boolean &_rep, const bool _result) { if (!_result || !_rep.data()) ignerr << "Error sending remove request" << std::endl; }; - ignition::msgs::Entity req; + msgs::Entity req; req.set_name(_data.toStdString()); req.set_type(convert(_type.toStdString())); @@ -180,8 +180,8 @@ void EntityContextMenu::OnRemove( ///////////////////////////////////////////////// void EntityContextMenu::OnRequest(const QString &_request, const QString &_data) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending move to request" << std::endl; @@ -190,13 +190,13 @@ void EntityContextMenu::OnRequest(const QString &_request, const QString &_data) std::string request = _request.toStdString(); if (request == "move_to") { - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->moveToService, req, cb); } else if (request == "follow") { - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->followService, req, cb); } @@ -232,7 +232,7 @@ void EntityContextMenu::OnRequest(const QString &_request, const QString &_data) } else if (request == "view_collisions") { - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(_data.toStdString()); this->dataPtr->node.Request(this->dataPtr->viewCollisionsService, req, cb); } diff --git a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc index 2935caaf1c..94f852a452 100644 --- a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc +++ b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc @@ -251,5 +251,5 @@ void PlaybackScrubber::OnDrop(double _value) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::PlaybackScrubber, +IGNITION_ADD_PLUGIN(PlaybackScrubber, ignition::gui::Plugin) diff --git a/src/gui/plugins/plot_3d/Plot3D.cc b/src/gui/plugins/plot_3d/Plot3D.cc index 45565bbc75..b2e2657a3c 100644 --- a/src/gui/plugins/plot_3d/Plot3D.cc +++ b/src/gui/plugins/plot_3d/Plot3D.cc @@ -165,7 +165,7 @@ void Plot3D::ClearPlot() // Clear previous plot if (this->dataPtr->markerMsg.point().size() > 0) { - this->dataPtr->markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); + this->dataPtr->markerMsg.set_action(msgs::Marker::DELETE_MARKER); this->dataPtr->node.Request("/marker", this->dataPtr->markerMsg); } } @@ -245,7 +245,7 @@ void Plot3D::Update(const UpdateInfo &, EntityComponentManager &_ecm) return; this->dataPtr->prevPos = point; - ignition::msgs::Set(this->dataPtr->markerMsg.add_point(), point); + msgs::Set(this->dataPtr->markerMsg.add_point(), point); // Reduce message array if (this->dataPtr->markerMsg.point_size() > this->dataPtr->maxPoints) @@ -401,5 +401,5 @@ void Plot3D::SetMaxPoints(int _maxPoints) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::gui::Plot3D, +IGNITION_ADD_PLUGIN(Plot3D, ignition::gui::Plugin) diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.cc b/src/gui/plugins/resource_spawner/ResourceSpawner.cc index 9320e88be4..73450c73ef 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.cc +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.cc @@ -217,7 +217,7 @@ ResourceSpawner::ResourceSpawner() ignition::gui::App()->Engine()->rootContext()->setContextProperty( "OwnerList", &this->dataPtr->ownerModel); this->dataPtr->fuelClient = - std::make_unique(); + std::make_unique(); } ///////////////////////////////////////////////// @@ -482,7 +482,7 @@ void ResourceSpawner::OnDownloadFuelResource(const QString &_path, // Set the waiting cursor while the resource downloads QGuiApplication::setOverrideCursor(Qt::WaitCursor); if (this->dataPtr->fuelClient->DownloadModel( - ignition::common::URI(_path.toStdString()), localPath)) + common::URI(_path.toStdString()), localPath)) { // Successful download, set thumbnail std::string thumbnailPath = common::joinPaths(localPath, "thumbnails"); @@ -564,7 +564,7 @@ void ResourceSpawner::LoadConfig(const tinyxml2::XMLElement *) std::set ownerSet; for (auto const &server : servers) { - std::vector models; + std::vector models; for (auto iter = this->dataPtr->fuelClient->Models(server); iter; ++iter) { models.push_back(iter->Identification()); @@ -584,10 +584,10 @@ void ResourceSpawner::LoadConfig(const tinyxml2::XMLElement *) // If the resource is cached, we can go ahead and populate the // respective information if (this->dataPtr->fuelClient->CachedModel( - ignition::common::URI(id.UniqueName()), path)) + common::URI(id.UniqueName()), path)) { resource.isDownloaded = true; - resource.sdfPath = ignition::common::joinPaths(path, "model.sdf"); + resource.sdfPath = common::joinPaths(path, "model.sdf"); std::string thumbnailPath = common::joinPaths(path, "thumbnails"); this->SetThumbnail(thumbnailPath, resource); } @@ -633,5 +633,5 @@ void ResourceSpawner::OnResourceSpawn(const QString &_sdfPath) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::ResourceSpawner, +IGNITION_ADD_PLUGIN(ResourceSpawner, ignition::gui::Plugin) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index b5097c15fb..7f91596a8c 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -794,7 +794,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) std::chrono::steady_clock::duration dt; dt = t - this->dataPtr->recordStartTime; int64_t sec, nsec; - std::tie(sec, nsec) = ignition::math::durationToSecNsec(dt); + std::tie(sec, nsec) = math::durationToSecNsec(dt); msgs::Time msg; msg.set_sec(sec); msg.set_nsec(nsec); @@ -1259,7 +1259,7 @@ bool IgnRenderer::GeneratePreview(const sdf::Root &_sdf) // Only preview first model sdf::Light light = *(_sdf.Light()); this->dataPtr->spawnPreviewPose = light.RawPose(); - light.SetName(ignition::common::Uuid().String()); + light.SetName(common::Uuid().String()); Entity lightVisualId = this->UniqueId(); if (!lightVisualId) { @@ -1550,8 +1550,8 @@ void IgnRenderer::HandleModelPlacement() this->TerminateSpawnPreview(); math::Pose3d modelPose = this->dataPtr->spawnPreviewPose; - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error creating model" << std::endl; @@ -1665,7 +1665,7 @@ double IgnRenderer::SnapValue( ///////////////////////////////////////////////// void IgnRenderer::SnapPoint( - ignition::math::Vector3d &_point, math::Vector3d &_snapVals, + math::Vector3d &_point, math::Vector3d &_snapVals, double _sensitivity) const { if (_snapVals.X() <= 0 || _snapVals.Y() <= 0 || _snapVals.Z() <= 0) @@ -1772,7 +1772,7 @@ void IgnRenderer::HandleMouseTransformControl() // check if the visual is an axis in the gizmo visual math::Vector3d axis = this->dataPtr->transformControl.AxisById(visual->Id()); - if (axis != ignition::math::Vector3d::Zero) + if (axis != math::Vector3d::Zero) { // start the transform process this->dataPtr->transformControl.SetActiveAxis(axis); @@ -1790,14 +1790,14 @@ void IgnRenderer::HandleMouseTransformControl() { if (this->dataPtr->transformControl.Node()) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error setting pose" << std::endl; }; rendering::NodePtr node = this->dataPtr->transformControl.Node(); - ignition::msgs::Pose req; + msgs::Pose req; req.set_name(node->Name()); msgs::Set(req.mutable_position(), node->WorldPosition()); msgs::Set(req.mutable_orientation(), node->WorldRotation()); @@ -1840,7 +1840,7 @@ void IgnRenderer::HandleMouseTransformControl() // check if the visual is an axis in the gizmo visual math::Vector3d axis = this->dataPtr->transformControl.AxisById(visual->Id()); - if (axis == ignition::math::Vector3d::Zero) + if (axis == math::Vector3d::Zero) { auto topVis = this->dataPtr->renderUtil.SceneManager().TopLevelVisual(visual); @@ -1908,7 +1908,7 @@ void IgnRenderer::HandleMouseTransformControl() this->dataPtr->startWorldPos = target->WorldPosition(); } - ignition::math::Vector3d worldPos = + math::Vector3d worldPos = target->WorldPosition(); math::Vector3d distance = this->dataPtr->transformControl.TranslationFrom2d(axis, start, end); @@ -2060,7 +2060,7 @@ void IgnRenderer::HandleMouseViewControl() // unset the target on release (by setting to inf) else if (this->dataPtr->mouseEvent.Type() == common::MouseEvent::RELEASE) { - this->dataPtr->target = ignition::math::INF_D; + this->dataPtr->target = math::INF_D; } // Pan with left button @@ -2532,7 +2532,7 @@ math::Vector3d IgnRenderer::ScreenToPlane( this->dataPtr->rayQuery->SetFromCamera( this->dataPtr->camera, math::Vector2d(nx, ny)); - ignition::math::Planed plane(ignition::math::Vector3d(0, 0, 1), 0); + math::Planed plane(math::Vector3d(0, 0, 1), 0); math::Vector3d origin = this->dataPtr->rayQuery->Origin(); math::Vector3d direction = this->dataPtr->rayQuery->Direction(); @@ -2716,7 +2716,7 @@ void TextureNode::PrepareNode() newId, sz, QQuickWindow::TextureIsOpaque); #else // TODO(anyone) Use createTextureFromNativeObject - // https://github.com/ignitionrobotics/ign-gui/issues/113 + // https://github.com/gazebosim/gz-gui/issues/113 #ifndef _WIN32 # pragma GCC diagnostic push # pragma GCC diagnostic ignored "-Wdeprecated-declarations" @@ -3536,8 +3536,8 @@ void Scene3D::OnDropped(const QString &_drop, int _mouseX, int _mouseY) return; } - std::function cb = - [](const ignition::msgs::Boolean &_res, const bool _result) + std::function cb = + [](const msgs::Boolean &_res, const bool _result) { if (!_result || !_res.data()) ignerr << "Error creating dropped entity." << std::endl; @@ -3679,7 +3679,7 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::EntitiesSelected::kType) + gui::events::EntitiesSelected::kType) { auto selectedEvent = reinterpret_cast( @@ -3713,7 +3713,7 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::DeselectAllEntities::kType) + gui::events::DeselectAllEntities::kType) { auto deselectEvent = reinterpret_cast( @@ -3967,7 +3967,7 @@ void RenderWindowItem::SetVisibilityMask(uint32_t _mask) } ///////////////////////////////////////////////// -void RenderWindowItem::OnHovered(const ignition::math::Vector2i &_hoverPos) +void RenderWindowItem::OnHovered(const math::Vector2i &_hoverPos) { this->dataPtr->renderThread->ignRenderer.NewHoverEvent(_hoverPos); } @@ -4086,5 +4086,5 @@ void RenderWindowItem::HandleKeyRelease(QKeyEvent *_e) // // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::Scene3D, +IGNITION_ADD_PLUGIN(gazebo::Scene3D, ignition::gui::Plugin) diff --git a/src/gui/plugins/shapes/Shapes.cc b/src/gui/plugins/shapes/Shapes.cc index 2cd0108237..3e5ca46c7a 100644 --- a/src/gui/plugins/shapes/Shapes.cc +++ b/src/gui/plugins/shapes/Shapes.cc @@ -81,5 +81,5 @@ void Shapes::OnMode(const QString &_mode) } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::Shapes, +IGNITION_ADD_PLUGIN(Shapes, ignition::gui::Plugin) diff --git a/src/gui/plugins/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc index 54215f8304..b2cb21bbc4 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -258,14 +258,14 @@ void TransformControl::OnMode(const QString &_mode) // Legacy behaviour: send request to GzScene3D if (this->dataPtr->legacy) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error setting transform mode" << std::endl; }; - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(modeStr); this->dataPtr->node.Request(this->dataPtr->service, req, cb); } @@ -284,7 +284,7 @@ void TransformControl::OnMode(const QString &_mode) else ignerr << "Unknown transform mode: [" << modeStr << "]" << std::endl; - ignition::gazebo::gui::events::TransformControlModeActive + gazebo::gui::events::TransformControlModeActive transformControlModeActive(this->dataPtr->transformMode); ignition::gui::App()->sendEvent( ignition::gui::App()->findChild(), @@ -1017,5 +1017,5 @@ void TransformControlPrivate::SnapPoint( } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::TransformControl, +IGNITION_ADD_PLUGIN(TransformControl, ignition::gui::Plugin) diff --git a/src/gui/plugins/video_recorder/VideoRecorder.cc b/src/gui/plugins/video_recorder/VideoRecorder.cc index 1eb9b3e69a..0e88285286 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.cc +++ b/src/gui/plugins/video_recorder/VideoRecorder.cc @@ -367,7 +367,7 @@ void VideoRecorder::LoadConfig(const tinyxml2::XMLElement * _pluginElem) ///////////////////////////////////////////////// bool VideoRecorder::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gui::events::Render::kType) + if (_event->type() == gui::events::Render::kType) { this->dataPtr->OnRender(); } @@ -386,13 +386,13 @@ void VideoRecorder::OnStart(const QString &_format) if (this->dataPtr->legacy) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending video record start request" << std::endl; }; - ignition::msgs::VideoRecord req; + msgs::VideoRecord req; req.set_start(this->dataPtr->recordVideo); req.set_format(this->dataPtr->format); req.set_save_filename(this->dataPtr->filename); @@ -408,14 +408,14 @@ void VideoRecorder::OnStop() if (this->dataPtr->legacy) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending video record stop request" << std::endl; }; - ignition::msgs::VideoRecord req; + msgs::VideoRecord req; req.set_stop(true); this->dataPtr->node.Request(this->dataPtr->service, req, cb); } @@ -462,5 +462,5 @@ void VideoRecorder::OnCancel() } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::VideoRecorder, +IGNITION_ADD_PLUGIN(VideoRecorder, ignition::gui::Plugin) diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index 8f3b34f431..0e9fa5797d 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -463,5 +463,5 @@ bool ViewAnglePrivate::UpdateQtCamClipDist() } // Register this plugin -IGNITION_ADD_PLUGIN(ignition::gazebo::ViewAngle, +IGNITION_ADD_PLUGIN(ViewAngle, ignition::gui::Plugin) diff --git a/src/ign.cc b/src/ign.cc index 76344cf872..c846aacece 100644 --- a/src/ign.cc +++ b/src/ign.cc @@ -56,7 +56,7 @@ extern "C" void cmdVerbosity( const char *_verbosity) { int verbosity = std::atoi(_verbosity); - ignition::common::Console::SetVerbosity(verbosity); + common::Console::SetVerbosity(verbosity); // SDFormat only has 2 levels: quiet / loud. Let sim users suppress all SDF // console output with zero verbosity. @@ -78,17 +78,17 @@ extern "C" const char *findFuelResource( { std::string path; std::string worldPath; - ignition::fuel_tools::FuelClient fuelClient; + fuel_tools::FuelClient fuelClient; // Attempt to find cached copy, and then attempt download - if (fuelClient.CachedWorld(ignition::common::URI(_pathToResource), path)) + if (fuelClient.CachedWorld(common::URI(_pathToResource), path)) { ignmsg << "Cached world found." << std::endl; worldPath = path; } // cppcheck-suppress syntaxError - else if (ignition::fuel_tools::Result result = - fuelClient.DownloadWorld(ignition::common::URI(_pathToResource), path); + else if (fuel_tools::Result result = + fuelClient.DownloadWorld(common::URI(_pathToResource), path); result) { ignmsg << "Successfully downloaded world from fuel." << std::endl; @@ -101,20 +101,20 @@ extern "C" const char *findFuelResource( return ""; } - if (!ignition::common::exists(worldPath)) + if (!common::exists(worldPath)) return ""; // Find the first sdf file in the world path for now, the later intention is // to load an optional world config file first and if that does not exist, // continue to load the first sdf file found as done below - for (ignition::common::DirIter file(worldPath); - file != ignition::common::DirIter(); ++file) + for (common::DirIter file(worldPath); + file != common::DirIter(); ++file) { std::string current(*file); - if (ignition::common::isFile(current)) + if (common::isFile(current)) { - std::string fileName = ignition::common::basename(current); + std::string fileName = common::basename(current); std::string::size_type fileExtensionIndex = fileName.rfind("."); std::string fileExtension = fileName.substr(fileExtensionIndex + 1); @@ -138,7 +138,7 @@ extern "C" int runServer(const char *_sdfString, int _headless, float _recordPeriod) { std::string startingWorldPath{""}; - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; // Lock until the starting world is received from Gui if (_waitGui == 1) @@ -173,7 +173,7 @@ extern "C" int runServer(const char *_sdfString, // Path for compressed log, used to check for duplicates std::string cmpPath = std::string(recordPathMod); - if (!std::string(1, cmpPath.back()).compare(ignition::common::separator(""))) + if (!std::string(1, cmpPath.back()).compare(common::separator(""))) { // Remove the separator at end of path cmpPath = cmpPath.substr(0, cmpPath.length() - 1); @@ -207,7 +207,7 @@ extern "C" int runServer(const char *_sdfString, // Update compressed file path to name of recording directory path cmpPath = std::string(recordPathMod); - if (!std::string(1, cmpPath.back()).compare(ignition::common::separator( + if (!std::string(1, cmpPath.back()).compare(common::separator( ""))) { // Remove the separator at end of path @@ -216,8 +216,8 @@ extern "C" int runServer(const char *_sdfString, cmpPath += ".zip"; // Check if path or compressed file with same prefix exists - if (ignition::common::exists(recordPathMod) || - ignition::common::exists(cmpPath)) + if (common::exists(recordPathMod) || + common::exists(cmpPath)) { // Overwrite if flag specified if (_logOverwrite > 0) @@ -225,15 +225,15 @@ extern "C" int runServer(const char *_sdfString, bool recordMsg = false; bool cmpMsg = false; // Remove files before initializing console log files on top of them - if (ignition::common::exists(recordPathMod)) + if (common::exists(recordPathMod)) { recordMsg = true; - ignition::common::removeAll(recordPathMod); + common::removeAll(recordPathMod); } - if (ignition::common::exists(cmpPath)) + if (common::exists(cmpPath)) { cmpMsg = true; - ignition::common::removeFile(cmpPath); + common::removeFile(cmpPath); } // Create log file before printing any messages so they can be logged @@ -260,7 +260,7 @@ extern "C" int runServer(const char *_sdfString, { // Remove the separator at end of path if (!std::string(1, recordPathMod.back()).compare( - ignition::common::separator(""))) + common::separator(""))) { recordPathMod = recordPathMod.substr(0, recordPathMod.length() - 1); @@ -271,8 +271,8 @@ extern "C" int runServer(const char *_sdfString, // Keep renaming until path does not exist for both directory and // compressed file - while (ignition::common::exists(recordPathMod) || - ignition::common::exists(cmpPath)) + while (common::exists(recordPathMod) || + common::exists(cmpPath)) { recordPathMod = recordOrigPrefix + "(" + std::to_string(count++) + ")"; @@ -280,7 +280,7 @@ extern "C" int runServer(const char *_sdfString, cmpPath = std::string(recordPathMod); // Remove the separator at end of path if (!std::string(1, cmpPath.back()).compare( - ignition::common::separator(""))) + common::separator(""))) { cmpPath = cmpPath.substr(0, cmpPath.length() - 1); } @@ -312,7 +312,7 @@ extern "C" int runServer(const char *_sdfString, } serverConfig.SetLogRecordPath(recordPathMod); - std::vector topics = ignition::common::split( + std::vector topics = common::split( _recordTopics, ":"); for (const std::string &topic : topics) { @@ -379,7 +379,7 @@ extern "C" int runServer(const char *_sdfString, else { ignmsg << "Playing back states" << _playback << std::endl; - serverConfig.SetLogPlaybackPath(ignition::common::absPath( + serverConfig.SetLogPlaybackPath(common::absPath( std::string(_playback))); } } @@ -402,7 +402,7 @@ extern "C" int runServer(const char *_sdfString, } // Create the Gazebo server - ignition::gazebo::Server server(serverConfig); + gazebo::Server server(serverConfig); // Run the server server.Run(true, _iterations, _run == 0); @@ -426,6 +426,6 @@ extern "C" int runGui(const char *_guiConfig, const char *_file, int _waitGui, // be converted to a const char *. The const cast is here to prevent a warning // since we do need to pass a char* to runGui char *argv = const_cast("ign-gazebo-gui"); - return ignition::gazebo::gui::runGui( + return gazebo::gui::runGui( argc, &argv, _guiConfig, _file, _waitGui, _renderEngine); } diff --git a/src/ign.hh b/src/ign.hh index 18eac3cfc5..58fa40dfed 100644 --- a/src/ign.hh +++ b/src/ign.hh @@ -82,7 +82,7 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runGui(const char *_guiConfig, /// \brief External hook to find or download a fuel world provided a URL. /// \param[in] _pathToResource Path to the fuel world resource, ie, -/// https://staging-fuel.ignitionrobotics.org/1.0/gmas/worlds/ShapesClone +/// https://staging-fuel.gazebosim.org/1.0/gmas/worlds/ShapesClone /// \return C-string containing the path to the local world sdf file extern "C" IGNITION_GAZEBO_VISIBLE const char *findFuelResource( char *_pathToResource); diff --git a/src/ign_TEST.cc b/src/ign_TEST.cc index 397441bed4..29fb643dba 100644 --- a/src/ign_TEST.cc +++ b/src/ign_TEST.cc @@ -21,9 +21,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) @@ -37,6 +37,11 @@ static const std::string kIgnModelCommand( ///////////////////////////////////////////////// std::string customExecStr(std::string _cmd) { + // Augment the system plugin path. + ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + ignition::common::joinPaths( + std::string(PROJECT_BINARY_PATH), "lib").c_str()); + _cmd += " 2>&1"; FILE *pipe = popen(_cmd.c_str(), "r"); @@ -100,7 +105,7 @@ TEST(CmdLine, CachedFuelWorld) std::string projectPath = std::string(PROJECT_SOURCE_PATH) + "/test/worlds"; ignition::common::setenv("IGN_FUEL_CACHE_PATH", projectPath.c_str()); std::string cmd = kIgnCommand + " -r -v 4 --iterations 5" + - " https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world"; + " https://fuel.gazebosim.org/1.0/OpenRobotics/worlds/Test%20world"; std::cout << "Running command [" << cmd << "]" << std::endl; std::string output = customExecStr(cmd); diff --git a/src/network/NetworkManagerPrimary.cc b/src/network/NetworkManagerPrimary.cc index e9759eb735..f8e51562ce 100644 --- a/src/network/NetworkManagerPrimary.cc +++ b/src/network/NetworkManagerPrimary.cc @@ -212,7 +212,7 @@ bool NetworkManagerPrimary::SecondariesCanStep() const // TODO(anyone) Ideally we'd check the number of connections against the // number of expected secondaries, but there's no interface for that // on ign-transport yet: - // https://github.com/ignitionrobotics/ign-transport/issues/39 + // https://github.com/gazebosim/gz-transport/issues/39 return this->simStepPub.HasConnections(); } diff --git a/src/network/PeerInfo.cc b/src/network/PeerInfo.cc index e749caff66..b345fde017 100644 --- a/src/network/PeerInfo.cc +++ b/src/network/PeerInfo.cc @@ -24,8 +24,8 @@ using namespace gazebo; ///////////////////////////////////////////////// PeerInfo::PeerInfo(const NetworkRole &_role): - id(ignition::common::Uuid().String()), - hostname(ignition::transport::hostname()), + id(common::Uuid().String()), + hostname(transport::hostname()), role(_role) { } @@ -42,36 +42,36 @@ std::string PeerInfo::Namespace() const } ///////////////////////////////////////////////// -ignition::gazebo::private_msgs::PeerInfo ignition::gazebo::toProto( +private_msgs::PeerInfo gazebo::toProto( const PeerInfo &_info) { - ignition::gazebo::private_msgs::PeerInfo proto; + private_msgs::PeerInfo proto; proto.set_id(_info.id); proto.set_hostname(_info.hostname); switch (_info.role) { case NetworkRole::ReadOnly: - proto.set_role(ignition::gazebo::private_msgs::PeerInfo::READ_ONLY); + proto.set_role(private_msgs::PeerInfo::READ_ONLY); break; case NetworkRole::SimulationPrimary: proto.set_role( - ignition::gazebo::private_msgs::PeerInfo::SIMULATION_PRIMARY); + private_msgs::PeerInfo::SIMULATION_PRIMARY); break; case NetworkRole::SimulationSecondary: proto.set_role( - ignition::gazebo::private_msgs::PeerInfo::SIMULATION_SECONDARY); + private_msgs::PeerInfo::SIMULATION_SECONDARY); break; case NetworkRole::None: default: - proto.set_role(ignition::gazebo::private_msgs::PeerInfo::NONE); + proto.set_role(private_msgs::PeerInfo::NONE); } return proto; } ///////////////////////////////////////////////// -PeerInfo ignition::gazebo::fromProto( - const ignition::gazebo::private_msgs::PeerInfo& _proto) +PeerInfo gazebo::fromProto( + const private_msgs::PeerInfo& _proto) { PeerInfo info; info.id = _proto.id(); @@ -79,16 +79,16 @@ PeerInfo ignition::gazebo::fromProto( switch (_proto.role()) { - case ignition::gazebo::private_msgs::PeerInfo::READ_ONLY: + case private_msgs::PeerInfo::READ_ONLY: info.role = NetworkRole::ReadOnly; break; - case ignition::gazebo::private_msgs::PeerInfo::SIMULATION_PRIMARY: + case private_msgs::PeerInfo::SIMULATION_PRIMARY: info.role = NetworkRole::SimulationPrimary; break; - case ignition::gazebo::private_msgs::PeerInfo::SIMULATION_SECONDARY: + case private_msgs::PeerInfo::SIMULATION_SECONDARY: info.role = NetworkRole::SimulationSecondary; break; - case ignition::gazebo::private_msgs::PeerInfo::NONE: + case private_msgs::PeerInfo::NONE: default: info.role = NetworkRole::None; break; diff --git a/src/network/PeerTracker.cc b/src/network/PeerTracker.cc index f4271fac98..e10a785e84 100644 --- a/src/network/PeerTracker.cc +++ b/src/network/PeerTracker.cc @@ -26,7 +26,7 @@ using namespace gazebo; PeerTracker::PeerTracker( PeerInfo _info, EventManager *_eventMgr, - const ignition::transport::NodeOptions &_options): + const transport::NodeOptions &_options): info(std::move(_info)), eventMgr(_eventMgr), node(_options) diff --git a/src/rendering/MarkerManager.cc b/src/rendering/MarkerManager.cc index 736815b45b..6ecf8af556 100644 --- a/src/rendering/MarkerManager.cc +++ b/src/rendering/MarkerManager.cc @@ -42,50 +42,50 @@ class ignition::gazebo::MarkerManagerPrivate /// \brief Processes a marker message. /// \param[in] _msg The message data. /// \return True if the marker was processed successfully. - public: bool ProcessMarkerMsg(const ignition::msgs::Marker &_msg); + public: bool ProcessMarkerMsg(const msgs::Marker &_msg); /// \brief Converts an ignition msg render type to ignition rendering /// \param[in] _msg The message data /// \return Converted rendering type, if any. - public: ignition::rendering::MarkerType MsgToType( - const ignition::msgs::Marker &_msg); + public: rendering::MarkerType MsgToType( + const msgs::Marker &_msg); /// \brief Converts an ignition msg material to ignition rendering // material. // \param[in] _msg The message data. // \return Converted rendering material, if any. public: rendering::MaterialPtr MsgToMaterial( - const ignition::msgs::Marker &_msg); + const msgs::Marker &_msg); /// \brief Updates the markers. public: void Update(); /// \brief Callback that receives marker messages. /// \param[in] _req The marker message. - public: void OnMarkerMsg(const ignition::msgs::Marker &_req); + public: void OnMarkerMsg(const msgs::Marker &_req); /// \brief Callback that receives multiple marker messages. /// \param[in] _req The vector of marker messages /// \param[in] _res Response data /// \return True if the request is received - public: bool OnMarkerMsgArray(const ignition::msgs::Marker_V &_req, - ignition::msgs::Boolean &_res); + public: bool OnMarkerMsgArray(const msgs::Marker_V &_req, + msgs::Boolean &_res); /// \brief Services callback that returns a list of markers. /// \param[out] _rep Service reply /// \return True on success. - public: bool OnList(ignition::msgs::Marker_V &_rep); + public: bool OnList(msgs::Marker_V &_rep); /// \brief Sets Marker from marker message. /// \param[in] _msg The message data. /// \param[out] _markerPtr The message pointer to set. - public: void SetMarker(const ignition::msgs::Marker &_msg, + public: void SetMarker(const msgs::Marker &_msg, const rendering::MarkerPtr &_markerPtr); /// \brief Sets Visual from marker message. /// \param[in] _msg The message data. /// \param[out] _visualPtr The visual pointer to set. - public: void SetVisual(const ignition::msgs::Marker &_msg, + public: void SetVisual(const msgs::Marker &_msg, const rendering::VisualPtr &_visualPtr); /// \brief Sets sim time from time. @@ -100,22 +100,22 @@ class ignition::gazebo::MarkerManagerPrivate /// \brief Map of visuals public: std::map> visuals; + std::map> visuals; /// \brief List of marker message to process. - public: std::list markerMsgs; + public: std::list markerMsgs; /// \brief Pointer to the scene public: rendering::ScenePtr scene; /// \brief Ignition node - public: ignition::transport::Node node; + public: transport::Node node; /// \brief Sim time according to UpdateInfo in RenderUtil public: std::chrono::steady_clock::duration simTime; /// \brief The last marker message received - public: ignition::msgs::Marker msg; + public: msgs::Marker msg; /// \brief Topic name for the marker service public: std::string topicName = "/marker"; @@ -149,7 +149,7 @@ void MarkerManager::Update() } ///////////////////////////////////////////////// -bool MarkerManager::Init(const ignition::rendering::ScenePtr &_scene) +bool MarkerManager::Init(const rendering::ScenePtr &_scene) { if (!_scene) { @@ -229,8 +229,8 @@ void MarkerManagerPrivate::Update() if (it->second->GeometryCount() == 0u) continue; - ignition::rendering::MarkerPtr markerPtr = - std::dynamic_pointer_cast + rendering::MarkerPtr markerPtr = + std::dynamic_pointer_cast (it->second->GeometryByIndex(0u)); if (markerPtr != nullptr) { @@ -263,7 +263,7 @@ void MarkerManagerPrivate::SetSimTime( } ///////////////////////////////////////////////// -void MarkerManagerPrivate::SetVisual(const ignition::msgs::Marker &_msg, +void MarkerManagerPrivate::SetVisual(const msgs::Marker &_msg, const rendering::VisualPtr &_visualPtr) { // Set Visual Scale @@ -302,7 +302,7 @@ void MarkerManagerPrivate::SetVisual(const ignition::msgs::Marker &_msg, } ///////////////////////////////////////////////// -void MarkerManagerPrivate::SetMarker(const ignition::msgs::Marker &_msg, +void MarkerManagerPrivate::SetMarker(const msgs::Marker &_msg, const rendering::MarkerPtr &_markerPtr) { _markerPtr->SetLayer(_msg.layer()); @@ -319,7 +319,7 @@ void MarkerManagerPrivate::SetMarker(const ignition::msgs::Marker &_msg, _markerPtr->SetLifetime(std::chrono::seconds(0)); } // Set Marker Render Type - ignition::rendering::MarkerType markerType = MsgToType(_msg); + rendering::MarkerType markerType = MsgToType(_msg); _markerPtr->SetType(markerType); // Set Marker Material @@ -357,49 +357,49 @@ void MarkerManagerPrivate::SetMarker(const ignition::msgs::Marker &_msg, } ///////////////////////////////////////////////// -ignition::rendering::MarkerType MarkerManagerPrivate::MsgToType( - const ignition::msgs::Marker &_msg) +rendering::MarkerType MarkerManagerPrivate::MsgToType( + const msgs::Marker &_msg) { - ignition::msgs::Marker_Type marker = this->msg.type(); - if (marker != _msg.type() && _msg.type() != ignition::msgs::Marker::NONE) + msgs::Marker_Type marker = this->msg.type(); + if (marker != _msg.type() && _msg.type() != msgs::Marker::NONE) { marker = _msg.type(); this->msg.set_type(_msg.type()); } switch (marker) { - case ignition::msgs::Marker::BOX: - return ignition::rendering::MarkerType::MT_BOX; - case ignition::msgs::Marker::CAPSULE: - return ignition::rendering::MarkerType::MT_CAPSULE; - case ignition::msgs::Marker::CYLINDER: - return ignition::rendering::MarkerType::MT_CYLINDER; - case ignition::msgs::Marker::LINE_STRIP: - return ignition::rendering::MarkerType::MT_LINE_STRIP; - case ignition::msgs::Marker::LINE_LIST: - return ignition::rendering::MarkerType::MT_LINE_LIST; - case ignition::msgs::Marker::POINTS: - return ignition::rendering::MarkerType::MT_POINTS; - case ignition::msgs::Marker::SPHERE: - return ignition::rendering::MarkerType::MT_SPHERE; - case ignition::msgs::Marker::TEXT: - return ignition::rendering::MarkerType::MT_TEXT; - case ignition::msgs::Marker::TRIANGLE_FAN: - return ignition::rendering::MarkerType::MT_TRIANGLE_FAN; - case ignition::msgs::Marker::TRIANGLE_LIST: - return ignition::rendering::MarkerType::MT_TRIANGLE_LIST; - case ignition::msgs::Marker::TRIANGLE_STRIP: - return ignition::rendering::MarkerType::MT_TRIANGLE_STRIP; + case msgs::Marker::BOX: + return rendering::MarkerType::MT_BOX; + case msgs::Marker::CAPSULE: + return rendering::MarkerType::MT_CAPSULE; + case msgs::Marker::CYLINDER: + return rendering::MarkerType::MT_CYLINDER; + case msgs::Marker::LINE_STRIP: + return rendering::MarkerType::MT_LINE_STRIP; + case msgs::Marker::LINE_LIST: + return rendering::MarkerType::MT_LINE_LIST; + case msgs::Marker::POINTS: + return rendering::MarkerType::MT_POINTS; + case msgs::Marker::SPHERE: + return rendering::MarkerType::MT_SPHERE; + case msgs::Marker::TEXT: + return rendering::MarkerType::MT_TEXT; + case msgs::Marker::TRIANGLE_FAN: + return rendering::MarkerType::MT_TRIANGLE_FAN; + case msgs::Marker::TRIANGLE_LIST: + return rendering::MarkerType::MT_TRIANGLE_LIST; + case msgs::Marker::TRIANGLE_STRIP: + return rendering::MarkerType::MT_TRIANGLE_STRIP; default: ignerr << "Unable to create marker of type[" << _msg.type() << "]\n"; break; } - return ignition::rendering::MarkerType::MT_NONE; + return rendering::MarkerType::MT_NONE; } ///////////////////////////////////////////////// rendering::MaterialPtr MarkerManagerPrivate::MsgToMaterial( - const ignition::msgs::Marker &_msg) + const msgs::Marker &_msg) { rendering::MaterialPtr material = this->scene->CreateMaterial(); @@ -433,7 +433,7 @@ rendering::MaterialPtr MarkerManagerPrivate::MsgToMaterial( } ////////////////////////////////////////////////// -bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) +bool MarkerManagerPrivate::ProcessMarkerMsg(const msgs::Marker &_msg) { // Get the namespace, if it exists. Otherwise, use the global namespace std::string ns; @@ -453,14 +453,14 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) // Otherwise generate unique id else { - id = ignition::math::Rand::IntUniform(0, ignition::math::MAX_I32); + id = math::Rand::IntUniform(0, math::MAX_I32); // Make sure it's unique if namespace is given if (nsIter != this->visuals.end()) { while (nsIter->second.find(id) != nsIter->second.end()) - id = ignition::math::Rand::IntUniform(ignition::math::MIN_UI32, - ignition::math::MAX_UI32); + id = math::Rand::IntUniform(math::MIN_UI32, + math::MAX_UI32); } } @@ -470,7 +470,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) visualIter = nsIter->second.find(id); // Add/modify a marker - if (_msg.action() == ignition::msgs::Marker::ADD_MODIFY) + if (_msg.action() == msgs::Marker::ADD_MODIFY) { // Modify an existing marker, identified by namespace and id if (nsIter != this->visuals.end() && @@ -480,8 +480,8 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) { // TODO(anyone): Update so that multiple markers can // be attached to one visual - ignition::rendering::MarkerPtr markerPtr = - std::dynamic_pointer_cast + rendering::MarkerPtr markerPtr = + std::dynamic_pointer_cast (visualIter->second->GeometryByIndex(0)); visualIter->second->RemoveGeometryByIndex(0); @@ -528,7 +528,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) } } // Remove a single marker - else if (_msg.action() == ignition::msgs::Marker::DELETE_MARKER) + else if (_msg.action() == msgs::Marker::DELETE_MARKER) { // Remove the marker if it can be found. if (nsIter != this->visuals.end() && @@ -549,7 +549,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) } } // Remove all markers, or all markers in a namespace - else if (_msg.action() == ignition::msgs::Marker::DELETE_ALL) + else if (_msg.action() == msgs::Marker::DELETE_ALL) { // If given namespace doesn't exist if (!ns.empty() && nsIter == this->visuals.end()) @@ -593,7 +593,7 @@ bool MarkerManagerPrivate::ProcessMarkerMsg(const ignition::msgs::Marker &_msg) ///////////////////////////////////////////////// -bool MarkerManagerPrivate::OnList(ignition::msgs::Marker_V &_rep) +bool MarkerManagerPrivate::OnList(msgs::Marker_V &_rep) { std::lock_guard lock(this->mutex); _rep.clear_marker(); @@ -603,7 +603,7 @@ bool MarkerManagerPrivate::OnList(ignition::msgs::Marker_V &_rep) { for (auto iter : mIter.second) { - ignition::msgs::Marker *markerMsg = _rep.add_marker(); + msgs::Marker *markerMsg = _rep.add_marker(); markerMsg->set_ns(mIter.first); markerMsg->set_id(iter.first); } @@ -613,7 +613,7 @@ bool MarkerManagerPrivate::OnList(ignition::msgs::Marker_V &_rep) } ///////////////////////////////////////////////// -void MarkerManagerPrivate::OnMarkerMsg(const ignition::msgs::Marker &_req) +void MarkerManagerPrivate::OnMarkerMsg(const msgs::Marker &_req) { std::lock_guard lock(this->mutex); this->markerMsgs.push_back(_req); @@ -621,7 +621,7 @@ void MarkerManagerPrivate::OnMarkerMsg(const ignition::msgs::Marker &_req) ///////////////////////////////////////////////// bool MarkerManagerPrivate::OnMarkerMsgArray( - const ignition::msgs::Marker_V&_req, ignition::msgs::Boolean &_res) + const msgs::Marker_V&_req, msgs::Boolean &_res) { std::lock_guard lock(this->mutex); std::copy(_req.marker().begin(), _req.marker().end(), diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 6f4ef07941..d9d8d8b4a3 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -228,7 +228,7 @@ class ignition::gazebo::RenderUtilPrivate public: MarkerManager markerManager; /// \brief Pointer to rendering engine. - public: ignition::rendering::RenderEngine *engine{nullptr}; + public: rendering::RenderEngine *engine{nullptr}; /// \brief rendering scene to be managed by the scene manager and used to /// generate sensor data @@ -2341,6 +2341,14 @@ void RenderUtilPrivate::RemoveRenderingEntities( const EntityComponentManager &_ecm, const UpdateInfo &_info) { IGN_PROFILE("RenderUtilPrivate::RemoveRenderingEntities"); + _ecm.EachRemoved( + [&](const Entity &_entity, const components::Actor *)->bool + { + this->removeEntities[_entity] = _info.iterations; + this->entityPoses.erase(_entity); + this->actorTransforms.erase(_entity); + return true; + }); _ecm.EachRemoved( [&](const Entity &_entity, const components::Model *)->bool { @@ -2499,7 +2507,7 @@ bool RenderUtil::HeadlessRendering() const ///////////////////////////////////////////////// void RenderUtil::InitRenderEnginePluginPaths() { - ignition::common::SystemPaths pluginPath; + common::SystemPaths pluginPath; pluginPath.SetPluginPathEnv(kRenderPluginPathEnv); rendering::setPluginPaths(pluginPath.PluginPaths()); } diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 3b53f5b9b0..48e1983cf4 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -677,8 +677,8 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, descriptor.subMeshName = _geom.MeshShape()->Submesh(); descriptor.centerSubMesh = _geom.MeshShape()->CenterSubmesh(); - ignition::common::MeshManager *meshManager = - ignition::common::MeshManager::Instance(); + common::MeshManager *meshManager = + common::MeshManager::Instance(); descriptor.mesh = meshManager->Load(descriptor.meshName); geom = this->dataPtr->scene->CreateMesh(descriptor); scale = _geom.MeshShape()->Scale(); @@ -745,7 +745,7 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, std::string name("POLYLINE_" + common::Uuid().String()); - auto meshManager = ignition::common::MeshManager::Instance(); + auto meshManager = common::MeshManager::Instance(); meshManager->CreateExtrudedPolyline(name, vertices, _geom.PolylineShape()[0].Height()); @@ -1950,6 +1950,28 @@ void SceneManager::RemoveEntity(Entity _id) if (!this->dataPtr->scene) return; + { + auto it = this->dataPtr->actors.find(_id); + if (it != this->dataPtr->actors.end()) + { + this->dataPtr->actors.erase(it); + } + } + { + auto it = this->dataPtr->actorTrajectories.find(_id); + if (it != this->dataPtr->actorTrajectories.end()) + { + this->dataPtr->actorTrajectories.erase(it); + } + } + { + auto it = this->dataPtr->actorSkeletons.find(_id); + if (it != this->dataPtr->actorSkeletons.end()) + { + this->dataPtr->actorSkeletons.erase(it); + } + } + { auto it = this->dataPtr->visuals.find(_id); if (it != this->dataPtr->visuals.end()) diff --git a/src/systems/ackermann_steering/AckermannSteering.cc b/src/systems/ackermann_steering/AckermannSteering.cc index d2dc5f39e7..34d22ab1a7 100644 --- a/src/systems/ackermann_steering/AckermannSteering.cc +++ b/src/systems/ackermann_steering/AckermannSteering.cc @@ -58,21 +58,21 @@ class ignition::gazebo::systems::AckermannSteeringPrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const msgs::Twist &_msg); /// \brief Update odometry and publish an odometry message. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateOdometry(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -165,10 +165,10 @@ class ignition::gazebo::systems::AckermannSteeringPrivate public: std::chrono::steady_clock::duration lastOdomTime{0}; /// \brief Linear velocity limiter. - public: std::unique_ptr limiterLin; + public: std::unique_ptr limiterLin; /// \brief Angular velocity limiter. - public: std::unique_ptr limiterAng; + public: std::unique_ptr limiterAng; /// \brief Previous control command. public: Commands last0Cmd; @@ -260,8 +260,8 @@ void AckermannSteering::Configure(const Entity &_entity, this->dataPtr->wheelRadius).first; // Instantiate the speed limiters. - this->dataPtr->limiterLin = std::make_unique(); - this->dataPtr->limiterAng = std::make_unique(); + this->dataPtr->limiterLin = std::make_unique(); + this->dataPtr->limiterAng = std::make_unique(); // Parse speed limiter parameters. if (_sdf->HasElement("min_velocity")) @@ -375,8 +375,8 @@ void AckermannSteering::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void AckermannSteering::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void AckermannSteering::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("AckermannSteering::PreUpdate"); @@ -587,8 +587,8 @@ void AckermannSteering::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void AckermannSteeringPrivate::UpdateOdometry( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("AckermannSteering::UpdateOdometry"); // Initialize, if not already initialized. @@ -690,7 +690,7 @@ void AckermannSteeringPrivate::UpdateOdometry( // Construct the Pose_V/tf message and publish it. msgs::Pose_V tfMsg; - ignition::msgs::Pose *tfMsgPose = tfMsg.add_pose(); + msgs::Pose *tfMsgPose = tfMsg.add_pose(); tfMsgPose->mutable_header()->CopyFrom(*msg.mutable_header()); tfMsgPose->mutable_position()->CopyFrom(msg.mutable_pose()->position()); tfMsgPose->mutable_orientation()->CopyFrom(msg.mutable_pose()->orientation()); @@ -702,8 +702,8 @@ void AckermannSteeringPrivate::UpdateOdometry( ////////////////////////////////////////////////// void AckermannSteeringPrivate::UpdateVelocity( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("AckermannSteering::UpdateVelocity"); @@ -788,7 +788,7 @@ void AckermannSteeringPrivate::OnCmdVel(const msgs::Twist &_msg) } IGNITION_ADD_PLUGIN(AckermannSteering, - ignition::gazebo::System, + System, AckermannSteering::ISystemConfigure, AckermannSteering::ISystemPreUpdate, AckermannSteering::ISystemPostUpdate) diff --git a/src/systems/altimeter/Altimeter.cc b/src/systems/altimeter/Altimeter.cc index 3152c0c7e7..18c83458ee 100644 --- a/src/systems/altimeter/Altimeter.cc +++ b/src/systems/altimeter/Altimeter.cc @@ -261,7 +261,6 @@ void AltimeterPrivate::UpdateAltimeters(const EntityComponentManager &_ecm) auto it = this->entitySensorMap.find(_entity); if (it != this->entitySensorMap.end()) { - math::Vector3d linearVel; math::Pose3d worldPose = _worldPose->Data(); it->second->SetPosition(worldPose.Pos().Z()); it->second->SetVerticalVelocity(_worldLinearVel->Data().Z()); diff --git a/src/systems/apply_joint_force/ApplyJointForce.cc b/src/systems/apply_joint_force/ApplyJointForce.cc index 042f585565..ab0db7b485 100644 --- a/src/systems/apply_joint_force/ApplyJointForce.cc +++ b/src/systems/apply_joint_force/ApplyJointForce.cc @@ -35,7 +35,7 @@ class ignition::gazebo::systems::ApplyJointForcePrivate { /// \brief Callback for joint force subscription /// \param[in] _msg Joint force message - public: void OnCmdForce(const ignition::msgs::Double &_msg); + public: void OnCmdForce(const msgs::Double &_msg); /// \brief Ignition communication node. public: transport::Node node; @@ -111,8 +111,8 @@ void ApplyJointForce::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void ApplyJointForce::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void ApplyJointForce::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("ApplyJointForce::PreUpdate"); @@ -164,7 +164,7 @@ void ApplyJointForcePrivate::OnCmdForce(const msgs::Double &_msg) } IGNITION_ADD_PLUGIN(ApplyJointForce, - ignition::gazebo::System, + System, ApplyJointForce::ISystemConfigure, ApplyJointForce::ISystemPreUpdate) diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.cc b/src/systems/battery_plugin/LinearBatteryPlugin.cc index 1b484783cf..bb9562fe7f 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.cc +++ b/src/systems/battery_plugin/LinearBatteryPlugin.cc @@ -63,11 +63,11 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate /// \brief Callback executed to start recharging. /// \param[in] _req This value should be true. - public: void OnEnableRecharge(const ignition::msgs::Boolean &_req); + public: void OnEnableRecharge(const msgs::Boolean &_req); /// \brief Callback executed to stop recharging. /// \param[in] _req This value should be true. - public: void OnDisableRecharge(const ignition::msgs::Boolean &_req); + public: void OnDisableRecharge(const msgs::Boolean &_req); /// \brief Callback connected to additional topics that can start battery /// draining. @@ -411,7 +411,7 @@ double LinearBatteryPluginPrivate::StateOfCharge() const ////////////////////////////////////////////////// void LinearBatteryPluginPrivate::OnEnableRecharge( - const ignition::msgs::Boolean &/*_req*/) + const msgs::Boolean &/*_req*/) { igndbg << "Request for start charging received" << std::endl; this->startCharging = true; @@ -419,7 +419,7 @@ void LinearBatteryPluginPrivate::OnEnableRecharge( ////////////////////////////////////////////////// void LinearBatteryPluginPrivate::OnDisableRecharge( - const ignition::msgs::Boolean &/*_req*/) + const msgs::Boolean &/*_req*/) { igndbg << "Request for stop charging received" << std::endl; this->startCharging = false; @@ -434,8 +434,8 @@ void LinearBatteryPluginPrivate::OnBatteryDrainingMsg( ////////////////////////////////////////////////// void LinearBatteryPlugin::PreUpdate( - const ignition::gazebo::UpdateInfo &/*_info*/, - ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &/*_info*/, + EntityComponentManager &_ecm) { IGN_PROFILE("LinearBatteryPlugin::PreUpdate"); @@ -670,7 +670,7 @@ double LinearBatteryPlugin::OnUpdateVoltage( } IGNITION_ADD_PLUGIN(LinearBatteryPlugin, - ignition::gazebo::System, + System, LinearBatteryPlugin::ISystemConfigure, LinearBatteryPlugin::ISystemPreUpdate, LinearBatteryPlugin::ISystemUpdate, diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.hh b/src/systems/battery_plugin/LinearBatteryPlugin.hh index e98460a15b..71782ddf64 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.hh +++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh @@ -57,7 +57,7 @@ namespace systems /// - `` Hours taken to fully charge the battery. /// (Required if `` is set to true) /// - `` True to change the battery behavior to fix some issues - /// described in https://github.com/ignitionrobotics/ign-gazebo/issues/225. + /// described in https://github.com/gazebosim/gz-sim/issues/225. /// - `` A topic that is used to start battery /// discharge. Any message on the specified topic will cause the batter to /// start draining. This element can be specified multiple times if diff --git a/src/systems/breadcrumbs/Breadcrumbs.cc b/src/systems/breadcrumbs/Breadcrumbs.cc index c6484e5551..a89567142b 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.cc +++ b/src/systems/breadcrumbs/Breadcrumbs.cc @@ -172,8 +172,8 @@ void Breadcrumbs::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void Breadcrumbs::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void Breadcrumbs::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("Breadcrumbs::PreUpdate"); @@ -434,7 +434,7 @@ void Breadcrumbs::OnDeploy(const msgs::Empty &) } IGNITION_ADD_PLUGIN(Breadcrumbs, - ignition::gazebo::System, + System, Breadcrumbs::ISystemConfigure, Breadcrumbs::ISystemPreUpdate) diff --git a/src/systems/buoyancy/Buoyancy.cc b/src/systems/buoyancy/Buoyancy.cc index eaa50b1aa7..c906ccf334 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -337,8 +337,8 @@ void Buoyancy::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void Buoyancy::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("Buoyancy::PreUpdate"); const components::Gravity *gravity = _ecm.Component( @@ -376,8 +376,8 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, _entity, components::Collision()); double volumeSum = 0; - ignition::math::Vector3d weightedPosInLinkSum = - ignition::math::Vector3d::Zero; + math::Vector3d weightedPosInLinkSum = + math::Vector3d::Zero; // Compute the volume of the link by iterating over all the collision // elements and storing each geometry's volume. @@ -581,7 +581,7 @@ bool Buoyancy::IsEnabled(Entity _entity, } IGNITION_ADD_PLUGIN(Buoyancy, - ignition::gazebo::System, + System, Buoyancy::ISystemConfigure, Buoyancy::ISystemPreUpdate) diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.cc b/src/systems/camera_video_recorder/CameraVideoRecorder.cc index 6918036299..013a255a93 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.cc +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.cc @@ -70,7 +70,7 @@ class ignition::gazebo::systems::CameraVideoRecorderPrivate public: std::mutex updateMutex; /// \brief Connection to the post-render event. - public: ignition::common::ConnectionPtr postRenderConn; + public: common::ConnectionPtr postRenderConn; /// \brief Pointer to the event manager public: EventManager *eventMgr = nullptr; @@ -356,7 +356,7 @@ void CameraVideoRecorderPrivate::OnPostRender() std::chrono::steady_clock::duration dt; dt = t - this->recordStartTime; int64_t sec, nsec; - std::tie(sec, nsec) = ignition::math::durationToSecNsec(dt); + std::tie(sec, nsec) = math::durationToSecNsec(dt); msgs::Time msg; msg.set_sec(sec); msg.set_nsec(nsec); @@ -461,7 +461,7 @@ void CameraVideoRecorder::PostUpdate(const UpdateInfo &_info, } IGNITION_ADD_PLUGIN(CameraVideoRecorder, - ignition::gazebo::System, + System, CameraVideoRecorder::ISystemConfigure, CameraVideoRecorder::ISystemPostUpdate) diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.hh b/src/systems/camera_video_recorder/CameraVideoRecorder.hh index f5f3dc02c1..c905301036 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh @@ -51,7 +51,7 @@ namespace systems /// /// Video recorder bitrate (bps). The default value is /// 2070000 bps, and the supported type is unsigned int. - class CameraVideoRecorder: + class CameraVideoRecorder final: public System, public ISystemConfigure, public ISystemPostUpdate diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.cc b/src/systems/collada_world_exporter/ColladaWorldExporter.cc index 66ee000dfa..6cc6aaa301 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.cc +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.cc @@ -85,7 +85,7 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate components::Name, components::Geometry, components::Transparency>( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Visual *, const components::Name *_name, const components::Geometry *_geom, @@ -107,12 +107,12 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate } mat->SetTransparency(_transparency->Data()); - const ignition::common::Mesh *mesh; - std::weak_ptr subm; + const common::Mesh *mesh; + std::weak_ptr subm; math::Vector3d scale; math::Matrix4d matrix(worldPose); - ignition::common::MeshManager *meshManager = - ignition::common::MeshManager::Instance(); + common::MeshManager *meshManager = + common::MeshManager::Instance(); auto addSubmeshFunc = [&](int _matIndex) { diff --git a/src/systems/contact/Contact.cc b/src/systems/contact/Contact.cc index afd1122245..ac5bf96914 100644 --- a/src/systems/contact/Contact.cc +++ b/src/systems/contact/Contact.cc @@ -123,7 +123,7 @@ void ContactSensor::Load(const sdf::ElementPtr &_sdf, const std::string &_topic, } ignmsg << "Contact system publishing on " << this->topic << std::endl; - this->pub = this->node.Advertise(this->topic); + this->pub = this->node.Advertise(this->topic); } ////////////////////////////////////////////////// diff --git a/src/systems/detachable_joint/DetachableJoint.cc b/src/systems/detachable_joint/DetachableJoint.cc index 0946aa9505..7d40dd4786 100644 --- a/src/systems/detachable_joint/DetachableJoint.cc +++ b/src/systems/detachable_joint/DetachableJoint.cc @@ -114,8 +114,8 @@ void DetachableJoint::Configure(const Entity &_entity, ////////////////////////////////////////////////// void DetachableJoint::PreUpdate( - const ignition::gazebo::UpdateInfo &/*_info*/, - ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &/*_info*/, + EntityComponentManager &_ecm) { IGN_PROFILE("DetachableJoint::PreUpdate"); if (this->validConfig && !this->initialized) @@ -190,7 +190,7 @@ void DetachableJoint::OnDetachRequest(const msgs::Empty &) } IGNITION_ADD_PLUGIN(DetachableJoint, - ignition::gazebo::System, + System, DetachableJoint::ISystemConfigure, DetachableJoint::ISystemPreUpdate) diff --git a/src/systems/diff_drive/DiffDrive.cc b/src/systems/diff_drive/DiffDrive.cc index ec8e5a46d2..e869cc5a58 100644 --- a/src/systems/diff_drive/DiffDrive.cc +++ b/src/systems/diff_drive/DiffDrive.cc @@ -59,25 +59,25 @@ class ignition::gazebo::systems::DiffDrivePrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const msgs::Twist &_msg); /// \brief Callback for enable/disable subscription /// \param[in] _msg Boolean message - public: void OnEnable(const ignition::msgs::Boolean &_msg); + public: void OnEnable(const msgs::Boolean &_msg); /// \brief Update odometry and publish an odometry message. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateOdometry(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -128,10 +128,10 @@ class ignition::gazebo::systems::DiffDrivePrivate public: transport::Node::Publisher tfPub; /// \brief Linear velocity limiter. - public: std::unique_ptr limiterLin; + public: std::unique_ptr limiterLin; /// \brief Angular velocity limiter. - public: std::unique_ptr limiterAng; + public: std::unique_ptr limiterAng; /// \brief Previous control command. public: Commands last0Cmd; @@ -206,8 +206,8 @@ void DiffDrive::Configure(const Entity &_entity, this->dataPtr->wheelRadius).first; // Instantiate the speed limiters. - this->dataPtr->limiterLin = std::make_unique(); - this->dataPtr->limiterAng = std::make_unique(); + this->dataPtr->limiterLin = std::make_unique(); + this->dataPtr->limiterAng = std::make_unique(); // Parse speed limiter parameters. @@ -386,8 +386,8 @@ void DiffDrive::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void DiffDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void DiffDrive::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("DiffDrive::PreUpdate"); @@ -524,8 +524,8 @@ void DiffDrive::PostUpdate(const UpdateInfo &_info, } ////////////////////////////////////////////////// -void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) +void DiffDrivePrivate::UpdateOdometry(const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("DiffDrive::UpdateOdometry"); // Initialize, if not already initialized. @@ -608,7 +608,7 @@ void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, // Construct the Pose_V/tf message and publish it. msgs::Pose_V tfMsg; - ignition::msgs::Pose *tfMsgPose = tfMsg.add_pose(); + msgs::Pose *tfMsgPose = tfMsg.add_pose(); tfMsgPose->mutable_header()->CopyFrom(*msg.mutable_header()); tfMsgPose->mutable_position()->CopyFrom(msg.mutable_pose()->position()); tfMsgPose->mutable_orientation()->CopyFrom(msg.mutable_pose()->orientation()); @@ -619,8 +619,8 @@ void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, } ////////////////////////////////////////////////// -void DiffDrivePrivate::UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &/*_ecm*/) +void DiffDrivePrivate::UpdateVelocity(const UpdateInfo &_info, + const EntityComponentManager &/*_ecm*/) { IGN_PROFILE("DiffDrive::UpdateVelocity"); @@ -674,7 +674,7 @@ void DiffDrivePrivate::OnEnable(const msgs::Boolean &_msg) } IGNITION_ADD_PLUGIN(DiffDrive, - ignition::gazebo::System, + System, DiffDrive::ISystemConfigure, DiffDrive::ISystemPreUpdate, DiffDrive::ISystemPostUpdate) diff --git a/src/systems/imu/Imu.cc b/src/systems/imu/Imu.cc index 5afbd67ae0..4494d40cb5 100644 --- a/src/systems/imu/Imu.cc +++ b/src/systems/imu/Imu.cc @@ -53,7 +53,7 @@ class ignition::gazebo::systems::ImuPrivate { /// \brief A map of IMU entity to its IMU sensor. public: std::unordered_map> entitySensorMap; + std::unique_ptr> entitySensorMap; /// \brief Ign-sensors sensor factory for creating sensors public: sensors::SensorFactory sensorFactory; diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index 3f5a1cdfd1..afd7b481e2 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -39,7 +39,7 @@ class ignition::gazebo::systems::JointControllerPrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Double &_msg); + public: void OnCmdVel(const msgs::Double &_msg); /// \brief Ignition communication node. public: transport::Node node; @@ -61,7 +61,7 @@ class ignition::gazebo::systems::JointControllerPrivate public: bool useForceCommands{false}; /// \brief Velocity PID controller. - public: ignition::math::PID velPid; + public: math::PID velPid; }; ////////////////////////////////////////////////// @@ -173,8 +173,8 @@ void JointController::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void JointController::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void JointController::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("JointController::PreUpdate"); @@ -260,7 +260,7 @@ void JointControllerPrivate::OnCmdVel(const msgs::Double &_msg) } IGNITION_ADD_PLUGIN(JointController, - ignition::gazebo::System, + System, JointController::ISystemConfigure, JointController::ISystemPreUpdate) diff --git a/src/systems/joint_position_controller/JointPositionController.cc b/src/systems/joint_position_controller/JointPositionController.cc index 5f7ca8a8a8..7262ebd466 100644 --- a/src/systems/joint_position_controller/JointPositionController.cc +++ b/src/systems/joint_position_controller/JointPositionController.cc @@ -40,7 +40,7 @@ class ignition::gazebo::systems::JointPositionControllerPrivate { /// \brief Callback for position subscription /// \param[in] _msg Position message - public: void OnCmdPos(const ignition::msgs::Double &_msg); + public: void OnCmdPos(const msgs::Double &_msg); /// \brief Ignition communication node. public: transport::Node node; @@ -61,7 +61,7 @@ class ignition::gazebo::systems::JointPositionControllerPrivate public: Model model{kNullEntity}; /// \brief Position PID controller. - public: ignition::math::PID posPid; + public: math::PID posPid; /// \brief Joint index to be used. public: unsigned int jointIndex = 0u; @@ -218,8 +218,8 @@ void JointPositionController::Configure(const Entity &_entity, ////////////////////////////////////////////////// void JointPositionController::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("JointPositionController::PreUpdate"); @@ -357,7 +357,7 @@ void JointPositionControllerPrivate::OnCmdPos(const msgs::Double &_msg) } IGNITION_ADD_PLUGIN(JointPositionController, - ignition::gazebo::System, + System, JointPositionController::ISystemConfigure, JointPositionController::ISystemPreUpdate) diff --git a/src/systems/joint_state_publisher/JointStatePublisher.cc b/src/systems/joint_state_publisher/JointStatePublisher.cc index 5a995b9dfd..024b8e3d70 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.cc +++ b/src/systems/joint_state_publisher/JointStatePublisher.cc @@ -69,7 +69,7 @@ void JointStatePublisher::Configure( while (elem) { std::string jointName = elem->Get(); - gazebo::Entity jointEntity = this->model.JointByName(_ecm, jointName); + Entity jointEntity = this->model.JointByName(_ecm, jointName); if (jointEntity != kNullEntity) { this->CreateComponents(_ecm, jointEntity); @@ -105,7 +105,7 @@ void JointStatePublisher::Configure( ////////////////////////////////////////////////// void JointStatePublisher::CreateComponents(EntityComponentManager &_ecm, - gazebo::Entity _joint) + Entity _joint) { if (this->joints.find(_joint) != this->joints.end()) { @@ -313,7 +313,7 @@ void JointStatePublisher::PostUpdate(const UpdateInfo &_info, } IGNITION_ADD_PLUGIN(JointStatePublisher, - ignition::gazebo::System, + System, JointStatePublisher::ISystemConfigure, JointStatePublisher::ISystemPostUpdate) diff --git a/src/systems/lift_drag/LiftDrag.cc b/src/systems/lift_drag/LiftDrag.cc index d809f2292c..4defe386a9 100644 --- a/src/systems/lift_drag/LiftDrag.cc +++ b/src/systems/lift_drag/LiftDrag.cc @@ -106,16 +106,16 @@ class ignition::gazebo::systems::LiftDragPrivate /// \brief center of pressure in link local coordinates with respect to the /// link's center of mass - public: ignition::math::Vector3d cp = math::Vector3d::Zero; + public: math::Vector3d cp = math::Vector3d::Zero; /// \brief Normally, this is taken as a direction parallel to the chord /// of the airfoil in zero angle of attack forward flight. - public: ignition::math::Vector3d forward = math::Vector3d::UnitX; + public: math::Vector3d forward = math::Vector3d::UnitX; /// \brief A vector in the lift/drag plane, perpendicular to the forward /// vector. Inflow velocity orthogonal to forward and upward vectors /// is considered flow in the wing sweep direction. - public: ignition::math::Vector3d upward = math::Vector3d::UnitZ; + public: math::Vector3d upward = math::Vector3d::UnitZ; /// \brief how much to change CL per radian of control surface joint /// value. @@ -154,15 +154,15 @@ void LiftDragPrivate::Load(const EntityComponentManager &_ecm, this->radialSymmetry).first; this->area = _sdf->Get("area", this->area).first; this->alpha0 = _sdf->Get("a0", this->alpha0).first; - this->cp = _sdf->Get("cp", this->cp).first; + this->cp = _sdf->Get("cp", this->cp).first; // blade forward (-drag) direction in link frame this->forward = - _sdf->Get("forward", this->forward).first; + _sdf->Get("forward", this->forward).first; this->forward.Normalize(); // blade upward (+lift) direction in link frame - this->upward = _sdf->Get( + this->upward = _sdf->Get( "upward", this->upward) .first; this->upward.Normalize(); @@ -281,12 +281,12 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) // rotate forward and upward vectors into world frame const auto forwardI = pose.Rot().RotateVector(this->forward); - ignition::math::Vector3d upwardI; + math::Vector3d upwardI; if (this->radialSymmetry) { // use inflow velocity to determine upward direction // which is the component of inflow perpendicular to forward direction. - ignition::math::Vector3d tmp = forwardI.Cross(velI); + math::Vector3d tmp = forwardI.Cross(velI); upwardI = forwardI.Cross(tmp).Normalize(); } else @@ -300,7 +300,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) const double minRatio = -1.0; const double maxRatio = 1.0; // check sweep (angle between velI and lift-drag-plane) - double sinSweepAngle = ignition::math::clamp( + double sinSweepAngle = math::clamp( spanwiseI.Dot(velI), minRatio, maxRatio); // get cos from trig identity @@ -340,7 +340,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) // given upwardI and liftI are both unit vectors, we can drop the denominator // cos(theta) = a.Dot(b) const double cosAlpha = - ignition::math::clamp(liftI.Dot(upwardI), minRatio, maxRatio); + math::clamp(liftI.Dot(upwardI), minRatio, maxRatio); // Is alpha positive or negative? Test: // forwardI points toward zero alpha @@ -389,7 +389,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) } // compute lift force at cp - ignition::math::Vector3d lift = cl * q * this->area * liftI; + math::Vector3d lift = cl * q * this->area * liftI; // compute cd at cp, check for stall, correct for sweep double cd; @@ -412,7 +412,7 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) cd = std::fabs(cd); // drag at cp - ignition::math::Vector3d drag = cd * q * this->area * dragDirection; + math::Vector3d drag = cd * q * this->area * dragDirection; // compute cm at cp, check for stall, correct for sweep double cm; @@ -441,12 +441,12 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm) // compute moment (torque) at cp // spanwiseI used to be momentDirection - ignition::math::Vector3d moment = cm * q * this->area * spanwiseI; + math::Vector3d moment = cm * q * this->area * spanwiseI; // force and torque about cg in world frame - ignition::math::Vector3d force = lift + drag; - ignition::math::Vector3d torque = moment; + math::Vector3d force = lift + drag; + math::Vector3d torque = moment; // Correct for nan or inf force.Correct(); this->cp.Correct(); @@ -558,7 +558,7 @@ void LiftDrag::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) } IGNITION_ADD_PLUGIN(LiftDrag, - ignition::gazebo::System, + System, LiftDrag::ISystemConfigure, LiftDrag::ISystemPreUpdate) diff --git a/src/systems/log/LogPlayback.cc b/src/systems/log/LogPlayback.cc index b7529705c6..31a5b6159a 100644 --- a/src/systems/log/LogPlayback.cc +++ b/src/systems/log/LogPlayback.cc @@ -602,10 +602,10 @@ void LogPlayback::Update(const UpdateInfo &_info, EntityComponentManager &_ecm) } } -IGNITION_ADD_PLUGIN(ignition::gazebo::systems::LogPlayback, - ignition::gazebo::System, +IGNITION_ADD_PLUGIN(LogPlayback, + System, LogPlayback::ISystemConfigure, LogPlayback::ISystemUpdate) -IGNITION_ADD_PLUGIN_ALIAS(ignition::gazebo::systems::LogPlayback, +IGNITION_ADD_PLUGIN_ALIAS(LogPlayback, "ignition::gazebo::systems::LogPlayback") diff --git a/src/systems/log/LogRecord.cc b/src/systems/log/LogRecord.cc index 918359f6dc..8a974c0c3b 100644 --- a/src/systems/log/LogRecord.cc +++ b/src/systems/log/LogRecord.cc @@ -371,7 +371,7 @@ bool LogRecordPrivate::Start(const std::string &_logPath, // This calls Log::Open() and loads sql schema if (this->recorder.Start(dbPath) == - ignition::transport::log::RecorderError::SUCCESS) + transport::log::RecorderError::SUCCESS) { this->instStarted = true; return true; @@ -736,11 +736,11 @@ void LogRecord::PostUpdate(const UpdateInfo &_info, this->dataPtr->LogModelResources(_ecm); } -IGNITION_ADD_PLUGIN(ignition::gazebo::systems::LogRecord, - ignition::gazebo::System, +IGNITION_ADD_PLUGIN(LogRecord, + gazebo::System, LogRecord::ISystemConfigure, LogRecord::ISystemPreUpdate, LogRecord::ISystemPostUpdate) -IGNITION_ADD_PLUGIN_ALIAS(ignition::gazebo::systems::LogRecord, +IGNITION_ADD_PLUGIN_ALIAS(LogRecord, "ignition::gazebo::systems::LogRecord") diff --git a/src/systems/log_video_recorder/LogVideoRecorder.cc b/src/systems/log_video_recorder/LogVideoRecorder.cc index 29416a3a0e..8fe62313cd 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.cc +++ b/src/systems/log_video_recorder/LogVideoRecorder.cc @@ -372,8 +372,8 @@ void LogVideoRecorder::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void LogVideoRecorderPrivate::Rewind() { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending rewind request" << std::endl; @@ -399,14 +399,14 @@ void LogVideoRecorderPrivate::Play() ////////////////////////////////////////////////// void LogVideoRecorderPrivate::Follow(const std::string &_entity) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending follow request" << std::endl; }; - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(_entity); if (this->node.Request(this->followService, req, cb)) { @@ -417,14 +417,14 @@ void LogVideoRecorderPrivate::Follow(const std::string &_entity) ////////////////////////////////////////////////// void LogVideoRecorderPrivate::Record(bool _record) { - std::function cb = - [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [](const msgs::Boolean &/*_rep*/, const bool _result) { if (!_result) ignerr << "Error sending record request" << std::endl; }; - ignition::msgs::VideoRecord req; + msgs::VideoRecord req; if (_record) { @@ -445,7 +445,7 @@ void LogVideoRecorderPrivate::Record(bool _record) } IGNITION_ADD_PLUGIN(LogVideoRecorder, - ignition::gazebo::System, + System, LogVideoRecorder::ISystemConfigure, LogVideoRecorder::ISystemPostUpdate) diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc index 78ab1b7d65..9493abe590 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc @@ -78,7 +78,7 @@ class ignition::gazebo::systems::LogicalAudioSensorPluginPrivate const logical_audio::SourcePlayInfo &_sourcePlayInfo); /// \brief Node used to create publishers and services - public: ignition::transport::Node node; + public: transport::Node node; /// \brief A flag used to initialize a source's playing information /// before starting simulation. @@ -97,7 +97,7 @@ class ignition::gazebo::systems::LogicalAudioSensorPluginPrivate /// (an entity can have multiple microphones attached to it). /// The value is the microphone's detection publisher. public: std::unordered_map micEntities; + transport::Node::Publisher> micEntities; /// \brief A mutex used to ensure that the play source service call does /// not interfere with the source's state in the PreUpdate step. @@ -240,7 +240,7 @@ void LogicalAudioSensorPlugin::PostUpdate(const UpdateInfo &_info, // publish the source that the microphone heard, along with the // volume level the microphone detected. The detected source's // ID is embedded in the message's header - ignition::msgs::Double msg; + msgs::Double msg; auto header = msg.mutable_header(); auto timeStamp = header->mutable_stamp(); timeStamp->set_sec(simSeconds.count()); @@ -284,7 +284,7 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( } _ids.insert(id); - ignition::math::Pose3d pose; + math::Pose3d pose; if (!_elem->HasElement("pose")) { ignwarn << "Audio source is missing a pose. " @@ -293,7 +293,7 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( } else { - pose = _elem->Get("pose"); + pose = _elem->Get("pose"); } if (!_elem->HasElement("attenuation_function")) @@ -385,16 +385,16 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( components::LogicalAudioSourcePlayInfo(playInfo)); // create service callbacks that allow this source to be played/stopped - std::function playSrvCb = - [this, entity](ignition::msgs::Boolean &_resp) + std::function playSrvCb = + [this, entity](msgs::Boolean &_resp) { std::lock_guard lock(this->playSourceMutex); this->sourceEntities[entity].first = true; _resp.set_data(true); return true; }; - std::function stopSrvCb = - [this, entity](ignition::msgs::Boolean &_resp) + std::function stopSrvCb = + [this, entity](msgs::Boolean &_resp) { std::lock_guard lock(this->stopSourceMutex); this->sourceEntities[entity].second = true; @@ -454,7 +454,7 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( } _ids.insert(id); - ignition::math::Pose3d pose; + math::Pose3d pose; if (!_elem->HasElement("pose")) { ignwarn << "Microphone is missing a pose. " @@ -463,7 +463,7 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( } else { - pose = _elem->Get("pose"); + pose = _elem->Get("pose"); } double volumeDetectionThreshold; @@ -501,7 +501,7 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( components::Pose(pose)); // create the detection publisher for this microphone - auto pub = this->node.Advertise( + auto pub = this->node.Advertise( scopedName(entity, _ecm) + "/detection"); if (!pub) { @@ -526,7 +526,7 @@ bool LogicalAudioSensorPluginPrivate::DurationExceeded( } IGNITION_ADD_PLUGIN(LogicalAudioSensorPlugin, - ignition::gazebo::System, + System, LogicalAudioSensorPlugin::ISystemConfigure, LogicalAudioSensorPlugin::ISystemPreUpdate, LogicalAudioSensorPlugin::ISystemPostUpdate) diff --git a/src/systems/magnetometer/Magnetometer.cc b/src/systems/magnetometer/Magnetometer.cc index 2ecad15692..829810f9ee 100644 --- a/src/systems/magnetometer/Magnetometer.cc +++ b/src/systems/magnetometer/Magnetometer.cc @@ -52,7 +52,7 @@ class ignition::gazebo::systems::MagnetometerPrivate { /// \brief A map of magnetometer entity to its sensor. public: std::unordered_map> entitySensorMap; + std::unique_ptr> entitySensorMap; /// \brief Ign-sensors sensor factory for creating sensors public: sensors::SensorFactory sensorFactory; diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.cc b/src/systems/multicopter_control/MulticopterVelocityControl.cc index 17fc2b56ff..09746000e5 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.cc +++ b/src/systems/multicopter_control/MulticopterVelocityControl.cc @@ -335,8 +335,8 @@ math::Inertiald MulticopterVelocityControl::VehicleInertial( ////////////////////////////////////////////////// void MulticopterVelocityControl::PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("MulticopterVelocityControl::PreUpdate"); @@ -427,7 +427,7 @@ void MulticopterVelocityControl::OnEnable( ////////////////////////////////////////////////// void MulticopterVelocityControl::PublishRotorVelocities( - ignition::gazebo::EntityComponentManager &_ecm, + EntityComponentManager &_ecm, const Eigen::VectorXd &_vels) { if (_vels.size() != this->rotorVelocitiesMsg.velocity_size()) @@ -464,7 +464,7 @@ void MulticopterVelocityControl::PublishRotorVelocities( } IGNITION_ADD_PLUGIN(MulticopterVelocityControl, - ignition::gazebo::System, + System, MulticopterVelocityControl::ISystemConfigure, MulticopterVelocityControl::ISystemPreUpdate) diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc index db6552555b..fe225a478a 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc @@ -120,7 +120,7 @@ enum class MotorType { class ignition::gazebo::systems::MulticopterMotorModelPrivate { /// \brief Callback for actuator commands. - public: void OnActuatorMsg(const ignition::msgs::Actuators &_msg); + public: void OnActuatorMsg(const msgs::Actuators &_msg); /// \brief Apply link forces and moments based on propeller state. public: void UpdateForcesAndMoments(EntityComponentManager &_ecm); @@ -377,8 +377,8 @@ void MulticopterMotorModel::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void MulticopterMotorModel::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void MulticopterMotorModel::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("MulticopterMotorModel::PreUpdate"); @@ -476,7 +476,7 @@ void MulticopterMotorModel::PreUpdate(const ignition::gazebo::UpdateInfo &_info, ////////////////////////////////////////////////// void MulticopterMotorModelPrivate::OnActuatorMsg( - const ignition::msgs::Actuators &_msg) + const msgs::Actuators &_msg) { std::lock_guard lock(this->recvdActuatorsMsgMutex); this->recvdActuatorsMsg = _msg; @@ -566,8 +566,8 @@ void MulticopterMotorModelPrivate::UpdateForcesAndMoments( realMotorVelocity * realMotorVelocity * this->motorConstant; - using Pose = ignition::math::Pose3d; - using Vector3 = ignition::math::Vector3d; + using Pose = math::Pose3d; + using Vector3 = math::Vector3d; Link link(this->linkEntity); const auto worldPose = link.WorldPose(_ecm); @@ -678,7 +678,7 @@ void MulticopterMotorModelPrivate::UpdateForcesAndMoments( } IGNITION_ADD_PLUGIN(MulticopterMotorModel, - ignition::gazebo::System, + System, MulticopterMotorModel::ISystemConfigure, MulticopterMotorModel::ISystemPreUpdate) diff --git a/src/systems/performer_detector/PerformerDetector.cc b/src/systems/performer_detector/PerformerDetector.cc index 7da45abd73..99c2c1a738 100644 --- a/src/systems/performer_detector/PerformerDetector.cc +++ b/src/systems/performer_detector/PerformerDetector.cc @@ -130,8 +130,8 @@ void PerformerDetector::Configure(const Entity &_entity, ////////////////////////////////////////////////// void PerformerDetector::PostUpdate( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("PerformerDetector::PostUpdate"); @@ -260,7 +260,7 @@ void PerformerDetector::Publish( } IGNITION_ADD_PLUGIN(PerformerDetector, - ignition::gazebo::System, + System, PerformerDetector::ISystemConfigure, PerformerDetector::ISystemPostUpdate) diff --git a/src/systems/physics/EntityFeatureMap_TEST.cc b/src/systems/physics/EntityFeatureMap_TEST.cc index f4c0e9d12f..510b5d3866 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -64,7 +64,7 @@ class EntityFeatureMapFixture: public InternalFixture<::testing::Test> << "Failed to find plugin [" << pluginLib << "]"; // Load engine plugin - ignition::plugin::Loader pluginLoader; + plugin::Loader pluginLoader; auto plugins = pluginLoader.LoadLib(pathToLib); ASSERT_FALSE(plugins.empty()) << "Unable to load the [" << pathToLib << "] library."; @@ -82,7 +82,7 @@ class EntityFeatureMapFixture: public InternalFixture<::testing::Test> << pathToLib << "]"; this->engine = - ignition::physics::RequestEngine::From(plugin); ASSERT_NE(nullptr, this->engine); diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index f78c0d64e6..33eb83abdf 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -157,37 +157,37 @@ class ignition::gazebo::systems::PhysicsPrivate /// implement to be supported by this system. /// New features can't be added to this list in minor / patch releases, in /// order to maintain backwards compatibility with downstream physics plugins. - public: struct MinimumFeatureList : ignition::physics::FeatureList< - ignition::physics::FindFreeGroupFeature, - ignition::physics::SetFreeGroupWorldPose, - ignition::physics::FreeGroupFrameSemantics, - ignition::physics::LinkFrameSemantics, - ignition::physics::ForwardStep, - ignition::physics::RemoveModelFromWorld, - ignition::physics::sdf::ConstructSdfLink, - ignition::physics::sdf::ConstructSdfModel, - ignition::physics::sdf::ConstructSdfWorld + public: struct MinimumFeatureList : physics::FeatureList< + physics::FindFreeGroupFeature, + physics::SetFreeGroupWorldPose, + physics::FreeGroupFrameSemantics, + physics::LinkFrameSemantics, + physics::ForwardStep, + physics::RemoveModelFromWorld, + physics::sdf::ConstructSdfLink, + physics::sdf::ConstructSdfModel, + physics::sdf::ConstructSdfWorld >{}; /// \brief Engine type with just the minimum features. - public: using EnginePtrType = ignition::physics::EnginePtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using EnginePtrType = physics::EnginePtr< + physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief World type with just the minimum features. - public: using WorldPtrType = ignition::physics::WorldPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using WorldPtrType = physics::WorldPtr< + physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Model type with just the minimum features. - public: using ModelPtrType = ignition::physics::ModelPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using ModelPtrType = physics::ModelPtr< + physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Link type with just the minimum features. - public: using LinkPtrType = ignition::physics::LinkPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using LinkPtrType = physics::LinkPtr< + physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Free group type with just the minimum features. - public: using FreeGroupPtrType = ignition::physics::FreeGroupPtr< - ignition::physics::FeaturePolicy3d, MinimumFeatureList>; + public: using FreeGroupPtrType = physics::FreeGroupPtr< + physics::FeaturePolicy3d, MinimumFeatureList>; /// \brief Create physics entities /// \param[in] _ecm Constant reference to ECM. @@ -293,7 +293,7 @@ class ignition::gazebo::systems::PhysicsPrivate /// \param[in] _from An ancestor of the _to entity. /// \param[in] _to A descendant of the _from entity. /// \return Pose transform between the two entities - public: ignition::math::Pose3d RelativePose(const Entity &_from, + public: math::Pose3d RelativePose(const Entity &_from, const Entity &_to, const EntityComponentManager &_ecm) const; /// \brief Enable contact surface customization for the given world. @@ -430,18 +430,18 @@ class ignition::gazebo::systems::PhysicsPrivate public: struct FrictionPyramidSlipComplianceFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::GetShapeFrictionPyramidSlipCompliance, - ignition::physics::SetShapeFrictionPyramidSlipCompliance>{}; + physics::GetShapeFrictionPyramidSlipCompliance, + physics::SetShapeFrictionPyramidSlipCompliance>{}; ////////////////////////////////////////////////// // Joints /// \brief Feature list to handle joints. - public: struct JointFeatureList : ignition::physics::FeatureList< + public: struct JointFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::GetBasicJointProperties, - ignition::physics::GetBasicJointState, - ignition::physics::SetBasicJointState, - ignition::physics::sdf::ConstructSdfJoint>{}; + physics::GetBasicJointProperties, + physics::GetBasicJointState, + physics::SetBasicJointState, + physics::sdf::ConstructSdfJoint>{}; ////////////////////////////////////////////////// @@ -464,50 +464,50 @@ class ignition::gazebo::systems::PhysicsPrivate // Collisions /// \brief Feature list to handle collisions. - public: struct CollisionFeatureList : ignition::physics::FeatureList< + public: struct CollisionFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::sdf::ConstructSdfCollision>{}; + physics::sdf::ConstructSdfCollision>{}; /// \brief Feature list to handle contacts information. - public: struct ContactFeatureList : ignition::physics::FeatureList< + public: struct ContactFeatureList : physics::FeatureList< CollisionFeatureList, - ignition::physics::GetContactsFromLastStepFeature>{}; + physics::GetContactsFromLastStepFeature>{}; /// \brief Feature list to change contacts before they are applied to physics. public: struct SetContactPropertiesCallbackFeatureList : - ignition::physics::FeatureList< + physics::FeatureList< ContactFeatureList, - ignition::physics::SetContactPropertiesCallbackFeature>{}; + physics::SetContactPropertiesCallbackFeature>{}; /// \brief Collision type with collision features. - public: using ShapePtrType = ignition::physics::ShapePtr< - ignition::physics::FeaturePolicy3d, CollisionFeatureList>; + public: using ShapePtrType = physics::ShapePtr< + physics::FeaturePolicy3d, CollisionFeatureList>; /// \brief World type with just the minimum features. Non-pointer. - public: using WorldShapeType = ignition::physics::World< - ignition::physics::FeaturePolicy3d, ContactFeatureList>; + public: using WorldShapeType = physics::World< + physics::FeaturePolicy3d, ContactFeatureList>; ////////////////////////////////////////////////// // Collision filtering with bitmasks /// \brief Feature list to filter collisions with bitmasks. - public: struct CollisionMaskFeatureList : ignition::physics::FeatureList< + public: struct CollisionMaskFeatureList : physics::FeatureList< CollisionFeatureList, - ignition::physics::CollisionFilterMaskFeature>{}; + physics::CollisionFilterMaskFeature>{}; ////////////////////////////////////////////////// // Link force /// \brief Feature list for applying forces to links. - public: struct LinkForceFeatureList : ignition::physics::FeatureList< - ignition::physics::AddLinkExternalForceTorque>{}; + public: struct LinkForceFeatureList : physics::FeatureList< + physics::AddLinkExternalForceTorque>{}; ////////////////////////////////////////////////// // Bounding box /// \brief Feature list for model bounding box. - public: struct BoundingBoxFeatureList : ignition::physics::FeatureList< + public: struct BoundingBoxFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::GetModelBoundingBox>{}; + physics::GetModelBoundingBox>{}; ////////////////////////////////////////////////// @@ -541,8 +541,8 @@ class ignition::gazebo::systems::PhysicsPrivate ////////////////////////////////////////////////// // World velocity command public: struct WorldVelocityCommandFeatureList : - ignition::physics::FeatureList< - ignition::physics::SetFreeGroupWorldVelocity>{}; + physics::FeatureList< + physics::SetFreeGroupWorldVelocity>{}; ////////////////////////////////////////////////// @@ -581,9 +581,9 @@ class ignition::gazebo::systems::PhysicsPrivate // Nested Models /// \brief Feature list to construct nested models - public: struct NestedModelFeatureList : ignition::physics::FeatureList< + public: struct NestedModelFeatureList : physics::FeatureList< MinimumFeatureList, - ignition::physics::sdf::ConstructSdfNestedModel>{}; + physics::sdf::ConstructSdfNestedModel>{}; ////////////////////////////////////////////////// /// \brief World EntityFeatureMap @@ -764,7 +764,7 @@ void Physics::Configure(const Entity &_entity, } // Load engine plugin - ignition::plugin::Loader pluginLoader; + plugin::Loader pluginLoader; auto plugins = pluginLoader.LoadLib(pathToLib); if (plugins.empty()) { @@ -794,8 +794,8 @@ void Physics::Configure(const Entity &_entity, continue; } - this->dataPtr->engine = ignition::physics::RequestEngine< - ignition::physics::FeaturePolicy3d, + this->dataPtr->engine = physics::RequestEngine< + physics::FeaturePolicy3d, PhysicsPrivate::MinimumFeatureList>::From(plugin); if (nullptr != this->dataPtr->engine) @@ -805,8 +805,8 @@ void Physics::Configure(const Entity &_entity, break; } - auto missingFeatures = ignition::physics::RequestEngine< - ignition::physics::FeaturePolicy3d, + auto missingFeatures = physics::RequestEngine< + physics::FeaturePolicy3d, PhysicsPrivate::MinimumFeatureList>::MissingFeatureNames(plugin); std::stringstream msg; @@ -1226,7 +1226,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm) return true; } - auto &meshManager = *ignition::common::MeshManager::Instance(); + auto &meshManager = *common::MeshManager::Instance(); auto fullPath = asFullPath(meshSdf->Uri(), meshSdf->FilePath()); auto *mesh = meshManager.Load(fullPath); if (nullptr == mesh) @@ -1324,7 +1324,7 @@ void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm) } std::string name("POLYLINE_" + common::Uuid().String()); - auto meshManager = ignition::common::MeshManager::Instance(); + auto meshManager = common::MeshManager::Instance(); meshManager->CreateExtrudedPolyline(name, vertices, _geom->Data().PolylineShape()[0].Height()); @@ -2421,9 +2421,9 @@ ignition::physics::ForwardStep::Output PhysicsPrivate::Step( const std::chrono::steady_clock::duration &_dt) { IGN_PROFILE("PhysicsPrivate::Step"); - ignition::physics::ForwardStep::Input input; - ignition::physics::ForwardStep::State state; - ignition::physics::ForwardStep::Output output; + physics::ForwardStep::Input input; + physics::ForwardStep::State state; + physics::ForwardStep::Output output; input.Get() = _dt; @@ -2436,7 +2436,7 @@ ignition::physics::ForwardStep::Output PhysicsPrivate::Step( } ////////////////////////////////////////////////// -ignition::math::Pose3d PhysicsPrivate::RelativePose(const Entity &_from, +math::Pose3d PhysicsPrivate::RelativePose(const Entity &_from, const Entity &_to, const EntityComponentManager &_ecm) const { math::Pose3d transform; @@ -2997,7 +2997,7 @@ void PhysicsPrivate::UpdateSim(EntityComponentManager &_ecm, this->LinkFrameDataAtOffset(linkPhys, _pose->Data()); auto entityWorldPose = math::eigen3::convert(entityFrameData.pose); - ignition::math::Vector3d entityWorldAngularVel = + math::Vector3d entityWorldAngularVel = math::eigen3::convert(entityFrameData.angularVelocity); auto entityBodyAngularVel = @@ -3022,7 +3022,7 @@ void PhysicsPrivate::UpdateSim(EntityComponentManager &_ecm, this->LinkFrameDataAtOffset(linkPhys, _pose->Data()); auto entityWorldPose = math::eigen3::convert(entityFrameData.pose); - ignition::math::Vector3d entityWorldLinearAcc = + math::Vector3d entityWorldLinearAcc = math::eigen3::convert(entityFrameData.linearAcceleration); auto entityBodyLinearAcc = @@ -3452,7 +3452,7 @@ void PhysicsPrivate::DisableContactSurfaceCustomization(const Entity &_world) } IGNITION_ADD_PLUGIN(Physics, - ignition::gazebo::System, + gazebo::System, Physics::ISystemConfigure, Physics::ISystemUpdate) diff --git a/src/systems/pose_publisher/PosePublisher.cc b/src/systems/pose_publisher/PosePublisher.cc index 010c88b10b..04067e33c7 100644 --- a/src/systems/pose_publisher/PosePublisher.cc +++ b/src/systems/pose_publisher/PosePublisher.cc @@ -156,12 +156,12 @@ class ignition::gazebo::systems::PosePublisherPrivate /// \brief A variable that gets populated with poses. This also here as a /// member variable to avoid repeated memory allocations and improve /// performance. - public: ignition::msgs::Pose poseMsg; + public: msgs::Pose poseMsg; /// \brief A variable that gets populated with poses. This also here as a /// member variable to avoid repeated memory allocations and improve /// performance. - public: ignition::msgs::Pose_V poseVMsg; + public: msgs::Pose_V poseVMsg; /// \brief True to publish a vector of poses. False to publish individual pose /// msgs. @@ -263,23 +263,23 @@ void PosePublisher::Configure(const Entity &_entity, if (this->dataPtr->usePoseV) { this->dataPtr->posePub = - this->dataPtr->node.Advertise(poseTopic); + this->dataPtr->node.Advertise(poseTopic); if (this->dataPtr->staticPosePublisher) { this->dataPtr->poseStaticPub = - this->dataPtr->node.Advertise( + this->dataPtr->node.Advertise( staticPoseTopic); } } else { this->dataPtr->posePub = - this->dataPtr->node.Advertise(poseTopic); + this->dataPtr->node.Advertise(poseTopic); if (this->dataPtr->staticPosePublisher) { this->dataPtr->poseStaticPub = - this->dataPtr->node.Advertise( + this->dataPtr->node.Advertise( staticPoseTopic); } } @@ -530,7 +530,7 @@ void PosePublisherPrivate::PublishPoses( IGN_PROFILE("PosePublisher::PublishPoses"); // publish poses - ignition::msgs::Pose *msg = nullptr; + msgs::Pose *msg = nullptr; if (this->usePoseV) this->poseVMsg.Clear(); diff --git a/src/systems/scene_broadcaster/SceneBroadcaster.cc b/src/systems/scene_broadcaster/SceneBroadcaster.cc index f88ae5b2bd..d2fa2a6d3c 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.cc +++ b/src/systems/scene_broadcaster/SceneBroadcaster.cc @@ -89,21 +89,21 @@ class ignition::gazebo::systems::SceneBroadcasterPrivate /// \brief Callback for scene info service. /// \param[out] _res Response containing the latest scene message. /// \return True if successful. - public: bool SceneInfoService(ignition::msgs::Scene &_res); + public: bool SceneInfoService(msgs::Scene &_res); /// \brief Callback for scene graph service. /// \param[out] _res Response containing the the scene graph in DOT format. /// \return True if successful. - public: bool SceneGraphService(ignition::msgs::StringMsg &_res); + public: bool SceneGraphService(msgs::StringMsg &_res); /// \brief Callback for state service. /// \param[out] _res Response containing the latest full state. /// \return True if successful. - public: bool StateService(ignition::msgs::SerializedStepMap &_res); + public: bool StateService(msgs::SerializedStepMap &_res); /// \brief Callback for state service - non blocking. /// \param[out] _res Response containing the last available full state. - public: void StateAsyncService(const ignition::msgs::StringMsg &_req); + public: void StateAsyncService(const msgs::StringMsg &_req); /// \brief Updates the scene graph when entities are added /// \param[in] _manager The entity component manager @@ -619,7 +619,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) // Scene info topic std::string sceneTopic{ns + "/scene/info"}; - this->scenePub = this->node->Advertise(sceneTopic); + this->scenePub = this->node->Advertise(sceneTopic); ignmsg << "Publishing scene information on [" << sceneTopic << "]" << std::endl; @@ -628,7 +628,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) std::string deletionTopic{ns + "/scene/deletion"}; this->deletionPub = - this->node->Advertise(deletionTopic); + this->node->Advertise(deletionTopic); ignmsg << "Publishing entity deletions on [" << deletionTopic << "]" << std::endl; @@ -637,7 +637,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) std::string stateTopic{ns + "/state"}; this->statePub = - this->node->Advertise(stateTopic); + this->node->Advertise(stateTopic); ignmsg << "Publishing state changes on [" << stateTopic << "]" << std::endl; @@ -666,7 +666,7 @@ void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName) } ////////////////////////////////////////////////// -bool SceneBroadcasterPrivate::SceneInfoService(ignition::msgs::Scene &_res) +bool SceneBroadcasterPrivate::SceneInfoService(msgs::Scene &_res) { std::lock_guard lock(this->graphMutex); @@ -686,7 +686,7 @@ bool SceneBroadcasterPrivate::SceneInfoService(ignition::msgs::Scene &_res) ////////////////////////////////////////////////// void SceneBroadcasterPrivate::StateAsyncService( - const ignition::msgs::StringMsg &_req) + const msgs::StringMsg &_req) { std::unique_lock lock(this->stateMutex); this->stateServiceRequest = true; @@ -695,7 +695,7 @@ void SceneBroadcasterPrivate::StateAsyncService( ////////////////////////////////////////////////// bool SceneBroadcasterPrivate::StateService( - ignition::msgs::SerializedStepMap &_res) + msgs::SerializedStepMap &_res) { _res.Clear(); @@ -717,7 +717,7 @@ bool SceneBroadcasterPrivate::StateService( } ////////////////////////////////////////////////// -bool SceneBroadcasterPrivate::SceneGraphService(ignition::msgs::StringMsg &_res) +bool SceneBroadcasterPrivate::SceneGraphService(msgs::StringMsg &_res) { std::lock_guard lock(this->graphMutex); @@ -987,22 +987,22 @@ void SceneBroadcasterPrivate::SceneGraphAddEntities( msgs::IMUSensor * imuMsg = sensorMsg->mutable_imu(); const auto * imu = imuComp->Data().ImuSensor(); - ignition::gazebo::set( + set( imuMsg->mutable_linear_acceleration()->mutable_x_noise(), imu->LinearAccelerationXNoise()); - ignition::gazebo::set( + set( imuMsg->mutable_linear_acceleration()->mutable_y_noise(), imu->LinearAccelerationYNoise()); - ignition::gazebo::set( + set( imuMsg->mutable_linear_acceleration()->mutable_z_noise(), imu->LinearAccelerationZNoise()); - ignition::gazebo::set( + set( imuMsg->mutable_angular_velocity()->mutable_x_noise(), imu->AngularVelocityXNoise()); - ignition::gazebo::set( + set( imuMsg->mutable_angular_velocity()->mutable_y_noise(), imu->AngularVelocityYNoise()); - ignition::gazebo::set( + set( imuMsg->mutable_angular_velocity()->mutable_z_noise(), imu->AngularVelocityZNoise()); } @@ -1288,7 +1288,7 @@ void SceneBroadcasterPrivate::RemoveFromGraph(const Entity _entity, IGNITION_ADD_PLUGIN(SceneBroadcaster, - ignition::gazebo::System, + System, SceneBroadcaster::ISystemConfigure, SceneBroadcaster::ISystemPostUpdate) diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 3a0573d58a..92463253d4 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -127,7 +127,7 @@ class ignition::gazebo::systems::SensorsPrivate public: std::condition_variable renderCv; /// \brief Connection to events::Stop event, used to stop thread - public: ignition::common::ConnectionPtr stopConn; + public: common::ConnectionPtr stopConn; /// \brief Update time for the next rendering iteration public: std::chrono::steady_clock::duration updateTime; diff --git a/src/systems/thermal/Thermal.cc b/src/systems/thermal/Thermal.cc index 28bd118931..c757ed2245 100644 --- a/src/systems/thermal/Thermal.cc +++ b/src/systems/thermal/Thermal.cc @@ -52,8 +52,8 @@ Thermal::~Thermal() = default; ////////////////////////////////////////////////// void Thermal::Configure(const Entity &_entity, const std::shared_ptr &_sdf, - gazebo::EntityComponentManager &_ecm, - gazebo::EventManager & /*_eventMgr*/) + EntityComponentManager &_ecm, + EventManager & /*_eventMgr*/) { const std::string temperatureTag = "temperature"; const std::string heatSignatureTag = "heat_signature"; diff --git a/src/systems/touch_plugin/TouchPlugin.cc b/src/systems/touch_plugin/TouchPlugin.cc index ccd177bb90..9f32ec1071 100644 --- a/src/systems/touch_plugin/TouchPlugin.cc +++ b/src/systems/touch_plugin/TouchPlugin.cc @@ -409,7 +409,7 @@ void TouchPlugin::PostUpdate(const UpdateInfo &_info, } IGNITION_ADD_PLUGIN(TouchPlugin, - ignition::gazebo::System, + System, TouchPlugin::ISystemConfigure, TouchPlugin::ISystemPreUpdate, TouchPlugin::ISystemPostUpdate) diff --git a/src/systems/track_controller/TrackController.cc b/src/systems/track_controller/TrackController.cc index 116d3cb787..fdf8d1d51a 100644 --- a/src/systems/track_controller/TrackController.cc +++ b/src/systems/track_controller/TrackController.cc @@ -91,8 +91,8 @@ class ignition::gazebo::systems::TrackControllerPrivate /// \param[in] _frictionDirection First friction direction (in world coords). /// \return The computed contact surface speed. public: double ComputeSurfaceMotion( - double _beltSpeed, const ignition::math::Vector3d &_beltDirection, - const ignition::math::Vector3d &_frictionDirection); + double _beltSpeed, const math::Vector3d &_beltDirection, + const math::Vector3d &_frictionDirection); /// \brief Compute the first friction direction of the contact surface. /// \param[in] _centerOfRotation The point around which the track circles ( @@ -100,11 +100,11 @@ class ignition::gazebo::systems::TrackControllerPrivate /// \param[in] _contactWorldPosition Position of the contact point. /// \param[in] _contactNormal Normal of the contact surface (in world coords). /// \param[in] _beltDirection Direction of the belt (in world coords). - public: ignition::math::Vector3d ComputeFrictionDirection( - const ignition::math::Vector3d &_centerOfRotation, - const ignition::math::Vector3d &_contactWorldPosition, - const ignition::math::Vector3d &_contactNormal, - const ignition::math::Vector3d &_beltDirection); + public: math::Vector3d ComputeFrictionDirection( + const math::Vector3d &_centerOfRotation, + const math::Vector3d &_contactWorldPosition, + const math::Vector3d &_contactNormal, + const math::Vector3d &_beltDirection); /// \brief Name of the link to which the track is attached. public: std::string linkName; @@ -342,24 +342,24 @@ void TrackController::Configure(const Entity &_entity, if (this->dataPtr->debug) { this->dataPtr->debugMarker.set_ns(this->dataPtr->linkName + "/friction"); - this->dataPtr->debugMarker.set_action(ignition::msgs::Marker::ADD_MODIFY); - this->dataPtr->debugMarker.set_type(ignition::msgs::Marker::BOX); - this->dataPtr->debugMarker.set_visibility(ignition::msgs::Marker::GUI); + this->dataPtr->debugMarker.set_action(msgs::Marker::ADD_MODIFY); + this->dataPtr->debugMarker.set_type(msgs::Marker::BOX); + this->dataPtr->debugMarker.set_visibility(msgs::Marker::GUI); this->dataPtr->debugMarker.mutable_lifetime()->set_sec(0); this->dataPtr->debugMarker.mutable_lifetime()->set_nsec(4000000); // Set material properties - ignition::msgs::Set( + msgs::Set( this->dataPtr->debugMarker.mutable_material()->mutable_ambient(), - ignition::math::Color(0, 0, 1, 1)); - ignition::msgs::Set( + math::Color(0, 0, 1, 1)); + msgs::Set( this->dataPtr->debugMarker.mutable_material()->mutable_diffuse(), - ignition::math::Color(0, 0, 1, 1)); + math::Color(0, 0, 1, 1)); // Set marker scale - ignition::msgs::Set( + msgs::Set( this->dataPtr->debugMarker.mutable_scale(), - ignition::math::Vector3d(0.3, 0.03, 0.03)); + math::Vector3d(0.3, 0.03, 0.03)); } } @@ -530,7 +530,7 @@ void TrackControllerPrivate::ComputeSurfaceProperties( p += rot.RotateVector( math::Vector3d::UnitX * this->debugMarker.scale().x() / 2); - ignition::msgs::Set(this->debugMarker.mutable_pose(), math::Pose3d( + msgs::Set(this->debugMarker.mutable_pose(), math::Pose3d( p.X(), p.Y(), p.Z(), rot.Roll(), rot.Pitch(), rot.Yaw())); this->debugMarker.mutable_material()->mutable_diffuse()->set_r( surfaceMotion >= 0 ? 0 : 1); @@ -541,8 +541,8 @@ void TrackControllerPrivate::ComputeSurfaceProperties( ////////////////////////////////////////////////// double TrackControllerPrivate::ComputeSurfaceMotion( - const double _beltSpeed, const ignition::math::Vector3d &_beltDirection, - const ignition::math::Vector3d &_frictionDirection) + const double _beltSpeed, const math::Vector3d &_beltDirection, + const math::Vector3d &_frictionDirection) { // the dot product is the cosine of the angle they // form (because both are unit vectors) @@ -553,11 +553,11 @@ double TrackControllerPrivate::ComputeSurfaceMotion( } ////////////////////////////////////////////////// -ignition::math::Vector3d TrackControllerPrivate::ComputeFrictionDirection( - const ignition::math::Vector3d &_centerOfRotation, - const ignition::math::Vector3d &_contactWorldPosition, - const ignition::math::Vector3d &_contactNormal, - const ignition::math::Vector3d &_beltDirection) +math::Vector3d TrackControllerPrivate::ComputeFrictionDirection( + const math::Vector3d &_centerOfRotation, + const math::Vector3d &_contactWorldPosition, + const math::Vector3d &_contactNormal, + const math::Vector3d &_beltDirection) { if (_centerOfRotation.IsFinite()) { @@ -614,7 +614,7 @@ void TrackControllerPrivate::OnCenterOfRotation(const msgs::Vector3d& _msg) } IGNITION_ADD_PLUGIN(TrackController, - ignition::gazebo::System, + System, TrackController::ISystemConfigure, TrackController::ISystemPreUpdate) diff --git a/src/systems/tracked_vehicle/TrackedVehicle.cc b/src/systems/tracked_vehicle/TrackedVehicle.cc index e175d44329..4b3ecc64e6 100644 --- a/src/systems/tracked_vehicle/TrackedVehicle.cc +++ b/src/systems/tracked_vehicle/TrackedVehicle.cc @@ -60,25 +60,25 @@ class ignition::gazebo::systems::TrackedVehiclePrivate { /// \brief Callback for velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const msgs::Twist &_msg); /// \brief Callback for steering efficiency subscription /// \param[in] _msg Steering efficiency message - public: void OnSteeringEfficiency(const ignition::msgs::Double &_msg); + public: void OnSteeringEfficiency(const msgs::Double &_msg); /// \brief Update odometry and publish an odometry message. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateOdometry(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateOdometry(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -423,31 +423,31 @@ void TrackedVehicle::Configure(const Entity &_entity, { this->dataPtr->debugMarker.set_ns( this->dataPtr->model.Name(_ecm) + "/cor"); - this->dataPtr->debugMarker.set_action(ignition::msgs::Marker::ADD_MODIFY); - this->dataPtr->debugMarker.set_type(ignition::msgs::Marker::SPHERE); - this->dataPtr->debugMarker.set_visibility(ignition::msgs::Marker::GUI); + this->dataPtr->debugMarker.set_action(msgs::Marker::ADD_MODIFY); + this->dataPtr->debugMarker.set_type(msgs::Marker::SPHERE); + this->dataPtr->debugMarker.set_visibility(msgs::Marker::GUI); this->dataPtr->debugMarker.mutable_lifetime()->set_sec(0); this->dataPtr->debugMarker.mutable_lifetime()->set_nsec(4000000); this->dataPtr->debugMarker.set_id(1); // Set material properties - ignition::msgs::Set( + msgs::Set( this->dataPtr->debugMarker.mutable_material()->mutable_ambient(), - ignition::math::Color(0, 0, 1, 1)); - ignition::msgs::Set( + math::Color(0, 0, 1, 1)); + msgs::Set( this->dataPtr->debugMarker.mutable_material()->mutable_diffuse(), - ignition::math::Color(0, 0, 1, 1)); + math::Color(0, 0, 1, 1)); // Set marker scale - ignition::msgs::Set( + msgs::Set( this->dataPtr->debugMarker.mutable_scale(), - ignition::math::Vector3d(0.1, 0.1, 0.1)); + math::Vector3d(0.1, 0.1, 0.1)); } } ////////////////////////////////////////////////// -void TrackedVehicle::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void TrackedVehicle::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("TrackedVehicle::PreUpdate"); @@ -546,8 +546,8 @@ void TrackedVehicle::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void TrackedVehiclePrivate::UpdateOdometry( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("TrackedVehicle::UpdateOdometry"); // Initialize, if not already initialized. @@ -629,8 +629,8 @@ void TrackedVehiclePrivate::UpdateOdometry( ////////////////////////////////////////////////// void TrackedVehiclePrivate::UpdateVelocity( - const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { IGN_PROFILE("TrackedVehicle::UpdateVelocity"); @@ -702,7 +702,7 @@ void TrackedVehiclePrivate::UpdateVelocity( const auto bodyPose = worldPose(this->bodyLink, _ecm); const auto bodyYAxisGlobal = - bodyPose.Rot().RotateVector(ignition::math::Vector3d(0, 1, 0)); + bodyPose.Rot().RotateVector(math::Vector3d(0, 1, 0)); // centerOfRotation may be +inf this->centerOfRotation = (bodyYAxisGlobal * desiredRotationRadiusSigned) + bodyPose.Pos(); @@ -742,7 +742,7 @@ void TrackedVehiclePrivate::UpdateVelocity( << ", right v=" << this->rightSpeed << (sendCommandsToTracks ? " (sent to tracks)" : "") << std::endl; - ignition::msgs::Set(this->debugMarker.mutable_pose(), math::Pose3d( + msgs::Set(this->debugMarker.mutable_pose(), math::Pose3d( this->centerOfRotation.X(), this->centerOfRotation.Y(), this->centerOfRotation.Z(), @@ -761,7 +761,7 @@ void TrackedVehiclePrivate::OnCmdVel(const msgs::Twist &_msg) ////////////////////////////////////////////////// void TrackedVehiclePrivate::OnSteeringEfficiency( - const ignition::msgs::Double& _msg) + const msgs::Double& _msg) { std::lock_guard lock(this->mutex); this->steeringEfficiency = _msg.data(); @@ -769,7 +769,7 @@ void TrackedVehiclePrivate::OnSteeringEfficiency( } IGNITION_ADD_PLUGIN(TrackedVehicle, - ignition::gazebo::System, + System, TrackedVehicle::ISystemConfigure, TrackedVehicle::ISystemPreUpdate, TrackedVehicle::ISystemPostUpdate) diff --git a/src/systems/triggered_publisher/TriggeredPublisher.cc b/src/systems/triggered_publisher/TriggeredPublisher.cc index cc7a4f88ad..6544754098 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.cc +++ b/src/systems/triggered_publisher/TriggeredPublisher.cc @@ -855,7 +855,7 @@ bool TriggeredPublisher::MatchInput(const transport::ProtoMsg &_inputMsg) } IGNITION_ADD_PLUGIN(TriggeredPublisher, - ignition::gazebo::System, + System, TriggeredPublisher::ISystemConfigure, TriggeredPublisher::ISystemPreUpdate) diff --git a/src/systems/velocity_control/VelocityControl.cc b/src/systems/velocity_control/VelocityControl.cc index 8082c39716..46b418de6c 100644 --- a/src/systems/velocity_control/VelocityControl.cc +++ b/src/systems/velocity_control/VelocityControl.cc @@ -41,26 +41,26 @@ class ignition::gazebo::systems::VelocityControlPrivate { /// \brief Callback for model velocity subscription /// \param[in] _msg Velocity message - public: void OnCmdVel(const ignition::msgs::Twist &_msg); + public: void OnCmdVel(const msgs::Twist &_msg); /// \brief Callback for link velocity subscription /// \param[in] _msg Velocity message - public: void OnLinkCmdVel(const ignition::msgs::Twist &_msg, - const ignition::transport::MessageInfo &_info); + public: void OnLinkCmdVel(const msgs::Twist &_msg, + const transport::MessageInfo &_info); /// \brief Update the linear and angular velocities. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateVelocity(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Update link velocity. /// \param[in] _info System update information. /// \param[in] _ecm The EntityComponentManager of the given simulation /// instance. - public: void UpdateLinkVelocity(const ignition::gazebo::UpdateInfo &_info, - const ignition::gazebo::EntityComponentManager &_ecm); + public: void UpdateLinkVelocity(const UpdateInfo &_info, + const EntityComponentManager &_ecm); /// \brief Ignition communication node. public: transport::Node node; @@ -180,8 +180,8 @@ void VelocityControl::Configure(const Entity &_entity, } ////////////////////////////////////////////////// -void VelocityControl::PreUpdate(const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) +void VelocityControl::PreUpdate(const UpdateInfo &_info, + EntityComponentManager &_ecm) { IGN_PROFILE("VelocityControl::PreUpdate"); @@ -324,8 +324,8 @@ void VelocityControl::PostUpdate(const UpdateInfo &_info, ////////////////////////////////////////////////// void VelocityControlPrivate::UpdateVelocity( - const ignition::gazebo::UpdateInfo &/*_info*/, - const ignition::gazebo::EntityComponentManager &/*_ecm*/) + const UpdateInfo &/*_info*/, + const EntityComponentManager &/*_ecm*/) { IGN_PROFILE("VeocityControl::UpdateVelocity"); @@ -336,8 +336,8 @@ void VelocityControlPrivate::UpdateVelocity( ////////////////////////////////////////////////// void VelocityControlPrivate::UpdateLinkVelocity( - const ignition::gazebo::UpdateInfo &/*_info*/, - const ignition::gazebo::EntityComponentManager &/*_ecm*/) + const UpdateInfo &/*_info*/, + const EntityComponentManager &/*_ecm*/) { IGN_PROFILE("VelocityControl::UpdateLinkVelocity"); @@ -375,7 +375,7 @@ void VelocityControlPrivate::OnLinkCmdVel(const msgs::Twist &_msg, } IGNITION_ADD_PLUGIN(VelocityControl, - ignition::gazebo::System, + System, VelocityControl::ISystemConfigure, VelocityControl::ISystemPreUpdate, VelocityControl::ISystemPostUpdate) diff --git a/src/systems/wheel_slip/WheelSlip.cc b/src/systems/wheel_slip/WheelSlip.cc index 78385295de..343ee82837 100644 --- a/src/systems/wheel_slip/WheelSlip.cc +++ b/src/systems/wheel_slip/WheelSlip.cc @@ -386,7 +386,7 @@ void WheelSlip::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) } IGNITION_ADD_PLUGIN(WheelSlip, - ignition::gazebo::System, + System, WheelSlip::ISystemConfigure, WheelSlip::ISystemPreUpdate) diff --git a/src/systems/wind_effects/WindEffects.cc b/src/systems/wind_effects/WindEffects.cc index 39eee5e760..47db52bf2f 100644 --- a/src/systems/wind_effects/WindEffects.cc +++ b/src/systems/wind_effects/WindEffects.cc @@ -392,7 +392,7 @@ void WindEffectsPrivate::UpdateWindVelocity(const UpdateInfo &_info, direction = this->noiseDirection->Apply(direction); // Apply wind velocity - ignition::math::Vector3d windVel; + math::Vector3d windVel; windVel.X(magnitude * std::cos(IGN_DTOR(direction))); windVel.Y(magnitude * std::sin(IGN_DTOR(direction))); diff --git a/test/integration/ackermann_steering_system.cc b/test/integration/ackermann_steering_system.cc index c21884589f..e18cff38b5 100644 --- a/test/integration/ackermann_steering_system.cc +++ b/test/integration/ackermann_steering_system.cc @@ -64,8 +64,8 @@ class AckermannSteeringTest test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), @@ -125,8 +125,8 @@ class AckermannSteeringTest const double desiredLinVel = 10.5; const double desiredAngVel = 0.1; velocityRamp.OnPreUpdate( - [&](const gazebo::UpdateInfo &/*_info*/, - const gazebo::EntityComponentManager &) + [&](const UpdateInfo &/*_info*/, + const EntityComponentManager &) { msgs::Set(msg.mutable_linear(), math::Vector3d(desiredLinVel, 0, 0)); @@ -232,8 +232,8 @@ TEST_P(AckermannSteeringTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SkidPublishCmd)) test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), @@ -330,8 +330,8 @@ TEST_P(AckermannSteeringTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TfPublishes)) test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), diff --git a/test/integration/air_pressure_system.cc b/test/integration/air_pressure_system.cc index 3db386e4d0..4e2644e2a1 100644 --- a/test/integration/air_pressure_system.cc +++ b/test/integration/air_pressure_system.cc @@ -64,11 +64,11 @@ TEST_F(AirPressureTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(AirPressure)) // Create a system that checks sensor topic test::Relay testSystem; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::AirPressureSensor *, const components::Name *_name) -> bool { diff --git a/test/integration/altimeter_system.cc b/test/integration/altimeter_system.cc index 979fafc37b..a536f0e794 100644 --- a/test/integration/altimeter_system.cc +++ b/test/integration/altimeter_system.cc @@ -83,13 +83,13 @@ TEST_F(AltimeterTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(ModelFalling)) test::Relay testSystem; std::vector poses; std::vector velocities; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Altimeter *, const components::Name *_name, const components::WorldPose *_worldPose, diff --git a/test/integration/apply_joint_force_system.cc b/test/integration/apply_joint_force_system.cc index e1b28c54b9..25c9011a17 100644 --- a/test/integration/apply_joint_force_system.cc +++ b/test/integration/apply_joint_force_system.cc @@ -72,7 +72,7 @@ TEST_F(ApplyJointForceTestFixture, test::Relay testSystem; std::vector jointForceCmd; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { auto joint = _ecm.EntityByComponents(components::Joint(), components::Name(jointName)); diff --git a/test/integration/battery_plugin.cc b/test/integration/battery_plugin.cc index 15e130fb65..b6e3ed9fd7 100644 --- a/test/integration/battery_plugin.cc +++ b/test/integration/battery_plugin.cc @@ -60,15 +60,15 @@ class BatteryPluginTest : public InternalFixture<::testing::Test> EXPECT_TRUE(plugin.has_value()); this->systemPtr = plugin.value(); - this->mockSystem = static_cast( - systemPtr->QueryInterface()); + this->mockSystem = static_cast( + systemPtr->QueryInterface()); EXPECT_NE(nullptr, this->mockSystem); } - public: ignition::gazebo::SystemPluginPtr systemPtr; - public: gazebo::MockSystem *mockSystem; + public: SystemPluginPtr systemPtr; + public: MockSystem *mockSystem; - private: gazebo::SystemLoader sm; + private: SystemLoader sm; }; @@ -87,9 +87,9 @@ TEST_F(BatteryPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SingleBattery)) serverConfig.SetSdfFile(sdfPath); // A pointer to the ecm. This will be valid once we run the mock system - gazebo::EntityComponentManager *ecm = nullptr; + EntityComponentManager *ecm = nullptr; this->mockSystem->preUpdateCallback = - [&ecm](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&ecm](const UpdateInfo &, EntityComponentManager &_ecm) { ecm = &_ecm; @@ -111,7 +111,7 @@ TEST_F(BatteryPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SingleBattery)) // the LinearBatteryPlugin is not zero when created. If // components::BatterySoC is zero on start, then the Physics plugin // can disable a joint. This in turn can prevent the joint from - // rotating. See https://github.com/ignitionrobotics/ign-gazebo/issues/55 + // rotating. See https://github.com/gazebosim/gz-sim/issues/55 EXPECT_GT(batComp->Data(), 0); }; diff --git a/test/integration/breadcrumbs.cc b/test/integration/breadcrumbs.cc index 17624884f4..5530b64d56 100644 --- a/test/integration/breadcrumbs.cc +++ b/test/integration/breadcrumbs.cc @@ -147,8 +147,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeployAtOffset)) node.Advertise("/model/vehicle_blue/breadcrumbs/B1/deploy"); std::size_t iterTestStart = 1000; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Start moving the vehicle // After 1000 iterations, stop the vehicle, spawn a breadcrumb @@ -212,8 +212,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(MaxDeployments)) node.Advertise("/model/vehicle_blue/breadcrumbs/B1/deploy"); std::size_t iterTestStart = 1000; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Start moving the vehicle // Every 1000 iterations, deploy @@ -270,8 +270,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(FuelDeploy)) const std::size_t nIters = iterTestStart + 2500; const std::size_t maxDeployments = 5; std::size_t deployCount = 0; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Start moving the vehicle // Every 500 iterations, deploy @@ -324,8 +324,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Performer)) const std::size_t nIters = iterTestStart + 10000; std::optional initialPose; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Deploy a performer breadcrumb on a tile that's on a level, and ensure // that it keeps the tile from being unloaded. @@ -397,8 +397,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PerformerSetVolume)) const std::size_t nIters = iterTestStart + 2000; std::optional initialPose; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Deploy a performer breadcrumb on a tile that's on the default a level, // and check that it causes tile_1 to be loaded since the performer's volume @@ -450,8 +450,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeployDisablePhysics)) node.Advertise("/model/vehicle_blue/breadcrumbs/B2/deploy"); std::size_t iterTestStart = 1000; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Start moving the vehicle // After 1000 iterations, stop the vehicle, spawn a breadcrumb @@ -551,7 +551,7 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(AllowRenaming)) ///////////////////////////////////////////////// /// Return a list of model entities whose names match the given regex std::vector ModelsByNameRegex( - const gazebo::EntityComponentManager &_ecm, const std::regex &_re) + const EntityComponentManager &_ecm, const std::regex &_re) { std::vector entities; _ecm.Each( @@ -586,8 +586,8 @@ TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelLoadUnload)) std::regex reTile1{"tile_1"}; std::regex reBreadcrumb{"B1_.*"}; testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Ensure that tile_1 is loaded at the start, deploy a breadcrumb if (_info.iterations == iterTestStart) diff --git a/test/integration/buoyancy.cc b/test/integration/buoyancy.cc index 8713c1087f..41456aa412 100644 --- a/test/integration/buoyancy.cc +++ b/test/integration/buoyancy.cc @@ -181,8 +181,8 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) bool finished = false; test::Relay testSystem; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Check pose Entity submarine = _ecm.EntityByComponents( @@ -217,7 +217,7 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) auto submarineCenterOfVolume = _ecm.Component(submarineLink); ASSERT_NE(submarineCenterOfVolume, nullptr); - EXPECT_EQ(ignition::math::Vector3d(0, 0, 0), + EXPECT_EQ(math::Vector3d(0, 0, 0), submarineCenterOfVolume->Data()); // Get the submarine buoyant link @@ -235,7 +235,7 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) auto submarineBuoyantCenterOfVolume = _ecm.Component(submarineBuoyantLink); ASSERT_NE(submarineBuoyantCenterOfVolume, nullptr); - EXPECT_EQ(ignition::math::Vector3d(0, 0, 0), + EXPECT_EQ(math::Vector3d(0, 0, 0), submarineBuoyantCenterOfVolume->Data()); // Get the submarine sinking link @@ -253,7 +253,7 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) auto submarineSinkingCenterOfVolume = _ecm.Component(submarineSinkingLink); ASSERT_NE(submarineSinkingCenterOfVolume, nullptr); - EXPECT_EQ(ignition::math::Vector3d(0, 0, 0), + EXPECT_EQ(math::Vector3d(0, 0, 0), submarineSinkingCenterOfVolume->Data()); // Get the duck link @@ -269,7 +269,7 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) auto duckCenterOfVolume = _ecm.Component(duckLink); ASSERT_NE(duckCenterOfVolume, nullptr); - EXPECT_EQ(ignition::math::Vector3d(0, 0, -0.4), + EXPECT_EQ(math::Vector3d(0, 0, -0.4), duckCenterOfVolume->Data()); auto submarinePose = _ecm.Component(submarine); @@ -464,8 +464,8 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OffsetAndRotation)) std::size_t iterations{0}; fixture.OnPostUpdate([&]( - const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, + const EntityComponentManager &_ecm) { // Get links auto noOffsets = entitiesFromScopedName("no_offset::link", _ecm); diff --git a/test/integration/camera_video_record_system.cc b/test/integration/camera_video_record_system.cc index e21b71fc98..13396cb3df 100644 --- a/test/integration/camera_video_record_system.cc +++ b/test/integration/camera_video_record_system.cc @@ -51,7 +51,7 @@ TEST_F(CameraVideoRecorderTest, IGN_UTILS_TEST_DISABLED_ON_MAC(RecordVideo)) // Run server server.Run(true, 1, false); - ignition::transport::Node node; + transport::Node node; std::vector services; bool hasService = false; @@ -75,8 +75,8 @@ TEST_F(CameraVideoRecorderTest, IGN_UTILS_TEST_DISABLED_ON_MAC(RecordVideo)) } EXPECT_TRUE(hasService); - ignition::msgs::VideoRecord videoRecordMsg; - ignition::msgs::Boolean res; + msgs::VideoRecord videoRecordMsg; + msgs::Boolean res; bool result = false; unsigned int timeout = 5000; diff --git a/test/integration/components.cc b/test/integration/components.cc index 93a507e83e..6393eacc66 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -120,7 +120,7 @@ TEST_F(ComponentsTest, Actor) comp3.Deserialize(istr); EXPECT_EQ("abc", comp3.Data().Name()); EXPECT_EQ("def", comp3.Data().SkinFilename()); - EXPECT_EQ(ignition::math::Pose3d(3, 2, 1, 0, 0, 0), comp3.Data().RawPose()); + EXPECT_EQ(math::Pose3d(3, 2, 1, 0, 0, 0), comp3.Data().RawPose()); } ///////////////////////////////////////////////// @@ -183,7 +183,7 @@ TEST_F(ComponentsTest, AirPressureSensor) sdf::Sensor data1; data1.SetName("abc"); data1.SetType(sdf::SensorType::AIR_PRESSURE); - data1.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + data1.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::AirPressure airPressure1; data1.SetAirPressureSensor(airPressure1); @@ -211,7 +211,7 @@ TEST_F(ComponentsTest, AirPressureSensor) comp3.Deserialize(istr); EXPECT_EQ("abc", comp3.Data().Name()); EXPECT_EQ(sdf::SensorType::AIR_PRESSURE, comp3.Data().Type()); - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); + EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); } ///////////////////////////////////////////////// @@ -474,7 +474,7 @@ TEST_F(ComponentsTest, Imu) data1.SetType(sdf::SensorType::IMU); data1.SetUpdateRate(100); data1.SetTopic("imu_data"); - data1.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + data1.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::Imu imu1; data1.SetImuSensor(imu1); @@ -505,7 +505,7 @@ TEST_F(ComponentsTest, Imu) EXPECT_EQ(sdf::SensorType::IMU, comp3.Data().Type()); EXPECT_EQ("imu_data", comp3.Data().Topic()); EXPECT_DOUBLE_EQ(100, comp3.Data().UpdateRate()); - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); + EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); } ///////////////////////////////////////////////// @@ -1100,7 +1100,7 @@ TEST_F(ComponentsTest, Magnetometer) data1.SetType(sdf::SensorType::MAGNETOMETER); data1.SetUpdateRate(12.4); data1.SetTopic("grape"); - data1.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + data1.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0)); sdf::Magnetometer mag1; data1.SetMagnetometerSensor(mag1); @@ -1130,7 +1130,7 @@ TEST_F(ComponentsTest, Magnetometer) EXPECT_EQ(sdf::SensorType::MAGNETOMETER, comp3.Data().Type()); EXPECT_EQ("grape", comp3.Data().Topic()); EXPECT_DOUBLE_EQ(12.4, comp3.Data().UpdateRate()); - EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); + EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), comp3.Data().RawPose()); } ///////////////////////////////////////////////// diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc index b05d0db4ec..3e36c0013f 100644 --- a/test/integration/depth_camera.cc +++ b/test/integration/depth_camera.cc @@ -104,9 +104,9 @@ TEST_F(DepthCameraTest, IGN_UTILS_TEST_DISABLED_ON_MAC(DepthCameraBox)) // Lock access to buffer and don't release it mutex.lock(); - EXPECT_DOUBLE_EQ(depthBuffer[left], ignition::math::INF_D); + EXPECT_DOUBLE_EQ(depthBuffer[left], math::INF_D); EXPECT_NEAR(depthBuffer[mid], expectedRangeAtMidPointBox1, DEPTH_TOL); - EXPECT_DOUBLE_EQ(depthBuffer[right], ignition::math::INF_D); + EXPECT_DOUBLE_EQ(depthBuffer[right], math::INF_D); delete[] depthBuffer; } diff --git a/test/integration/detachable_joint.cc b/test/integration/detachable_joint.cc index 02005b0ae0..f17d636f22 100644 --- a/test/integration/detachable_joint.cc +++ b/test/integration/detachable_joint.cc @@ -71,8 +71,8 @@ TEST_F(DetachableJointTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StartConnected)) auto poseRecorder = [](const std::string &_modelName, std::vector &_poses) { - return [&, _modelName](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + return [&, _modelName](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &_entity, const components::Model *, @@ -149,8 +149,8 @@ TEST_F(DetachableJointTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LinksInSameModel)) auto poseRecorder = [](const std::string &_linkName, std::vector &_poses) { - return [&, _linkName](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + return [&, _linkName](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &_entity, const components::Link *, diff --git a/test/integration/diff_drive_system.cc b/test/integration/diff_drive_system.cc index 51d1b5b330..882683d10b 100644 --- a/test/integration/diff_drive_system.cc +++ b/test/integration/diff_drive_system.cc @@ -65,8 +65,8 @@ class DiffDriveTest : public InternalFixture<::testing::TestWithParam> test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), @@ -128,8 +128,8 @@ class DiffDriveTest : public InternalFixture<::testing::TestWithParam> double desiredLinVel = movementDirection * 10.5; double desiredAngVel = 0.2; velocityRamp.OnPreUpdate( - [&](const gazebo::UpdateInfo &/*_info*/, - const gazebo::EntityComponentManager &) + [&](const UpdateInfo &/*_info*/, + const EntityComponentManager &) { msgs::Set(msg.mutable_linear(), math::Vector3d(desiredLinVel, 0, 0)); @@ -249,8 +249,8 @@ TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SkidPublishCmd)) test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), @@ -351,8 +351,8 @@ TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(EnableDisableCmd)) test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), diff --git a/test/integration/each_new_removed.cc b/test/integration/each_new_removed.cc index 353b4080bc..5c2777aadd 100644 --- a/test/integration/each_new_removed.cc +++ b/test/integration/each_new_removed.cc @@ -49,7 +49,7 @@ class EachNewRemovedFixture : public InternalFixture<::testing::Test> TEST_F(EachNewRemovedFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(EachNewEachRemovedInSystem)) { - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; gazebo::Server server; diff --git a/test/integration/elevator_system.cc b/test/integration/elevator_system.cc index ab5aa80304..5889143bb5 100644 --- a/test/integration/elevator_system.cc +++ b/test/integration/elevator_system.cc @@ -40,7 +40,7 @@ class ElevatorTestFixture : public ::testing::Test // Documentation inherited protected: void SetUp() override { - ignition::common::Console::SetVerbosity(4); + common::Console::SetVerbosity(4); setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); } diff --git a/test/integration/entity_erase.cc b/test/integration/entity_erase.cc index 7bab7a0908..cd1118ae6e 100644 --- a/test/integration/entity_erase.cc +++ b/test/integration/entity_erase.cc @@ -38,12 +38,12 @@ class PhysicsSystemFixture : public InternalFixture<::testing::Test> TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CreatePhysicsWorld)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + Server server(serverConfig); EXPECT_TRUE(server.HasEntity("box")); EXPECT_TRUE(server.HasEntity("capsule")); EXPECT_TRUE(server.HasEntity("cylinder")); diff --git a/test/integration/examples_build.cc b/test/integration/examples_build.cc index c6376de6cb..2868b6b704 100644 --- a/test/integration/examples_build.cc +++ b/test/integration/examples_build.cc @@ -28,7 +28,7 @@ #include "../helpers/EnvTestFixture.hh" // File copied from -// https://github.com/ignitionrobotics/ign-gui/raw/ign-gui3/test/integration/ExamplesBuild_TEST.cc +// https://github.com/gazebosim/gz-gui/raw/ign-gui3/test/integration/ExamplesBuild_TEST.cc using namespace ignition; @@ -138,14 +138,14 @@ void ExamplesBuild::Build(const std::string &_type) // Path to examples of the given type auto examplesDir = std::string(PROJECT_SOURCE_PATH) + "/examples/" + _type; - ASSERT_TRUE(ignition::common::exists(examplesDir)); + ASSERT_TRUE(common::exists(examplesDir)); // Iterate over directory - ignition::common::DirIter endIter; - for (ignition::common::DirIter dirIter(examplesDir); + common::DirIter endIter; + for (common::DirIter dirIter(examplesDir); dirIter != endIter; ++dirIter) { - auto base = ignition::common::basename(*dirIter); + auto base = common::basename(*dirIter); math::SemanticVersion cmakeVersion{std::string(CMAKE_VERSION)}; if (cmakeVersion < math::SemanticVersion(3, 11, 0) && @@ -161,13 +161,13 @@ void ExamplesBuild::Build(const std::string &_type) // Source directory for this example auto sourceDir = examplesDir; sourceDir += "/" + base; - ASSERT_TRUE(ignition::common::exists(sourceDir)); + ASSERT_TRUE(common::exists(sourceDir)); igndbg << "Source: " << sourceDir << std::endl; // Create a temp build directory std::string tmpBuildDir; ASSERT_TRUE(createAndSwitchToTempDir(tmpBuildDir)); - EXPECT_TRUE(ignition::common::exists(tmpBuildDir)); + EXPECT_TRUE(common::exists(tmpBuildDir)); igndbg << "Build directory: " << tmpBuildDir<< std::endl; char cmd[1024]; diff --git a/test/integration/gpu_lidar.cc b/test/integration/gpu_lidar.cc index a1f3368a43..8597db0348 100644 --- a/test/integration/gpu_lidar.cc +++ b/test/integration/gpu_lidar.cc @@ -100,9 +100,9 @@ TEST_F(GpuLidarTest, IGN_UTILS_TEST_DISABLED_ON_MAC(GpuLidarBox)) double expectedRangeAtMidPointBox1 = 0.45; // Sensor 1 should see TestBox1 - EXPECT_DOUBLE_EQ(lastMsg.ranges(0), ignition::math::INF_D); + EXPECT_DOUBLE_EQ(lastMsg.ranges(0), math::INF_D); EXPECT_NEAR(lastMsg.ranges(mid), expectedRangeAtMidPointBox1, LASER_TOL); - EXPECT_DOUBLE_EQ(lastMsg.ranges(last), ignition::math::INF_D); + EXPECT_DOUBLE_EQ(lastMsg.ranges(last), math::INF_D); EXPECT_EQ("gpu_lidar::gpu_lidar_link::gpu_lidar", lastMsg.frame()); } diff --git a/test/integration/imu_system.cc b/test/integration/imu_system.cc index 2a21938e12..6c912f9d3d 100644 --- a/test/integration/imu_system.cc +++ b/test/integration/imu_system.cc @@ -136,15 +136,15 @@ TEST_F(ImuTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelFalling)) std::vector poses; std::vector accelerations; std::vector angularVelocities; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Imu *, const components::Name *_name, const components::WorldPose *_worldPose, @@ -175,7 +175,7 @@ TEST_F(ImuTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelFalling)) }); _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Gravity *_gravity) -> bool { // gtest is having a hard time with ASSERTs inside nested lambdas diff --git a/test/integration/joint_controller_system.cc b/test/integration/joint_controller_system.cc index f14a798f73..402b1d3af8 100644 --- a/test/integration/joint_controller_system.cc +++ b/test/integration/joint_controller_system.cc @@ -70,7 +70,7 @@ TEST_F(JointControllerTestFixture, test::Relay testSystem; std::vector angularVelocities; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { auto link = _ecm.EntityByComponents(components::Link(), components::Name(linkName)); @@ -82,12 +82,12 @@ TEST_F(JointControllerTestFixture, } }); - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Link *, const components::Name *_name, const components::AngularVelocity *_angularVel) -> bool @@ -168,7 +168,7 @@ TEST_F(JointControllerTestFixture, test::Relay testSystem; math::Vector3d angularVelocity; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { auto link = _ecm.EntityByComponents(components::Link(), components::Name(linkName)); @@ -180,12 +180,12 @@ TEST_F(JointControllerTestFixture, } }); - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Link *, const components::Name *_name, const components::AngularVelocity *_angularVel) -> bool diff --git a/test/integration/joint_position_controller_system.cc b/test/integration/joint_position_controller_system.cc index 7e6f4e4afa..b679799a5b 100644 --- a/test/integration/joint_position_controller_system.cc +++ b/test/integration/joint_position_controller_system.cc @@ -71,7 +71,7 @@ TEST_F(JointPositionControllerTestFixture, test::Relay testSystem; std::vector currentPosition; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { auto joint = _ecm.EntityByComponents(components::Joint(), components::Name(jointName)); @@ -83,12 +83,12 @@ TEST_F(JointPositionControllerTestFixture, } }); - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointPosition *_position) -> bool diff --git a/test/integration/level_manager.cc b/test/integration/level_manager.cc index 5e3466943b..cc40b3e561 100644 --- a/test/integration/level_manager.cc +++ b/test/integration/level_manager.cc @@ -73,15 +73,15 @@ class ModelMover: public test::Relay poseCmd = std::move(_pose); } - public: gazebo::Entity Id() const + public: Entity Id() const { return entity; } /// \brief Sets the pose component of the entity to the commanded pose. This /// function meant to be called in the preupdate phase - private: void MoveModel(const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + private: void MoveModel(const UpdateInfo &, + EntityComponentManager &_ecm) { if (this->poseCmd) { @@ -93,7 +93,7 @@ class ModelMover: public test::Relay /// \brief Entity to move - private: gazebo::Entity entity; + private: Entity entity; /// \brief Pose command private: std::optional poseCmd; }; @@ -106,7 +106,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> { InternalFixture::SetUp(); - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; // Except tile_0, which is on the default level, every tile belongs to a // level. The name of the level corresponds to the tile in its suffix, i.e., @@ -116,12 +116,12 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> serverConfig.SetUseLevels(true); EXPECT_EQ(nullptr, this->server); - this->server = std::make_unique(serverConfig); + this->server = std::make_unique(serverConfig); test::Relay testSystem; // Check entities loaded on the default level - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &, const components::Model *, @@ -170,7 +170,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> this->server->Run(true, 1, false); } - public: std::unique_ptr server; + public: std::unique_ptr server; public: std::vector loadedModels; public: std::vector unloadedModels; public: std::vector loadedLights; @@ -187,8 +187,8 @@ TEST_F(LevelManagerFixture, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(DefaultLevel)) test::Relay recorder; // Check entities loaded on the default level - recorder.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + recorder.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &, const components::DefaultLevel *, diff --git a/test/integration/level_manager_runtime_performers.cc b/test/integration/level_manager_runtime_performers.cc index 68ef368ee7..db317d4408 100644 --- a/test/integration/level_manager_runtime_performers.cc +++ b/test/integration/level_manager_runtime_performers.cc @@ -70,15 +70,15 @@ class ModelMover: public test::Relay poseCmd = std::move(_pose); } - public: gazebo::Entity Id() const + public: Entity Id() const { return entity; } /// \brief Sets the pose component of the entity to the commanded pose. This /// function meant to be called in the preupdate phase - private: void MoveModel(const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + private: void MoveModel(const UpdateInfo &, + EntityComponentManager &_ecm) { if (this->poseCmd) { @@ -90,7 +90,7 @@ class ModelMover: public test::Relay /// \brief Entity to move - private: gazebo::Entity entity; + private: Entity entity; /// \brief Pose command private: std::optional poseCmd; }; @@ -103,7 +103,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> { InternalFixture::SetUp(); - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; // Except tile_0, which is on the default level, every tile belongs to a // level. The name of the level corresponds to the tile in its suffix, i.e., @@ -112,7 +112,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> "/test/worlds/levels_no_performers.sdf"); serverConfig.SetUseLevels(true); - server = std::make_unique(serverConfig); + server = std::make_unique(serverConfig); // Add in the "box" performer using a service call transport::Node node; @@ -145,8 +145,8 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> test::Relay testSystem; // Check entities loaded on the default level - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { Entity sphere = _ecm.EntityByComponents(components::Name("sphere")); EXPECT_EQ(1u, @@ -198,7 +198,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> this->server->Run(true, 1, false); } - public: std::unique_ptr server; + public: std::unique_ptr server; public: std::vector loadedModels; public: std::vector unloadedModels; public: std::vector loadedLights; @@ -214,8 +214,8 @@ TEST_F(LevelManagerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultLevel)) test::Relay recorder; // Check entities loaded on the default level - recorder.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + recorder.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &, const components::DefaultLevel *, diff --git a/test/integration/lift_drag_system.cc b/test/integration/lift_drag_system.cc index 75d1b2ddc2..4a0d439ec0 100644 --- a/test/integration/lift_drag_system.cc +++ b/test/integration/lift_drag_system.cc @@ -110,7 +110,7 @@ TEST_P(VerticalForceParamFixture, std::vector linearVelocities; std::vector forces; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { // Create velocity and acceleration components if they dont't exist. // This signals physics system to populate the component @@ -130,7 +130,7 @@ TEST_P(VerticalForceParamFixture, const double kp = 100.0; // Set a constant velocity to the prismatic joint testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { auto joint = _ecm.EntityByComponents(components::Joint(), components::Name(jointName)); @@ -161,8 +161,8 @@ TEST_P(VerticalForceParamFixture, // drag system. This is needed to capture the wrench set by the lift drag // system. This assumption may not hold when systems are run in parallel. test::Relay wrenchRecorder; - wrenchRecorder.OnPreUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + wrenchRecorder.OnPreUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto bladeLink = firstEntityFromScopedName(bladeName, _ecm); auto bodyLink = firstEntityFromScopedName(bodyName, _ecm); diff --git a/test/integration/log_system.cc b/test/integration/log_system.cc index 9177378dc0..325b7c2988 100644 --- a/test/integration/log_system.cc +++ b/test/integration/log_system.cc @@ -330,7 +330,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogDefaults)) std::string homeOrig; common::env(IGN_HOMEDIR, homeOrig); std::string homeFake = common::joinPaths(this->logsDir, "default"); - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeFake.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeFake.c_str())); // Test case 1: // No path specified on command line. This does not go through @@ -417,7 +417,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogDefaults)) #endif // Revert environment variable after test is done - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeOrig.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeOrig.c_str())); } ///////////////////////////////////////////////// @@ -473,7 +473,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogPaths)) std::string homeOrig; common::env(IGN_HOMEDIR, homeOrig); std::string homeFake = common::joinPaths(this->logsDir, "default"); - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeFake.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeFake.c_str())); // Store number of files before running auto logPath = common::joinPaths(homeFake.c_str(), ".ignition", "gazebo", @@ -686,7 +686,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogPaths)) #endif // Revert environment variable after test is done - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeOrig.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeOrig.c_str())); this->RemoveLogsDir(); } @@ -1089,7 +1089,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogOverwrite)) // ign gazebo. server_main.cc is deprecated and does not have overwrite // renaming implemented. So will always overwrite. Will not test (#) type of // renaming on OS X until ign gazebo is fixed: - // https://github.com/ignitionrobotics/ign-gazebo/issues/25 + // https://github.com/gazebosim/gz-sim/issues/25 // New log files were created EXPECT_TRUE(common::exists(this->logDir + "(1)")); @@ -1497,7 +1497,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogResources)) std::string homeOrig; common::env(IGN_HOMEDIR, homeOrig); std::string homeFake = common::joinPaths(this->logsDir, "default"); - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeFake.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeFake.c_str())); const std::string recordPath = this->logDir; std::string statePath = common::joinPaths(recordPath, "state.tlog"); @@ -1523,7 +1523,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogResources)) // Recorded models should exist EXPECT_GT(entryCount(recordPath), 2); EXPECT_TRUE(common::exists(common::joinPaths(recordPath, homeFake, - ".ignition", "fuel", "fuel.ignitionrobotics.org", "openrobotics", + ".ignition", "fuel", "fuel.gazebosim.org", "openrobotics", "models", "x2 config 1"))); // Remove artifacts. Recreate new directory @@ -1558,11 +1558,11 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogResources)) EXPECT_GT(entryCount(recordPath), 1); #endif EXPECT_TRUE(common::exists(common::joinPaths(recordPath, homeFake, - ".ignition", "fuel", "fuel.ignitionrobotics.org", "openrobotics", + ".ignition", "fuel", "fuel.gazebosim.org", "openrobotics", "models", "x2 config 1"))); // Revert environment variable after test is done - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeOrig.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeOrig.c_str())); // Remove artifacts this->RemoveLogsDir(); @@ -1584,7 +1584,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogTopics)) std::string homeOrig; common::env(IGN_HOMEDIR, homeOrig); std::string homeFake = common::joinPaths(this->logsDir, "default"); - EXPECT_TRUE(ignition::common::setenv(IGN_HOMEDIR, homeFake.c_str())); + EXPECT_TRUE(common::setenv(IGN_HOMEDIR, homeFake.c_str())); const std::string recordPath = this->logDir; std::string statePath = common::joinPaths(recordPath, "state.tlog"); diff --git a/test/integration/logical_audio_sensor_plugin.cc b/test/integration/logical_audio_sensor_plugin.cc index 741c7dcfb6..321afee8e1 100644 --- a/test/integration/logical_audio_sensor_plugin.cc +++ b/test/integration/logical_audio_sensor_plugin.cc @@ -65,10 +65,10 @@ TEST_F(LogicalAudioTest, EXPECT_FALSE(*server.Running(0)); // helper variables for checking the validity of the ECM - const ignition::math::Pose3d sourcePose(0, 0, 0, 0, 0, 0); + const math::Pose3d sourcePose(0, 0, 0, 0, 0, 0); const auto zeroSeconds = std::chrono::seconds(0); - const ignition::math::Pose3d micClosePose(0.5, 0, 0, 0, 0, 0); - const ignition::math::Pose3d micFarPose(0, 0, 0, 0, 0, 0); + const math::Pose3d micClosePose(0.5, 0, 0, 0, 0, 0); + const math::Pose3d micFarPose(0, 0, 0, 0, 0, 0); std::chrono::steady_clock::duration sourceStartTime; bool firstTime{true}; diff --git a/test/integration/logical_camera_system.cc b/test/integration/logical_camera_system.cc index e9716dc52c..b69291335b 100644 --- a/test/integration/logical_camera_system.cc +++ b/test/integration/logical_camera_system.cc @@ -93,11 +93,11 @@ TEST_F(LogicalCameraTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogicalCameraBox)) // Create a system that checks sensor topics test::Relay testSystem; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::LogicalCamera *, const components::Name *_name) -> bool { @@ -177,22 +177,22 @@ TEST_F(LogicalCameraTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogicalCameraBox)) math::Pose3d boxPose(1, 0, 0.5, 0, 0, 0); math::Pose3d sensor1Pose(0.05, 0.05, 0.55, 0, 0, 0); mutex.lock(); - ignition::msgs::LogicalCameraImage img1 = logicalCamera1Msgs.back(); - EXPECT_EQ(sensor1Pose, ignition::msgs::Convert(img1.pose())); + msgs::LogicalCameraImage img1 = logicalCamera1Msgs.back(); + EXPECT_EQ(sensor1Pose, msgs::Convert(img1.pose())); EXPECT_EQ(1, img1.model().size()); EXPECT_EQ(boxName, img1.model(0).name()); - ignition::math::Pose3d boxPoseCamera1Frame = boxPose - sensor1Pose; - EXPECT_EQ(boxPoseCamera1Frame, ignition::msgs::Convert(img1.model(0).pose())); + math::Pose3d boxPoseCamera1Frame = boxPose - sensor1Pose; + EXPECT_EQ(boxPoseCamera1Frame, msgs::Convert(img1.model(0).pose())); mutex.unlock(); // Sensor 2 should see box too - note different sensor pose. math::Pose3d sensor2Pose(0.05, -0.45, 0.55, 0, 0, 0); mutex.lock(); - ignition::msgs::LogicalCameraImage img2 = logicalCamera2Msgs.back(); - EXPECT_EQ(sensor2Pose, ignition::msgs::Convert(img2.pose())); + msgs::LogicalCameraImage img2 = logicalCamera2Msgs.back(); + EXPECT_EQ(sensor2Pose, msgs::Convert(img2.pose())); EXPECT_EQ(1, img2.model().size()); EXPECT_EQ(boxName, img2.model(0).name()); - ignition::math::Pose3d boxPoseCamera2Frame = boxPose - sensor2Pose; - EXPECT_EQ(boxPoseCamera2Frame, ignition::msgs::Convert(img2.model(0).pose())); + math::Pose3d boxPoseCamera2Frame = boxPose - sensor2Pose; + EXPECT_EQ(boxPoseCamera2Frame, msgs::Convert(img2.model(0).pose())); mutex.unlock(); } diff --git a/test/integration/magnetometer_system.cc b/test/integration/magnetometer_system.cc index 9c332f24ba..31a7f8b288 100644 --- a/test/integration/magnetometer_system.cc +++ b/test/integration/magnetometer_system.cc @@ -83,13 +83,13 @@ TEST_F(MagnetometerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(RotatedMagnetometer)) test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Magnetometer *, const components::Name *_name, const components::WorldPose *_worldPose) -> bool @@ -130,7 +130,7 @@ TEST_F(MagnetometerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(RotatedMagnetometer)) // Hardcoded SDF values math::Vector3d worldMagneticField(0.94, 0.76, -0.12); - ignition::math::Vector3d field = poses.back().Rot().Inverse().RotateVector( + math::Vector3d field = poses.back().Rot().Inverse().RotateVector( worldMagneticField); mutex.lock(); EXPECT_NEAR(magnetometerMsgs.back().mutable_field_tesla()->x(), diff --git a/test/integration/multicopter.cc b/test/integration/multicopter.cc index 669a2cfe47..79611ca6b9 100644 --- a/test/integration/multicopter.cc +++ b/test/integration/multicopter.cc @@ -82,7 +82,7 @@ TEST_F(MulticopterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(CommandedMotorSpeed)) const std::size_t iterTestStart{100}; const std::size_t nIters{500}; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &_info, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, EntityComponentManager &_ecm) { // Create components, if the don't exist, on the first iteration if (_info.iterations == 1) @@ -98,8 +98,8 @@ TEST_F(MulticopterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(CommandedMotorSpeed)) }); testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // Command a motor speed // After nIters iterations, check angular velocity of each of the rotors @@ -148,7 +148,7 @@ TEST_F(MulticopterTest, const std::size_t nIters{2000}; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &_info, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, EntityComponentManager &_ecm) { // Create components, if the don't exist, on the first iteration if (_info.iterations == 1) @@ -186,8 +186,8 @@ TEST_F(MulticopterTest, }; testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, + const EntityComponentManager &_ecm) { if (!iterTestStart.has_value()) { @@ -256,7 +256,7 @@ TEST_F(MulticopterTest, auto cmdVel = node.Advertise("/X3/gazebo/command/twist"); testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &_info, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &_info, EntityComponentManager &_ecm) { // Create components, if the don't exist, on the first iteration if (_info.iterations == 1) @@ -290,8 +290,8 @@ TEST_F(MulticopterTest, node.Advertise("/X3/gazebo/command/motor_speed"); testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, + const EntityComponentManager &_ecm) { // Publish a motor speed command { diff --git a/test/integration/network_handshake.cc b/test/integration/network_handshake.cc index 5d35984787..b828f2734c 100644 --- a/test/integration/network_handshake.cc +++ b/test/integration/network_handshake.cc @@ -45,8 +45,8 @@ uint64_t testPaused(bool _paused) bool paused = !_paused; uint64_t iterations = 0; - std::function cb = - [&](const ignition::msgs::WorldStatistics &_msg) + std::function cb = + [&](const msgs::WorldStatistics &_msg) { std::unique_lock lock(mutex); paused = _msg.paused(); @@ -148,7 +148,7 @@ TEST_F(NetworkHandshake, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Updates)) configPrimary.SetUseLevels(true); // Can only test one secondary running physics, because running 2 physics in // the same process causes a segfault, see - // https://github.com/ignitionrobotics/ign-gazebo/issues/18 + // https://github.com/gazebosim/gz-sim/issues/18 configPrimary.SetNetworkSecondaries(1); configPrimary.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/performers.sdf"); @@ -178,8 +178,8 @@ TEST_F(NetworkHandshake, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Updates)) // Subscribe to pose updates, which should come from the primary transport::Node node; std::vector zPos; - std::function cb = - [&](const ignition::msgs::Pose_V &_msg) + std::function cb = + [&](const msgs::Pose_V &_msg) { for (int i = 0; i < _msg.pose().size(); ++i) { diff --git a/test/integration/performer_detector.cc b/test/integration/performer_detector.cc index 63838697cd..b5d5e0784c 100644 --- a/test/integration/performer_detector.cc +++ b/test/integration/performer_detector.cc @@ -201,8 +201,8 @@ TEST_F(PerformerDetectorTest, auto server = this->StartServer("/test/worlds/performer_detector.sdf", true); test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &_info, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &_info, + EntityComponentManager &_ecm) { Entity vehicle = _ecm.EntityByComponents( components::Model(), components::Name("vehicle_blue")); diff --git a/test/integration/physics_system.cc b/test/integration/physics_system.cc index f2aff19a24..7730302e55 100644 --- a/test/integration/physics_system.cc +++ b/test/integration/physics_system.cc @@ -100,12 +100,12 @@ class PhysicsSystemFixtureWithDart6_10 : public PhysicsSystemFixture ///////////////////////////////////////////////// TEST_F(PhysicsSystemFixture, CreatePhysicsWorld) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); @@ -122,7 +122,7 @@ TEST_F(PhysicsSystemFixture, CreatePhysicsWorld) // See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(FallingObject)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/falling.sdf"; @@ -133,22 +133,22 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(FallingObject)) const sdf::World *world = root.WorldByIndex(0); const sdf::Model *model = world->ModelByIndex(0); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1us); const std::string modelName = "sphere"; - std::vector spherePoses; + std::vector spherePoses; // Create a system that records the poses of the sphere test::Relay testSystem; testSystem.OnPostUpdate( - [modelName, &spherePoses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [modelName, &spherePoses](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Model *, + [&](const Entity &, const components::Model *, const components::Name *_name, const components::Pose *_pose)->bool { if (_name->Data() == modelName) { @@ -191,7 +191,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(FallingObject)) // must be correct. TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/canonical.sdf"; @@ -203,7 +203,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1us); @@ -212,7 +212,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) const sdf::Model *model = world->ModelByIndex(0); - std::unordered_map expectedLinPoses; + std::unordered_map expectedLinPoses; for (auto &linkName : linksToCheck) expectedLinPoses[linkName] = model->LinkByName(linkName)->RawPose(); ASSERT_EQ(3u, expectedLinPoses.size()); @@ -220,14 +220,14 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) // Create a system that records the poses of the links after physics test::Relay testSystem; - std::unordered_map postUpLinkPoses; + std::unordered_map postUpLinkPoses; testSystem.OnPostUpdate( - [&modelName, &postUpLinkPoses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&modelName, &postUpLinkPoses](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Link *, + [&](const Entity &, const components::Link *, const components::Name *_name, const components::Pose *_pose, const components::ParentEntity *_parent)->bool { @@ -263,7 +263,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(NonDefaultCanonicalLink)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/nondefault_canonical.sdf"; @@ -275,7 +275,7 @@ TEST_F(PhysicsSystemFixture, serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); @@ -284,13 +284,13 @@ TEST_F(PhysicsSystemFixture, // Create a system that records the pose of the model. test::Relay testSystem; - std::vector modelPoses; + std::vector modelPoses; testSystem.OnPostUpdate( - [&modelName, &modelPoses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&modelName, &modelPoses](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Model *, + [&](const Entity &, const components::Model *, const components::Name *_name, const components::Pose *_pose)->bool { if (_name->Data() == modelName) @@ -318,7 +318,7 @@ TEST_F(PhysicsSystemFixture, // Test physics integration with revolute joints TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RevoluteJoint)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint.sdf"; @@ -330,7 +330,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RevoluteJoint)) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1us); @@ -347,11 +347,11 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RevoluteJoint)) // arm is in its initial position. The minimum distance is when the arm is in // line with the support arm. testSystem.OnPostUpdate( - [&rotatingLinkName, &armDistances](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&rotatingLinkName, &armDistances](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Link *, + [&](const Entity &, const components::Link *, const components::Name *_name, const components::Pose *_pose)->bool { if (rotatingLinkName == _name->Data()) @@ -397,8 +397,8 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RevoluteJoint)) ///////////////////////////////////////////////// TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CreateRuntime)) { - ignition::gazebo::ServerConfig serverConfig; - gazebo::Server server(serverConfig); + ServerConfig serverConfig; + Server server(serverConfig); server.SetPaused(false); // Create a system just to get the ECM @@ -408,8 +408,8 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CreateRuntime)) // shared pointer owned by the SimulationRunner. EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -481,29 +481,29 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CreateRuntime)) TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SetFrictionCoefficient)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/friction.sdf"; serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); std::map boxParams{ {"box1", 0.01}, {"box2", 0.1}, {"box3", 1.0}}; - std::map> poses; + std::map> poses; // Create a system that records the poses of the 3 boxes test::Relay testSystem; testSystem.OnPostUpdate( - [&boxParams, &poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&boxParams, &poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Model *, + [&](const Entity &, const components::Model *, const components::Name *_name, const components::Pose *_pose)->bool { if (boxParams.find(_name->Data()) != boxParams.end()) { @@ -567,23 +567,23 @@ TEST_F(PhysicsSystemFixture, TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(MultiAxisJointPosition)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/demo_joint_types.sdf"; serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(0ns); test::Relay testSystem; // Create JointPosition components if they don't already exist testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, components::Joint *) -> bool { auto posComp = _ecm.Component(_entity); @@ -598,10 +598,10 @@ TEST_F(PhysicsSystemFixture, std::map jointPosDof; testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointPosition *_jointPos) -> bool @@ -647,7 +647,7 @@ TEST_F(PhysicsSystemFixture, TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResetPositionComponent)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint.sdf"; @@ -659,7 +659,7 @@ TEST_F(PhysicsSystemFixture, serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ms); @@ -673,10 +673,10 @@ TEST_F(PhysicsSystemFixture, bool firstRun = true; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Joint *, components::Name *_name) -> bool { EXPECT_NE(nullptr, _name); @@ -711,11 +711,11 @@ TEST_F(PhysicsSystemFixture, std::vector positions; testSystem.OnPostUpdate([&]( - const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointPosition *_pos) @@ -747,7 +747,7 @@ TEST_F(PhysicsSystemFixture, TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResetVelocityComponent)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint.sdf"; @@ -759,7 +759,7 @@ TEST_F(PhysicsSystemFixture, serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ms); @@ -773,10 +773,10 @@ TEST_F(PhysicsSystemFixture, bool firstRun = true; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Joint *, components::Name *_name) -> bool { if (_name->Data() == rotatingJointName) @@ -809,12 +809,12 @@ TEST_F(PhysicsSystemFixture, std::vector velocities; testSystem.OnPostUpdate([&]( - const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointVelocity *_vel) @@ -845,7 +845,7 @@ TEST_F(PhysicsSystemFixture, /// Test joint position limit command component TEST_F(PhysicsSystemFixtureWithDart6_10, JointPositionLimitsCommandComponent) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint.sdf"; @@ -857,7 +857,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointPositionLimitsCommandComponent) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ms); @@ -878,10 +878,10 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointPositionLimitsCommandComponent) // commands do not break the positional limit. testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Joint *, components::Name *_name) -> bool { if (_name->Data() == rotatingJointName) @@ -934,12 +934,12 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointPositionLimitsCommandComponent) std::vector positions; testSystem.OnPostUpdate([&]( - const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointPosition *_pos) @@ -968,7 +968,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointPositionLimitsCommandComponent) /// Test joint velocity limit command component TEST_F(PhysicsSystemFixtureWithDart6_10, JointVelocityLimitsCommandComponent) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint.sdf"; @@ -980,7 +980,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointVelocityLimitsCommandComponent) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ms); @@ -1001,10 +1001,10 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointVelocityLimitsCommandComponent) // commands do not break the velocity limit. testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Joint *, components::Name *_name) -> bool { if (_name->Data() == rotatingJointName) @@ -1057,12 +1057,12 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointVelocityLimitsCommandComponent) std::vector velocities; testSystem.OnPostUpdate([&]( - const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointVelocity *_vel) @@ -1092,7 +1092,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointVelocityLimitsCommandComponent) /// Test joint effort limit command component TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/revolute_joint_equilibrium.sdf"; @@ -1104,7 +1104,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ms); @@ -1125,10 +1125,10 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) // commands do not break the effort limit. testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const Entity &_entity, const components::Joint *, components::Name *_name) -> bool { if (_name->Data() == rotatingJointName) @@ -1186,12 +1186,12 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) std::vector positions; testSystem.OnPostUpdate([&]( - const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &, + [&](const Entity &, const components::Joint *, const components::Name *_name, const components::JointPosition *_pos) @@ -1219,28 +1219,28 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) ///////////////////////////////////////////////// TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(GetBoundingBox)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/contact.sdf"; serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); // a map of model name to its axis aligned box - std::map bbox; + std::map bbox; // Create a system that records the bounding box of a model test::Relay testSystem; testSystem.OnPreUpdate( - [&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, + EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, const components::Model *, + [&](const Entity &_entity, const components::Model *, const components::Name *_name, const components::Static *)->bool { // create axis aligned box to be filled by physics @@ -1258,13 +1258,13 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(GetBoundingBox)) }); testSystem.OnPostUpdate( - [&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&](const UpdateInfo &, + const EntityComponentManager &_ecm) { // store models that have axis aligned box computed _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Model *, + [&](const Entity &, const components::Model *, const components::Name *_name, const components::Static *, const components::AxisAlignedBox *_aabb)->bool { @@ -1279,9 +1279,9 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(GetBoundingBox)) EXPECT_EQ(1u, bbox.size()); EXPECT_EQ("box1", bbox.begin()->first); - EXPECT_EQ(ignition::math::AxisAlignedBox( - ignition::math::Vector3d(-1.25, -2, 0), - ignition::math::Vector3d(-0.25, 2, 1)), + EXPECT_EQ(math::AxisAlignedBox( + math::Vector3d(-1.25, -2, 0), + math::Vector3d(-0.25, 2, 1)), bbox.begin()->second); } @@ -1290,7 +1290,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(GetBoundingBox)) // This tests whether nested models can be loaded correctly TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(NestedModel)) { - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/nested_model.sdf"; @@ -1302,22 +1302,22 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(NestedModel)) serverConfig.SetSdfFile(sdfFile); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1us); // Create a system that records the poses of the links after physics test::Relay testSystem; - std::unordered_map postUpModelPoses; - std::unordered_map postUpLinkPoses; + std::unordered_map postUpModelPoses; + std::unordered_map postUpLinkPoses; std::unordered_map parents; testSystem.OnPostUpdate( - [&postUpModelPoses, &postUpLinkPoses, &parents](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [&postUpModelPoses, &postUpLinkPoses, &parents](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, const components::Model *, + [&](const Entity &_entity, const components::Model *, const components::Name *_name, const components::Pose *_pose)->bool { // store model pose @@ -1336,7 +1336,7 @@ TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(NestedModel)) _ecm.Each( - [&](const ignition::gazebo::Entity &, const components::Link *, + [&](const Entity &, const components::Link *, const components::Name *_name, const components::Pose *_pose, const components::ParentEntity *_parent)->bool { diff --git a/test/integration/play_pause.cc b/test/integration/play_pause.cc index 92a9e6d398..ed7b2241f3 100644 --- a/test/integration/play_pause.cc +++ b/test/integration/play_pause.cc @@ -36,13 +36,13 @@ uint64_t kIterations; // Send a world control message. void worldControl(bool _paused, uint64_t _steps) { - std::function cb = - [&](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + std::function cb = + [&](const msgs::Boolean &/*_rep*/, const bool _result) { EXPECT_TRUE(_result); }; - ignition::msgs::WorldControl req; + msgs::WorldControl req; req.set_pause(_paused); req.set_multi_step(_steps); transport::Node node; @@ -58,8 +58,8 @@ void testPaused(bool _paused) transport::Node node; bool paused = !_paused; - std::function cb = - [&](const ignition::msgs::WorldStatistics &_msg) + std::function cb = + [&](const msgs::WorldStatistics &_msg) { std::unique_lock lock(mutex); paused = _msg.paused(); @@ -81,8 +81,8 @@ uint64_t iterations() transport::Node node; uint64_t iterations = 0; - std::function cb = - [&](const ignition::msgs::WorldStatistics &_msg) + std::function cb = + [&](const msgs::WorldStatistics &_msg) { std::unique_lock lock(mutex); iterations = _msg.iterations(); diff --git a/test/integration/pose_publisher_system.cc b/test/integration/pose_publisher_system.cc index f620734a9d..c9f6729f61 100644 --- a/test/integration/pose_publisher_system.cc +++ b/test/integration/pose_publisher_system.cc @@ -143,8 +143,8 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) [&modelName, &baseName, &lowerLinkName, &upperLinkName, &sensorName, &poses, &basePoses, &lowerLinkPoses, &upperLinkPoses, &sensorPoses, ×tamps]( - const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // get our double pendulum model auto id = _ecm.EntityByComponents( @@ -191,7 +191,7 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) // timestamps auto simTimeSecNsec = - ignition::math::durationToSecNsec(_info.simTime); + math::durationToSecNsec(_info.simTime); timestamps.push_back( math::secNsecToTimePoint( simTimeSecNsec.first, @@ -240,7 +240,7 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) // sort the pose msgs according to timestamp std::sort(poseMsgs.begin(), poseMsgs.end(), []( - const ignition::msgs::Pose &_l, const ignition::msgs::Pose &_r) + const msgs::Pose &_l, const msgs::Pose &_r) { std::chrono::steady_clock::time_point lt = math::secNsecToTimePoint( @@ -440,8 +440,8 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StaticPosePublisher)) [&modelName, &baseName, &lowerLinkName, &upperLinkName, &sensorName, &poses, &basePoses, &lowerLinkPoses, &upperLinkPoses, &sensorPoses, ×tamps, &staticPoseTimestamps]( - const gazebo::UpdateInfo &_info, - const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &_info, + const EntityComponentManager &_ecm) { // get our double pendulum model auto id = _ecm.EntityByComponents( @@ -488,7 +488,7 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StaticPosePublisher)) // timestamps auto simTimeSecNsec = - ignition::math::durationToSecNsec(_info.simTime); + math::durationToSecNsec(_info.simTime); timestamps.push_back( math::secNsecToTimePoint( simTimeSecNsec.first, simTimeSecNsec.second)); diff --git a/test/integration/rgbd_camera.cc b/test/integration/rgbd_camera.cc index 2bd7a8e0f8..6194e3b564 100644 --- a/test/integration/rgbd_camera.cc +++ b/test/integration/rgbd_camera.cc @@ -104,9 +104,9 @@ TEST_F(RgbdCameraTest, IGN_UTILS_TEST_DISABLED_ON_MAC(RgbdCameraBox)) // Lock access to buffer and don't release it mutex.lock(); - EXPECT_DOUBLE_EQ(depthBuffer[left], ignition::math::INF_D); + EXPECT_DOUBLE_EQ(depthBuffer[left], math::INF_D); EXPECT_NEAR(depthBuffer[mid], expectedRangeAtMidPointBox1, DEPTH_TOL); - EXPECT_DOUBLE_EQ(depthBuffer[right], ignition::math::INF_D); + EXPECT_DOUBLE_EQ(depthBuffer[right], math::INF_D); delete[] depthBuffer; } diff --git a/test/integration/save_world.cc b/test/integration/save_world.cc index 329182edea..0eaf3654e6 100644 --- a/test/integration/save_world.cc +++ b/test/integration/save_world.cc @@ -115,7 +115,7 @@ TEST_F(SdfGeneratorFixture, // This has to be different from the backpack in order to test SDFormat // generation for a Fuel URI that was not known when simulation started. const std::string groundPlaneUri = - "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/ground plane"; + "https://fuel.gazebosim.org/1.0/OpenRobotics/models/ground plane"; transport::Node node; { diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index 53fb52b802..ac452e6955 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -57,7 +57,7 @@ class SceneBroadcasterTest TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PoseInfo)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -107,7 +107,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PoseInfo)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneInfo)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -124,7 +124,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneInfo)) bool result{false}; unsigned int timeout{5000}; - ignition::msgs::Scene res; + msgs::Scene res; EXPECT_TRUE(node.Request("/world/default/scene/info", timeout, res, result)); EXPECT_TRUE(result); @@ -142,7 +142,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneInfo)) } // Repeat the request to make sure the same information is returned - ignition::msgs::Scene res2; + msgs::Scene res2; EXPECT_TRUE(node.Request("/world/default/scene/info", timeout, res2, result)); EXPECT_TRUE(result); @@ -153,7 +153,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneInfo)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneGraph)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -170,7 +170,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneGraph)) bool result{false}; unsigned int timeout{5000}; - ignition::msgs::StringMsg res; + msgs::StringMsg res; EXPECT_TRUE(node.Request("/world/default/scene/graph", timeout, res, result)); EXPECT_TRUE(result); @@ -193,7 +193,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneGraph)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneTopic)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -225,7 +225,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneTopic)) bool result{false}; unsigned int timeout{5000}; - ignition::msgs::Scene msg; + msgs::Scene msg; EXPECT_TRUE(node.Request("/world/default/scene/info", timeout, msg, result)); EXPECT_TRUE(result); @@ -238,7 +238,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneTopicSensors)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/altimeter_with_pose.sdf"); @@ -270,7 +270,7 @@ TEST_P(SceneBroadcasterTest, bool result{false}; unsigned int timeout{5000}; - ignition::msgs::Scene msg; + msgs::Scene msg; EXPECT_TRUE(node.Request("/world/altimeter_sensor/scene/info", timeout, msg, result)); @@ -289,7 +289,7 @@ TEST_P(SceneBroadcasterTest, TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeletedTopic)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -350,7 +350,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeletedTopic)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedModel)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -396,8 +396,8 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedModel)) // Check that the model is in the scene/infor response { - ignition::msgs::Empty req; - ignition::msgs::Scene rep; + msgs::Empty req; + msgs::Scene rep; bool result; unsigned int timeout = 2000; EXPECT_TRUE(node.Request("/world/default/scene/info", req, timeout, @@ -420,7 +420,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedModel)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/shapes.sdf"); @@ -511,7 +511,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) std::string reqSrv = "/state_async_callback_test"; node.Advertise(reqSrv, cbAsync); - ignition::msgs::StringMsg req; + msgs::StringMsg req; req.set_data(reqSrv); node.Request("/world/default/state_async", req); @@ -531,7 +531,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StateStatic)) { // Start server - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/empty.sdf"); diff --git a/test/integration/sdf_frame_semantics.cc b/test/integration/sdf_frame_semantics.cc index cdb579e224..77ac574b12 100644 --- a/test/integration/sdf_frame_semantics.cc +++ b/test/integration/sdf_frame_semantics.cc @@ -64,7 +64,7 @@ class SdfFrameSemanticsTest : public InternalFixture<::testing::Test> EXPECT_FALSE(*this->server->Running(0)); // A pointer to the ecm. This will be valid once we run the mock system relay->OnPreUpdate( - [this](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [this](const UpdateInfo &, EntityComponentManager &_ecm) { this->ecm = &_ecm; }); @@ -97,9 +97,9 @@ class SdfFrameSemanticsTest : public InternalFixture<::testing::Test> this->creator->SetParent(modelEntity, worldEntity); } - public: gazebo::Model GetModel(const std::string &_name) + public: Model GetModel(const std::string &_name) { - return gazebo::Model(this->ecm->EntityByComponents( + return Model(this->ecm->EntityByComponents( components::Model(), components::Name(_name))); } @@ -164,8 +164,8 @@ TEST_F(SdfFrameSemanticsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LinkRelativeTo)) EXPECT_NE(link2, kNullEntity); // Expect the pose of L2 relative to model to be 0 0 1 0 0 pi - ignition::math::Pose3d expRelPose(0, 0, 1, 0, 0, IGN_PI); - ignition::math::Pose3d expWorldPose(0, 0, 3, 0, 0, IGN_PI); + math::Pose3d expRelPose(0, 0, 1, 0, 0, IGN_PI); + math::Pose3d expWorldPose(0, 0, 3, 0, 0, IGN_PI); EXPECT_EQ(expRelPose, this->GetPose(link2)); @@ -231,7 +231,7 @@ TEST_F(SdfFrameSemanticsTest, JointRelativeTo) // Expect the pose of J1 relative to model to be the same as L2 (default // behavior) - ignition::math::Pose3d expWorldPose(1, 0, 2, 0, 0, 0); + math::Pose3d expWorldPose(1, 0, 2, 0, 0, 0); // Expect the pose of J2 relative to model to be the same as L2 (non default // behavior due to "relative_to='L2'") @@ -286,7 +286,7 @@ TEST_F(SdfFrameSemanticsTest, VisualCollisionRelativeTo) // Expect the pose of v1 and relative to L2 (their parent link) to be the same // as the pose of L1 relative to L2 - ignition::math::Pose3d expPose(0, 0, -1, 0, 0, 0); + math::Pose3d expPose(0, 0, -1, 0, 0, 0); EXPECT_EQ(expPose, this->GetPose(visual)); EXPECT_EQ(expPose, this->GetPose(collision)); @@ -334,13 +334,13 @@ TEST_F(SdfFrameSemanticsTest, ExplicitFramesWithLinks) // Expect the pose of L1 and relative to M to be the same // as the pose of F1 relative to M - ignition::math::Pose3d link1ExpRelativePose(0, 0, 1, 0, 0, 0); + math::Pose3d link1ExpRelativePose(0, 0, 1, 0, 0, 0); EXPECT_EQ(link1ExpRelativePose, this->GetPose(link1)); // Expect the pose of L2 and relative to M to be the same // as the pose of F2, which is at the origin of M - ignition::math::Pose3d link2ExpRelativePose = ignition::math::Pose3d::Zero; + math::Pose3d link2ExpRelativePose = math::Pose3d::Zero; EXPECT_EQ(link2ExpRelativePose, this->GetPose(link2)); @@ -389,7 +389,7 @@ TEST_F(SdfFrameSemanticsTest, ExplicitFramesWithJoints) this->server->Run(true, 1, false); // Expect the pose of J1 relative to model to be the same as F1 in world - ignition::math::Pose3d expWorldPose(1, 0, 2, 0, 0, 0); + math::Pose3d expWorldPose(1, 0, 2, 0, 0, 0); // TODO(anyone) Enable the following expectation when a joint's WorldPose // can be computed by ign-physics. // EXPECT_EQ(expWorldPose, this->GetWorldPose(joint1)); @@ -440,7 +440,7 @@ TEST_F(SdfFrameSemanticsTest, ExplicitFramesWithVisualAndCollision) // Expect the pose of v1 and relative to L1 (their parent link) to be the same // as the pose of F1 relative to L1 - ignition::math::Pose3d expPose(0, 0, 1, 0, 0, 0); + math::Pose3d expPose(0, 0, 1, 0, 0, 0); EXPECT_EQ(expPose, this->GetPose(visual)); EXPECT_EQ(expPose, this->GetPose(collision)); diff --git a/test/integration/sdf_include.cc b/test/integration/sdf_include.cc index dd9e5caadb..133810d197 100644 --- a/test/integration/sdf_include.cc +++ b/test/integration/sdf_include.cc @@ -39,13 +39,13 @@ TEST_F(SdfInclude, IGN_UTILS_TEST_DISABLED_ON_WIN32(DownloadFromFuel)) std::string path = common::cwd() + "/test_cache"; // Configure the gazebo server, which will cause a model to be downloaded. - gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetResourceCache(path); serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/include.sdf"); - gazebo::Server server(serverConfig); + Server server(serverConfig); EXPECT_TRUE(common::exists(path + - "/fuel.ignitionrobotics.org/openrobotics/models/ground plane" + + "/fuel.gazebosim.org/openrobotics/models/ground plane" + "/1/model.sdf")); } diff --git a/test/integration/sensors_system.cc b/test/integration/sensors_system.cc index 789d57fefd..b843da142b 100644 --- a/test/integration/sensors_system.cc +++ b/test/integration/sensors_system.cc @@ -111,7 +111,7 @@ class SensorsFixture : public InternalFixture> systemPtr->QueryInterface()); } - public: ignition::gazebo::SystemPluginPtr systemPtr; + public: gazebo::SystemPluginPtr systemPtr; public: gazebo::MockSystem *mockSystem; private: gazebo::SystemLoader sm; @@ -162,7 +162,7 @@ void testDefaultTopics() /// are removed and then added back TEST_F(SensorsFixture, IGN_UTILS_TEST_DISABLED_ON_MAC(HandleRemovedEntities)) { - ignition::gazebo::ServerConfig serverConfig; + gazebo::ServerConfig serverConfig; const std::string sdfFile = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/sensor.sdf"; diff --git a/test/integration/thermal_system.cc b/test/integration/thermal_system.cc index 68d1e566ec..ba9308f88a 100644 --- a/test/integration/thermal_system.cc +++ b/test/integration/thermal_system.cc @@ -67,11 +67,11 @@ TEST_F(ThermalTest, IGN_UTILS_TEST_DISABLED_ON_MAC(TemperatureComponent)) std::map entityTempRange; std::map heatSignatures; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { _ecm.Each( - [&](const ignition::gazebo::Entity &_id, + [&](const Entity &_id, const components::Temperature *_temp, const components::Name *_name) -> bool { diff --git a/test/integration/touch_plugin.cc b/test/integration/touch_plugin.cc index f1ae4745ad..36eedfb8c7 100644 --- a/test/integration/touch_plugin.cc +++ b/test/integration/touch_plugin.cc @@ -100,7 +100,7 @@ TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OneLink)) std::this_thread::sleep_for(std::chrono::milliseconds(30)); } // Known to fail on OSX, see -// https://github.com/ignitionrobotics/ign-gazebo/issues/22 +// https://github.com/gazebosim/gz-sim/issues/22 #if !defined (__APPLE__) EXPECT_TRUE(whiteTouched); #endif @@ -180,7 +180,7 @@ TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StartDisabled)) std::this_thread::sleep_for(std::chrono::milliseconds(30)); } // Known to fail on OSX, see -// https://github.com/ignitionrobotics/ign-gazebo/issues/22 +// https://github.com/gazebosm/gz-sim/issues/22 #if !defined (__APPLE__) EXPECT_TRUE(blueTouched); #endif diff --git a/test/integration/tracked_vehicle_system.cc b/test/integration/tracked_vehicle_system.cc index d98434d463..2d8180bf29 100644 --- a/test/integration/tracked_vehicle_system.cc +++ b/test/integration/tracked_vehicle_system.cc @@ -70,7 +70,7 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> bool &_shouldSkip) { #if __APPLE__ - // until https://github.com/ignitionrobotics/ign-gazebo/issues/806 is fixed + // until https://github.com/gazebosim/gz-sim/issues/806 is fixed _shouldSkip = true; #else _shouldSkip = false; @@ -90,7 +90,7 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> << "Failed to find plugin [" << *pluginLib << "]"; // Load engine plugin - ignition::plugin::Loader pluginLoader; + plugin::Loader pluginLoader; auto plugins = pluginLoader.LoadLib(pathToLib); ASSERT_FALSE(plugins.empty()) << "Unable to load the [" << pathToLib << "] library"; @@ -133,8 +133,8 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> // Create a system that records the vehicle poses test::Relay ecmGetterSystem; EntityComponentManager* ecm {nullptr}; - ecmGetterSystem.OnPreUpdate([&ecm](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + ecmGetterSystem.OnPreUpdate([&ecm](const UpdateInfo &, + EntityComponentManager &_ecm) { if (ecm == nullptr) ecm = &_ecm; @@ -156,8 +156,8 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> test::Relay testSystem; Entity modelEntity {kNullEntity}; std::vector poses; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { modelEntity = _ecm.EntityByComponents( components::Model(), @@ -253,7 +253,7 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> poses.clear(); - gazebo::Model model(modelEntity); + Model model(modelEntity); // Move the robot somewhere to free space without obstacles. model.SetWorldPoseCmd(*ecm, math::Pose3d(10, 10, 0.1, 0, 0, 0)); @@ -455,8 +455,8 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> // Create a system that records the vehicle poses test::Relay ecmGetterSystem; EntityComponentManager* ecm {nullptr}; - ecmGetterSystem.OnPreUpdate([&ecm](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + ecmGetterSystem.OnPreUpdate([&ecm](const UpdateInfo &, + EntityComponentManager &_ecm) { if (ecm == nullptr) ecm = &_ecm; @@ -478,8 +478,8 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> test::Relay testSystem; Entity boxEntity {kNullEntity}; std::vector poses; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const UpdateInfo &, + const EntityComponentManager &_ecm) { boxEntity = _ecm.EntityByComponents( components::Model(), diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 4a37616c6f..47b2f7f219 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -75,8 +75,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Create)) // shared pointer owned by the SimulationRunner. EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -354,8 +354,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) // shared pointer owned by the SimulationRunner. EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -538,8 +538,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Pose)) // Create a system just to get the ECM EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -712,8 +712,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PoseVector)) // Create a system just to get the ECM EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -1047,8 +1047,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Physics)) // Create a system just to get the ECM EntityComponentManager *ecm{nullptr}; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); diff --git a/test/integration/velocity_control_system.cc b/test/integration/velocity_control_system.cc index 6925dbca76..31ac1d6f1a 100644 --- a/test/integration/velocity_control_system.cc +++ b/test/integration/velocity_control_system.cc @@ -58,8 +58,8 @@ class VelocityControlTest test::Relay testSystem; std::vector poses; - testSystem.OnPostUpdate([&poses](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&poses](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto id = _ecm.EntityByComponents( components::Model(), @@ -145,8 +145,8 @@ class VelocityControlTest std::vector modelPoses; std::vector linkPoses; testSystem.OnPostUpdate([&linkPoses, &modelPoses]( - const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + const UpdateInfo &, + const EntityComponentManager &_ecm) { auto modelId = _ecm.EntityByComponents( components::Model(), diff --git a/test/integration/wheel_slip.cc b/test/integration/wheel_slip.cc index 24a9f3e697..a08991c360 100644 --- a/test/integration/wheel_slip.cc +++ b/test/integration/wheel_slip.cc @@ -82,7 +82,7 @@ class WheelSlipTest : public InternalFixture<::testing::Test> public: double drumSpeed = 0.0; /// \brief Steer angle to apply. - public: ignition::math::Angle steer; + public: math::Angle steer; /// \brief Suspension force to apply in N. public: double suspForce = 0.0; @@ -120,10 +120,10 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - gazebo::EntityComponentManager *ecm = nullptr; + EntityComponentManager *ecm = nullptr; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -141,7 +141,7 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) Entity worldEntity = ecm->EntityByComponents(components::World()); - EXPECT_NE(gazebo::kNullEntity, worldEntity); + EXPECT_NE(kNullEntity, worldEntity); // Get both models Entity tireEntity = @@ -152,8 +152,8 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) ecm->EntityByComponents(components::Model(), components::Name("drum")); - EXPECT_NE(gazebo::kNullEntity, tireEntity); - EXPECT_NE(gazebo::kNullEntity, drumEntity); + EXPECT_NE(kNullEntity, tireEntity); + EXPECT_NE(kNullEntity, drumEntity); Entity wheelLinkEntity = ecm->EntityByComponents( components::ParentEntity(tireEntity), @@ -165,8 +165,8 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) components::Name("link"), components::Link()); - EXPECT_NE(gazebo::kNullEntity, wheelLinkEntity); - EXPECT_NE(gazebo::kNullEntity, drumLinkEntity); + EXPECT_NE(kNullEntity, wheelLinkEntity); + EXPECT_NE(kNullEntity, drumLinkEntity); auto wheelInertialComp = ecm->Component(wheelLinkEntity); @@ -193,8 +193,8 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) components::Name("collision"), components::Collision()); - EXPECT_NE(gazebo::kNullEntity, collisionWheelLinkEntity); - EXPECT_NE(gazebo::kNullEntity, collisionDrumLinkEntity); + EXPECT_NE(kNullEntity, collisionWheelLinkEntity); + EXPECT_NE(kNullEntity, collisionDrumLinkEntity); auto wheelCollisionComp = ecm->Component(collisionWheelLinkEntity); @@ -240,19 +240,16 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) // const double kp = surfaceContactOde->GetElement("kp")->Get(); // ASSERT_EQ(kp, 250e3); - double modelMass = 0.0; for (const auto &linkName : linksToCheck) { Entity linkEntity = ecm->EntityByComponents( components::ParentEntity(tireEntity), components::Name(linkName), components::Link()); - EXPECT_NE(gazebo::kNullEntity, linkEntity); + EXPECT_NE(kNullEntity, linkEntity); auto inertialComp = ecm->Component(linkEntity); EXPECT_NE(nullptr, inertialComp); - - modelMass += inertialComp->Data().MassMatrix().Mass(); } // Get axle wheel and steer joint of wheel model @@ -261,14 +258,14 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) components::Name("axle_wheel"), components::Joint()); - ASSERT_NE(gazebo::kNullEntity, wheelAxleJointEntity); + ASSERT_NE(kNullEntity, wheelAxleJointEntity); Entity wheelSteerJointEntity = ecm->EntityByComponents( components::ParentEntity(tireEntity), components::Name("steer"), components::Joint()); - ASSERT_NE(gazebo::kNullEntity, wheelSteerJointEntity); + ASSERT_NE(kNullEntity, wheelSteerJointEntity); const double wheelSpeed = -25.0 * metersPerMile / secondsPerHour / wheelRadius; @@ -382,10 +379,10 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - gazebo::EntityComponentManager *ecm = nullptr; + EntityComponentManager *ecm = nullptr; test::Relay testSystem; - testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &_ecm) + testSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &_ecm) { ecm = &_ecm; }); @@ -403,7 +400,7 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) Entity worldEntity = ecm->EntityByComponents(components::World()); - EXPECT_NE(gazebo::kNullEntity, worldEntity); + EXPECT_NE(kNullEntity, worldEntity); auto gravity = ecm->Component(worldEntity); @@ -415,14 +412,14 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) ecm->EntityByComponents(components::Model(), components::Name("trisphere_cycle0")); - EXPECT_NE(gazebo::kNullEntity, trisphereCycle0Entity); + EXPECT_NE(kNullEntity, trisphereCycle0Entity); Entity trisphereCycle1Entity = ecm->EntityByComponents(components::Model(), components::Name("trisphere_cycle1")); - EXPECT_NE(gazebo::kNullEntity, trisphereCycle1Entity); + EXPECT_NE(kNullEntity, trisphereCycle1Entity); // Check rear left wheel of first model Entity wheelRearLeftEntity = ecm->EntityByComponents( @@ -430,7 +427,7 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) components::Name("wheel_rear_left"), components::Link()); - EXPECT_NE(gazebo::kNullEntity, wheelRearLeftEntity); + EXPECT_NE(kNullEntity, wheelRearLeftEntity); Entity wheelRearLeftCollisionEntity = ecm->EntityByComponents( components::ParentEntity(wheelRearLeftEntity), @@ -450,28 +447,28 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) components::Name("wheel_rear_left_spin"), components::Joint()); - EXPECT_NE(gazebo::kNullEntity, wheelRearLeftSpin0Entity); + EXPECT_NE(kNullEntity, wheelRearLeftSpin0Entity); Entity wheelRearRightSpin0Entity = ecm->EntityByComponents( components::ParentEntity(trisphereCycle0Entity), components::Name("wheel_rear_right_spin"), components::Joint()); - EXPECT_NE(gazebo::kNullEntity, wheelRearRightSpin0Entity); + EXPECT_NE(kNullEntity, wheelRearRightSpin0Entity); Entity wheelRearLeftSpin1Entity = ecm->EntityByComponents( components::ParentEntity(trisphereCycle1Entity), components::Name("wheel_rear_left_spin"), components::Joint()); - EXPECT_NE(gazebo::kNullEntity, wheelRearLeftSpin1Entity); + EXPECT_NE(kNullEntity, wheelRearLeftSpin1Entity); Entity wheelRearRightSpin1Entity = ecm->EntityByComponents( components::ParentEntity(trisphereCycle1Entity), components::Name("wheel_rear_right_spin"), components::Joint()); - EXPECT_NE(gazebo::kNullEntity, wheelRearRightSpin1Entity); + EXPECT_NE(kNullEntity, wheelRearRightSpin1Entity); // Set speed of both models const double angularSpeed = 6.0; @@ -526,8 +523,8 @@ TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) } test::Relay testSlipSystem; - testSlipSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, - gazebo::EntityComponentManager &) + testSlipSystem.OnPreUpdate([&](const UpdateInfo &, + EntityComponentManager &) { auto wheelRearLeftVelocity0Cmd = ecm->Component(wheelRearLeftSpin0Entity); diff --git a/test/integration/wind_effects.cc b/test/integration/wind_effects.cc index bd49f777f8..8c4e11b9a6 100644 --- a/test/integration/wind_effects.cc +++ b/test/integration/wind_effects.cc @@ -85,7 +85,7 @@ class LinkComponentRecorder if (_createComp) { this->mockSystem->preUpdateCallback = - [this](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + [this](const UpdateInfo &, EntityComponentManager &_ecm) { auto linkEntity = _ecm.EntityByComponents( components::Link(), components::Name(this->linkName)); @@ -101,8 +101,8 @@ class LinkComponentRecorder } this->mockSystem->postUpdateCallback = - [this](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + [this](const UpdateInfo &, + const EntityComponentManager &_ecm) { auto linkEntity = _ecm.EntityByComponents( components::Link(), components::Name(this->linkName)); diff --git a/test/performance/level_manager.cc b/test/performance/level_manager.cc index ccd9032c31..022dbe0da2 100644 --- a/test/performance/level_manager.cc +++ b/test/performance/level_manager.cc @@ -38,10 +38,10 @@ TEST(LevelManagerPerfrormance, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelVsNoLevel)) common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", + common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + "/test/worlds/level_performance.sdf"); math::Stopwatch watch; @@ -53,7 +53,7 @@ TEST(LevelManagerPerfrormance, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelVsNoLevel)) // measuring time differences between levels and no levels. { serverConfig.SetUseLevels(true); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); server.Run(true, 1, false); @@ -62,7 +62,7 @@ TEST(LevelManagerPerfrormance, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelVsNoLevel)) // Server with levels { serverConfig.SetUseLevels(true); - gazebo::Server server(serverConfig); + Server server(serverConfig); server.SetUpdatePeriod(1ns); watch.Start(true); @@ -74,7 +74,7 @@ TEST(LevelManagerPerfrormance, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelVsNoLevel)) // Server without levels { serverConfig.SetUseLevels(false); - gazebo::Server serverNoLevels(serverConfig); + Server serverNoLevels(serverConfig); serverNoLevels.SetUpdatePeriod(1ns); watch.Start(true); diff --git a/test/performance/sdf_runner.cc b/test/performance/sdf_runner.cc index b2fdfe1818..0fbb754926 100644 --- a/test/performance/sdf_runner.cc +++ b/test/performance/sdf_runner.cc @@ -33,7 +33,7 @@ using namespace gazebo; ////////////////////////////////////////////////// int main(int _argc, char** _argv) { - ignition::common::Console::SetVerbosity(4); + common::Console::SetVerbosity(4); std::string sdfFile{""}; if (_argc >= 2) @@ -56,7 +56,7 @@ int main(int _argc, char** _argv) } igndbg << "Update rate: " << updateRate << std::endl; - ignition::gazebo::ServerConfig serverConfig; + ServerConfig serverConfig; if (!serverConfig.SetSdfFile(sdfFile)) { ignerr << "Failed to set SDF file [" << sdfFile << "]" << std::endl; @@ -68,23 +68,23 @@ int main(int _argc, char** _argv) serverConfig.SetUpdateRate(updateRate); // Create the Gazebo server - ignition::gazebo::Server server(serverConfig); + Server server(serverConfig); - ignition::transport::Node node; + transport::Node node; - std::vector msgs; + std::vector msgs; msgs.reserve(iterations); - std::function cb = - [&](const ignition::msgs::Clock &_msg) + std::function cb = + [&](const msgs::Clock &_msg) { msgs.push_back(_msg); }; double progress = 0; - std::function cb2 = - [&](const ignition::msgs::WorldStatistics &_msg) + std::function cb2 = + [&](const msgs::WorldStatistics &_msg) { double nIters = static_cast(_msg.iterations()); nIters = nIters / iterations * 100; diff --git a/test/plugins/TestSystem.cc b/test/plugins/TestSystem.cc index 94896f5185..2c362db0b8 100644 --- a/test/plugins/TestSystem.cc +++ b/test/plugins/TestSystem.cc @@ -32,6 +32,6 @@ TestSystem::TestSystem() TestSystem::~TestSystem() = default; // Register this plugin -IGNITION_ADD_PLUGIN(TestSystem, ignition::gazebo::System) +IGNITION_ADD_PLUGIN(TestSystem, System) IGNITION_ADD_PLUGIN_ALIAS(TestSystem, "ignition::gazebo::TestSystem") diff --git a/test/worlds/breadcrumbs.sdf b/test/worlds/breadcrumbs.sdf index a8b75f9899..bbc2bac8e6 100644 --- a/test/worlds/breadcrumbs.sdf +++ b/test/worlds/breadcrumbs.sdf @@ -481,7 +481,7 @@ -2.2 0 5 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Cardboard box + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Cardboard box diff --git a/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf new file mode 100644 index 0000000000..b9386ade65 --- /dev/null +++ b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.sdf @@ -0,0 +1,5 @@ + + + + + diff --git a/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world new file mode 100644 index 0000000000..b9386ade65 --- /dev/null +++ b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/test.world @@ -0,0 +1,5 @@ + + + + + diff --git a/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/thumbnails/1.png b/test/worlds/fuel.gazebosim.org/openrobotics/worlds/test%20world/2/thumbnails/1.png new file mode 100644 index 0000000000000000000000000000000000000000..a72d5aa96bff8d0820bac6184f5e3d8370725889 GIT binary patch literal 6279 zcmc(kWmpu^zsCnf=@3y`8WAJ}q(i!-k(83|j-^GULt0vPX;@YomJ&gbTpFoGL_lHz z=~}qseRbd5cmMm`d7d-#%sl7J%sKOm&+j|2+M3EFgtUYJ0FbDvDCmO6Rj_5@-v##@ zQaice0oPkjRUaSRg7Ix)z;gl*6=QDzAnpCva5A__>A;ILK8i*@dhT{U{#IVLfWN;# zucMo@x3!grEw8(meeSL#EdWsCsw&9p2jpRvARY@d`FQ(`_z`6)I>o$`;_x(adiBgT z?xcJTYYEph4##@O`G(0Qmu5kXrauzXG`TeDVwWSuA(1<`dy?!T(H7Q_Z$25zFzc5( z@A`&alTtOa`m&Tw4a%!aLGS@r<<<`wmoah;wJ9s2%+SKFqc5l7c%~LBD>zIsvlby( z$P0W|iD^H7fZ2yA>K^m^FZ?XU8-_yk>W|bp+Yo(yV%%6b&1o!`| z(-vm;%e(3-L{)ngVw+pHwXXWWkc8~HkGpl&ZtDyFPg4Hpi!!Qf)x*_fs626RPl?M0 zJxgklw`)eXhiWg21^PYvFgqyhm&10oPSn#OQaAfBKMMNN|2f;AVz7w6l8A%zkh|~D zUp9S^-wog*6tN#(hL6WWRmgFf?TiF&nKrsLcvAO~wCs<*=L37Me$CV9TzrlRbh$nV zc7+Nny&Dg?nA%jYf{RcRI_50oCi4YQk>WR%&Mqk~5eZIk4cvX%j7mp^> zItYi!kvdn}Nqoge%pyh!Hlt8T6k%z3YZ!;)3%y6HnU-Oe;mwiuQqgGRg}Au1(@i-B z)|G+^@4K&{UVPEUz1W19&9W`JF>I2cj3lFc{WgCT~@{&sb=GR_P3I2JK+>5JKHn(WEvNjWJB+t+{klr1vx#vS-iGAT1(KjnS;Xr#{e zykw2I=T9F;|3R6383S6;-8zOOqYtsIf=wyJi+C&YHRW?DydGog2tkTrd$ta?BB`(h z5#;xIlw+-^MLyLvc-;cR2?V&4L^)uNot4nR?5#j?q(r6Nx?MrWpi^VuUk~hxA%ks_ zCqych?R{k&m;EcnjKftr#^paWJLeKQl+#eoRLl~_0#Q?bEnH-B9=~UHl=BhLdz>-i zxIVK{5WL%X76<^2j*c#Hm|x3`js!74b#eFdgy!h3rg<5Emj@~EMeFj|HQ%*%jaF^d z6eSJ&y+6?>yhXPagahD*n=1Fh@RF}hgUMGJqyt){Pz9&X74%7wm=Vl~fBujL^6{a9 zPJ%{L`opZwe9o9y{a5;8iFa9>{WKaf_!Ab2>znIYdZPx5y-J@SIw?B7=gw$)oSYXN z%{E|LA-P!)EZRxh?->X&F46s)yUB+<1;_M0$5duzajS8o)f?fOW$_<1)^l~m$cgp) zW}nd}ghC+0&;8!qUQ#%{7v-6I=GY~F0girOd^o0GLNi%fTnH)9ve@UX77gR!d%|c~ zpOt>T)=}Obo8PRd)9lIj?F3BGLya08dD-$70H&MGR z7w9iXyb#8PVR8AQ56q!+*?RW8d105qrTzn#Ex}@_!%W-dgV=v<{I8CKlbcD?M;^HC zH{01%GY;9)N2GeqI1HbBKYzP9iQrspl$KMBK?NUV-@p;@o1$^cox9D za~EdUhH5d1Iam(|Y0zc)&|wYcKr6PMZ~V ziUHuNp)19T+RVg+Hb~~OA$LV=mE!}K02iM!Oh=>Am1pzexm0y!O=pd~=}aw&L$z~z zwwv0G5m!94+)txzm$uJ|b0jY0AujV;h*DJ#zgvU>%*=DjvS-IkOPNj2;PuI~?;QHC z-Dd5LGE1612W{I4(U$#Q<7Dh`{#`t|$$~4}ySpB%!182I(1an%^L|}@ouOnn9r0an zU02g4gv+3dK(or43R|l8W^$If$=)4^4mp7gX11U2^gP7hY|BWUpL&s%&y;88o5Jyw zldnq`81oLKVbdvvp;wd77nWl2GR7@`BQM%C!59VrKfmVX>*{sP8P5@f#ja*2aBQ6Y zJ|obfd=3ClhaM&-B|o$?5xksCs4A>Fzmk^sHa+}HW+HtS$V6=!PZZa`R@fDUUD9f7 zXm0-l3vp@U2}**NzuMDqb#$-r)@YL^Yrc8m{M=+Vmi00ErM`c!nC_sL3(gmKTUc-d z$~4_jNR~Xn8fEtrca+0+uC8WecqI5C@PZsS#5?Ga8;l3)l!}m7T(5R$lwjSWf2Xp` zLYdu7KN#{`n7+D%jiN{QVxi@CfqlVic`Agtq@{4SDg2>xm)MA;`xxCvaw>sHIp+H0 zleKYTGYaB63==l$0?fkt;-Ug)BUT&yxpptN1#*X3XMDDcW!*oirvBap@<(y07b5Ie zm>527|2(Ey&)S<{K0qvCu3rlN5Ovjr)a4WKA2JK4dtS!Z?{?mfVT!z%zYx)#6TZb{9(H`Z(cE@lVqoGR z)zi;PINsLyHs5}2bWma->nf*z0(=_1aY}O$by2zgaNVheKkGrFl12olgMK7eHOF*< zIl@0zV|`!(I)Ro9DzJwiE3(|H3v21>mD;Ew#=R8;+AuqQgeGnZ+bbItxWVO1rO5y* zbE^#{cS%d*%$$!oKYF~Xr7047d40?AGqk(9I{jI<7Zd**2hHbS{3pS1pQvK2k|hOS zOi;u+ZLm~GkEtj1o)LUR>1hDfaFMpk;|!t$!u94rI<;skg(@!;QV=0zcAla?TEBrk z*n!#exg7iDGt*n~Y7l)Rd4tT(rgHU{-*kyJh z4iG@qQA%efqB#s%e?$=7a}MR~LlYf*v+p{y?J#H5w8d6!Ztgu{pk@$VEyI#TF!h@M zQA;gee$y2E`jxqF3AEvB;~Zv(vP~c%#i4hn44Vi5FF#aJ-1&PN8AqNrU6@xOsfhO{ z@VxHX?2p`UcfQpR%qM6j2%kAD->YzGGz#l9DMUl|^0l;3FT)J3)wv(XL8A!xeP4!G zc!L-@Z7_2!l#w;~^fJp?&ZV3lcp>k&2<+Eqo@64?MQFrf@GlWN0_f+8=7IxB1TtXl zS3D8={o@xWc#0>jb8WvvuHI#mUAwq=?TFZG7Mx@4nws@?2ECQ4zRj~@hY#B!V`4@h zs@>Qqm~R(_vxc7k=>1WNm@qxz>6f0>&dKfwItjc#4U(rQSP-bEO{Ven;iWLe;H#!e z1LVIh(ig@j|6<9cuYdk=3Q_sTF3_M)ml6XJEyhqLij8IQo5nkPUmr8`#;~bgOglA3 zgF}IE&bZ&{L0d%b9hWnLr%*n!95aZ`Q(n$pnnL>I3^To&oWY5~SOwq9=u3491~{0% zX@QoUat$Wxv8W%~+4>+?1X4`j2F~Os8Ku|E4y1W4>{OfEEzER626Wb`@mh}YiePQl zH=n%sA)6)DP|iv`WxOt{q0b|w2bE&srtSv2e>TrbIpf%5$zNykY^&*n>Zohljkd?> z6FfrnultD6fv&#EX~ko>+!g3I(CnkzIkz*sGj!Z|?5>XZOcdR-1scp&RDKU%B&$_h z&?j`B!9i}+2(fxzi zX>f&Nqnfeu*aruO!S?ockBL|RoRx7+kzVC@b z!qavKeq58|b{iV%clrJPnL>9ENSnwJ*s$WTeO-w)`}diW!Bq2zH2P2&xs?CLkW>!` zc-beRT=jzgCw_Df!43aFbneOPOWO>!2e*Kq5VR1#fOdNM$naG{Fg~~VAUy#JgS~=$9RFStd$?S)laJ?$jSpQ7=(v`2QRHLR+(Jk=zBNoP3Qdiu2Q3aV<8A1 zC%+Zl40dz>%BBm_CM-VI4F2_ebJ?ePq0wr%!LIKsXB@Q2y&NIbsd?p5UtC^136>P9 zwzCb~D-alJFP>-C(bqbbR~D_T9; z@o^1iIQP(l8w8y^*v$nCp{0op_0E#EuPrSNAN#yqYW0P4hY6D7dPY~?=ukH5iY=w1 zGq=1WqDkqIvZ=)uTzK-`gasRV7hO*W`H%%_9mihCyr5z$e&7XCtmFCgcI@AmH6 zX(X6tib~znN_bEEOk~$`Q2-6>^xnN>S$CsZL+^6czN?)zHSyd%9;roz|bfv0+p&U@VzLuOw5t(rbD-uev@x9Ni-;3PZQ)m-U zpvg=K*Q}z;8VsFhB${crmp-YVv)RpT=H}teAahp_4h6G`Wq?b-Hyr_YE%OQfN>yKN zb2~AE+-f(L6bGAcA55yo-L_NML&M~D^7*pV?w}3{+;1;xfa`+;fXYPe7Y{4mFt^ar zTfhrJpQlEx#;x3P8TP0{ZOZ3F9?k&^GK+fvu>UmhjVma8eAii55jTb!Am}qe+T9Mk z7^&NdyD-6=M5Rnr(+f`$yBcd`U`$XKKet5)?I@(>4d-zX_qm&H{Bpdo1A+H&an++1{m)FO!TCC4AhTAnQz+p z5&WCyEWiuT(7)AJ;`X4za7=Q7Q7=KkMNGAZ3S}BT^0-zsv}L&%(7A$lntk}L=#%vi zvAhXv>8R(%X3%UsUVjZ4=pEmJAA5{D2u*5TlBuqBvMwCL8+u3 zW$kfW93yFpSQLV4ungzWq=KX_;`ee@qj98(q-&^Al=Kr*wq3;hjpoGNQyp|cyUbvm zf~oz2g#ybx0ms{b!={7SPy5}gpglWkCE$BKBJVie&5r{=qKXSat2(0@IvIX-cT>pP zWY39=TRn+U{Mv1Cy!L3sAANNKQcqrasDGIMTr`~V`W?Ovb zXPgXN(-wVF+}qO|%hER_QC1YA)lEw-3(JCIhs~!|VQS6Xj74#V#wMFC9doplxXjmb z!8cA8?pCN;e^k(VVSntm{Dz$Q} z_2+toAWIlAA@Hf8+-KU)>(zr-qaJKme4wTi#)ltq@8`^_ae*Sr7!2=@68Q!qexQ07 zrmn7Tt+zCT)qbV3W)m^&yo6m^zNe@|;^F*fufRKORLcMKu!k#yYwB~?iVR-Jv4M5yUBp8lDp=ah^2fBIsfLn)r7+w);92 z`qfgi*9-R2=fgvD*>j!8E*qhaV9gEL8LMUd9$g*#r$KxJ*3XCyO@wi5R(x@jYro#w zMj^~xHx4I5vFSlh$-&vM;b%=Vt;^{_T%g%mZv=qm-ja>yUuIwG`VRIEFEeDQBt?ZS zpDG|fM;}j!Hc>=EunkdKS1K`Hl4+yVuZ*GZ-vj{8IKnIpx9RM$N~Z0TjYvU1lCexH z)AVK97Fr$h*wM~Wwb_O$=H4hTT-mXzX{SQXszb^Rs^;(VqGD3npwdAAgfroL3NDN8 qfBO1Q!WMn0_@Asx{tu+@v#?6*EEdsJA9C=g0idd=sZb+l8S!6Umjes{ literal 0 HcmV?d00001 diff --git a/test/worlds/include.sdf b/test/worlds/include.sdf index ed6f427d9a..1d00bc2dc0 100644 --- a/test/worlds/include.sdf +++ b/test/worlds/include.sdf @@ -6,7 +6,7 @@ - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/ground plane/1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/ground plane/1 diff --git a/test/worlds/log_record_resources.sdf b/test/worlds/log_record_resources.sdf index c0e2761c55..2c596b9d9d 100644 --- a/test/worlds/log_record_resources.sdf +++ b/test/worlds/log_record_resources.sdf @@ -56,7 +56,7 @@ false staging_area 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X2 Config 1 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/X2 Config 1 diff --git a/test/worlds/save_world.sdf b/test/worlds/save_world.sdf index 055dd32d4e..7919821f10 100644 --- a/test/worlds/save_world.sdf +++ b/test/worlds/save_world.sdf @@ -39,17 +39,17 @@ - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack backpack1 1 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack backpack2 1 2 3 0.1 0.2 0.3 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2 + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/2 backpack3 2 0 0 0.1 0.2 0.3 diff --git a/tutorials/battery.md b/tutorials/battery.md index 4b235125c3..aacfaff581 100644 --- a/tutorials/battery.md +++ b/tutorials/battery.md @@ -53,7 +53,7 @@ Next, you can find a description of the SDF parameters used: * ``: Power load on battery (W). -* ``: As reported [here](https://github.com/ignitionrobotics/ign-gazebo/issues/225), +* ``: As reported [here](https://github.com/gazebosim/gz-sim/issues/225), there are some issues affecting batteries in Ignition Blueprint and Citadel. This parameter fixes the issues. Feel free to omit the parameter if you have legacy code and want to preserve the old behavior. diff --git a/tutorials/detachable_joints.md b/tutorials/detachable_joints.md index 70a2456b8d..38f2d0d5a3 100644 --- a/tutorials/detachable_joints.md +++ b/tutorials/detachable_joints.md @@ -8,7 +8,7 @@ kinematic topology has to be a tree, i.e., kinematic loops are not currently supported. This affects the choice of the parent link, and therefore, the parent model, which is the model that contains the `DetachableJoint` system. -For example, [detachable_joint.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo2/examples/worlds/detachable_joint.sdf) +For example, [detachable_joint.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/detachable_joint.sdf) demonstrates a four wheel vehicle that holds three objects that are later detached from the vehicle. As seen in this example, the parent model is the vehicle. The kinematic topology is the following. diff --git a/tutorials/distributed_simulation.md b/tutorials/distributed_simulation.md index 5395d72fd1..26918a3671 100644 --- a/tutorials/distributed_simulation.md +++ b/tutorials/distributed_simulation.md @@ -106,7 +106,7 @@ keeps all performers loaded, but performs no physics simulation. Stepping happens in 2 stages: the primary update and the secondaries update, according to the diagram below: - + 1. The primary publishes a `SimulationStep` message on the `/step` topic, containing: diff --git a/tutorials/erb_template.md b/tutorials/erb_template.md index 1814d024dc..b289d5a9d5 100644 --- a/tutorials/erb_template.md +++ b/tutorials/erb_template.md @@ -17,7 +17,7 @@ Some of them are listed below and demonstrated in this [example ERB file](https: ## Set up Ruby Firstly, Ruby needs to be installed. -If you have gone through [Ignition's installation guide](https://ignitionrobotics.org/docs/latest/install), it's most likely you already have Ruby installed. +If you have gone through [Ignition's installation guide](https://gazebosim.org/docs/latest/install), it's most likely you already have Ruby installed. To check if Ruby is installed, use ```{.sh} ruby --version @@ -102,7 +102,7 @@ Each box model also has a different name and pose to ensure they show up as indi %> ``` -[Here](https://github.com/ignitionrobotics/ign-gazebo/blob/main/examples/worlds/shapes_population.sdf.erb) is a complete shapes simulation world example. +[Here](https://github.com/gazebosim/gz-sim/blob/main/examples/worlds/shapes_population.sdf.erb) is a complete shapes simulation world example. Instead of simple shapes, you can also use a nested loop to generate 100 actors spaced out evenly in a simulation world. @@ -116,11 +116,11 @@ Instead of simple shapes, you can also use a nested loop to generate 100 actors - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae + https://fuel.gazebosim.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae 1.0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae + https://fuel.gazebosim.org/1.0/Mingfei/models/actor/tip/files/meshes/talk_b.dae 0.055 true diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md index d7cecc59f4..faf7e8ae9c 100644 --- a/tutorials/gui_config.md +++ b/tutorials/gui_config.md @@ -1,9 +1,9 @@ \page gui_config GUI Configuration Ignition Gazebo's graphical user interface is powered by -[Ignition GUI](https://ignitionrobotics.org/libs/gui). Therefore, Gazebo's +[Ignition GUI](https://gazebosim.org/libs/gui). Therefore, Gazebo's GUI layout can be defined in -[Ignition GUI configuration files](https://ignitionrobotics.org/api/gui/2.1/config.html). +[Ignition GUI configuration files](https://gazebosim.org/api/gui/2.1/config.html). These are XML files that describe what plugins to be loaded and with what settings. @@ -104,11 +104,11 @@ favorite editor and save this file as `fuel_preview.sdf`: - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Sun + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Gazebo + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Gazebo diff --git a/tutorials/levels.md b/tutorials/levels.md index c2f62b8667..f8f1f98df5 100644 --- a/tutorials/levels.md +++ b/tutorials/levels.md @@ -77,7 +77,7 @@ being added and removed. Take a look at the 2D example below. This example focuses on a single performer, but the same logic can be extended to multiple performers. - + * The **green area** represents the area of the world which this simulation is expected to take place in. @@ -115,23 +115,23 @@ Let's take a look at how levels are loaded / unloaded as the performer moves: * `M1` and `M3`, because they belong to the level. * `M6`, because it is global. - + 2. The performer moves south towards `L3` and enters its buffer zone, triggering a load of that level's models, `M4` and `M5`. Note that at this moment, both `L1` and `L3` are loaded. - + 3. The performer moves further south, exiting `L1` and entering `L3`. However, `L1` is still loaded, since `R1` is still within its buffer zone. - + 4. Eventually `R1` moves beyond `L1`'s buffer, triggering an unload of `L1`. The main effect is unloading `M1`. - + ## SDF elements @@ -248,7 +248,7 @@ ign service -s /world/levels/level/set_performer --reqtype ignition.msgs.StringM The following is a world file that could be an instance of the world shown in the figure - + ```xml diff --git a/tutorials/log.md b/tutorials/log.md index 2de76ff76a..fcac96bf70 100644 --- a/tutorials/log.md +++ b/tutorials/log.md @@ -8,7 +8,7 @@ Ignition records two types of information to files: * Always recorded * Simulation state * Entity poses, insertion and deletion - * Logged to an [Ignition Transport `state.tlog` file](https://ignitionrobotics.org/api/transport/7.0/logging.html) + * Logged to an [Ignition Transport `state.tlog` file](https://gazebosim.org/api/transport/7.0/logging.html) * Recording must be enabled from the command line or the C++ API * Can be played back using the command line or the C++ API diff --git a/tutorials/logical_audio_sensor.md b/tutorials/logical_audio_sensor.md index 0a1e776e47..526ece535a 100644 --- a/tutorials/logical_audio_sensor.md +++ b/tutorials/logical_audio_sensor.md @@ -8,7 +8,7 @@ The logical audio plugin does not play actual audio to a device like speakers, b ## Setup -Let's take a look at [logical_audio_sensor_plugin.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/460d2b1cfbf0addf05a1e61c05e1f7a675a83785/examples/worlds/logical_audio_sensor_plugin.sdf), which defines a simulation world with 4 models (in this case, boxes) that have an audio object attached to them. +Let's take a look at [logical_audio_sensor_plugin.sdf](https://github.com/gazebosim/gz-sim/blob/460d2b1cfbf0addf05a1e61c05e1f7a675a83785/examples/worlds/logical_audio_sensor_plugin.sdf), which defines a simulation world with 4 models (in this case, boxes) that have an audio object attached to them. This world attaches logical audio sources to the `red_box` and `blue_box` models, and attaches logical microphones to the `green_box` and `yellow_box` models. Let's take a look at the SDF relevant to the source for `red_box` to understand how to define a logical audio source in SDF: @@ -30,7 +30,7 @@ Let's take a look at the SDF relevant to the source for `red_box` to understand ``` As we can see, we use a `` tag to define an audio source. -An explanation of all of the tags can be found in the [plugin documentation](https://github.com/ignitionrobotics/ign-gazebo/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130), but there are a few important things to point out: +An explanation of all of the tags can be found in the [plugin documentation](https://github.com/gazebosim/gz-sim/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130), but there are a few important things to point out: * `` is used to identify this source when operating on it via services (services will be discussed later). Since a model can have multiple sources and microphones attached to it, each source attached to a particular model must have a unique ID. This means that no other sources attached to `red_box` can have an ID of 1, but sources attached to other models can have an ID of 1 (assuming that other models don't already have a source with an ID of 1 attached to it). @@ -55,7 +55,7 @@ Let's now take a look at the SDF relevant to the microphone for `green_box` to u ``` The same rules regarding `` and `` for a logical audio source also apply to a logical microphone. -You can also take a look at the [microphone documentation](https://github.com/ignitionrobotics/ign-gazebo/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130) for a detailed explanation of the tags embedded in the `` tag. +You can also take a look at the [microphone documentation](https://github.com/gazebosim/gz-sim/blob/314477419d2aa946f384204dc99b17d9fcd963b3/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh#L35-L130) for a detailed explanation of the tags embedded in the `` tag. ## Testing Source and Microphone Behavior diff --git a/tutorials/mesh_to_fuel.md b/tutorials/mesh_to_fuel.md index b3667a1353..e543a75f60 100644 --- a/tutorials/mesh_to_fuel.md +++ b/tutorials/mesh_to_fuel.md @@ -1,17 +1,17 @@ \page meshtofuel Importing a Mesh to Fuel -This tutorial will explain how to import a mesh to the [Ignition Fuel](https://app.ignitionrobotics.org) web application. +This tutorial will explain how to import a mesh to the [Ignition Fuel](https://app.gazebosim.org) web application. Adding models and/or worlds to Fuel will make your content readily available to the open source robotics simulation community, and easier to use with the Ignition GUI. ## Prerequisites To import meshes to Fuel, you need to have a user account. -Go to [app.ignitionrobotics.org](https://app.ignitionrobotics.org) and click Login in the top right corner of the screen, then click Sign Up. +Go to [app.gazebosim.org](https://app.gazebosim.org) and click Login in the top right corner of the screen, then click Sign Up. Once you verify your email address, your account will be ready. You'll need a mesh ready before trying to import to Fuel. There are several ways to acquire a mesh. -To save time, we'll use this [Electrical Box model](https://app.ignitionrobotics.org/openrobotics/fuel/models/Electrical%20Box) that you can download from Fuel. +To save time, we'll use this [Electrical Box model](https://app.gazebosim.org/openrobotics/fuel/models/Electrical%20Box) that you can download from Fuel. ## Model Directory Structure @@ -126,17 +126,17 @@ Click the `Add folders` button, or drag and drop the `Electrical Box` folder you All the files in your model description will be listed there. Press `Upload`, and the "Fuel Model Info" page for your model will open. -![Electrical Box Test](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/model_info2.png) +![Electrical Box Test](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/mesh_to_fuel/model_info2.png) You can always delete a model by clicking the "Edit model" button and then selecting "Delete model" at the bottom of the page -![Delete model](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/delete2.png) +![Delete model](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/mesh_to_fuel/delete2.png) ## Include the Model in a World With your mesh successfully uploaded to Fuel, you can now easily include it in a world SDF file. -Copy [this example world code](https://github.com/ignitionrobotics/ign-gazebo/raw/main/examples/worlds/import_mesh.sdf) into a text editor and save it as `import_mesh.sdf`. +Copy [this example world code](https://github.com/gazebosim/gz-sim/raw/main/examples/worlds/import_mesh.sdf) into a text editor and save it as `import_mesh.sdf`. This is a simple world SDF file, which you can learn more about on the [SDF website](http://sdformat.org/). Scroll all the way to the bottom of the file until you see the `include` tag section following the `` comment line. @@ -156,7 +156,7 @@ Scroll all the way to the bottom of the file until you see the `include` tag sec true Electrical Box 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Electrical Box + https://fuel.gazebosim.org/1.0/openrobotics/models/Electrical Box @@ -171,7 +171,7 @@ Change `Electrical Box` to `Electrical Box Test`. The syntax for including any model from Fuel is: ```xml -https://fuel.ignitionrobotics.org/1.0//models/ +https://fuel.gazebosim.org/1.0//models/ ``` ### Launch World @@ -182,4 +182,4 @@ To launch the world and see your mesh, run Ignition from inside the directory wh ign gazebo import_mesh.sdf ``` -![Launch sample world with mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/launch_world2.png) +![Launch sample world with mesh](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/mesh_to_fuel/launch_world2.png) diff --git a/tutorials/migrating_ardupilot_plugin.md b/tutorials/migrating_ardupilot_plugin.md index 021ee9adc4..c92a196615 100644 --- a/tutorials/migrating_ardupilot_plugin.md +++ b/tutorials/migrating_ardupilot_plugin.md @@ -22,7 +22,7 @@ documentation](https://ardupilot.org/dev/docs/using-gazebo-simulator-with-sitl.h As context to understand what we're migrating, here's a system diagram for how the ArduPilot Gazebo plugin works is used: - + *UAV icon credit: By Julian Herzog, CC BY 4.0, https://commons.wikimedia.org/w/index.php?curid=60965475* @@ -224,8 +224,8 @@ To better understand the ECS pattern as it is used in Ignition, it's helpful to learn about the EntityComponentManager (ECM), which is responsible for managing the ECS graph. A great resource to understand the logic under the hood of the ECM is the `SdfEntityCreator` class -([header](https://github.com/ignitionrobotics/ign-gazebo/blob/main/include/ignition/gazebo/SdfEntityCreator.hh), -[source](https://github.com/ignitionrobotics/ign-gazebo/blob/main/src/SdfEntityCreator.cc)). +([header](https://github.com/gazebosim/gz-sim/blob/main/include/ignition/gazebo/SdfEntityCreator.hh), +[source](https://github.com/gazebosim/gz-sim/blob/main/src/SdfEntityCreator.cc)). This class is responsible for mapping the content of an SDF file to the entities and components that form the graph handled by the ECM. For example, if you wonder which components can be accessed by default from the plugin, this diff --git a/tutorials/migration_link_api.md b/tutorials/migration_link_api.md index 8a610a9c87..6d6c2d020c 100644 --- a/tutorials/migration_link_api.md +++ b/tutorials/migration_link_api.md @@ -14,7 +14,7 @@ class. If you're trying to use some API which doesn't have an equivalent on Ignition yet, feel free to -[ticket an issue](https://github.com/ignitionrobotics/ign-gazebo/issues/). +[ticket an issue](https://github.com/gazebosim/gz-sim/issues/). ## Link API diff --git a/tutorials/migration_model_api.md b/tutorials/migration_model_api.md index de79a30bc0..a4f6b05cb7 100644 --- a/tutorials/migration_model_api.md +++ b/tutorials/migration_model_api.md @@ -14,7 +14,7 @@ class. If you're trying to use some API which doesn't have an equivalent on Ignition yet, feel free to -[ticket an issue](https://github.com/ignitionrobotics/ign-gazebo/issues/). +[ticket an issue](https://github.com/gazebosim/gz-sim/issues/). ## Model API diff --git a/tutorials/migration_sdf.md b/tutorials/migration_sdf.md index 30d3978bff..d49e0c326e 100644 --- a/tutorials/migration_sdf.md +++ b/tutorials/migration_sdf.md @@ -198,7 +198,7 @@ sure you're loading the correct plugins. Both simulators are installed with several built-in plugins. [Gazebo classic's plugins](https://github.com/osrf/gazebo/tree/gazebo11/plugins) and -[Ignition Gazebo's plugins](https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/systems) +[Ignition Gazebo's plugins](https://github.com/gazebosim/gz-sim/tree/main/src/systems) have different file names. For example, to use Gazebo classic's differential drive plugin, the user can refer to it as follows: diff --git a/tutorials/migration_world_api.md b/tutorials/migration_world_api.md index a377214b35..230bac2dbe 100644 --- a/tutorials/migration_world_api.md +++ b/tutorials/migration_world_api.md @@ -14,7 +14,7 @@ class. If you're trying to use some API which doesn't have an equivalent on Ignition yet, feel free to -[ticket an issue](https://github.com/ignitionrobotics/ign-gazebo/issues/). +[ticket an issue](https://github.com/gazebosim/gz-sim/issues/). ## World API diff --git a/tutorials/physics.md b/tutorials/physics.md index e1cac1a129..42d374e1ac 100644 --- a/tutorials/physics.md +++ b/tutorials/physics.md @@ -2,7 +2,7 @@ Ignition Gazebo supports choosing what physics engine to use at runtime. This is made possible by -[Ignition Physics](https://ignitionrobotics.org/libs/physics)' abstraction +[Ignition Physics](https://gazebosim.org/libs/physics)' abstraction layer. Ignition Gazebo uses the [DART](https://dartsim.github.io/) physics engine @@ -10,7 +10,7 @@ by default. Downstream developers may also integrate other physics engines by creating new Ignition Physics engine plugins. See -[Ignition Physics](https://ignitionrobotics.org/api/physics/2.0/tutorials.html)'s +[Ignition Physics](https://gazebosim.org/api/physics/2.0/tutorials.html)'s tutorials to learn how to integrate a new engine. ## How Gazebo finds engines diff --git a/tutorials/point_cloud_to_mesh.md b/tutorials/point_cloud_to_mesh.md index cd7fff694b..91af03aec4 100644 --- a/tutorials/point_cloud_to_mesh.md +++ b/tutorials/point_cloud_to_mesh.md @@ -20,7 +20,7 @@ After installing, open CloudCompare and import your point cloud file by going to Depending on the number of points in your point cloud, this could take several minutes. Once loaded, you should see the following tunnel section: -![Opening the point cloud](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/cloudcompare2.png) +![Opening the point cloud](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/cloudcompare2.png) Many 3D scans will be composed of millions, sometimes hundreds of millions of points. Converting a scan to a 3D model with that many points would be very difficult due to the number of polygons that would be created and the long processing time necessary to compute the normals. @@ -34,13 +34,13 @@ We'll still walk through reducing points, however, to make the process quicker. To reduce the number of points in your cloud, click on the tunnel so a yellow cube outline appears around it, then go to `Edit` > `Subsample`. -![Min. space between points](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/min_space.png) +![Min. space between points](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/min_space.png) The number you will need to enter in the `min. space between points` field will vary depending on your point cloud. A value of .01 was sufficient to bring our point cloud to an easy-to-manage 1 million points. Point count is visible in the `Properties` window on the lower left side of the screen. -![Point count of subsample](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/properties.png) +![Point count of subsample](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/properties.png) How many points you reduce down to will largely depend on how long you are willing to wait for the point cloud to be converted into a mesh. The more points you start with, the longer it will take to compute the normals and create the mesh. @@ -48,7 +48,7 @@ The more points you start with, the longer it will take to compute the normals a After the operation is complete you’ll have two clouds in your scene: the original point cloud and your subsampled point cloud. Most operations in CloudCompare will create new point clouds and keep the original, so make sure that you have the new point cloud selected before running an operation. -![Selecting the new point cloud](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/secondcloud.png) +![Selecting the new point cloud](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/secondcloud.png) ### Create a Polygonal Mesh @@ -59,7 +59,7 @@ A normal is essentially the direction a polygon is facing. To do this, go to `Edit` > `Normals` > `Compute`. You'll see this dialog box: -![Choose Triangulation surface model](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/compute_normals.png) +![Choose Triangulation surface model](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/compute_normals.png) You’ll see various options in the dialog box that appears. The main thing you’ll want to consider is what `Local surface model` to use. @@ -72,7 +72,7 @@ Now we get to actually convert our point cloud to a mesh. To do this go to `Plugins` > `PoissonRecon`. You'll see this dialog box: -![Octree depth and output density selection](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/outputdensity.png) +![Octree depth and output density selection](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/outputdensity.png) The value you enter in the `Octree depth` field will determine the polygon count of the created model. You may have to run the surface reconstruction a couple times with varying values before you land on a polygon count that is suitable for your needs. @@ -93,18 +93,18 @@ Our tunnel has turned into a blob shape. This is because the mesh that CloudCompare creates will always be water tight even if it has to add polygons where there are no points. We just want our tunnels, though, so we need to remove those unnecessary polygons. -![The blob shape](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/blob2.png) +![The blob shape](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/blob2.png) This is where our scalar field comes in. In the mesh's `Properties` window go to `SF display params` and take the left handle in the graph and drag it to the right until it hits the area where the bulk of the scalar field starts. -![Adjusting scalar filed params](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/sf_display.png) +![Adjusting scalar filed params](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/sf_display.png) This will display only the polygons that were created from the point cloud and hide the polygons used to make the model watertight. The polygons are only hidden however. We still need to actually remove them. -![Display original polygons](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/hidden_polygons2.png) +![Display original polygons](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/hidden_polygons2.png) To remove the hidden polygons go to `Edit` > `Scalar fields` > `Filter By Value`. @@ -113,7 +113,7 @@ Hitting export will simply export the mesh within that range. Instead, we'll hit `Split` to create two meshes. One with the polygons inside our specified range and one containing polygons outside that range. -![Splitting the mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/split.png) +![Splitting the mesh](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/split.png) ### The Completed Model @@ -121,6 +121,6 @@ By hitting `Split` we can view the model before exporting by simply going to `Fi Remember to have the correct mesh selected (`.part`) since choosing `Split` will give you two new meshes, plus you will still have your original, complete mesh. Your file format will depend on the software you want to use but `.obj` is a widely supported format that should work in most 3D applications. -![The completed mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/point_cloud_to_mesh/complete2.png) +![The completed mesh](https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/point_cloud_to_mesh/complete2.png) You can find more information on CloudCompare and a more in depth look at the tools we used in this tutorial on [the CloudCompare website](https://www.cloudcompare.org/) and the [CloudCompare wiki](https://www.cloudcompare.org/doc/wiki/index.php?title=Main_Page). diff --git a/tutorials/rendering_plugins.md b/tutorials/rendering_plugins.md index ead63d9e38..0acc5bd7f5 100644 --- a/tutorials/rendering_plugins.md +++ b/tutorials/rendering_plugins.md @@ -4,11 +4,11 @@ This tutorial will go over how to write Ignition Gazebo plugins that alter the 3D scene's visual appearance using Ignition Rendering APIs. This is not to be confused with integrating a new rendering engine. See -[How to write your own rendering engine plugin](https://ignitionrobotics.org/api/rendering/4.2/renderingplugin.html) +[How to write your own rendering engine plugin](https://gazebosim.org/api/rendering/4.2/renderingplugin.html) for that. This tutorial will go over a couple of example plugins that are located at -https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo6/examples/plugin/rendering_plugins. +https://github.com/gazebosim/gz-sim/tree/ign-gazebo6/examples/plugin/rendering_plugins. ## Scenes @@ -45,10 +45,10 @@ To interact with the server-side scene, you'll need to write an See [Create System Plugins](createsystemplugins.html). To interact with the client-side scene, you'll need to write an -[ignition::gui::Plugin](https://ignitionrobotics.org/api/gui/4.1/classignition_1_1gui_1_1Plugin.html), +[ignition::gui::Plugin](https://gazebosim.org/api/gui/4.1/classignition_1_1gui_1_1Plugin.html), or a more specialized `ignition::gazebo::GuiSystem` if you need to access entities and components. -See the [GUI system plugin example](https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo6/examples/plugin/gui_system_plugin). +See the [GUI system plugin example](https://github.com/gazebosim/gz-sim/tree/main/examples/plugin/gui_system_plugin). ## Getting the scene @@ -72,7 +72,7 @@ different for each plugin type. ### Render events on the GUI The GUI plugin will need to listen to -[ignition::gui::events::Render](https://ignitionrobotics.org/api/gui/4.1/classignition_1_1gui_1_1events_1_1Render.html) +[ignition::gui::events::Render](https://gazebosim.org/api/gui/4.1/classignition_1_1gui_1_1events_1_1Render.html) events. Here's how to do it: 1. Include the GUI events header: @@ -123,7 +123,7 @@ Here's how to do it: ## Running examples Follow the build instructions on the rendering plugins -[README](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo6/examples/plugin/rendering_plugins) +[README](https://github.com/gazebosim/gz-sim/blob/main/examples/plugin/rendering_plugins) and you'll generate both plugins: * `RenderingGuiPlugin`: GUI plugin that updates the GUI scene's ambient light with a random color at each click. diff --git a/tutorials/resources.md b/tutorials/resources.md index a086a4fba4..9e735f345b 100644 --- a/tutorials/resources.md +++ b/tutorials/resources.md @@ -44,14 +44,14 @@ Ignition will look for system plugins on the following paths, in order: ### Ignition GUI plugins -Each [Ignition GUI](https://ignitionrobotics.org/libs/rendering) plugin +Each [Ignition GUI](https://gazebosim.org/libs/rendering) plugin defines a widget. GUI plugins may be loaded through: * Tags in SDF world files, where `filename` is the shared library: * `` -* Tags in [GUI config files](https://ignitionrobotics.org/api/gui/4.2/config.html), +* Tags in [GUI config files](https://gazebosim.org/api/gui/3.0/config.html), where `filename` is the shared library: * `` * The plugin menu on the top-right of the screen. @@ -59,27 +59,27 @@ GUI plugins may be loaded through: Ignition will look for GUI plugins on the following paths, in order: 1. All paths set on the `IGN_GUI_PLUGIN_PATH` environment variable -2. [GUI plugins that are installed with Ignition Gazebo](https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/gui/plugins) +2. [GUI plugins that are installed with Ignition Gazebo](https://github.com/gazebosim/gz-sim/tree/main/src/gui/plugins) 3. Other paths added by calling `ignition::gui::App()->AddPluginPath` 4. `~/.ignition/gui/plugins` -5. [Plugins which are installed with Ignition GUI](https://ignitionrobotics.org/api/gui/4.2/namespaceignition_1_1gui_1_1plugins.html) +5. [Plugins which are installed with Ignition GUI](https://gazebosim.org/api/gui/4.2/namespaceignition_1_1gui_1_1plugins.html) ### Physics engines -[Ignition Physics](https://ignitionrobotics.org/libs/physics) +[Ignition Physics](https://gazebosim.org/libs/physics) uses a plugin architecture and its physics engines are built as plugins that are loaded at run time using -[Ignition Plugin](https://ignitionrobotics.org/libs/plugin). +[Ignition Plugin](https://gazebosim.org/libs/plugin). See the [Physics engines](physics.html) tutorial for more details. ### Rendering engines -[Ignition Rendering](https://ignitionrobotics.org/libs/rendering) +[Ignition Rendering](https://gazebosim.org/libs/rendering) uses a plugin architecture and its render engines are built as plugins that are loaded at run time using -[Ignition Plugin](https://ignitionrobotics.org/libs/plugin). +[Ignition Plugin](https://gazebosim.org/libs/plugin). At the moment, Ignition Rendering will only look for render engine plugin shared libraries installed within its `/lib` directory. @@ -89,9 +89,9 @@ Rendering's `/share` directory. ### Sensors Each unique type of sensor in -[Ignition Sensors](https://ignitionrobotics.org/libs/sensors) is a plugin. When +[Ignition Sensors](https://gazebosim.org/libs/sensors) is a plugin. When a particular sensor type is requested, the relevant plugin is loaded by -[Ignition Plugin](https://ignitionrobotics.org/libs/plugin) and a +[Ignition Plugin](https://gazebosim.org/libs/plugin) and a sensor object is instantiated from it. At the moment, Ignition Sensors will only look for sensor plugin @@ -119,7 +119,7 @@ Ignition will look for URIs (path / URL) in the following, in order: 1. All paths on the `IGN_GAZEBO_RESOURCE_PATH`\* environment variable (if path is URI, scheme is stripped) 2. Current running path / absolute path -3. [Ignition Fuel](https://app.ignitionrobotics.org/fuel/models) +3. [Ignition Fuel](https://app.gazebosim.org/fuel/models) 1. Cache (i.e. `$HOME/.ignition/fuel`) 2. Web server @@ -147,7 +147,7 @@ Ignition will look for URIs (path / URL) in the following, in order: ### GUI configuration Ignition Gazebo's -[GUI configuration](https://ignitionrobotics.org/api/gui/4.2/config.html) +[GUI configuration](https://gazebosim.org/api/gui/4.2/config.html) can come from the following, in order: 1. The command line option `--gui-config ` diff --git a/tutorials/server_config.md b/tutorials/server_config.md index a9a27830f1..9faab891f6 100644 --- a/tutorials/server_config.md +++ b/tutorials/server_config.md @@ -114,11 +114,11 @@ favorite editor and save this file as `fuel_preview.sdf`: - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Sun + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Construction Cone @@ -182,12 +182,12 @@ Let's start by saving this simple world with a camera sensor as - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Sun + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun 0 0 1 0 0 0 - https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Gazebo + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Gazebo diff --git a/tutorials/terminology.md b/tutorials/terminology.md index 3742a569fe..806ad26f8a 100644 --- a/tutorials/terminology.md +++ b/tutorials/terminology.md @@ -66,7 +66,7 @@ to developers touching the source code. * **[Event manager](classignition_1_1gazebo_1_1EventManager.html)**: Manages events that can be sent across systems and the server. Plugins can create and emit custom - [Event](https://ignitionrobotics.org/api/common/3.0/classignition_1_1common_1_1Event.html)s + [Event](https://gazebosim.org/api/common/3.0/classignition_1_1common_1_1Event.html)s and / or emit / listen to events from Ignition Gazebo. * **Simulation runner**: Runs a whole world or some levels of a world, but no diff --git a/tutorials/test_fixture.md b/tutorials/test_fixture.md index 4b9b5611a4..3ba5b40178 100644 --- a/tutorials/test_fixture.md +++ b/tutorials/test_fixture.md @@ -10,7 +10,7 @@ using Continuous Integration (CI). Gazebo can be used for testing using any testing library. We provide an example of how to setup some test cases using [Google Test](https://github.com/google/googletest) in -[ign-gazebo/examples/standalone/gtest_setup](https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo6/examples/standalone/gtest_setup). +[ign-gazebo/examples/standalone/gtest_setup](https://github.com/gazebosim/gz-sim/tree/ign-gazebo6/examples/standalone/gtest_setup). The instructions on that example's `README` can be followed to compile and run those tests. Also be sure to go through the source code for comments with diff --git a/tutorials/triggered_publisher.md b/tutorials/triggered_publisher.md index ff4759c3ef..c783d428cc 100644 --- a/tutorials/triggered_publisher.md +++ b/tutorials/triggered_publisher.md @@ -16,10 +16,10 @@ Publisher systems can be chained together by showing how the falling of the box can trigger another box to fall. Last, it covers how a service call can be triggered to reset the robot pose. The finished world SDFormat file for this tutorial can be found in -[examples/worlds/triggered_publisher.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo2/examples/worlds/triggered_publisher.sdf) +[examples/worlds/triggered_publisher.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/triggered_publisher.sdf) We will use the differential drive vehicle from -[examples/worlds/diff_drive.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo2/examples/worlds/diff_drive.sdf), +[examples/worlds/diff_drive.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/diff_drive.sdf), but modify the input topic of the `DiffDrive` system to `cmd_vel`. A snippet of the change to the `DiffDrive` system is shown below: diff --git a/tutorials/video_recorder.md b/tutorials/video_recorder.md index c786dba6d0..dd6f899f9b 100644 --- a/tutorials/video_recorder.md +++ b/tutorials/video_recorder.md @@ -38,7 +38,7 @@ the [GUI Configuration](gui_config.html) tutorial for more information. If you launched Ignition Gazebo with the `video_record_dbl_pendulum.sdf` demo world, the GUI configurations are embedded in the world SDF file so you will need to download a copy of the -[sdf file](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/examples/worlds/video_record_dbl_pendulum.sdf). +[sdf file](https://raw.githubusercontent.com/gazebosim/gz-sim/main/examples/worlds/video_record_dbl_pendulum.sdf). and modify the GUI configuration in that file. On the other hand, if you launched Ignition Gazebo with a world file that does not have GUI configurations, you will need to specify the settings in From 6b103a033f08799fd5f22779d7a687f78e0b99cb Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Thu, 3 Nov 2022 19:14:26 -0700 Subject: [PATCH 23/28] Fix two tests on Windows (#1779) * Fix Server_TEST and remove some ignition:: * Fix SystemLoader_TEST on Windows Use NormalizeDirectoryPath to fix path comparisons. Signed-off-by: Steve Peters --- src/Server_TEST.cc | 14 +++++++------- src/SystemLoader_TEST.cc | 9 +++++---- 2 files changed, 12 insertions(+), 11 deletions(-) diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 59879223b5..6a95bf93b9 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -1108,9 +1108,9 @@ TEST_P(ServerFixture, AddResourcePaths) ///////////////////////////////////////////////// TEST_P(ServerFixture, ResolveResourcePaths) { - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", ""); - ignition::common::setenv("SDF_PATH", ""); - ignition::common::setenv("IGN_FILE_PATH", ""); + common::setenv("IGN_GAZEBO_RESOURCE_PATH", ""); + common::setenv("SDF_PATH", ""); + common::setenv("IGN_FILE_PATH", ""); ServerConfig serverConfig; gazebo::Server server(serverConfig); @@ -1143,10 +1143,10 @@ TEST_P(ServerFixture, ResolveResourcePaths) }); // Make sure the resource path is clear - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", ""); + common::setenv("IGN_GAZEBO_RESOURCE_PATH", ""); - // An absolute path should return the same absolute path - test(PROJECT_SOURCE_PATH, PROJECT_SOURCE_PATH, true); + // A valid path should be returned as an absolute path + test(PROJECT_SOURCE_PATH, common::absPath(PROJECT_SOURCE_PATH), true); // An absolute path, with the file:// prefix, should return the absolute path test(std::string("file://") + @@ -1168,7 +1168,7 @@ TEST_P(ServerFixture, ResolveResourcePaths) // The model:// URI should not resolve test("model://include_nested/model.sdf", "", false); - ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", + common::setenv("IGN_GAZEBO_RESOURCE_PATH", common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "models")); // The model:// URI should now resolve because the RESOURCE_PATH has been // updated. diff --git a/src/SystemLoader_TEST.cc b/src/SystemLoader_TEST.cc index 8d3882ec35..57832ff421 100644 --- a/src/SystemLoader_TEST.cc +++ b/src/SystemLoader_TEST.cc @@ -21,6 +21,7 @@ #include #include +#include #include "ignition/gazebo/System.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -93,13 +94,13 @@ TEST(SystemLoader, PluginPaths) for (const auto &s : paths) { // the returned path string may not be exact match due to extra '/' - // appended at the end of the string. So use absPath to generate - // a path string that matches the format returned by joinPaths - if (common::absPath(s) == testBuildPath) + // appended at the end of the string. So use NormalizeDirectoryPath + if (common::SystemPaths::NormalizeDirectoryPath(s) == + common::SystemPaths::NormalizeDirectoryPath(testBuildPath)) { hasPath = true; break; } } - EXPECT_TRUE(hasPath); + EXPECT_TRUE(hasPath) << testBuildPath; } From 3c06d743cdc59f510b0eda3ab4926cf64a215aeb Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Fri, 4 Nov 2022 10:21:24 -0500 Subject: [PATCH 24/28] =?UTF-8?q?=F0=9F=8E=88=206.13.0=20(#1781)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Michael Carroll --- CMakeLists.txt | 2 +- Changelog.md | 65 ++++++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 66 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c97405df04..d2cb82ef15 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-gazebo6 VERSION 6.12.0) +project(ignition-gazebo6 VERSION 6.13.0) set (GZ_DISTRIBUTION "Fortress") #============================================================================ diff --git a/Changelog.md b/Changelog.md index 3e0257d495..c69829ad8c 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,5 +1,70 @@ ## Ignition Gazebo 6.x +### Gazebo Sim 6.13.0 (2022-11-04) + +1. Fix two tests on Windows + * [Pull request #1779](https://github.com/gazebosim/ign-gazebo/pull/1779) + +1. 3 to 6 20221013 + * [Pull request #1762](https://github.com/gazebosim/ign-gazebo/pull/1762) + +1. Some minor changes to hydrodynamic flags test + * [Pull request #1772](https://github.com/gazebosim/ign-gazebo/pull/1772) + +1. Fix thruster integration test + * [Pull request #1767](https://github.com/gazebosim/ign-gazebo/pull/1767) + +1. Fix scene_broadcaster_system test + * [Pull request #1766](https://github.com/gazebosim/ign-gazebo/pull/1766) + +1. Script and tutorial for generating procedural datasets with Blender + * [Pull request #1412](https://github.com/gazebosim/ign-gazebo/pull/1412) + +1. Enable use of ign gazebo -s on Windows (take two) + * [Pull request #1764](https://github.com/gazebosim/ign-gazebo/pull/1764) + +1. Removed unused speedlimit file + * [Pull request #1761](https://github.com/gazebosim/ign-gazebo/pull/1761) + +1. Fortress: Removed warnings + * [Pull request #1754](https://github.com/gazebosim/ign-gazebo/pull/1754) + +1. Enable/Disable individual hydrodynamic components. + * [Pull request #1692](https://github.com/gazebosim/ign-gazebo/pull/1692) + +1. Adding thrust coefficient calculation + * [Pull request #1652](https://github.com/gazebosim/ign-gazebo/pull/1652) + +1. Restore Add System GUI plugin + * [Pull request #1685](https://github.com/gazebosim/ign-gazebo/pull/1685) + +1. Return absolute path when finding a resource + * [Pull request #1741](https://github.com/gazebosim/ign-gazebo/pull/1741) + +1. Adds sky cubemap URI to the sky.proto's header + * [Pull request #1739](https://github.com/gazebosim/ign-gazebo/pull/1739) + +1. Update triggered_publisher.sdf + * [Pull request #1737](https://github.com/gazebosim/ign-gazebo/pull/1737) + +1. Add ResourceSpawner example file + * [Pull request #1701](https://github.com/gazebosim/ign-gazebo/pull/1701) + +1. Enable inherited model topic name. + * [Pull request #1689](https://github.com/gazebosim/ign-gazebo/pull/1689) + +1. Fix loading render engine plugins in GUI + * [Pull request #1694](https://github.com/gazebosim/ign-gazebo/pull/1694) + +1. Add a service to trigger functionality + * [Pull request #1611](https://github.com/gazebosim/ign-gazebo/pull/1611) + +1. Fix installation instructions on Ubuntu 22.04 + * [Pull request #1686](https://github.com/gazebosim/ign-gazebo/pull/1686) + +1. Fix reference link in ackermann steering + * [Pull request #1683](https://github.com/gazebosim/ign-gazebo/pull/1683) + ### Gazebo Sim 6.12.0 (2022-08-30) 1. Add topic parameter to thrust plugin From 25ba1ce99f7a2f798f705998d712000cbf553ff8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Marko=20Kri=C5=BEman=C4=8Di=C4=87?= Date: Tue, 8 Nov 2022 23:48:51 +0100 Subject: [PATCH 25/28] Fix minor bugs in RFComms plugin (#1743) * Add more info to "bitrate limited" messages Signed-off-by: Marko Krizmancic * Fix variance and stddev usage in RFComms Input configuration for RFComms plugin takes sigma (standard deviation) for parametrizing normal distribution. The structure for holding distribution parameters (RFPower) is defined with mean and *variance*. So, in initialization, sigma squared should be given to the RFPower struct. Signed-off-by: Marko Krizmancic * Fix the running window of sent bytes in RFComms Because of the wrong comparison, the calculation of total bytes sent in one epoch may include one message extra, resulting in larger number of bytes sent than the actual. Signed-off-by: Marko Krizmancic * Fix the running window of received bytes in RFComms Signed-off-by: Marko Krizmancic * Fix message size calculation in RFComms Signed-off-by: Marko Krizmancic * Fix max line length limitation Signed-off-by: Marko Krizmancic --- src/systems/rf_comms/RFComms.cc | 29 ++++++++++++++++------------- 1 file changed, 16 insertions(+), 13 deletions(-) diff --git a/src/systems/rf_comms/RFComms.cc b/src/systems/rf_comms/RFComms.cc index c18cb6b20f..2ec1444cd0 100644 --- a/src/systems/rf_comms/RFComms.cc +++ b/src/systems/rf_comms/RFComms.cc @@ -128,6 +128,9 @@ struct RadioState /// \brief Accumulation of bytes received in an epoch. uint64_t bytesReceivedThisEpoch = 0; + + /// \brief Name of the model associated with the radio. + std::string name; }; /// \brief Type for holding RF power as a Normally distributed random variable. @@ -234,7 +237,7 @@ RFPower RFComms::Implementation::LogNormalReceivedPower( const double kPL = this->rangeConfig.l0 + 10 * this->rangeConfig.fadingExponent * log10(kRange); - return {_txPower - kPL, this->rangeConfig.sigma}; + return {_txPower - kPL, pow(this->rangeConfig.sigma, 2.)}; } ///////////////////////////////////////////// @@ -245,7 +248,7 @@ std::tuple RFComms::Implementation::AttemptSend( // Maintain running window of bytes sent over the last epoch, e.g., 1s. while (!_txState.bytesSent.empty() && - _txState.bytesSent.front().first < now - this->epochDuration) + _txState.bytesSent.front().first <= now - this->epochDuration) { _txState.bytesSentThisEpoch -= _txState.bytesSent.front().second; _txState.bytesSent.pop_front(); @@ -262,8 +265,10 @@ std::tuple RFComms::Implementation::AttemptSend( // Check current epoch bitrate vs capacity and fail to send accordingly if (bitsSent > this->radioConfig.capacity * this->epochDuration) { - ignwarn << "Bitrate limited: " << bitsSent << "bits sent (limit: " - << this->radioConfig.capacity * this->epochDuration << std::endl; + ignwarn << "Bitrate limited: [" << _txState.name << "] " << bitsSent + << " bits sent (limit: " + << this->radioConfig.capacity * this->epochDuration << ")" + << std::endl; return std::make_tuple(false, std::numeric_limits::lowest()); } @@ -303,7 +308,7 @@ std::tuple RFComms::Implementation::AttemptSend( // Maintain running window of bytes received over the last epoch, e.g., 1s. while (!_rxState.bytesReceived.empty() && - _rxState.bytesReceived.front().first < now - this->epochDuration) + _rxState.bytesReceived.front().first <= now - this->epochDuration) { _rxState.bytesReceivedThisEpoch -= _rxState.bytesReceived.front().second; _rxState.bytesReceived.pop_front(); @@ -320,9 +325,10 @@ std::tuple RFComms::Implementation::AttemptSend( // Check current epoch bitrate vs capacity and fail to send accordingly. if (bitsReceived > this->radioConfig.capacity * this->epochDuration) { - // ignwarn << "Bitrate limited: " << bitsReceived - // << "bits received (limit: " - // << this->radioConfig.capacity * this->epochDuration << std::endl; + ignwarn << "Bitrate limited: [" << _rxState.name << "] " << bitsReceived + << " bits received (limit: " + << this->radioConfig.capacity * this->epochDuration << ")" + << std::endl; return std::make_tuple(false, std::numeric_limits::lowest()); } @@ -421,6 +427,7 @@ void RFComms::Step( this->dataPtr->radioStates[address].pose = kPose; this->dataPtr->radioStates[address].timeStamp = std::chrono::duration(_info.simTime).count(); + this->dataPtr->radioStates[address].name = content.modelName; } } @@ -442,11 +449,7 @@ void RFComms::Step( continue; auto [sendPacket, rssi] = this->dataPtr->AttemptSend( -#if GOOGLE_PROTOBUF_VERSION < 3004001 - itSrc->second, itDst->second, msg->ByteSize()); -#else - itSrc->second, itDst->second, msg->ByteSizeLong()); -#endif + itSrc->second, itDst->second, msg->data().size()); if (sendPacket) { From 216d5a5103cf3925b00dd009ffbf757a7f460fe8 Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Wed, 9 Nov 2022 21:11:58 +0800 Subject: [PATCH 26/28] Addresses flakiness in `Hydrodynamics.VelocityTestInOil`. (#1787) This PR adjusts the hydrodynamics tests so they are abit less flaky. Currently, it seems like the test checks if one item falls faster than another. However due to the inherent parrallelism, it seems like on different computers the balls start falling at different times. This means the 4 time steps we wait for may not be enough for a difference in velocity to appear. I suspect we no longer need to disable this test on windows. Signed-off-by: Arjo Chakravarty --- test/integration/hydrodynamics.cc | 26 ++++++++++++++++---------- test/worlds/hydrodynamics.sdf | 8 -------- 2 files changed, 16 insertions(+), 18 deletions(-) diff --git a/test/integration/hydrodynamics.cc b/test/integration/hydrodynamics.cc index cfcab01f93..aeb29dc2da 100644 --- a/test/integration/hydrodynamics.cc +++ b/test/integration/hydrodynamics.cc @@ -120,6 +120,8 @@ TEST_F(HydrodynamicsTest, VelocityTestinOil) auto sphere1Vels = this->TestWorld(world, "sphere1"); auto sphere2Vels = this->TestWorld(world, "sphere2"); + auto whenSphere1ExceedsSphere2Vel = 2000; + for (unsigned int i = 0; i < 1000; ++i) { // Sanity check @@ -128,19 +130,23 @@ TEST_F(HydrodynamicsTest, VelocityTestinOil) EXPECT_FLOAT_EQ(0.0, sphere2Vels[i].X()); EXPECT_FLOAT_EQ(0.0, sphere2Vels[i].Y()); - // Wait a couple of iterations for the body to move - if(i > 4) + // Expect sphere1 to fall faster than sphere 2 as no hydro + // drag is applied to it. + EXPECT_LE(sphere1Vels[i].Z(), sphere2Vels[i].Z()); + if(sphere1Vels[i].Z() < sphere2Vels[i].Z() + && whenSphere1ExceedsSphere2Vel > 1000) + { + // Mark this as the time when velocity of sphere1 exceeds sphere 2 + whenSphere1ExceedsSphere2Vel = i; + } + if (i > 900) { - EXPECT_LT(sphere1Vels[i].Z(), sphere2Vels[i].Z()); - - if (i > 900) - { - // Expect for the velocity to stabilize - EXPECT_NEAR(sphere1Vels[i-1].Z(), sphere1Vels[i].Z(), 1e-6); - EXPECT_NEAR(sphere2Vels[i-1].Z(), sphere2Vels[i].Z(), 1e-6); - } + // Expect for the velocity to stabilize + EXPECT_NEAR(sphere1Vels[i-1].Z(), sphere1Vels[i].Z(), 1e-6); + EXPECT_NEAR(sphere2Vels[i-1].Z(), sphere2Vels[i].Z(), 1e-6); } } + EXPECT_LT(whenSphere1ExceedsSphere2Vel, 500); } ///////////////////////////////////////////////// diff --git a/test/worlds/hydrodynamics.sdf b/test/worlds/hydrodynamics.sdf index 234d6314ea..7fc4790c84 100644 --- a/test/worlds/hydrodynamics.sdf +++ b/test/worlds/hydrodynamics.sdf @@ -15,14 +15,6 @@ filename="ignition-gazebo-physics-system" name="ignition::gazebo::systems::Physics"> - - - - true From 78b66994bbef46d0d03917e935effe8886107343 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Fri, 11 Nov 2022 16:39:14 -0800 Subject: [PATCH 27/28] Address merge issues Signed-off-by: Nate Koenig --- Changelog.md | 2056 +++++++++-------- .../JointPositionController.cc | 2 +- .../plugins/scene_manager/GzSceneManager.cc | 6 - src/systems/physics/Physics.cc | 4 +- test/integration/level_manager.cc | 14 +- test/integration/sdf_include.cc | 2 +- test/worlds/diff_drive_no_plugin.sdf | 8 +- test/worlds/include.sdf | 2 +- 8 files changed, 1042 insertions(+), 1052 deletions(-) diff --git a/Changelog.md b/Changelog.md index 5f6176636f..dd0a808ba3 100644 --- a/Changelog.md +++ b/Changelog.md @@ -721,1880 +721,1880 @@ 1. Set simulation time to Rendering * [Pull request #1415](https://github.com/gazebosim/gz-sim/pull/1415) -### Ignition Gazebo 6.9.0 (2022-04-14) +### Gazebo Sim 6.9.0 (2022-04-14) 1. Add new `RFComms` system - * [Pull request #1428](https://github.com/ignitionrobotics/ign-gazebo/pull/1428) + * [Pull request #1428](https://github.com/gazebosim/gz-sim/pull/1428) 1. Add comms infrastructure - * [Pull request #1416](https://github.com/ignitionrobotics/ign-gazebo/pull/1416) + * [Pull request #1416](https://github.com/gazebosim/gz-sim/pull/1416) 1. Fix CMake version examples and bump plugin version - * [Pull request #1442](https://github.com/ignitionrobotics/ign-gazebo/pull/1442) + * [Pull request #1442](https://github.com/gazebosim/gz-sim/pull/1442) 1. Make sure pose publisher creates valid pose topics - * [Pull request #1433](https://github.com/ignitionrobotics/ign-gazebo/pull/1433) + * [Pull request #1433](https://github.com/gazebosim/gz-sim/pull/1433) 1. Add Ubuntu Jammy CI - * [Pull request #1418](https://github.com/ignitionrobotics/ign-gazebo/pull/1418) + * [Pull request #1418](https://github.com/gazebosim/gz-sim/pull/1418) 1. Removed `screenToPlane` method and use `rendering::screenToPlane` - * [Pull request #1432](https://github.com/ignitionrobotics/ign-gazebo/pull/1432) + * [Pull request #1432](https://github.com/gazebosim/gz-sim/pull/1432) 1. Supply world frame orientation and heading to IMU sensor (#1427) - * [Pull request #1427](https://github.com/ignitionrobotics/ign-gazebo/pull/1427) + * [Pull request #1427](https://github.com/gazebosim/gz-sim/pull/1427) 1. Add desktop entry and SVG logo - * [Pull request #1411](https://github.com/ignitionrobotics/ign-gazebo/pull/1411) - * [Pull request #1430](https://github.com/ignitionrobotics/ign-gazebo/pull/1430) + * [Pull request #1411](https://github.com/gazebosim/gz-sim/pull/1411) + * [Pull request #1430](https://github.com/gazebosim/gz-sim/pull/1430) 1. Fix segfault at exit - * [Pull request #1317](https://github.com/ignitionrobotics/ign-gazebo/pull/1317) + * [Pull request #1317](https://github.com/gazebosim/gz-sim/pull/1317) 1. Add Gaussian noise to Odometry Publisher - * [Pull request #1393](https://github.com/ignitionrobotics/ign-gazebo/pull/1393) + * [Pull request #1393](https://github.com/gazebosim/gz-sim/pull/1393) -### Ignition Gazebo 6.8.0 (2022-04-04) +### Gazebo Sim 6.8.0 (2022-04-04) 1. ServerConfig accepts an sdf::Root DOM object - * [Pull request #1333](https://github.com/ignitionrobotics/ign-gazebo/pull/1333) + * [Pull request #1333](https://github.com/gazebosim/gz-sim/pull/1333) 1. Disable sensors in sensors system when battery is drained - * [Pull request #1385](https://github.com/ignitionrobotics/ign-gazebo/pull/1385) + * [Pull request #1385](https://github.com/gazebosim/gz-sim/pull/1385) 1. Referring to Fuel assets within a heightmap - * [Pull request #1419](https://github.com/ignitionrobotics/ign-gazebo/pull/1419) + * [Pull request #1419](https://github.com/gazebosim/gz-sim/pull/1419) 1. Add the Model Photo Shoot system, port of Modelpropshop plugin from Gazebo classic - * [Pull request #1331](https://github.com/ignitionrobotics/ign-gazebo/pull/1331) + * [Pull request #1331](https://github.com/gazebosim/gz-sim/pull/1331) 1. Distortion camera integration test - * [Pull request #1374](https://github.com/ignitionrobotics/ign-gazebo/pull/1374) + * [Pull request #1374](https://github.com/gazebosim/gz-sim/pull/1374) 1. Add wheel slip user command - * [Pull request #1241](https://github.com/ignitionrobotics/ign-gazebo/pull/1241) + * [Pull request #1241](https://github.com/gazebosim/gz-sim/pull/1241) 1. SceneBroadcaster: only send changed state information for change events - * [Pull request #1392](https://github.com/ignitionrobotics/ign-gazebo/pull/1392) + * [Pull request #1392](https://github.com/gazebosim/gz-sim/pull/1392) 1. Fortress: Install Ogre 2.2, simplify docker - * [Pull request #1395](https://github.com/ignitionrobotics/ign-gazebo/pull/1395) + * [Pull request #1395](https://github.com/gazebosim/gz-sim/pull/1395) 1. Disable tests that are expected to fail on Windows - * [Pull request #1408](https://github.com/ignitionrobotics/ign-gazebo/pull/1408) + * [Pull request #1408](https://github.com/gazebosim/gz-sim/pull/1408) 1. Added user command to set multiple entities - * [Pull request #1394](https://github.com/ignitionrobotics/ign-gazebo/pull/1394) + * [Pull request #1394](https://github.com/gazebosim/gz-sim/pull/1394) 1. Fix JointStatePublisher topic name for nested models - * [Pull request #1405](https://github.com/ignitionrobotics/ign-gazebo/pull/1405) + * [Pull request #1405](https://github.com/gazebosim/gz-sim/pull/1405) 1. add initial_position param to joint controller system - * [Pull request #1406](https://github.com/ignitionrobotics/ign-gazebo/pull/1406) + * [Pull request #1406](https://github.com/gazebosim/gz-sim/pull/1406) 1. Component inspector: refactor Pose3d C++ code into a separate class - * [Pull request #1400](https://github.com/ignitionrobotics/ign-gazebo/pull/1400) + * [Pull request #1400](https://github.com/gazebosim/gz-sim/pull/1400) 1. Prevent hanging when world has only non-world plugins - * [Pull request #1383](https://github.com/ignitionrobotics/ign-gazebo/pull/1383) + * [Pull request #1383](https://github.com/gazebosim/gz-sim/pull/1383) 1. Toggle Light visuals - * [Pull request #1387](https://github.com/ignitionrobotics/ign-gazebo/pull/1387) + * [Pull request #1387](https://github.com/gazebosim/gz-sim/pull/1387) 1. Disable PeerTracker.PeerTrackerStale on macOS - * [Pull request #1398](https://github.com/ignitionrobotics/ign-gazebo/pull/1398) + * [Pull request #1398](https://github.com/gazebosim/gz-sim/pull/1398) 1. Disable ModelCommandAPI_TEST.RgbdCameraSensor on macOS - * [Pull request #1397](https://github.com/ignitionrobotics/ign-gazebo/pull/1397) + * [Pull request #1397](https://github.com/gazebosim/gz-sim/pull/1397) 1. Don't mark entities with a ComponentState::NoChange component as modified - * [Pull request #1391](https://github.com/ignitionrobotics/ign-gazebo/pull/1391) + * [Pull request #1391](https://github.com/gazebosim/gz-sim/pull/1391) 1. Add gazebo Entity id to rendering sensor's user data - * [Pull request #1381](https://github.com/ignitionrobotics/ign-gazebo/pull/1381) + * [Pull request #1381](https://github.com/gazebosim/gz-sim/pull/1381) 1. Allow to turn on/off lights - * [Pull request #1343](https://github.com/ignitionrobotics/ign-gazebo/pull/1343) + * [Pull request #1343](https://github.com/gazebosim/gz-sim/pull/1343) 1. Added headless rendering tutorial - * [Pull request #1386](https://github.com/ignitionrobotics/ign-gazebo/pull/1386) + * [Pull request #1386](https://github.com/gazebosim/gz-sim/pull/1386) 1. Add xyz and rpy offset to published odometry pose - * [Pull request #1341](https://github.com/ignitionrobotics/ign-gazebo/pull/1341) + * [Pull request #1341](https://github.com/gazebosim/gz-sim/pull/1341) 1. Fix visualization python tutorial - * [Pull request #1377](https://github.com/ignitionrobotics/ign-gazebo/pull/1377) + * [Pull request #1377](https://github.com/gazebosim/gz-sim/pull/1377) 1. Populate GUI plugins that are empty - * [Pull request #1375](https://github.com/ignitionrobotics/ign-gazebo/pull/1375) + * [Pull request #1375](https://github.com/gazebosim/gz-sim/pull/1375) -### Ignition Gazebo 6.7.0 (2022-02-24) +### Gazebo Sim 6.7.0 (2022-02-24) -1. Added Python interfaces to some Ignition Gazebo methods - * [Pull request #1219](https://github.com/ignitionrobotics/ign-gazebo/pull/1219) +1. Added Python interfaces to some Gazebo Sim methods + * [Pull request #1219](https://github.com/gazebosim/gz-sim/pull/1219) 1. Use pose multiplication instead of addition - * [Pull request #1369](https://github.com/ignitionrobotics/ign-gazebo/pull/1369) + * [Pull request #1369](https://github.com/gazebosim/gz-sim/pull/1369) 1. Disables Failing Buoyancy Tests on Win32 - * [Pull request #1368](https://github.com/ignitionrobotics/ign-gazebo/pull/1368) + * [Pull request #1368](https://github.com/gazebosim/gz-sim/pull/1368) 1. Extend ShaderParam system to support loading different shader languages - * [Pull request #1335](https://github.com/ignitionrobotics/ign-gazebo/pull/1335) + * [Pull request #1335](https://github.com/gazebosim/gz-sim/pull/1335) 1. Populate names of colliding entities in contact points message - * [Pull request #1351](https://github.com/ignitionrobotics/ign-gazebo/pull/1351) + * [Pull request #1351](https://github.com/gazebosim/gz-sim/pull/1351) 1. Refactor System functionality into SystemManager - * [Pull request #1340](https://github.com/ignitionrobotics/ign-gazebo/pull/1340) + * [Pull request #1340](https://github.com/gazebosim/gz-sim/pull/1340) 1. GzSceneManager: Prevent crash boom when inserted from menu - * [Pull request #1371](https://github.com/ignitionrobotics/ign-gazebo/pull/1371) + * [Pull request #1371](https://github.com/gazebosim/gz-sim/pull/1371) -### Ignition Gazebo 6.6.0 (2022-02-24) +### Gazebo Sim 6.6.0 (2022-02-24) 1. Fix accessing empty JointPosition component in lift drag plugin - * [Pull request #1366](https://github.com/ignitionrobotics/ign-gazebo/pull/1366) + * [Pull request #1366](https://github.com/gazebosim/gz-sim/pull/1366) 1. Add parameter to TrajectoryFollower stop rotation when bearing is reached - * [Pull request #1349](https://github.com/ignitionrobotics/ign-gazebo/pull/1349) + * [Pull request #1349](https://github.com/gazebosim/gz-sim/pull/1349) 1. Support disabling pose publisher from publishing top level model pose - * [Pull request #1342](https://github.com/ignitionrobotics/ign-gazebo/pull/1342) + * [Pull request #1342](https://github.com/gazebosim/gz-sim/pull/1342) 1. Added more sensor properties to scene/info topic - * [Pull request #1344](https://github.com/ignitionrobotics/ign-gazebo/pull/1344) + * [Pull request #1344](https://github.com/gazebosim/gz-sim/pull/1344) 1. Adding ability to pause/resume the trajectory follower behavior. - * [Pull request #1347](https://github.com/ignitionrobotics/ign-gazebo/pull/1347) + * [Pull request #1347](https://github.com/gazebosim/gz-sim/pull/1347) 1. Logs a warning if a mode is not clearly sepecified. - * [Pull request #1307](https://github.com/ignitionrobotics/ign-gazebo/pull/1307) + * [Pull request #1307](https://github.com/gazebosim/gz-sim/pull/1307) 1. JointStatePublisher publish parent, child and axis data - * [Pull request #1345](https://github.com/ignitionrobotics/ign-gazebo/pull/1345) + * [Pull request #1345](https://github.com/gazebosim/gz-sim/pull/1345) 1. Fixed light gui component inspector - * [Pull request #1337](https://github.com/ignitionrobotics/ign-gazebo/pull/1337) + * [Pull request #1337](https://github.com/gazebosim/gz-sim/pull/1337) 1. Fix UNIT_SdfGenerator_TEST - * [Pull request #1319](https://github.com/ignitionrobotics/ign-gazebo/pull/1319) + * [Pull request #1319](https://github.com/gazebosim/gz-sim/pull/1319) 1. Add elevator system - * [Pull request #535](https://github.com/ignitionrobotics/ign-gazebo/pull/535) + * [Pull request #535](https://github.com/gazebosim/gz-sim/pull/535) 1. Removed unused variables in shapes plugin - * [Pull request #1321](https://github.com/ignitionrobotics/ign-gazebo/pull/1321) + * [Pull request #1321](https://github.com/gazebosim/gz-sim/pull/1321) -### Ignition Gazebo 6.5.0 (2022-02-15) +### Gazebo Sim 6.5.0 (2022-02-15) 1. New trajectory follower system - * [Pull request #1332](https://github.com/ignitionrobotics/ign-gazebo/pull/1332) + * [Pull request #1332](https://github.com/gazebosim/gz-sim/pull/1332) 1. Extend ShaderParam system to support textures - * [Pull request #1310](https://github.com/ignitionrobotics/ign-gazebo/pull/1310) + * [Pull request #1310](https://github.com/gazebosim/gz-sim/pull/1310) 1. Adds a `Link::SetLinearVelocity()` method - * [Pull request #1323](https://github.com/ignitionrobotics/ign-gazebo/pull/1323) + * [Pull request #1323](https://github.com/gazebosim/gz-sim/pull/1323) 1. Fix weird indentation in `Link.hh` - * [Pull request #1324](https://github.com/ignitionrobotics/ign-gazebo/pull/1324) + * [Pull request #1324](https://github.com/gazebosim/gz-sim/pull/1324) 1. Limit thruster system's input thrust cmd - * [Pull request #1318](https://github.com/ignitionrobotics/ign-gazebo/pull/1318) + * [Pull request #1318](https://github.com/gazebosim/gz-sim/pull/1318) 1. Load and run visual plugin (system) on GUI side - * [Pull request #1275](https://github.com/ignitionrobotics/ign-gazebo/pull/1275) + * [Pull request #1275](https://github.com/gazebosim/gz-sim/pull/1275) 1. Log an error if JointPositionController cannot find the joint. (citadel retarget) - * [Pull request #1314](https://github.com/ignitionrobotics/ign-gazebo/pull/1314) + * [Pull request #1314](https://github.com/gazebosim/gz-sim/pull/1314) 1. Update source install instructions - * [Pull request #1311](https://github.com/ignitionrobotics/ign-gazebo/pull/1311) + * [Pull request #1311](https://github.com/gazebosim/gz-sim/pull/1311) 1. Document the `` option for JointPositionController. - * [Pull request #1309](https://github.com/ignitionrobotics/ign-gazebo/pull/1309) + * [Pull request #1309](https://github.com/gazebosim/gz-sim/pull/1309) 1. Fix typo in EntityComponentManager - * [Pull request #1304](https://github.com/ignitionrobotics/ign-gazebo/pull/1304) + * [Pull request #1304](https://github.com/gazebosim/gz-sim/pull/1304) 1. Buoyancy: fix center of volume's reference frame - * [Pull request #1302](https://github.com/ignitionrobotics/ign-gazebo/pull/1302) + * [Pull request #1302](https://github.com/gazebosim/gz-sim/pull/1302) 1. Fix graded buoyancy problems - * [Pull request #1297](https://github.com/ignitionrobotics/ign-gazebo/pull/1297) + * [Pull request #1297](https://github.com/gazebosim/gz-sim/pull/1297) 1. Add surface to buoyancy engine. (retarget fortress) - * [Pull request #1298](https://github.com/ignitionrobotics/ign-gazebo/pull/1298) + * [Pull request #1298](https://github.com/gazebosim/gz-sim/pull/1298) 1. Remove EachNew calls from sensor PreUpdates - * [Pull request #1281](https://github.com/ignitionrobotics/ign-gazebo/pull/1281) + * [Pull request #1281](https://github.com/gazebosim/gz-sim/pull/1281) 1. Prevent GzScene3D 💥 if another scene is already loaded - * [Pull request #1294](https://github.com/ignitionrobotics/ign-gazebo/pull/1294) + * [Pull request #1294](https://github.com/gazebosim/gz-sim/pull/1294) 1. Fix various typos on API documentation - * [Pull request #1291](https://github.com/ignitionrobotics/ign-gazebo/pull/1291) + * [Pull request #1291](https://github.com/gazebosim/gz-sim/pull/1291) 1. Optional orientation when spawning entity using spherical coordinates - * [Pull request #1263](https://github.com/ignitionrobotics/ign-gazebo/pull/1263) + * [Pull request #1263](https://github.com/gazebosim/gz-sim/pull/1263) 1. Cleanup update call for non-rendering sensors - * [Pull request #1282](https://github.com/ignitionrobotics/ign-gazebo/pull/1282) + * [Pull request #1282](https://github.com/gazebosim/gz-sim/pull/1282) 1. Documentation Error - * [Pull request #1285](https://github.com/ignitionrobotics/ign-gazebo/pull/1285) + * [Pull request #1285](https://github.com/gazebosim/gz-sim/pull/1285) 1. Min and max parameters for velocity, acceleration, and jerk apply to linear and angular separately. - * [Pull request #1229](https://github.com/ignitionrobotics/ign-gazebo/pull/1229) + * [Pull request #1229](https://github.com/gazebosim/gz-sim/pull/1229) 1. Add project() call to examples - * [Pull request #1274](https://github.com/ignitionrobotics/ign-gazebo/pull/1274) + * [Pull request #1274](https://github.com/gazebosim/gz-sim/pull/1274) 1. Implement /server_control::stop - * [Pull request #1240](https://github.com/ignitionrobotics/ign-gazebo/pull/1240) + * [Pull request #1240](https://github.com/gazebosim/gz-sim/pull/1240) -### Ignition Gazebo 6.4.0 (2021-01-13) +### Gazebo Sim 6.4.0 (2021-01-13) 1. Disable more tests on Windows - * [Pull request #1286](https://github.com/ignitionrobotics/ign-gazebo/pull/1286) + * [Pull request #1286](https://github.com/gazebosim/gz-sim/pull/1286) 1. Adding angular acceleration to the Link class - * [Pull request #1288](https://github.com/ignitionrobotics/ign-gazebo/pull/1288) + * [Pull request #1288](https://github.com/gazebosim/gz-sim/pull/1288) 1. Add world force - * [Pull request #1279](https://github.com/ignitionrobotics/ign-gazebo/pull/1279) + * [Pull request #1279](https://github.com/gazebosim/gz-sim/pull/1279) 1. Add NavSat sensor (GPS) - * [Pull request #1248](https://github.com/ignitionrobotics/ign-gazebo/pull/1248) + * [Pull request #1248](https://github.com/gazebosim/gz-sim/pull/1248) 1. Light Commands via topic - * [Pull request #1222](https://github.com/ignitionrobotics/ign-gazebo/pull/1222) + * [Pull request #1222](https://github.com/gazebosim/gz-sim/pull/1222) 1. Support battery draining start via topics - * [Pull request #1255](https://github.com/ignitionrobotics/ign-gazebo/pull/1255) + * [Pull request #1255](https://github.com/gazebosim/gz-sim/pull/1255) 1. Add visibility to ModelEditorAddEntity to fix Windows - * [Pull request #1246](https://github.com/ignitionrobotics/ign-gazebo/pull/1246) + * [Pull request #1246](https://github.com/gazebosim/gz-sim/pull/1246) 1. Make tests run as fast as possible - * [Pull request #1194](https://github.com/ignitionrobotics/ign-gazebo/pull/1194) + * [Pull request #1194](https://github.com/gazebosim/gz-sim/pull/1194) 1. Fix visualize lidar - * [Pull request #1224](https://github.com/ignitionrobotics/ign-gazebo/pull/1224) + * [Pull request #1224](https://github.com/gazebosim/gz-sim/pull/1224) 1. Disable user commands light test on macOS - * [Pull request #1204](https://github.com/ignitionrobotics/ign-gazebo/pull/1204) + * [Pull request #1204](https://github.com/gazebosim/gz-sim/pull/1204) 1. Skip failing Windows tests - * [Pull request #1205](https://github.com/ignitionrobotics/ign-gazebo/pull/1205) + * [Pull request #1205](https://github.com/gazebosim/gz-sim/pull/1205) -### Ignition Gazebo 6.3.0 (2021-12-10) +### Gazebo Sim 6.3.0 (2021-12-10) 1. View entity frames from the GUI - * [Pull request #1105](https://github.com/ignitionrobotics/ign-gazebo/pull/1105) + * [Pull request #1105](https://github.com/gazebosim/gz-sim/pull/1105) 1. Model editor - * [Pull request #1231](https://github.com/ignitionrobotics/ign-gazebo/pull/1231) + * [Pull request #1231](https://github.com/gazebosim/gz-sim/pull/1231) 1. Send state message when components are removed - * [Pull request #1235](https://github.com/ignitionrobotics/ign-gazebo/pull/1235) + * [Pull request #1235](https://github.com/gazebosim/gz-sim/pull/1235) 1. Docker fixes for Fortress - * [Pull request #1238](https://github.com/ignitionrobotics/ign-gazebo/pull/1238) + * [Pull request #1238](https://github.com/gazebosim/gz-sim/pull/1238) 1. Added sensor plugin to be able to visualize camera in `plane_propeller_demo.sdf` - * [Pull request #1226](https://github.com/ignitionrobotics/ign-gazebo/pull/1226) + * [Pull request #1226](https://github.com/gazebosim/gz-sim/pull/1226) 1. Update SdfGenerator to save link and sensor data to file - * [Pull request #1201](https://github.com/ignitionrobotics/ign-gazebo/pull/1201) + * [Pull request #1201](https://github.com/gazebosim/gz-sim/pull/1201) 1. Fix buoyancy not being applied for one iteration - * [Pull request #1211](https://github.com/ignitionrobotics/ign-gazebo/pull/1211) + * [Pull request #1211](https://github.com/gazebosim/gz-sim/pull/1211) 1. Increase maximum values in ViewAngle widget and increase its size - * [Pull request #1221](https://github.com/ignitionrobotics/ign-gazebo/pull/1221) - * [Pull request #1239](https://github.com/ignitionrobotics/ign-gazebo/pull/1239) + * [Pull request #1221](https://github.com/gazebosim/gz-sim/pull/1221) + * [Pull request #1239](https://github.com/gazebosim/gz-sim/pull/1239) 1. Fix the force-torque sensor update rate - * [Pull request #1159](https://github.com/ignitionrobotics/ign-gazebo/pull/1159) + * [Pull request #1159](https://github.com/gazebosim/gz-sim/pull/1159) -### Ignition Gazebo 6.2.0 (2021-11-16) +### Gazebo Sim 6.2.0 (2021-11-16) 1. Configurable joint state publisher's topic - * [Pull request #1076](https://github.com/ignitionrobotics/ign-gazebo/pull/1076) + * [Pull request #1076](https://github.com/gazebosim/gz-sim/pull/1076) 1. Thruster plugin: add tests and velocity control - * [Pull request #1190](https://github.com/ignitionrobotics/ign-gazebo/pull/1190) + * [Pull request #1190](https://github.com/gazebosim/gz-sim/pull/1190) 1. Prevent creation of spurious `` elements when saving worlds - * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + * [Pull request #1192](https://github.com/gazebosim/gz-sim/pull/1192) 1. Add `sdfString` to `ServerConfig`'s copy constructor. - * [Pull request #1185](https://github.com/ignitionrobotics/ign-gazebo/pull/1185) + * [Pull request #1185](https://github.com/gazebosim/gz-sim/pull/1185) 1. Added support for tracked vehicles - * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + * [Pull request #869](https://github.com/gazebosim/gz-sim/pull/869) 1. Add components to dynamically set joint limits - * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + * [Pull request #847](https://github.com/gazebosim/gz-sim/pull/847) 1. Remove bounding box when entities are removed - * [Pull request #1053](https://github.com/ignitionrobotics/ign-gazebo/pull/1053) - * [Pull request #1213](https://github.com/ignitionrobotics/ign-gazebo/pull/1213) + * [Pull request #1053](https://github.com/gazebosim/gz-sim/pull/1053) + * [Pull request #1213](https://github.com/gazebosim/gz-sim/pull/1213) 1. Fix updating component from state - * [Pull request #1181](https://github.com/ignitionrobotics/ign-gazebo/pull/1181) + * [Pull request #1181](https://github.com/gazebosim/gz-sim/pull/1181) 1. Extend odom publisher to allow 3D - * [Pull request #1180](https://github.com/ignitionrobotics/ign-gazebo/pull/1180) + * [Pull request #1180](https://github.com/gazebosim/gz-sim/pull/1180) 1. Support copy/paste - * [Pull request #1013](https://github.com/ignitionrobotics/ign-gazebo/pull/1013) + * [Pull request #1013](https://github.com/gazebosim/gz-sim/pull/1013) 1. Tweaks install instructions - * [Pull request #1078](https://github.com/ignitionrobotics/ign-gazebo/pull/1078) + * [Pull request #1078](https://github.com/gazebosim/gz-sim/pull/1078) 1. Publish 10 world stats msgs/sec instead of 5 - * [Pull request #1163](https://github.com/ignitionrobotics/ign-gazebo/pull/1163) + * [Pull request #1163](https://github.com/gazebosim/gz-sim/pull/1163) 1. Add functionality to add entities via the entity tree - * [Pull request #1101](https://github.com/ignitionrobotics/ign-gazebo/pull/1101) + * [Pull request #1101](https://github.com/gazebosim/gz-sim/pull/1101) 1. Get updated GUI ECM info when a user presses 'play' - * [Pull request #1109](https://github.com/ignitionrobotics/ign-gazebo/pull/1109) + * [Pull request #1109](https://github.com/gazebosim/gz-sim/pull/1109) 1. Create expanding type header to reduce code duplication - * [Pull request #1169](https://github.com/ignitionrobotics/ign-gazebo/pull/1169) + * [Pull request #1169](https://github.com/gazebosim/gz-sim/pull/1169) 1. `minimal_scene.sdf` example: add `camera_clip` params - * [Pull request #1166](https://github.com/ignitionrobotics/ign-gazebo/pull/1166) + * [Pull request #1166](https://github.com/gazebosim/gz-sim/pull/1166) 1. Sensor systems work if loaded after sensors - * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + * [Pull request #1104](https://github.com/gazebosim/gz-sim/pull/1104) -1. Support printing sensors using `ign model` - * [Pull request #1157](https://github.com/ignitionrobotics/ign-gazebo/pull/1157) +1. Support printing sensors using `gz model` + * [Pull request #1157](https://github.com/gazebosim/gz-sim/pull/1157) 1. Set camera clipping plane distances from the GUI - * [Pull request #1162](https://github.com/ignitionrobotics/ign-gazebo/pull/1162) + * [Pull request #1162](https://github.com/gazebosim/gz-sim/pull/1162) 1. Fix generation of systems library symlinks in build directory - * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) 1. Add a default value for `isHeadlessRendering`. - * [Pull request #1151](https://github.com/ignitionrobotics/ign-gazebo/pull/1151) + * [Pull request #1151](https://github.com/gazebosim/gz-sim/pull/1151) 1. Component inspector 1. Edit material colors - * [Pull request #1123](https://github.com/ignitionrobotics/ign-gazebo/pull/1123) - * [Pull request #1186](https://github.com/ignitionrobotics/ign-gazebo/pull/1186) + * [Pull request #1123](https://github.com/gazebosim/gz-sim/pull/1123) + * [Pull request #1186](https://github.com/gazebosim/gz-sim/pull/1186) 1. Fix integers and floats - * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + * [Pull request #1143](https://github.com/gazebosim/gz-sim/pull/1143) 1. Prevent a segfault when updating - * [Pull request #1167](https://github.com/ignitionrobotics/ign-gazebo/pull/1167) + * [Pull request #1167](https://github.com/gazebosim/gz-sim/pull/1167) 1. Use `uint64_t` for Entity IDs - * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + * [Pull request #1144](https://github.com/gazebosim/gz-sim/pull/1144) 1. Support setting the background color for sensors - * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + * [Pull request #1147](https://github.com/gazebosim/gz-sim/pull/1147) 1. Select top level entity not visual - * [Pull request #1150](https://github.com/ignitionrobotics/ign-gazebo/pull/1150) + * [Pull request #1150](https://github.com/gazebosim/gz-sim/pull/1150) 1. Update create entity offset on GUI side - * [Pull request #1145](https://github.com/ignitionrobotics/ign-gazebo/pull/1145) + * [Pull request #1145](https://github.com/gazebosim/gz-sim/pull/1145) 1. Update Select Entities GUI plugin to use Entity type - * [Pull request #1146](https://github.com/ignitionrobotics/ign-gazebo/pull/1146) + * [Pull request #1146](https://github.com/gazebosim/gz-sim/pull/1146) 1. Notify other GUI plugins of added/removed entities via GUI events - * [Pull request #1138](https://github.com/ignitionrobotics/ign-gazebo/pull/1138) - * [Pull request #1213](https://github.com/ignitionrobotics/ign-gazebo/pull/1213) + * [Pull request #1138](https://github.com/gazebosim/gz-sim/pull/1138) + * [Pull request #1213](https://github.com/gazebosim/gz-sim/pull/1213) -### Ignition Gazebo 6.1.0 (2021-10-25) +### Gazebo Sim 6.1.0 (2021-10-25) 1. Updates to camera video record from subt - * [Pull request #1117](https://github.com/ignitionrobotics/ign-gazebo/pull/1117) + * [Pull request #1117](https://github.com/gazebosim/gz-sim/pull/1117) 1. Use the actor tension parameter - * [Pull request #1091](https://github.com/ignitionrobotics/ign-gazebo/pull/1091) + * [Pull request #1091](https://github.com/gazebosim/gz-sim/pull/1091) 1. Better protect this->dataPtr->initialized with renderMutex. - * [Pull request #1119](https://github.com/ignitionrobotics/ign-gazebo/pull/1119) + * [Pull request #1119](https://github.com/gazebosim/gz-sim/pull/1119) 1. Use QTimer to update plugins in the Qt thread - * [Pull request #1095](https://github.com/ignitionrobotics/ign-gazebo/pull/1095) + * [Pull request #1095](https://github.com/gazebosim/gz-sim/pull/1095) 1. Adjust pose decimals based on element width - * [Pull request #1089](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull request #1089](https://github.com/gazebosim/gz-sim/pull/1089) 1. JointPositionController: Improve misleading error message - * [Pull request #1098](https://github.com/ignitionrobotics/ign-gazebo/pull/1098) + * [Pull request #1098](https://github.com/gazebosim/gz-sim/pull/1098) 1. Fixed IMU system plugin - * [Pull request #1043](https://github.com/ignitionrobotics/ign-gazebo/pull/1043) + * [Pull request #1043](https://github.com/gazebosim/gz-sim/pull/1043) 1. Prevent crash and print error - * [Pull request #1099](https://github.com/ignitionrobotics/ign-gazebo/pull/1099) + * [Pull request #1099](https://github.com/gazebosim/gz-sim/pull/1099) 1. Create GUI config folder before copying config - * [Pull request #1092](https://github.com/ignitionrobotics/ign-gazebo/pull/1092) + * [Pull request #1092](https://github.com/gazebosim/gz-sim/pull/1092) 1. Add support for configuring point size in Visualize Lidar GUI plugin - * [Pull request #1021](https://github.com/ignitionrobotics/ign-gazebo/pull/1021) + * [Pull request #1021](https://github.com/gazebosim/gz-sim/pull/1021) 1. Set a cloned joint's parent/child link names to the cloned parent/child link names - * [Pull request #1075](https://github.com/ignitionrobotics/ign-gazebo/pull/1075) + * [Pull request #1075](https://github.com/gazebosim/gz-sim/pull/1075) 1. Performance: use std::unordered_map where possible in SceneManager - * [Pull request #1083](https://github.com/ignitionrobotics/ign-gazebo/pull/1083) + * [Pull request #1083](https://github.com/gazebosim/gz-sim/pull/1083) 1. Fix transform controls - * [Pull request #1081](https://github.com/ignitionrobotics/ign-gazebo/pull/1081) + * [Pull request #1081](https://github.com/gazebosim/gz-sim/pull/1081) 1. Fix View Angle's home button - * [Pull request #1082](https://github.com/ignitionrobotics/ign-gazebo/pull/1082) + * [Pull request #1082](https://github.com/gazebosim/gz-sim/pull/1082) 1. Fix light control standalone example - * [Pull request #1077](https://github.com/ignitionrobotics/ign-gazebo/pull/1077) + * [Pull request #1077](https://github.com/gazebosim/gz-sim/pull/1077) 1. Parse new param for enabling / disabling IMU orientation output - * [Pull request #899](https://github.com/ignitionrobotics/ign-gazebo/pull/899) + * [Pull request #899](https://github.com/gazebosim/gz-sim/pull/899) -### Ignition Gazebo 6.0.0 (2021-10-01) +### Gazebo Sim 6.0.0 (2021-10-01) 1. Deprecated GzScene3D in favor of MinimalScene - * [Pull request #1065](https://github.com/ignitionrobotics/ign-gazebo/pull/1065) - * [Pull request #1051](https://github.com/ignitionrobotics/ign-gazebo/pull/1051) - * [Pull request #1014](https://github.com/ignitionrobotics/ign-gazebo/pull/1014) - * [Pull request #1034](https://github.com/ignitionrobotics/ign-gazebo/pull/1034) - * [Pull request #900](https://github.com/ignitionrobotics/ign-gazebo/pull/900) - * [Pull request #988](https://github.com/ignitionrobotics/ign-gazebo/pull/988) - * [Pull request #1016](https://github.com/ignitionrobotics/ign-gazebo/pull/1016) - * [Pull request #983](https://github.com/ignitionrobotics/ign-gazebo/pull/983) - * [Pull request #854](https://github.com/ignitionrobotics/ign-gazebo/pull/854) - * [Pull request #813](https://github.com/ignitionrobotics/ign-gazebo/pull/813) - * [Pull request #905](https://github.com/ignitionrobotics/ign-gazebo/pull/905) + * [Pull request #1065](https://github.com/gazebosim/gz-sim/pull/1065) + * [Pull request #1051](https://github.com/gazebosim/gz-sim/pull/1051) + * [Pull request #1014](https://github.com/gazebosim/gz-sim/pull/1014) + * [Pull request #1034](https://github.com/gazebosim/gz-sim/pull/1034) + * [Pull request #900](https://github.com/gazebosim/gz-sim/pull/900) + * [Pull request #988](https://github.com/gazebosim/gz-sim/pull/988) + * [Pull request #1016](https://github.com/gazebosim/gz-sim/pull/1016) + * [Pull request #983](https://github.com/gazebosim/gz-sim/pull/983) + * [Pull request #854](https://github.com/gazebosim/gz-sim/pull/854) + * [Pull request #813](https://github.com/gazebosim/gz-sim/pull/813) + * [Pull request #905](https://github.com/gazebosim/gz-sim/pull/905) 1. Fix GuiRunner initial state and entity spawn timing issue - * [Pull request #1073](https://github.com/ignitionrobotics/ign-gazebo/pull/1073) + * [Pull request #1073](https://github.com/gazebosim/gz-sim/pull/1073) 1. Buoyancy plugin upgrade - * [Pull request #818](https://github.com/ignitionrobotics/ign-gazebo/pull/818) - * [Pull request #1067](https://github.com/ignitionrobotics/ign-gazebo/pull/1067) - * [Pull request #1064](https://github.com/ignitionrobotics/ign-gazebo/pull/1064) + * [Pull request #818](https://github.com/gazebosim/gz-sim/pull/818) + * [Pull request #1067](https://github.com/gazebosim/gz-sim/pull/1067) + * [Pull request #1064](https://github.com/gazebosim/gz-sim/pull/1064) -1. Fix non desired window opening alongside ignition GUI - * [Pull request #1063](https://github.com/ignitionrobotics/ign-gazebo/pull/1063) +1. Fix non desired window opening alongside Gazebo GUI + * [Pull request #1063](https://github.com/gazebosim/gz-sim/pull/1063) 1. Documentation - * [Pull request #1074](https://github.com/ignitionrobotics/ign-gazebo/pull/1074) - * [Pull request #996](https://github.com/ignitionrobotics/ign-gazebo/pull/996) + * [Pull request #1074](https://github.com/gazebosim/gz-sim/pull/1074) + * [Pull request #996](https://github.com/gazebosim/gz-sim/pull/996) 1. Update to latest SDFormat changes - * [Pull request #1069](https://github.com/ignitionrobotics/ign-gazebo/pull/1069) - * [Pull request #1023](https://github.com/ignitionrobotics/ign-gazebo/pull/1023) + * [Pull request #1069](https://github.com/gazebosim/gz-sim/pull/1069) + * [Pull request #1023](https://github.com/gazebosim/gz-sim/pull/1023) 1. Suppress missing canonical link error messages for static models - * [Pull request #1068](https://github.com/ignitionrobotics/ign-gazebo/pull/1068) + * [Pull request #1068](https://github.com/gazebosim/gz-sim/pull/1068) 1. Heightmap fixes - * [Pull request #1055](https://github.com/ignitionrobotics/ign-gazebo/pull/1055) - * [Pull request #1054](https://github.com/ignitionrobotics/ign-gazebo/pull/1054) + * [Pull request #1055](https://github.com/gazebosim/gz-sim/pull/1055) + * [Pull request #1054](https://github.com/gazebosim/gz-sim/pull/1054) 1. Place config files in a versioned directory - * [Pull request #1050](https://github.com/ignitionrobotics/ign-gazebo/pull/1050) - * [Pull request #1070](https://github.com/ignitionrobotics/ign-gazebo/pull/1070) + * [Pull request #1050](https://github.com/gazebosim/gz-sim/pull/1050) + * [Pull request #1070](https://github.com/gazebosim/gz-sim/pull/1070) 1. Fix GUI crash when accessing bad rendering UserData - * [Pull request #1052](https://github.com/ignitionrobotics/ign-gazebo/pull/1052) + * [Pull request #1052](https://github.com/gazebosim/gz-sim/pull/1052) 1. Fix performance issue with contact data and AABB updates - * [Pull request #1048](https://github.com/ignitionrobotics/ign-gazebo/pull/1048) + * [Pull request #1048](https://github.com/gazebosim/gz-sim/pull/1048) 1. Enable new policy to fix protobuf compilation errors - * [Pull request #1046](https://github.com/ignitionrobotics/ign-gazebo/pull/1046) + * [Pull request #1046](https://github.com/gazebosim/gz-sim/pull/1046) 1. Support locked entities, and headless video recording using sim time - * [Pull request #862](https://github.com/ignitionrobotics/ign-gazebo/pull/862) + * [Pull request #862](https://github.com/gazebosim/gz-sim/pull/862) 1. Label Component & System, segmentation camera support - * [Pull request #853](https://github.com/ignitionrobotics/ign-gazebo/pull/853) - * [Pull request #1047](https://github.com/ignitionrobotics/ign-gazebo/pull/1047) + * [Pull request #853](https://github.com/gazebosim/gz-sim/pull/853) + * [Pull request #1047](https://github.com/gazebosim/gz-sim/pull/1047) 1. Joint Force-Torque Systems Plugin - * [Pull request #977](https://github.com/ignitionrobotics/ign-gazebo/pull/977) + * [Pull request #977](https://github.com/gazebosim/gz-sim/pull/977) 1. Add support for cloning entities - * [Pull request #959](https://github.com/ignitionrobotics/ign-gazebo/pull/959) + * [Pull request #959](https://github.com/gazebosim/gz-sim/pull/959) 1. 🌐 Spherical coordinates - * [Pull request #1008](https://github.com/ignitionrobotics/ign-gazebo/pull/1008) + * [Pull request #1008](https://github.com/gazebosim/gz-sim/pull/1008) 1. Populate JointConstraintWrench from physics - * [Pull request #989](https://github.com/ignitionrobotics/ign-gazebo/pull/989) + * [Pull request #989](https://github.com/gazebosim/gz-sim/pull/989) 1. Buoyancy engine - * [Pull request #1009](https://github.com/ignitionrobotics/ign-gazebo/pull/1009) + * [Pull request #1009](https://github.com/gazebosim/gz-sim/pull/1009) 1. Infrastructure - * [Pull request #1033](https://github.com/ignitionrobotics/ign-gazebo/pull/1033) - * [Pull request #1029](https://github.com/ignitionrobotics/ign-gazebo/pull/1029) - * [Pull request #991](https://github.com/ignitionrobotics/ign-gazebo/pull/991) - * [Pull request #809](https://github.com/ignitionrobotics/ign-gazebo/pull/809) + * [Pull request #1033](https://github.com/gazebosim/gz-sim/pull/1033) + * [Pull request #1029](https://github.com/gazebosim/gz-sim/pull/1029) + * [Pull request #991](https://github.com/gazebosim/gz-sim/pull/991) + * [Pull request #809](https://github.com/gazebosim/gz-sim/pull/809) 1. Update on resize instead of pre-render / render - * [Pull request #1028](https://github.com/ignitionrobotics/ign-gazebo/pull/1028) + * [Pull request #1028](https://github.com/gazebosim/gz-sim/pull/1028) 1. Add a flag to force headless rendering mode - * [Pull request #701](https://github.com/ignitionrobotics/ign-gazebo/pull/701) + * [Pull request #701](https://github.com/gazebosim/gz-sim/pull/701) -1. Remove unused ignition gui header - * [Pull request #1026](https://github.com/ignitionrobotics/ign-gazebo/pull/1026) +1. Remove unused Gazebo GUI header + * [Pull request #1026](https://github.com/gazebosim/gz-sim/pull/1026) 1. Adds velocity control to JointPositionController. - * [Pull request #1003](https://github.com/ignitionrobotics/ign-gazebo/pull/1003) + * [Pull request #1003](https://github.com/gazebosim/gz-sim/pull/1003) 1. Collada world exporter now exporting lights - * [Pull request #912](https://github.com/ignitionrobotics/ign-gazebo/pull/912) + * [Pull request #912](https://github.com/gazebosim/gz-sim/pull/912) 1. Workaround for setting visual cast shadows without material - * [Pull request #1015](https://github.com/ignitionrobotics/ign-gazebo/pull/1015) + * [Pull request #1015](https://github.com/gazebosim/gz-sim/pull/1015) 1. Fix selection buffer crash on resize - * [Pull request #969](https://github.com/ignitionrobotics/ign-gazebo/pull/969) + * [Pull request #969](https://github.com/gazebosim/gz-sim/pull/969) 1. Remove extra xml version line in pendulum_links example world - * [Pull request #1002](https://github.com/ignitionrobotics/ign-gazebo/pull/1002) + * [Pull request #1002](https://github.com/gazebosim/gz-sim/pull/1002) 1. Enable sensor metrics on example worlds - * [Pull request #982](https://github.com/ignitionrobotics/ign-gazebo/pull/982) + * [Pull request #982](https://github.com/gazebosim/gz-sim/pull/982) 1. Add ESC to unselect entities in select entities plugin - * [Pull request #995](https://github.com/ignitionrobotics/ign-gazebo/pull/995) + * [Pull request #995](https://github.com/gazebosim/gz-sim/pull/995) 1. Visualize joints - * [Pull request #961](https://github.com/ignitionrobotics/ign-gazebo/pull/961) + * [Pull request #961](https://github.com/gazebosim/gz-sim/pull/961) 1. Deprecate particle emitter, and use scatter ratio in new particle mes… - * [Pull request #986](https://github.com/ignitionrobotics/ign-gazebo/pull/986) + * [Pull request #986](https://github.com/gazebosim/gz-sim/pull/986) 1. Removed unused variable in Shapes plugin - * [Pull request #984](https://github.com/ignitionrobotics/ign-gazebo/pull/984) + * [Pull request #984](https://github.com/gazebosim/gz-sim/pull/984) 1. Use root.Model() - * [Pull request #980](https://github.com/ignitionrobotics/ign-gazebo/pull/980) + * [Pull request #980](https://github.com/gazebosim/gz-sim/pull/980) 1. Add ModelSDF serializer - * [Pull request #851](https://github.com/ignitionrobotics/ign-gazebo/pull/851) + * [Pull request #851](https://github.com/gazebosim/gz-sim/pull/851) 1. Entity tree: prevent creation of repeated entity items - * [Pull request #974](https://github.com/ignitionrobotics/ign-gazebo/pull/974) + * [Pull request #974](https://github.com/gazebosim/gz-sim/pull/974) 1. Use statically-typed views for better performance - * [Pull request #856](https://github.com/ignitionrobotics/ign-gazebo/pull/856) - * [Pull request #1001](https://github.com/ignitionrobotics/ign-gazebo/pull/1001) + * [Pull request #856](https://github.com/gazebosim/gz-sim/pull/856) + * [Pull request #1001](https://github.com/gazebosim/gz-sim/pull/1001) -1. Upgrade ign-sensors and support custom sensors - * [Pull request #617](https://github.com/ignitionrobotics/ign-gazebo/pull/617) +1. Upgrade gz-sensors and support custom sensors + * [Pull request #617](https://github.com/gazebosim/gz-sim/pull/617) 1. Fix entity creation console msg - * [Pull request #972](https://github.com/ignitionrobotics/ign-gazebo/pull/972) + * [Pull request #972](https://github.com/gazebosim/gz-sim/pull/972) 1. Fix crash in the follow_actor example - * [Pull request #958](https://github.com/ignitionrobotics/ign-gazebo/pull/958) + * [Pull request #958](https://github.com/gazebosim/gz-sim/pull/958) 1. Removed pose topic from log system - * [Pull request #839](https://github.com/ignitionrobotics/ign-gazebo/pull/839) + * [Pull request #839](https://github.com/gazebosim/gz-sim/pull/839) 1. Be more specific when looking for physics plugins - * [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965) + * [Pull request #965](https://github.com/gazebosim/gz-sim/pull/965) 1. Complaint if Joint doesn't exists before adding joint controller - * [Pull request #786](https://github.com/ignitionrobotics/ign-gazebo/pull/786) + * [Pull request #786](https://github.com/gazebosim/gz-sim/pull/786) 1. [DiffDrive] add enable/disable - * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + * [Pull request #772](https://github.com/gazebosim/gz-sim/pull/772) 1. Fix component inspector shutdown crash - * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + * [Pull request #724](https://github.com/gazebosim/gz-sim/pull/724) 1. Setting the intiial velocity for a model or joint - * [Pull request #693](https://github.com/ignitionrobotics/ign-gazebo/pull/693) + * [Pull request #693](https://github.com/gazebosim/gz-sim/pull/693) 1. Examples and tutorial on using rendering API from plugins - * [Pull request #596](https://github.com/ignitionrobotics/ign-gazebo/pull/596) + * [Pull request #596](https://github.com/gazebosim/gz-sim/pull/596) -1. Add missing IGNITION_GAZEBO_VISIBLE macros - * [Pull request #563](https://github.com/ignitionrobotics/ign-gazebo/pull/563) +1. Add missing GZ_SIM_VISIBLE macros + * [Pull request #563](https://github.com/gazebosim/gz-sim/pull/563) 1. Fix visibility macro names when used by a different component (Windows) - * [Pull request #564](https://github.com/ignitionrobotics/ign-gazebo/pull/564) + * [Pull request #564](https://github.com/gazebosim/gz-sim/pull/564) 1. No install apt recommends and clear cache - * [Pull request #423](https://github.com/ignitionrobotics/ign-gazebo/pull/423) + * [Pull request #423](https://github.com/gazebosim/gz-sim/pull/423) 1. Support adding systems that don't come from a plugin - * [Pull request #936](https://github.com/ignitionrobotics/ign-gazebo/pull/936) + * [Pull request #936](https://github.com/gazebosim/gz-sim/pull/936) 1. Fix tests that use multiple root level models or lights - * [Pull request #931](https://github.com/ignitionrobotics/ign-gazebo/pull/931) + * [Pull request #931](https://github.com/gazebosim/gz-sim/pull/931) -1. Make Gazebo aware of SetCameraPassCountPerGpuFlush - * [Pull request #921](https://github.com/ignitionrobotics/ign-gazebo/pull/921) +1. Make Gazebo Sim aware of SetCameraPassCountPerGpuFlush + * [Pull request #921](https://github.com/gazebosim/gz-sim/pull/921) 1. Visualize center of mass - * [Pull request #903](https://github.com/ignitionrobotics/ign-gazebo/pull/903) + * [Pull request #903](https://github.com/gazebosim/gz-sim/pull/903) 1. Transparent mode - * [Pull request #878](https://github.com/ignitionrobotics/ign-gazebo/pull/878) + * [Pull request #878](https://github.com/gazebosim/gz-sim/pull/878) 1. Visualize inertia - * [Pull request #861](https://github.com/ignitionrobotics/ign-gazebo/pull/861) + * [Pull request #861](https://github.com/gazebosim/gz-sim/pull/861) 1. Remove deprecations: tock 🕑 - * [Pull request #875](https://github.com/ignitionrobotics/ign-gazebo/pull/875) + * [Pull request #875](https://github.com/gazebosim/gz-sim/pull/875) -1. Removed and moved tape measure and grid config to ign-gui - * [Pull request #870](https://github.com/ignitionrobotics/ign-gazebo/pull/870) +1. Removed and moved tape measure and grid config to gz-gui + * [Pull request #870](https://github.com/gazebosim/gz-sim/pull/870) 1. Update wireframe visualization to support nested models - * [Pull request #832](https://github.com/ignitionrobotics/ign-gazebo/pull/832) + * [Pull request #832](https://github.com/gazebosim/gz-sim/pull/832) 1. Multi-LRAUV Swimming Race Example - * [Pull request #841](https://github.com/ignitionrobotics/ign-gazebo/pull/841) + * [Pull request #841](https://github.com/gazebosim/gz-sim/pull/841) 1. Add view control gui plugin and support orthographic view - * [Pull request #815](https://github.com/ignitionrobotics/ign-gazebo/pull/815) + * [Pull request #815](https://github.com/gazebosim/gz-sim/pull/815) 1. Wireframe mode - * [Pull request #816](https://github.com/ignitionrobotics/ign-gazebo/pull/816) + * [Pull request #816](https://github.com/gazebosim/gz-sim/pull/816) 1. Explain why detail::View symbols are visible - * [Pull request #788](https://github.com/ignitionrobotics/ign-gazebo/pull/788) + * [Pull request #788](https://github.com/gazebosim/gz-sim/pull/788) 1. Bump dependencies in fortress - * [Pull request #764](https://github.com/ignitionrobotics/ign-gazebo/pull/764) + * [Pull request #764](https://github.com/gazebosim/gz-sim/pull/764) -## Ignition Gazebo 5.x +## Gazebo Sim 5.x -### Ignition Gazebo 5.4.0 (2022-03-31) +### Gazebo Sim 5.4.0 (2022-03-31) 1. Add the Model Photo Shoot system, port of Modelpropshop plugin from Gazebo classic - * [Pull request #1331](https://github.com/ignitionrobotics/ign-gazebo/pull/1331) + * [Pull request #1331](https://github.com/gazebosim/gz-sim/pull/1331) 1. Add wheel slip user command - * [Pull request #1241](https://github.com/ignitionrobotics/ign-gazebo/pull/1241) + * [Pull request #1241](https://github.com/gazebosim/gz-sim/pull/1241) 1. Added user command to set multiple entity poses - * [Pull request #1394](https://github.com/ignitionrobotics/ign-gazebo/pull/1394) + * [Pull request #1394](https://github.com/gazebosim/gz-sim/pull/1394) 1. Component inspector: refactor Pose3d C++ code into a separate class - * [Pull request #1400](https://github.com/ignitionrobotics/ign-gazebo/pull/1400) + * [Pull request #1400](https://github.com/gazebosim/gz-sim/pull/1400) 1. Toggle Light visuals - * [Pull request #1387](https://github.com/ignitionrobotics/ign-gazebo/pull/1387) + * [Pull request #1387](https://github.com/gazebosim/gz-sim/pull/1387) 1. Allow to turn on/off lights - * [Pull request #1343](https://github.com/ignitionrobotics/ign-gazebo/pull/1343) + * [Pull request #1343](https://github.com/gazebosim/gz-sim/pull/1343) 1. Added more sensor properties to scene/info topic - * [Pull request #1344](https://github.com/ignitionrobotics/ign-gazebo/pull/1344) + * [Pull request #1344](https://github.com/gazebosim/gz-sim/pull/1344) 1. JointStatePublisher publish parent, child and axis data - * [Pull request #1345](https://github.com/ignitionrobotics/ign-gazebo/pull/1345) + * [Pull request #1345](https://github.com/gazebosim/gz-sim/pull/1345) 1. Fixed light GUI component inspector - * [Pull request #1337](https://github.com/ignitionrobotics/ign-gazebo/pull/1337) + * [Pull request #1337](https://github.com/gazebosim/gz-sim/pull/1337) 1. Fix `UNIT_SdfGenerator_TEST` - * [Pull request #1319](https://github.com/ignitionrobotics/ign-gazebo/pull/1319) + * [Pull request #1319](https://github.com/gazebosim/gz-sim/pull/1319) 1. Add elevator system - * [Pull request #535](https://github.com/ignitionrobotics/ign-gazebo/pull/535) + * [Pull request #535](https://github.com/gazebosim/gz-sim/pull/535) 1. Removed unused variables in shapes plugin - * [Pull request #1321](https://github.com/ignitionrobotics/ign-gazebo/pull/1321) + * [Pull request #1321](https://github.com/gazebosim/gz-sim/pull/1321) 1. Log an error if JointPositionController cannot find the joint. (citadel retarget) - * [Pull request #1314](https://github.com/ignitionrobotics/ign-gazebo/pull/1314) + * [Pull request #1314](https://github.com/gazebosim/gz-sim/pull/1314) 1. Buoyancy: fix center of volume's reference frame - * [Pull request #1302](https://github.com/ignitionrobotics/ign-gazebo/pull/1302) + * [Pull request #1302](https://github.com/gazebosim/gz-sim/pull/1302) 1. Remove EachNew calls from sensor PreUpdates - * [Pull request #1281](https://github.com/ignitionrobotics/ign-gazebo/pull/1281) + * [Pull request #1281](https://github.com/gazebosim/gz-sim/pull/1281) 1. Prevent GzScene3D 💥 if another scene is already loaded - * [Pull request #1294](https://github.com/ignitionrobotics/ign-gazebo/pull/1294) + * [Pull request #1294](https://github.com/gazebosim/gz-sim/pull/1294) 1. Cleanup update call for non-rendering sensors - * [Pull request #1282](https://github.com/ignitionrobotics/ign-gazebo/pull/1282) + * [Pull request #1282](https://github.com/gazebosim/gz-sim/pull/1282) 1. Documentation Error - * [Pull request #1285](https://github.com/ignitionrobotics/ign-gazebo/pull/1285) + * [Pull request #1285](https://github.com/gazebosim/gz-sim/pull/1285) 1. Min and max parameters for velocity, acceleration, and jerk apply to linear and angular separately. - * [Pull request #1229](https://github.com/ignitionrobotics/ign-gazebo/pull/1229) + * [Pull request #1229](https://github.com/gazebosim/gz-sim/pull/1229) 1. Add project() call to examples - * [Pull request #1274](https://github.com/ignitionrobotics/ign-gazebo/pull/1274) + * [Pull request #1274](https://github.com/gazebosim/gz-sim/pull/1274) 1. Implement `/server_control::stop` - * [Pull request #1240](https://github.com/ignitionrobotics/ign-gazebo/pull/1240) + * [Pull request #1240](https://github.com/gazebosim/gz-sim/pull/1240) 1. 👩‍🌾 Make depth camera tests more robust (#897) - * [Pull request #897) (#1257](https://github.com/ignitionrobotics/ign-gazebo/pull/897) (#1257) + * [Pull request #897) (#1257](https://github.com/gazebosim/gz-sim/pull/897) (#1257) 1. Support battery draining start via topics - * [Pull request #1255](https://github.com/ignitionrobotics/ign-gazebo/pull/1255) + * [Pull request #1255](https://github.com/gazebosim/gz-sim/pull/1255) 1. Make tests run as fast as possible - * [Pull request #1194](https://github.com/ignitionrobotics/ign-gazebo/pull/1194) - * [Pull request #1250](https://github.com/ignitionrobotics/ign-gazebo/pull/1250) + * [Pull request #1194](https://github.com/gazebosim/gz-sim/pull/1194) + * [Pull request #1250](https://github.com/gazebosim/gz-sim/pull/1250) 1. Fix visualize lidar - * [Pull request #1224](https://github.com/ignitionrobotics/ign-gazebo/pull/1224) + * [Pull request #1224](https://github.com/gazebosim/gz-sim/pull/1224) 1. Skip failing Windows tests - * [Pull request #1205](https://github.com/ignitionrobotics/ign-gazebo/pull/1205) - * [Pull request #1204](https://github.com/ignitionrobotics/ign-gazebo/pull/1204) - * [Pull request #1259](https://github.com/ignitionrobotics/ign-gazebo/pull/1259) - * [Pull request #1408](https://github.com/ignitionrobotics/ign-gazebo/pull/1408) + * [Pull request #1205](https://github.com/gazebosim/gz-sim/pull/1205) + * [Pull request #1204](https://github.com/gazebosim/gz-sim/pull/1204) + * [Pull request #1259](https://github.com/gazebosim/gz-sim/pull/1259) + * [Pull request #1408](https://github.com/gazebosim/gz-sim/pull/1408) 1. Configurable joint state publisher's topic - * [Pull request #1076](https://github.com/ignitionrobotics/ign-gazebo/pull/1076) + * [Pull request #1076](https://github.com/gazebosim/gz-sim/pull/1076) 1. Thruster plugin: add tests and velocity control - * [Pull request #1190](https://github.com/ignitionrobotics/ign-gazebo/pull/1190) + * [Pull request #1190](https://github.com/gazebosim/gz-sim/pull/1190) 1. Limit thruster system's input thrust cmd - * [Pull request #1318](https://github.com/ignitionrobotics/ign-gazebo/pull/1318) + * [Pull request #1318](https://github.com/gazebosim/gz-sim/pull/1318) -### Ignition Gazebo 5.3.0 (2021-11-12) +### Gazebo Sim 5.3.0 (2021-11-12) 1. Prevent creation of spurious elements when saving worlds - * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + * [Pull request #1192](https://github.com/gazebosim/gz-sim/pull/1192) 1. Added support for tracked vehicles - * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + * [Pull request #869](https://github.com/gazebosim/gz-sim/pull/869) 1. Add components to dynamically set joint limits - * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + * [Pull request #847](https://github.com/gazebosim/gz-sim/pull/847) 1. Fix updating component from state - * [Pull request #1181](https://github.com/ignitionrobotics/ign-gazebo/pull/1181) + * [Pull request #1181](https://github.com/gazebosim/gz-sim/pull/1181) 1. Extend odom publisher to allow 3D - * [Pull request #1180](https://github.com/ignitionrobotics/ign-gazebo/pull/1180) + * [Pull request #1180](https://github.com/gazebosim/gz-sim/pull/1180) 1. Fix updating a component's data via SerializedState msg - * [Pull request #1131](https://github.com/ignitionrobotics/ign-gazebo/pull/1131) + * [Pull request #1131](https://github.com/gazebosim/gz-sim/pull/1131) 1. Sensor systems work if loaded after sensors - * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + * [Pull request #1104](https://github.com/gazebosim/gz-sim/pull/1104) 1. Fix generation of systems library symlinks in build directory - * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) 1. Edit material colors in component inspector - * [Pull request #1123](https://github.com/ignitionrobotics/ign-gazebo/pull/1123) + * [Pull request #1123](https://github.com/gazebosim/gz-sim/pull/1123) 1. Support setting the background color for sensors - * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + * [Pull request #1147](https://github.com/gazebosim/gz-sim/pull/1147) 1. Use `uint64_t` for ComponentInspector Entity IDs - * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + * [Pull request #1144](https://github.com/gazebosim/gz-sim/pull/1144) 1. Fix integers and floats on component inspector - * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + * [Pull request #1143](https://github.com/gazebosim/gz-sim/pull/1143) -### Ignition Gazebo 5.2.0 (2021-10-22) +### Gazebo Sim 5.2.0 (2021-10-22) 1. Fix performance level test flakiness - * [Pull request #1129](https://github.com/ignitionrobotics/ign-gazebo/pull/1129) + * [Pull request #1129](https://github.com/gazebosim/gz-sim/pull/1129) 1. Updates to camera video record from subt - * [Pull request #1117](https://github.com/ignitionrobotics/ign-gazebo/pull/1117) + * [Pull request #1117](https://github.com/gazebosim/gz-sim/pull/1117) 1. Better protect this->dataPtr->initialized with renderMutex. - * [Pull request #1119](https://github.com/ignitionrobotics/ign-gazebo/pull/1119) + * [Pull request #1119](https://github.com/gazebosim/gz-sim/pull/1119) 1. Use QTimer to update plugins in the Qt thread - * [Pull request #1095](https://github.com/ignitionrobotics/ign-gazebo/pull/1095) + * [Pull request #1095](https://github.com/gazebosim/gz-sim/pull/1095) 1. Adjust pose decimals based on element width - * [Pull request #1089](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull request #1089](https://github.com/gazebosim/gz-sim/pull/1089) 1. JointPositionController: Improve misleading error message - * [Pull request #1098](https://github.com/ignitionrobotics/ign-gazebo/pull/1098) + * [Pull request #1098](https://github.com/gazebosim/gz-sim/pull/1098) 1. Fixed IMU system plugin - * [Pull request #1043](https://github.com/ignitionrobotics/ign-gazebo/pull/1043) + * [Pull request #1043](https://github.com/gazebosim/gz-sim/pull/1043) 1. Cache top level and static to speed up physics system (Backport #656) - * [Pull request #993](https://github.com/ignitionrobotics/ign-gazebo/pull/993) + * [Pull request #993](https://github.com/gazebosim/gz-sim/pull/993) 1. Prevent crash and print error - * [Pull request #1099](https://github.com/ignitionrobotics/ign-gazebo/pull/1099) + * [Pull request #1099](https://github.com/gazebosim/gz-sim/pull/1099) 1. Performance: use std::unordered_map where possible in SceneManager - * [Pull request #1083](https://github.com/ignitionrobotics/ign-gazebo/pull/1083) + * [Pull request #1083](https://github.com/gazebosim/gz-sim/pull/1083) 1. Fix light control standalone example - * [Pull request #1077](https://github.com/ignitionrobotics/ign-gazebo/pull/1077) + * [Pull request #1077](https://github.com/gazebosim/gz-sim/pull/1077) 1. Parse new param for enabling / disabling IMU orientation output - * [Pull request #899](https://github.com/ignitionrobotics/ign-gazebo/pull/899) + * [Pull request #899](https://github.com/gazebosim/gz-sim/pull/899) 1. Enable new policy to fix protobuf compilation errors - * [Pull request #1059](https://github.com/ignitionrobotics/ign-gazebo/pull/1059) + * [Pull request #1059](https://github.com/gazebosim/gz-sim/pull/1059) 1. Fix performance issue with contact data and AABB updates - * [Pull request #1048](https://github.com/ignitionrobotics/ign-gazebo/pull/1048) + * [Pull request #1048](https://github.com/gazebosim/gz-sim/pull/1048) 1. Support locked entities, and headless video recording using sim time - * [Pull request #862](https://github.com/ignitionrobotics/ign-gazebo/pull/862) + * [Pull request #862](https://github.com/gazebosim/gz-sim/pull/862) -1. Update ign-gazebo4 changelog - * [Pull request #1031](https://github.com/ignitionrobotics/ign-gazebo/pull/1031) +1. Update gz-sim4 changelog + * [Pull request #1031](https://github.com/gazebosim/gz-sim/pull/1031) 1. bump version and update changelog - * [Pull request #1029](https://github.com/ignitionrobotics/ign-gazebo/pull/1029) + * [Pull request #1029](https://github.com/gazebosim/gz-sim/pull/1029) -1. Remove unused ignition gui header - * [Pull request #1026](https://github.com/ignitionrobotics/ign-gazebo/pull/1026) +1. Remove unused Gazebo GUI header + * [Pull request #1026](https://github.com/gazebosim/gz-sim/pull/1026) 1. Collada world exporter now exporting lights - * [Pull request #912](https://github.com/ignitionrobotics/ign-gazebo/pull/912) + * [Pull request #912](https://github.com/gazebosim/gz-sim/pull/912) 1. Fixed GUI's ComponentInspector light parameter - * [Pull request #1018](https://github.com/ignitionrobotics/ign-gazebo/pull/1018) + * [Pull request #1018](https://github.com/gazebosim/gz-sim/pull/1018) 1. Workaround for setting visual cast shadows without material - * [Pull request #1015](https://github.com/ignitionrobotics/ign-gazebo/pull/1015) + * [Pull request #1015](https://github.com/gazebosim/gz-sim/pull/1015) 1. Fix selection buffer crash on resize - * [Pull request #969](https://github.com/ignitionrobotics/ign-gazebo/pull/969) + * [Pull request #969](https://github.com/gazebosim/gz-sim/pull/969) 1. Update DART deps to local - * [Pull request #1005](https://github.com/ignitionrobotics/ign-gazebo/pull/1005) + * [Pull request #1005](https://github.com/gazebosim/gz-sim/pull/1005) 1. Remove extra xml version line in pendulum_links example world - * [Pull request #1002](https://github.com/ignitionrobotics/ign-gazebo/pull/1002) + * [Pull request #1002](https://github.com/gazebosim/gz-sim/pull/1002) 1. Enable sensor metrics on example worlds - * [Pull request #982](https://github.com/ignitionrobotics/ign-gazebo/pull/982) + * [Pull request #982](https://github.com/gazebosim/gz-sim/pull/982) 1. Make thermal sensor test more robust - * [Pull request #994](https://github.com/ignitionrobotics/ign-gazebo/pull/994) + * [Pull request #994](https://github.com/gazebosim/gz-sim/pull/994) 1. Improved doxygen - * [Pull request #996](https://github.com/ignitionrobotics/ign-gazebo/pull/996) + * [Pull request #996](https://github.com/gazebosim/gz-sim/pull/996) 1. Remove bitbucket-pipelines.yml - * [Pull request #991](https://github.com/ignitionrobotics/ign-gazebo/pull/991) + * [Pull request #991](https://github.com/gazebosim/gz-sim/pull/991) 1. Removed unused variable in Shapes plugin - * [Pull request #984](https://github.com/ignitionrobotics/ign-gazebo/pull/984) + * [Pull request #984](https://github.com/gazebosim/gz-sim/pull/984) 1. Entity tree: prevent creation of repeated entity items - * [Pull request #974](https://github.com/ignitionrobotics/ign-gazebo/pull/974) + * [Pull request #974](https://github.com/gazebosim/gz-sim/pull/974) 1. Updates when forward-porting to v4 - * [Pull request #973](https://github.com/ignitionrobotics/ign-gazebo/pull/973) + * [Pull request #973](https://github.com/gazebosim/gz-sim/pull/973) 1. Don't use $HOME on most tests (InternalFixture) - * [Pull request #971](https://github.com/ignitionrobotics/ign-gazebo/pull/971) + * [Pull request #971](https://github.com/gazebosim/gz-sim/pull/971) 1. Fix entity creation console msg - * [Pull request #972](https://github.com/ignitionrobotics/ign-gazebo/pull/972) + * [Pull request #972](https://github.com/gazebosim/gz-sim/pull/972) 1. Fix crash in the follow_actor example - * [Pull request #958](https://github.com/ignitionrobotics/ign-gazebo/pull/958) + * [Pull request #958](https://github.com/gazebosim/gz-sim/pull/958) 1. Be more specific when looking for physics plugins - * [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965) + * [Pull request #965](https://github.com/gazebosim/gz-sim/pull/965) 1. Drag and drop meshes into scene - * [Pull request #939](https://github.com/ignitionrobotics/ign-gazebo/pull/939) + * [Pull request #939](https://github.com/gazebosim/gz-sim/pull/939) 1. Allow referencing links in nested models in LiftDrag - * [Pull request #955](https://github.com/ignitionrobotics/ign-gazebo/pull/955) + * [Pull request #955](https://github.com/gazebosim/gz-sim/pull/955) 1. Complaint if Joint doesn't exists before adding joint controller - * [Pull request #786](https://github.com/ignitionrobotics/ign-gazebo/pull/786) + * [Pull request #786](https://github.com/gazebosim/gz-sim/pull/786) 1. Set protobuf_MODULE_COMPATIBLE before any find_package call - * [Pull request #957](https://github.com/ignitionrobotics/ign-gazebo/pull/957) + * [Pull request #957](https://github.com/gazebosim/gz-sim/pull/957) 1. DiffDrive add enable/disable - * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + * [Pull request #772](https://github.com/gazebosim/gz-sim/pull/772) 1. Fix component inspector shutdown crash - * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + * [Pull request #724](https://github.com/gazebosim/gz-sim/pull/724) 1. Add UserCommands Plugin. - * [Pull request #719](https://github.com/ignitionrobotics/ign-gazebo/pull/719) + * [Pull request #719](https://github.com/gazebosim/gz-sim/pull/719) 1. Expose a test fixture helper class - * [Pull request #926](https://github.com/ignitionrobotics/ign-gazebo/pull/926) + * [Pull request #926](https://github.com/gazebosim/gz-sim/pull/926) 1. Fix logic to disable server default plugins loading - * [Pull request #953](https://github.com/ignitionrobotics/ign-gazebo/pull/953) + * [Pull request #953](https://github.com/gazebosim/gz-sim/pull/953) 1. Porting Dome to Edifice: Windows, deprecations - * [Pull request #948](https://github.com/ignitionrobotics/ign-gazebo/pull/948) + * [Pull request #948](https://github.com/gazebosim/gz-sim/pull/948) 1. removed unneeded plugin update - * [Pull request #944](https://github.com/ignitionrobotics/ign-gazebo/pull/944) + * [Pull request #944](https://github.com/gazebosim/gz-sim/pull/944) 1. Functions to enable velocity and acceleration checks on Link - * [Pull request #935](https://github.com/ignitionrobotics/ign-gazebo/pull/935) + * [Pull request #935](https://github.com/gazebosim/gz-sim/pull/935) 1. Support adding systems that don't come from a plugin - * [Pull request #936](https://github.com/ignitionrobotics/ign-gazebo/pull/936) + * [Pull request #936](https://github.com/gazebosim/gz-sim/pull/936) 1. 3D plot GUI plugin - * [Pull request #917](https://github.com/ignitionrobotics/ign-gazebo/pull/917) + * [Pull request #917](https://github.com/gazebosim/gz-sim/pull/917) 1. 4 to 5 - * [Pull request #938](https://github.com/ignitionrobotics/ign-gazebo/pull/938) + * [Pull request #938](https://github.com/gazebosim/gz-sim/pull/938) 1. Fix joint controller without joint vel data - * [Pull request #937](https://github.com/ignitionrobotics/ign-gazebo/pull/937) + * [Pull request #937](https://github.com/gazebosim/gz-sim/pull/937) 1. 3 to 4 - * [Pull request #933](https://github.com/ignitionrobotics/ign-gazebo/pull/933) + * [Pull request #933](https://github.com/gazebosim/gz-sim/pull/933) -1. Model info CLI `ign model` - * [Pull request #893](https://github.com/ignitionrobotics/ign-gazebo/pull/893) +1. Model info CLI `gz model` + * [Pull request #893](https://github.com/gazebosim/gz-sim/pull/893) 1. Support Bullet on Edifice - * [Pull request #919](https://github.com/ignitionrobotics/ign-gazebo/pull/919) + * [Pull request #919](https://github.com/gazebosim/gz-sim/pull/919) 1. Don't create components for entities that don't exist - * [Pull request #927](https://github.com/ignitionrobotics/ign-gazebo/pull/927) + * [Pull request #927](https://github.com/gazebosim/gz-sim/pull/927) 1. Fix blender sdf export script and remove .material file from collada light export test - * [Pull request #923](https://github.com/ignitionrobotics/ign-gazebo/pull/923) + * [Pull request #923](https://github.com/gazebosim/gz-sim/pull/923) 1. Heightmap physics (with DART) - * [Pull request #661](https://github.com/ignitionrobotics/ign-gazebo/pull/661) + * [Pull request #661](https://github.com/gazebosim/gz-sim/pull/661) 1. Adds Mesh Tutorial - * [Pull request #915](https://github.com/ignitionrobotics/ign-gazebo/pull/915) + * [Pull request #915](https://github.com/gazebosim/gz-sim/pull/915) 1. 4 to 5 - * [Pull request #918](https://github.com/ignitionrobotics/ign-gazebo/pull/918) + * [Pull request #918](https://github.com/gazebosim/gz-sim/pull/918) 1. Fix updating GUI plugin on load - * [Pull request #904](https://github.com/ignitionrobotics/ign-gazebo/pull/904) + * [Pull request #904](https://github.com/gazebosim/gz-sim/pull/904) 1. 3 to 4 - * [Pull request #916](https://github.com/ignitionrobotics/ign-gazebo/pull/916) + * [Pull request #916](https://github.com/gazebosim/gz-sim/pull/916) 1. Physics system: update link poses if the canonical link pose has been updated - * [Pull request #876](https://github.com/ignitionrobotics/ign-gazebo/pull/876) + * [Pull request #876](https://github.com/gazebosim/gz-sim/pull/876) 1. Add blender sdf export tutorial - * [Pull request #895](https://github.com/ignitionrobotics/ign-gazebo/pull/895) + * [Pull request #895](https://github.com/gazebosim/gz-sim/pull/895) 1. Banana for Scale - * [Pull request #734](https://github.com/ignitionrobotics/ign-gazebo/pull/734) + * [Pull request #734](https://github.com/gazebosim/gz-sim/pull/734) 1. Fix textures not exporting after loading a world that uses obj models - * [Pull request #874](https://github.com/ignitionrobotics/ign-gazebo/pull/874) + * [Pull request #874](https://github.com/gazebosim/gz-sim/pull/874) 1. Fix documentation for the Sensor component - * [Pull request #898](https://github.com/ignitionrobotics/ign-gazebo/pull/898) + * [Pull request #898](https://github.com/gazebosim/gz-sim/pull/898) 1. Make depth camera tests more robust - * [Pull request #897](https://github.com/ignitionrobotics/ign-gazebo/pull/897) + * [Pull request #897](https://github.com/gazebosim/gz-sim/pull/897) 1. Use UINT64_MAX for kComponentTpyeIDInvalid instead of relying on underflow - * [Pull request #889](https://github.com/ignitionrobotics/ign-gazebo/pull/889) + * [Pull request #889](https://github.com/gazebosim/gz-sim/pull/889) 1. Fix mouse view control target position - * [Pull request #879](https://github.com/ignitionrobotics/ign-gazebo/pull/879) + * [Pull request #879](https://github.com/gazebosim/gz-sim/pull/879) -### Ignition Gazebo 5.1.0 (2021-06-29) +### Gazebo Sim 5.1.0 (2021-06-29) 1. Depend on SDF 11.2.1, rendering 5.1 and GUI 5.1. Fix Windows. - * [Pull request #877](https://github.com/ignitionrobotics/ign-gazebo/pull/877) + * [Pull request #877](https://github.com/gazebosim/gz-sim/pull/877) 1. Set gui camera pose - * [Pull request #863](https://github.com/ignitionrobotics/ign-gazebo/pull/863) + * [Pull request #863](https://github.com/gazebosim/gz-sim/pull/863) 1. Refactor RenderUtil::Update with helper functions - * [Pull request #858](https://github.com/ignitionrobotics/ign-gazebo/pull/858) + * [Pull request #858](https://github.com/gazebosim/gz-sim/pull/858) 1. Enables confirmation dialog when closing Gazebo. - * [Pull request #850](https://github.com/ignitionrobotics/ign-gazebo/pull/850) + * [Pull request #850](https://github.com/gazebosim/gz-sim/pull/850) 1. Using math::SpeedLimiter on the diff_drive controller. - * [Pull request #833](https://github.com/ignitionrobotics/ign-gazebo/pull/833) + * [Pull request #833](https://github.com/gazebosim/gz-sim/pull/833) 1. New example: get an ECM snapshot from an external program - * [Pull request #859](https://github.com/ignitionrobotics/ign-gazebo/pull/859) + * [Pull request #859](https://github.com/gazebosim/gz-sim/pull/859) 1. Fix WindEffects Plugin bug, not configuring new links - * [Pull request #844](https://github.com/ignitionrobotics/ign-gazebo/pull/844) + * [Pull request #844](https://github.com/gazebosim/gz-sim/pull/844) 1. Set collision detector and solver from SDF - * [Pull request #684](https://github.com/ignitionrobotics/ign-gazebo/pull/684) + * [Pull request #684](https://github.com/gazebosim/gz-sim/pull/684) 1. Add Particle Emitter tutorial - * [Pull request #860](https://github.com/ignitionrobotics/ign-gazebo/pull/860) + * [Pull request #860](https://github.com/gazebosim/gz-sim/pull/860) 1. Fix potentially flaky integration component test case - * [Pull request #848](https://github.com/ignitionrobotics/ign-gazebo/pull/848) + * [Pull request #848](https://github.com/gazebosim/gz-sim/pull/848) 1. Added follow camera offset service - * [Pull request #855](https://github.com/ignitionrobotics/ign-gazebo/pull/855) + * [Pull request #855](https://github.com/gazebosim/gz-sim/pull/855) 1. Remove unneeded camera follow offset checks - * [Pull request #857](https://github.com/ignitionrobotics/ign-gazebo/pull/857) + * [Pull request #857](https://github.com/gazebosim/gz-sim/pull/857) 1. Using math::SpeedLimiter on the ackermann_steering controller. - * [Pull request #837](https://github.com/ignitionrobotics/ign-gazebo/pull/837) + * [Pull request #837](https://github.com/gazebosim/gz-sim/pull/837) 1. Cleanup and alphabetize plugin headers - * [Pull request #838](https://github.com/ignitionrobotics/ign-gazebo/pull/838) + * [Pull request #838](https://github.com/gazebosim/gz-sim/pull/838) 1. Fix race condition when rendering the UI - * [Pull request #774](https://github.com/ignitionrobotics/ign-gazebo/pull/774) + * [Pull request #774](https://github.com/gazebosim/gz-sim/pull/774) 1. Removed duplicated code with rendering::sceneFromFirstRenderEngine - * [Pull request #819](https://github.com/ignitionrobotics/ign-gazebo/pull/819) + * [Pull request #819](https://github.com/gazebosim/gz-sim/pull/819) 1. Remove unused headers in video_recoder plugin - * [Pull request #834](https://github.com/ignitionrobotics/ign-gazebo/pull/834) + * [Pull request #834](https://github.com/gazebosim/gz-sim/pull/834) -1. Use moveToHelper from ign-rendering - * [Pull request #825](https://github.com/ignitionrobotics/ign-gazebo/pull/825) +1. Use moveToHelper from gz-rendering + * [Pull request #825](https://github.com/gazebosim/gz-sim/pull/825) 1. Make halt motion act like a brake - * [Pull request #830](https://github.com/ignitionrobotics/ign-gazebo/pull/830) + * [Pull request #830](https://github.com/gazebosim/gz-sim/pull/830) 1. Update collision visualization to support nested models - * [Pull request #823](https://github.com/ignitionrobotics/ign-gazebo/pull/823) + * [Pull request #823](https://github.com/gazebosim/gz-sim/pull/823) 1. Adds support for ocean currents - * [Pull request #800](https://github.com/ignitionrobotics/ign-gazebo/pull/800) + * [Pull request #800](https://github.com/gazebosim/gz-sim/pull/800) 1. Add conversion for particle scatter ratio field - * [Pull request #791](https://github.com/ignitionrobotics/ign-gazebo/pull/791) + * [Pull request #791](https://github.com/gazebosim/gz-sim/pull/791) 1. Adding HaltMotion to physics plugin - * [Pull request #728](https://github.com/ignitionrobotics/ign-gazebo/pull/728) + * [Pull request #728](https://github.com/gazebosim/gz-sim/pull/728) 1. ColladaExporter, export submesh selected - * [Pull request #802](https://github.com/ignitionrobotics/ign-gazebo/pull/802) + * [Pull request #802](https://github.com/gazebosim/gz-sim/pull/802) 1. Remove tools/code_check and update codecov - * [Pull request #814](https://github.com/ignitionrobotics/ign-gazebo/pull/814) + * [Pull request #814](https://github.com/gazebosim/gz-sim/pull/814) 1. Trigger delay - * [Pull request #817](https://github.com/ignitionrobotics/ign-gazebo/pull/817) + * [Pull request #817](https://github.com/gazebosim/gz-sim/pull/817) 1. Map canonical links to their models - * [Pull request #736](https://github.com/ignitionrobotics/ign-gazebo/pull/736) + * [Pull request #736](https://github.com/gazebosim/gz-sim/pull/736) 1. Fix included nested model expansion in SDF generation - * [Pull request #768](https://github.com/ignitionrobotics/ign-gazebo/pull/768) + * [Pull request #768](https://github.com/gazebosim/gz-sim/pull/768) 1. Util: Use public API from libsdformat for detecting non-file source - * [Pull request #794](https://github.com/ignitionrobotics/ign-gazebo/pull/794) + * [Pull request #794](https://github.com/gazebosim/gz-sim/pull/794) 1. Contacts visualization - * [Pull request #234](https://github.com/ignitionrobotics/ign-gazebo/pull/234) + * [Pull request #234](https://github.com/gazebosim/gz-sim/pull/234) -1. Bump to ign-msgs 7.1 / sdformat 11.1, Windows fixes - * [Pull request #758](https://github.com/ignitionrobotics/ign-gazebo/pull/758) +1. Bump to gz-msgs 7.1 / sdformat 11.1, Windows fixes + * [Pull request #758](https://github.com/gazebosim/gz-sim/pull/758) 1. Add functionalities for optical tactile plugin - * [Pull request #431](https://github.com/ignitionrobotics/ign-gazebo/pull/431) + * [Pull request #431](https://github.com/gazebosim/gz-sim/pull/431) 1. Fix documentation for EntityComponentManager::EachNew - * [Pull request #795](https://github.com/ignitionrobotics/ign-gazebo/pull/795) + * [Pull request #795](https://github.com/gazebosim/gz-sim/pull/795) -1. Bump ign-physics version to 3.2 - * [Pull request #792](https://github.com/ignitionrobotics/ign-gazebo/pull/792) +1. Bump gz-physics version to 3.2 + * [Pull request #792](https://github.com/gazebosim/gz-sim/pull/792) 1. Prevent crash on Plotting plugin with mutex - * [Pull request #747](https://github.com/ignitionrobotics/ign-gazebo/pull/747) + * [Pull request #747](https://github.com/gazebosim/gz-sim/pull/747) 1. 👩‍🌾 Fix Windows build and some warnings - * [Pull request #782](https://github.com/ignitionrobotics/ign-gazebo/pull/782) + * [Pull request #782](https://github.com/gazebosim/gz-sim/pull/782) 1. Fix ColladaExporter submesh index bug - * [Pull request #763](https://github.com/ignitionrobotics/ign-gazebo/pull/763) + * [Pull request #763](https://github.com/gazebosim/gz-sim/pull/763) 1. Fix macOS build: components::Name in benchmark - * [Pull request #784](https://github.com/ignitionrobotics/ign-gazebo/pull/784) + * [Pull request #784](https://github.com/gazebosim/gz-sim/pull/784) 1. Feature/hydrodynamics - * [Pull request #749](https://github.com/ignitionrobotics/ign-gazebo/pull/749) + * [Pull request #749](https://github.com/gazebosim/gz-sim/pull/749) 1. Don't store duplicate ComponentTypeId in ECM - * [Pull request #751](https://github.com/ignitionrobotics/ign-gazebo/pull/751) + * [Pull request #751](https://github.com/gazebosim/gz-sim/pull/751) 1. [TPE] Support setting individual link velocity - * [Pull request #427](https://github.com/ignitionrobotics/ign-gazebo/pull/427) + * [Pull request #427](https://github.com/gazebosim/gz-sim/pull/427) 1. 👩‍🌾 Enable Focal CI - * [Pull request #646](https://github.com/ignitionrobotics/ign-gazebo/pull/646) + * [Pull request #646](https://github.com/gazebosim/gz-sim/pull/646) 1. Patch particle emitter2 service - * [Pull request #777](https://github.com/ignitionrobotics/ign-gazebo/pull/777) + * [Pull request #777](https://github.com/gazebosim/gz-sim/pull/777) 1. Add odometry publisher system - * [Pull request #547](https://github.com/ignitionrobotics/ign-gazebo/pull/547) + * [Pull request #547](https://github.com/gazebosim/gz-sim/pull/547) 1. [DiffDrive] add enable/disable - * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + * [Pull request #772](https://github.com/gazebosim/gz-sim/pull/772) 1. Update benchmark comparison instructions - * [Pull request #766](https://github.com/ignitionrobotics/ign-gazebo/pull/766) + * [Pull request #766](https://github.com/gazebosim/gz-sim/pull/766) 1. Fix 'invalid animation update data' msg for actors - * [Pull request #754](https://github.com/ignitionrobotics/ign-gazebo/pull/754) + * [Pull request #754](https://github.com/gazebosim/gz-sim/pull/754) 1. Fixed particle emitter forward playback - * [Pull request #745](https://github.com/ignitionrobotics/ign-gazebo/pull/745) + * [Pull request #745](https://github.com/gazebosim/gz-sim/pull/745) 1. ECM's ChangedState gets message with modified components - * [Pull request #742](https://github.com/ignitionrobotics/ign-gazebo/pull/742) + * [Pull request #742](https://github.com/gazebosim/gz-sim/pull/742) 1. Fixed collision visual bounding boxes - * [Pull request #746](https://github.com/ignitionrobotics/ign-gazebo/pull/746) + * [Pull request #746](https://github.com/gazebosim/gz-sim/pull/746) 1. Fix compute_rtfs arguments - * [Pull request #737](https://github.com/ignitionrobotics/ign-gazebo/pull/737) + * [Pull request #737](https://github.com/gazebosim/gz-sim/pull/737) 1. Validate step size and RTF parameters - * [Pull request #740](https://github.com/ignitionrobotics/ign-gazebo/pull/740) + * [Pull request #740](https://github.com/gazebosim/gz-sim/pull/740) 1. Fix component inspector shutdown crash - * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + * [Pull request #724](https://github.com/gazebosim/gz-sim/pull/724) 1. Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config - * [Pull request #715](https://github.com/ignitionrobotics/ign-gazebo/pull/715) + * [Pull request #715](https://github.com/gazebosim/gz-sim/pull/715) 1. Do not pass -Wno-unused-parameter to MSVC compiler - * [Pull request #716](https://github.com/ignitionrobotics/ign-gazebo/pull/716) + * [Pull request #716](https://github.com/gazebosim/gz-sim/pull/716) 1. Iterate through changed links only in UpdateSim - * [Pull request #678](https://github.com/ignitionrobotics/ign-gazebo/pull/678) + * [Pull request #678](https://github.com/gazebosim/gz-sim/pull/678) 1. Update PlaybackScrubber description - * [Pull request #733](https://github.com/ignitionrobotics/ign-gazebo/pull/733) + * [Pull request #733](https://github.com/gazebosim/gz-sim/pull/733) 1. Support configuring particle scatter ratio in particle emitter system - * [Pull request #674](https://github.com/ignitionrobotics/ign-gazebo/pull/674) + * [Pull request #674](https://github.com/gazebosim/gz-sim/pull/674) 1. Fix diffuse and ambient values for ackermann example - * [Pull request #707](https://github.com/ignitionrobotics/ign-gazebo/pull/707) + * [Pull request #707](https://github.com/gazebosim/gz-sim/pull/707) 1. Scenebroadcaster sensors - * [Pull request #698](https://github.com/ignitionrobotics/ign-gazebo/pull/698) + * [Pull request #698](https://github.com/gazebosim/gz-sim/pull/698) 1. Add test for thermal object temperatures below 0 kelvin - * [Pull request #621](https://github.com/ignitionrobotics/ign-gazebo/pull/621) + * [Pull request #621](https://github.com/gazebosim/gz-sim/pull/621) 1. [BULLET] Making GetContactsFromLastStepFeature optional in Collision Features - * [Pull request #690](https://github.com/ignitionrobotics/ign-gazebo/pull/690) + * [Pull request #690](https://github.com/gazebosim/gz-sim/pull/690) 1. Make it so joint state publisher is quieter - * [Pull request #696](https://github.com/ignitionrobotics/ign-gazebo/pull/696) + * [Pull request #696](https://github.com/gazebosim/gz-sim/pull/696) -### Ignition Gazebo 5.0.0 (2021-03-30) +### Gazebo Sim 5.0.0 (2021-03-30) 1. Added Ellipsoid and Capsule geometries - * [Pull request #581](https://github.com/ignitionrobotics/ign-gazebo/pull/581) + * [Pull request #581](https://github.com/gazebosim/gz-sim/pull/581) 1. Support individual canonical links for nested models - * [Pull request #685](https://github.com/ignitionrobotics/ign-gazebo/pull/685) + * [Pull request #685](https://github.com/gazebosim/gz-sim/pull/685) 1. Mecanum wheels demo - * [Pull request #683](https://github.com/ignitionrobotics/ign-gazebo/pull/683) + * [Pull request #683](https://github.com/gazebosim/gz-sim/pull/683) 1. Fixed collision visual bounding boxes - * [Pull request #702](https://github.com/ignitionrobotics/ign-gazebo/pull/702) + * [Pull request #702](https://github.com/gazebosim/gz-sim/pull/702) 1. Fixed material colors for ackermann sdfs - * [Pull request #703](https://github.com/ignitionrobotics/ign-gazebo/pull/703) + * [Pull request #703](https://github.com/gazebosim/gz-sim/pull/703) 1. Setting the intiial velocity for a model or joint - * [Pull request #693](https://github.com/ignitionrobotics/ign-gazebo/pull/693) + * [Pull request #693](https://github.com/gazebosim/gz-sim/pull/693) 1. Remove static for maps from Factory.hh - * [Pull request #635](https://github.com/ignitionrobotics/ign-gazebo/pull/635) + * [Pull request #635](https://github.com/gazebosim/gz-sim/pull/635) 1. Depend on cli component of ignition-utils1 - * [Pull request #671](https://github.com/ignitionrobotics/ign-gazebo/pull/671) + * [Pull request #671](https://github.com/gazebosim/gz-sim/pull/671) 1. Support SDFormat 1.8 Composition - * [Pull request #542](https://github.com/ignitionrobotics/ign-gazebo/pull/542) + * [Pull request #542](https://github.com/gazebosim/gz-sim/pull/542) 1. Deprecate TmpIface: it's leftover from prototyping - * [Pull request #654](https://github.com/ignitionrobotics/ign-gazebo/pull/654) + * [Pull request #654](https://github.com/gazebosim/gz-sim/pull/654) -1. Bump in edifice: ign-common4 - * [Pull request #577](https://github.com/ignitionrobotics/ign-gazebo/pull/577) +1. Bump in edifice: gz-common4 + * [Pull request #577](https://github.com/gazebosim/gz-sim/pull/577) 1. Plugin to spawn lights - * [Pull request #587](https://github.com/ignitionrobotics/ign-gazebo/pull/587) + * [Pull request #587](https://github.com/gazebosim/gz-sim/pull/587) 1. Added light intensity - * [Pull request #612](https://github.com/ignitionrobotics/ign-gazebo/pull/612) - * [Pull request #670](https://github.com/ignitionrobotics/ign-gazebo/pull/670) + * [Pull request #612](https://github.com/gazebosim/gz-sim/pull/612) + * [Pull request #670](https://github.com/gazebosim/gz-sim/pull/670) 1. Examples and tutorial on using rendering API from plugins - * [Pull request #596](https://github.com/ignitionrobotics/ign-gazebo/pull/596) + * [Pull request #596](https://github.com/gazebosim/gz-sim/pull/596) 1. Prepare GuiRunner to be made private - * [Pull request #567](https://github.com/ignitionrobotics/ign-gazebo/pull/567) + * [Pull request #567](https://github.com/gazebosim/gz-sim/pull/567) -1. Deprecate some gazebo::gui events in favor of ign-gui events - * [Pull request #595](https://github.com/ignitionrobotics/ign-gazebo/pull/595) +1. Deprecate some sim::gui events in favor of gz-gui events + * [Pull request #595](https://github.com/gazebosim/gz-sim/pull/595) 1. Heightmap (rendering only) - * [Pull request #487](https://github.com/ignitionrobotics/ign-gazebo/pull/487) + * [Pull request #487](https://github.com/gazebosim/gz-sim/pull/487) 1. Add image suffix to thermal camera topic name - * [Pull request #606](https://github.com/ignitionrobotics/ign-gazebo/pull/606) + * [Pull request #606](https://github.com/gazebosim/gz-sim/pull/606) 1. Fix build with latest sdformat11 branch - * [Pull request #607](https://github.com/ignitionrobotics/ign-gazebo/pull/607) + * [Pull request #607](https://github.com/gazebosim/gz-sim/pull/607) 1. Added run to time feature - * [Pull request #478](https://github.com/ignitionrobotics/ign-gazebo/pull/478) + * [Pull request #478](https://github.com/gazebosim/gz-sim/pull/478) 1. Depend on ignition-utils1 - * [Pull request #591](https://github.com/ignitionrobotics/ign-gazebo/pull/591) + * [Pull request #591](https://github.com/gazebosim/gz-sim/pull/591) 1. Use double sided field in material msg - * [Pull request #599](https://github.com/ignitionrobotics/ign-gazebo/pull/599) + * [Pull request #599](https://github.com/gazebosim/gz-sim/pull/599) 1. Add lightmap demo - * [Pull request #471](https://github.com/ignitionrobotics/ign-gazebo/pull/471) + * [Pull request #471](https://github.com/gazebosim/gz-sim/pull/471) 1. Added renderOrder to convert functions - * [Pull request #514](https://github.com/ignitionrobotics/ign-gazebo/pull/514) + * [Pull request #514](https://github.com/gazebosim/gz-sim/pull/514) 1. Compilation fixes for Windows - * [Pull request #501](https://github.com/ignitionrobotics/ign-gazebo/pull/501) - * [Pull request #585](https://github.com/ignitionrobotics/ign-gazebo/pull/585) - * [Pull request #565](https://github.com/ignitionrobotics/ign-gazebo/pull/565) - * [Pull request #616](https://github.com/ignitionrobotics/ign-gazebo/pull/616) - * [Pull request #622](https://github.com/ignitionrobotics/ign-gazebo/pull/622) + * [Pull request #501](https://github.com/gazebosim/gz-sim/pull/501) + * [Pull request #585](https://github.com/gazebosim/gz-sim/pull/585) + * [Pull request #565](https://github.com/gazebosim/gz-sim/pull/565) + * [Pull request #616](https://github.com/gazebosim/gz-sim/pull/616) + * [Pull request #622](https://github.com/gazebosim/gz-sim/pull/622) 1. Documentation fixes - * [Pull request #727](https://github.com/ignitionrobotics/ign-gazebo/pull/727) - * [Pull request #710](https://github.com/ignitionrobotics/ign-gazebo/pull/710) + * [Pull request #727](https://github.com/gazebosim/gz-sim/pull/727) + * [Pull request #710](https://github.com/gazebosim/gz-sim/pull/710) 1. Replace deprecated function FreeGroup::CanonicalLink with FreeGroup::RootLink - * [Pull request #723](https://github.com/ignitionrobotics/ign-gazebo/pull/723) + * [Pull request #723](https://github.com/gazebosim/gz-sim/pull/723) 1. Respect spotlight direction - * [Pull request #718](https://github.com/ignitionrobotics/ign-gazebo/pull/718) + * [Pull request #718](https://github.com/gazebosim/gz-sim/pull/718) 1. Add UserCommands plugin to fuel.sdf - * [Pull request #719](https://github.com/ignitionrobotics/ign-gazebo/pull/719) + * [Pull request #719](https://github.com/gazebosim/gz-sim/pull/719) 1. Change SelectedEntities to return a const ref - * [Pull request #571](https://github.com/ignitionrobotics/ign-gazebo/pull/571) + * [Pull request #571](https://github.com/gazebosim/gz-sim/pull/571) 1. Use common::setenv for portability to Windows - * [Pull request #561](https://github.com/ignitionrobotics/ign-gazebo/pull/561) + * [Pull request #561](https://github.com/gazebosim/gz-sim/pull/561) -1. Add missing IGNITION_GAZEBO_VISIBLE macros - * [Pull request #563](https://github.com/ignitionrobotics/ign-gazebo/pull/563) +1. Add missing GZ_SIM_VISIBLE macros + * [Pull request #563](https://github.com/gazebosim/gz-sim/pull/563) 1. Fix deprecation warnings - * [Pull request #572](https://github.com/ignitionrobotics/ign-gazebo/pull/572) + * [Pull request #572](https://github.com/gazebosim/gz-sim/pull/572) 1. Fix visibility macro names when used by a different component (Windows) - * [Pull request #564](https://github.com/ignitionrobotics/ign-gazebo/pull/564) + * [Pull request #564](https://github.com/gazebosim/gz-sim/pull/564) -1. Bump edifice sdformat11 and ign-physics4 - * [Pull request #549](https://github.com/ignitionrobotics/ign-gazebo/pull/549) +1. Bump edifice sdformat11 and gz-physics4 + * [Pull request #549](https://github.com/gazebosim/gz-sim/pull/549) 1. Use ComponentState::PeriodicChange in UpdateState to avoid forcing full scene update - * [Pull request #486](https://github.com/ignitionrobotics/ign-gazebo/pull/486) + * [Pull request #486](https://github.com/gazebosim/gz-sim/pull/486) -1. Bump in edifice: ign-msgs7 - * [Pull request #546](https://github.com/ignitionrobotics/ign-gazebo/pull/546) +1. Bump in edifice: gz-msgs7 + * [Pull request #546](https://github.com/gazebosim/gz-sim/pull/546) 1. Add support for sky - * [Pull request #445](https://github.com/ignitionrobotics/ign-gazebo/pull/445) + * [Pull request #445](https://github.com/gazebosim/gz-sim/pull/445) 1. Infrastructure - * [Pull request #423](https://github.com/ignitionrobotics/ign-gazebo/pull/423) + * [Pull request #423](https://github.com/gazebosim/gz-sim/pull/423) -1. Bump in edifice: ign-rendering5 - * [Pull request #430](https://github.com/ignitionrobotics/ign-gazebo/pull/430) +1. Bump in edifice: gz-rendering5 + * [Pull request #430](https://github.com/gazebosim/gz-sim/pull/430) 1. Add 25percent darker view angle icons - * [Pull request #426](https://github.com/ignitionrobotics/ign-gazebo/pull/426) + * [Pull request #426](https://github.com/gazebosim/gz-sim/pull/426) -## Ignition Gazebo 4.x +## Gazebo Sim 4.x -### Ignition Gazebo 4.14.0 (2021-12-20) +### Gazebo Sim 4.14.0 (2021-12-20) 1. Support battery draining start via topics - * [Pull request #1255](https://github.com/ignitionrobotics/ign-gazebo/pull/1255) + * [Pull request #1255](https://github.com/gazebosim/gz-sim/pull/1255) 1. Make tests run as fast as possible - * [Pull request #1194](https://github.com/ignitionrobotics/ign-gazebo/pull/1194) - * [Pull request #1250](https://github.com/ignitionrobotics/ign-gazebo/pull/1250) + * [Pull request #1194](https://github.com/gazebosim/gz-sim/pull/1194) + * [Pull request #1250](https://github.com/gazebosim/gz-sim/pull/1250) 1. Fix visualize lidar - * [Pull request #1224](https://github.com/ignitionrobotics/ign-gazebo/pull/1224) + * [Pull request #1224](https://github.com/gazebosim/gz-sim/pull/1224) 1. Disable user commands light test on macOS - * [Pull request #1204](https://github.com/ignitionrobotics/ign-gazebo/pull/1204) + * [Pull request #1204](https://github.com/gazebosim/gz-sim/pull/1204) -### Ignition Gazebo 4.13.0 (2021-11-15) +### Gazebo Sim 4.13.0 (2021-11-15) 1. Prevent creation of spurious `` elements when saving worlds - * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + * [Pull request #1192](https://github.com/gazebosim/gz-sim/pull/1192) 1. Add support for tracked vehicles - * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + * [Pull request #869](https://github.com/gazebosim/gz-sim/pull/869) 1. Add components to dynamically set joint limits - * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + * [Pull request #847](https://github.com/gazebosim/gz-sim/pull/847) 1. Fix updating component from state - * [Pull request #1181](https://github.com/ignitionrobotics/ign-gazebo/pull/1181) + * [Pull request #1181](https://github.com/gazebosim/gz-sim/pull/1181) 1. Fix updating a component's data via SerializedState msg - * [Pull request #1149](https://github.com/ignitionrobotics/ign-gazebo/pull/1149) + * [Pull request #1149](https://github.com/gazebosim/gz-sim/pull/1149) 1. Sensor systems work if loaded after sensors - * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + * [Pull request #1104](https://github.com/gazebosim/gz-sim/pull/1104) 1. Fix generation of systems library symlinks in build directory - * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) 1. Edit material colors in component inspector - * [Pull request #1123](https://github.com/ignitionrobotics/ign-gazebo/pull/1123) + * [Pull request #1123](https://github.com/gazebosim/gz-sim/pull/1123) 1. Support setting the background color for sensors - * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + * [Pull request #1147](https://github.com/gazebosim/gz-sim/pull/1147) 1. Use uint64_t for ComponentInspector Entity IDs - * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + * [Pull request #1144](https://github.com/gazebosim/gz-sim/pull/1144) 1. Fix integers and floats on component inspector - * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + * [Pull request #1143](https://github.com/gazebosim/gz-sim/pull/1143) -### Ignition Gazebo 4.12.0 (2021-10-22) +### Gazebo Sim 4.12.0 (2021-10-22) 1. Fix performance issue with contact data and AABB updates. - * [Pull Request 1048](https://github.com/ignitionrobotics/ign-gazebo/pull/1048) + * [Pull Request 1048](https://github.com/gazebosim/gz-sim/pull/1048) 1. Enable new CMake policy to fix protobuf compilation - * [Pull Request 1059](https://github.com/ignitionrobotics/ign-gazebo/pull/1059) + * [Pull Request 1059](https://github.com/gazebosim/gz-sim/pull/1059) 1. Parse new param for enabling / disabling IMU orientation output. - * [Pull Request 899](https://github.com/ignitionrobotics/ign-gazebo/pull/899) + * [Pull Request 899](https://github.com/gazebosim/gz-sim/pull/899) 1. Fix light control standalone example. - * [Pull Request 1077](https://github.com/ignitionrobotics/ign-gazebo/pull/1077) + * [Pull Request 1077](https://github.com/gazebosim/gz-sim/pull/1077) 1. Performance: use std::unordered_map where possible in SceneManager. - * [Pull Request 1083](https://github.com/ignitionrobotics/ign-gazebo/pull/1083) + * [Pull Request 1083](https://github.com/gazebosim/gz-sim/pull/1083) 1. Prevent crash when using workflow PBR material. - * [Pull Request 1099](https://github.com/ignitionrobotics/ign-gazebo/pull/1099) + * [Pull Request 1099](https://github.com/gazebosim/gz-sim/pull/1099) 1. JointPositionController: Improve misleading error message. - * [Pull Request 1098](https://github.com/ignitionrobotics/ign-gazebo/pull/1098) + * [Pull Request 1098](https://github.com/gazebosim/gz-sim/pull/1098) 1. Adjust pose decimals based on element width. - * [Pull Request 1089](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull Request 1089](https://github.com/gazebosim/gz-sim/pull/1089) 1. Better protect this->dataPtr->initialized with renderMutex. - * [Pull Request 1119](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull Request 1119](https://github.com/gazebosim/gz-sim/pull/1089) 1. Updates to camera video record from subt. - * [Pull Request 1117](https://github.com/ignitionrobotics/ign-gazebo/pull/1117) + * [Pull Request 1117](https://github.com/gazebosim/gz-sim/pull/1117) 1. Fix performance level test flakiness. - * [Pull Request 1129](https://github.com/ignitionrobotics/ign-gazebo/pull/1129) + * [Pull Request 1129](https://github.com/gazebosim/gz-sim/pull/1129) -### Ignition Gazebo 4.11.0 (2021-09-23) +### Gazebo Sim 4.11.0 (2021-09-23) 1. Support locked entities, and headless video recording using sim time. - * [Pull Request 862](https://github.com/ignitionrobotics/ign-gazebo/pull/862) + * [Pull Request 862](https://github.com/gazebosim/gz-sim/pull/862) -### Ignition Gazebo 4.10.0 (2021-09-15) +### Gazebo Sim 4.10.0 (2021-09-15) 1. Fixed GUI's ComponentInspector light parameter - * [Pull Request 1018](https://github.com/ignitionrobotics/ign-gazebo/pull/1018) + * [Pull Request 1018](https://github.com/gazebosim/gz-sim/pull/1018) 1. Fix msg in entity_creation example - * [Pull Request 972](https://github.com/ignitionrobotics/ign-gazebo/pull/972) + * [Pull Request 972](https://github.com/gazebosim/gz-sim/pull/972) 1. Fix selection buffer crash on resize - * [Pull Request 969](https://github.com/ignitionrobotics/ign-gazebo/pull/969) + * [Pull Request 969](https://github.com/gazebosim/gz-sim/pull/969) 1. Fix crash in the follow_actor example - * [Pull Request 958](https://github.com/ignitionrobotics/ign-gazebo/pull/958) + * [Pull Request 958](https://github.com/gazebosim/gz-sim/pull/958) 1. Fix joint controller with empty joint velocity data - * [Pull Request 937](https://github.com/ignitionrobotics/ign-gazebo/pull/937) + * [Pull Request 937](https://github.com/gazebosim/gz-sim/pull/937) 1. Scale mode - Part2 - * [Pull Request 881](https://github.com/ignitionrobotics/ign-gazebo/pull/881) + * [Pull Request 881](https://github.com/gazebosim/gz-sim/pull/881) 1. Physics system: update link poses if the canonical link pose has been updated - * [Pull Request 876](https://github.com/ignitionrobotics/ign-gazebo/pull/876) + * [Pull Request 876](https://github.com/gazebosim/gz-sim/pull/876) 1. Add Particle Emitter tutorial - * [Pull Request 860](https://github.com/ignitionrobotics/ign-gazebo/pull/860) + * [Pull Request 860](https://github.com/gazebosim/gz-sim/pull/860) 1. Refactor RenderUtil::Update with helper functions - * [Pull Request 858](https://github.com/ignitionrobotics/ign-gazebo/pull/858) + * [Pull Request 858](https://github.com/gazebosim/gz-sim/pull/858) 1. Remove unneeded camera follow offset checks - * [Pull Request 857](https://github.com/ignitionrobotics/ign-gazebo/pull/857) + * [Pull Request 857](https://github.com/gazebosim/gz-sim/pull/857) 1. Added service to set camera's follow offset - * [Pull Request 855](https://github.com/ignitionrobotics/ign-gazebo/pull/855) + * [Pull Request 855](https://github.com/gazebosim/gz-sim/pull/855) 1. Using math::SpeedLimiter on the ackermann_steering controller. - * [Pull Request 837](https://github.com/ignitionrobotics/ign-gazebo/pull/837) + * [Pull Request 837](https://github.com/gazebosim/gz-sim/pull/837) -1. All changes merged forward from ign-gazebo3 - * [Pull Request 866](https://github.com/ignitionrobotics/ign-gazebo/pull/866) - * [Pull Request 916](https://github.com/ignitionrobotics/ign-gazebo/pull/916) - * [Pull Request 933](https://github.com/ignitionrobotics/ign-gazebo/pull/933) - * [Pull Request 946](https://github.com/ignitionrobotics/ign-gazebo/pull/946) - * [Pull Request 973](https://github.com/ignitionrobotics/ign-gazebo/pull/973) - * [Pull Request 1017](https://github.com/ignitionrobotics/ign-gazebo/pull/1017) +1. All changes merged forward from gz-sim3 + * [Pull Request 866](https://github.com/gazebosim/gz-sim/pull/866) + * [Pull Request 916](https://github.com/gazebosim/gz-sim/pull/916) + * [Pull Request 933](https://github.com/gazebosim/gz-sim/pull/933) + * [Pull Request 946](https://github.com/gazebosim/gz-sim/pull/946) + * [Pull Request 973](https://github.com/gazebosim/gz-sim/pull/973) + * [Pull Request 1017](https://github.com/gazebosim/gz-sim/pull/1017) -### Ignition Gazebo 4.9.1 (2021-05-24) +### Gazebo Sim 4.9.1 (2021-05-24) 1. Make halt motion act like a brake. - * [Pull Request 830](https://github.com/ignitionrobotics/ign-gazebo/pull/830) + * [Pull Request 830](https://github.com/gazebosim/gz-sim/pull/830) -### Ignition Gazebo 4.9.0 (2021-05-20) +### Gazebo Sim 4.9.0 (2021-05-20) 1. Enable Focal CI. - * [Pull Request 646](https://github.com/ignitionrobotics/ign-gazebo/pull/646) + * [Pull Request 646](https://github.com/gazebosim/gz-sim/pull/646) 1. [TPE] Support setting individual link velocity. - * [Pull Request 427](https://github.com/ignitionrobotics/ign-gazebo/pull/427) + * [Pull Request 427](https://github.com/gazebosim/gz-sim/pull/427) 1. Don't store duplicate ComponentTypeId in ECM. - * [Pull Request 751](https://github.com/ignitionrobotics/ign-gazebo/pull/751) + * [Pull Request 751](https://github.com/gazebosim/gz-sim/pull/751) 1. Fix macOS build: components::Name in benchmark. - * [Pull Request 784](https://github.com/ignitionrobotics/ign-gazebo/pull/784) + * [Pull Request 784](https://github.com/gazebosim/gz-sim/pull/784) 1. Fix documentation for EntityComponentManager::EachNew. - * [Pull Request 795](https://github.com/ignitionrobotics/ign-gazebo/pull/795) + * [Pull Request 795](https://github.com/gazebosim/gz-sim/pull/795) 1. Add functionalities for optical tactile plugin. - * [Pull Request 431](https://github.com/ignitionrobotics/ign-gazebo/pull/431) + * [Pull Request 431](https://github.com/gazebosim/gz-sim/pull/431) 1. Visualize ContactSensorData. - * [Pull Request 234](https://github.com/ignitionrobotics/ign-gazebo/pull/234) + * [Pull Request 234](https://github.com/gazebosim/gz-sim/pull/234) 1. Backport PR #763. - * [Pull Request 804](https://github.com/ignitionrobotics/ign-gazebo/pull/804) + * [Pull Request 804](https://github.com/gazebosim/gz-sim/pull/804) 1. Backport PR #536. - * [Pull Request 812](https://github.com/ignitionrobotics/ign-gazebo/pull/812) + * [Pull Request 812](https://github.com/gazebosim/gz-sim/pull/812) 1. Add an optional delay to the TriggeredPublisher system. - * [Pull Request 817](https://github.com/ignitionrobotics/ign-gazebo/pull/817) + * [Pull Request 817](https://github.com/gazebosim/gz-sim/pull/817) 1. Remove tools/code_check and update codecov. - * [Pull Request 814](https://github.com/ignitionrobotics/ign-gazebo/pull/814) + * [Pull Request 814](https://github.com/gazebosim/gz-sim/pull/814) 1. add conversion for particle scatter ratio field. - * [Pull Request 791](https://github.com/ignitionrobotics/ign-gazebo/pull/791) + * [Pull Request 791](https://github.com/gazebosim/gz-sim/pull/791) -### Ignition Gazebo 4.8.0 (2021-04-22) +### Gazebo Sim 4.8.0 (2021-04-22) 1. Add odometry publisher system. - * [Pull Request 547](https://github.com/ignitionrobotics/ign-gazebo/pull/547) + * [Pull Request 547](https://github.com/gazebosim/gz-sim/pull/547) 1. Patch particle emitter2 service. - * [Pull Request 777](https://github.com/ignitionrobotics/ign-gazebo/pull/777) + * [Pull Request 777](https://github.com/gazebosim/gz-sim/pull/777) -### Ignition Gazebo 4.7.0 (2021-04-09) +### Gazebo Sim 4.7.0 (2021-04-09) 1. Particle emitter based on SDF. - * [Pull Request 730](https://github.com/ignitionrobotics/ign-gazebo/pull/730) + * [Pull Request 730](https://github.com/gazebosim/gz-sim/pull/730) 1. Fix log playback for particle emitters. - * [Pull Request 745](https://github.com/ignitionrobotics/ign-gazebo/pull/745) + * [Pull Request 745](https://github.com/gazebosim/gz-sim/pull/745) 1. ECM's ChangedState gets message with modified components. - * [Pull Request 742](https://github.com/ignitionrobotics/ign-gazebo/pull/742) + * [Pull Request 742](https://github.com/gazebosim/gz-sim/pull/742) 1. Fixed collision visual bounding boxes. - * [Pull Request 746](https://github.com/ignitionrobotics/ign-gazebo/pull/746) + * [Pull Request 746](https://github.com/gazebosim/gz-sim/pull/746) 1. Fix compute_rtfs arguments. - * [Pull Request 737](https://github.com/ignitionrobotics/ign-gazebo/pull/737) + * [Pull Request 737](https://github.com/gazebosim/gz-sim/pull/737) 1. Validate step size and RTF parameters. - * [Pull Request 740](https://github.com/ignitionrobotics/ign-gazebo/pull/740) + * [Pull Request 740](https://github.com/gazebosim/gz-sim/pull/740) 1. Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config. - * [Pull Request 715](https://github.com/ignitionrobotics/ign-gazebo/pull/715) + * [Pull Request 715](https://github.com/gazebosim/gz-sim/pull/715) 1. Do not pass -Wno-unused-parameter to MSVC compiler. - * [Pull Request 716](https://github.com/ignitionrobotics/ign-gazebo/pull/716) + * [Pull Request 716](https://github.com/gazebosim/gz-sim/pull/716) 1. Support configuring particle scatter ratio in particle emitter system. - * [Pull Request 674](https://github.com/ignitionrobotics/ign-gazebo/pull/674) + * [Pull Request 674](https://github.com/gazebosim/gz-sim/pull/674) 1. Fix diffuse and ambient values for ackermann example. - * [Pull Request 707](https://github.com/ignitionrobotics/ign-gazebo/pull/707) + * [Pull Request 707](https://github.com/gazebosim/gz-sim/pull/707) 1. Scenebroadcaster sensors. - * [Pull Request 698](https://github.com/ignitionrobotics/ign-gazebo/pull/698) + * [Pull Request 698](https://github.com/gazebosim/gz-sim/pull/698) 1. Add thermal camera test for object temperature below 0. - * [Pull Request 621](https://github.com/ignitionrobotics/ign-gazebo/pull/621) + * [Pull Request 621](https://github.com/gazebosim/gz-sim/pull/621) 1. [BULLET] Making GetContactsFromLastStepFeature optional in Collision Features - * [Pull Request 690](https://github.com/ignitionrobotics/ign-gazebo/pull/690) + * [Pull Request 690](https://github.com/gazebosim/gz-sim/pull/690) 1. Fix joint controller GUI test. - * [Pull Request 697](https://github.com/ignitionrobotics/ign-gazebo/pull/697) + * [Pull Request 697](https://github.com/gazebosim/gz-sim/pull/697) 1. Quiet warnings from Joint State Publisher. - * [Pull Request 696](https://github.com/ignitionrobotics/ign-gazebo/pull/696) + * [Pull Request 696](https://github.com/gazebosim/gz-sim/pull/696) 1. Ackermann Steering Plugin. - * [Pull Request 618](https://github.com/ignitionrobotics/ign-gazebo/pull/618) + * [Pull Request 618](https://github.com/gazebosim/gz-sim/pull/618) 1. Remove bounding box when model is deleted - * [Pull Request 675](https://github.com/ignitionrobotics/ign-gazebo/pull/675) + * [Pull Request 675](https://github.com/gazebosim/gz-sim/pull/675) 1. Cache link poses to improve performance. - * [Pull Request 669](https://github.com/ignitionrobotics/ign-gazebo/pull/669) + * [Pull Request 669](https://github.com/gazebosim/gz-sim/pull/669) 1. Check empty world name in Scene3d. - * [Pull Request 662](https://github.com/ignitionrobotics/ign-gazebo/pull/662) + * [Pull Request 662](https://github.com/gazebosim/gz-sim/pull/662) 1. All changes up to 3.8.0. -### Ignition Gazebo 4.6.0 (2021-03-01) +### Gazebo Sim 4.6.0 (2021-03-01) 1. Use a custom data structure to manage entity feature maps. - * [Pull Request 586](https://github.com/ignitionrobotics/ign-gazebo/pull/586) + * [Pull Request 586](https://github.com/gazebosim/gz-sim/pull/586) 1. Limit scene broadcast publications when paused. - * [Pull Request 497](https://github.com/ignitionrobotics/ign-gazebo/pull/497) + * [Pull Request 497](https://github.com/gazebosim/gz-sim/pull/497) 1. Report performer count in PerformerDetector plugin. - * [Pull Request 652](https://github.com/ignitionrobotics/ign-gazebo/pull/652) + * [Pull Request 652](https://github.com/gazebosim/gz-sim/pull/652) 1. Cache top level and static to speed up physics system. - * [Pull Request 656](https://github.com/ignitionrobotics/ign-gazebo/pull/656) + * [Pull Request 656](https://github.com/gazebosim/gz-sim/pull/656) 1. Support particle emitter modification using partial message. - * [Pull Request 651](https://github.com/ignitionrobotics/ign-gazebo/pull/651) + * [Pull Request 651](https://github.com/gazebosim/gz-sim/pull/651) 1. Set LD_LIBRARY_PATH on Actions CI. - * [Pull Request 650](https://github.com/ignitionrobotics/ign-gazebo/pull/650) + * [Pull Request 650](https://github.com/gazebosim/gz-sim/pull/650) 1. Fix flaky SceneBroadcaster test. - * [Pull Request 641](https://github.com/ignitionrobotics/ign-gazebo/pull/641) + * [Pull Request 641](https://github.com/gazebosim/gz-sim/pull/641) 1. Add a convenience function for getting possibly non-existing components. - * [Pull Request 629](https://github.com/ignitionrobotics/ign-gazebo/pull/629) + * [Pull Request 629](https://github.com/gazebosim/gz-sim/pull/629) 1. Add msg to show the computed temperature range computed from temperature gradient. - * [Pull Request 643](https://github.com/ignitionrobotics/ign-gazebo/pull/643) + * [Pull Request 643](https://github.com/gazebosim/gz-sim/pull/643) 1. Add TF/Pose_V pub in DiffDrive. - * [Pull Request 548](https://github.com/ignitionrobotics/ign-gazebo/pull/548) + * [Pull Request 548](https://github.com/gazebosim/gz-sim/pull/548) 1. Relax flaky performance test. - * [Pull Request 640](https://github.com/ignitionrobotics/ign-gazebo/pull/640) + * [Pull Request 640](https://github.com/gazebosim/gz-sim/pull/640) 1. Improve velocity control test. - * [Pull Request 642](https://github.com/ignitionrobotics/ign-gazebo/pull/642) + * [Pull Request 642](https://github.com/gazebosim/gz-sim/pull/642) 1. Validity check for user defined topics in JointPositionController. - * [Pull Request 639](https://github.com/ignitionrobotics/ign-gazebo/pull/639) + * [Pull Request 639](https://github.com/gazebosim/gz-sim/pull/639) 1. Add laser_retro support. - * [Pull Request 603](https://github.com/ignitionrobotics/ign-gazebo/pull/603) + * [Pull Request 603](https://github.com/gazebosim/gz-sim/pull/603) 1. Fix pose of plane visual with non-default normal vector. - * [Pull Request 574](https://github.com/ignitionrobotics/ign-gazebo/pull/574) + * [Pull Request 574](https://github.com/gazebosim/gz-sim/pull/574) -### Ignition Gazebo 4.5.0 (2020-02-17) +### Gazebo Sim 4.5.0 (2020-02-17) 1. Added particle system. - * [Pull Request 516](https://github.com/ignitionrobotics/ign-gazebo/pull/516) + * [Pull Request 516](https://github.com/gazebosim/gz-sim/pull/516) 1. Add Light Usercommand and include Light parameters in the componentInspector - * [Pull Request 482](https://github.com/ignitionrobotics/ign-gazebo/pull/482) + * [Pull Request 482](https://github.com/gazebosim/gz-sim/pull/482) 1. Added link to HW-accelerated video recording. - * [Pull Request 627](https://github.com/ignitionrobotics/ign-gazebo/pull/627) + * [Pull Request 627](https://github.com/gazebosim/gz-sim/pull/627) 1. Fix EntityComponentManager race condition. - * [Pull Request 601](https://github.com/ignitionrobotics/ign-gazebo/pull/601) + * [Pull Request 601](https://github.com/gazebosim/gz-sim/pull/601) 1. Add SDF topic validity check. - * [Pull Request 632](https://github.com/ignitionrobotics/ign-gazebo/pull/632) + * [Pull Request 632](https://github.com/gazebosim/gz-sim/pull/632) 1. Add JointTrajectoryController system plugin. - * [Pull Request 473](https://github.com/ignitionrobotics/ign-gazebo/pull/473) + * [Pull Request 473](https://github.com/gazebosim/gz-sim/pull/473) -### Ignition Gazebo 4.4.0 (2020-02-10) +### Gazebo Sim 4.4.0 (2020-02-10) 1. Added issue and PR templates - * [Pull Request 613](https://github.com/ignitionrobotics/ign-gazebo/pull/613) + * [Pull Request 613](https://github.com/gazebosim/gz-sim/pull/613) 1. Fix segfault in SetRemovedComponentsMsgs method - * [Pull Request 495](https://github.com/ignitionrobotics/ign-gazebo/pull/495) + * [Pull Request 495](https://github.com/gazebosim/gz-sim/pull/495) 1. Make topics configurable for joint controllers - * [Pull Request 584](https://github.com/ignitionrobotics/ign-gazebo/pull/584) + * [Pull Request 584](https://github.com/gazebosim/gz-sim/pull/584) 1. Add about dialog - * [Pull Request 609](https://github.com/ignitionrobotics/ign-gazebo/pull/609) + * [Pull Request 609](https://github.com/gazebosim/gz-sim/pull/609) 1. Add thermal sensor system for configuring thermal camera properties - * [Pull Request 614](https://github.com/ignitionrobotics/ign-gazebo/pull/614) + * [Pull Request 614](https://github.com/gazebosim/gz-sim/pull/614) -### Ignition Gazebo 4.3.0 (2020-02-02) +### Gazebo Sim 4.3.0 (2020-02-02) 1. Non-blocking paths request. - * [Pull Request 555](https://github.com/ignitionrobotics/ign-gazebo/pull/555) + * [Pull Request 555](https://github.com/gazebosim/gz-sim/pull/555) 1. Parallelize State call in ECM. - * [Pull Request 451](https://github.com/ignitionrobotics/ign-gazebo/pull/451) + * [Pull Request 451](https://github.com/gazebosim/gz-sim/pull/451) 1. Allow to create light with the create service. - * [Pull Request 513](https://github.com/ignitionrobotics/ign-gazebo/pull/513) + * [Pull Request 513](https://github.com/gazebosim/gz-sim/pull/513) 1. Added size to ground_plane in examples. - * [Pull Request 573](https://github.com/ignitionrobotics/ign-gazebo/pull/573) + * [Pull Request 573](https://github.com/gazebosim/gz-sim/pull/573) 1. Fix finding PBR materials. - * [Pull Request 575](https://github.com/ignitionrobotics/ign-gazebo/pull/575) + * [Pull Request 575](https://github.com/gazebosim/gz-sim/pull/575) 1. Publish all periodic change components in Scene Broadcaster. - * [Pull Request 544](https://github.com/ignitionrobotics/ign-gazebo/pull/544) + * [Pull Request 544](https://github.com/gazebosim/gz-sim/pull/544) -1. Backport state update changes from pull request [#486](https://github.com/ignitionrobotics/ign-gazebo/pull/486). - * [Pull Request 583](https://github.com/ignitionrobotics/ign-gazebo/pull/583) +1. Backport state update changes from pull request [#486](https://github.com/gazebosim/gz-sim/pull/486). + * [Pull Request 583](https://github.com/gazebosim/gz-sim/pull/583) 1. Fix code_check errors. - * [Pull Request 582](https://github.com/ignitionrobotics/ign-gazebo/pull/582) + * [Pull Request 582](https://github.com/gazebosim/gz-sim/pull/582) 1. Visualize collisions. - * [Pull Request 531](https://github.com/ignitionrobotics/ign-gazebo/pull/531) + * [Pull Request 531](https://github.com/gazebosim/gz-sim/pull/531) 1. Remove playback SDF param in Dome. - * [Pull Request 570](https://github.com/ignitionrobotics/ign-gazebo/pull/570) + * [Pull Request 570](https://github.com/gazebosim/gz-sim/pull/570) 1. Tutorial on migrating SDF files from Gazebo classic. - * [Pull Request 400](https://github.com/ignitionrobotics/ign-gazebo/pull/400) + * [Pull Request 400](https://github.com/gazebosim/gz-sim/pull/400) 1. World Exporter. - * [Pull Request 474](https://github.com/ignitionrobotics/ign-gazebo/pull/474) + * [Pull Request 474](https://github.com/gazebosim/gz-sim/pull/474) 1. Model Creation tutorial using services. - * [Pull Request 530](https://github.com/ignitionrobotics/ign-gazebo/pull/530) + * [Pull Request 530](https://github.com/gazebosim/gz-sim/pull/530) 1. Fix topLevelModel Method. - * [Pull Request 600](https://github.com/ignitionrobotics/ign-gazebo/pull/600) + * [Pull Request 600](https://github.com/gazebosim/gz-sim/pull/600) 1. Add heat signature option to thermal system. - * [Pull Request 498](https://github.com/ignitionrobotics/ign-gazebo/pull/498) + * [Pull Request 498](https://github.com/gazebosim/gz-sim/pull/498) 1. Add service and GUI to configure physics parameters (step size and RTF). - * [Pull Request 536](https://github.com/ignitionrobotics/ign-gazebo/pull/536) + * [Pull Request 536](https://github.com/gazebosim/gz-sim/pull/536) 1. Refactor UNIT_Server_TEST. - * [Pull Request 594](https://github.com/ignitionrobotics/ign-gazebo/pull/594) + * [Pull Request 594](https://github.com/gazebosim/gz-sim/pull/594) -1. Use Ignition GUI render event. - * [Pull Request 598](https://github.com/ignitionrobotics/ign-gazebo/pull/598) +1. Use Gazebo GUI render event. + * [Pull Request 598](https://github.com/gazebosim/gz-sim/pull/598) -### Ignition Gazebo 4.2.0 (2020-01-13) +### Gazebo Sim 4.2.0 (2020-01-13) 1. Automatically load a subset of world plugins. - * [Pull Request 537](https://github.com/ignitionrobotics/ign-gazebo/pull/537) + * [Pull Request 537](https://github.com/gazebosim/gz-sim/pull/537) 1. Fix to handle multiple logical cameras. - * [Pull Request 539](https://github.com/ignitionrobotics/ign-gazebo/pull/539) + * [Pull Request 539](https://github.com/gazebosim/gz-sim/pull/539) -1. Improve ign tool support on macOS. - * [Pull Request 477](https://github.com/ignitionrobotics/ign-gazebo/pull/477) +1. Improve gz tool support on macOS. + * [Pull Request 477](https://github.com/gazebosim/gz-sim/pull/477) 1. Add support for topic statistics on breadcrumb deployments. - * [Pull Request 532](https://github.com/ignitionrobotics/ign-gazebo/pull/532) + * [Pull Request 532](https://github.com/gazebosim/gz-sim/pull/532) 1. Fix slot in Plotting plugin. - * [Pull Request 490](https://github.com/ignitionrobotics/ign-gazebo/pull/490) + * [Pull Request 490](https://github.com/gazebosim/gz-sim/pull/490) 1. Fix shadow artifacts by disabling double sided rendering. - * [Pull Request 446](https://github.com/ignitionrobotics/ign-gazebo/pull/446) + * [Pull Request 446](https://github.com/gazebosim/gz-sim/pull/446) 1. Kinetic energy monitor plugin. - * [Pull Request 492](https://github.com/ignitionrobotics/ign-gazebo/pull/492) + * [Pull Request 492](https://github.com/gazebosim/gz-sim/pull/492) 1. Change nullptr to a int ptr for qt 5.15.2. - * [Pull Request 527](https://github.com/ignitionrobotics/ign-gazebo/pull/527) + * [Pull Request 527](https://github.com/gazebosim/gz-sim/pull/527) 1. Generate valid topics everywhere (support names with spaces). - * [Pull Request 522](https://github.com/ignitionrobotics/ign-gazebo/pull/522) + * [Pull Request 522](https://github.com/gazebosim/gz-sim/pull/522) 1. All changes up to version 3.7.0. -### Ignition Gazebo 4.1.0 (2020-12-11) +### Gazebo Sim 4.1.0 (2020-12-11) 1. Update Dockerfiles to use focal images - * [pull request 388](https://github.com/ignitionrobotics/ign-gazebo/pull/388) + * [pull request 388](https://github.com/gazebosim/gz-sim/pull/388) -1. Updated source build instructions for ign-gazebo4 - * [pull request 404](https://github.com/ignitionrobotics/ign-gazebo/pull/404) +1. Updated source build instructions for gz-sim4 + * [pull request 404](https://github.com/gazebosim/gz-sim/pull/404) 1. Add tests for the AnimationTime component - * [pull request 433](https://github.com/ignitionrobotics/ign-gazebo/pull/433) + * [pull request 433](https://github.com/gazebosim/gz-sim/pull/433) 1. Fix pose msg conversion when msg is missing orientation - * [pull request 450](https://github.com/ignitionrobotics/ign-gazebo/pull/450) - * [pull request 459](https://github.com/ignitionrobotics/ign-gazebo/pull/459) + * [pull request 450](https://github.com/gazebosim/gz-sim/pull/450) + * [pull request 459](https://github.com/gazebosim/gz-sim/pull/459) 1. Resolved updated codecheck issues - * [pull request 443](https://github.com/ignitionrobotics/ign-gazebo/pull/443) - * [pull request 457](https://github.com/ignitionrobotics/ign-gazebo/pull/457) - * [pull request 459](https://github.com/ignitionrobotics/ign-gazebo/pull/459) + * [pull request 443](https://github.com/gazebosim/gz-sim/pull/443) + * [pull request 457](https://github.com/gazebosim/gz-sim/pull/457) + * [pull request 459](https://github.com/gazebosim/gz-sim/pull/459) 1. Use new backpack version in tests - * [pull request 455](https://github.com/ignitionrobotics/ign-gazebo/pull/455) - * [pull request 457](https://github.com/ignitionrobotics/ign-gazebo/pull/457) - * [pull request 459](https://github.com/ignitionrobotics/ign-gazebo/pull/459) + * [pull request 455](https://github.com/gazebosim/gz-sim/pull/455) + * [pull request 457](https://github.com/gazebosim/gz-sim/pull/457) + * [pull request 459](https://github.com/gazebosim/gz-sim/pull/459) 1. Fix segfault in the Breadcrumb system when associated model is unloaded - * [pull request 454](https://github.com/ignitionrobotics/ign-gazebo/pull/454) - * [pull request 457](https://github.com/ignitionrobotics/ign-gazebo/pull/457) - * [pull request 459](https://github.com/ignitionrobotics/ign-gazebo/pull/459) + * [pull request 454](https://github.com/gazebosim/gz-sim/pull/454) + * [pull request 457](https://github.com/gazebosim/gz-sim/pull/457) + * [pull request 459](https://github.com/gazebosim/gz-sim/pull/459) 1. Added user commands to example thermal camera world - * [pull request 442](https://github.com/ignitionrobotics/ign-gazebo/pull/442) - * [pull request 459](https://github.com/ignitionrobotics/ign-gazebo/pull/459) + * [pull request 442](https://github.com/gazebosim/gz-sim/pull/442) + * [pull request 459](https://github.com/gazebosim/gz-sim/pull/459) 1. Helper function to set component data - * [pull request 436](https://github.com/ignitionrobotics/ign-gazebo/pull/436) - * [pull request 469](https://github.com/ignitionrobotics/ign-gazebo/pull/469) + * [pull request 436](https://github.com/gazebosim/gz-sim/pull/436) + * [pull request 469](https://github.com/gazebosim/gz-sim/pull/469) 1. Remove unneeded if statement - * [pull request 432](https://github.com/ignitionrobotics/ign-gazebo/pull/432) - * [pull request 469](https://github.com/ignitionrobotics/ign-gazebo/pull/469) + * [pull request 432](https://github.com/gazebosim/gz-sim/pull/432) + * [pull request 469](https://github.com/gazebosim/gz-sim/pull/469) 1. Fix flaky RecordAndPlayback test in INTEGRATION_log_system - * [pull request 463](https://github.com/ignitionrobotics/ign-gazebo/pull/463) - * [pull request 469](https://github.com/ignitionrobotics/ign-gazebo/pull/469) + * [pull request 463](https://github.com/gazebosim/gz-sim/pull/463) + * [pull request 469](https://github.com/gazebosim/gz-sim/pull/469) 1. Make PeerTracker test more robust - * [pull request 452](https://github.com/ignitionrobotics/ign-gazebo/pull/452) - * [pull request 469](https://github.com/ignitionrobotics/ign-gazebo/pull/469) + * [pull request 452](https://github.com/gazebosim/gz-sim/pull/452) + * [pull request 469](https://github.com/gazebosim/gz-sim/pull/469) 1. Use a [std::promise](https://en.cppreference.com/w/cpp/thread/promise)/[std::future](https://en.cppreference.com/w/cpp/thread/future) mechanism to avoid waiting in a looop until all `stepAck` messages are received - * [pull request 470](https://github.com/ignitionrobotics/ign-gazebo/pull/470) + * [pull request 470](https://github.com/gazebosim/gz-sim/pull/470) 1. Optical Tactile Sensor Plugin - * [pull request 229](https://github.com/ignitionrobotics/ign-gazebo/pull/229) + * [pull request 229](https://github.com/gazebosim/gz-sim/pull/229) 1. All changes up to and including those in version 3.5.0 and version 2.25.0 -### Ignition Gazebo 4.0.0 (2020-09-30) +### Gazebo Sim 4.0.0 (2020-09-30) 1. Names with spaces: add string serializer - * [pull request 244](https://github.com/ignitionrobotics/ign-gazebo/pull/244) + * [pull request 244](https://github.com/gazebosim/gz-sim/pull/244) 1. Filter mesh collision based on `collide_bitmask` property - * [pull request 160](https://github.com/ignitionrobotics/ign-gazebo/pull/160) + * [pull request 160](https://github.com/gazebosim/gz-sim/pull/160) 1. Add force focus when mouse enters render window - * [pull request 97](https://github.com/ignitionrobotics/ign-gazebo/pull/97) + * [pull request 97](https://github.com/gazebosim/gz-sim/pull/97) 1. Fixed docblock showGrid - * [pull request 152](https://github.com/ignitionrobotics/ign-gazebo/pull/152) + * [pull request 152](https://github.com/gazebosim/gz-sim/pull/152) 1. More actor components and follow plugin - * [pull request 157](https://github.com/ignitionrobotics/ign-gazebo/pull/157) + * [pull request 157](https://github.com/gazebosim/gz-sim/pull/157) 1. Filter the record menu and write the format to the file according to which button the user pushed (mp4 or ogv) - * [pull request 153](https://github.com/ignitionrobotics/ign-gazebo/pull/153) + * [pull request 153](https://github.com/gazebosim/gz-sim/pull/153) 1. Fix scene manager losing header file - * [pull request 211](https://github.com/ignitionrobotics/ign-gazebo/pull/211) + * [pull request 211](https://github.com/gazebosim/gz-sim/pull/211) 1. Fixed left menu events - * [pull request 218](https://github.com/ignitionrobotics/ign-gazebo/pull/218) + * [pull request 218](https://github.com/gazebosim/gz-sim/pull/218) 1. Fix yaw units typo in Component Inspector plugin - * [pull request 238](https://github.com/ignitionrobotics/ign-gazebo/pull/238) + * [pull request 238](https://github.com/gazebosim/gz-sim/pull/238) 1. Enable alpha based transparency on PBR materials by default - * [pull request 249](https://github.com/ignitionrobotics/ign-gazebo/pull/249) + * [pull request 249](https://github.com/gazebosim/gz-sim/pull/249) 1. Qt auto scale factor for HiDPI displays - * [pull request 291](https://github.com/ignitionrobotics/ign-gazebo/pull/291) + * [pull request 291](https://github.com/gazebosim/gz-sim/pull/291) 1. Sync components removal - * [pull request 272](https://github.com/ignitionrobotics/ign-gazebo/pull/272) + * [pull request 272](https://github.com/gazebosim/gz-sim/pull/272) 1. Add error handling for JointAxis::SetXyz and remove use of use_parent_model_frame - * [pull request 288](https://github.com/ignitionrobotics/ign-gazebo/pull/288) + * [pull request 288](https://github.com/gazebosim/gz-sim/pull/288) 1. Make some tests more robust - * [pull request 314](https://github.com/ignitionrobotics/ign-gazebo/pull/314) + * [pull request 314](https://github.com/gazebosim/gz-sim/pull/314) 1. Fix Qt5 warnings for using anchors - * [pull request 363](https://github.com/ignitionrobotics/ign-gazebo/pull/363) + * [pull request 363](https://github.com/gazebosim/gz-sim/pull/363) 1. Plotting Components Plugin - * [pull request 270](https://github.com/ignitionrobotics/ign-gazebo/pull/270) + * [pull request 270](https://github.com/gazebosim/gz-sim/pull/270) 1. Visualize Lidar Plugin - * [pull request 301](https://github.com/ignitionrobotics/ign-gazebo/pull/301) - * [pull request 391](https://github.com/ignitionrobotics/ign-gazebo/pull/391) + * [pull request 301](https://github.com/gazebosim/gz-sim/pull/301) + * [pull request 391](https://github.com/gazebosim/gz-sim/pull/391) 1. Replaced common::Time for std::chrono - * [pull request 309](https://github.com/ignitionrobotics/ign-gazebo/pull/309) + * [pull request 309](https://github.com/gazebosim/gz-sim/pull/309) 1. Tutorial, examples and documentation updates - * [pull request 380](https://github.com/ignitionrobotics/ign-gazebo/pull/380) - * [pull request 386](https://github.com/ignitionrobotics/ign-gazebo/pull/386) - * [pull request 387](https://github.com/ignitionrobotics/ign-gazebo/pull/387) - * [pull request 390](https://github.com/ignitionrobotics/ign-gazebo/pull/390) + * [pull request 380](https://github.com/gazebosim/gz-sim/pull/380) + * [pull request 386](https://github.com/gazebosim/gz-sim/pull/386) + * [pull request 387](https://github.com/gazebosim/gz-sim/pull/387) + * [pull request 390](https://github.com/gazebosim/gz-sim/pull/390) 1. Migration from BitBucket to GitHub - * [pull request 73](https://github.com/ignitionrobotics/ign-gazebo/pull/73) - * [pull request 68](https://github.com/ignitionrobotics/ign-gazebo/pull/68) - * [pull request 67](https://github.com/ignitionrobotics/ign-gazebo/pull/67) - * [pull request 130](https://github.com/ignitionrobotics/ign-gazebo/pull/130) + * [pull request 73](https://github.com/gazebosim/gz-sim/pull/73) + * [pull request 68](https://github.com/gazebosim/gz-sim/pull/68) + * [pull request 67](https://github.com/gazebosim/gz-sim/pull/67) + * [pull request 130](https://github.com/gazebosim/gz-sim/pull/130) 1. Use interpolate\_x sdf parameter for actor animations * [BitBucket pull request 536](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/536) @@ -2611,18 +2611,20 @@ 1. Support and * [BitBucket pull request 542](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/542) -1. Depend on ign-rendering4, ign-gui4, ign-sensors4 +1. Depend on gz-rendering4, gz-gui4, gz-sensors4 * [BitBucket pull request 540](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/540) 1. Axis-Aligned Bounding Boxes * [BitBucket pull request 565](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/565) 1. Add window focus upon mouse entering the render window - * [Github pull request 97](https://github.com/ignitionrobotics/ign-gazebo/pull/97) + * [Github pull request 97](https://github.com/gazebosim/gz-sim/pull/97) + +## Gazebo Sim 3.x -## Ignition Gazebo 3.x +### Gazebo Sim 3.X.X (20XX-XX-XX) -### Ignition Gazebo 3.13.0 (2022-06-01) +### Gazebo Sim 3.13.0 (2022-06-01) 1. Extruded 2D polyline geometries * [Pull request #1456](https://github.com/gazebosim/gz-sim/pull/1456) @@ -2679,609 +2681,609 @@ 1. Make tests run as fast as possible * [Pull request #1194](https://github.com/gazebosim/gz-sim/pull/1194) -### Ignition Gazebo 3.12.0 (2021-11-11) +### Gazebo Sim 3.12.0 (2021-11-11) 1. Prevent creation of spurious `` elements when saving worlds - * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + * [Pull request #1192](https://github.com/gazebosim/gz-sim/pull/1192) 1. Added support for tracked vehicles - * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + * [Pull request #869](https://github.com/gazebosim/gz-sim/pull/869) 1. Add components to dynamically set joint limits - * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + * [Pull request #847](https://github.com/gazebosim/gz-sim/pull/847) 1. Fix updating a component's data via SerializedState msg - * [Pull request #1149](https://github.com/ignitionrobotics/ign-gazebo/pull/1149) + * [Pull request #1149](https://github.com/gazebosim/gz-sim/pull/1149) 1. Sensor systems work if loaded after sensors - * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + * [Pull request #1104](https://github.com/gazebosim/gz-sim/pull/1104) 1. Fix generation of systems library symlinks in build directory - * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + * [Pull request #1160](https://github.com/gazebosim/gz-sim/pull/1160) -1. Backport gazebo::Util::validTopic() from ign-gazebo4. - * [Pull request #1153](https://github.com/ignitionrobotics/ign-gazebo/pull/1153) +1. Backport sim::Util::validTopic() from gz-sim4. + * [Pull request #1153](https://github.com/gazebosim/gz-sim/pull/1153) 1. Support setting the background color for sensors - * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + * [Pull request #1147](https://github.com/gazebosim/gz-sim/pull/1147) 1. Use uint64_t for ComponentInspector Entity IDs - * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + * [Pull request #1144](https://github.com/gazebosim/gz-sim/pull/1144) 1. Fix integers and floats on component inspector - * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + * [Pull request #1143](https://github.com/gazebosim/gz-sim/pull/1143) -### Ignition Gazebo 3.11.0 (2021-10-21) +### Gazebo Sim 3.11.0 (2021-10-21) 1. Updates to camera video record from subt. - * [Pull request #1117](https://github.com/ignitionrobotics/ign-gazebo/pull/1117) + * [Pull request #1117](https://github.com/gazebosim/gz-sim/pull/1117) 1. Fix performance level test flakiness. - * [Pull request #1129](https://github.com/ignitionrobotics/ign-gazebo/pull/1129) + * [Pull request #1129](https://github.com/gazebosim/gz-sim/pull/1129) -### Ignition Gazebo 3.10.0 (2021-10-15) +### Gazebo Sim 3.10.0 (2021-10-15) 1. Performance: use std::unordered_map where possible in SceneManager - * [Pull request #1083](https://github.com/ignitionrobotics/ign-gazebo/pull/1083) + * [Pull request #1083](https://github.com/gazebosim/gz-sim/pull/1083) 1. Enable new CMake policy to fix protobuf compilation - * [Pull request #1059](https://github.com/ignitionrobotics/ign-gazebo/pull/1059) + * [Pull request #1059](https://github.com/gazebosim/gz-sim/pull/1059) 1. Fix setting cast_shadows for visuals without material - * [Pull request #1015](https://github.com/ignitionrobotics/ign-gazebo/pull/1015) + * [Pull request #1015](https://github.com/gazebosim/gz-sim/pull/1015) 1. Remove duplicate XML tag in pendulum_links example world - * [Pull request #1002](https://github.com/ignitionrobotics/ign-gazebo/pull/1002) + * [Pull request #1002](https://github.com/gazebosim/gz-sim/pull/1002) 1. Enable sensor metrics on example worlds - * [Pull request #982](https://github.com/ignitionrobotics/ign-gazebo/pull/982) + * [Pull request #982](https://github.com/gazebosim/gz-sim/pull/982) 1. Improved doxygen - * [Pull request #996](https://github.com/ignitionrobotics/ign-gazebo/pull/996) + * [Pull request #996](https://github.com/gazebosim/gz-sim/pull/996) 1. JointPositionController: Improve misleading error message - * [Pull request #1098](https://github.com/ignitionrobotics/ign-gazebo/pull/1098) + * [Pull request #1098](https://github.com/gazebosim/gz-sim/pull/1098) 1. Adjust pose decimals based on element width - * [Pull request #1089](https://github.com/ignitionrobotics/ign-gazebo/pull/1089) + * [Pull request #1089](https://github.com/gazebosim/gz-sim/pull/1089) 1. Fixed IMU system plugin - * [Pull request #1043](https://github.com/ignitionrobotics/ign-gazebo/pull/1043) + * [Pull request #1043](https://github.com/gazebosim/gz-sim/pull/1043) 1. Use QTimer to update plugins in the Qt thread - * [Pull request #1095](https://github.com/ignitionrobotics/ign-gazebo/pull/1095) + * [Pull request #1095](https://github.com/gazebosim/gz-sim/pull/1095) -### Ignition Gazebo 3.9.0 (2021-08-16) +### Gazebo Sim 3.9.0 (2021-08-16) 1. Entity tree: prevent creation of repeated entity items - * [Pull request #974](https://github.com/ignitionrobotics/ign-gazebo/pull/974) + * [Pull request #974](https://github.com/gazebosim/gz-sim/pull/974) 1. Don't use $HOME on most tests (InternalFixture) - * [Pull request #971](https://github.com/ignitionrobotics/ign-gazebo/pull/971) + * [Pull request #971](https://github.com/gazebosim/gz-sim/pull/971) 1. Be more specific when looking for physics plugins - * [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965) + * [Pull request #965](https://github.com/gazebosim/gz-sim/pull/965) 1. Drag and drop meshes into scene - * [Pull request #939](https://github.com/ignitionrobotics/ign-gazebo/pull/939) + * [Pull request #939](https://github.com/gazebosim/gz-sim/pull/939) 1. Set protobuf_MODULE_COMPATIBLE before any find_package call - * [Pull request #957](https://github.com/ignitionrobotics/ign-gazebo/pull/957) + * [Pull request #957](https://github.com/gazebosim/gz-sim/pull/957) 1. [DiffDrive] add enable/disable - * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + * [Pull request #772](https://github.com/gazebosim/gz-sim/pull/772) 1. Fix component inspector shutdown crash - * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + * [Pull request #724](https://github.com/gazebosim/gz-sim/pull/724) 1. Add UserCommands Plugin. - * [Pull request #719](https://github.com/ignitionrobotics/ign-gazebo/pull/719) + * [Pull request #719](https://github.com/gazebosim/gz-sim/pull/719) 1. Setting the intiial velocity for a model or joint - * [Pull request #693](https://github.com/ignitionrobotics/ign-gazebo/pull/693) + * [Pull request #693](https://github.com/gazebosim/gz-sim/pull/693) 1. Examples and tutorial on using rendering API from plugins - * [Pull request #596](https://github.com/ignitionrobotics/ign-gazebo/pull/596) + * [Pull request #596](https://github.com/gazebosim/gz-sim/pull/596) -1. Add missing IGNITION_GAZEBO_VISIBLE macros - * [Pull request #563](https://github.com/ignitionrobotics/ign-gazebo/pull/563) +1. Add missing GZ_SIM_VISIBLE macros + * [Pull request #563](https://github.com/gazebosim/gz-sim/pull/563) 1. Fix visibility macro names when used by a different component (Windows) - * [Pull request #564](https://github.com/ignitionrobotics/ign-gazebo/pull/564) + * [Pull request #564](https://github.com/gazebosim/gz-sim/pull/564) 1. No install apt recommends and clear cache - * [Pull request #423](https://github.com/ignitionrobotics/ign-gazebo/pull/423) + * [Pull request #423](https://github.com/gazebosim/gz-sim/pull/423) 1. Add 25percent darker view angle icons - * [Pull request #426](https://github.com/ignitionrobotics/ign-gazebo/pull/426) + * [Pull request #426](https://github.com/gazebosim/gz-sim/pull/426) 1. Expose a test fixture helper class - * [Pull request #926](https://github.com/ignitionrobotics/ign-gazebo/pull/926) + * [Pull request #926](https://github.com/gazebosim/gz-sim/pull/926) 1. Fix logic to disable server default plugins loading - * [Pull request #953](https://github.com/ignitionrobotics/ign-gazebo/pull/953) + * [Pull request #953](https://github.com/gazebosim/gz-sim/pull/953) 1. removed unneeded plugin update - * [Pull request #944](https://github.com/ignitionrobotics/ign-gazebo/pull/944) + * [Pull request #944](https://github.com/gazebosim/gz-sim/pull/944) 1. Functions to enable velocity and acceleration checks on Link - * [Pull request #935](https://github.com/ignitionrobotics/ign-gazebo/pull/935) + * [Pull request #935](https://github.com/gazebosim/gz-sim/pull/935) 1. Support adding systems that don't come from a plugin - * [Pull request #936](https://github.com/ignitionrobotics/ign-gazebo/pull/936) + * [Pull request #936](https://github.com/gazebosim/gz-sim/pull/936) 1. 3D plot GUI plugin - * [Pull request #917](https://github.com/ignitionrobotics/ign-gazebo/pull/917) + * [Pull request #917](https://github.com/gazebosim/gz-sim/pull/917) 1. Add a convenience function for getting possibly non-existing components. - * [Pull request #629](https://github.com/ignitionrobotics/ign-gazebo/pull/629) + * [Pull request #629](https://github.com/gazebosim/gz-sim/pull/629) 1. Fix topLevelModel method - * [Pull request #600](https://github.com/ignitionrobotics/ign-gazebo/pull/600) + * [Pull request #600](https://github.com/gazebosim/gz-sim/pull/600) 1. World exporter - * [Pull request #474](https://github.com/ignitionrobotics/ign-gazebo/pull/474) + * [Pull request #474](https://github.com/gazebosim/gz-sim/pull/474) 1. Fix finding PBR materials - * [Pull request #575](https://github.com/ignitionrobotics/ign-gazebo/pull/575) + * [Pull request #575](https://github.com/gazebosim/gz-sim/pull/575) 1. Handle multiple logical cameras - * [Pull request #539](https://github.com/ignitionrobotics/ign-gazebo/pull/539) + * [Pull request #539](https://github.com/gazebosim/gz-sim/pull/539) 1. Make some tests more robust - * [Pull request #314](https://github.com/ignitionrobotics/ign-gazebo/pull/314) + * [Pull request #314](https://github.com/gazebosim/gz-sim/pull/314) 1. Fix codecheck - * [Pull request #887](https://github.com/ignitionrobotics/ign-gazebo/pull/887) + * [Pull request #887](https://github.com/gazebosim/gz-sim/pull/887) 1. Hello world plugin added - * [Pull request #699](https://github.com/ignitionrobotics/ign-gazebo/pull/699) + * [Pull request #699](https://github.com/gazebosim/gz-sim/pull/699) -1. Model info CLI `ign model` - * [Pull request #893](https://github.com/ignitionrobotics/ign-gazebo/pull/893) +1. Model info CLI `gz model` + * [Pull request #893](https://github.com/gazebosim/gz-sim/pull/893) 1. Don't create components for entities that don't exist - * [Pull request #927](https://github.com/ignitionrobotics/ign-gazebo/pull/927) + * [Pull request #927](https://github.com/gazebosim/gz-sim/pull/927) 1. Adds Mesh Tutorial - * [Pull request #915](https://github.com/ignitionrobotics/ign-gazebo/pull/915) + * [Pull request #915](https://github.com/gazebosim/gz-sim/pull/915) 1. Fix updating GUI plugin on load - * [Pull request #904](https://github.com/ignitionrobotics/ign-gazebo/pull/904) + * [Pull request #904](https://github.com/gazebosim/gz-sim/pull/904) 1. Fix documentation for the Sensor component - * [Pull request #898](https://github.com/ignitionrobotics/ign-gazebo/pull/898) + * [Pull request #898](https://github.com/gazebosim/gz-sim/pull/898) 1. Use UINT64_MAX for kComponentTpyeIDInvalid instead of relying on underflow - * [Pull request #889](https://github.com/ignitionrobotics/ign-gazebo/pull/889) + * [Pull request #889](https://github.com/gazebosim/gz-sim/pull/889) 1. Fix mouse view control target position - * [Pull request #879](https://github.com/ignitionrobotics/ign-gazebo/pull/879) + * [Pull request #879](https://github.com/gazebosim/gz-sim/pull/879) 1. Set GUI camera pose - * [Pull request #863](https://github.com/ignitionrobotics/ign-gazebo/pull/863) + * [Pull request #863](https://github.com/gazebosim/gz-sim/pull/863) 1. Enables confirmation dialog when closing Gazebo. - * [Pull request #850](https://github.com/ignitionrobotics/ign-gazebo/pull/850) + * [Pull request #850](https://github.com/gazebosim/gz-sim/pull/850) -1. Depend on ign-rendering 3.5 - * [Pull request #867](https://github.com/ignitionrobotics/ign-gazebo/pull/867) +1. Depend on gz-rendering 3.5 + * [Pull request #867](https://github.com/gazebosim/gz-sim/pull/867) 1. Using math::SpeedLimiter on the diff_drive controller. - * [Pull request #833](https://github.com/ignitionrobotics/ign-gazebo/pull/833) + * [Pull request #833](https://github.com/gazebosim/gz-sim/pull/833) 1. New example: get an ECM snapshot from an external program - * [Pull request #859](https://github.com/ignitionrobotics/ign-gazebo/pull/859) + * [Pull request #859](https://github.com/gazebosim/gz-sim/pull/859) 1. Fix WindEffects Plugin bug, not configuring new links - * [Pull request #844](https://github.com/ignitionrobotics/ign-gazebo/pull/844) + * [Pull request #844](https://github.com/gazebosim/gz-sim/pull/844) 1. Fix potentially flaky integration component test case - * [Pull request #848](https://github.com/ignitionrobotics/ign-gazebo/pull/848) + * [Pull request #848](https://github.com/gazebosim/gz-sim/pull/848) 1. Cleanup and alphabetize plugin headers - * [Pull request #838](https://github.com/ignitionrobotics/ign-gazebo/pull/838) + * [Pull request #838](https://github.com/gazebosim/gz-sim/pull/838) 1. Removed duplicated code with rendering::sceneFromFirstRenderEngine - * [Pull request #819](https://github.com/ignitionrobotics/ign-gazebo/pull/819) + * [Pull request #819](https://github.com/gazebosim/gz-sim/pull/819) 1. Remove unused headers in video_recoder plugin - * [Pull request #834](https://github.com/ignitionrobotics/ign-gazebo/pull/834) + * [Pull request #834](https://github.com/gazebosim/gz-sim/pull/834) -1. Use moveToHelper from ign-rendering - * [Pull request #825](https://github.com/ignitionrobotics/ign-gazebo/pull/825) +1. Use moveToHelper from gz-rendering + * [Pull request #825](https://github.com/gazebosim/gz-sim/pull/825) 1. Remove tools/code_check and update codecov - * [Pull request #814](https://github.com/ignitionrobotics/ign-gazebo/pull/814) + * [Pull request #814](https://github.com/gazebosim/gz-sim/pull/814) 1. Add service and GUI to configure physics parameters - * [Pull request #536](https://github.com/ignitionrobotics/ign-gazebo/pull/536) - * [Pull request #812](https://github.com/ignitionrobotics/ign-gazebo/pull/812) + * [Pull request #536](https://github.com/gazebosim/gz-sim/pull/536) + * [Pull request #812](https://github.com/gazebosim/gz-sim/pull/812) 1. Fix documentation for EntityComponentManager::EachNew - * [Pull request #795](https://github.com/ignitionrobotics/ign-gazebo/pull/795) + * [Pull request #795](https://github.com/gazebosim/gz-sim/pull/795) 1. Fix macOS build: components::Name in benchmark - * [Pull request #784](https://github.com/ignitionrobotics/ign-gazebo/pull/784) + * [Pull request #784](https://github.com/gazebosim/gz-sim/pull/784) 1. Don't store duplicate ComponentTypeId in ECM - * [Pull request #751](https://github.com/ignitionrobotics/ign-gazebo/pull/751) + * [Pull request #751](https://github.com/gazebosim/gz-sim/pull/751) 1. [TPE] Support setting individual link velocity - * [Pull request #427](https://github.com/ignitionrobotics/ign-gazebo/pull/427) + * [Pull request #427](https://github.com/gazebosim/gz-sim/pull/427) 1. 👩‍🌾 Enable Focal CI - * [Pull request #646](https://github.com/ignitionrobotics/ign-gazebo/pull/646) + * [Pull request #646](https://github.com/gazebosim/gz-sim/pull/646) 1. Update benchmark comparison instructions - * [Pull request #766](https://github.com/ignitionrobotics/ign-gazebo/pull/766) + * [Pull request #766](https://github.com/gazebosim/gz-sim/pull/766) 1. Use Protobuf_IMPORT_DIRS instead of PROTOBUF_IMPORT_DIRS for compatibility with Protobuf CMake config - * [Pull request #715](https://github.com/ignitionrobotics/ign-gazebo/pull/715) + * [Pull request #715](https://github.com/gazebosim/gz-sim/pull/715) 1. Do not pass -Wno-unused-parameter to MSVC compiler - * [Pull request #716](https://github.com/ignitionrobotics/ign-gazebo/pull/716) + * [Pull request #716](https://github.com/gazebosim/gz-sim/pull/716) 1. Scenebroadcaster sensors - * [Pull request #698](https://github.com/ignitionrobotics/ign-gazebo/pull/698) + * [Pull request #698](https://github.com/gazebosim/gz-sim/pull/698) 1. Make it so joint state publisher is quieter - * [Pull request #696](https://github.com/ignitionrobotics/ign-gazebo/pull/696) + * [Pull request #696](https://github.com/gazebosim/gz-sim/pull/696) -### Ignition Gazebo 3.8.0 (2021-03-17) +### Gazebo Sim 3.8.0 (2021-03-17) 1. Add joint position controller GUI, also enable tests for GUI plugins - * [Pull request #534](https://github.com/ignitionrobotics/ign-gazebo/pull/534) + * [Pull request #534](https://github.com/gazebosim/gz-sim/pull/534) 1. Remove visibility from headers that are not installed - * [Pull request #665](https://github.com/ignitionrobotics/ign-gazebo/pull/665) + * [Pull request #665](https://github.com/gazebosim/gz-sim/pull/665) 1. Added screenshot to toolbar - * [Pull request #588](https://github.com/ignitionrobotics/ign-gazebo/pull/588) + * [Pull request #588](https://github.com/gazebosim/gz-sim/pull/588) -1. Improve ign tool support on macOS - * [Pull request #477](https://github.com/ignitionrobotics/ign-gazebo/pull/477) +1. Improve gz tool support on macOS + * [Pull request #477](https://github.com/gazebosim/gz-sim/pull/477) 1. change nullptr to a int ptr for qt 5.15.2 bug - * [Pull request #527](https://github.com/ignitionrobotics/ign-gazebo/pull/527) + * [Pull request #527](https://github.com/gazebosim/gz-sim/pull/527) 1. Kinetic energy monitor plugin - * [Pull request #492](https://github.com/ignitionrobotics/ign-gazebo/pull/492) + * [Pull request #492](https://github.com/gazebosim/gz-sim/pull/492) 1. Use a std::promise/std::future to avoid busy waiting the step ack messages in NetworkManagerPrimary - * [Pull request #470](https://github.com/ignitionrobotics/ign-gazebo/pull/470) + * [Pull request #470](https://github.com/gazebosim/gz-sim/pull/470) 1. clarified performer example - * [Pull request #390](https://github.com/ignitionrobotics/ign-gazebo/pull/390) + * [Pull request #390](https://github.com/gazebosim/gz-sim/pull/390) 1. Add tutorial tweaks - * [Pull request #380](https://github.com/ignitionrobotics/ign-gazebo/pull/380) + * [Pull request #380](https://github.com/gazebosim/gz-sim/pull/380) 1. Fix Qt5 warnings for using anchors - * [Pull request #363](https://github.com/ignitionrobotics/ign-gazebo/pull/363) + * [Pull request #363](https://github.com/gazebosim/gz-sim/pull/363) 1. Update codeowners - * [Pull request #305](https://github.com/ignitionrobotics/ign-gazebo/pull/305) + * [Pull request #305](https://github.com/gazebosim/gz-sim/pull/305) 1. Qt auto scale factor for HiDPI displays - * [Pull request #291](https://github.com/ignitionrobotics/ign-gazebo/pull/291) + * [Pull request #291](https://github.com/gazebosim/gz-sim/pull/291) 1. Fix yaw units - * [Pull request #238](https://github.com/ignitionrobotics/ign-gazebo/pull/238) + * [Pull request #238](https://github.com/gazebosim/gz-sim/pull/238) 1. Fixed docblock showGrid - * [Pull request #152](https://github.com/ignitionrobotics/ign-gazebo/pull/152) + * [Pull request #152](https://github.com/gazebosim/gz-sim/pull/152) 1. Fix entity tree for large worlds - * [Pull request #673](https://github.com/ignitionrobotics/ign-gazebo/pull/673) + * [Pull request #673](https://github.com/gazebosim/gz-sim/pull/673) 1. Master branch updates - * [Pull request #672](https://github.com/ignitionrobotics/ign-gazebo/pull/672) + * [Pull request #672](https://github.com/gazebosim/gz-sim/pull/672) 1. Backport #561: Use common::setenv - * [Pull request #666](https://github.com/ignitionrobotics/ign-gazebo/pull/666) + * [Pull request #666](https://github.com/gazebosim/gz-sim/pull/666) 1. Use a custom data structure to manage entity feature maps - * [Pull request #586](https://github.com/ignitionrobotics/ign-gazebo/pull/586) + * [Pull request #586](https://github.com/gazebosim/gz-sim/pull/586) 1. Limit scene broadcast publications when paused - * [Pull request #497](https://github.com/ignitionrobotics/ign-gazebo/pull/497) + * [Pull request #497](https://github.com/gazebosim/gz-sim/pull/497) 1. Fix flaky SceneBoradcaster test - * [Pull request #641](https://github.com/ignitionrobotics/ign-gazebo/pull/641) + * [Pull request #641](https://github.com/gazebosim/gz-sim/pull/641) 1. Add TF/Pose_V publisher in DiffDrive - * [Pull request #548](https://github.com/ignitionrobotics/ign-gazebo/pull/548) + * [Pull request #548](https://github.com/gazebosim/gz-sim/pull/548) 1. 👩‍🌾 Relax performance test - * [Pull request #640](https://github.com/ignitionrobotics/ign-gazebo/pull/640) + * [Pull request #640](https://github.com/gazebosim/gz-sim/pull/640) 1. 👩‍🌾 Improve velocity control test - * [Pull request #642](https://github.com/ignitionrobotics/ign-gazebo/pull/642) + * [Pull request #642](https://github.com/gazebosim/gz-sim/pull/642) 1. Add `laser_retro` support - * [Pull request #603](https://github.com/ignitionrobotics/ign-gazebo/pull/603) + * [Pull request #603](https://github.com/gazebosim/gz-sim/pull/603) 1. Fix pose of plane visual with non-default normal vector - * [Pull request #574](https://github.com/ignitionrobotics/ign-gazebo/pull/574) + * [Pull request #574](https://github.com/gazebosim/gz-sim/pull/574) 1. Add About dialog - * [Pull request #609](https://github.com/ignitionrobotics/ign-gazebo/pull/609) + * [Pull request #609](https://github.com/gazebosim/gz-sim/pull/609) 1. Make topics configurable for joint controllers - * [Pull request #584](https://github.com/ignitionrobotics/ign-gazebo/pull/584) + * [Pull request #584](https://github.com/gazebosim/gz-sim/pull/584) -1. Also use Ignition GUI render event - * [Pull request #598](https://github.com/ignitionrobotics/ign-gazebo/pull/598) +1. Also use Gazebo GUI render event + * [Pull request #598](https://github.com/gazebosim/gz-sim/pull/598) 1. Tutorial on migrating SDF files from Gazebo classic - * [Pull request #400](https://github.com/ignitionrobotics/ign-gazebo/pull/400) + * [Pull request #400](https://github.com/gazebosim/gz-sim/pull/400) 1. Visualize collisions - * [Pull request #531](https://github.com/ignitionrobotics/ign-gazebo/pull/531) + * [Pull request #531](https://github.com/gazebosim/gz-sim/pull/531) 1. Backport state update changes from pull request #486 - * [Pull request #583](https://github.com/ignitionrobotics/ign-gazebo/pull/583) + * [Pull request #583](https://github.com/gazebosim/gz-sim/pull/583) 1. Publish all periodic change components in Scene Broadcaster - * [Pull request #544](https://github.com/ignitionrobotics/ign-gazebo/pull/544) + * [Pull request #544](https://github.com/gazebosim/gz-sim/pull/544) 1. added size to `ground_plane` in examples - * [Pull request #573](https://github.com/ignitionrobotics/ign-gazebo/pull/573) + * [Pull request #573](https://github.com/gazebosim/gz-sim/pull/573) 1. Parallelize State call in ECM - * [Pull request #451](https://github.com/ignitionrobotics/ign-gazebo/pull/451) + * [Pull request #451](https://github.com/gazebosim/gz-sim/pull/451) 1. Non-blocking paths request - * [Pull request #555](https://github.com/ignitionrobotics/ign-gazebo/pull/555) + * [Pull request #555](https://github.com/gazebosim/gz-sim/pull/555) -### Ignition Gazebo 3.7.0 (2021-01-13) +### Gazebo Sim 3.7.0 (2021-01-13) 1. Fix examples in migration plugins tutorial. - * [Pull Request 543](https://github.com/ignitionrobotics/ign-gazebo/pull/543) + * [Pull Request 543](https://github.com/gazebosim/gz-sim/pull/543) 1. Added missing namespace in `detail/EntityComponentManager.hh`. - * [Pull Request 541](https://github.com/ignitionrobotics/ign-gazebo/pull/541) + * [Pull Request 541](https://github.com/gazebosim/gz-sim/pull/541) 1. Automatically load a subset of world plugins. - * [Pull Request 281](https://github.com/ignitionrobotics/ign-gazebo/pull/281) + * [Pull Request 281](https://github.com/gazebosim/gz-sim/pull/281) 1. Update gtest to 1.10.0 for Windows compilation. - * [Pull Request 506](https://github.com/ignitionrobotics/ign-gazebo/pull/506) + * [Pull Request 506](https://github.com/gazebosim/gz-sim/pull/506) 1. Updates to ardupilot migration tutorial. - * [Pull Request 525](https://github.com/ignitionrobotics/ign-gazebo/pull/525) + * [Pull Request 525](https://github.com/gazebosim/gz-sim/pull/525) 1. Don't make docs on macOS. - * [Pull Request 528](https://github.com/ignitionrobotics/ign-gazebo/pull/528) + * [Pull Request 528](https://github.com/gazebosim/gz-sim/pull/528) -### Ignition Gazebo 3.6.0 (2020-12-30) +### Gazebo Sim 3.6.0 (2020-12-30) 1. Fix pose msg conversion when msg is missing orientation - * [Pull Request 450](https://github.com/ignitionrobotics/ign-gazebo/pull/450) + * [Pull Request 450](https://github.com/gazebosim/gz-sim/pull/450) 1. Address code checker warnings - * [Pull Request 443](https://github.com/ignitionrobotics/ign-gazebo/pull/443) - * [Pull Request 491](https://github.com/ignitionrobotics/ign-gazebo/pull/491) - * [Pull Request 499](https://github.com/ignitionrobotics/ign-gazebo/pull/499) - * [Pull Request 502](https://github.com/ignitionrobotics/ign-gazebo/pull/502) + * [Pull Request 443](https://github.com/gazebosim/gz-sim/pull/443) + * [Pull Request 491](https://github.com/gazebosim/gz-sim/pull/491) + * [Pull Request 499](https://github.com/gazebosim/gz-sim/pull/499) + * [Pull Request 502](https://github.com/gazebosim/gz-sim/pull/502) 1. Test fixes - * [Pull Request 455](https://github.com/ignitionrobotics/ign-gazebo/pull/455) - * [Pull Request 463](https://github.com/ignitionrobotics/ign-gazebo/pull/463) - * [Pull Request 452](https://github.com/ignitionrobotics/ign-gazebo/pull/452) - * [Pull Request 480](https://github.com/ignitionrobotics/ign-gazebo/pull/480) + * [Pull Request 455](https://github.com/gazebosim/gz-sim/pull/455) + * [Pull Request 463](https://github.com/gazebosim/gz-sim/pull/463) + * [Pull Request 452](https://github.com/gazebosim/gz-sim/pull/452) + * [Pull Request 480](https://github.com/gazebosim/gz-sim/pull/480) 1. Documentation updates - * [Pull Request 472](https://github.com/ignitionrobotics/ign-gazebo/pull/472) + * [Pull Request 472](https://github.com/gazebosim/gz-sim/pull/472) 1. Fix segfault in the Breadcrumb system when associated model is unloaded - * [Pull Request 454](https://github.com/ignitionrobotics/ign-gazebo/pull/454) + * [Pull Request 454](https://github.com/gazebosim/gz-sim/pull/454) 1. Added user commands to example thermal camera world - * [Pull Request 442](https://github.com/ignitionrobotics/ign-gazebo/pull/442) + * [Pull Request 442](https://github.com/gazebosim/gz-sim/pull/442) 1. Helper function to set component data - * [Pull Request 436](https://github.com/ignitionrobotics/ign-gazebo/pull/436) + * [Pull Request 436](https://github.com/gazebosim/gz-sim/pull/436) 1. Remove unneeded if statement in EntityComponentManager - * [Pull Request 432](https://github.com/ignitionrobotics/ign-gazebo/pull/432) + * [Pull Request 432](https://github.com/gazebosim/gz-sim/pull/432) 1. Clarify how time is represented in each phase of a System step - * [Pull Request 467](https://github.com/ignitionrobotics/ign-gazebo/pull/467) + * [Pull Request 467](https://github.com/gazebosim/gz-sim/pull/467) 1. Switch to async state service request - * [Pull Request 461](https://github.com/ignitionrobotics/ign-gazebo/pull/461) + * [Pull Request 461](https://github.com/gazebosim/gz-sim/pull/461) 1. Update key event handling - * [Pull Request 466](https://github.com/ignitionrobotics/ign-gazebo/pull/466) + * [Pull Request 466](https://github.com/gazebosim/gz-sim/pull/466) 1. Tape Measure Plugin - * [Pull Request 456](https://github.com/ignitionrobotics/ign-gazebo/pull/456) + * [Pull Request 456](https://github.com/gazebosim/gz-sim/pull/456) 1. Move deselect and preview termination to render thread - * [Pull Request 493](https://github.com/ignitionrobotics/ign-gazebo/pull/493) + * [Pull Request 493](https://github.com/gazebosim/gz-sim/pull/493) 1. Logical audio sensor plugin - * [Pull Request 401](https://github.com/ignitionrobotics/ign-gazebo/pull/401) + * [Pull Request 401](https://github.com/gazebosim/gz-sim/pull/401) 1. add frame_id and child_frame_id attribute support for DiffDrive - * [Pull Request 361](https://github.com/ignitionrobotics/ign-gazebo/pull/361) + * [Pull Request 361](https://github.com/gazebosim/gz-sim/pull/361) 1. Add ability to record video based on sim time - * [Pull Request 414](https://github.com/ignitionrobotics/ign-gazebo/pull/414) + * [Pull Request 414](https://github.com/gazebosim/gz-sim/pull/414) 1. Add lockstep mode to video recording - * [Pull Request 419](https://github.com/ignitionrobotics/ign-gazebo/pull/419) + * [Pull Request 419](https://github.com/gazebosim/gz-sim/pull/419) 1. Disable right click menu when using measuring tool - * [Pull Request 458](https://github.com/ignitionrobotics/ign-gazebo/pull/458) + * [Pull Request 458](https://github.com/gazebosim/gz-sim/pull/458) -### Ignition Gazebo 3.5.0 (2020-11-03) +### Gazebo Sim 3.5.0 (2020-11-03) 1. Updated source build instructions - * [Pull Request 403](https://github.com/ignitionrobotics/ign-gazebo/pull/403) + * [Pull Request 403](https://github.com/gazebosim/gz-sim/pull/403) 1. More world APIs, helper function ComponentData - * [Pull Request 378](https://github.com/ignitionrobotics/ign-gazebo/pull/378) + * [Pull Request 378](https://github.com/gazebosim/gz-sim/pull/378) 1. Improve fork experience - * [Pull Request 411](https://github.com/ignitionrobotics/ign-gazebo/pull/411) + * [Pull Request 411](https://github.com/gazebosim/gz-sim/pull/411) 1. Fix a crash in the grid config plugin, set grid material - * [Pull Request 412](https://github.com/ignitionrobotics/ign-gazebo/pull/412) + * [Pull Request 412](https://github.com/gazebosim/gz-sim/pull/412) 1. Document deprecation of log playback `` SDF param - * [Pull Request 424](https://github.com/ignitionrobotics/ign-gazebo/pull/424) - * [Pull Request 425](https://github.com/ignitionrobotics/ign-gazebo/pull/425) + * [Pull Request 424](https://github.com/gazebosim/gz-sim/pull/424) + * [Pull Request 425](https://github.com/gazebosim/gz-sim/pull/425) 1. Enable mouse highlighting selection on resource spawner - * [Pull Request 402](https://github.com/ignitionrobotics/ign-gazebo/pull/402) + * [Pull Request 402](https://github.com/gazebosim/gz-sim/pull/402) 1. Add support for custom render engines - * [Pull Request 373](https://github.com/ignitionrobotics/ign-gazebo/pull/373) + * [Pull Request 373](https://github.com/gazebosim/gz-sim/pull/373) 1. Component Vector -> Map ECM Optimization - * [Pull Request 416](https://github.com/ignitionrobotics/ign-gazebo/pull/416) + * [Pull Request 416](https://github.com/gazebosim/gz-sim/pull/416) -### Ignition Gazebo 3.4.0 (2020-10-14) +### Gazebo Sim 3.4.0 (2020-10-14) 1. Fix gui sendEvent memory leaks - * [Pull Request 365](https://github.com/ignitionrobotics/ign-gazebo/pull/365) + * [Pull Request 365](https://github.com/gazebosim/gz-sim/pull/365) 1. Support nested models - * [Pull Request 258](https://github.com/ignitionrobotics/ign-gazebo/pull/258) + * [Pull Request 258](https://github.com/gazebosim/gz-sim/pull/258) 1. Generalize actor count and pose in actor population erb SDF - * [Pull Request 336](https://github.com/ignitionrobotics/ign-gazebo/pull/336) + * [Pull Request 336](https://github.com/gazebosim/gz-sim/pull/336) 1. Add more link APIs, with tutorial - * [Pull Request 375](https://github.com/ignitionrobotics/ign-gazebo/pull/375) + * [Pull Request 375](https://github.com/gazebosim/gz-sim/pull/375) 1. Add screenshots to GUI config tutorial - * [Pull Request 406](https://github.com/ignitionrobotics/ign-gazebo/pull/406) + * [Pull Request 406](https://github.com/gazebosim/gz-sim/pull/406) 1. Fix adding performers to entity tree - * [Pull Request 374](https://github.com/ignitionrobotics/ign-gazebo/pull/374) + * [Pull Request 374](https://github.com/gazebosim/gz-sim/pull/374) 1. Remove sidebar and put world control in bottom left for joint controller examples - * [Pull Request 384](https://github.com/ignitionrobotics/ign-gazebo/pull/384) + * [Pull Request 384](https://github.com/gazebosim/gz-sim/pull/384) 1. Allow executing a blocking single Server run in both paused and unpaused states - * [Pull Request 297](https://github.com/ignitionrobotics/ign-gazebo/pull/297) + * [Pull Request 297](https://github.com/gazebosim/gz-sim/pull/297) 1. Add camera video recorder system - * [Pull Request 316](https://github.com/ignitionrobotics/ign-gazebo/pull/316) + * [Pull Request 316](https://github.com/gazebosim/gz-sim/pull/316) 1. Decrease time step for quadcopter world - * [Pull Request 372](https://github.com/ignitionrobotics/ign-gazebo/pull/372) + * [Pull Request 372](https://github.com/gazebosim/gz-sim/pull/372) 1. Add support for moving the GUI camera to a pose - * [Pull Request 352](https://github.com/ignitionrobotics/ign-gazebo/pull/352) + * [Pull Request 352](https://github.com/gazebosim/gz-sim/pull/352) 1. Remove `lib`+`.so` from plugin's name - * [Pull Request 279](https://github.com/ignitionrobotics/ign-gazebo/pull/279) - * [Pull Request 335](https://github.com/ignitionrobotics/ign-gazebo/pull/335) + * [Pull Request 279](https://github.com/gazebosim/gz-sim/pull/279) + * [Pull Request 335](https://github.com/gazebosim/gz-sim/pull/335) 1. EntityComponentManager::EachRemoved documentation fix. - * [Pull Request 348](https://github.com/ignitionrobotics/ign-gazebo/pull/348) + * [Pull Request 348](https://github.com/gazebosim/gz-sim/pull/348) 1. Add more model APIs. - * [Pull Request 349](https://github.com/ignitionrobotics/ign-gazebo/pull/349) + * [Pull Request 349](https://github.com/gazebosim/gz-sim/pull/349) 1. Update dimensions of the grid config. - * [Pull Request 383](https://github.com/ignitionrobotics/ign-gazebo/pull/383) + * [Pull Request 383](https://github.com/gazebosim/gz-sim/pull/383) 1. Fix top-left toolbar layout so magnet shows. - * [Pull Request 381](https://github.com/ignitionrobotics/ign-gazebo/pull/381) + * [Pull Request 381](https://github.com/gazebosim/gz-sim/pull/381) 1. Add instructions to bitmask world. - * [Pull Request 377](https://github.com/ignitionrobotics/ign-gazebo/pull/377) + * [Pull Request 377](https://github.com/gazebosim/gz-sim/pull/377) 1. Add search and sort for resource spawner. - * [Pull Request 359](https://github.com/ignitionrobotics/ign-gazebo/pull/359) + * [Pull Request 359](https://github.com/gazebosim/gz-sim/pull/359) -1. Fix source build instructions for ign-gazebo3. - * [Pull Request 395](https://github.com/ignitionrobotics/ign-gazebo/pull/395) +1. Fix source build instructions for gz-sim3. + * [Pull Request 395](https://github.com/gazebosim/gz-sim/pull/395) 1. Added playback scrubber GUI - * [Pull Request 299](https://github.com/ignitionrobotics/ign-gazebo/pull/299) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 299](https://github.com/gazebosim/gz-sim/pull/299) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Added wheel slip system plugin. - * [Pull Request 134](https://github.com/ignitionrobotics/ign-gazebo/pull/134) - * [Pull Request 357](https://github.com/ignitionrobotics/ign-gazebo/pull/357) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 134](https://github.com/gazebosim/gz-sim/pull/134) + * [Pull Request 357](https://github.com/gazebosim/gz-sim/pull/357) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Enhanced log playback performance. - * [Pull Request 351](https://github.com/ignitionrobotics/ign-gazebo/pull/351) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 351](https://github.com/gazebosim/gz-sim/pull/351) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) -1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, ign_TEST - * [Pull Request 327](https://github.com/ignitionrobotics/ign-gazebo/pull/327) +1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, gz_TEST + * [Pull Request 327](https://github.com/gazebosim/gz-sim/pull/327) 1. Added support for specifying topics to record. - * [Pull Request 315](https://github.com/ignitionrobotics/ign-gazebo/pull/315) + * [Pull Request 315](https://github.com/gazebosim/gz-sim/pull/315) 1. Make sure OpenGL core profile context is used by GzScene3D. - * [Pull Request 339](https://github.com/ignitionrobotics/ign-gazebo/pull/339) + * [Pull Request 339](https://github.com/gazebosim/gz-sim/pull/339) 1. Support relative paths for PBR materials - * [Pull Request 328](https://github.com/ignitionrobotics/ign-gazebo/pull/328) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 328](https://github.com/gazebosim/gz-sim/pull/328) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Add file extension automatically for record plugin. - * [Pull Request 303](https://github.com/ignitionrobotics/ign-gazebo/pull/303) - * [Pull Request 362](https://github.com/ignitionrobotics/ign-gazebo/pull/362) + * [Pull Request 303](https://github.com/gazebosim/gz-sim/pull/303) + * [Pull Request 362](https://github.com/gazebosim/gz-sim/pull/362) 1. Support spawning during log playback. - * [Pull Request 346](https://github.com/ignitionrobotics/ign-gazebo/pull/346) + * [Pull Request 346](https://github.com/gazebosim/gz-sim/pull/346) 1. Add Render Engine Cmd Line option - * [Pull Request 331](https://github.com/ignitionrobotics/ign-gazebo/pull/331) + * [Pull Request 331](https://github.com/gazebosim/gz-sim/pull/331) -### Ignition Gazebo 3.3.0 (2020-08-31) +### Gazebo Sim 3.3.0 (2020-08-31) 1. Added marker array service. - * [pull request 302](https://github.com/ignitionrobotics/ign-gazebo/pull/302) + * [pull request 302](https://github.com/gazebosim/gz-sim/pull/302) 1. Introduced a new parameter in the scene3D plugin to launch in fullscreen. - * [pull request 254](https://github.com/ignitionrobotics/ign-gazebo/pull/254) + * [pull request 254](https://github.com/gazebosim/gz-sim/pull/254) 1. Fix issue #285 by adding checks for a marker's parent. - * [pull request 290](https://github.com/ignitionrobotics/ign-gazebo/pull/290) + * [pull request 290](https://github.com/gazebosim/gz-sim/pull/290) 1. Fix non-specified material error. - * [pull request 292](https://github.com/ignitionrobotics/ign-gazebo/pull/292) + * [pull request 292](https://github.com/gazebosim/gz-sim/pull/292) 1. Added simulation world with large number of entities. - * [pull request 283](https://github.com/ignitionrobotics/ign-gazebo/pull/283) + * [pull request 283](https://github.com/gazebosim/gz-sim/pull/283) 1. Fixed parsing of the touch plugin' enabled flag. - * [pull request 275](https://github.com/ignitionrobotics/ign-gazebo/pull/275) + * [pull request 275](https://github.com/gazebosim/gz-sim/pull/275) 1. Added buoyancy system plugin. - * [pull request 252](https://github.com/ignitionrobotics/ign-gazebo/pull/252) + * [pull request 252](https://github.com/gazebosim/gz-sim/pull/252) 1. Implemented shift + drag = rotate in the GUI. - * [pull request 247](https://github.com/ignitionrobotics/ign-gazebo/pull/247) + * [pull request 247](https://github.com/gazebosim/gz-sim/pull/247) 1. Backport collision bitmask changes - * [pull request 223](https://github.com/ignitionrobotics/ign-gazebo/pull/223) + * [pull request 223](https://github.com/gazebosim/gz-sim/pull/223) 1. Added velocity command to TPE. - * [pull request 169](https://github.com/ignitionrobotics/ign-gazebo/pull/169) + * [pull request 169](https://github.com/gazebosim/gz-sim/pull/169) -1. This version includes all features in Gazebo 2.23.0 +1. This version includes all features in Gazebo Sim 2.23.0 -### Ignition Gazebo 3.2.0 (2020-05-20) +### Gazebo Sim 3.2.0 (2020-05-20) -1. Merge ign-gazebo2 to ign-gazebo3 - * [pull request 149](https://github.com/ignitionrobotics/ign-gazebo/pull/149) +1. Merge gz-sim2 to gz-sim3 + * [pull request 149](https://github.com/gazebosim/gz-sim/pull/149) -### Ignition Gazebo 3.1.0 (2020-05-19) +### Gazebo Sim 3.1.0 (2020-05-19) 1. Port support for computing model bounding box in physics system - * [pull request 127](https://github.com/ignitionrobotics/ign-gazebo/pull/127) + * [pull request 127](https://github.com/gazebosim/gz-sim/pull/127) 1. Add DetachableJoint: A system that initially attaches two models via a fixed joint and allows for the models to get detached during simulation via a topic. * [BitBucket pull request 440](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/440) @@ -3310,9 +3312,9 @@ * [BitBucket pull request 514](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/514) 1. Add window focus upon mouse entering the render window - * [Github pull request 96](https://github.com/ignitionrobotics/ign-gazebo/pull/96) + * [Github pull request 96](https://github.com/gazebosim/gz-sim/pull/96) -### Ignition Gazebo 3.0.0 (2019-12-10) +### Gazebo Sim 3.0.0 (2019-12-10) 1. Add example world for collide bitmask feature * [BitBucket pull request 525](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/525) @@ -3339,168 +3341,168 @@ 1. Move function definitions to their correct locations in EntityComponentManager * [BitBucket pull request 380](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/380) -1. Depend on ign-rendering3, ign-gui3, ign-sensors3 +1. Depend on gz-rendering3, gz-gui3, gz-sensors3 * [BitBucket pull request 411](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/411) 1. Rendering and Animating Actors * [BitBucket pull request 414](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/414) -## Ignition Gazebo 2.x +## Gazebo Sim 2.x -### Ignition Gazebo 2.25.0 (2020-09-17) +### Gazebo Sim 2.25.0 (2020-09-17) 1. Added wheel slip system plugin. - * [Pull Request 134](https://github.com/ignitionrobotics/ign-gazebo/pull/134) - * [Pull Request 357](https://github.com/ignitionrobotics/ign-gazebo/pull/357) + * [Pull Request 134](https://github.com/gazebosim/gz-sim/pull/134) + * [Pull Request 357](https://github.com/gazebosim/gz-sim/pull/357) 1. Enhanced log playback performance. - * [Pull Request 351](https://github.com/ignitionrobotics/ign-gazebo/pull/351) + * [Pull Request 351](https://github.com/gazebosim/gz-sim/pull/351) -1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, ign_TEST - * [Pull Request 327](https://github.com/ignitionrobotics/ign-gazebo/pull/327) +1. Tests & Warnings: Qt 5.14, breadcrumbs, Gui, gz_TEST + * [Pull Request 327](https://github.com/gazebosim/gz-sim/pull/327) 1. Added support for specifying topics to record. - * [Pull Request 315](https://github.com/ignitionrobotics/ign-gazebo/pull/315) + * [Pull Request 315](https://github.com/gazebosim/gz-sim/pull/315) 1. Make sure OpenGL core profile context is used by GzScene3D. - * [Pull Request 339](https://github.com/ignitionrobotics/ign-gazebo/pull/339) + * [Pull Request 339](https://github.com/gazebosim/gz-sim/pull/339) 1. Support relative paths for PBR materials - * [Pull Request 328](https://github.com/ignitionrobotics/ign-gazebo/pull/328) + * [Pull Request 328](https://github.com/gazebosim/gz-sim/pull/328) 1. Add file extension automatically for record plugin. - * [Pull Request 303](https://github.com/ignitionrobotics/ign-gazebo/pull/303) + * [Pull Request 303](https://github.com/gazebosim/gz-sim/pull/303) 1. Support spawning during log playback. - * [Pull Request 346](https://github.com/ignitionrobotics/ign-gazebo/pull/346) + * [Pull Request 346](https://github.com/gazebosim/gz-sim/pull/346) -### Ignition Gazebo 2.24.0 (2020-09-03) +### Gazebo Sim 2.24.0 (2020-09-03) 1. Resource env var, with transport interface. - * [Pull Request 172](https://github.com/ignitionrobotics/ign-gazebo/pull/172) + * [Pull Request 172](https://github.com/gazebosim/gz-sim/pull/172) 1. Save http URIs (fix tests) - * [Pull Request 271](https://github.com/ignitionrobotics/ign-gazebo/pull/271) + * [Pull Request 271](https://github.com/gazebosim/gz-sim/pull/271) 1. Insert Local Models. - * [Pull Request 173](https://github.com/ignitionrobotics/ign-gazebo/pull/173) + * [Pull Request 173](https://github.com/gazebosim/gz-sim/pull/173) 1. Modernize actions CI. - * [Pull Request 269](https://github.com/ignitionrobotics/ign-gazebo/pull/269) + * [Pull Request 269](https://github.com/gazebosim/gz-sim/pull/269) 1. Sensor topics available through components and GUI. - * [Pull Request 266](https://github.com/ignitionrobotics/ign-gazebo/pull/266) + * [Pull Request 266](https://github.com/gazebosim/gz-sim/pull/266) 1. Customizable layouts - fully functional. - * [Pull Request 278](https://github.com/ignitionrobotics/ign-gazebo/pull/278) + * [Pull Request 278](https://github.com/gazebosim/gz-sim/pull/278) 1. Add Fuel World Support. - * [Pull Request 274](https://github.com/ignitionrobotics/ign-gazebo/pull/274) + * [Pull Request 274](https://github.com/gazebosim/gz-sim/pull/274) 1. Insert Fuel Models. - * [Pull Request 263](https://github.com/ignitionrobotics/ign-gazebo/pull/263) + * [Pull Request 263](https://github.com/gazebosim/gz-sim/pull/263) 1. Disable rendering tests on macOS that are known to fail. - * [Pull Request 209](https://github.com/ignitionrobotics/ign-gazebo/pull/209) + * [Pull Request 209](https://github.com/gazebosim/gz-sim/pull/209) 1. Fix tests on Blueprint. - * [Pull Request 295](https://github.com/ignitionrobotics/ign-gazebo/pull/295) + * [Pull Request 295](https://github.com/gazebosim/gz-sim/pull/295) 1. Publish remaining breadcrumb deployments. - * [Pull Request 308](https://github.com/ignitionrobotics/ign-gazebo/pull/308) + * [Pull Request 308](https://github.com/gazebosim/gz-sim/pull/308) -### Ignition Gazebo 2.23.0 (2020-07-28) +### Gazebo Sim 2.23.0 (2020-07-28) 1. Deactivate PerformerDetector if its parent model gets removed. - * [Pull Request 260](https://github.com/ignitionrobotics/ign-gazebo/pull/260) + * [Pull Request 260](https://github.com/gazebosim/gz-sim/pull/260) 1. Backport support for s from Fuel #255 - * [Pull Request 255](https://github.com/ignitionrobotics/ign-gazebo/pull/255) + * [Pull Request 255](https://github.com/gazebosim/gz-sim/pull/255) -### Ignition Gazebo 2.22.0 (2020-07-22) +### Gazebo Sim 2.22.0 (2020-07-22) 1. Allow zero or more key/value pairs to be added to detection header information. - * [Pull Request 257](https://github.com/ignitionrobotics/ign-gazebo/pull/257) + * [Pull Request 257](https://github.com/gazebosim/gz-sim/pull/257) -### Ignition Gazebo 2.21.0 (2020-07-16) +### Gazebo Sim 2.21.0 (2020-07-16) 1. Added support for controlling which joints are published by the JointStatePublisher. - * [Pull Request 222](https://github.com/ignitionrobotics/ign-gazebo/pull/222) + * [Pull Request 222](https://github.com/gazebosim/gz-sim/pull/222) 1. Added an additional pose offset for the performer detector plugin. - * [Pull Request 236](https://github.com/ignitionrobotics/ign-gazebo/pull/236) + * [Pull Request 236](https://github.com/gazebosim/gz-sim/pull/236) 1. Fixed battery issues and updated tutorial. - * [Pull Request 230](https://github.com/ignitionrobotics/ign-gazebo/pull/230) + * [Pull Request 230](https://github.com/gazebosim/gz-sim/pull/230) -### Ignition Gazebo 2.20.1 (2020-06-18) +### Gazebo Sim 2.20.1 (2020-06-18) 1. Properly add new models into the scenegraph. With this fix, when a model is spawned it will be added into the graph and resulting calls to the `scene/info` service will return a correct `msgs::Scene`. - * [Pull Request 212](https://github.com/ignitionrobotics/ign-gazebo/pull/212) + * [Pull Request 212](https://github.com/gazebosim/gz-sim/pull/212) -### Ignition Gazebo 2.20.0 (2020-06-09) +### Gazebo Sim 2.20.0 (2020-06-09) 1. Updated battery model to stop battery drain when there is no joint velocity/force command, and added a recharging trigger. - * [Pull Request 183](https://github.com/ignitionrobotics/ign-gazebo/pull/183) + * [Pull Request 183](https://github.com/gazebosim/gz-sim/pull/183) 1. Fix segfault in the Breadcrumbs system - * [Pull Request 180](https://github.com/ignitionrobotics/ign-gazebo/pull/180) + * [Pull Request 180](https://github.com/gazebosim/gz-sim/pull/180) 1. Added an `` element to the DiffDrive system so that a custom odometry topic can be used. - * [Pull Request 179](https://github.com/ignitionrobotics/ign-gazebo/pull/179) + * [Pull Request 179](https://github.com/gazebosim/gz-sim/pull/179) -### Ignition Gazebo 2.19.0 (2020-06-02) +### Gazebo Sim 2.19.0 (2020-06-02) 1. Use updated model names for spawned models when generating SDFormat - * [Pull Request 166](https://github.com/ignitionrobotics/ign-gazebo/pull/166) + * [Pull Request 166](https://github.com/gazebosim/gz-sim/pull/166) 1. Allow joint force commands (JointForceCmd) to dscharge a battery. - * [Pull Request 165](https://github.com/ignitionrobotics/ign-gazebo/pull/165) + * [Pull Request 165](https://github.com/gazebosim/gz-sim/pull/165) 1. Allow renaming breadcrumb models if there is a name conflict - * [Pull Request 155](https://github.com/ignitionrobotics/ign-gazebo/pull/155) + * [Pull Request 155](https://github.com/gazebosim/gz-sim/pull/155) 1. Add TriggeredPublisher system - * [Pull Request 139](https://github.com/ignitionrobotics/ign-gazebo/pull/139) + * [Pull Request 139](https://github.com/gazebosim/gz-sim/pull/139) 1. Add PerformerDetector, a system for detecting when performers enter a specified region - * [Pull Request 125](https://github.com/ignitionrobotics/ign-gazebo/pull/125) + * [Pull Request 125](https://github.com/gazebosim/gz-sim/pull/125) -### Ignition Gazebo 2.18.0 (2020-05-20) +### Gazebo Sim 2.18.0 (2020-05-20) -1. Added a `/world//create_multiple` service that parallels the current `/world//create` service. The `create_multiple` service can handle an `ignition::msgs::EntityFactory_V` message that may contain one or more entities to spawn. - * [Pull Request 146](https://github.com/ignitionrobotics/ign-gazebo/pull/146) +1. Added a `/world//create_multiple` service that parallels the current `/world//create` service. The `create_multiple` service can handle an `gz::msgs::EntityFactory_V` message that may contain one or more entities to spawn. + * [Pull Request 146](https://github.com/gazebosim/gz-sim/pull/146) 1. DetachableJoint system: Add option to suppress warning about missing child model - * [Pull Request 132](https://github.com/ignitionrobotics/ign-gazebo/pull/132) + * [Pull Request 132](https://github.com/gazebosim/gz-sim/pull/132) -### Ignition Gazebo 2.17.0 (2020-05-13) +### Gazebo Sim 2.17.0 (2020-05-13) 1. Allow battery plugin to work with joint force systems. - * [Pull Request 120](https://github.com/ignitionrobotics/ign-gazebo/pull/120) + * [Pull Request 120](https://github.com/gazebosim/gz-sim/pull/120) 1. Make breadcrumb static after specified time - * [Pull Request 90](https://github.com/ignitionrobotics/ign-gazebo/pull/90) + * [Pull Request 90](https://github.com/gazebosim/gz-sim/pull/90) 1. Disable breadcrumbs if the `max_deployments` == 0. - * [Pull Request 88](https://github.com/ignitionrobotics/ign-gazebo/pull/88) + * [Pull Request 88](https://github.com/gazebosim/gz-sim/pull/88) 1. Add static pose publisher and support pose\_v msg type in pose publisher system - * [Pull Request 65](https://github.com/ignitionrobotics/ign-gazebo/pull/65) + * [Pull Request 65](https://github.com/gazebosim/gz-sim/pull/65) 1. Refactor Gui.hh so that the Gazebo GUI can be ran from other packages - * [Pull Request 79](https://github.com/ignitionrobotics/ign-gazebo/pull/79) + * [Pull Request 79](https://github.com/gazebosim/gz-sim/pull/79) 1. Add ability to save worlds to SDFormat * [BitBucket pull request 545](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/545) 1. Add window focus upon mouse entering the render window - * [Github pull request 95](https://github.com/ignitionrobotics/ign-gazebo/pull/95) + * [Github pull request 95](https://github.com/gazebosim/gz-sim/pull/95) -### Ignition Gazebo 2.16.0 (2020-03-24) +### Gazebo Sim 2.16.0 (2020-03-24) 1. Add support for computing model bounding box in physics system * [BitBucket pull request 546](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/546) @@ -3562,12 +3564,12 @@ 1. Fix shift translation bug * [BitBucket pull request 529](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/529) -### Ignition Gazebo 2.15.0 (2020-02-07) +### Gazebo Sim 2.15.0 (2020-02-07) 1. Fix seeking back in time in log playback * [BitBucket pull request 523](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/523) -1. Fix the deprecated ign-gazebo command line +1. Fix the deprecated gz-sim command line * [BitBucket pull request 499](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/499) 1. Always use the latest render texture in scene3d @@ -3588,7 +3590,7 @@ 1. Add hotkey keybindings * [BitBucket pull request 486](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/486) -### Ignition Gazebo 2.14.0 (2020-01-10) +### Gazebo Sim 2.14.0 (2020-01-10) 1. Use Actuator component to communicate between MulticopterVelocityControl and MulticopterMotorModel systems * [BitBucket pull request 498](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/498) @@ -3602,7 +3604,7 @@ 1. Fix tooltips on entity tree * [BitBucket pull request 496](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/496) -### Ignition Gazebo 2.13.0 (2019-12-17) +### Gazebo Sim 2.13.0 (2019-12-17) 1. Add Multicopter velocity controller * [BitBucket pull request 487](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/487) @@ -3622,7 +3624,7 @@ 1. Show grid using SDF file * [BitBucket pull request 461](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/461) -### Ignition Gazebo 2.12.0 (2019-11-25) +### Gazebo Sim 2.12.0 (2019-11-25) 1. Parse visual cast shadows and add CastShadows component * [BitBucket pull request 453](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/453) @@ -3648,7 +3650,7 @@ 1. Prevent crash when attempting to load more than one render engine per process * [BitBucket pull request 463](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/463) -### Ignition Gazebo 2.11.0 (2019-10-23) +### Gazebo Sim 2.11.0 (2019-10-23) 1. Handle Relative URIs * [BitBucket pull request 433](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/433) @@ -3672,7 +3674,7 @@ * [BitBucket pull request 430](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/430) * [BitBucket pull request 436](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/436) -### Ignition Gazebo 2.10.0 (2019-09-08) +### Gazebo Sim 2.10.0 (2019-09-08) 1. Custom odom frequency in sim time * [BitBucket pull request 427](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/427) @@ -3680,12 +3682,12 @@ 1. Add Move To gui plugin * [BitBucket pull request 426](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/426) -### Ignition Gazebo 2.9.0 +### Gazebo Sim 2.9.0 1. Use the JointSetVelocityCommand feature to set joint velocities * [BitBucket pull request 424](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/424) -### Ignition Gazebo 2.8.0 (2019-08-23) +### Gazebo Sim 2.8.0 (2019-08-23) 1. Add video recorder gui plugin * [BitBucket pull request 422](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/422) @@ -3696,14 +3698,14 @@ 1. Print world path when using cli * [BitBucket pull request 420](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/420) -### Ignition Gazebo 2.7.1 +### Gazebo Sim 2.7.1 1. Fix order of adding and removing rendering entities, and clean up mesh materials in the SceneManager. * [BitBucket pull request 415](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/415) * [BitBucket pull request 416](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/416) -### Ignition Gazebo 2.7.0 +### Gazebo Sim 2.7.0 1. Move creation of default log path to ServerConfig. This lets both console logs and state logs to be stored in the same directory. The console messages are always logged. Allow state log files to be overwritten. * [BitBucket pull request 413](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/413) @@ -3721,12 +3723,12 @@ See the `test/performance/READEM.md` file for more info. * [BitBucket pull request 389](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/389) -### Ignition Gazebo 2.6.1 (2019-07-26) +### Gazebo Sim 2.6.1 (2019-07-26) 1. Clear stepMsg before populating it * [BitBucket pull request 398](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/398) -### Ignition Gazebo 2.6.0 (2019-07-24) +### Gazebo Sim 2.6.0 (2019-07-24) 1. Improve performance of Pose Publisher * [BitBucket pull request 392](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/392) @@ -3734,17 +3736,17 @@ 1. Fix distributed sim * [BitBucket pull request 385](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/385) -### Ignition Gazebo 2.5.0 (2019-07-19) +### Gazebo Sim 2.5.0 (2019-07-19) 1. The LinearBatteryPlugin system publishes battery state * [BitBucket pull request 388](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/388) -### Ignition Gazebo 2.4.0 (2019-07-17) +### Gazebo Sim 2.4.0 (2019-07-17) 1. Bundle scene updates in sensor system * [BitBucket pull request 386](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/386) -### Ignition Gazebo 2.3.0 (2019-07-13) +### Gazebo Sim 2.3.0 (2019-07-13) 1. Improve physics system peformance by skipping static model updates. Components state information has been incorporated, which is used to @@ -3768,7 +3770,7 @@ * [BitBucket pull request 375](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/375) * [BitBucket pull request 376](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/376) -### Ignition Gazebo 2.2.0 +### Gazebo Sim 2.2.0 1. The DiffDrive system publishes odometry information. * [BitBucket pull request 368](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/368) @@ -3788,7 +3790,7 @@ 1. Support custom random seed from the command line. * [BitBucket pull request 362](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/362) -### Ignition Gazebo 2.1.0 +### Gazebo Sim 2.1.0 1. RenderUtil fix bad merge: check for existing entities in GzScene3D on initialization. * [BitBucket pull request 360](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/360) @@ -3812,7 +3814,7 @@ 1. Support log playback from a different path * [BitBucket pull request 355](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/355) -### Ignition Gazebo 2.0.0 +### Gazebo Sim 2.0.0 1. RenderUtil: check for existing entities in GzScene3D on initialization. * [BitBucket pull request 350](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/350) @@ -3876,7 +3878,7 @@ 1. Fix distributed sim documentation * [BitBucket pull request 318](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/318) -1. Port Scene3D gui plugin from ign-gui. Renamed to GzScene3D. +1. Port Scene3D gui plugin from gz-gui. Renamed to GzScene3D. * [BitBucket pull request 315](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/315) 1. Entity tree UI @@ -3888,7 +3890,7 @@ 1. Update Camera and DepthCamera components to use sdf::Sensor object instead of an sdf::ElementPtr. * [BitBucket pull request 299](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/299) -1. Added system for ignition::sensors::AirPressureSensor. +1. Added system for gz::sensors::AirPressureSensor. * [BitBucket pull request 300](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/300) 1. Support conversion and serialization of Imu components. IMU sensors are @@ -3917,7 +3919,7 @@ 1. Update docker nightly dependencies * [BitBucket pull request 310](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/310) -1. Ign tool +1. Gz tool * [BitBucket pull request 296](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/296) * [BitBucket pull request 336](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/336) @@ -3987,21 +3989,21 @@ 1. Distributed sim deprecate envs * [BitBucket pull request 240](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/240) -1. Use ign-sensors magnetometer sensor plugin +1. Use gz-sensors magnetometer sensor plugin * [BitBucket pull request 221](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/221) -1. Use ign-sensors altimeter sensor plugin +1. Use gz-sensors altimeter sensor plugin * [BitBucket pull request 215](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/215) -1. Use ign-sensors imu sensor plugin +1. Use gz-sensors imu sensor plugin * [BitBucket pull request 219](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/219) -1. Depend on ign-sensors rendering component +1. Depend on gz-sensors rendering component * [BitBucket pull request 212](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/212) -## Ignition Gazebo 1.x +## Gazebo Sim 1.x -### Ignition Gazebo 1.X.X +### Gazebo Sim 1.X.X 1. Add Wind Plugin (Ported from Gazebo classic) * [BitBucket pull request 273](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/273/) @@ -4026,7 +4028,7 @@ 1. Added LiftDragPlugin (ported from Gazebo classic) * [BitBucket pull request 256](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/256) -1. Logging refactor unique path functions to ign-common +1. Logging refactor unique path functions to gz-common * [BitBucket pull request 270](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/270) 1. Added test for log record and playback. @@ -4035,7 +4037,7 @@ 1. Add ApplyJointForce system * [BitBucket pull request 254](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/254) -1. More ign-msgs <-> SDF conversions: Inertial, Geometry, Material +1. More gz-msgs <-> SDF conversions: Inertial, Geometry, Material * [BitBucket pull request 251](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/251) 1. Logging command line support @@ -4069,7 +4071,7 @@ 1. Add systems to queue before actually adding them to runner * [BitBucket pull request 241](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/241) -1. Added a docker image that uses the ignition meta package +1. Added a docker image that uses the Gazebo meta package * [BitBucket pull request 237](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/237) 1. Move some design docs to tutorials @@ -4096,13 +4098,13 @@ 1. Example tunnel world * [BitBucket pull request 205](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/205) -1. Conversion from chrono to ign-msgs +1. Conversion from chrono to gz-msgs * [BitBucket pull request 223](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/223) 1. Prevent error message when using levels * [BitBucket pull request 229](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/229) -### Ignition Gazebo 1.1.0 (2019-03-15) +### Gazebo Sim 1.1.0 (2019-03-15) 1. Distributed performers running in lockstep * [BitBucket pull request 186](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/186) @@ -4131,23 +4133,23 @@ 1. Unversioned system libraries * [BitBucket pull request 222](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/222) -### Ignition Gazebo 1.0.2 (2019-03-12) +### Gazebo Sim 1.0.2 (2019-03-12) 1. Use TARGET_SO_NAME to fix finding dartsim plugin * [BitBucket pull request 217](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/217) -### Ignition Gazebo 1.0.1 (2019-03-01) +### Gazebo Sim 1.0.1 (2019-03-01) 1. Update gazebo version number in sdf files * [BitBucket pull request 207](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/207) -### Ignition Gazebo 1.0.0 (2019-03-01) +### Gazebo Sim 1.0.0 (2019-03-01) 1. Initial release -## Ignition Gazebo 0.x +## Gazebo Sim 0.x -### Ignition Gazebo 0.1.0 +### Gazebo Sim 0.1.0 1. Add support for joints * [BitBucket pull request 77](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/77) @@ -4158,7 +4160,7 @@ 1. Create EventManager and delegate System instantiation to SimulationRunner * [BitBucket pull request 79](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/79) -1. Integrate ign-gui +1. Integrate gz-gui * [BitBucket pull request 11](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/11) 1. Remove some build dependencies. diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.cc b/src/gui/plugins/joint_position_controller/JointPositionController.cc index af7b3a3b73..e202513024 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController.cc @@ -291,7 +291,7 @@ void JointPositionController::Update(const UpdateInfo &, QMetaObject::invokeMethod(&this->dataPtr->jointsModel, "RemoveJoint", Qt::QueuedConnection, - Q_ARG(gz:sim::Entity, jointEntity)); + Q_ARG(sim::Entity, jointEntity)); } } } diff --git a/src/gui/plugins/scene_manager/GzSceneManager.cc b/src/gui/plugins/scene_manager/GzSceneManager.cc index 7b2bcd03b0..9bc1007876 100644 --- a/src/gui/plugins/scene_manager/GzSceneManager.cc +++ b/src/gui/plugins/scene_manager/GzSceneManager.cc @@ -132,12 +132,6 @@ void GzSceneManager::Update(const UpdateInfo &_info, this->dataPtr->renderEnginePluginPathsInit = true; } - if (!this->dataPtr->renderEnginePluginPathsInit) - { - this->dataPtr->renderUtil.InitRenderEnginePluginPaths(); - this->dataPtr->renderEnginePluginPathsInit = true; - } - this->dataPtr->renderUtil.UpdateECM(_info, _ecm); std::lock_guard lock(this->dataPtr->newRemovedEntityMutex); diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index e414a6947c..1a83e6a906 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -168,7 +168,6 @@ class gz::sim::systems::PhysicsPrivate physics::LinkFrameSemantics, physics::ForwardStep, physics::RemoveModelFromWorld, - physics::sdf::ConstructSdfLink, physics::sdf::ConstructSdfModel, physics::sdf::ConstructSdfWorld, physics::GetLinkFromModel, @@ -470,8 +469,7 @@ class gz::sim::systems::PhysicsPrivate physics::GetJointFromModel, physics::GetBasicJointProperties, physics::GetBasicJointState, - physics::SetBasicJointState, - physics::sdf::ConstructSdfJoint>{}; + physics::SetBasicJointState>{}; /// \brief Feature list to construct joints public: struct ConstructSdfJointFeatureList : gz::physics::FeatureList< diff --git a/test/integration/level_manager.cc b/test/integration/level_manager.cc index 82356d7ec5..b42194816d 100644 --- a/test/integration/level_manager.cc +++ b/test/integration/level_manager.cc @@ -106,7 +106,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> { InternalFixture::SetUp(); - ignition::gazebo::ServerConfig serverConfig; + sim::ServerConfig serverConfig; // Except tile_0, which is on the default level, every tile belongs to a // level. The name of the level corresponds to the tile in its suffix, i.e., @@ -116,12 +116,12 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> serverConfig.SetUseLevels(true); EXPECT_EQ(nullptr, this->server); - this->server = std::make_unique(serverConfig); + this->server = std::make_unique(serverConfig); test::Relay testSystem; // Check entities loaded on the default level - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + testSystem.OnPostUpdate([&](const sim::UpdateInfo &, + const sim::EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &, const components::Model *, @@ -170,7 +170,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> this->server->Run(true, 1, false); } - public: std::unique_ptr server; + public: std::unique_ptr server; public: std::vector loadedModels; public: std::vector unloadedModels; public: std::vector loadedLights; @@ -187,8 +187,8 @@ TEST_F(LevelManagerFixture, GZ_UTILS_TEST_ENABLED_ONLY_ON_LINUX(DefaultLevel)) test::Relay recorder; // Check entities loaded on the default level - recorder.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) + recorder.OnPostUpdate([&](const sim::UpdateInfo &, + const sim::EntityComponentManager &_ecm) { _ecm.Each( [&](const Entity &, const components::DefaultLevel *, diff --git a/test/integration/sdf_include.cc b/test/integration/sdf_include.cc index a682dd6fc9..f10c93b4d7 100644 --- a/test/integration/sdf_include.cc +++ b/test/integration/sdf_include.cc @@ -46,6 +46,6 @@ TEST_F(SdfInclude, GZ_UTILS_TEST_DISABLED_ON_WIN32(DownloadFromFuel)) Server server(serverConfig); EXPECT_TRUE(common::exists(path + - "/fuel.ignitionrobotics.org/openrobotics/models/ground plane" + + "/fuel.gazebosim.org/openrobotics/models/ground plane" + "/1/model.sdf")); } diff --git a/test/worlds/diff_drive_no_plugin.sdf b/test/worlds/diff_drive_no_plugin.sdf index c6bdbd6f96..b1fd389d94 100644 --- a/test/worlds/diff_drive_no_plugin.sdf +++ b/test/worlds/diff_drive_no_plugin.sdf @@ -11,12 +11,8 @@ name="gz::sim::systems::Physics"> - - + filename="gz-sim-scene-broadcaster-system" + name="gz::sim::systems::SceneBroadcaster"> diff --git a/test/worlds/include.sdf b/test/worlds/include.sdf index 1d00bc2dc0..4432b9f3c4 100644 --- a/test/worlds/include.sdf +++ b/test/worlds/include.sdf @@ -6,7 +6,7 @@ - https://fuel.gazebosim.org/1.0/OpenRobotics/models/ground plane/1 + https://fuel.gazebosim.org/1.0/openrobotics/models/ground plane/1 From ce3072252c3c410258dfb6338a61490a5064a4df Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Tue, 22 Nov 2022 12:34:43 -0800 Subject: [PATCH 28/28] Trim trailing whitespace Signed-off-by: Nate Koenig --- Changelog.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Changelog.md b/Changelog.md index dd0a808ba3..adbce79903 100644 --- a/Changelog.md +++ b/Changelog.md @@ -486,7 +486,7 @@ 1. Enable inherited model topic name. * [Pull request #1689](https://github.com/gazebosim/ign-gazebo/pull/1689) -1. Fix loading render engine plugins in GUI +1. Fix loading render engine plugins in GUI * [Pull request #1694](https://github.com/gazebosim/ign-gazebo/pull/1694) 1. Add a service to trigger functionality
      Documentation:" "" - "" - "https://ignitionrobotics.org/libs/gazebo" + "https://gazebosim.org/libs/sim" "" "
      " - "" - "https://ignitionrobotics.org/docs/" + "https://gazebosim.org/docs/" "" "

    F9&U4NjH^02KneAQaA$GoA>Oj+$MSdp{cAc-Id8N%r6`-hbNzZ+&iECI$=r=;!j* z5CG_^S=!k&JDz24v`W^$IV~@(&6Eh$=C5-vU>9Gb=|4mBEoVHjs*aF*$!uy}>1|2Q zcxQb!wLG&-dWrzb!kdCBemwxwtc1qyt&o{FNvG0ZrxV*b2(fwqkkQZ9Zpe-${0Q*C zENn=g_b>PPkWmp^`rhq`@BiVG=FKcxEwY)7nu=|pc+y5hgS)X}*2vTzz7u)}*~|ce z5MnVh55C_eWc66&4(osH9Cstnq}d2C{ch4Mg5%AXj^D zIsFP&0_2>x)>>&%sT1d!eVyWc=)h}ANW<2VjUy5J;_e}su+OkrJQi!@l z1Ql5+WwdJnA#N+)xc}{c_Zk5jJ^kQ29c}~SZgoSalZk~nvv{oWN{gTV<;fCXBc8)^ zV<4p904V?f56+M&UB0kb;aQ&3QkkziJ}ZO(A+T83%BhO21PX6U-#ZA{N_Kow)Nn~Q zbBi-w_xVeepRd9N$$RhlUC6I8KzUQerlp2|Q)PSQGZ(~Cg_14R7h}sR zgB4zYs|?rrE&8{j*=1#sbDjOp0y>7;g{plwxdX2NO8y@2tIfK0F_(&MfPC1HzxkWX zxUEKS^6^=b&l!<~Y-XaS{Os>1Nl#5qikiwD27$%BO1@>&tr+BjV43CnheC(KBGJ24SSjpNhYJ6f_YiJuuEKuDYq%Ozw(uJnzrE*1`! z_W9i1HM#*?lddL#1Z>|fHG+U_YB^sF2o__*ut?HVaZ4&K^0}3vxc{9tJ4AR(hAu1rR%w0wMHDpRZdXo!w=^9&W=g!+Ip!(`KtI-4@ph(@)TFaZ-!QHV)9cVMibrMg4dmeY+vG;65;ngp?@PoR4@dRD~Sy+T2)`dk>S7j~A=uj~fZ}wL>Bst~*Nz z$X3J^bmEq_*`C%?e%bMmT7!TH%G5ba#aAHXKm4N(3Sdr?O5TDWty}nYG|$7Qmj&-p zeAqcd+@(iNS!Pus087HDDg5bgv)QG&^NkkQ=Zlexv3k0p*0054@-E0o@7ys|{OChijfXdt#OEQutn4G(lkIEPSkkx>ucVvxkbhOff z6GhT-l?O#YZh6ZN9yjut>)#5Sea&o2=8y0X&bGwQ{`bhVnEX54yt}O} z$N)|}0)PTgznwAHj7iy@{SXDtE(`BTDp4$)ucCJ#h-DBlZ`a_a81$Q+70r#O~+=P>){E?+;1|kH`wmH9ht%df-OAH zCy0O?IL98?c!Mi^MOy*{&;jlos75RYcOw;uVi5vB*f~#qK0Bugwqce;}^y3(s*ALNK9{JcQe1)NSfs-cK_R*Mo)k7s}*r?|54KH z2jt=MWu`)QB!k7!5Rr5A==V zCZ|QCtGy#Gy_mcv1UC9wM>3mQQ}{+-&qrqTCMQp(aDd>9&*ru){NQ#B0Quaxk{EVp zOGM5X6%u-nzPNtNp8czfcmDm~OfJs*e=vSaFACPCa{mid=j!0!2JihH0eSD7E7Rg~ zTU|(yl|$m4)s;=S_!_z%;+`t$rR{|oqE{@dxl{x4^5p0Wy!rzVyq@GOR% zxpZXi{9a2&0)R~J0jbDb_ih+;1PW*!=&&a_*yrG3f(Rz(&@+fz6|Tfw96(6giU?{0 z6CR+(ZAG5KrsSp9Ifz))IUklhLLj1~a|5W#QaK?o=_*@zAmXmPdk`U2{foEM=&Onf zO_WZ}&fPd_Des`MM30=k9-N>t~+XLsw zm1GNIaR=jwoEhPazxAvMh-KkbLpV$Qqj0;~rAqx<`$D&Nf|HLIQeoIoKrD8(IucdX z7gak&qptxmpE&@SU7F+f)93$R$^|+nIHVIpR86rerHp{9SDDRe??FRIEK^rU{5a#w z)N^d7cTi@Iz5)TOcNnQq=%_Nl@}9tNH^aByX+}-O4;c{@{!B)d?U_)*Wd8MU=bgP^ zeYYyEF}Iy1-CErF{e=q97LM(WIipZSo^i3WkNou2HTuoXaC4w|26|_#i zTK$vNiLPFqv`NLH6=#xG3Sg?IJ5=u^bNIp(o)O;ZMai*Q%oYxCud^3^`ZuHL>s7a} z+v3G@M$rHOAOJ~3K~&y%I#EMOg_kcg8B|XB>k;We<+xmR;Jnw@P(_ePCf^ZJv2gj+ zssL3Wlt%9$n^|U{fBU6RGcM~dvdV<}2H~9)-#G2NGOg?g!wnn(@(7&1-P(?Gj zu5P#vV)8OTSt*;CZI>^sEoe*Wz{LR{Rm3-jrYJhgs6A^5$(H{4KTMb%cJ(T&%kHQto%K?IkeDwV zJ8h>E>x@s@T57PRpPm=A{76y@MD#>L3hrc%KbQkRbD*3301f3J?SGIL@XXqe9!og{0# z$=rNYHg^IJqbL^68b2SED^pd895ce&d0YC)X#oQHVunps1L)+bwZjl3j9%w#EYun%&`DFpAE2-AYxA%D5O6x%!TU1RU zS2V75kM@H{N%t_SRXltEu7|tFZ51{ok2ly(i$y)vAcU$^Urqq14+75~0;Nx5?kqDT9B_uMb*5s8^K1h_(h=|Nkt4aFln9e>b z8O10UuDo(dQz9bcP+#%u(I0o~UY)Jnc^gSbrhg||49$b@cSgs>m%PH$KkF5#GbN#b zMn@zq5hWPKs5FKV9z4+iz(E|mPC0Bo=_(+Q0WwZXYyN=Een3R`zTH_88{y)M6o8~g zUJj!-`K@P783-b1?}d%7&Zah>S+4H5NLWEmbKB_Xd|_*pA!;fq*5p#%U#o)}yuUnPgmhsG2h{Bj8_ zKic3-S}HQiO>Fg3FiL zd~5*V?6Z7+Wt{yoFD#`6Pc=|1y_VKk=lmbdL9iGbAw@Q|I+omnT*rP69yb`IVsl0N-kMlcU zZ*!r}RVxD4ktP7p>}eSaHk#ajlq|+(v8HJ_e9{yWiiKDU}SYpMW&sLWiEy8i8$061yXm25Z!OtSK-v~%YQG47TrE!_sF zSU8?9+R{5io_s!YhtC?kNQHnPl7~+lfnf8sMo;Td zRML0?u4%D~3v=9(HM$xI+PgucU8T$EB`nk3kD|s65<(To;c@4$vei*ohaoAYw5Yy<~f;OPACE3-g|AO z@chFpzp}TUHMwwAp@aes9w*(y5U{d7=pKYs_~{ytidUSdM@-ywtq<0id~OS$j_jHc zY^|WD6^Fw+0t69o=muqT+Zt%zbVP(t|ExE?G&i&XzV@dErG<`U!5KqgW!{`kEn94? z7+VB;_Y)q=Pfp9TkIHP*>r{_i3kYOTgU6^&CAlb?w~{2)u*VAdni%%$vDt+*&Mer+6Fv>PBAGjru{jDfh5(Yaun7$<6rG!yhOi z(K}!_uCGGEVuS_&!rfA7g9u?P*`|Gd?wz&HJH5Mz`o)D&$7VmMg5e~pKoCG{5C{$!)X zmAV9$@qj#bma0lv_s&a=LLm_4bGH~9UOQ&V^Cw59^c;iw5#PpOm>8_g zueO+2Yc7_RbPNazn)DwOteEqT&OTeL50UPC7p}Vr4j#s?BpnGNV9OZJ0yFsvz+ywR z+TSM~n^i!VCzDscgY20VHl&b3hXN(q(gT5%n9ZD&BA+{0Q8qU$NcSEj{MqWA@cOD` z%~ae`n{&lVH&jvZh=c^G#kxHNkHzYc5$|YplB+;ozRV`)McsuCZpY3NyH~1Esz8*P z;}R{|Q@k?|?#4_a8=n?oLrN`9KA!K~jf>PRMrLp)W``yf2&ORtLDW)>9)}o^HNMeR zODQNc2SL=*-V=`s5aIdHCP5^lrb;@B6_MUED8NrEu1)Y7>~uD`9jO3ECpo*%?B0vH zH@s0+!)T{9)ZPi^BZB~JL7I+j5X&GIY<C?QU;h^m2dknl?tAx znhb_J0)W;|$UuO1^!mejo%&#k%HeTxT4~U{C$5~Fq3L^NkJacv2An%7P+ecy(jkkX2{+efBt!j0>h?a=P3ZV^{j~qv#XK-q{6Tv z5m9QPLMa3;Mg}F=(q~iK+6ju(i5maq(PAiAKS+-9g)MWRbky+&GXUu9g;Jw)l+7$t z>KM}9f*6DZA&~c5M%gCkC1W&2=Gaqjyvj2r^3dq$=|x$^axV?nyd!Tb!%a45ucn0r z3^ddYGdpQYEm*F|!IaDaoDU5GI1f=%H3tDA1hE(##VGOOi;O&2L;H^!N{MuA$bpau zm28l*ndN)L;_Gy58MZ(H`P|vkujF`G!Qu?o#4R-+mf6gTWpZv9%NpekV%Z#MArT0t zmj!V4f?}fU+9SA>6nRf3cdQX!9s;C~a$3J5RRs-otVy1R=qijriKZ-53BS zm6o$=&g(_T*PKc5%L-ep)30j7sU_WYWBKnrXb6Gn*s#{sHxEyC)Fz03ftYR^gMi$N# zsoxs0{Qkcjgo&EJHu;6)<$ve9Ev8d_#jhHZefp<80B9WrCU-;-wN;o%8DP@UCm+qf zT!ENPoeo5l$fPNoZQ1Urc3<`PRA->7tSbS`sWG|#{Ac61Ep;e)ly!a6>m7!B4-z(8 zthtTMX!ahQrMRVaC`|4bBg5Q;VqvqX@va(T)fGbAQt8;BMDHp{G>B!GNF53x&=#I2 z*1g~FKlhb4VizeRxFQ&PPykZ`b+`fq$r5WJtGYTA908UAjAID^%2RY%ct_*YoI&tx zYQ1CgFRz1@@o<@X@|4YNKDU6l_n-lrVRP-Bphzo{IH$p~vR*1IoL8{`grjFo=5#kV zZTKJlUZ=>M3Plx5;wYQid_t$cEl+-%t#@$Sy=y3DtC07K%d^3De2|ox3t~AN7Kcw8 zOcbbl{M~!;I;bJF`1mIyCgL^wx|lkXx^`c>lBTES^t48CK-LG4t zR`c1nt*Rw%#b8$dK_oO53p;tC?F<4vf`?=Q%|;7RM{ZT(Co7GmQ3lHkLE4xKT1$w_aG#K zsHy7F#r~570MwecpwU&{vEKrbhp4H@lXsx1rWo>>Ef!V4Jri*{`(eeBu1^_>L@+wd zH*gC9lh5GVmY`Q15_GwhQhbVJtDxk zrIt>I%PgmL=HZ)9=C41Teew6%CMvvP+vyw?sVg&A<{kl*LaEVN3S%jxxa2tPMDE;; z@un?;-Ryb&Cml7tEQQ1{mK-BxjnC#*NGz9;g3QckUYwBF-qY(EPJS<`a51tR`oP z6}As007MNbHJaRCzDRfPC-t>OfVW8(S(qafI!B$uPzWp*PKN$Q7S(n7)xF<~zKVX( z<>3|%74DQWD$g$^Vm5P=mtdW9&Lu}f z9U#xNM=#_2TqvdbcjJn1LD0YJt5yff`+t(o&%z)PLI4p3u_O<@!;tMWYHm3Py;FFx zY;pbdW)%RY=Y>F!T6jz4!a_~)plSpyBw9;C3aNzP{<$miOeZ(W`ooCVWkj zeldBjXi52^4L^79$pescZWAcmhOIXLT4GqsjH;B*g+z`aGlggEcfJ4bJdnjK4CJlV zlh&69j~Zc9>Oh=*wh*#X<2vKh*~&Ij>E%4iS4MRk>~~dpW|`c}K)n3bRBB{1>@s%@ zg>Z>EdXsa+J6@xX-~UeM&6k$%%r4=9VeQX~0IVN$mdICpA)%1#(Jew{5X;j~7g1A= z&kCtUnYml^r3P?w0@E}3}uI)PeVY8L%*`-4$aGmzvgp}-p@8|~eIN0*gi-4p9gHlB*DxvRwSS;6QS$GruyOxj8+WfxLsHqgN{tDV><4tx(|k^OSAl!p2IU3kXq5 zE`}w$s+X*75xgpCdR~^9OSzziDBujyWV4X z4=R*w?&BS0QzL`Q&UrpGJQ6>6++Z}MH3)^q#mMjsGl)dgl(zIb6c;bERdAstTe9iC zFXpz)E5kL`RRNJJX=RkTd?I-j&@w{1()4LWv8w#~w;~=4FvCs=aK>*JX7!=TT-W7e z#?X8=wLvU7sCO&)ucp;-QRgjrTd#EVmc}njem43KLKO-k;LPgj(3Q?#H|2pIhdS*JH049Kwhmxg6SS`9%N8EbWnw%7V z4Q(9UyMcbyyBEIo1K$eydDwfB06>^XPJQYgMt~?JN{ugnHv2LK;-3Bzy&{tch&c4d z@qrt)G#TRyV+CkJ+)!~ih39jj03BCECm>d`GCPtxN z9-VPp#T|tLX+!R+l8%xJrN%cO&3Es{^DC3jZ9PWn9E42p?A?k~AiSmHU(LD$`G^1U zZZ@&AH)i;}oR9t08+-nlIseRDeQwtG&)Z*XUA#<_j)G;>Z_wTFxa9Vgg{2#vqoM0y z*51=Z2qb{JfBX+@NJM#6bsT*AwF(dsW-q*--rJf-=8KyFzQLW?J4z?U8qeLXHMAI+ zY-Xc2$;{>m5cq5W_dc z-h*T@G%6H8WA9;u2u3GanY*YV*A7#1#+%IN3mdhy3rOR$+LyJUK2s${FO z@IauV#e*MyzW1Z?y?^ma#wTU!i-of#g$?P92OQt};jdjV+}@CL?auC-&%Wzt-(b6ExaqeEu6E25}1O-C95sH z(Ad8d13~@RH~TtF6pN#YK!*ZlB~WD*r!yW9E2~NXAlQH0V2YOa+zvu}Ct#6*5XhA| zvxU^POz=ie^Y++1jH*EtfK=E$h!$fLcQhh;2jpmQJK{o@vx8jWSs*F3$WzP;M4kOWNGwvv=O3@D{_TkOl;xb6Z0Tiys$!;)E&O6^x9;xs?yJ39RbVKqEyi1_ z18ys3=HsRg#X8y@w4gp@w-8}N>IkEz;$BNE z`HIaQr8_Gggvq^7Sj!N&^8vuS@3nOzrNlCGDwHc}EsQ_;R0_)hXEeJpeV0aD)^0{SY zkkW#;=6r6I76Os=^RM2YZNLS~`P<_kbfw-{vo{Oh5So20CDtw6;X6%+R;w6ePePzn zVt!?=Z+bx_PCs1)u{`^1(d=m!s3U@R5GHbdRVE!}%gWY-8&nkvM2L44kDd;mG?)yf z0+bqcD2mkG`9@1f@E$t*0Z*&E^O7Gwf^2TPhXD$7r6&&`{F^IN`XH7+`(MuhVDEk+ z6kfi{5TMN5#mh`;(b^5V`;iRr;(5wWMyBxj#F~Yx$pW{(-XZ`Q;P|Z6k>vEQ{_Uu} z7mQ8|-fWr0us*7-FGXiBWY>e8dr1(>e9rVM2~ctLob_C>35Cd^$Hje zua0wAn)Lv{mIW*#Y)zPD?fwJcJ(UZWwAGUR1Xr)Jd*5m=30T0RquE8tR{E^pXZjWI zHYWGZ(R^(BYv#>T;hk@^g~I7&$?qZrMh(S7zwudd>shn46WY={<4x}7V}napjy3-D z(*>`W`LHZA|H0p0?c9ku6s0cmR3OMv(orCQM^g;Vl$mSxbgc#E`9FKZbDnRps9ZI< zK5Oj+QA66oUp!CQRfluRSzWSz-O{mPbubZFXwdSMN{9S8g`;c1^<=L|E${cJ9W_z7AqJADa5)z5YD&yl`s@IK6ULr*?GiiqzNZ zw0|o?0ZNIWApu}MEcK(G>nG3mel%|GUJ513G@(Uczc?&E`g3OA06^GKH%c;v#H6h_ z>y|gbYIc%20GOPWU;ne6EiO2R9s?1Z25@1VG({4M*|F&!giOTS!oAXSGyF7n%aUd# zyRK*F#BHFWWh&0Phvw~XwgKSkv!X7_&B6~qD=t3HxQve*^7gyY;~#W&DCR>`YXT0Q zG#E6oxo0;304h_L&t3m0YVQRAIC`Bk>!LoG0O0o5nsoy5n4>=ktf}&dl@^0LF#){% z)wJ2ylQS+bDi-{s?{^Vld|H&LFEbZ3q$%Cby|}^?EOBmKv!`_^yr=olbPqyg75j2P z!ldsqbHH5@&KgHQZ|*&3sTy;**pJc{UPcpr|D$c<;jP#HszHmu4fp=Bt?QC+V2Ql3 zX5IwYi}C!0P{#lk)P(_ZBpyPONOcSG;N z6h5E1VqpQRgt2^XD>H|w<@%r3I1%-3#k8~zB%(%--vxP=$(mF0?Cwv4JMsG2lytTC z)H{rHC>A55wD8uWKpyS1`kIIsj7vHih?U(y9u`w;GS5*G&7Q8aHM=twRr3GNo>{qpvkl-mD^F+j8>28R~3qO1@TPI9vGHRmr@_CN)zqq}C6yLX zIsPJl)b$=|=Wd*Il_~wYfQS(;6j03V?6N$1)&#M#gC$RIV|=Jk@S!d>N`>jf%Ba`^ zp@g!{yVLkqzD2)!^!;u=+qn4g-p&1aISqxfjk}9lJjn9H8|8uFZaKKC0Z~XOF25>( zz4H#%+%6$)(pFJRNy(ZfnxA^F%H&|Iv|vQmSvviD<(=<7E5mlaWZwYKQh>nPES;Ea zW-7u?>Hp1t^QzGcc=sm{Me4k#eC}jeCe3)gG#6q;%INNgh%mhK!LV!`8cRuu~r~gC0twv9ePimRMXrH zUI777&@-!8P@tNMHKkY8PN$HKW9no^q4D;+Egg#4IeIe72U2zR!XTC^6qECEHY}wQ zwYQEf{L(0$??u(-9en$im;&Oc9i?urs^N!ir?`mZmAMimM`tW9BHSt86Y zO{1 wx)%?8~iB8U5@sj9&8~mO}|4m$vQ_YBt0=6v8wy07$2n!`-d%9H?q?r$X`m zk1uDJr3xf>UqYex&>RF;pXb4neib(>=`ML_4g#t1>Q&a=4~vDHT^3x`n!R9gYRiSM%S~sz4h1hs z6-YjEn*AW3SHL9#3~oom<2>o;tt;6*h?qw`xDyG9vr7|1l68oDPr1DI4ovEsiA+L~ zUb^#-ij(*AH}9v@(=wkroBOkm(rrdQ03dSoZDpo&jV-eN@UZ{Fm%ATg%|`JR1U7t~ zGYZ4l#|IU&d%qq zHi_dWw$W89<1K>Q@3w+i;L>G)kt39qeMYgco!#*AMJkmL63g5(1B=^f#^a8@)@=2I zSHGTxiEQlzEO@Nx3BD#(DIo+h=dnnckx{WBSU(N`Nl(}FYQ~JLp&*ewUF#o3&XUrC zmNPS6zguC!h+s{1A-yG=drpMp9Uy9|>3K0*rp|G`Qfm;t`R&{qU*8cPcq~SS-TJ(x z+wZoj%eef88Y<-*%A1ULFuy9Jmdxjtr>_+$;C_;hjE*EM9g)YUB?=S*JNuzhSmZ9B zS2p$x&8JgS4cLG}&abe!dIJG~(VJrQrWhPWLf}S>7s5ISRpzd4^Z0IZmihXgUpdPV zY-=akH^Wr02)v~v^PbX~yF9TE|EN{ZW;Sq~L^4_Ix+00F`T%F2r^{~K^J~^?Ux;c> zYz?t_Hs6cGXAJ}xy;v1~Pk+=OpKg;=ZhyD=wkX2AXNfI+KC_44XoQI*qQTt=mkkm_ z1J8dp`I0>_>FO`ZIjrv^6A7KA{YOdMlmt*@E}fc_59e_M1A*gLB`><2d$ACe57%O3 zh@jcmOxdeGlBulIiqvH@O8}#jg2k0}ZBXAtQ+TPxVrYU`&aO-l$tob&k_rS$1fb?X z=L;{Th??@8;G(71kBy|G51&;*UHbR?R$(@?sUzFguot~P&EvMJ;o}@}-qWiTb&0b} z!`w-hPu3fYjw@sSY-U~Qqn28ZC2KNo^|Ia)`{tO!oqdpg@;Br6|Mlp@zn=6CL!rYSlGwe=tk0n(Xi?*$ALW@C#2!dSF-!~ERs-PZkm)!mV;u1K09j4)5>?Bo3E zMKL`qckaf+V1UExlV2Ak2rxWWI99H7neC^g1sWcFW43vYwX+Bx~SzD6#u$VZuF50;pCmoIK)Jv3I~LwMNM+6imK zxqlQTJzXqZH7YZe@d8^W6{*{Q+(3l+up~!7SY{46_1Jh6&^rvtR~1p1$hfJBh3_td zEE&K}x;p77R$>Z;QA@G7q4M+qa*WIH$j6hf45un;wk^CVocCl4Zwf!ZG`e}wes42p zOsDGp2>@VN{BFusqdfYHmyO5fZQo#RHp|}3vy;6irp%lxea%*5RAK*d!x?JyHTQ63 z?z!U17k2Ma!oD;$0x-A}Ns0N~5mBAV`5m)Kkiq81h0M0>M6E-cmL(ru3$8=bz`iV{%v(3N*PB0(B(ffvUyo zQX(Rjx$hrEQsH83oT&`3MkjfDCy*Ku(UiWPcJ>aVGIvYE2q<&6<<8SP48QSbJHz8_ z4V+4(tgtq&gDN`u+E@Q5VqMSrh*&CQvp`eO^rGB-kZdU+ZeBbR0fFtGSP#G9JptgY zsxhpvJMX+RUdOg>z0*AVt=ptN-MkJ}VwlVo-^y7$2shcfS1jrmR$o+KA!U& zxb^^KL7ToQD|6@VhLD64(6$uOC@M7BmfqxUc2%MTwna0!TTUuKhe9xuWNp31U48Ls zdGu~eNc{1Cef;9*+41}7=yj1z?bcd@Ww?81Kja;z#&MXOva;)vI3Hc}PbE+xmYEk4 zvzg^mcyJUCk26l;te=uZ^ z#~U( z(Y=Ss_1nGmD{;Gex%#)3CU!UXdo?srGk3OTBwJ1>+>kH?$#pX>qjibETOT&$$wzbc zieegnzNA0%R%4CN7q;17zBPd}lyr1Dw%pY>`nuTd3mcl4$>#opa5td`io+TTU8E!j0gA1&!s48eNwsEF`pj`T( z!C%9?_8+z5OcitIEmyghi!1{?@>KhAur~PRKTaBCXTuOpYm|sj?|3=3dk-8f$8!FHS#g<3_zV#kh zuDsMjlEDP4xeAv>aPjLNL`g^U8f1gl9o*{)K-j&TH`EzMuYGTb3g?%0T?G?F_VvTN zeJ6`jEo(!zd1q-o!vO&s>ok+7jTwWWInp#%1u<}A5zWlYxj%hs&!4;blmOt~dtIqX zp8j;cAxaYMaAy>6()pQ9gtPNfr~2 zlTVf}(+@_8DyD95lptc%Qo_|OmtHt-ai%`{)5~v?OdckHaQQ{?5&#RY34$E|{BN!# zTR?WO>dJQq#zd-|1vyNTX<%T$%cr@l&xTeYd6d;Mpq!!j@VvORAsCAqdnw=Wn0!T` zz{J8#4E`QMH)hYSVnn=rk~bNb!i!mL3$L`BQ@fbCxTSyeAI_A<&hPE$Zx0UN=m4*v z$^K5*MNOiF?Kn9rgX^xPDqk50P~DzLL0A`=zB#SdQ}zS`wk6pm$u4y8cG~Jk-g2=B zo5S|KRB199y{geb-&Q?0J< z4)tKijP^~ZrDMSR@ArB;2_wue?BgFTPd+WA;<^Pd_Q3_RT+qqSs;_@gJpFOGn9|0f zx&Npw>%o?^nAire-oBg35QscGyAap{095zK01&5YopE;jc6VL-?=4TyDrRO6-m)uK z#(zXSIji3Jz3oQ8Bn)e%z~X+gs7a z<6`S5J$|dx9mTNbekIP|vf-6WpI?TV$L^~w0670D-{gkW_E^9$dL zJV@h~HZfMYPdjFIZiUb2Es0=XJlDrB%J=_hw_G|~1cQ{r*E{OdgJn#*T}uzsWq+rE>@jBR#aIZNU(GT4oqB1`(a)*uou3umdn8?)yqQLZ9# zB-O0Yue3pN-*y#wPreHMLb-6kMXvI$B=2Z=n7;8xFR)#cUJox-`kCr|rACWirghC; z`($wE%iVX!-$=-H0I+qZD(2o+B%5}7D-xAu+A*kEY2-$Fj{pQws@j7HVFgsShf$L0 z`DLZ_DqvTxwib^R1^`@6T~kKx+{+eY+a1O8u@wVN(J2e&HM^*oz(h!%d`aXXZkesa zB<*NHuG6;Zj*?by)#)!MF6$Z{p^h+V8&P=lw&N(#k`X|j8E}48=}3XZuPYQ`?AB2h z94Z+OUTsH-zIs+jDl{q}3Mt`Hq5uK4y7Mbtaby=lblNdYAQq5JFuIdQsb)_yl7XE! zpz%h_J=jm=dtGgFI6bSxV@tZ1a_;iUre_T*93CX=p1WDsNP@3YC_ssKBzk)R+J=W| zZ#U5f8v*?KPxBQQ3pY4OqeM+kelhxM3<}{w?v1*hYX$&zo?ZvMR%gH)zqO?eo_(}> z6UlZZM)Dh9zDOj{5CD?FT*QL_x3jB~?P~9lQ3|rQKK&X0k^oj~fa@Sy+A-}xB(g7C zP&o(PDdUdSkL7XXK zb``mbh{|lITzASKA12KG-K1Q2@^I&!ZkTmDUXE=s_gDw0OJ^<^e=W;m?|Cf?DJ;A? z`I}Xwlvee3an?19+I0NUcZbUfeiJ>_69@+7$dmWpJMX>oA)PSj2Z14Qtb&<)WAaXG zVnpKYZ_NZp5Z+?7z_rxD>*!VZotM8#`)*|fU;D%Zae9;|JzJcqo6uGPV+U6(rosxU z+)vM|t)nzb6?wk8CZK4nmU91NxwZ-vAnv z0#}i*s8Nq9gR)Mj?uUb`_l*hUgI{ltj?*YsA^<5SeDS4w_TzGP>TbrUEOew8w=^J9~?t_+a*JY8nhmm)zwHPo}VqAUrdIuCNC$d9=D=5yixQ%Qe z4qIX$Gjlt4Gi7jkRz<0bV#N&Q!W)Ajm>EGS%r6|SCY{%BA3`$J8yw;7yP2pqM92n! zi*tMSX>s{gIX$U1=DkhUkBQWc`N6foPiJL}; zd~3b+N5(w5{?ckwu9 z4g(SqGm_)9TOXjcjqY;dlm=8_OL7&x^)I%y#%k$_*n945#d2y(5hD?)sG!v|fH*y^ z_FipWJ}X>Bwxpz`O{!60RZ_L|?O`-Kuf(m4J$ui^+#!OvYxj2(A)hx)*kIYKZcB%x zpm3Bzb~$m{pm#)`rJG$pI=7Bep=~lTlk6aX2(}>d01V5CEf>xfesLN08r)caLZ~zW z*JB1}*~BOz5<#O;XR}D}Ekh1wNZKZC8wQx3uV`_N0hS;~!agb&Ue`Uqa_mr}E$P+o z4s1cSBOn04-h&JkmJJ-k(CV8;wJMH{^4JRT90OiP>mO-V{2?+2mniv-h=`Sf<-|%! zy*`6U+PXGJC-2x5!M_8T*~4;d8`t^PRwSCl`FVu^Z~eUYN z6F>f^0ui)^B*Wp6x%JsjJ4S5jQQ>+F*#=Q7q+}q7)~pG(e(iULh_G%3^qv29Pbu8M zl8%3+)7^W&9QL4+O7n8oTuW|wImlI)jhp-4+k*_##W|^P=eBOwQS2b{b zvb6eBkO`b=`;aetW6)FTqLI1}mWifN!va>7-%JnV1D!f={>PX3^>ivqkH^1DNYOoM< z%7WXwTIdquue|@LEtB=IevZ=l*qQ`U;qy-xP^SSz8k0etHi|67XFnF`k`mkO44;CVFLj6UTw|KZy%G}l4oN- zzHrCyc1?^X!WW+|mRB@=?k~P{#oX^aXx-S=S)A#SIL&V7|7|}oy`5P0oDcu({QRq2 zR)|Sde=lJQzEKQQz4iV0y}ym$`&-!xbfngkK*XV6PDv9hTlo29CEJ>8%eGu)3SB-e zWQ-d2VGQJytH)&>&Ar+IM)$IE?iN?}s+sXP&d=QCr}CfN9jLo+cjp)Ov+s{hqVB%e zO}o0mH`9)hwc;&LPeT;d;XAF)R>T}4wl`~|de=IBw<}bj`DIniU3(C{{+nASL0~B6 z-dm1SRm@$Lds~sKSS-oBqpN4d=uXPSNlVK{G(1QJa1Tno!p|>ls819y@zzl)v*#C| zER=@j*a~6FSptUcPRz`g&kAvx?(M`(fEvp+Ts}^9)-mEMsx?N5mV%HxJIkn0X{a+6 zLyc4}ytizv5A>@lyrL`FR^%Oz?xyY0W&Ha8E%zM&sCWg;T7rP^DubkpSc=YMlWmV^HZ!TA@(0fDAD9u zt(E40g0T2s7LsWE4qQcKg>O|!?7E5Z>nQB}w&}^-NW=wam5a^zbkhyT_o10zkyw2knr?1+bVp zSygeSO@vKavv<6l*mcP1=*>=ND=PDA8(h-TNn2OBui4{3wYPD1+h~KsgCvR-YLxbG zk_T{pnFaUsCn3t6rqr2JVW4cMRy3LX5b|`J{ zJF|3qb3F|2yQHPP<0#WNg9~5!Y}ft>0-`>FqK>?c%J z<>*1BG+fg%SZ0RBI4GXPj*1+&2T_!2iLO{oY}z(J@$Bb!?NZs2I(zv_LMXyJfc{=0 zYGhk_SCMe0s@x}Sz24=@I+~rAsIk!}lH-O~hzeAMz6wsULD8nehQ$m?TMI|y?cduz z`C{oS{6!LLCL+&7-Z}5Q_e{={Bkvo%o_M?mo-onM5R0y58Fu#bC`O@=DFx+pr8cBB znc*r^)Dsa6-kaOp)aLHt@1iY7Orv)$=ch_=uZ{lO@+@fOG&X9foqMh2*e<88znhpC zy(J_g^sA(!B|S$Qb^2xQN>U1h{wmCfH7|gWg(w*xWxi?Y7c7$$hAdcvN}(Y4CRXB- zj#>#O(!6g3h*S0YZw?Xgqrbd1eE!~lzjO7(eg3!0&;H}$$%o6c&x^_P>gq|+-Hru# z6>-PicYEBB6c9-I0l4NYzFy*s86P6(IGiqW)1z2Ud>T5hY3? zx{^$ycOGOmr|DUB=bf(i3#nG;IR(VN{k(@ddF^%aXzRAY3aG-{2uB$EjCq_d9x;lDra?Blo7M!mAXtrPS%pXl~5 zV&?UnU!`#)@Ca|gQ+tyK< zwvF&!i-nhyqPHE(BP0oiovrxlSs}ZevsA|*ATZd1`nySY6rqMEA1@G5;xeUDSsO?~ zl&UyWh;Z?w=*fd$r!9ZOrYGP; z6x=aFLx|ukW9WF1{EBB0XL|gi5KW>$+rqK;KJ=EdZwFEUH&W9zst&W#sKhYdQhz@^ z`*J}JT*cn9z?WiO5h_SA%r({ufN&YB+v`H(Wf-osYyf~q&Mt?L3mfsm9z9o@D+E46i)34j>RH)2~-Rg$e(8|?J;a7Pb! zbT|b7re}7vZ+4EN;jS?T8y1pD)Ox;cC+K96{E9w&{B}2=ZOY8cg{zi6pSh|gMhP^d zj4Btt+4#2aXID=)d#Z!CI+u@g0N8)jx%ug2f?dpAlqxaqa1}2nHu!=8eD?kE-4D7i zt4!{Hw}%REUVjHdFNg03ZNKL_t)3DQ5E$ zG|_zBeWzP2e6x?uE~_L{ci!o?dd9>`#*C7*xM$;rn?m7w+^wBey zPn|GFNFrZu0DtoE`I3ymR!8mJOLT;`q+;&#nfr(T^W?4H9W_1wa^ir4{f*q3a_RH4 zTc*@_Lrq~4wfmse8Ag+{5Hr#q#PXH~2PxKfO;9kCsLN-$Eyz{uDsB&BTM^dQeu&T- zL}Ck}W5q9tRM#4u<9GgOh)VJ$&DTFH*4O7?FL{~bXMF0alA{E(wuEl2zIGmFCQ|I7 zTKYQRJJ8jcK{h((&}pMNMRO{!zH{94Xvc4Lo5j%GiplfklcE+6hCz5fb*ABYQdTTVDP@#00I(=djcIlJdvX`5d_Yf5OeJ!&6m&0&M1;NS65Qn(Mn_5HFoKREW(~c3LyeONF3*N ze^BpWdg-f|X9Kqek+`Hwow2yG55CoxkM!gxv-1}&hzszg5LjyvMX8caQ^&eHisV^x zB_(aG@S4)1)r+)If>{biU@}z}B-$J%P)5~hO>ptF2zwub(x8nJrM)Y?@G|;)iNtIp z1P}ZT%1)u72Ctr7`$P@R>X-Z~^K$Fe#lf$xj>D+$ z_8u9L=05&#cB@0yE&9QKrOL%MHD%-KLXPvPk6O8oz1Aovjkk357@TwW|AikOVN?E+ zgd8!Gr z=H7dX5_R#I5YW>s?rX7iGqGZTd|Wj{Yx#KysLZw9L*@?>^n0_0b`^_#V=zDgLAz=V zmt|q8tWU;dH4YC_li<()>}vNY8ts|>NVhtw5r8m2G2zK`fANJq`NZCRw$vx3r1Xa%w{?H}L+WcA&Nylt$5ewmHo&ZPM0JqLQ|$a^D_ACRSo~gaG}$ zIL?$U=*fr6ryrJI|6}px-{((0T$T$j8)-B zk@qYdwc&Qx_VX|ztx$YS5lw^Bt-{XyvBA-IwkU4Exb4Y%r2@p z)5>5m_rXt%0TEyO-Vm<`&uyUCPI8Brfj;IcG6{b6{mJ@dZtFNz27mt7SHQtMRgfSl zJfz-YW>?ZWs9h(8t$`uBISY8OpN#Hg^Q%e@h2dd}3dS$W23hl#C#NL?AYyA^5aFzm zen{WznTYGCiV#31Rh_SWVZGynSKFxY;&Cp^NuoJqYMoDg^Hzm!6An!uNPJRZOB2$7 zI88F+x*}UHS8y+O3=BF($!gpv=SFujsnnZx!c{D09P*)-Qzz~`Cc(68ALY+K%G-meocqhK zN?VYLmE?!0I>ELXh+bX?p~SCHVES_D1@G>RVrR)jnAg@hZ~ftx;J+&%A7TIP_UKMJ zeqO%zpABv9Ha_6?qbz9|@nIA*U^L(=^0jju6MynoSGRi42Z7#E(s+lhe^mudul(6# zw*kbodQr{JKtx=3p4O>q^`q`6k}<%=lUynEjzO(%tFSzXm@F%W)zVMTD#>Nq*la_) zJBrEia_W*ypM16i25-qbPCLd`1O&FAxTU2gk#&-EbhGAqyK$=@4rFo+oiF%Y{04H0;A}laO0mBL(&-`|z+dhQGHtQvn0CcTHy$d&lL% z6>~S(OGd}(@Gup{UwatkQ!5peY&%K;TXwhkcqUzaW2hV*z1d-gCqJ3hXI6^|278IB z`QYA$+Q1}gdQ#cKdrMj0OioI%e2Efe3n~`=AOHO+Ill9quD5jY_3d;O(b^xq*{KTh zj>j*q!3THV?rvNP=@I0k6%!_cs^omZM4Nt9aZ8s=FEB^LEaD|Ay`yM!oGF9O za+E3^t5-hg3wKPMe6>MDTwGdmTrPc;dvTL+mTc*FAGD+w(-9U6*WXQA1A_pr;xhNP zpyk9OVv^~sXS`+aNv6mbU+3DWDi<>p5-Z!zR_rYaBT^~MdPZ&vGhZ_{%0#w8()NuLcRCBRWfiX9g-w|y^@jY)Q)*+r!zta9Jmj%&s%x{~vmBj(zQi^y>?v-688 zZfQ{hni#7k4G+`yFaib<`0u^i27vLiQrJSaB5jn8lr6mw3mCwbUQQwbOgmeVoaTZW zzx$tW%hoAF-0pTv#NDk}R(R41f%0rM@lGd2d}kFti{NU82W2q{O*I+_MMD@l?Gdq z*qAAeNu~!!!IvHp(ze!-LWPSfTXV9Y@elzFVKlC!>1ieM0Vx+mnz1nr6OZ9>E%eKJ zrn42H!s%&Md+xB9Wi(C5=uRer|HYN{c2npiW}^4r>&c7GFREV%{V;Ld(h@%@%!_qW zIyrSKgf!Soq}P4%Q@<|#`{kjlrWRRF3s&=;cN@#?T!@irM}PcRm+iaXq=IaM5%*u$ z#jFNKW4ilpFY6k44!z^$q`G=8+OZY=YI*`h{?4zUGD_@+1JA{?E7?1`e3}CUP>(#g zf`0s`=d!45NhX$fFhIkRYTf@ zj+w~&;Og$ZU|eEY6%cp%6Ry3qh?u#5r-%}T3W}LG38I4e<63mlpjUN>V4dZF2pD&l z)zYj*4D#;xCJ?*P8)u6bgD8&a`V@&_a|k3G)A8Hg<;2>YI-|&yth74+sw8rzrF4wm zvNlRb=n8+Wn&Fj_LMoElCpff=d}D6!9oxbuZGBzl!%W~D0f2L~k-3h5-gAF1L50hS zMFv!0VoY1=_y6bPC;vFzJC1e^OmC>8Sc0=)^uRPzg=armUVc?3Epz@=F1E7dff+7e zRHu*amp{nQJ}EYb(i**Gt;MLDw~kX;Em8_!J}W?l*^##--K;X0&wXGE#!4v!W)rE& zX{96dmWjBWJCi6Ksm^x9#8=M>F~aA1_eVr-qQMYNqT@_~L=Ng6ssT|Er}U)q?Q-9n7NmE1}hC|TMf2#e@puX=cjJ* z%obyJ_ZY$xlGMrX^{<4&UfB%ku7fz1c-2@Dm~gXpe*P zXam1WGM#p`ID&_5gaBWnVBPo*SAxl6nl+hXQMchY8TBM(v5F{tq5vxNWv&T>BWb=V>d57MNqQQ_s& zB2=8B`X`>P?T02-t)5W|^Qj%($)0{Zm;O!Y^oR(IK!9SMfD)1&X7Vz_AHOI?W9}`9 zI~5?j^ZTR4*fPOJAi&!EGz{lubR>QmQKFXd5opAdxhpbq@jd;5|z| znhfW(!R6QjLvUcRL=HwrsUWAb%SsM7@|<>!(jawz!yJs$0N={oB20!{$R9)mZv&@N zgrA7l8mhqWt7(9ekORzq4S$i5USl^C=vR&#?ouuB2s2^Kf-Mm_9v-Is-Q>wnX5xiZ zlggtN?Lq>NYCtVcHEPfrzxvVimV#$Ly?Bx*9c^OOd=Ocd8!q+Ape?+7gy=@5xY8IW znu*04>19Nc?MInRR@n2!lU$&y=5H65bo_2hI;&z#So?XIND=Y;+zJa!7$O^>dBai? zX+{uh5285Jho`LQ z*{OHl>;l3^e{pg6S||Qs`016C{5xAvlqf{B1&J8KmelM&Vmn2iCnu#?={2p*2E^0=jT7yV|}W0&Zh(nd{QltME|m(|MAiaGFLB%+CF+@fB_OlCGlD&&t!!Un=0*eH8U}lF3Qs9mQ(|%(Sh^ z0}7wranjQ3*tf!9)7e~#&L9>lkT$3^OwTG;U87$)OQ_H;>G?ak=!1OS}6Z3kKc`XA6=wsZ>CL%cVnwLJOFjmeO1YFRGG~wn;mN8Lpm{RpGtk z-Fq#W+OFReA$E}Gq-Bz};oA9beqM=wQ)VzIb^%t}D;7PtE$H~o?&)VsA=A{kkl{>e zAX?GKDTBj17kpB_C#y0l&rM*c1cm9yblI{ z(iFA&W^rYObXB9JVniF@Y&n~3=?`9O2bGBpR#Ot`;4Pa7Wvz`Ky+ZY;M(#~Cn^C3%X|j`kIk4<>r#Ss7u#g)DHevb(Nfsuu_PnIQ3Na|$04 zv1*2S?ST<3AyY`3(UH1(lIukEwqr4!XjBG4X;Lmc5m&i?^5OF2XTKQl80;k*N4(_S zx{7SU-}=`>anqPz*f0L>mLHh)jG#0B^#7cRPlv0#G^oBJlc=qSDFAeKqpidA;8EKc z6mJd@U86>6sJJOUS|RsMr1j#@C*Zee5M(rGOFDeBvm9H&BLJXUhG%je9?E(~X>1(w z+QV3G?Zwlg39_j@~)*p7js8y8g*HvwELfE|mhQt@ zwwp(NxBYI>+tn{VqBW{;BG$8FQgHgkQf5c182E~w{XM?*->9soikTG|j;Qv?F#{BH zFP_9rpd`ptpTLRi`A%jcBw|9Rlp5aUi^ta_giM@tw26Ww6BR^>){&C5SMQiTt(fWv zlhZQzivyAe?`Zw34GzbSLi7Uy)b3Z4lTv`{_AttNdU{%J$cO;o&HqY++BoQI6C?+~ zFnR;`-&4+cCh(q#*n1*?5F1#_1%sV?U3i-gwMUYHg;nmA!o`JI;Z;E;5?-&K57t!P zEwXbRRJbCyyf@o=>rzK}^=V6K<*a4kc;xDYL;wZ{SKM&An3)6~f_&zZwuv%@3Z8v( zJ}aK02^UsJh=9w9D;9o@m=DYV3S|3++It&oPyOh+Ku_qn<-+&2W092BoUm{VtZ`}> z)><{CKVJE>D(v3x>^^K=d{Ibo-|DE*p4mN)c8;RXz%YPPIDTHFu{wCYRpzcd z_wy&!#izyjC;8Rag-H%ScSSk&*eLLqfrxZw#N44~wQOwMv9nnLT}KcOSNNq$Ve&xGzmkN|UHCm?{Yo78lj>#69}% z@Z&$e!~m-T;5Q)s;2m`L;(PD+ltJ-(@{R-+S6Y>&KY#8f=YGRkS-!Wo9dAr8!bbY2 zefs%Q*tnzP^zvCDT@Wye?XFa50Gmea-QC2*s@dUX-P(e>8?XNIsa}{aTK0~l^ITUT zZhF|(wov3*lxt0)+}nQVJcuQ1 zG;F*E$@7{o*!AQr3VpcjpPj7;HBL@S0JH^({SyErEz{)QNG0lBz3cjL{QM?fuD#?s8N*hIb|>gcWRa%ykxMKT!@v1-~iS=S^jZ6ZaU zr_U+?xcfm*%BPc`txSmb-)@UlbK2A0ov66shus-P08lO|>1bvU_ho@)5kQ)>S3Vdl zuk1SPwb}{aX-gT?-HEpzqz(6~c)4emR6%0CSuFhGeD#)+w&{#wKyale&!=DJOsvgn zKuaE+C2!dkB*I?rNS=D{H$&@$i)t$>mp*Rk_1d+w9VaavC5n6y)#g*z9vW$Dd!kWd z*nhQcQY91U_EtoWmlGQ$Xd+cDeVplH=9)O<*?F}RXfsSs%GpIFhM2YA|1EQ9X}OEJ zE0?sKTD$bFdKo|})K};p#0t@szFhb!Cj|D6yIXNk7^%R}6wB?)Cq*^$#ntUSMbz7@ zIgj4xWIe+Kfzr#+-A(`@>l(2mbQLYeRy0034&J-%VbmT(3Ng-<4DArX#F(}X0FY&= zQWj^oH;+Vc_(msgX%i`J@Z&$5bo+X=Z+4HO?kLhmRX2JfTXHdBF(v^L{Ief2$2-+y&E=``<4Fv!I^!H;Xn61q-hC8~IsOeKXeo@tC)9fwfGv`YH zz~NycoaJKXH*;wa0Ac5~wAC}@!Isn>#>Ld5Mic9^FZ1qpEP-I;85rj0l`Ba!XoB@K zLwjJD`0R_^SEM5qw{+HzqzuF8Ftledf-#e7iKy|Z-ntV~+ED!dm1go<2A{oPoC zL`D8Kx|1S8l!U0aX0)IqCD%rHpxzN8OwKC#A+GeoM+tC@V`oX)J)v%im<|BiTagUn zi8$?=$%$ZEaMXDLGQ}nMEDwSIS^M^YS2Qjjevv-HOA` z%qtnPbHc$7ii#@tk|bUget3}DinK-qxO!2{udEz@Nk>Z)AwD)HQow);l~L?P9S_X% zsG^gGh(O1Ri0cGHL6Lxo%ehlVi3z4q5tlR9?nhbQGz_xYSvA;C0pRL+DaWYNfQVum zSmquSXrsI%@qjAk?(~agYY>G`YU%2Ek+yUQYV%y>B!Ih6*99a+6l-Y|*Ac+ArrBH0 zr*=8Evvd3P4~k;)OF3cncCH=mum0MAJ(~#Um$q6`cRQBWWBlTFjAQpfOVF;1C;86( zR%gqMUzGK*ksFHd`~Q0P^B+tALB|Rarst(dyM%<*+l`|bmBCiu7$FWYOioIwEfQ@( zx+eP0FDo(7i4wJ#xRCP0Obi=gRozh}Q_ZGU9vvm}!{--Oa1E%-JIS8gx!2OMlAj|J zGZ8Xu$hoz_IMsHI<=Y*_FT28W=r+}JLkH;ZB&a|vsG13aV|Mm^_zr?=6XsK!Y5S=d7(|{}K!KRzH&XWLA|zwRNngYu*j= z1Cy3k8U@&5hVFI@T*q6uz)}`%aCnC(tB7T5zNTeBVCME#yqvhTj+$LX!-G`N;?Z#$ zCHl)BPL)PGySCW2j@8LW{zhk8o7ked_Z|JpZy6oc&QtOsh#{a?0WKn19~*P${#-cT zp}|vFEmXt3s>xUNKe!5V7{0ee1*;fdfb8B3uxRftmB#5O33-}~uZHg~%5%M**t>$? z#AKdebd=7|t%;S1RFY|Vu1h}QI(S&9Y8!eeL9i6!x*2LvuP}(O$r3`)pVzgK9~`8B*d9baUwzxd4+df{vVoZ>1&42Tv;w7Jere-Gz546J<)zgc zjX@2d2<+Hz@0-0l(cW>ib7;(3FcT^?ks94eFP`MUXbZodRAV%pix=K94 z!$*DPgMqEQPzL4~l`AQ5(RUJYKXI0L4Y4iezCDaYlCv0FaWAq3DGgcI4EK{bR!OF- zh0KN2VB2*1YWso7x+YFlJ`Ji9LGEN8z|7U$KmPt)hF90&fER~aYtTe`%-ryL|s^0GaQBr;FpQ}d}8Yn5ru0hF^W%JgY%vsfpfhU}QE zr?o+46nVOQQfMvyjKTwgMk1sP_IDE02#BLQ=|#=FsB+)gibBL5vD7`yj!cfpLvK5t zoK_}QNv7r0mP`Xg=O_Fpl!%~=bOm8OvhM)e$h5Qdn zqriblTQ}|mCJsp;>(BmX&}8kq*WXF%=eiK9X%i`OeDS0RMzajw@#3nI=Y6oBCB&)JkV>8#cX(x#u!Oy3 z6)C&)%LRS;{ru}6Foovb7*#tqOD!i?&|i?Fmcv1y^&bGfRX@5OY_UhJ5pM0-%W2Cq6^R| zKG}EP>7s(9t)o<-f=1tT{7y%j&#SLj9q+ww^-#h2*ZKW#_mx8O+`vqs?h*})v=GFz zi%M*g!%Aj&@w0hnJDQ!{fQAtOp??s&GB2Ez<>aV5@+;Rzyy;MPc4A_7mIO{RF`7tu=P#cYQKrS~%3HpCR#?fovWyI_B5^?iz~#h| zXH@7d4fc`-IhtKmRZcQ|YITj$(CSAr%W);0ez6o>EF}3>WGj+0S5l9egS&!`lw_&Z zA6AL}rneo-eU$JYiAAakvIU`nM)E8*p4hZA^YPo=raBt#r_u}#_7em+|9a6}BGDF* zBeEUvyW@WtY~rC0HlqovQ}yIWpDljYcD{(CZe&(D17>e==QsXAYAOJjo>x(&ipZemMP1{oku zbeP1$krf24a(rN zkLSgNhlh!XY_Fb%h4uX7yqG!iTuwcB=xjwwV-#xuxchEb&?_&GlazW#Y43i#eK+fD zMMR)9GQs$H3ANr>X>8ZD^Y&IO1v)caJ}HQRh^vJU;ALI#c}uut7^U?S5d1UX^pNT z0IZh&>UrVH%_Di|p}9#f;l^KzdGC=n8pweU5rMVG6?yr!*2@MAOC)%`!=*q2Ex&i$4o(4}po6pEsd zU2y)EMVt0b137ueRqo?V=TjHA^p`)Jx{^da%>+kpc2VKvv~(2}lklYI2(ym9_g+uO z$|OoAOIOcJ6Db`jVkXDzc=p5sz}*kJFF8zgJ)U&3N*p0)SV4cW}#ioH=Rh)6W-+EBDnurXg>(3n3SKOQ<2~=!T3S3@oM9 z@Gupo)#S9qz`(-xATn{FTZ;XM(zyRhOBw_AEE!eA5c1I^&H_Oj6c+P(N4EiwO1Na& z4Zfn|7o|38c$CU95og*&s+rkH+0C9^wMt6zj>(ZNX#Y{v(5Ss56XW!(+Br1CT^%L3 zoYQ;%g>~{iIiGgwmE0`_AV5506r2NZUH; zser3Out}2HI50%9nw;6&4t-#PDklU;GA-Rcc^2*7;rs0kWq@pz-R%egT}9oU7!Y<} zy_V)SdL`8cmlG?xAtsofRa&F1NKVpxYO8{>p4ono-A<_ANd&6Ce4JMWjW7JVYEpUu zi51!aV#J}dT8PmB>lBl&9^K6(`nJk_Rge(1s={v=jEIR96R_uM%>rVbVC(p%P6ooG(3ZM{IY4u=sN3qs8J}qzRUe_OF zSjR^=Y{M&*q$mrR`(Cnjm{x_aa&L3`;lDeDRl6PoLm5>yURK zTGrGmtWjNGiR~#BbNAre{fkfY$+NPY`SpQYdrJ#xNG1&pLw1$+xEpmwF)&}#AJiW@ z?kJNe@7Y%*5ynFM>hH(FImmJ`bsN0{B6Rm+*)whKw~n)_ARQ@N_>)hU{k=pRWCBTa zot~8>yEHLstP0-~0=^~5kFy1F?HMP0nZ?*vxtB4Lj25Kraur>@CD=J5D~;+F6)`JV`TGpmKI|-Ju96hZ^>4~1XM2x5huEmyraQ> zIy^|5#T>UJa~vi0TmC$0X{7>(U1^M3i?g4PZW$cj@UA8H)`c$By1DhC2jBgj=^Ov% z2Wi(h%aTVFXS&S2sezc~#3_w|_gBX_h=v9jCMP!dqyVsohB7?6sAP<>oH~I`oA4rF zUQV1ilpVj>m88O8nTY@hL@>IO39c$Vg{uPTNhu6B%dvN)Qw0F|%rgVC6zwco>QLth zk>lE$fF+kuDnPk|Cc;|d0*wX1)w6PRH}j68L<2+I(p!gV);Fy|B)L)ykWcOGqC$mn zroAU;sXZ_f1Kp6CW$s0ufayRq!~?9IFH_0~%|5ragD27pih(-;6+{YU`m&;L`nY zgeX#xh#<}^ zat{_$D;C-^Kb)MFgZ-qpo6Ik*)&YlNg5|_Y2wkIX9EkL(uCTkKSR@a&pa$obea(A7 z#Jz`Y9VszenVnZkD+F{mXzHDR|{v97#)R;)W8iNQ8`b_I^^;s4Lsn>1OL9p{1WXSmaw;=LDhMov{(bD;nb zqC`<9k|M;OtYt=-tj&6(b^o8<^r{!#i(bgAH@$0S6>}4Vi=T-^sCQT z^2k-WA528&0)V*j(%<;J@pA`$e)QHOjZLT_YzLqyQ!=GN=rXizMjY}VnXOOVq= zbHjV3KepFkG79r&ZBgb1+62=IrLPG;-}@7#6rTR#t%If~|5BPp=rAhcD-ZW}x<^E9 zamT;_=|O1|J(xzQkvz*Vxm@5i?p4>gT=82F5aO*I5z3kF5VX<5g``?6zls>ZdpCUK zL3xHQ2a$aXVC_BWNpUvXi@6nuX$x8hhd-s-xG0HB=PUP?4G1g5aJUc?6Vk6_&o?*h zOBA|>ZLBs5px`X86n4QS;n_*F@IfYr2?C}gv)CvKAAN76^v!tkj)&jMNMZiEp1hMN zh38)z#jsg6A;MrM76S`e9^JSbTLUBJV7Sm!Bxfyq))qy31pwqAN>#b`N?|^8`Meo! zM@gnp!`{0+v91tRm-kE!Ng$wj&;r1x-`|vH8#LEJOhmT4*yaBb@_k!X&ue!7&1lkN`_AAZ~yD`jbT zPM_rr>}q0h9m1;{F+09_7jDoBHdZcdKT4Isy6{hbc+(}PL(szf!f-dfQjPt#AMDcJFo=l&VAHSa+VWQ@4|r1rlPR%B?QPk#Z%nMT z5ehnbM^)|@XCczQGcc0cG#Q$1A{yA4#4^MaQ*fc9pT8*DuNiEZHn(wYlu48o(NlyszL`Toa)YUPJJF(AY}gBp|uG1x-Hv~N3Nmr(jaP@ne6-G8^2&ztMl91wB) zQAz}>^Lj2cb7tW+$g6b`e!ijJI7$b0e3&SM2-ggZWVkAshBA51hIVq8Y)bReffnFK z&P^F{Klp5rFP!|nYgonu+NjZf+_CYY)wXy?tMj^}m3nujAG{XpwyChzpcP6*L7wxO z^NvQlQ9f&IqKw7nT5%}8Md9EJ@jfnKYU!3~(^>=L=FQXM^w?dz@nz03Co7lE*Ho{4 zHTTOm^{bz+U;lh9dQwEbcwSyUtGdORul!==E?-tV57Vmy8bK5a*d;fsYdf$^_`61yaqrn!M-j2dTsh+@S;5GEt`5g@IK;?p6$_HaCAaSOE|) zv&7?~!fe|zfjB$}hqqdLC3Kz}#^=Oh^(n3>o3-@jzl<{@Dnj27BHCDWWqfa9i9moY z69um5$#3$bPX<-)O{9cgo(@c%d-5=xTJfNG`HPikjR8R%JeatBZcu6LDm|ru8m?AX zb{6uy-F6a_`KuU>yN0UV-v~Xwj&|`4uI~6C=}qh=5pVP7@>S{Ho@stVKe+uM&90`|-d)zZO+$&{~HAW>i@5BVEEdsfND zBWa}B#LD3%u+9xO83Vlc&&MWGOt3hqZUfoTPzQ~bXYV-fnR4O!`!?yDK+CGB4R*K^ z{q_%Rlq&DoRg{fvv1p)etj=E+>A;92P}bh%@um+WDHYV9RqmV03&Gz;p-~dac`aAl zkj5wfiXLXB3_qqHe$J!|s0Tb$NR zJUgzW2w?(p*GP*J=;SIo{Gc~`U3KTaHdP%Tv%eilB&B$40pR%;ckFf9q`r-y zG81kTMWHW#coO%taP;J2ilji9pf1-2eH|R8s7+=^g~DOf7DRt0OHph$$@Ai*_6>_u zn8-QFaS-bUVB@u3@T$93*H)*i!Es!y0<05Efv``*~bnQX}59V_&>d|99Us)Pb|4$aP?neLl7 zMeq3HjXOPd^K)O9+y*4`b&*|!8=Jz>M+5KJSS1(tv;TG!NFTZH4V1jNiI8drfMjB} z?!^KP{`>#s>E4r`Y*pFNxQbjIhyzKcw;!ZG|MPQ6a*=FK>0QPDOewUP{`gO(y-B34 zk_q$0%Tg8)6E_7(P>B3ZxpZ6m342~$)?M5Wd#+Z#TKnz`9)8dlmx1MF(`kR!vj!OE zZz^aTX<=Xi^W||_uAOLnWO@d7B&9;!)7q*i(ZUf6?bF-!gEB1#$kchHwNU0~kt>-NDD&_Nlz63Troh6MmS4^yR4^pf== zP9`}b2>V7`b*&X)AkXQ@DuqYi25m(!#jA@ZSjl>(UNDA8$_>XH z1XLQQ_tR@9C6Dw5c9V>$`ej(iNYtyiUk2HR*u4wxmM2*Hm7xpJMxxpt_GC6`3 z)|HAc-OFu+Ol@k3LI61bLSIQluFSFk5!1ckAIrq)$RlETArL!7hfA4zFJ6wyQ!Nav z_y0&URM5Q=fQN85x9=y_+5pZYj zs|rET8(5)CN(KH9Bk;{SAn4iJ;PN1IC%(epLgC@TK1#GQ=pCB~qgch67RQ<0hbbx) z8}Dn=EzfqS^I6lD5egVCUY26yPo8J5s>Mky_iJlEzI|qjH0& zKxT<;fx_d%q|U!7fYnLhg^HC9j5e6`bpI_eVe;>VTn!MY>7)JFCMr&qGOAUXaqtdT zfCwEMR4G&jwNYIaC{>rBmcwa;8kI)TBP>p9G4GVonBU+>2s_wDN|-O_0zonmvC(0Y z#KcWa9S2#C<~Y%aP|TgAQp)I0Opc|8xj3!{JNC};ekX$>f=zL;c%Ym<&53#XAT_bF zv0~!aU#vRRMz+$?UL@tUY?ZDd_6+UnRT=^DhSDDuCVg!z#+jbpPwSExfCvDgE(0I! z-pBo5#ai=VYTx{3Exrm2+G&Fu!JtgQi^POGWSl$6m{y&wuY{$%`o*$8RO4;EbI*MDzuOw^#V>xcS|7Xe)Rz~2 z@w_h1++a5{u_DL1RpT}_&CcEFv0Kflob!Xv2B@$uebP5#0V|A{ZZsuko!tq3@P2=B zRvW9NEWS=MiV$!;Yiy(#u()g{`|GlT zY)8TQ>-yf84vpMy8E(%`Dmk)6UE7qz1lg8t3ZD$_XzF@9HsI+D7cYzARv?$yqT?;) zV8B5fuTE+Jh=xi>_~6q)v2anUFOSQ7-sJN}91L!fDPoQbeH4&{RI) z!W-0_Pd63KPRh|f(jlcaa>r>2k1 z-aDDL`09&wQ~1sGCprmnUe{J>gY_*ow`^5Ak24b~KolrP%)joC!EO@kTCIYlJyvU1 zm!u=X%rPEm0HB)FsRl&yfh$y(e)*=_tQN+P;^5pQQIFsdL&S)Ntod2*B}1&j0A#7ZnLKw+?f z(V#REgV^DVk(T7YOA@p^Z?d@w{w0mJt4SdWle$_{+}8*gXGX#?Me8kF>*~@CrjeK2 zj97_<*3P5M#Hz|2wv_z&n;L*IFn`_TC@EJ?3;_kx)S|-`fU;t24}#Ts-P^KP=Hm^i zC_(UGESd8r5D=L-RK1?_Sb1&)eSe|Z7Yt*+0baK$a6L{fBEl@ z@BGzxYh_0c00!>_7WZg3Muk=G03hCSO1pGug5h_4O}6PhyPBg!y9)c;A?W(-tAdFo z2;7H!bWhh^Ja-U~P zDpcqju5${FL3f@>y+OCkP!#mXHty@r1*Us0(t#29&o{I@uVqzpqplO&^y>WU;Kk9t zmJl2!YI97Gh}d5x4sz>*CCHf`HtDz)3&8cf5rG2(EMLH;i8}{82oZ7kut7iuP9Ls< z9KFTJw!d|$4C+X&PhzCvlvYItX-&DC*7QG`e zS5_u4x&wKJuMkP@$^{G-?_IIjPB=sF*>xu4gIH)I#;Rn{Zc6f@d=MIU9huyeQn(lZ zQKJ6i|Ni{V=Q#ij_U!#n2TJ2F|Lpv3zWTQY0H8H`$N8n(d#|Sue9e=`$^GvQe(Qs^ z^B`3!L<%y2jn$P@N8=TU+1f~njK5lYlLTs~%tpkWasIkO1aV0OgluH8k!ec0|H)8P zFy8UfD!WfB(~gRI%0C|M35OmGsTaU#*(l+f?Xj!P!0Tn`EHH z`&JKBcO~T%w6PN5%=~pFsz4cr+eG_@e*OQ=FQ1ne&q@Gz|NCRPbiJ`j2F6JG4C2MB zQYrKe$^78OkC(!q`tHBkRT|H4@!-aHWd({UsQ`Q@pXc4Z{_y(~-1s^8q<=#NCbj7J zFi~2i*F_eGANGwwQDiHF>sb>l@bLP)v;8Abf|PVNQ6^SZLCL^`)r%nW^L){4Vy|x< zBB-Ec2vR``+@-Ivu@^UisHdBP#Jw94#{03-_)0qPR-GC)PXT(9iy# zGts|?lo^FmL$5EJho23!!Of3%)2m0}_#ig1y21qzw8gq4V^mZ6@nKx9Tt0Kpe!S2| z$wsIYB4ReO5(pC=FY?@#(W-e2{GZzujG4wPcpPcYEc^W6L^kO3wt!;K6%6 z(W*#BmAs>rE2}s4`4{EWzgqw52g{CXcO!ss1EfYou!$B}c6m{2tHy`P@~l~$*0^Dz zwedO-9CJDVtD&wT58Ia`DUS0uJ{xG!C>?w}Km`}qv&NWt>nPR+XkE>C@3 z@`kiC70^7+Bws0bB+2u*{UEE>SJ`lfANC|MO&Qb%jlH2mkA*m_49_zNfO6sQa}W>($9IM()%~%(LFl_;-!vpCZ|OjSX+R*7 z`O9kWNoHe>3dlj1NVxxDPql4K0NRMF;%dN_PPC4ciBQZvgFu79RV3;#ae|9`Mq5?h zm1VK}UM8?OF+Xqfyh6#B;$WoGo__G@;Kp22)XIX~iL@#i8&M%hs?^1Cxw>c;Zz{1C zy+M1~So1fNd^i7QGb+@?O7dr={BSiZgCcg5eyLphZ~ymOai)hmu{7ar><@kZmlx89 z%ba*}Pi%Ao%n_1&8D_7l%j2?h{t{Q#tIuDg2i=qgIIiPU_<7Wv5^Y%#NqmAYXuxWcrcB`$A*dJdHk9| zzl?vbf{t2ka#K-Vkj)ez#A97ANT95!uUijzY6@x!k}Tb>eAs_KGm#R3c`#s@^cS-RflBTS}c}aMO%BZGAQ;qOhC;2vDH?&I@ICShDS3Z zY~N2s$zB(}DMFy9(2#|$5x#X$c!4s?##%Ch>%yB@-TSaFoW6&j4FxOMe>VdFPwYMS z#&)<9)dgXz!Mtp-P9omgi%q0_LmV7hm5CI9SdWEitK>O!%R{<`y?0VXIR0X_p$605 zu}QAv?bD;gMhFaXs?&i1#4>kimNzT>@4hS-(Km8xzQQ6@fNNObJ}+FJG2K zY+|JhHYK;mEXRH0YFeDtQDzV!N)-TWjiT|Nzo}%y7g49Li3y@i8G}qHsmjc3V{Ky9 zIv_DBJbzj4Kj}q@0swL(IIN_Igk-O9E`w-M2NPT6z6*=&_+^3j@u;~eVRnE596_X z(X=`_mi@ew?6``g-{9rU&rbct8^4-UvAz~?ga~npQH*85r^n81AP%Sj5tnDp@~ja` zg;ahgf4??_gY6*Wx=koGJvBZ`j70!W`ue?pI@TH|2l3=6v56A(wM1;%RR8iXE`~di z5bT*@aauE9HL*&8@Y{u)DkL91yoAkbi_5dRXp`MT$d0447y0_4F(GUcE?yQUQa0ANS;UfUDTc?Le$c)B z3`++FaC7$z=TO?xvaYlqfnSiw8N&qUFa99_*28aK%L<(wCZpY0&bhd!B|^A2{w+_q z9XXwZjcK?SD;1P4CM`t3)p@gde{Fs{+KZx8Y0I*Zgq_i4aF8R{koUZaACc$Dz0}pA z6p&#BaG<2-^JXxKl)6?@AYy+KC4Fro_0``k0N~T_ZwpDPT>8nqMBYyJg3S?G=T$lRsKl>k0@)-r>_C!qNodW=3 zvA}9Etd2PiV7GE(Rc~ywp{a91c?5FYz=v9bnLtQ@T4PWPKB&dBqc~B_Jp9(#aF2XL zz;O0AVjIB+|HLPKHGAdbk?XF^?q`(Go4t2>O-;<4^tJa~ubt5EwZUrbWv@qzn+2cr zT^j}{SFX&m!?f~{jo;dM0JiU^-Q2P+{1reax+N9L`p!$ME@}61W-R)e20QWURdeyQ z1b`3zc&aTb1#i<2iX)?>|Cl5I3P+y}F1{>#cM;(AMpWYddp+?t75SBbt=$ui8(a?r zY^qQ$ixqU(+!)BSOs-I2UHJ8^Ne0HoswwI8t0Em30N#F>mg|t^+7XG%mAm(0KT7no zznud>xpLXa$~tF;q;JZ#n;a%O!YI*I;p3i?;>Or8cz^T7Ivr>sp@@#MF1)tL%r?=h zi$)xjI%cjm`1ubmW>2fr&xOp6RkM3gcX^N#a2scLdR39+Hq zIZn5&fzk;;OuEJ+b}l1VK~*_v9}wB-o%<%AwpeHdEw-}?tQm!B6az?l0hN@ zJpH@53@vV3B;4faX%we(V2*o6SgVM*wHqTKFnkj(EF#J|)zpN5y@@5_^A`mmbPnY= z^eL#o)!xQRW_NYzlYtRj{+EAo5i~3ft1HMMuoV#Y-Cof zH1;RfShXosynV%h`QZKjjUHGwocDi!Tr8Z7WZTR>CJ%_{8X9az-I*dVsN~11)|z*G zkl0OJtUbFWD^LP7kAJmdmVOdIp&+f2!3qE-(cV!y3X_#;O}wE`WshqXzsE`@lE67%|HUDxYeW!18d$O;$Rv@i4rWh z<%4JQ*JZWxHxhe9g+wh(Fo;Ib_%!Yef-N6@P_2sQ8qFr(Msd$tkxQ|RwDhIy{=58 z%C#4hS-I)y&`Q$;2r{xd`fgtc$oIcDNJj=Z#E{8;a{BB1O0+e$L~#3&6b!mvQ&Zi2 zWKQp=GR2fi=0?7-5bIn`{q0B_b^FpuBK-WMTAkPPH^1E@xO4aKY}&D9;Wecn?nS~G z3I2e6Wnv}1gu$Y#^sCdRD`^G?R*rH>*c7N`)89QFTq|`R|ISETHQ2YC=#>mJx?hR< zD(Y#eG2*_-wv2=u2;!hMrXy>txM89)s@~8&jP{Z^(?ndZorzUd5)-&mgqh3?ajLo9 z#N>m0C{lyX)?|nRh%t zt)(BAK(@={O6c3#gwTL4=UqVXY-G}*g*HJ_#+l?9kb$o(canjby{TM7%3z#nU|yf8 z`uwJYd(_Y2n@N=-(@%OzTdZ@htzuSn>6usxQCHLAtjb0mO^GCD*```-XKkdSL{+&E zr2#cIg?A0fp-(Nk?HZOAEeLFgeNCuv`$1Z-y)mT{_^0DXE%mI!$=a_HpF zCdzw~al5Ph;;EQ&Lk=wq?f$v9b8-^Htn4N`YwmFJ6>3(E>Rm zqEfi~IID6m>?gTEVg|{c*O!gbLG@a#{qnpX?nbWSeC|SwAcsq{NrOuI8j%s<@>S_w z$O1F5%IBiRgiaG7ns!mW%G{VduPz!?f_zPVt1 zE!%J}##;yAXg4;IQbx%QzBU^D#y?`^cm-hHOQZo%8YT8Zn>&oXuA`Gzw|n<-mi7%Q zJbRXRrG_Z5>VlT%4PUcC;V9LB=!xZSHWi(HRZt5F`-bJg-ZU^qz~0#U#tTo18Fn6J zVsuTOlfI678Wo;?m2Y-6lfy)meR59rr*VGSkPjm5fISV(4L(|6&jtuwNuDcgm%E{l&VKnqQqvkG^+PW_9DIza8rDd@c|b6A9@(_(Qa2SSTbcIm*(> ziX6>Ps!A|ig#fU4qxm`ki-QaZcfVJb%YcI0K`ulIX4a!J+qo2QVg6#kEkM@auTkOq ze~2ePbDizv;GkTd)sv&7E_~863>d|#si`i!7@yBiDr42&J6Y%NAe;pvz8Z#y?+_+k z#$qNn0h^{nY_S?R!k_Gf3p1K)m<3P0j)o>n?m zfFNK;wRZQvGgKOur}g+K`Szdgy!j%(qh{SOz}kB!LydJoLi7M;n<(CxDofGJ#6|1R z!o;h~W_4bR9*v2smG_>-yRFKpE_@U#nEAl+pjyh4pqwkLLOD7%Ra5rXR9jWDc&CIjcB_jBS0HKo}L_>84OoMRm zyZxI_$DV!kJ0n+9u%vBKd)M%jKipDEj$|g{s-UgIczIqox!(k#4&Lia-I<>^EsqKx ze0vB0U;O9Gt^Gt>B|(rvM4~429(BdDGoP=hsaXOC#CkJ6?h zrLbJO$}6zgj0 zQrHo3a+HV%svHD@@{{8zQ-~O)N{p-De3>)7^@_=Ud!td2ss7|BsS7GrP8;0XPXtO6 zk}o;#Pi)t7O4^+;&Nc@*r_YP)16bU7m;r)K)Ye{HhS(6$kpcu)(Qqd^{Gc!8rd-By z<>EA`#Wy2y+W5!|6WfXlcR49jK$}F zy##=`Z#G@7Y)@bD$Qp7DSMxyjUoZUWD<`OjG6;yByO6lHQ|oQNJZrWerXo+i)3ibM znK0F7XbSQ*FW%H!hp|nS2-&)gZuk9O7v5y7TqtISO=K+{8*RjE8GJ*oq4h;0nGZr# zsS6JZQ6V`#{`pN-!svd~nTs*O;$=M?>*>B3@8~28vq2q&4}2R#VPdgo65C)Cqj#($ zmCu}H!v#+LZ3yNqYw~NLA8A137RXRUYXk~qh6pn!_hMI(;AMi>xSDn!XHlY?R{6XC zBtwL{3=eNrc=BK@)`dd_N<*^&U|oH3?mpWcA5m+RmRq#f^i8GYFqlSR4=28OaT8}T zkt!DM_N$TSDktG8x;3m$8*Na4BvG`jXIC29wJc-qtm~LOi>a%tcz#+l18S%XTAWtJ zqG?J}f~p&kUS_ltMX5yG!uqs1{H*usf3+iugvtF>-H)9HiyOE@Y-0-Lg zVX2J0(H$l7^sy0l&W=@m8l|DQWqTq5No|$3s;TIk+zYpNm$-FM;>=)@bS_xEXdxf4e(fYD+HAR^QhPouBlz5^u zv58eWFu*XFMolH8DlO?T&>EzQkClv#*VWF$ zG#wh$2n@56GR|~U(E6hGO=#;nB1o}tNv7+?ilFM{FPF^hDpIXkYLz=?*nOOB?C^N`s$$RNNwkyNU~g=J zAzwIcluV4sajlpRtI_G^={pB;QVFF)eWhKa zE5>iK!N6LcHFe>&!E9u-L4}f1S^UG~gPWhZw`GTWv7lx$9w*PevHef~$IGt+u#!eu z>XewM0XJ&3Y%7Gq=8IM&>}Sk+h5b zCp~SHxnWztV53%5>Nw;W3L?A=|8nm$$VLhk6pOoI|AXJ5C`D8N4EbdTIt8^LdD_78 zs5NB=y;bT6O{~k64-JeGEX>0V^hzKdgz-CNaiIhWiw6!7n_M&T@VygpyRQp>`Rf!| zqELBslq&_+tFt=?BWb!G2M*y(8ba78>i{yB; zm%R8%sMnwT{@7SVg)e@(dYdhUt627##hd!@qrQn$QxPgS`fMm1uA4OD7O32Qm};vO z;&Q|HM{F0b^!zRyX3MiW?8%N_f3a2u#r0WK-?GI4Kt6Bco{4(e#%gg=k9Ol?;fB+w zDSdY(qs)j13ltF5GpSsA}zcGVo6{5ev4`lr-Fp1yeqIR@$L@ z_}Q>U--0wrJTJtiL>d@ZvNZ7j_y7D<%DV^uco_G!SRa~1$uM6j?2ql`t1_PlZM+CE zvQU+*h}x1GqQ57Ho`YyUj@-BFZip{MzV{{9EER(XwwANF4Se0BcHoxO5ruiX5? zj}H@9)3YCyU;b5o{ImS>c|{HPCzb(@KVPlR+FI%#59Ijt4Nnf^;Qj;HYIMOhJUjFA zbKlgwUeN5!pS^acFC9ey2yv#FxR|@eo4Pl)vIqy$NIY?rLErGnubbz8SKc1&Y&Nm3 z3EY`D(@LX_Rnj+rXzv2B1T6~D;0=-Ea^+=_3-3?V`s8@$Q6^mD{?vAGRq%pjxF%~t zK!yA7^~BY6d>H2oS1#OD5+VS5@QxO5>aO<)TP^?*|4o-vOWZL}1yykkS8FHlZ4)J+ zrx0z(^OZZ52V&M*rG2}eHD}L?uW9_I4^pwM*?lMLCMZh5y$}24(iMwFN`*iF-=1G_ zHyD&cIc>YSuGD#`Lz3gp{Sqk$_4JAYq-I zhyCSoaRVm`6(sRs8hOY4iIwAidXy~BYYAzR@@{!n1H<0CS(Iw2@5NKBTKmB?+B!&t zh1$8`=}mcZ%U-n>lT7tSI_;_GEiuztBa7TyB3u~;+YxZSPUCrr0pMO;Xz=Pi%B0{-Ajus(gh=*_3H&o8O z_q?3@)q?)`f7<`zFK2QLvFFpL#m2MAOz`5z>)-q^-+MQe+kNHW&T!+QBjWxz0)Qyi zP3663WpTJ41r1m37q3e3(CKek?0oC5@;!Mo6eaF!WdlA{tzEHn;;<_nR9$*836hoX zZfUi4-p#Nz$2@ylNR@b_zCC=ucSC6r4r{#PKI;gNJ{l}e>NwL%f#hSzzJZ9oxzl)v zZ?m$xktOP_yfu%EtgIv zxH7Y0h7Pa4W?h8XnUvl!V33WVy^>O({?>xLKe5`X#hdElxLll8U;L+=#Yq4=mvE?{H`J3o6UCVIReu<)riZ&xHZlMpRw@7>*84XU&BN`eDo9(^J&&8fnYKzY zwcZvCatC~R7l7(2s#eYw)Y)U%OmFbENDQ+>^@@;Abkx&CER+*hZ4hz+5I~HyHkky; zK-ZNQd_m+ybxG@vfd$-QUd$~1Jknm(xo=8ZUpD!yQAPnmx$+ws$F0_f!8^_u&cv!% zG_Im5_uiBEH$|yN1k_?+1d^7J^o-!?-tqV#Mh#p0iJVztL(w@mNhr2!DWbsK6x5U? zB~Ui9sF51>jNu+`>w-Mpw%e+f8yW-sdy!U%!xp`vR3IKZ_MDp;gFB==H^A|2D89F4dL!GZ3*{CH)HS`IZca5_P1TyB zOlyNSR>D-g8twrceKPol=+!6xVtX^mc;``;^o3b0`>X3po5@5!DQzqUdI7=5(X z2FXKy2~Ay}pS@YmXS?6NNCtX(lqv=1FN*#oih7y>7jJ3+7HRbQvN?Farwv{iE=md^ zfYR7m7<46}G`(TM)|G&rw7F-bN9`bTu`9k#zY07}+b-bCmt{IIqHs|Ps+kuGfKWV` z-Wn`5y`O4}A`v=&S=vY`jZvltJMsC`{O)3>WngXJPo>b@%$kvv*3oUmxldNIZ-_ig zgs`9(GAikko`K=)d7%x;0iz@IHJMlo8KEP{AO?=EtH{Lai~l@Bz{lSmY9kg@AcidY z!b#4EiB++1$-pr2(;v-^MQvrg!X{S3E-w|uB9yDOCl9V6UsI?sh{k@z6x->3^9|_ssTz>GzEGI6g?EXvnsLy71fodZ#yy zWUf2CpK7as;j1<=R*vDtB{g>m3B_#1#EJ;C#b5ou7Xb|i7;Hy~;A$2*SQMc#7-e?@ z2Rn~5S&H(JB-_g*O56ubgm)691tbdgXALheYUymH%9o*fIO9LQ~0lbyx3Htuf7}$fasa(0y zeqs~-<=-s2IO@8kCSCDDZbc8681LM^q_$mNcJMX7rJ^uQat4)S&vSs>H>m5sA76QzkS2wVX>BBTshO(0Yh z<(rxT>XNFQ0pP)B!_&WSq|&<~relI)?y4mN!0zLoJRn`cpswX4A_gL-1_qlbSIgUR zoEdEt0Q-i{pOpYGeUxI`*O3eH%A(oK=dSI9l~kTg>^-@fSFI#p^uOeJbx})+g}1Df z_CM)iJ39(I)7wIUp&ITdHyZmkARdU=l_YK+&XE8at_ca4+#2iL(KjOUTbAY9e!AUB zN7$(;%av<=e?b&a+Tz8_QocJmMg?(C*M+Zg|KopuIyp=vOSf7(*|bH;p^d6?3cQ|@ z?$R^z+w8A|QYV9!ZlBpy65Kruj#Mx$MnHw<&r31OzvGL$YfcwU&6_@P%+T905?tVF zstR8f-qqwC*Gqq`0g>4}@o+mbv5GT2KdI#GkmSUs@PqBxH*90Y9*kA9S7nsybZA6W zyEv^s_@jwDvzK3$JC8D@QCW-&gn9=zC#mE?h8cooX4^pt=xcHnH5IK+-R9znde_dm`=1P?59+%2x}>JOW+I$+ zo>>6>EgPlECTez4xjOLXWJJ{MFu;7#P7y@ySm$1#)qK{tn(9Jkli=ITt8(RCL#`yj zN79jDVnnRgUR$NL>W^(YG$I`x?L;kF#7x{&tgR9OO;z~1@S?1g?Ux)CD<_*$zHlPZ z2+k_lrXnzqvs7gt|H0nbue0Ly&h*|uik#Q~@g7o`TB&@Bvz`7ViTd^SgVgYDuh-9d z{ptH=bT1DaaAGWaahxQX8BG1?qgNdLJQ=J_q?W(DTa1znjY#7_4^p39XVA0{&7 z6n>D5B8Wi_8e^11_1Q?JeIo*h*31Qpr7PF2Yc{=S5#TEYU33^V6s211`Q)vMSa>|z zqHMYOteM_Vg|6jmmTX51vF_j--g%TsVs$z&GU|{HtIf4!S96_vDK>~8*x(?zhT4-L zc=^@2?`G{yN$Xhv`lYs9p4H?TfW!O@(YxR^VN(?(O*Pp_Nv$GCZg0zq!EP`bqOePg z0k?Q-HWj4Fnt2^J^UZhUVVMTwSMJD5gdl_kBjQfO0!Dp0hdM4x?C2vQ&l znquDASg{u_83RH(vU2}~gXbLyS-Mjq2-Bfj`?{cP%PI}?lWNl*l00{3_Vg$b%tF4} zde#iKt)%dreN}{kNnpQ79Y*XK+uV9`>>X*VnBj&l%*JBnfMR^uiFMUozP#HH(x#+j zpo6ayU(=4JJtNwOc6ew|fjA(>JuQgle8VdwD6qc4kIbDqNPcTSwlPYTETmKMBUkq8 z_IhPpG_0ma$-$E>&NM2#cv)?>84{9uaa@Y|!Yyb?W3Y9^0N8sc zOL`g=)&+H$17QIm6bmPb^2@Vp(9-t(lnAncsdK;cD6@%{?LdIh(0C)-NSPRKaKyx2 zI2zUR zBHlE54^uwo?!UCWCDx--$BnD$tDi22K!-Ub`i7S$dXr7o=7?c>e+>xhV`S$3VW|`V zB5~8ZcOs4nfUtTq=){VX4`%X+t!EwpoO5n)+TX3&hdU@H5n8LWXZgL4`cfPVK(qZI zjWgYaH({t$VCO-4#s1)KXbFg*Y-jg=ZJsI1ARC%4U&bctnrE5#(<=~5CIC47GLQRO z8%2(LTlUZX*XPu5IyMI%h(Q$syww2f;dh4YSu&xDMI-fu_Z+8c{`zLH9U#~?xuQ3+ zCJMGY7aP0-o2a1YZz1wct}8j7y)FSkYZS#nx$;b8G0%(m*EfHxTq}2Y@4kwXZhuwEF`Gj_;WEv5rW_?)`Upa_Nue*Fx3u7xvG$MAS zwyxcddKz0lyJ)EU+fg#K<;n{ta?)bNlgG*ZZx4gY24%;_kj# zV}vl|90zF{V=OA-@k1Y`nZ)yd!IVwu#` zG`*h|i(mm>F0LwO1`yxL8+2eqnBGg~C)K?V`%2;bqyRrbz`p8iUl9Q{hGG6?V-gu+ zDN*MIn(f?O<3a*50XZ(0PUdOSrKAHRc2vLqt6BHfb>VHI0`t0Nlc@6-B>=unai8>! zYzR>rwBb9C(qitiEgNV0@^vL#!r^Y*F`C7=+Iyb8E~O)taUXl`a(NEk@5iY&R-JE1 z2&eZ`o2cPVs_nX_4n7+$8=}#h2 ze9H)G_faN&xc6)#Rj!;oO4FmX%av0KKm`Kb&chS{)|YkA3pkdbq7do2;T%}z)R7av z{OdyG@GpOwcdS6kdK01zdCuo9N;MOoKMyeRXg9h6<1)a8u~(qW-dN<)ht#F--0pVY z%Tz0u>tMBbq?3WxO3ANp3bi)Dw{&DW{!!b0L!JA*cY2b{6CPU)_de`vgO|spuc=!5 zF6&)JApJ?;F-elc=@+>m? zZZL`JwPyw!VSj27Z4HNZW&1bGK#uCdCj)VG0wyRHE zMXn-hu|=I|xnAVBSU6Xc3@K%Bq=(g}7XbK~m^ z^3EiIJ&@yl;4)e0}|1^PQqXKuG#}ycahm)g=`x_qLG+FeH8B z8oE99=uaY)4VghG4!^ZOx?z90iDHqb*~^j|zCpjbrZaG%*h?o`uAXa^fE|e}VE5CT zA2;qB1iW}zcJ|dxV{ZBKKgn?+3Xp^9}swwF5xO6osjq6JXh;`wW3UYNO z=yoA-HxsGE>bxn}-ZdfmkUUQg6K&Dgw7jU>CMcLlNav9ZOlZwwb?<||toEp<0Rb4j z1M;DmcQutOx4LK+XLVC}8P}l-X$hzTQ$(=%^+heDX0>|gpMJXd+b8<;opk*q83G+2 z9K1J*G6I0b%YN4HYY0S**bb63q_? z7yyceGZs655BQp;!_LD@Y;(A62YkcM@&1!cfm~Xb-ql>Uxu5c!)`bUV z@o{HnvDots3sk|x+MsWkh$ly>O?11xBLmo23FoV+Nomy--b5(&@En3)LiU{yNL@v7 zrkOz{J=LE^SA{G?oT%}x?vM1_Mx6ifvQ;0TlvB&|Iv9E}FhI3(!<|S9EZJvm ztjN(-L>-EEgKsL5un9n%cWSch23Vi`(X@Tc0y|o$^$0;&5pYUi2-P8Z$93tYNoE4q zkT?^&if*(S+Nx|T@Ns0mmkv#oX|dJ3X+-rnE0*p`56yw_C5Lz17nBD(DRO^mmB!u2 zX|ZtL@$6OA5fSfw)UONr`k=!OHH&*!CcdM+SR@j`oF?50SHnjvSJqtT224IczO3i@e!(31p7z(6BmBoY`&97-fbHp%Ylt@hj_WA*iJ zXE8n4xz|0GtnL;lN1%|%tcY;G_uO;LKKqt6wi2)qsoY)6P6!<&MGW5hz}{yT18i%& ztiyV3m#-VM-qIKn#+iEc`TFf2jHIsZiji%)R+OmamiDmqArAj%Hc%h`vt4NImba@g zXM8r$q>&I=g3Py$U|SIY-2GindMKOG;+1c4_syLezhmW?6#Kp95nrwDF27`{P}-1! z-ZZkMZ%P-QL}1h?Wbe)fOHN>BPIs$nY$`vxl}P#q0HnRJSFFwq5t`bM_LGfeCI-wg%2WpsU*=Ci zlIgA^;!9~iaQod}l(Yo+pn%)LShyXRsX&J;<~HpqW^O7s+>0eA<-vb2R3XETFJ4|+ z+tar~5SU7c2vtNxU>iTVlgYq3NfjzQYM~Rr8*1_KVJb2lzf~~^C%@aNNaOY*VGpKu zv!hzxd^dq172MqC$939Qai)|;718pfiE|ZaDoSX$7l+S}AWq)GTmR~B<^b^McP2VU zp&G2YPz%=0V@vKN!u9 zYCv&<$0$`qko5HYq`|gHx}K#7+{MXz_E4>DI#6-0JoC@~j}WOjJxG#_l)}3o3?!mt zYkte@p)B;qc=PJRs>-_*50#o8#`D;81BWupdz|>S;+=2x-IrRy_1rH(XFHd zk(I`zr(Cn)(yq>%%Q-p7t+>9w8wq2GJs&>qCq1<|X#^TJwYP?oTp_~rZmJ_Xe^JQ? z5jICYisFneURDfU+2>8^TiYGj4#3KKw0o%c4)xxF7IOWdr}{mWv@i{JW@N1f5D9GK z*K_MF-}`XTlvHzIRlS2fsC{mR2G!tO-HbmrEa*?(6sdaG2x@5Sq&kb2nw&{8$d2 zBi=((`g|Cv2m#SsKK`lzfa!y@Q`$Pi453bFN@r?c%xr7v5LTUYEcDE6F9pGLg3GUm zD{6^b@8`}0V<+KGo_&1-fOYr7L6WH}=bp17fPkd0g`rcgY`u1*5g1;5wno^*nfaTb zoL|pOd27fNqhR6)D3);Y^TV(38`NoiVWc^9#w(4-Ul+FVP2t7|sW|-sLe^JEXbsO^ z*OGM(4CTU&j4ZoV@Yk4EEz}s7WKV zpEbFL8OakQEYvGB0imw1&YIP^Ddy(7zx&Pft84EtZiRkG*c4$&#N(SgXYu0$gs4yL zJ@rlLn#!+E&GuTzF2j_Me}94$^j58e*~{vkzjhZV?!EtbD&Fm_Pm7LIMI>>z*3{nA zUQ8YY+to2L!&zJFDvj)+UOQnA6$=~48SNBA^n=CHoqS!`+AEFTag+u>NAV6Kg!P3{ z8inL2vUg^1-nBrOmqDX7Y$}fk>zR!+1)l4bV`cNhGC|7!8ThUeZ%S zI1*~VvrH-!7#FYV!EPc`+tz~{*h976>?(T?^0XgzRCYqD_0IU?uZrp23;>FS37JCH zi@}_2ygWyBVVT*KzNwtp9JSofVAU#@I?faTBLqtdxiZFhTYIqw0pNqj{eyRU%QNE) zmrE<@klk3NWuFBfx1D>LWC6<<$<$t$Jz{w|W?#Ghcrz7f4)`NF@IwlpNRNfui$ToiVs&-E9H=le}KKZ+);9uSZi!z<4 zD>Ff7Sb`5i77z33vm#vg*2hX(l)VReU0BIU6??2IK&nu!#2mWWVqk?Xu0M@{HVl6u z$VtU{a%qy+!3zM;sAE3h^6v50J4YS zeti0*6#byHoFsJoDQ)zFA%hc`d3?XnF|i}hKJB}9$MJRH`qNm)bo8^RJV9Y#4IZqe z6C(vjpLQ|x%uc|| z>4aN2k!k$oR=RDJzMgHx0t9?Ngo{gOB}I?79H;94{BNGSk_QLTU@s0?d$jQp2Y~PX z@m|-xyz`GH%hN`3S5KZ4)5ApgQ(|0t@ua$5%!*4|lB=|*WK^}i3;-Y>>298^6kaLf z1>*~Eo>?eSaYnMYEKZu?ULyXZ&wsisSN7~#8E3RSHNxKpfRk^E@$FQKkM-R2r*Y>K zbo_N8@=5Oz)&${XetSvDucgddH+dJW8GQ z(rXQN;?Z6Z8y>vZW6!H|^U;5{E9pgmpkj2^r+qCus$7I>9$elBJ27eO8nDe6`7r55 z^4YG=C(+~}Q89@R@yRzO0`zwD&i(A(cLzk+WhMZ?-aA=H^VlkgM~5+Kh!RSAD#?`0 z-o;ZuY0So&2s$!_zzP6>4u(^e=6LhK91(yKAWDT9>U4zpD3;T3dD4(VMT83JP4ugG z`!7FRNmLCf6k?H1g3=ssGJ@GWAPC;D(l|S+bwWC(Ah>2pT#D<$$31=Lz5e<0(r&rr zKx>|L1yz|Grsc}s`c6(1uvb#pl9htZxowHG0&2@QddJ)7nDS9n zEKISmayJq2?uUcLNi&$ns8N96-Xziqnaas-&mLB%&82J*;B26gz*|WBT3BYoy?F0I zhJ>e2gKL4(2+XGPEL>>{9s-?Z{`5`?h$r6^g4#%NEPHjkMDPZXee2Jqi-dY4N8W3*1pOZ#vBYMNz$SKOyU^kYQ zSdhW%Vb=ZKDCucnxOh=>mk{iDxE~7zem%1yQ6Jw*#b~u$SU~7c;?=oP5jo4Re%Yjb z)n*`g062S60>JLWTtyg$%m~qlx=s}-1o*fnSl&GNy`fI<*-w^$pi`3e^1Ap45e`4- z%Vc-k`k;hF3vInEKeFS=S9TDNi9>u?c8v_T$8*By$UK53cw1s z1zJV_q4i_y=POiyH@7!y&Z|*%NjPdYbtMQU!2%&SoZ3y=uRqW z>C!5TF4a`t)B%hzl|#bCX(ODSY^Y7;B=|*IIc7NiqEIo#8NK-Vsw%96V~~PHJG>-? zquYs&#nv6JcsrWP&!1J*+}=osAMGbn8S3_?4|e0LR4s&TqyvfU^1>B9og|Mt%hl@F za@1$bSMG9mh*vAu`MY1SuWD;i7J*?pRyrX8olO;#bhhsDOdy>qx{L-B5hAjKZpIlj zYjZogd1RRu&U2=iEcAQ0tdn zF06?CeQSe*0PE+;=$*#1N5p7khj-`Ez>eRUgEBH=dGfQPFF*g~(Jz+nJRkW-nvylX z6xY#uHb6wxbHjJPk;B*2-g_{sU~pU&1j|oqKFvoF5;n`k`%6nM`rxPT<#c>FPkNiy zVDy8F;r*xK?%qcO(IGXJ<5sbIWn9XAp>4d5NQ}?f2_-qe-#Vr)U{q<6xonaXDeO(7kgvkv ztar6HjjvZ$tXFk}P35ChF^A|?32m-B=8O{o>zbS z-yeVZXR`<2A0o0qQDRvdC$zpWoA4vaa<09zKFJj+IDJ}mQzmYG(dyED@-OyPg!S6l z#tU778P+q~sq{C-LA?2M*b2kM$%hZyj@Py~q0y}r6(XUj!`$-VQD22{>q~3*&IkQs zVReKO%pvqE*9P7T$>Mr!&Fx1$vG=o$KX3iQZ@<$U?#9ATNqY3{_f#HW`CQ}MY1&ta z_|t!P3c@gPbRVlXD;EA$@3 zd>UP=MZ#8#0OQ+9H@=8c`mO);R_B$I^i-U6sqmM|*-l$JxdS3aX2<8Bi`S-WD$^G6 zKIx0VI3zI6zP?Ve=dA_F%&f;1AUNxfzFb34&!NEc6p?Ao;{}5U0M9--SjQQW0`}~Z zl}?EWnc37{tfO^8FaI9febx`}Eu<4eL|+jAeD}XlVh=$IfiUfpVh+d+)s({w2hd|NBR=yoP%+e2#^sW zP8EA-N;f`8OyRxZTkrP5q0XT6Mld3rovvWI_rc)gNhvpUc2q}+5@H$>o<7+W?)QIt zDBF5h8uq4<^uWP<`K3X@d~O|R^J!7GGby`bRG=E+L!1w?2+tt#h z1C0n5Uss*lXm~r;F~t#W`~Rp&64tO3bMy4a)#;a2y|{Gv zKKR~HMJTKXZ`oE}N2p>_3dMw?!*jPcRe>rxtpaJRmo~{%a6oJ27?V4xsodU!Ea|D` zS+gz15wPr%KRN;;Ob${-CUh0D0s|S<9F_*&al$BEyFE_m%llW|?f%)`liG&oO)Qu3k`|r2+%-i~%fMYr+=2p!07N?Eu zT7zl4x^X1du5+bH#dO`qsG~wiNc`@@OzbI&tubEICqfXh5->ESyF}XB+MmVrvswpj zLp$d~3L!jU1~9#w%13+llf~YHJjzH?tqF0mr}D9kFT{?7XRm7Eg&}U7aW;uy7#^;|OR~OD+V&aRuRML|`Wa(f2#Y{3Z0AO@4 zUY(nbTe)X%d3AjCrt6&g(^xnc*FW{)<31y@FhkqbD02%^DCU*?23+hneQj1RL)RHf zT_K%$yLG~FFJ7HB%#ii9shlJ;+J=?JIMVP_`# z-08p>?ogp5`=3NZK@%<6_q6y-|xx@v8^YjS#%xOH-niq+RP)GqZ^ z2XcAKBCG$FS8-~de_9+rsmqny1}oJT=*9*RF&WGA8?CqvE7s8I* z=-}hgas`~_-dKY|W+>+-4AdEtRMMo8meV`;9=!eN-SKos zgkx*?yuTY0p(!F}=skXk9gc6kv)-(fB=a#hiFevS;!Q@fylR*hs zsF48x8ko`BKawLON>#mf@-uaeof)~(Sgl=uCw9g=>w`HS!}8q7ij}Qt6Aoy3+&awe zKFE6G2vtZ;^*&geAAhw@awYwR*pmgS6ar~t03DI6XKT4Bot%bFsL2o<5A%^YSF*U8 zb?Fdc_kOMuwK#6_vGx`gC$%*!$DbH~OUo%B+O4c-RHOZPd1lyiQ@Aa$5^tXf>Hwe|=?_ZHFHK&o$Lk|o>$Kj_KEti&L9ZvwgIP^@)&8;#_Sf z#R^pfLf#N7?5i}`wQO^(MF%S)N1+$_P)Oq9w6TqstgC7*kx#$?=|GKl)L=|$Uqvyh zh|->pGX)GPLho3_*mAd<%D3GZ#3@}lF~n7l8Fn6I$6puno=xq4{HLee3G`7aAvh>| zv1H_lz_VT<0PKAfwCD^_E?e&Lz{Dv{-bMh(52|jlNif9CL!qruLS~M}3q%<1#_XVO zuK*DyJ^lK#4O$>D9DC26Rj<@Bxk@qnz4wh6V6g|=@Nh4YB#UC^y?5+=@9m-^g+Bjr z5L4}che!oCaRgYLG{UcRhSMIMzo_!DZVGq*Kd5{f6QPKXqUv5V9+yYFWG-B@W9y6?sF^6aZ{*&qGEq=Opo zeRsGxZGmkK^B6BQi=&WrHRRg6vPm#0mdYtpC_lE* zRoi~0-f~lUfyJBBuP%(R?oXeT;t1{>FHf4o_xr`nOmFGE!)SwvNbIcfq%clNh?7x5 zfAv4U8r@0&;P&I5033(!_lvnr2ikj1dfFLIdMc=Fy1-TjQrMeBDnbB0`o+~#DI06j z&=77)7Ktrajtu5F>!nD8q(N|Ma9ciCfG% zY#rs&n$|b~0A@$-*-xs`Uc5dvQehuH?w3nT!8w~rqeN40XKMgLI?z}Bvv>p9mJ1u@ zO2z0M3mp#$r*~4Br|rF!%|x4jxgeG(z3m6{;8714oM%!vJE}$g)5X1sbSvOrYhC*~U-rrrqV5-pfqwonawJb`QIE!5CF3RGQMBiZbfLLkBxi zlqhdG&UIKS2$D$M8%Kxl4K7~Rd-pRDB-)0@x6`zzLj8~`Nt>2U?A}L%Vs3DY)RPW0 zJ5~|tgwlal5nj9qE|9`gAdO1n_*NRHYH{3zxxEUfCn=PXo7l$7kX8(pwz+$6=$HW! zbb9q{n-|LzbhA zkgzw_otc_!PZ&Q5miEJkYyPR0Knn*`e~1%ILMuDL%!%uh#5Qw8xgry;l3*pE$8~ebS?+%JFj110eE?o1Z?`f|LS0I zQnLqBc`?)7wnqqYPDY|L5do}WZ~4(5jFBMeEAK<-WT!~&{3R~KM$ly=T>U4+!CqV~ zZ3j___eD6bxs4zsgn!Uihh90$-iAiHDV&Tmz%!XQs*gB@g zN$m`;=SEx?<WcIQS=64J_BMC_a&)2z}{tX6UI-`87RYcA)d-%Wq zyO-ax60(7|jgK?hPS=$fabWPw?ARJ#t$xK+o)nG-dN|P5!0~esRLudq9HOQH=yz zBWXfvv21P~16q(>tf-qx-foEs zRl0I6w1Ml_{UlDb*53Q3u8VTLXkG(A*4Kbg9;a$jM59>{5gYF<+lHId#Cz|(*NK_+ z|6;HkM+wc3>uP=pz|wbq;@6`G|NIO9kXF6-KgV7(`t3g*?8s0WqLk{=JHu8)U|vKC z$PDa!+E*&3Zl=!6iZCBVGHL7b^~9=juor&y+ut86jT@dOgQzLl!*DMljm+E>POdFV zY7+-hkqo+;!aB<`)`}8Rn!wAPfTNUz11qywnMw*G=}ZvudB+bv89C!k>6+33!|9Wv zTv*jwRf>T!xAd#US(Em4F>eGOWye+FWZnjC-d&i!3(nJ~wMvSP0Ey1AGd@bfc>Cl@ zDQLSjzQ3CQz~ZD9zj9}|zY{m5yLeerlB?4%%HQaC&^?lk&(_|17HJm|dh1{Qa&_>y zuOoskhsXz+VLVnUA*F*L-x^=9odmIa$DQ(D+VOlG{qO(vGl9uPU?p@%p@Zs-Wb$Kc zPlV2R>DiK8A;HrhFFLb5@jjG09p}W%Cr`>t^efBW@o)d}Egcgxi$y}087vKFAYOUi z;L6*KKZK;O1sW96gxDA(0U&m~*6H1BaoVsCMZoU;Ow5U{xKr)Dl>zec*M+zRb&rHd zi0ie@$DN)2CTj4`2Ysb*dD2+pyKQd&VLsSRn#w7SgWc%c@9EC{RA~gj^~@x>>Ww4p z(%&E;8bWbb5#1Prb>+Y=<|g=G@YRIcjxJuWTz3HPKFGwVqbZ!XY-*p5ENLt7SqB9Q z0aY}TSxfZumdm+qO52f=5Ww4@9|X^fQxhdfg!xFP1I^5FO3WOmN+~R6R>lD0R=&-i z(<$}#GywE>;>~;>As=bUF%6N0gzx|3>8sB-A--{<1n3b{Rr#4`Pn)m*vUvG-4giLS zuJtZ~auE(cit5?xI_@(7=*)C>ANY)Y>pT+d8U834o?txi4g z#{9~QXFdCDTHD40g7==%LWG5)0Llhh|0g2d( z2p6Xfd&q{7ipVxhgsXEi*iFi%-MO2})w|?lazBf6H9xL5zCwHnJN7O_G;nJGEaiT= zwAm;kh1<3rac88p`8j|H^~#yb3)t_BAMVFL`ZurHz~o-4BO-;~a*`|9s-*9IGMKe3 z(_23nE>CLVp{&l$kD&yD97y#aY_d9ZRum zmq_7uJe-WsrAd|setluGp^joA!X#JA^M(|~DIsAt(580F)8_DTe{tIAnBr6+fr{|{ z$3vx%Gzw2p3_hZS09f>%%d;lQm2V{#h^RCZ&~uZJcFs+a5s)( zV$V9G>D^RDJ*08|x>g#S(nkrc&YIpNShr$pv3LKIp-w63Dbna2&tEiGR0COGGqZCn z-mBR_MG2*ST`leUtO0-z{%E%1z4aYQ6N5NaufHq-u389R|7d#;dsX4WvOjAWShn9S-6G=lHQ~^z2^YAz z-0rduk_1~j@F6Qhpk!0~?N$mAB^sqQ{GwoK!Vri>;W2^UP$9v^sgtv5b=Iha;#5rz z(~DR2N(w~qJ2^;26}!F31ow)@$C+v> zhZy`v5#ioPgZ?zScvkf$k?e7%_SsNXYd3pU9lYC<$j;6k?C^2FwK$os&J6pFEv8h! zMA%V-g=?ua0-i7Bs& zNW{G5+^)`>x^O^n_k)4NRNc_&wRuD0%&?xBrgYoAC?a6d{;n@pAL zjlv{#j&0?|H_dxqFWu|s=IqGoMB)N~8D9KsDOitpAl_t1aMAAGajqnw!&?Tx$w4|l zt_2;?2}!Bb)tSrFX7Q>KVIv|)jLbGs1rcO2K?-H=b?{!#dyr?UODeox5!EFR_YF-bUI4Y1pRMH93q{%*zdAS6-X;+ul?yA5;I`p%X@x^Ny`T1XVsS}p z3&_ie2?KkO{0iBW*fU$W_q`!09NvzdVQ0fPNVU8=yCJ>j@WZ~2=sICm{0aJ#xY(k% z$nz_r6=|{l0bkoYAv+Lb8rwJlgShoYl9N2GO*hSP(0Y$%j1v@b+vR7IA|)r646lW*Qs-gQYz*~-j$@^ zboxO6n7);&h!&@fcU&&r72e`?#$`v(>`fvap) zdlQVPocR?DKv#z4Gn}aXJ5g2m*|F7I_F>|ts&i6rXpZFjQ_P{=J|mJ~v9 zi{4nl>?TMctSEt>def+ripyido=xQtK_?2B%Y}7@fjQW>RbCj5)yma{s|zb}6LQ9N z8FtR_`rLTO*+7dO5-^%o=1R45AB6hYe{dlU(ekvG>V*_8zR8tV636b@BcP?#gYONc z)0{nl?Co!`6|z(-D;LB$@4ffVdFQj8qrC^2sM5AqLiE8;Q6Jyh(@|OigHA~2Pty1P zR>v4;3Kg>l*LZKdGhDB1XSFV9#&AE8%7GMetEP-|5#7Lg)@*n8&Ulf~zWswSX(Wx} zz}Oj^)@$2&>mtW3ov0H_I^!RFcK`^Iq9(AEENs{`uwKS^&Ui@z6Izlp-nH{Q z*fKzt+$5RJAfbG3wXkBF4J3v=?^+Qtx>7 zqH2+8>R7(sah$2)ehdI7Psn;TAEF!vF!(o^sZ^Cb*he z<6Gl-=uIL3xcA|p6W>X-G`^JxQdXCn-*V^u{%|Kb`m#g-?>x6=TY}Mg%fOHhRKNh* z2W{tGHrPq#r;WAVHJkVw!N|7hUElH=?j~Z}#-1ga3jkjJVuQ#C0a%uxihf1i@zy89 zpp`@T7XSD--)JGlYD9n}QKlq)+_+A(2WeBeYH3B7O%#@yRJYO(O9?9txfIi4(};-q zo=W;!$7E}!2wmfK9Ku1nLs}5hYUM(2hN$xpb=MuM64U~A-F0#;a;lFj{$jq$rF!xwp zm{#ow{Yfmf$m?Hjs@ISv=)E4-{T+@{Wou&Q{%#w3=-7K-t*lO{m>F+LPKe%KB~%3j z(5^Qa4DWwWNh*^lTg!#5)-KAFil|%~B)s?0Kxv%6uG79=of{+s+Kl%P-|a;S)l2K_ z)q)RN>r+!YantLp>Rsc@g^`rEZK6lgQ{Cd+GI58q=cRPo0%zyL$d-QkQ2ZAV3B_{$ z<)_QAfPa4^4Iu#B`F=keM5oUx+2u~3mMSKl1hOswhz^H6eBuCz}!tL1`-HCIn_V zZc0Btu7|s^H9WW->4dxk6_K#Y*E8cC>x91g(R_R>y`qHOdn*%mClS8>qPUKfMX3S? z*Z6~X`*BL%Gb&7b$}>lq`uJb%sTjMref-%Ln%q-TWPkA&8!=!y(osr6aEMcN_Pi3` zDE6Qe>hHu&<(%Qq|Kj5O>*nH{`t0*+_EmNAi}K2WK!j;dae`UP3>Qx>6(cFcwp$RI zr<5j9q;B1d_U}fw?nR&cs~td48uE!gc+~TrfBt7@k~_m5@?qpX%Lm^+fudNMgV*WR0L+xh}b;t+7Po?=D&JhA~~puMung{Qv+U07*naR8X3{ z<7Vw_=>*yXfZca8d7pWo?tPR8pXTUjc0GJ8fD#Pyo=I#6(C6>a}BFXMH($MA#dsTX&=V zJJIM?l8++5K(Ffv^*UB9Ew`2}H4)QQ=Gjrb{~#0WKw5M`F@*c?J^0pXYjltZhwk`` zVp~5b98AGCr6}Ebl#TWiXZ+v)FUN2_eXMJM4ZQukd6JWK_>!B}o6z=^M+6mG8y(T~FqIu!g0TRgSQ>d(Q5#9II&0cC$J>UR%F9K*1jyb1R9weWgiIkp zPmJw!ZE<2|-_*d2KqOD_jNpl0mS6zx_&Uu)UAhEQ+mn3g%)bO z^iGU#DyKAA5yrcExTC7M zGj01O;V?Hk;>#+L2&pUkLs%G&MV$kQv zVR_bUBNx_qXV^7dt!z`crt)ou^`^VG)|=XwOS}6ZTb$Ll_Gw=?rCUGE9{qCwfZ`RV zhjo9y))Cb!E6M{QO0S*Wl_XY+M7hu_|s^ilBWA~>sQmoXLm1t{FYl|T~}3A z7V~&`x5x%sM831HdYyQX(k}rZjwqR~nHhXmpHJi7spLV)wplK%H6h$nQr$LoE-?W^ zQ#clu4{vO&J@ewE>F@_KfI;Bn76PzqP)4H6V9Czys5 zdje$&jO8phg^yFUI&0cQMR1m@g_RE;D658}L%Yc_i6mP?>#x~SmH=^lkctF4yn7!=TPh(@0SFX2 zy^{{60Voj%W!H#FG$@VEc)5QY29^ggsSyBc=b@e)rc#KNE6bky(+fXBCk%+@|kgwYH)@NQXL3sVN)+%ZyrV zT(iE;hGDbVU~>p6CPWzBN^Rttf0e%!k}$T7)5()U%j6vKi@%xyLfTWp+mambe5_6Fo#i-J zw(;KbEFU}efryo4-dCR0gg0U~2ZcTdcO1{jd@rZ_$^p%Wfvyo2w`isB1 zh>{R@(4WSGo!DD07RJnd-dAx#TBEJlmRBD`9b)^g27Y9)U zciWl{i9o$LagYD$BWm4P3b5iB)oW82`1hV1BF>kTI{-7m%1)0)U)^3 zdpT4QN_*2Kf{EUwDIIN*ABj*f1qSw(TfefiZ<<$sw?6uD@%V>Rb{qCkBG92@ zoe~4AE*d0ohJ^{WIyc_IXfN)K!eDv07w3}*5iXAEBv+D+ND9kSw|LSVe_9;>vUH8l z2D&aCiH&;DQ$zsZ8h`k>j|5HWMBu3+9PGwPu1=qpx4+vH%9unE>4>BaSYI@vh7$yE z_g*S3#KZ58h_F}~L`*WV>jh`LP^bjqVql$6wQ}AuX|#q_q{K);s8va(bWBZ4^+mO@ zF9=CMa%aAE@Dz{e%FaoI#oVxma$$~S{4sPNp|lzyd4VA8L0&KbO(p;_r=1)ti8_O$iD!D z@$CeaSZ(p_RXyETlY{7rU`mXloDJ3|>kCuNEh=c~SG+uJgiO?eO5Pe@u52*Dt$nc5 z+KHo7oj$9sj6nFBA(;x=E_9Ang!jHXY$_+wpQhoCs3jMtS-C9&U-+8dO%Y&za@_z6 z4UcJ{Ru z3~R8Lc*jlU>a}YMccY`(RXyXiH=`6r3X3DNc-kzUG~O^ETnW;>yyJ0v#oV2_Z3n?s z!QcHFsZh*@z?rKKs-xRUNVvNkDIhyZUAWnn=30<4Q#rv!eS1t%5AP_q)<~E22EsHqUdw%=-qi&Aa-PYbTLd3yt zoDTH%sKz#I8&3L4+KSPB8rXacy49{Z>zxJQ5YC$owbB?$D~7Y@r6i%te8SeA9p8SZ zhZ0JrQPNt^o|fXVh#|N(3~!wErgHZ_9(2hq-7#7f&iinGr*~7^c#2S*uvtejh5rG8@Hc1i?tLd0LaeF0gm#C574gn{{ZKiD z8^-5POMt+fZ1bVP)c*haZ(qh4Im2mRqe4KmjTb$zQaC?u(t++2oe)ZVVK&f6 z2!!+3wW)kM)S_47D+o8Dn0$NB+a4(11qzk8w2DV;e;S+0mkY}bbz$E~2j24N5uiFw zm1zNT@u>}4z_oDIWCOiz z$~Znq`_t&i|SS zyS_@CAeF|GuZ(<4I;n#O%Jb>75}X=5Sc@~15YrYXjf${8jig5vgTo|OtMjHmiG)+Y zTjRdz-ArkC_1U^y*e8E8-jP$$7#_VPN^v4S^R%o5wK_d40lemk4ms-u) zz*@&PWn9#t$v~+H#UMsSs1%Bo6#(o#&W8Ij5}tou?Z20&eI+QcKzqCQGeOc#ipy};;plJwO1vvS)$gDyM12}Pw@yP%ixym(!U z@uxG~RL&az;Nu}_5;YbQh%tf4Lqq|3{7u0OsVJ;PKe#bz4jEyhH_0J-Wh-J zxQ7HXJKYvCAY$N!5q61$0FV!~XUql~JOjhxq`r7rkw&q@5I-hTRJ7@SL@>RV3EU=c zczKOC+TRVSG3C+@c4Hz)a;nzu;zb1r_rEvPF)mJO*_yWTuVkv^;71k09He#^D^QV+ zzW#bm3WexoO6M$}Ju9v8`7pX#x#G1i`GE;_N0l(Al!7={N@2BjQXjBqVJdC^v^yX4 zpZ|Sz@00ZIheL0D+)ikj1telyvo!g#M8u?^n3;S>D~*aS;|{+M{;sFl#Ky4)z*FqoJD5lLe?x7Est9H29pXU~^ZfdoXs zKWGC{f#{w*^Ch3eBv--w(SdyYD~n-rCq4hV+HUQf;imNB91+Bggi0YW%#Z7)a``Cw z^xvJHeqAk&n*FzWf|p&qs+2;p!S;^dyRColR*VF`_HX~rxR@J>_kHp6m7MY-n61_> zZjmO^SeI^ckUHa0!P&FQTZXW=!~CdHF(P5wSE7*-r0mw)d2bR+OMLrLZ}zGd99e*; zVs1$x5uCr+e8%BkEKwNpd*`pKFh)XDF$tdT>R=0^)b<{Nq<^hwX>~0e7BHAlR4XSq zENR?*kmW;tBeA+oHvy%EI)`$8U3!RkD@8$}>{^{`r>vR&G$sWq0&l%UNIT2Lncc$L zlxPD1T8xj`I~L+IB6<&^eAKNK*X*b{{$(ZRt<}PQ{b%#f{`8_+Sb;OV18=;ueDYa& z>;0VC3?lJm--hgwP#ChN@=;2ogTz^%^_4gLM*al=Iv(uCa#Os6izii-&=mwhN`Kks z1?W6|T42ktlSVPPC~oLi>`Z6_gsCl4E6HN+*ZPN;b7S|KJZ^cE+oGRr(l5jk-14)i-9TGPA<2lWZ5o} z`nE?D6<+sN!#AZjc5qKmeG42TPAuIk8|vwuba~cPE4Mmp_7JVm9pfO%ansi0wb7({FPb zwiRDVCzKe_puz(Hgyb@SHQ0**)c9TqXm;Q;5NP>urb1j6zams z-coJ->-HbgEsj{yQ=S9y-_(Bp?L2HLEptWiL6NXo<4NQ3*M*QjyaRD$HnocqGPSQ- z$CzLS;={*pN@pA1dn?aITEGDbQe%ekL+tHPUHH*^WpB43g5{}^Nu-jfpX11j7|=Us zU0D``w@lLaVnb0b*WCg$wO_p)N#`TRM%I|BER&t1I3w?*>VVZt1c2zBuR$FHKmrr& z73`TAnW0vvQdg*iBy74~JCR=1D<>eGKpZ0E5_%f7<*}?Z&%SOQtX!zEnLWEE_>=*n zseLxkGE>ZlQGXgm3F($wBO*=P_sKQXB{fc5j0IkV3etFt-w4R6GAIYKF6wX<``{7WwdMS+%fG%EEzp;dn zzsm58jah=4|ZcB^d=yVGOFsBlkNGizjf*A(wW*%@1#<<>4bt~ zCBEU5@>>Kf4C=6L9btOP$TUNnE<2=4hoc{b|(Y49d0jmc4_tuK@#Nzo}fg z2<}%=N?i!1Gd{FW@>y~k>?W-T8Fr@!UA(LWuy>Y;U~$}>e^uT4XdvKGHqbKemeS`64SThoMZMrPF8y2RI#MHV zptsX(Bcuv9A@W&{QE=f`}JWXCj3fOrj)KB1*NaTi*~$&Rs*Up`@qFnUgBPTaHrG6x5X0 zt-D3}fALkRGFm>D9V9ZjiZU%etWly=aPQK?-B=maMx}id zXQrHc*()Y%oqsko0ho)`x_PaRP%iArr_0%yjN{OIRvJx&GP3*pPbRm*RkzIl*O~$H zTvtBZisUu{uy6t7F|ieOLkq!x`XlwL|M1YnI6Z65zb-nzjI?jaL)zEcz^k7wzy8zN zzx!WL{`?=G{`o&X{q*<8($7Z;rW>I}NRDNF0)Ti2^mn2-(~|!P2(N#>eEx%tL;vB2 zgXP4nbFzl}iMQOPXO2&5A@WE~{NRKB<;$v#lG!vOQQad9QM`e5q81lV?8pw#`n99N z(=S%!=zL`4C)b6ywOd()w10+2argJ^z%W6zbkejqOL3}-nG>7B@$0&n*xiR|oT=IC zCPuY;KOG*#h%mpf<&^^fJNH@b_ZK!Z>W9xQBHsUQUq)GgU=oySDbB(Uh6u8o$rL0> z#qJOh@$>(Ca{s-)Oqgu#O{}6=0W&JRdRd0y>8T1Rj7_pM;K?y#L5`8oVuVu*=$gC zic)2H%fi5AhNP!uEYAQ}$7LHTAM}IO-2KXbu_sgU)6WXIEcfsm$ozHyVtyCAhPjW4&KhYN6cI5-2gJMYZu!KC@Z13Bokqh;mvr#UrfJ( zpnV1aSKV?+-{8jtx0$s)c)uTKdNHt!s!0E?$)DIn=)4bt{SW>!37>kuzETcmL#d zaAVk%0m>M~#Hw0^dv7%EKZvrSNqYM9^8z~hkLO>=eOq;QZ>$0Cq+hk#Ky{N1*Zx3X zQF0@`aCv3rB=w%_(l=}OV&_pN@||L8|KeYqT|*~@5VS5iB+n8Q$PBI`2`asv&9I-W z#z+jdAX&HK>Ju{A+Dj*4xV9!+Qk-d9`Po@b)Vls#a+YjGq64_b0ST<1hP-84`-7)> zeYjRq7M>61H;`vMC$%~^^Rh30i9DTsSx^e32 zrSHUpwxZe3hax2*qPnijqCmj>@k}@hwx+spm|C^FRD&Odhln$dnh;k=Y({7D6euwc z1DL$7T*JO$@5weKX8GQe^uM$7rkGj|Y)}@sL(H`)I6#po9$drT6CyN)$2GCn-jf^{ z9)EW@+)p4F%!Q{$j4$N}Zr@MYvyPA)O9)q7vuOI}j*$jHad(bW?b`Vd6I2VA zk4)!?DetUY`25JM?b=M92fJ~9Cze6CiB+c!3D~Uz6NjPGiULg_17Y!=*m;ff(zivpY5hK8*tz2H{I z9~VNox;D(mU?PhfF_gD5u-4e5a?Z;GBfwCcsm{=}UixCd+!e< z2rR?`FkHQ=w84BULLCN2CRTz+2xA2RhWk;dcMSr-?!&ar8NuOReD-B{V4nTPwrlwG z^QF+x1U?%cBo|+o@wR&W(eUcH8tla()4c`$S8a2Q0C4m{EKsbl##}?iSY#It0E($? z0k7~m$#Xe#w)sYL%k??r?t_$pwZSM+#~&}8v(8y(owe3G&qVQlDOjpfI6U%Y8{v2L zvKsEkI#Nll%Y~ydBBFR_DGn^m%pQPDes7^P3aBsf6U(Vn5tegjVzrz&)JPtb#^FJt zqi{Re0|R6OGuTUr*;amb+&uiHe%{XvA&*5-5faVo1~@F31d#w6h@xiF5p=(9z3vwdLM!v( zY-nW8FFLH<$7z)4j=qlT?8}ygT9=+Y*oII+62y#N_*vnyVBid!M7{cSIoJ)PQQ6`i zyg!iqN)sa>mNWO@m-?dzt2h{pK&&y9#>JJLp4HG)%qsu@AOJ~3K~&_poV&X4t|75e zo1N9-!bYCYKVN;!-fk?%UOF)HB)<3ecTA#OLlR^3*&mO!L3uX4)LVY_*+O8l?ksulceZUw-}}$^`#Z5v)Boc4 z&gI8Q7wR2}N89AMy85cR*%vu?Bbo{Weqn3+@xQtR0I{)2Lu`MQ6E^NJU0I+>Ot>)qzO}1tItoY6V417(nCh(c;uE;AUmz=**qPo-b z;fI4R1(=x`u$WqQEBxy5_Xo`y6GSH=yILu%mre*!VmAf|5awzLDwIU_d*ANMY@=E@ z)VNjpr$nO|Pa^$$|8{xy(w@DvkG?lh3hJeIH7TtY7Zw#rfT?Tf;H_Lt`o#cl>t51S z9u-VZYSJv?L;zS$obU}9V0u=Equg^ojKqzrUif?O_7P$HswU#zc9`OLN0KYw9i0!} z>m$PGQ7nT%ZE${ORRjRg-;QJ!Z6ejhqN|pH734X(y&FRPz}tz08|_mo+Qv0EWiede zd6eE68@Fa;-P!X=^RWIk2(TPCN`Z+`5Uygp0{7FN(MApS;%ezc6XEP?2;?k}&t2Tp zTSviYth-A2mI<6(VrgiFOD^wZdRmWKWa{ec5MwPq@x;NUL1MY`Ez?bX*KKR0eC_z) zuBM#_nM7Fp@c%fw)4m-55VE0>Z)93op?CO#81_q<7v^3yO~vjCLKc;4XugINccv<# zS!(;?Br{1*Gr;t$>FTTd@AU(waDDTKju2E#958(SmowGc|A%jEGV>gb{#t0l-)haSBE1)Q&8I1w>vy2AiqjfK!B}%GuTqSfm+Y??(f9k z@FPon*qwOF9ehB+hOUvbw(g~Iu9^ArdD)rd)i+p{>(N!k%xaBUUyFlMlqdmJ=aTrD~F^)PeX>s`7#H zmg~Zmb9eQk?(Dr<#s<_&zb@7bJsdGPu1nvPbZesM{##i#G|)o-Oiawnv0YBAs8zoF z!L++>;-=b^-qqwB$Emvbx+LLMiFTysa_0NHu`<_FN;@u(x9mNS4ilL@y!i3lTkee_ zTYK+VMeH5x$m^^GfXPWEfQt-xW-rs~iphIVZ!Jxtw86>-dJrQ6OhH?&iwb$aou&FF>@yqSawKc=$9gW;RMx@Fi%|U`4l> z4vahG4;<8~MM2NxjK7h!oH+%ZN1TFt_$PIOU9c7sG-;{ z$WpTvNg)WWkFv~gv_WUN%ctzLdqk^7yt4`t&F1c-JhV3_wd`ELtTg7^LG`w-g1+k| z@G~mBcu|oHX-A#?=NjpZT}_?)mEcy@^p@R!bQo*XQhA8i^K0)yThiRDv?r3-qEVdw z5rF|+?W?&HVWuGQk~S@%q@c6%S#}1QE)l!aJoRL{RU4e8o#c}?C&R8-w31d;tL=m?|i_poVC`X zgloh~NBH2|>0B&J8BV__(w=5wlc>|5FR4aM>wKr_uB!K3oU84}OG$UC7fwewJFA&k z%>I?ZVrqdwMR<8!nMi4a(q9p=tLWX|*istOT>swx_|@fWn{AsF?Uh?1GzSWR=o2qa z+oE zgBt6C$hDbh8hyh$QosS3z523x@V)-^08b9?&2f?54K?g1mAU(t1O6D_Rw9%N_Z=N})-RJpcG#UkF+)O`1|*OCn+w;quBdu&}Y}g5p#$ z@hAW0>eebekcx@-9_RJa%SS_n)!dB^QXS#>m&MIdFt<1?5V(fwg%b&eD7l1H-nrXI zQj&>PIkzaTD>eXg2XAMKORHn0j3UR&OPdW%Z*Nt{n?#vdp~7Ms|UUzAbNJElIlN8y9PUfBOZ`I2Xc>K|SyaxcI{iG>;pkMLIMNu4x17lijv;6f& zy&Ek6z&eK)0JLfS3UI@rNhpM!4mTf~`DL?Or3_#E*<@XVw)a-nR3uj*9xBylqBBFa z@KLIS%`Lo@v#$y!7#+mr!nu-0599uBB-4eY^1uCV`rdBzA>jsbPsv9Xw+_^x4T`Kg=^HT#Mu6#Az5guh4l)V3lP7w4*+^i5tEpq+#JNgx zB{wA-MiL1EAh0hott5nlgLraM=etpyhCuqxdau6|w~Vcox1i*)tN=|F2+P!(f!@;Y z4%Dr96t_obeIU~UGvp(K3On}S=pZH+Hh=OV(J#!I7+gcBA>WD+ zv7;W``=BSI3tJI6@(oX4*4u9-5){P@BC}oJ@x<_0D!n+@ai&~D*)Vc7-DTe%Sgvx@ z0f@M69lO^%ULi)CSal9@0hnudD&K6xkdg4MK>YIC9-krUDWP9g^Htq7Jcxs;jTa6gtYk0(BOC!b$7fXH|FZU6s& z-9_vQ*M~bB8U_V|Wa&sXRj6tA-^%;Du~>8^xe31hj;p1smR?M(Z~gg)Z|AFUMh2}Q zxgp$JdoY1q@KGURV~{*dFa7km?&1h{AEw`kakh3DZ}mIBiw`K+(E6%2k=lKbYK_y= zdgCCg=naUBt!R8wGec8RF?WFQ?yqeXQ(G;3n7+%zo|%Yu9%c310f232KK44tAQC5N zDsL+HMxrl;0@V7m<=uwyD(pQR0U;->V))YgUfo{ho5Zgg#Jtj|h? zUn0`2rt(ec1O9U3HQY~Ro048q@EY+*)n=vs=?*wsd0UfhD9N>J`0T5KI`m3-iwzC- zViPHQ8yG5R6nh@*#I~j?Sc5Yfv=wbVqO_0V!)Ri~#OKe;rtk>C#zaNn+gDvxO;hi^ zE80Uo`>F^zcaBZ0n$j01IT2ag6y-9Q`6%Uyh6k)P7E@;{T23vFekk7UkG?Z7zQ;r= zpCX1-jW|;xO_hy$dfv1y^+b;Itw{Vdg?|IV#WQR>qP>;3G{0;l4_(*;-g1&_>7?RJ zOK)gW#SHzODC-;1$;GKA;^oA8OTOXJeiFrsn0Fqg&a#P>D5at`WqQ rrWIO7Z&IKIoB+I^S?$ttjSeDS;zp;B)rLiv`KHq{j3I};8IL2|hDYhRA793Kxp=*O87 ze`H}Goqt*Q*0vDxyML6A|0m%L$DdnW32401&KEh^1RA=WgAuFIaep>%`3ELnB41 zaJ;p_y10A(5O5amI0(WFT9*)#XC`P$GBIAgthynO_+*QvDiaiQ_w-jrCQ`x&>2F8t zu2mi1Dg->a6^&VG80+(?~AN;EyOiZjK^ZuI7h+EUR z?i3&1yR%#qXV&0>O1vD~yN708E=zEJX;FCw5aGHqD3R(-NyW?s*B)q7GaNfhuAyq_ z1=|uo`*P;6HNY~FYRW)_Rtl@R-+hp2qXZOOPV8Ve287ZF}h8n=$(ru2w#`bF{J{oc;Q^yMcDdG@NpBXrEw)lsp$a>ILC zIxd-3iNWFWHJIG4AWP3{&kIybx45$3NZV^%*FE;OBU|_=3-d9%Fe^Bhym!tyn{F*T zt2HeNvf>&xcY+rfgP;9@C8BtL+M41^#A&(r(M0In000V=R?Bfy7d{&r69s%w*s#UK z3KL;Dam?%+`uaz+bYQ&YIM=gt_jmq>BUIQ84Fc0X$VkJE2>|J6&57(N5l5|Z=HB`B ztw~#Wc}pwhKZD3IU~>-Dx#^*XC=Da}t|1)VPfVmtj90J9t$Rrnqo}$h2qPaFRGQ`~Brr<7!&3@8ABF5o**%1>8+zmkKP< z=e0)<7?NBQ@zu*poY7GQg;A6#0gURx17cHp+3rzcoN8upmZKO=qLyQKjby)K+fzu& z+j)@MX0`mHObaG*@{{GwI;_>wbGIEL!ssBD(?POzLWVknv#cW22KV2}W!I9k>ge5` zGB`VLOspiI|4ybHr;Z<=)(;l; zk4~ENr5_nAnP2{Nt_`L={ph1%lIdb%fg$ai#Z?n$8WF|RBk60@Vc%l{W6;)w3U#E) zxyy!;JW#WXS|+7LY+^Nj9fTE4>9f8O0)N^ws8HfT^N|UrjYJ`2nD~o7o-NKATloHV zTuf}z)3)~V8K*BBWzZx_w|1@AI=%at65fmF&MY8dQBCRWwL zH-&H?(0d*|iDhe&%24EKondyAnJypDJ3jez5hWpEmIx-Vn(haDkHju>aD z9J}659P$L1%c;G_s}cs5Qs5m7_Y?9^OkLX7!0-mSmWcx6TLd8DBXjL1OTK}30VoOK z4=vM57_#fOq+&+lEn`dfmM%+HX1#QaiCgc$<4uXc+7CenSWaxU@RAhVTDMR;)eC?% z5L|1~vr!mSF2?rJhl6Vv#O|XE5U!3Z*_mN21@o^Ry$UGyovgq$#)s$OUMwUvL?BO0 zT+ZFW+xgZ}BCaN#oFbH?o^5$Ml(SATmbUO#&prm02{$52{udySgQlXgAn##v>L)L1 z^8Dz-!R5>9R>-2gNJqnuXa-0IQ=odCN^jy`9LkflJr?`-Q@m z4Weq{s)bVqr>Aw))5C*gbeP=Chxvss_RMtW>LL%`aWSSBKdN5+xOg*+b#q}z)f(SM zms|H=t6DmRi4-w371c{$E&O0Rwgs(XQk5jh(57TBnEa4qa^xGjD;j?1e%kTfr1sWY ziLsz}8^}mI*dtewt-Vq(IjuXeMr@&ML)F4%eJwQGyDq};AV~*CM&Q!90E4Z3He?fp zVgM1(zb+-YMb3I>S;s)mdGDRI&f3vCR%v45YVMa~ORfGl-->KW)upMcvZ-sCvMEF+ z+Wv5v^tHEKFCD54_o1|Bluzrr>g`!8fQDx#=xs;Yz{m{S2T351hiqhy-pNBMUna^v zn4UKQy=utSB=NG|v6TJZh9XTzDCt&!Hw(>UcT#lhpK|Ve)1?WuP(DFEG!hS@Gzx{bsXa5;nr7#;ixX-yS$i;?l#+ z%dvg@(ZIxN{Hp4n#C&Lyp8hK^u(lp0&wg{Osl4!FCZ{zK*9#HWaxt}A_Y+hi9OKY@ zZtlDSMUkWZCwaB-<5#toyyp;iMRI;esW3fIn$OO%o++5WMv1CR?;Vrndg%|I<~r0a z+*BkXm#e0=l@L}7x2}|4*{X>-ORiBtF}3oG0O1V`)poW3ol2;w{Q8&6Eti~8)efEo z_jQ((3eH@Tt$z444}LKk#n||^cwsK*Zp|V$pfdtR&o3G=`xN$|sJh7Wt;PiFuO!z> zgE(|l3oj26Gh|yP$*(&Oy0xV_*t=b{fA51>DOAC}9qN+asCQE!7TTtR4uL&)3@oh? zR6r%VcrRyz1Xt$aqOoV@v~PAFWlH1K%MuZpL2Gq+Txu0kx;pDerNDb|4V5!z3`(0P z#T)?Kd)B*rQGNNx)AxRR$HeO7XG;J$c$!N?%debVH`(&!{kw*|J_B6Ym&i6MlppV?UU=`Qu9~g4-*hp1kC*Gp zj>ETe)Tk8dNG+}!s;)oj@qR5A*)@b3rzc^lOkUT$ov2!PxjVfbg1n0Qm0(iPj!i~K zq9~D5mXrcOj8mQDI?1(n+}ny6VEn3526Ti7P%Ru2EXFp@G%D1wnw>WfKFHttrO_Y! zFK1e9jCYv9dm_hm;T9M6)nAm#W13-{pi&U$MzEf%m(~4m^*aNdq;H}`tt$wxGq75F zd(~bXsfxslee^iVw~UNgcHhb*Uh3-~PNhICCN|2nELXu4#wYc~i938dzg88=dKPhb zK8kEj`)}o@-IubViF?|_%ET+c}wNY#yyRQuRdGcQQim0YB^8q6YT*FI zdK`(^S@xD!ACSSsYJSo5wj#mz!$N(xhlu6eng|(CA-?`(x%(s?>?P||&1__fsVl}V z&XkFf9PK|zpZ&&`t0^0p;}$9mHxg9{xIjb)#)YKq9V}zPBBLgkz`>R!~fBHFrs>2P2jBFwOD3zr7PO z&P#gy-NEdl*?o}Kr4JlohWUAO_GvMD-dz5?oW5#=BsIUV+YeGXpf?Ir+~`iDwf83O zje=&b4{`+|5xjMDkZ6O;NwfZ_N;jBDUyX3|Q4bY<{llsJv-|i;V>Nf#$N)e!ck%#A z-r~`_{ZUP-@J|oSqf`x2wR=@NPxHbbrRw9E$KBW@O4!O#u8yAdxFI`pT>41kSATTX zRtscn&z|E%A%e5)9Tzhf_=XHojGY*>oH^NE*aIporjEl%PoV~8t_u7o?{Utbl|SM}9#b^c{p zOue^^0CEWWPQY@LK!h7w<|Nli&*Y;>YsA(%JnK^hRfae>fFS6qNtAD>qhHO>YP+ORS0LEZms7j_ zASfTDxQ~WP2wAovNvW0$*-*p+5W#Y6%_czHF|b_iMQ8@Vv$N)Apxfqg5bW(`IyHWA z3ol*@(QekY8e%EL)`xhtDWUKmS(cEL3brBumNu*@scbb_y-}nM?ra)stjc4Adg;oU zldqRe!#nO4Mu;22TT0S<@Am{Qw@b3s#vXO>G?yu@()g|4+Qzlb6aEGmSSD6)R+F`@ zH5C&(I!uJ1$DVCPwxZpKX+Df}gx+#7wkMx1HolSW$<5Ad z*HE?aV(RRgI}1)(ib<|T=g!3Q^SUWRmA;B1Atuk+$i$gG|5;Hk{e0p_kF<#t5ma+0 z++c!L9twmOKcy<_?lT4Yu-i;ftv& zXO3ut`-zBJquq47lW^o9iKXE3e)A=WGq=lLZ0|aOLN#~)_8-5x1!5y62Rc@>^SV_9 zl6YgehDJvTGnh!-^#sWVB{q@bX1MbpbqzHYWkZ7+mt%_>nRxuF63Ray5P@$f>5=!| zd*_^W&h5TaDUHR{mNOeD7nYmKGx74QS56x5sY@>Q-q&@#`%bM5l4GGqbPN97U*ARr z;IT=r`a3bT8fs?VzL)4oIMiHBY-_5*&;Hi-*_Q=b)^V^^5tlvR(k#RwiyTR6jcl`n z-I$q&`-#M}1efyht&s~;zd8Je<%|Cp~?*9Y~bWre7X5*kXr74^5HIMvTPHYgGPk z@cQ0=wtsnC?L0`80v#(8VY6_>%!x_Oa%_`KOR`=U@u2huZ&}oE-hr)rwQ%BuEsv;Z zspPY<2Sga|$E)U(L$CsBtQIcm>3ZQ^P0ms=bzS)TD0}g(Zayz%~B|>@v2GxzJZ^5si zUi#MDTEIaN<-++_htM!+8I#eEpwI>4{m4uB8VE;hL>JR?bMfJ~6=6x!A$C zBF;K^nrVa6vsyk83kpWukrbG?za2-JlHROddL4zq9R~$2>^;tuQRiQmQBU3fpl>2P z`D7_GrRCUm(OnO}Jt${Z$C&oa)?uO}^|L=7pZuuYf08MUlh#&Nye$CW?2GF1E4Oyt zIJns{GqE06orD!)OxrvoAV5=);6Byd#e+A^c64ex_J@g8Q&DeZm^jJxCx38t%dO9? zj+Bm-ttgIlC|DU@ezK6-D9LqQ_}(7&AI;Y9sdVEZ?+MUW-ozReUc4wrhq26}1^=p- zzM8uz(=s{`!SmH|nfA4}l#k56{-0lb^!N5JUzBRoRzMyNThaOF#pNdzFL`Uv^hbKM zYeu{J+rKk3i9!ubuya3A24DYd*^QdJxty#hyJl(MCL2m7OEB_Nh)nS5?_UAH&f_$S zwMq2F^YY+nE_2-u^{xxA6v~HPj%|NCVuoM;uXa1vs<*zM0l@Cl&hig?yOEAmQ&4Xw zs#{>?@aA(01Lk^HD)=6yq+R!*V=$V zGGvc@W2V4*NSQqK+Mtet6jWd}^6Wj71udq2bT26@mu?wxtnZD?^t4WT`iKAgtlO4_ zs~hJ!N_BPPBw_&PxM}#-UP=5iME)!|sr2@uXJ-$+p&sp+r{C{C`tD$SQYi)R{My!F zH(pMxv&_Uo2PV%KUlwRV0e}k%=)-q^NsatnuMNhfq*EHpnOhBe zT4(Wk>C;?`pS0bS`AcOsYqjvZk5XJqnOwDY2;Os)D2Zr51wgR4Xx@34zI$0+{fpQ3 z-(G&_!`?X3%gZLatZ`yLd0w5Aq$AwAm!5uJY$1I2zWLqX97GLigvHW3#AskHFM}Pa zDElN60}w@3WNWV!x`w=^*?GV_m|=d=D1&mOj$f9z=`$snaZ)c{y{ht|X`?*b;+1&v zs+Mocw;~;($UKFk8fPhjyF2;5Z1Ye0dy`|$HEwqzp2!Ygj8hdbhWGXm*c`HYn~G9S=-vL~c%j2{i_zL|q&D%G;K8f%=mtC&Q`?3$`=<0A+Ep%{j#X0<-&R#h z`c*l1Lb?|s3==1vBQ@U1nTj$k#amUl;X!guQYs^YX?EyIw<49)y`JYa%F`(%Vr=-Jod(*S}_~ZKg(`tF{?A-Tu zZlCNbg@O3rZhm#)7E|hsN5V+>8($njbFT5T7@(Bay_9x<})EDsMNX6|_R>*~=De|z`xxRSoFsR?LBh}(UXzJas$hS#kM z&1?5!xML0;Mcext02Y_@;z!llr)4wua(7Imz`@B+o8ym*>e_ulPF zDAb>=e$Y20b~NjupErz%->dvC;QUSc<7zPMo}rY@qiZWlT_v)jA)=Icu#Qy<F!M)y_-*7 zDewL0towV;KAy(CIhlqwPZIZI7R@BG@9NwjQe)iQ9H z1jFgb^$)(?2ZZsfN_c1Fd46H3-G_Y}H6ZImd_Uzaz5S~rF>vVWF0n{kj+^ct#yyi{ zTKKGYzCQT-yWQWv^>??o?xiQ6Ez_Q1hB#G&-ME;!df`OjB9;UKoiwHQ5($hO&Y(;| zPAq)Ly(gK}tm0+f#?5fh(Rl8{HF(9q0;y1y#-{SFq4{||+D{}zZ~UtE_ImOwueq&v zE~oi0%C{oHXaS(V9V-RmY9T@x@3_8OxY4E%GH~nvvUKa4!r|M!rt-EFyQ>gqBbH2^ zw~-thTZgGIWrzS3&d%@5?5h?ope@uk;R=ahab-=UL|CUxNZXZu=?!y(Znl63)7SOI zS49XZV5pZa$@TT4l!1s{O%LAh3&-SE6`|w_hDbr;Vq(v}sE$7_03aWkYon5S835pL zJzH#8fJJ4H0isk%a}EH@OBY)?+7F?i@|%?eU$lzim844t3ze*?DGNu?!VV}maDlFb?W1f2BX7xa#rWVsHwaR zF24M;Syk}Sv%W~pS4=&Ca^@tT@dmFwEY9Ax=_Y0}xClx~hPrUlW|QaSHUKM%V*p6@ z8qp877Ex(6cRE(iv5A!}Y5N)91iYHUn@H(cMX3^{RZdp8ro*LnIuQk9AnAwu z_o8%Q#Pz0HI8iH$EEEu&<*j>(h`kZv>QyC{d2fGzOKTh-SAXZfKS&aN^e7r^M?uJ= z;K_FeO2cB@B)KjNzqqinoXWXVM$OvA*)14xxxIPVD?}+PLk9@p9e?%1sd(@+v#SG5 zw=TTkSxivOY%#NOrj@}iQvLR+tml@k15&mkVs9skQ>`QHa9e$wXQFTcg!b$#k>_$| zy`^gDZRyu%20FsgQ7X;k)yq8O``6<*S~mP7BeTg zrAe-5XHC-6P3iMtJioMp)XQ;r@p-ut9Vh?_NsEB+>L>HEO@kG-@1OnC*WE4HI!eSr z85NQT1i6qGZkqCoUmKXw@)N;G>eTlMSCql^K>n{55cd&_Ch01Ev|0b*k5 zZ};_oaz9QNZtr&w79Wm2n|qFNm?-bzXC<9F&Hx^aO#i(49@B3;NuNAO=TCY#G8BpW zEZ}aTs`rp&I%&hCn$pW?p`1IDsKur2Y@}!BO>nxzaEf)Ol^ox7;RP39;$mzC6l){u zf)=R@A~<}v=W3FOz&Ka7rpx1MIj6X90zjFl(AbEFkw&JC0Iw)jCc^$uCz%qp=1mac z`46h+Kd8R=lR^$_sZ!RzEXtJ9kn}VltV`PW9%pNgX0if+C?rB|0GnZf0s!nh%(~z_ zfpSb1LeoY^iR=lX5)flbglwQqjM=URfFuis4~xr2@@G1WbZ2RP(U?>Vg!n{G9Lls~bP(S)i)|_|My1)% z05khw!PZqO!uGwcHhMdiZ4DTzg&Vcbvs?EPDfUpIE&ajUJs=QxLaP05E+IVrxH$f} zIQya+zpUpM_6;PCU*P9WE6?CK)qqeJ-aC>ushqiNV8n{3DXFP$xJ`Sw3&84cM_>KP zeCI&N5!#urC*IsVBHLXtBuZEG`lsdPS5-0H05YfOonat()zp+e8$?nkUw&TQD#4SjUMAd3y#FKz#?BUM-E4mAek#6rt|41`ZsRHM zzt=ZWpm?mmmKPTO`d)FW4j)B(_snQlgU9jn=JKn$xO8qoqiu8WFhU2%Kdz5IF2wb( z>w50O#Z;@B>~>J$&bUU>jo4PK)Ad0SdVh;Ez4VM7kLK3jIM|K3Wr{#MlGM5#tEe|w z)OT!;z`(NX8)|Bj(Ww}W-dRBLEALmdj!~fW@W~<7~9}JUU&fb_J6cH zeqB=&*Hyju4snPJWbb(QaVAnNaWpSx4iM6TdGPK2iSOPMkI7T=T{09%u@+*HA7daxS@sUrgs zFUO5kN9Do;KyN2PgtR5lyy@uOY25@z594qB*3RU0b@*;i8I+A)XwNr$d!i-UnNSWO=6$xs?1QPUn z9ksdb!O6Fykc6#}nMKUsRLlelF<`O$W>PYAJixl}>!o~eJ34ySTTWb@1%Xo9*Ye{; zWdn$vgI(I!fd$6==99fCedmcNru{NpJ$Ngt3oqADWC%du9bdgD^&4#tJN3T!Ix&NI zSTe)2-`u|D(n`!sV4IcOVm7=EVC}tagb4|V%z=?HJMnR@0O08_Z5{u3zOmis+FJ_A z2(7=J_=a@OM{%lUIDGtZaq>yi8AGfmew$eBzm+AKMun5tl}s#6tcVykBrPf%277yF zd2(7SjYPrbKO35S%NV0(7c~Gp`QFe(`0BG|e=kb=x+#4zcXjEbRE-YPIMYe0cOIm+ z^vbB|>-zi)yZh86xkiL$>DOpo8*QF8*C)Dwc<}a$?B>^I;KJJu%c3c~sIi3VxEMFKrrCKT0>gZ0zWVpmoktleJpS=KNCk(9e-Ij%R5iJ!Cov|gb)BdLBhVlW^0l+WzZygeL8eg5F?_kIM*VwV-7O6-d|UTGu`)xt^Ily_lj zXJW-3p8sfm7ePSIiT$^7R4_iNyJlebK^CQ2Y3w8wHwA0l!VvOc3LqY(x?cEdZs(VF zy^*sOxqM)ls4ZyWD>( z_m_snAN-x|I9Il!d@K6+_b-IqgC6#urjjq| z9cKf>07}8t^Gbvvi5K%BmzU~G>-p3A9Qo`*Xqt9s`_s*I|ZP9i3+={|5%bOso-+kzCx!WKNj zuOYVHtqeQJ^Ex=v5mn@wID9{k5@oAE6k6{UnK(+7II4;<|M!_bI*R+bHX5fDUHo)W z$u+rbW(&70JZdZf-nyUe&RsuMmE|(i;=1S@F@>US)dLf|hT>E!jpV6Q!zqnPrhoQF zHNDH@!{!_Pr-@ z*oRarxK_CTR+jcnlxUHRt%Hn*@AR&Yt93?C$8ufKvTooDgS{95r45TRwd$)GMu#yf z^bIkytw~4dE!}&sSBXznq5vS@i9mtKD!a@RmQa_5imAQ-Uf(w48fpsf8cN%6ApjU2 zCecvkqu@T?l;j2oV=`?MX(`j3STdM z6#oJdL${qLx%O*Zp6j|W23M0Zcnzk(kO|0mTYpQ$s6gI{Y;|?vZROW#jJprhv~T&s30t!)1Fap08>nwcsYT?!^>87S+s8OLbY@nG~(k%g?UeeQF9+_A{ zYx{E3eTn$?Uf{t8{l%3{GZn>3DRh=~Pu)dPW@bc0jY>hHkt?n)sH+Aae3VE-`v$wi zo0y$EV;vYFewT|Wb@I>IIURpoRTH-kMRj2^(mYGQ<{DZ~?TT@BciMw2iO#Z0($Gwd zQKE!FBc;*Wev+AZWovl&UcC1tZ=1eAZ0Ts))tr{6cK-GCDgL$0#NKvfV)QqN>hJvr zJG0Xo5KOGEnpG6X|!a@#|j&B4Pc z(Rleq{pu%WHFf0RF7#EN7iM-1ci|}OUmPVW%22J*kXNDA*8wahYPr#P3n1Iuj)J&{ z*9^ZnnBjQOuI9UnRbqB)m4IMa-f@!YI2Zd!x@M5qy+&d@SA|ZeFKvrKR4{&3$zCyj zRmuGoa)4k3NvgdU{L1$qE`Zrvnx52Q3}9(^827fKC{@MSFthibn4Gnu5nzCwC*eI$ zPHM^Qk_fms(@o)31a(zz-!scAE3_%!Pzb3*@Sbeti5LOyJ?nYP(-ZKHds{}(s31M| z?3+Np5&%d%9|PEWn6d{QDL^F8h^P&gbD;#GSm-XtHqLdv6(ImQ783?U>}>}}cJD)g zpxi8P88sZfomWfO+lfRtCCqf+N;GU8axIUZ^_0T2XQD()H|H(a3lFWBaqBRZtwxfp zy`^&D58uvB5d4y`T;n!NWolT|l6Z=@KO33|8NxQ67a+Dgj5;Jf|S_lAhD zXu)*xhm`~~u?vtC(JpA^&eQk(zqivp7$5zo2PVeTFA9m+4E{|7a#!S&4EN*UQ%T&E zJ_Nc?uI~;4#Wkgu{9W;f65^i#Sm7YVjR%#8iGT=Zr!};{LOyw%YoXtZA(yR4ZyI~u zJbdy|q!dIkG6mXsJ~XJXE?fXo9RC6aRu~0@61G~nbt{mkzdTx8HYP$HDW$+W&bJ}} zbQO6kD%@2ZX4*Gm#DEInCdiE|vJ$tn{Fa%|L<|f`&vbOVki+fSTRQn{sSW;u*&sl@ z^j9w{Ks2$E$m(oh(!RNFzAkNQ!(AL+a^tj?&l1WSYAYdtD8+1O^bI;gz4UEh+3Mhw zCs|l&QYoH(UOoRoC5eXtoebg6;jz&McOGUkr%a5e2rz$+^rw1*Cpi_ z$7Pah_8g^Zc3$^)V&IMQLp8oamJLov1SK&QhfN)$Oh z|GF@V5`l?q0^FL~>PTs$TtnOUQt}XIS{uChs>B4-fqDJhp1*R+pnyRSKIlh@nw>Y2 zddZ%vDIdPui!*H!CCTo$7fhSAoN4b4^J}U!#J2JG%I~ z9PY<;>C?Wh=H5gou@A1{b+VF4LjO*d<5YkB=hF`IV9AtO8(ki}-6PLG_-Ci8jmo-4 zFA_xf=JsrE*r>~mC?-zEQ!*D#dKw%UgA(*}?^``N`$Rwyr|S48bE-JX#UlyG(ayuv z7zD(6>4aI+AL^}rounJP`qeA<;z!j6@0cMQXhcYIt&NiNT8!J4SB;R%p8duM6;4j; zM;{I1Oeuvgf4Z2Q*5Tn|p?t449G!)D*2zhA?^)kgUWn*-oL3uvS4xzxsJdK^H3^{v zBq4%p*wxnw)a&jx`EG;?Q6pQ%O*l19wXJA&)(C_;AV>ikOV&~2c=_{XW&i;4n&7I5 zjCyZq{>%6C|MvUCofwCi+UuF$`ELIoeXsxDK~9K@kK3-lbAo;9nX2(O0_qDgPp`xC=*PUT{C#0>B0bYR4LB|z{B z0a$6&3ah!33E4W~rMDHW_&&JNGOgWx=txZRKcoE^)>QT?Lb;pFAkflcY+DC3(a{9L zh2TEDp+UUfSPK2hHEbI?de(E5uM2N$@feocl*N`l8R-5_B>v@6rPK?b?wTYI_zDp- zVV>%}duDr2k9PI$p~(`}O#EVE#lo*HyouH8&x`T%x}JLWZ|rgzh6hPgI3eNc8>B6z zF-p}<0*=-gY_1S=>!OH=sDg99Qn;L0*>;@ex^PXoQTFt<<0w^H-C}btr&7KAe`$NO z9@(z!Ol++^oGIpr9Ph|`Nmj9nWU-_g)Rv{TRNZa^ZOJg)uwfVt!|)IAzwj^cv)}yI zwqYAqqq_mCHFm2s)W9N(#o~15n{&o^rade_tbI;KMrK~JBz1rwh|9c@5$Ei)_gdfj z2Id2TjwN|wwx)L%ChjPZ2kd<2F6Zw2*p2U`E#q?gehR@{AG%vncN}q>7iTI;<+7*6q!%+gxR_9c{gG zb?&7MW(eNW;-p^J12W0FEkClMy7SHMC3&VL#y16EcOb7K!tLg8`I=sO{AY*t;m5^r zKc?n>@gu-)FvGnVfK2H>`HS;S;AZ?KE-PR1Tz@HgechiWne2~MuOsWJ_tw919@bEz z@S3HV4fMLgDfE@sB9G0ceRV$Cz7@+1$%T|v6v%C+GvqDRg}p{U=%FP>UG9!Uz5y?L z2D5Ge`^5aTjuOcxU;XU}2$U8=AX|pjm1nIeBeuL;qf9wRWQoYDfe~@#9FDp{bm>(n#$Xn ztnoUQT(OXcd}pwrPgG$tq5MXQamhQdVYuSbKgsbzqk#I#Ug9!AiX)P2o zz{gUXo!7Fss{)0{(~SVu-FJK3yuI^Jw?_MMK6B;5NrldOrBO&^>b0#siq`pv2?D^t z3eY8P=f%;B;Jsg-)?6pC5}{aF=8|=Wfj||lpYZ{^Ar{?8g)P{@)(i|!u4aaatnruP z60SVXospIrIl9{!%6cq*43rHDIkeCz40sECI|2xe9JY1-yyX8uP4?5J{%5467R+}${4`HGii-gL09ijoIxbJ^+i!I_ z7%m%V6^U|X>%xt0C3n8rOM6Nu;`mW6B*tAO1b9#L!#W${?i(E$ajsl*D|`R~0>C%G ztJj|axG#Q~KlxF4_;I}s-fYAeo62|ZTvNcsTbFK@jF44(rt)z|{nh_cm*olP%rP0)$ zn@^dFtbffI%^Bi7p94)e4coUx zMFar&?ti-{6$%MQU*u6DOy!e~I(uHSLB3ApM}KmP0;%EEFAnQ9(E&;&tfAG+{N!I9 z9e$Lzbue$;abpC#^I9e~D$Sft2zdo-`u8_~XS6}7XzRfB+8UeP7#erQ08$Hx8c&(- zmTpiFlp6o~|32`JlCH|yKi&= zfGojUC>1p3&_ZCjbVA~`MDUaeFovGIs9qjbuM7I_ZbSrMGj=pko!z*vaeu65x6(&j z$-nrt_&<;8|M`!me=zm`+Q6SlIg^-AjgH07|Kw~PR_^Zv16OaUF1&Mu0+WukHM@o( z0Gz+5SorBJG5)(euNlNa2r~TEZhU%BCSBRUD*-O|&R27n_T+F|ZNJt*gxOKWN?|}K zmu~Mtq*DPH9#V$d+ZK_rjP=q70n)L$v~U}~QWWEOPi^goY|Y+S1=5XdNOJ{L>!mci!%`X5s4$EN)u(AD+Q{@mKlFkBa57ah30HM>>^N?wIPRB22f#Jb7|A zVZ8v~Q=X0_J=HF6Az`=|Ga_Kk+K3|9ocqN|z5QCMG|o>Zs5b;kP9k7uV(?b8p+r#~rf zK(0c6=#6)l76%moh$~>YbABB*x;V5XUfT%s#==@-Rv57{0z1RDmxZrIJK$rACr}|Fuq($?1!-uKaT57E_-u{L`P7haVTqqq<%>SNRKybGY)CQe}k1v?J1v zm^=u!Zj0mU6({vou{Pgjd$~%~k?0O(er8S=vt4ecy#He z4|d{mX_?r*{$alTds{jZN1x~X!FUfugu3#>y+lPqT!}0*rSA;Xmn@!NAyn{{49siQ zbD5AgQ#e_eNuF-9s_stox~l_wN8AK=A~SP2oBN7;W}L~8mevSn*%6}7owMGpZ7Caz zkRy+;{iR8l&Ca|tH)(JI1&nVcyhrW4mZ?|}fldTR?|Db(&r2X`9Tiy{C^b0ah4uiD zZWW9n1jb1NtM#^HAq4`E_uu+&zz54=a?X*byT5K2ub3TG&UkOVHGbzo)){FXi*jL2 zX|~_+%>Oc#GnLB*x>{Kv;)w0KZ~%1Yn>`ha*|UyU<@hczm(yADo{G8Uhu>TB&O7UE zGe;>*ZzEaq>9lVze$i4`~AnwDydc zwxP?d;XDAb?&k7Y!n1l{lQsweE8f$`%TvQ? zN1G@8C8SxY2ziFaby8=n`RlNy1qXY-BK0$zL@qdCRk>TQ=I^}I6AJ6nvCB16A(%JR znsY-FF3bHkM_n>;sYN0;I?QrmLlSDsRASVV>)JJ@85?_@KQF#~wm{_SW?>;P(9VtV zr++!!s3aQgLrC0g2eucJmIsRMfe>4pdE%~q@6Bwm6CZxI31C&Z3*RUtypp$}>*jUL z$NYoub_QdaWTLf6LTvf8L_}#V=YKs#0o}1y8f{Hcs-jGK2QPoQ8t*6D z4`LyO5Fu%+)$$-hOZ14=j8WHDrjF%x<8it=S6pXWZP2OO+JbdS{N_sI_G?)-P^^mt z06(eKN z_n;y~fmQCR-1Wv00hq#NL;a`!+q3Q@B7k4~@!40b1gxR?xeZu3f-xi&p0|Xx#$QG% zK`cdlZf0wOvX+#Pbd}N~*i?I3otw^B%UIaTpT8_;M^)Ta1fXKU#Jb(rJ3tVn!q%R* ztks#(iLfR_w46OHci-rk!e?EPbmi8)H0f!6{Dr{fnXwg_+Gjo8o#@U;Bcdstt$cm% z?aa@g)<-`tPd+PW&#Kjt$uBb>-~PcCipwB8(Kmj3{N(*P)0Dgm41DIt(OO3b0#qzo z;_;;|g)T`5x9%lE3KZD#IJRF)QJ~afbyhcnPHJjmv!H6U{HEG4Q~40dB7 zKx(v=pB`33O;EA%^A|PGY`Z%V0-y-q+dRElm+i2>1ONBln;mR`X4XEFr*&ujY@}Eo zca4zevJ{A;TSAPc^*lSh{f#b@k!31&9%jyv(kKLQM4c(UP6YT1EX+GHg*O#@phCTL z8>Ecy{8!uKZ8h9d{h{piWSWVKNi30bU@b+N6iSH3rlejwq#k~MfC6Cyqsqgp;PJYAJPw92o+ zy;ulfyEj;~WBZMr=m+=H_r~hK+>-y}H?#lg_2jpN|7W`@j)f3#cxqm|o$PK!zx`hC zfBF5bfAYQI?nI9ytZM%+4()*!^OLGr*sQ0Ad+`~P1rEle4{jFGOq0J9l&^lT;8Z8pxBW9qSWm zZAt7t=m>$P@^#@^M9+Nr&Pegb7yuo?Bn#JWb>6diFcovNbvI@41$R4uA%UbWoDirJ z$pW_vZjL2edY#G(xu~N@Kb~Ec4(YxKQuo5wg-^SxUO7(N?Cr~&>ns@GNdVDXy8oR4 zTx%vsm+WHOwlf^TVJ=APhZ)bnTT=yq;C->)PmcEEYUP0Frkp+=L2)=h@M&^nYg#AJ zv9?7BoSiu~jqPn|cK-l^<+)|E5h9RU6bqYlHTMF%K3h;mNbo-Nnb+F0mNPniWS{(~ zeD*uT%H}h>|Mf15G)?Kb#=hyb^B}vTfrTd@ zEM}*!%o}yThsB9M_{2QpH{`x+LE1OHtq0*z^p6SJbQ8{)rs8HJ-mvW zgRcNS(vBQVRMr*D^Xd&ncOddJx52#jp1qS zKiY_>BTRep?mN8=R)LDdO>_Z%s}1_q_G>A_qkIN21G+eOqgx3IJbhZix~ZtZa$!3o zEtR+`837ME5&r=hSYHNX>F$?#ydVTV)Rn`vJJwezc&{*nBMK!Ac`}z{VVEq!42kyE zhs@TcTb$I^&`or*8}1$PI_!<3D)-J%dV_?JPeVj3=cd0MwO@2`T6;@X?%4Xdb(pa= zuQ$Pd*~v~Vle(GLUcBwz>siu~yj|RWR}^!mZ+Y(=dH?XAlp!~kV0C8rt(>9WL<@!U z!O&}YHH7> zZwx{S#KBG^6y!6@vwRNmU}I4B0_u)6BFG3$=^3OWqBxTQrz4P(ffuR^$2!N}R+Mz* zd*E?tQ7WD9mnw)SaH0|KMKXDOAJzQB#AqNuXQZQ45&<;fu-C7u`@c3&TD<&d`NnUJR3wDN$M4T?eZ9jz{5(i0 zmyS2D?pWzWG!GlK-XFolexgsGU2^CM1zcl|!LSIMbJt~~y(jRVvXO33Ra#%5yr=Lm zN2rLup{=MctcrxIy^h5Odu45gqgV&jM1E4**8$Xxi@elRIgD zD-sfmneAnpE(W?T0wXNicI@FpalA6z(4 zFdrTf>hk(Ga+cTv?Ot83-x?|wc6=+A0^a|Z(;y>S!yl7vm&{ySK+I03%W^JI3kd=>TM%_r)tcGqL{uxMBH^r0I?8*v z{Z==hSrt>fGh3Z3bd1SR0w@5eOSkhdQwrIt+>}1fWL>(X6GfjS;a);z*#C6 zZm=VHw=Gwe*X`N!(pFwYC=^PCN1x}Nanu>(udstPJ5mx7B_hF`E0V0f`t?|xLac01i(g+%(q~YAn9T6qNi*0#wJ9+lu zVtrfCiL?$DC-wMF3KXVfDhffxMWaDrF$mkwmy1`85zCd^d!rL~WRuP-cp=4^M1d`e zA!D(1Fa7Y}o@`F`L~#1FmG6vnYgpUgi7$--2s%SOJ*8} zo(?}*b;g>Sed+GE`$Azcvrj)<^d{On>TN}cU5-`|hU zSMEjS|FbvJM4$kgFI}W?dTM_D>FSq{idc)olbQgsM3j~P{Atn6WTeI3M87Ms0RM3$ zeo0`BPx}fRl~$EI9f_+w!_I4&GhS(QwYP?JjO+<*Yd^l76mwh5t*w2OiqLu~u{yIC zG%+Q-C6vfR$kV4Ko8$5X)q9F#SJ@AbrBMhGr;wzS&wQIClZ}K;dFiI|hoB$A^&4}oZH0v>KO{OUYyJLMk zH*uyG$2HrfX9FFkeN(&M=yFMx4fJ3yF_kx^lab)$AH<7jCmzl>amG-stal_+Av89* z-Gm6&hEPX6Nd(@IM-mcI0(zM2DpS+7>{Narx9+7`U!OcJ=EwD55?$@d8{#c(NC-ns zh%J7)W_BaMd-4s^6cm!4DgPI55_grUJ>wLYdfT;3UQZx3dh5L>3iwId)q$Amx=nX(5 z8AzRo{!W~9rT1SID?z+q9^I6Yrz2ER@Rj48O!vhl1d#dvjauRrQ~%A0X&mqlTVH6v zIWC+Cgu)io7~M(`fC!31JKUB@PmT5yzS`}(rG3SM54v*UP3?=7@7%d`a(5>oo}R0V zq@${p+j%WvNVHnm^-u+FwplrJ@??`7P!-OWm<%LJym{sPeE?YNhc;b&H3u}f6W#RN zMMHzVHuqq3JAL}I`Nmzl_QoMzkg)hP-ymwKNCp7HdLZ=8NU3#)SWQiwNp@tv)XNk2 z8`cU6bk<9aw)RvsNWP1(- z0J!m3^|s@{q#%e=2yyQOfH?V@AKs$Y#pU!x=`8`ma4*h=k&49pq#o==lfU4YkNBP|L#u^blk5n;cg-o@)sco&UmR&r@_8`d^_R57E?MPPEkdjNN>Yf z%T#`GQgaj@?;c#DbcQ-mZ3t!u6+3=9v%aLU8I}NRI@|EUAV;&*8EUo*=Re_$R7SYG zy`a2U^y=zi@U8!1n_WmI57OaY%!<$`mHeBsf#MuD@5z*2CBYb*%PV4zUwN?;5BHKw z38_TR5Rk{wg|QBM6>&m`)M1jz=VBn$6RZ;{ZS9#5lyD>vg0o~Q=N(*SU|r%#cBGJ? z*gwDYLSb(!Y9LG~=9Yceyd!!w0gHiZN2d1c6#6@FccsGBnUNZ0L-BCNlcS`gSg6&K z)TDyOQ6h}F0D>NBQ&h|j?s$Q80-!@5cO(j2G&veAB!}Q_?XJ$;jy^9LZ|d(x&6T_~ zVZQxVPet^oBwfVbSwGApIt+=37{+n z@(8P@ZRHmSb$;rkT(dmqu$$ZunjJaRpB{9~iBatEV!D$Eh@?b*W>hTNoN4yU50VxE zLSV75aV8h1)nGef0#Tj2!EP)SI!8K@rt&OqtqYe8Rc|{&gy$bGJL5>j!Wb`W1c0P3 z2|!8&gym_C7p-KlmPk?&#i+B(`p57S00_hV_%Semh3y(!haL0jI_3USH!@M#IP)OziuLht+)+taN-Y*Ab-PoLgQ(LCsNIEe2@%Z>Dt^8K`?B&n zR){z|teBn|B@zXL-CggfJJM32HI&b6oJk_GwIA-ri_<#kNFq3We2LEU=I@Li|Ml$B zw_dnnwdS`n)+`#ghSFFd!bg963J%Is$4ezn#JUvm>Q+$YF6}GP7z6PXadA?kM5#r& zwBy^Usr+C^a*g%y*9RZ}yEDc~g+if(cXaZk*nK_Y&FA=0{@(BHNDV}wGJz5&canT+ z7|S!Y2cozm+1vZp*Sji0_UpX~Vc+<~Qj6ouaSHGL<1LO&Z0|y`u$_VC<87T* zI0FFyo`0Bc-HYSiW*d-nBp|2=U;c9CENKtDiMACn4BE;t@4naLqxTwix zI=63pceFkaB%*YnmuChAoIWk$R5F2X=RwB(PcgOLQ`8Y$$H$rMjdiuM&U$Y=M}?$4 z^~3+;`S+YdWT zAHLXT@1~uxE|<rTki!la6*Xt9w|n?-FK%4|5FzSIHqhKaY2%Ju zoP+_!2IIc2sIx1@)rUo~wRv#4ay5PPKb<69RTpjp8WsY3+mY00O8@bd9>i4s;0v1$ zar<5z^=>cGQIdy~kNUPyF~t`+)9jqTh; zY7tDOeTXDttM5y!KpU*YuS4rwpYH9~ zGByJ}e_r+`QFjtajb|@vA#r>sm0CDQ0s^MyEbYFYc?VLGcc3SW;Kc37TT-!Lr%^tp zg~Z*58GBL>cVp&nk|)L9xE{)t+kKEQp}|>l#;N@n5Cozrz0v{&F3##|<;cF^6 zjy})5BR2QoxbyRuWj0hSoMI=O?pQ-(0t-Y;(;-haFB^oGP28Tj?3~Mkd9Iz7XGTS0 zaa?C3%_AjS6EhWrfVd;6u`i@c;@YP4WD(r*)ZBTy$J~~epDekh_cjcQ5usdIXX)J^ zY@I$UE*?uqK`z^_CvoK&LvVo|5b!orIa4}7&@uAdhVMtaKeh^3CIm6Ylm_prFn;H( zpN6P^GxHWhTf!|+cdUgHt!-17(GiGO+Mn|kG__yPAKZJh)7y%K#IxsRkckqnD(^k8 zb6ZQ&c9uz02nf_N2H__9l?eo^5U1k3^(z+<*~bH+PE z-gvw8QH&QOCI`!@JAPr!da@CQ6NnjtOgiP>v@?o$iKcV#?!FZ#shjt%kqR}%q=~2KLE-cq=UE2_W7Zu72P}~{MUL+?^3Z2NJ zW-A8(03ZNKL_t)#^4zu!_mkyW%|VbTurA#6pp=SZ%P8)s_y5iD&V$TbI{0|C@kOe+ zs|&w4xARkbdSKVlD*zbm#8RTOBqgwYyE*e_=3gCFaIt<_N}!PKmc66Z)GW_TT{uJ- z?#JcQp#UL4CE}<5=D5Ed^|zzdxnW}?sZdDdwpM8&bwI(`Of5e*LWP7x4$l$_Po5Mi zmMRh`vC8dmFBTFxfMRic{S95;d4BDm?g(+|Y`*(WFCFL*rqkrmyP6vhs`HHqaP(`Y zo;npz-!G4TSyXG1H1A+?H)Zb0!DlNXFty)#*x_YBj{4gnAN}sz{pl5pB5dS{D8d7q z&rCkEqg!!zOCPQ24YPqp5z_JM!m(cO?0I?X>m3yd09>9MHraJGAp-BE&eHjdD#|41 z!$yg`{mmW+FNXd>016Dj9SG4tVhg+y@eN7`I$t`uwxzT*&dx|@15E^-p=PNsh4;KD z;a~gB!A;Tcmul-Kfj4k$O^D*%eUMFGmOvmQOb3e77@0!CLm!URT;CQ1ht=HX$Q!bCi4h=(fP z!~EFyw<71rH+BI$l)CfHp1n-6YmaPfS-)IW=#6qxYi<{^f!B7d=iguCvm1Y$dC07gPjBsHsIR3@AS&069NQawF*&mLPC{0-bl$) zJ~hq|SE5|)6-x^uq>(!7Iiiup8M;IOp^gjPNP0KG}X6QHROiwFX^gcZe0-|*sBSx;gEf! z6J?U^O?Mt< zu$}hzvVjBZE|nG#JSCCiZdV~ z$R%2gcjS0Sj(62~M~$}SU@W_RAuoa=Zve0kTz+ohSAQWu+E?CFwQ{Vqb(ZSV-+!-9 zMA#&W!;w|n9`H?%a*#~*Ku+DmC$XT+6IL4QO0q+8^)zVk5ktJRa zeG(B2_L9}iOzx)F1S2#%-rk!XuEv!XY#`-B1w|Y6K=9{sq_ij&#@3!?Qg}tJGTcuB z37UfO)2e|kci(gAfZFYA+QcZ`eyb}rRx5XYP_3rs)>|FUG-IQHt$V2{oj~Bpx2=7g z3KdBqz&n^eP5XDxS(U=(acgByU>kME5!dR>laN}lHMZ2kS?Z0Wq$i0bgodKD*)I^d zjU`Xz!m%?Y^=W7^e3IT<{mU$pB5GT^1=8}!YgE|Qo zJ@eyA$6~M(^RZs7tTX=c`*S{4sA)@!ndK-dXMI>C4w8=IQ-$a|JOTgaa9$Lvl5r* z=HQbR0l1ptuH+-lJBl*7^B^;|Z;SYF_!$<>QR_<6y`10VJ@M(tgGaXcbcTe$-d4=C z2!=m&8ydy-a{i*&MFeJk2@!FEBF7y9MXA8%^7G89J;3NP>|QnvC*zJR za%^Rr?e4%rRwiQD%1a$iL|geUewerD)qDT>@Y?ah+rPUdwLk#ocR+*1Zp>t?@qoDZ zMu-2bzoj}o!B&XF{iJEC!8vl)r+qcL70-^UYw1^2Gm3GB8KLB?Z>uzCsm%TPu{%55 z1TtFe7J;K4kvtuJk#h&dVi1ncVB7=+BpuZNSVTnZ6;+pRc^)h?q(*j_b`Eqbe(~pL z3~>@*lu4;@ayJzMR4lgcXKbdB^;K^xYHMpAHLST91PT^owTL%x0}%i(Vu^WXT|PC#y;#Rm2&|S)X)NZJCoN1BWL9=D zzy45PufRGZefFZ-zMHmxa{pWX*+I3MS!h#4b5|~{v&34$jZvSiE-2nvD!2BPLbPim zP-jVMj5`Vd&R>+|h^?2RR7izY?${sU-uL=(M_kQe;D9P#BgMkjr6&RziTm#jq{5et zY;EUZ)|*5;j9Q%5Q7U=h7H85{9udgdreoA>sJ5)!lb`QVTcp0C4N;-Swt3cvTRsPuuukTodzEl~OE^O*MDznZnQ4HDZnC zy}R3*12-60UxyOz2>R&Q^lP_$D~SsCeMN)kMOT6p`0!rR@2V^n2gmi#e!2SearxOn z{iiSLpQ8AKPl~^eRQ|Ao2-^>`<$29h!6+4V>8ip4z|#*F?QiMt#A#2}D{E^apvKSv z*lU05wRCn=F?QK%6L|lezO2I5A;1|AA{azk1=Aa&BoTR~*e>)O%m==vaLE@1{5Xt#qKS z{iXfwmotU?aKq+lXa6aEzAlaSpyb6J!JJtw{Z5gEn zmuCp=o`BxN^7LZDLQ3S|>E&_#r5`LFOWs@JjsnDL>8{egZ0_9^ zl3HuGUw#Edude)R?xrX1`A5~ukIPL;(JO!t-eAAkyF?jFuR(&&pO?1sM3fD53-2=S z?1}QZT}<8NP7-FNm%FoecDr$eSxfzWx#6LF>#eS>Ja2~lC-ax}JO6k~D9mRzzfx0m z$689^YM=J6p*S%UumQ9DllRNRUu?oyHz_p#b}zO{SWNwf$II-bLS9{(N$bZG> z4FGVs7bjhrc9khzJ~h{dS`xwdZYq@^py6JOqGd{5FNdUN2*GJfH<9Cd6Wv@8A`i~d z;wb#&?pszW9)KVbv3e;=Wq&*36UUUUGt^QGshNvi-~V<$Y{Fq@LubP*fxUo?Kf@;a zhC={VB&wCY`*x3aNTwHYgREk){UFn^Se({O^S71LiJ;&;538981HYz>M1iZRamIH> zdhhj2YQfz{o3X>$k=4q22Wd~K2${=v{<7?C>BV^s0$2tvl_(a@8t;uydkQFIS(wuE zlgoc=d?yhyY`@l!ttpJm1L8%dbgQWm0$m-TPiKAHV<9Sd8%zwArv}%uLl8mApk!^i z%oqPR#De)alim=g4-t_yRIY;0I4T5!xFZ>KGnL=)2ZqW0Oe#EiQV4-eF*yD#XAs2J zKJ76I033(+@H>MGr{|{jWu+)I0Zfd7ZxDGH0mXoMdG;p@YC9iPa?Vk!P@^UvP_I?4 zI%WU}8A~b_*3|6ePfFcD=WZ$|Au;Ky?kH+GTp@piLsfu;MCJ%wJ2~Mq-c%P9$2)KL zSW>i_TB(phF>+Lwjy$zS$idsJk&JQ+TFfj%Q8(^EbUE3_kav^~H2bZrUs!fs;lZQS zqFVWPf3Wqzzn)!7*x7(BbS&ab=5uq?zQF8yTamM#jVA#h>PV$=y`x}y8aZ$^-T6jO zD)HeTo?fPcn`a;7PkvOc%_Y1uq!x>Fck;rX9l6ESua^|-Cg=!Qt(=NQ%V}hi zSKL*MZkW=u$vt-noskaOH%AOepFAmSXT%4M0r~zQG8wo9hMAm?`3Z^EH9I~OhGFpWV@eu$-F(N>IZVx{!&mWs8 zMj=25P%0c@?buCeOglIj%e~j5^(&7uWG%7Dj+8h(thjIFxp#Y~dXq>eLP(q+Rvd%P zyA!KlAOB>&o@qh^jKc7f>m5}~$CL2+Q59#h&K)2~Em#9`l5 z0F)R)OF6&!q_(wBIv`LZdqQc960!cY?moY?>QB^$ zktzaKx$AF70H9MTn#kv-exlZ0d$^x`C4>}16k7Pzj>tpOQM1E}$Nqzz7!j+LV@^0V zGjJ8lXFp%AZ}!eD3t-m2SnK%{RG8{ZM&~9)^q+QPD(mZJY*7xuB7&|4-uAxm8aVyO@@}n|MF2G z1^(4f=gt!Vq=|^M=y&D8N&RW*|MbL|Tglyb`mg`qE^f!(*kekQm=iyb1B-)hhukA^(n&m!_dYAfjUF0AT0!Oi0{d z0`hBgKWR($%}=6Hr(y9Ib5obD{p8(o#DUqf!>THrchnt6Q7Tqvh8O(NFIO_c;CIQg z5$6FQm|F0_TQZxTW``wD)Z2Z46$4T>ITb|AdSfrxCIN?wPk*)QTTi`g>rVi9^B;|# z{%o;0@h?BFAN{C!@nOC=s#_#t=RwBN%!^aA^RUx?o)BU<)a`cR?9H~>&7k*Eq(CF1 zxY*7_uv%Z65&Am!++$q7LI@DRl%C(2$L6N;ZI%vs3K4`70b#TyC%Y=`s#ZV9JsTIX zX4*D0D_wUvK=wVchvjj~sL1)2=*! zQIe*f}sT$aBxE}Y>h<(27zFa^e0mAMiZdCd62w~k*X0TNHGH>I|K$Dh=$HQi*;rEHcvp>fl)l2*JU?*jm}#RQ zzD7To^wn2?2Dk%)1`@*NjkBKIx~qA{Z)Z4Ei&ZS4`i>Un_xTldo{ zciBJ}b6e%^CR1rwIY6lMAP^zKYoEdO%fb#q)yi@AeYI;I?Ij@{mG~?U3d09KsDro) zxtRri;rhUbk6pbr4lfJ8^o7_zSVDD>PjvI7%?Vj~QV7YSa3D$boHk>X@u_4DncAN|FZonzK@vnr`YH^f1W+T?+q#zqF_s5Yd3Muo-Ih%0 z%4YBo#o~eqZpj*dsrG&M_qU}&Q+a2+icm@*4`2Lb*1!jnX(s$VhkLP##POqonpZ>r zA@FT7UI61a8_9r<0&}KJ=~?Q+OsmGr=^_M&nm=qyWEPt+T*Zd=Rqlv|mxivE!mZkc z%R!W&W6|4=gbZd1!OV8P-yeHW^sf+scy*#mCNrOllMYPM;Q1Axh*6Qs?ZT zNtb8TEjJq$r$)wMuexA7U4AB8Q&sQC8*-N74lmP9IxhPiAfnPJ70wQ>$uHe`m@Q6> zyFBiG`*$YHLOS{)2Y~**3~a;Ap&dBqZB1=(o{*SqOQ~?{Udj%gEd=R34R#|=V_jzz z9e!L>1^tn@FiBaXSgTl+1zjtwj*^R~h!+g&7sy{UwB3Q`C3^7bstI&JeyX{ScP5b6 z%B3rp_U=19LSnLgoC#C;q^k}-Susr0(pjTa=v3%feDd$lg+y2Tq@#ZH2ZziqluB?M z=?1O0wee&3fs5StK(lQc1Ar(Ium6M2a7!(p89VcxzUU8SZzRXNYPhX>BQe=k!)@6c z%F&kG+E=4(*&C`j6)L{OfM7D3H56wYxdNS1{tl@5kIz^u=eC<3%(a|Duu)szgX&62+5rWn9?6V%6aU=p?F7MPo zSLp1&(;4hW_3GlWl^V02>Mno)@mS;HE>U!GGeE+?Hkm#&$MX9~5NGkEvK7bO#>lCDAowwM8g*hZiRJ#+qVe5?S)zOZ)w#>oLd2;Np*!bI?q2`i@Zf_L z01WQLTW@4UpkkR%t@kv2QB@1SbuYmU=!6Tz`H4zuTX_tp6?@S8(DdHu#5XWgq_LK*!?r2CISHH?#Y{(Qh3LM)#6+0z!x| z^JHsZE^XV`^mihjHW5)>cto7sOUi|fQW4y{5l~{Bsn(y7Su;Gk2LKSDW5L;K<-)lp z{eb_ZF1$D18qW<9HCCkUB%cU;lb%cfbh$vfCL&OvvoyJrJo=l9>yS_B@Dua&r{Q3_ z#UXcqv!iOb7oR;V0pRSBefr~aup58yucl9bR6O~s{P|Dvm+xOw^aOB$m>Wf#IyAg6 z%0xge&ewG}9L#EJZz_Ki#K~I$wfLPSXS}IBlMc8GYUq;?r6S#uf&9x(y$-6SC89F7 zeBNuS!_4GOik_zD|32aR|n=-%7){Ox0qYb`Qi(!G=>BrN3VE% z03c3PXRO!XjYrqB=XHbF#_K;nxRn6Hwb<^(!Q{vzRCDKQN_$GhqRL%9yXIr87QUD| zZrE05X8No;`=pvbtIga=`6XA=IVzSeUy^ezlQjC3=vQ#XJHNVu`^2f_iD2B3bu&=! zvFwI`JU#zt`Q~qT)1Cq#a46?$>^AmxIMr zBsN6fy{*U^a<#7u&j~FXwZTnad4B9){Jc8-tTegv=I`4BYYoQQ-dC(M;8ttxQR!?RM?`n!O$$@o?(;D!?Ns7;L zz@Rc_q+|DCr!G8s>TkzH(BF+hfTkAghifY@1d<0CVXzdJ0ul0g2rOEh)+)mOP84Ke zo)F>uMa9r0IdG1umF*04l*nd!O7o*?IW^7@Ha6cX7929x+lr(X3`Xcga2-el(}Suv ziQVC&WD9d##B%V!}+ zO3S+N<xenfJ z-qP}{ULSD;N+FTb$k*OmFB$`^Dz}@X?8_W0p1C>e<4p2+mIE&@{ebbN^0&Ux1AyQD z@Aq3|hhM+>&$o$S!%!*hDwN3T+2cpW!|x8`2nQ3H##e5f2liJ&0lN>g=A6&~u=_@b zZ!JSttcg&O$Y++Jt1o_-AAeH!M{;{#^~aI}yxSShg|GSLtF9x=x?(tyqaC$2j>BSM zRU}wO;XSoL1G~&n%LYd%mp1Kd9!`=cQ+ug}Gj#a*s$4mp$Rtxj;{2rM#jRuU^FKa? zkR{BsR>_jdq$@dgA?Ya-9H13Z6O@_HtK;r)QNpn%R;J4aGsa(P-PbtnNSdV+Iya9zqS2TU-0{Cl@R8;cpC29>1#Ki~2%F z$UzuVUhfUGiLFG}q|S-Pz{^`I=C&?;(p5=E9enox^Y&i7l4Vz#*jn2h7e21dylE=S zvPc%$Y{TgpHG6u{deKO4BS3(lC;bTh80kR}AV4n?1{#e9E#EyxBX*NbvYW10HmlNI z8$OQNX6a$=bK*qY$jlv}n9z9G|gi*~SKnWI4MUEleSPU1}7JS~C+3?NhFOi3s}MJOch7!G>t8IB1fx4b^V001BW zNkl230l#u|$-a%w5|KQtw0N7(O+ZfmeyL7^k@GSt~ z^B)Cm+S&WP*?Gb4SL>OH!qG?o#45$02p|v=ho?!>RZ`;O%FJqUt1~|9YrYV+XJ%lu zIbwV1+i5;jqfyM+X@^b-0ogzyfUErf`CmV7q&ifSrx3xFzJD4c?rACjfZQjhXco2i zbofT9G+unVHpT-$(hI3BOj6)h_T6{8tDQ}QNNFK7A~QO-|MKu*y0b&>HQynk;oU?i zTwIm&%Ss9yKTP6~#Nwnzw(V~OTB;6`W-8P1+Z`cs`fR^~ z`}Ez;!Toer|84hZbFQ6yEmM);p~&a9Tsl5sdqRXx?ra6NDBeipXJB*^vOMaa!(JB;-kCz@KlXY)L^W}5A@#4 zXOQC=a>iqeJF`Qd;dv*Os0z2I((p8SUc5rq#G9LpQ1Us#%NSWa2vxpeE~&=WgNSt) z+MYF~C>?R}lS-`&|;_As^(*}g|b zA^bh<)j2AjoCEJYH~9HdT5Q?m)6f3&s?VTfQC||i^<-Lc4M|+gEt4V0dSGlVe zPDJ?GkEb6j-;>-_n)(eHj(plrVbI*MjcF{qEeBnTqFL#yR30 zvNP1p*fY5d1$IV?Jaq;-U)pl**v!FM&*wYabuquSTwCt4t3-HD#nN>TV!rrzPuvla zDrEUFfuPELXQ-JR>Ksg-7yYBi8)6S=mNkThvv%1)i#iIhd!U2(z|s7&O#6xmqEwIv zAd(8VfOXE$EIriudklKo+K1Ox-jr^BWo+rOr8Gi;XYX~RObUV6+Q2#^jkOE2H6g@? zoiV*7Q~F|Mmp4^Dw{b`EQ566sq78sW0B`=op^$jX@6-h;E=mcgJaR1YBug`DwXTb@9!l{=$w6Jl6- zp8ZVoK?Ia9JvsO-aoK^0IuXpZY5H~EfwP1Xq{OtR=p|_!wxpXc%g?^QPP+2&VaiTS zU;b>5+^k6xlNrak{J8!Emwf3Y2;$^*g{`}y47dAsxF z&lX$d?1MDF)#rKZyF(#B$6_@#Qe)DUNndG=;?}lLo}3HDI-PB6v;I+(FC5j$KDP41 z(-;N*oB#gFXWw7nd}fA+^59g(Y1l;DI~p%A-dA-j9{pa%pw;0WH9VBvfj|L^soPM( z2%PbCu?61Jtd1s?3ONkRmab9s#F=ElruX0~&xr)9iFx?#zBOK_f@#V5!lpg#tnVF0 zoL|OU_ULZHA$q3paVBl$J45~H52yX3=;moLJWU{o+u`O}v0H!w0D_JLwEVdd!Bd;4 zz(F~`iPB?-f58)AbeixuOr8~d^JGuD!QHsI0&(5nxLq`FOvtdx+7(qeJ8Sf3J-1cv zloqw0NI(agsV+6jprEm=tZCm)$w9StMP1#Vyq^tD;-CD>i&uTjLkitHF^3v zR~HfX$F0Xvd(b#bRpHpCtyy`wnksQG2pAowiZHl-ikO_UZwp!Y-o zIuaZmqBGe)jQIPN7Jzv5IOonP)g68zkcg_aLl48#m;mNC?)tf%Pu%p{#Dp$73 zovl0&ET?98ny`6_5K!ihb4-S(u@Hy?R@3U{Ss9WR4W&Kx^q0%tQN&l@4e%{c)Y!+~ zo@(eo@)_Bhgx$kPYT-R4wIZhO&DDfZLNoW>akSf1Xb64kmeQy7EuE3>47JplFD$=3 zz6D|JCUf;=o^)lD$(_bK_dI!yl`GeN&v(Anv6X-F*Nd03z#5{~Y0?>JsW2Nwi>rzR zWCP6v#&Q+V_9s7I&d#gdjwpeY;_H8Wz+r!b`>`j8QYi!wQTHH13Dalg*SXU$erly3N-xlM)U+wD)m7mv2h`Ne1JGWR>x@DRZXJQEmc{DN&D zxRJhe|L`J+n%08f6g^sU}9_gbdUN+OCof{3I>Z^;^J5Uk;893|3KKA+pb zn+C`iChaSwMU}hWSg)qlHtCNTkZt(UJm(qbwbnOZ=cbW&)H{rV0oK%bM~CmFNl&5x z0=WLN5QstqSEkdqJLy1eF3AK$RLt#OcFXVlXQwFO`fp%>b@oB84Fq^cNms^Q2?U?) zGr)TI-9C9Zc{@A*DBSQ_WzSp0=w1^3+Y@_GhCBZ_5-Jetub&h;7UQ!75SQ16$uFkx zG7X-%VcW3;9++j!*cz`d?_qUau@U6vca<(**#2=;ENuvU|xUKwcE=;q^ z7~K#OFFsp8{8r!O?)Xd}-Bl;|^zoTKKGVndHM{?e?5sid`h<2ZNKIn8=Rx{!cDK-j_v8zC(`IEn0{7$l^b=GN}Y&u<-CK@ z-GmoOI#6uH!P`-wL+%q>bVfSus|L2?!$L)(@$`wu^7!qn!8hOdhka%Wzmi$zms4jA zE$2Qv&>UDic~&%e;=AvmC$tp9LzVTUYK8o;R`=!98{E-B@6fNPW%Kf~*YG4+O{yJK zUG9o}A;N)oUp;-IH)H7dfmn;U54YjR&u*qB6 z^2UApKR)J0!fiq*U(vZ=I5^&CvsHNjh!RXP><+|WEPF#aI#%6*%z83P1YdIh9$t-w z2yVNrH%{LCXEm`eewmxxN2#dRPHK_Q?e*tnxpc2tS#9zJpe;NjSy5Ni{p{dO#3&Wp z1aHwbtasH{_P_$T^Iq3kKYLMDg=4+v&QeV}5)jYc>vG%MRwNaAA1aX7ej4(@#b^&- zGLzvF>Nir;{-aW*hUWuY#gn6QE*024+*j8RhFqIbqtF@!ruSUfpTo}0}L*$Gv zbC>oc5e3#Q!g695Na5ek@2Y#Kn?g=0AtdGt%O)V);IWmja%W1fBea!g!3~2m%vPJe zsM4O&iI7T!j*g|<cTguw)^oraFL(zV-j6vV+LoTZ+le5bo97<}Z;q_5g$Si& zb4Kzu?R}kAV7#~9Ibu~8ZFC9HmLt{3AJ=){eNbBIL~uv338ZswYqw=fBdEY13zDOjVexMw@MV{-WY%mfzT`Ulq$2762Z8 zyC=1f5+~1!Vrhk{HA;?do)%T^tl4Y_jmIrR8%m?MBt$Sp+Pffk0ciqu=xCe1Z!xgy zEaZ27f0Xpp=YNqyjlW9;!#nYMV%qY({&7SelCDCDkAE^p0#o`%n6}ez;rGG;5PBOr zkqXx{6RJZGaYyp?Lq%eIEQg13NAlecj>T6M8!gBoSl~{+Al%!mTm_a^Zc!H$Ju<(>iq#FN`>58 z69O6aH>D2&XIP(+yp#&(9EiFUd+WPHrIC~4UyjqEiba&LE)vPZ#YeAVU|B=fQ@ayV zk2F*TCnwQrVxm;)Slm1-ldiJH^Q8U7pIsk4OjRtfMqwI~V6}E}CYiv(;VdCmqx4KB zQn5e*QXx57T$Qkq;y0mqu$meI7@s8w;0dgy_0l(K;(Sp&xSz0B7Xt)e``$R|N)+(; zujW|SRnCzuS*{rLBW>m>2S*Z7V*tUIy7|qflP?t#fR076uyIGCMDB^H7=^&;i&7^- zM~DJ-B4;nkJ>)`xTMj!2Ogd}Gl1GnHSNZ;d781E2P?7Kij#DNIFEs)pvxwuaWGc$! zS#k5Mbh_=FV13P1W zQ33$>a)@AgY1%A+V(me_s?%`q8$BVg;rVxl8W5_rV-HavSX@`9?{vMR_6>pi#!X!D zdS=@ahW=@+6M6pehEQ|c04p>q?lb+W^4449qpno3;G%)adK`Sd-3$*!OlPdk+TDC! zcn8TqF>az_aryZ=PNmY~*{_zT?{rv@+fFxY`a`tcth)KUy!beuJufdlUSB`X7nfBW z3ng)fX7Vxsi}zDD3jO(?UY~zhefItJ#is=TFa~g}UybB@}j{0^_>@L_uMW$`yTO^)77H)Rtm>^!JQtR~f7aSag@AMmDT)Mi69 zzqXf8%-!GW)bJCS!k24z_#jYS*j$xqBc^mZ7X8B*0H!YrR%9??Ep*g^CzLPOu6Gy# zArNS;!il`2V(pr`xygGemp19he9^LQFe2IFOyb^q$sBr_{Nj#ej+l-GJHjwvI=`x% z^~KVe!ZEox$s_~BZBBZ3tUDv!j69bUsF>3Z_CY!0|`?gwL;^@P^9jlALH-R#w{NR(jK4d-7n*pmnH zTE*7rZoIfQJKdn$KZM7}88W34HOn;|qnFj;!&GU(G96~Vw|`*6;nf;DeK|OgQH*=Z zV)wq@WpX7D%+E{R7oYt3R7FC^0&d-gx?{~PrF>@hzHO{vcqn@VIT))>PbM9~240Bp z_w(YOpEa~zy6L4`FI>A9h1>8G-w}#AJ^ZbHoXKM4Z0@ToC+zFrFg7hWz)hnFA?h`O zPHan58wATrPcM4_bIs~hhwoBbB#;y70 zJ=m^Vxm+6V!5)YuwuVvfh=v7 z3OWBuNOTTtNyC%al%8=Fe%u$It{dFPTgqoP>8Px)r9xuVI1&KB`C7yr4kcVg3^%hv z5PV4U48@7@Dn=B@#+u#%5$)`;!78hc_>fxg_T?RU>rLsa+*O4umbNB~ZD60_N!$>h zxkgl41U@t`gqdN#0={N4$)H?Yp;0Jg=W!y463N61Th$&|$M0l7FnLy}m}Ob$Ej|A6 zqPgcpL6HTjcv1C_V<9n0C7XipC$8@@u)@Ifjw0siEGBMx<(k93 zfz0l{*G&gX)IH&wy7$8JItX4)f&hwz?Hxvqcbl_bNC5!Pez`dNde4=fg<9873aLeB zs8uX>ynYVur_OkxMAFp^S~HM*_%LmHjJ*4EQ4U*$274C+B6f~-LkuK#(4#G;mQH?? zc8`p=##Tri95b|sL~!*aXYMNynbIkZY%36FQpYmR#gdx)sb`C09Ng74IJC# z9R>Oo0ud>NLLqCu*!Y zHT|-Dd54os<>O3nBW?#?;p-E7f2c@Qg=gZJEq#0eSod|X^A|jy#3&^XL8{UZ%BW9$?cq<`sJNMgH)E zKEKt=$7_C?yaDoVDFg~7Zl^@EIHIjQ0sxA`rp>>C2$GJJTHHLzRV26)l}f~!5)xNa zgA&uBW&za8iX%2q2y@4i5HPzepM4lWmZOK+a$>Tf77ELiV*raRbq^w`g{{1fMUBN% zlu8*1L|9G?%dd!l9K@MoMVpF*w;S&RRt`Gu0qlQw*q+0U>b^73Iu?9t{$Kyi7s0Cl zH_LH+FI`+z<2Re&q^(AR5Ri7n?Z?-AkB~SxilR(3_Jul;Y%RyvTE00SoFz)*PP;xz zWoXq9Fw)WHRgtIH<|5sFx63`1GWX@mnZl_!@YKqsWgmfZ?RH`Wc&GB7j^9Y1{bI!* z^W^P}(XJ?w*IyRaco~V|oj6LE8wKs_&89olDxH&5DFW%ByteCeGx@Z*`8XFAvNknR z?nkh~0<3R7)!H{>t`h`+9NsWY($|f&89b1qo5y?X zsDA689SgCAYW=#e!*|ngo0V3)3-Z3QMnZ9j-&Q%{JlRObMT^!1#jS7pQL>) z1kNw3`NUm5H5X6K>D$>4{^v{QHokAsZ7imy*?P+;{HDjp6@Qx$ff9t+LX(^OhKj{2 z6sDqHdNRl}H++z$J;Pz&u%#b_+NqW}21!MtSlPy&%v-;_HeY?Fc}HdL^OY})eV5V* zJ3XOevYw2j=3Fy!N`HMZ3Gh&>G4WsRKWVFBamv=O~wv!9Hn0jl;nwJ>r z*Gn>r#P~!VKgs}Mb!BFcOXp!Ranq;OD=g>3_DSJ~us{d5w>3m$DY`R6w0)elk@V6} zKdYYn^flfchxfC5X}P}o_|K<%iGFMoZc0~2tOnY$ceE!dXlJt3x8U2~kPQ?9vPGS@ zq#`6w*H2c?dj9w*K}HykiM3nPa+p$)8}fIIJX7-hyfW6>M3oZ9Ef zTe77WDhNEwm1}ftru5ua(TU^}T*U$bPT%f0O9BA8CpsG_=3=mvog7)?FFsoF8JrEY z5YR+LHplz;ZrmJZEEFOD5Xkhob`_voZc5w%qh|0BP(YNRx8zM|@dX_ppiV?%j%!Na zBuob~h-Wiq&rH$bNzD7g{JeZMg3CT(Itk=zXEqEh@`Q-adLR%AtK6-wZF%X&C(7nz zRvrM#+!r}Xg=gRBNgdcOU;J#*$U~S0wYV;wrK<3o_;%U^htDrdtVfkIiEl66whLPG z>K#Tx0uWt%y5=~W_D36>#Ljv^O#5o`yzGr++7UWNsc?KRL4lwC#d1DzHA6UdCOA4x zo|jSq0eVZQg7$jXER(2aV3ClRcGcu*1ps&6?Ffmh8^it8w6An5yrn<;@4ozs99nGQ zQ`t!0{Z{wp+!pKB6w({f=-`AK)S-~&$1N4ASn$e3fl`N(i_;+){B{)qkhlK)lXW&w zARtPmDZLK=kjjj~6u?u`v5*qWwTm*zbh9WG%j@d! zK?(q6?lw}jI=EW0QcobqDexpD59_H(dulZ`T);8K&lFxof!- zJ7VMNXTMsR$}<;L$3iCpC9Wq1d@$Z_$K>rS+oqB0jpwaZAb$G8DPKhSt#SZ}_oOtU zK<6m!DaD*MEtnR^>~5uTeo?I^rs2MMPjOeyE~?{48CyR#PIJxu%2@*3Cm|GDbGT7J zaO#S;oKsPR0e8E)y^T0G3;fY<54;1ZL}MJr-Cgg9pVZ>I z8sAHFCah^i6t^1MEbV#m(S~ew^7SkmD(|7qe7UV4PI{_;91%fPxc*@@c~-1vmQj0d z%m@imiL9@7%(EE6d-HdOLg161ECArq9}F3Mw8l#r5zv*8dw4q$vx?3Qp~MBjjSzXJ z@*p@8Qeh({o;)i)`Sa=d$LqgfmKTgZ!2Y*xjHzF*(E?H^6+5_utfw;2a4%h-I3;?7~X-Ik34%(_DAygz8)W| zY@iijo0ERqag{$(O}|2}z}ri8S8arQZl2uv*f|8ZnmuKs4HP;OC_Zn7yYn?ri^Mn;!y`35QJtOu0D+)2_D5oTEC&a&JCxml z><)y|%q-sTk#viWA<2bD&1jh#WDH3b;!msJ#tui}C~I!&hM#j6=x4My*b=Pnw%7Bri- zH54+J963unO?s*E_B)AtQr$XR?|-Am>L&oQrC-g>{JH`WoTN>@Wr3d!G$4|Ps&Hvf znYCLzGq%0hU-t3;-e4>OQ&Ck=LpDUQ8ypeD8TG^!3ZuT@AfVZKaq-m5Z(LQ;{L+8% zSB10t!7ti?SU{f2S%}q+hXG*^F{2uxcG%cUv*PxfR5&Y6=~qp| zU}wE|Mv8ne7k9?{di#ClnAM)Ep0+yE01v*|2Y@IEloWPW1%Ty^Sxzc)pfm!3iiA?g zsvRB_mPnJQI8#;bqErSir@{+~<(l0qgZ#o7;>~1sURJqNaVUz|3W}R&p?wm}f{0D2 zz(fBys@87uJnxJ&0L#><%zd%2&QO#|Q+OfK6kaGK9}-}z!j~(TbOd;)10-Q_Sq2+N zM*Xa>a^E}9Q6f03Ht8yBD8v+cKmj@x2vn{eLwk#>YH?XjpBL5IHQ5~iAhqCNB@Ut` zPx1B+#v+n7AJdxV!!qd-OcgxMHymNWlSkPmwG5Gn8tW_06RZlyRuw>y&rL0#C-M+= zB(pA>WJy4XG6Afd7~N0S3tJUVMJQG9HN5#!d<6rGDR{l3sEHa?vFIG=_E{+qk`B6(=ATzWVt1s448&At z{mmC80K}cZIwnt1BA9kmt{osY23WT8ai%8E%kDUGhLWyQk(fLy_(JO}Ew4@cKA8e!G;t~wa%OXZ0Vov zs(&0`G4YLnfP_R}_k`J{&l$g(+D&=A&49PY3kBmx$>?sPBC&jKZWS?`V>0f`q$ByH zK>+Vy`n-HSXBuE|61CN!^_3>P9~B9HYC@o`LipW>|L&%L9J2_#6$Aq)uvpr_mH2bFNt$vh96$|I+*@w$uHd*)fLkH>QjcAsUlMnvo+?Hu3VecT)v9zT}gko-^RJh8k zSg1&p3!C($P6az>|K->GHxaVDDrh=pdRWCIs8g;%lQnJ*)Bj!fy; zz;bz0sYoy>?DF%qsr<=XolRG^BR~J~tTWW!d0Y9W2*$u;4Jm|s+@NUdi~QVmEOab@ zz#3w*XM5TUgJz+bSL4n zbv3m@3LQ%ZOji@bqJUyy`-c&VEp3kXKn}d8JqGzi4Rz?=H+m*_0F?GMf5zE)Wh-Ci zE*&Ttg?R!VFr=pXqlc+?w3-;MUU;f--M>8F-9O*>?obE>g!7j>xZ^ATjNXWoo~r%( zf-No!tI5;+X?gpfyzvkERqk{mr_Tyrl4sv!w`@3lCu6HqARCERj^D`mK+&;?Q`ydDIr~nRNdZwuMyXVF@&HqP^SKRVWPsoP zXUFsNGR;KV!8k=G-ah&1`pHk%lWkvo7Kbu<871!BYFhZ!9_^1*LP|9G%O!*jr7;qM z?ea0$HDY~&aNEDx@u-f7Vx_aIJVTZZ9osu{6*ciAU-gBd`P3cCqr2+hjv5}xv@3Ni zIEdDi9_HL}wiF;~w2jn0conaoFmUIYZ;KBeE2Xu|7i6U$2Cbsezqtdc95boy`A5rO97KD#drFIY-{=Lq zbRxb}c(>mQa|_U`f7ckZ3)vs={Z1GerzU-aIdx9hg@cyB0>NT!xO!u&QROZ17fkTP4mN6p2NObJZMV4o>?6Weri4h8DYCk+kCp_?kNQJk0Mig zQ+QiC20(9jfKK1Z*utV%+R*s)&=6Od5MXkj4fwbZqBOs4og8J7&u*^XnS?Gn$67|X zx-pwfH%GRj7r$K97`bR%SJ;1q>W*BGqayho*LMIRPzY#zqZ>$K9}ZIg6Uh$5*ceqZ z284)0W1LC5q}2w0VOIWs@(ODq#IWgm*rx;9dIO!ImJ&gr zt-OwL^~|*Qt%o1<*pa6@icsL9W(%8=-u}l!wu?gqzK-<{BUAaLr=nD@XSP^c6v#5s z!AZ;(Mf>E?o3y9c!mxL=1$o4ok{Xp3Qi;pY^Rut@RD|3#n_pI|sc|;YaJ;2?%lKex z+F(0oF_22ggDL&vAIyLJKV3fk(egJt1ck;Oa8uS3(tG&guNMtsDzUb;&(eD1YDbtxP%Q0^j4M1qg?5t-x1k#}C_@mw(dI`9g^zx(FC^ZMV?X{{)*dbu zizw&^!`3l<{(57V_r5pY>!r%{t7aGC9o&0}5FWZWrS3T5xDW3LC3;Iz z3aN#T#m&GxwhSZ^%q_BpY+1_?FhEl5y3GN9w@aSpwoogPAn7Wh&|C7B{`9~7 zatHJTfYDj<^sg5(K?W=5AB5wDZf76LSE-JKr3&-jk5H+AdWQ z;m$i9cBck_2jA@rf$XNI5%fZ~6g?G7kxo=a$*qZwKg}r=kS@Lsp zZYP&+HTRyjE}!@k^a=o`FAAuK&KZ&sdb@?(3B;8n0Qflf-jj+2UnWro7t8Tk5@iwy zOy#3Y4o*UOu$mZW{ELrQi|fi+;u|s$Tzt0no*1UT`?W54C|36RNsb6{DncCIi;@dg z@2NA=K(L;hc7>oKw8r1=V3Vc08K1?=>xw)zPVj7p!CS=avTR(O zbRwN$Hh1`2Q+V=pn@!L;(&PIHZwr&hzo7?K|4vfpGlc(LFD$#}U4NPHHNcXwFot1$ z7@w-+d;0D>U7d*Id;0jz4pUti{y2TRbM<&F6>2SHy(qk+-Z(mZn5ak)!Th4+;u8pz z6b*@nh`c3^vSo5sgGpf><;*oSB4i_7EG!4D0GpqR%^hRMWgJ5mmDu@Ef%EcSx7lfh z!h?G$;%0d7zTacGIqoU%$mEXsQ%u+~g>!YI=;+OK`n<%NbjG|G{<8zh5Ro+`C5ApF z?P=09$CGw6PK@o$@gnRZ%_i8O_hA-dm}`+`RvzN+EQVsFNcRRkT|ZqdkNd6%AK=;vAEm+do_&3#efUb zgX309 zEtlR~>K<}<9L=9r0H751hVtZ|K6^iYX^R2@2&$!9UYcTRZAJOY&u^TJ#HN8H(OFLf z*1R-$fe2gyh=C5XA6Gq%(}A*v$WvAL4I`em5Uh9p!D#ZlKtK^<^}v+gTkouQmcGhU zx%c&6`+dIgo&L>}JW3_h+!_?16G1>+FR}KY$DFz3d~u`Nk~>PJHNh{HL*Y4C%MLRiHL}4%iaM1>QtEAIlH-YUX&^w5P#B?Az&5_q_dt+@FfI{NooBNFt z`wt>M@=?I_S+SZLJ|=mFSwrio4K~Me>sfMMruW34NprCx2e&1JJ6I-p=pJa^yVo;w zI}@aL7!$#x-yJZ^QN`#iO)l*0#vQ+v2?@p0HjIhRP+Q~UObP)nK3YkQEIo6M?!Dg? z3cZ7T;;PkFbAunftLRysZT_mpn3Bgq-c7oKZM-jck7Pk%UL>}EYRoKwct zq_=eaBrjLidx$a_C8Ai`{&B=3nJ;X$c1>eSMI!C1a_NKwL^!;kCOx&dtazr+E=o@4 zVO@i%e4Dz(za3i)tp3sFj49{t>5mq_`adSWRtd7F=*+NPfW}?f7{_``>zQE)gYglj zl_EggQ7nr7<-fTRuZ&gRDSX*iFV2KcMEmy3OSrWq)fS%NpJUh@T6$Pp`QC9fx|;&Q zkN?-*{K5Ml^ctrI-4`knVYfx}p4M~oRr0fs-^^}%sj@Y4LknHcE#E4oMiq<2b#?eK z1te4W_BO)JZGIb!m=r4)GVVQ9gaVR@7?Vi zh(`o*F>nLNS?aao&)fg_@L^iaT-23y>BTCouUgOE{aP11C@n4?ub4j@&~^{Ck0fw< zfRs=yJpi1()j58YEv_r}l@}6Kv=wC)bw$!uLLe{d+aTKe|M*~WUG)wkp#nhSZO8y}XJnaQC03eF7 zH&p$RP#UFd!HBSX`9y@hCezqxLW6@lr9IV%EKuT^f=df|Q(6H?E%G}4h8%NFrK>!r zwID)gq|d(I1Axi%VtHc*Cov+(NT7hlRV5>Q{^811#9m8MVO6-J7dQV$WU@ddo6|`bqfO|UoS{D&6KVNr78W5|(mut@?O+*N$1c>Yw$|Xea zAkwigg=e^}*{Hdhyt{vXr^i3xc5mP-zIta-(vyt22Mo)BKonYlf9bV$bQbe2aq)33 zkYyLPT)ETtvj93%;M1kOkn9#^QmAldIZH`bhM03t>zS=db9ni9!}cWy&XKp&9c%AH z{pmf7@5Z+BZ8jVc=or1FtQRU{AV5H#Z?>W>;cD%WC|^QyJbIKiKfGGIY^ZL&*c{&n z50iXhRY!2DhKdD?3>eOv*CY1k9}MG6UVOT?m0vG>RcuiacR(4|-7|$85USjM^6ysc z^S#BuLIA|Qi%7@f6?Z~@z6==YxCz4!?06Lku6+0#@_Of?`XPEtDA5{fqDY(Dg{vr^ zSom9dNrk& z5CCDha*TE{GP1le>5+uH+_>(k1_TugZVkSw+!gST{)?kK?{$NJh=6=< zM@MpSAp2vL_2h0kv9Yw#{(*E9mc{Y1q_Qx{o3MSItelZ33jaAo z7O-C-BUa9M=ZFKoY(=)(1+bp|a<_N;vd$1fAi7#Z&iK$A1z`7>_Kp-~lHDzfg(ae& z{K-WzBO#z%(|YO4!uzj$lz&AS>;CWbe&e~#7@X3mV}S%_;rUN7ansMsi(jsv{N+Mv zG5?}$zJGDKJG-J+vk?)hg|~B`U%4Xp%bD-q*~~Gakhd%pV9S@*)n?@oA$fVyRNRqK zCY>R2)IEs2@t^!)3LBB>7HUZV%c(&D02pQq2e?`PI*>H<5*k_b`+sm)E8$ym!z&(4l8T0byX}8B52QjA9G7xUQ%U zZD#`tc9d>&kC=zib`CjtvlD#!Ys;!I-~uSr1&b%jE`gEun>|@}C zBPshwQFD;7l!QE~NN`kQcg#s`#!D5>12!{zRwt&nExVZgZc0ZUJP~8iq8LoWkgx`z={C!D2=&)4;4irxcb$>rK2ZXS6v2Y8Kf zJY20&4ym8F!S9`@h4EP&C^nvog#&`|qhyElOCAQtF*n%Lp`Kg@6ZC_7DVuHxgyVPP zq^E4@lT5M+)Mr1MHRjOd0R?)-4Ii6lKPw;q#rpE2VtG;JQ)^34o-RLLUw;y+xADD{ zRgm|;(d!*VI+2JFC8ArWw}@AoxFf>wG{)L2Hp*num8)yRA`w&h`Hj7NZWl9u_k$P! zhR1P}!saYJ|7gWr7*aQLh=?yfS`Ch3TlzSWQsd?4`RFuZkTLD6 zd|}I#fBMrkqxC8h{gVgO|hv^x#)25#Iab zv5v*nw)aOPz5{^yRn-(d-hqyVRN~Vg%v2;eE<{FnRdBjn zC7=WmSnGAOCoEd{4)j zJbS;}{;_9Y>#e4SH>hl&y9beqECf(#$`_YVCwTQ@U5uC?M;}!#nEeOdp);(UDAR zV&#@G8SV)x*||h`=eg_))l5$SKwQ(W!c0IQADnj(p;+4PIO0xYl{={IrGY3LC;*r| zExaMB6R#0bY2mC#0j{FaS>hc5AUhi}=N}O-ALrn~8ZRU|=K-Ktxs&ZKmz22I?U*;f z!Aaa5>)Ay)x|=dLXFW6A0OQpyWhfiS!}NKH0!-nZAvVzAbS)kiu3L6Y2GWrloh59c z#m>;Le!ct0qkZ(N*p_}ZHGyvLVR2otd8+sH#Sa(zQOiVf_`tMAcKWBWip1&r9aH%x z{*QImv-67Qs;Ipb)^lS@FC#%j(-&phSG-jck@LPGuzOFOE7v=SLbt{tPG9s#vY6WCr731MpW5ZMnO{`p(yga9pPR*1 zwVYT2DCb0O+wU1)x`2|q_;rH@|K9!GZ#}gX0KWZCkChgHm@n+kB$3f;K2g(W>J8QLneNsBdBKn< zKq0iAy#{nnhVo_0O+}(R)IvhJcI%n3t?DhWi~s;207*naRQ}CQ^DoZi;<7Y_V>*ws zzINT&FjQVq+uwP&t5exrmd9sFbL=weK}1rCa^<`u{w=)W6W`j1ob|=Z5)lWd)Q(hP z(O|?ur&Lp3ujdSk& zs>()ccqaislY3`NluJ9hn=lENPpHLZ*|=Zvpm|G24>CkxV;|no_;N>{ zy5k5Dr9>9}@Oi|pn%n?0g|AA#xG1@=1|e;R(!OGhug$=!NqqnS=|K07qQ!N^JQ8PU zFEl*5n@G*B=uj+eb9t{fM0P@;v?HVzK)|{;u9q5mY)EFTxl@DFn43?6oAd0O<7)@g zNz+-vt!Do6rsC6!TrhDwdLwK6@L65S`USpoa`n?0>Rnl6{Qw%%9DaZ7)C0BPh+9I= zP-iH|$MW!wiql<96A__66d^)>d1Ed7Hr+q~xGlhw#2ysS#$?dSB{>$8y z8*G9+nZj|X<$7uYrh~vp^ZBQ%>n8;PNG)_GyoHaxKS}#a2+Zdu?J8@0Hd5J`C6J0d zbw?2*>Nq%v=X2Y_I=Q0@poml_-hgE=A!oPS;w*Y0JUgK%4B5p)I`JXD3>ah~2PZ;*L;l9@78Tc<8gCB>Pv8c?Voz)KM)8)a-0QkieXtGSHm`@j)klH14X_$(z@s;^aH*icw&Tpc zq$6$RHkdoTXyrXV=ykA7zrcvO}0Ok?;Y% zx+WgzMJ40CuMBMIlT1DR*$hR!I5-iwe%1FX0p-l-v8=A zC|pkM=6w6tczxZu&F6WNKO#esb=LCEfj6cH?t; z;~`yZ-Ae6h!2vU>uzs4`5|)ngRRfRA9O3?xeHN0Ql2SC9M}F~(nH$|q0pQ|kzPL1B z|9dy2Lat$i3@rI_X_Xem+%6}ES)3sz4`KYQ0Co&PIR0=+04BFv2gw?%<@yaC`Mfyz zT!-JI-j3$*ki~^rjH||*fW>8eNy~{rgrui9O^*#Y>R9wJc-trv4&Lbo0+*-L50T4ho!|nRbV~doPm`nWoAx z^zzc60JhvJ+ZZkzWlCg2)vJ7v+i&;Uy6-rXOvekW@m^|5Kf9fZrU`i?OLabcoXxy`kaFga?`VsRe+fuT&&d9Fi_y(u6CGNiWcQ!IO8i zIQs<>8+Y$#h_IYmK*;*)v;T+pzS&<+?c=|iaar{;_WHe!l=vbw*$c)M^=ZS=@P=$f z#oV%7$d=xe&Q$&?$ERKXwf*MScBJhH5f&3e9=u<@cixk;-W0CU3NWeA8Dbtycci7n ztSjS0@a!Ld>4o@W7>i?nesiCld#Ub=VrG#|V3{OXzf>=AGicsDS5f;7)R|~r6W;d_ z(V3TdsN38pTQ77p=8alL0uiMaKm0#V8(irs^vO;gOj6<9(pk@f(^p6c2>@X4e%de` zzxsFgP{8p=OU~?Wx>sjBN(>1Y^+-<&2)lD$OVNRTI0_i=UGp6h6;#G;glAQ zKRDC7s={yI$#f*JX6`%V85yiGN6)kjW=>ffq`Oe(4<;SSy*2?g`0l8|E{kV<{t1mA-BN8t6E!CTn^crcex@g;E69Ok>lo;(09#^}HqT+78h* z6E+fj&E64L^>IfwY0FZJz#S#<7$Y_0Ym%d zv^A7hKI%w*kf!wP7}6jYb&w75at!uixcLJ~Ci$K-nJ`pWSBS?O2VvS%TzfeiZg@M4 zeE+ph9l(bSBv*yY1~Ti4!!PuN1Vr?eAKgubL~Fc`MU+bK>67nIny@_PB6;uIdE{AF zZ0*Y7uI!KG!CPyabu^G1yOz%^dley~t^A+=uTOUylzrO()XV58=BwurD{lGWXg2*6hUnrP?N zo)sk`%sm3DBoId%AC0XWiHZa{_`m-9N1G5#f0Y}pGQq=PDG^{5M#j#9Z~fuu+Pe77 z?`{c&S0T1K5}wA-3e(J!frJ93kri7)ip98^9GC4zh+XQX62NdtNetGL_qOz$3q}M| zAq(PEj7djMPb+JDupG`En~%=Us#^F=*81s%JAGXp z9euQf+RlLCeullOrF;2o&{;ZpSUmdcd~xRa5k(yd1g@fNsGX(DqcW822tqd%*f!NuI0q&SY&;*oLU}7w>KXE=+=hZw({g?g-JmzA=Cm8%+g)$&{l;tfis@> zH)pB88+Es%tB6T|FItR^?h8IFyK{)YLN}ueE@*i01F6!u>ci` zs_?V(s=pJjG-w1jA9N>2g|llIaXL^8QMsHpW&m3UNpCy4d|og>CM4%N;j;Er;=+#i z_U?AXkE5-W*}a=~w>1j9cv7H19ZP3COZKD^IuWz;N@%pDmkOg)@;yO>&lsGF0@6(E z-PZ5^@hD0}IrA4Em$TuETMh!TT)0=v;kkQyh) zWivB#mePR|8izMxA~=7NvlSWekL`5q ztfBKytJ$kSA9BEWoGJb8y^LE^scSD}03C^@J|u$e+o@8bu`SoB2pLfh7GuLrnzPj4 zp2LGE?nqv5$w;xij#TJ9O`laS2a*<-wyY`q&XV_^bxFMW-7P+6Pd-=xK-`m`{Z{UM zuG8eRznrtv9cdzbi4gKSW*M{^s4(O+g=Z8XpjVY|6LVOUzyKB-xxDC?hbokSSu;(s zO`g>Tu6-stOV)T(c`g)f@oUvOTnl6U+S!I}_Sv_G$S%^{rvqKIdA0ZoEE3yM^2jaQ znkbC1KPD@^`D??Q3Q<16%SFFhb@wEeFjM&3 zpYO2?6A|Qd$09raZ~2ML&Z=ynqD(df;U>15Jb33B`x_kw!nIjCL{JefCWhxFol(SH z2>{rFOKxob4Vx93!j(&V^FcQpf&$8gOM222o~&;ZRNEd{J9pB~KrhB7gwc6$HQLpl z;U!(!9qHg8mOHGmn>JGEj8~CxhNKqW0arUhVs9sI>OiS6JX}TwyMX~Mu;mSAE3(En zqDL8Hd#>UwEiR2Ufo;g0WN#+z#)d?vEkd5^5M+;uNIuc^M?QOSd zEC+jWluA>1X6Z|XCl8l8kxHSCP-)Z}v!39%je|G44OV4JM*vb`e=q87M^H!aF`X3% zimAm~FW@Xqj>=+g`Jph!=lT2dw5NmsXDLcVwR8yB+0s(6UpVPR@P2`aDiKeAI_I#Y zCX}6*I=?>a46ORu)e%96_!9fW&-k&HW|#K#nVnBOPZw7^iwF*D%ra=x#H^t>Q$k|3 zbe#AQr}FWSXN_!g9UNO_FF3RIu0@F?AACckexZ35Tj%niTSx?|-P;kd4s96Tj8Q<8 ziQ;ne)I9uhuR$oHfebSu5eg$#1M$B9=C`)a9~M_DiQDh=guv+)11uH`7jt*`PLFW4 zfz+{y+^Gs@AxhWfhZMdGd2+^Ag=?s`rt*{Hl3lTRNmom^eLEEb&mZT_t6k0=QJ~W^ z!HRd(F`wDAr%oO&y(dKQM6)wvD=#BaEggB-I!xx{YZ`zu zcc%0xu`#4~^$d+ONv}#W8`QE!yAS}mR_pIZ?N~Y{9ci&~+KLi!c~tTW3~72NW!bRt>m#zi8#zXu&Of zIbL}VlHIdM-}bXF`r`GgIIK1Fv^GqU5k7b8RXQgm%v}S!vz(_Y9Q*rn4Py#dEgb^v z-OB*r;#skrn%BNQ^wzU!AO}|~jb-i;k?ZLw4Q>OEe=-viQ34Ufsm%JCMQ7!DEG8#9 z*^OEp0SNZ)XF`T(IhMV%x&HLDtY?zQ5*PBsG#2pC#Eq+(loYDonPseJg++cY3#kr7 zpT#BT;O*{4qHDUXqK>R`=j-)Pj^<~E?U}rz$LpQR7yoGQYx zYNG3+R0@H!vx>I`c8%~Job~J=&QEG`T&CRs)lE;!o1gF26X1Z&F%-^u5r<#s7jt{| zC~xxeYVktMrA|Aey&*!jM-=>bc>{0u!>|4u`|KyZdpAwGvYwg3U_aK0q&mR&?l=2Y z?k2~jj4+&?1m07W1cSn6pWJ^V1Hcddzwxi7vy~Flp6qQ2dVx!Wig+bJa~#ah%vFv9 zSBArbSVdCE)e~glFi%i6e!lJr$@`XjEDvHWIYZ_2)!fWq0MGIuB}9?<^1rghty(dm zUgSAVAsm^5*i!)nIud+0Sh355L4Ieq4-+zOWCvTuqHXEr09pAFT47 zUv(2-|69YjBRQZzXv7y=XL8a73TWbJKa(K9wYO_uO9=f6(klIiwM(ZpeJ7%P;isqO z>dHBMr^iIX#n{lg@>eQ!)~^wP37jEUk+%ehAAaw$J@WZYz*ukoOIyDXRqYr3?7!Io zgfIWyJwArW!{Xe07BYAv9k7LOfe>|HUmu(T!_I8Vmw`w9k$e$S#+&ExM(iEsQ=9bE zMl(A-GezwlINXoDr)ue>WWT3?Nb*0gl&9Q$tBVi{kNx|Zka+Q|Xx5lxCwS-MRC4SR ztvWI)=Z?LZY#Bt0W$tX{l@_k@wF4lLBS4&ARIF7uWx$C-q=|0}9VqRqTW@!{*O;Ce z?o*iJQ{^tO%m@UAZI-($@1dC6Y^aMW7ejV7#FDEALs-U$bRu}n@63A30 zOHv7DSO#o^xEP@Ks)lk5^xEFCY%!Cq7q zj)2CGOQr|U4DlenFBEu7yau6X z!|%dzVsRardA&+yZO*wL5BE7^4#<-&owGy$DiZx0G1I@}juZl-ObUVH=cN!RBe8WO z`TQS@g26eFsZSIkkcCI9^Hy)@3`#nXZu2#Il5vNJlfU6QV1ply6q%1E%@$~#h#K!D}MqJZ9%jboRkUQSS0fB$Y7+NlTUi$ppa#HHr?Hy{9`zVp7^!dalJp}}uXj9{x z=sh5U&Lj$qGBLUpSGhZWxL|_qy|47AXQit=1BKjAcK5VS#ByS#6itQ4z45)T42VD| z@%;S-KRdqc#ic>9#ub$syCW^N=515O0 zl=anoZ1@k2Ulj(5_JO|mR#HCbXScS}2dDq^tMc;ea{gVk4>m|He)h%chu?J1M&^V2 z=BHn%-upZ5;u~u(uGmBmhqzWiqW~VvGMdk{?v`5$c}r0i+yLUP8r@2~rSY>;#e!4V zXJ?gnv~!qPLne3JFENEj2rOncpE3~x$;0S&$|xs0*0o!PYwe{GK_`+;NiUBp9Sdd^ z%`Xhs&`hjuGD({di~!2i%=9`I4Z=Xu*03Fb&O~=FYEo#&&t4q^w|ytw=)U?lV+8Du zbTP9HojjjfArXkYrS>WI#_w(QclE_51(QKo=h)m0kq9BNSh##{fXI7lV(Lhra+AXB)-rCHWd zWw!L2`GW#kTLA#KL)+hrbu6mFw@4yhX`y4uKgJMY zGF0822#7A9l)oNL9e^|B9f%kFs-U~CFZB4m>iE5?T3!vu1R%%;igSlnT?$7EC=?Pm z#KMhPZ<7@R&}2Kp%c&fn1<$(rMZWzX-hBGwC5M7FpXDVT{k%N?s3@myGmDb~o4{6H zNQhFoxHM7=^1wV_td)}7Q0(2y>h~yEB{o)H#~&^DJYp}W*>ME`H{R(m3nQNzCK|8{ zioY(4>FQHs)ddkOC)QSEKAR)z;n#b-?K6nh+trsF@A!+6tkGejW5En8nZ9iC4R#~0 zF`8t_&jjhT2>5KRz@(L+IifIx*t`!eY;k4oi>05Q`twh!4GgP0)PO7Rg0*lA49}=t z1ahMr(DQYP;%@@RVkPNs=rg*PbVqu5Y0jVKb(T7{0jw8^F6(JsGj&?6i^hK=%s~YT zxuzhw20(Tc^)>dha$(>4_9*H|SJC9C2;RpW$yX6MVE-cTytn+W0eMIV${Ei}2=B>T?`?2qtP0=E zq-ST#d2{;F7CvmnCn(lz!(R3aGeCxF1CXmS*%D=%06XLK{kh8h6Mr4<4>xOue$ z*YE1<-x$UnSu=L2${qjRmEe~xePf{$!CV~g>hT^z+6(6ClGr~XG*hd`K@cnk!gnKL z(BaOz=_Z}T0|8k>Y`JfZw}z~tw5J+`t4+b+zJl$?-v5*Fb^9Io+BqxK_X>r;a^V1* z&LkL7IZKO$n~q(TQ+w7#br2QLGuwf<%_m85ur2#ra(Qg4nZNUuKDovPl>**`fB?-v zo|^DD8T2Vt8NOTA3DtskU`x-EmS#-Urrt=6;pPzOx>IF>8XI79ic^CgHigC2DcRvW zJ(QRYv``3$&e0+ilmTu7fV*Gn>sWXXQXvtYeVX(09vsAj{kZW@32Tu^DC8uvnsSe# z)zy%vw6Crj*zexo6ni&JoG25G*YcnLFVEPIDeG$jTw~dAs7>oP5BFp4Jvv)jDp4+j zfN1;mRB3DgFz$1@qo%pm^Z)=L07*naRA^;IArSyNdur!i#-0sKzto9Dz;fwUxF*xp?;d#oC~Is6X3WixyLN^3+T&+*OLTYZJ!*=hcLZWx@&;Hww zuU4^fSF%}KG?4t7G#OP~10g_fFWP%Od-~%!KdCbJm*@8MnVpXPov-w{$ot^WX2(A- zm*;EMWHGb7ortZe*G~F+oNg*Fwa~F>XTb6D;9|&BEx$8_Di8mgQ@5P)Szn>3r`7}n zASALcjL98GKyt%oN-q$k1RY_N;Ncg#Y}eu(MTsz_1ETrZG#O8@vcty)6=%w!RAP1( z@-fdpwoiXlPM>d<0-cd)9I~>3UQSJ0BY^BQ5rSDm5Sxz0lb_Cn03o2et!?QU=DYRz z9tXF1PjM=fj^goDv2ZK|W)q*;X$1s~LbAQ3_b}Ltou$c1$#1qPyeVDQS3=lUOXuX*2ehV?TCw~_9nw_P`mfiD3upa^N@Ms zh%wgX#IRXFbE0h>Bq&hF;*)GR|J8x}FU0b9ts!rT zj{h)u`mGzIuf2We-}>qs|Iu$f_)mW8@IU+Q&VQ#r{tp<&YNs-@`W9vmjY?}NZQI)C_z{`2;`J@06C)UvGFQgKJJ|HJ&E;#XikHk@DSJ>*l{ZU|rh z=8zdHgS&AfZD>ePIup)%rO}q2>zuT&!p#h}p&^;nTVkCZUpYI-HpfbTH)1|)&HW+o zNob*CVGZrS-a!PN%3@|wtmv8SyKhS89k7%s#5oB-c|``qh9Dg6R0f(=W4P8GYDRf@ zPL_=#6zDw^GrRwG7G**z!HQi(+_{qqg;B%pD)f`96dsc1HF zi_REPcS($8=;~NlDqL$ukm^(AWyxW*i>%4|Hb9l z7Bg4QY`Y@m8iUIl6^mw5Vv0ePJMVtgzP)`jyrX>X@|pYczq;L+AFVEiV0`2r|EPHW zUeTUcHO?m-{*d%kfGjb<+@W?tw8rx|hfBNQBp^b+H#sR;1jH6ANmnwwGQ1h{lUj^z z)R!t2Z0_MbZRBHYe6npdIW4)94n{X4^r%t~m-;jOQwJKyMK z11%MP@F!yc&@Yt&3=a}crTpa|UqG2xZa!S4Yz)6==M^s%B5*b=)aA^de7IJ&)x^v- zB~9IC;%3-u+oQ89e`&eyXaDqfqXrrOwSR7YvF9vJPAg}8<22OH_f)TXOk6pyhR|z< zS=0;<%u9uqu3Xv9UIUW>Z69WQoatD6?|(ab?Q4Vixmk{bU$9wt1aK8q6EC$GKQF72 zqymlv$)|?dc|2Ty8G!r6K4&RhJS*6_nEyBP!JQ*(yeYj-L>L=SZQYI$5yY9~I4`M? zT!5LFki`R6U?%}X%sFaU!(ouqie(RrkbnbWX6F@eeN2^bhD;IIUhSa{OB%U;h!UZ6 zm{m_tOa9?HzLNl;Tv#@!A_9b<5s5o$c3Ot_TR?ZD`@0dpZ_7)gV<7|p1(|bJYw)EK zJW0*AbTFc1f{qQzFx$5iz8FL(myX5z`P|jKGpY}3ZauKS7qcM`H@~*>x8Ckvr83-j zqrjRgHYdhIgB%X+9 za$NHIFwJVKR`#e+`~EcOl@QR|jpoe=)UKI2Cp>-@7 zfSQdA1xBfiViW@66bIXK=Z4z7sd`&7YI7z92we{aYG|;Y%F5NWw)SG@hV9yI6bYREHJ~%x%=6lU9<}ks0l>eW(a|Nx_eK9z4$6+ zwCz?40MS79b|S^&M+(FLY^c~{#d{DMbs`#e;%YgzT1RL7^3poz<4mDkO>%m>(REBZ z5ro_cQ+Pzwm)((G30)mM{Hsg$Zh*Sg_m+ZHSwQY25k39cjCV9^h#fl59_OMFXn3e{ z4-^7H5#iB~WuXh5aP9g(0Qsc_54?rp$?8aPprG4qHoSH0*V(gd+H4Wv#JF+DM-mrTw zl?vbc)A8)mojfs@=dR2N03Q5)FY753c=}0Rm9(7uYHhMa!y5^^t*?ma^_;3E1t3p3 z+TO_QJVG9zTi)Xst0Kh&cG z-6mThz{S&|Sqa;Rsf>h>U`wwPDFkx1l$2ukrrtTwJBOK!gtfGLFU|UD{Jh|UB<@O` z2&sg3RLq^NLZwASlcUlUUa+Ch!U2IPT+);I)Hb+(F}FGvNmmOEiwm=Lkcig0?(fAs zG~<;i1ZD#zl;HB3JRqQR9LOlHc0n5@ZOG#@)ETIaAt4b}xz~vh0&N%zhh!XQshqp% zg)^k!zQXRb6*?%qT?L>=-nVghB)Cka$ZG{46=SB$l(f@hcZ2Kw|_r5aVIMLa; zLB!5Ldq=LK>6xht&u3!2ZA$hpJAIT3u~K2|-pyDYbNQ?&=Jxj6J)RR*g%b*G>2)mT z=arC{&zw%=`IDSEHF#y;$geBnUG^~ml+|=R|L}7DaGpO~mS@hJEZ(`l_ji8x@V|a{ z@IO}{{hm3KQp5sfUR}(VPv*rjk#oNI^38v6EC2g`_C;Ntdo!?Az*S^@wANBIpe3C(9+O( zXdPm1FGZo>`1hhFLse`@4z%0gWq?of0w<#b!1k?#87RG-h{xKz!j#4+ zmAn-f3zv;F>%Or@$I7{jGpQ3HBmhyluv|Y34iW%p;xax9exqaT4P>V;QNVoa$H(^c zxjlJmPM_Jyg=?m&EU7#BsN5KQvW8);_yowOZgyto=Vnn)Xb5QcwXB@mP|DYTT}3#5 zR$V?U+9Fea1vp?H5OgeVf1x+JnPdaKcQ57bPU>HeCy@7$FZ|@(z5Pd{d}Nk^#&L%0=$-H)FaAF>CZ>#}OT(c`m{h^edrKDHEhWpi8xk7|PX zS*23Jyvx8Zcxe;9b(mZ{EgBC2@5q*)i6V6KiyijsAnz}q73n}B;_(M-W6^8e#1R1D z=G#3L;i3jUULrc{j5OjVq5hYKAvxKNOCa(9R|cQt$Xd!5elcsn0Vs1i`?$J%RIX}% z0PcR7`P&RF_|1Bu>?W0;-MsRb{zRFaotocJOySmzm>lUyL@}EtL%tpq_{#i2MD(ry zV!fve0aNZ(B(>`c{uPS`RE&t=DoXpBh_-GfenG{VyL?zK&Wx`ZgMoBgo5annVDTld@boXS{O(G$@yjl^iQ=mJd~mln4Z) z+lkTw1sr{_;KT{$Q!`j&jh~%W&3J%=vzeGo4SSAY`!E$E1a4HhV+|R5JFu}AIWmQ3 z27r#my)XBJN=XU6PFwk{n~ADd7YY$~Bmyj_))~*Z1g$#*WCN8Al+>bJSZ92>wEOov zs}Q_KWAx<#)Y&Zj)z~wnT^cbDl|jjTVgSHf=L{hL&vd!Z(Ou!|Qk)0>;iv{^{J_Y2 z;6{OnhBuRBP;2_?yFb4$oF!@U8pATw*oB4)vIeo3FdxOjEIj~}OYhdfOI|?a0f>SI zP@&YpI51#R2q>U)EmsBG>Vgm_uM>Im^U3xNPD{mW1LlVZF$)GoZJ9%Kgl>}2*52p0XOWQ7gfr6b7)QAV4 z3glMsZTk~xg+esk2Q;^(Og+F|!*KpUpCFf{*S~V$+!9?RMI8_sYj)aOumHYXHQITL3gOGUf ztOS6;UKG@bL|I?47>(cO#>lC+qq$PN^QC^{lS;Hk473%Ue3<|EpPZk6bdAbp>sB&( zT3uJMQCax;#GO1fm*=ipAC?LMou1gap+@^^FjCn_ZBV#P;hm+teuGwzNedx>+kRL1 zC{-t)EU%qe1?+6;nz+xVCYDMtrS?j91`XhN^w9zUx?5UG^v-i!`o>^x=WZ$$x{7on ztEu03r?V|BWr*Tx-fw6CWlw<68S2hJpFYaRr>j?zKli@e7g7MidE;Q!D#UC>&7 zF$z5UG<@rWH#@eXnxRc;Ut2>`A`c#mnH@ha@`;%qmn`L2f&T2TOdB{0c~3&&kN)qo zhMV9mEys3wZc$>~ky0XIt?cF;kBXQ5+UNDJ4IckwiU?Ap(!nClS&C9w%$zA*cNA5n zhk8>*3G=aG-#V#KC*u5Zp7a!FWvWQr`C?xPJb#o2;uxpZNQ`?D5#vmv#KqW{ik5T7 zT)WY&L`5hhKK}7+@3m}tUb1SVn3*QtC2({0BNd@{^zg4QO%bxpN4L}NNDGMoG&!rj z^oP5Xv#nm(Ev?tQ4BS6Or}B!RX!X*&ib!V>w0Pn=iF{ zHyiB5ye%W5(#Ulud2*E}qI?~skQ&Rv^Apdfrd+z)Z}$M;;%Q+^S99e=wRA$Z5=apd zad~O$aV}L$CnO|2?Hox7fVil^JBHGPM(=4&NrX7qi-ZE8K%_61&KfEfE>MiIo((Ww zPsGOOtxj*{;?!8827kSY1AuIovz1Xw^o}k*g8|m?MzTr|0N8u8lMXcsj5DcYv78uB zR4jszByawWYJ30fPH#6t0c?P^bvxz&_dp20@9qg22Fm`M9q#HGe9VTL&r>2;PE8PW z*Rpq8g}e)Ae7UHtMeCaC_@l);-`$y>R#3aGvo9DTMi~d2QaN|V_@-q|`wEDv+=r}m zf@DYPfXsu0U+t?P&y-?ezffG#ZseA1gi@V-|3^^ z_{#tu&Ce@DOggf=rGe&P+x}-6%%^?^RY1b4|OU9&B;wY<&dA+a%_tWJG_zPGkfyk^7y^Q(a#n~KU*CCd~yC!&U7{@ zulikbH-btF@-#e19(-$Supe_%D&(&UV0jP4(ofC96erq<|#D!M5Cx z?h*m(wX>m`UzmnI89d{N5Wp1f;By^QxXzYVk!WNPO{FJ@5V=)=XY0$pKC-_4eAMBuNWVrK5WBXb49t4g{&cDD4deQg-X@3n#5 z+TW4rUyOL1eVYHK0j$sc{uUyPKPehT;jaD#k~}>7yl2N~o2<*p{KZoDCN$ zmhTJ!K(*sLiGr4>dc_Kq8&OUp-Tvj>?MTOhbKbdaRFQC1Kr70zZ+I;8rN8k; zhX)kS_~j%>2wml0^1M1*IvZ#NC>B;Hk|~pIbwVRYh-ask2ep1NBaYqzgD6CKEd zt-&<}A`ivF0!Q(@5Uv9i)v`?r^ws61;pWS+I;|p}*9LVOtLKQwQ1{`RZ@qyscT^*fw)E3y75g~XT29aEE`Err=GpR%Mi4**Q7mq~ovmgO zMCH;pJ+^N^8UP^bZfTanc^~pU5CH@xT_qG&g*$t00RTR&mgC@9eCORH?W3>J&_*gK zl^}A(%%wfazl6=Rua`}=hgEDFFRllz*519H7=zv_eC5EvB2baY2AUBxesb1$QJ|BQ z4)q!gN#LyKbT#kS&5!CWjECXD^=JAyp1Ki9>xf;(r9Lg44^tpD_fQ&(?Q96-x}PTk&n zHh>2azSM^K`t5hS4VBk9m`~hW|MEy`-dRBiFr@>;@BO3aX;%rUs-;s}tO(L=_aVD=);4wRcpE?Zta9bcebB zt-)2(3i4FuelhdTU8&C$b_PO6xM3$Ibo)OKRy!fDYF&xI&AgBd!q{+5=!WM5_;`U)G6kc30Xn5mWoz6%L2|)1dr}N>qR2tLPWMHr#6L2oX zs^@I(RF%7}8?jU(=_*_LMN2|ha{+j>YWsg-GtT8>iGk^rIaf%w+DMr8!3Cq?868L! zhq!kp)t3wBJxx!lwzUUuT+Y^cJ+*F>;dsWW5drZPW32X zK%fWW#v2`5d7TIqiEMzTbV5Qtb$nDaMxW1Y(viKLm>mXPMdV2c=5L;Jz z??3<&dh$2Bzw_bQA5ES+?9Sw3thzbC!`^nZ_j<+<18*0@8?kOh32$Ua5`d0{$sKvH z#%nJdhrVKNr)TD^?~H!_|DJPT*63z>T0^J;5$dP}BB+*LYV7SMaVp3I(=FFFPyqla z1hy65LbCWBy`#n0@^)cMU(9S(I8B1Z6sq~$p`w;%({oTL_xLSA~aY-eBNNFK7sz@j;gh0M~J9m=t^I{l>;B)Wk z^0;Ey!Z|{TpE0EM)7&D)^V%?zHEMR$NvK`$VHef+`V{DbR3PtlSoF_Z~)z0Jsux4v9Boe0KZRrIT(SJwEdBx{Ig zKfT?E2tNMn2|JG|jaq|>g5W@DtO_qQ%uh`=QY(zZa~>$9JvBKlo3@stBniM8B7)s} z>GZTpdx|BHO%>-IaS6n|fI~mnjmA$4W>E#fERpVu0F8O@mI$GEsik*At>v-Z&pG$ zxHe;*;My7dFRUMYyGx$V9~Y+dfm*ws75H*2va!FKota|dM|YEt{|2v;r^wSQ4~wgf zSleNvw-b?va%oLT&e7;rA{CDACl{X-H8Fxmf+Q5?b4#8M9(0&0#b!pGQIt;&fOyH{ zzVRjOc=N{;aIo~k_Pp>_^a84D(71j16_1RzRS@uY~#h3gFUwGezG zd+2TJ2D;)*Iq$%hPA9@vBso;E^2|O4Kz0Kt=5DwjdjgcGlMr`S%s4ceVI2UVDAmQx zIzxO;NrfnbYe8qIn+1;ow(q22{7mE=ML|jh0F+Nm(p5YgWH@#pToT`486$FZPOVm{wKp84eii#SC@UGdIRk zH|Gzb;g_Hy;haDHBxhw)038ILeVX_8;uY3FkaVPC(=qGIxdTLIM00q`;XA$IjrjTd zbFRWw93qFRsau}Btb*CSo1R_gj)?+w%*mht0BJ`IcjWeg8ttn%5pDF!Sz69qJLQU( zS(Q5!!1q(usR&YG+EYA=WOBgaxc-a5|AOJ~3K~#{3@Z8$zL`p5Zr);3w`ax`+g&1so*Y=8reK6RIrA8s} z!|z?z5I!i4Sy$ZsVqYo*#B%BKQyXVO>a{Ox3ddd*Cclzl#sxtpqfF{ZY;dYuk)>I^#tR2A#K)5V2tk04Leo z-1FFnDEL6VJTtv{o#U=TvBp6g+=zu-MQAaE)Z98#QZ|a1*%5anAE-h1t*|lAE*8$4 zpsfrqpa;GxHf0kERU_U+0D@v>^NHob+Wf*KJ*8vOtcLDL#~np}RksdyV`m5jJpUJS zm)8cd{OwwUjje-(9eP>tyCxwdVoY;mNZj31-R%ek2q_vK0V|97_v{>~?Hg+Qh8pas zox{{rb-*w}+>=ov^0`gAilMQ%qofwLbj(KKpdY1$x1b^h8L_vmbu0lf>1!Dw3Vig# zY4e<$x0?;WP@)jnm|p8lMyZeyDveKmI=lIx%RgTy>I$aZGF5QvAkm5R9+IxoiC`bG z(d~raBO*9{xOnYrgUL~$6X`A0`GX{t$mdpS0SHnDTK@F3Vl(f>*fa>y-FN%P?=5tM zNhY$s><*-^BaC;yb~^lA_r^D#?fk7{0I;sSoPRRUpOt22-O{HXQ%_?+tGYnK}gZ{?19?EM>6*TVAGknp_Q%bW=|$}L}VFO9!g$0X$lfgmEe8#4j z0f2+Iy0dfREtN|LMBP!uwqFE({G`17b}#No03-@tB))dPnqO4Tk`SSzh*EKRR35(5 zyF4muT_IJucaEeMp2B#b%$<;{{Vy8^R{>5;_l`{Eo$-k1tY1B^*5Qlc{ld;D8r_V6 z=+hq-T8qvoVxdR~P!Ew$AT(~>PGp2pCb`N*#LiHsT`5Cm4lFKAxwJy!U^kKqZROoB zV#>37KWh+*jgN}3JCvPuXJv9Uer&3lGc&h*Zccu@+(56k?p$Ly{n~eiY&!X3{zWTQ z>Tb%_EZ5r{ZOo^hJ!8o0FrezZX6I;e5C&lN6mH zQ$fC<#mvty-Q}sBoVknV?&$rh-FY_MNZgUm1g#mvM$O1}|FskaR;A}b-So6%JG`(I z&nxDdIZInN6F@M9*L@L=OM>~idE=W~P`5wcde+^%=&OxhOC~2}n{n?wnE9)h#Nb9; zn@m%=aKqaPyVb15qF*0gn>xDxc1OiBN`w%2`f&Mj(HT=OoueofkA5(1(CuFoy+UXL z)``Pyn5NJ+;Ma-B&#fsbe}REL2hNC)0u;O&R`$;#OwH*9TE{4ruKJDZ2h+Z)UKCmI zE3>h-4&q|rqD07guwjjF+xEZ6mud}3LjZt$?vsw19Gmgua(+^orFRt*m%)7olG>9W zFQ-S9sn^^7YgyAFO4s>Hv5~meSPD)pKo+APx5td8l9S37U zTl#FEyW6^$+jb4WHX7y9d2Y-FWCNWIRAa4G%xu$`%*Tc~D9(_Mk@-mtKg&DPiFB5V zxh)n>D#2=TZ)g>jKrlP6oFQ-6a~%NSjo;ovgwd^pIV(h{Vrh+MMnb+`@Z5Q)#}VzE zm*ouUNaQnSbHn1oEHCW&qjK`31cGwuR4lv&05X-&FYWEGcKKy5W)1;_Vm^?!#yd+Y z5{y12JtZ1GFlS>mTYs-nfd)`u-FUKoJ(yI+8bh|hr1>M zjlfcX5XeK(Wl-fH6X(W{ivCDuT@l5ov&Id*rR`t2Zs9Avu^EGa+Ng*VE3p10O<*MJ zM@;FxB~!R4lQ$luQf;1&ZR>hir4SNp1oDY(&1`%MQ>&B2!CT?53+2*n;LyAGGn6nsDOtC*eP6MNx0pK=U=3BdpYf#%M2TsK zZGBb-_Ekw2Cw6ujZb#ZvoIc=P;07XCq2bv)Y)0J|6002bBH8|4HF%GxbQ?kBsdMq69Der z&&JQoU^C%CDrDcNm&wKXHolfU|LNjt0j)GLXf@c8d$)9ND5F?xu&%77%d^_Lbxj%t zwqoF)f~>4YJTsmrFcT0V%EU_a3P4xRSZ63o<%TyTt6F$F4w+x;yo14BG#>}S1py*L zwe;MZg$01H9GkSKINdhRq|Ipqz0!Tr*=Oq@+1imiH`MkG zy}hsQd^Jl4Vfs32NpBj|Ch00R+CyA7K&h`FN`+LIbfnZ`w&APV@P!FLK$B$OF4~f= zWD<>ctNbtSh}!oG1%NALj;&N)|7nL=hZxWLxyeAzC6j&9GQ57LE48RG9U@Z&^T#;zk7IAMs zHl=qJH4JSOz|b}Vs8}=>ga9x)OlCDlO!q}^H)38=l*)W+;Q#0CO=4_KvNWM{%`94jlUs=F#1s7UH(92Up^|6afDFXClZ7OuAm5BKZ${{L@g=X~cI5WJ&q zcq3=i{Ito2My_6zC|gsU8D(&O(inqUD_}T#T(x;~VPfPf){!zX0z;H4Nd(uKdh@q7 ztGQ2e0|1YIJm0yUsuiYKdl<2t6q`3v1aJ*K|9D|yC02>OQ4mIv=iyG0Dh53TactoDuczuN+QhkxbAL2oaxYMBOrooWuq;#xqT~!I~6_o)4vlv`zK=n zh@-)4*MIL|>sM#x!`jZAuNdgngWqE&BG*;bB(^eE6%SI+)+F+2~wTX(IFm!%u7w7hkU*EJfC8=7q zRc7FB2-kIGAAe`!9jgehz>HgQ(CU&Gx`eQS&YxDIn-l+mHlDKei;=)=&(p)YE6}Cb zs7o)H4z<~u)VDi6V|0%>r8Fm&Z?Oce>(CZnG_X>Ok=ncmlM||YLjOc zA)%#m<`{w;-qjqZ`tXzD;En$DsA>82Xkv_FLw4-fmopCl_r5-Mb@1?>9@V{Zq{G;sC(r6Q*CtllsKsdm05{(5 zi&b3EI1tx`7yA`4YOv+cVQ>EGH#Y2x(XNf#sflo~p?4068M`h9;rzv5xImjl4zPm8N1Z^QLr)vDQ?Z#xPx*;Gm#9yuQ9zc@Oe5ER1B-E6oU zpFXS96QUl;il#$oDZ;d*IZTbvoubCfes);1ty4Ml@FtG>JR`Gx|*7T z(q15H*_x`kYqfqf-cQPjvvV?u8g9pOZR@#1gIy4lgv@+K3gKl99TR_UOy1~Lk`7IX zFYr7)Y_Kg7w)ScOYIIG;LR*!yIy!D$~Qo>2CGTe*BV#!$=?t-g!7Os#OY)!p!w0k=fYP_&`ZoWGR15M%=2}1W?$wgfx98V#Fphlo8kbRk>$Rs|T zZdsgUfsAF#+p*~|2xq*d)BB%g{c!Uu{chyA zVm`HOYdYAj`?zwOy`|oE3@h&Am-kIUt^^WjDqqi?@T*TARzLc~&N@9LM2b4JIJe!R zvNavN(YFxG{kHTBG|0(qjqR~iQ`ZH+vL_JN559Mf)*x`(~ZNPy%P5zw~wN};Vu zX+&TX}ayGgV zzxo>+Yq=icD$;?2A)pr^>zmFOfCY$Txb@y}&Fx>{7{SZA4f7Uix?EUs8`(TqN}q4M zGn7Th42K^V7;=|UDU36n_VsW(o*vbm*NiqH7F~a4EXd8T_O-$3lPk_VZ7_;eoTw;P zSMln3G4-dz+7oCDif)-hnpFI zK#4p1MG)uJU*FKNnx9x1%S+8s7hZZH6QKkV3NFSB+Tb7jH=jz~wt51aREe|6s%DVe zoCnm{-;8yPN?|dvN~8Gr207;|xdgNW^VyRsIHZa}a!YCHm=24z4E6R+6ccAUrtwt> zmTXPke%Sdg<%7t?qJibpC*?9(TF>gZ(HPC}q$jN^6uxv8jAr`E^I$ zrRI%wg6vr?wTaNg*vx%-=FT6~s|ht%4$`l^-jk$)rtOXfJ8{wrO;bMliUEH zYv}lXne^KruG4{OD$4rCBq|+7h(Hcdb=3xpuO$Fb z&0LZzB91dXIjmKLk|-iPuhXa1;@o!r-%@+UeI*-|cih{IWXYtPI;^ZjRSTc?O>Z+k zx?c!M1QC)S*6PRxQ@%KXN}s+xNN z)S^^Nj^yIpLVz>ElXmcK|8mcUbPyf=d-3^iOun-}`!E{!@4j;Fn{VI#TW{R>n|ZR` z%l7Z?eY0xL8aMa8QD`;?uRE$5HQP?3xBSH2SteFk#8+Tol&u26xu6lHq8N~FTF#kqAg3E#Z)4qe9K(S_$#DU`9_l7ZDGe_OKQRC!wLZ2`x`sw&uT=_F$RhXV!e>DP$=1b>)^ikMh^`t z15AAQ)1tQ*NdYF&H&T(`{rX749ONuWa+QxXwm4lmb4lM!Pns@Fm6^$dx9l6L=1yuz z*HCXGYD(HTNRwQjJSv5TP|cl5l+5s2ND(H_tIj?m?d#A+Q@CHY^sc6+@&T*5xV_8k zhyg`^JI+T@oT+l=ZhkS{xs%)4cRsM$Flw?SSKUgTE-G-gT0X+jCGu1$KYEh4xSoPeQ$nVF>ChVGt_-c}9iW;4cdxc;&B-<6L)-Isim54##?PS7$xc7g4gb zuP@zJ9_}Qk536n})>#KI^LRf+jf-<9ELWxB_(744BB2j-{3iC$+laHFk?)KSl1_8f z)PB4dcMHT>_Li#Y3t`I3YQdKQS@N;Lc0f*^6A=qT@awtuZtvi&J^&p4bbTzk`(_?x zDoPY8IC)T>9(w%D`F?LBk_2{dxtee_VTm(-`a${f7?#)Z?KPe()mvWp>iI>MvJ6c=J~VFZ-zf{4mz;Yd!Kj zJ!-rSK%ltX7VX*eIr_n_tn~~4+jsM7?oEtYUyrxV&Ox+$BO3HglzjgCM~0+jpHveb z?j_HDy1=#vH<1!U%*B}#CvRK%8=5Z@nPjkhAO^ zI7{St_ikRz-EcP%(`PwAvr+Ww*T$V*xM|CzdtVz@3omf9x8xd5#PF*jX$`tV$z+NN zq8Pm;;k1fb*yfE?l5NC%Np6R;>}nGGdFl5@do4;8#B{vGZgi|dN-HmuSvo49+)wgc z&%L*-4SLJov!D#p(X){Am254UY-a^kyrxQS3lNS^bNiBcUr%oxb= z`NR6ne|<|E{Nzuk7Xd67?Id!oh`27ibO^o8sB?7{bQTq8QK7C9E_jK;5COMNYC`Ns z1mShZxvncOz3X^iBoDxz%bDx=i9x*#pbQ>AC{ZCO6mVV41q3m<^(%v`3$kC^IC%+s z-8G5d`LR2Gx*kWk8loI>2{bxO-jU#&a=@oU4Xyu_C`8`>=O;_Spj|)Xy(7`tt?u%& zGs;ZcL@FJa)xp_#FKr56E!_TVJ#R@z$ONwTO9mE$t0@~Anb7t(V=*pWJ0&)5W=aPG zg_S&@@LAHH&W2hDgNt+5<*Wn1;2=)>A!?I6Jp0L_oYTp3cY3tKBIM=F^TL1y1HUXv zw2p9oYA1*F^wLzVgQr(1s8S6pjp;yZ6X;ix0^9x8Dk2j?10Bszt*yw_6y;hcDo(VH zQ2v*!Rs^`rrp6UA*GoFTUeT_^N=LXja~(@j!U}}@<{Oe!8U}p!(}f_XoT9D0a0-%4 zG4XIGHi_yGt9s!?!P*T5%88RhLA26~bDQ+EfOi5G3s|r?vjE<>auP6`bP-+i{#} z;X_IFymdVbGaQAYFL>*>w}kkkS4=l=yggW2dtRP+U+h`|f`Y@uO8hmSe^dnI(V(b) zE)N5h!n4OU0GLdf1ckz#^z{6siBl!}4d6Olp}e^|oZLs9 zTR$!rrYzxl;k~7D;)(@95AS|;R7`^V&&k8`;H^F)tfJC@%)~MU**Hj}1j(`3Y@x>C zb}TbDIZy<<1jM6HOW!PSqKsiAa@RLxA~iW|WSiA7t}g!@?+jMOEX&eR#YsFG<~I+v zzP34dJvIXbRW;}H>bdtd0qt#kv7cQlo0G;DS-ctW2KGeGleKP9R7Z`Q9Zi0;xADbS z5B{yq;cH)e<3Ib_>;I|2oqTATr>}o$@Ly~`|4**HdVR1NUkIiEbj?~KTj1gmg~)C3 z4(onk^1Lo*?$xhvz>0oTzM2&Vme}yi-Y6D|Ycv^|DqnDWNfjUxfs8a|z+-D_N)lb6 z>r5?McTVzLoLk`K-X+y-pp6qtNQ<=S0!%Y=oNGYz7ADU=M?biEBXu=3rJp=nIzP62 zC@7{jSOw#fjb2S%oM~X_Z5SC~Fu>$dooyOn<^}}HF?qi6ZeN5RVoKE%q)lKGOB7LW zWXg%dV3!vrG|rNEwYKbrD9N>J=;k{EF(t$nA`}~ea$?D`vkWLwL2e2^dD@T%Wsm`w zpe{&&0~rO2Z|PcQJR+#z#svqj_k_cI_;K;xH@9u&$uR>H@#7!Plb#m3fl^pborJ)c z2t_kK+!YNnwikrwCykCU9T@Siefa(9%K|rlWt`-CRW7vp^~P^)zDQd5LOATp1JrnW zzgqLhy#D2Wl&Jc})UY*{M<)Om$5L-4OdM9ji{O`rU%~hw0fZ=3Kl!5z=J#=;Mw@2) zTC}}y##_2KP$t6ovZ9J%ac*S~m&dqU%l(Zw9ct-;nLtO#40pdgCd;D3Ah)!Ol_;dT z@H)d)C)UAEQn#_)GPQLL*DnCDlCi$be)?RQTRhaAQcM~a@r?xtW?Q$vGDL)vht=7G z^`~WYkhIZHFnL;MJv8wPQI9y&GLDT>b#(s%&?)%icvByw{E7(l;#y#-{*=D z0RRX_+h+Ghv~yto+JC$sr>ZL*rM#DHw{Di14Gl94cjHxu2S6|x+LD^mMP(`}pVf8Y#bodz{Ypt|DZ72Q&&vR*>-R;BA{|q`@H$o< zI?T+=MBS^dY0@{X4J9)%J6;t9d&{n(IMcSKz|rySti;)a7%s~cpCxwCvrtx@C0A3@ z*C&rkF*?}3m4zXJpjU|k!E+FXyNQW|=_C=`n&UQ#jff?mM5KbQA;HL$0$`{LCt?(n z=uRAy=EgggB2ccw^tg7GeE7$RuyK%#_Y#@M%iKZ^zR_OF5K5pQE1f@_J zWgB0oAi`T^SJTO-<#+z>^H2Zu^Gyf)+i}Zk(80KZ@VSw{I zD~;ZUGV!woVsZhS%GV3$+x$z8p>CF@anjWzh(}dm6(zaSv6?)u7Uwn{Apq>Z5f67` zNthCY1}PVsDr7=;8l1g*xiVr|g0`k0{6Xk%M_mP3&0V=>E!hHyqJA3gggH`OdQ>RY zaI^5!Q-6BsZNoR;8`KMj5VS2xhI@B&tyNQzU_kZUfBfxd=iggRDD<$-}bNkZAqtJ&s_bg`=7V0M-mAsd;XRCQcTY*ToF=Mb3H1{=}w%K=!-T+aRBV|#Y&uQa*581M%&c@UCO>p6`|p^OW(Q6~>dWiEI^ z@l_gffvA)UG4o5hVw-#?qKVGe>FsZ9nJ5TXvr*(ND}|x`ZaI|#YDSW2A%8J}x3rQN0LZBHGUox?t;|-t+8O`= zAOJ~3K~!0)7QQLTq-yJSrc5|XTulmLab}fPYh5&8>mo13S@m-lXHq?zR4a{5;kwgZ z40yu`(2qan1Co5qGf8HB6YB zNv`8uv*-DVz4t3)VH?Tf-MO7BB@R|B##Ks#h_5AZR_e13;O;7zt()nj1+YX`e8n8C zjs9>Y`I7RzD9N>0(RVdd82dD|iecUU`Y`Eh41`XIM>-oAIjz&a7Bzu3Xsa;!0Dzls z56_>~CRTvx9ZTT47=?EH&H1VAjQ?9f(^3K;uRd|=~y!TEI6`nm>Z>L#3anYHl+H+ktr&V)W*>md`h{)_Kd+uD}sR6)YeyeIu zlrl<1jh#DR3HOTGTVDXc?cHzml3hR*$usdvuY+J~ALch45(%AU??@aI_wMzW zVDoyWWAv65SDDwS2!%hs^;%Xh{Nmg;r6yW_H|kE?u^!kWJAx@ZQmAKM7=5 zjR8EpUjjhVGuVooB)Dy~pC}`2RHzG2o);4GpRLv8`z>nQ?ObB6%K?YL`;2Ah%800_VyL>cg+&!Vo%j{Mx1yxz8vyoYR}McenBnke)rE8#xbPVT7fy2X{XaNb`@gFg zR{5DO^~-%vJi%z~c{`iTTp83h4fAV2- z|GU-wZx>JBFV7#??11{#P( zEKeT1zdR!4C{bEtXWc6rHK8SnQDdtdTtTlIvNhR?9{zA9D}C!mDuYbdaFl9o6cf}7 zKiWO%P$U8?V}6ftcW;s6$a3HMkakF6h7vwxVirfrZhD)rUKA zM=h~+s8M?x5h~>^efTG5XOC+;=d6cs{MAjZ@%&k>3@Qyu1xA={+em0FtCC#n2yI2= zxh}kGdwZcx0)nf3F>z~CM`rd;QcE#PbqCu8xdelb@bHtmu7W-&&a|+lkYVS*Y~P8~ zfzc7V+P4X>d?buthTT{4`B~$g*urstGX{X(P;Kv<@s^2VMV9k%q!b`PF>w;-Sx(#= z-`La|>y^A@iE5Sv8CmwWrsCXIg%9j4X&b`i6FaHMm8G88y@?cVyq9za+q08q>t-ga zE=rZHeJ*^c>+H>u}Y(CT&Q4r++0l| z?g&r~h00ZdNmYjwJ9}Xu!w6zsxB4PN74(*>g_A_rC{e;ZZ7L$-$zd&~$QPK*+%m8j zTt&ZFarWBRH^gavb`s{&`N)WBQft*&Eldxa`I$}H2Ot|6RH%$v+6OQk-(R*aOv}l( z+w@FXyNX<{|{=GcT^_t*UM@qQBH{TsXn=O6+`%`9aY6`hF zz}~UKK+!$=v<&6~9f}>Ra^j#B^J=5&!i#2HnI*sJ)|ZA_<7FR^bi?fbmAP}(qCA`x zkIv>FpUr+YE1s0isdbC8KB??^)tonO=BeJ>`0|6pe_>tOxcSr5Z{L6ZPZ#C0+D^4j z6Ei|oMSWD;Y2)U#oz`{=&3^sQzP4ZdZftt<@_B#qX7NA$x9HylfcarFdu}IB>&rV^ z2SiFuDTmJL51c)&E;~Q2)znO&6e`3JzYBOlg^j^wi8~AUHj={GP!6I(9|X=MaKCMq znIr9NmW%UMpFVU=u#8M zwr*t|v6Fomt_FCzi(vCy&0RJ3NdxoqM&3?lV6V#H92aU(tFEiPis^m znS_WZ&#N@o-cm6960aO+sD++6%2lwBbbT97}|8 zF?B>-FI>w{4hG)jujnUHVLpmBucyVtN!rQ&8-4Oz6}~MzARR?rM=exqr6EcX7|x$n zqrF6KrKDkyW2wY)Irxavo_Wbld+)7Ye>(zz=RdomRQST**tyc}=tW<{Yw;W3*gSny zoqoEGacta4^RWTAz#3kKx7Pd+4&LZ@Kj0gd8c(M5^3OF)ju0Tue+e+w-QO4sfPV7e z^XX>sNL_hki^`W;kE+G7EgsvAYl%q^5$0!&$nb@Znhgwd2&7(uiFb3Q01%EoDSO*- zXjvJUSQ$KdTp@yvlu+-PUWhJU=~yINQ0L^h4rKI{Np%2$yaenxXakF)RNeXN2oZqs zvW3}jKNg*GId!(8rytZ+!R3UXzTX`Fq%6RylL7{L9r3 z?!2BQxw_y9_lv<;SN(R}*TAs4%q1E2pb#iJh< z^TVcDc;65?zW(LD((1Cz-()YfNZAIs=jK=YEm1fyNR-B=BwLdNOap-Az^t1N1(y{B zfc<+tZIB#^ui5xoxHi(L(EUXuq(`w1%?oyrtgA*ov^_Gz19Avu`1zdO-kC&73W%zZKVW zFS*0z#MwIhMF6NLZuY3D&wa;8h1PN;xD65%XH9=A3bQWa#hG>PLZGRRROsUfm|69= zqQFg{^+1Pg#nHT@DPr)khNkj$;cZ1qVU#M9DDT)rC?ZLvkv-2&oB62)1{EVQ%qL!y zP`pGFfQiM4O}Gz|j4RD^UGni0H#uDr_+@KDz-Hm^e{1^litXbr;)+A9=39?_rO;M{ zhyvaRPymqv1B;kA8+~5r1A(}>brLoJ7+;Iljw_MXG^IC@ic&q;PU?jNfH+lL@W!s$ zy_;;^OqIduaf8xhAd+WS)BMbOCsIvjhEd28!lv@Bp=$1JO(s`6Z{(fe$TeI}t;7{k zcQOg*-!TB2Sfzc_k+8~{WdN_j=SD=+)l9WLQp}=xYT1Bw`6OK6|`guiX5?AkMT?w`Yr&p_7iMU+&$%&s&=t|1fvN_B!xise_ z$H0sTzTvv?;&9X(M@j=zaAGo%Dke@w830$ffvk4X@x{31;7cV^Iu2Qf@Ba3-1O*&F zC`bE=cZ?du^GGKl?@VhIB}z!7-tuTKxw5t}Ep1ai%WD6rBPEZY=-6i`7H|n*NQLW%eTS0*h?$qLr2s&wfO!$Iw=}sJ z{)ND+j#{$ny=5U?%hV-KML&q%1@1#N_v~567tKUM6$lJqe|~cZ5!vM%uv}?qEv0(&ZfuB`LR1a zblo90zLtuVFF>hR<}$WV*8I2;lGI=~v9(`~r%@7rAsVqdn2T=R%Ldz#QV0ki{_(uO zW0XQ^;j+G-95!MFga}DbpFgXJ;H}@>I{KuHQdKXUiBTy`dZwDY-bN%A)B;94`)EZ! zh{&{jR_r&7>k6?Ik+K$)%2Z<5rsV!#AC;%lc$i zJU*TMWHP_MsGgtAKbn`%iu$Oij;iLosE)q)%73&RS-JVFe5#aDsEhjOd~ttLJe)2b zl=X2@9m1FYr7yF_&OF&(x)(>i+D?7tZan=v*nBDP8(z?5Z&$uRwqoztIa&)F6_2WW zzdC*~egzDC_-Ub{aGfQ1`|?iix&k0D2*@?GIJ4Mt>U?Vu^x+!8A6^rwqcn{JpOWN0xpZz=5=ZLpjcr2=f&>7<-;Pe_7ON z@3mZ@%<~6V{L1xr1|R-Er!T+rzy4dB-twa#%&us{?`3i;i|N&@oV6A=PQ%uU0NznK zb<|GjgbcH%Z;f!9JC`g@V&w8;HEd0eiRl+z=6^5gpCqpGv55zx7{j=e%S-(grM zpE>||{$bN$SUY#}WuR}jps~xj3KU3S26rLE`D*oCUv;B&feA!}B?^Ppy&4f-X!;HC zOEU8e9_mk@dwy>C67|w4QN|uB62m^n(~nWfHc=K*EER|CS3=` zDvjCDB)L`!&kt)Ew+HImzUrBnExwxPwM9f6q(HiG8&NL!YJ8BXOb6LXDH#cv+%?Wbj2iP%NJSI3Ea5_mr-9tJ`Em2`+r`O8 zO*+uxGpJiem}|(yiUFF6n$80U0Wbhq03hU>P8BEMPg8mMfP>w5wMh(aHUvbhjZ$0J zvu>AJ!?60B(Gr)rcZ)!T?Rt|f~zm-Mu#66%F7r%qH|ljqIJGglVj z#f6d7QS4~xtpd&{<_&?qu6LpgQZw=z-ixteT6w(`z$($fcT^@49DK~s5mDePkvuhj;lOm((! z)yxCHHb(}J(Ui0+A~snHzk>#O8Q0|ZK6~uh0fA<|Ne8Ks_xy(MT{feJ`*Ro zUfcbX4J~eVh^RC;%eJPCgH-m!rypK&qr96>p4a5bTdEd*F|l!~J12YMFp3FYxt4@0 zaRu3)f`m|MB|=v~5Mw-fXqmYw{CGbtXHG;<0&iV^Yw+yDg)lI+K~!+`X@LNv-4MB2 zP5lRdaN11$SO3Hg;ve!d1cEUs25hX)jd`h@`r?pzIZyDG1m4Pr zQIsMROrO`;AOu@5z(SN_2ufjbZj-*zMoA+Sr|QbuLdUJ8F9&L5hxukhV?^H7@~CAR zpA2<8QprFIh{goo^9O%;c6RKGMKCtHz>W--iWdx?5ujQ)M5tzNdfW(Fef1pz4vc67 z+fXrc0!9bcm}A$lL@};{5mMUfmGB2)Ej5+*mIb}ikwO69kga_=bxiC%D}_43X5s6p z=XUBV5ZjYKpZ&a>o-*N%OXF9~tgzwIzSc(Gs1S2N+~EmStB&sV_2H`u;KU@GnJQO&RtHKLALsm-QE-6qN znv$%gtvgw(jNo(>l%!o(KR;>YBYR7TxHz-J?KtV{)5oPU*p#G=@}8qqJ^R@r$u%G} z6*0j@O^3WZx88jW0Nzp*t88fcn{hdFaiVmjgyfqJ3^4rg50AS(ys10_D6L-qwM}JE zj^M0s0(&SJ^oSFAz~4pGEHmEj5{0xA268NDb&%2MlaO+D$07k^w#q7&$+vFQ2 z>Rp&a5c}HBrp3d_;=!zVbUy!RvbaAf?$64{Wpgqu9}RXhPJ#tw)tpU>N2jx&98G>W zTRdD;&(7u_O%@N%<{z8=A2>LfSI?^E)cVr7qNq=5JNI+Ue(;}Pul{S~17*K-CDWmU z`Q)S7OJTKVPb&A>?s5#iq2Nv17LjW|uuA$9XChiF#x>sm64K`ir0x(cEvm~-!e*rn4nJ&n`>VPb;9DzcEasy)y0p3 zRp|7nk^NavX#jZslOk+uZSbP284=^2Mum%0OOC3Aw>5!+{x}jaR2hsCC0j0DOt+vG z%e(PbKh8rNfC|r^R2_g{PURO76%vIS_3UXSK_%XCZ)k+osI_7r(ghKh4**>iztbB> z8`o3RZTT)!3W>@h7E9eE*Qn%$xz)p7N(?Bl0Up8%eq=6 zuoG=uPod4kSSNA+>hQ_?KgZ_(rGIxf-;8EQ&7<#K@ms^)M9PMvkFGLzA6%$0ZoEAZ zt1r1?GDIQIu3=k~4FJ}Xb@(Dw=0$9y%bzsPl`NL$KV1}afBM{=Jaxy<+{trydgRWI z++ymx(Zv<~rY>Bvr8x+!IlP&K(v*X}olM%05fRpW$2P7d`8bkDfNUcQ`V0mpaXZCs z>X8$mLJMM1fpVQhLcNGWwv1?+FKjNz-N~P zhRksG%s+d-KKrEh4UhNJ5D%THdf}>;`ya)a=BTcE@6SJMq!}6Q#wV*IX9iS2VmiTL zrou0WCUt?T-BN8+M9I6gdIn#l9}M=6zf=RPyT3jv^n9-K$k9C?W6Nhm=AdL4DrB!z-F~jI)qV!93 z&t1sC_G{U2C(#;3dcq7QLSes#6nMmgH~TWB7R%tYZ?N^jlKXZ2t-i#SR#PX6qTWW- z0nO#qO`kPu=kNBN%vq{tPRFWVcxS0Nv*a03t$K3@TBz_qEsKQ{0}pnSw5Nf=I}nDi zx9lo2e>e_r)q|@@&bX%VQBRvlE!`(C){JtF2-UaK0IrUib%Z8TfWTgSHd}3VFf1Yw zu!|(twW`<_6cc44-*~GZ#cFokxQ1OrajNA7$#I-&t+6g#IddZA6C(~8N(Jjoxo$U8 z;l?`4lC8mnLemcX%|!P%qk!*Iz@mhQ6h0;~6OVQi9V-sf97zLYBAID1up$ES-QIpB zx%tkZnmgf!x1=u~?!-Z*zamkOdO>fI4NYD8&U(MM70bZbHC&wAj<^?agG_T<{|Gv- zOuUScWD-~|OgeO=x=*|6LktYIqI%(_lhl!lQ=RtA_*yD*7>PwMCU$n*%#Q8H|EhTY zVY6Iv2D40cEoJANg&}JUv_T!==8fdSuB4zhP}QlMJ!k~Ud+T?$E}xNa|C?JcR9)Rm zX;}yYJ7`0-0RYmTE@xg`)>fMdSJT;}>cRJB-}zrpe*BMT^qCtmdG-y-oMib-8_Zj* z5nCSzVG`}X+RKJfSHDK>-aWpSD2>627y%K)0@l`4&Rn3*5|lG%A|(MgQbn`LPj#e*yNQm_TM|1SNt)Y#HP1Jro!gm? zmA7pF!eT~;kL~4pNc7lDP)?n4AzrnqE?fPg{(UezVZAX;`zXNei2M7{Udw^4yM>gdy=oVkv&%O1o77!gt9Vrt`5 zA%cMG|MY)&Xs1_Pg#FigU7)1c2X+IEq^EVP5Yc;{9XHrEp>bbFeJyrH2tdTg_si+o z(&EI#xW>Q|i{-UH-4q@%xKLGdH+w-v!mE%pLzicSh)khJU7XofH4!lmjs9+){ zVnKT)n2ZS)=QhcLtC2Fwdw%ri)zL@Qc-mxCYI-FmFTo|%=KaJ>KjV?#x=Y;E+fy9 zSt;ySp;RE^?6|25fAD%w8=SR7s+~KTz^RK#P!y(pz1n8WA-8!WP4Z=c!|EnHSn;Ie zHZ!F<_W+P@8t*ttl)}&|%Png+YS2dM7)`D=Z=@p1KK!`Yx)q0sp9Eh-qWLFcAciQ# zYVMMrK7Cx7L^TVakBmSqwbiMoS@5V}@$qE3-?^;ggteX{##%Yz*c5*)du2gRL52^n|NLY1qt})UoQ7S6y)3Q0877wSzgM9aArwp)h)GG-=Ez9HAp$>TEMR>2nwI_dER9LIApvH1$!yPG}*B~%*|j)?oO z_63H^hDOKORMbJqGDq>{dh|z|)57OZs%vldLtG|yMIbbVTSecP?$Ai|a5gFCP1VMfI~c~pNc=5p=zUbj zn>IC{JaLOND;bNn^hwV=et(`NYP_vSn|d%-gOMJLb(ce@6c~g3p&D)KU~#*ftfDOf zS1nb62qe4WO8`pAhHfi2wThnGdfn3y=!N-%!3gP>YJimv*X^RjdJJAbll+T(=@?~9 zyLu>iOEU6IQtS`acw2Aon$114v7<+uCLicH4N`zhcyS_uwu@7{bvt8*FaFy*JNNPj zKd2u4uqaR6XU7P1!{+Pn4Mat;Xl+aZ(N^BoM2^#*`N98vG~AA50xIxFzGd327fp%) z(BF&^;p|y053mrmItFMp^M@bVPyehG38WxdX-_vL$%cILuxtu{^Sxp4k0w~vy2^GT zeo`Ss&vIYF#{kHaYuf31G~PQn0OZ?W7>I?1Y+p_3^MSFo{|o|YKz0N-;DFYxfTv36 z((Rfh??U2=w=D%MKx{0*cS~&$1AFf1SL{JTGA7t&p)V)OiahmfkuF`oVl`T;+SCNE~Dl;r{n$ z556@AhPIBvY2B|b_RY&Ar7aYv(TLl{vTOmf}Zh^9x4vwZk*aq_d}nU@WW%w6Sl z*RjfmMjJGd=mb$4+0&!`cB~B+=UysQdFRUDU?*CgV8lJG4Qivr7pa;D0TCb^e_FKQ zCJ=E`^Vj}^-Sellq!bH;=PX632Efjgy`ykfb0<@>&1-2FpS*gyGeJ{&ai$Qqe>HWZ z{UpeRDjM%4)y&7aMg;G;sp-bsgUR!H>t@>DO0+=}2N}rzz5LPp^AG>YS(jP<#lN|u zG=BX5o-cKU@_GAe<65dC_2m5*25UyKiU6Er6LD|2o<;2}iL_8DNK$6nvqp^Dl|~}a5}c%$E&bWgYTGa~tKRaj+<0g3=tnaEaF%`R;1fg*_wtj6 zB~w5=<5X1(7o|GRG%7f{UuuK(!V44CJ39QhxcS}y5oSkqlqel35xtIf^DFg((NHBl zgTeQQU9;S9dK;06l@@VX!=bE40Kjx)to6&(C&%T?T^LWTGO$`vx2@b7EJcn@jHp2T zpg1-l6UB9a*py*B(W*t&(f407^X)} zZzBQ((Q27k^+yUl+8NENrk=Pc{YC6Wl)>#=nfTX;`Zb_7Mv3{CJg&}BwFq5Y*WPyt z38=KB<~{rA;^sSpZ~eVz=|HQCM(NDmLSt!1&z@GVf(SQNC$8e zfmyJLi*Qx=6J1d#F0G2hi!d~1o&yte-7AEdh;7L_!_~TCjSnRQTct4{8HsI?88|a& zt&)Mh(k3t2)H)8$ws%~dy3u}u2-DM$FDV=`ag=XA50gi4St$mF-Z+wpS5tT$Bg(m0%@zT&#@ zajum@6Qj69aE4OVWX10EL0bED&RHZn^D~XU9$4 z8gZh=a^}gij3t;M8$>2iQKDS!mD0?hBV`*ehTr5l>FLp4eA$KSiZ^qRh|aX0IRLo% z)xpDW&sIrEXOCVg1ZMB8-rIkDn~BSbd-UBa=vRZ?SkCJg4Q1C@-b!QLVroo*92(q0 znCsHVsSY8+_yUa+!0W%c`O`l>dl`Y@=1qyThQ&!^FZI}8_}$SD{y|7>nolU(qU;hV zxw>S$B>-g$pNzD$UQ8kBI7*avY$qWQygPINVDlh7eO$`2A_7VES}t=$k&-AA81zx1 z7*`}LJJH#Ls*`K&+|8F!v+~{?FV#txMrCsSLy(yxSW(PT8(S)c{nH;Vq^ypQJ zW7!RY;>icy-_?bIf+$nkAbY4wGKqTpd#c8i7_fkDbyxZCa56p>4P`=SH|#3 z*DYcfg(zF@=lW80kDOd*+3Q54w#thay5)<$>V^NM8(`^+GO?XE@_ZZx1Cw9sSGH>; z8S`Ra$=ovfU?>tF0$f2aSwzkdh-)r22U>g(?%ue>w9 z|D8#cUx5M(k*$9%>TgBLsL4@%^s{PoEslGtBLWLDH9xb1tyl&&Au)q4pyAuMvfyYg ziaO6xs%_W%w9n2OAfXy#L!K=m`F9qBog>FXKJ|jwXvLvv(v^|%2Fe>1OuNuEPLa~do~JD zL+ik$B=%jdxpXBr-x)A-lp0r)i81Z#rX(hob*(fov5Az(7-gEp2s%=pKuj=XCOW>B zN=6V9r+qCSpw8bNB5^1xM zS_zVll(U2?V1hEPzy9VxHk#>C6Q@f4mv@W+;uYGypb{f+6Cp6Wh8RG6?||X>VR?4w zPM*2b=kD~-&nL8XGZSYek>^x%r(}LDsZ1V1_uHzJy`x+24(ig2jdSN9BRgY~YY|UL zFM9fd{w!|tI)#}Iof?CuM0og{r_ltlU~cR>r8B|z4vKv`|fL_kI2Z( zNHWPxwndSYN)k)uf&{^^3=d@3p4c_9Cx%A_j|~3=dt$(V0mHDZsobav7T~fhm!zUd zNo2CiJ|i+BUcBz!ciYqLW_hsoIk$N?B7taQ-l3=Q{%A#CKOi(&vwIZi<+C8azio$OL1mAEL(9IPyRz zGMH#M9t-_q01506*JKP0ALjrdB}j#xzNqGQaiLfJTmUwccblRR5xH?>WwVo_ zkjuMs8eldKn7(XmcMw}cfl|V$JUAeHF!(cTrge?@R z09!qov_+H%sn8ZwjP2i}FhYs0KC3u$Qz&FNw|u6g(iYiTyrR=Y3}K`5%irESqv5Bs+g4#!+ZfY+^5?;v7U9j-%cRqikb6$%v!a1hkg z2BEy&4mpwm^2;(SmLczQy}pcEa&}RnL_YrJBdtr<8H81Cg}|fxt$b#LL_VIa@l!!^ zq;pry?XwRSYXnGu28ZRwiPLAM=M`fXC?K2YooflJsG^o^cvVaz-M^P2Leyf8JtduB zwM*hBk^h7ooPM-$4y>jilEE^zWqF?vNGfsi!GaM+snA(K^r=-+;rQ8FTOM`2%u=Yy z8~^c-iut4EO&7-`j?uN&J17~bmOv?G7|0}4z3<-sZ(ce0-O=&lnZYeecnx0o|``9pCs={>-B7Pou2-;NVjNZ0)f-18@01=%(%DF^l zSITT`jB(CUcRy?oLcR{Q2H9);S?rL{496+~LD~xdaW*WSB?RDrB$iyU4&53mbK6J= z?Q`hQ2d|_-B#5ZW9e*Y^4VjO0&3|#l!unuuM=}u9+(9B|DD5gKk?*auV6_V(LAD;A z8|ocKFN0p)`bM`-q6AJi+q=C)X7=wUDy;qRU-;8L3|{^24j&?q-`OrXZ0`n~J2`rs zf2Mwr-@3`SVl11OSGX-emv!j{to zDl@x`2*2X3wp-sjl}Z3e+UhEs2(i@_-5t>zNJbX?a9SbREe1d;z*bi#EfK~-1&G3pg&FW;6i&+P`=0;g2StzEeE>K{k6< zZD4Nj`Huc^g7TSi38sB%94&C+UP<>%^+&R`_^$b9BT*#js@_4w&-nORVKv1q$=%KPq-0BOPBuV9Yuw_p3Tlp$t4U-4 z(A|#)H)5X0_YNW|$nk8bp@zsR=^iY(uPBpEscoBxP1O zcjBV67kaZjNB6(kpAGdYsw^XPmR5B}h*0IO%q$S70K?dO2?g~?mT9Z!pX3d|zqP$# zrw_6m+2bAD5J3o5ZlerD)O}IRXKQCImiFdX+i^!-KEFzcI}+;I3)RT6R0u#(OCq9F zKJ&A)8wL?Brfzg<$|mzwVY?@SNW6I0;BnU8ounbMp@2@4yz6;)WGaeVN=nS9W>ucK zdpkh^DA(;F$b$|Hr7wp1Stq}&&=-4*k>?PtZ!MYGHLaOIWjCS$?k ze4)@;@c!A-H&>tjWTrJa=PAc;{!X{G6HL!4_HeB-s|%+BY@)B3PsmpW5rhOJ+`pF& zSB~wdVcipisq_|I0(jt-Pfb*-nK+ScajAJ%(xnSi6+|LTWZYI#30*n_c>1&1{>@}V z{qg4S?aDx?+5qd?>+Qx`VsJAq7KVs^DPps(-1O3%ADe9EgaE0Kov`8*rMyB0Bv`$z z+p;Kr{xJ}o&$iutZdTmHo#J>BX}AS2-^;%pgHSnx*jvgVPIsoZ>2)jp$86}Ffe z6u@$8-t|Twmb*u4aG>_CsiZC4f?P(8AN$x z&VuP*i=B1kz?QBy!iU8~-+8Nxh*F8saRC5_ucQ$RekBxhlg|wEv#fSE-%k5`GVQ9k zEgex9OSX#GpsuXI*UPknewf@OMa=ZST^0WTZA3mmw?M;j5Xsuvmew1%V- z2p|NGPs+um9^6bWj|&tKcU9a{0H6yS#&TLyIjo_{d0EWNW-X51VagBK9qqDovBo$M zVKLEh+gCQD+JA&EZ+l0n0Ii|3PjahCm-gaOw$>78vf3$yL@+)n0KsWb-d<7Ht|h;S zTF&WfcOpc*@kX0h>9e0N0l4I_nG&&`&}22Ba9{q@4*tHF-(0WGZKv|J_A#dNTge+2kjjU07D*B7QeYRZHBku96}ebYK70ga6_yul&<%gKy4@ zXJ?l`cI2!xtegJ!-T&%v_@8g>mzq*<>(AwJaqvpI0bnO>r7OqL0303S>YeuLenRWP zqt5xbAM$E(tc{#j4u9_n<UOD2T=MyxP4L2ca;fD`rN><>R}N zbEP5@ruWChe&-3M-ep*#m8qTBFT1h7W#458v;%B@Z`dlmwAEwib3I%h`*fx}==cRZ5 zC9u}1NT^6y%`Uu-CBR&9F@W-C|HI>#*`<3&A?H<*ql=F+0Ep@)@b*9Gw)a96iL>_? zpZPiuesd7DBqC(bpIYwI13`9Wv;%c{F9Q?`U2WbMth2Xnz1I)NQ7T*grGpRi{;JGpy*o!LL_jR(Mo3@>03p!1HSe6LEdf9T zC_`LzI$x!?T>C=%YG%>u_4i4qma5FsiYSt-fAq%31tJ6yb_Z%_U+&z9nzV;vVe^@p zomYIV(zfXIMSoZJ4^(d;+g+KoW$RESUBxk@Y|{K96Tp?Pz$Hy*H(KSaHB3q0;;wYA z+XGc+$5I+;~p;+gy#`{Z)Q~+Ub9z1Qim< zdX~WRf(x%O;6R1g+E?T#h$Ip8uSK`M)@2cEb5q{hedm6^|~)`cTSN3XVYeKHzN8#7U7h}HTmBxH#k5t65X zG#C~&uv!ECSi^qMg3o7vM{Ea-h{M)l@74YE%bYf5*Z$YxN@kc3?KR6(R-;{+nbo8V z4(Vp!z-nC>d;LM1nd?L_ztl27wpw?VSmweme*B18O}ZeTn^6yJ*x01K6YxAzMI!A5 zOet`dR3H$U07uUHjmuOH8~}j~kp*N8deGVl*m`ApR&o)`Vy_yKt~rv%0YI@Z+0-}( zm(R*#VHwbgVp&gNSGZIwn&~Qc&N#NWuQH1gts%ZFjYr{fo8a_DL$mYBo8dMSMRL&E z3E1og8fL2lm#xkG`PIvXB_bIJwp55(GKd9p$o*)yvFv)jl$2IfY&N77H+%&a6LaGW?Pjy4=Kd8f zKR5A?y#7WzOk|WwBFd+R+s=~@7uO%OSLCKXx`-S#Uh>P#YyxYkn3*awo`E09r0Ypo zaXr)u+uXGRIMA9@jDs67vyfbywf zI)L=7J#dzIGX;P+#on&G{Z>aR96rvOHe4($Ct)=SyUe6xpJ}#vidr)1DmKpGtH+_# z0C4?{b}=_h6XW8hDPM%ZDll~VLR$pFL0KkRECMPmQ*0DB>=qrwH`{G9#^Y_ zTp_?{V)~VekPWc9H^Zc>qC_44V)2qEnRDK1DoVu8z8oB>-6J(PkZD^O4ea&)f^pXJ z{%X$=y?j=#Sb>3x1xH6WDA@kJWR;nsOIKxHO4i;DXTyr>mI93shI`*uGFQ7SP#E3e&8*?oXV^v-bf zH_e7sxiH*hHh*~koBhdY$-7qER#7Ue%u0!8pJWUyzF;JH@Jfpu&4*ReRoTR>RT~b{ zo(f{w>Id^nEhQo#dqvAoFuQ@T$^PAxmw}H5jyNO)pZsKY^0O?PyYbWN_LsY1B!XBx zTkr1b)K|QE$HQ2}DYkY3o<~)=RgqxoiY{E0*=lZe;i}x03&RRKCItY&@Y8$+8H8eC zm?}sBD4hS~_bfN@d!wV_W7v zIKm5=*B_QfOxoEE`4L9M;S+EC&!trFAQBQ)B=~*DXUl%?`WMDrv(#VuV1eYg8(~aa)!|XZdI8|A|G7S!N;iSSKlDcrr8HrMLQP0nu zp<-@3yWwZ|$*;sJ7ELEMeOA5pTRRMs0l?nfL@FU)f`0Y(9~`vzLR&cic=Wf^tK=pC zNC$zah0>Fg>NE9&X;0CL{Y_H_BY0sBk0hlMK_oYbS2w=W=1Uc~6}<#urGGo}-o_T@ z!)mo)5E4{~Z~gvmHMfHU)!h+FAxp@&V7<$p#aZn+5quM^rhI02w8pm#5F+;f1wVlf z6RE43131*>!m@&fpTRJZ05m!-*t`NIu=5U}2k&0{tsP%K_ay+_e6u~g0#xn35+_}? z71>$6{>u)(o_}+{#{`f@Vam0-4AENBg)Qbr7nUrQ6T5q)_O7W`SEL;or6LGX)(p@f zm5kC>xlP(?c2T{g{kaVB@P4aNimXCQt0b&i7y!y?YdG;=kA8nxp-B(y!EW-67C9T9cd6OCeeN_fu<~5W-n1=63Iv zr_z7=cLlGxFZ|ZvVr9}FMi?h(avFbHjXo}Ck2L_?e7h4w0tJzy%ST1;V6$Qo5q46P+^18;mNgwb2-n|e`(eBTU0QAxIef5*2jw@Fkx-$?XU3E+N@bV`tDUV} z(w1z+1B7dqwe=}111uJX>LYt`smc0FR4h!D*$w9hPH%L^Rk>yIonmT6XD__{rOx=Y zBuA|3nmns6KF${xh8(z+6>F-RyA+5Z7Oh?&1JT%U)K)}%#XpngxXjaOMBQx8^8TNV z78frvy-fST>b~DP4El%BTG83iSW22tozdhKBHq>k8vPDSNQ#-MZCS}$YV8V_Q__(v zd#nnYjjeOAA8c+hb|r>@zru|#c2-*^T{_>8)O;uv2^k0>aePu%xea2;<}8a#jo=yL zjFn#D=K4KOMj~oSrf=}`;2g2x!v4La$}QD;1~xY(BB}7`mB1EDH$?_tb>ULf~vzwFjZ8h;Ol@WdcAmPe8;f zw{c6hcY{^*s?`q~Tkcz5>b&=tBdM?+bkOigaqp`=erC(eNrlDSGBMt9TN?{q5Fp3^ z{S@6nYY?Ozwd$Aj+V^%?fcD7`#{h8nYOAqwKYEa|9PjZv)0aHSguvAoCrA0*&8M4o zyjyXrRizvI5u(J8e>e^j*_?RRP*qT?Ba~uq#h|kre*8C+`Wbhobh)F8NBNz%yK)(P zLl|O}*)WwsC{!q{cBdaNR-fglB}Y$k0N@><5jP0|D%`Fg47wt2NoR;h+}8MXF!r2A z;YEeKuZdJ5LYY}MYH93&t$1!6j2HIvtRCPwA%h?#R=GvILeZ)V2E=9ZyQ!<{Yp=H# zqskhGfmrQV8wM6rG8sP3&kdL3OuuJV9lHxxnH7QH{hB`p3S_12=P=pp2p&`G%8ibT z!+Wja)12o7i?MF?1Kuc}y}yWB($@#g?EUrD5B~V1)en-6l%YU@^Re#ig=J=fNV1je z){m${(H;b|i;8_H0oNQi0iZnyr)OnVIEK=wzBMvH6^Z6H5s^^Hb^`#gb1h;Mt{?sL zam^+OIF><3WH@!LVSBUFoC{bVVE`Z{?%fSh08b0~#+75+)X-Sx#K{=%eyhh;UyIAC zcNi~5x@jDY zr5nZi;AR{~lJNorK#BR(#BIrZ6K@+=L*9FL5_Vb)4nj_BSg9Mx)d?OV^q!#Q!m`S# zIeD+Pe|&2i{+CoJ5C%6B4tRdLV(J&P1kS%bJv|G$gRZ!xL8s--{q%Mu2R}Y3+tJ;J zC;#^rwCEifsLZ+wQB-;c00O=FtG3zggWvq{_)m<<$McV!Gp`@LD^wujT*+v%cvzVv z3c7)62Qm>NNTa=E|GQexOEV{O&S?S?5Z^2RyHBG3bVG>uqWOWP`LKHH-`aoYPtO|> zoDe?1v7Vg}E7yv3QqO#-_1x{=k5>ts%`U`|-puS^+o`4R7$U>CKoCTN?RBmISVRPD z&+IIPu|xqEpXRN;+P&EWqN_Fik`L06436hB6SpN>@3Ff_HZ|lxg($-{ ze=AX;IQt;GS`n?ZZ3qZuW}sHE@){#YfH*!baAmg++JaG6hdgdXYe+BL3nJ&DmIOpy zI9pK=i+BIk=p|JGD6xMS<})*2_Z=oLyIJ)MC32Xw)brXvYk(Z&bJv=?WUxjf5)w^G z`uW3#q_gE^KW7K`wp_hOd#@*+ElW_$%;)$sWd&VI(NdWOQ^LI1d$*|WoDRL z#0qzn3X?h34d7#cRbh4IghUmHhkrNe?1jb5px-68 zZw}l+kfYsO3BoeFiARPgNRn4RMlHpJdj3~yDCtO3kqSIrNV!f0cClE@XEQ|XzCIBa zY#nh3Aozd)T31SGGSaQmyZH6Xg%t|D@g;x@h!64hAmAtH;BM03vzI3YTbMgbx^$!C zJcy;UBxFrw(ak>KA2H63;{cyxZmn@D5UrgM&}Y9m>)SE1RAn}Z1ppBte+5=Vm2+3+ z7Ko%0NjKmj)8wqY^~J6~C=H3)R2~IIvGfuaM_gNyBLuAV&RDafmQdZQeh_L41@=uV za~lZ>m1DsNt*c=gL9sO=YAK_gROsuK-J8kYopf?iPEN{C{`KVN|6=&)uV?dfGauXG zsS&{{!tJ<7k^$a+vx5@J5f9i|?87(UQTt+zWO!1efN$Y$>R*o=qPXgYc$Z1t5_zjI7Ak!K7MA@eT)xiu~3wmVSmzLXNm zg3gc4WMr>eU0Or43;pcfe4_)o`GxkwA5B(w*qW6F353yHF@x2N(Xf) zQV@%{tGaukkQjEPP~I4bInqUDap}%eGt0=QhYA7UU~*apv0y_h4t+a+KfiofHb*S4 zcvE@Ik|%h6bz180sRq5e{}20uCDVXHpeZf8!;td>aAzn?M7glFeh`bf?d(O2x$x=; zV!`L%(Q7S^M`WENk(Yv}{eXRW*?Z{ty*Ua%o}DfX0_1b8l#mLA01+SpvzaBH%$lh4L3<-;h+)ak&{F#|g{~og*bQT1H5THvZaJkZ= zRCM~HENJpfJ4=W6TZqe6!D^>V`_cC&*~A>an)=*aM|_*EztLv8iV%>`jCcG+_K8PT zKZg8jY=>tJ#U1&>|NUg^WQ^VPxfEuJQ&mT4cz214OyO8m!i#6V@@O=X2-A}-aWEoS za}z5wYqk|PRP%IRP%71^26E>K05`wbiBehS&KqN|(2}7JIp%~4sZh^slL*G982l&! zfzhtaEFbw?XP`j-uTlvW|4JB^vm_HyF051{o9K&2dH-58A63losxr%AtWu)Ut}5&* za(ewin{9egVA>C*!eU`s{b2Z{@G>Z-kZgmnZhWDwLcw%4tTEX}>v7`??JyC#bmiRC z%_^D7?cGY8CK-rlA7lWqe@PvYDd*0B9YAO?qs5H?rET7Meohd|0uG z8}9%Bu(;G0pXNuewWc-I*=l0MxqlRK9WXjB0X8jT5H{UC?tHl`BzOoOK?o@3mg!g4 zkQYbSTCFe^)>075|M!1-LXJ%7mV}xbbKy`zYp9V7H!6VbV7go?F}(xV)U^5m07@me zfv;irqvHMjth|^k9?kM&fy%lH0An@4d@nCAp0`A`%_==LwkY*f+f3Wc*xc9x04CW( z01Q>zIRg*=CQPN7e%ZA@)h1gM=NFTok7gfCvq$sdSzcaLdTMPUWDtiv=PK(;=d^W| zs=6Cn>t{YSqo;*l;UcAd4%b8LM=y;?&21W@MWVf{HUJ=U04rX5D6m{uMm(3GA%alo z994zW&%>c`sp%sE8RGm>@83!G@1}f4b1LrDW`@NnTn)3mRNRt{(c5BFu@-yF7=#+t zOw4)51ox}#6C%V#U$GqVqBnqEout0-cc+A zK}7jX`&mn!EHpkT`4-PFbyc`VnaEF&5Z>`5pIZjpfuPEGK1}nG<_ur?swB564}&jV47G%u>c^H-$R9{|FQue5_m z%+B>^K6*RXW2W#sN1yy)vgKOsg_Eb%?QeAWV7;1ZLhJLqn{Re_%k|<@38r*jj3a!I zKxa2Hl_#qvT@^$!pBnW1M5`h(dQxy3%;Hccy=D{5Lk_+sN(oc>ckb?oD3G7K!&h3D z&o*JlFp-^uNGiPibn`#0Ivn#SFEdxad#zD2WGcsNohA+~%MLRM` z1a|=-Hm%BEEOtA%m!|z-wGvyRhqcg>dk{q2y%|5B#z599e_?WNRu4pGMVQ)a>8kGg z&EMX;%4_?49o%32hkXE8)xEL>B=5Hy*=oPy4{pO55djcQwdt3%Wuso_WCdLjcU6^p zgJAEAPmJS$RQTXGc7?#v<9z2pwYxG-#np_m8*jB2W6faq^sEeeTUJQg3wRFaoToRk zj*kaCVOPiyyR5k|d=;IA{JNZ@Y;6Aee|h%)zr1{zN4>KjHbmic;wuaq%)AYKG(h(b~88;mX3#le>qZ3bAn;MS$Kx#821Z{j|&s`~I-QB^Srj z^HM0B4=bis^F9jz%wL!fwXK|rMMG+1PLo*a5^jI18^jV3RDdR<>uQb=>`~}2!ACBp^!MZ z89PTJz}ZE$e>af|ZRPku)}@nmEQ1O}5DB2=k$mkzTLtJWwR%cLB8-JDT-s5`@6PIo zZW3ZU1?$@DEfjtfe8~oIrE8zPm0z~z%-xBl?X&cM6x6V z{@uSg+g|0jC8Kpfph6ryDOL+ja%|t@nNzxSVJv3D>iUCr?=YI2l}vHcr41rc<<<+U zjbqc_$yvFvx>juw?ti1NA~C(t%?Y9l$CV97f+k&6UYg-Y`C_O$yAc3XneFTb&JY2t z<~&dn`^%+<1E#4q%k@PbC5|TzBqegj90LbJ!qcBE8Cdq@%K)HFHlBZSIr}iLM#dJ_ zRX`$D*XH@j3wFJt8t3J(G}BT~D?P3ByfO>tv~wDOOz%|Peb&91sX&x@4(UgW;%ujV zKL|SKlb;VK?~UgV=lQd&yeRZUn}s%+v8AzPW#)_gq{@ruDNvsGQ)YHCG1p#iF^3l% z$Uv~_%8_Sqb2+u4<8a!;(@VGt0TE6=T0jkh^5Iy^pQ&NpGGl`4`(m;UXD4Xjsa8Lz zGP`#xsS4ZL2^d}}W`>y*n@hb0EVvYAvrgV}7nc$ck4@?W{2Oo5%UzcR+^b zXBq&$^&ejQ^oP@}Ob`wVkaA0J&4`sQUGpGRg=NU_*4y2)53*N&y&tBsoZG#-=_;4= z>d)Yn7yx$eM%I!H1h3NB6?x;Uzp=w>_V&g|XxYv&tQl{gsH4ByD%PJA+*t&zj!fgHx5a&7zH-nsYNNZ-BLm zsaac_b}^aPkTVpu6aeh9y0b3Q%DD+6!Nxc|BV<6|5%@$SO}aEb8;uCa(-Z(8N+mhq z&H@mv_KscU-12;sz5Hqf0F0(El0y163J9XMOnXX5noWFWXE7qvMRIcPSbAeCEt)pBlYf|cWUG1{#%cFB=5j;HKF%xV=9v-9fWVct88 z5aHsZVm`JP&&+hC*Fu0*=W;)L5%B6a`^C&S2d!Qp1Ulo`eUlt9+xG5CzDAilM#QqY zYp7`TeFdGnM}IT@$^UWwl27Qp@ARAnK;Zeq(HB}_B!s}Ku;<4n-BVgGCHhiAcOYAR z#X&R8gv~jSQm7DvScHizGt13(J~0P(6AWNJD-KmMD1_S6gx+cUB%hBeCjJ4z#iP95dMIuy6^dzN5J+|9il8Eld$M;B z`eWYF@JYe`6rDe>adjNe5?LIuKE=pID9{fK#j%v^PrINm5sB_gu5mMI)( ztngycg|pU$iBtgwp}-ov5V9UIF_3XDVaN0^m9PH8J`>O`KFR^$#+TZ0OR7*j`Pu9x zkDoBYI1yotN?{OU1Lbgxz~De0+z9%+>SZ`wbrD9*G_RI-VZ&s+{nc)m2pNcG%ysc; zdHL7?z^ymiD3H;j&TdE!c5fwRW`kJDKurNZacMlx*D zqln=u@48YqYz!?41yx~9X#sGRSJE84LVY$gh9O!M!w0BrEJVNic}z#ix1N3AoN<#p^0-n17nJ z9kQTUd}#1d+(Qha4wIF{!t77aYtF}q{3pR z0oK~cCUp2kN|1UJ^F(S|?scn&HEYlSfX%IT_GNi#s`dVpnT#CT)!7T%gV1U!*v$uk zXUk0>??x*Ejpw>0ZaKIUC^Eha33>X(M!C}! zW8?Ntz>>+?Mb#bz#(0;IhU#18&Kegbg6&bb(ZV_{VbzYX=@sL)>h6aP<4i>|9Vm#F zlS1ah^4!aB-H6uG=?A*C6FmLt@Hw7*001BWNklQBY%Id1EL%4SDdt06lgeE&H|a_k(bgEgpeym)k3j%7zL4N=;|BX5Dr{QI?7Z&7C8t70^Ip}7ZFB}ivG0-5%a0(9)>_rK1Xu( z`uBFmk4pgP97IB3m09O#G4=*ntLlfHoALZY-*~IdVC#n3akWX|AJ#4{I~PC{$P7m! z(4}?8r-aWgH3010PE;gNU^cA)AV_4~QQ5?_2LZQLLi!s~WOnKHOduLjVIbcAg98-` z0#b>%{Ze4NSRWUXj&-hBSN7hia4ZwQ+ zw|D&fMj}s+jdnpIIX~`Y_C^(p-5aq~cm+`<)($#HuJk!#d$&^G1>jm$$n#aZG#y&b zx0c`D`R980(7<}!#o&@Ty=9o$cK=~U#6DL4Yp8p@{{0PcT#hj-NZ>2pbuH{Nc`Kp-Hy++02_wu&4V zV;!c7>cCdcZF7c-g$-I#hS(YergBy0xIjXIK_r??XUD6%F1=JLIEqmh&hNC2n0;m| za@P0D&QSJz`rF_}%w-ajjFwXq@|(%+x4KxDTg)x+_6QP%fW=71?w+$21tw|Q>Gs0b za_#bzof*DYQ(T&y9IKrd`mH>b){@U6=Fag>VzlcWMBeMLP8lAbRYIZDG#h#)yR)9h zZEK_YYT?2}TJ4Bf<^ra4-MuhwsbXQ6Ak6R+lftUPGNp?M{M!+bBPo%!x>aGVA)VXK zPRN&n3x;xGR3M1J5!u@Co-M;R2(Upcf>^2m`8A_dK%HOA<_Tec`ywanX=0`#qn881 zjmC$+NIADE68!DNU;nQsC+{xejyivs4Nuo7S8k;|U1> zfC%x-VHs7 zWZrrnAd)7M=D&4MF&Xx-p*=pBUXWTPjrqreY{*)AediP zWoB6p9Jhm{qpp?<>{G*aOq5E7w3*EgKs(psw5wYEpw9aBe)Ya!wjMlEEwOq;@!Dd? zZo|@30V)(xOPa!!6DuUfZMAbfW=iL5sKZ!e2#nIHpbeiWwYD4c+Q{v(o-i zBo$82%343@Wdehnu@F$^Hfl)}`0S$vSI^F|d6|(4Wq?&~Q6V6f3qt@>q6$R8LD#Rv zVImQc9DVxE^zPSsQsVi;oWE~pFGLAJB%c0!{!%PrL_`cCY;{F9F*z-df045!cKXaV^K%(^H1PTt z+RjpxNFx8|*;r>QOei6svm2J{4LO5QaVmfIXT#?iU_qUQ#QfW(?unZAk7Y3k07414 zGV$=Mt0S8RreW=_wushH`TPN6L!4ZU^z50o6*Tq0BBSfheR;_};sn1d%Y>EhdJ~P7WO4!!JmrGZZC4C?p`Ekcd!VXAp4m@spp< zT3xYwsIEPTT7#fkSRPJ1`r%|%JB$i@hmoj@Y!+YFS#Qe?aQ9|1e4K|ZxwSxyIhO^|A2z!pvbl95Sv~&6Tst~^BaK?pS<<=f?ngiP(}mnQS`JUJDk3MHh$;Br+;!b{t25~`2+D4 zefS$&z$|U@th~s|;i5QOlxJl%Srn&Pc_DTeBK`>KB!u~;&L=dQeK4LsoM%rfyV&hM z5F)sof5eKy$>Px>KON0Kd~*I*XXBrqjel}6{e{)PG>vg~QB|2`14QpX#eUdj_1j|Yq1WU0QT>s@BaDh*?U#*DB{t#v!s+Kk&=%%aPy0bu`Tdk2T-?X#Di{b zqVlPhwG5mAEFhSVDt0Pi$%6{TYE;?Q(1xHb`N7nsW39*JNs-pSxpOOKwt_$?*YSwA z|D6NI!S8*ym-Yi+hB?Y6`r%(~itq0KMjsHyCne&N6i_aVuITPJx})QAHnyWvldlVN z`iGGaNDjs)TL3Hoxc9Ywxv-}64rOd5cKB+Gcir7v2_gisV8h^ivb|g0zn3~q>0S`F zq^X=xNDg#;SeweVuZOxMXJPktTrJG?H#_6wqR1S4*3|0mS9-c|%jq5Z?wablBJQZT zt!AT&jBD=(Y0qP|`NSk0m2^~@+5WX?c2V)%G)RODkQ|hAV+!8JJE}PoP&`d{W zc4-$=*F+Mn`MRRtDj6V%d&v2BtNXz8Y|EMTIT~Q`BePo5cCLp_2|IiKQF72IiMl z-42k|ZgKfs=&ijIz{>pFtvOW@v&MYhuLS_ml~Vz-S0fFvl|MDJQJXm%9+;l8dd=;Zku&(d6vj0Pcbz= z`@b$uezH(8KKSmy8H(GAS>jf^+h6VmkqBae$W&?)0y%ctYC325jvFLLyHXxR2exoAB;` z^lD2;1ZeErp)xx$1L7Cei@^q~YTZh9} zTE)yqR1$Wsa^TP)I&c-X6F+-yR@TI zKn_l8 zH$Wn&N;f()S)&odT885YYnwT~N~Us`kBj&Ibae54{>xIwH~vwHC>I71<|Ey|78MJF zwZm$eS+-SXq@#ZnWn+T?R#W#N>>WnV(UYIe_HHFYU>J#fVg@(j=~-3G3==k4^mO%{ z4no21=InQK@hBGxg+PX1neb~0$4W*Xw2qz@K_r|76^b&my`!i-2-uq48oE3#x`(mR zPKEgR$J0(v1|ddW$u#C566L~fj9x_mhp(hrUF9_1H>=w>n|*ShdDUZrXVlHM8OE|$ z*sIVF`-$>!{^`%>K_XNrqEtTl#k^j^z#L&7vM~#NF|Mtkw?Rdn-LSpmfr+AFp4QD0 zLtrvML>$}+TRR~`X-xQUUP_3~7sq;1{Yyv^YMC3u!NtsQ^(hrT{^<+=&|RnDjZ)9X z^G}YS{oVN4>5=@-?StO{fV1&Ww{!*nV!C(? z0CI4~k{krcCMHT`J|XAKBztr@|9GA~eR}>^c{!9A@MjoK-#fkh@w4F%v+`V{ya#~nF(ShNmynCETy!XE*@?cAN}=sbZW}ned%}i$ie8$-2G11S{gko2e;zU z)57R2YS~RL#`W5#-$(r{Q!-c#xPK?%=!`P6d$&@4PP2)24!Q>s3dkn90W7%F%cq8j z7DGM$qH_Q_vPAOGF-F0~vBB!nz?;k+?iAR?pB|U+-*( zS`ys39*>TT#id^Li&zfYB^!ERHTP+!Pu`g=&NLuMg;IgFROD1-ROGZuuUq8=@GPfx z>VZJv&h@2z_{}eN0N~S~Y|0uwUjr=GO|PE#K_Z&?QD+JNf*l^T*?w)6@=8w? z30;uq2$z07*VzjZ!BkW%tWPVF$UZr2)G*;@q8cfG(-(QJx6dRmAob=LosIBuRt$plRDkyGSgOLiP? zvW8dN8LXGLv((uO!$e4hzRj^@jq}eGK`}Qqam;@graoEiin(d^18X=F&~ZweE?s*N zR)ymvJ%&57sWugv%2k=wl{J-1+R7T&h&NT>58pDg*0>-NVJw$J4o3{4p+KsYgQg-= zQql|9v~dY#wv-6O|KHk`^hkCb=ZMIBYwf*GcMp3O&XD3xN}_04G9*BNH$m1}fB|28 z(#QABrkCojs;+ulW`+-u?{!sm^@yZd zn8Qp>qq^!E=4XsyQ@U1PPtPi5 zCe^{TtBLUO&(GJlwLm{hUT(decs{K3#V@TXO(zd>vCt>N>9DNr+u2(F@jssp_Tu^C z?77!E%?b!Y?DR7zVORov3~)b@8` zBDhx@E^sXwVCRMO01&pxOkJapl3Sx7T+C2R?a%-1_&@*Q@%W$=4qb06l$=fvP6Ko{ z!rHYNMY3y3$KE;BjSdT{Lk67#SMj{ZZ8K!>LD$Bk>|*{mZy~w)VnUjbuyNBcm75QD zH}-TlqK+SAJ`$cU{NYqU)^d<2RA36HG{$WulcF-S zQA??Sl*TY7;dzNSq3q{!<~n;p)KW4aRS|vuo7+fO=I+tG2>|TA($*0Lk+Kyx8t+f# zLBa3-87uK>i220S;?#?l=`(+@cJF(~n>SOXDTvj3|LT{GQr_)i|Fbb$5EbpsH+ujO z#L5|`0wjWBX6KoPh|u4O%EGM>p*&OK=Xvk!y^UcpC6H?hp`7^A@SDQU&*+*xD4RE_c4cUQ7z=rp_Ce6(vXw4CFlqm{zp<9uoKx^XiJVkJlGwdd1$FT#s+=0+-V6c+doBF_cOLqsPHk6gzIO1xOGj3JD}{ zR8QaXN3<&dAS+G|PT&3T@cU`Bx$*_G(=I98dG*81*LzXWTdMHZzjRVmqpTce#Yt8U z0f0I`1%R|0Afb*ZNND!BCqFzZj*myb$jVbhw5|dGt)j|Iw+63m4_*(0P8w}?(p>=H z+1e-AKBot{bC6985;S-{Dp2YoBY3$;y?iBkflMkA!pTuNykAV`#VP2ih*j=P>70Y! zb+yFuW(PX-YCFMpiBNPm&T*Cdd-PHq`+~NJL8ueLNny+5r)85GcDWz8cBf@44rAp% zDKF41laB6gMeMcb&RHJSJe{rEsl>k^;qtBh(H{& z%iJl*zi@d8OS5FipwK@czFq>j$rYwv+aC zm052;>td5TLge0^oypC#|)h zx&O+%Gh0QPxck+C9Lh;w1A;TG6c#fxdR!sG>5<)kv-7_{m@*3~7`JYvNchu#8J&;Z zvwZ_z{>nNMG>)ipFgA<{XE{oB($#fTE~GszG_h=Kwr(flO3@yKa^^e7QN5K+>4qO< zT4NAk7$THVp4suk^2yKh$w>*oIwDe#_JeX}monL3{>pk)S}7j#arG=F&RnblH~O85 zh3{6KyBblVl?V9cgb)O{{ri2XG(x@5SKGsKzx=IMS#ncuvD{&cB?#j%{ zg=JtOeDcfLN(w&(7_^kYOp|FmMnn?}5N9`WToqm|nmK#J-&`=HfEonH#!962Hz|TP`B% zNO{jS2fEs|#u{U-vCg>)C(Y>rp0@#I=1j@fID7S$;Y$QtLK$L-OOh~1#IegcuR{zHRl8Zi-G0QcALq7?eg+GFx^QoMGo6?5Srj+D12Hji|DG zIlO%6=uYG&xzrJ&rcBsFh*01UQh6+M-(x=ch-Wq;~mRP>88ik zU^iM?(M9Gs@{~eRDe9MGH0K-De-WPo`@Op6I0dB+*`L(04Qhn{*Olg@%N7&{p6e(X6Nqc zvDtg6V-2T0EfUe=2ico{vXxJ5+SOi#tQjornHjJeey6T zB?Aq=45ZT40qOt|aW<*|A#Q64B`sz)h)7c5h=>8QapfwuC3n^XBp5v@)^8;8wyovi z!#s#che!%fe_Mn-k^xQ-``cBs{%+n?(P5s6J$cQZUa$W7@~KuVKyFdbG6`yCO|UXXOOt#~;Z zgrC(UH*+WHx20#eI1p>snE4Piz>BtAATJq}7c(nfvr_cW&h2dCc#%`!EEiX#IElBb z^Z-FjWwvB(6pGRiW4E1aaeU+E{`5 zOe-;NM+DUPsVo&0ktsQdlo+*c>?fo!pIBi=1d;cx1cdWpr6W2&DG^aeG}w)-SG}W`oM(3>3~#7 zQK|@G_^3GfFeB|D%h6#OwUjd)rmD)FggJ&C)!&x=r5NBB-#c0Q?1Q~TJ|+OrynW2v zrCq2cRl0m)P+<_07^appn>LB^cma4_Mx!o2|7?Ga=I15z zq{^KRX?9kX6RXF647sOQOKzYLRsdjDtTwg$%|C6v`;Tv&+`qPQ_J><{pVK!F7GTFa zQ|C-&&hu&n0BU#G4CnpU0GxcVyfc|O&}kB`8Cw8AR-Qh;`=_73`|Y>x{N<}R|NNcL z{M8%5-)!Z7{c*QXmAmO_B?7lu-K}|Nx_T8&j?0JlW~Yw|0Xya)Ctf@Ng-I>C7&~Ps zc^*-p4?|Fzx*MyG0QA1jVM~!l9Z}rY2;Qi*s6$|$G27PxhBd0|C$yug$pF3l3tPQF zqEWqA8-X1++Kub4bi6kfdtaVW9qX}mGZngue6;gn<@JNj;x|kLVT?!^#7dZk0vSll zIyg){E>{tA8W=IulUB$CVq zkF$pFe6f!N#}D%1qJM~px!P-?*g=?T#o9>w!C)u$=>+ImnQPZ$L>xZI0ATC+mhfog z&Msxc!V!HV-i~%u000ThNkl2bVBqFAQ|XxOwyPpiNgb zgqNS(zMC>!#ELb;MP{~(O_>-=&p-A**AZ=m3Q&THR!l3sh7b^;w-?1-efYt0Bs~(u zDRtLWr%w${xHVY#HieBYhY})2bM85NFSWy1E%VwW?Kl6_%Ixiz(<-yfa5Tqs3u0Bz z9r8%Bf4$>p zJPgh_L?n$?T2X{5bB>*}R+?DnT&X^6)~(P`Bw&#gu3iJ4{0rbN)+X0penR^|;JBlk zz>NmDv6Y*im6tcK&%iZK@_$U};*J(htB*#FsWk{1YbLn|O^ylyo2F-#2uP72YWd(o zQ#fW8hyLu`%J4=h`40WJQ_L(9L@jM?ZDj@EEXQpvlKFX7tw0S3DEPQg6YQFVW zPX#o5TsXsPdogK5L{oW&d4o7aZ3PH%ih~W+UJKW@b*n=`i14pP zWgx4$Sz}t?$QT9_(u8e`j2o*`%wh(&-RS9{FQ$`%ap4G<<|N zSrvSGWE+j-&I>ISP?bBccQbtUxOj3e8$GQ^VGxoC(8MZ2WP>u}GSvk)d+SyjCR(bZ zhL_m!QOXPmlaq3=6ETChXq&?65aYHIY)k3oWV(idb#Yfv{wT~(tu6h2D#rH7Pp6N6 zGA(l+5AE@RnU39;|6)t1ZSob{lG$>1Gb9D=wa_2pAo4D-hE3%SL2d0%A+1`o50^+o zQt^<&Vrqoet|RI^7aTsSdi$aHHv@P)bmh1sZYxtc?;&bnZzya9IJrd`|jb5FLXZz=&EwVr)K!n%p=ytxt*Pw!}s%t_hyIh z=ZkC$VD>Jvt`ao`0Kl!cdiQ@c+I^`l*>fsXTQ}43qe|TRleTL0)%NqLjwlXx_!bBx)?JOTZ$kSesjf@VF9k1=h!$*03ZluA(TGTclZr$As zefSrHt9aduGW`FZ9TZWkfo80X_^jpAgFNnN0MHRR2T@D)cVo$YW9Fj|W?`hN(ghKT zIdRaX?p74Fv<^^5RLtyUP2Avmj0h5-v3WCzmYkQViCbFQzxk#G5p_rhznlVyXxe#LO|6EC*7g$lE#krH%tC2o zjWd;I17dujLOOd|;Pi`F zw6AOc25(;VU*n(YU;N!G#?A_RqSk&GzW(0=RPBF#l#N1PuDOa(>5bp8*@DU2Nmon0 z0U(%Fc7k_zzwzAGm-?-n05HpsYz^bwdA9n|ho)-JBcG+EotCA+6 zEXi_8yE-57@VM~H!!{Ldli6E3&&Bj)xSnWzK!MiJcR+6rE4w9~}e+3IAaDJ3s70x;EVc~|Q{*kzbdG76O zR7q_r{AlmMsu2}!-b`%inAsH83yK*8Dsskqlr+VI)SR|*-pSN4;sV92*(XGZfI&ZS?+r}Jvr#2iW5IaAfwN#O7nzl&YkXKV?%>XGHFF?p zBj(0|hzQ%heuM27TBA!WjA)?h3f^lvOzFz0*?Fx648_#d?Vppi(h#`b{?^X$VaDX6 zY#U!ZYxw9_%fzbi!=Fu-PJ|EsXZG;ktku(`P-d=|m&g8V z-Lt2KK>rdlBT2;Ku6XU$mQZF)vKK%f_w_CkKLTdgSfvP0>E@wl`~frR>ZkrI9UPPDqpvLP}F2Pyy{ZV@v~7Zn=|O4z!< zX#OojH3k5;kTY|YebQ=H(RzS{;i6@@(li^Hr7_0F&1C>99Rxv_`qyF|5NRwjyP|am z7DHG7*t(mBu^L}tw4^kq9d+lOcDqM$g7f}X;625VSw;dp{~52{Z3Dn?(Q-s~tC@Xj z62kU+DA~}>R}c-9WSz@EeRA}XjGK2~Y5~CMZ;M4+7^o^fAKBT&2@PU=SY6gX$|4bW zmygcC3cA$l2ie3#EoBN@+x`Mu9z88cVR3F$fYnvO=qx8HH}$Y7-1up^vMAN^I+mlB z&d!W;3h4Gb;p`^Kz>nXLu+PNmhY3TGcASdC7Y60;?6SXwhe+|#eBB5Ua=6wN|JDa=PZB`P2o)8ikXoME@OUM zu|#7ljXEL~kaq=P=x&DAiY`jJOT&(%mXaY^a~Z=_vUe|BhJ%=7Zp{Eer2L}wpc}Je z^-ulB+?l6dZrn(swmLs4g$MnAVd4I_sXRaY00000NkvXXu0mjfQCMz$ literal 0 HcmV?d00001 diff --git a/tutorials/files/blender_procedural_datasets/rock.blend b/tutorials/files/blender_procedural_datasets/rock.blend new file mode 100644 index 0000000000000000000000000000000000000000..afcf231c2397744fafbaf03a76cfbfd952a101c2 GIT binary patch literal 1439687 zcmeEv31D4So%c;k;ZjjRSt^S>y1wp7(WUT&bjBmo&W!T{%5(%YueDdsik%6!W*h9mu!`6%5j`?)+R4}={Cv8QDM#(ByH6%$eSd88f`u^QyedE}!AO?sc#85{ZO&*=3jIow$x`NO8hfa9(oBCEmpsUpy`+ z{HL|G)vK?s_nMoVz2(c7dy5w@9@SY{S?S?iY*Lo(Yop~e9{6+T&Q(5%bS&vFTC~X9 zy5m}JOt9zJo=MHh|B37-dVoJ*H3^;WD{ z;VoOXOvzSVUG3q79&o*?s!I6>?1=m_fk%Cnu`}>dUTRK7N7^}O&Kxf(C(>X(c#U<( zJDoLama;!=5%k;9=Apw~U5C8Z)J9*QH8nL#pXhT+Z=yfwY~jL%O25!2>Yx+Gg0W5! zXW)N_q857I{mOv%Q5itG&64D!pXQ8gFjp5^w&> zT5s+w9TyQBC(4PwhdwbL_FuND#hbsd(gP3G4@BqmclaGnl%b1Y3_$qNEYrKYr234+KwbEO)a;3MrYLT~iO@mjpa-c{8PcW>V7G5(koVCydR5zBiusZ(YCHTT;DT^=0UsdWY^I1APE< z1C%i~Q=ajP|DX#VI57u6-(M-V#asY>pvn^a)i^MJp0{BB9B<94h0;G}Pe}U(Z5by| zeUC@~NB11y1F_w4#5XFA3)!)UAO z4^Bq=qs@pttHr*Ue_+mmxd-9_=OC(1uAz*%%tD#FE~;MYRmnJy`3hn^uA|?mdb!3t zVh85CC}ZA;G)~_<7C0xf{e!lL4LL8xIt68%RaKQ@OBvVA{1|mh#0QRrZH@(xlhyth z12E^uTn}@8%zNs*d23!?)AX_81Hey2e78cm{2L}d=>X)EU&Iyd@BBj>~q?&0sTVt3DGxnK2c7r z|7rhi+qQW-cI@!?d@%pR8UXt}7zdiLx3gxo*C_ivH4+C_&QE%a=IFKSSoXo=Nozd& zKlc8oUp~`IOrNFh10cP8#%%AhgxnLjETOI^rq4F@GjrDj2C#A0c!lubhr#&2X3ZMa z$1$fvEI{AKoEZ}IAl-uz`P-t<}XykzAXZ~oF|buL)3&YQEa##8B{ zmEP6t@?76vM2gF`Zi+x%(+#%UhF+Xd;qqiFCafd zXv|Djie2Zc6W0(6;17y6{6=u$XW(=Bj5*>b(a#dV{%AAjf3PcU%Q+0}hHH%NNC^X* z!}h#}*bdvn?np6a02XlIGZAcDNQUvW|7B+EPsls~c1ftQf4bORkMEcRV2Q$I`j4`6`<8q6aN_W58Q_UC;E+6*>Ce}(;2pPn;Y_4(QG z6SZ`BzuDtR}5BL3QWuA{YKvR9KH@~V{_3xzI z$D6%K;**RQFW2*Av_IO66R{d&KGy$;>3Yvc#&|QYM~p{2;8=h-!92zYjQxlq92*cn zSdZ(#=UiZ-`p?N|fAoFW?y9S%pZ?U9CLJv;@!p$@6XE3-eB} z{h^c5{^$p2H|&h~j5y7?ALoSd1&j%($GE^et^*b)@GvHz4%dMj*2gCDwUg2Q==(Tn z%b@*WZ7%>sHbvL%&jNt`Vag6QF@+gBoK^|NG7H*2BSTwAaD0p^G59>g6?F<9wOh&7729D{9n7lTfb?$8vjQ#_k%7ca{Pz>-~+9*7JI8D z=3^fK{(ds`d-@RUzf|67!E;U+|M3na*21G1`++-=?a%(dW!4hq19-O&YklhEWJ+QG zEnBvzy$Z%|q@4dC4&a1Oz&9`#F6G3&$3&g~tC%P4Zj$)FTITzBz7KO=_yFz;oox2U zJ{4?g_j%YI_r`GYJ_+C7EtXDX`@_EQ0i?5L%ClgSpCjV|_61HR+fxsGR*m+D-4PRT zqR--?QI9JsyRQGw8 zRLcIpyaSADsIOTr&jQG`rAy@AP?fA3s^@vjm(EvZpM={#@sN||2>+$`ZU5q%4G zMC`*J1??Y9F(;t?@w{v)-($eoKauTEzo$Ls%$X_o{TIrf&m!6DpReBcS}Hb#ZE+1J z?(@TzxW~U*-Uow?bvj?A$ivP^*Q~-bCFdV(+<&)qWqwxHa+|*ebcdvsCs& za1Zc!+h@G_!~XdG0``AkcaHPe1B-iN&vPR8f5iUTV*e#GlU~!TMc%r_%e{tGYt%dk zad4r0vt!Xbd9GLXZ^v8z$D2Ovk9jZFz!>ZCOg!vY${arm2J7gF-2c&L^#2vI|2s$W zu)!>o9&dXbYyQv$Vn6&IJ`iS8)ZzYi@B~g6EUy7)BCr2of5?h9vt4Wx+lw;x1aUGC zc$5Ky6wd}BcH+b}z)_E+ixk(;FF5Z!)^?8K2R&eYhyEIrH<(Ae0EcmcC;TP|6PCwX z8YkM!6l)FSLGO5+__h@ILjL8l-@ka4?0rf55Cf4eoH@sUza*nZ&JdZ z$Tlt{JNg1**jS(NjbHrY7v4)Ry)>cDfq?;KYs93L%NMBiT4TN3`&}d7f04D?qJ?wR zT5Z03?_+Lqmiq1op7X|<4Rttiy;80%khLJzgA;XaU&!vPgZ*JE#6I*-^hwNp*Hl&& zjR}SNKjOr%e)TJFq8&HfaD$%jNxQ47^!MHH+&0$k^XAT0c7?t1-M7lcq8G`dE-5yz zk}~r1Rh_*1A$T}vPtd&`+PF~4{*UIn}6850Sxlk_XDin6V&@T*aO5q5n=&i0ALI0dLq`b z|6?x9eLvV8dECP<)W-|ejaC1L%|G|K&#CXUDqj@8#It%2KKNiPKY;zwX2gH&&((@; zn;Wa-8NkId9?bU|Y8QL0O;z5y7I}tC_VQrkrh0isOiq+n%YJaZz_c{tnmj9R_I|N9 zJQ3|%OeVYkBMxBS2PxM#abiH+{ttWa>gZ7SBjJBbR@NTet_f_8iLcG9rE|GWb@E#_`>6Xh(!a4^zg*%v`aWU=;ydmIAoe2$U@nMz0;sE&{*P;@ z!#yJ22f|zua7$&(04atL0e&b;|cQk-|6T%9`baAN)`(`=iY`VbgUjRo+^O_lW6rs~35x)+G|# ztJFAvn4gkyV6n{cFfQO+EAX&sE5?jEJq`dKu&qtb=g0_^(Ep1 zI9IG#={@tzGqLQ?cH>?jY_IO|iS5xhVN=+-M%IS4at&iV`~?1idxQ!PJBxebgC*R&NC*#{*S#H&i&vIamIb(z+d9b|JTagu0`%a zY?ONuZSs9Kyo>P0H@;Do>l@^oOv~h1`^8n>z4zW%w(Ws{@t@CsWBrc%^t_h~`yp;4 zjw80i2XOx%^+XXZ%Osgk2Hmu@{KGk3Ni; zUnBh*^FOTja1Ag>0RtaFifbzb2IB~>;XA>gS1)5klh}T>z+?R9GbQkYHS!Dz_7AE5 zp!qRZO`YxY}@0Wrv2QP z4Z||tAH%!DD95os-aA^gO7@>*9Juz{cJEDZx>ojkQr?6z2E=- z_py8+xc=9+*U$1{9f$QF#&fLckz(GCevWYhdF%-wW?-yGU&eL#4eGE@z`hPzz(*Ny z@FT1TMr*6_z{gmKc|PpL)PA-Xu^jtl!PACe8PELy9)4A>{b5rz2a!F9RdQZ^^>&#H z?C>z}TPe@ytXeJ4mDQ{g+Oxf%|NQ5pvOn65n2o-!;e%N^f~!N(c@ zVNlHfYh(?I6Kg@t0Wj}FzpoJ=SSdbGwPdM>y@EJLu>WK47xsqT8S`OZl;H#D>#*Ch z>iO!#_>U9)d7<=qjQ?s}kaYv*fruxd2OP``0Jlo~0x5kbj*Z3>2lj`p#`=sK|2N6A z=CFMO)}m`_)wy!DyiX=$|1x<`6FzYJ?RUg6y~5%85A9ZcT5JgWAP*lvUxgiUuLrh9 z97l}j*l;4>>kadxiPrybzWHW}^{dqU59|MHu6e!0f9wgZlf6Irokm&vKk&c`u`aEJe`aEopH2~%S`kH*hTlNCcmjR2|k2xXs1K=Mh14pe1q>NaPeIVeg zaYkZ`qPJ|~d{cCy_5Uw_`OB*Rb01*uzI|#fSS#~C*nX}&oA9F_{b)?=uh-~R+LmG) z*jUGIz4wRx9d++d)^e~d)(NmX_6cD3b(-h1EsUhnp|z1=(dm9Ka&yzm06 zW2fx@Xt$2bdVZ&EiM2j#tZfTh!e&S@uZN$&rda23ZK%d}u`T8e@D<$q!}=fN1z-t} zd&uyol`FLG9BVsA@xz*atmpoqhxz|=&pj90PUD66<~P4t{nk9}kNdsY>*4wxw!&Tx z`Y-x7*N2D=xQ5t|6ZdhHjZG|2&xMK4V66vV!QKGofS@;#-t`Of0lfP?UiSab|NPJK zGGlDI2M!!i@gMs?h~uy;`Yz|`==aDwaz>hK+;wh4Bn1;sZ{=VJ)G? z2=Nd46ZpW-5HG^)aJ;U;{@BaGJ)hM}Wlu}i-guW~QPm1>u6)h@Ak09yW@^Kj>&oZ?YDdF?d=}!E9{hK3b4nG z-+@~w?|@cS;(0Q8?n_R@D?C$%c!<4BvfS%UL$G!0R)qr?++V1w0Zvl*MI|jzI%c?yyv9e zaTNRFd3U_qgZAQCL!{Wh=5z4q3#i94@pv{0dE6`G`(A}o_!;^Z?wtS!C;A3;gFNag zm#*^GZ@pGzTC3WD`)_zZrV#DX)~#;de3Yt7L<2&`!L^1>ffwPTOO= z44%5bu;1iTzW>Ji0MH@mqRbOI01xT{@5Mp?z(t<#j{=4|gIxf+y_46mmi);Nm*)!3%tlr;MfOANSFL2fly@U+`oea^hNL z^-6E+>-VbPB7-l(2l1VSQh3CLS=qG3TesnAZ|lz8-m2Orr8~$2-e`Bw&KM^lH}3x- z&-;Lgi$OT#;S7a+$ zHxYhE=H(~@{0{vH_JQuPPr?)SL%c;jVk+!|eu5MBBOGjn{)TJoHf(O%a+>3uvo?9* zOSd`BstU)E|4t%Nwe(faf{OW)$C3H(mY;lF>fOiRH;gp%8(r45^7kBPl9Og6k|YF40p>Nur=QyMsVHLzo&;|xua_~F(~x<}&2jgxeoDODpoHty&? zu(9Jnsqp2%-CPc^1)I6~y8o-T$2-ZgTSff$!nO0jr|cSi_fN3a#MdeV~yk7)Dq<1(zva0 zi(Fv5I~*0i(;HO0$n0I77dJR>B%|%!=^Hn697*@_LYZl5Z=afnPBZDwE?v%;^r>!B zZf{g^Gqp>noX6_6ef~6O>N}@YR7{pQD}hXo3e)JJed}~PCco=n5#M>Fs{cUoWqR1e z!{LuD)9_YGJfN{kVcYHj;5%11@njh&A&pR_8 zk8s4x8a&d=;pNLoIO08T@JNq%OxZrd5ie={i1Y~WIOnM>@d!se`XT8N&pR_8k8s2z z9O<#_ovCx+my|61d!e!4Q6neesaM-B#3wxQhpm1?{gMvp5})wIpJw_Q=@Q@8H}MHi z{FK2bUCJGWPk7=VHu$7Vd)fLYf5H=g$l#MM@sgHaiBEXqKV|Sqmw2?Vtv|vOpY^0m z`NQy!3UJ26vlYhvjBBJr{n36=_5eJ5YrphX^t|)WmkU!bQe-?&=IQ4?dIsi$Ll?hE z#VhwZ-EWzu)^1brD!X2%3bBMgh&ec*&$A>Y{bi;-7diN+55Nq`b@EziVBAy~&!04F ztnW9f^z)~;=9P6J^6zyBo^reve?GrOaI=kmYQ|_($v81two6W%>Rj($q)ySJ=qu^~ zUFz6|0R_ZZX_l{hWZl__z&<(jk@E%zdA`(ki*edb@@?vG`# zAMHi^(PwB^g+KU>eESXlZGPEiVwFFvlxXbde4|O(&rkIn3n)4JeWc9iPr>il^2>-x8R`_W#s zANkU*x;&`+o#QmDdKmWdUfa-36Ud~Unoip`jY_CIH;OhIuL?0=x!Ge!5o5u63v zxQ(HtA>3E%{x<@Cloy7+sO{!{NcY2HBEXM3Jq_KW`qmbk}h5{VG z$C$%0hGUMZls_DcIA+;nr#*%Nk9K~ILA~ojx+t*Zkvu4bxF=GzX%#}Ls zGX=d;4z`(N4(W5uIZw2L69>l}^00kAk6**y7G1u-QK$5Imh+%T6oR_YzJ6z;pGNq+ zXiI6V(3q1)*XAnNX2kJz4-oepGv;hFG0UVjdb#DS@%7Y4O7!{P#q;@WR4z16uN$q-;p&LBt1HJE*Jn6qAfjLZX?k#%1v?aZ_<5154$&{Va&Xix4 z@S*&;j;36cN%eE#%69(V$ZNNE_o42df$jr~`qMq>&Vlyby@$&bb+q`>s#giiAt(QS z8|A0Gl%LYEU1KXhsh5+U6ABFZGg8BL0gAQ>BAhOT9UI#RdV72NkMs|u_qX?@_qHGG z>pht68|Y5=x2F&EAL>iDckjWq;@vG(q4mg=ylmc-k8p+L3(@hO_I-W5hYpf@>FKbM zk0~*u8zbM|p~+jHBGQDnE|4b@p{1l&-hWsjMo-t-ShM z$^*}X&X_pL^iC5;ndSjYA+y`;JDN0DAG9g*!8l6#QE`;}m}3=3DSxpzO1UUI;}F|v z$04>iq>r$wv@|b{I_1Y<6Gtisn;;t;PF>PKT4hmw=E989SM>Xl{2A;J}s zFGR<&<51Sf$CUC!$w#w%bK|J zRFB!0+pp7_N6h%vspF2jPp462p$m+$G^h}SbYACGXv8!~vL zm&40%AK{4il))oC;x)TJml=J|4um5f;Yg2V@5~%tQZBltUvR&@#*_(9f3xiZy#k-` z#P2frq)Wex!Y4fO?_@tUDgDT{FZmOm_*sKTx|H9xGw}&e{O1im=_ZX|M&T2l_{jsN zpBg%pdz!H$^-BJPC;m=@PrB4w6h7gJpE3BPOSz-)2~Yf^2A_0^Z~HCfCp__o4L<3T zZxlY^i9fAZ>yLDkM*oK+^hbE&rwl&nQvXr-geU%CgHO7YI|`rh#2+&Fq)YqR{gC=2 zJn^40_@qnuqwon&eAkR`q`TAT@2Lp=5uW%QA4!+}HwvHd#HW9gF69oxS9_;s9OmAs zyC;7L_C?QsOn$Yv^6Ac{&X*_SENs7B(g)!Ge;YzqW1lJ84Cg3n zMuf;Dd$Zo(Wf}=MK`LNBEL2w)O)ZH+1jo80hXj z(7wB)q(`qd`51|&(lADfGw_nH8(jUu)9eiS@TwB*Na}>C$evsJX0S)GNu~^FGc1v`@;1?Jy0*%L9G|+ z%O>dS<ntdeMhWeNBX-v%WmSjJ{ceej@V>NE<-QNLiBRBJX6CXWVmP5h%|FgxL&9S z>LqoD)(ic{Cgkho`t%XG2O)P($}|6!3N6uACYmn>^m0*%USzuD!{l=QrO1r?-2M-R z`3v6b z2kIqj##8Fcrt0gZuX|tj9=T7v=ScgFy?s4(s`(Vpm)Ezb6ZZ3X;x^7E&dH(5-u@?UcOaCFEV8-`N+I5 zQZG*lHs@7KB(5X0yAkuNjje5|_NzCv-=OZl_P3YJI0R6_gNMsZLqNv-66R}YFWblV zk`eX5GTYnV)p0Q0F2QsZO+J?Gr2J^_^JuTxM|no_{?JXJkhGlG9D;rfE@7`j?{@^5 zJ-oldxj%Tp%0nO6*Wx}F_q8%m z57bmBY+oyLt9jp&=~lC^wIggFD##@~kM>|+D`V(z{g~PoLa*V%7EQ(MYgL}snpX~I z;a^2Naj1Q*r@t<=WM7Nvh}c)^^r;8{)(+(|)uU z?dNXS_M=^OE8p1cIDhqMuEi+-W`gAD{w~J54NNK z-w|RzZMoBA))&sSu*4I;miD8)XuquK&$O#<$s3y-XNqqx&uedT9=YK0Qd`LnQM^7x z&q5=_el^Y;CgF^>A9*8wMcZ$R>`UhCm&+0R#7${G+KcvMi)dG8+PU9w1~aYB;FFI# zpa1jLTc14d8v}px{?_F3v%dZhZ+xz0mGpyVIq|w%udxr~rFjKT^%Kz5^?aw}g|&|J z!dkpLJN1XJX_%@QPsU#vf}7oglW-QcU!ne|u@zB8P3K-de__8};*cCy<)MOrr$)CE z&-qN`!~G-k{EJEPu37FFtk0VJa7;7b*7wVp@~Iy@#J#OAopxgErRDfJ&hlVE@~YoR zO8!uKSX`hyQ_M>lncuzk>(A9D{1|AFExFj&+j)J-z#)K;AM-%Y`#29w?KOHg`nB&b z^L{VqgCxCQx-9zPebQI)z7F2Q{=sSAMI@*Qn+Ljg8a^h?Tw})jT_N)}GAWQUj*$-I zSn3U7^tR>C10T6Nzg&P1s{TGblxDiG7t1q#nc_8)ICc1_cPg*@Vv95GQt-_M^RMKle?>FN}ZaR(3Y))Xd{YW52897Yoz_o zQZa(|3yT*gsugKJ+KcwfUaRd#yXy9JH95|o2V$U<2WLNyIy@@AN&`7}A$o)yE6uft zdV3xy_or7mcTd6@J&!>D`;453Uo|22)7Y2?LOxImkM~A2$9<>Shczj$Pt+9lgL6`D zdw(!WZu3mA+^|xwc(iwP4s_p;j)ER}eH&g38F{&^E1!}5LHNw;MSiAb5eNWhsz=^` z!2SaLn0}ox;}rcpK;pP$!^T($f-#xna+qI-txsQ$af$Y#{b(fGmF44=M%j<^0>q{8 zapkX6EP~uWI4zeyUhOEx*L{ng_Z5Rt^+5_F08Q>lP|Uh>T^AkOC<=bwIAL*4}` z3^{`jJL=RmH~jF^46rJ@qcGn-dVr|{@1z*9Zcbo;=u6gjY zm#6Ee*Z!;yWv6n>GG}nvm%j0j)1`i}ezoAQ6`b$1T?2Z93xyW&|3q+5{;JS@ozOD) zgO^=BrEdKnUjH}mUG#^w!2iOx&aMCVci;B#_wKvuVUgkCvoHTt{eNEb>$>w7eg!hr zt$yaC55E5DS2b*^`x$6FbjgQ4uBBIqQ1yQ@xI}b#wD~K3~`Lbn2m%uN{8qQ>hIPhm9BLw+%9n;yP~_v}{5laWuW_E#Z>nves?WT4&9&&&vCG`g+8Z`N%AEV9N71|`>xm4sqZjW zRbczZ;X8r-JqqO1pHmt**)-sPgHig2-)DmTC!i2h&+%+zS}3Lj=#-sp@Fjb?As;y? z1E5fLm`b02LSimqocg_c_xhCb>5MEPu43Pg`*hs5<9mYK&l@)HRV1zVQ@EcOq3<)1EN34nn|-^F%EkLkMZ~_Gb8q2##K4BY{dd{7yH9r7a7ORjfh6dD zMPS0##~NGj+vz+oqK{NY@7pnrhMX8R=zo}4Q{Gbd?b^0%ZEb96OSQIc!_($_ItDuM zjBLq`Y7qoH9a}O&2;kGQZwH@Ai2O`Lz)HH5ITF5aM?a=tr_4A-e=mvnI08lO`ykfg zjPmQSeY@e>J9S(NhB_PXVTr1a7M=^_;VrqX>0+KBbe7$PW->HUzaq4^Te~I zkC!qJm+7ZEy3BjROwDCKxzp4$H74}y!9OV_;!lm>Ut_-KEo*soxR>Z}ZUWzxE37}$ z;18Q`8=@Z1B(Mx*wC`YVe>dLGbN+eqUlWEjN5IGfv4BZP1>12}gq*;|!RI1?r=H_9 z-v{A3Kttu$2YkPo_w6I!x0c4@yMzB*JRIu)c>04C??jVA*8%Qx<~ux0uh;X1Y){C% zokA5z(H^V=TtkQbJ(S+y`#8U`^i!3fRp9@WZH}N zqseJkUEV1=-|#5w9K2sX_@&2C#*Y?kR9+`OXwn><&hh>7p3r)2zdw+d0(87SOXBr| z75gi2hWoPO8}R?Id8EeH{DXO0wiC6C{+AN{uwOqb4GC4R)xgPCd7>9npVZHZjkTP+ zoU?_b1WtWOK}MAG*KOqm=oio2k$<}=7y89JJvg@*xd68-P`*}xP>-<;7{TA+z-}?e z16?cSqfP3&5t!Rxj>vk$8mmVi{GUy|2tc`@BNMO=l-1AAZ*Md%Xz|M zx}8~*PRp9I89!4!h3`v3cd!GG%rC9qbL#zOXm^1<6M{rJ`2C~jja;OcOJAe1#3LN> zl3z1&Tlgcsvt{6jx6_nKFUK$c`%Z)-UdG^&FY!ivXUpPu)Rak&crEsKwk*71QzqXW zUcQ`!qny(o)p{Y{9NsQ9wWB@>N4%85BR%4IXXfJ(j(CR+9_bOU#a*RBBKZ-HctZw{ z^oZx3nU6;};yq>XNRN2WPRjQe!V%9k{!V&1ynKBUj(9Z&kMxM=IKNU^wvTYc>oRzx zN4#ez<>L{Kcy}5+(j%VZ?9S6C;fO~#(qsAANjW^k&a9!&?*Kh-%7kaX7~yx)e}PYU z;wK-^k0>^{Slt{ zLk6F8=|55UgeU$}2A^~(cN9M1iSK?x>yLCfzS#Yo`XfB?YYaZ=(tc6+geQKN!6)6M zvENe>`XfB??=<+NOTUT2Cp_`92A^~(cN9M1iT}L8Ctd2#j$70p;fbI8rs@BN4*Azu zafSGVC;m=@PrBqAg->|mXAC~+62B{gKjDdg)ZmjY?H7elc;XKmeA1=f?~LG2c;a*Z zMY?Qv6h7gJ&-g;RlsgO``y^RwpCr?jKi{MOr>t?7{hIt*UA<3&_r+Gq$b|2>Jy0>* z|Bjn``onp@`QhGRzT;-n%mH&>r7wJ+dUoI-B}Si0+_2`v3*ZwZR&B9^>^GrNgwW+ z+J5feneSJbH1jTfzl|y3OHDI(Yr747yfph|UX1tqBwgRi*$>W1d86*Pxu3cs?{{|d zzjt+fzT;LS`_1@%TUJh{(6hg5fkKG~?MQI?HT{@=&3gK~Di3})?>lZUdEae*$!k)6 z{SnbEztc9=c#r)Zw@(NRjzWH&e;@hYinAu;6eLffj`*`X5ZA-}8rX)d$QSVIGmKw< z+r*`tbejDGmKdTnNO7F*TcV$=hx5wZN6VqZu+(R9^DSg z=l=aedE;BYUmw5kxWOl8ijYhpuMExV@Pm*k7fLe5euRNvqrX!R)Jy8US})X>JAYkX zfA_zebDY29_Fj>FyEKL=+C{za{wLd7D0Oem_fzVHdZ1o1@6&przT8C-dO6PDaf3c^ zFojl5GdB_SJLtN;*x$@s!}UTvP%qi{YrRlkZdHU{j`Mfis1K(2jvMvziekzL)VpsF z*9-MPy|{m<^+J8QOC$7hoWJ8neJ~CBOa8m*0VRZFGmnJpg?gY~QXe$&#rTa|8=;ru z{2e#ygK1DNuMBB_)Ft=vaJ^6u)Jx_=CcYTIaT_A^a-6^8Mtv|1>IJ_CR_c-YX1HFc z2kIsJVH01B-?$qh^m3fP<3@cjg)CZxNp35%oa5xF0p~#rO^3nd1G` z4UN~dZpBk@J>~zP{r2wkjfoBA7>Lv3D6JLzq*z`u~rTt(>e}Bn8h`6O3V4Jy=p_ebdsP%$p;Bx+w0}ifRQXez^ ze~(UcP&((fh3kcQzFzJO$0xl!y`7}Q8Uss`rMK=_wxB1y+=%vEwVbN3Kd$vcec23(=_S2)ulz1$zm4XXTZ`2DfDsw!~iid}*{}U?6QH1AmfL<7P zcS#<4K^i>D8js!=t{09!)JyhW-H$j<1^FSrwRKaA9;Em7_K9=Y^~K6-V`1f}LNAld zIQ_8Xp%hM?0t&T!mirA-$)ZfNQYaPlxM;{z1KDCTacBkI0p2PA~Ff zynX53{?6WmM_5@x+7=5dM;Ln9XZ!_MsTcLVc%zrxU7s9YR4((GaJ^6u)QdYs>xKHV z>E-m&duZU`p|a!4=2%!cDWI3_W<2_}gh)2EH zcy`&=OM7Q;Pj6rQ{*D73`_lW<2Z|}G8Q_VHrGne+)jEKBK_&e~t%_pwqs*U&>xKS7 zy`)ap`lTP)g5~tmKhUxNpj}gbgMBZih3*ma9 z9;lbh8CoyYR~`{5T;>*LzNddhiis%LRzDhmZZ-ncG zdZ1piu8A+kZ*2NGy_A2C#HJOud{pKyyg$M;NGlO66v;>JGf)rIi#yfyBjYzV*_>YV zV!B^CQ%~vc;t0a$pgfw_u9xN2eN3Ex+2kIsD3auCF%O-2uKtNddZw+;*0Sc zo20Fm-95d%`)!~C<)$*>ZBo$71x55S!$vAlj#^Js57bNcl_tIzzp+W$dfAgcIMCJJ zySIIBce<1xF=+vOqIYj%ZE5f}f9U0RA@jQ6IBoAc*ffIWsP#1UK)twUoA_ex;t&i@bY#aKGLPa5zSTT<^3Ug z3HGC8K??bmnLEPuLOoC~?s+D@7=7ha85v&=ru)zjZM<_m#&WP(mIeK)O@J#hLUeK+03O3y!edwOpyy-#3&w;XtzKlD;pL@)S8LaB%QzHq%z z57bNcLK9z%-`MnRy>uVg)7>XyP`kQuRCtUAt@Q>zp>8A-KDp1b+Rk&WL2kIqtk%=$H zZ)}n|z4Uiu#kjYeO-v!y77HsU1@!W4$UZ}G{<0_sUNq+(4c80xK)qxxHu1&yjZHYG zmwgA*2RgfZY=9!=b$#iM{&ZqX99)owUj8mbFTwGsricu|>dXV-dZ8Yum+U1bz8Jp= z(m+0^m%TD^?H@SOQ`-1UI%{KL5nJo!%OQFR`pe23c+s5uaJXKm2kOOrory2TZ*0Oj zy_C7JYY2_S{_Z^?dI|aqo{K5<$UGXZ7wUm}$;>kG#rTa)zxkTx4f31oIrWseF*O$Z zQqxV`t(HBh+`KL)>Ec}0NnK|Af2K|YRVo{Gzma&){)n*C zQmE2q7E%uC1=aMIV0;Ndi@X$dzmfhyy`+r4(T{9`(R%4iACM;%YQVbk z#QjG4hpiX-ku6%ZUOM*N&>^epJvK&uxv?aue4JnjdSTqfb?PNJ9+h+3G3tIJ#~3bwK3^tmq3-_Zz7P>cvf( z_-)2(o8kz)=#8n8bOKs>U#etqo4wM@Gezbv<$Mn(a(!gy8N3M^I z9;lb>e61JyjZJcdUdr6~9*ceNj~CI)Qd{T(<;eAs(F673E;RAQ=*uQKLN8@*z>LNI z%V3CJg5%LLTj&Di$n}xY1ND+xWa5j_mrZhnUdr6~9*ceNbP>HQw}mcHj(X06dZ1o1 zi%onn`m#xm(97+SibjT0<4l?NU~Re8)`t|+1x{*Lkp)w56pwRsx{XAx(u>?@E%uAt{PZgQ(2G@;w z$RUMH`;QKX`3vX2-GVO2dUwJ}F!NgtZN)z|F!`InD7bs`4JHq3O(F668sx|S& z#2K69i1DbbxA^3{q+{?NU)%5W{pr`rqwhI?$w?aguBN*}x5r%*9$(zU;r>EAUoSP` z_~aU)m!j|Q5q~V+<7+YT1>Z)8UXaE;GB=0oC1vzLy<}Dz{Te;n{G#-twi|5Vkh0om z2)SPBCB&C+n)g2U7`-439#%0}H6ric7OofSfqKcV(t4r3Y(i0b(Qm8S&?C!Z@xEHC z(Mz|Ghrb{V9%b!I-5#zN>VbM;Kcv2b{E&~*OKESb$$i){cwg-a6JK_TJkSf$;4wK^ zD3W*I5v~{NfqEes>WgKjQF>ARXkTCNp@W5|d3wKYU2#A%v{LjV#@$_#57Uc;yBlOaHL%Of8drzrr$Iaz|+w9do=A}jS0^OB*xE~JJ3-v&~ zxQ$vb)R#?v$L6gY)C$SGHqm}#Z(k|TGuw1VQ!ch{#CP3GJ)+hD)C2XBYBK%E_>E29 z_=~TegMDe-fVIIQ%UjBXw+X=)J`wU9d~jdtTpOuCIci=;*AycXsE?Z0Q4iFMyVk@P<2L~kDr@Vduj7b3$BGKdV6J`?vOmPDz6h2pWQVoti(3KvPqX*en{dj z-uG-045lR`TYzq7_`HsKpk6W?O?)waW07%kdVxav+k1Ckho`-J4;FmuC`V;;sen0@ zyd3&bof(f{h1@zI2PP`>kJJX^|0eY-Ovb$~Trb33e!O5}L4_hzvBb%SZmn+-0G&Z-Yn@Anq#om7%f#2JAy?VLL zt|+k#z04>we<^4G#eMTgy*wp6_+8*7qIdXT)c1jN-wC>UL%VFY;4FD?w%RPs@^Fc% zRXr|6+!sQ7**>te;*|3cW(H*0v)0-{(j{H6=zjIE_k>5p<4GI;mgDQrT+a6rrCb| z`w5vtVZWmwzrRzhf0v;vsZ-KnyJ27aE(7WC`{$wb?BA~(&F?ZeE1HFCqvNOc?^l-h zy9`mkUm5wk3?J2cb)9Ga5A4d6`iYyS?$zHtcke6h`{zSXzb)^(7R{7=Y8n9X?#HzKGLyCam&KOC``~6CRH@{yAz8Ft9 zesDZ-uhag)amN0gC;sjbf4>QG@OVc0E%sjiN6s^(KR!F@C(5VPcrrErcYZRa{Y+Cg z>T$$95`fAsBYJly#aosuVgmg5QOFdl`|OEhVG{;toZE%{|q4^R6|e0nXaAGt(u zWjtXz;&*-=`JJDENf)V8kFDWU9S8b@?r_=%Y^^P>Tg-O5XXWeF#ye5Uv>)w7`%!+{ zRhL&Ad;LP&v4Q1|=AVfUpEdS*n#fiPJ>z&<{k8w-@dO|h@~hsGiv8fpIOUMJQPdIi ze;bB<0oM&B1>(M9eC(I{q#j4QK2_p)^1tJaCu}F|hxZxSpZ}la>7#@ROL^~5qNh3- zml%f_m$D`q&L^|~AOenqgG;6s{TpG=&S=ldRGodf#~zFn37 zQap~o!#>q?jHr1o>wP*ZqvKNk@3cQq@rnwZ`H;a<(EnRQ?e_|`<^xWUl0VNq*UWQG z8l)X3KlDc?F8y(7acStojcVL4msj@ha`wYKm;L$WGS3~lOwV(fW;Wg)Ydu#?ue%&Z zXa(v2PW$jbT=E}Szam~^o=g6m=i-|vI6q+I0^H|iFl8C@Tz)qNa~uASI=HCvO}XC{ zP~~sy{bbgsKAHPHaaI38S~p< zd5%?pd#0?Tg5hkY{EB>j`7EpaDyw{+RldwB&$P<3tnzHDJSVTr`3dJEoS$T_ z*Z#$M3)e^domcM1@pn^os~zV*rB5`=W;y%{`*3H9gKnR4jpWQe+}FOA*RS2WCbhn0 zn!44@Pkx!}52THB=x#kPnRZv<`3dQ8d~=@*q4&s&7ERmCPagTx{Bn?SNd9WoD#y|5 zrtbz>gFqzAHW|mKcT&7zwCc&`_Zl%_b-}sItKP@__?+p(^1+F z{=YETK$F+@dxd(`FwcHp*Y?XyGxHOZhL9-h($Jrn`N>de^OMx-c=k))l5aoSi}uTy z{!F`;)rfHbj_QAiT{!XWrm%ff-Sgx(@k|tDEO#Hvk89%~@-ZRF{zrS!eq>I&siK9WNsXv^t#&K>^bY$NGRkClfeafsU zIE%;6DEk4MHq(?eSNGBJv7h_qFRSq``PtI?Uvf>n{zu)xes{_k%<=U1Qo;5TCM@N> ziQqgm2X_{BgXQp-R=KKExsy%k|!=bxz_J^$pqwCgdw9!i?~!JLQQX|DT(C4+s-P6-*9f5Ky* zoitUhnEB^j)_vf6%{ImJo?`J`3vnu`(>XueqsDWx2UsO zr(XQEu;p!`!+#y5NT-NCP$&V8>& za`;{YzoWoXKAyu>)yw6ZJVLXgYSFn({k~zOvOKnE^&NHC%*kyX1%Fq zqU?vg>k1j^@I1%qLh%QaKP@LgMy80J9Dkzim%n~c_Ph7xWk1@B_M@g~SC)@g8nym| zJhWeU{Cv)z1V20JIhalz?%m^KzpPn5xT{x%?yI3{$S$6KdQa+iB*3yu>LKz!2i;>&aMBq zFYb8w+xK1du*mT6D=+_4{ptVxy}An)eg!hrz4w`qKDaaWT>bXCpFJcpJoNA{pZx02 zKk)nmEh~OnD>Bqo&G}f}P1BO~cieQzga5YWU0=L?R?9=*y5MhW`)>QEIw}A4=HGqx zkz4-j+=l-|H!W%Zuwxc;k{0(2{Pyttt($28cW_S`@7z+u{|sH z^*r47*<5?R@bjP6ePUUzJ=s5--0)ONw}<$b{aH_=&}d}&<(|InOMjvKE!fUduLbQD z#4kNRSpUYl74_qJ6VT7Lf3ReRbV zz%@U(pdd$~IHe)6z9WyMKL%MemMdfoa@Xz3pX#CC-8|o$n#yX6H;RkV< zhC`KmH76S|E1c6D*Zr^}qWe>DkI1Kuhg>F4x$qnZcfxY=Oj0|pjw5ZVz5A}$)=idn zom*8gsX}65OL}j|p`HP!zsIL?DsvKPpmI+~XXWn7WgY3IOZQansad|fy0dcW%FaD| z(km->FOhG~u1N1)wrpj4Rr|8a%ENLly6)hbA`TaIW zZM33H+Mi;Yvxh|H$&*hr&n1?+ zzmXE%L4WoUxj*%!)~h?i+#fZmjbCm#Q?KXcU5(-MbDLh~M;}nn1=!b%mEBKR`y0mo zv>)+lS6$|Fq%St9GWQn;&ua-jS9+E5K2pe~TqlIr>;44P;B%#0Cp|l9D=vCDI(Cl! zzb@2%TjgmCeHcor;C?^9U)VI`mXl4!el4ZhFZoaL>__>~|B_NjWp%%vER98b51TUK zsDq?)W1hbNU;2s@yiQosCN0t?P4XoCvx2dE!%|>8I!*GdBmJ-x`zAQ#g#vX9 zO?{KP&wunRol+*sTvu0@FrX)8a`4DNSD_zw{co9q<7|`2oRE!tKG*f{qODTwL8Z1e zw{@luq@4lz8E>cj*J(*6FP)sw#X(8BPRl*Nrmx2Pn+ZGzS3ZSe<9n{2xAK2#BQ}n|j44qd3|IIu7jV=-V?2 z5`vo33+eQ4UDw3?L`okKVFqR8tTmi3H{S2XDzMN&d%s`-L4jI{fKYVn39GJ~LW9)e zoThe_UoScRdo-w?rb_rjxtRJDCWGrdA5naCxx$fWQ9()_y|2DQ-I7?`)w@5vSnS-F zzHaf2{fqI5&Vl~L{d@M}^UCR-{>A!h3jK?F4jt&|YnNYBzdn#%R#mll(c*!wL;H6h z=;#*cN=N>mI!gS{eWw!*!VEr#oTlO%{|1sxN*1nsD zJ6Zqc#>n7!8K#Yv|AniA^?N__XQJD|`rHl&Z4ic)f6e~>R=MSTYT>2lpUi(xY$TMP z4@{1BMTPR%uP*tTzYq@)k!uMQ<&_bYBCihKaMq7N^J>Ydnn!dd7ABhTbKK3n2jt6t z{R1VVtKWU^?lfB%rK4GpgZ1uf)~fwlR*ZHZXtem0gK6eBIzBLUf14jK2*-5QcV1J^ zQ{PKe&jhIZgLv<^LJWxm&j$qKmA-oF?=z|B;ryjvM96R?40-ZDyOmW7Cce9XB0m>pj%h8T)=u>XJ9*-5Uno;DJ5D;65Sb zLpg{C*|(Tn^(YG&M#>@nmx#Ri8yVQNP+?D(s z`XNppXamYYJhWk>=szew<)!?@XS?9voku!*qJAfj@TI1iGt4~1q{IvQ4zAHh2ye?5 z#KTXAwhtUR7~4Tetc(=$4a(ey_c{MbaM6aNx4uI?f1bR}q-K3a(s!EcZl%6Idf24H zCM6u=rMizL54uj_WJ_3FE{`?~+Ytxjc=nZg9-28je?B?_p~!{Qr}TGM?D&>CH=nMo zMF!Ds+kPZJO`H(6!&@PfoGrKki3onojx(Go^3QRWsOMb$yPWm;pYf_a3 zEi!YLv-qLM@*60uenu!g#w`4b_oFc;onI0K&jWF6&3Ss&EH$W+keh~AG$78%nt{gdS{^cQxHY(MOS=MAX8 zi$&2|*Fjj)(&G@|={H}OyzM(dO!^<=zwLiR5&oB&obP|xY~i?iq4*zr6a5P*{g3p< z%l|T`{4Zd3`iq?gKunhYNBx!RfApJD{4XQCl4joVZOP~2jjW2dvXOEh;%zW;f9 z_F#IWaP>DYf^C!UR*CbW-wc|EcY;3XI1P@g*KdVYTd0`P*kJ`u@W zgux(C$$myU8uYbbexz3Dchp}geh2f?U*LB^p8>sH za*g{K-?!?Yitw}4)bjl75(t3_hdJnHq%&TAmOABURJo)<-wNgfAOZUzUQvIg`WgKt z%Fnn@_N34b`e8Q0&)l=h^Rr9gXI$7zmVQP$BaX#=RNA}T=V@^7O!`Z+mUQIvG{ed3{qHPmn3MT$(8j_1NS(mm+vGC!2YYK> zt35;c7N+CK{%PHtYp3F#rE};*ch)^~)lrp~qS+^M9C`n!p4V%q?x-g`Vw~)yD?04^ z+)Iz^3&ozT8anlC6-;H0p#6h+*5^{#XQmXXKllRIQM92{`!=_2o03ZIAD=0R7*9CG zNX^y#(_O8LodDZ5~RvU zDNl}WMFr{%%tOFI9pS*|JSk_)`0*pjb6iBf08jaNztRi+nfGw$&x98+AGc83OgkcD z+t8`845~B->>YNpK9|Bim@`p-rHo~j0?&JO7|ZPYbvf$MIqD)hD_fXdRPA3Yw_Ymi*o;4(*4&D^d3C*ynDX#PL)n+;FJbVY2cIwPHEtj z22N?|;H1+)qLII|QK;!yx9k)Et~XlEy2YKBzqi)h)p6iJx+j6P(r6CyBYpDg zGW;k9`BlYa#`QS)kv{ol4L{03es~5j&cQto@*{onOU~E&q#Wc|9fz6VaF2%kNT2*N zh9Bi1zojwxaXX*I=n_}?DkMzkewLt5Wa**HhnEbfrCqL3Bzahhq za*!Xt%U>>A?zfU3>64$kP`8hAkY7!?j0`+($>1PA(kH(z!;f;1-%5>E_Fu*x@*{on z%Nl-^gZ!#u1{gk-On#(Ke#u3q{~5kMznB5$6-FcENBZQKG5jcp&o5?x;ky;&NBZP9 zZ1_)|1*4jelg<671(;YT@qelg?A zWfniuCqH+u>3@c=&o5?tNm%?ypZvNEKg!|riy2=oxA>7h`DG11%Hi{i8DFMb{79et zlKV{mGkkr1G2_b&iy!HeU&ipG96rC8@deKa;9&eDeexSN{3wUdFJ^q1rP=xXNT2*t zU8esTzCOR0@nyEfkMzlJ$nc{aKEIgpWsb#<^vTcdHvP}=CBLOH<4e-wNBZQ~W%yAJ zpI^-QGS}iq`s9~2{3wUdFJ^q1XYnI_@=IQ4`k&$J^NSf@=3D$opZqe0ALa1*#f&ct zEPkXarSr8C%@G7rvDkfKEIgp1;3$;gZxOJ{Dura%Hi{i8DIFw z1o@FZ`MEu&{~5kMznJlb-In}FpZvNEKg!|riy2?oZOM=H$uDd8Q4aE3MnSbXO8(1k zOMawJe#!l&{~5kMKMGnhCk@DMOMawJei_4$a`^lxXqo)jZOM=H$#2;3qZ~dz3R)&V zc3bizeez2kF#XT)_4!fIGWoIFk{{`l-;m))IedN;v`l{Nw&X|pDkMzl}%kZNdK0gXtCO>vt@*{on%Nl-^!{TOKpMsE3II?IV5i8#eqXhtDr&e8EQ`aIk%(PkyO4oBn6` z`ut+X7d~7~exy%+Lxvya@cG4zFXo|JzkQ@ner})Xe}=EmFJ^pcP}Vd2rabAL)}{#_*#YKEIgp zrNwF=>672E;YT@qelg=qtHqD>$uBiv`k&!Tek)?em$eo@(kH(m!;f3@c=&o5?t!E^dJ7+*-A{JIQ3%Hi{i8DG|Gc0NDSC%>%WM>%|cG2_b>7C+J_ zzvK<3{~5kMznJmmN{b)qlV8U0qZ~fJnDJ$U#gFvKZ`kmo96rC8@nxgMkMzkeb))Hj zhOf^rW_;OX@gsfm8#4SThtDr&eA#UABYpC751amH_>x~u%=og!;z#=A*Jb!o4xeAl z_;QuSkMzkeYxq$PpI^-Qven{8`s9~9V)~!q>+_2lU)n5wq)&bs!;f%|cG2_b)iy!HepL?_E ze}=EmFJ^q%Y4Ia{^6N7ED2LB4W_-EE;z#=Amo@w-2l=gx8DCy+@gsfmOTNYQKf~AO z7c;)R!Qw~y@gsfm>oWW(M~+{-0Ml*pBYpDA8h(@`$1h%hxz6H8`sA0q-Sj`hH^(ntfVtk{ zNBZQKG5jb;j$gb0(_`@?eexSN{3u6`U%UXb-{MF562fV;YT@g{NlxzH(UHjpZv0hALYpL zix*$|EPkX%r*;>DK%iy!He->~6FIdc5s#g{`C zKhh_^)H_W7GkkOW;>DL6EPkXn&Ox$iXn&+zs6#e9JGu*Hw` z$*;@sqZ~PY@#4!7iy!HeU)J!W965gR;>%4IKhh_^WXAMA!#Bq-UVORP;z#=AmofY( zM~+{-`0^HuAL*0du;E8Ja{S`Oms>1;q)&dScbWcY_~!VeLH zzT9TXj0&7 zNMY25$B2&my28ItL*81R=x@p;OQb`3It}|a5x-HD4+;BBlS|ZJDc>goJoQv6JoQm3 zJlkCgJe~#SZ&?C7OevMkoAME^kbGnLdrT=~SEj|}BV3exXxE|sbo-w4f!^-^ z_`f$sIqcNd8|$IJK`GE*zaHT~8@dmq+v5KWmx>p7f0lA!Z;|gqOLoKoxf7`rG(M}&SEe>OMCcPJ!yv-~;1Eyo_4oBDb? zuXozj-?Ai)1{POS$L;brb5?lVHz2W-a@rW1Neo2yX#RIQK?1VkSIC%uK{9yv9_MI} z>?^f?nZ~8pWqxPzut_0vVI6ah!Z`~$M_p$<(lDH0y$w??JZaf@q#Jdecub?EF&HOJ++a!)cAuwwgexT9 zSk4bAPq7s8xdO!a1^8eaP>%@%<65vDb=aq1?EGU37qB?6Tg$oD6rql>vVEV-V){A; zdixyxS3#EdhifikWxlO{BdhCDGiF}6PW`4Q>uC$t7qZ2s-aYC5#Kzt|-Fv&!eF>R* z4#=c9p2K7>(ek*-{IUGi6wIWQkMNYweO*3Yh3IhofrEzz+T-opT5O9JQ`_I8euo$G z)d)1p!TEGCBJz8qvch#F!g{ySzt~>3kL?{Y?WG<7Z`#|AHA=_8KwtN6`9E{8L$iG^JQy4(6PTv0gukzpw`q;VnYwq9bh0I`eqPM)gSr(Hz_-1rR>8- zcD8BCB>GakJ!Hs%BlXpMAJtcLf3aVKv+I|+eS@>49K?g{*u&t7HefEF{Ys8@uKmx+ z_>3c$0)C5JArH{c!8^{S0GEUGf_q50yaIXJ^ZtvE%i}^`nYyJesoP9K%SoMsxAu$W z$Hi|c59LcWkQdY{IHL|l!xfmGlUJ}|~=om4!STQhT z%H_mBexD2}+Kax+_Og9!Z`X8fE9xQVOV!84mnaYAb7yGzC^vMeeW^MZpJT+pnwY*6 z#8bZX?BD(gbxT<(`;d{HZNmP%mOb8mLbSc`5nM;eZ+xDv`wQgTB8V*8@hY08{9ZFF zGmkx@vYE#kOqySo_((ml-PA*BrnVvVlk>5q$Hm7e59J#+@=~;I*x)DvzZzQ9jB;`KTAljj}J_C?;54F?}hB zr}TWqCqKEdRp!UC80S7K-kDT&6uwBhvDK{Jd-taY`i?mIZxN&ttM4cgt{kvovmcwf z$iyL&4w?I~LyhlNYg_DrAU0y32x|^Et@jcn>&Tk*WpkiC>}T*>`^cDf2OA8SVEIJM zqYZ2~>}((IUTyDV(Khft7JR@1yb8Aa#<6L4scnKR$D-|!2X~Bco`*u2hkJi(=w8h8 zf%`kuZwP7ZO{jBnh4bVGr=Bi(wEWajNCSL+<%Nq^yyNAnEzBJ-)^J>cKG0V8MLj;T zo_@x9>I3x$0dL~;0&#HG0d~9&j-R9tIR>S`>sLx1?ULi+z!@yp8#z&rzJU}6%eaPv zb*yJOSkG&OM_JWVKOD!XAAh|JjBz-I&Afu7A;$-#!0Q_%k8ua_NFUQxqIEJ|*-*!aVBreU#}c#azX4rmKA<=25TruBNLLdrW}A!94287jix=W!H=Y&=>fH z%?;$Te_XwNV+Z^&?qSE*i-b_vxJ>$+*7Y7ptnKJbFWfFqb)^sUdZ{Vrd4xy16QTsl zag9`9-sd=v@UuvgPtfN~e$dnbCM*wlURSsVAMn~g4SjPx2!nh>06r`qgh75V0MEP= z!3#1p7Vz_!ayIzKRoh9KmbwKlmwp7AO3Y zd0a;v0Sxv@QHN_tQO0$yFSQTr=RiQ8bO;}OJ_Of*OPPQRI=BXYXqSqsW**46@mi@X zbohQ*2&h0E*C7Of94RUAI=+bl-QYm`a3EzKvNMnV!#w&g^O*lIze7GkvQrwLc|ngi zN2QK>lx)#s$L1ZqeLZ`M!o>l2TO6bkar!#9)be!velu8~$iu(CLGBJU>Prbp2iac& zP+D8hoAqPn8@Y920Lah6o~}42;qDQ1O~D5#nAx4Cm+^g7&@AbXy9=j8&Eep>50W6~fzV!(JF=Uwo( z9~*1>@QKqy*9t6JMU4C4dnE_`Otto3Q%sZRPYInYx5|j+$>&vi<~c= zorC`AA75P0(|wP&ll#8H{Ue86Ecel7$H94)oY^M1Ya-{wIZ};ZRQ&+V=*eyJoKAW`dm7>5r=o}x;0TK=rHK8s zu|HvbKQR7JKVUumgXQhLJ%`GDUWB+vM~hEdlbwcBen4f!NC%sA93U#=JL5UyJL?(u zS$?|p6IOh0>gc?FUtjN`17%IR;$cw=$9au-!R>N-QSto)Ccb~zq#w;sbCgQWVZJqS zK?gzuiIeAY*9&wC+j254qC$V2&V8{2-aTxO7T|6=3JM~d+dcUzh z@zAfa#$x+FX~uc3F_2>Y;Ew~wKYV{-zcGG9x@|JYKd^70i{*0D(cvKHuZ|bgC;f%(zt{MSt~cw8`MX+>EL}M<4cVY;riv{dGRGjo%2x6J6+D(%zAy20fk>RNS^y#*ar<8 z;jw0%10y%5s)O(1C?>v3VYHv~Qd1AlbsW8fQzm-3aO#Ng2d-6VZen!zMS&_mE z_RR^+a^dsF6Jn50R`%;rt`2v;9{P(Ch zHQUK`Kig}QetK{CzV5~{10CVxZtXTn6nKlAk^8!LnsxrY`Ekl_PwD03wXX}lKbEsv zPUJr>=MUw~Ka&5Syf*=taPh=Ph*f(qBG-d2$Pudn<4^ty(qo-nX**x*9+Gtn3}z<8Y|=We=5S6gS>?lWsPz&-=O& ztBdx;iT3{g`uDbV<=XW1!c`sD0{!V_Ffh-t{&2#QsyyKK-%SU+ceb+hxnI zb$_n*`O$~9|NmG0{cruhuXRHkA)2hQHU!MD(z3WTtOBw%_N2L4G%TNB@kDc{szHbxf%gs8Y zJlW(;qr6c*F<;5NU#Axc4wa`LH_UnIUrwzLlf2pYlY8?f&P$A+^HP^Dku$45y>&+U zvB{U;R=y~Yn5SgE&v?>P`PXaz_o4E;Egk4qnQooAUe8M(Ikh=V^5x2_$rr|-o|jHM z@n=qc-{W3$@`)#2a$vK*C_gs&@-gL$@`!m#=KGWj&%fj)mv%p{@0I+Y*W&L(<#(I7 zA@b#WPHhj9d^zym?duEUPxECr=E*)r`LW5D-&4LQk6@l~@X~WHxZwQf^Z6_N`%wAa z_HKxLIp@^u$=jbZ?6&(qif8>kH#g^QAi@=$`|Dk%u`?TvKN+zaNqt=dHQj~ zzw2~ETp#_wN1DSVUp{>` z`NH@I^F{fw$(K(mUzA78(`vr2>t?qzIaHp0+%W6QZ-1mcO!DROpV_{?Fn-IIz55sC z$0lF?O8KHZVxCUB;NZCzKmWRaGwe`#`f6_|)_lP_mqRUIbz^5LtwzsvXs^F{fw z$(L67qC8@r9&-q5OL!bAPd{#$_g~Jxsyv#Wh*;UP9k}p?YO};RG))(?*^>_MnJ(M4teEBEki}Hwh zI^}|k%5(W}9sWL4ez(aR;C|iZZ@j8KO!DQx&uw2{7(e;4-oNPQz@*QQlpmXX`4{Dj z@`!nQ;!7@m@uB=UghS=&$MygHvhMom^6$PXd+OnF|K-zL@@4h?GL66g9xqYf^8GU9 z$tG{UpuAB&LGIp1xo#P7s673+Ve;n6tMbDnZ!VwjU1uV182`1-8|BF+Z}@(e@`?F6 z=iCds-{5f~+%S3bo~w$(ByaZr{Pw(I{MR~flqcj3^OGr`_4|IO~yexiR+5Ya| z;@H3X-}s*+_C5WGryr3$>x$LyecSx=)%-{J#xFxj_1#yg{wExS?gk&r5l0+xlbhc3 zrnfu#=%bIn-R*97#_ex^`)79lJ-PYKZ~oYu+~g(?yzz~19KWLC`tHvWo%hY}aECjb z`p}0y^sSG3+~a=Z2~T)Jd*+#E{^x0@owj`BBOm$2qq=bjYB%R@!q%_=L1ha{q%Qz!#8}xKR)ky&-?G^KKHphU;p)Azw^vzK6B^n zv(Mf+>#VbOPCfP1orgW_VLSJ{=RJ3hJ@(lD>f+Mg>Q=Y9qT?fdZ+u-k(T(BA``zz; z=XC9T;>9n1@qfSQMK9Vp|NQfJUhsk!?3{Prc{|aMXFcm#J5PJs({`Tpq$llkecXA( zBObAHpZnZrr;EeR9q)L@FLr(Z{VsN2@h{fy+P>+79`vAdU-FWdeD0D#) zblcnB_Rq5{i(h|ot>Vzd>_#2`q^`a8m9Ko|&MRK=iq)T&z3gQ>U0-&(KJ9ezSoI;| z5PgWbh(2_Av6_nqKls5r`}gl(_2JgHzV(-GbDP`zX_vPrU7LC6`g`wge1G)K-~7#A z?*8n&`qi)A`KE9Brk&`^bUNL+^wLXLeTZ1Zd@vW$ho?UEsXJ$!amLQ0AN}Z^E+=CS zcDlA#ap?Yj|BY^RquX6mA0qBuUcc?~%P;@$*SzL6JKf)_KbKv0+0M6o%eSoh67h&w z#GFJN%Cg)!c<|sV7oPs~r?2MWF^_r7Dj)BC?|ZLeaLh5s>~y*CUtOI(?;6@a;!bzE z(*wIP{_X2t_qrYay!N%P-TBsU{nnl6PxK*T5pjq<#9Tx^L{4_Kv6_c-&N*kN8^g}Y zC!f4?|NGxR#=g_lLbSirtrfrD&2L=J>^WlI4;(n~@^AaLZ~NjK-tdNs@!c99Ydm*N6W+^2j5< zZcpRgKg1f-&E>pn_sie@?ccr=f8O}UH?IDsFAZ7icfqe(PJ`y809U9kGb{h!~Iuk&Da$Yf`L>kpr z56Ht<8>xdB|JQxp*R67p^Fric#6B5+oELgWw^rP@8`s~(SQ&e?{~h1)9jh47e&m6- zpRNTl{%D^Z?9Q1xcfb4HcVg_(hwjhEyYcT?hr0Q>ZI^!^OWP*~@i*-={;0#q!KlM% zpBjkuINFc-j~a;fWBk#6jKBN)LtXpnuk>2Qp{u_myV`kYjF~>9e@FW<|IvQbK)Md3 z@qf;9p0gQ$#6QjjG5@g!bh-DXZVh~SFYvn`j_A&LPwDdf-=p1Vk3ZBQH5hARv`_v= z`*D7bbvRvvqWuRx@PVuIK-YG(|My+)AHUmV|G&D}+`fzDRm6aHS%+8;S%c!76#0MA zMHg+(MbZ9bGFk0QVhxV^i*ryH`!98C&yV$6?0@R|cH@Xa*WTxu^XNmwysM2>+!=f1 zKIg+&f8sopo&#e2Iq9U6cJ6hrd#&2<^6pdDW-oHHo89c_u71C(i@|@!JjA*~`_Xo+ zJCS#cJ)Qf={TO@fhvFQV%>9=--)sFthPzmex_tiNcYf!0ekpPw<~_zw+&KqE-m~_` z`6p_hy->vdxZ{qCvHx3FTkqPo=JliB|J3cD?$Mo7-rLpx7b6bQ2gVySDeNcm3A3embJd*JHa_zOHNgbCHvge{t@K*mM3**ZtTJ z$Gms@&@bKN9{2cU*Y^3H^PY3f*4DQF;}PAyE$edVq%OAa>ek1$`?HMNi*+Z)->v&! z);{#VyZv8W4}7A#7Pz82&mZ5dGkean+nX8w*XTzV&*Qs&{`0$-yuDlFKGdyOztNp* zKiXZBeDL89fB5%y=g?<#d)@t=+x6D2_pBRJTo2u>8{bh~P9M|#eN6ZH7T4!kz0Lp0 zpU;_e7mD4DfZ_+&zbATsH`uS_zQ8$?i@G0Ve(=1PU3~5Z&pGehOS>QQb?I}uJL(57 zKDYb9NDsU=KkMLXub1QJdS741P4(LYo8MahT=ePpJbv|ivH8s3-d@}{$-95#|G#_p z-w~gse9+hU?L2Gcdr$oz@aW<5-(L3v-|UE2tnTA1uRP;M@q0?5fWE5x8y-FUL_EIv zo7T_8%Gp1D_WL^SY1Te^_)0v!mH0;d#w0-pOg?M~hjX!_;I)3L^`{?1P z;_)rsypDe*KH{IYj~>1jk8dr0diJ{i&#?ByeB|iJU?dunM_|fmF{^c_|aXs&gm#oJh>&N@MKg1tBd?6m+R_&K+ zKk7dYc=Yg7@%Xli-}DVD7!MJ$xe`-%9;&RDTb(_R+&H#p7G)d1?Kq$FJ(|R>q@;&;LO6 zPe0WEO8sX8P5jZrPsHP!eeZfdQ-68;{sTRHB_7|Y+Miub{LsVC#p7GNbzT4YJ9p2Y z5d!*;9=;WiZ>9EYwa+hmhDQ%S`a{*fd}_tNy_)!=hcCqAJ68Orir<}W{?Nlu#pBzk z{p@Sk^Unn*{YMX9i^sPnelOi!zti}khhK=tH@k8@|CQqJ>o0ov?2lCc#6kTp)PK)k z^zdWx_|7zcO_D!vxNLX+(ZiSG@y*U&pZ`j=e@r*{lt&Lg6OV5$z7l^+_?D`lLiKZ(=zMpO|LEac@%Wa?-&Xm1)*9dN=;23yqWYK5 zjP>t}>-F!eIzH_`diX*-zK!_ulvl5QKk7ZKef02C@%Yxt|9O)CufJ?}{OI9p@%T0x zfARh6_47LC8;;j=$g{mW;r{x6dLhXFi#__26=7dn5p zZ`|Ggq&#}~Qarx-pRM;F<2SAON343k+dg{unRtAs;w$m-1G2iy&rSc)!#CpbU6Q}2 zt>^z<9iQe8dibSyeDfdF`B(Gz1mn@e=O0)7%coWSl}Y_Y2#7y=_=$LY^Vz!nsrv8r zhaSEXk8h*-Z?9(l(ZkQhxi-Y*1ho6eacgg;JvU~j*IRuX$z7~(~T8~P$E?@S82`cjFW$rt zJ^WHUzOC}NRQ|^K>)`&~_@jr<|6KJipF;g_)c?5ua^Z!$JbL(vczmbgm*Rc@iXOfa zk8dqLf6VUrFU=qH@N@C_Hsqh;cmJ;c>H3Ktz7>ye@k8tRYZSjHcYGY=FM9aVCshCP zsm15-TCX2Z>DUh>JbL&-Jiev!cXY)%f8+Og9=!O{P5bEKr{eL=et6yg4qF{@{yy0K zR8IPj9=;ZjZ+1@qdm-^6Ssd`_;TPiZEv@}C*7$};51;*o>R&$DkM-Mskn!l@$Kvsw zD}KWEooYOK_)LOj0NpZ9;iuJ51G!)Je``j<~`{9mRy@8l*hD@qlYiV<6GPO#r@|v=s$Y+ zsd#)#%fBbC@ePk2z7~&f`H=N}17Z8(`DGlmj~;#@9^b~=kLSN}z@vxHKBM}V&-gF; z>$jhO(8G_#D$a7diaTWd@HNJ`x%cOz7mgb{^R}n_vc6G;pgJRB6_0OYeB3{XgZxDgKl*#szkIT~U;n&h438eZ5RdQF;(uD#_Wl!2+O&@zekvZ{ z*+BlHhp)xs+gSUazv$r?;_;o^{NH;Oz1{eshtK{&^-n)6ei8q4{OIAw;_+>*{kVS> z2k}P_Uy8@KviAM`7xeHm@%T0aJbL&>Jigga^z$d~pTCzw2vNsA|BsjOaI@W^dCKZB_7|YweRzX9)2z!-`aQ|KYI99JiZI# zqy2RJ=;25IsQSmp#_#!q9=;HdZ}$ED`Sbhl=;5d0@olXA$e)AVw=kJM^zgNKe6x4= z^Dp|J<_~)Kg?N0&Tl#-V*8$o`51)Nj^)H`t3x8pff9T=I;_)r4|6V`n;Y;!O&a8bu zf1!t;iO09H_9K2>_&4K658sH#x3Ts^m(Cx0_@#J!8*4wFAEfa|51)Td^-mn$)1UuX zf7AQ#=;0^g@hyyx{YyH2^zfBk58Ll0kw$2a@Qe*91D+J9M6Kj`77;_)rE@M-+f!`I^R&3~Z3 z{>1fjnt$lw7vk})to_KpI5zb!J$&}hs(<}^V|?^I&0qBJWAXGOdv8B}!Kd?&9=;Th zZ?T0>!pNhw~u=XF^@oD~|hp)xsTNxkom*x+8 z_=R|U=hpvNf7AG*htF>PxYc{g_|7eVWBvTo%XZ_39)2ty-^#8Z&*=DG{YwvD>NCFC zU-j4TJ@5Y-KhtOW(OUawb?wK&{G+G+Mm+s!Eq-zCi31)z{8Bu=jm=-2zti}mhtF@b zjz7NHMQ5z$W7TN)Kav0G{trF;L_EH&-G8}F$EW#=9=;Nf@9157&p*)@#*ZF;E*{^) z`XBqhH2=}Vx8m_Fto_*kUvb%P`{?0Ew_V2%-^$vL_@z90_(D9sQ)@r!CygI^_^Eh& zYvW`6Nb?^(d@UZ|h4K51M-RUck8kz|{rU6!MGv3dPW3OJW=s6i>o4^1WAXTot^MeK z%A{?Wrv#p9d*;WgJEdiYvAzSWlY z)A*r>Ux>%IG2ZWAqleFqRsG9nV*U5|M-M+1k8fps#4hbWdiYX2zH{Sa{!<=3{7gK) z?EsG+z7db_=#TpI=lgH;@JsRdW|#Ey&(|;X@cA88|MDq}_xs=I;V0tptp<4X@RfLc z8{<9y(ZkQh|HVQ4(8K3< zR{hJT9%vsu{6svy%|QIo!&l<*Ev$ay`c`YoP+ruB;+z7>z}!t&4G zA3+a4`YP4Ge6m08$3M;=Y5VBm3-S1ljlWwAzB?E{dibe$d}|y3W7qhGM-N|%$G5ch z{rrO-ejy&;#_}ijzxU_@K>yLhXLnKk%V%l*e_Y3>>nD2nv3PtJ1Nny@z7&sdYyIC- z|I)+H^cmmcQ~mn~r&;{b!#CnL{dju+`e9G~Tl-6W#&>4zpVGB|K@xxTw4dKq^)H`% zOZzF09)2Po-*zDW=;15z_*Pc`{{A<5__=s|mjmsihi}E>TiE!0{?Wsa?xy;ePiyh_ z`a=(2h{w0I_I>`*!%xNIJN|S(|4z61K@VSx$G6(je!704hhK=tH@k8F{pm>mw0_aU zXLncq%crsVkLMpLj~;$39^cWH_M;E1Kj`60@%Yv@e!qT44?h!+@66UuzyE9dGzoz@%S#R|94(DznOpZ@QrwUvyb=l&(|OH@JsRdj*XA&$8`SC!{_%^ z{nHQQ{rey2;V0tpoeabeJ$xk|-`4Wy42vIn__=s|Yny-HKck0l#p632s6X`Zqx-4; z<a_xo??;TPiZZEXGX`_Jg% zvt0ErpT^=J*DrCfw z(Zg5b@vW@?{`?0${9HV~qrd5&KjZp4jURgWRy@AhWbghrjURgW(fw8b@~Lh9{QEcP z;S2HjPKWAWdibe6<2xUSAA0y&JpIUR{JwsohhK=tx3c*^VU<0*`GX!ldw}Ynehjpa z9)2ty-)bO!=;2H8_%_ymzy3lGKNFAdY@mJg@QrwUOB;XepVRzB55E+TZ}yY@_2Wqv zfAsMASF8TzQ(60d{{cPxL_EHwwf{70A3b~}9^ZOP`(eTQgC2e^9^ZN({^;Rb@%U!1 z=&%2A|0xdIM-M+bUiB}Z!gxP_pocHSYsiX@B3f$@MH1#X4C%sdH>PFm*VlATKf_EIGBI*@H6rF zHkQAB{{%gJBOc$z>gUXL^PBe3!!O0-JKvK3>G=yieEv16fBCf5f4_c54?hu)Z)xY> zc>g#K;)fo-5|3~8b^Y_NpMTK9&&A_g*!=JL{-5;ltv=(M544XSe)J&KzkHf4@lVH( z9=;HdZ)N>|$SQif@k0+k6_4*?pndf4wRn7M%YWa0p@(0H$G5Qf`TaNa@YxBffBBTg zd;Oq?AB)GgGT!qCJ$xx1-~7G(_3J4XfAsJ(@%Sz*esTSu)*pKKMm)atK>yLhFU8~A z4$MD#`24}DfB954et&-fJ^VyGzOC`+Sp3k#SK{$q4)h;A{9HV~*`N34&+p%(hi}E> z+gSWPf6>E_PE`HNr?L9=^ACFXLOi~$weR_l9)2nw-|U&!yndpGuf^k=y|RD)^yhEr z;TPiZ%?H{?51&0m^)H|7CVQVBMhbEMKo36_k8kn5{`~v>NA&Qecznl}KYsrJJ^V~O zzO}XQ^@AS15szh^AFL(j~=G_XB=DNpXM)m_(D9s zGmGDz_kW~^pXxKdjq!f}89jV0o_;KikLQ5^&dU_Qarwu zwIAo73%Wn#KYI9ltooPF+~OCyIN;I4PsHQfTL1m$7omr*#N(TNegFLB>koSPxp;hY z%I8sO2xXD6xtiA>viPHipNq#g|EYfb{Qe_)_*Oi=t*w9S{on5Vp@$zmO7$l2_wyHe_(D9slY#i7ho6eax3Ko(`Q1*EKj`6W@%T=S-*53p55EwPZ)NfK`&a1U zv#(YC%O|(|js5RUlK!KIAB)Gg9Ecx!_)%Iwfgbz-=K$|ipMwmWPknHznZ_@^$R_GEgs);VEpLe7vk})w&ZVgf&C+T`0S@t z|MID^zfBZWKNXMf%y@r)2R(c( z9^c|K{qtYEf0$msqK99I$2a@we*VP#rPtr+;j^Dn{mZAZ{`>O>^zdWx_?BDRj}&12 zK@VSw$G0(l&;5Vt;b;1cZ*KYH@6VuzZ^YA&{Ac>{^Y`D-!!O0-TW#Uf`9lw%|E%g? zKCSUyf9T;S;_+P$%pZFAN<6;B&-Taf*AM97=i>3LjgR?D$B!Pq6_0OY>$g8YL=Qju zpz2>f#lZZdhcCqAJG1)ppMQ%UekvZ{(%Sd^3wrokJihr~_T%sC4|@28czm-D_W9Vq z^y*)F`0PWffBpN!+TY*taZtbL;m6|XM>Q~h^zfy4eCGq}H+uM)czi4Czpr2D;T!Sz z*4BSNf1-z9ipRIK`1|^S9zOp$)xUh2f%ehEPsHQf48#vTd?g;=?A87KyFWie4?h== z?_!{R^zf~Cd|Mm8??2JQkLId>`7{=P-@l`WFT~@UeZ$`UN4kEYho6eaH~&z-{`~xf z9=;ZjZ*J}1Ze4zx`a=)D5RY$ReB^Jh{-uY{eqQyje{Too4?X-?JpCvve|-Oq9=;Th zZ)N<$Z2aiqXX5dlTm6SF4%RR9@QrwU8*AV5A3gk1JiggC_v^>+Kck1we?j#xpThX# z*WKUrA3gj;Jie9j@&0f6{0u#OB_7{q3!lahJ^WlezS+0*$M5gIp@(n9EUaA#&>G%?>YY)ztCs; zQQ7(v_pj6EPv~hs`z6)CeCmPr(Zi3$<6CVR|K*qM)*pKKQarxPf%OMH{7gK)wY4AT zk9dc1Q~%P#H~NfkYx}=bV)DBK9zFb0JpE{_ecwNzhtGdm_0Kr|u7CX(KYt+(+D8vR z5sz;>&^~(jN<6;VP4~Y4k)A)$!_URzTUq~O|D68(JoNCbczj0#?W2bu{fg>eKG}2n z=kJ*Rw0-pOg?M}ymjAJS^v?g%!%y`Y-`v`d`A>g-Cwll=JpEW${Cxh=!!N|+TWo2+ z>%t~~(8FiHs`{5tz9s%Cj~;$39^ca1kLSl}{LsUf;_=Ns)nC8;{R{N)Gx7M2jgR^J z>}9*-M-ShK$G0>-?%$;Oj~;$09^aYqG4^!)=;8AZtNt0sK>X3ePsHQfSo@)igY^SF zd?g;=*3KX2tnm$x9)2z!-{R-`^XK<3(Zjdm@y-AKn%6({@S|T-{SyZpzd!##4_}DK zx3c{8^EZ0?Wgfa4_}GLcl6i&`H$!CDUTk0E*{^h z)oY#p7FB`=N`2_@Reih{v~h=r#ZTF!b=*Z>av|QxB})=;6oW@y+J_{E78H z%^&perFeWxA4wZ=r{;#N%7o`r+pf^zd`>_*TaI`iCCA6_0Ord4K(i`c3l( zJ^bi5RsZs7to?^~e0u$d9=;HdZ!xg{LJvO`k8f`M_xC5!!`I^REsXc;NA&Ou@%Wa; z9~H^d9jqVd;j>2dFQ4pf{rG>)8sG5f;m6|fEsTGt@#x`8@%Uzc)33kSzoqk!9)2bs z-|-ecy1@9+!#Cpbt*rk2`5SuprFeYj1M4q(`24q2|MICUev!X%(0}ys6Y=<#w*Kt- z{-5;ll|JJ;H~y4$^PBe3!_URjkF4#le{ua9??BOi^zf~Cd?&`AZajMU(Qm8%<N5B64{W2J$xx1-{k<09)2bs-~4a;>qp!_xVTF| z;*TD_5szA3gj;Jif&*^vD0S$lq=dj2}IG zB_7|U<$vs7;~6|Wdic3`d@CD&TtCDCj~>1ik8fk+_vatz;YYu#`j^k#+K+R`rCkBj zK6>~x!;k(z^)H{r0FNHN5RdP4Oa7(vj~;$1 z9^d?P{rGwPpog!;<2yAz_CM+GA4Cto5RY$d>;IE&{?Wr{f2jJGPh;)-^9S_sWAXTo zKGQ${>^c8S4`1ptzJ>9A{zMNy6Hh;yE%le?FM9Y!Jib$FKXh?y>fidm)MtE0|J0v< z-+!a0{rrzq|MJOR(?9?C`2#)tL_EIPclCMSzo3V&#N%5S|DbN{Y5t*ypNq%0w)n;Q zHxA;59=;WiZ)x%K>kstsqd!*tGY*Siygzg4!FyYS#{{LsTM#N#`+_#No@IEX)b`0P(q|MX)^{8Ao0{8&7`rSYD> z=;2H8_>OJ-p-bCG4?h!+Z}yA*_{IMBxZ`$ze>-~kMm)Za&7ao~dibSyd`s(p+`o8b zvj0X8pZ}@qUq02A_@z90_=$LYtAXe(2#V@%U!n-LHSY{zVTz7msi8%l-DBv~GUWK6?08Jid+P z|80#&4?p^I)j$2P@%!}?diX*-zLoJlf9T<-;_;mu@6RvM!`I^RZEgI1{e&KVAs*k_ z;_u(zKo6gNLiI17>{t5pcZS6uJ^WZazO9Yl!JEL zzR_p;QQG)@{X|duOY!uhu=?3^{cr8(f1&!Dg9=;NfZ)5GB zVDpb2el8y0iJd>=_eaOU`hy<66_0N*F#qV`N1s&v%V#>kqlYiVr+w{Go?mipO_h{g3^B z9PsGj^S@I46NmPi*FW^|6Y=;q*8jM7`lKiB-v34qUx~*z``&*3`u-I?{9HV~h4Bwr zjed9h=;2%O_%1DfkoSPLOi}R;~(9%pWc5)4?h); zZ(;Ql^?%;M3pVqQ9=;ZjZ)NfG>reFX3-S22Tk7wgN&L{mXU{EGzi%GjvE`rdU(myk z#p7EVe`lM2^zfy4d}qdoE)MDkJ^V~OzOBt)+&@a^4?TP%9^dij`}uPq8t)F;M-RUg zk8inU{?qo+!{_I&(yVEpLe z=i>2QTK|3jhaSEakMD9z{-*7thaWv}9Y1^0;czm;2fBlX6PxA*o{6ajw)xi9rhtHm``X>&?KVdcc-SMM`AB)Gg zw)pw=3wrocJidjEKklEV_ixa{&&1^G6)y z4|@3gJk`H^7RLMY1N86{@%ZLn=&xU^`{$SKwvQgZ5|3|V^XK<((ZkQh<6C^VpZ|XS zi5|WckMGp_e`*)IxCc)B(8G@os{ZBE*!=tc13i2p9^ZD$_`h)3Zu{urr{eL=-rlcY zZy!B;Egs+O$i3gcO7jOj{6ajwmE~`&zv=tW=;5;$sQ%?MH$HS}{L#aY#pBx=@B3f$ z@TGWsN1yHIPpqHm@4rP4KNF8{VZ84@(8D+4@hxor{QJk~;g{m^Z7hEebp22B2R(fL zLe;-~M*q8Czp;L#@kb9o5sz_~yp@^)Gt( zRy@9=f&51gKPpxK@|oNCBYtWAqlYiV<6GPM^^A^BJiev1@A-=!ekmT`VqpB};qz}){nHQYf9&7W z{-cMVh{w0F{E72V%A<#`#N(U2qhJ4i{z4Bw7msgYyx;#s58sN%cWUeR{;vOVkU!|* zM=w(S(~p7pqlYiVZAKUf6SO3z(SNe=^WApFV zzv$uT;^{~6f3}=|x;{|9=;2%O_%=3vj~{yY(S@pie5`)_`V~EVAs*k_)*rwBg&uw? z9^dIe{-cMl#pByr{BPaG?jGF+g!rL{Ux>$dVf`Q3{G*4@UZVP!PxiWg{vXxxanL?` z__26=v(NR{ul*gH<{x_aQarw6<30Z9;b-FUEsc-y$3g$m!#Cpb&EDA`zu*5x55E+T zZ(;mH*UfL*M-QK0r25Cl`X77GG=AveC*tvKjQ8s=^zfBz7>z}()#c7haP_PQq@1>u>AG&FM9YwJigiY_vhc=-$M^S6_0N*&^~(jT0Fkh z!1{q6ejy&;!us#euh7G17pwl|QyCxgmtOy%haZc_x3%@R==eCOKlJdWczhdc-{X%S zekLB@;;R1o-f4qMc2k}D>KM{{_ z{!e{A<}Tg8pog!-<6Bz${{91c__=s|OUr-1enJo5ipO_i{rB|?J^biW)j#8S*foFu z9X)&@9^Y!9|LEbT;_#(%ff?C;J$diaHSe6t_uuU~Qfmfk-@51+kE z^-n*x@X-bG4?X-?Jic@5zd!#$4_}JMw>5r$*LJ%8pogD{$9KLZ{wa?hz7db_=%4%b z6Zw~(ztF=k#p7FS;X8{>{LsVaFIWA`XKK7ZKSB>b5sz|NKKf9T;`@%YZRTtB4W-$xHWdWGs=KCSV4p8rb^U+6Qw^n$qdibSyd<)C}*gxMS{rw-( z!{@J5{nHO?KWgs--5=@~J^V!crXR-p`h_085|3}SrT=OEpogD}$G0)w*B|uot$2JJ z>%Y$*dic?+RR8kHzOBFh?AiZI4`1jrzS)(1-oHPJ9)2pGe&hq~qld4>;_+Qr{QUkQdibSyd<&a@-~XbA&tI+jmrrB;kLQo+{vAF1L_EF|i@(nw zdiY8_zLoJlf9T=o;_;mu@B2UW@U3`!vmfl&pFcl94?p^5)xUfSlwgdHx9=;ZjZ)NTK`5Qg_LOi~ejX(DPY5&o~XWydwmrwrh{r%7C`C;e5 z`3F7xSUkS9_5W5K8wWgk_)9^cmZsQ+^k9zA@1nd)CY%Ypns4?hu)Z}$5B_&tBn!&l<*ZLNO&{cH5_bMg4* z*1qrm(8IUl@g04kfBx|OCwlnN<*I-A6voH?;WNqp3q5=x9^a|)p^Jn3MGrp}k8f?f zzkh-rz7~(~!gzoG6FvMwJidj+|LCsopGoo$J$&{W)xUg7<9+{x9)2ty-^T7A`STa_ z@TGWs^WW&tzu&(@4?h!+Z#BT9hi}B=TMdjKJ^WHUzS+&L`TZ^Q@cFl@{^e6_S-;Zt z2R-~mJie9j53u=14_}GLw;hNddic3`d~1uJ?|;z4x8m^~4a5&U{OGl+fB7^ve&7G0 zhcCqATYR*ie`iJUcgLpwrH7yDGrrBh_|e1H;^{}eb^N=({|r6+LOj0N5BJyq*#D&K zAA0!gb*g{))HeQeR-@k?KYIAFcznlO`@hShhcCtBoBi*8{C)q59)2bs-(sMB^ze;% zd|R78KYyZ!Uy8?fZ2jNg#qXHp{DU4o|2EY>ad<<2{`~xj9)2Po-_qLm^Cx=vN<6+Z z58sN%cWHc_Khyk04?lXn>Ys7^Yd?Sd{D~gE5RY$e@sIOo z9P}SO{8T)?h4Fs=L=Rt!$2a@Ue*gXZ@95zd;_)qwKeOxmG2I7*_)0v!R&$fmhq=NdiX*-zSDv6qlcf0$G5QY`}TThfBgG9KAk`G@Kf>l<~Dx+{ycj4T0Fk%IvHbP- z*U-afSE&Bwll^Fa{`~zL^zdWx_%;LmM-N|$$G5ipi|el=lKDdqKNF8{Vf~NyN7MO3 z58sH#x7afOoy8{q(ZesryeW8?Sxzv$sdZ&m%vC;RPw{XW&=haSEVk8f%5+q3_d z9)7CN_>TUgfB*b6Yacy)EuMa4Ki025fBzjl{6ajw?ZEt@htJ-o`llb(zULo$__26= zE92w*83*}~9=;ThZ)3c#Kj`6S;_=OXydOX3(Ze_5@hyz^{-cLqipRGy-uHj#;q&iM z{mZ8@-mhQK!%xKHTU-74^)Gt(N<6-$D$a7dic3`d@HLTfBu6Wz7>z}+}c0g z+D8vR`cBoqe6s)BufO>ILmcEEdiX*-z7yjgx5hU-dibe$e6zZrf1W?+;cM~u)&uRM zhhK=tw;qT;did4z!ORek>l}V%d-X0gE4c_)lR>u4Kj~>1jk8d-;qlaIJ$2a?l{`kHB=;5>PQT@v&xA^(< z8}#sF@%U!h-sfNG`=jXLOY!&?*1pdldia@me8-l*@%uZ|_R+&P;_)r5{i8ZQ%|G<; zOY!)Y*1q3=Ko6gPuj(HkiBa{T=l1m3VxY#;@MrIpVb$>lb?Xxp;hw zf&4=c--^e#GT!eWqK6;NRR8j6w(#lthaSEVk8k$wz4dd&Wl8-@4?opsd<)}!|BN2K z7EeF&fA6oqasN1NA3gj+JiZg-WBy_f!u+9!&)%;3mrrH=5B6a9Kk(?`$Kvs=to`VJ z`t#$_!{2i))`4q;-^RIOMLJvO?k8fq`*KIpK4(1O%d?g;=#^yirH|;-q__=s|v-kAt z$MYXOd@CN`Vt_{vKl(n^zkF&Ne_X$({YMX9h{v}vUi-%*i646Ssd#+H|JmRF#{M;( zKlJdmczmZe|9<_39)2Mn-^$__=l`^Q^zhj`RsZs-t^Hu*VEpLe$KvrF+4=v-HNN4| z!8^7;A(Zgr&QvJ&(`^kR($Mf$r|Iova#p9d*SAYHU`=99HOY!&?1Mx!- zKNFAd)Y|v^2k7A&@%T2zKc*Xhx_+RCUy8?f^u_-8y?ylX`IV}F`4kp^zkWmyKM{{_ zY4MBmf7*Za@RfLcE8}l(JbL)KczjFCzqtO2gZe`c--^d~X1ss@6+Qgu2UY*_X}0j` z_|d}`;_+P?AN^1BA3gk3JifKXFX}(#(Zko`@vUtB{rU$z{6ajwrRCo#);@ap?1xnU z@|hbS&rj3-qlX`h$2a>@KmW(ZqlYiW<68`@f9T<7;_WJc@ZSFV8`ocH|Ix!w#N(U&ZomEb`2%VD=;15z z_%@cme*Y9b{9HV~6B~c*U(^1hhi}E>+gkgve^2udJ^biLRR8p2Oa9!W>j3KydiX*- zzLoXg*B|uoQ}OstEdS&D5eMy~hp)xsTMW!UdiaHSd`p}Ec>g1fAA0!gM^*pwsjdI< z{3D$|^zdWx_*T|`uOIaArFeWB>woM&)BdA}pNYpe|GmBWpY|U;d?Oy;#`+)YZ`wY3 z_@#J!=axUwc3OYv;qxC;{mZAa{`>bI(8Eu}_^goRsdic3` zeA|Kkqla(B<68{$A3gl&$5sFG8U1H}{-b`={-cL4#N%81exHx^Go63*@Kf>lR@Q&d zAN26Gcznxk>sQwY)(`aX3-S0CHvTyO!~u^UKC4y#@@cI9asMWbAA0z)czkP%pTEC} z9=;ThZ}z5s{`&P3dia@me6xLLu701vYS7*P`1{l7;T!Szmd2mid8G4?9)2kv-^Tc8 zKkk7LfAsMAPpJOov$XX$_Fr+pqlce}$9HP;@83T|4_}GLxA^b={_WB0<~Qx5ho6hb zcV_%!jYkjPipRIz!l(I%9)9$0)xUhkU+(wcufNd47vk})jF0}O?W2dEipMv5e?NbH z{Y4L7i^sPxKHmRH+eZ(-5RdP|`XBp`3p)ey2R(fD9@W2mDr-ObpXNV$__26=^PRo% zPkHq4rFeXEtN+#hGwDBi_?dWoi*0;22F8ybz7db_)cWuFj~;$09^dJf^}B0+(>{9m z{3lia^2v|ruU}6NxI5@SdiaTWd@JMQ{%3ms8$Em_9^cmZcz-Ui6H@ ze?Sl4ipRIH`1}4DJ^bjss(<;^w*Kw6{-cL4#N%69{>1qw9Y1>bsd#*=f%!)dUyH}L zviAM?4SM*6czhQ&et-Ur9zJ`Y>R&#!&0oBKl8zre{8&7`we|lN9iRUE9`x{~czj3u zPVJq)Pwx11{X!2v6OV6c{3AO)4(bOzd?Oy;?8g24jq`sT@aW-};_;nZ`_cb6;L*e9 z?^pd3hyUvDKkw7AY5dW{PsHP!9np_p)K9wpqKB`<<2x}v?%$^Eqlcf1$G5Tbhu^_*T~bp8db{@U1@MTUz_~?FRqD-5=@?J^bir zRR8js86WRYrRyJh_(D9s^}zh2ho6eax3Tlztz+`KgZ`t3uf^lrSpV<6#y32A_=R|U zTWkNQj=xvZK6?1_|B)RV z2RwTCnRtA&H}|i<;`x30{t_~tk1uRpQ> zO4~;d--^d~V)+yI@6z_s!;e0s`j^jQOZ?LOLl0kw$G5co-&tMzY5t&xpNhw~u=qW= z%ZT> zL=T_ORsZst+x+|cU+Cc{;_+Q>i+_?o=;15z_-4=V*T2UPJ^WlezN4G=>;GhnKYI99 zJidjs@B1h8@S~qs{mZAd_{H8g4)PB@d?6m+a-jd{;iuy9og44JKMOs4Egs+O$bS4{ z{k-4>yY+`2ejy&;?B;vlzmFPb{OIAcUr_zar?U9__Ycv-kHzEL*!p=!*LJ#pKo4Jv z$9MFl{{F$AU!aGdiN`m;Nk4y|+_fJE<3|tQh{v}w{%LD`!=r~^ipRIwQvYfE(ZlDz zsQQ=BXv_Si{YMW!5s&Z0@+aQENO|<|m3Vv`oBz1~`;v?E&G^y7&&A_gTl=SW{ELs< z&0qBJt$2J3n}5IlKo39qCDp%trpE87f9c^1ea3fb{g3OHGCyuJe)RBD@${qKGXH7( z(Zko`@hxuFuYaFE^zaMu_|^mCM-QL9^cBw@9!U?ho6hbcV_t;?~kPYM-ShM$G5Te~8#_#iw9)2ty-)ewI4_}JMw=v%Lf9T<7;_=O1 z(2u|K=;0gj_?BDZpT-Y8{8Bu=*?;%RTRNPmAldiaTWe5YIb ze`#mH`hy<65|3|g>yNMB=;7z$@f{D0A3c049^cm155ND79)5J&b^P$HZ2W%z2t9lu z9^b;oALoxah#z|Rsd#*AtN*8W?4{4%<_=ZOhUy8@Kvh!c8eR0q}dia@md>0n~SpW0n`V&2TBOc$}#vk<; z_rPc$J^WHUzOCg?ygv~KJbL*2j;eq8KYUQ_$_#rhuyJbL(vczlcOn(Gfed?g;= zV$1jsChen#pNq%0wfL_(pYZ76Tk-g255MN$--jN4G*bN&hk^Fd!x!T5Ep7Z>f9T<- z;_=t|Pf2Q$A58sH#x3T`m`k(UX;g{m^9SyXP9zMUb>R&#U z#Xp{(rtPDLpNPjdzeRukJ^#?dSK{%_t^dA%Mh`z1k8d+Df9T;`@%UB){YMW!`YP4G zd>T7{#QlRbe(2!~@%Xj_{YMW!6_4-O;-}_!>tA~KTA%UFUf7>Me}0G_ej%QI6vq4b z(ZgqVQT@wjK9GOt;m6|fZH@Q)ujt`R@%WB**8L%F_tk%}exiq;iO07Xh(CJxMm)aR zTl@Q;W37Gk@JsRd=EleOXXBv%=;8Cbs{Z9u+5E-*_c-9u!%xKHTUh&X{z`v-40`xV zJig@?K5ZX8{9HV~)c}tkz7>yeJ;0-fAKgv$FP~l}!s<74DUTk$6pwFZ?Z@{& zQyxA1Ogz4|@xFgT58sH#x3%++|NIN|@JsRdjz;xA%oE4%Q#^@N@C_*2eqwCwll+Jid*sfBya>dic>jRR8j6 zEq-@ccYo7=^zemvd>7V#KYyWzpNhvf`?Y@kd;X$_uf^k=J*dxn`{>~p;_)p9<{v$L zc2Cv6d~)l*uV3il$KvrF5A+{Bd?_B^!rJ%y59r}%;_=POe*8|b`9}}mh{w0I{>S@| zaghJ$;g{m^Ev$WieuN%AznAJ?K2w`N-+!ZrpNPk|wD|e@haSEXk8g3ye*FCU4L$r^ zJifK@e*J+Sz7>yec2vLpxPKl8@kb9oy0_{dAB+D3*7$};4_}DKw;EW#(Zf&0<68~H zA3c069^cC5U)|sIA3gj+Jig7q_|d~>_fh@JCp*6%e}DfAJ^WZazO{}2juwCP@TGWs zX9MF$4?h!+Z(;rS`a=)jh{v}w-uK_=;g{m^o!RlY9=;WiZ+>(?|9t%D;YasV{mW-z_3Q87p@%QT zX3e*W&S=TKkW+_R+&H#N*po{yxZf^zd1(`j<~*?fd(~ z=;6oW@y$NcpFht(^zfy4d`GwF$KT(7LJvO^k8k#k{q}wRLJ!}F$2YhB`}I3|_@#J! z8>|1&#liUtJ$!zg>R&#U<-gy*MGrp_k8ff9_x&$=_)0v!OY6Vie?bpF7msg#LO=fd zSEJt@KYI99JihaR^#?ut=>DpI`4l$)zW+lHUx>%IwET-_e{nE>=;5d0@txTClgI!rFeWx%iq=a z|C9Kkho6bZx42b5|NQzRf`Xp@(0J$G5ij&sxp??);;N&%avrFQ3Ig`{>~( z;_EY-4jBj>KpFh*aj~>1iPd{qwzn?$Q!;g+v{mZ8@ z-mibq!x!T5Ev^5){-TGUipRGx-t!MVd@UZ|!s5T@`#;jdFZ3DTc3}MI;j;&-{^ipS z^xFn;v#`PZoa<+Cu}uOHCEPsHP!o!GBGfBz6Yd?g;={MLQme|`sg__=s|v#a{N z*DrebRy@A>0FNGi^dQy0e6m~i_mBSmAbR*hJigg2ule~gdibe$d?(hv?_bfw*W&Rl zZ2Z1{p@(0H$G5Wi^Xo74@YxBffBB3pfA+7kcQ=30!;i(|TMqOeJ$xx1-_bz)(ZkQg z<6Bz)egB0Xz7db_%=pm7LH(kKUy8@Kvhn-=1wDNJVAa2T8e4z-`&a1UC*tv~2l5X+ zd?g;=*7C>qFX-Xt;_>z`jgqKB`=lRu+F>ztO|j;_Dv;K>yLh zm*VlATm06o@3xN~ekLB@#@hGw3q5=z9^ca9=jU(q@JsRd&MbZhGyvj<9zK7h>R&#s z_5bF^qlce}$F~`XAA0yoJie{<-+zA(dic3`eCJmGzJ8;JZ^h#~KDwWO{{3O}@S{hm z{^iqJ`=N`2_@jp}#N#`9Xup2^{tJ5esd#(~%IvHbPt zr|99cuT}lar?U8;ybj+ce(2%H;_+P!V{6svy*+={B`~Cqvd?g;=spYTVKSU2d z7mx44^2hJLp@(n9aXAa{1iQWDIVX2 zweQcL(8JHf<6GJK`4C&b(8D+4@hvU>asG{G2%JCA!!O0-JK7Telt&MrpQ8FF4iD?+ zPnW3J>pyz35+Whz7UV^%y>V4qlcf0$F~^hKYI9DJid*!A7fAZj~;#@ z9^a+$zJ8;J&rVbQ%crvZ_v;_@@MH1#Rs-Wl4_}JMH-C74{(b(?!_UOyJ2Bqp4?TP% z9^c0L@9PJ8_@#J!D{J594?TQ-y6Rs(^_KXj`HvocA|BuD!hZaG|A-#G5|3}bW&P?> zaI^lQho6hbx3T`m{v*v_^zf~CeCHNF|Na1a_|aoj|MF?AeZPN!9=;HdZ)@%Q`42t( zR6M?g#s90j@u%~L9=;Zj@7UrW`=69Y55EwPZ}yx0`H%fi8h`Zg*<)4z@+ocq;@@9K z4?h-;_1hk8d>)KlJc3@%UC2 zzu3Q|{YMYqh{t!frTri7JXn9w!!O0-+uHbJ|C{C?dieYas(<<9C-vt))~_^w(8Eu} zvl_=-G z_x$hOci+3OY9ysT4$(lJ|J-xWJ?GqWceX$2i61GRe8*n~1DxPu-z4AY5#ZToYJ@IFXC*S%^UjDltp7g}m@2USQpP{EeKmL)P z_(jE&@6fX!fBum4#J3esz9SF+yF`B1|42{#iQ>t3G$DSFp7@dC$@k2wzd!yYJ@My? zC*S%9^ZLjA^=|$_dg9|%^?&7aRwBQf|B;^fb;XnKsTV&Mz4j+P@dL$^@7UA7-~W)F z_*2D`Z`-rK+g|&Tp7^oi$+!NO^7`}3Cq3~qYwG{XXI!E`s37%!r6)eo-^q96$?xx< zAwBU&il-d$zn_=?BcA?APyA5v2e)*&){!H=YJM!W`<`3{;{Yg)J{l5CY@>%rk z*Iz#%J@Jc*C*S&C&(|OKm*vL)N>6-Se<$Dieje}JFX@RtQ9R{nd-D6^XVMctQat&_ zp8b8U$lq^#Ak`n~i9c67`JPX(KhhH)zpVaGJ$!C){kGqDJ}sa0#IGx!d=pQ8KmR2? z@dL$^?@USguKkdn_*2D`@4DB1IRE9oze#%H$BHN4#IqlaKV3ZOiJ$qX`oHoy@!H=X zKaigIMDgT1_WZAK{!i(NKhodHH~A0p_M3?O4_gOm`;ngbq2ejW(9_>bP`-TVzoaMr zO!4G9^6HQLt0MzA;z>_@eO>)u`LsRz!Tj%~OPT$Vp7=$@lkdQ5Ka3yT_9H#Lq;>maD*{{EUm-NJ+D4u*r9v<<_)j#QpA1R)E$0c}If21e= zT=C>P_VkDOcei}f6CZy<{a^VcUi%||`guqHq$hq|@#GtSVZQzS@gM1lA1I!DlM?%P z<0t8fKUF;Wo_O~6VJJ^Nv_H}lKUO^X4!rtf{=&6?(i1=Piu%9u8GGf!{$2f(p7=!Z zp8hd^&~IEy@uVkysCe=ndG$y9z=!3Np7=Axlkeg| zUVcCRlAiebA5i~SJ_8Sr`7>94q$hq+@#I_ov3&Wy|B;^fw&KZmy~O_9@<~tpiQ>t( zU4p-K>A6&Yq$hr)c=AoW_AjjeD?Rb&`aAg^m6Y$cAL)sY8|wec=g2D`^AB$SM|$Gd z6;HlH5C27i?;d3KLwe!|iYMQ(XTQH+@UH)np7>M6lW**`|L3Ff@}d2bp7^oi$v62u zdHccsk#Bb5AL)soc~$*i`PBbr9`E}P>4{GiPrhfK{rmYh>4`s5JozSG`TqPb>4_gI zo_x=|_Vef8NKgEk;>mYdqCZ#vq$j@KRR32#_5UcZKfnJVJ@Jc*C*S&q^LW^wn}3m> z__pH7chSS6|8(t-^u(Vio_rI}{&0V>o4=8s_>tntx9!y*;|DkXke>K+#glK_lOOjl z^&2mw_D_1^;|=wH%Hhe6^}~0(EAt=H6Thx_@*Q~g=i5K&i61DQeB)le{XQ(^<3s-? zJ@KcCC*Oe=|3vhh{zy;!Sn=e0;^9&Dj8lKo6F;-5{;zySUi;zwz2D>DNl$#Dc=A2+ z>i=b){G=!TNb%$w|Hpa#`Qty*6F*cu`3^k%ij@CTpOfjI^u(Vjo_tSA?C*=5`jejc z`j+}X_289{{NtntcjUGIH7Wn6o&JaP#Gfmke9yi5!~Z|*luvr%{$#+zuKNnAW;!hP%zQYp#6%o?-L3-lHiYMQZ7r$_R{+6RZ z(i1flLF{E_0xcj&d>Ex~`>!IPf&q2kGR z;K`5qA6NgRC;m+F#glL1>F;+6{;M54>4_gGo_y<1<;%zX_18Ff(i4BGc=BzR zl>c=Op7g|z6;Hlr6WWjT#Lslp|CLYT=^y#yH#p^!p7=!ZeO z!+iT;{>arI>4`sAJo%2i`osTRJn4y#UsM059G?Fne|7PsCw^V=4{%dJo(Oe?I*66(?98nZ!4aBPrUj=|C>(yB|Y&ciYMQZhe!VH zwm<2KA1R)E&pkZ$zq)wR6MwFF@{OYwz)CyFQEfhWK3f21e=Nb%%*>fsCiuk^$Z^>^|ePuM?5dg9L%PdP?j|AG03 zgIYHKO?u+%`|AJ7C!WpQ?;4C(KGYxSiC_@Tk+&O@XE*d7ax{S zdg4zMPrhRhkMWml|D-2=q=*Xm zZ+vN5f6^1bu6XjDxt`a*zkWe_;s=T+-+@=YzkieT#Gfjjd=syH#7}qqi}b{g6;Hm& zg}nUO|LV>klb-mQ1NDF9bK=<_;wL_|AJP+_D4u+WUin!6aN|Gei9b?2`PQG#%kS?W zB0cd##glK_!~6b6dg9L%Prf4$kNInSSbx$JU+<~^E1!Xvzx`gpy6b18Cw@`!m~Yk;~(jXA1I!D&piD>|L*z)>4`s8Jo(m_^Yyp> zpY0zbJ@I43lkccR{~|(azoaLA=1~1#`HV~S=hmO}#3za;-{e2Z%kQ@z>4`s5Jo&au z^zX_~dg6zQC*Pr0KH`rnKk11-Q#|=DdiwYCFVYiVf296TJ$U-}^Doj9zo>Zft^d`$ z{%rpBd(-wKJ@IYDlW*+d{r-pa#GfdheA{0Ak$>gF?xQenF{FU^?uPdH>6HkAB`;ngbf#S(`@P_#?%W zZ+s(fKVKyByZs00i61JSeAhiZ+P@|LvHvDL@n?!B-+_n6_{A-s^u*VX)&G^xprrj; z&iH}!#4jqId{4ddBPkyr%1?UY+lnXOv6sJn$ih=R>4`s4Jo%2i_Wy|BUHc(D@gv2P z@7R;SF#oUg#GmW$NB-gBNl*Nl;>q{S zlOOiu;z>_@{Zs1y%BP;>^%n^qANnupiC-m`7V0pKP_duc+wMp zqImKhm*~&Mlb-mI;>q`PLi>@P_;baRZ`+d}`ghAGJ@N5d>i^{9;o(1@=gfbSp7?de zlkd1h|H2||KhhIFP(1mLyz-wBtZP4{C;n9Nzs%iFI%ekMKfiQ>uk+^fIeexxVi^1T-IE{tpWX6FPyC|d$#>}KAN!YFJn4yV zE1rDMO4{GWlb-k!#gp&AlOOGe591fkDh^pE!YZYTdF zJ@N5Zs{d0C50Cc4hw_u2_;tmT@5r0KnG@^>o%lg|;s=T+-}wPr--nPkQ3d6i>cwul@Y}tE4Bs{s-0n zmCtBG{3bo|i;5@Tp;v$GUv>3Qdg9xPC*SiD`*H1$^u(Vio_vqI_AB_m(i1<@-^q9A z;UkgXEuZwnpDUhnjJ*2$@tgF-$6u}fuY3}({c(QMEuZwnuPdH>&pi2&Ke_rRJ@Es@ zlkdp0ALO6=j{lOL_*2D`Z~Vo1`^En84?6x!dg8~5C*OgG$Naxrf6@~_^M};`$;TT% zEDIhV`VZ-ePZUqSW3PPF|6AXY;Ym;Yk>bgB;I-ce1n=sf^u!MpPrk`~UVr}nVbT+S zrg-wLe|~=d#Ji+?SAV1@zWz1p|H`NSk$m~S|B#;eMa7fvqKEhQUyz>ow&KaR?cp(h z;mS{X;!hM$z9$~u@4rb;{7CWSJM{FA{PCCHnYBOZi9c67`PMJy_2=6!>4}fOR{dZ3 zj6C}(_`lK+j?{_TuO7hVb&C|B{~N&wQQwzw)X7cwYa=pIrMPJ@JX+$+!Mfc|7tbd{{o|i9b?2 z`JQ?4=YtlW;z>{ZQ1Rs3F0miCe9{wtrg-v=C$vB5iLVdT|CLXCGhcr{egAeV8^u)(sul~<^d|7e)?BYpJ{JP@Fcd?}XUHM5*{6O*Kd*sRQub-2i_*2D` z@4#z+zyBaT@ngl4Z`*4>zx_#1{LCL#|0f?0kNn%!AL)rt6i>cG50CXL7f*WPj}%Y7 zqZ0ph^-p@@hl(fPQ%`^BKi%?4PyCtU$u}u!e-}@B;_Kg_{!cx4<@@bNdg2!qPrfs^ z^7ildzoaL=t$6YsdHVO)k4R7aiQ>sOUdWe^^*guzq$hr)c=8>1{_n?s(i4BKc=8>1 zmY7A^wn__*2D`Z}R@U z{#QNuNl*M(@#H)7@W{Vh{~D@ z_V4=->4_gIo_voyyx)J4p7=AxlkeE`A3uJQp7{DVtN$yX`p@R|=g%LKp7=$@lkdp$ zAHV-3J@IYDlW*H=KmYtO>4`s4Jo(no^76mmvp>=kKTU4Nl$$JkE;JGpZe{*{C@sHdg2!q zPriw#e?R_^p7^%n$+zv{{rsKu#Gfdhd>1|Wk$>RB_9H#Nz-vFOAG`V^J@My? zC*RWv{!4n|<3FbUPd)r}UjH~hgAe5=J@M;`C*MJd{kVA26F*Qq`3^k&zt5DOl}~!& zPZdwTZBPFN|5tkA$ND?@o_P33%6Iiodg5pPxca~H8G7;;{9oybPxN>49eeHX=P#ru z{z&nZBl+cg`}y&M^u!MpPrfG;+K=?apDCVvhaO&=FSQ@i6JP&~`oHoSdHVYTul-3+ z{G#H?cjUF7-~Oa0zO8ujt-q1i-wm&P(i4B8c=8>4^8XGGPkQ1zplTNZ~a&D`h)$t{zH1=2a2a01F!ym z{2@K@r-~=v_)flj|NIQ;i61MTeCwahhH+b27sNNoi%o~F8_|d;YPY|1K+K+JH4p4 zdC=MKN1NTfezUXJi<;4k%Di>7-#zF{Dc$X8_4jughE1FyX1-j=X`*xG9yH2VS&zWWE=&DPf8L376xvDNH1d#%0{l6}$8 zKQ>a}s|&Sl_zLPfZL|^xM&m!`9A1w9>cY_IfQ*)6P!RYwff)`>icpehhg~=Ey6vyYWe(=|!Er zsNZg-y6tU>7NS^`07k8&POsnDdl;qE+tFTE2+%%S$lOA-CJZP$%S5}5Jv|F*`*3IH z7>&B!c_`XNO&)cc(Y2c^Qo)CZyRE%`&(vtMxu-m(r2VEe3@Cet(jaKA&F;=lr`Lgn z**c=U zt|)mkYDwMkFCi3*=!kXnJ59dlh4O}8d14#;Ad+T)-HE0y_WFjEHsr=}^lJa0v)k&m zUybe>4?!Cr?z9%7Rgnee*6a(##$jKW^bR-MQL~q};o|doyD?m&-DXdu7M=7C54M|| zt!Vq8vuUJ;4mVoSfqdEB?Yz<2GP*w8>xgu_qLH302^AE{di$--&i1i1H`_3lI-Yqx z-vqmdEofx7v)9=@+%;wIHjm7|A2oLlTfK$M?_=K&-hK7wVUw5}seeAQH(#Ec7?y}_gaTrT??SBqQ|)f>JD=U?Lz&eF1Ecd+A3}Cpz%6; z?bbmDwkJNfeYj^@uesAPmL!TsfoY&iJ#E3%4Y6j?*RjSL^q=+bzLtxvAL|}Qu#1C3 zI6nN?##xC2yN5gd&OTyG^SF1p_HNTou=9~ukLFx-y>lSpLtI&KS))8yYaR8Y<*klH z(O05=b0hkcZ4K05tF_&f5+XRWxFuRDb_2njsSob_IQfaIIhmvAxrOLjcmLRvxZjnq z{or=%afEVTF}5RJPF&0lu;2y%I?P z=!?Be;KEn^?misOQ28nrgJX=J`9MBCY|NpwJrp1<-q{nK?@5HwI>o)_Be7_7B%&=> zQFClI4aM51X+vEl3kzycj)D z2?>*8OdYSFJkK^Zb9EF}xjL%(h3et-j{{G4QS>(JA%1DgZdBJr%Y@%1zTdw4@ZHcW z)@>JmGVcSc?e1e^0PWV!ek46euW6&O>%_6Ixw*@=oz@(9E}}dy7Pxi1xG`npTx^@R zfQ$oA#>xBwN>ZNC$$CL2w!eV<15f^-PBbD#alrybAy)qPg5SM-Y|P2uu3d!QAXD3u ziMi|3@?HJg>=;1)X>#K2gYItBXlx($4-Z<6M%39wS|R?o*F`EIUXb;TM;>41i14fA zTk9wpQqyH9Wk0k9nIFNWG{<|q%q_Ge69f|A+@sdgQI$JF!8%Wb7kf?s} zItJ=km+}UlERr@|u6^3d3SA8gx{6r0js0V*t1lF~MNc2Cqs^A2@he6R%SPH}4`R!} z0%gw#W>muaz|_`(NiqU@=w|5YCeqJrE~RoR8a*R2J|hWPUpnx^y{)IByE`pW*u2^o4jxJ$)@vCZJ}Go@IbCb- za5tq%%4xd2TH|%J1Nu5TpWpq#GPmP~x7_Ig_8FhFh}T2O&k_m1Z!5!&p}%MeU* zcj@isqnnad&qsGmhu7ShH<`)G9r<}EnbmxBe@{XHUNuBr;4dd-@*VB&EJ(`Ef{D^1aoSJGU=eZN-wY%p+}?i zvri3=PC^$qw?26&`I|IfaV$DllaVL*qQ8rOD&Hpy+q+pZi^Q;)rI$`i)V}h=l=aBt zdFTGx-TP~e>nryzM>0N>n!}tIKH2T;#ogY*!&ZOu@m4%HAI+xI9lcrkP39|Jo0Sa% z;0qf$_iW_Wo$JdtGX>K?ABcKikwR|EsNP^<`|+R4$Gc)ZvssXm0bBJPNzLZR@Z+)P z$2V5)i7~7$FJHfmW*4#S-SrVxs4<>>Uc95Zt+!Cp)giNg^4Rbsp|@WxnchTSi}6FB3M*1kU@@ z$s4z(k6JQB*-odGq$s0D>Go@{TN zd-8pvhj(i0v5>d`J%dN$@o?(hlYyp8yI_DOV*p9}?DP+MePczY9#@3N%$XNIw4dl* zj%J~g=2mkyT3U)`x0|lMQSW$nqq`%H zx6|2s4O2QYGa^%2n+GkK2(;5Mm@G*ZE}2%p)s#7+Z5fU4%M6_Kv8Jzp{Ulx;S3h>^ z=F07lG?v%bmhauZdb6=6|GIx~SwhH0x4R?evnE1V`$Hdn%TgQ9NT?FoIPF8Fq4Y9^C z#Yl|45UcBdKCiC}nJuP{jA`%A?r!&y$rX?fb^4ML?LE_nZ65B++@;v2Or`F(k9(a> z8RqOg6roHR80Xa2@^NTY)VFdiHM$$k9ZAslwo;ke1(~e+5HC`@+iJ-mqkn8{P$w|m zKVf#*{m%TZ{l^QC>3j1st=wL|w+1^|UR_%eqmgthZ>(M!wbx&N3U+W^c%6D}Q^w0T zUK4SRu^B6S@FkZn851)R~AmT%=9Hj<8w8e4m{b6F&^>! z!lhTT@!6T5b9}^>fw61+-JYE}9m#90V@a?j)8~@-`rpt11Hsq4|7~95m;6Eq7Mu>4X=UUJ{1FwDXJ*RrO z{saqPA|ewFX+kb*5@v1zg3alffANE|b?6_hm38S&)?jwlFR!tGU~i@fB+&(aSE=A=t>| z4d)noGA>$>MI)Igx{3k{U8Dd{EONje&}OlxOYmfyLD!4k_ci$**hTqnRMMU>HRGIJ zS+|p(?Qjzrl_)U3@@dy}%>t;cA8dWmvp>jU$36G%+!4>!JZ84`o!{7n4A9AXiB4X; zy1IP(>aFF5SPxOzC@kYB!!Fa0EQpD7?1fmBd{5pFAcxD-1k{_2Yj|4vL36dFG-;m_82-)gEY}1yB{5+q?)5|C`*7>4EF?Oxius8gn zmtl!s@<7o^I`Z(P&r?bf=`cb{F*bEY%1C~uXyYkTbD)W;k$zlO26vzx*a>uVQo%P% zAA>TpWD%P=Yo?p)!hc-FKas)iZ5h^061?9&+}+rd@gyYQG5s=pF!6m*{)T!*^0Qsy zGZ&&Y>4Id5P8N)_i5_tV2X|6}6N+qxL7nZng)hT36sA1LvhK?wz5!X@C*Q?hegwa{ zf*HvLS+jm!GIH7Y0otd9c2rWn4bIDEd&mtlMIIaUvamo$1MHK6O-jl^S&Uog2kPHj z^kL8>viu?|THuSWMgyd13XA$?2?d?D%+5<+(Z!sfU14K@`r zFgO=o{1C$7Wux==3ZG#>kKjdJ-W9rbzz#rnUzS|hQ?sp@fo^sWWFla{ySIhT(;A1d z3%gwg>BE8S&@u9S0_D7rU%Lf=eqLo=WS2wdVcU#0?4+ew7iL@bHg^tnouRpp5fAn? z$VL!5`yv@4=8hJk`yvi=9poRQin__(lTBG3P&)-URtV>9d6-IL7(CUw_+MViIMy}5Ms&(aoZk;zrjj-x5s5jHg_ z*p$^h^hFoXL(?bD5Af(*tHLt!sR6>Tc(2)km` zqM%+36)lDIW%mCyy00x^KFsP1zI5XIlE{W~;Y*{6axX;7rf;@;f*3i|&0X*)R8c!n z>r1es(+WEh8#1a)`!B0n3@g)iNh)*-y~^V7LU+Hn@OXDYr(t!d8rP0cFUT;ikO4gK zVf!rcA7T{1!!`yJWB`7%-P(Ljing0Bm&|++u;ekCf`=3>$!lZ7?v*7EyIufZ_3sbc z7i7SPJer%Y9qyBb^dZ#6%y&%Xmykm?P(Eyt1@X!Bc$sYLjQgRWI!F9O^?Tbf$-E82Gi@Hd9c}*y&@?K6Khb1`k$V< z9XI+%DL$29G`$S!S0<3mOPDfo%Gl!%Ol^-%SGzB+A-#Fag6c7Cv@9g-&f=D>du2 zt$r?9y_h+&DP-{RQY9P!keq)>=3!coQ7PyM{qxM3DuHtnMF!67;*3qIN*VDo){xg%~ zn^je7OB*h=>A@6o=(wvP;dN(A&K9`kBbOV!4IWL*8DQ<0Oaza5n4Iv3C+nB8^xDn+ zmMkQc@kyrOBjacprZzTYS+m!`psYlm!4!NbPgBka*nN)~Bi3v5cKGbLW?aHcD zWApIfk!t{`9~dUn@{xAm#^(A|MOi;Pn3l)(PP6YxLODiL@IV_qYBdfY<&4Mn)y9^8 zbh1tkd##4fk~ZvWKE2cG7Hu<_qHW}Oi=0(ClnS*{2B?dPGgHc8*OD68Um!dD?Qsz@ z125ERFeNWd${W%LVT3?7#$HgT(<$m?`oN9jh8eeM8UZ;F+fS$W1FcqHR&#rHzEXON zwDZyVm7A#B6k~9W?O~p-pGh=0=p2ck+5H)iyZ(2l?vot(LZ;v(wqd+>1=-mzMT}*j#%Gy;a%$Xo3uoqulOmX0It^IGI9*D!Uy`i>KW>^EKyFU_(BK zcB~&vXFF+UklLRe%b}l7rsPp-e|nY%J`n%klYJ0%X>C1}R4$7hCfAr!22Cj+9>^kO zmJU8;_79kGhW24iT{P1DQFw4i*r>v9g3*MEL^<3@)oeZYLA3n-sP2MymR#FeU zuJ7m+`0wG8j^%s9`qD5r-%BC-VP5o3b{y5i~h#wr9W9OCbv<=$lf`b7t^HJ z@wa4(_9^T0(6&cYV6l8+Zk|}0y?TG`PTE(auZbu2HT#FCFKCkrTDhm7#l3QCpdD7* zoIOAHGLGY$Q+M(9>9UByfZu6>pIzUdk?-089b7S+JM83Ntzpk2Ko7%!9K||J z$U-)HM^qnwaW(}ME)7{&b~cct>qzgFvIYU!(06jrz`D@YzdzhI_sjyhE`;4MI|5`` zQOF9V*zpvr;rPJ9~Ja&+Y$XiQsHZE@v_e9 z{wn#oT+GUmYe2~h0={q z_J`5E9zo&V9xI5V$c1(*Y>)P<(h#v-Nu#> z#9!Tba~7~u#D{S}&Rl%Z*bh5Q{$Baq0^)=GhZ`vxcCR9$gxx1JDI~xa;CJV_);29 z(=$T$eAyfhzC$M{=e$r(7Tc46thu%m9^eH#8wd2}wq3djbo%B?b=MBagLYy2L5{_r zEw`a*+Ao#Q?g8V`J~Uw}$6yLMpxgR8^ZVm#wJ-P<=n8E(`pvc>BBVL%m+kME@yn5l zq8!ADVL;X^SXh(%RJIj81ntv8dlHCAXuouqliBoC+@CiJl;gI|btz*oxor?)vhuif zE$eTwK`#wM@?b;SF5@X=K)b}gzO-Esmq!5|pdOqp3+-Kr1b<$E2M_hn*#(>#6ng4D z{+ko}Ii!FKxp_K+MVadr*j$9#Yu221Wd zkn?=ms7Q`i+4Cl{BNKW>9?}lz_2)kG9Y6P(uay5q3-9N7YsA8FNgJXa@X0V-^}1xP z4o6ugH?Q!kJpS3{&PHpi`|QHL=;%|Qik_A3r+Z+26&b(}F=^%}%JpxA$;tDqovu*^ zz?(UO>E)5>r-yA>O72+}*3Yr#6Mwe6T{0Oyqk4Q6hwx<)&sM|KN``^Wos28w!dNt^ zs8^=rg@uLM=bO0-w98Q?hBB~S_R@BN-wXnFd=*>p_RIx6J90&c91_KiYx{DAgIuP8 zJIgZDHbX!AtGyS|UUsSFnS1@Rm_7{1y4Q_l`B+XRn41Ey^B0>Ua0{QsA`T1!_R2Vb zc$F05)z6r<8|d~dQ1GPwY_#<)%>>cAFWzIQ6!UX$~HTsx!>BPPQ3QD)!4vZYHnEQ#dBCbN@MMLMcpzvGpnYEs3&57{ZTllf_$P| zOyL>3!#n|gF~W9w5>{gKcbSDu<+%}LIq7_dn30pEb^7`~S@^C^s z7i?sEcFm@O%mLHn*q>#_RF9eCM@%^?#1xw&L!YMseIoA4>bN~(y_F3had`*l$Pw4# ziuy99z94jiing~gRgU|}3O<}I>zU;gjY{Co$0SpfiFywT^?uRxo5-(574oPJm}z^A z;M|xhXZX$DZty=T@V9mV-)IM9%+14S-*{K(>pxWP^Js^3Qpn7)+w_0p47*y29kyg= z@&*C9;Hzve_`_)+=~;W#>Bcnx1t+oR~Q)w@=`$9LN}pLLe?a4SiPNJsH?hr#h$~h1=DZZR35R z^gTOIfbx%~FW)i~3}gDJ!ZzJ`59G0<3coS+49|N=FgJ4yaBb8E24VCKYX~amJmu_mpDW$n--~ zl!y2+D(KFRzu@zO3RxWgOvABvXB387Xmy?G~2za zW?UT56=afIJ9IeTZtdzBe$-<)MLp0)<3bzR{seU#RMb(<0^hlQ=fSqzl_ryeuUy9M zyY@0rxk=yL--&CIbmGq5FZ-fBFNh^)yG5oZYs_d*^ta=RvQ$^MyZy9~)|TCIFe|#o zT%B8(=7PtqKCUUXLbbM@l8jJ3C=c~MFVx${kf-Il`cId)t+CD0G&r-hQH9=JyEOe$ zg}<4^+8N}_9ZDSJ3)Jp)N4`A{l$Y6d&&=_{Ch8xb9Fvf%){n#e%}b)yylLa=U>S7T zkpZK%(X)w5QAifqM2PoMBqqrI7ChV|gD2GWN#Q-5P(E}O`?}J(+(^DVDXBl?mpi3y;gJxOnmy`b z%Qf>)0h}FM73Vfl)_DMPefjq4%G$^L=}A*Zv{C#s<^FQ->h0@yZZ$%1gNLl^0sO72 ztE*n2={)QpfYCBbpjJ1~_hLcc_B+JLBoK=bi&f7pIdWj%&B3V`eH|yRwdQHxqd=RZ z-7vR-azKlpgFtzpZOZ+4$MQ;y-TaO9I84=;eO~E#<4Aa%26O=)8rPjG3GJSJ6Uzf~ znploYz#rH=1+?`C;aD#D^L$O#hFJf&g4SFX{=n9MM))Qbw2hwtFD z^+uWP31wOyw#-YY`y1i@31#9lsa)_$ew+9VejE6pO$QV7@XCCarw%JOfDVH^gh1)a8k{Ovu4o9?$#-?Mk12rhn zJWVEiVRx70=cppaS*TrWSg`yX=5M+*RMWQzP=}*J9c&pNl<(Fn>#!;#4@jo*LY_bo z&lI!9>sb7o)DM>r>w3g>;W@0}Db8k0I8BIb6^xcJ@9pPHTup&aU?jr|yMk??@fRrC zlI{8hW^{T*ex6szmaXO3)TvxF_d7es{etkVzggWsmdO>p-->H553w?$Pf99mQ}^s{ zLLcz6vkCertmg;@*fse%p5SND=k_d8Y%{FOQfwsLWqnS%G{k5+Ys!M0^}ijCNhk-O z*>r1;EcmIM&_}yMAHdDk>>e=K`k-LzcCHOM&!B>jjxpbK_x3DKkXddPkxRHQ+eXB{ zH3xw2CKK#oR`r*{yd5z%$b})3MF@Ob+MCwVrLcd7HNG40EjxU`OK$nX=JPwhyEJ%5=Hau%P#B zA4a>v78z6BHABveqyIjsz(POi{EFUbkA5Nf2jRXgi<6-!UW}1wqxyedZaa_xA6?_J zO(We(EJx#!6iQ-cd$sIAra4Ihw#+SqhI%e~YAJfo-48LEP-m1^6&u?VWCb3d+2teY z|^3AwH;GwxqQ(i(-p0T?n^smdxwe1_bSTBY^^*q@Dqo;nK)rv9w)ec)o*COAM>+p3*q({8f1z6EY^T|)`e?7Qf&SyJ)vP@0DUWj*2f1~1 zeJ=^Ovq#~Z7OtoYC3I^__#yHtV9Wm>9tJw$7$?c-nZr>+7+Z8fso|fi6@!zR# z)2dih|1YbtkpH(UPg|cLC&~)tX@d%V04HAoSmj)Zt@z6rS^ii51Cw(n$Q1uqVIQ$= z85K%-TluCUY$4Vo;$A;O1)f3>xCjc_HrDx?-#_ z4Dc!I7p@EaIFMtZUy%PM?dvMU=gYO8d85_zqXAir9&{ZWbFz#7Fg$M6e!xy>8gYs( z;tcqm)s!rrkEf6Wdab|9-&Hzkwo93e6-FZr*l+sfGLUJEsE+Vx2t0R&fD_2Q+4=&HQkw=27$B$U`W zRm7$E=fiOcW#KdHtb!s)spxpKM^>>qc*X75EWJFl-`Rgg&O6GDMCg}bL+2Cp4*u9Z zvD7>6$p&<}P)YVHs6I@eQDNu6vd=L6!US5^FFqkWGQqFn zpPg(Y;Ps$(c^mD3atBkCo0gxioM}t==K7T7f{#&%U{F4=gSUe<3ba_*(COR3>T*3U z#bVt@Z=>#Lwf%<&%`I~^b9Nu%`0dD`uJ6iF|8zM2rQZ2-cK=x4FECeorM@)t+3DKd z>i?phbyZ(P|9&)uuTusYFUAPWcmW))`&WJ;M{sePU4yWppz z34RJ0utAr$b2LR6WqsHclr^Ew+K)MIeoY*_wRP9_E@o#j-rSV9beZo+M8bDCg-n8J z?DihY0NC~?h&joZgx}qw?(uV0H<%QAlja_}5?K{eOP8ggTqJ%fTI=Tfl;IS8iYe31 z6Qzqxc9yhcPH8@pt<>@)6Gbp<@wQJvpIJYh&QAG?>27mR9?O+JB-RZ!x;y-t9{W^h zo6Q_%)+MlNABOVU)0T(MtGICotH#H2+C&}!mkl|)Q7rc_$lIw{Hc6jb%k|NtY0J~S z$FE+zXy1iFhj7uBa#5=E>YQ}S`Lp{XhdI2TmbWJLi~pM`^(l{Dn5!&M&&d;m*euc8 zlR1mmE~@xubndH zZqJIFUyj~Xe|^i1+k6rME(AED) zxn8=5{r$s!L(Y>shaRLu!pi)e`)haaugPoj_iP^oeI)@tFu|RMJ}K(3k|ZCj%ykfa zKos_ZdLrMb|6IAhS$?<)9~Y!=caHev?QFiEUYv~Y9m*5pWqA1eAmH!3^+zv|yBygK zyYBsw^5&e?llw>6ca*z$PP%VXSM*1xf&M5hE4@(c?H89qW0YviM0*Va?X@M>taNr7 zJFQ1(woXqvh0D^#^rfw?FR#gaw2hm~FE8KJM}ckoUlD%oK+MYVONA+AnchmqcLJ^p z-_rnJ-NB~=t5j06heXxC^3v@)_m&%SiQ@9LwbfMO;|16l#$EMsd7SllJ5pD$ccdr( z^#K3g@vfYK!K-iP&KTLIspqmT%S-j$9Z~h_$8O2hB_C-ludgl3`_4BTd~P^xL)hpz zV57>eq4SGy85+)-Eos#p>`Vf)7U*7_Yc*QW4JCcb?2=KW=B zJE+hoV2j+IN&QGP+TND#+u@(ai*~@@5%a=(&$D=Q62O}vr7t-zFZ>a?KEU*zzc#OSFUS?(C_P632Sw6~TiK+VeCZ z2ioMuy_IWgD|c?o>+j1qZme8eS-!nSf5OlDA1n8#hw{t>o?U8W@1A>#sJ#Q_Bd;0+ za-e6QeNA3Bdnk#}r_6Y`F0|`jeulbo-ug-Tei-1zbz1Z%$v-OZPu658Ak&(=m@M3u z2Yb;5x*tFWwdUq&jB{iNlx`H0XVufAaz>w!VKhO8CxoW$)uUF+&XXqronDAm<@PZ9 z*0C6vY)jvk0bb`}N6uHth){NG%JpJ0#MRE$$b&xNBv4-hc;9@3%%t7%?gh?BOFy*W z(+SJ3rwtB*vR*roGtRhQFco#_`&@pK%pL0SLxi%-S8T(f!f6%lA0 zs3Yv-f_V*GUhtB4;IPe)45=tAGB@{*vHOEx8QozXXz?GH+Y0zHsp)rdfDRQB#gRin zsdi2hIsZ6dA9jt?o;^jK1{Gyri0;V9_26-**P1s&d@%tEq#NPdFjl`#;CoiVx3o@0 zW5CdvH8i?{O&=9(+Qu08T>MYU^(Zzi^JRz>a`WEyw!DEYIjj}JTo~z^3#LwFyBf)M zOS!z#~$Q@ba}o~JV$0T`faGp4E2Sr;g1|{80d2f z=crdLvwXbRlyT63%#4{0uQ_G1(ES#YYHI>86JtpCGu-+~s(b!qDhU7r4C zb!kK^QRM|YE`%CPHG&dfXRSvn)u3X>Mk##GTRL?cvl=9;LKJ2%-IwEH@H*#*s;up$| z@t3V;zq!C0Am$e2-SJL8o|UE+4H!KdUk&K-LWD!vb~@RlQg&t-IfvXJ(vg=xYwtl@ zL(V}!&YXpb;a&Y#?WH*8^VNl-x<@X?ckkJ|6x8{tcqJ4+P40!<*^GGer8|#c;m)>nY_Ms^;)vr zxQhz{IoEtwcqIQrb=lyfYFjcUXhb*vlF%YKxJ=R<#Is*9D{7uyc-VZSwb8{UlxG}kH80K1*JU6@0J$PsqLeLhG;0F`%-5&I~)0M%#Ss?%p zdkRh`;IM8iF+EtwCI zLsJ_qQII~;MZj}XrybNC?KG~?mvFY>fXLKktc>uPnO_LY2)oELSc)z_m&J==Azoy6 zb+rR^zYxi#SEj;p!*zG(P{zqHWE1{2?F@^F64D5`T3#kG%uN_uU1<}9l$?S@e&_)? zL=y1BqTlmo?d%&Fhdlv4rq2uU=`HNy?(NP&FGloV%HZ?1wHn>m%ykag+cu{K{aATX z&L~ih)lZYw!6e5jDHdgD&mc0t6Eb5?XFZSysE9_tOEz=GPFe9gE{x(1BePHnnz(i$ zvx}s{F0!h-TF9_R6qdpPvHNS0R}BOD{~ZQ&eSxEW<5@NXW%dKU#%BV$w$ysRmH3_7jt(Qt zB7kfLt9=-JjL!u4nE281=6IG0X}C1|yN&-Lo}C5i1740j)9_%oFdL&Q=%YRk$Ft1f z)OcWqf~G!374=Bh#O>O&dG6c1@MwQeWq>~F-&Ssas6)ypT~x_frGHYH7KK+*!7I1M zt#Xz8ZNB!Dts`Q^dBCwHbFvIEa6!t-Q$ zo|&W`+w=?7=aY~%;CqY>Xvjf8=k!l`fKuGF6?=Yy>Aciu#|5ALTC?VZ9A`0LqY_`5 zxTrL}FSWLtV%h;rejQv~HLi`J!$`_G31HCHd7SA5jO^D1H?Gn>j=P%OhqwWugv-3? zXx7~Ie$I1(_u{_@+X}{lMf5^?=A@*wIliHWwrvO7){ZR@Uq%6)APciH>-L2O=Txt* zaUxeA1@an4r#Tax5Cuf`tQ4&}uEV>pf}I1S8t#|i(;R!QYp z;x`mbHqN6Q=;J(~57fuEcd}u7J^_5e&aDra94FvMau1cgv9tW#0KNn80v zbq`AX%;Xdmd{Ac7+`%b6igcpE85n6txYt59wuddOSJ(o0;p5~M(zDt7@~;SXP!X>z zQttiN`AE%-9?Vi4D_q(Q&B`VP=o5U;rr=wmFPK_!ONQ_RU&Pn=7sK&2l^1b#g3z|3 zp2ZcChWGpA=cvL4zXNJH3Z2j^{Q5By!5ZSYe&pO{}s60HLds2 z6!o??=!^N_fih=saeu(w$RQ_v^xU7>I#+f3Oy6Sz5;k*}P81d6OsEd{gY#v1aGvOn(}% z*$eWD(Vm>VjJ8{k9WNNcl`<>7i#(VW&F1IPo#jq|Sn;aH4 z%vO7L|iv#@Xf2!Q?Q@PE=n_U^x zxvZ#ZYXi}uzTDj_Y)t!JlAlR{pR+G0xV!Cg&E|kl3!kHkJ_2j>mPtcayJGB#mHyU_ z1JF+Eg?6&?t;u(zl6I1%g~&OJE=LIE>gGLp+0~d$lwMl7CWF+qb^AU{1(q8%fPQmGTOl+5L#8mt_&zt^?}aCrpUT z;}YIvwqGXO;Fsv227$H_6Krm6$rdu1Lls*D4?UWvEc9&~)M+@OPSAh5p#N;&!6+bu zsc0;!w^}z7bVc3Tc0@cJ24WZNOkR-QlFPlNTJQ>~0|wCx_OA^&{3rqUK!5Gg=3u+^ zZ!h-+#6$3vRqZCYT22eH!LQZYTfkq1O|ABM)N@k72fQR^1C(uWyLRXH>Yba*vX#ip z@0q@10uS&p*ZsLw#C-#euB<#Ah-uhdFA>4c1G)ka_haj|WPiw>ds9FCRckwMBwvE~ zwk;6TM**8~d2@d?+AjH(^1jTa$G;iVXoVt>?21Ph*U$}pR$s8~(G>b3f0%=0mj_r_i?(? zP|MyssQ;mIzmPtAzP4@WArQ0c|D-&Y6;>ZEM>s-}t{*|J#Q@gnvGuVJyABIXJAldZ zfD~fpZs1q-?A?tpAcsK*H>F*f))`p#q$uXGlolAYlP{hb8r zlUoe1lLY2a9qb;mU_3XP2J6TpLrTE2z9CQ-Z+f4lqx~MJI{qEVfcQC@j)xlrUW}7xL)6vau#-QxoPbe#y zP!{}kQ1Dmh9>0JbGWO~2N%WTVsv9lu9quBqNOff^gltE^rZF6ommNwqyB3K$4FbFb z>8u%e)@}5Mh-};cru-aN#6Ax#`46&n*EO+>~7BdC`U^g*MFeH4MmbA^HeXdAqgG?lr~O5&HloZQg6i<^o;QH76@1 z;gW32I+;1-QtLi4<0!OA{eLU3XCa=NJ%L!7c!00WEvJz*mgiZv;!(_WHA2_8Oj-onUbI&q^*^dgLa4CwF7?lN-bM!TA!{yX>*$@ z)!t*u_yqLvrQ!QRCeD<5zzN( zLEn}yXOdlJAW0lbmR-o=0wmEhd#Q3XEBeaiP+ z3<7P0veVe9I|jVp=S6g*TjWurY51fLQM%v4tg{FnC z-0Y}e-`O1{qY`{>JaNz7ErncdSYnH2JW+4}o8P@xFyj*bXlr*o0p4dNyg^qS6Fe|$ zV8GP>dAV<9exYLmp+(!m9~T1{&;BpV10ry09SvAK3@-`TZ;DS_&u3wEf>_lK$dEHk zX5S`xw|iS4|H(91M}|V~ACTWOHI|-B+Mz?_p`+<|I8x-;m@zooZ&Xs3Nx6UhYs%vX zbAJo=_(Gkh6l1S(~{c-wgu351T>o z&n^Ja{MGMKG6I-DYRl&(`h(BlUmZ;Ag!x&Hv4`B1TMF@6xxF|hQ7(w^Y;r_3Gn zX5OoUhwBUZP9SZr`Pz?Jzxbf&9aiRX_%KZ*)5N=QM zdCJUxncT91&lGJ*hDI*5V>{T6eUq2Kf5!#?wPSe9xeWq%%>m!6eT_Y<3)u%1vIqCA zT(-Mv4q7{A^O~?Rvcs<9Ukm3A(5p!vQ)A1_SmqL%2YuJ|v-<>wf%<@-%#oV1P2M+s zU98UKVKd0HkXFRz4kjjlSJ*a+_0T3PsRV2ddBtdoI-u>x0lK%Gwd?aj+uIm`wy%F} zQSMxR^if+!^y}ji|0&Cl+;GnN#3kiGFD6gYd%DqQ&irC|%ywc!n)HA-Fi8ND#e)=L z+CCD@Q2@g@;Ab~1YZ$<}{?7?bU=VlC0+7`u_;4Xgy4}}IO<7M{HuPR>4P(C&!fJy6Kg?!M(5>MC-Hijf zgUz`1oXbzrM`-PgN?E$W$u8J0bTZmyQ~PcsGGIdM8rS2<^gbGdsD8%}hP6q5!i zw`^mKljfADbMk+b+a>C3V!PS;>F~2#Xywkx+j8qf1J`#fugc|5H*c=2$~92)P9lkC zv`p@gI*)>N&h`|=g*w~)Hl{!M^ToIf8C`p^=2~ekrmfe}27!88d#U!3k~o#mFKvV8 z_6aT)>XyBQRsW^(Hqd;dv{|JJrY`Waq`*5H?~hCLp6k!P*p9E!pDmWiQQDu`?mD%j z_X@WDb>;2jkNevtWuP4$3rjmE_Aw^`OjUn23Sj69q5kYVfOGxd@6Y02E^ogQJ1OnY z;u77J^=C;59dyV3>?Ydb|16hf*|3HpR@trvXDo_REV*c35I`|2zxSrOB8f^*07Qq~~AFW86C4>iuhA=d-8 z2s?3YINyiaSb{o@0x|$!V$Wr94^=U-=}GxH2)Hh!XX~l;?=Fukr9rW*uY0%6 z*I~EusN6SDx9R)3mseKrU%i>{=$dBU7xf(m>-&M{VRx{pqe6XeehA-T43-4yTh-6` zCIw#T;|78H{{Pj-4GQ(L{SfSO5U|T>`?!+=Z);;1vyDo0p6lcEye7s*rzLWjKF&Y% zCA84vCCDCV6ZCC7<(3`}b1ve<9t!$5`qyzu+1~tTx*rkPS7a~)8DLlAk~+d}8T(EC z8fb6a5ODX!d#R}D9%~zw(lhZm7#O|EQ)xWh_UZzzB#|+Wkp+H~{H1a~l4E*$$pH4{ z$?jLV_JJ40C|6uzB1-G@F`VIMQEWQZM_JSQ)(7Q&&-%iTh6S6j`6A{~jso*2vToWn zC){+U9@{W5exrO@9rSXC+MU~I1GL}FuawstE5dS>g0HxA55|mO<3N4ThMZS&�dk z>SpsrGfxw+$LuZ$vo8`CB?c;I&%434>)%tZXI4f+s$4CyBU^$*Gli3o*f`QjBE0<{$u4niTbE+sajD-mEJW1iS(V#^dxp~PBv;nAMcg2 z+5!DxGbkzuI@rO?zYNde%6*^`Z88hz{VV&pZ_6ANk-LK>Ui&o$Z{x4uTkfyr_4Tc* zc7bg>F0`%9xr`qL%E;o2Y|)ith6f#7%c^CVS%#j`0puJ6c(6^HI~%PnxkEG8;YkbO z3aVPet{H*PXaXNO5A(3SCs*qRSfzUVzH+@$9@)v!+?j$;GJ($?wv)vtU%s!CLnvrQ zv#e_Oq{IH(74{Dvvoep@Juq+NQvDE5BJ8Z?=YLgOT|qm-2L}Nk1Yhn$PlWDtf($HJ zD^L;|sOT&r3tMB~;9vh&VIMbl4mue@BQ;W^sM+*azn&6AP*3n*ui%fmQvQ@zS#&F@ zLh290a(@8tg8Zp-XhS=C7*3FLmM0SZx|-%r8T;QFJ)pgZQ?~c{1Uaa$w8XceFW7W) z{x;g%1_9gH_TPT}(*6)_eNw^OZEIyarLDf(=+KOhDs*W3E}J(;BFkBY??V=yi;&JL z|F&nlq8|nhAKuq`1LrByb9;q8xoEX=%1Z39JK;- z%Qp-VDW_aP@7`#sBq$EPg7HrLm%}-Rt(n9$O||X8Iovm^r?%31(gLOLN0o6#QErb# z8L^a6|JBK5VD2*Xw&%E_jUl6Z-sHT{_dDyKUtb;`zddh)zB#FgA+xNmM)b?n zy>=PMGf;QrgM(@Kq=8Nroyj}>n>`0-a?5FWr9r^qmHy50LjCIBU#<)2Gp(QccP5nm z1MBys@QDLDeapE&tzIu*D}(57)8RfY@0tE*8*_&Zokr3yFjq zTQoKuXmgsJHRtmDP7Xa~XZ$AcNliDz>KE-^Cu7qSc%`Nr;w3tTevD23K)Fq`e%5-! zjKBxBodo!Vt~ziy8d(tY;$I8LylLKgS`Xk$-$+W|ddmEJFl`-}!?=}DouVFtfE@6R zY3gwrz?as;d+Q1L!#I#X1aGuRCqE{?PZoiHK)%3RQfd3n{LAw8-IbG0jw;O~M5rsq zevF%l9Z3MMcd|Gv?EDR4;X%pyY6rjuW|D4%x4ZB+W*X23yrd-!9yH&c|4X-7`3d`6FU&iXAK>LxOo0{P`j z`bJiIH;{df)E*R+to7j`F3z{F#^?g094>s->5gR!lH5i@S?Yhd+*T>e6Cz9O)u*O+ zo|t)tfWGC<@;$j>pt&PCwvp8wUQge^vOA@4026OL?Y(B&AN3vw>Ma?HXnuL8h3c)z zLHq^%cRVX!$xYnNz8sv~SbB3-FJhK74&xHJGKNo(zBN~i%(>__DJS_WfjDID7Ri^i zdbq*Dq%67g+eq)0iIZYdV3xp0S$3>&Mamike8$Aee&c8t&qBIYa|$#prAQlBM*jwN8*58x@TGz3wCM8EGFj-)a^p_vU&J4TWtR|lb4#f{X^xxplhkYHsZbd&`JDn z%Htz+f?7&bT6U9_qI7SiI!S^$v1g1BpN|6NTW0C`v~crULJ^buL9+W}z<*TD-<&`V zD#{ZAo+Kw$O#!e;@Spj&<@!@7=o^Ozok{YW;ehZL(oBBj%}He&+fjso=s0D=3)3Fx zH`{^sxDefvNpP77->I26i*=SkfL3#C9Og~W44QFOz6gH>{_ExTZ{)># zM3}3vG9D#F!czMQ^xsJ#PTIM>b@^@>=m$}rXJ_f}nGL0X%FHAElWlop*HRAJ7Gup( zplwkeK024!(xv$Hd0>q3W91Xc&-lE&@3LI%|Ev7-+;4&M>pxr`<6WGSEV+j#(mTFy zg3n)_Tz+t@RduhRyd(}?A-;?PzCu~&YL`r24!x{T(1*8%L}xMW@?OD@E6SSFu>x#q zy6@(0}}@gl_ZPGXm|91!wLG})WcK?A+czLJ~;SI=!0yyroAR| zj;7EDac@H*gosA0ZNcB-zgF#Uwl9>yCzdorVHfdJY$T%PUj10D5YNS3U)A|t|@4`>gLF$#FS*J z6>go!6Y89TrmJ&~TJmktqx$o{tDWm=k<$l7uLLo=J_L0wiyVMPzcgTNeLwr(> zQw+UQT8UB4=qrNlqKx*$GOCAPDgRU!lP{VP7|R$j39{$nt_UXif68<1o+5%BNh*NU zO^L&Z|ok1 z#disX{q7;SXYvoGWk$5Siz!nwlmL=Shr(p* zLUZq->?G*P#znmx4*XH?L4};)PoA!jqGR3Uh%I2UQ7z8eDgKReI{+_!%6Q7VoN}vc ziFzMAC$BSD{utlHfw)TEbG4os-+(r$ptbu|EbSGcJ(?hQnP{SivOnXA(XWCTh#%Nd3p;hk>#-4&^9tKXvS|`)GJcDaA)ER=h|a zMua_~PUGpyG3FF5%#*4lrePi;`J8h7d1zBsMPTsAox)6n$ZUHQun~`eDUXd)_Fb;! zYWDp(XcxmkTcK|GbwGqEu)!*>VS>fM!XI_**8O{`i(#NH5}(c7>J_Q)Ozp+e z+zayXt&XsLYL-YsaRJm5c}ly2@4lQK2=gQ}u|E(hPm?FUv)s-hD@bW;vOw}o^o%!m zkXP>9+*{G5g-iS|TW>n8kQ)t9z2fA^4q}yEx`kT(--O33qFk@I!C zuL^P|pEKF6j;Gh>v8&I)6mlMy>hrl*B;85p;UVYAG;&U_&tq4gqiN(U)u+g5^l8WX zkaIkRoNr7o=Nqn^_2y*ze4|v(=W}vC0e$*?pu|x47;@nxP)>H|G9HtWtr1v#mtck4 zd9fYgv3Z3_{*EDM?Rn!17y}Ff{IGLUSm@CS@rB*aUPp3xdB^^s*IG4*tP)Tr`dTz@hNzqup5W;`dCiKO><4Sl<)Wp`hUO7e-^zFB8~#i*q0{JvSc z;X_U&%2P%9;FivBy;o!(mz0Hm-t3{3@6iUR<9SIrpmQ{>ds1y3fr$hRJ7dyuimv>Z&ujGaN3X9Zna8^oBh9mq>% zzf9|(hnHgXFoV@+EO#6uddh0nrd*_{B<8R z3!uDi)ssg`cU$fwRC-@KV#^?)2N}EUy6oinOSxQMHe_tZW^({z-%+4#;1{gYv`xfa zXUs?EAzz@b4*#^dTzPAw?9Qigq0MY8n-Ts=z<=aja?u`|Mn^HeG zFX+_H<3LCC&2rzr5M4c#w^a`G`ubi3+uV|S|D&hhyuZ49?=8L8?TYZ2c~`m5H!X*0 zP0EsM&TMj;fNXG)aN}7vSroClM&2+E=+TWMa@bTJRNm=6?CeP=Yq6+fJ5Wb`521e` zul68h@Np{olX(_FHg{|tZsP2f#0q0IrftCYG{9FO6`N|(dXf}rh~bN|eEr?!Z9-xi z&GsxMeiPT?^K|owEjEF&*zwYG0;{Qa7X{9>{M+P}WAne~#JM4mBP%?EerS>AeYE^w7+PR{mi9A{_yFh4k`EbEy!4NKlR zieHu*CLwDy@R|s&K`kxj?y)%a9-h7uUApfB4uWyW&awBrbv^9 zAO{ELPI~zNC}2}=+;y^O2??cx5#tlrh2JnBBigTYEaDb4FYkvJ2PKC0)51Fm*wmyk z39v^2tXq6;a3UD?>E{)7GB#3vccI%)G;ZCwzI;>eFT8zY_;Ky< z;6R4OJM#LYdBZ0?q422FdW@Sf<*2ZEyH#eg<$XK^=jgD9*@8PVEPm+#A&BzP4na@r3T6m!zPV z?Cz0zt7vzy0l62(+^~CWMhmF{q$To=d9;7>u5upe6>y`F>?4*Z52gQ=i>uMzX=jvE zQOep}?Ik(YCFw}b-d)sTy-)}1gOPl97Vux(ZIjxV%o&NwWChyZnF5^l{yh>!P(4Rym z4XFL`g9TCu6sSo;5Cz&T(7rSjsums-J4(i8YM#%z9PJf&8K*m z;(xvG8XuWSkM<98a339cp|@@7+~{mnedG7J!*%k<_`d7Z`fK5vRp=|<$twtAyV>ENasE=9}Tta<} z8)QkDTz-CD;g0F)GSH*sa^?Kdik<}3FIr@U65;*?kvhq#Dd(dvhbgi44t?L4OYhDF zXykdzn{dd?lz~ou25Uecy(4d#yW2>Gro7NQJs?MEriCdGA+Qhdo& zhI*>Hogs7cC|wjs6E@8^Msru?$}X)d4;XT5(&4?**k!7W9nXVff$^tbsjKMtbt?iurnRflU_Ewch&C_GJKlxC9v^|e8pEJ-? zhWU5s7>{0hHe(oTjd@cJSPuemg=xdU1_A8HXx`ATAVv#@{_rzqjQX=u*9B3Q`Z=5o;!?+8JZ5{WhY!jCCtA=T@0exiIej+ed+%CTL4s7NO zePaCjvFSeF%y%<3gEGA)XnOLzuR&~PEPbr3b2Ki`^Hs);vFTo5wu`ckRIv27dDtwM z=WW5hoZtOb#=vFNmz-hD71jc}kMniycV&FWFEC?*_qvl?OLyG)wIW}h3UcauX)i=c z@)ECjd0APu#smEp*{bluwuV9#K5$=imcGUl>GhgKbp7jUfUJWu#lX+l3kww{_ znJ`kY$LRhQj*K8xkBrnjj=Xm(Sk{xlL*!=VumyHSv87wLqBE`CJ2FUlrRnsQsE(xB zVr~|z(8d_+3XBi^O4YxXO82mtM{FsfF7RRDvhA}{Z8+!~+OF(Rn6{MVUCa;iGx`Wn z;Uo0=PX1l&@~!^AZBcz=%*`7x$M3?2Z4o15l%V$x?YCb`b&3`0P#?HW<`dJU_=R&- ztWdO_Hm`YTk1Gq@DaCAD|414;^Mc1Y6&h!)54F+X-1mfa6g7X!vWe<<@$+%R^V|;| z=_2t85O;oYUXQ?&nv`;a$0r^cXN`}lh4nW9C8rs$qNN=-gI zJw`is@*pwfM`$;%v8-&7gJg!LERqx1gVQ8DRip&T!p>MPNkaV?heA^ujL!s>U9Q=0 zKzOGkALK2~#uVutOuG^{1A(b9pz>DgX)(m60`+dSUR0r#=Xzggu4{W#jQ%!b;f2tv zQp_-Q{C%7}#Y_{+pS-0W%VO?43#|YVEWT9zjZ_vaGJyFMY_20kGH;pAl%XB&yV|2( zb5K2ZEj{OE%yi=PbarBd!V3mRl~0cw2`EgI5>@5M=JhjU=r6Y!j+N6nE=W*2DNFm- z{0v&Ic=;Y&ddEy)ytz&PUN>VI3+yNQxF0VtkHdZft{!R?b;={aI@usHCd4MEDacBj zIn^Z@G-p_y8qJc)Q~SC~{vc|H`LmzOyrn(m2jvSq2CO46z=ts?_KK9EA+qKjJ#sKR zI&w&5Fq)(b4o62x5mfCkUG5q)UE(k6q~jlCgdIQ1*>$Bwyo1Ez5GgMDN{Rt1Ah!cXMQCm-JQL5yM`^%-Ps&LV4j**?pP?(pEqXl!Vj+yGj4CCQ=!S~y5y^62DL z`bdoCJQNeyKap8Ymp_2zQGY%V{aQA zolYkwCbAQddpxf)7QAyk{tUPGN?M{&qUTV5DAZ*rOL_w{MfLr1t$VP1EmRnP#KZBp z=R@PJvBYz;VCgHzq412P;3g$Yym23!9HAM>;zc>pOM-Neazeu2VAamju znsIkUY~R=@`9XLx5pQM2d#&mLzyzLF9(V48q%idE#!&5aQ+p>Y^Os+&2S3bvQcfrk zXp)0~%OXm*IEPez2!3z;`DPuA`HC0QTPP;ZTdio5fxm>yA8T?w8G2;&)RXKtjjN!b_$L8d9mhr%4<|x>@SP_&j9uA&@?-k`2cGY3 zo5N$L_LFpAgwoDT;fP0is9%RYG6htT`LvtryDtjYXPzn-k93|yw>B1P6{Vkzo@Kv~ zh;83ClI|waF)6&R_Y{^bKDo~=~(t=Ed4!@o|>K*!!Z&v-UPHM9kNC%$$%aP z>9X2)ag3C@H@-8rGdrR0VB`Kzs*?aCT^86i#I8}0m7QkdPAiYCTzn>BG2Edf}7y_K=f{pNm_b)AIh{ zL4F_O%zc4fe+-SAxracRkW`ZG?hAsxP`x)}y`j(0u9B53Co7JVl6FdDkzm{6?C$Ty zoJ(0~hRkAqp)oGCow2nocW;WlpaelO5OBX^^xk8Zx;!UF z2PukKxJ{Dh$l#3D$643NS^CWN_;ZJ&V>dU_vxN%sLO)G@#<3}V{@ObaN%k#T1SvtL zx?`HLls8}r^-;3TUDsr*JMSdO&_(a@O+eB>@4AcW-%sx>T5y8*amjlj)fqZu$r0u8 z^~y1!Byq62{&Sel;KX`vhsP^lWxVckbZ!Ek(}fDpQl45hrx|mF3cQm!UB<$zVtPNx zZ4@nSXt|-W)ke>`i*`9AZEW)ESn&`}wVuZq?h5@)x6{S#+*97pA?i7$|6-Hz(DVe^ z&H3~cSpiADs`F!Ht>UAQ8q;zVcS3OO()&_@wwRBQ4=MWlDFc?|d^aJ8Y>uU-W771b z9Ey;`bL%E!H>a}{%1)<*_tH5qvX9b-`OWS3RcN2bA`|#KVw+fYrCwY<7TkAzf9f#h zn#|tEYR)J{1yfA#cxHk|g|5ON(<1bhVakG_w4U+<;3H$>(^GPV#Pk%Ia#dfsy}YqK z8UrOIi8L|=C}VIuJu`Sn+sWVnXJ@BgFIXO= z0=#DWcJJGF%dPwS_oohQ>q++XAK11xv2Ra*PcoSZM6FVN9%IIE+=9*aiLt}viS?dK z*`AwBr-$f4ejj5!V|z|#kCUhMdwG9%$}<1j$0yU-p=?<#;9@4gcc%R==Vj{N6ds#g z^|47Ld+D4?|L){%$=$)hQD=dae74b|gC>b;?H^;h^Oc_+P2Zay#dz}bh04!UxCKR3 z%eeA5#jg$HndxpnTA9R`e3Y6& zf$ixbb&!FU?VY<0^z^Ek#0n;lRTq^71J1Y|N+NJDJ;8Sz-8)FPJJ2;dc+XxsAeB7O zzmM*k*>+&pw!OVQ8zgrOzt0^Fj|abxVyGqt@9W3;l715AB) zdCz@hnx+6@9cRIO%m?_y?ZOALhW?(jybJ3=ANT)abN^*cpnYd}WCqA_Fg#3QVsv0a zEktx;{wRC;$H>)tSV>PU11JiPwvr=b)DDk7>oTb|W__GRZuznT;Vbf(g!{<7BSX{d z6{XCxyzKBhna+F_IvLaRfw7`rsrqVOTk5NQ4c&Sjy8F~JW<37G?YqW?>7HvDKOT?! z!z1{BY}bJ`*4cOj)OgX@(Fr9wu*~!&sGr9yW2W1?Id%XY0qi7`7`hYU&kW#@kv+SI= z%=5#e*@FauL;7f^n(%6zQdFnwLNm6MZmf~08`hf=Rhg2R@&-lyY#cD(o}p;z6Z65} zArd~!NY$?x^{egG<~hdoH2oB&mmZ=3z4Q?5>uafAszN=si}g=VQ*v8AZ^yfEU7N>G z=^7Tf#BGvZuXEWb>zcep-B_$;3~V0zsSkw;Sm$?@_hWe7{rVN1`4Ec@awvGe7M*sbHF z|7ve3q&Qo}?n$TVNEuRKkUT$3hXE#IadpC&M)u}gclqKgh@Gnyjoe`pC%P%oN+=Q~(mm(1YnigQVwbA;Cvk$+VXqqRn`gpPEQ_=yQpjT|&zZ=3TKu zd(=~QOLMF&=fOBg5fF#zNF-m{M*pg>UJfN3nVnVIdz?>e)_B4XURUE*U2tR9~e#aFe_JqS8F>U z>kKm%9y33<{uo<0*xbTS8y(RKYd7Jhzx>aWacYidtmfCXRJupZ6QS(_-1k(KzN7zk8-{)t z_oGllKm0lrL0(~$=gg@Z>S{Hewn$^7a;vlWx@}$`au$qZ+>nc&Y0g!lxgLJSudB>^ zZeQ{1|0(gSuZB7%eyMp?rSBGg`Ryt^>}uSZXSo{s5)f0WE{}P>>X>VvJnO3Nn0=gN zyhjcnrrkNFVgIz!&D3m@{;sAnZjn>mpMs%3uE1DvyCk_T#(L}ip_wPp zHG1hC8Oz#VqplG;L}^kqxIe7R7A$QwMbF4Qunu&`tI*9jO9jS`ex-QNJZW5PN{$}*<@`+oZ>jOmPpo=Q4~ zn>F(xpa|5gW8^J;s71#pEU}J}ve3%>;!izm)(H!p`c3-(YR&qEg33|D>x6r~d93|) zOly`}Z>#j3-@*N_MaSr>p&vFKBU3}&N;*cyf^m!iVO^~+Omm?M&Gqo>SPlJF{Cazd zUxga#nE1uA%6+;zuMPYv*D-uCpr>l+i+??YUdU^DuEsHEnVqr77qzBVphO2px zwec+$zSgj(V_nfLgzGcSgu4yMaTufL`V8&xb3}R=CNxPHcRW`L79L}S{FV3eUU!ec zi5#WSCvujywJ*M3eDPbn`_Z0Q4!XWT*~9RixB;LdGhNA+Hf$8+A&R+;Sed}k_G z36rVlWxX~Z;46=j--ed5^ab;RaagqAuvh0r=QCM!h%8{)QnNyv3*fop7|PgyqLR`q z^pf|(+tjQ6DtY>KGyi#P*>^^M&P3oi7`+<@|-w~d9{Z6o~c3~V}Cv{MvkN9 zRD%B2_9C;*i{dae^_D1$T?ttB0^{P0s=INRw?zwYwZUVAJh%H)(&NEVg&@++)Dbjq ztWuV-VjavIS+@27+?_1G`q{2M-l-ay+~UaE!?b2Bv@&MMKCVQ6S-JzS5tWl+JvUX( z32j&6H6>^1E5DmRpqYp)y_HU9k$a2{O^W6=evgHp`YmKzr$bx!&~wcH7?o|WHRFls z@tX8PTg9)=^-`94s;?Xs#9mM_ukb>H_GT*7nhr%8mz2}Pw*t4oADvciys8=S6QxYHQoz&ipC2x|yz2WwC_w!Q1E+sm< z2NY3aYy5~mDa4J@5j$5l#1(BkF<9*zMVA zb!t^_y~uh_{1Z+nSDxYp%PqI9hB0O1JIG=2!d{?BI)hF(t*EH)%pe7u^Ft+~)G&8) zB#fqw=W@OZ-+5g5IPF#np`x>Sly!B&tIumfz6!2kljCO#6`s|)fxh#OWm_R6+jO6K zZ+^nkXPu{&Y4)a~8q>8@$GyQkrWnFIFsnEpi4yg?J?_hiU|(oVc;4JVf15YR9;FXb zjs=^o%fD9d)B4~Ry3jqNBI3r2c%v%Iir;~Hbzn@FIR0`7*%Jy(kL z;QLm*L8Fk2%drl*Uonpx`oiN=42}=|j_dQ>DOmb>1+57TSc)Ow9Qz!$$&x`v&DVE7 z&dD`*kYWI7;Z~VA`A>Xf(u}mXo67jh%>BKB$6=7BI)*?W>E%~Yn{;eEPElf{3}`{1 z-b&th&OgeJOp+wgK1`-5XKkZ*Ut-@K=`o6+Ig~y^YrtKkOdTQLGEGIr4HkCP5A*?S zP~PXkBP0*${Jx66;qXQ^hSySAu&hCTuL`@i`$q?lQdVTm?a59Gb>sslbUD<)yVbjR zzIR#X0TIr3`@8sk7^bb}UeT3(N{(-ED3J)ilVwB3LLa}6KdKK~HGpTH%#Xnq@}nr|mdwSH^68_k>P}F*Jy!n31m_E>H{>!GjI08)Xw_^1Ef@Qqb`z`A?uQizf zHdTk{e~24nY~&2sQ0JV2=-6~u>;^M9HZeGOt}r%ES^8QlHu4qtHS8&y0LKV9)9VKZ z_myS6`!h9SLx=jX7It5D;vPO=L!jm~^+P3;P~tew+%Qodh|lV+8XL8)S7>jz9ngx7 zm-tpYT_Jt%^l6pfgYlB9f)|!yaf=M=roWvs%mXh*iv%NQ;HKEDqcn&V!ZdN1?gXP4 zUYdE7Z%19%==-fRwjsuRT1)TkGteVpKsu6**1<$_=eApS_x9iN`fUep?$Kk;b#v9~ zc8Z@;zloOw#V@9{D@5z4`Wr1UPQfs5NT!x`O9$A=ujHUcyMMj?Gc%vAKx8T@yEx#% zs)Y(nRwqt)`6RW<(ebt2)SuKF&F?DJ37=A-o2B%9N3>X#b$q=uj`=)q7(bRHwajOp zV}(kXU#H`6w|PV=DBNGxmpj_Sp}FmMNpLQ2vL<8es2%Qa82Hk9vSh<5o65Qo;El=L)*1AIA)MgnyovRW(ouQ+YrCrPi~7p z-h2^pQ^p&aLp+vU6K0zE9mDJH9J`ZpBB(fXQ*XDn-(MPY3O1gKse929JQfw+yKe3M zrnhamYK!>~4?NJmj_GCo^PG17$lPbTFk0=8S^oD0@lEt_eg0b}_&0es?^99%3=ls1 zb%b?4r!i^o@8=yte}B8^P5i!@;QOR4e&0;seLSwp9zuugu#D;jRNEvOhj~LCwZ`(D zLsUuq+__B_;r)DBvX^5^>F5?5lJ^1k-feC74xkMB*Ctu%c*XL`5q)Ws=+W9x#bc@V zXck^fPYxbVZ`Jll)}K-@H}j0gW4N7hc0XIPh`M`e$MQhz4#K_4WR+DW>&d&6wX0M8 zHrCNGuI`@e;DjBdrd@G`ivMJcxZkk1)2_+yq}*K{9kDxP^MD5Qy25*c6BV%Aa9^pL zJZ4=y7M1!)6s0FPp<|WK(tG%QjF%Gzyzsd4hlX~P^G}x(yMvcz_-C3pEVO+Yeu=B<=uI6?~Pcw}Ww#}@GS>^<1V&G?ZEHaj{NRN-ug`r!A+Y?ruo93pneW|$|(?>SeZ;9Psu13pUo67cL zp@n2yc^&E(_wN$!pM?fx5NxLn?&tJ5Po8r*3!Wk0`epyH)stO4x9;Ch>mHr-eFs2 z3kDw1UAB}@mX2`Hk!8Nih>fF4*2UsV0al#RIcN^4ohHxas{vV=hO|&I-8WDhGX}be zFYRR_PMsZscvJ^Sc!$rj+Pi9Pi=%CAJfGvQG>@giJ0<=eWt|8rQdt6|&}+TaN9rou zL-!4l(a{^9oTZ)dqZJ#eez_<)=6QS=yT>fp)$3uW9{Q^|Rr&QV;X15`6)pW@-t*iQ z)@=!|I`@|i(F1{n=Kd0453q57+hbW#u=G*4M@vmdHg^BMTYLB4+S^a}0@BQUhl+1t zS&_5Mv-OV7bQ1W*(ff&==-`9uu|R z$IKYiV^WC+Y~={7^ReK_m&QKcU8x<@*lV2dxE2iK%Kd|ljpak$A|Ez#eS_TNJ>v)^ z8Ybrsi3u|DvQ!`?nXCcZMWdl@Js)J(G{opVeFhrn1vozznCH6QMO3e7>A%_=#vPSw zl6jG@zzc1%4RlTI%(;1?L9Py(m>%Qkf8XlEx}ct`Oh?W@2ahLzD%q~wubO!XKJdHe zE$g}+S29)Ys>|)Hn`4InfEC$;f;+A$<(o$}lsrcs2WqIBTp?8&VSTyvH)Kc%3 zO%C?jv3r-N^G`be;pOUY+ZLvus!E!CESl<040b;$xpOU*?w^P2(NfE&RW~2ZW=G=^ z0OY&kfq#9MigM$hwrD>C&xMp_EZ|Sv&Fx(tZjX7pBg;v}rYKh9@Caws*2&$~*-2_7 zJvi1$hrrbJC+yo`6Kokxov_DqKQdMN!8|(TSb{HeqA-Mqc zz>w3Dx+gY0mUA9i{O ze@FR$n_ydHT;?oe;OmEX-%U3?pRx2o`2q~R7|U{#!-M48RX_0m#`u49BkLAtWCm+* zzWR8m05QxrmPvU_-~Bc>-eb*M`mAVFIVgb5wftuuCq6|Il+cmEA5VPTyWv0XIDT|p>Q>W}VTb!djUTQtD(C(i@8Ot2n zrKYV4x}h|#+=&g8_g&8`QZd;8R&^GkAH^#D;5l?EG(K7`^17BX$Q2*<_%OUe6$NMs z%5|K8jwaLN%x$BRsFiBX8ny;=NB>VEp-=q*p!< z<9N(KpK%;lX`eigW5G~|-&-0-<=&uv=<$eAdCF3U>`_x&#ZUNnVhdYo`ZY^*O<=w$(_9msWdz@zaoLhGOc2Cc`V}<#?43Jdt2~Xmp<_FU-Z>fj*P}&;lw(g`lMN2%Po)f(k`=h&9 z%CWES4I(v5agQ=a=!5R;Y-2Y9U-+RepjTE!j;qSvH^#d-J#MTg7c8>5U1#Z|H6}Z8 zbbV*+^%;st(o%y3wg(%JyPRZ!-akFXnbFi{n>wKFLw(dvyxolJ_I0I^xOxu-)bH-! zyKPT$ol0ekDNeCgEELsSNkA$hy@pk~5T@3ni`UxJy_WVUf<$@3Ir5ob>Pr@*!cgcA z56-Hjs1bi72|iZfy!Z3Cf%F_(3Nem!km6Y z=8B#pH&A=WY?xKRH%}CqGt&8W>e7vNN9%;W^v=A62FtuF!)f5%`nW-8hU@X-w%oPm z@#4flDnE4$32oMu4Y`6OPlq_~zgeRqfkSpp%10xKs+H>H#a=USGPbsA&tXkr_!MI8 zh2zMy;5n(YRJS|R|L-p|7MQkztv!D(Yo69VHYvK4UQ2>mdlc#ArJ25d1Iba3#*(ij zXVFF5)i7ZGaz_tO(^^ZRJsfyZP7cp*?mN%zlyPorzVZB6ji)%fBj z&0|Kos*f)^$(Nrmg{pih-FHy5jFaX|k4_*~2VZ;)>F>F9C$VT9@kNi5lEbgE&{Tmh z;dfT!i^eGPC1d2v@VU$vB~uOk3G2P#oeGjv5|{=`f5k4Kl#O?Q`Tz`c8TeTV1FQ=d zExc^+AWMwcF5Boi_m3^(+R>pB*mZFFH>$yX;kg^PJYQOKwSSDUn=$m8#bi|BY?5~rg|!i?tQGJLTOW4s%&t}b)6X_e=oTiV}8ug_iAIFvW!i8 z#~4pDHHI-N3x;=#+|+Sn9ogXyq;T|&ea7@9%#Ec&#|152Ri>-ocVNc~cEV-kp9(dSi zsBh+>-si`-Plh_e8#d*0yB#_&hGMBVFLIT5qt>+2{h9NYHo%*myLKmgZ{MHnzin5~ zt=o1pbW}UtR2D7z;h{`+gf8CPdPh4amm3@!WV`0jpfYscM@O%QDY%Mq2*=v#>;e~) zQ={#7$ywap^xi^6p7Xv_d!)z1xR!Y2XyE%*%Bd_25pyz)`8R`Ui?WOAT&BJ_EUh94_%`=uZLcHFw zZ};w9d~iX_+HR`bbzhh!?q7qv?!o+y$Ib68$yfugy@4R%Dp}es>{eK1+Vd9L?fll` z#{AA#;5X|7IRgzO8+LPUZN{k1?VxNUo`}$Jy*f;da8}}F+&}uAvo3^^L_KVSaqzm?B=m9SlTg; zbzn~4N%i}>l7IIIosZ@Zg@`%aNB-0>)?U|Z9BzeOo=XMecu$Qmwv}$ZK8#bEOZ(JO zP?ZZ-jtJkEp(W5~0jxBkZ#Hpz zth2g*Vy>(7Cbc%}xuo=4%d=zTU76h4eigw+;gqq^XXz8Lu z$Zk@($44la5}7Tncb1dKn3*IEu>B4fW0fv0_Kd;Q7UoLcGN$cp4_27cYm-ZLP8l&Z zF~RTRb#=zT-%6NJI-H@7U_xl=m{gclrX@Aay}lPLeFq*kIC{U@MSV+Iuu#%Dtd7KJ zVWi~JB%$?k$8oQe$(@YZ`?nuh52gpEYNuy+WE{t@GS7u}9dr>}$K=z!-y@TJGKLmq zHT{*7YD^tj(CO7j35R51S9z}Cj+h{1dVVXWEmy5A9^!SeNs8YarGQ@w zv&wV(v9;bWh{&WxrfknTpyy4B+q3Lr+A$mGP2}G5jU=@}FTYQr% ztDt9+-a~mLBqbo7&1RQ|m*|`i;Oenqdsk|Mh3^b8ZRz<|?^o)C{KH`_A8~RRy?dGvX$FFK|;Z@WY53*%vbpPZ{b6 zZs^QInhyVsLcgF$jNxJORD0NA9lcm-T^SzD4wC1W`^V3^|I!~ZGnzkiz;v92 zM0!-w!MM%XaDXjFs*CvO=eiwOC{2FUwk8Qs`{*v+x+1AciCH}d@s z)gRU+;=99RW#l_O%e-K|_ZjNg_|C#^dUTM(a6DedExc4RBf$5RAA+PZl>X2Rpav}wNg2sO1beq8O%S?BD!-fS;ukHmM3u8;B57SqCOMVFEH z`tLW;-)9W8(%xhj9n4pEv$85Obd;RGls$-iT$E^VN~tBm0EtOQuY-)IoB<^*T(O+Jd5?lzc=CM^Ool!3wp>6xNC=&Gdw>Fmiejq@9jf)p(sTy zk#zTrlQcs|j!OA^vFo;f->a){o~ zcc-P5NcZ@gs=#07MbYr?O1$8?-L}V!f40vEE;=aeafEY9WyeaJ1*V62S+I;Z_=Ecu zS!arOn%fHR6)5i^OIhA7XtyC9$@6}5glZzS}3u$$ju>8r*?FTsKL?PXDCjFHk%@dAwz^vx#dkSQKJ!+ca&u|!Ft2Dcl%^%`2n~*@oig2QimZ3Eq2OxVrqI?)W$J1(mf8={9HcFR)}$#~PLn~( zyxxrH-MoIS*3k5h!l$Lvpd6;)bvqd;K}J-QD>H^V3fpG6qDIlL zGZZVym4MFRo-~h_PiOGX+ZP&;4YC>8#r$FHWi0&Bvf;L}y@)3QN|U$RhQ!19M#jPk zGi~kOwq>0OUa~9E81AO`v>mm)hc_-{qv+70KuI;))6=${v%irBPoh8)wP>WPVA`Ql zzBgO{NNok}{slz8q?ZyW(H*L4U?~+cQOskT;IXaL&p|}|swwLAQmfD;P}EUlx}F{C zwCbxqXM8QaJJ(QO_w3pm+q11tY1xz0+)viEGF9eG-hlr~bB6m@u=US8l*F74&tBcZ zcVzkWrnqHJU|sg>O-c`{h-ps`^4jz4<2sognK?Kv+1rAb&|W5~G#+^l#s9^EN1x*9 zGv@Nz8t|6{R-{s_9v@d(PeY;nHO#9SBd;>bcffkni8^_ue8hV#{ipaV$^)vDr9;^? z-N$)ogz(9tO=0{JDpQqs6Oe5g%d%ZJ<+|ZHKHu~? zuE$o%%fGbnh2#;sNwdadOw2#M=`K0U@0<}cPn^$xZ{x8t@P+nLdnlt+n&NoI(%I=r zNAhVi#xe%pRFVgbv15ihvW7~aT)JZ_Lx$Ti$|1=foh$S?eePf0&_Awgn*Tf>ixqkA z&Hqw!-n>Uwe3QQ{oSt}3_ck8&=~JnHweX0}cZ|}BT(aZxNxkiI{+xDObdsAv#ZrKj z(zM)6ilgcS9S3O<2@3%5@|cmAt5);hSMyi}{!YJAbCt)jU>HYrOo~@Vq!pCsna>3S z&xjVdj z;!UwFcTx5K;k4k@`lkBR^IKA(b zVH_BL;nQP$S0-}9>H3Vvyaglt4&>%!^?R72=Cb#(S>5A?GUBu8o~*3d!($_FqIHRO z*X#UA8P;7+I~X1xZp-~Q^Z4twRMrju06cK#Sc*El#Y@^sC$>h8(6;|5*_(acAf(3j ztGrKweU?u-%Q$melJ7~|tJigOkRyYlcxhp!)Kn_`oK7HdpJVi%_`V8#rf3gSo^{58 z`*-Gg{=2v4E%SkKQZV$N=L21NOxjjB;U*cpdDe0gve@wSm|7U=HQxM+8~P(TjVVBN zGS2v;6fWv{o~wmm-$n-~_YxD`b7*Y8xW z>A82*^pyFbwk;(aB0q7n1n}{_EWH!yw7FL8zs>#lWyhb{8hf(vGdtC|xnFp_DpN1J zRh5O_2a6o@)cv^b$GP(A7u4Q_deV*EuHU~w%Fgl${zGLh|6I_4;@XAO0g>L0YAlDOITU)9l-+y{8k-z@tg0>*F=^8uXZW4c>y+ z?&X@-zyP|`WL|IHj2G8gp7VHf=k=*7yiWZ0r;lga{`5)5`BcK`K99yfzI|rZ700`u z+_2r>^~A{J_$cisRWjLL?Nassz3!jeUi_3Z{=?(W?4d-FWG5K7D-P{r^IIE%Evr=Mk^};!N>+p7^}B zOoo{H3SNUA6R*Kr@H)3v^BNeydz;Pc>+#|`%VzVstqQL{{^6&OU-Hv$T=esLel_v> zqwAM;USCA>dVuEj$CUcVYIuCr`5uj5sC zz2@F`9lzmKM-xu$eY7ysb+W$!KL z^$k3)zrV!1UVGtF&MeJshj=|#JFh{HiPzvQc%8dS)@zyHOT_Dq*W$%>md&2meN}k< zjZ5!JuKl;`X}$bo(vSAhzxek2Js(<}9s1xlf7kT^vY6U>`G4Q=&jT0HKI=;QH?rt- zzna>w{DBMyJtkg*x8QZEL)L4V-)N!9^LpdiqK9Xy@cN;zyf^vmFJDdi(U*wN|4s3_ zd-&l+XVuSq31h=$PiAn4tmpn;Mf-W+wxsjWSkmccy=-&MyaqicUW2#bwR^R!*D}A+ z;U@EX)7dhwXR7czHoAZD>3=@-q;t{Eq%-hXg6H+gKij@I_1azZbLmrNH;cvfX#{;| zF3yJ2RYdw4i<<0ab6+8ReL3OGZlHO6QCVB1R!cu&UV|PJufbdJy0B5!Ynk78Ta$Uc zxnUb=lh^B96<+`1M?P^pH~sY|{d=xw9oln!`l_YX&0@6Q8u;3Ar<-gkPVKf7&|~5? zcne+fAZeSCJ?56f&Rmz;maap!?0-gCu>&jTMN zJ^XhGXRo5Qqw)vy8uXZW4c>y+scU7umidhqnmn&Jo-KQ>d=*~LT=&Z3-MfFZ-HDa# zW;yqY@l)7i3K7pm}j&9>>|Cw}#58f%)@j`n^0`%j41FFivteBoeSyaqicUW2#bb?$mu zuVsEO6|c`0Ki7#Wy#7w^6UV!s|AVsi`dZ@k>_0ED40lO4OVOHL=Xwo#OuPnf!Ryp( zWxba9y+pj;c((XHidA@h^4jU+m;LGZqFS$IUdLW=#qov9&%nIyBRM`tz7Ms>1}DrV zWH{(C@fy4ZuidS(Ud#N(o0}}dH=ZrNk5g56J^a2;9N+yN;kEd$uVr2jEwPQXjpp@! zn%4{U@f!4)cn#iy*M%Epy_WgCRJ=Z0WVm~IW&iciD_(iL_c7wN&wu?W$142e63^?4 zcutdU#`D^#-KPn9OuPnf!RuVNtk*KXmx$M!&lWwrtqQMCPJZvn2R}2h=$!mI>1MB` zfAQ^aedBA6FLYI3uPHP)GdM9Gn;027oSv){TZU2gm%ZfY`X=dRUngE?=wIazWH{(C z@fy4ZuT$G)y_Wfn7Md!<@zMs$X79P;Re1gQ+hfUh4?IR|<|y%*{U7n|16Tjf;$>et zm%f)i98wtb2O^dJ)YwlaA51v2tCG&bdx+2Md#U^ZuR)KA*WfL9?IvWsmidhqVsCo* zV*c45H~czE2ZZl1^DSbc&CV|KqWw zb5W9fA-l=%RsPB6Kl?n6?`2*;L$RWu{}}yD|5-l~SfJh+wLUs_fs=4oQBQN1{kEcm zn(vumv7B=fPykcXsSNGpbr~9&}=-*CneG!~^xcQ09Bf%5iues9S@WG)5xr*k!a+R~a zxwvsoQmompB{ItlH{O8M`9tgmGj2e?1vh^X!j0g>!wuwaK<;?BY0%iyJlwpl$+*!2 zpKB4^ELd;@`YpJjgQ5X>BRBzW0AE+|gzr%U4WrgaKO9HnCYM?3oxjxknw_JRoU-&- zoj>JU1UCa)!}8`L8Y|HMSlK!?ds7H6qQ?O*uIO{Y;f^XNqSi-$Sg+yzPt)`o)&&c{ zlq|FeUYr}lcwxN;^xNdj>CKEJPJkQm#}z!`yUNUkFAbDY>zA5*o!&P$ zSfB*rE~o^Ph_XZca717%lK>UrK(G5Td8vA#?AFdq@P3D(evn^|ExD`v0Mgw;+`-2 z>&2AL3nBR;g3sB$&wk0@BXsWJr}Y=)Z4G+`n-n&;k$=} z3uGP$K0u$wL4%tfdWobg?V%ex@ydqE^F<%Ytq$5*c8yIr*@?c}-%#g!Y3}6TpLGAe zlryN#7cA??83(+sfc_7c>93kJRzy6!2tGW#tP#8fI9@=1IbO>5$0{C0@ZsS_ z_I+Tk9 zj82hJp+!H8gLwi43|%mMrFLn<7Yt$;p4eOGRA9+YNdU{CC2FzZeQ6yZdOUrYQXy|_ zFvOS*UyG~jFnm2F3#F97z><_tK$ysw{rSU-vlA~T<@O94zGlC*LmkMUeTXnhIGz1p zlu+lwkU^*L-OrT=mI$4}c^#xp_z?Vc&EKQeM?;kj9(bybl9Lz|-y69fx8G`VAYASr|N4QzhX4`?5fA5DsJmWC3J@dyAG0kQr#R`Ldz04RYPGp&+tB z%AjoMt3fs_YF~lY)h-)^&X$%9 zr{0w;wzzBn{ncax@DJH=zE3tl7C<)S_KGuI^asd>lM~@Rg?6OX7p5W3H&ux?7Ik}N zST=l-_7wkR3s(P{$b!F?@^7Ua(80h#*^mp!hMWYeqx{~6&5IAd;uFt--q215*^&t- z_MxPcqr*+k&(eNkM`%xxc_y%@5c(k-+&|IugO4cpjEv#OhRUe*(da5CMI3Enu=>I+ zi_Y9*3HKjb#EJSZ;XMUA#X$d@>=k&tues)$oAA#cq@#?Gf)funPs_X!Jb_<(250bN zLuJ(ZXmm+%Gw}XIyhU&`XTc5V_v6NK$jKr9Lbwr}c)0mf!A(H!ki2O8gaa|XS@MQ< z(MsMlFX(vZlg{jC6R8%#P4~Zs<&AQt3jKa(2g{leUIZT=UcMoC5gcKDlbnc#mxyu- z{a6ybEIg6Ovrv|AWO13{#ceQo$iRP?wJ{r2FmVWsh-_jU^9oeqhE6=nvxMnG>f^ zU$o8_Y%2Cj;Ke*GyqhiU4e%!N25YWs~u+=mzTbFb9T$sdOC zqJr9m{yCrh&OZjBeUjkB!_D7|9wT@{UB&kZJL_iQhWFL#5LMHHlrvv;=Dv_fwFquz zPla)#>@Y$<^ce6xgcrewhZpgW1mz9z(&$d9S$JuB>=FA`#y_0Q`0#?UT8U-sKh1an z{lRsK#-Ln}5qtnI7$aA3gzvyhV^Kkl(=5EKhJ0ySkg}$*?aER@+m*a7Eg0~^_7>2O zAZ2BE>7qZtVQM?&4M#IdD8K*^BEH#>!wtbP`%kg}z5vlI@KD2Jo!T!^uoBgx`Q$jw zk92G7XiweIEZ>opTgsrv`dGkY4SG>>6zqxL`S^3-v6d)Umr_fz$GX-iSfMj0SwIiU zs8Os@>!Tk{Ux_#hmR6!%i>ySpC|J;6X(i&QHsBx8Ea%eiAR8bHARF8R5(O(!E#Tq6 zh2d1aJ?W|a*~yWqk!cb$`>7qXr+UtOguL_D6wUI_2`Bd+O40j1O4s{038(vep=cI&v({2PYrfDA z+2DRxj|1pK*`&+p!m_pSXaS^Jz5Ie_tm zQV9B?eU^^M2_QUxKwt(0281Z2~L0;jFBsN!uNf{!;|T{4$q;cE~D1R+mPEgcVXygrOF-MJ25ymIXYN} z2&4tZc_>-%;bu7qmRy6meNS3&1NwoROG$kDKOys(C}2U{`0Mb`XOm*m)SOkU%+0)a z*(oML{?z)t`xnFVhOHh@tZh~gY)DYLQ0N6ekkQz{V8en9Orb}P>WGm8{avDP{Ec{j zt!344{DZP#*{scG?zK{WTPtwE4NSqO;BX(@zmmH~q`c+I&5Pr!4?lV4kLpku7MqNZ zy`3;mM|Elq#~1n`C)^=D9>MXA8h#eFKKipHVbv6lU-YdnXlq55mauBjkM)IVM<~8A zOjdB>;bvIok>Ckq7d4zdYJK!$NpM5q`0hV0udo4(N4=#j93S-ial_$A_!rVk1ScMD zGJ>0c+|l8(b=#{vvYI7tD2X{~T6DKjv)sTOE*pDiGTtJ%v4!J<{(u`e99}K>@bGfC z;6-o*hMzs*_)CD7@pmLsErJ(YI6mkv$BQ8xU-04KWmNDYIP&nKj{7tkG|;@`KIh}O zPqV_=_;}&KuO>1rf)`sjKIr#5Yj`gc3a=J?cz78TyaU}q27&+1Kb9mMe<7DFEHk{MZfeXyXbZ;&{eJl(V_qJ{ zCinnez!z6=gzr(q>7&+1Kb9mM|Ds&7xXke4?raP%ws3sVAH+*29AE5}z>E8uQurTu z#AVd5#i;esm!%5FcfV7z!z>5?5XPh4(iV;n`pfMwrMHLdFoF{gH(llSZ`4G%Y@?Q# zX5ofHsG1v&&$ja7yOMDqZb0)&EN$WVpdWe+Xb<5<@ZsS_{3Ahm1H3f4Q)(7ocwepj ziA~!l>0>`BA6{0noUw)DgZ|*UM7Sx}V+0?-3vlHMj_@6LS*hXpGd_ReO2&&V93S)} zAj%8JhvU@dn1-X-E3wg*h0E`l=1>SYW)Y5m0X)|5P{U)LyHyg%N$4$*xI`Z7x?}RI zdaQ4dm3p_7d!^i>%b>@)=tCgWni5YnO7>Vk^y7;tI_pd)o+VERuflzN8yh8_t<_^K z^h2_^H)^`UN0d=LKvCysZy=34|eHjg#v zFW)IG+!(@(;KRd9LhvFu!u(#*9_x)CNETWIFE)=g=r6}hcUZm%K0Lha6ubzIJiM%M zk9Dy{@M7~=gMR zUMF}F9AV6&dYq%yM?aRzV;yf1yx2U}pdagz)nhIA@bCgVgWw2!it2HWS|9yb5|8!l z`;)0T!-*AN^PokM+~PoXjjUyri0( zKo0Z=@e=Y_i@g$farf)>2>d}A)e{u8KKij#9_ySBFDuzIVDngm{&G7EM%{1=t>DDN z%>mJ41W%|5kJ5_tSkr}Lc^_^-^GYmj9&6AKJqEOg>@b244=>^$3CbJbWuv^BQa3$l#=CKC-A&)g2rZ$f?9L*@9 z07KveJ=So{hCJ5rP{U)Ldc7o&le5-9V)GNoHMVB5$GWa-ly8%jTgsrv`jiiWpw(aY zWezXi`B$f(1CO;NkemN#(&_qm?FrNmL8QvwJw4KyFWZGP7g)U>eWVQr7!? z@SQ9hTuLDKtSy0DpU8rrlX9TE49bS!`-9)Rzkb=a$AV9nM?$d6jTZaN^|55K9ej9MS9HUAnR!cE&JlksJS8;nQ2W%qm-H=Ir#^!wKoUN87xk=#KZ zUIZT=ULbD+^2X!$?e+FhKOeO|T3r&nWPT%=Y7xAgwBQBwSH+9q19$;nT)`2(d;ER_ zep6o=wLV%~61>dklbII5%k1x&J12)C*E=2-W8 z=u=6&f2EhR-wNYpp5pMaAHn{l@CL~bCpHX>OVe!^o9e!)U3H~y+r>fAv!o2}PuzC1 z{tmhy|M91v{QeDzGrvFSesjW^dx-WYpX9ws(ixadI0Nqq?N18d4J5c0I;+j=sJ4fw z^)bFpw_Wg<{J4r~{Y1&|H7JLM#f*f79D zcgw3Tc=Rofvo|}GzIh@$J-%yfe7b?$wyJJSRi@nc*WvXwmn<8eNB@3ev0VgTaNAivazGHG*tcr%Sdg!H0*J zy9F-+`JwUBm|n+y>p3(ynvTWy9lV=TkFQ5>>n~S{+;A^7=QOVyFG_BFdq<&#@xnGw z&<~sE%MGk4vv~?mJlu>5ZUj%Lu5r_-f1dP}^wi+UXbCun(nr!`4FKqTtT)CS1Pv%O z3O9ebqu9c@VL1c(O>*Y>^mlJv5`1`g856t+j>_>;_d#t`cY3BK(qo6GGO>7KWO96T zuu;4?z)Q1o%__Y7$qx7bEBRIsgy4041^<9`3G|mojFE4p`?9C#-%bxNf)5Wbvw|1F z5r#_3m-_b;sJ~}qXf%Cqnk3BGh?ggK#9JIMpuZe1hKN+bhldy0_ql>2@LS_$Q^Ome zp3LA-I@WU}o1KbeJ6#R=(yU9Llzf@r(dM&xwVHfk`v&Mo#8~OlCjkTi0zkL|9DMKZ zPtQ!H$A>jll#X-MeBT{A*2mWCc=K+9hfGmJ)aG%i^4?$*Nu$IIqzN!9APu)iGw~1_czb=Ea z0rc6*_&;Bom`^--=4C@S$%X;K`NG2_4@f@Dl5AKA%Leq@+e8SxkPU85(~aj)YNfDY zo$%~6iqF20jG-q&jz!SD(n}8q!gmh`@058U_`o=595l90^E=L3qd3o<;v>mSi>wjg zCrZWv8>>LSVT~v^iVHqGygVp)3CItPmlbFfXSp%(XNg=3weA4-YT0 z?{fu5<#<_vMscOb6cSxNn^&vJ7dDE6{;*M800Dpi5Uv0R-&d?roHs^YkA#ejpnIj4 zFnqz#1;bb2U$o&11~H7o66IyDd&kX&uP@R`*8j3ZgSsD-h4I&<%uD%Ox(ph=`g{U{ zY0XJqc9h?a-;{WK)&Ds2hOcK-XgfM0=z6dk;t?NUTk^ULBAg_#(N(G zA0A%j1TTUk4=*b`FMF;<@M6o$4*LCuRo>8tZiW_oczF3$!HeL?!^;ZK%bsr$yx8)x zgML3=&Nbmh@ZsU*EaN6C0O@krABr{!gjNhKP?i|rzH0 zC@;I%D}fjHlX^W0j(F6(>QU>XKWvBL3@+}PP_Q~3_smYNL?&ba0l81V0(s}xQPd5_=ZsZ z*f0a+MN#XcKb*5r?T{`DYP=1$z~gp`ZeL$!pWM#Ic1R0}8I^k* z_a2(Vho(ldWB5g#Wz_m;Znd+hanP(4hH;Rh8_az3dpWEyx$eera8l#|#uI`c^kao7 zo#Ph47z7AjfU?19i0Vx|)79kUrYu}%KDg`zg*UKu{xF*i3kudWu+Z5w4JZgGAwXQg zk6+W^pRu4`N?-I=8>$9W3#b~Y|In%i-VB14NY$WpiS=#Mp=$itrfPgnREv2jf4{s8 zsv5_9qKIjA|5_XIP`=^iUrgNg_BCfdRbn@ZN{42HOIN@YK9O`z()WQHR1KjY62z5p z03T7FO%kN3ss@kS#$R1_62xtAiLt60!gt^Re0K#O_#RbNh*}^0Xu7JwIGFutGUuD$ z%R$v}8+78>R1MG{Ry9O01_1(wpgfxdMRW70lW=|fvomkcW=GS5V|xbcNK7Sl zVs%wQC#Ymq<8iWTSZ|d2f~Xd~QZAI2K~=-|YV~7ER1K65{MIidzTI(R$>Z?Bu~L6t zO35c)k#sVTQAz5?9DR?`_rRz4mw`BZp&t^&m2n7EbA%7UU)TISYJD`s_EM#4G;25O z&^VF3G{4N2m_mc9#_YE=|1qA}&4PX`F{QMa0tf&E6)i_k>f>v}#MDX3{j=%&w=4SU!@-FEiYLFZGtO8_c)?{pGmv zU4|M=+$}iqa09s;kUJi38jLAw9&TROT-?aO7g_{23l`jf{&L*-P#MIH-~_nAldj+i z-_=DT_|iZbwSK8djhkH4LKpR$i!FkifvsVA!?}<^e|hMlAs3S9alnf!`do=W`lqOJ zB5Hl~hxMAKhDft6Se#3`-z$aGqpcNL-WbLU>ouU?CTBt+uYwcc24m$4p71?t2x8Rw z=!fIHuE`a!1QB3{d`_k;M>x(4dzF>cCjVAaL*%y36%5O?}LYLL{*9F;Mqdfm>A6%U6e93cQ z;{O=w`@fTL_J5cHus%i?FMgc%+n=evzZUu-Pu!<9-QXk2sOw17`shc~_ty@MTV^hq z^2rmlbvBoU1_Kvu`)kl|TZcmXYr%`tuN&ZAN(!yU;opR z`>(ISK%?w_7v0(PDDA1qe?36{>)8iszx_yPe_gmv+xggUsSXAT{g5Z_Uu*jDT9i@c zLDc%_2i+#tT)lw zd|T}_4=>tp-8?_ihsk#K(L{Wi;RSrDyS(0v7tmjhm+tP69Y*j0yrBJ{oB>`M74&B{ zUb-Jkqyl(Jj!%w^HhjDmqj>g}a~8aS{&Kuf|AYHzS$~6g2~rxB-%;zA`XlF0o3)ST zH9YmvWF~-@QhO`wr*4U-168b-@OlLLgLv`phuD7v{mZ7`LSIGcLf;dd1@&9#v(Rtd zpU4pr@gt$11ONCTrQhOk5=UtEP7IDs4reEh;Gr5yuTI_PQ1#2%fArmRS2_P_i_iRf z(PxWNez&}=dPGF@+LV-k^v8!1vxOIJJLB=0u@}+_R66c3^Ipypb0XcFYJJmR7r~^^!g9Z;bFEQgLIX#-5z{53_gqykFOXOPw zH{E|^#trBPZhqP+w>pM!BRBzWFx0N#3E!jobE4KqKfJhwOU=0HyZsG#w6>DhooC*g zEG#qJq#8UIaMFSs&=1_aT#a5SzB_~)(a(ao2@ZNxeIsgp^oRA8rXGrC9WS%|5_Mrb z>Mq|CmN&ewfxd0q*I=K5(uJNc_zCW7u#dsMrf^!$or(P({a&Ig=;{uP<9$uVE9kx_ z`rETo{zS?z>N2>mDYon1gU+1nXHed9<>tkO7jO9T8Q<5;wv(McnQ&%)iS{?Fr~fS3 z?01Ch_Mt22gnq~g_xt7afzGH`$VIJ>ek{pVVsr&vaha_z7>~M3%N2B>AL|Rhx8fCa zf)fun&&a$HJfUAvuaJvcAN^Po+|U(t?)R6MzX#({Z)v-N4)ptRQ}GHq!HI{Pe-+#W zq;d!*~&VczF4N;6-rc;bnziL6>O}yx6Xw1O5I~`Mj42T|p=K@bGd< z@FFq@#3-3+FeYgS5E3vd)K?nMw$AI<_UIZT= zUc^5VlsCZ3a~*%XR9DcYe0W*Oa>jNA9q13PON5(pJx1^WyZ~3O;0WJ=m*@TpI=SMq zX(^R8h4Vgt;Y!Af?Fu^3A4-S{hpEjm4M($AVxuh!m)|kXp;vIs;tIM8cn3C5e}RV@ z9_!qyT}ng3i-E-Mk?<9Cd(xAc9oexoo~fne=Nk;dRj+4{^@Wv^wVy95^+i%%EM=Q6 zgC6Vn71}~!>-)kl{L7d3KRkQpJ=WcHs%+uY31|Erbg4agtY;}=efCo!k9Fbkz!h{t zKO~FmYPy5;-Iku18ab4n4F0~>?@{Zcou==Qc-;DaDVg!DL}=@5E>jIg;tu?_=09lj zBKw7Y|4Ou)9%8EP%l7%??f_Mkc2Q#}3t@@-SXf?@AVy8D885*Q4&wnB@!T$4>fUC0V+a zM}T(IZ}B_=f)5Wb(BlM0;FIusdvkV7euX(eyn!7^$Cz>S>Tjy;i2Ryp9PN8{1y9&eKw2(-rIow zG7FpnhycO^h!~K90;6FKM20$QeQ<0^0J89&r0X+~tz>{KSO5b0!vGOL03cw5E5N~b zwtV2{M#`x5(dLo>l@++kyf%{_Ilwz`sOCgHzmv+I6;0X23o>O8=fR}{}6S)?_i|v#c=r701Z1|Lz z;KReqTEUCp$ivH7b4pC`(lj5RmM{4h!Heyb80h!=_}ByxIwdCf@bK~~!HeL?!^>H7 zN^A-6Lh_~1B6zW#5(E8yyckc32|hf$#04*cBj6?KDX*yY(GR}8PWfz(ti9k-Iz7Ny zD0{Mp?nzH6pYYDXLsQxMvVG|{7h41`wo_uDAM26zl$hYd!wc*Tf+O%L>M5_N_0f-} zpAuuc#O!Y*-8U{TA7Adq#(aFXQ(~asFJENL%cH9WAHWOv;tG!NJ?bg1sP)m0=Et-V zUY^b;ZZ?V@BX~khoZ_fEJ)69sS-5HXExg?~EjqK8Co(?V zoCl&;U}-xg2Ku4Lfb%jp}iZS|9ybs=TI| z7Qu_nV-5PT9$7usf)5Wburmmbz^AAl=cx73kEVO9c|CgOBgxz{!%Lybc}+pTU%tqg zms@%TAHWOv;tG!NJ*vk!YJK#h=^kswOZP{T`DKQeT$A&fg8m?0LLO_eR{}3?O0P%Y z56Y;X!>IMqkEP0MTJYgzC3^;J9&6BFZim6BtCR1iX>VOR{Vq81aPvCRV+2pA36Iiq z@3EG=gH5~l`^rUU?qi8!i{QrQu?GFnW5D;29Y*ls;YIu-L3snbG`dr2mYm^rN!^p! zERQw&R@y$6bSGQG4rB9JgZ|*UM7Sx}V+0?-3vlHMj_@6LsoSw9FK8BCRy#|R*R;#$ zFI>s%lFefc`a>RTI8JRIYdD%wLIDPVf*xx)X5q1Z0X)|5P{U(gIA43L@nRrx;rk!D zn19Aittz&A`ry#Wy(5z&*|DDKiQ&Oo(tY)m>cpf{U1?6)V?9iHO@AO;O77D?eBx(r z!asMftkegj>@6>Y9_tw&0{LCR&x`)``N^Rh{*XM@FQtEH@Qih=pUzch=oZdLlFs9E zNoRq+pFErl_AkFv-`L9hROvW`en=K~zotJ}FKXVMsP)kw&fCLh26C4L^T+{dc(TTl z$F1$dp>e9Q_H*`_yQ{Gn@P&7TZ|qe#5Wagjzgqz5O{_-p-T)cU0s zw=22Pv>T~r|ME%4d1^<>hnJPCk;HbH@dEm>|0(*>{HV!g2)q(2eq#RatW2!P~l=bhJShIW{{riaz^3W=|M1N7bw~1ysq|2aYiRWzP z55D!2#9QNUC#~`f$3o8aQr4cklFsnv5>ctc6p~2$=(Vf^kT-leP+#4aiD*r zjqIwwZ&2?Gz4roVdvj;}z$vyrS;1=g{D2Iu_q|@b2`Xsr7YN_bPDqCe{?(OM^So+vvp& z;wAQniChcgrHw`x^v{W=@N#d&OFxwPU<4-~ZhlU1BX~kBjhp({d(=;)rv^txOTaml z=DR!U2T*03dIJg#uhGXIN#n?ky zCemYvr!uiPU2-r!N>207K(tQ^Omep3LA7T_JTOn~ii4gR>g)rCFKKS-!-+kjVKwCaor4`0yv_htE!> zD^@0V0R#X7K)3=NeDCj1&rGGqhWh*Qo9CuHeOjBu+_fP^cVuE}da!P{04pp-GAgv_ zhZmN4LI@09FnpyhkhIm}TE*~mfBq5WQdJXvf*q=QgRy6@zKO4E#kgAM#`?2X(=B(a zoGJSEti|x<4$HzgD&?4zy> z{!`9EYLOfxi;hd*ywbv03s)CPr$R;Rf@$-g3c$8_-`fZUiU54f^2iKz9_pQfktQ@Y^B#hec>%R#Tf zc+_3q7{-e-%nSWCITH$Y7n}e$=!YwK!uP1b$5HE}A5Bl^Coj&o2yW&KxKW0Aqns%> zoORJyVc%zqWyXFPrMKS{JYh~^e~tY#_SfzjNwOsYCg6MbBM*l{mX&dCe|BuV`wx#qx<3E3w|S#5tE?9i64U3&awpLpQR@2|gh;Zx3|yvKeu zC2^ts^~dS^B7ZOcq&}c82=n&WLT6B(l-F_`@FDp7TE9oFk9L~A4)K_EZ(1z0h&(wd z{Kt4=e+~L;S%>Dy&W3ppIZ(JzjxLD34ey^j@54bm+u&$#_Q1{C@kDLqj_hc5;=tgM z@dgC}%Yh92`;pDgHYM{O<-PKKMwdZ3kjuTR_z2ml@X3jt4du=6_@~8xeCI}z1LG8A zb_S0w6wZ6fanB)4C+Yg3OX(mXecwpm10VOLS|9P`fY4n{4$wUUfj8CnHER7*Yhq_> z)^!IwZnN7Ki_1(7xDBQwpA-ILJQ)Y9SAc%(Uu3#S0H!YlS>^}u;>tY1`%tQRi!Tk7 zQR}10b8zVLr9r!FgDvnJb6&CNPA@OJEXJeWviqmP`xnLw=>Mn$76sqy$rr%~@Pg-D z!4bZ18y(LK;!6W%)cU0+C4jYA_K|@s0@%X>vaJGyC%V*Z-p}#|)&%H-T7f`Q`?_ zC;X08&LsW&Pn$mfCeh#DEahx@8Pw->uS)+fh(3?<;!l2M@rq&A=a<%R4!Py^ zIrBd`?l_%VpC6*{?rHj7{wZ7+(C3AIthesZYx>J;IZjkNU)1`g{>V|}X05k8Zry7a zQ_F0FmD7$;FIEagvctbx(64C6ZqwCGY%fkA_ zj1Mo%!Czh)k2-(4-i#N}@5jppfAO&|gaUX4AHWM*56T(frBOlOJo(b(Qs&CbYWl7FzvOZlDgS2c3iT)yf~oW3jL5L?pw|JZB%=6)cPedw7$}` zlo>p33#%3jK6$c|^_AI|nDrIV4|$@ei?T1!(EIGwf)5Wbm^XqW@JU&N8_g(5FNs7`NYqhCvcmxVQp?!C*)zmaM%et5xx7trs+OPM{_^KZ!d8^jCvgHrJuUm7T*)<=^~ z_lNNs?)=S@@nwb=j7PoYz@=vS0{VS;DSI{Jh5Z}Qzij#~^i`CQJFegivK#s>^jYY) z?n@*tOYFGlMC`3|%6_|Zdh8H~Ve!c)6_>SZtgch?^mzJkdZNK-4EDdQau(}}%X+8i zw^9c6+he|ik)YLIKJ`ZA6vp*9_d0GDAWhd@E?U+3W zUN=mLF4!iVSO0vFEZ@OWk09AbRfWJ`BH<)f1QVHyPOT#nyPS z#8c$+<#B+1_c)jU|KNkI<8qLGl9F9Au-Ovdr%3Lk?j7rorz$xaBiNrT6$fgJp!^YI zg!ol`$-uye$IB5zZUV1SZn9>{ljarU*IZk+?{1dPh=1c|#PCRZt32wj>d33o+ zKHjr_cFDjHyBC>sFwr!}y|h8$ruyo}WRAH}dWP~x>6t(>F!15=@+t5Fj@aKWFX`7v z=5I1E#mn+W)5iy*8hOO8vFpT2olX7SDIxf;NS$IB#m0Y_{rmzQ2l2ByZPWsRAf z^FsN9yaboO~`RQ{IGImpXL;Y{JgL2&$x2y?Ynlk-N(!In(nb_eg3M-W}Rs=u=xy0#hoJlR2a`Dl132-xxexaXcw*D79oor{ zsY=uOJZVR`sV{5v=Y*Sy7;Y%P#!XSUao!B7PnhvysHb=x9pR<^ z+(soQyiCXNLisgbiXmRWhsVqP-~}A9pIrTtegP*d{j!+)CDO6Vt4&_ka>7gXr_uU_ z^6QS(!5g35KXHqsypj2gW5<9GkC)xx1st*EUHxLfOGf&oQ@l*(gqOajqIseGeqJ_9 z=ZAO!A097%175%pd096$dd<)^!z07vH}X%3O4ItSlOdUDR!Lp(!_A!VQjg(<@^d_b zdqD-V%F7q@3_d(w=w|>&?)NS0BC(cDUZ(YV?!{KawRf``kCb1+`opQ2F5{(i)|Im+ zfoFT^<>1ev^$X?q>lf7Zg3g@r2z-zi{=N;4cx<|joN0YtN9Ow+JG|_gvUhfuKgLeU zi}iFgFO*;BW#6Ow_aAwRFPT65mE^^)yWP{d#Dg1Wr6|_P~w-Pps+myTQylD{eARdb{qq5>W8OR4FIi zRG$fR|R;@v_J&xx8exyBGxA=vy!B<#nZc1TQL}fbuh-z;V1R zm;c~`Y24FVTxe!V1K7p@#pn#>$WbTa!tCR6ppKVv#hNSBT(K@4hcpFvWJA8|yfS}` zEBRuza~+8v<9ZMyH%o2B`cWT&5H(O7^vAfYcgc$N8B=XP#sxWb%@Pnw4on}zGOf?+ z>C9tXS4`D>BN5Nli)GwnT$F#dk!X=L2>It@Twf9GK;1xHK;2-!5RZ5ws)g;DZHm4W z&u{TUM77PDqOS>E@DR#}wNld!-p}Gg4bdzt4}OZi7m02d++($yq7U*@H`ssY%CF05 zYBiYFZ(UCZQuJ9fdnSFlfdgghob&Hf>CBYgwwM%slwX_Ggu|r4hsO)=8*s#yqLrF9 zi%E98bRb2awPdR4>FF&{B9VJTJ4eSQ(THZ z%CGSvkCNV`o+iCX*`sPwOuH*?QcQc5rA>PeoUv_b-_o9?ecOBy(iC70OzE=US}NV- zSIvDBZ7uZ(>|2&|*te9I@1UGR4>U2)WqHuIaJSwqdf>3BwzqJH{L};XH(j~)1~%QQ)U-aYN9ln~pW1M? zaKC!0)Ma|WPC3tw+rpjl$LWF4W5M9Ws$O zCT@ngu81hHYenCmx&n$xQ3>Ix>%D!w=8ogqyf6 z+$n!h&jiz*C_fwLeQ|y^&X-x*oNt0B-jnpRaX!uYb?F4en84r0e(%86&8Zx1YJNTI z*3I9=yny92j=zsmn_t_v2Dfgu_u+decb@y>M%C(rj4sXMUa4Q$DKQtidV!?cL?KuceH_kK4ML@>8G0 zKIMb^gS^+?D+$-3f1Q)jh~jIEnXIpHO4>t@PN{lfP4+qcSI;dmNnuh9NrX=~%Q z-(FE$H*>sJi6T|7tonad24B^c|8my7E8M@S?SESDudjZ=O85J%zp4LU^5pF+aIV0X z9`YM_GSVsWf2!`Gzq{>vs2%1*JJ6n|{Z4z{J`r)DSU2N+GWealk5ZpERE9Q}$JE9j zmzQ_0-LZYk*w77SeyNR;Rr;j*_>Qr%WI9XqK!mdAcgg#I;o{a{Oj>9DLOV zKlhw_Zt^`P3HdqR+COyLBUnqeZZ2;cA05;G+WxU=eV$1+a*^I#VA)6fwIhcjYs2WK zx0T0Jo$IJT_pAB1>4x>PR(mA;v?vo!Dy}cptqTlLcD+vkCz{V7jVRWa?|+pD0yjGzjek= z@N&geGbg+hHb?6h%CGTqf!preF7WgV`0#jn0=$4D_ET~A`tsK8vKJlykgznZ-#T3< zc)5ORCMUd1$M8b={k$w&whVJ@-*^N*JYFo={osiGbji@B9b1RS(k832OzZPHEUN>& zRR8ys{rfFHb}!p6)pE3cq5OVclE-qJ`&@vX-TVCHRvTd>`n694D?&Y{1%eRHTC=5;#+`Tp8Nm#pMlzdzKS z$#oX4t8ksA`BFTei1;biEqv}CZJlN9@XqxYCSG%pT4^?s;bk~mtZxy|@l$c@EQ>L} zT7vQjt<=_8ydTDg65^#;{_FYoHE#Rj>%`mgp{gU{@>tfTkHZUqC@ zHaWge9S2`CM}0Q9&I0*4zT37df3TKinU2q<^;_5D&NuC>;-*x)S@&H~^NsI4J>Pu3 z+y87&bzeLFa>&o|-Mw9$@l3wz%Z>~_JYIO;fFu5{6Ze!h`G)+6X?Li>kQZKou4kOyIGz8S zyfm%PGj@iT`@Y)jGG3Y~pI@uT@Iv{0yufBw_Op){jK4ZB>>rjX?_O4S^^13u{zK+* zna&vg;HsG}<0Wki4jvP&Unswim%u61xTWIkXm`cM+0kD0N{nANIHT^SeM@_m_HFGX zJa>|51t)_WTEJ94s~5@X*|{yFVi@Zs^o`vx5G zzH`Q(UbJr&FZKVY(eLAhI+C)_$I?D8Tl<#sM~^=~dj))u7q*SAXH4x=)B3!w%K-(vjLd13#s>{wj>TcS%v}bAGmQKcVukhpYBC^jf_nO!8x0960zD<;0?pWBj zDCe?o^=mn3`Q_@e>(*^*H}H=&tirB_wM&k7hj#-H<(Gq;bLkV){BWlA+0L2gUr=o} zaZjU`6MYhwUykxm#H_pepHJH@-{E~vJz)3ac^S-i*xBfs@kpZBaO)}(*t%&J9IEEk2>V%JQwX9&T|YtJYIO; zfFt&k)8FaS${F*<>&QILRPi#stI_oFa(L@xz4s|Dk9q_zcinmCS3-FR!3TL^1L=B( zyrf;q$xgp?=DDhwobVExM?HcUVIizvF#hVikQfs7ixybV#;oJ;dRf|iuy0Z7_U+7k-9zm5BOkOjKTmA6$%fS@bKMa+zEzI3SMxD< zH$&B*&U2cOb1r>ix(AqPeTtF!9%8D^s-I}|`}7IV)r)1^9%7V#u06!aKlc#(yeJ6j z2I>OphT5yJ#)~;H+jDws!iiyAvt#R~ad|XPJ=4E_XzS+D>ywQ-Zk;}-(rHVRD+uKS zdq8xOG5tPiZRPty&MpSr<5$(7&xU3^$;_DG9mTA$amKyou>nk%Ay_-{FtgVtIkIm%TKtiV8?~HpQ+P70 zZ=9HE$RC{BR2v~)z=y}nE5Qpm;{7dp!i*O~J;m$j2ru>LHYRhz%XADclwaee7~%zd zc)XknUceFi$<;4uJ#E?Pm&KO5cSCKF9%C=FDPC-fvY8WJsy~g^FO*-O>kQub?EZ;c zWF?hzWANeeavFF6M{IgmzZme6k$&kEFEcserSGX|UMRnxm(9}oAzr|T$IDXi0*=Vb zy0Ot~hOQYNNt+ zs~$e)!f9O43KyDL(g3zGK>34K)QPw-`#4Utlq=R;q2`Kp>D72@15qvP(9Y}zekOmu z?NY5+&$=7`ZGB!l*#M6+1()P^O;eQHO@ z;A`d_Em|A$Q?uABT)Bg_=F{#5?hGlj-3?T`RsT<;=^Kf7Gw5wFpN?zG(#@#jb_1vU zaTaeV3KyJs+!S!%fG4(6;xlo!JfCz9}aj-}Ay*Rn!cd^0&Zv09aDPs?iQ5gF@&{+wk{zyayy)ZO*La>^*m2~=hCSEnANP}~o-nP? z>&e`c=h%YxG)g{Ry1}ktdn7Jnb_1vUae5}?nE@x{hSy<(Cmx&5luhgNIx_d<;fE_Z z;U;c3aLOOlGr=s=YU0g#U);o-^JSJc=bPY(_ax`noKJIpZT~KwhDKyK``te0VC%RXq@47~kKhRp z;|1y2pBfq++j!+wyyW&ub?;RFvQhJmEA3V6jc+LqoE0L-AK~$rClP&-3*f`!%Z)p>ty@VSMaaNOZ7y6S|PHJ(e;LFAt&a=(Hs4Z$sF^d=E;BlO@j{zCv5;L@f#VY856*WY{3_tX_$N8Rg&KoZ(pn&o-a$$it009UB!cMaR4v(+Cy1a9| zymj-{SMx6ir`*54;2OFog$&){vGE;4iKAQ8#Heszt|!R5g%CQr==f?bMVb@@n6S48 z|M~8t)Mw|0A5-qH%gZ}29Ub0Y<~Q0aohp4&cYMcKSvGb`YT78r*GJ_2KXIuLHez7B z2IXdy*Se)1SYn^Lde-#!>;Ayn`}6C5_rN>8wnCF5<%9sT_AMkOb_6xN0HjN*mz2YIO$LcD+v zkC#F40*=^Eu7it5$xGAvtuuCj7wZ#^T26SGj^Ty!2YHz&xb42}0?&>CA098X=fDyB zY5nMqEtRe1?c4c>gr#Zy*6A|dmQv}L`X?KcIpL-H`e^+^`N@ki`@i;=$K08#=j&hP3yPL)&c!e{j)|hC%p8nkLHE)lb2R|zg_0~zHRL> zFC;HE=7+8CyPr(Atu?LRx}J=;wO4b?=?^t#e7y9sgRCCI3+2~&3C)kd2YF$?*x-oA z^Jm+h!b0cK!K}8uRlH2x(Xjt09}f7z4bl3A^3S$yPxCPGtHH1IFrMThAK_9Kdz@|J zRcToZ7D{F3Lb3DZF$K`zUA7z7w<|nKiMt!H2viCo7YZ93Sk6}vf{+yAJzQk5`ujB==uv+@f+=x z&bYFE==yDG@(0T)l;6A}?_b9G%`2FXv%C(+BW|ht&1)Zge_%WD8Xm}GdEt8>Z~Vvm zmWtne+kmu|NZX%K;`Z7l^sV~g;v-)uW7VhJ?Q?d?alagEFZ)>SflSD)kMCMF%haAT zt>3yHJXm-ANnSwmhS5!LE03=k866sz)5tWZ_2s!gsdkh3W`CEB@1>L}jwaCmY#4Q4 zD}NT{r#%>(5)1bSd9iVy@b_5GAA7LqrUuB$9#r?3_2EXT%XneGBrOXs2tQEg_{$;x zZ1$iNkO4l(3(s$ZBOYHcvaK@2gA}D{{njbnz|zbfq#Jx#=HEY>s^o;1=@?!pKlKaS z+dtn_54dm~jeEd__6JK_8@FlSE4^lm@xt+1t+$K$;@JPH48E#j`?P#(ExX9IkMMoi z{?;Ko|Ij>0;nUST(4MFLPJ6y|1`@0w9)|ZxhqeS!w|t_Pvgc>r5@ajv_Ya`F4dpp* zSvp}&Ans+kFHlZhNb@JyIt1lG+Y+QHsT6lf(g*8`hE+dPYgIJKX5}WSaD%Cv?T~vsJUWo zpNW*Eh(slcgI|lt+;GLv4G9xBSgMLIaYL#V>pNr(E;e(+E{xQlMENO{lWwW6Slip& zzf(@VoO;=Uz3$9CR&)lHet$s$s{&35~%bS7coR6h_Zn_!u1p1#cDGrX41IpjF z#S2b6ZtlT-1D^Q%rcctF*5`FtR>n_0DsBqrH2Qtq^zzC;;SJGGCQ*LP;+5zu?a4>* z;qme@@S^D((vxow`pQNrC%jC@@Iv|hyxeu?o$_S0#tZoHc$ok%;E4TXnt8#r zKCh!Q`ek*ak`rF4Z;aM2l;6*b8zHP(-j}%ne0aQk0=$4D_LJM+eW`~P)B3!Qj_^{y zxKYaqFMU@;^FsN9yr@>!^b7d#c%l6dj@VD=@6-u9OzZPH$V+A`kBdIdw2O^TJ4eS(?kp}lwa2` z{uQK0Xm-M5$@A!_-^q~Zj+uC`n zagt96a(#vCEzPr#DH~4;s(R|xkuBm*PrmM)c#F7CW1ha-E%o&lSGxFr584)S6S5`T zHnk<(o8_sli)Fnxx>oLj_!6OWtEf*bI}d(Gu0ZQRiO-y*J(V{Vk5q5M&L zCa^^u`0#l7Ja_>|L0*#Xqr%#)jp9_u=SvMNyM+)sy6E_-osCqt2smczbRyO5 zYxv^{N~XH~MO>=ezrn!B^2<1Wz%6Sh1yf_$9}cFvwV!ksMp(Z2TR(1`@v)O7(D(qS zx}AJ*uhsv5W#8o!idOZqqP0d3RqNeUx2oL=FDo{?%uuk;xiXNl zP4BO`QHIMuDX$Lec}GhN1u-aqXg$ECWZ{Btg# zgAek;^V;Bu$EK-jP3!YIvfta>O?7MEk&gxRxKy{4pZbOE?O#AwPZ4n(jeBB>_6JK_ z8@Fk+D|5=ik@3?TfFwz_N}Q z=;YQFu8!eVNLl-T#h(A1*z>P1T7`EMt>tpOQ;xOQ%u(9b6_B6ft-Z&UU#m8c?0NSA zu*?FeRl5}ii~YXwwwE6Ot3E$^D+0>T@fHEpY7CHvP`;qk)z1{}HHw=Bn=Pcs3> z517{Hbu6^ptxjrLZC#;wsb5tr`FNoX!E?^XvUXv*2Tl8qj^>5(N89s0Ucd)=VcY0> z#_8|$YTo6|pgymwBfJ#eP^@$rFU{rY`~~$GUMRnhmw|Tl;(@#(>|N z7cuyqh{PCccWmD>mMl32tN4;*yq4!^r&RXsE_uf$#%RKx{T9kcgQafY+T+poAFt)c z!jXFi&%brg0Z)vv>mT-7GY`wXu~hukTZ&dmj+g&^$iA%&x({%8`ULV*pV)sFEuU#( z3)A{+-^>$ZsCKJgT%7DOeNsC+-S{(jP51#G6>vrQCuHIjnmft=`~6BzLKSf0aq|%F z8}P*bx`H24mZtSvr!9$G3#`l@6x{ira<5%gZ2GwA<#~~{Da?%uxT5@=7rE`-C-Zyl zK|%20@$xWu(ezE~C)Ux?ruAFAWSmGv>6yan;!I9>nTX+q^80yNwrrW$x*9Lw!{g-< z@B)t5Pws=~JW5`g)^DA$1H9B%7VVF;);W4vzZ5n{>le!J=SAAQ;I_LjF$VbXc=-l+ z0Y~ho;_&t5t=or3xAG4OOVj$T({+HC!a2qMobWOo!wcp2^Wy3k)$(sIdUh}P@Ob$q zcmYT3r%Q%5?btdrHavbK|B|dUt=~FZ2Y9KUQ7q+zmufj$zfgWZFJF7;_=4N+K3>3w z#|!6+;E4T{J|%|x3#RpX9WwLJ*4|zIVX=3M#Y#?i>ANha%@EOzZPHI>L*!vRKOrFZCE+D1VR_74x88K3?E=(s^;e*ZS8qv4v^< z)|F(O7(@B4>TfMh`gl>k$5MHCOC?o`q1Kho$4`S>qV)^q5AqW9zcf`G4*Zah#Q1Ak zGQ06LZoG|UEm$a(ofjEweUsnu|E0aZ1<#@C({CLATmCxy?0h@0?je7{z2cPkKlS}X ze@EXOY9A-@#C+vJvC4ORVhrVTRd*)WS-7skb(ZD|B*Z{Gk$ly86~3gev$&r2wL{|- zey5$%t<|ThrHUs~>n!8){#9HY(YGBf*J}Qw*up1D9MP(x_2@tEwT}B%Xq{!|94(Fr@^gH*zvIfS|Gw!uiD`Xa zkJ@ra`OEDi{`xuh++7iN_7~uBLZ9Zc@euWyj6M+3Fh*Y5#FP{O9!;ZYY1-+<+5u!yDTMPdqkVXEUwO z>)=+UnXT*Mhx>EF&EWZAed8qTf&9UFsMxXk_yjwSyx6ekTK(gGGSw5N^?5y+Zzbs1 zf@c>?K3<~dzPy4iFIR+lQFaaGkJB@u_z`eIZrCa|c;d0?R$Zp`c^#Q=C5RucN67! zs(Fx;knOvue`d9PoGZrndo{gDb^Lkm@Kg2u%f}(Y#9IumO?Nz$t3(maMThE1@x<1jWS?mY>@9iF& z*5`RLABR+%S!Wk(IngK6=zq4S;y{flLC2JFY zHkP0H+f(+AyyN``UJq=P`~Df_GkU(nGcPMzwj7tjdZ4oJ{-7R!{L};XW3JrnN0w{N zmR;q!OQU65UWWAMDtTwXus0S$jM8MBhl{I?z z9kNHkiO0>4ao>O^{{Gsbo&1=pG_B8*c7&VyvPLr}+)Tu9L-{psio%Wa4siocJZ_!< zH=5oNeUaWdE1jN|zRBEQa@)~jcPwtqU+p`PM(bcC1sa~t-qeE4OjV|bzb8ZX5VFW|%D=zpx@pwbItkhHLmuY>Tcro+g zWM#i7UaS`sC%cRnJ0&mH)6u+8ew~+nkM7@pFtlt1W)Y5jU=o&-)jZk~l51D;sZ>34&f zbynPDzMj19xiT(2F*TDDZmQ3OxpDk3ke_x8`#r=9`0#ka`iQP?$V=LpQdYdEdD8yh zT4-fv$Dm>CJM-a(>H9@AFO**&m!x@ub`1C+FXYMwM?5AkX}6flikC(5{HMdq65S88 zYIJmjSDU=-_pKN9^14zzf*19S2Ic359**Nh1*mYrG%i4e3(YKP0NWU#`~fQJL|mAC z91B=Wl|{W<4!AGbQ3|xp{VV@T64`rB5_)LiVOL!zCQPwS9gIg}Jw#yvsnYb0} zg_k**_wB_f?O>^|SOHOo{pnAUGy4>E>kwI#Z0x5CO|zi%W8wQcL< z^X5}2WrY9W@^A#D6LAaqHOnO&aSJ{?UU=VtBQ_96qEz8#@*~;tl5yq=#Y})1rR)+l9#MXcmp~>+ zW%$zWiZgs^ud=jh?}0P6E$v&{v$SuUtMTMBA~SiN9n3JBXkTd+kvVII*(I=Nk3;#w zU|Bj@+YxPNw8xWjAG8d!+deMi?p^(YW%lH=YPYInnC&usVxO0BhFQqpwnrD7c-%Y>_YHU=A*LB(P3!YI zGPhfpVb;e@PusaM8AF?pKR6CWWS9jX9xq3N7fs)oK6z?dzr{<&^CG2ZEXgpN6JBC7 z%trFkydace7JPWT90gv$5&OwBL#%0iUWZD0nrQ}WXIzpDvv=iV1t2!VEadm=m#;l^ z1R`I28D_zU$IH>+1st)TOf$rq*5`F}gcnOP%;tob*bK7~yvSk^c=2WQ10NnQ$ATAd z#C|f(5NleW*U=GPs*+(gC%nXFm~EFA@Zs^o`64)CKbdBTHLcI<$lTs#hS{9(5}RQ* zk{8wLT84b^L0;G|HaOz3X@*$S`n-;g@S-xz=7g8n46~8EM2tu9JL$Z%`p5lbnjzM- ze(QQN&M>QdS5?U{>*GcF9&?vrHjviJNU!O6R_Ut#|0}xK|Ig zkJ}IjsT~xPe7B!rmg_29XQ^F?3^<4GhSExDd+k=SAX(z8s1p0w3gseCT?Hy!2`uk$rbQ{N-_RM3mppOQe3m_^b0m zZdjU*C#Lmz9ht`wIb-kpC1$V z4Ed=~+}lOXf7Q#EsQ`R*ro4Mu-Q~qQO8-Ie z;ye+Wm40!?@a@IPF5@L_3l1I=tzRg=kC(tH6fY`Ho_1H9eM@_lCH0OC&ZxU--_o9? zeQUoC&w;{^%ZsqjIe7_paJq18bjLO)eL4TP{nDx1=TsIuH@O>E*|*P;ciS1vPlbJZ zj$6)U-|CWV{oQ4IM}F(G9e)l~Kd&`&-(IVBuf)p#rerWbp=j-r<45H<=H=-V$V+`< zpB8Q3Iz4dp(wJYH`_If|Kle9h|Hcx@T4%9ou;2RlMZ(N_Fo@#-yfiTxqXjZ+uH}pq{^? z{1KTc#CPJ$umwImUQP!un*MNkNv^lqs!rT{U;ky-Tqh6eyn=sCUaHL1iWmDBU2nKg z@FeEN(Hs4ZnH=+?GA2>}3Cwd|9MLs`O)E1SIPthS1KfZoR(H8co6khNs^#&a;gJ?N zo66Uhx26DSF~^(8%xo!g%PMZFuWs1)wEX#$IS(cE4CRl~Gru7X;f+h+!{g;l@B)t5 zW-c#h@GxG= zK0ID9@3X-X!EkwbP3j5IhRV?9a^HsQM@N(Gkj?Y6TtxknRfa9cj#<&z>C3Q{H~pgg zvy`71wib8;5P%>c>RVj*)^FH zZsNA=qWr;$Nj1D>7x?gaDS{Vp#QVF~x9n=>gqOH2yC}cLOL)sJ@Zs^Y2E2eHj~8c4 zz{KVxtIzu_yJm92OWc-SlwWtOhPGe=A096y@B)t5;jVr$;ANg~*=2vU<%sWP`!{aO zF3RucWwUgCh!^nT@p3VE0Y~J;bjvN%`n(R>FPR0x;)nZl!b{wiU6h~WQS6po;KSpE zeg<&Felp#1%d|ePBl9i0lwZO+zF6uqUYaQb8wX>y?4taB{em_RZgl}Z$P4?$21h(L zjT|wp&+Ev1%Pz%B_1I#i%Xq1!-W0CmuKJVaI?c)^z&4hqvsS%n3JfTXs=? z+A-|+5HH}v;|1#@y1pSVX=h4V>6uP#+11PmFL7ITQGR_~5^jQa4EP`~XDvksGDHVm-&@TKE3bDSL0f^DPJdQH_FF`qN^)S(0j}dO^|JCo9%V!zIeV#`M*mYL#eoxY z4f)%#cz272;C)X$P+EtS1c+ea@Aut2;pl-iJGO38x4owaF4~$X&RM=*-clY*s|GBk z2O3HAz((i+l)4_6^o>N6)nA_TvSoXVuf65K>w#%`M60SE**Z}k*%DoFn;bt9eq^ip zn7fInrw1VCTzUZg;1@N~XVdyT+3b(%@LLH=)n?YKi}uG_p8Eu~yY8!lkH>5x3;AcW zNEeB;DKDQ?w-kQU!@zy<^8L;bR}0o7Yw4j2IXeA)OCY?&Gu6+Q!FcQd-2|*_q^%A>jqoK zy2(Eg50B^uYgN(O{il1aXXIFW&0rfXPd7k*>IVDGuH0HR%XHf!)B3y~Wh1C`e3@-~ zq}t7TRk7cv8@jW@u;6OWs>;=Tb-tmpQ7dbilT z=BE1cV#&wN;S_ovmv&0;d*6A{+))0uxdA60H`KeD-to9eH8YfLVGXxwV;3%v4ec}4 zH~8U7mvO`PNLtooxS{-Qa|2Gu4X?unPdql=_R6$AuY=J9nMFh5hif_EX7K#5zHzqu zg#1A-e8gjYu;a*!4STNDKkg?}Jz-j(*OR&L!?6X=E>8M*=?1%o?UA@#5#~kNHIzS2 z&xBTQzzMnGb=csE$EMzN)B3y)rDvS97Fj($j2~|1gqw*7Zk)6hk$NWhIOuX|E6)4k zob#M7v$Q$i1W&vtIltz7n)B=C20S$e9~}FA@N4?~`ttJ5D~4_;^9ya3s!E?!9p5ol zK5gmJ#LvU4`Sl(0{-3z{^|hE6Jc;rtlux^*KEJl#G5fZ{zkA)0dpGX6L+01V4s

    z`}z8%)Ea;Dha<*GH8Z+)ls}5gRL8&e?!URpXe3xFX6x%Ge~;{b!ymg6+VB4FM{ix5o~X1Viji(~1%%M($=k1u34xPSt*Ke{!Ob)J+JoF1$8h7>VjoOlzwhkT%!AiDM_+{P+g zCUkbH5zavFn=UqFnX^H8HLRnw%VSKD~<%aupHM8BVs2H0@PYm|z)|xc6Yjouz@u#&ak$e2$EGINS zH6r6PM)KQ*cMx1S|9rExE=Pw7qlGTM+`>@BwP#XieB59@gkorrm=*%mGaEO#jA=Eq zThC^rBh^}yKw#sUj0s|muckIi*=(rGiJkU!+!SaFiv47JE0!5=twqm%xm!(b(&Svw z)>^cnIV{A0?agShY&LrlA%KZ903Z|UA)Fpr7Ss6+P9RF@Lhq+5m$W#V0k2(5(c1#8 ztd8y!=s1A=MtSDli)D&P88-Q8TjxC*dkgP3sk;K@XG*@IkG;ja@Y24&17h-3^ z?x)))cT2*EQQn#G%xBxq`n8J*VdV5dg{JAaAUHI$BfvQkl0<@j?r*N|zcJf=rL79< zRIo)zo2Y4^Z~xw@8oBDk2}#Gd)q@}9i|#&ci}reiJ4Jg<5(Y*&EEjQYS>1^d39+WJIR%`6ktSw9vD2b_s+-O2kgGm zwm5SRnSZQanjar$eB9ve^#~oWMM9kmn6g*StX04`0YYS($&^w`u-k8~OF~I&JsKU< zM!9-oH=a+MYtiVSu5)LN=P9+;QwFy8(O^-=NBi}QzqX2<=jx?offP4Z1#T;yoyh1Rx{*G{(0PKc9<<=umF-`@ zu=XqM^up=eT^ZA0;wPR~O=hFnElPMNyR_APr6- z>108J5|VVc=2vFg7KA`>9?5Y)VDPXy|9n%#G#{E}23Bh=nj9;qANkcpDZ>d$(h?8? zGMb~5c?TCi*-DyE5(^qVQI1SCwdiuQ09--{&W2)SC`Fxt;fH4x%mpqLeC!{kJDHlx|8>Ya=0nMKh|Ikf-* zWsm6chLDhVK}e~SBGf;g`$XgMjSn@CKnQGJ%@DJT zGA<&9KpS2pn7x4XG%hJd(gz=$4hxS|nNVH1a%{TWaXB#rz-sSph%=^2*Ibcjt>~QR z=xkU$pA=(@c?(!=%8XSLn>0C4qHAYVK>H3|c~rWD0648j_by#~XMB|MYGQTe>%y%+ zlj3!yN+)BcN@ujMa;pk!YFAFo+!ytXj<;~Q^ENESGXRsc&aEmPNey&m<>C#Zr#uF15ojdD@S zybXksW|w7cj&wzpJ6-!~YGp{_h-#Cxabk1RqOK~fwfF9fQ1{5s>Tz4F z#s42is~)3a%?+{;!~JPZPrY`N$+~asQoZAiy}Gl!O43g04N6w7nsjAmzjo0ILI8qSsRf!-sQX7Xe~T z2ms~S;G}55&q7ahYkbxg!~Oc*KRliG)#l}_(G|B}8zaEVILS{nk7&~5`OvKGrdIhl zbYZ(UCrY)|D`M3Z#duIa9?Kk}2m*4-pgFoCYRlicFMScA4-an1* z|21VMKKRR9-%xt`!&m>e_{M)){k#8p_mi#Zsg5#=L^fP-H(qY>iDAxr9~?W=S_ZHY z0{{zf=m`LDfJ-!l2Jff*e(u(vNg1cDHQCvWW&5|IYvU(7SMOBhNZQS00h9v@H(bm|#w@q@)NSu4Dt{>%yM< zY`e~_Ojy?QX}$xPGm(yxyc|^wtb(FC6-9#q5cP?JtNiKe})!v9c`2Oh9=Tu}?I7{;C zXneg^{rRfFH;X5@R{+4M>@=RyW=h&cYh&En93I|0R@c8U>*u2Pleo#=`=h}#ue6ag zTjwtLAX7#N*|?m_gtgXW))9;mF6sD4_0Gj;64_jhs@$e+p-MkFR+w-k6Sj3VD}QS=8f3~o0kqEqG_8455WdJs*M#XB6j+)Y_3K(UL7$(oeRj|rId8HB2&4I zXENMQvaZ1Fp?o+u&!U1L?Gf)zqe9$Z3&T-D2vQV-2XDfpue=XY#;1MFB^@8t!3Pnu za$=E^ZECLy?`&91BbGmzof-^4zyr)B%{rpaE&7SXO|DDV=t+$7)Rn7qi>rBeE5_kr zlu)FR;{4oi$ZBF~<+&jFP>YDJ?#xq%87IzoqkVHtqL+a#9OrbfS2^psq{v5`kDE>u zmy|J*w0J$UGNGz+H@-hY!s+1$MereM@;GDT6NTaz9QW0^DaLx`LV^p+$(>?hCAl2i zx4M(eP4Oej1Yw-wV))Ew+l&&<>FO4r_kJa*x209cHzf(xF)@V=TJ=%Q~JCqU*xzYjZ^ zbSR`d=!LTPr+~vE5WT+?=xUkFbXJ=Z0##wW{j->1{h1>pt?@?>ipgp1TzCSL`bcN1 zkEdV#JcO*Xf0;&dYrWG*5~Jq|DIh_WZsT$~pKa8hP;&Y6T|$Y7S=8WJha-T6p5zC4pZ_gIJ*2c4Gom*SZ4=*Kvm} z_DO8}0i~sM001BWNkl27(yFH)?ain|a;t+zfenBo6A1M?!G|js{3>oVX!f?N4jCvca^6d>NVj#i8&BS7+e5r( zhqIf9gC7s3*9&#hNH%-rm->J7w}`0a?vuKtS#@wc`suj1$5>=++2D^g&ubUcy0F!B z-g#Q%Ma&vKu@FO{A9<89??P)$Vhim(bhhF~Pew5xJgmk?bv3oi^b?t~tSgXKvslc% z3s@U)L3HhBLk$3%S28ZhVhXr;tn4I|li5%s6t$Q!6GG77LX|G~GZIsP$?+qYpwX57 z%*_WGd`u8$!{t}n)4moFHOkk8E5-(`->h;vcj2tj=7OLDR5`Y3TR0PNpv5>vM<)Qt z+T6Q9VD5l^bh~iIGfAqc?QF%tle8tuvDKw3C#Jb3kqqT*h#Ji4z$7uX_cqL{?k9HY zgvAY(G&o{*sC7UOG8A|Q0OX+Q(s>t9t_T3lRUwkO1&vi+mkyI9b?GqcrnN3{sX@BT z9N_B+CMgb*UW^TzlpwaK3Y#wh`WR+CJyDC-Lpd2A*5$-DSEV-rov9I( zw%V)0s+lc@rkYvA4WsNaE6mPjlyx3SWgnF{MH>J@ApzjRe>?#risSRkvo0n{2tlR{ zV?%Z6obe0iTmX3KS67#^jJ&g+M|AM8PFj5RVyY{@_s*=l6(Q@&yHL%njH$CBADD7t z7sWGP@ZN=DY_g7ApgpvIt9<>pk3abRAtB2J$lRd`nKBTdy&)HZ0z7Js6|vX~=^3>O z$K6~|Z+$+}GG<&5^z+|)Zw5ZBUrK_5g>(FqBiyBLrfuOZIO`iLq8J+-dk&}vEF-lWaU2p1R&tA@{e4u z{NpSuzrePZKY0wqI@1v%2`fypYS5gkHO~-bk+6@dfVj^7+ndW0BA(VU!c2J>zuqN;W=L zgpg`#Rbiu;4fg7nzrMEj{_N;hfh@(jH=z&CgjV|1`0(Z1huA1M3%;eqs{~U^F zG`sciw1*QVveZsYPNFaMo`!H;g;`F&maMn{Z})U_}7?!GadoodQR))wXcil8`O zvN^g65YYP*Km$|(06+jFExvg!;h!PezSaU`GIZMm(vEojcaP$Xzxpo@s0*Lpjz(`zwt9lR zI{15^YyEed{D1j+@7J%Te`}T78~N$O>iAAc7`gR>QF|jgxmOPNt6M)BwN|3`x@>Pm zX-6347z08`dp+_#a6v>&xg_30Yc&FZjb~D4ebN%Ta^0dI|AlQ{>B(cbx_u_BQUGdndmULEbd zH*567V6Qs4TgrqT-7X?|g|R4&R{E27=Z(;u5|=gSY@ZGtCPxBruk?kBIc{u}o@ z|FHOX|DdxK-Fg2{c7Nkv#tkkLcK-P$WrRy|`k<|C{MzX5!}@prztfE-``cgX{+BzE zENn3{xK=SioDQS?8a>g|wg^68>H?zA%~e@W?ciZ``3v3SI|be#3$6EXzsBMNRdwaq zV0wD+q0y6AdB5=2SBr^Ry_n*iI66`?X4n8A&B|NPC3V&#MQA=u*8c7f%i|BK(Y`vl zQy*ThPVUqXUMuhZuAjJFNZ73!t1ehLcR4y=1Mu+umpwUmE92q94x4}cG^SOJ1j42m1 zgfJVJ@mZa^fQkr(q%|+~ta9kXf{UTkp)MRyP-ZdTW2+aEbDwCQ+^EsB1~*()x}^(Dtbj?0|4Uc-4FX*{EWJTg6INa@L^KYpVO)Rsl+StIBm)MkYnWZ<2-aq zfl1QXV(A+DFjf_J{=B&X(~&;eD<*^5+3;tiUp)=?`e@S!b>dx$l7A> z-Td4qns5L9DPlU+#5nD&^25E_RBq95qW?%^MYgx1Wv0N@zup}@tfCI%5uKjs#Sb>F zq*+IJ9SFd4zuG;ySuPj(0H7*ojW@MRT6}z{C?lwWO4~vvZ2eLiWz1U-6bL2N)OOFs z%{7S$dRbST+$|qjsS>EBc0nhvCbk&sjVswAX!xw-fHJqp>|Vc=q6n+K5y_Zh(S_~n z+HNx1uPGzWg(&5^bT@xEo*b*REuxg6hals$f4_nNR(UR|Oxf&2*STYiPER$$Km?$k zITG6#+?F#gapZ4`4s;{*k5ejwgq@)0_vJ>mdcQzydP)?2Zh*R{o&W7~P8)c317-h&~Vrp-cM_Miu zRF$rrT1@^0fb2}p+1ZXJ$EwZ^0LYZ)r&_=DOZw*4lRLuhA>aI-eEA1+mVh3Q@;ig+ z2Zy8A2h$H4lNX6;dw5Dd)uecEF!0+{7Z)Ro20hr=r){1uu@*)L z^;}(O{r0tnRbE82E^KcrCKOa@vD}>v^fD`C>q<87u9vnpXG8En8BF_na;y+R|~qTX@ul`6A_gK(F!OgR0z|k+j4tW}Glis+olVBBp3`O&M9ekjR8#Q--(_ zhHG0BOznXLtvt>eLjY?$rW*wxn4rOja$+#0aZWhm#A@%I_b!wZQ|C^^Y;hQ!buyve z2PQ~8Po37@g|&-`w~%!?=TujY%cmxvgSSB>j7L;ga}O3&1$y@gYEh+|o2*x!5JTX}1Ou6^%Z zJnbtkh^~B<+xBL(dNG}xDCay9;Z^CZ_Ns7{5ki3r8i3SOJMC*zdtEzggDRb>Ts3pv zg}QL%*yz%gBlF1cVJ%u1#x3tDB0=IFr;G$QXJ*A1GkW$o|EY#d8Cmj?OnSVt6?4fZ z$0~TxrJJ7Wx&MQtx<)tj1?bNKVC7s~jLp3_rVDJyYOgEjJs3RBYfF%s4&}@i6N4ls z09d`4EMJG4S2LsB=%{|`uE%!|=}NKt#T&B^#Nc}ye*EZuH?^;3HqMwesC~A@*yzeF z-tBO&p4a&SybE!IV~QdgU{zBSw|LUzX^VHZ;_x^n${C5qx7-D{<TTc= z9Umz|2w^1ahyXy(QURBEapWw5VeV|=T>uD1`K&E~0Ohdz#kPnjA#m_s5df}!txFl< zk{acC#0UW&L;uh^9nG`x5Qrjx+$(ELKrax&NA5L=V%xZLI~rmxYKi*Bja&$q)+cvxBhT6d!YS?imK(e>&ZJd*0zAa0A(|-8g441jt zsitiH`;mV*cvvGLOT_fnkH=s6yE}MHR(6uj%URsu58s{X$|X(S*@_;#J55>`H$x~V z<-{N)9|B;8AcOz}c3y18EzTp_T$MsHj8P+Wj_U(~>9Gofiznl^29xU$Ab4k7ZET6x zoDc43`1GxRZbFGp*67`oRw;-~QqF;r+@C z^q1P~+CXhwPKSH-#^uzSP)=;x7VWi&a`?&bo*dsUqLfxsJJ_q84c+Z%e5^#w@}W-K z;=!8}XFcO&da6zB(>Cv&OImAD|85B(G*=}d5I0zBLr#v>>V?E=zx`YT&HD%?GNr2Y zamH@_XiO*+6H6$Z-mmJ?MhV-0e>Og@t@c~jGIVonuSa|D&32w|#u+07m?V-nl+BkK za`EzSy)|bzKR!EOX+5WH9?4Fj`qSe6;LhQ6|4MxIrVnAbU)}!km39ofA_@v zi6j5-19kUSv3*kWnI)7A_9~gMtjiB>7QJ(^vwmeK!RwGqikTp)urgsQJIUb(IWFmJ zi9b&n@n=4cruO{@)gtkmP=YfV4Aa0h!)o8ZSB4O{AcMUc(W3FO=7O5qUwE;J(|%n# z%#JC?VQ|k*4;^)6dg!zYy>+&Atr2_}?$?;?i=7GDL$o&}`U6h;s=Y2%Zr3g*Rz0#E zIlP(cvuxd!^U3PPw6`7SLsQKxI`2m5+)|xTFtwK{L%X-;svPcDOcIf>$+1dWe7Ii` z3f2S}v%0XR_KZ`;K;_n%(7#uD7xv%J7cHfCfe@0k`Eb8N(t)m=jHy)~i^6JZF zcG+5=k3i6vGK7GR0INH(sojE^zj`5Au-=NPkD9z3o4T;}ak{~5{&gI)i*iVg;)(sK;!7wXi${4;X42tN`B5Fi+mRoS^Uw+TlzU)W0MC5*S|Z&=REUDXL!F}Fbn2PnZ5=9Rk+SZyni#_zScmPy$x0eF6q&YVxa&vmG{;!+Cs`n+!U>KIqRz@BwCabE(m30 z<8p>xA5lm23SY3LY-FnP#4G;pHd%m&% z{tPIL4{L8jIW{3cF*Yq6R7`D@G6KXIZ*}OMiwFTGNR+bR0Vo`Pps}mem20j>#Zb$b zmSc-4^{q8o<&IFY$UbPSNy&Ig`eHs2yG%w9ildK`jOeooR;z{kInoDKY4Ps z^j4Ya{gXcqM%a5>Prbj4EloZW26}BCwR4Jjk2JnnA$TzRQbs2ez7MmGtDtW z0C!c)XbS;~k(p~PmyQ_a#3&zSycnBHpJ^j{n6!9%Jvz9NLzs8d&ISZ8kZ4)YTyO!s z0?=?u6)tXYYdnT@O;0t1;LIG!!bld%sIy*I-Wks&nWqzkkPl5cvCf8SW~V2Lax&Ui z0MJ~M(^F+sz@&xEXERm0{@oglYpbc%mD81@ob0^N^cH=!Xz&mv44v#2a2}y#cB+l? zb#4hGC`yPM3=0)hW0=}aPEwRFruh)G|DfQZ`pXX2RY?8uV&LF7GB(8gpt*YiHIp- z#QU&JIwO?SxvdMg;3B1ME@B4sN%jwyw4B&kUy(UE=CNm(+UYYN+m-V%BG+?NdMhr+ zwj7!KLk_1KFB$+~y&r$_zkOqT&?OB`GR;t;{Zx%ED*UrL#vr+2I3$gW>bxunj9;k_D7`!4Tk4DxvptM%82gErVN2VAkSC3qsa{ zghg4XqPB(m;a+RE@?i{2X7YniMjNJc9gQ?TSawj6FK*4ae96%vo=?SJBz%5 zxf>q==R%#^$+3Q{MkDiSf3WMpuFoyQ=%X?b^fTrCFRfKy{S5zKckchI^ZFmb=)X9+ zRbX87%1+EAogAx`3keq#d0XhjjOV?an7GMrzcx-h?CLLdlO}I;MU*l^ps^y$ ziNSFCz4vAdTKn`=PfpYeUt2ZWqda)~T2{?0M%3%dVO~LdJ-YYC6eD2KlZYZ|*@X7} zf3Q~k>dE+R0AMVd6!-FSKasuVLG{{KkBlqg7yC)??v-zxs9A>#0s!Cp=le&uinZNz z%wWGB?bnpk_Iflu)z!>? z@1N~C<1kmq8vps<+-R5NgAcP%_embiT%j)R%;Wwuj|K)VAaqX+)tS!=(Si6{Zx8r z0GgABcgtJ*^?e=g-YWWi4I$Xt>&nZNr7fPcIU&$mo0HOKL+xEKm2YoEl!8d+ZdNNh zF`=+rgdx;|Oxw{xy=W)W7N7O?)nDok_iG3+=_|?zDm#qwSyvq1$Wf4wo(s;*D_X13 z$B_U)6qBq;+bb+iNpGF?)>*R3Wx`P8kG_grP%cS6&~bx@v!ZZzs=M1U1}$U$VBBC) z!iM|xA{GZhgE5jFQQ*<}r1~tHSNQmpc>ECYLeA{M>44nWX2R zZ^GmLtZA21N>$<78&TTkgb*%>)uFv6(P9}q1Us*u&%e+_1<(s$ZzELq`oBK?;E!g6 z5*e|@1meGV2Lk4+9DP1KYhMybJl*-23T7<@O^)aP!|OJ~~X0 zeT27qF?0*|R-?n&pT>fn$`4KaBI4~|0Rs!6tM(3$TlDArC*J&fEg?kfE0h2%6R$q% z`6ws!(~I*j?fTsD{p{lj>8SUCq@M6!uv7aIg7Zi=xCE2U<9X0kz@JrF2xDD(zGKR> z+A^i-3hV6hs7>My{l%UvYkWDg`Bgba&%IaxtZ$~{tWc1kJc8F zGv0a{%ksdt*J4#U0EnC1JFjauJyGS@6k}slxcS2ocK+Cgb+@D05~RNJY*J0Ft$ces zB7}Go@Yt^IrjrvjJJtkX`{itOP?N{e?d5d?#djN*=MLX>VaLaHHMOWFM*rz*YAL4y z;N9<>B9E2ON1=@eB$<=8BA)yvnV2K_+bZ*tOTA(UDr& zN#X|QlIqH(ZC*``h-e5f&r_2W`yy++_h7WoPc_ECS>+L}z)G*0nU(X2&V9DRH?L#? z0xs0J#>$v6POSFRBel9U*C=6-OO;!kq&gEYYZ&PpPK8Cqs|sh7ciNXzqe@pz&FG-+ zZpG!qAi2y`Zcc4>Vb<3oVuTWF1G;cH;}IPrl!%BDO04m-Q%xz6F^d`;i8&zzuq{ZWg9PZV+eiDqs=NRqlGtc$O zi9+wT=@Pn%`F+cdML>WOScqzI@TM!LN)M0w2~bAr!e$*FH+geKp4=@NC#x3{UHOyS zrLKKBwbgV^vPL$B(>@RYLeRqt{j-}ZGHJ4EV&@_0jC9Y%2r!A5ITyI3-UqA0_^95z z+8~5Z`#Q?FDv)7h(U3ZBa75Dppm#1AAFB4cG_`N8$h0Mr2Cs*H{~fjew%UJN?Y&Vy zc)cb7Tu@X;W*vc{X2;hnQ~Bk?SWc`eT{W|e62=H3M|0P_j5!yq3Bd(bJQ}}IM!fS; z!h#Qo{ZUFp%)AK@=D1aqaa}rV0uX}i#dFU$b?r_cR=S!K53LE50AWPs&KmC>sM3`a zJ2_TdvaBs8Ckn-P&IYS|KGbNp>g{}2SrkYM$8+;$+mw{=k zLvZ2xcZZBot6ZI1#8#aJ^j*P(k0T+m{qb>$j82}|q#hhGd{6+169 zKl$~wwcRsUzQyS5srx6M%hr1IdWogVXOhlK|4qcN;GNVRaqdIV-Ie6r>$!cj5w zxBvhk07*naR3#xHqb!M=a{&nX$d9d;v$V};ee?7uJnhlhiHLY~rQ%sbnLQz-w;i`u zBU8B$=CoDBiDX7aOoN|q-aMgC{GsQ6wU>3p(e2{ykEa08Iwz9`pAB^XZaF%!qy9Wz z)Q2z|XlH{=*u!^bC@%tl@c%RSWPfXrVMiKr@oY zkN~e^j~@&_7{-iY*e`yv{{zE*@XG);3<0)gAdMDE8ttM;aVNX0yQ{0ZYsoz`GWNUQ zv-#n>5gA!kO?FcfJ%MC(GdnUX^WJ;T`M%%xTMXo}0t+%TMSQ+D*(DPR?$FlwKV3cg z7umc2C^>uuok zc&yCz>SdoX(pqp`xH^Tk5ql*9eVjWxeEK;WrW85Yv1#2x3u&M_S{)>E^rNvpb zee1$lElr-4BP>=OQL|vFQ)b0z((kv{T_*C*B@wj5&L^7Op{rN?B2|vZ_U_Iy3eKy| z=FJ*^p)ozmT#uUV03sExxrLyK$5yZSX8@UnEo#eD3x`rh_wGgrhXI8m(K6G1gMa@k zec{n`Dvut-M%x#Ewu?rIDmR@CFPkbY?XAzZy&B(svEJEo5vTi`-#ii?O~&$=)1!Wg zG4#)ds?Vf?-6IwP;x;jg>U`#F=aGti`Ke3JuTv4>D5>^lYWC6W$G)A zDs-8eJW@c&+O?1|lEsQ~$YT{Yh2yb1Kix@Z+8RqJVT=R~zInUm_{=CM8Jjh)vT zNAJbfLUYZPxrxT*TYqx)<{$M{VYcqnrl&Gn0wkDKAn_Uae2zY~O8evbe`A#2yd?NXa@NndUj#u7@RVMzr+Y#J`xr!+P8H(> zrFqs^RTxYXnVjTUmIW<=MQtAIcvy}f7VT9Q)T!$ec7B+W#=1iYU~*#E66sK_UJIgO znaA31a8;NrQblUUM}^}v?$U#IV;oM_+75HbzgBkrW^HvR z@amjU80_b6ja#r<+A`IR6?eFw5lZS^mpfERQzjbc$y!^S@@Z+cG#GU}KF+l=j>oXb zLv9zL;Dt;UW^$4d^^7KS|i#kuYI~%583J_zxqa_wdtnQ5<7${gxi8& z7kKZuL$+V6hfR@1%Byi}fw9W+0B_S%46LOF(pDCYOOvG5*7=?5Uj0yGs(fl0C(RX6 zYkh3rr(Zp5eZ_Zm+6H@(SUWEl>0=~ z{vOGFvM|x4oD7Q7z2x9wbnr0Re}6VON(RSiI+JCtKN9`wx$hy*3@LLmeqWuvTL8f2 zm+RKR=qSgZ!KiaxrB((9@7-;G+0pUl=iA(++^2K9B>(`Y$=r}pMpR~iz|JR|)8nGb zae8K1yCE+#?f6X3RnOT>m6=hcIZtg_pRMc!D2i9otltV}{nA>vU?XV34Vkqdb4>_jGnGXu zoyozIqSh6vG}D7(^nO14AOj0dlVLJd5o=kRGSTT&F+r1w^y(a&RisNGTSR7NHZ0wM zfd!SD!Cr=ubLmvA-wX)>$_W?L7@JHacc|kt#wuxx)^^%2vY9G#O)12~QWd(r;WAEV z{Q{>oj>9m*MQh7l>eYE`!!yRp+%Q3tk#zkkiv|GJZ`F|eRm7S(6cL{b5Y>FFVuqn> zKW|mf=Hj`Er258TAGL**wxX zb;DO@%R||bEKD+%)_~C_Y;kKX`iMVg18)gJZ90|DhC<*ql$j|DJXL8nQ`3{e4Hy>` zDM(fOW2$0iehr9v9#Bp$w&k5oPZkEPem8D}O4`Xu(OP${f!SG(gY!I6Xp1)2M-xH` z_8M4*;hBzgay*u0rqih`Qtj2aR>+9aWvXBvszV6rZhLv6ibNN&nw}PZou?Ct6Vufl zU**~fSa;ha74MHIX@y4#1!HX3V4YQd^^Ks@W33g|=`qJ=Opx(W(Y@rOoxIWDH|PTI z_Ci+X=s=>L zbiL~Uz~rQGeCF5q_%LUj;zC}#7CK&K1&c;zsxYcBMXJ|tgu*3Wooi`}M5QyS3WMwJ zL#IJ=45YK|EhMN5MDpg(v=EA7j0P=^7RdnMuUyzVYh6(!dhhKh8tcKavK~-Iu6?p4 z9P;*`4ve<4(8*AqJt&7Cl!SmPjm*sg@%L(+5Rh|cp6bD}fB?ERARH=u>UG#f@X9V? z*_u6<@(T(K%(Yk;dYn%Vd|ISBkJZ)-HEUsVQV@Q2K8|e(+^B<=5FXXq7MVs*bJQ)( zAI>G1V%_zdyoj~TEao|Ow!L^HQ9sdIcb~V0maf00i<0PFb%7C-l&QI~>`=*uJ`7|BeH}+Z6 zT6Eic_GPTmrur~u@sA40TE?@M<%JihSm*DYn_(ddi|+hfeDXJ2ge;|NKJ(Gq@VKB^ zq!ypqdaZu`hWX1{7@exKBXxG9+!i0~mY9*btPROyO$e-A3&uw|X8aKX!mXTx5ir)u z%EBmVpYnC{S9#cV@KBVg2{*VCvUpVHks3VC+dba9ED)sv3%a!Ef!BYW3a`qet$-?4 z3BsH6ST0!TDhVmZ*SFm-U0VI=&ussXm(TtO_U(Vp&VE%Sx7J7hi6a`W)7W15e6zN* zKls{r9{lg$e(=BE|KNAd?j1k=?Pi&oZ~W%brI+diCmz;3FkZWa`pvG7u?QBq@ZoC4aFZsfwi_`{HTJBP7AsLmJ z?uWmlQDC!ciG;AK*|W_velZm?mEqIMNU@#BpOWI8hi5(GGarm zY&wyI5LKG3JN4PH2%18)oe#b@O(xP=cLM@LAZ*ozbuS&3rN>rk?8aw1mtSq{84wZ5gL{gvMiuJe?xZcmH$%1e7v_k)X-%eRXIwXk{oP zfBvubH}BNiTP^_Xyxu(dAR(tY0L&~rFeIC)557GS9`zf72mDY_#z{7nul&Nw(Sw*f zbT%lMpl7>T&=T+bvZ#>4Wjf8!8OyUVXMjvpjinP^aU zwko}wQMPwA=s(Ve``K_m+j+e~a;+lOT6eE~vf2N}$TRljohXa6>oZJ;p@KAfZaS9C zp_QA%R5C`4v01Dz&I2PO0071}FjV5+-fv=!k&f(B6;*g$-rD+=R_)qq_l5fP@$FyB z3mF{_zOjGywb9=3E&VTfJP`q*!9>s=?06k4-WPH0m&FV;o)znI|H8>qugj)WM=vKtb8A| z6&_mvTa*$vV1At=Sy~ka<@dO?o<2^oAWOy)e@Dk-kG?aR>=ylZ(}VBE7gRs<%jtEP z<1?)+Y5}yiZj*&g-hZ6MW2vQSuDR({b+)|Dwx^X*r5)_1*md|#ZnWjBg3=l*uFMS( zDCUkTVUw%UOiv07f>_-N%0vSJC5>BS`|m`pb+@(VU@rCOC`ZGH{-YEpU04W?4vN;A zS7zEM>(%(xH=5{h7Y$1S#IK99-E^*(*LZ|=x4kkm)04ulb2N+>4lPr?emyK=z1WQz zr&<~}V8UbRR4Qr42RTsUhTIK#*b-o&-r)Jnbgy`n(PqyT9%X_$O@^Fvr^%S0y0l04 zlV;ELYaD+7B~9;IfF(5{q_gFXk8=QUYs~RzXJJ52DiZsL&~Ga472dKk)6qa}+zHO1 zrP_z80v(SwSH#C6UY)~L&-<#srB~6%g05;C9~-(_teyW~m|`FCBSsN1ry)D`s}ZL=9|B%lltOjiKW+yyJvHl9YL>|4yK*A0iuE$|77;a8P6#UH=xn zY;P;fh8G@kzs?vZPC)BxytTv8AA~vN$M$spD6cZtvM{qzIUN?qyYc?}v%Lqi-S?(v zhedV`;R_V?Ccc zLwDQL$`S&-oq$j>KFKkn3ZvH2iELhRQT0=#+FHmWg`U~97UO~zsZN&Mmz|JmWeJ5c z*D}?zFx(-+rEb9DVW|~pY0!4Z8YmJiOM{L-*b|NpGNWvnnKILzO>cCRgN1s>8SUqI ze$~1H*9%^m@nMd5B6nH;QL0MQTyw`qd68dY~nB~o+_wJ)EK?}g?uO+ z9yV(g*|YU}>b~(i&h0-8H}4s32m#iFPR_<8I&rXjyYc031nuh0ZbSu zGp!2iH-s#VnsdWCj4G}0>0md-ZLrMr0!kpX5|o_-@y2R-o-MR~BQ(Zh z99}diwX!I4S-IpHgJGILfM6td7U}kuSL+DmG|57{VO5M_nOf^Or~_EJ5}=(t`qr)P z1o&g%ZroTEizf8as|{;xXWJtLn4rm6YNaa&F`0*0?Iq ze=@TIv%yg#uItz<$96ol`FoIMoX)e>0a`z z1wzQQU*eB}ahBFtH()?XI+F{pD^(g<+8=VDBk5`9^`_&ocqBJ(*Rq)^rqu(vb|Z8` zipL6WG8Hi@yl~&^T}Mk>j&!5VRyTNa%|XE0Ylw@U0hQr#Mha+pP*W5J?%2W6D|6rdW;_zm9L@X+}W0OC%|M?c9zy*=HsjUjX$tfeUFsJXQ z0MJ}_2_s4w^q-@g5K2Z5#pa94MYetES0J4(V3TEKVRip4JY|4owb6@@bM)$YVAdSc zvP=JX2G3ghOY65Y094IB-bwI}z> z{-gX{E87sNG=!3sD}LoDY{3l}p_Njvw&GxBu*?l1;D&6$#bXY+_0#QI$Ju{-R__WU zEpsWl7?hb-g;AxQP0w}C##rvq$!Upse25O<&Pyo4zzD+58CX{JfB={k{WrhLm`e%c zEbzV6R_&^t`R3r~lA@pF{Ukq&vm>R8>l^>*Gk5;Q)wM50+41q{yMy98*m7%Szxi*D zvCJV9uDn(sALV7`+)S`^sCAsM#nGjbQV5!&wc)uTJA0CHK`4Q!GK>dn?CRCv?jM}p z_-s3mmNq7j;T7v%@`EN%r)uR=@XlWhJKMg|7GqiM5=Ya5HC6)vB`olI&W+&X54L6Tf*b>QD5<&|0mk@9~ z${p$kY@%-1(`_Y)~>z#91-3AOIGWl84`(Oizl= zXWD0vQ=_fl7kUzpW z4clV4pSb}8LXo#tYuxP$926cg+K$~&7+nlDmljwseIuQ?l4*udl`}FPqwsAR}*1xsa|EqrccaQGJ z=|t|l-n15u?#DH2b~R%yVUWimtU!G-Kpc@hjXp4B{1y;R})G+&d;7qw>P};Np6&l z1`?L6Pnn=Nb(DpXxp70Lr4b(OznAL5Uf@kEohzfh;sLrCm@?DCrH)S-C&Fiw0SS!2~H}H*8*#7&=d#vB5NRQiN=aEJje-! zM$bh&6fC$Qw+2w{k69DwM{lVyiugAipZa~4p;d{}>t&no) zToRXFtk+i@Cdkew8(Nx|ezE)BUycBPdju_42YXr25<71+XZ-?A<+U<;UIiu-iPUB< z(|d2%@tw(S^eNZ{TRfnswnZvx!|it@H0P|Xg^US zjcwk%#GQct7+>DI8pOl$C(IQ47{HvqE%K*bX4vM)mhMOSa(&dn5A|e2zJFCc*+91} zgtz3wH}vS!7y2<{N2f(ms1F6CJ|Y3{N67}s!r6WPZ(5lW{XLg3tjpJ%syKg&mbW#^ zNZ4Vm9UgQk{AA76%3RCRAf9#fDB8O}eR6O5^FPvqT?bAm_u>XK&ylW{|k+-&`mX& zDB)2|ZECH%j?WI?i)Ux$H~#f8N}tMH7n#w@6p0ot)pKA%OG_x}UiOPr=ZH^XgDq{; zmx!uNPYOzjRtDux##rvrGBanhOh|-Vy0cnz`ak7RIadpvlY3lzCOycy)#~XPN0*M=*yLsYVhyGSM#V zY4)6 z&QwK;UxIINJ= z2;o4ofyR-)%$K!pCwprkGjz?v2uFk>z!5E7YNL^N$hPZnOmly-8H0eZb-l|QG z3!D=diKYbHkWEjE$#GH9)+}ggt+85}bo{iznd39Zt%#G0+h^xQmqzdDQ*tq8a{@{z z53C+#b%oXy3ka+2?{TVkn*Yf1R8b)hGzBFeR%SywQD{ zy|{KgOsCSCipO^zg@H;y1L%DrLdq}B8 z@E}j;!d_}E-1)`!;8Bj=P((mH)l!>VUuYk^6Il!G4Ucgm=NF3rXl)4r#);QtgA=7x z<=HVkE%35skwOtQTFjn&kStJDJaq^mgjSBQMWj?>(o=QzUS09d)~5dzsnp__>tu)$*}#-!0(RyEqoZ;0u!eMT2)t+lPIaGpCj ze`&ppU!8xPgIU_tuNTV%t7T@^lE6?eP%UdJ^&dio`&x zqhPd`C4I>qYPCgVhdWfbl!ujyu(sj2KI4M8A)lNSSOg%)n@}R9;SOo9ii)^lExPN) z!xGbKC?n{Jh8#a@fRGE8!0Y4x{)PCrlXu@}gjcjFq)wDhMzi~GKlzP(mQ99-{qb7| zXJ0!QeEnqngGux#D@Ixu!{|Zy$#-7S z6U$5!3P4CSDC%7Y9STPWxwQ}tN(_QT6B!_|akJ(IY~`xo-S&~AD?ElNuqfD3xp6%D z@LLl+jW%wE$wX34D5Hc_2Obt=olm73|M)w>ov2;A_WG}lM6c>&8Fd}e2;G$}@0a7* zZkit!iQanSQFA@tx*d*>^47YCJM7`T7_4QStX&U#R|8Swr=)@fO`QV})!@PF&00s? z|JoR-q4ln_b}iU_b7r)Sh7t?4)`lx{gNinzY&0z0fTc5a@2jJ*CA74UzB2(Jd7{>? z2X4T)OW*yAVG*f3(uenw*1G%nyAwT=`MNIvd;-^)-KLdGC4%VqQ|-Lg93JHR??laY zS4&fC3#04@-1)-Aq4VRKmOhn*W<>`aCneYM(V3h?`nufOK!k| z1|RHYStNzW^kx6SnT!Tyebu@9yC*BD-gL?3fWERSe(kdjb9c6;&6nP2qFZE<=>Fpr zA$7mOi&$ro1PlA`#Dqcjl3(jMR`rb04-S6kt;he@aQ46^&f1H~^wEVam^g)0>GANp zXVZ5cpZv+m$=zwPt4+Dp{UTrg>-x|9Aql4FL~f0ZMovzhw(|8tl}DxJvA zwhx3vXJs^$VMkPnKVZX-C^JndAq{A;?bQ;K6>6|k*sE?Gl{A?nOjwwbRsuy)r3cD z9cSysS~Mtke=xiBavkARuokl#2_>pD@leL2a^;He*LgB7!wQ_pegFU<07*naRF>eJ zS_|L#t<#k&z7x>Smgm=b56c<~U;*94T%Y+hMhJAS2qZ_8xt5vfe~_xeIyGuEy#I}H zGLr2rPZp-W;^NQWz2c*GrlMzS`{utpYj1kjKh?yC3YYxBJJF(OCX6h%6O@e5#7+kB>KTmn_IubNe%z4)otIHK|5gJG{Qex%=Y-7|Z?q z-`~so$X@tQ(aP!@;ezsTe)n6)wm2`%X*VHZDQ-S~u2szsr)cT3?y}c=GSafJq5&-Y z;pD0xLA?5rvcU^)o9{DP8LiR1;k>(Z;QR)WXE+g*5nY(Z25aqbuSLD)hhFC^pQ*v~ zq6YqMAgw}|xt^RAhYx254`&~|HGXn$^7x&}=|K{W%OcZCnID1s5zx8yU8mP>@VQi5 zI1~WtT{oRd6q+qIWVg+AI3?U z>DIa%4azdpT3N7GE7M%}(y3f1k#X=~l-++j!qH|rAO3qa-duBwL@$CYnV>;SXl0gt zf~>8ig?X%l2KVcHc#v(}3}H!%NC~4B#}BdDK{|q#YgQKtPpM>bFsrdo+(# zHaiFGP+@fG)kZuj39%R)CLEf_+6|bUo2VkQ29XiOBdoD9uVisDGx1oiT=oee$yjza zJ-p5fLMV<*@QSI@VJmrv$;1_qOmNpuc$+!dnzb=xATs;5Sk}v-Zj8m{xGW)GBv>$wZ?A4emZJsEj zY&0m5%2ew*1fa9+BT_Ry%8Nu(PE=u3p{s|%XI{v)G+CsvctDSZ=Bi5>pc88rDK02N zY-;XSzOobGzg+ulv&?lemd&0UkEJY((V%kU`E>JTZy7CG{QPC6(d2t_S~)He3T0-V zqW>6W^H>+DR;5O}EBta~FKT6xNsvsW-wwzu_5xktR@Z)^^1aeey^Pid|A!x18|^eCy1}C#{QOVz z463EiKWlCGa|4|PMV~XqT*veI#&eymYO4+x#G1;e9(V9$AV177>&8E5Aqc(r(5YoW znjOBnDe{5tZhM3f^oOf;g;6#g%iV8A1S(oGCL&W#xLc_?ye?na@tuG@{LX|6@}1v0 zsWNB?3Smgl6~hx{jBTyCI1V8cC?$v`q2gwtMZ%^CDW*s7q{U1(&;Gmh@Ke$3)Xp4h zjg(0tXZ^|B?;rji5>o*{o3fCzS+bw?zI!P~9=65VlXUGy$OK8I@*Ds9==4#7C5ScWw(&ckXqBmc_?=16 z7D1Dr+)v6x_pbU(koUhac6~+&FqfFhBh6Oxlfp1gfB?$B7t^7zr-i-kuAT+%s#Rh8 zg++&8mCmF}1KM)}`r?-l-u$CJy27=$y!Mti+)w=mA0AXO1;fL9dYYG+K6p3IET9$Q zG|{5Q)^CJvz>ux#*Et4`v^G4g>;k_t8m@n`#a$W=N=nGtlhpNDJTB4Cn^3^*gEGM6 z2(QjtYwnfT8|h50-v}nh`RSun7RI=&^||)GB|{6x4d=j+T3d84`B|j!ey!gO9iQ&K zIis9VN*?^pIB1Dl$BBj|Aw+B2yBhj+zV}vyW)p-GLM&SGVUQ>QY~BtZd~MWPcZd6# z(RS;F8WZ&By|{NZWSnfjP}i|4elW>??|5re9K93$@n4R9_s@oZ^wshEyZOKT_4O~l zS|6=>E0_K0S((mMebp%vwR**mhULAl4sZWdr-+qTXJLb9GikKlcp=&ThZlyu&5g-Z z1~EujAV8Y`;I7sM034iseG)$|P5^YTz8d+Lzby+>>o}^k@lf`z1(Xpq(RlS2R=7(a ze{W`u<$`9h8t!Fyxn}+1;kPG_$Hqqmw((xbvYFy8b!w+tRdY^xw$lBjhm2D~LFKyf z+V6$kk&$t!__JST{9G`FB{jZh?RuC_m9cXe1?YCLH2dPk_t zI89ch+6#GEm`2adW92tQ*b%LD*9n*#vUpJ940BQ6;N3j0ga|?9f>yTw=;_F0Sr|n3 zkTJmo*?zHBX4-2KSV~e~Dx1vYi7MkCAHDKg^eLK**P`+1-|Bn*@K>e&6(8}8y*ob zl$fc^G&bEL){DLe5%5Z(&j?HDRYy@axQ!ZLLllFWoB@EwX8afN2M{g*>eG)yXE^0uB2Unl9Um`h*q}NaTbgZ z%(Ac+w6+9bdR7#%R;4i(nrm*6o3qF1v|qN?-R1d>mImqcsH@6niaR8a)yiexXo!a; z_PSadU0PWhSyq-+v$FypLYW&(1jF%OI=80;i~L#ETy-WV1rs!zDZr_xwT)FLn^t5S zGN(8J04mTCQ^Qh?P-w0?-AjI%>(++r)!DRPR9zJTug;UPr0iS(A#)QnMVV><;s#6= z#u(dLck@^Q0XFXg2_a5E(Zsj4;pUOD#vRlZ z%_Rhq6F#q_rT{>^d19bZrHl!o#%NbGIP)%`6@11R!8vGq)04UN8ypEr3!YapmeH^* zGmWPks=zK(ZtJeK=N{0lb+^9igEI)N7+z(j7r-uhepgnWORp?an0=&G zMMD!F_3PYfkcC;h7L=J09_0=(#ullrb%iW#d((4#t|}`o&Nzui<>)AX7Ffv>#T}Z* z&rcB!o8mdMJ%HA_M+lL*aRWvGWU2w+^6L#CFhtuvi|locp=8XZ3)+!io&w*LI`uT6sSak>`%U+61 zP}IXRLBQJn*wsa3QZMu3v`raN!`o7|y;y^K=gg$%4+x$I;7$AS-xmTXAaX|1_HE60t|VXhKG z0ABy))vzUsM6cfn8K>z~aY1!ylBr~zf(4oB@nH@G>T3=mM3*L;sh}yehRGq3Q-1l= zWZ7*0@@tF z1zRpBC4ah(@C^ZA4pq_+0)7jvf&jfFwX#SzFJ|1 zj}&2q3z`f|zs}1{Z{Dh*nKb33v*~#?u1|LsH(~!P^}XM((_(X)?4Ep(MY~mppp7h5 zRH{S{S&Kn~$CW}ntycCgTtt?$EeojyWg-(7LoRme10F;^W z8{Dh&{kJ2(&To9S_04~CoLM-u#JChi3ge@^))9MmXP@|`HLu3&D-Pvk=k+ENq_ys9 zX;5pel?mIz3Fu%qD^d-%+B7MrnCVmRIMJXa6x@Jcd9~qqbob4fHMZGv-5QgHAr#*H zqrO+?WG36n}D7PbWXf ziV^5KciGYXgT|^OJStpz`Y>UfIzAihX6Quj25jwScyKTFYHaWB%&W6#P?m+6_RFBj z5kRyC7$Zj8Y^DhzWvZNj-utUzG5qxOB=xTUpVNLp2*hJq=Ee(ot?g{yu5p)5jtiNa z`(Gbn^M=WWXow&@TJJi#w6n9a(RBzRwXUP2#lw&CY8$V$on>>=GF8*1eBZDoid6f( zSV>u^WO<&puqmY!T5C?3>-Fn_D(uB64dB%MoHxNMcX_NxI$IvPgBfL&G~=T@Yzb?C zy9{-aWv+kl2mO=#X_;xp$=*A&BGp05$)<`@5)Dd12`ZW~P~5Ary|-p%s$^lfN6((5 z0I;$XP)hPxQBJr+qhV=G<#d32jqR7}!lRR;0^@R;>yFBGGLot^L4#j?qxsIC4G^2| zT??w|s0HlAw6d-z&)5!^WO>%9LYC4>ZZ z>V^!>@{_SVcsEA5A9rcc6txv6kCbrf__(kDrnF9j36FVoE?j#3Q>}PZhHc*430$Ae z&PuPwku*9!$(KvUg>)4X#3ds$e2y2MPzvZCWz5H59m<~RAGA;f|Ss}>|)rDuOz zo)q`VGMFV(Yn0_a{rkWRf>qYJF1!Z)FzD(+6#9>PHF{2TR=~&f>T=wVtyT0x@nig^ zB;S12shxHDPsIr8qmF$4>W}nvUq-<`6pL)0SA*2EAk0UHuAVO&JQof=M>a^vGU!Es zfUW2@*5V(=QbHP`|MU}XuD0!`1N9OByma$Rez3X#L24_!zRqhKELdfW+v@baIWs#~y3r#5veYe+cjCKpgNxkdl zkp>G}cWV7dX}#yVZKjpYV>Rs;$*9DDb|b-UGDP?MIwu4gJ*U>K689DeIQE>lMi?Wr zvoe{;`if|@_{ObTGLd16h8$s(1EW% z8h+1-36zpbAy~QQn=;pg0C#9Kl)__oGl4uxlY5(okP5u#4(T?e^!MXHswC=^`=aqvD`doCeF z#s(ABEbWyqtxQh~ge=R{V9m2=xP;G8y}=y{mKbgQ21lb9IX9v6n;cyuD#n1a=xEO8 zumTt$gjfwlqSC1<3k?95K3T(NFlY*+!J4^QoCTTdBGo{kdD%I5`#G8+CP?*ea_)VO z14xuSFK9IgTjz-`Qe7q**D}^5*4k#zwZ=xn5|@mYHj7nb)s>m5wX0nsXma6Fpd_8D z8-#7$Fc3e}C2(nYMv!Bb%~Udxqr+mc-!2jWf8=W+7UvAb~~5+H~;O~ zY`>)FnzXbmtp(-~Ox*D6d~mENBdb>e#z{0Rfk11`^+Mj-a4~3hI?o&>1Y~Z&fL|9Y zS9~q4wNT9T_=6k>I4#y#bA?Oy--%%Eu8s#xI+c_WB~6j(qc`LE@YBlN2%mMfz38kg z$36gDdc|8{@VCAU!eztV=M>r7pCwu@{Fv;u&$Ir61^G%Dtu6=&RrMJ}vIw{F5iIEn z=L9W%5wbFN{z+qu>Ao@+9zFf0SJ9X#6+(ET1NK6B8ukPeln`?EutNQ=e4=so_=o8S zdsl-Z)gK0L^=^h-kl{gw-4~v(1VAfGIUztUz1qklg*qnTP&68}0F;o^N2wFAuqmvz zxM!jG-w7CQH0w9R#WTGiz8PgEhxzCrpPiJ8E)jQsLP)Fq#?I=Ob2+)U_nT5@rJTjt zv9(&8a;^th?7~(X2>`PX+O3`bBz|1TDGjIATB8i*%nN#8Ds?IVtnLH=fc2AC=dv&= zH6R*ZcM;V&G;@^U+y>~5e0@hk{oq(hVV3NbDGBBhLTgP{3`;qaDp_0q zGGQcW3gNNFio+es7@77<+^1gt`4vo>xcRx38#3Wg%80e|opdMk>Kx_>)&b!9 zr(2`_e9>u;c@T`z)~oSkA}2>V zvTC^?jh;gpAq=8HdFjPQG%ACpuojH5o40CZZit0EQH@pS(#wr}rp|^^T@7p62yG7x znOH~&>3ycf?$l2@&Vwh}(GRA+ON&HDgHn~|rJw0qYn3#w{^Dx?Q93y)Mu&MamO+E3 zQ)w+IJrElSjs%^Zk(R#eH0u85g{{1?>owwO|M#kp8l^2o)#>wP3H`*=)tuohP*Qqp~+8P6tk)S2Km3_MT zm%?RHzXlfM?4>f(VOs=E9yB=xoDyr-r!qI$OySt}$@ixKuzo#6c@%Dv_~^Pm!vtt8 zEg`V=LTw?HzxqZK?-btg#i=to%&j$2mbsk4QVz@Fq%o$Nk@^i$WQtwTWRZ)1ocjpi z_i6UrGS|YVv$OK%=h}I!nV_>l$ry1$<_0Vo%WS45hnflM*SS&P*ZImNZ}U#A)^!@I zt}66kH|t*Zgv(AoNKh-COjMcaS-(J+u4d1v@{$++q%!WSk>1WW3{%Gp}VohTDGKDy7GDh0EqUCf)oyXdp&aQDLZuR z=3={3rSa;_YtZda1f8o624ZseCuGX@F<4ruj;H0>QMz}3_VDfTgYOR?-W}~dn4auL z@wAk==`_M-Jy4~|ql%BCrLA=Z?$6djtu3&mPbbny>ogc5)O$ae1*;;DHREJa)KNw@ zZiUNzAhKL%gEAV*yfp0%FCNM6wvVMI;s{(2LZIGt7MK?yph_FIh43gBbaa#(RmFy& zAOPh>dS>_%nqUoNGZl86@o`Q$QPNs%l`^(U_pZEwygHAD<-&7tF+fG-dztBEB4_;~ z9+m($n|D@=_b+1*C?}Me#%U0$mL|u=qJbm?jJ8Fh&&N3iRB4h)`4nb@;X+`cd)*Tr zZEw2CM1r-9Q=_d{=kcf{6oCwb-te2Z!qHLQTz45G$ZODgF0|of?Rtp%P+1x#2y*8a zWF>5>(HLcMQX6fx1mRF?Z62%j>j9qi+#`#&E@+A}*T#U%bYsn(ot4Wthhgj6ng01!_kLUK${=1{FG z@{7?{6($}@!ayrKIVr5Mj!!8g)6-l@lSRs_F|AED)6uAuxgh{tP?>6ivt9z$0%d@d z$s*IqST@&O24wBpbNFjQ5U{XF+4}#8d$SnHvNJvGKkHp%kH~$ied(RuO}3g#b2OY8 zjs=Zo@mR7o-XT~p28R7$!`p-97h6yEgCG3h7r_t&*nl-2LK=ylotznRn%$gcFV)r6 zRh3nhd&VAjJ*yv1L}X-EHQBTXIFLkxm6?$dH_koh|G)oRrqtbu$|uUXcP~09Ij80_ z(`OMq4er1%gn{{Fd|L95IFumi$*@L?)C5&33mr9?7f~-HgaGsK1z{TDm~qTQVzkL8 z=S05l(c18fRO_cyjR4?mPo*$kNE|%9{YupWoIcEkyJGZEl!IeVi=>6Y4Eqc@MzWB{{SYxs@5H)mO2# zbDiLnadm-*Wt1{X-TIAua){%@gLJ4cn;Sq* zQ&BCz;rr>M?~Ri~QI543>$EQ?Ct`eD+TO429R0(C?qA-0@;h@f%P4z1$qs}{wUr3K zfmZWzjmK&VCcK%|zWg8;y`X_8LxaN-VN;9^X2{uBEng0qhlhtH!f4}m?7Z9e?o5oa zJS0h9R$87GX51CS!*Y07S_{Q29KnG*>o;R9%%^V;9HCJOLpcJ3COttIN(a&%buK=` zS{R>{L6th~q|q=wS|9zeVeGjNA}vl%Mjtdgmx9Lr;*p(;K`w@+95J(f_s{!A8!auO zs7UnT{S?3!i6RU+3)0bX$pey)B=vAIkN{95I@i{Z2=nm=f7As4&nIQ7RcSCq2%*lU z5CB%L##-9iis$5w7j{X6krxu@bm)#lV=QK9uwTS2mh?rn;~@-x`A-jTeYJ@Q+I??4 z-<9;jv$?hR`2BI*ev*cDdh#%ho2<6t5dsIFq?@-Z;}a3pSvr)fFINwHlKr*T+~Ba*;rn+cpZv>H z^*93nLs9-D+rOJ6eVGhpb=mvy54*j`MRUW?hO)8dZQPEHfpn;bM`ciW|u0J^^v&>OzL4gj669iMe*+wa_bON&x_G2sEx#tsh)B`gm} z)L;m~_DfYiCL%MKA{LONPcuSMrN!eGn{GJSA2skFG#W^hm#1CySV!kj+J{g}$qxHiLRtArJq*4k2r zT;)m_aJ13(xVc z&!Jb=!mz8{VsmbzQ&KSk&nNfa9=d_N7nA;z+%0Lxn80Wn8s(<=TG>0_>1RV(?eM6< z9F2TwCqx)dX7H$zrcAY)mQ#*vOP-6cAOtx@iJa9*T3VM@6I3aHb+~*sQbnTTCVTk9 zasQw&avEL})fl1JX>Z$`L75pq(B2G`wAomak=#1TuO4Kq#oLcFov5R(%yKi@2+{-j z#+vsxuZLf+;$Pk5af?@%Ja-;rf@(`%nd_iJRcd&RFiyOX6ceSDm4!A2{Fo{+eQn&w zvM?@|E2z>B|EQPr1*Rw;tHD9>jLP6C1i{QKbrwf_^8?ydGviZn`Y;b-+I^h61>^LC zj(C+E{%j1Y96I0}+=Z^`8EJp>HkbV zI}{0p&SBR7-ybeHk#NLf)Y#%Y#yek( z{W`8~F~f9WWVfFjos9SPhlLa(H7p=&H{$+5QKYKO^mJTzDYO9he=tM{#$AD#+lV*- z7!7`vMs?QTFN}qBVond#>8Hig&N-2(F;*)pGX3#)dN;pXPe*e7M(j2sn7M*DJv;TV zJ2j|>WNBRHJ)t-oE14Td9(PZe4&|gL%2ag^6`Wu4jynSglrWFq8+kEx=B?9W22h!4 z9^f+7bChk4FKcb*>^WH)OmT0oIKH3G6-*blOZRGJsq=}7YSbEQ6qKo!r53YpQwa;_ z{e1v|mPS3baf!@0(#i6*u)g9eX-CIXU28tkl{VMHQjRH`;=7&gfQQ5n2?8`15@Lb~ z!R}figz`jL10vO0*};Bc7Y0sKt6~dhd?JL>p&|^ZkF~V54#yZ-3!>1I8Ah{mEi%@E z0i!Ko01M;O(&#h5J?RN!tW%2BmiYYNn`?eHQiNhhA$L}Kyehx~4a&~7`_0#<7*@EX z0AP?jpu|U!pgV_iRdVv+#p2$ttX6&_@NXJpmDFBDL~6=ZS6ZBMEDKX+W^(eG{y1@y zA$-;cx$G1#!1+YwBUNNdE31SB3w}(J!Mw$Qe4-FVYd2y-@&3nWeOBD!N=$hlPlx0h zZG#yA;oQomn_jBnSs5u#Y_64^bmhr|LMt0o=)7H0g;CjbB|F`#n@BxfXkmas?2phQjWyr zMyf?>0ASLSTH5LoClsmDkJWufCH8$2nWDIugD z!4x^OyhY-(oAsW@P?$?&cZl|sQ(2+LSOmy58t$5CWo2Q43IPk0p`gl)b>*3+9?{B{ zPfet>Fn)z4J?ZQ_nj06-#M-hio+XHjn@p9)XzN%J!=s|TMF zVbh^J-OXL3_#)D4jO78Dg9-E3007j-@fu?x@j{vorCTS>^}sy|^Dyo{%3VS5>TfI) zh8ydCrO5^dCG${onJ!-o9dI}~6i^a64No4)m8%hD zsK1{(C;=fPGA#?ErOhXbax62gg%O!140|Don#_5Mp8?W49*-#FsK1}Pg*)jFTP2k-dhQKxSibb~3G?vj z9iP?}Z>Txhn=%&gn$?v#W6FyuCP*tg*ed|R)i)aeP>l3v2?#q^LQGILRL}fwYbRhn zcAnNduhg9y91t)cFK@7yzqw?L)e5vQ#@fR>>Hd3@utI5oFovWjn2$xS|KuM%G1AUb z*b(;$B8U+5{4aJ6?<8*jazn7G$pSt@gvChbJ$3qVw)@@K{KbF6-~QJb4PU(c?_I!; z2g!YaKu?^Rd#(`EWU7 zG8h~bCl51B(UsR~?qiw*Pi3Y7Y<0!XI(BqivX6A#*c|s_VCm6=2x2OK*`)3ev&Rh`te=c}qhj|_4+{o@ZO zy}e>%C-9!D>9;!N%XPdKTz<7iC^Et_4dbO8YMjX{|iYc1az^R;^{5&*FCmJX_Z|D(qCOEup7(bd2E!}trk-t!-By|LR| z_ZY__(_Tc9o~*BUS{Y-k^T=R=l?K3SiwLT(`r}h!0sNT$;Qv1EKP(U4%hG|&9#=6{u3MlC zNtG5wuE_w-A35$m>TCydM!L~fm)7k*^-aF`^9Vt`P4R4K=_DRrNb-p$9IsxF9=*)+rM+fd|YOlP|QQ(F#7orH5)1S^4eQL zHc}3)j+@MAaG|TSiXUHpqcJ%Z!^6@c8ubND>m$_&u#mRLNj*{H2kE1O;_y_Y8{t+Wf9tKLO8c`SUOlZJ`;Mu6*)TX7kfV^?K&$y!cqZ8PBG&pBKFXfVj>H`zZi8 z?qP%hEO77hGO(g00sx4fAbP^K|A4N1mo(o-^yFs_qu7+I-Boq;mAN?L8LvMim;luCo0Fpid0H!u_bjam0E4ST@ z%9SyMqD3-=DGmNtAO+UedAvmHn>=ih<|U8CsJcqGUypf=p8ICw>Q}4PHHtBW4Se;h z)s0s|uYz9t+nw4beeE~f&waB|-=WPbta*hsud>=Ebzkexg;(FK#mi*nTG-s?L7n(j z?7kWs9uINcVL&X#Xz5b8eCHBXWZW}2`8=p0 zE%&fBwoJ9PV6?Fo8f*UWsH`q~08p7lp;3licgHx+C(04$-EtkB3N+&^_z{_=*O_y5 zv=XLBv{MfN25qd-RuyI*biRJ8lJ=$6R!d_IXk|oZv@mn65cA2LappELC#(tTOqSXm z>1C?v`uivnmDMo-#LJJ|AKm_&BLIk25&%F5D_yWF?~>-*bBC<#Q?GL6c$nPtJMV!7 zRa)npR%vtQ6Uvbbq_dx`@2)L*b7?|z-FH@Qj@u3ZV4%|C=|KMAcaPR?#B=P@8k_bd zCTQ(?yg1BguKRvO9L?mJdUIWxInRZMq>=sSTgCs>k^iZ?yhhpe>>sw|Z@V8D?3bOb zVECl$-Yv}7RO+W$5Ho_%U%< zvn-4(bz{|cmUAwZxU~~FDuc^~oG&&}7$uBQcJG7i8N*I%jkcmRPpd31pnmlg4^u=K zLSW}Yv+-%!ds4WqgZaeOHmWpvqE@a&#yBpgB^WukBIY4LFgX>ANaD0@DK#cj30rOX zB3Uem$>^x8buRw9v$XeP61SK&FnCfnw*x|vC`@;E3TO}y=VMi-+D%CvZ0g8#*+>-= zopi;Vel^vy5HvU_&d#x?mig5$){BXrdxg6V0RT=P6y4o&ynn`rs&75pxNYf5(Kg!~LF8H$djI2z z8!RpI$eL@uQFe~3dEt~ftx8i2)SQur2{Ia_FbIQNs2k5!@csuA0ALYzfk&G!R4B(k z`qrtd8Y*p0DALka+T19^J=9vEowey#qeEW!rCQuzh@jnfN4hk%6`u#>(R<_R8IYN< zO0#2??92YW;?qAKtXzpG!$)^gG<&d!tlWsakSJ*%|7fC>86FmdBIaYl@T4yRkX!oh zJx_1TToW1r3!w8mQd!rxYe;_+iJ<|1xoX1}bRllGiDY;F6MK~SMtkM%#ojT>pv z#qMn&gb5+s^Q@Rc_^gUCK?pzzlMW=S;%bK<-u=vYp!$~QTCDjUe)X+0KG*uoac$Yd z1Ubgw+VyB~P`Y~q0o?qhW@F9Uoo2v+5%%D{r2nvR4RF-pvNT#)ze2UJgrnqGrd??q zR|}&e)3s%O@S}85F>8&}&0+*-@j>*>8^M1|O(n?>M(M6Lxihz7Gys6Ybn~(|On2=( z!gO(vD+Z0>H!$oFHd38O22S1h$cgD(KiS&!DaU21!y2RfOgubYEd+_&l$k!dp8}fG zy3crwl;P`dHo_W9`qCO$z8q49kME_<#ksu|I9ElHX+VGw(#mRKn(IC$XwsLm)Qwe7 zmbN>-d*Ss*{!$#Q0Kn0E+3?^TFqey7A^N?)Af~vodMzRh)jD30YLOe4)KeykdN>`Z z<*VU?cScV>m@G0cD{bzDBpC=VoYGU%kwUiZ#I`^Dy%PW^5*5}c_c20K1%wOBb6$@d z&sEDzBQ!Njn#!+@^(*w=_Xd|uGbx`ka$S9&kCnAhU-1s_CIH|^ zL`k#v(S&-~xe_7*)&lcznJLOKSh)SQ*0k(c@!azmZI>>G`B;TjYK_fCveMz>uD}GX zT#KAXTQO1HC;9%J#NiiLUaz;eg4&9wO7p@u+V`InIfijpxWFSqu@t7Z!ax3QA0gCS z^Sh7o`l>hSigYAD`r}?cQOEbvGSz^9$2nQ+<5pT(${xSV0U(yQU;Nk7;~$2&mG1w5 zG%ux{7ZM)e{y|Y>JqbSwJCC!WeDXm82ze28_n_m-jgCc`>2x5|f$BcVqbBo0qJ`bK zU1_X&WulcdCl4~pu@ZK0SOitdd@RcS7k@VW(vv4EfT$#^FUUs4s*x1x4~^%nW9TcsS`xS0}YD(PC`I zd+KKkf-EYtczDj5ih9VU6E0s1=D3w#|H%*n;V53c2wk~h_59&La(;J>y%glQ4T&XP6D{s^~mxI;Y;rgw3 z?N+1;jj?TPdvTko++6!wy|oc|F$wGJ_(6KX!_Jjkot@C}9jt}*Tb0QI5aWf|<=eVV z)AhQJm+iK)Y$)9b*)1*N;Tvx@vyqCM924a7ZCFUaf(vk{cBocXCuZ~cDga;t)g|t- zP;0AR)Z}1oP-7QD&=CS-z%jCCEZV7HPzjTd<>XY9=jZ%ja9;^(v+#r zM^YAMuDEwPbbSuMnvZSm{PVH^Vxj@y>R0PYuPig2_JuQ|wH7KJuB0^vlDfYXs7jNJ4NVW_Y8NlzGUr7$wrvd~%@w=Db$6}cWy({f=!LO8Rn6jl^^ zbTl=(lBIFhW~~iBA4vev($VMbq$eEOb>GnsSPYJ+ZzZ*zE?A2RN_x(5+_bj>qYYu$i%33J zdFuQV*dnb7rg}eyCtBrkFwVB z?0HA33lF8vit*yF{zKSZ_p-I+;+xl!e^O6>J4k+$Cavb=t2fgBQ}pqiE3la@PW5nCBnNWsX6((Dw4=Jq(ri6niJRQb)oM## zIW1j~HWv8nN02RhExs)>Qz2 z`P5m@Xqyh?;GlH;Q%4G(MuMig_oN&hip3Tc0M>5A?h2TvC{4!LN{3%Kwg7-5#4P9q zcJR(?wWqIbdpjsoB@3O6B=zvz_0L)NE;g-Uoi$edbST$v#?JZP`9Zk^KNjKjTXEbt zdnJS+k!t>wix#DL>2mnNKkv;hDRJ1D7t&|Cv^(9&9Kc$>8o3oECb}4C=WC>eX{`Cq z)}yr%oDHf+`vL%N{e07p$fPTHK)R0#R}93ftkUETifV597s5f@rC+%kQV&~gk3KBI zI;*dG%)^tu(8{XP$WmK-hG)F;8_PVv*1|ku4*(k5o);3r(DlYF8@yY$^ zzpvazlp~|zsl{=DR%N3NvwRKpcBg37S>B*^e06J$QA(F(0RT!Vm*-5IWn)uPhEMLX zq9}OHxs2K~5*DSNKV1-Bg*c-=RhqOfU;O0`<>=s}1OVzA-r9>XoTpfAzF5Ho83QMu zWC-9(zqR`C&xiBxHn#%iW20^FQGV%_8V~XCxU^sqz{$gG^;(n;q{GyM3U#>>m?J-? zn4+jb0YRB5=3`92NNWpgQakvxc<^V#hkrR*xe^^e$N&NHr_^pt&@`TzacDz=j~4t=w9E>xE0dbz|e#lKcn&@*}MVt@B%w zD&!a;ypI3v_IA)%^DRKF!vVmrkj>|+qZ6@yJ8rJ~K}?OdS6;9Cvzeq-OV$2=6+HSM zi$D4Az3$&LlNZwcmo~HirTQ2DYyOY_w@Z89x<34;m#Y6A0Ayoz?|Z{JPiJ0!F&_sp zDJBXbs4jWVH^JFe7;TfjFv?asp7T3U@?4a!6B;a5(^gw2u0Fn>U3;T3Iw_s^r}Gx2 z3_BO9v_F*%rZYDvSD#@F2vDWP5AG(8uS6)O47Im{Vyv_@=|EJMyvH9*!YbuHj+)E~ z9#^kN&2|5!U+P!`UPPh>8=ndulIFVq@P|W@X)h$by}Z2{oa|<&kMnoFb!?OcYd4;& zyzH9s0NgkVDl~|x+wNDdN0Yvgg|2oyqo($p zMp?>nZOIpfE)s3D9UK*uy(sl;LC`0D$|%XmGjj0C4%WT3BV2q4stF#$I{7&O;)FagowIAmv08 zf?SYURA<{S)Z80storUviOl#v=zAj>heRqnPPOe#k4TJ=Q1+9%DeZ|)i`QeE_r)g< zizoNfy0t9~4Qa1`rP1HZ=dY932mmxUf}lnT#p6@q%-tWpJBkCsee8^i5k-E5KK$Xx zYMAtd7t?eg7sGViyG!<^DlGLEEsCe(K2=zFmMASBtJ4R0(N%tfOtT0*%sr$g=wIEh zop9vWF`IFzoPH1!q=j|Jl+kt(e=*t;j-m#0=I#K{-12`+y3-uG;^Db+YV~@2x|#OHfFqIb11`;7OJS=%YibPdfY)-e4r5?}H^codM+mIZfC-xCHMu8o&{di0 zx!}%^h?AUH3uUgefm+%L7u8a6gINocR4?)Z+(nplg^?B^2y3j&v_A{aa(-1xntY_@ zcIM|nG>aCNi+0Jj3+mT%_bNJfsYRyCTq|XiJkugMiuCkppI-S5viOAg*z`~I)+^P? zsZ0lQJS9vaB~7j4$wE_(v$1ln6xB9I7{ z`K_VV(7Cqfu!&?S%T(uMRbTOniI#;Kos|3Um)kE@f+}6PI>lidvo+5=;@C9fo`9+U zI&hZ+2N2b{Q)oIQVsVK&JDy8lsQDG@7V~uDZL;28K|Y)9tAx#lS{4TH{rd23R?4x| znNVXZpgwus?rlu6gS0p$aK-42v zTS8F~VLbB9ups0mOdLnMnBGDoW zHUp;%cE!wv-P7&Haf^TENeKV|*T3AHoC+tp;sKcnK9Cc}DxncVdml|^qDAA!RAjnL zl{MBVOBfm*l{})>+H9=m`)63A?$Gxm;>_mCR1=Oa7^@M6l(1L7ST7SbKG35lqW@`W zl_d-X73zo!4rZl3@heQ^`gBIW3Oi?Y)%aBSF`<-LV=+N1m#J;~<_+gY8=hrZYU zS_9+hp3~Y4Txq&?Gj>K6>DYvAI_b;3566qv0SLij4#s@jt#x>1brz#xU~($TRHJ9r zOP!sdNHp`vd`1}6m^&t9X8ZR}5|ZS($qff0aLC(X@3mDa^lKADLT zSVWvfzbtgM&5!16pjp|m`g~Mh^9e;qpQcNfy<2a!y?`Wr>D1I(8)JZS?1*i(4PIaM z2*XF8oXM&D7V#oNJ)%l;vYUA^4XRX28#Nf^*c#M(oV$n_Kc>V(hyX$eVdOjxhKGer zX#08D++>4;!jXzwm$gf0zu@5Bx?$^U6ccp%Pys-=Y&$yyVbtAKPjelo+}|0!>iRbf z_3)GTz+RwV&8j40j1(otL>q%Jc7|B(7y3LP7Ht1hvh{O$atvi&Xsu=>ECkp}{1^ae zfDu8C${|ZrCfX&f9)Fx7fZCepVmr@$@R!5s&r4I^@f_mrzP0gcg?h+&X&>EBtIHmt zxWAW!h5mlA^Kwm==7T@%I&BvsD5y}(&}+ZBa{teU%hw`Rn&}~}ET)Kt*nQ&G!sJwq zj>}4mJ$`RI?kkrCfB-pypCd*!wmtXrSl=MoYLXxJC!YdEn37)Tx_C~YaxQlOhQI52-#Y9y* z{NDEmGVvD~Qb~T0i+*o%_l!#Rm|YM~QsUPuS6k-w$>9daubK1}FCv&Ak!i|NW7QuX zmCbcOs8MTe++;@&GE-bB-~AQ#$=@n>gW^sc4sTqN|IYLFf9S05$OHd)@ZMqn-IKwO z&`a-zd#^Xle=s~OH@5!H@%_{_4-Px8w7sietdEXMLJ=l-y1ye>yB+g@6chdY&v*7d z82d4)Eqg_xn2+ad{FQ6bS;043j*WF6Qx_+iXCpa0DltXQb*S3m)=ndP9)B=tZw4#Z zqV8_)^n=dZ&KRh4_~@i8Gff!Y`)J}tY%RO$Fc#4W!6aq5NS&Ubnrf2Yp_a`VegFCyD7R%M~BwMkEoPQ`0~ zYlQ{Fl{fG3TIN@1ddQ>e>C)Bl@Mw~bhL7LrkhMOGM)`m{m6?)ed@8z+azs!zQX7r9P)k_R|$a*>%@#~Yst7k$7u9-oxd!;_w{7UCvD2&jjnI#bfFUXLcH zrGvnXG`+o|b>*IOd_;JjV~qg-qd-qxKdsYLwzqrvF?UO+$t=VB)SeZhpC0U-2lzM%yCMm|&StXMl5Upqqz>H5OLsxLdkKYpr#j zsrf`b_x09;cSfzvVB8gPlL11M<4TK9x}y6i2Md0MYHfb-yGKfz&Q3rW3TxEe;>~qW z-b)a`@|DoWj4@P{Q=hDS)=hkIohko6V*+$+`p`q!7fRw0|jQXfD0 zaN@28#>lA>D8m>}!(PF{R3?J~5rhdE9hcVFph}aTG{yp;utp!hKVF<`@qoBEaTehV zh!0^16Lk7SK2!50@+m=&%s`g3r{V@9^k7_@NMB9&!Y-=TgTJN=-@OuRaE8Zrvb z0ayy6B@#90oOspVeujTj>yn2k)OY9{x|%m&j%-yXYXAMRx2ultiv9P?{rAhTPCGln z1z}(|)X!uRP2sIowx~Uv?{E0?no|Myh^r|m|6Bl85Ro~Ln~>yUm(0-RgX#VLjbVlOcAhi$Zz}$XR7s? z@Av#z8<81?^;5|P(X(WO@C@1D?Azy{t}`K_hEM)<^o)*4dlsii#!4yy9a}(!SoR1X?2=j?7^`rO3VU6|n3g@KG1L9Od zyh_SUi(CVSY$PAPJMu!DkL5FinJO(l)pJp7wUy@=bJUnNOR_M`!}s4F?z~+4_&fbM zJ=2j6n(Mx!t9v1#9Isr9hEpD^RnnA+*3x2zc#R+odmm1CjTDKF>dg570Du<}FCZ;|b#m2rF@ z_LPC0Qw+Ew{ldR58u47e zWy(yuZrR1)E?tg}K2041R||_N3M$lS$i@;Z7-g-t?X7@t6g3$j@MG#lWYU+iFe1~| zfYBCVWQ~pLjCq)c)DiKFIrBQ4&jTD?#XWO5QJ75?20@KE<1iNkqNPdt(kNS9^1xc> zM&y2Xcvv`wc$sL2rn!#PYOCZlFE46PN6}K!$ij$X;6+*c_3r`zu1WxiuFA%xa}3bh z#sql}FhvN#;GmSb5t(kR`Cdfb2Uog~HH@ll?x-l2U#rjAvOL59NS3yk=t`UOfE20n zW8zK$FD3{vo{AOOI_X+(k1R%BY{n)#S| zSmatOBMN(Zpwh9aF7dd*7G~aHEr{IImc4wU=agZiE#-L5i-;SnNL4mc#=@j0COttp ze*FH}7>g-#`ND1mYB^2aUA-1p+FWZpIVll_d?Y*Dfl&q_a6We~wsPfah%l(a7-I>? zn1I8W7Hbbje**xoMgU;v<=TZs_{`&PPN#xrMbh%p<%m$!+zk4= zdA&^t03lFa;b39oxp;Ui;wGmaE_1Df;XY0W(qTz7Iu{+74&>E0>RM|z^_)vVRc0`T zO8cyIC=$K-TxHUi&*XHAOd|w~sjSaF*%d6`3Nc3cQ0ax4hab~%S4_I1OjMC*_hHpn zJa>qQ+_*r4ph}&oh%wfWi6{VSL6yFAf4^`(v!hcX3&X1D#b4}LWsmNk%akJ?e%fQ9 zvC55w!;NNyaG_{=({vmH8c^Q?G?@LW&e&)io5;K_#*Oi-=E!CJ7uBce);0m0Ih z&p+oCh9&aZvK3;+F<}tX37{V z3+=F2ur_Wp0N8k`!aQuWJ$abVc|?R`!Z5~=4CL|sj51uNng`gADaI%pORX(J5Y?HM z7Fkpj+Lb`A8_CByT1#L5jmT)Dwe3F2z1UEW9g*+&<8zz%&Ks6_*eHAFTN(g1zF-JL zR$E!xXXz>I?0@#^FF<1rV~qCy(##+&v!EX|#u%lfndaYEDWoxmZ49D@Ar$o<^6U`W z*F^sTl}Z#vA*Ha^0-&@!a;GMn}jU zEK5UugfSq1)}~)fv;`m(D`^(zV+aG~=(S&8<{`QJXQLvU`e-`SL5!zK8JjOwr~1=1 zJmWJP_h0Y|S@{<-`a>NZOrO)PMKyvEe`bCMrx93V`mviuV07k8K^YqCmxLi}UDFN+ zchl#;(ROm;GbSpT_GW}3Yk;~IW%hxu-Heqm%)=l4QI{}WX>)5K=}9;Ea!xwwV9Khv z_0{I_!;E>jvEsXCvPhL5Q%KzEl%l?o5 zSiSS_JHPYgE0I>VwdEgtoKO!NWf4Yxg+6>|gy@8<_c@CX`|mtD`QyFrpJip2daTl{ z4)jNq1kL#BlkRti>f86?e~<@%n)HS8zC{@#1lN{5XFa%lIiwywevl!I)^Ej5BJM{d zsxf1%$aPSmfYGDB8h3Vrpi1xjY0vF?VU2FTSUqcf%{2Aa3+a6KdGf*J`M=)I$J!{n zaxHS)E{qW&7y%e#cV4O<-B0}rjhlS`PU3oiYMY<#X51%6+u>132x1=A$_x(6e4@ON zK~M0jWG`+1W|*Psb0Gg$wC`xi?Q-!+Iy1A(&S^ce`k`7)Yc2totLVs zSEFPgt8E^)J?de1un~$0Lt2~W28-4XWoZyEU;4K`IQ%5N{?*Zof1`W+hdWn)ArI;& z07=M-uz1APV(qSsvigak+83GCVFfo~y`0buNbw-yI7$I{)=E?G}WQ>Ml-fXY<+)e-=Z*V}x)QcR}R zH1lv{&38Ts#YC&pL=E=BH`;)}i->b5mxWQ%f<@!gveM@D7FoH*t4p3y_UL|EChAAu zJ`GyLZxNAcAq>Lq4npgx7tZRpX&$~(U8W9PZ%0LDd*FBcZoJ%jpz62wJ$du zus$bdx=oXEq@~R#8ew?&!;v#1APnu@N!*R#&h?WAnVU5F5g8p70Dvg^=udhsea31q z#yT_3xql5p;LLP4ZdWMBb6ts^aS26kf-1{~GH$X-S5S@toC1Y7or^4uQD-4jYd7L- zq=M>{$6+~x~)qIN$)i4?+i2NI_7%rgoYMUzYy!rXh5TLbIM-u9Xw1$ew)?03bt za{G>iY$WrEnkK2wdZ8jwN*a;tY$&y|qhsM}BUc8sw}NaWo&Miw+ujb+;WH{5RahEf zOpqAq^hC-`y9&VhYJC<`;|>%@gLi)I!#(*^5v&$_`=`*5!yeNO8 z9%^m+vNVpRwefQJw34pOwUjEI$aH3uFzL#N-_Q2nFZVvk2K!}iS1n&TXFgqBC4{2Z zM$q3YTv0gKFEK{rL;bV?*8Eo%;TVUfyGH1<7+9;%UCf#G0^$Og!uWIfxCb$FhOX{* z@uMFHl~p(B=i!0@09}87Q4)wN?<0CPH&O@d?DmJG`8HkoF5CWtm6z_H?%ky;-$lVO z03fd>SX zL|G_2nDZTUZWnnp&SH7tx2D3bvmcO)xt|EY%0l}w9UK(KSck1dH99&fWN91(AaWhn z>F7j=+#m!rK$sv^n&d<@)_tSw!QF&%y!XN6nZ9rJ)hRJNpQx}#7xMwHyk5WaoxZDi zFh!1hYGzRzb2FEz(F_Ivxb%gZmiBC)R8|(INTl2CYpWbAbf4raH^QJwhezejuQVMv zRbBF|h4G1?9M5S8^Jdi%*@{#-ZU~{skI5oQiu!2z>X~;>XFJHp5@S@U6MFt;clr^^ zG4}{%IH=H1{=C0P(Q+&;Rp_V0DG1?b_-doih!r^N#;tV4k4ap^8@J-tW*~EW>D5|iJD6Jn zxmmmOck^S45XjtMg3^&h2rvSzZJFuONwIh}5Q6%u=T(UNyGGfAkMgM&k03%(wc~x( zR(8w(pP{@3y%qo{UDl$V(ChfT(H(vC==e_nKx>ia$G!30gWmTGIow`)3mGb8#zMja ztfiU1cqxn$X5)ownJMShgAlY==*m@2C}JL-zhY}F!bs$L`BLQU{9qO%?oy`!VEe@? z^KqH#>JoSPY0Sryu5c!6*4ShylYtEDthM1AW9QZ)?nGlg(aIo#f+{@ack~}0v+H#_zIt%NxzhAh9aqjEyUVNEoks70{ zmUi`ebjFd_&|0C67_{JWz+FW#&jfH}v9+6VG7uMPn5jS1S$G2|X@^|}7-?nqKP(@< zo$q~+?R}7?r!t6XK31|ci)6IgvggM%s8H9xk55En)h{NhzT%as-g=?xF8j*W$Ql?O zl`^ySRW|O5xOK65p-<7Tct9HK{^+2Ln(kw@t~~(&QRrvs2T?v!i^tR4SDu}BmT(7I zP-9x#e4<9jCBg{v8d<&`x|K>OI=P=YO14)g&2^s;luwiwk^bYeGjjQMc>Cv@*S=C` z9-$0rX$eEE&44iEkbY-bg(+ejSpdIETi1NQLNP%_s*mrcXKFYy-DHin2qA}W8mZtTYg;xRhT@s)`F6<$nv~M29pO;9ixS@p3zp8rp$F% zXO!dJcgL8aumAl`DNWcox8hfBMoJj1?CHbo>wkZ<%(PF?$|hUcWVha`7;PxWQkc`- zywc{}$GyG0_aNs1394+;6-S?>2m!_rH#zqSCg_!4U3Nyul@8A)3S)#YsL~<~)JJn= zqF*KTHD60xtJ397=I%qcb0Lf{MU@smyqf@m&DSc)fqCkZDn9%bTD)m#&+^1A1B!1V z&8@W<6O7Llno?(_8l%E1d#_LHj+v*33sR*V2QeiKPr;50gWnn8Wt1fpTWeW}7o|o) zm1=FZwnd`%KAgzHM0J)=R8VnDK%?bZjAnD)x7t=(%!@D}ln!NQJMb$s=}TTYE2|M8 zp(ceKKEq?>=HUWM>u|687g>4Yv05R9`hHss-f(U>N|^D9(8_utdGG%@m4)U$DJQLZ z`D?e>Z?CuB*ld4!x$*K!^VPIC%HR4scmDjn?(zLezGtj_{rZ2>iGK+uYggY0ov#7m zSV^;VDd_IymG=Kj+j|8`mZj%m|8du*&#Ww8)!xla&yLxdomuRHYk-A-T{r=h5Tf`Z z1r-ePL586hii%JKr3i&y_@*Z^LV6GdLLwywWB>?QV1+fRXII{P?m7Se{h#r|I=}ma5oKiMN{kkJyN)SZO$SP5#*3IL zEElxDS9C8#>o=-!ssdx2CVe&E1huk^lej64?`Lz_b~;k&P#I;%CuMsxB$N;Wgw6tq zim7&(7vsbtx(iD=0Roc~Id_&Vb5m(~!~GI13ZGV5;{H#@Km3;mGB@itE2G0=I*@+M z5TU-}pFGTtKFJy@fh3a#){v)6pN5%V-+_&FQjYNDj$7! z;O;(JFcJ^%9(a|}bf7MN>9D@!AAFn^nI7z{=Huz=jRPj=_~hVpstiV<2-&o+&>#YI zHp8SR*REFpNH)<|9Z6}WNvFq{`gor7LUwKW7U83{C)TAaSnD?ZA~hn&`Gte}dS2`LgwBQ%e#8zwnsT2CpDAewB`a6re4;5O zZVrP8S)$QkZ#U1z`oUY{#zn8b=70Qy;dlS%y@NZcmUggP#C2X>@{GoGU@TD%8e^Q4 znF(v$Ri%Q{q^FXeI=NS5J%t9Auf&8B9#K^q!a$vNdd>B~Sx0TYTwT5zTZ!l7ht4cE z8OWf*f>SwUwc{64-CFbgm|27QM9pB1fHjtVqtW$g!?T!0D+{9wJ3WP%=lGg~y}}wl zxHFxn^SX1?D6DtA2XBoVE4~-fpvs1O#l;uu_um|66YY%B8Jo%U9Lu2E@uC`c)GhAO zl}xu*gE(Yntj39cbXew3M6nozvb4rvqt2UkF`4R5cJl{&rBuj}+*I~eh8LVC9R)%F z5ScUW226)a6*iw}I2}K_9Z%*)1oZH3<_M2@q8TT%>GV@HWppMd;iS6cyE?!j%WF42 zwKUhcbu@U&$j0+=b(Kb4GBc3AELxXE;{reT9d+rrr)ESdZW|Z)=1Yv_muly zEJP~H=K+`1>y@XTzs}}z+*6lcsjJc!xtYJ=;80%uQuVWq% zeV4EN`Cp+`iBp~CJkMcq9tHrdjbPGK(}D6Lc6>i`g(zc`a-uc% z9_9cr9jbDw!9ssGFQ)p<-#-?yOCKXFpkbZQ8>*zQj64s%R68C4l8zJ?v`BSO<%>OG zV*puH7&5tD^&u7}p(;m2v* z6zND&Mxq**xtaDQp)fow&hLQ+37zfs?$Dn{#W^``)Dfz%bK!Yy$#<~eQ}jnJ#IwfT zeJN5C)t&TVV?yf6G{+37RKd{Ez-mY1u`eup1vU=zy%fIWB-uV zXf)K8JmUt|2&azD*jVaXFHsZWSJR4feUK1wHj54d7>O8Lip4VDFBE_);E%BcQQ{Q?0$JPJS-U} zR$GA6beAy|T3ypn>VB>6>$sa{e}zrb`AVgbSB)1a2bu2wxFCAQ=^p? zJ|Pqk(D5k6q6vV-TGxx4XL8^&GuDFBZMbvC3z^I827n?_%@uz}3qp{E6+ZPs7R1b1 zYq?t)x4hOykWY~rbJhu?H#JN9Oxe_m8!PSCA38ta3axHbulT)#*?fjdS0+MmK1#2FDLF zU1FJO_c5nqMF6~jmbocYvv$1#09&`KXt3J$oaELTET=kZh_EIAalR^qPgQBl+|HSL zvcSQ<287k?F#t*W(hFzY|N4sWqVY^=gEoKMY!t!@pY%$t5Xejl8r6m4YDLTZ+|9LNRVscU{w}}C` zroau+m9(IaoiBpuQN)? zbV)i97$JmWb*ipBmvaF6iQr=gMo%bgY39XAvz6)4ddlfT%F73%Z4FIbzmy{8-SY~Fj`;@JI?IkkD zuvV^dCg|}!<7&`o)pRbv((|^qI&*o~TDbxh2q0QxOt3umBj%=R!;jeN?P9zqPB~kq zG{bTBj?_oz#(M72vKFI;K*as`lbhdY2NgzuR2E#^x;NwIsxLE>^km%jqPqCbKi!?z za4&pod3aC~3No8gRsT@g|5nEeUZ_DFy(7SFAP0mV@uTeC3q}rL(<`GVo(YIf-h5dvtPA4i5^w;Ii4- zj^==u@Tt+rI6*sGE$*RmQEt}Y{U6ULhi=f_+sU_{tGP&*c?#9F*PE0P#;H-r1hodo zM`eB47d~CO7-8ujkKVno{1pJOXrxZ3`2lC=8^w6zts8&4=R8D$i)s5towGo&C@W92 z$#?&cXRkE=TMu5Zb-V{}O;)eQjFaJB(Y+9PA%zED8r@4ieDts0d-y*cjowDIQYE(C zZ;1ck8Tt>G>d&b4_jXUddvxU=@BZYt8@xuuex)Vu{NW8Z*6Uu3lb(F$E1j^$ok{1? zcIdQ|+@nidp)Ab!xNI!@@BGn8wc}ZXNng!dqwBA=YF+=~TjTk0t`#D})h{&NU}XLo zcYZp#`dV}2M)kcv>A73LIB^wTdp#6BUA`1`FU4_PxUr;j=ydl~m3H}3q)Xf03S3x> z(I^7eSP9&&?MEz#S<;t`Q=@GdbJvS5ZHMC{dF7QxKGhDqV1iu!d;<`s1NHuQdXtmV z+F8`&y&sPOpxPGJ;P9Zh`h`ZB8WB*&NPAoEzL(tmQoGvn-}zqxwl>hxj*rSS1r~++ ziXS&b|509F_HTT#l@667wH@4tqcE(nO53~p!;$bPWyBF}PVQ$1AE)=;7`cv}`*i7Iv~(eQ^*2{9 zf4*_^ORd%GarbJxd?oTi76jDk@2;N89h{LXqbVxBU~V$ z6SBGFZ&S{kINKZHw67}5LY0Ow;(D+->jwe6h^x|$4oW|s(ObNbhE?VTEU0jm+tEQ8 zH^k_mT)rF=3VEW32PFV}{?}LB!q9S-6yo+6a0( zIa-*UNG$yY7S0hHGZt=(%Kq}t~?!1R9;v_uofn%-a9J0sk#!;=h4n5le50j0^@YBUvQ7i zv##dDJyn={Z;YpX>B!isu-RBW8KnmRqa#HGA1(##^N%cB`yR8 z2#H%l1hlc{pZNnK<`We+MBETYVm8r79~b4soEvdhJ7TzBFptRGEDHCozSM&?h3!c+zg{kweTtTXjq-G zR8(On$EC{(cQk~@7)cr(_qNOpkeP1fbR0;)LVejsKzrIVSK1!sB@_;H%eh__hgX4;p! zup(q=(J|TcsR<&6cIJ8}OS{N$p$rHmlM_WKDN{4tEqOq=Pnk!w#P(+3cA;||5I_57 zlwZh-lYVk%Gx}u!(6$&(KS|48Rvc3z;-G7+A0I6Pa7? zQ>`#=&JqBMsiBlOz4L6Uhv=>_7c?I$bV+as{Ct}E50f$69fUYveUlgzT+f< z2xvCaWoqUErb=5d&c=JvZIZ2xAfM{_!b^^&7t(y9*RE9-lM~MQe1&x}Ix3wi)(MjV zAgDUmFr%f_(#{o>^;I7M(y=O1Z8TbK-KONnj0@(3)r3G;RqkIGutueOEEO;i*8oubkbloBrJ*dm*Ka9DF!+ z_{f!?Z?x8ZAfTmT9yQu#Bjuh4nHi&Pb~}hp|6zWfkBtC`Mqv5>Pp8G0Yx%%QOHKBn40TfY())zd_Qwg)T|9aRD~Vw;nK5a z+SdTkxSTr)eK9pB9{~V_EkyuSX$QOKuW4-)7VRyb|95BB-FN%bm?9x~?r$e>Z1>SPR{YQQ?TG8XGIYhkriEr#hQxSKe`t%G|#Hoqjq{ zA_M^NM8%0y=Fu`U%A|JvV|M#@Au98-e=vCCX!LgXTfckozinz;Y;<0`)&9HJ zH-GcOt4GBiU;CYZl8<#%7digFm8Pe1J2@_^9WS4#X-}f=UU+`%(YJqna`($|edYQW zTa%uYnQ{J?)>yy7E`F|t7UzwFR(AXOn#|3-Omr=4(vt+hoj28v2Lx1M2aj?`&6^D> z3Dmnj5NNFWJ3mc2Tal4gOY5KT=A+M&kLA4(XYJP ztS|doT5CZT1`Ps%+LAXqD6PTjl4tf?#4E!pbHyt$7e&B~!KJNmd{U~?u3oD&*Mi<| z-dqdnU7ve2sIWZIqoZ%MgKadglj2M5wg9{-YcaRB4^Kl6fR|<|B{W zx$4r^mb{Hy6+dJ~V>vZiVtv`)d3%BgaZ`+r%xF(FR|65!q%V!eAO6dO{g3nRg{akK z@hJh}>KB?tYW#@H%ym@ zTF0l1xHyRK|K9%OxNL8R7NOShZvW!a=%8>)Ugz-TYA-Kjj1!ex_JpxQo@i%D*4>T< zd-?o_E)Y`{mJq0Ryx~FNum&c``mJiU>!HQv%dr=*(P7~xNO9XsdeV=nQF#0yPYLN0 zI+eCwVNt+3O%X>d%T1CRH}H4cju1p}8irJBl+qTZO*1o1P2e*xr2R;|^B{kBcV;|) zYKjN|AVPZhaq8NYIj3ya;I+JTq?jP1gTf^fSKI!gEA81~U!NgLK}fuaokejoq6=i7 z?jtTvw?{u_GB=d|OyJ1e&>^g`xtiE0d->&>8;rXwv!_jEVcu3f`NQQ)5g=-bFMO-% z$80)KtquQNsr1-^(tYetuYNHOYy80*`5g6VU*wFFmCLc)?!1UCUyeIl;n61r033Xn z5BJVOrjPFxlLJ%hK2~0LFNTbhbg1T@6zk8#=WDWS{+zT60AYo@QIMN(0X~Iw4***) zR~8WpoIzLUV6StOF6NPFiB*<4{Iz{GR{RHVjTf*yWi+|eF<{iW{P~*uo*CLk);Q zl^2;#2PPZY-FJ&}p&4kd`pH1$6KxGt+uowA+l%<*Sk6Q}1d2pg+hTlD&g-Hxrr28G zD)#nP==qdVm;+&R(oHr|m6jMjDkvvWjWLgEh1Df*xL-Qw&@wgSW61<9Q=_Go3qh!W zXNZ!_tRFH*f8X&Q5vU1b@DI^YCMQIK8J68BP-A!2KS)%7d z7i+NA@l;_ZClc^<{Ev{2mGFpBHczxJEg{5NTe{)OoHEU(bE;*-AmCd zf)l{`XHi0`OFn8e8r`o^U-n(&Ha;p3K9>1JX@x2`PV9yjwM5E5=0=zH;Lgqz!%FwW8PO7P5^cPRFfhtG^0-zrC-|tw ztwkk`gYO4BMSC+Oj2MlzCC^>4YS)vw32WRMkf}*eWKiYK2HU}B*+^+^DLoTy%!VQh zH<(h0YJ9j~6q!A`SE5D6X_@I$4{75s4DW4m**kb#Q|R}b3j-W)(VJGPd5nQN;NEy%)7 zhW7f;R~>3&&12-j)_PFscgbuqU`Xsrijrn8A^tp`XTPpma|xL;H|GY3@>P|B#$=!dM#9EaVym`Frag>f9Q zO4}0w)7m5>Gd)o%Gu?|(b2XSRJUO+U?I<0p%Hx50m6qqIg+^m*E$~9>*tK!=`Jdl+8R7+zG5(@htOc%-Qoy`yc275(wEg+N>iP^YS^<$xVbvqQNemu-4>B4~1jZZe7t&R^%m)JfzE>&)f!lWm| z8t?Dq_2uB`UiRRvNoze&(qt1;j`i}DxVMunI>gU+x^wpQE08k#S*Kv z78I!-9~9@ddiQjk8$9Gw?HCN>6WM#1yM@6xp)$8ojdPz^i^p>c?#y3C6BmAo*uPg0 zfT+bUzEr1zPL9jD-K=|H%G6kkM$V?A);OyuFxnQ0c5^VJ?74}hyAbZT5h2YdnovR* znf)z*_C`=!@}>hB#9a6+u5&^G5ywYz`}vxKY2W?h9*|ieE+HrPIBV?^VH{0o!E-^x3|0CtxD3))d7qaVL z!`3D}c-I;ijE5EoL5qYCt(CWQEPP4`QKjvF=ry)WCdko8HrM;5x&IXNkp*{{q$k5F zXPk_W%NKrmnKIIUm@{#ff)sT`_i|h$`si*NHAJoB{nBMW!*ji6mk^(jsL4m=_e2W_~FqX57vHvuy-(GZ~N86 zT>SHNs5;xB>!ZAoZrrL;TD$a8olx@bANL49Ub(Il^F9A3e{(DP2krHM3sUR)?ad&p zG48Q)YQnmR>ipyH4Uz--!Y_Bnhb7}=v{UZBHJLxTFMV_QlOK)T-qc(VlAa`lP)>H= zn=V=~Y(85nrrId98mE1kj?~ukH7{_eA_*!?6?T>qV8PMNj_+ri&sMF$pvvC=vwrVk z&OKV|26ulr4C^8vYu8%0H$#`QoDNk~=WqW0QITjMpru{AULgQ+%R9I;1!AWIfA1*ODj+K3e~npDFK9RtjgS!Q&VYqZf?JRqY_qmHkMq_(P3Hd z`sq+b4S@!e6ItteOwckjTu?%ZBTy`QkybmNE^K=%%tp#R_{&%0zxZDd+FKzKpo}=~ zZs($Z?e*r)TglZ|8-9gbiNE|GZ@u-e9#bAw+Foxb_hWi;KO>BIKD~cxgSvJ*79I_1 z+!|cH76XtQzu0_I1(PSH()21F;rfC4vY!r=GkyYq^;^~HK-HJLlZP1>)Mx~RYp*x^ zj|zwE#O+xnXN`rYW%C9V=ErP&Qo5`FckpXzfe`LfMDSzg1x%ONSPh*28fT=pTU6U( z|IT#za{Ta}Nm%1vK#R;UMzq4DCv|C~Tr)z}SNxk-!j+ELUh|h)UNvHl@@gDy#!)A14G!x8>gb;Rpcw zyT!>)_7pIvu(gf=01BkqWE;1ti^K$7+MmTQi3>`AP)*H+0}0Srh|yFGml4 zoCCnA8^U9u^^5F)d71mTH3rWTqouw0a(%d8v^D}Xxc$*7Y1N7B_fUW6jl|7~@=ZxbtS={3Dzz*5b!+toW4Eq$ltGXyj7%;-)xx zcpgC9e!kYff7Y)GZ)QGy8Vd7t1G4I=y9DFJ5BZs03nD)5G~tL>KTGD|zY&17?7N%N zAOHYg+V%lpp#Ew&S;f>eHhAO0Oc90_(}@}$7o%PwOY@h>2I13XgYYC#ix2=xou?aE zgVa1>qt^38U9+Hcsy!-*)%ciAyF!;iL>{O1Je7IZ-U{dI!7WZ}u}pP3P=tWvkh(WA z3V}kA8l$ke9?U9X1mQCTy!YdARGS%;gfU?Zim`TmyB9KR&}lJrY5b4{r`*r&=WE=f z^UVY;GC|{(Cj_aloF@qQ6&5#yUtvj4T8r8E%pqkSPm<^Pr0Cz+Ui}>E3_RA+ixE5)iX9ofSa?ZgDz-a}Z>;uoiSA>98)`=JvJ%*iy znU;3`AkPG?R%nkD>qBDS> z^}|8T+>?R|-9e_M9Uh!@o6dttOPuti%nc$GsV=5^`D(@C8eqX1YYpns>e5<^!k@{Y z9IK$#^|?m~IeUo0y3i7han`}$g3r8w)|Y)puSP^b;EXia{A{S4xs_XQVa$Un3o6`d zv#v? zH_>TthPJrO?!G?BcI(mhg_W-@)t`y|Wx-Ymb}+8^;-@4J2mo4AxV1jR+B%o>}^zeCuT~|W*ga&_CjVY zmZ_nPD97mo(7E+0^hw76#tG-7dokMkVEXmHx2g&g)_68n^(B9NB)b=)^TgpNcE6y; zvynQwn{`fw|9+img?i!0cHUBr6^{xs+$*w)E)ui(Y|W3EmewUs%2Ye9t14|VHRHX4 z`9zntn3^;B?db;F*$Nl)uN}kDi`d{%zH-G29#?rIKsh!22YOCvuXMby!q1`p)4o#j zQ+MX5&ZoU{zIcqXG;Rp)Gs*~|WdHpc&8o5Gdm$U{mtM#yC1q;dzjF1<5O!0}x-CC3|Ir_8g2DaL7f1c=sJdwNT8 zIX-pl@9-dI58s&(LL4!>+VX&a^MT%at|olCd?`*R)<}Hrs~w|}2_iESRN2udsqjdx z>y-J#J%=tPY>u*BeXZ%o{NST$qs~{h#QJp~09LQXNnZjXN?JeW_kKLG>9q&{{oigy z*G|Uo8>^qrGpyaZy8bN&Q6;#p3bXY}ex?bx(xN6nISV)ojg^SF(tNS|;P0&1f0Vud zw{FVcdp7?=d-UswXbdWe)05uXh5bYnCpEu;*R zUfI1EdJ*G39UT>;qq4dt+{KLQoO_f~uoh)*t%11Z)tCJKUg1#uv^-t}>h=^48}xWu)3Iv*P%0_>;r_kNcC43N|>qiJzej!K5lGfp18 zKfUt#MpzZ&(cAOVFks!4o7>*9zV!O>PyWX`08I0v<=6jgIJob9?gztz^7gMD7;Pyd zS6*!ZfX_c)X$v^~_X#1@mZu7P?F&s^T3$KXwf|@I(tlUxhWk{6)N1(lKij?h`NqkE zY`9-o3lH9ytlo_Mn0GHnT#)wVknl6N>3MNeX$e;?Q3k@JXtB4G#|<&}BH4L6*?O)j zeAe0sD=jfTEWh(VJn}-y~FjDLK zj_q~%mB#qEy#M1dp=9g1TGE%yqatLoFqD$H^Vjl?zO`7~ThBhKhTZoWr)$?Mhxf9* z52iQ2+;+~3OBchS%8x!ty@+`+@9*X^H;omad$Y)a=2~!YCtcc(cHW&ZL8={ZbX*#Z zBB0jb(sr1QRa6&DP(ZW>{E(tW?lZJVDRC(lw|{Zz=w8;@4)6S6bbK$5+hXN%EJA7x zE?*9_M2mp>A$RUkKtY%G_+G|6s>+#3?#h+;+H1}Fs^8uSAAK;j2GL^N;O(v8-9I{s zo1#ec_kVBS0RgJ8C-<{j*Ke%_t&L#LH|bmn0bu!7WV8*doN+qXE14kNqdV_R03c|v z7rxa+gwBPqzgJL3rUNud%Gcc#gSG#YCiFRbyyyD1km=_${r1QL+l$lw&5FXq~0cI9apY}B`M`Ui+Z&jy#xmcQ? zZ|63{C*R@1?V7V2JNLGPkbJDFZQ(d3E0^Q?viI=Evy)=|R`p;Z&iLk6tBWoN0I+_u zGIz4*Y=t{NDZGf)mORQx|54$`w6hhZLv@ZE;gBo`X`Q2A#ZAwJ(h@TJ)ay4ZPX-aL zT#FZdi#(q>F`#=45%EbQiK}0#9eq5*BEy(7MrPEjneY(jUEg0f@oIkY=h@gEz@{LX zvfCB*SM~nRtA#RBU1N)Akybbv$o^rGXWAM(hej zxBuXHzTI)3PEN|nQMr6MZY&4q+Kkabx%FHv8>z4=f|yTw@|;ZAncD_c4gl}{Nw3=S zjJ7T$j&YLorBT)aC`Mbb(BF{&FzxB2r+Ob2(_KkVZ%o`0)sBZ27P}oML$d~}ZO?5o z{hea)C_lNIJ&CY8kOBb8)C~3t%0NqNH8+L70R7Xa4N8fVYn-Dn?7f}L3#$3oGml#o zQ+h_~TSTU`v`*jc;0Ct7E+iEdk)1W3(!)V@s8}cFsZFOHtBOlo3L}YUr$TKW4>LXA5%$cLlVxx}15C8)@rZ z-w)a3Sk8Gd?){ycCl>@Qs1n^cywdi@N79XvoID&XdLh+?b*sodM}Czff?HZ>A)jiM z+MvRjAmsESmZ|Y$_T1N(hWiC!prqvy1*h^!v^yW&^GN6!9dG4I?0DQ!U093b=2oIbZP>_R1X`lZ>>M8nt6VGV2)0^URoJLPb%|>?d{tUi zT4JHzW*1(lZ$4YCG`&30&kl65C%2!iWfQ&o)6@&t99nfTiz1|yLR9B29m{2EBck)!SOl7N zXq3~NgQEk>p7a)EO*3=;$pk3P&?Vc=Jo%#8y$5Rr1S^>TIl)mmfK zr7$q$BdscptG$dtqcEGOEIB*25rHzYd_6vg+MoqW!HH#@X^}(m zDJM~bQ%cII;hYdkxS&8_bWqloyr{;l!S}x1Kc}>`h%$#?_)lv0{zCd4Nx8oMdTVr4 zmZ_N>5Wgb<2w}up)Y7tGVYCuhhd*5T`f2LZ1tLOfEgpSxeO@1aR8W6*0PE6DkJ$3-f$lB_40475K12WWa2=;X4|9B>(x_hB_|=!M{k^67Gn=cgAHIFLzgsldB>)&xj?;$+gE#h1zF*3*HYosU zSFbHMpC6|W_5GJ9BSoTAVYyFCZm|T^UA^-S*juN^-DiIz(4(K<7QaRaz5F|O?)>5U z(eUln7k+s3Njg3*D=p89n6qpg4ZqJlYFd9lImvdvb?N%Q9k;#d{_W-Ae+}#33#vRD zsoqW=RyZ(dZv>2!=2~DhQVLX%TVH8A>E#E1KG0J$C)_^w^`%eV7`eq?T{<-oA!Oxh zymTQt`Xt?auIg-P_C8F48mlk+VV&#JHdp;JGe+5Gzt&Nub@JiPR%9(~-LA>po;=8& z|He{pCucsj27{Q#4bk2Tvat?gW;Kd{5(4*sGQRtxQEw+thpM?Atlg+o+oHAZH&%o0 zrN|oGey--yf~I}Bexq{qNk#x%VqK-_)w}-M&C1DxjLhI#*#B_4b}gRt<;ndlTK&L( z@n45kPAL(W-xRmrYi$M>U#us6xppmHyA}(d=82m0B=;!eq~7(4srCZ)@a@UqQK3uQ z-Uum!;Xz3mi5uLH=%tq$MQWltchtYtYZYDEYRCKJjgiro5O7UnHdcg@bSS-$5en-! zDtV&Anox!HBjyG4;!E}MVcFRV5AUXxmWb*iIguN;s)PO94=JTYm-hI6=4y^n%5#DRToBUi`J@rI#C{!{YWYEgj#_-urg%<=t7!O!1b>+dw26oKUYsjO6Id7J{idCKi8_XXTtU8zqwRQbeZbpSo$%G8e-a)=}`5L z^jXV?;6<$eC^yRf;P>_cNKj>jlBmklp$e;f@(b7(b%8%LPL=p;2(6}Lrsb+$9 zFGj`G0D{#nIEFlFpF}7uUy45d!O#shnrnfZGsjJ#C2l@j%_o`=Qf>QQ$l{h)q*{b- zm5SzCzfx7JY{0 zP=&=!Z_#msdp{F^HQX=PZd7*PO#z^}=KoCUFhM(;!Q4q_^=dpkC5O*>ukH1xD9Xd9 z0c2s717P=3bm`@~AJNf4K{=@}SY<6=iXOdpMnG$A1kU_!){B0<#yE}Yv&yfr>N`4B z_d?{1@cf9O#pTP<-M<(;_2VpG_s&tJmbSw@(bIvPV|F57=bG)>8lPVQ00<(sz`dGD z2%qfFFT7Om-76OWuemcQ0D{)o+s}9ijSGM6#H(4ScR6;oeh7e!EP3RPghz#~K8?Hg zBoOeKUr~e4v66JE%ExoK(c*L@`-l19xN!DK=l$A0O*XiIbuGLMC;`uBZt70;84Q;t znTCm|1`m(X&6AF&S zGiL_4Z@t~9jaQ}D>Lm9jl7uk4m4$?n3{Z!fRM9(Tb+Uk zT48H5aPIPif<<(%a7OZIfp9lRhcY!rSwCXBG-Ym7X}y3_2KiLiyS^%&7|pt8u-fvB z#>q+Pzy;ycPX)!f~gH!yJiD7~|`M)l$Dh%bsS~S{D2MPh_{zs~q*;m(>{ix1o zhbaL>Si4bSoMdCgIqj_SxXB&2&MCOj;K{Dqd8;^hYiW4*x?96(e$=1bIU2onIC%4T z^bP<7qH#2Q>tOK4qu%$9M(>QK4+_~gblTnugUZZ5L5UN^-staY=UP=}dX6k`p9U4~ zp0zSFs>HZPTbrQ>i32f>vKuc{f(l!?9On~VO!cYrm!nL8lbX7>qMYQ3HVS2Kjk42$ zY@YHSti^PoimA!Rnh9D=&HAmXA9JTARHyo1W3BLMwe4AhR#`46S}dnpD_f=}8*435 zE40on3&4p?xJRc0IUTAQQjE}C4~#~mY^5y-fikg6mqYH6?b{Us@bJxi|Gi9QrrPmF zhehu}-n}g1h6roiDX%%FR-=}foXBK>w&{3e+;a}eU^Gs8k}~4Q%=xcR`>N9LoKIGL z+4mzZb89VfK^MW!<(bg)3@88R}1^N5mYJKx|e4)x3UH==a-UUJYm^(ARbMz~> zs~Ck|$d)cf{oSH_Jq%-x76GBN9je?`+TI+K@?%y`O|m2Pl%&Df2l}yF*QkF_V)@Vh|JA&pz?`|nuzZl6ED zTN;T*VKFufYEWS{%G~COcK`bP5X4jXdroNCc&6%wY&w*SFl)W*rz54G$SrZTx7(oR zm!jGh=}6Hs*G8ciu*r#>Pq6$7A03w5Cr%v$2-m*UYF`K)>*~Qz#*`8Ol!dhhRAEmZ zWY(Z8tt#v+1Q9`%rp%1fM7T1}S)9x{&s31vY!We_XtzIFGmB_X7?XQ+@F<^Y$mgPW1hkkZC1Yf8Z%$R^ZlEn%vHOwj$0rnNS|{P{ZLgn6{gO||14d^81s_2(;-V>vo1 z2>>EcPDDWGESrtzs$q?nnMsD~a7P{Ps7gmX^Og4TgB%EynF*`h9bJ_!$;+WOd6Mm& zd3Ug1c# zS{H5&SgQ?cR|HnV)$aCk;I)*_lu3!^t-)`9@SUD(=fu_fU-&QXS*sE7c=Z3V_9j7+ zUiY2Y+rRzGJu9=;u5R=ObOXdj5ELk`5~a~bk8Osf2*o%&I?ctm@kGqQCo3G`i?6zxAy?ysYf%>IMiooQI08>a5DDFW>jx z|Nr~{miK1)K`ADb1iSs8E;l}JTDJj&UQCTKWu|)%%l+GBdT(7FJ4t?+U-*xt{^O6o z%V+ui@++;4mu6)5bCv6YP!zYBjc(n)mGrl=ORv}b3e6@0lDn>tKlrP`&RZEKu>XD+ z99GXgf1Wsy`S>eK?7v$g-2h*Dy?&7^gdt&&IC$fwI30^=pF;$_klgzF!~kGDWtoqx zkuGVSz_84YYJ;aoi2X9T3_*MU1zvo8V&jnvX!fm z6A&lF|L}hvXl48=fe>yyAI}CHVQ~KCYC0C#L;?+zFtXHZ*P`h$cS0gc9oE>SUlxg6 zzaD23IXWmH=^^)Ct?Pz03JiGjFZP=ozF(pFRE9OGqyY#30F^Y%MV)7Y+KS5ywfoUb zYd{&ahtu|lGoGuhcgEDgNB1)7AnKxa$@`V-Me(`Z2lmg_;xKGF7Y3M%Dy?vSnE3cgr?p;=Q|-T5*bt} zbJ6b2r1MPBdyrEHO%BU4Q=2bWthE92G4-(Ha;lKObWX+gH45*X=y# zcb*BN7E6ZQMtW*1UWK?34y$C^7iFfFHhnvsBosAPTnnBe1lF!a{Rdf@Dp4p|YQM_zu{WI9*@X2)`^0ngq*eJ-AFIy>=}1`V-;?#k zC)pd>LA0t%?KMT8Hl(!2e8_gD0PtK zNuA(XfyJ|~|5nAS7a@j=s!Qa$wc%OTx`nW#7VAIEMWNH7`gD+Gfk$8pi&QN@l%Pf} z>+p0C;pQvx?kT?^$0w)VujUvQ02sr@=KOD2e>qq%L@F48ryfM~kWKb(p zq&n)7r-8y>{aC=l09cyJ8HHRMIuN)V<;++N0HAo8iS-ju{a{q4+BI4!|eat#a^9~2+` z-SJs>CyF2fPJl6mWu{JBDcf{N3;Gxhn2P}f2qT+xR%UZoorRf0SZ7D~vPOqAIs~2C zlNL(AxWS4<3T_s?iaEIsgv}9|B2m21{e3yymk)ng*qihbDKbUn)SoB_JWja>MgYHxlAb80@=soi|L}9spMI3ZtA3Ym%&|FQzb7g%4Y$EOSgga1QaYd;YvjJY{*;pAD zFdwI5K^PkD7tM7~mRgnC@ljZ#TAOOuv8$rmbrd%c&CzYE!mBSkj*q*SgE>LZ7$vMB zCXDLT7&F|{Uo()k{YL z0x-B+v@h7CqetYFph6cH(k?AK4Pq|V(pZ89I1xu%mAb`%AOfOLqSVDqK>%h$Q6!RQ z3Q-6kT)Q5XxiZFBhFv-qwso?SC9QxGnh+E%IfTuZUpA3eSl8b4KK|(tLSO(u7*ZeE zo=b9LG_YoKHoYOJ%;N>EIt&0%?>d+uD~alD<>P~r25503TkYQBZ(q7nJ^Z0}dcI!p zalyw0pG>ozLX4FbN(rgTQjCq!lXM4a=2dW+iP27>@j&?BR}wTg>4_KBqYE1~876b~ zla@x7%5MJQ%qqp;BH8gk+7~5Mu9w$L|N)&001BW zNkl~6qzyrC}BjYDM6Jbb{c!Nv~P*GGz8s|57}GQcYjdp- z?o9Lsyf@$<-cE%yd7+C^cOzVKGfU-gEXPy1Ka~IE^|;%huRP;lKIeTSKo^_zA~ePT zQK)LirB75}eud;S88#^Muu*2|QeZRLtvlH4m^(gF!i@IH$pH`RR6ng4(|T?;=lFPb zD6A6V?3`&VR$mB%Dpf*H`&@FZgh6ON1hOtevjH~-RF@o)Ynv;I8L~^r@y-&*)}N1z zHUNSB8<~Z%YF!UPaJ-cTZE7W7z^CCQ>Uy9lUTJWff%i6l-26OKnd_!VmLGskX(yg z}FPnB%p^fNUZx0l^sKSBPD9UQ98DBG;9UW09^h zQ&x*>x2JR>&zw?58)LxLFEtK6=DI+{7temVv41lG#uyF!swTdG5I_v=%lWlO3!=F} z05D14RJ#};SY6R}sAAXt=4+67SeDwaQV77&4RdF~F;n=7vuhvb13U!2azdtg-64gFW=zR~wZj z=i&QP>s+4Cr0vS4eSUa1>s$;lhBg_8hL|`QLWmGh(hvvje>4LC1WgvV*utl*z3GcW zr(+2*bejYiz+BvakPWux*BmocU2?5^bgk<^1aJTS=+$p^qa~3PhozW2xAEVca0Q7& zD=w``RY;kp#ZfIfuT&{j2>_^t=i_kW@d8U5W0WcjK74recU$Ps9)iE%GUYPyoTgHx zGD2zY^5ym2|D|#GJI%pwfuldU^VUddQ(twDAC%2?Z@6C|f(!ulWv@&XrVv0N3T3T5 zR<4HDt5r*5w>gMF_fl}YT^J3b2K(iI?D1SxmmID1;hi*YF)9~NRP zRRMrmzj7g;aLIL0qxXM4ZY;5-RqAvf!hoYjdik4MUPyay3w`PBbHDQ+^1a_)4!?N* zOA1q%422tE08C@u3+n7>D;wp!Iqn(>d;U;m$L=RW-5|Gpd6*h+wr zGQS1%A9~;!2VN=UdWgU1fG<54eyf6Isf{wT9$&xacFqUIK)(8|&g78q-N+Gyaf`kC z*Zs)>=c#I+_aTCoM>^asHeQJPTiM=6vr3ye0lD|~m@;(Z2Lk{=ZPnG%j1CG>=<_dE zroD3cQmCaK?B=h2tMlwCP+5Ap+FJm6qd%IIJ^U=5D@R;kkPDD~;Y(R$K7^fEYvOp=2cDmgD%?CQLC8 zrz7Ebh`QKl^YiZ+|)=V#-OelRFg_3=+f zR?1ylb{ng15L4z8HzZ1#Nw2JSow&(H2SxXCFg`5d+p$=a<9Vbomr>~K{HL!5aQ^6rh9<0C2b z(gi;q@$q3
    QFt4z0cun>acgrIS5-D}oaR;X5uwi`4_)m!h+ZrsiGj>@%;Q;o@L z#{~xDrPkW^X|`DdFjMOhz8v9^GQT|JPql8r1TL^(h#&-yR4R`UA2P4AyBCAcf)qGD z&Q3To*7p9hoJ3K}v4g0fMxPpV_>^yHvPH^F)MS249{wUf4OoN?HXm-CdUP)Z`-rLQ}LVZTr z;G>#w9#;qmLzp0~4B*gG^Na*Ez+Oc1i6{~o)oD5wr%|ey+XYR z6`ApC6d~AukO4H$AOisC($rVnN}KUq5%y@CwU9k^5CE_^Wv^aoJ5htV0UjTf%a_A+ zBxVEdg=dr9Pmk__0T6-Ve#r~v#@IrZW=TZ4!Oy^=S*eTo)7pYuKTp$28Km#J+hznKm`AYGkGkK;RTwGaQUtQnW*u1c^zOlM~ zZe@L=ySlcrw$WW(?X0Y{n`^D$e4AdYt1r~`>%P8Bb>~c&rsLscBD1kRyu-h_;chh9 zT7?7-di`qf@$4v?mLL8=xos^HJJ@(Nf&dT) z#Vu#FUz~wlWvO_sy@)8GYb%Z$l5{K}0v1PGq}DDTwPoidQQ{GEggD4(AWFqErRCgH z7y!_@7#69rayd+3ktmCmXl=5w$R@H#C4^9GQ}4QEqKpRCuPPl0jG^@ix4v3Z7#3nL zA~udjOT#lIO3gFngv8FAFoD*ESxX~I%`-Xgk07+oaM)ysKx0qicQPUv|`W2!z zC{n3}VUg`U0iLtQ>^u_2HFW-U{=|+XxlE?nwp7I#TsSL_0R&JnOc8a_@m8+MEdT&> zp%>#PILput2t;6Ec4?Hc$$ALGsL5<-vKtYjjgq?mFtdl(uWA`kP>FJUoa0_=eXvEZ?7Ii zfHDLjC{Jz3j*k&R);K?(NsD-jQiX-O-pjvoCHPn0Zn^==Bv9HI15~M(L+n^iL#~dF zc~Pndd&P~r>Ai<}ZysP$VRL)YJm-x* zFx)HL3bmZU#;VIaEVy<ceWs)Js6zzVPJe7WB8!iB$IdNHC ztk@!v5CDFGZmjaRHCH3IbpZ$fvT}bs+@1?-$wF?0#7ARACD8M9xOs zzGa<@!D)eE(&O3K0024{-S&Au8H!{iPLo5ezyh3#^s)X$i&MR};x6W+D_7<)J(~77 z^{@?NCO)#0lYA-=1`q)ybdf2W)UKs2Q+0SJUC6?T+e0fgsPugpj0j#`KVkg6Vxas(2EFlP&N^WLW{*L#!3)crqv_Ip~a-yXfW-S z%tMP?x4G{1ALN$*MO=ej0TE;#b|VZSBqtKW^xMVPa2IS1gHXm0Bv+{XU zUnPjZ!@H>;lRS~SKoDsIh197g!)xCpAO7{h$xdPHWU{&8VTP16qwVt3aI42_Wdlqy z;FXT^@V%)PhWW@U%&Y6JU!w@4_5!oCNmm*{O06vTVMteMRrMH0_!U-bk|8GyX0u|NZO`%pZRFMU|H`^S8K9-kq$;>bd*k;DJ}$*f zs9dN_X+g0E0C?uxQ&T@UeNL2O3Zj%`?a$Z#r_fu@iarEjl-yH_bD3OP`F(<2sd6Dx z_zz!g)V~xpoWnaA^HFWtwE=k;gZhedyq&i;e4eU%Z%>i|uP!-K8jC$$ext6qDH3_@ ztIgh4R%X%|10kR;N(LfNC3SIo(@Tb8K2wGEoI{u)FCskG#(dBRGjUN`zHuaw8=BZT1>UaQ7;X79Za zg$TAb{n`EH=4#z&poCV3=Qm%f?0z&$$Kv)+M-ao>vRhkrraev^#5^?GFL0N}+GVmR%WL50Rm=i$54_W6M4DjD&&{_2otdiioNJ}9b7 zPBP>W!L@6VUnP|#Cz}XDQRhN%^C!c&$pqIB!h_qXF`&8b?|d*F?U%i+JgCuH*R_#1 zJkt;Wt;}pFY?w}a({}?hI~GBO?%hnNg8(q1(9LzPOl90=$ymrz8w27NYi)SH{F}aC zAz{;zrS4n|uKz}>NK~!ku3d`}0rj|or)LO>`S?HAcZ zjP?sFkPK>c`-5pZ78@_b)I|^9n{+M)lOE4!5>q%jC=c$Wd8Q!*v*S5gfH0IzB!uAp z+vDZSVKU$l0msK)h_y2P2U(uTGE-hmDlG>9uy!qKth!Ny?cSIH0G6H!fB{Mwo~fY5 z{0dFSLL1Y&CywsUNB6CBzR|`gfHCY`4A!ql!`-~vb-joj-AjWSo%Fa?KuL`VsvG5z>@G-&q@g@Tn&EpZ-|B9Og4Y7^*HgR@(n7AI&vSp0uEqC1JT5;c;oVDp+`^^fbs7R!ZUS54J zA{14Z+~%4GA+)7Jkw~q;BAspF4L_GUZjz@+8X?H0BDYyF2w(=ce^KO9xyWGg>PShw zI0!I7r~uZIiGV72QU-p)>#4$J_MPQ~HFWPDusEqwWF72J6; zG&M`LJ=U%3+^0OcmxFX9D1it;AAxS2J=dh3gI-*9e*64c3p4fqhpoHy8gpY5uYQ`n zm)2&~D~@)uED?h1PnQkC6A~6Um1bxyhm-`+ob;;<)|Op+f7ofk=~uk)`P%qM93RY= z*0iszyO~Y!SU`TZIdM*5KpUTnPv13-HMeFXoF2aySFT1ys&4=NsJ6^1OY`u`@nMMw zJi}`<21Lu)Xd?XF9-Y$H5E% z2(8mlI<}#=r!D+|K831VhJwZMD{UukILv*l73Y~c%?r>P^baIHS+w0tfykv2nir~= zN?B-;>k~gXkWc0A&6(vvLjWob+*&5hWkT)1e|Sy|slx(42%M^8(lN8Doy?x=!d2ze-nQaiv;*u?k;W$Pyh7o7}`T)a;P&yp#U< z|9u>XIPkFVAOOI2X__9A5_l8|VTNOo7pmXq_qL0rI{jDQZvD64sGeDtjSbIwo=o?6 zd4lbxGsS#tv{6D^2TuqApD5zO>XK_TIJlj^rc@j}Z|D`m2Y z$S0C#YVB$W0LZ4oh7wr+IIRstuuP>*pi*3mTrm$J0E^R#no@q|3q%A|eqBq8ziMgN7QE0w?PL)EV1*7vs(=A@9$zMs=ZY8VljO9Hhh?dR&|#e+gp@SXKDTINnJS(u z!m!oc0SI`md8TAJr@EggtF(m_ZRA3cDx-mxh8L=w$@&G?4T%y4oPhNtKtY{m6M-2d z3@uu9uS%yqjxf~RxD|ph)Y^=;3l<=&aVaxp&Rny32E7H*R5q1bnYiWHHC7~&I>>r& zQ3?@;z&ujFj!vDJYfJ3F!MAn`-^H5^w%VkgV?%7gz3rkr z0ahOF7iq4?GdW9D!F6_WwFhHy_hEkHZfa}40Y+~s;|Q~si0Ah+JP{oa{pN;yy-w|+ zVD+|^B4acZg>roiF_`vBdz34#mC!s_jU^H{*;CJ2w@$3R7ldGPP+H#QlO9s7P2WCe z!7*yAdA!gT5iT>uGi?n4{0i+q$d<2!rx*Ac8FKr)@A%jv;|K!RgY^|xa$|{I_6c)h z=EB^nCl}w_SogFxMw#ry7qWfcUnGrKiPE*NHIMFRk6~v9+RVJe}NK7$Zysh|65 zlQ<}7nDO*r^HmHHL=?^i+7KWj5dz(3g4r>Lr^1*wU!{k4gcrl^6=W^#37wY_O6c=n zfYiaW9uMk_I%xa7RDvOJ4oJ{<;z@NwR+b!@YfCq?%4diGbrC|yW;;H)_*P$xp1R8v zGj;XLji5^J{(Nj9IV&b|Lrfi{l^!3Jn8113qcCoSH$E4~Eqao}2#Z8oIZQT{TI=>X zA5)mmBxaB@7&RC`01=oB1@mw^7A{7u3)G7U&}P=-m_V(-?3fo*d3-CQ0Rjft+DM%Y z9xr{VUSDw$2CCHcH4h;ug?{mOm;4IZe_wHt91Pw*8og_b+U$HCLZp-sGUGB)MwDWb z^I^e@N?f3+pGzKDA{x9m{kq`dgVj^@~(>E``7V zO9cw+bUNT(M7#hW^V$ce z-^cU+#k9K7+j(zrJiVEh$K&MwG~01#7^R;F06@|M02G5qy@b+Yn(fSLKWbe$%rF0k z*-mos{_{owgrOIc_2)wXz@*2$h(t{$3N<<68?W?&<{)meQEz9+zK<}v`Qu@I#Z5<| zEHs30ddva6+1~UaFj|8H8|QV+*+`=C5b^(<32 z?`J=FYdoGxRp>uhqSul6@~_3zLBvO|{?m?EAu=jap1_!XkP z-UnsxUI}b;AOP#v<7C7kf@Pv0h9CcI1QBR$_}N&7HL8_KhCHm(;a-u?l)d{_pN$Ab zvmw{g*lOOY_nD6@o5PO@^YHTJFi(^dU`i2lv6VCiRcZi`+=O*H+AA#YxJ)I_6?L$! z`D!aJb&-h)Hjx#v{m1_x z08?b+>&*?YF<`V`*qf`hF?UTW614!B&b=HvA!$7`w;drA zo>mUdT@;Kl1~~rQIkA1&4Qh1wptSTW2w{IOn+!_Kpe0@fHTD^=e`~{=9DU-POmf}W zB$wZ)e-fXL=W6%E3}NUX*f}gNE<1yII|6kCn z?ju$pao{4F@RJ@!o5`R&-p>wq(jt?eA{$(!!!7zsgrOf(txR&D0050=Tnq6q4+S-9 zCFGB>bpo6W^kW@hs`yMLr~6WZv^EIC)A0p<<@i$scC&FzwfDKb?g zGHN+m0h>GT1lTq&S{g4V>16IiZXrA;Afix~nUziCU^fR4zWHzWEfRq#lv3M+z~-r8 zf~3&41BD1Ok2pTI(?ma{QJu}Ro-xd((z0XhA?x@UVL0h=DYT7mbE=p+sPn=BM$VZN z>MV}Hs`Ibf4=S9U3dtn_dh#464)kN9rLoF-``^`N*WP`#Wj7lO$Hz8`XM9wOLThPS z8{QdNtVIS1L)H#V6nY-1^n^BFD^q4_?{;eatpwM_Y#u)D&A`F(E@y{so=6i*YyqG2fu?QP|Qm9BA1hnz1 zl;`T!kB5tb!D6Gu)Na!7X(C$Y`Ttl@b(%fJy z#APb8v9zbd@}?zg?SV2ss~}tqm(HYt%qjQA=y}@%Y=pt` z<*=A)TdEoWv^2INbbJC4th5{}S1xC|m?`n%{VcLMe?X)L^Hu zcF~e+tMao1KO1HY00?T##snBM5ARgcq$6HTl^YTSA;yp}ROUKrIfSC)?L4eeMBsyW zCYZwZhS%KiWs(s>eb1>+(uemBzgzIJ(JC+d1)p%42$hy%l9z*=k4iq`BGFoCEdT(AZw5gV z&kpuq`{Ui(m7gu~-&-xeU6eyECIufAd|1kv(xsXpg1x|LGZJwz<06TJ)nvK%ebf34+`v?Kb&}hF<+_(`rypuln)rQgFc(+i} zSRc*mlH-Qtg>SZk8g)D}JubC2ewA9#RSOfh8A5P;SlSi~k;fLm`m6hmbq)aFBAI3T zqvZb9!FPM(57jBw@tFiGZ4~hL+%P%!#{Jv7|DF^Vsf&t4wm1FdE8(Rtg_NP?%OS!r zZaX_4POD3f7n8jYItJ*gzk7?iu>T+<3QeSqJG+so;`-NYj&wjb#2Ds98hPwq} z(63NnKyBGE$~=63IzA`>gv>>jg5+1}aKE4q@*-jk008daoDqtsgR4u9F(7I>vtten zxc>Fl!R@rtc9Q}3B0L*#dmtqvvGj~j8QOk-cIk`t*^m!*^Wkn@q{_zs#cijt=D86$ zx}V8Xz4xE`^TzT{TI)J{AEyw4d@85|1y|HX)I*gPqb{zr9i`^IO7~)5srbEzx#OWq z$2q*09^TE|I&nPgMZ~RGlSqnAyu&Sr+!%lv>Rb#U0==zl>4HB!F0+Y@+ib9%Qx|ce ztq*ani5neK?=oNj&$M5mtxf;odsB!&*r0>$yuR!@K6V0pcqcIcgmw1bcl(!rtu9LK z1bEUbYhAa#>H-MLRM}cnD?=Qlq#+o!x}?=5)I;ZAu1xzSbueKF5m@ay=~%2>4G-_6 z*;rIN&a}@*`-PG^YO?Od5K&ZFn&XC|(9}Vb9&fID)Io}C8;P4_@)s1pJCduweE9Bk zzsI@ICD))rm)lOGN<*Je0+ljS8Lf3Dj8s5KgOv8Tx~IW=3LZ#;e@5MS$!o)j)fiUtvnlyPOt+5 z!0;$H(D*G}StG=Ot#h6zKFzhN+Hp>^u|8!2Zs>QaHG>tXai^vCmdwe>QufFQ0LlL!^5a#$mmM8V$!oIh$;u;N% z2BJ{SE@^d1SSJhc%RW1wO6p>L!scTYtd3V?inTTn!qI4Gj4|41qmBL7qmPfU;nSbZ zJ>*W+)zwCY5qKIC{LWj+zy3Fe|N7q?juW+W#4R9}LST$()@Zv%i&F0$mD>m9ELDMz zSC!ou}yu#-G$H$M|dMrd*nz?dCncA|WrC}B9RfqwmNTgRG z)IkQA%95K+WHRK7ZlbZ~Drqo9h``w~hX|x&p```}PzON>q|}pxa^-4hjPYY)6i9}g zItXFdSat1Y3jv@$ZmhbGNm(ltKoB(;VGvW8PXxq}P(&FT?iIioS?UE*XyN}|c^V1V z2GC2Plc9*)juP57fH8tw<91V9p8MI? zmR+q4&y{8Rh*C2Ti(Ji)IWKgXD#`Ww^_Wn2nh0hKl1iIJb!s#~c<$TCGeunlfngr@ zs{|MWF<=2Yp+CX#eqnvG>{qO|F`r0TYMas!)>nGB&Oi9i>q>u`h9>q`FRlK;#g*S> zbWTdp+&hhFK1qtP9kd%0DYTt1K?tQVS{bbkBG4E>7_w8kGL?&?v$^3vX=PYjcJqmx z4YZ=w2P;d>EWvVcOwN-avtk%5j84WOjlf%+)5r`nd zXuMy7lN3~ItPJ2MZvHk*pxSY$18pumgupVhn1|D`BorkBfe0iFjrR-xlqsRsAgC~2 zD4P}DB=EUa*Y_|bNGPMVX&_Lq5GBFKTlw~WnPmFfrSRHkFl`7tymwgc9+lhM`Td=I zbj*v=W=z9UntOfmzr8d2?!$t|)M~=wCW~7R&-LW6bYpCj@v0ri@$vYugc#;inN8*L z3!#+)JZ0)hp^b*Lhl~G2NHJlkzTzQ*q6VFw0+qBh5CH3ZQs&CGU`~LKALdSoPgAb! z#xg!Acizd1WA)k}wVePTKg{?*IUYg?1WU{)P$bH_RWvs|>fuF(k1c4U8g6#TQk%tZzL8uYIk#_t9gvOJR-K>Z`WwdKH={>h_x>000WAlzA9J zKp4W#Jbllyt7NHpp~D7sJX|DF3WM>ZgVP=m2tb>bwfKtr_&sBD3al{IzGv1Jx6-y8 zIRha0_{WnQ-0x+r(IQPCagh0o~r)g%-|3=fV zkb^r30N~;mYb+p^hXzmfEaIS*t5K24IRzcUa9y-E0rL>^P>~5tAb>!YT1gEtvOaT`Lk0j|=)q2b3ABT(!Cr1jDAYxRhq--qn+^jE&}uHnuqj&O!_x6_ zJ`tF}!A|Z3SQPr;RtjwRIz^&T`A|9ms&*Z_n_$n<9FP)b|Kmgp<5tPqtMTlZ`xSEU z?J)}w!Z4qTr3*pWpuhZ%%lMKu^7+kw76)sQw{kFiM;Vcpy{zmBkxE%eRd6}uV#Z}E zR91=^#Xf`x0Py-BEua5l)eXu1FPHM!c$V)b#o;vDn`GOQbUQDPk0&2#EtTflNB}@3 zSl{mbFe{D`Bc0;1LwsCc$)Hi=LuwHsbgLEh`fyq#msq$k2ATR(l);)Vj7!8)r`_w~e@BE{i z?HtOJF`>wm^9Do6EaxLeLc>AaVirOzPvu{o`-6#AoJEONM(f$H{f{3FXYVo(@7+pj zT{mvA?&Waf#VDxJqk9>l@bViCM4?e&xUIZPcf6P~4@XT#80NX64oXHmYA}AH|NY>5 z{c6WqYBH6odv!N#FhpQGCR!T7F)3!Ex#qq5H$5#)*klkvYkt&R_wt!MxRW9Z9Ut@D z#!bN9R%YF)diPTRz|~)`Py75A|M95Oc1DNg#ny{*h>u=UGnZP~R> zrMKT4T5(F;Vk?)!TR#~>2pa2NYu%#`A`He&_Tar~G7`--Z+cwz9^{jw(ij6V>_5yg zg_uEOK-^@la~>wp!j9A9vcBSpQXSn*4{oQ;bx&~R#{@xG?Kn}38ExMGZvXwi?dKB- zAn;={+AowawoHtgtg-I4&iTzX7Xa|=mm3g6Oc2I!uv65!?r^WLA;$5*w=DY7Hm*^FHCDZ&ds*D1O6tn8<3;4?Ue-S6 zXA_Z4M5XO$WvuamEOl6?VU0orqXrA=)aKDx6WNt3Vedf(0npM+5Yp1DBS>>aRy>Sg zUg{x1CY7#(lrm9(xzJpgQfQ??iJ>+|X=4Bgjp4aYr1?0}?@UyB;za&rpKqlQvt!Y| z5Lk=KPm)}H3fJZ|Pu`0N1fX@!|D;!Z%0SOWUPOviF&|+HKco6EYBGr7q{s8Aj9bjF zlG{HWFZ{^t6P^U)x)%fU^zsx?4_li88x~n6%2uLLi=BHhp7u*o7y!WL=Y3IXCCtu^ zY20Q@7kpVNOkqBi2mxbEZN)eV57+Ie& zz+ygz2rf!Gs~Xcn$4%x}=icgW6}b_)`_|a5bIQ;u(<{?B@7OLI0@&Da1`kS1P}Cu{ zWp{X@i-Z`&tE95_$nk3Fd~hZ^>C9tMk2cr6<4VvQZwHoutY6Hm`_xuTh>u;Z-?a!|G+LTr2^5;BZ$>OLe|v zPCh!=KPDSwehW<-s+#HeU=w!P($?y=N z1fX388~4#MbxU%T`p)uMxSgksra+lS9z~fLcAn1n`38ej#95&7X<7sauDF_9G1k;% z&lSfHS-s(N%I6!~u4K=6?3LB#r}O4c&?=78D-yzP^~3f<;A)1b(5{{vUUUsB4Lk59 z$?re!b4apFA`C#i4~Ae0fU#i7GR|)}FVd63@fgZg#?kSGm?DuoBT|4s5I*yWCt${* zMd=Vhy`)39#{UJ19Gkv^Jk*?_20kr0?v*t7O z_L9|~0R%rL*&dSya1X#$ahj(n_km5;cr)T!Rp64o;8oP~;F-5fd4YqX$m|A_lWKb+q^AoaQR ztcs|+N%-RnNL1Ka`1utY6l0fvKI#&;n`K$1aRQK@!8#drif7P)2$$mM_ww>qb({Nt z5g#n&8cWbPh7=U86!q?Z{`^b%n-QUqos0lsm#lc=F+;x4zWEo9sSdAAaV!)WX>>)! z-_zmO%pU1M47g!pVJV5I`s-|L({jk@kP1=_wIc&QXU4GeNt3eehUyqyAu8zR5C$++ z#>){JaVfLdY7F8kNFwMc6Fo*wv^)o!q7n8#X9*g;yGX z*N=oJ@yW>grBq#PP2T8P+lS70)wXyDmN~uVKC_W1k zMLstmgC5IaLOS)1l&tJi*mSbu=YFNkh~@6rr$F**8>90b=*(mM#>NmsD?=537Io); zMdd;EwKY#;3G4WQV~m>XSHBx7i73QZp$iVl=%YxK;y1ow&O?^0wb+Xsm#hh>%!*Mr z-H^bKi)+Ky0b>25(^+7pVTx&*()LUhb~exU6AA51yaX?l;I9<4vlAnSL+hvE;L1R0 z>^d;TF?(2{#t;6bka~8I>ZiiNGPc}=*0U`^@$R3r28iy(K}Nd_-2D5>#I!yX<#Q%x ze?TTEP@v|+5|&^DGeGsFpH3aYndT-dV7imlMktTATv-JH`hz4}`E2Vr5pAz}*%Sh} z+A!MYhUw@E(f3ntvY|x=MJU+~IB>{@mKnuP%;~@cK{TMd&N|$y+M@UF#L!_)`|Z@V z&q}nq>08Af%=^eq%dMp69b*mruek4Q^QtobcQ$5?V)%*;nYLOf{O8W&yc*)e!_=Xm zWJIG(08$%zrv9$%Ui{5(_7l)Uv6E7wvR+vG&o?z2 zx`=KVMQr6N$0k)FM5HbeLF$nn9@oczD3RP=HBRP#Ip{ukWPxE+b66B(GUg#8=IdBs z(3l8Ou7I#PWC#u<+8LxV^a~Rv*~pkkb$N@~?){-vRb#Do*5b${<5sF^G9x+}>ib+v z-;+KhCT-}Kiew;mcw2dddZwI$^1O*khE<%GdPDpydfTYb{!%&KY?JvNb z#-5k`>PWtz?Q*{I>VY%PE<*@~%d^1BxzE+>%JvvuRxWb~UeI~SI-P{jzBIn6RW=f9 z(RjK{i?&}Fy22gIjr`g{vg#a zq^7~CY8hTdNrs~?ZZS^@>HY+#WqR)-PxcE`%)+VSH{svV{!@VrHgY6qWM>n&(R2r^ zU#&JFNsPBwoIA2?yju%Fxy`EEt8?TTL`>wvj)RnG8U&H>__-X9B z6l@<{h^I=14(C|B%mN7|Lp3XZ(Y%~hF_bYI@yKR#4#Zk*ZR%_6mp>6R!`gw-D(X5D zsF(jDOv9@eDbKH;IQ{6nh$|d#?&b@ilPqOE3TRe+IFc>rYY$`2VH7I<34>JPbW@ zId5ynDfU|*zGI#A!@d>t6v@}f+=KbM6oHrIRK(x*ex-x~ih&}v%GiH4qVp^afL@wL z@u`}?UdU#4 z)4`xrZd?^5kSzkSvN6Mr3Bppz%$F9huO5Lp8{6{>$Q z5^PvcXHua`C84FT!cUOnutSLhayBemBkiHLPUu8gu@lyWiki90x*YzkVg1@RsBn`` zXf9SmDfXO!0?G))&&19VJL}O!nWQ*b~I@B2iA} zuN*TOYGSeBR0s5^kf`N9k(EyhNE5XL$3kha+n2QoYTg|BcFTdKR5An;Cx%0Ncf_na z>&ti@RtLPuC&QDQh$b9=rn7`+h*l|C*ZAmY&%lI!8*<@xigyBo$cVmeP9f@Xe~I+0 zt)}*J>lMQv+L)_KsOy~zs(XxPa^uG~PF_6~tPxABxT9snMayQ9@6f7X-$fV4qS&Qpa$(xgf(u&djnbFDSP;VYCL~9UXCX&sof;a4zj>bVK^on^w4(yd! zbGCe(y872y!k5JG>*pbBjUSHL&42cm8X^ejc|T}B+~i*YW9)p%pBW7i0I1a@=iyR7 z(${rtVv7(R@5pS(U(FV#u<|bWZm!YfMN5R}4{gV+k3`zBN)DSsP8~Z7;xs$sLlc&< zc-BZp3q_TU_IWK9b$3}XC7Bz;H+qb$8B2luU5Jocw__+`Qg7^$EHp194+o2%{QUi{ zXO4L!t@MNUE9@$vkM97x!Tg}MDuje||NmKlJd7j4^AB&;SHDV;rwB*4a0U`W5OXh< zsntTYpeE1c%5gb@RFZA>il2^HE_w=w&QX?9`u%@+ey+7*;BYjFJ0$BCs}9*FxCi%W z_?N%AXTA^RRQRt@MF;m@S1 zSX-a8~0cliv9pg$%Xbc5eSIE`yVG zzNC)EZ`DfGT3|kxF1T!4fxxy~jtahp8(o!enblMHsFgRb5+A0Kr&)MEbJe%~c|>dc zxx*AX2W&}cY>Ep4;Zv#^I+2G<6CIEbTK3Sxumwek@(vWur_}>wC8vEE?2tmRA)C|` z3T33ye4D20IZnrg1@NbVSdmK4xv?=O;PGGjd&@@p$IAQ9EfNsu_#{r*!ar4m(2V~h z)GEm_5lxar9wEptDRm~Lkc~=1!d8rew{Lqu@M8>5$2j-AJ73EU$8Dx6!231<>ND&l zw;`jEsW#I^b@NCt|D)59S2EzK%`9T!=aa=L!BNw7-F&m~ z*b!%oR#|aHp`N%}EN;eV3@-nvnHOMN&DH4?HYDap!5iG zcs)v8W-5E;st+GNcOkltWgp}K|7IYm-3Xw2E} zi3C&CfL$Dnp3>ac-n!r4$ag$+!OA7<vLeCy0rYKOkQdwl0=qSJV-~7hrXn z%X}{vbEajEyKXSNCQp~G^8QlOnY`~~?bRygU(@tVVNutj%VdB;y#(&BGR(4NYNJrr z$(XbRc0h%@t!|BWM(~ldm=N%k3)$s>C}E3fY9>2!&tlrO_Q!@=J=Gh0=><2ZuzB%B z^hrHD=MJN?ONRU5#!c@cNZ730E$(W-6sBexpUnpoH@I=fek~FbrP>mJjP|z9KfjH@ zi$$_EtZ*Sn=bpj5ROWq7`M83Xf_2bvGAA>Ln2A2wbBKD!VS`fGXvp zus`Db*W+|39a0_mz}=!!=cjPHp}D-U!J1s2KL-UiIm*SG5iF?n@hP0n)n`Mst?e3l z(v_@)^P`nF{Srcqer&uxR5|F(!&r#NW(n(Cc)NwZx2o7x_8CW8uRA+ z>eXh=e(o>QtpMBC_lM`L*Dcap_nS`L(JPI`&U{t_1cz7WmkL80PIP8{6yT0CeCkH8 zys@h@)au(V%q z-WEPqL9Vl;Am54nh*)ajOB!n?{6j$t;bE2qp`*gnTA-^-nNxEo7oZ5z80EZ1Cgh^Q}@V0@RF44Ko+9ivOADY7nKM*lHn*8@N%avIG6yOi{QTbu=pD^~@ zvM5+ZAytFc&=9_Rii8rxn*!LchVn^9BbH`ApTiAg>+uI?H z5fC@=?Y1nOx)Q&Ib*hXWU#9Hr0R|-W&1n$^=O^ArBjM}p)^<4?qLK!2raUQ$$7Dq9 zJtz_1g!9eV8?~tc93AVOk_t&!Z*p}=JrzfE;j}^jed&dymPPwpXg-?cgXlaj&A9(l zR&spF*tb=TQM7bD3D_Dp1d!3qk&SN=jc&IAz&z>u7GAx}zu7S{?PJeZG~wkWD~|JeyHVIHvG;_Z?j?PDBg2^uQsGQ#yF&8 zr2uwg$Sy;m{Bw1D2i!|`_bongXT?Ku=wH{dEWMFsZ#}MmE~Rd5O#rkqq`oREyV~Q$h;Z*H8kZoTnrxojYe`6NNjk#>gF_VJ%-zc>jV`B6mXn z#TK_c>wTktJM|kYF9JpZ>5oGX^T_wF-D)4Xth~Z5l-|a@Z4EnzkY-t7{QjGhbMa{X zj%|37RV^n*ayW2`cz1UyukHSYkghd-Zv22`E0Vq1ytSrbX_QjN@LYv)L?Mop1!d;_ z7dK@~Mpn#GK_*BoE5BfB4=7^$UmbQB$!F{g(PC8Al*OScOe4|E@?L{BSNg_dX69I? z)KnRGw=DF(eG8(pA@sG)`plClC0|;04o$zboYM*gu_Zv#Ant++_zmvkVCY}sr?r^# z<)4rl>@Cd2{8L$S&`JAl$!7=~H98}G=M-kDDAezdS7M40y?SzV*mZcX1oNocS#s`T zp`?lqmeP}2-sAE=O5YZAvdag}Dry8eG^EoAF~Cj#xSFR+al_pRxvhnhqzM88Kglr> z+72_A*Ak7hOk<0KC^AsPa7C04ggBEJU?-ubr0w}XbRlX;h%kOwqoB7Ps6QfgdjZ0-d!I|4l#9>>c ziT!qEZww;GU12gYM{$JV=$IB2e9Bx=(i(mojTc6@ufc^`CmH;XpVe`ti`IWLf* z8USTrZPfFamoo7jK6@tpu9$3_&JCAo{l=l2XHNMv>pYu8$6RbLw-TL&Le2+4oR%AA z!k7cb$MB=48;6;-EVBpgWjJ*#*8c?t*U2^sP7+qK@`1k(lr6R>GfIG6eg8a{L?iBJ zjt$S*gsewMx+n&;xWZ7#hp_3jVG_W!bHc|GB@HzQV9@Jgb!vrwL#hsAcVS~I_}`#p zBK~hk9}VNfqul4 zyH)k{)$?^b_3Gyq!IVLRyrGq#C$q2@sGzeIEDl?U$xk|NMg|VX|GrJMOR=lnoL(Q| zG(0>n)=b%;WXq4akz3Tf4V*}iFM(x$4k9nA1MPCsMH$Nyv(V_bVRM2%y5yk(|;L9`>P^+llcz66SF}Lr2==-b5 zI3jytM0LBBu>6FV~>HSm@VXiP_(8#!hhHFzIo@T(AtIK>5xL+j(JkVtH_ImwG z(Cgqwr{~}9^2e%}@IrwAw09xw51YiwkhRe{PIgew{B!FSQgv5k!w?g0nwgKaQ%c&f zwigPnKy<#B{hupZr)H6wseBV#-qO+UH-a5yv2t|lN8($r5eVO3o);;`$YB4Q%Q0Pll zboU=T3F}=yTo{N+uuAc~VNn{-HziewSY+j6wObXXLF23tGFUMITv~L^>Y|S6}}BeMkReczuQLs4m&Yy zAlbZ$&ra&$;T+NPm=Ue=m02Uxv}mTIC21(i#g#V<%qPq<#D*8ImxH5Y60xetO>sdK zffx$z+QNYApH@*y%L2QSnv!4`^(=~RGEQ>vOo&-5u&NH~RflDE>~p6H;U@fe{q;}} zkH-QBn0L9y3Q(iX1&<2< zr(<2iPCoFTgG_md!T;1yA6=*TUn1%R#4gO-6w#aJ+}G z#clY2x{IZVvnpazM)T|X>PdkkQ5|ZT2QmMn|4?n|ru6p1%+{H|=3RW>z)=N}~Iv7~o?VP6BL~GbM~ETvDZg~&fc8!zkK&|c}n zkwLQuhm#-gRR8s4A@t&lgFr&8VM@59talYs^&T)Y4;V(VxwpHZuc;mhcIfq_%0o`+ zChm-VQWYs$K;X<^1SWm7z4PH~hXWqph;2$IYYhsnmLrkiz?q*gr~VDi0ZO!z_JP|Jyn@3N5TL@29C^ZG+c+LU)Ml??PHtr0mJ>-VWdpZ&3T*Ob6-- zDM0PLZvQHDn?Xejo5fgL(+CbO;+mJzA>gHoi!c5nM=)lB2y|#GU{RURc4q=>*}{@D zzv_LN$f3uvSqv-|>FhoAC}30B7H7)lOftxLsTRC|jvES;-aV5gPFyS@Mwi39MINd{ zD6r)&h!V5nMawg$@Cn-=%Liw734uoDN_Oh4Bw(??DSRcf&b|gR-n}a z^N1*K_*wcMB=^oe6*S2l@cvt|v|R~uL|_Py;;tX`Et@XZByZ{7YAL6Xyu5TEoTm@$ zL6u!Dm>0vB&=pzZqC*gyH<8N%(q7JVBs2bEi2f2kgJri;S~F@{6hxo}B|!LD^Z|=? z#|5=<$bqT0p?i(WkFljXPxfRBVJs53Z&rU8h~4`ti zY+Tu-BA36bOq-u#-a9^5r1_kP4zZZ6Iuh{;4gJ)3vkbXD#p+G{{l4&fQyf)wtMU6U*v9s_nG44AN0%1VgV{w+IsmQ zQwJ7)-L>RCY;twI%d`f%h=L+r4^;4sbT_xgp9;?SJ=24|Rz|ylD9lyp6gd1{G9T#G zK@BPnQbb!7H08TZUXjSn*ADoA$Ev+_4b1_~vJMtE@HBUy(*78o%l(Q@COvfw|4~{h zhv3rW|2)iXr7T&x56h!ol_dw6xDXc1Q5W?ChI40Sy5oW)CU|JRXy|1;rts8wV&vSd zzF19?fIx=XcoE;3r*nsgznELuCNsaELf9&x3&O_q{!>|JHnE1MZJ19}OpGhhkVa$< zqe1ynXdbRO1J5XtC%o-1$plxEsywD($rk^KLveXBtDWvV(vIrSKjpqS<)QYPc(ift zF%_<1CVD+Xh+mu|lg(vS1G-j6@4Z$kH-A2cr^AMVB%A_30l9$aUlppvn$iJT_CqW;Cl@yZWb z{hWot6;Xe;dv$um#u-&3eZc6m+Xn6E%t*}(?$ypso9(FuEB||;d?M+GUp;hYaP)Yjtb9CP!{MMB})9u+(2o-tE}dGe1{P_20hs8t**D z8ynRaROF!4j+IL>hb$u{i#$Ikla!%lq2kpt^NHo+)>qf^{h4t`;?oZr=j~g8-LC5` z`VtOq?6+2!Iqz7pivJ;~$qs6q{sanC{`ozeeU&K(IflcF3B-mAYRVznN>;G` zQ4(oSRz#^G3k55oTXRZP8K3<5N<5+`NlfLUk47RAXPb9J7W`X*6amT{%a`Fi3KAVO z3rvwE!J#vYP>WkrT>+sWHz)gE02cf`J^u$O5rSspy3R}vE0-nfX90o*Vf|a8E4_Rt zDi+ux?D|;pqx@#yTW=8*TJ&y!SorOY^GL=dytHrjT+yMX3sAXA4e%9-HCN;C5^tuL z;v6jF8!i%ih3sQS8cC} zCo6XZ26KlPgZz*6w!gpBLQsE7uF}yWKj@9u5XY81Wzel-Lg6y{Fs8Z8T{qrf~&g-*HM$aRDoJ7AQ~&L(if*f)V{t>lK->#w_iR zv#btnXR-P9Bxg4 z9+I*sN3V*zFTvaQ`>(T7nPT8xZG;X}JoODwyn@4;b2xB~h}c>J1g@$89JJM&+NQ?a zc8TG)#xO3$kLuPvhqfCfrql-xZ{GT>%Lt}##M%~21Bvre zEz07la&hku!4mss%;Rowqyqn02T%ryNio75{8~tPw3Vob@NI{9`59WaqP$A0kbzGk z{r$b%=3ZZ0W@i9&T+`Wp{eBq# z=IF103RDn68gbbkv~rgkSjJU4RugxM+L;)YOGjR=^}_FjJ%r5Q1?uONRVUItMpV2BqE1wG2dEGv89SAt-oi2A*{t|PNsK3@de zz7)RGTc7!JX4&g*tMAj~)yEa>SKh5}{x@=u7au0S6^$K4he3;G2)#gH*<-P3&tNoQ zy*Ni!W}p=nTuLJ9mX@j@ly?xu{q=E#0ov{>Ba+Q;;T6Dc$P3PQ06SuS`bMm#@5nBZK`~4#@MBnBGxs1#;4Xnd+Tw4d)kUuJ!^VG{`bhTF z7B`2%c1*>%60mNHYCis9QQ|_LK7zoO6e-S4fgb$5B}9c0Ly=puo*$fIGMl+TI?h)pefqwF4q;qt%?5 zk#0UPTD;A+054<=BG81mFpG@uYLD{@5<)54$dH894*}uVA{!l?aX&v#;G2qp^zt(> zKmqH97vaY9i#2X-Q1BmcvY7;zc%II_ZS}Rzi!GKHw(TnF zm?Ho{jmrX&hnMM!gnI%E=!TtUMtFAd+vsz@;*rsRr;0??4)u!EF^i?0N0cZ{>}ROc zeGyLSJ{WoKQ=g!LFoNye^#uNoEi41cG#~0QHH<1(vS30fSdtCdi_RS4b*484oc^CN z$s%L3BmBP+W7uqF$37=Rn#X&p_U_HM41(_4EwSpMV2AL5d@%)oCO3=nXghG(MihC0 ziB@5#`XbZiEdnN_Nn!YR_J0%7;~H-!D6F^Sihn zt2)B)5(B&$lkxqJ{{$@K=>7ZEje%T|%Co1i@+34=r(YIuzd=rZIaswL9%v|n``bBo}Ou;2=InaT~(QR8acT$w=IrQ!4&Qf=&Z#?xE>r<4hNMkgZjs0LK6XyG<8fKTW%Cc~vGvm1 zfV~Bn146=Q1omVZLSwY=VlHLbaMNyyBku(KuM2#UA_3p>H5}igEGPK`{>8m2j=>C*IIa0;tsYnpsV7V0awM9|go z-xFYnUTQ(__VRg%7g_)K-SHC8wdKR?%1VO%Lr$G;()vt^Xh(qA+wrg6wV^)N$A1>@ zEv!@@4O#DTro#5b$`H2VOxgHMCL>9F1{LbC#Z@JEZ3^-mN0)^r4I zUhc!v{VbQsuu&8QM7231B(Ks&E?hP4RV#Z03EbceVli@*Xi1H90)eC3GK;ga@6_I1a;;vAJ!va)y?kWc9(iX}P-0|U}_HC_4fBsX%lg5b@OdZ5MxW_(ZRCOEr z#!m{VY}ve({UHq#YO7eGWO?+|3Yitf0@^=lemO7$?`mbdMo#le)oRpA zx?=#SDy(AQ&zHg7u$h0dIn;u(3`6(?sHHhf(Yw5h0Z}_EkZJDoS0l1E+2KkLveda) z^ChHTjnEF*tV#sMp!0NO?Ym z7F?cB==YgluY3C)yb#0@c3Hlnn>Nh~5|O6I#Y_7L5?A#TJGD|?>jfpxs3M3R8XN#? zRA*|8vZXi{Xo*bML6ml>*>#;q(=|SD8CUG-kY-GAh3&pJQEUd%@%wOekd{}Gi63ea zjhmldX;Q09nzyH#jj>f=b<}26LI}DFD}_O*dWB{l67!1xna;wPd)}ko&8361e&gHy z^3`SMQg}0C0_3`?BtXedShebx6mES~bV&6n>hG6$s}bFWaTZ&oOy^9bOu0-PU#pn0 zF;kY|a@Y9on+y9+;Z-kImSscHIVg~*OM5~eGDSu@sHpKDN^(uthmdtMqJ&DEM(xGr z0Wk!rrCCZ3U^Gnh*lhPDKvNd8P@&`p6i3k$P49F)MIw%z7 zO+lc=biLu>BcxO;-dbaQ{TJoxfju_2+=k$RKd`qUnBp!kw(SMWqy3ZV- z0^Gc-+%KTOMez~A=Qh%#4|SghDgm`y zEbRmyy^`TCOCj^!#d^~3?Lru1G&fEankjf8EzKy>-8!og((Z-bcvYOf&Wt}d z-(wMJ&z3994P1sep!8r%-z2qpUV<1PDM@k_eE|hcKz*Z_i^nUXOiX-LK8kix;-9)t zX&po0CRc-M0S1MzV?%^Dr*v#LpPSt0_BvWjM(-9+ig$L7uA04@#D%cutuPpskL9w( z5ZpIo*G}^2xShZ>GKl(yu48JQ4`+EJ3y-a8V{D|_>`g?8=Wi&YGi#Hb5uvDZ`150b zuJCeWiEtE*eEKgor@=uP;>D0m{po?9DL8)viA1MN1uJ9 zY$uoc0L|9GJdPS>Maw<@8~}e<^bsTryMga3*8GPnFt1tNVmwAhV^vEmw~Cw0zxzsz zrl@N1sn7AfnpJK?%c&xI>-8j#*hiXK8o&Lirj{rCOSwV{u+wVks|JFqy+G<0_ZOeH z^EU-XB{K%%v4gDiTTiXBX4ZxfsN!!kMo(IVoE1+Q(J5S8@0J3J5t-455Fv#XNKHvN04GtCp!XmZ}`aLza4SV()O4!_%Dn**6{ZOc&H zPka8-iih^TwMe_12nQNnX!HqIr_!q)g;Np92{0`Co2CpqUx_bov6@*k32+lT9+T~o zjdD|z%iz#l0?dW#$f&m`DfMwV>%9g{onZ>BlW`1`PDm>kL`fw}<=-3#6bRb`&Dooz zn}>=B8mH|fySZe#+RSp`Cx-%!=>5`<2YYeV{BYRFj=NU3C*b=gGkQ zHLab=UxOVFh~9!IT}SGJj3d|@Km0kWB!L0A*8m=_@jqCsP7&CG2ra_l8do zN`Ww_KMoJFJ#IwWbzcnw7T$K-U!qTH2W`nfze&CWY;i3TFV%_?cKzJkJns5XlI@ZK zPm)d+g?du9?T1EF^Y-lnl4+nlStJZV^E=JN5Oxh!@lVZIQvd07ii|8jO)$wMoePoHOa+Vv=-TF7F+8Af>XyX`J}ZB?i73) zq}$N}Gws3Yfy;``!0JWFQdqh3<9^@1UETBQKUAN$v*;@ZHSDbTyWSbcTJ&%@Py(v? zg_xHo?V2C2K)av!@2JFjxdn*?7?j$QD0qe5_K8*l05Df3Kj?{~$*Y)`u z>gi&wG$Dl}WU+NXMh<{OBuF2mzD+|M8ddyQaz;LG;mq*n=}CnRBey9&Ip52h)_MQfghKIIM@;&;NFj zl4DNOCn3Z=0NwNWUff7HV00D}qVL*5D-6J~t&U1+q3@bo#~=B?X(auqb4j6Nnb^b# za8$z8i#Op`RO^(()deop(W@QN+8oq_&^+#*Tys^lYG-l6JVv5m8u>}pid1%_(@lkH z{iDZLy>@(=+83X;T<1t}OUlI9Fgn-7^2N$=PV?lYk{KRkU3z;&Zb40R8g?<+bl$0U zP@qXQlc1T8)OaBs)+ZFfN4D9q=jrA}MKr%-bs>M3X;|!3s2ho9pMJkP zTG(I$pwe>){~)%GuIq`XI#t626~zo{#KPN3+6*FFp0*~gXX+l~+l9U0qpjD&_OF)s z_q&j(mKL<`%>AF5odMgCQc8WVQ(FyYW{D?lZt+hU{1JT1!pQfl9C$?b(zy-I`wW2d zYOg}`K_;eS9gzmjWAT!O2(g&fCi^Sjh&w{bFexLJ>IO0hlsx^BVyz^Lli$CKW!oFz z{>(MFRKkM9&g5xm3x!fAYu_B(LMW^JuK`KI^P zXNfPL$KNOw*~&FXAm1)lPG*~;gZSF`z`+ZjEGs7Sx-f;j=mlHOn*bt(yepb6ECcY% z2K|KafItu^Ji;>P_l;Rg3AKx~A&xENngv+z|B`Q|DV_D>7E<=aiT}KsQ8{-yQ%a&J zPOhHq_n?mUX_K1FYq?uSJ}op$5HoIw>SV8NT^RZn?mV{o<_L9n?(MO_(_YWjiG?t5 zj{!hvQz2TKUV3I!yd0=!_l~UmzlxhILkKXbjsC=|0m~z0ni*e{(lIfATVB&hJnF^+ z=u9;zZdW@$tpR8Ex5o?rR8O2fLABDcT`O7=`yu{eF$8enj8$^{-+6>T_51Bm6|8M( z=Ora#u(f)zIUr8be7{oudSvc0lFX6kr%AomaYLK?3z5w-38ds<2Cb6W&mA{5>jFum zGHYUQx2Ie~qM)R%5ou?Kjo*i)&4~n_Nfze66nQWmM1u*b(fY8{Dvs?SMKcDWRX0;q zlS?4ULPJPI-;V#z0uY_>yp@qGZVFAkwAf_hsYM7gCVBr5WfiA=#LaqpS+1s{x#qwD zUXjtVwJD1`k!R^M+A+!SmAn$ecNJH$7|Vz1u8#%=Vs0?d7=p{YS2Ew*8j_Q&HekR; zNU5+H6hy36s)~11B=~$#(y&kncEa8+gTP8CfWFkdU%xZViGDHpD`$qWUN@Q~>;a?; z@k-$XrKY4&B16ICJgo7V^x$<;^+Vy}&=gL^cOd^zowZy!ufmQABm4kXvW3bZluU94 zBueahBG9=b*85wwn8sXK;XHQkCAsiwVH8I7(urPLk4B|b97p^woE1y*j4m|jz*nhX z^Od2g%62iwzadjN(F-*%T?m52lI+;o@#NYxVrD%dUqJu%Wa*7^vtw&J_aHMx#?P5)=@y zu8baV*&mcPWL3~akEyNi2!T3`8yc0VJu zDOJH)9l86y!4U4HWnfj~H4kuE{#Vj}FIujC3tzLl;xo0rdlywzd>(RU!+jvZ4oO_z zWF@itD{cd0qzuGiHGX!@3=D7;^7NnlMA%AB&yk86N@SE*;qwdakQYYzcr3?shxwQI zK#?v}d#KoM0b9BdO0?RLzC+pbYKCUVt}W*IXD3>+i%kW8E)D;%e{j)xwQi*QKwV|- zcwYT0rGm9xCmZ;&{CA?8d9jxk%;8~KL$yOK3}kH^UaE|~)^QBjJr>sF(b)*Z2DPp* zm)^@dnfO2z71>d-qS33c!;_32>vSz!fy;r$I4?c|N9BJ*NhjfA!iS6PY@u zU*9b|eNGd7EXdwL--B+p&5caA zHAP~$lkAMSKFc+8%~??;szl5GIBjaLs}scCKpkhs&&wvdRc`jM~BABu!6tuM%AuoO#Gye8U5-H)*wC3{yOTH-0eJ{V_D z)&*}K$PLS07k>GIp&T9Nwzx%)wl!({O~qnJrvT+kwy0l_ ztvMj_I?xz_DEG-YLMi&{*5(X7OG}$Nufq=h73>SUyPIgQkd+$eQoyP#bEpqnioG3_ z8lHGJH0tOc@AMiRl}L*eB7o5&xN%jv&g5GZ1!QHgv)Dqx3NJ}7u%=u>HEeL=7Gr&@ z|Bc4v1sZuXR5!nMCCpt*{opNV3yTa>S^19S@?rOf6(kp$qjoHrnXK@@{2AB6f8+}g zB$6utn#4f|t){=V4#MZ}=uW=aWLF9I0j0iBI!5cO^UY;4m-P*;8LL9j^|0P}_tk;{ zdP<{?jz@L7Hzfn7&~Rvnaz)p_im~>V^L=A&1&aWz;+hj}@$TAoq)?y&Qz zal-Y1!v!Oz^I_aFpaKn~**(Ah;)ry}pEt46Ga#|c#Vt3R6DL^g?i@of2l-@13R4%u z4VPuxl|Exfk?}KE7M?Q(Ot%xIv~k3r&!{1$@D@5{j*xh=*I`29sJo0ZJpA|guB2PF zdPAWn_~kAj3C=9V@72+hVQflf-?pW%ZpxyIB+fJNccDzX?}I2zkJWKG9 zB~92MQJVxU{EPqXMq`s+{&KSRe7O8{IPO=6kJ6ocGeZ_8xH`1}a2`=lD5@`dWvZ`! zxs~>1XCsJOEbW_x8zBO4ojimfr?0ivd^hZS5ittB|9|ge4DEG)aw=q@l`uQEr&=2K zK%VwRW7#JhO;3eu2tf!r6iD|%Q02Nzl^2pAW@q7CEOOmm3zn}&gZ&Z^Y<{jjIIN6@ zm1|K|=)r!udOfiktOeKMtAw5JD(BA)Z#7T{C1CiSyZIk}w@Rm9s#T5!Fm3bd|U~V4^f$NPCY8 zYrs{BX*Fxm5~UWoYOeUB<4Q?WWy&EStg%i2)zWBXjRLJqK2;mf)vU2)s$6fo(?n_= z&sr#^Qb{xE2?tR3B2r)U5JH2!3RO_{l-ny=11@J2B-Bm0?Nu+Vv(ZU8KgO8bL;Q%! z!Z^A}P-oVFwH6`d7*))}4)C=3d|j5tIs4Y0P8^Kb8fdKG;DStEI3X*;+E?H8Uw&_) z@eDyk>Vgt~obUABrk&&et$F948)IvW9#}Zp%DIQtnV74U#RRgEG|GAb>FojA4H7~5F#M4?4tthG)FLg!>P_tt@4NM3vt-5e&@e$0bQAGFN$89i9|8{DJ2 ze}B3E>lgfguw;I2srnzz>{oTAt7*QU6-Sjys|g1SU~N#NZp~HFRH<_D5$7_?N3ydK zI9rJyQtILPqKWA&+>*3;m7DpX64a>k={RK}Xwdls;o=L8{X1#g0Ss$VW>xxG_smq&~mB>$F7d~iIYfoGl*P^(#&1$2;o^4 z0V6;l3ay1rdlGZhy%=H)!?QtX@p9;5yj7~SFkzj#Z}{SW(2}LL2#mJnRLw_9KO)6c z4fjioL6im&luslkvuqhcuzWR62Ld59=~cBZ&xew5oR8&Pj2q!&p`Q--liQE6%8J%zD%BJkG*NFz0eI|u#4HT*FAFBS5 znvBe?Z*;5yhhm*0X6M#Et?c5J=-}h2C^Ykkb0J}Z<_#}St+bA|PQVx&)|g{;B^}R; zNHNhtOq_aclnoQcd~A(9xRVt__4)s3sj=c~VJJtg%F)T;*4WW;Weu#|hz~zWMP+2E zvyp191!0|*6IG@$u{Tc26b z%fqxdNXw(F>Xo8jiE$+-g%}7qwbm4(FOOINzu+#kdnoH(d;Z2Q-rAq(eO4oY#>Swz z>=k2$8G88EsC7}ss|Vwg%F#o4M2xZABl$=XimFWa_X=%Thd?FD+ zVV&-NIMvc{9}f=7D=#;!u}OzTO$K0HnsstoEnbS6tAQvr^D&_)9jLg?%c*+$-+Q$F z%R6LckaRd@2oPv#r^UfI+udCHIsj~+d^boh0ziCg$O4iLN5Qp}GMwb%oX%JI=BSx{rH z;i$go{l!1u4HN1`lrp5G^+JLW;sH6?Dt2#A#kItbX+Bo1HQ!Gt^YCxHGriZ~OCCA` zu&320OFpJ38_Rby9W~kBohkJ&AXvN{CM{+GrYFK}WnFArmS**Oj4ARHMi?%psXa$-W<7`r@a=0HHI)QGi@uXq*6*%>}chB?1i*Qm9u+zApwjCM}%Q(?C_v; zRZUTo@qp~yp87G-%G5fXFm&O$n$y7-E(Ynjwopvb{@v`}4~K{MvU{%$-2)dPl(czs z#j8@KDx;;r2*MgGChFZkI&t_z%2CqwWTC4}`w7Ja5JF|9y^zK&USIS?p}mkUT@H&> z5sFl02tkx1cUTeDsVEJh2*6^BT$s1YjTEM{5x7IG{%+Y?54@O+j?3<5c>FLA8!T=y z=N554*CqL>hn*q3_b4~UCT;%qzdlyN%%%VKdf?vMutvAvo2W|f+@4wseoR`czR@;F zs005=VOwkdv|mkn0%1THc@cT-TZadCQ>|=$(ObKjSPMqkphmr57L2#XCLOMo5ry_6 zYK@iBBwa3YefI~$r0d=O&Z#@P$$Rc#7R3$HT%h$faY<){p}ijDW4U%S9vzFY;c)mU z8_6=&J0DCIFGoBeUO=p|z3sw_NH&tSE(Ze5mB2LyPERZ5k<&bi8bUzJZ ziU}GYR|tV0((y?Z)Tpc0A_Qe4G1m*Mwn3c+3GHnc*+?><7;W9uB`br@qy(cZ_3(TI ztTL^HiC=6W1Yqr!K~mYXx-f8GbczuL=ysXg)&jtuK_d(6w-P6%Js!5sCh#;oc*wNAB`WUy_b{g@g2}-dnjWctdPZ0byugjlr96!jEFzG-# zXU)8X$W1VfMK4I`V87VAo$tI|P7bva))}=hMW;KZ1z5Nc&?et|Kh54A!P%(YUJE9@ z>Vw}q9Nf#4PkO1Ubv;bb`3ZRWYOJK?A&Hs{Q$!h_oK&?AqZDtwJ$7M%$w|cn!aRKC z<%VMqUwx(ND#q&zoG?`D@MVCt2JLv*N0w8R7iN;`tkB2D)jxc>7ByIqP_Q!$_UNcw zd@95QPPPh1aJckSVbtV1@04><#?2273=||(mipuG_q8%}Wsp!r7)si_zTjDntZ_$8 z)>_cY`fY>|P>y(rFFap!(J*H|&4w~LqwQY&Ty6fasx5MaW{30Vj>Pa>Ml4gUrP;YX zZLRrA{dLWf2ms+3&z^ETI;`ds*UhhWk`7P%qL`?lMw=_XEX?lhPibM3L+xZKQRtgr zYd)!7EfaULSWFZ@cOZP8piz#k7vU$ut$)kc&Ig|Yd(93bf5K~WsB6pQ!m~9@(Dr*1 z7aqCvV#AAwv!mYpnf8@0*4IBDKKIM*c$rinPL9)32m}a8avnEUW}5k!ava1I5J+JL zdu96~ed?#0^+oSwR~Td0UrbySVBunj2?l`XvR`JZnChjc!l=Qb28&v3MpR_j3rUsf zlZQof$vY1XaoT9oVy#tw|D&`_^(Q|Z&b@fe4ZkY&!sQT*lcmtgwK(mID=#J$DeT{#QXf45b)KEBp8?nA3yqSdn5xc3fHCqyGI&(3y^ttjF+tAf3kbBb#@S{q zP!DbX^8f%K07*naRF1tGArw&`yKtzV5M6q5JiDxz>Fm^C->|wmr(vDvvm0yebTW2E zZFTNn`s`m%60+=LEsLEiBBT*cRypCQ7^t$ZctVn{mk*y5EdI&2djIq9_TJwSfAVg& zeJFl(H~+`Kef;h34F3Gh2_|S;10u*BFgxnaOtw20$a3J?>tAZmLMs-G211d0CW}I2 zV)L;Sg?6?83s6jz>k_dRL~dN_XLM9)VU4zc5g|xP>)?IXI&P7va_xe9TG>gja`uzn zR&I@r+e`~H*e{K;*-*;LI6s%`wK#o{0l?zZkslFjt;n=1!|@Xe)<#Xn0wOE3^X_E6 zvbfdI{T6dWt{)RX;P`{G(iUu)DYrLlulusn2&0wj@$j(hY=*8R4r71mrK6P>?_d1c z;l|5%z51j#`e48R#?kQIQTEUpZ4Me?bzyJ&^{e8yRJtTf-QO!@spkua3pmG34j3T> zjV0e0d%mlr$~9r=bi2R^8D*0WA01UQSB^V_C+AU;L`h5h9*I9{Tz%{EH{UpqL41sn zx_8m^XSOCzW1lww!2R>=i^3GDF#}D`vkcG z!x|8|c0s~yC`GA_0SE1}1_(v&ip*K~D^EqvrBW4oo`&nJ`-CDdAX-_M-;B>bxlete zAqySUC}Bue#<@N0r=w(zWsh*Y|MB#EVKKJG%nl13}zh$}oK)6Z;sEr6IG)S1T~ zC4`YIjjD`eu1$_Bi0*lDIzF!am{#cIbo}wr;76z958wao-h=nv-08i#+xy;r|Mi3K zCnEaGWBg~CIlzcoFc`DE>W$JZLU<$EWGrmgu3yRiiQf699=zoFi_TY=kCiO6W62YW zoiMa=HL7(u5AdUR#%@`!OG7Y_8D$$a5_)mfzp@cLeI>fM=09~I_|l8D`(UT(x8S?=(5gJA@WVvl2r5m>+oIDdT05RB$Kbf=kEfYieWA(NF6 zrBRjfBjRFG2!WP{Fr1I1A7UP17hVPgQG+obM{PE@U#(n==N5a%{GF#qF)UEl6os@uuqtQ{xeH=Ae(qY!v z=CbEJ5$6Jf$Xyv0U|H$ui5TvbTA0tOvj{^Fky?wyb$sQOsJZOF{RhYGCE8t~-4(ie z)gu&nApr}KcP+?n`?w;aZS^Em^T(Z$`ECk`}n;->0yFIq2nfd?OO+K z$6oXlSl|J6%-wr`F|2QR3!8yfCT?*@RU{0#_4w#sws<*mXRT$XRB5y@sxr%0qH-eL z8Hm<)>A9%A;j7C0+5fRkC^|fsvzSMYc}N^rW#K8my-1ff`QqiU%rxcb;cKIfXMKvm z67ww3-pb2touoZd`NKA0JnkBIe^C{lW3#Q&BdQ^;OA8ZvW0M{uTg~sl5Kvt!KZ{by{Bi=^5Oo@zM~JsoyvQ z${H25GE9+sf=~M*Sr|6g54n$dfK_EMh9IGsAs*n)g&-Ts#*$AcatuEQ(9y~ghGk)m zwn>{Kj6|skLkpKe=Hsx=FvAF}G2n&d-fKeyXwt8|2knLT zY`nvHEUh)e^nOvEcr3BjW}+7d%Qt>$fA75o09g9!pVzc$VzeX;0#}yvnyb9fNlcn`8u*xV>^%Lm)-4y^_3;(}0PKA<^%J6{bu4qYKcpN@PJ|bd zAO7w^Yt09M#Ves75v>ei*pJA`R?a+p|BcawXKO)?K0Fb%ExiSOfV))fc=U{)>aHx5uCSVCZ!AIZ33m7F_#M>xI9wuy`qS?(zBpFEjn< z-7z3!-3ONA_C}zUi5k>TC=bZT-y2L$MKO`f*Wzp>wY0DP<{kj7-Hb({fB3rx&Py^n zsR+YSow~|!Yk+W)kJZA(5Mv}u9n@)1W0awdXKR$B<9n&dRc(P+xyq;NWGj#AObhej zcl!tf^RU%+_x99nEUmGx{?@KL_O}|ChihG4X4;WQIvc^ko#NP=xlzm(7qhZcRQ5fWP!&m zX2JH($V$Z-wZW+agwHI-h;(tGwloR6PG)P>I^V)JlcG$ctB)jctGllUTe+A z1P%7fpw8S4A2m6q$cso_n@@6+ot-zj2>;Gu_2K=z9h3j%m)hT4^Qv5V5k?rsC!)FR zSp(@n-1>z&0Bk&4n-lcsqKr|q{%M4uOcnEpmUeI^Fj0<+u{xuJ*)u>XXk%C%HP$?L z5h=%Ule_e&vtL!Yc9*!ma`A=HC-~~eE0WWe+<6NKTWV29ZK_=C~DH7b7_fCBnrLy zjOP~Cwdee~$fc#-|DgK+?Zf&pO!v?Hnp)WlF9fYsuB4UK%s${g$PeEft=~$v|i{B$%MalDG50q`t_hhmD#+aNY2k z4I~dpK2b`Vg^S_%sG1{9{e-I0bk+g~Tz~52#`w7MLK3x^k#=$_oIm2^QBh1))Z%Gh zo)4wE;lzbXc0Zin{!VY}M`Hju#5mKoi)<~x)j$A1bIq?Udc)o7y#9hQnm_mE$&`7O zr^vPIt5wpt&)|#C#4QZzK-Aj&{0`P(m1afH4FWJrZ>0li)MKq-c$k_Jn-c2^v$}Fh z)>)d+&Ux--S(uq{<#JEw-t9kuiKN(&JeP@^Z0axfNQWDOW)CnwctTMQpn+#_B@lr+Uy zxfQl_T?81c0q<-Ru7p8=D8q4^FI)tjA1qc#i4J2*m z{A+Ww*v75IPbgv7SW6gkZhFFy`+Gh?dDF^Zf)GN4Aul4;=-PQd;E%m40KJ`ON4N{cI~kLR&Vs- z>G;mayWc+OzaH|=gM&YkrMMjYD%!ge#C5mX7rEBjid>6aGaoxb9Q8@qpwxei)(xyJ zH5AGW5HiMUW0kf_TdB=*mtVUWw(2zSuu^uCs_(ou{>~4FlT>Xi`|HczwM#*}!4N{$ zT1ruGAdgPPI8{FNwRqh#vfd_11qK?ff@#`|IN1OLFk^q!&dER!$Yd;71fJXkjKj z;o^HD*Ue?mk0_0BbJaJ>mZ_{#S7kCVi1OO zAk%>`+T;_(JZubj0bxFNgg#Xnt<1D9imAHrT+Q8AZVa1ixJFy-93MeUx8I-K_~};C z<*urn1=!h}UHR+ySS($M7{`bA(z*3!9wBrV&HLXSJ^JBz=dDS5JvjNyF|zw&=Ao!Y zZhgH27W(%K*FcX6Vl{mBK(|I)XFcFP4jT+%K*V`dXUzgyn7ps%*RQGJDP9nf}gm#LEEEy8D{9Ezqgc))aY1Xid}6P#wZ^ut!zF~af`VWj~7z6 zI9++U5jJQxl3|Snb(W8%R)%rRLvr)0ZR+83Z|F=Km!+l*0|M&d#)?ll@>>KGwDC-h z2ee4_t#5SthvH~gc5jApo8SCe`}koVH~GS5I6khFG_G88PRw<7M8_S=hf)edIR=En zI(z4jPyCoNAAj*zSJJ-lLP|MK2ePs34-YCWEkei|OBg~J4fcyNRqpaBX__lOVaOV2 zE_<#EGl;1wOy@$NE4%q}gEBnWFT0zeD6~^84?fOhsgED#^C<^oBnrKJHS$6t%G7^q zSjkVFoz|8{0FW*Ip#7C?YmHFpG(Q+l9}K7WN7>dS-^;3FA*V`L&wS&W)Wz!6H6D=n z{>_OO5KsJE7`0pi(W?oOYc~niZbA9SPKq}?L`!07j8w4 z*-SYm3v8ro%L{hQe^|lJd%zi z!hi^(3?^>s3QQt7&S;AB;mTdkk!J6NvFE|#{pRxgsqYJ5Fa(! zU?*!RsT!a6VBV{Q2pHXKS+5Mp-SaU58oaS53AEhh1<I-|u>eO8G7Dghb$7BC5iND^ zQ2_vco3>U1#&J53qBKf4#-s{s3{#Z$1?AZFo)CsyxG8E-!Z8m?RcgwR+tnkCWM!;N zdE`1iJA?p)%2b`N1zflkirgHQ=H%R{RsjM4jw}FF2&v04#wbYG`Nlw_tdOqQ-hmp)h5+E7lEG-am1Smt9tp;f9z$CWDy?QP|h zk7bz5{65yg=%}KcEOz)JKh+4~`$^7hk9of<&puC)LWe zIH*woi!n0F$WqTksq43rGej5OyE6@H)C=j_jU?*umFw{sP(^XK#ec<{-Rf1Yd)so_ zKkr$d-FuBCZ~hLAkHvfi_hafug!{xAXm{vfs*sw z43x@dH+iz)P5W}VR{}s|-TNDFPUll=uLqM8VYHp!Jv_#rPE;9DnMqHa_XN3}81qol z;ZCdv3(ih8<5yx7%pYq8C`U6!wFPTtQMhSeG!Ov52DWWwB4t>v>j7Sz$mNlEKEyXm zrKHIT3Y%04UFMn);<2SPUwKlMm7YB0S!&K_x9dB@Lx>XD_U;{(%J_GXByGwM*%=5C1>rE$OMv@fig zS-`BB`KkaQYA|bUebK`h8*PmRS4B-YFb^+n`pqtJqdowvT#sdCM#q&Z^~uBBC`%}M z!WbLWC?VJhWOKdFTF}xUjAnXJsa0v>Hp6(v+B-j8{MeMYER7PToT}kri81WG)dB>F zU;sN!-zM<~29*H77A1f7HL@~ztfpP*AN{}#rw;~`dzBdF)oCTC&s_X908sv@_PO54 z==P(d?`W&~lTQx%ugCtPm9<%U*Hp>MRJoF3wv}!yd)&ufNY5XeeSd0xRN4CyqDo6? zOJRgGNkrC{{3IfoG?mkao|YyAoujl{8As;Klh^I-nj8h_yg{WV8+HlyXcN zvIexa%qN&*_gHpT41`g8J#faC5B{JM6Jz|TP}5=UFP#Av5U|P1SJ&@21wc1ynZ~ent-ha0?`7a;+!P8dNoLz=8bTsS`=CfGe2k5(&j^1<=UOqQ4d$ScKjmu z-B>`G1WZ6UOl5q|(AT2xUH2N?6K}7ZV;3gwfHx z%sp7`?41EX0M;S|t&2VY)K++F-S2OeKVevgWR1J*PdU}okv`d#$Gg(8QH=p(z-Svc znJd6WfPicUi`X~x*tX;YqIjMT{xmvC31qli3 ztjv^qsy_VT=z~A$xgDuH?>cK!fvCx9EB@lOFdaylYaWtpC|v}Sas&ur0tllrRh{)< z`@OLjk+V2qkPW5FzPig-OcWu=3(3h=o{tnFP^B7EL<3AHVj*s?2SyoD>MGZmp}5VJ zFjc0`7hxa-2*c**>h4zFzq|kZ-~Z&N|M8tqZ;(O&@E3cHjfW_j`=>-HM$`OYoIM(6 z+j)7?O0HmvmCCCLp&Va&so~ei1@WJ+G=K5>-@OX}t<9;{fDk0tB>)&Q_Chi|C>x6& z#)yX);aRyuF;TUy=PD#Hnbpm@^=$k72|}p3>?dt@a5t5u(b5*Frrag?P>`^}LFp`! zRc0thZf-cbp8*ESu`>;oQ#I?gMQD6fF%KJK-O3j>m^;awn?$6_$JzE`^H~76_|-ll zV8(I##uO9$>O&t>jNvNA$az^Qfp(w6<}8uQ0Uz?wE&!`y_0z&V}&c{89rDnx0fin_qmP?t<|MqjIW) z8r9O&mpnIZxQ(=1M^AT(<) zHk7SZ-#xQ3W({DB_U}x?gc@UwwmiTNka6#|QBY@?px6H80RZ9w zDJF_?geh9Q6l4RzLqZ5%zg0sRIp#$%QPzTUDj|fV?K>&i3y4wn!n3uw#UH&hc2kHK zky_Uih0e#ykLcFh<6^3ujPlyQJaij)SMd(kIwCUluygRmEw*qm5Tz-n5)%~GnYDJ> z6HonAGaU$5TwCjK>fzmwCbH14{^p)2bll>d&9E5gph@PZPhpELY=-w<8+JECk!j}P zqkFm0){BTA5rmM#Kxkz#M(fYiyoem$ODV_4_cJ#W?|qb73nyDSA&#|g0l-U0(qVw0 z_b7K=+O8BlZZXO*rr44D94=&D_g0K$)LzIiqK=A003Y> z0I+r=&c@OOk*u{YXyz{8+S7@WGycvKC&WA?7=x;ek|u7k&V}H!OR;kbBMi&eA^;fd zm0FrIHSLQu?aO>D-Q%lFb<&~DWxvWbLU8HD+mT&#u&!Wg+y-FfacpQvmkv#~@7F^*5S3u}OS_=7*~5sDTrM~8RQ z_Nwp2baE;XhDlF6{k8UVAY76wYSOSyl{9Z!w4ZA?DN>3$O(ultH0kw=AtA^D{MFt3 zt_Doe;Gjeptg)gnNB8pj0(WnSTgc{ka`zZ_K4>LObH!&IPd-h(BoxWgsM7jP9Iuj~ zO=iR>1X^1ytrDia?iXX_)KYiYUSHr|gxz%ER5K-P_d*B&r`vh|k-mgZX#fBq07*na zRB}y-j#@=1TD%k%Q)RRbT~feW!f^Xcw4xl%-{HACPgOHEO4MY|^;TOZFaAo)Wt`{R z=K6xiV=|9C9FD9bxSvk~ibB_xA8$_D7wHpyl=Fz+&7Wz%_eUcDSh(x~Kz~a;Aqf6$ zUgz7y{zeCu`@I~?Y(AXiV^vIKbHz`GV*gH>kJZH&>*sN$OIIQ%ZJ&29%F4to=5WzU znXtx~hr>E;EPF+&Cx`mW|LKA(truZ;*NuJB?45VdUP7^B4AmCAs6pKmskPy=0AmDN*psdN!gDo5ARCIP#ipmi zm3+q)sRqai=GI^GQF3*_|whJHD7%^WvSvqJ7LZ}HXQ>C z0H}{KL7nx-Eomz^XII(l2wC8tq+|gAtx1wd#FaJ1C@rN_N@)ijP)e(_2;q64yPo$F z&JbFFjq_f~Ts!a8*})HDKAyRv{uVbW3rSF;+{gJux?gSm^NAbRpD+f>!gM#oHAT7+rN^eH^b9F+biIfR4T~6fnN;SqZ zzn9)Wsy>piEi8|T>x0Wj3gO3ee|MPeDDTY`uet8IzAX2<bA4xNvsUGI_WTk(eSX8mC@2DX=k6ZHGl3N!Wg+`Mub3Rm!==H&-ks{pLQ-IPGfDvOkM};=kuFdfL9V;tC$ZUIsDGF-TXj`WG*>7~te-ngJeaU+w>+Qzfe5!_rWqEo%G&j<| zzyuu31OP~FC%87`Yo8!`;!>9Gwfp_0*-cXQ`qO*E>HTrOomai}?kgmK$s-Lt+6=w+mTlQ5XQ5Pn0Z8cRd&$R6M}v(TV}Unl#I$o@Od5bSY_A0$K58oemQ(<)0fIhY0F9!tMr}Z}KZ|^BY^y>d2ZIlkVX7wZp+%qjZY|2QmI? zBf2mx_QTH~i0!s9x)h_M!H*su{@az{E8<`O_t6jj*~;E;)VKck!*`w?Jlv>GpEl*? znR?UWBG++?xg?fz6cL79(Vx4)@{ww+da^Xu*rltX8-en%RPwP|)#0|??cqnHN|h|s z=%`Y{x-F^~lEZtcwXpGQ%>{vf%mmwD*gXqQ9%h$cYETcSBS|@C0l^fVZWqmE-zZBM z*1{5o&Lt_VwZMGhat8<@K+xU{95rctRDJe`t=x(l8(v=MtFJT(MX&z$-ms_h>8Bir zMq8_Gf46k9OL{7ujlv=HWudc?T)Z4=Yll5umG;UP8VEseD@O>@zHrNrACkM@A7F$Y z{?+*KPU<3{TG=YslfGEJnEu61}i5SXGL{o#>w#MC;R z2V{CG8jD_)>DFpcriuqdN&Cj{9r1uDVe(V8a6LS}mjS@?Q}MJfd4NwJ6)s^HG???3 zZ9G$B0ej&hzZ}Wp>mYH(BRG z*xxIG09c6I922y1EoL4m#!_o{j1ZKWYOe==M2;V3-OZr3!27!eARq*T1*5>7&r^<- zFnb?Qt(igoy^s)w7N3fkk1Zfk7yz{QQRN??qZDz{)!XPWg;DMrD{16k_jD-q6riD+NHf9dqjbL8T~ z?xi8ZKz(uZm-l4+Z?69A?zAtqKbQnHhR#~3Wo5v?_@ts9KHVuWMXIvv&m`lMiuo85 zwDqHLm20rTeY|^nN*F3LRi>)F>N`h?(^8c*K|;sJ)wC}N#|WVd&(-pQ!~`v0iz!9S z!-OK2Sl<0;>T=iCLeyZCW23FDJe4=re!e)}^V zI4Irch5PvK4+fYZKc?2&D%Fi;|D(U`FI)zNnTL}FubArQ zvTv-t__=yx$wSEAdA08+WdCl;15%9T-iK3{FxvTG^2rZ}U@i5?>)$@K#$pVZpfb~M z{{E3$N1a46Z(ehD5|@Jm1V8%2BWrBd$0)2C8#xb1F;)HjLQA{+RAjXEB04^)jJA&p zJ?(5P&IU59)40hHLYN>gqWd3BAH6%C^n`21nMJogPT%;wqpHxizTVkCr@gDMGw1LZH@3e?&MCJcJBi7Fb~M_!^gw1%bqyW)*R{G zS`DZ{_Jg8Vk4oyywIV z%1}O5*+?#24AY^ka!nboGVR4=?Pfwf3;>!~=+0I6={r+UISI+kdm}0H0 zEOj=LBG+-7vmFbf+wC`oH}7`tY!{W|ltaZ>jZLi5C&0 zjXRlV>>HGu=I%Du>GC! zY&=`ryO}V-0ATy&h8J?-GcUy6g;13i`6F)N(#23p1^^B$Te|WT%3hh;&;5FD0sVaX zL^P}m*NtEJLg0mu#2Sm>*Z-fF@Y!ejwLbwL7m2y{<))+gI1AYIXKKwA|K|4xsxZaW zFu~H1>RkxuJv;!^+TP;-&fiTL@OnoEbv`;Mtfh~CFmTc4AAR=}0Gd7DuW`qzsS4|q z0ab3C7gE%cjKTiRq|8ibGw5!Ge#EQH6k}cMNiLW!Ef+ZN`iP*l8X!V4P;1ZBRB8Q) zlOYi?7g!#(r1R5g^t|C-+1rX3!#vT*u*!`e@zV#n^jJ_6lj91{h={}M6%SF>l{R)`OoL|0S_m8BoPN+Dwz{(Qt{fkiy$j*u-c+Rp0zjCY zROfJnDl?0$mNGSsieW{$N#}mv{jz;jWQDyy*25+LhJw_P*5u?o zMPka_AX}7r&ER+$aK^FL^}LWf&}w{C4i8Eq0GvS&Rc_K#?I?kM#L3dh?X0%sF@{At zGq88w*j!?f%sg)DJz1o>Otl~L$w`SETPwccY;;(`^tDHO`M7ra{?~5(i!JAtdmgH; zf9QM7{r;Q2*96Oxhc5%r>Xk?<8~3CmPBxeQA~DtyIDD!wZf`bvo~o=nTJx!{_x$00 zG0U-?8dX|%<;^qEkf95pw;H^N@4xYsoWbT-cF!l0nNpkC*5KRwv-ejvgm@GNSE*z$ z`9zrv@zDwiHdQ14y59G)eMN`OX7z&E?~q=e%lbw~WoI++B7qFKKpAptC><+jOxZXy zPpk^-JnRv{U88xTCnuF(t=-=BPvm4lxBG7W0^L+O}$?wMcMeofR5 zgvUk)g&PrBLtw$#%LENkW;$$$Mce)@Mj_CEV*z-1E2u?mKQ%Y^%DuzV8q(V4rPYRr zAn;i|=KY~A6{Wc;E6PinB!&p`(iVj+E2|AzOPnD?0E9T?QOGQTR#YjQ7G^NgNoJHL zZRj$i&vPm>Q)b3x96Rmp=%|zdBMVM2+g$OzNQ{q5WB|XDoIxe$hYqWzdNfkc#! zX6~iHk9p$(3qElc97fxE^0i7OhvLt(v8u#R*ScT2xcT+?#lM)04<_uk(rLSX_4)0; zQS(=n$wtY&e*e?)Uca;RcWNK}7tg4FcxC#Js!x6`4qgjuf_u!-70b-b?qUR080S5L z0Lf`p?|G^)K|^rKCdZW%O|M*ufSyACU%ng_i8;QX*E${-s0-^nc3nN=1uPw^cmC+; zN!R(_cF2$c;~3Q4yc%8JoEI>%fC8-{XTE?80B}C4BI|5oXIX}TfPl`zdF|QS_^^6% z^I!UM`{Yj1-0*5WPgi#7LKuV?MA+=|rS%z$(rPk>ru`BCe)zxdWzM^oK=_OdX+_d! z^{zL(r#j1g^98@N5po~*ZYIu>d>+lP`9j?-(x5Gn&&=}&JNa{8?;35rfFIq>$P!~H zLxv2i!d8Xde6H?A+$bV~GBNI1$8G64XD+eI%;cnu+mZ;vhIr-ImZd*yW?uT$-pQ?; zacnGkNxu>v-@Q5QZU)&%yW0@}YHbc6{^PqY{CbflAkTDcs#5CJz; zb}_LIFL$;YK(p|O)|!8GC-ozKd^hzYo=^sph5zM7m? zaZ_>+YaKa0E}200a8|FxgWZBGagXiYoId-t4k9`s7~@c7+KZSAC5akx+OKAzkRGmH zi-VfzYzEVQ#Sn;~yA`U!?7p{oMzd1Q?IT1hn9sU*tK9tjf4Re3=P@iPqR{VN_|}7T zGDwTV)7uS5e;GNd)GyUo>CC(F?H9hi@7l2X>RxSWXbr7gjh&OU6M;*gktJ1_BGriK zM?6oo^F$MZjgQKpF8r7S1L?EgcIZW1l~zdR(o%wkM1-g*%hWKzhWiEgkO@qNN(KlB zy$j*#ZeHcaX%e0El?bM%mAfX(Oj~24rr;dYk)lGzZ5}Q68_&<~q|VPC!?o{miTB@| z5T4fB(i)1}vVMBF;-5}Z(;uqSq54tN_d@=qWhodkhJs_GCVUTlk2%36W9ae+XNJK5 zd#6=9V(+D9Kbc7^>s{~o-fTf4Le!FzlhRbiEotGgn}0d*W1dYkGPwWVxYm*`<5CFR zyD<$LV)vuz(cR1sdED}%ro8!sfhz3Y&FRjKX>--Da{d0F9$O3bo;-b6Ja~W15LIru z$7XJ$0AvXnI-`gAT<7FLzVTemD2kf0$_@880x+p-TLUlTM$!0ark!y@1L3jd%Ml>_ z@c-C{#SR!?bX1UqGIz1)7{okodk&|t3;ghU$GiBsMsvmYBR)JR5uw)cmM_O#vej#~ z$#IDc!kW1G{l5Du$HcC3!v!*iQA3{G&z&rE=c8$3$=AxRJyUZfpdWMLGsZzkMuy7N zT>VlDnG-ZIUC|rAf6#J?t{lCHfAqcn?v13F8nPrLs|xFEu=_hXW5@+&BNex$3>afL zw|OQaRhc_)j9fB+oBlC|scUQrD;Y8(dicQv z5t}Ri#`87dGw!jE|MjqQ$seAzJ1~DX$+y=6 zvUKAw`YsbqhRm;VM_7{qGn!Vedr?C$j>2QABp_J66gyXS_f(N#KGlq4ts{YfDs6Ww zkO3<*%OwM%A~B1`-fnxU(%Q39%vutHSwmjPtJEMvGSs~gHkUmjSifHLLLN3mXFW^@ zs<$0Z`&Bkpe$4N^Gur<+aoYc&CbEeJfPBgS(W$z#TdsDbC-K=UQ5>-su0)f>WQARA z%b#rvvgDY0y0X)L<=Sk=Lpi=%&i%`0jg6w2qUWquGYgy@qsa@{e3E}|L|-I2pK2}` zV~;QbSM6}Y8cQA*_|rc>nL#QYi41gUPwuF51gNMXtHPv1#W)&G2e;BP)ytP>0W!;% zqbDu-$4Av8DD^yTfPzjf*11PLfEAr3rDe^eeG+_r^fs(MpAy3vD%fNX}$BE z)9xkVK4H$f3LAVOyYR19X`Ndz=d!Mz{L7UqQ8rfDSuAFMH_u1f zpDGz}H|IaOpG8dx0NF&#m>;KRjxR?Ik)4?AP&d|uTa!V|=UAsWQ^O4<9^`f`@S%bG zlD&DVvE{`ccAN6*y8q=%VWr{XNpV3U5C}H{_YeTGsru-EV;92t=dYMjN5u_Ckb90>2#K7dc%?b$3)T z1YO$JTJYEjT-cz-Pafo4B3VlM%4jMw<3zaGSVt{sH8~A(HnsIt&!Jk`R3ir$`Kq;z z+mbA`*8O~9tg-H%joUMeOfTdv?irym-n%mXE-~^=b3os*&(C;47p4IGWj4;phot;&q6Nwl)a5CN*p%#XgXE*#qc0h~;d z$O-d7`WzW-yjaghsz^+kYHMh?U+T&dkx_&Uy^t;D47y_5x%W8bP*{Hy)mJ3CNVPkV zxnM53$5eLX`TEJijldYjZ5g+v3*20!Wx>qe7g_Ty6vqzL8tv7XV3XrgpMH_BL~*M62r5O| z&~aZm=*lTVjGe(=mPl#HOOshhGV?)SzjdsRGy8CA+{n<`DOgKYZggcQCsjVx4(+`3 zYHMyg;DwxV9L{`oTAYPyT*%<3B|XT)IJs6~pC~ z_A6JO{i+{vhU}pF{{H4~^YG(-@4q=}{iDPBzd9Vevvd5zz5ZXFjBiZx-GlyHyC*-s zv;QY|5C8R@z5o0E(f2~LQ4g*%56etzWo5v!v8pnQt|dVXYQj;aMmwb!ak8^UZ7%6; zEO}4A&lTqm4Os>)kg-@BhKc`YW*)vExtA8(^)y5Sz;QF>~}QWO(~~ z!)8x3yCR5~>$`x!Xls;hEc=XOk!YP009XPcvC7Q-H^-aL*FXAyPwQ>&*Lc{L0EC2& znEj}@LAdh8*1fmKGhZ!4qp8ZRs%+R02w*L_Fe6=AFW^MvQaM^{KI5n>t4hN-08kKf z8SpYU=}?UhOX0JlyO|#gRT`CBAgFSa4s~2@0c&pf z^`2)mAp;q*?pEl^%GGCL2Yg(3xgi2J9jIB^C(%?yhSJlje=na?F|&!*l|_Ic7S26= z_h#aSJn2_lqRR{OBCacHtp?N6(v1hNeyO!`DM|)aW62vIS6;~5Ye6z{8v&O%GdSdU^ZR{t+ItOtEZS>6ml%Ycar8niL!ON^B6-Jx&1FLJp1j3v(j+obmNtKM$`SDTxu+N$nfLW2f{Bvvq0+Xj?A@tJmHi)Y=EsU2{&dPX*4omK_|e@I5&RmD zTe8Z{+O^vBR5=!mwKEcOtu2MeMu#ObOh@YDAN1YiC!gxLDVMfGRoS2X{(d%A#Z*_h zNd~I76#)P;h8+Ev1LCw_ogK2oB^H@>iWnk5_E><6(*-kz-3uWRaKRXYG32)rXLntk zB@Z^2eK#s`y|Ewhxyz61d%0xUNV}#EIYtek)GX0?aoD(gDe7&9dpDELMxYAoTyLt} zgmpeSDZ@HHzL&l7Ys-F(GX?;dj#Rzp8D*QxJ^-#p zkN77)9MpS00UX{*^Qn#+f@p?8>(bVH-syuJ0K%GRF8f6E>{mNQVpM6%%&c6AqNdQ5 zz4OMP|8ekM<6O90^ zRX-c+@kv=E+9e+?UyO>W{)_)*r?nC=KEqtT@S7{gALjrdYpk;wG**<#H4?1R$(ljmgr{-L!WhG}>AsYe`quT5zp`Yw}G-wYCsGGlr7B z0t7IG0NF@!fnLau?`F=u^)a6OvWJMeqAD}nFE`XYG>6>%#CZS!AOJ~3K~#WytiI%F zZMn}xfVH-ljT8`UK3^Xll|fC!Z5h->(*I05>ei~CjTMoT`++kbeB!ny>9NVtBM7X! z5m-wA=OtiX#1?@Gq8V`J{>56)bDJ(|2ml!DmGeNQT1S?-C4wr~e#D)AWNv8X8VqY_ z>!rr%sPrN}Ijzdfz$}gh&isRC=y=o;t+gN> z@R;zK@K~7|#&L37amna$8v(7XYyTL>-i45H92^w+)C4uI73tFEiAhIl|C7WK#fOJQ zbJ<4@s@Kz%0@1YmsD;#n?aQsqir$O^PD~hzMwOnoY&$6Rc@#KYQaE+j_>E6ygqnJ@y(!2 z3>O$SMLJUR1aw63W04H1_3O2Ctme!q;W4sw`UJnPvn}d9&soKR^;a-6_OND0aDZoLMSzTF2 zr1~s6Ros%Qu*I03eR^==Q)}6{EePPfKRGF;`oRa2s3pCS?S4FU zc0ad%G9(L~&0u;`mS>MT?noK%Y^=}u4RenBpCrPGXQ#$#MWv63kPgiH^EDTR5jI3? zEqM0lI(cH;m2~H?Mu^A-+y6M#6%j!)tW<8R+;{N$keTK7LoLb&!~Twjs^&|LE!OS(+86D0s*XETryeGO^uG1jn&{`;Z{fx@iH}j#8qMY_g3-r@9g}~fA7=ZdG_SH zUA@}@fGFrSqK%Euk0v)h!`&tx+q8LxTucDK*s>m893NG}=j~PBk9d1Ma1jAfOAwJR zEdmy);Q|kDr@~{Sqf+_|5v(C+C3Yt8w?U%sVeI%hg=!VB{Q0)eWjJ<0*gdD&b!q#IVyE!o!@BgDCD_u@4NE|bEXQ9 zO;cPBa%snB709n%4zD!DYim9LWFwtVwEMwaw`DXDkr%MVtE#;b2#<9(gLBqe=B&Ff zb2BI4*!+d|$NydN!GB<Oq3n5=;XCQp2IwjK8SZ&WJXgl}bc zH|+E!r+TxB%G@|w$?DZwI#e!#a8?eTMTJ^T?4-PuDlgRtFiCV?*t9f4A|hx_NoLaA zc!E{hYE4OM^1_ytEh{PuqcpiHdiSW(nv4MgFve<4Qew9y7z46Ul;*Ic`-(mt>+c^| z_p`@%+`6>R+(UYdaR_SS(ifUR#D;rCbH#V?C2}M~&1K&W)Qz#yXTn2ksVZ!8&_igL zemG7aoH;Lzo)#uz4l|Ti`D7}^=q#?yvbbz`B)omT><8WjEK0vGPllq zzDTu0LYz*2W{3K84_2ymy?mmi&$5XYJ{E~~Ov8H58|)SJrxgsXwZK|pZV2N?TzJeV z8tfG^U<6R*CTa*7Fl4AJA`8eLMGR~_Uq8H)&PIFq=y2Y6q0R+6xplq*yZq&rkSyp5 zhvTG=2XJ};vxck%qiA?ghBYpImQM{aB1=wb^4`BZx%8#x#&fkQvCg|UtaDXZKu87( z&Z0o9rPhi+J}UVc1)VIBp}}sxaycqf<3)V;qr{K67jhS}t}9z48X1HQL52uikAy~% z7YP99KP-}gI=Gz<_X|W|43Oi44<;_5xxbsg_{+U}Z;v-#@*R;oZVARfSLE`QIm78u zwSK+kMSTC`Bx=Z@#*=}%^0ihz(S9sW9^^^CiktGmdlSdy;haf{$*xNF)%>8bhL$f! zWon|PWPHZNaij9B7wUe*lR*{M1u_^O6v?1MhEY=v4@)MPAM?Rpv2rB_Bxh)doit2ypr^uX4l0EKEQvQiVYdOyF?86#neOKDnQ*UW<&eqr)=p z$b710!1g~*8All~l^d5r;2xk-R{Bi(T;)diYDD_ldT>6$@6#J~3vTho*@B6XflKE_9^=ix|HrE0nS?@v=`iuaS zrjOR5upuu^D{aUaA`8aS&T*y9jEmp#4eJB88YxI~WKt*}VV zl`po6)R2K%*Bc#_$*9`Dm8@Kjk-^*FIdsf+2V?p1%m9T+HasYUSnS_S2K$Ax0%14< z`&w&3ts`Z~`aAi}@AnaLdRk3SDtG=mTxoPro<7LuhmH&BIG2mm-z}1Ub@Cv4|Nl9r zGi|IjlucARoN=V*9<&I=1x5>``gt6uGlG=?LxAf)+jhc@#gq!yD+-Sd4+;dR3Zp8E z47Xot7)51j_HU)*qmnTkAC*o@>_walOvn1izq>CyCVh7JY3fJ3NcC{P@B;3VV%)lF zuLst^(WjXgGS^IAc&Tx8H`A5nf*DQStq>7{8rRCI(##TM5Euii>D@m*c4cBZQbv=t zR23#{id#P!_AW$as)fgH{b=Z@0YNmA2RhCLV`#KpM6ejc(P3HTR{FD?;J77pWy6|q zY@^1CuW}Q&r7CS}#qVte`9uQ;F4+s;=()uf*5!luC!AwvGmIJ%5g12(=98_J-F&{z z1rw_8rueN^r=ckvx(#VGD^iZE3>aYI2bs`FDeDnEwI#%s< zzsfB#Fp8wl8OJKOT(YH0(MNyTcTVlrP?0#x20ZfvCbIPIpPtmaG9PPa_`(D3#w~7a z7}N!FRHc;x=aQW~%ozu#xqE~KtOu$xh_L@jLIBC|v72amTDcUP-gd+|sM4-quPt4Q zqPozfnX7|8tLttq`)<&b49cL!kwKB2@56`t#mW6_(Z|Oa7cpVGk2_V>dt&KgxEQ(O zwuTd-7;W3@fsl-GW-Ubx?og`6k|%wpa^rHEnk&A`S3Ua$H5d5ISKCZrbIAh>M%%`0 zs{#=@Z%TKbCw=9{20@Kix#1kgM@85aUc}}uuhtNN(>7L7Qy6WdmhfZFIE;@9#xbAj zs40YCW+5NSYO>1e%5FScb1QaySQb+Sh>e~H2ul}3FW|R+JnU|TaZ4trs=elO&T1X6 znCLvwiySCqXtZ_iLc{%Hl|xk7Tf603pXPzbe2@7abGKWoCVu&H_>4=cDP$b?+QMYtb+( zYKq0cfu}mVJ2K!?zlFmZF1%QOjNSi*rsGq%y_t=a6HYpVIRJF0R)6(alyJ^U2PxN+vKJR;|^5h>(HnRYr$JQ0GKI2xK9j zYA+JjP~7pnh|MDf@}XI|7&4BgwC+hp4apFkzGHM)I<}_c4Y@ahF)XIW=G0jc++#%0 zxfB$s&H9=%jN8&d)zee;@SVb$v?50$Vgj|YWJn{Zrng&{VcW~w-di6|-?@?8dRYAQ z2mRMS&JHGebXewRXuI?osjj(#7MZV->9k?z5mFM9kbD<{_L>D%PK` z4G&6fDXd8$F&n9TqOB$epa8=svogp+P~!);(~akAbJsJ+c8Oc^scu`&m3i@sNi7_m zu@P%TN}bnQ`W|c6g;MljC)Wr0a@TwIaTc?goK|zJuqsS8R$5tSpX$Ju*+vs6 z1J>H^KlYP!(~U2^?S>hxi|Lcdl(=}n>K_6Cis@eq&0}1tAv2~lrn1(g#c_Z7$s~IS z0A856GLmr&VvY3Icj^vV+nOPF}i6L+N*vtP;vV_*5H^#?b@$)`v3KX!9OkE`3-&ebCbWiq;=Yt z{}a!*0DuLb0zk+9(%d3>&cdV0f86{&nVF6)Oo`6?YP@lJcbXs4uyHy6?akqD1AsQx zrCKEeg&Y9EwXTcfG~duxs_MD1ma@Vg^;MSJF#&L94Jl2N)RdK-W>y=j6jh3*nbyVu zShiH;nl&jfFU-UJLOJy!qBf*85n!_}q+r5QtnD+U2>|HvGSY#nWojI%U=1{u{N7eL z?W^%|=^WForDCeArg~3CO_@z}nV7IHoZ)Z(?iL=uY)&>6q=EHM(9t)vC1CkQ>#{iQdIjKWTu42+d{R8e&A?M_l-b3@4|RH6$c6$~tp+=`*9P zsjR9jcX1Lfc;3nuN!!rf5~RHvC%GLj-4I>7YJmeHXXos zUu7fB1qz>KV_jy(rCf7?t!2Nr6{>P(a|;B{M0P$hsLP3i0Bo&9lM^dEHao}=oR)s$bC1g3psScbAXtC-baK#YUQF-(-sY!2k*x6m01%nd znHyHT^f$!x{;#wyHa5PQ*SGF*fsDiWv_DCAybCw#FMQ8b1_6vB#!=-K86ZPMxcEvF z5jz_J5gBE5X{E>fh?BK*ee1&yCqc|PXK(%CVWa0amOVcfw|_Elbh#?GaYG=24Ef=m ztal+qM8-fVI)e)t6Eg$2=Bh7!rWLssR29|_Ia%TY(xK{Yg@^zIlcUzGc7Ner1PHfI zE`HrOHEvkvmF@d6j~c>ZaMQx>9F_O>%m4HBkz2P*O`$be0%OS-dhc#FNsP5%3=x5~ za5OcZq2J%Dez&iG=k?JEpest|6}c)+)Dqo|VEuYc`b-9lb6mL+`!QFAt#>@>^V0{p z(KI|L9bs5_Y;s)IyK-_;MJ?$lOVVfTEX-(pSj264`Y@j>)S{+nF8dc=YMiGGY=$o4 ziZLitGcU*-O&}YqrR~U3)5}b|F%IMCT-fISvMY3IUC*4w*t=@meGV5GHpJ+#sB(Mx zXPU$P5*`l#cCW!+;p|9tN!d_2mZD23Z7liwpCm8*V$X}&+uu0?M6GO4&HW6s0#b>>jQUdwpIhj`*1eQRbi09$FC3EwOZxo_Kyd`V=~}nYVQ2i z=*IW^*IsKM-bq{{Ow<%XT@bFKR6UVA_JqTvlY5_w7KkafmLCv+&HOwnd&*-RPPA@X!LxBFg>l1Lz$YN ze)n`f2IL&)IY-X;rn%xX!N>wI80?isS(V%Rna4IFs=~~U2#@7c<7lnOu*@tXobKd| zV^HJw-pD3rvpB7YOQtnBpfDRd&v;fO+KXn1E6#MRw;c+f5kRf$X=UB&anAZpm??k22%d7y^tELj+$6@Zs5%m@x#z#*)uCh7B>F9?w(o zoE^+L?-=f}IU>V8)2wMWne-zL2o4sU@7K;oaCA3Qh4BJbO!Ul7m_S$d(;ubh?8*ID zIFAfh=>~OC?|GfA@b25Aq_6y#AKXrzxgG#q{9J73a#*!D-`TcjN_1^hTe)01+pR0fR=J?!5<4Jpq zIr{b_scrpwZSZ*SWDNzefQ9g^GBfoh&;51)&|33VVdpxyupxkGbXd4SuEV%juf}tR zS7$SvoRqpWcitSWUyp^v+dmmT`?b#aqy!?P$Psmg#~!>tal0U!XluxkD6OI9iXXS7 zJF8thMRVCV%5sTw?3Ho!LuNEpnQgB4(sSmdR%hI)kV5SOF zqy}+T`q#S>5LIOzLuxv*z01*D98CmKOH59cF0HO8pJ-$-J*_;S0YEaS{2I50m;g7C z=v@dqTfu{O(_~_&eG@h%S+d3+-z|kQhLuOk51>d{8J@>OqoQnk0( z;0`_MjkQR{O7|kKHSv}cd!`wjNeJ}}$#O4>jsZYTAM38ypRL_}b3_DHZt{t?8rmCy zUlZ}Nbbsm_Uh|?~-||GnI-7wI_}njcbYWU+ffw+DpC*SNrl0;`G(N0!VSC%rlNGx) zu=C;68N)4YNA4t%0aulsd)q(Gz=LUUKPe^B+JC~E{NTa_E$Tf2LP8v zg@D$Y;fHGXpZw>Y`ZWM}c>IHUw7!U3oO48Suha2I`M5Hg@Aj0mA=`3s{)o#Cs zP2mn4UD~K2^QkU#GuSUy&gjg#vaVHbt_Fj>LU_zg2iKp8rN`o?sILy^yq@MOS?BXV zh?>$G;u32shfhi!dFRd9d+{_5(VWBe%x|4wTs`?qxrir+^~_E%oJFkc-AufQ6M@UU zEvLG<<+ay+qsZu)245A{<-Qq1R#R1)T3e3@ ztp`y{x(Xy6K6Z4Iffv8gJNaSl;K5Hnx%(Xeh(<4MbYDA;{|o@s2M897JG%7blq)QVuh4XZdS`q^vx$Br5RuGn%+;&$-1tuh zJUH{CD5l!sTvh7g!lkuD1oz*aJo&!QVw#)_kI`TaJ^XMYedZjaq|d6tGLF@({v)#B zLUu2_)Q}-}XR$8r;9>FL?aA)j)3s+~;j_htVMe~aUgI9?@8*t_;m6{^o0F$kNV!?M z5bDZSscEcu!e@@KJvk|tE`{y&zzvzBrbq`$_{=3-0OB0Ly7Yw>mu#?GAV(QW44|5ln! zR9F{PZn(#s9dGqCS-38&40(}gWXJ?CL{~buR(zL!a=M$5CE=mfH0@Uezy;RYGOUZ? zLAkUYInsD@)px1qK%jCf1AhOk2#edE(KOg8oS#&^=aHq+VX?Fw8co6%R*47is(Y{3 z*!|bM!=E|)vnx0MujQQ|w^b6B3F~cz!o$|;qjPQfxf90l_@k(`H9Ee*x>pj`P1~Cj zchD1A$-}^FvDn1xua^^Q=CAVier zMBs=9T2a)Na}A42J#bMkfEc#~AY@}@4G4)^5f{uT3kbEIha74x$v8NTcbOZ{XGNkJ z2QOk=FxP=NO3~!F`sjP7H^1K>?B%UBpGy`tgXUfH0poy00x0tt$I?8$auy!kTb_Qx2i?jKi_=> zb)QxLVOH+zwK6du{l)3@w9LoKY6>EO4DA_- zqbkg&Z;oWZkU@W^KnA8FCxIb*_JIKzaO6<$dO=+{x3AuX=n?gR01@-486TBo$rZl&VG$5PeqM3bSn`V0cp-N} z0LD?3X7l;Fb1GcFUL#BWof-JJd@1rmKJB{|!h?o5x|>B!=}r$YU7kMCy2(z9Rd-um(I;ww$*Gc~cRSG-q#WyxBSKF=n)D$L52 zXnIo0UT`pB$CRPNj0=1-#brw4z|<7lu#R18LX$A;)RIsxNtN0z?EwV&>#Q z_vJ~yI=qw4RcWnNKc6TsV70Dy@7?h^KWrd4JDkB71syqo>Pf3*6@RZ3fHshB7r3hUx@r>HW^I3}mn_^2X+ zbflb;kuew_mwv=$z!9M;Z8p&x&()%qxck<~W$<18Vp9e@9Vj3OYJzk8(S!Vz8o$3^ ze0RS}81D7ew6fF8)I)Y>tOuo?uL>ud6&|J|g#i7XV&1ULL90hLb8H4n!Gbc>*=Q~* zc^8Jy=z^Arpj_bM;aNR5IxO?V%${>iSVP18;t8s}w08D(BSM)QS2?)9dF~fFe#jmz z!tKyaCLO`bXlgF|sx#5@nxMfKE(a*4+Fc(momNPkF0lUN zw$y5Nzs%|9>(AEudxaZaEMJa>`(>F~0Pq44HD%nEVMClg%ymV#emr!#0U~nUS`f1` z(MH+%`1aw46GuN>gzAhTUD;$fuia-PZfDc3D=R$Iimax%C4|qsknemrMTRF2GF_3? zBz#5$LCjo+k^@JCMAtf!fzN-t9oB>@4ENa5#i+6DxwsWTP?a&7WWYv;B>`9qG7w(K zRcYyLJ`{JQABi$20H{imAqyKK8|%q|>8*;WHlws75&$)N9s*he*3xjVxcBb(){lpi zuY%7YIJo&0>EUaau=DdED(e>UQTAKsJ(f9;nli!u$Mno%DVdeWBtD^ zSbp3PwcJ^?pP^Te$XLc`iWA@k0F-?(2hjZ=N<2ZU)#a$@^&LuK|$;s?}-2Ot{i&*xAvhTT{@A{Fv@JiiH*Md3+g4JuW zqs1YcnISyh?Jq>uGWc4PcYTaK=6wcA&KT;m_f9j^0gpXas|yPG+KMk~;**K_oxhs= z(>Er!hswzpW}mF7DlH(m;Ld!a(~iDw{~V9U$2&~AL_~mH9-KQgHlKq)&&_V64O}rrO!_8h`72I@2zE_0y$i?md}db#@3l+5T{5F-{ORvJYCX>jnX^!M1V9LOrOCn2@mMj0p2X$0SZ)gh zhw8TwlR->@yPE9 z9!ft{4}Qrc+_4z|pctpNA5-PC;8Rxr(0cc+{|;Z8vEl01)zj9$Xm3umDT-?3pgwyhl_iyLVVJM5XP+ zqpH^SoM!Ogq#^=ip(rUYY^5O2jcd@#x-2W(AM4%2N@+5NCaD>W)ZuY8Nc4vj^T5FS z)o0i~p0!Bhqtd}`Wbouc*4Ydk@vX{@E{*Vcl^ZS@6PQo6aS=L#X?qMnUdT}#`_KNV z3oUK*JTGKk#9gGOHVNZMn&Op7+?HfP>1;5$eS7bZ?(F}`N&G#t^!hlxzuJBEg^Pdt z#f!hyX*|P_U;5U~@ohhEzlj`Gda0;}osC*CY0jbvU8=GnGCeL>F|G^tOfhbjsi6g1 z3}>|GR>z_wu)gHASAC~}t98A&CDXB%A)kF3k+Xa`_pF>lHvlkK%9n}m@8n*{xyP)g zGBYwjYsqSw4k}$*L{z1<+9E=|=Zy~jKgQlH*s|+B@B6Q5&-;vbzPJ1KjPAxr3(^#Kl6IpSo0B#g8rSsUU|x1)I1x6bpZgXFkzh&LcaNXJGEus zOPDI{{@tv#7QFKZ2VTf-z15|hXzef-fgmx=J`e(z-fYB8K01^^?F5CcDqCOn!2z=C zc5h86rF$5EVg7sJ5z0t8F{6WUc;}Op6Kh>l{+;#YXD*L_ zi$DAi8Lf+e9z86YYr)>FjClkIO!_Krc^KFcJ{ulXUO-2Ol6l07*rcn9u?kWy1g#2< zpt06!P>d9z5zdPBW>`-`m)zFb;ctbKNRAWxS% zguvqSeJ*JK$DDD(T8B|xAncG*)=17@T>WLX_J|3x^P>{h4tPsbin&xW-V_-$AZpH``q!{TNf8G@V9UfF+U6h%g^cA6Cq<#M@M@dWccS|p3=U%RrDq25tUG@kEzJ0<$I zFs+QwY|0285tlE<;NZc#L+()^khH}NTykO<=F}QT2rQfnkvOJG`^1<>cUg4h{^)`;}Aq^#0YAT{<5D5FC0>N9&6|dKKGef~>1#ZqSjp zcX#5)Y<9H6F_&{r1XNYl3+bdI-}v>F{=Q_K4E8Ho8ZTgkz_=r44}C(QoanH|^MN94 zx`LrK1JO$}vm|3=7AOONGtbv1Jp~T9M-J}ic!8dFzJFfGnnAB&^hPF>}ab1fYmDr5U|>cfGuB& z_V46=NM&JGE=NE9(h(52{<(Jdaf$VywFM8ul51BJY%=DYItzr5{%*-V+Idv;w#$XH zL7C}dtedNWn~PjgNQn0JP5paZBJM36n~T=R#SS#k!ZL+^2YP5(h!T%88zIBxO^3%T(<4X;c?HpoEhCPKljCN?I<6 zQ8sCccmMeC{Hyiag1>WfVvgzc74~vuM)T?4gM=7r4aX?)L%STWE*VCj6w zeZmB7uKK961TkZroO`*Zl||DfLV5A&iFJES5XOnF?5u@=5RkbE8yvsKPyda@Q=!^Z z7%Y4XPu~Jb%L`I|<7=I#|JA&DwRR;r+RC4)f1NUwJe#rA6pdwnUTBl0@gq9!NR;QE zc1QO2%KEYoggkz4boRw``r_U6*)%hcV8ut)Q_LfcRlgkTaaTHUVam0#l#`9?>7=W0 zRg{If_OtDLpxALxF3oEJSTmzE7t~tktgA13+-JzGn_huS zzLAb{%6&>XLASChjqq7i6F5dC@HFy-k>HT$VnF;dqrMz3579DtQBs`IR`4j<-Go%=EG?@9nT z^J$noNff#8S?$Ms^*K>x?pfEs=?kptcxn=)m-}9;bk5Gl2~ox(;TY*x#`T?p-hu8P znG3HsP_1?rjB)6K#F1_Hp+35=@UKVrReq=!&P8}-wbsM>iq8e@?^Ogy>uf-PV3hl4 z>vXJS+?8HL>dQfQr&zu?wg03|&p9YFjcuw=VY5zt$J9h&p%(Kvq@2-u!u_XoEJDB@ zmonEp%1f<0+MSrlfvjx8;Dwg>yDJ8v~(iw2Z z>B>3)EnPV=Wp2V$aG%XDlJlIkxFHy)sx&7&Yev3sH~-!DCja}}!%1o5fC7Qz6WH__ z&jAJ_?Es{-0Vk^*;?n%;OUb|cM(tWlARE*u$9-BA_SE%x{`Fzj^^#_5bNT1uU@7n# zf!ETe7~E9oUqh_B(@SW@nhAoycL0Fawjjv>p!M7n_ZMrb=Fi*|*MH3XLR`P$z4UhU z<{zb>`6KVSFY(Pg0B+~#J5HyB5KP~@#FIKsXLc!~rL?8AM_nbA)7ll4DJrY2H3qW6DD5^HT)tRW%JzopgRMeomq~lW z5~*!AF_$>FpZL@xgxF)1$6BWsf8?jn%1JmfM{Ev>UKI;yI| z6k|;ZsLEEE0U$z9Ss3hLAq1-29NjP0uccl{CtWq!dqNPcZ}{j)>Tf-9m!5gC#s%#@ zE~AFmI!~CIZkL)L8bb z+#s&lIY`^y;%3AI9UWEkBCE5`3ur!4j1z0%@Ih|Ww8m?aUgdr91ONt;qCXzv}N5wM9ROsnxC+=!f4Pp4R4% zKjs&HVWG;5A9GpSd+!Wq8A;D)UdTp=Ra6&~p3>5J5mS|6f^d&m12_p3KJ7j(7B(X$ zPKp?6%iioEYONa{R;IF)vi;j`|3>hmf3(>7=A{MiT2x%B)#}JXvgqM)4#43e$0+lC zKS^pew&osOfA9yJ<2yYU?Rw`Aa5vvNf0*~1n}2mkDOr53%RSpn^orV5hRpo|IV1gQDgOnq|H;9=RP^(?i z5>~sxUUmKF+J3|a`_;|esz>Roxw^Yo{m%DBKQJ)q${*az-`}aUvP{r#4~;dzI5~V+ z%%mJGvHV2@2~(A0f{czNUf5AX5DGv5WB-20C?$K?gXVw`Ae248!*qxm4kkbCqe^!T6=23f`UAR)&z=;<_)OxHC4 z=sqr@8b=f;09^i56Z=G_&s|PbX)nLo%!g|G!|^lYT9gr-G2%SZ)*!)nDXqHxHL0j5JFUG zMZhL~OE6B#%=j@g$~D*g{d;+1)z`}H-^_wGZ>;)wtorD! zZqgE3xtrhUhN-ym^)6ahw6gVOf8lJXD@Q14p9v@c>n=ODXXqPAC~4$@+?~Dm%kAFP;s#pz{I&_vylBgx{1ZEg=xZ z+-es$1ouceF_%8m;2z8R(t)cl`-Fj(_Gxs<@`Wf&c+wKOw3LzEk0x=`a~AM~Kq=X{ zo}$ej_b;Kv?JO90^fD|PgMpb1)pY!B&91lF%6LCXGoui6cHccA|3 zFLu7aEq4l=4^POFBA_Cm`ADU0ueVbQK^NC}eMvm~NO|1EG=K8+LgpPC+z6e9aB)pT zQI7|#7;B?XU)?a)^ zhv3;4(<(PlR}(IskLHuk8!x0k`jew)#s*K(ub&;!jo9M(@RY_^PK+_`*0*}|%GcCZ z2@uvfa_f?|heHSv(3wuu-U!A=6?%sU`xRPR7SD#xIioEB(pdFnX$HGhkg(399AkHQ zbrDKtOE=fm0Z1ps)<@PIh$ zjIv(HL`V_C-&zlfv95B{UJn4EnizBsg(*iUVOZmoQ$mT+?)hK8z5dIG!NzpiF?P01 zV)0S}0P%|EDP?Ot+MWieF+1j+`!fLW!pYfRdqfBw-x4ZY!-q8!baW&|K&^IK+G40% z>%q7y+h@a@-{^vy)-fx2f{{j#Dn90FOCDZ$INkIkYAs}aiAm}zGht)6`tl7g*|XMV zJtYh4tebRY(h{w6yVri>qxi*rWLhD@=|qZRVG=H*sR{t{s_VcYI%>XCZ~oW9&)-Z} zALRpu&)+cN&Q2#rv$X;j(hILO%84Ex$r&D}$_+TD3WHv=`m%4eeHx}QTbhD|snVVV znJM{uuh;(WC({4y=bHfVSh~Elg~h|&bXQL)c!E^Y2~L!DcOT~O-kjWdSS;1}-~8Fe zZ@gOjsXA+}`T0oA=7rRyk$LXZI)M#>l#J?3TJmBZ{@bcj2_L{GMg#}y9b34q>XmF44LuaQ7 zERx6^I83V%3RP~3vDT%%@wM(L4QVPH%{|aJuBSy;>WP-p(o2ak?m)XSBL{+Y2kOCg z$vGK}^~0_#D_fLSDaSZ52FlVZ13l@+${FK~v|o8peyeXvO74f;r9352w;y}U69Pzv zHQE_0K6bEtG2$Log*M9NL#?HC)?sklYM1pD#*-PR;2>=Y#IPdla^+%-Q%_Zd03g;f zAixAsmG$GXHPFug%JqxCarLt=Hj;BxP#$*6k-*KN()lQV+@IWEdhJ2hZCk7Tc<78P z#!Tuy02n)Ijeng?e#({?tz5*tjWr;TuID$~gZtx;9{>LMpx3>Co=a3|^P!q=r<^kbGZ zI1}XIllj5L=b|$&)vR@4%7cho3%H%CFZ=mGUH$2n7qK7z%cHo?ad?QU&&IWcc~s_R z`Vex{)&}&X%-7ITN~{6Ksh6<5+Y`JY2_>DaB54YIf-p|TM{V=v-?Ua~Qz}!)VcC1< z>drTQc3FNdVH?--|IXe2>wCNJzW?BN-+SG@adjTK+!X6NRlxf&pa-Dn2{I*-ck?c(EVCNZB9)p>8P3=)QS zAYmjMsO5{17gAN3gZp`X$v?c8Eo_Dd_p)@s!x=SRD~)Aem3DAYEnkcXna;_b1wUl+ z*vGN?Vx#}a|LF7Wqi>$?e}B#FtO?Hp2Ly<-&N^$Yb=ErPtet9D^D-8tgb*qOkD{o( zR6ln$SxCjhFR$MClO!KyD)(2e^+w&v#!FiG%nlQ9V6DolPS5+ksNHtfz4rHR*Umm_ zo!vLe;h|{oK95@i#)!2J$wVk@VPRbFfnB+<&IPS<<1EP1ihwajoO3u%K?_V&6O@7% z((nHBJuTfddN$UWCTn6ZTfzts%79XW?lY9MjIwc4FiwngI7|*}0v$;~!lN2voJKVs z)wlzwFZt!fz;UyT(N;@~y^YwXrYc)abZa97=faw(uLgI%H{d=6O1Mw`g!?hy`DhZ> zcv$0KcvSuN+oKnLVId!CLdl=rE56xP00bOd_(c7|4~JpO2YV&1dR9-ntD0+p(T@9c zuvfkKxkcfzyYCF}^rA|a5B0rw27b&`Y5a)kYWke>V@4=2MzNCS>d&;Q%!GAL84M1} z>EceI$_yTBd%Gq64f>2`YLPXtbUymwA00e106S+*A^S(0B@Oph(vqFe`vUM0ag~FR6SNpqVy5OnOe(zuGor*eQ$!T}HeC=14y^ysw z0&AvL8q9^w8>y^uLBfScc5Y25BZv2MRoQ%?v0iQF8o*OD9(pMw8`o2Oa&tkG_Eg-_ z(xN48+?9>hkT4h?R*aL&pKN^a)z0jbTDlMiDL;BtAnp{|_RY1x^C^1AP%-oZ>IF0( zsB)rl%{=o$Iy{s({7f391JX7C03ZNKL_t&{8z|wkJ8$>vOFlxuU;9^=cW-BY%xX(s zb1kTHTVL|mpG#zEI$QZM=|)pZ>We<1u&^11DIXn4YhBdv96)Ws$0H)+HF8Ckr!E zK-y;m5zumCw6u*Cf83GTP=5?;h@i=WaxyD&0)S$mu>xi0z_-Tv5o3aan^v+?4D~CA z7?dF4l##}Yk2f_TNFFpn%#^Zd4nnDj5;EAU%CW{Xf0&AFpa}&pV#9-q`=q;F#!V5` zMAlR1U#*v!_F{(Xd2P`zGi{B<(oX_p`BFUTsl$dxDfx%r9uR=HI?5<}BB?l#xxM&C zqZ}LOoGPrY93C>CEvzUz!&RIF>&ANakHVj#^cT;C+@tkn9|&-dj5^h944$;SxW&DI ztzS(UCm(%%APdu2@ym&xO<(8Dee<%lQH}sPdQcecZhoWp+OIALi9i^6knoM?(<;-W zBRLDH1qq*YC3?H?{YDKjUu$5kE5~|tB!Q6jnIK5{&W!>9-uyS)AGZ~mZ^oQi1%s47 zd@=yr+6WLgF_WtrtG?CFkLh2?Io8#)1*|GJ3unSv%=6^L7@YnyXCt~W;gmvur$nzb zUVfBKt0m9ARKNSqVBAryH6Ix|Rc^F$SzkE|*1DC8v6j{W810U>3RT%+tkmS4Rb_jU?+vP#?<3l6-1a*r@h2m4i!vMMvyIxj>~o-b~O zvb1Z@CF8EN4rcA2loBsus_eEz z-*_YRcFTYIrLI)wom;rS{Dnef(zQ%@Nt<{r9Ilpo2!A*ZhR;=U#lHGR`DVgJ|&dw+^DwREihx-J`-+S zONCDl?qy&>7KRIoSArKYWT;X03zYThZE&Hhy`?*LG&qdD_l63*vBPQarH-wr*^cv)XOG=|9tZH5uJ8%9fcy z*OdsE!Owq={YNNpp9-HE>Ey9aWQ;@DWmOoXtgH<8h?ef-1T5iGqn#|xtPQ|g_Yc0- z`v+g`ec_$ao^%m`EH_R$LV)2B)w;n*|M0`fI5Wn$kM8HqhPb;`+<#m+>q0?4wJct& z^S@E2KOIx6!IS6f@{N{#MWi;US4Vf&dOvnqaiG^e6xVM|P2&J;tw-bGO#8EgRsC?) z70ZajpI!qh1OUZCzF_#c`8Yg&B2}EFAy0JyTAYCt?joKj{XiCf7Ti&OT#!p>0^e}@FUjSE*mR; z)DV=DxFygjxq2l=^}KlMO2+ttmR9DLMm4s3J5!~_4q%J}VD~oOuEj_pIZ_s8{l%ml z>lskvWF=kTXJ4$vO;J5TDuuP{2|ii-yJcRJYjP?-xcXe&S`UhWZl4LmI#-pU zoP>43J^JG3797C$et)mI>f;+Wh2uW0FZsxw!C4%Jv9Xh4_twPfY5m^`+M_gHNaMQb zJ}xLH=(Ff-73IWW{}*Ls^0mLMbXKZCR__1c&Tqea?|*yzqx*DslK`_;87r@a|6b%T z0zgsqZf*bJ_ip{qceej9fBVAd^Z%osEKO+|goHH#1j3q-xoNBgoks<(q_VV0QxHmI zX+=O)Y2vz=^kr?yXN>&t^9NUdsdZ`#c*;vcDam>g@!|LoDn@$wLcDlBDkrA%sPIDO zCp>A0)yv8FNG1!ODlMU)q;=K>2@ewPg%n{BaZ@Aun>Y4643&jBg z07~g;qXG7SJxjwnerggz2qBbGN-3k9d!Fy>7CT(-zIEx&@AEran);?_j zAh}iz^T!kZVL6C~$ZI<-{>Z}t!jhkNQQGw12L=@w4Q{{$xw6|Ms zTu-@22?503mt!5(IVvWLn<1K#lD0=V2@{S|8uQq6y5&Gin+=q;&X2h8sVeNPZ}-y$ zuNWIunf6+c^_4Zw3+d|R*z>8;){oiZW{CK`wX2En>HghphApRz2%prJyh%?^lXrv| z?Tnc|?c#Y}$>GC_O0Wz-P0MX$G8hIPJpCJbww zd8EpW7qaGRu=T-+`{W7n+krLiM6PuXhgWmY15#V`a2R_EwihIP{)~ZtNH$QH-e~BP zBRV03a6!3GjdodI!!b1U-9J9O^6925v3Yu`8sr1Dd?9-L{-_w~Am#Z$KMSJ#1a&Kj zxhhTjOn|DEH7-o~t#9?iR5%BOg0;Xn$;X-yc=2w^Fr#3JH?8|PfZmTr%V@K zZ%jJUSzw%^Xf^IgtZuZ%tzAiqkv3|oezwnq2#lYha402|)41v3XB8%VmVl#_5DHme zagS0;M92sORa%rgPo2`2&P8D=bZM1zRi?GFi|0ZtW;W7lWurRpZWr96&H}n8PzOmD zJXP5GvJU|G*gBEJw_?Z}0SwG@Iz*`ql}bejey~*G8W*H|cvww(>fSs3Y@pJ%c=wA3e$46AVg}hj z8C+V*#<(V;{UeEDJ|0*X5}RT)`WAjCPR)d|>zGSXc2 zg-^?|mbo#;0sxQc6F2glqX!qU*^y=%6za$s%Vw4(WSquLVYRc`Vna55cS{!{9BEJn z?K8pAR&n{$HKSY*vwWnVHus$}D;Z-&M3c6d^iX z2N$v0qBpO;S?!E=_rE`wA}?CdU#pelK3ca98h~8|+rY!)oPHj5omgwM17I-8x#?z1!J0eq8?vS-1_-f%b^ALd_ox?8l-CJ>K_(-a+9Z{<4@H5NDFL>7;7M%uV3(CcWmRfSQdMG|HEOo$%&q$MbW z{%(bYTxT4DgR9(F<0gHD>JfTItzW;J@^y2+Lh#3`euq=2yQ?F=n50ylttkn)T|61C4ZY<_b&c9Zt zj3{Mi;}BC>b*xGtCQnsX7N*Rev4G=INK0Fe44E66TJ5ZLhY7#k_8(dz8={)t;6Mlj z9$jpCFJFy0gRPy4Gg6c`4Ct?aZegJ%2mxc=k#R{tji7qmO313mLgQrP%E4g26agWz z6xVOC);lz~CoVsr?QG*$hOYAGwW^PUwHv<&0P8O#r+{(7W2&-2%;p6t(|g0|l(pXR zp8FDOy%V?l{k;-f!t;?1QhsX4-B|H4=yUQ!+YG~m-xvH55GAN84WT;~Jf##fq zDI=6jdQ#>lY6x&J*q4++m1|kpbkQS(gf-rMR9IuTKgd@u#wXLP!ZJ<>1s)uDFTKrL zx2w#Ik0e&m^dD|?hBtOP-{F_P5WMn#7u7AwNp|OK60Q(JgL<^|N`2*(8_t2+dpTX7 z76DbmT79+S9CY>`bw@Wl!y9|O?@!9TxZxoqPv2WLM{UuZc&R6N?D1rG??;UJuKQ~y zzep%a7X-#fmd=OZ2&JH;O`3vI!UYvR8|;i5G=(0B2_l_RsT-0QqG*+f@YgyQApz!N& zt_6(Ktgk2|e#E#(;|BKvX0#pbRmM2Vrk;GX?eP` zXJ4xIwm&{2O@Mo}yIoQWLChAW z`oimt!-qL4?$$WQNbhkj0%onNEqK`U?5ty)I0r{tMN}72LkNFb;gl|TgpzWi@l`ce z18h9NLp%D?Rb^FajdEVZFrlWUHOl%i`{qB{32Hp5bEBL!&{*-EBk%l+{j4vMupT$W z#`Wa!hvW3PxU%S>w{pp5kQs-<(07g1|mG12(K zoOSt7V_p5YBd`2av%6DbI~5SP_{j!>EsbDzGS-KD%Jb^G;}L#YLCl5+)yn0#vsDg{ zFBVka$}UE6s&P!jSmkc zs#kGCU=!lcFmY1=AysZDgDN*4A7PnZ zA>5m?-YK7oLCC7Z4fM*T$N_N{ypR$KWp*6>20*x^v%oznB1Y!aUnFhSmjvZhOFKBe zbMY$xfbMpI9(WP3AmNn4V80R}o%$95grGsnv%d0U-ajbu?%;yT!i60mkShnVFe=Q|c#>j75Rox-d>xsaL}FKP4T z+R=kNZF}4!@=4};b1k5hTzI`PdpdBRGEP7GW)DNbCuS>Y;s4(+5zw^ljSruZ!9fw{ z4RB6DvjcZ9UGE3`X<#J3IqEdAGY)IL3!SQ1jq}&Uc z(b#DWghE*3OXnjj5r6W2ox_z%N5~Y)O90wu!hEEr_P672XZ>2@98|gK@0C1YTDznr zuroSLxO1);>2hL*2Uwm(opanL?)a+-65d?(`+J25X;m1o;79D}K|cSg{D{5sD@$uv z6Li`}HJ0y zqz7_ARb{OKM1W&Xv%bpKuKFE`854BQ!r-6^mh!mea04#_W=p#ENy$9Y+bNT_-`g!| zaPnT(-yoMhM+tTLDGvitQfK4h5%KpZ84>bCfu>iVzGgWzlmg>Kc;v#T5=u!`*tIM1 zF**&J7d#qJEv?lqZVP%WGlp$W8PSzhm2IsDGB?gTnVa_cFdu0y=!H+#34zX5fu^m1 z(#vl)y@-vDDiKh$)P;2}0_v>u6UO)qz)GHOD)>mlmVsM_&?||tZs$;T`YOxqgPrpJ zqf%D*WHw9>gmM&tnoAhLm@G8^Az$XBV`gp1$t?`rmnaSZz zFbC)2+RAabevIB6FJykqt6YbR_qo6CCv137fdejxt{loSvM{o+m~3S}(NoO4)5;p{ zW*>68;LUcPUdXU2q{>Y>F~&?6Lo5xGxeikkdgKn7G{mIgTo2{#=Q
    0@EkE4TU4H`ARjEr0{#6r~*dm4laVoLG>I!-tD=$VIX9eQ4M< zEPR&rl`ic}&2h*7Bfe9a8#K|&;u-5|eaS!m#I$*ezcxCQ*+6ee_w8@>zxtiQ-Q9{1 zC@Nb>Cpd6MYYB@&N(f0~_S*BQb&%zTbAm=K0J7?lf9FDVVTn*mljnB{K-?7jw|nX3 zjQU$vbH)ix-w!T*O_{w@X-b!Qw4KdMTF61OeBd`&vf#~6_?RF}5G^fXPh9t?k*KDYQP(u*Q{h!HcNS05EW*04M-fF2(5A zHrDk9YIh+pe`#@Wyf-*>uxH5~pt+#Vxu_}r;wPMQQ!2l9!tVP}_q_PK?BYwg@+A*j{v(FgZT@MlQf3Q}ZxxV;Y_c1E`j`tR-c z-aUx^$axzIo*w-di|_sq?Cbw_ zdhfTU13LN(FD3uiD~J(M!;ZW{LwFW|Jh%^^N)Vb_CMYGo!<(7_}e%C z*T1QYHhQMM^Z)Ex|E2ryd{9)~LiWbR?rb;!09kps*L^3iI+Yqqm1$Et=gfegU;K}kE+3wG^T*fz z?z>V?7A{f%NLwDBPeee&gsaL>FCX5FI|sm(E2=TVT>nmUdw?(#rktiw7d4 zUO-LZ9Dp${pV;n!-hZt2AFJ_L<7tNp$^|Vm0}jfu*3!mJueBZw4k|1_$%l#w0?uh^ z7tTh`IULUK-pK=bMpu?n2og@{ zl&HiwrIbv%(hnI*(W)|NrX`dNJ9qJQ69P$7ENq075j^5hM#de54Yyf=AP09dJjZ$wV}hdoHQ28xh2~lS$B)3cDF`J8_cGyA z;ZZb8doe49YBmzV?fdeD2vI>=*`y`FLDCXS7otg5c@gtMR^`ST2vQa|1rrqAE|=bH zR1>p*C&OJPS}?+tr)}XJ$b35f#h4^Mje?j9pAtg4J0&5Iw!Ph3lMlbq1xH35NeF}q zql^|~9VD#15q2M!Fa6SDb0xqXmCViJ*)VB|NAHblZ7*H$ZhfmaTih|;V&*&`_#l~Q z_f+|l_FMvJc*METiIL`bQR?rO(;*%K$_W!hS5^eH%ruTPtpg^=%H=prc{bPble9dU zoBm!kwGCVM7d{=(Dix$Gs&iCEm;fBUp$dkna-&?3@YZ_R+bN4ZVF))LD&f=Ss=s_Ot}^W` zEN+IAo0=9cAL#8A5=&Uq2@BidN?34vm$^MN|{zeD>>fT^e;VMh;&AmxOT!M>b*UqQ^Wft*p; zg->T15Im9q03ZNKL_t(3RHL2IZt;8w)~RY*Jjb2_^lE9DM^QRKg2t)qynQAFaOnCO zA1UEe?o(Y^%1C#o6amF0f_ntXIK{{?k6Po3vG!w*0{zE>h#ZQlUcjotFiz%4Ot?>~ zFZtO(A;ljEQKiKvptDm*urt<=7^MW|WVP7o=c>}|+^n!Q?8(`+fMY=WJm-FXgC+ba`n|Otcp;+{s?3Ohm6_SN zp5kTi$Go=S8D&R@6*w2BZ2N<8b2T6Yv^1xN%%>cP)9cow!l$~j+^2Cv{NM`*2ynpH zmi5$=kp!2vz1fRgy%cL{orBRF6b5+<+^5aep!28%fKUFlHu)Gzl{}{WP)?9jwsaxV z(%t{T6Xx;7&9J`WV$spB*HdtgP_PD~l;d|=Tk;)%7tkqr5P%E1cWYv` zmPA5!bm0$-LC3N;5uGwPlEEqPJW65yPia)KbF(=|vQQ zDa=RJ&;qgP612`j(k5DJV3j3#Q4M>;Elm#mWKe4!cc)0l=Q6739#Xkc(v{M-p9{kk z-Z~R#Wp_WCVEr-PCi$Ln%AtON+W=JDMMAZ-vnuwL%aN>XH8Gp7);{>tqjXI)R(wLC zJa#OuJRf-xJN^?u2+BPgrW}1w<=7BP@Uf2df6q{30bXWK-x~jajJfPf9L3Q}9Ejy|w5(80Y!M=v*tvwv*FTzGvW_67Ls& z>KDcZxQx0+H5sL1($!H-78A!9^B$bWa_YEXBAng3+G;?tNcqTE?W2Y&r;af|hm?9W z0~8BiWez=N15;*B2HaM@`+g^hHk_{jfOj%1&-L@oOZ(&ZWPO`~xM)qY^;}BobyND$ zaitrtB_ZPBSyT{s3hNie{%ift+b_xdR*r2xlgsTq3P^I)Y}EINSYEo zbJkax%SJOoI^7ggc%#u8BpQb^Xi8t@4meojtEn}mD@GO&(9cQ~74hLr>81GfD_ZQ9lEe5HGiK*!JK!35-0nJuSwF&J1rp%`cA zQA(bT?2~u$3#8ZGm+FJV@{fM+=*thv?<4zrUmyOxKj{9&``O{ZFvgf*wM6V~N4r~L zyD8I{JBMMw-+XWS&Y`XhGJu_kDS#JtCuMLdk}f>}?73g6 zUzmKfx1;)6n2)XZ*jNk7iCvBs-EW7F>gr_vE;gl$>_n9&Q`9>Y*d#*G8GD4`bkft2VMBaT7U>)D#KJD!p)ys5sKH^ zDrrgYK^K<%zNzIvoSlG_LQ@qzUjKpI{5rDfBCyLoT<_GMlRVOUKk&5!+y8k}xy|&m zLBwe;>wKT))~{asub$ia#e1aj zYu~iWUKz^pXq$*l~4TbS6lx}GrAF~W@GZI`IEnK z`mcX|ulsk_kN>mXwa;8>{k1F8|L)y~zkTq*51XS;Tsiqas;~Ur;`Ak3_+(2(spK3? z>4t};cfdJIT9S6jllysPB+rhOgPxVG8KB_R}VtOvlL z%p7BEcvPxTq%BD{fu?k6OOf)5A&UmHMn4h_w?~&b9!LM180^L z`(Z4?gfljaqMQ!Rq-U)0yD!y*VAH;#ZM3}|^`De$R}ykdRRM)9`fDF=s)$E55ypJl z<-H$loKK#~zW}8AX@Yr0BgyPQ4Ow*%O811S0bPhQOV9?%_b39k`*Ne2x{Vv@@VI(rs`}!v`i7$GXIzi@IzYr5pJ>(E!Q*!(@BL}d zyM^L*c72kDq}Ml<4-+vLXk%QL)2?yWbHRp3)!JUvotwYVtR4W8R*<&T$-Vr!pI%wn zilzfIoC}DyU#Q8DCoNe{t*QLZ3pHE$@BH2o{oG<|P2~XL`p26pzRF2;RY0{^6rA5i;a&{o#oS`0%(2Vj%?Ie}5tr zPh0A(FP>QAJG)VL?i#*vEoJj)QSw`zbhU~&0#t=dnreYJEl)J-Yr*KGk^w)ymmwmT z+YEeq+(U> z@`)v1ErPQtVvI0xLNrvwX`G`HLG1LwVF3VPU6z@pkO7^$!C@&RYi)+QboBI7Od&c< z+lnz99al+Hv8SeSw({?OrQ5j_({8$;fzTRSy&N;fh_&P$R=E`c7m8K6rAdG(Jqe#x z$k786ytNt5Lg-F4=RoE@AL&ChM|rqnI&(s?a^VlaW**oSV(UFHzL*~(&F5*v?Hrbw z)wu)4rf2yEAR|t`?56Vh$P%f9JgpaZJgUpv-{^;_kO4Q9D<)3oo~(JZp{b^hiWc%n zuB|Ak`0mH*>52q|otNrduxwydEQUuFWgN3PdWa59?$APOD~#*XR9;A?O9u#n6zz5K zv~LJ`_pqm=I?MTkD&j)%Vq#Y>#}ou?N*C1xS2LRG=FN1{tyCKivwXAwLu2dmGZhjzdP z``{Zx8vgA+m9#S(+q7rjc;n-(!#i2hQbMw9pgX(qvL#j!3-lPKViCNRG*wuan>W+x z(i)_i^~VIT8f!rii)9RYnP9v8*W-KHjCWZ$XR!MqueXDR9+O;F335I8Ft2YZQt(;h zJ3EngNCYT4<-3mxXOYyAYggjhYJeWHf$i6H7G1 z)xEg25i$aiD$|fAi&zyBpaH}<(LZ=)g(3Q>sOQRliXXRcTVKxAQ9dHrOCcevwMK zVB&DWoksLHJgJyq?d=E=TAShe)x?yJaGCz&f^$FzJmAaU3jixyk8i{{H975SqkWi4o8#Jzgrq79OVBGHZ=#2MWMm*FUCkwn5&;D0duXf$RqnDmfaUZv zHsDQ;m`F~V8o@>r8wK2X$mX0H=VqakrS{h01!gW6td~d&Aci{bR_n$CK#p+e;J`hl zbp>D?im4_2ptC-z31Beo8 zj1H60_me=)G-BAVLw-gt*!cOO3Izb9n`i9N#w=rZwmaoROR~5sbA--VJ&R}Y4jZc> zAehqABYo*sjmaIdce5F=x47WsT7$ZD6myISx^&KZ?@{NT zN{cdcrkpV$yu(>IMj*n=*#c<-0M6z0OaIZ;&0hilj~Dmk#s8r+_NVRtRLF|4)$@17 zICw;Pjk6KCYe7?ae{y^`Cqzi4-{)R)s^k&(njb!4o3FoUhJE)k=vu5{_w<<7T4R^U;o6u z)4s753=a_i8k?DS4z%=6(y-)WYbhsc@5>jw@BsjVJHSAMoMNDtkvMWl(1jNtp*N2k zDjOIoTIeE7m(Gs%cC>mqo(|0NGEig>M~xPazH#5l8+Gll1p8gTaEpJ&dZ)t-hKQgJHpgGAWMJBQxS+MI_cUwwS~ zwJCpNyk9;1?JJKz|KIw(Z%1{hOYa@Z+J}g&%F-V`{#V`6d+o;aw|0LeXg#4J<+Oa~ z(aE2Ms!@wKL)GG3#v9*f@pt$qzF1|^=*d+sX3XUv5@et}I@YFgy7cQ;VgMK&SL7yK zmG0S6aSvAeVq)r@V0!8~nT7zVXy)xDYr=bc=S$tQ`}ArW z)#W>1?E=6;pvM*4yj26YG5D?jG5*H?EO}U&k+##UI-M5#=yB!2uUc1fE)j8@KM^8Y z4PQyZ^*HQAK|2mw&GgDAp8H!5Prmx*ho66V@~12I<>t5l?kn!!a=ak}W(`hynhRzs zZz``sjtJ${($j_x(ZeDbhzbr0B~L#SI&u7$3@kz z#alC;$n>spnKlz`&xo(z{*6KR_AO-jID069l5wcD1N1;zEg6cqE{Xo_5mhLv++BUG zIXclYVDEgT+kKF?cVb)lq@j%QyC19fmgp5yu{dQ>!dj~$355ulP@Lv$#JFP&;<`+l z${8G;RHGC9($B4isib;QC>F##8=9ylP9NlHQ%wiP8FBkd;a~iwEKfL_v!v#{tMfqC z;y=s3FP3U&JS_$c=FN*=U|7p4d&cG{mXJaaiWP)m9LGsot2dh1?LdF^y+4o--Y{eU zL7x;o1~E^YGHEKI_~4)lQ%SM#asoQZ)pgo4VJwD6r3^S1FzIO(i!c@5VKuc?<~lpEP>e8pstAwn zW-^>H_84QP@_-OVf~*bDV`Dv(igU>rW7B>`)>;gpnAoJL;)W#6ql!4=@Zq-y)?m_< zRqoJ%2zY;g<_Jc`H?>s+fmykwq|U_&s^-vG(vsxR`80AzAICdX5pQot zDiV}My||Q2!0KLnaC=I7Z>5*)wxN}ceF z)}_dlK1#(|2>Ofl!`o98iidBHqq-D|&*ef40Jd+{x{nGb7%(=Ayg&eewJV7!+&f?H zE<0ts@>kZ9h5|m@PEQ}^-a|Gt*FN5Q`1Xh~Slx}|x~y{7*@=^;n)Y;+IeJRthBBoS zidVUv_DozmOA_9CF16ZMxl0=I_Mi8;Vx)khiz${ZpO$tLLx#8j-A4rjq6J}dBP^%3 z${b@Xs!5^v=tKj8(@sTVa8xo*rjKsPLxBJ+00eYsD&N`&0T_7XlJ%dIt@RKP?tE*& z1*52ST{-kKiJ3FlSPKcMw3Ro7?L97t*g{&=(+BxY2GR|2(wAT3Xsdm=W zLr8EucoYGnG-0c~_h2;sNIy}ekI5L6nH7==bxs3FJ11=jWKd-n*uC~tAz6)aO?ron zot3S`6{lSAd}zW%EI@F?GdY-=3qI%sCj&&fdMEeu!9gJ;(}fd~=Ob&h@9!6!GZhM? z8Ky%S@M2_yV*MwxR6ep11z`D!-MW<~O=+|jl1=*t-7JqnDxTEN4QA_|;OK7lO!45t z50o(=(xT2Ck%*0^fO!@slKPzWy`=Y~%!dXLRK&Bs<_w}((448t-GyHCnQ46|5AtGc zlBT3hQboME9&pLXU;Jr6pR6HhN3xYKCKi{3d&Ce2fX(YkJ~HD&M|`daZxlab9v~EJ zZidGnX046TRQ}|CzA(mO96CF3oyZyhG{N4uo;r(f{Ql9}mAH34ZSyZpB%HMt8=?0& z?p99+9g6eVFS#0R-bg7s+f;6HY=W5g_bcM?qDMOQyv50pPS*l17=fWdELAK>EKE9C zTX~&3844Bg%O7hD_N&frY)V&7-C~xbLUB?2Yke`XgQH3puDu-rLNT$mjsgbd*m{qv zm*Zk=o1392-1wC8qxJYyx3{Ap5{RI47u5v$6|}Y@GJix5D&iDcp0)#0l5)vh<)vbr z&z#iHnpH#<3hyx=nJ5+Lkk)?MQq!I(CU$WUuir>&ZRMT!7On9znoaDBu`TD|AQvoc zDRS8(LWz)!2<$54lfK@0v0i2lJ>(;skF749GpJ$~)Xq%hR`+5O{-{UZ8C_^6AjAKUt>dieHue5$|u`^P~n#wR+i393IA_H+KJ2|_&M zY+D?fK=Q1is#s2Qmlun{7jql_O_mF;@(Vx*0CeH061Li_kUQ(kq8n~tQFZ4( z^jua&>+-b!cnbhluADAbG@UD}yRi&8dN7r*a%W0E>FOE#2BFH`)t_k6B+q-)xg(C) z>RwEpptqbwPilr zX33+95{EjkzQ3qd7~@H}mX(Kv?g4-j@zu>=001SEnM344zp2BgxA&_**%};_&Z0d# zpjo}Gim?gKr;89avFwcL4VDvIeRN?=hPeo!qH_y}P=mCoya$iat_$xlb8vrTox^v> z{!0_@JXRVRLm`;p5Jr4;Er=t&A(=yToNd-bz{(H$qqm0km5vgM51x1cP%-#M7nNb$ z-u&cBKDfx4LU#PjQMC5}5u-=zTq3gv3Zikw>+;zmbQSVRPv>K^c-9u74K&{+L)FE< z);a+rU&6|7-AsCqiVN~~Q~5bL5;HGE( zqQDd4CO6l^(Md)8{VZ>nOJ)l1Etcb?)B{A+HVZlrOaG)hdjELv_UcQ2mbO$eHggV* zFDGGTCjH5s2S;DJ2mh3*9#vL)T+?1k8>?dNL*5L3rpjLpITYgtQ2G7&Q8p^}4lc4I!b6{HHAG2jAdlVO~-HX|YV z`qgCG*GW?`&K6~yjQR7gcT~uuRG7*?n2)65)^@f3i`{?n>$PaB)cyA#|I0T%_y?z> zcSBWgB$q?k@ZLp1OWWzg(WPdxXxHdlV4kz96OGk`SM`Xu|E z#^L`~jA~XR02`lFLUJydDP1w1S^SX210}%&!0P4LRvtZ24NBD;!Lvo@G9My^;yI-?U>MVyXj&LJP$zqIpN1d@_z*LhSGMkm$jgJQ<^ z;w-8O6$>ue;~$KdQMP4r@0p4!7IfKZ9CS|GGE4YD0J!#Av%VS(4$AL-;fQ1`ct+zQ zC!=67fgv3w0H|2d$3%p!8#Q214V;WP06hPhHsh?yU6_jIdU$*{yYb0Z5Q))Ar6NHV zzgJ#u0Kn#RH5Kt`-_%xAF}Ck~rMp`4>LZW(?o@qtm&ZM|O5&5%SXqx%UXb zF5RjT_rZHKB}R1#j4{FbkBcA@wYCat(rQ0AEQMl|uFeJq0ISSVX-mh-%BA?^UgkZ# z@Y(jAZw{zExc*Zu^pG~y+FoobKR7I#Yk`@oZnthG#n>*`bIbRlu^!5RAKuAl-XBB* ztVvUPYO!i7iVODe?GfYb>T9jxVZ{L8eA*-Ng9yAQI7a8hv_dX9W9;-%&NvGbVG7SU zv&IX_Oz!D$iE84>yOXuc5vc{siP6PuSSJJSt&dWP2-(0?nX3w$t_0qB=W(%mR<oVoN;l+7F<+s>(`P+$PO+kSOH=4Mp9-LJ&>aTC077I|4Big)H|R63fg~k z>1ZBEaXeQ0$*G3FOnOUishC*rV4=7H#A0G=?SNR@R(r~fFUFSa7lE@N5ot^5!Zp@I z=kVP4lmTN*MZC9P9Nx~ho=f-NpI!hU7IHcCFgz+L4wCp;lmTB(9mSkcdMSZN)1g6+ z>sOM|Nu_g_H0AK9@^g~HvNvK-6ZO?_cvNLW9o6NetGxp*=H3YBC&cU55~7bSETWdL z4*@_bqQ)LpwxfJxfk81cNke&$;4vTDw58IvD#jKORLF^3>@D8>^vWzS)Z(&AVqt(q zx$ldPg>)ji^ie8LALda_%77OW8z$nJcXPo`3R4lpVz6Iw&S;mG0iX8G(cMfcZjGnQ z``WLpEW2nu^?4ZpT=@^0GT=eXxnPr?Nn639WeQ@kel;dh{KAK&u@;cFvC#>a?D?)P z001BWNklXy-0id-JhOs!kU*P#RVD)mmY^v4XiRgChyjXwqgRyrwKGsP~ zl3083Wn{L{eOLqy-dGPfXJIP4kBatAs0(*;KlctP#l;z{ayvLEF5Rjz4wGIrI4FsF zya3J?M4mGekVRAZ{J@y8j~kLiyUq0wJ?0aG4!2*Z6VA>X>09^9T@dOkI0ghA##Hr7MNSuo4I^KmNL8?v({SGJ-skzvdk zW4=HDxcRd!0J!$4rq>sJ{3vZurkwgcZ{hT=IecGp2J2U16>~&<@V(K6FaaWlRJqfI z_Z9(R@6|dH$81Ge9BSG(jKj2VR(InvbF~dc@zc8S#mF+ou6?qZ4{bIujZVNNtFH#5 z<0`BP1Ym;o_sgg*7RQit{%MDoI)j7(u7;ek)5>RsV`Ebpzv#0u;4qUqoPE~_p||u` z9`KHWC!XDNtcUQ#pZ_WT;)ro!!cc1|;Ik>6(@4SDr1KS$S?wwHh1%()sc0uL+UwlA zISNL-Iyqqtjw)vm5H|3$t=cugpW&>xe&Y~Wp+JcwD<24-U$WYYBQJ7d*0*Sq@`em=&oYee={o&U%33MFJJqc?fR`N zo1beWyJ@tR#v3o~{ilJfF<@AQPwN|2ccW}%o$=oJ?HB8`r6esiI@Zg~*#(rjJaa0h zR+s*xMpI-8M#s%UyWPGN0YGytoOCrJe*b>)n}5*z7k}J)?^oyr<84^te2U_ZEd>+F{lTvW6O;>W6P-lVj~F4*;!85gl;OqEMWM zvO)B06=A&-Johsz!^2VreCMTlHZX{=c_S5yIp_1C31gu`PG+D)=`y9SwF5-dg&Un# zy6{qQbjTPB6Yh*39##3!AbCI=Y~KiB9-baIR8*VEJ{oIb5OH04Yp|Gjb-B+w82~hQ zhONB}0MxZZA_FnbD0vngRO67P^CgpZi8d4_Qdbk!o-Y2Wwi+-18J#q@`n@MbF)?8( zh2SJ+Bq(Xp)oDu+8r6SN#&ua`E*lscoi^5j3!H1>6WsX3O7C&m*b=<47DlP~&hH)3 zB2m!{<3JA#z-qsBD?Pk3rCLyhe0gGa^;1ofB&_Zw*7)g(0RT~aDt`Fa_4i)*@ZgI- zc<|5OeegSz{NR;qe{*;3Gg8EohnxqT3y)5l$+SFreDbxU{&%&VYBRAeH?B0cFs^W} z^5{0(uLUwKs%~Y*+Kjc$YW zKUN<+t`Da7j)!j@_1`ph)_EHHY}&lwVSn;LWhPmCJACf&Y&#GGYklptC*|1fzEtn; zmoQIKtFHz@#G|@kY<3<~9tV&d*Wu1fbzM2K&%E|iO$N-{XKy+p=8d&bMdH!-$IfE9 zB8#!1>4dG23+O*7*Y*;60#qQTeN*o!^4Q{%J^Z%(i~lps?$@3It=Jj;>dd=+8OK`u zAGXBE`Z0bXIlV7oSj(Eixy3sd3m7XTQDKs%wR$6Aos(~@eebv8!4nrIlIZj*;HL8E zWM^Bj+K)?&Hw-*G2 z#UZr#!?GC_33KY5AP9MtyMqt1<;r0ByA}te3i;~gSO{vT?FC*mAq!+`5T%lIb4Gh- z{MmA1kTfMZVze(st<5m&>#zRf$Ml2fBRAH9`g-uqe{tA9aR=`gI&(BB5{g~_sg?|R z_hC_A4T_1Wwbk+6oI1(1s|l?La_cwx;;eUgRJJxlQ~AzL+@?tmgUy?%&RugoAe@m4 zsI90d71h)Y4$A%aC#2X4A~8CxF27Pg{2=od$z|MXeD$xc_4i8}kDx~(SeZE$@TevZ zZf9vzB~8_PQUGF@h|X?YOzqw84A-v2GT<+~-f*49c92mH{LHGiE)pH9N1mbve#vmJ6g5HXu)uoH- zl7c3w&@q*_+B@y9f4tRuQbrAhfc=9~hTK%1ZZYGK4eg|>DdEd%59DzU43|99g=F`> zJ4{<@a8RyYNuru~TDFZI8|y)tJ!8OF>jcgqWuxzg1oEqv8A)1)=`sFy>>b7Jt-G& z@}mr}mUWA?$#{oOdlm8h_oqQD7@zHmPXqeP?48WCaK)mCF;ZHY?r)My3FC^qRCXK-~duBKKO{<%-Li-~P*gv4YF6EQxWDW2%TLl3(2LUKxc z8y#0GTM@~e$&qJ4zl~}N09LQWfG8Bxg?r-*$N9)2;`+68#zaHllFyZ`nxe9Z_d&Mh zoHO#11_m-_w?5sD>M~3u=d2prAmWU(C>2%aRLq+j!6GA=E=V!4DrV=r6am6S=+Zxa zcR~Xjawa9mcW;prqJ?DMV>z{a&Vy`S3K_#}Y!_5qLdV*>&z9ua%#-_-t^CpLDsA$$ zOR~KoYiohGSWR6ycFm1&S@N^~d_rPO$~~xG3cR1G=a^u&Bu{$JIg}(r@DSgan8!A4Pw5!7n{N}2602~zFd#%V$#*k&5)eA%f2l~ZunS__x0ezs#?+x zYXF158>)Z3*7MNFES`s}mf1^-)!t9Ta1p&CmDzF>CP_`{maS|@ zjLoPS-eb~G1QXCaMo7jPGo=@bGsc313&jx8RNfj-L4I?IA{HY{D|CEXIn#c0^0lM> zo6hS+b33ale`>%uWaGy?x=T0_05n#^a_Zu`5K1rx)tr|=3vkv?Ahfo^q@jQSERRu5 zkXs8EY_ZQY*TY&nkO7Zsl5RH*b=>)B!7?Ot=JShaD#tjRMX!6};G79R7ezQCy3$u~ z{siZW1U&#CI(Z-)d3BnVN2M7=s>K-FT=~gX?fSGhdSUNZpWFGB3tnI{;;pTa$n}&U zxe#V%12gXGi#s#BNSdCF`koce62!vJ3K%3BTHKH_!Hgef&yL+Acc#T{zU{Fon zG6O3-J56Rhn}sfKc{;dxGvyp?bv8Z;6M+bmo^ck_mYSs!pMOH;E^pA@iG~MN5D6~W z>BGX5J|CIEei?9w+P*wJ1YDKPx@&>E2um$vo%Es|`Z;YVE*T z%!Wqi&Kgg(#A2&7l`E%iIo77itS+7RU`iL&6yr0UR??Ewo)EjBLRpGR|r%N(KDj_B34yD4!yT zIYki0Yx2@_HKEwJTb({Aim~+uYt#QiWS7SIlat{)Gg?8o`ct?5hcw#o-dI-}R~VOB zn;VDg z`scmL2i2%(9{udj!EdWazh=u7?+`r#gZf%P>N95%a0b2x5hpgy0$yofitcTR(iEJ{-GY@^`F1<(yzVUdf5U%ZOf)DB@{cpYgE7~a7q_8 zZKIQAruy$BPgAbgjC^n|b&x&N z&f!NIU@gb8ozZj7k#uI~FW?!DHKSrN&IMUx3ALbOMNyO_Nv+1Gt-HU!K75=UepsnU zP|g&^c#%`j$=w_nql7Q-FiNE^oGCmPj5ZF^4-(0R(sr90VbYY{hecGAvrxiN1PPC8 zviGMExD5Y#o((f=`cvE^Aazuz5Qs>S) z2vfdsEg@5L&RO^2OvA!~$$)QMOP;(xS-+M9kua5Su7$dA+b`6GWMLv0hsWR{PO$ z#W^s>bnaxxZG}-yb{`i}BIAZa1jd*QSQraay5+<2rO&Ot_toAxD@uU%tH}j)oC{VJ z&Xj&~q9@0C@VM$dDEHr)T(G_hLOvHsc>tL9%<-M#oiC0S2ga<|WiaEYTkJl{%ZVil zNtg&z`3rW%&qS#%P+AuF7Xb~+hyfzBwxX~uy~qBO!s#==p$lKOz^7!$qq+nHox4fT zgiGvh1agk_mtU^eRunl>1A;f+**S2=z6IuJ z0MOZxX(V3y+$xbV-~UR#u@<6-Fcm`b(Xr-|$&fM5uK#4ylnS{GD$NsRC%O260VJ2Zk;YB5YhskM3qK{@m(xXc(V$?@=l^hiPvX z*;Zy&2K?dM9ncmSj4_Dn66Uc%o!w}7RGJEdScEYblA)h@!%;2H zfOU4G{(f;zpjUaJ7$Berk4XMj)1KxWvVkE2BavuxvHY_0J!!X^a5qf7kUOY)v?xLFL?-wfKB$qx1Coup9NnKqaLe2^Q zYT7rnLKlNX%4J`$*t`P-CL@OKY+ELn##CPCu9_Qi7h|gn_jEx|=Y%(YbfTR_wNP&% zFabd<0nxj;6QcFRxRC+l0?56d{7Rhli^5OT#x^Q92>F$hAb=;7h z-B{<22x~zsim6Rklt+*uw;HR=&Jvc_#03MaWuw^z7C;7(bU^6RlVe@+)X?~>pl3jm zI)e5{pCu%xFij!34EWve42f>m-~Y%&*L-OAUTI9ay15YoLOFH4$HjtTLvOX5dM+6v zTJ6ZrMi;L8xLn z!aE!umekBh#mI5C|EOHQnJ~_3?Z8`4O~v?Bdxy5d7k{=hJgNX8OhjulLJ!@?g)^RW zkO6=1&w9&&yk`XD6-95Xn%cpMO*;w^hKE&{O2C=PMq@qX98@Sq$CY=ub~)C$x5nGj zpFYSLXIA^TAyp{GCskuDAo?M7|gu!9i-i~bL^N}Ioi8dJ-&d5hAn-Oui z=$&pqU-J%YZM8VrIiGd-w2_*^naXp?UifUA0P)4fD?+}q6}Gpdd}zW{O!`_Vjvj(U z)K*pRaarpG#5rAdgt@>lYF~;}B^&)^x5kw*%nw=Nxjx#(?@3r>=2>qgl;dXJaj6@w&Dv| z1fTCk7T|OaPDy|kn+2cIU$1if(R{{pZ8-v^SI2clz%H5fAYiQ>Fb0ja&{-eELPnfo zk&20JUy4;ECZ{Ir8^E*n9uR^=6cfuO6Ovhj;8Cp^^4d_>zb7vBS*pcq#!}tBc}fLa z+Ek15EXFY(8^(ED7wCbsW6sV*SeI_qqPi$EyLLGlcPo;v147)8rb7Dj;yGN~iw8#) zkss**n%NZCk0>CQ8XE6sZ8jj#`RMI4gkU5dpB~*R^}u^mnejqP*q_`v9=v@#c>8qt z?xfh4A{HWCZ9M<@^lOh#zP20}Hp87$v3Wh6QSUu&-biV*BLhC^8E^4}Zw$_z&csK0 zYTWS5aA93IA^{lfYb&a=8y90sC{J9M`N(>UCU@-(+3bi~Q*b^rlDk*o?+x6yN&tYr z^T)m4eJ}GKoWn1^J>i_~2soZPL`XvZ+(z*F_2mD4KmVwDDU^?{uecjoO z(c*$EOcj@{X09wZe)=58`O>YLjCe7zTQ}3VDT}cse=c44556%dCf1Z*C`KMN+0f9y zlKdiwc$7$bqgEHnfex`*0W#;0#3SwSO8~{}Q zlylj7*`_ZIuKp*dYt5IQ+xcaW*4V7F6K$tidHn8!|L;2={KlIfem*OY^Qx<40szie zk59ffDGu`LG_QKr71~ZqJ^Wz*-z-1VS?%^C@jGwd{eRy4@bja=lMVm6cZ3K6XDo=g z3YkZA+Iu(CNcRs)?~&&70I+%`k%|{50RTu5Nf9jrF^o&~;=A>aeeY}_EaF6Jcu6V|-qZ(W&Mj14~VC_mAB!WWOg<@eM(0gY+7qe9L(TS#{ z-uvIixBf{odBiUguNF2q7nFlfgI7;6uAXUt^$|X%XD>eIV4Xv;<{~b(z_ElB@=R73 z#c`Y@>B*n39{lO%WWV7o29cn7m$x|Wo46sRA}&cq7xVaDE&@)=qkm8$DM>j4#MQkd zh`1@dkTXtGT$jKgN=2B;(Q#!;Px;L%;*3Go*Icr6MS6oL5AxN$*gH&HGuSI#QPyBF zu`1*=zZx8tK`eklR1<8T2fubDx%15dkqGX6Z?q7_O!~Uk2|Bwm=S+q?AKCF~wSFy$ zYC;A~D25*Pe>kP$FB@n8Xl?|>*s6#Vgn#s5M)akPs|h)L3&l+7rDDhT@|CSn=Wg%S z1{W+ygw=l9)8ud*H^JbG?JoG(vLRY;&ZE7Q~BncHbO+a>DkF~?vah^LMp~N%SZO% z+v9Vrt7laMY`#-+HH)>rKqWwca%zjIiyP{PU+>@f=774{Db=_8*-xM*I%Z+b_0m))oa*V?Cet;#{8jGA)K-PO ze^4^cl7=F1s?027aR1Hm;>I6-keSlakEV^QzN&QL0cU0h#N`Ph?&ejF3VAWH7cE)= z(iN4Bo>6DVbvZhzXg{P(y4hpn;mkV>k#P`nx6Xwkl`}@nHR_6;#r+>tkG@w{L;JLY z9U@qRG-f}Sv&Ol1zL+?=5$M4hq*WP20vH<{l)Ci!$dK(0V`uYfBKuhD0bu8anpFH5 z#|+N!uhD5$PVDjBY;aIcdWPV(v?-r|y-mt`E?6-(X*=jWE`mhJkb4i)p-Gym%G@GN zENLo4FxoTD(BbwAwaKZrl@Aj^8U*h#@7gfpGnpX+=K&qGwjwS*5@a!@Cu6(Q_lrm0 znsgr&44|A?U3eNApFGIRsZ}9o93H$ia@Lm<_r@2FqeO(MY;A_84{}?1Vw9jm74r2R zmDKt8SQlfvc{3d>!AXnpHI>veuLBZt8hm=Eisois3}z2T-ZSH44FH{;_~7<5s!L#y zG^KYqIW#Z-wI&w~KHA)WWh*4gm{in1t-P&;Gm?6W70EK?vj@3 zJt`Jo{A2zSlEroD9ZY+MowvKX`dahk-We*rc|DzUb<$8#DxSPMo0^D_lWJz=QnYZC zXN>96TjMvcrz+rdhI)_bitIkh$$g)5O8K1Sf>nhZpH!1mts)UO1Y!9Q#ZPB9shiZFEtR$u;pW~$R1<`BPyq4&&)IwZNS3AfVc&7rhmS~~S+2{pnI7-gaJgE7S^p9Z2o2xYM)K(>p!W-c*-QpBetzWA*Ue zh>Xmt>YZUBUn(mrGUDEI&-uRJ_cK@VE`ru5&a4#7?n^no|8)fH$R=M_L*4qie!EoyCA69?)sQjm&7ZV2$_N#yK*5s$3WrC7Cpu(pZOC@t- zt*LUODoZKZel-C~9{+rLwOkjc{k^McjCMiEth189t&&^4gre%XO!b8rN|K(qLMiHQ2b7Yt$Hm%> z=;;S@gtWpY_e18KQ>8W9BAhCVTIO%Hqk^C|(5Tuv1Cd;u@fUOBobzL@N+WzKOM^8` zXVa$?%Cx3?Cw-3#qAODsM&?Eq1`UFR&ye}Cb~{6Be-X0rapi2Sb;C&#;it6m0TPD% zm=gj~zdoRYwrYH3ObC&MK~*5@zC$P>7-Ve0Stm;~J*%2)9_DL}4oaDuY^tivOin67 zNq0NoKK?x#zN455&8Jjx+GS6;x* z9v3)#{_+2L2mnEsHF}=RbkyQ!PYNtCc}Q>nmt$*nK9a$+@4}D&QNQ(?Hl6{TPSOvmaw^`x z^P#fFQBIPMIDVMtQ@!_idkiMRh5{runZOVHKQz4<~p_%iVzkPG9ht1uRM z9?Dw2@=Ktsm7Vn}hP4zGl3G)UgsfFQR_M9LKw2T_aT35VQ%L}yfKfRMd6n<8M-4!dtaDJh`9cBO^TG1;md?5EE)ZXRa8Ua%lA2R#R(oM>Nb2Yj+Y| z*^S%rQr^E>CE&;+ohYko;UN=5mgdXduMmj8^Zm|)cP6z5EdgsCr6ga011=r>))7jK zw$sx}Ro21tVC|LSfi(NxvybOoP-`8fS8*<@U1u|h8k{m{uKBo?7c;#&O&o01 z;~xEN`stq!H}58@vY-BF93<@V`!ff15`wAh^r`eh#(nCAl>4-po46wwBiTeHUEzm3 zpX=7TA9sY&?v?Mf&mQM%w_-1#voneCiqY=qeue??VS~%uCS9+$69f$&wm2H1hfUt- zd3fIU_aerr7coqx!*IaCUI2ugKFZUP!t}JL$)9{Mm!ny}w!94;F_CKEYuZ3a45wsdy3$F}LaS~PQRi_%4E_(VB3i(7M zE#>@4QOBRB#wgqDdsS}Ywuc@%*0}k(JbPRO3D3rI_l*Xjq|x^xMGFRoN=r6 zk%YnK?O6C!1Y8!@8aFy9ub751k6Gi==VI5GAjMpxVsZUutjddPfl7yEsYd{evY4`7 z6YH!a3>+#79RPvZq3mz){st%H`6&cg<5XqR6P2A_0!aJ@qnws=g*MD+4Yu4OtZ}n5 ziLhXmnRKMe)S!U~-b%Lc)^UzZPA>6%uqnkigLG|GAb<382W$fBO38f7UZjN#!&T5JC3pyVE{a+6Lp%E0F*$~iY1>(hO8y01nj z`sw?nAG6uHL})-3X0`1}dY&q+2jJC@GTm8x{#x*(kplbHL;ePQv1B=kwb3j+NDhvioRq551Y}w(* z9YH9_!a9W%If6U<^t2L!ih$0~W#G~E8!=_%*+(z-QfO|n?bi|luz4q*o>sCn*T2!~ z?u4VoJ5-f3+7be1kMeS^=R@U1OqGUvw7u>VN}hf&Klx1Vf0!HXen}*YabmP16eh=I zZ#SHuNZdjU?a95Xu8zDYQXfk#FxEQ<=wl@Pj z1**(o>P|M+&bqJv?s_&>=njME?dYJaa+A;Wt#7r{ky?FNmV43Kjp*t7Gr+V*V?ltk zprl28s8Oz%Y2nia&6doEGVXY)G_o*dW{RomUkg=bER+2`!6f8A@f}_)q$nZ@6|XRHc=LVS=Lh8utjwe#^^w_RsN4pt~K&!uTP#76#X% z@lh3b1YsAuB9eE&f!5XJD@rU?b3Y}n#fyJaG(R*q7Vjg?jw zv&j%K@j_PRChiJdS--)GnKs6uO>mLwbfhRJ!>0w#C;EFKp(JYZs4aHhh+2K-2N!E- z_(-2Ws?P40vnSG8=SMs{tkR9p9F>9-Wn5mlapnME=3u-)ty1kK?h*+L0CY!uQbAhS zzy3)vKB!&@(_AttH4aTq8a)p+KIn{tdL`#z{bpFqHDweCvC5*+A@>L&ATz6^)5<=7 zyi!)1!Jz<9sdMie|AzS0s(T&A7F*+VX_lB8_b4hz!j|wN?o9m(xQ(~geWM(qBx(!F zX*O0!T?ZiGpqMI3$$TUc)YyBoNovD)z>MR#Bb;$YIW6tv=mi&tTw>WfAa!Ovzy*SK zg*{}dz8Zh08eLMevaOLm+^Q~e*FmjCSC`9JyBr~mx_8&`!zt;{EXMjpJKjSosy*lZ#@TS3_1t9Aj)LoI)9 zN>}CP{#)5H7GU)wYVC}9!L;VaH(FQR8=C{)t$KQBxckGz8aqBL=Vw(mRuqV?tOJm_ z$;S$#C&$Mn;y5df*aZuW3u>fGx*iwQ3mDo_EmgpASL}W($;K)jN00{dbY*2>YVeDIA2MqlqHJN4 ziGXGkMJPdaPCBf#bRwkbSPl2frKe|mE0_%x_c0HR#Vt-5nGa=^nKC!C(+WSP7cmFG z7zrD7aDnhCN?~vsbVbT)wL=*}viCRMn?JexkAK0MKWp9o8QwnbQ{1S7m|?+YtTWol z%uq^@m!L|6u6D~6hz!K#FY4`KRHn?w zK6)9np>>JDqT~64(fod?CRufw7KaCCKk?;8`guqQ?KSV5Pe1{JU zH4{9#d-NA(`aNqL4wu^N{@EwRgTI;*??QcQv|C;XCg^;mT;>6QHkGTlti?L-J(ll( zZ}!t0E8Bt9y3nQwypAUt{{Ax1&{kw6_!w#oJic`y4zvcUk*h;~BhL}B5DiI{Kw9|r)i_0{C;i;HSiNf)%Z7uRtu{k@PVk#!w~GhK1x<@wvTT28TYm}NdMP(+ ziD9{m%f3iLL~|@mE99ID;R(<8eLtXOUT0t>ZowJ`+AWf0{Sf zJZl|L^5Z`^q?{50l-1M;jG{+{$Pxr8Q;l@W!%yd^x33m1HrBfCPB10i#LrzV@*Y;FO7BaK|TY-;EDHL>%FolWfM$jleB z>td$;ge^Q8R?oKDzQ>dc$I}%V;LDAB2=^!x^x)@t?a^Ml8(eV9>+*W>bl^3&+R5A? zSL@P*?L`y1*1Cse7ONeQOOOhH)5=!44x4;*P(FEYN*DmZ!3Wi&xAU_v3Tqr=LD*TNuX zy=#$mE=(BWr;L;NnZzj#&eoD1Cjj?;*c(18i@Ej!l8uzi&DzcA<~Q4CPjgjTFJOMe zC?oy7=;#0D^!nGEd|_nktRn;tK1r)gqgXxZig*9$WbIarN)}m~)`sr|bUu_KVCy#{ z#tB;D#Vzrpe}2F`+FJLKL&`Xro>V{}Zi|QSPODURx59L!f`k)F(vgZ<{P5HC@Z(~7 zByl?u0do$ri9#~}av+2B!@>0^pD4!Z__zXq&X&I{jC#A_(&PLB!0LL4ec-K5hZ1WA z9H`4Plk^7&91#5 zr*l9E@k55!aDGq`1yZ{6V}0;xwf|wh|6x8ps8F|Pozv2)!uk* zLV!{dHHA@jb}lg`9gR^=ALr;QT}*Y@U`!BM)}Z98zuv2IgV9<`${Rjq*0^$}fB*$x z97e~w%r7~qH+tg!kH?3f7UP5J>AU6WgKB=RjCPxM;%uy{RG)mB`Gj=Vcyqu9*CNJ= zb3lL?<&ghh%#;@~EZosr6o>8Oqmm0k1!->vOZVVa@5%KY(b)=Cz1x;%!?pP%5X^eh z(!Q`$U4lffe79qi%O;8igfP-t^U(-NSJqFMb6}*Ug7o$RLZCRQ+nYE3ehUD8_}>g_ zfaX>J0F5hPTkR` z#mQ&#%eQe<{2@?62yEUpJ=Zz0bt6kg`p3jnw z-~v-+;7Xj!6+k>lI3lM&pta^ zjIQ5|#!o8Y(N>QSw#C}w%Ok`Wv~$h(BStwH9!k;`=Di63Jf-|+`?}H&0Lqzl3lFAn zg@m;PB-XA+;a2cBPqpWh;bZ;u-SYXIgw-#96it;4Bws?2kV`$0>I6|@8Si)2gHvVhF=p3NzcdMi=<9;__=DdXPnWO z-q(wZ)fIU@uH=_|V$hfMeO`-kkIv7fQMSr-Hc<}1IbcDB_N?hhetaf>y0G3OKtw>3 zHg^`Bb@>VLV(lDEPRjj{(`=;3i%iTLeeZelW|^9uH~b}+e>KJ@Y;rGT%W`h(UIGAj ze$bho$}9d^e#}mI=}v zcvYs;v8?Is69WJ@zTZ53kner9<;N@?swI8ZXjjg4mDOg=N1tb_Zd`;BglN;D?Ck_$ zlQ;WbHd1A#5ir7FZdn+)lAFmmG1BSEihw0u504Bi8ihxP`-LAdU0LiGuv$iY<*>mi zh4Fsb=+)fY>6xrDBXdoF;8pbkYPB65lzz;s4Ef_^c3N3ujk4&L@B)U4b$-NN{Y_2y zlzSAw$-XY=1oe!hxyOL{Pt-+#Iyt zK+e=~_SqK)fBeytKPap5;qa$GVD|1E=jtdTFQSc2Q5DVry#9B3Rc=^q#0UWJ+HdwK zCvW}FuU!DWYPQ5!qT8AL^acPheu1VNtEI`bDYPk!sao;1@uT?kQC<}%tveZ>$CQ%U zNrjv>4Ay0wFiy{&6zIFL`$hw~HaPu29nk%^$3cTrP6#9DtM}U9?OEkoJN|rPhDREr zdUVVL9Uqpmut9^*&Sa2qlmlcVsg>mcBLuW0@Bb@*^ig=#><(82i|%DVv&69&t8py8;A2gGK6v=Y>(j^m$x%fqIOmGF!Mfz>2XjgZGL6x^ zKvz~3W_FG-e2#l`dQv_6aBj2>8hrcJ#EY08v3#bHfi*jmOb|j~b}HkxsB$Aqla7=Z zFfDDPCnzNVj!?oqG9OCJpCS}wVYo-D+$IaTQ+FryBQ`siNPkaRpQD4~G# ztNFR2lx*CNaoA;)ot{?X!-7yigPyR-8+{K`-UuWA;rI5J;;BYg00C8CdOC=Jo&a(| zjlMrE1~;NdKcDt?!*nRQM~!lnlgVkNrK>U{OIzjI8Yt#EYI0bZ-&<`(z>IcfYD7R) zX~PC51md2!`OVg6e?7WVm45#pZ617*9)6sT532D&Rm}AKTpfQ>6sM-uW1W8eWwe`( z%zR?>OZZahv5}bpfNUa{Yv6eaArR8P8>~`@|JLR9=HDBfKgk)dZLr9qbw?i`vS|3x zBc@o0r_55~XJ4|47l7Bs?RY+{r+?NuWV)@cZZBlqW89}-{B(k)17l>c#Rpp)q?Mex_1lr3@adV<(gqFA zJ-YwVoDkpwRAsG!@j-e08!avE+Knjchznqj)*tiU-|ZcKlzI^z?iVsQYq#QJrcdtY zm?t>eF9F=+UrfQl>%Y}o65_J4TG}UZkN6QofY@l)9C%63`}rT8^maq;vE$FPtvkud z!`zRVEKJh%xJR6We4<4_!NKgb>TU9X0$O{{&n{8oi2%LWgyknLX6Zzsa8(wjwazix7>%*on*n{U;I8NG?!qDB z_IEqhI6?@bfs_&MQOtZqyF)E)kZ^RKBLp7(Vj8wYI#LH8rweQU0G~n12@_ORmU+}# zi^++oG@qX-?$O?sSl_w$+IcnM9v$wN<V<|@nH!B zikU`m5Tg&TT2?J4+X!S#PbwtdCp|Ggmw54`w$Rd^KP~!qLdMDPS$Xewx*NNq-DB%F zqVN2J9u|@7cfIzyk8GgXnH*e?C?y-OMCVV6qfZL}=PcwiZM1#w&rTZyFP|$y>qYYP z{W<0I>{0&u@6-;*<_e7V{mTysWB^^aT>MxG7=HnZ);t9-B;2QLejDFA{sQrZW-Q5ZB3^K;mbsPomQO2pYE^Kh;Tsl-q&#zLgO6$igYKiUF8bC;A z!^d%Qm~a5%1q@HX_C}D;lpitdi0b#8aD=GZo4%?ncE8-Gvoi?}QBkWad*=roKW6Dj z&d#dlz*m*+?S^YNqUm{sCuv|xSb+nyvoOk9?Sh0aI#`cVf~s~zmyn8LjVtHI z8gRBQ=aR1Q!diltj^yc+0sxYZKnh7VR)`yhmr)@!&siLmbxl~e>(A}3WYRu3|H-qn zx5g(2H37$8UvGbvQqNA4m(rkAdT{;|=L`Yz;PJnIL;f#z{uLa#aY2@~79lV`s#ZM^ z&o7Jqp6{gyf#tyLg@0P>-j@g`ovjl*FBV2XWMS6OsN|&Lf*N^2_zD`F2}&7RB4WG6Wu0@Aed70}(H7Zo8?VINqvIF3E2{DZS+q=(pv946Zq19uoArlU^SMvk>;7kN zjV|d2Z$=_yILttCNoOx;u6xe9vnP3#8>8%Ci?`N2yvt>(%hco(;iqYp8_LOhe|om+!6%E_v=m34#yC}3S=b<9l#+C;&;b*@ zWy{nw`W_)5e74jpv^RXC9QVlhup%7dwm>rnlsC%aBI=ZRR4e3LS)-g6Faj_+u8eZJ za!OiV+2`CgsWlL_d1pIt#(5ztQ-ib&E&zQttOaE6Vx=uh>#Vcd%G|7`yI|87w}p{5 z9ZN!Ba6@#rgWWe8l#_I%WNxxW-Y(6js=F0TPpa7>RGSb$HyrF(=I84CX(4=y!6?il zoy{PhD&&M?9a$B2{Z`CbW*$^`QNW-+wH1>YV#!unwuxN==Pb z&N+`Kc{QYje)9BRUiq=CI<3^q*lN6gR8BVtAt>);0m)M<3)|fe@z_Hg2RF4(|M)dK zj90MdWpV@L_hSHHRB(DB5!WVHI#oJXI@hKogvpaN%!%0h?njIh#)%hESsDPc`$nU= z=9QUYf+F1`Y;rWC4Vz+oRPMdm3|oSWTFmc<43lWBcGte!96l)k;KsLGjW+9T@N`diuze~^L;97`LS?G{e%yn-k?C*tlf7m_#BHg;1pq+#@&|3G3RL53ddh$en>6adkf;n zeE0Q6qwgJjmg>q@xuJ}t=PKz6#Nz?TaKCJ>`&`g>{_xmYz%rNlwNhYC3L(m zSD6I_$g&%Uh4EHxioV#*UvQXRUW=$rd-C3l@j7p-=AO_xGZ@!0W3@*h^C+^eWM#Ra zOuV?n#Bvt@^VZ$u>3cIm!Dve>ibOxBf+ zTjJH<=pEh9!lv*7mQD1t59h;YMKRZuk?Y@VIp=g~$A?wa64t`WgWO2h+lvT+hd-Mf zewK=W#)g%M|Z#8h}+`u)0A@3=y~t|$=U9kjj+k{sh$s| zAMx3ltTOG#{NX#(-LEEI$R7V1FdowtHTKEy$ zeWS_!I&zeI^x)H!Fwn{gpCTJ59VzC~Dl;g$iJBa-2ILxaHiOAg#TaRJd4Jc#@1txU zIq-JHq3r%oCXCV1e#sCoo9fLwaecwD4(7z#`WB#n?apfrSsEN|Ej7&uUoQKun&`Ix zOtBADgPChHr16`)Zn3`DLTJy2iUs`=R2W(~W8s*BF z`Rw0~t3_{#K@CWWa?W-74E2Nk4IaHH21u3GS?9$p>3OTV12nv^ITwUz>8iB0M7^*` zAYd(IBW0Au5GzDaoO8ywa&8(u@%*!P#Y>)0*#CHrlu~OQ&jkxvzbqnvtW#CZTMAcs?=07{rqv5bj5rq1D|yU zY_P?bz}DuS$P1}TEdcC%BLRRSGsZYv?Kn1InR;1y^~P`aPaoz{Q=C4` znMW8W`BWEk?I(;72x4B$bTQG*HJ>s9;IO8TS}bmh*1(^fR6&b02Lh#6H|RAMHbhv9&@EmKLLi^&=XSBN_uLgjqDNs{3xE`K9 z%rOn4nCadPzJ4nLfTthM&mJmpkaPtTw3uqkZ-4;Xx@2)7cDUVQze_+1m+`Sp*m$9;;N+%h#>Q0|dzqzENdZi=Z6 z5{C9+O4{WWUhG8|cXRvIq_yq?kSfzm5Mk&q*futv}Yt_<5ErHoMWvau5xB_6|?s3u6#uN=Ml1%{vUo{0^#Hjh40Kjm;4^1oZ zI0b;S%;uHj0Li>grASX@)L`9p-X1VnxyL^%kXnl{L2ox)ozI00j-Neja>i(xneKMr z1$1ydGSWsZo{g23HbA12v{h~}mDN~VW*S+{%U8Si>)oPO{2_V7fg{$|jA`2VfHr2m zdu099$CL9fkXfTE%RI_B0Sb-2hZDh9zSG9+7ew3hiCVi6_4h(+TsBqBo+ko^CaqO& zM*F3ztSl`MFvjL{1pv*y?<|z5b_?QdcPmhp!xRg-U<)$;s{P5r-jomuI=4%^)vNT2 z^3~ImPqZljU>Rg@onq7rn~fLJuK)l;7_HN1(~q$3xPS2f*sN9SIu}u}z1=Wua{SfJ zf%nU{Q0Uj0naR-$$gSL`{cF+iWhfYck(S4luA~GqpQ7Cu7j$|eF%j4;(pRe7plR%- z1&q=*X=f*tM@kkpo2vP_93PcYi+}#t;}^cM=f5f1bkW2yLO{I)cU!v=Q3`jz-<8jK z!*{lWB_|Ynip{$*7qlKM0SH087F)6rjdsqt`A{ByRx_mLLz$0sF}onSc_Bjul`72i zq(bsUH8lWm^VeEogGX&1B#f}DK7g$aAH~J1A7uB9#Pg{&HlL^<;oY5J5zJ@M`*ro! zU?y%G^2>-CI}Awb4#VqbqyG>;iizV_a*^A03uK!t0Fnwy@gaY=#hmEJ(Bh zx7t~4k(gX%W);E2A?42N4d$`^kJ8>c54$`_co1_!Ko$1k8&iNsM5^NBzAghH)1Bp+2j29L8g^8(#9QOl=VY4xHt8A+w03x zjytm(#CCGWxALf!bmaI z)04^zsB`e_!#SbES%^AZ__Um9R41Ve%-)-g@j=<&3r7cKK2gYT8XuNnLtw^4I+Cii zv$M)tFv=luZ|z2O^m&SYLsf2q29G)%_aG54LJ68XcDF;y31!q8hdXRG)i`>>kab*X zvy-Y0gtX3!7~}N#iB1m=v0qSO^fA5R`xyuxB65TkF0xZt}Fs4)qdLUcVh9679#dj*PXg zvmFSZK6!829C%f3)^A2@H|j*N-fqA+ZFD{4@^~RFW~xke*y2{%-cDGiraACbY1*3s zILA0G=bAEb)&V6)pJz9|-I|^uJVcQ?S{y%A_NEnU04qYH{dzqb1FO%HrR6i+_)W2PO8i9BM^7J zRU-+c5?nY7)D{6mOS`>T3@;$~h?T0&K-lJpIj%aVsLIw0W8n*n&zf^k zXk~R}>p*)%b}Bm?nciNoiukNrRwM9-*B>hcXRpfomp8Yy<~s-6C;0G&ErE3rTX?j| z+^E!ccLFqV8|{}4z$oX(ynj6`Pc%AEaG%9pK{*hBY@}N2KB4f|@11!eGs@x_dip5e zcqPs!va{{uVu(8;YH?>>HdZ^YH!k&nQ}@MN*`v4fM{nl`A5^o;8W7Blira!v^1+`@ zadb34*SEga@*+OkFYxSc^u&#?w~$u|4n#oFIIp)G;v!kQ7S@C{gf@0V#z=e9&&P@~ z7#~*7LC_RsW(LD>8W(qojy=UpUC6;g`At-ZZJA1 zTWdbTXHe5OERq_$fVS4X;X%>a3h=SQqzDWX^dn}SYxFz^;Kxi>h7f4>eYDfI+EGRj z+zA?7GS(P3Grv{Z`~h{P2^xMI)FM zX;PT*RZ4Pe&G%!*IQTI$(&041ImbEm0%}c7nj?%*Myz)ER0jz|z20!YNJk3IlEM!6 zB6|L;3_27D9DkO*Y>w4j^MF8m+iR}*v(t)lf=RDolj9I&^@o$Ln2%-L7S_1#PDm*T zk1iuGFgI+|LVEtBa8ScxbyF=}zSxGXa&m4|YKN%>fPPRbIh01G1`!_ZZ}Ox? z%c-lTZunH5J}jNNR84si3lbJ2%#WCsHXF;REwEvj99L0W9DSbR8?eshQf>4EzZEOB}Q4+YJ3L(uRJj>k4{`XR<%Olp zs+tmc`mUZ^fhz3mnOvgkSLAPc(!1&`77Wtj`0>eKq-%fD=nP(9=eIRl0$a-pGcAsH z*ni&W2`z1zYK-w|t$Ez99h0#}rN2a4E0)1!YSv!~Ux-gdEq+C3w_0h-(kg91fZt_7 zk0;y0k64-M^JfK6z=XTyQ-djZ)6;56cip;|Y~G3I=Tb|j3Y#8LkrWt4+#LA%M6;K0 z59M=`Mp>A!$r0wBo>l;)c!}w4Z#R&o@gllZ3@jjNpYe;725X!bFq~D47lOz1TzQv= zb||S^Jv~ism$Ra{Bku+%-5o5H+kp#UGCFtB2g&U z*$R@bh}#|xQKqNz(a)#cqtnx>w-Zi|tBb_v72U~2X=WuS3nvP^X(Zx)sXEJDVe1w-djA63|vMDD<)ycM)Tudk+bq@1+ z(Uj@Z!WPIKu~xguVTl1>>o=opqSCQMtj!uHk$xqu1FRlFD`b|LE5tzOph`8GP5T{& zqP|D<+mZhOA5LY8q8fqw6+n_!yw`{}L%;X8g(`sW zwX*UgxSn~9BLFBfJw7UBY1UuyzyA-nDW`aBPzr>S!N&K8|Nh#41UE?QT>gZGVv;SSB2ZYcI z$>1d%Yw3}20ca8OA}{tATr}_qSqM7d)(0zxfN-cK|3K_fFo~)5`6C zi~<>g_y{^HU3;^M+Tig~=^>?vQ9?k3HO-0%$_2$K2bLO0#Z0<_FjAW(5zx|x4eX&o zRhIj-Ol$MGsxaKAR8TZZCji6!qS5z6KxJuVVNnXc`+CD_ck4Ut@j=<$3aoY9qgW*~ zL1bZysm?}97A6}jx`=LBzZn_jfIykn(ILf5b5Ua`lz}r&NqhVtcMgyx?nmsSzc>eg z>tAagewI>7`q!fIVcFUUig~R!4jR0io7S4AwY~rL1PiS8x^F7;=-nyhv`Y1GzjOe% zzSSa>{OI=&#|M>>PNru3pt8BU@y%AF?>+lq-s-V-pY=C*Z=HA7d4Gd<*J?ILZNK34*BViaKl#NpY6;{c z9DJJ2hZ4tA8?Pj~G9Uld@a#zuHaQT2YreA;6m$L4KRlkFRg{r*tUmwohz{-;hgKG0U52weVQ_2 zv>hFkn|I@MTuWm6yFogt2mxJLWHAI0W1K{7VXc#e;eu#sdpkkYR z{TVp0)}9?`ZQRne@5VP;#}9Iu+ia{v?o(ubcEdFJ#k`sBC&E2v1~bmoz9sfU*_C2wJnK2&w5v=}7Iqo-F^nHBJ=<`h3P3ckfrexe)crSJBzIpp#*i2&bp(|Gy4)xJ<+83 zREdDD{s50C0BpV97(Xc&s-OB|b$0_*+ArRjyz=e#Xup)Xp_G7y&Q|S9=*LV;ODF^l z9(M#jm1ro&Jqqq(?fC&++Yw>&Qga)`d{siY6k4KhpLBisWxbuU~?6itoV##b} zjG)>}<_5i`34z9jhZIHbvx5&(0NDFhBWSQ7;SL~(nRC$J4g8Rs%4ubrYn~U-^T!3I z#}axmB#%2HXo}@f0dYg4-Qj0hfA`DAhuP@Tg2bi1@k%^7tiJZ2b+A(k8nnL`azVz& z6`l*5cN0J1=}2LQ8urf{x8r33cY8Cyae7@|Zun^XP!$Fol&S7)2AmV;+}6DWm#$GZ zNcfZYXZRtUb^W~%9YBJFZQV;`u9qLMn7Hn>K=>>htF;@^d@NT@5m1-0b+17fQH4#q z0@W)Bu2q?C^t^nkoOSIDpVB%d8Sg0*WO;K514@ZeuFUk{dWfDLS~-~;Kca+z(JpN9 z*||cr%V>*oJnmD5zq%vJR44@<`iOF=TvP#-jkYfAQ@2+eodZ8+pZ|E|9QZK@2g0Y$0X|LK zBh7*DtV6>JT=TDdr&G=~ArQ8BbKq&|^6^D0e)HE_s}eT9!a%PZ$`f?hmI+IYa1phlFiwQVuj795BdQXWuQTI6JFs@HBrs8I7S zBN{K!06GBp?tiuM{K<}fUO2se@nILx-fnRINT1wS`yW=%J}77B%4nxbTl1F!YgTJt)a0U@BJou0|wPKea7^C!jZ zyfVrb&$-&W1+9D)z(@{38D4bUuD{8tEBDkMw8=ues7Jd3WI_GCWy5zn<_tI zGB@R1BYGIO#j>yj2l?En%A##(+!lmDv48?m4*&e>($b-;MwQ#J#T`I%%~yrdl|z`Q ze(p+(ljfyFKo<6S_Y6W|K2n5$)!-!*%|p%}y2Wj zy?|Ne!X}pm24OnJi7^f}GGT+Y);#QcG4wHR3+_`@n(lUxbOmugEC-0STF=jF9u{k*cM>GreWyK@Pl7y2nK9OFe#f5 zY!l>=9BMd`oYd3P;dZ+D-jh$AO1pOW!}7!0Ri|$1?jc-rfF7KCPMuvl{Qp|t`T}&f zYDz0NuAGsnBQf4Dbtr|zs_=+d&it)!CU5>eFm$!Vt(xSz1Oz&ihqvea!@~zflu86JrEd*tb_{c)>R%^P zfnZgCvlr~WKO63rVJZ?c&UZ5?;{r~_V07*naRM1=tbtot!EMRi4y7lcbBE0--J*BZR z2p+yZljju z-hDlP@Yb9;K|HB=?#sO@cYJx0wmP|Alru*JQVXe3Me_JoKDk@X7yid6z!T_D%!dY6 z&JrMmP1#-#=M($mKRjSWqjxT9Z-j_&|LrN8l5D?__AkUYe=tG;8&^{z>Ya;&NLHB* zVrdF@bbFq5wXJ+}5Y9&?OjVUT9mz6tKp+Gh-kP(fOi0{*E)@zdzS>SY`u2~2a*b=5whI@kz%7x7fY5pKq)J89Ej!6yv?ZIXbyt^e-e* z3Fim}zV+wFyr4-bmX0=vSk3)ge}1e(asHL2)X4I>{`trm`rsR<1_Jb8pESa+Qx7${DXi5jJEov;Fh2Es4v8?pDNauzo3?oftM} z?CnHhLo&^chkFF@;rB<4zLr`zLsDb+N_h3>I{P1Fv%{*&oYJU6L5?-qqGINn{a`k%WPmCZqrGJ)J4lUo(sffn;NE)A0i=ve4T;lEOE8EeksvGErLb?K`cz^gQyM>{|LJf0BCK6?2x)@ zO63i0zuIudyNasPZ+<4-dw+KDz*tQx5QxOQExyS)NJMI6s6}ew9Vsmi@5~Wl@BLZa zQnqr=5}Rp0qPqHQLoA%L7NDVf>Sl|G-jG!2oqx0^k#SRXHloRK)!7OUKFpT$(wZS+ zsCO<$h8vttdgQ%gH?zDC>VeS(7+N8`m(xGUr1w?TBN8>P6-jk4Z ziV*-@e5K9dzhNT1XA!haJ9>OjB0_In4Yt(J{q~@@6O9ha^-GDX{F3UmB-eB{!`510 z3g6oa5z&@so-fNwAH-5=kxy)xh%$4CINmSV@rUnH1dN(Whk^*Vt~biLa}`O6LJ1To z1lr0Afu|31wxZ`{Sp}k)+RjEKLxG6J%$18v5X2G)Z0Unol84b=*;)^DBpAo^mYk)* zh4}bh9>nr=w`i}2VIm1&`}uToTxBD3x>xSs%!nWxR-^r51vyp43aeuK`GyX~_@J~E z=}62+CWu5awO3wibE`QY+4fqXOfOaiL+sa2#tOqB(faX`?_^R1Qu#MyfF(CslwIFbLeb^tGa9z3-Xjt zY%#GxB)Ne+Yg_@U#pnIYJN6)>Ra(}AQ}?3>b(Fb~xOOdh^7%>{GHojz2v_-5L$w;J zyAih5!XOesEMzDq$JN@!#2H`AY@-)AOJ!!Aq5gJA1m3~)*pzd}RC+`h9h9qn4yJS{ za4F_u^ZVh=az3tahSnfx_B9c3%gI`^Ad!HWPwf7OS=!Y)6grY9fC!42V0cI5 z>!~3p1?x~q_OkRq4%l(eJ8BIA=e#LgnK@f|TY4D@6$maby(L@HZ0tZiV{ncD1kRFN zQMVDn;9>%cm~7quVfux?;xPKBzK+N5KK|bE!5QiAu#8f5{nM-1cYQw}R@*N$ct*v% z9{)5`TJ~bAmibOACr5>XSI8yy#7v!~e(MBiC1%H<}T{WpQHEXoOv_s$4=Sob#@T5F2(!~FpV;{#rNLPe-ovdQj{#tCA>Mwz zaqrD(+R-|aK`gBCAO4_rAa;gWd{Ga*eQjHV0;8t#mQ3Nl{VyNtP|V7=vSQ!3-1_2Y z7pRFe-cT|!F85@WjGut|RAe^+KtwmCJAXWVd%p3f&eU8uE>pO54`R9deio&Q+4X7q zsiX1R)|G!fgC^^W%FZe?VLzXC@SM`eVF&tOpDlc-WH*~5>=qwo`d^Ao^V^vplgyE<;EW-m}$3?CL@LlJ?};`Wcn-jR-_RP~tAtgP}V5P*V60-{=VRiH)d`WY&8{S zGOw``{GpPg$;0B|d+6OG+^R zfkI(1wLvVmt~X5SAHF-|ft4x!{s-BEx2J$GJ*t|0UC!L=e{^_qFAowaB+iD$8EW)` z?9{MEjK%Zomtww4IjwIA@C_~{r@N&yK8S>n`0_6ef&a^tfuTg?sPM?!7hLx}Hjfw({0cF}3B~GIoH7 z&4K1X6RxOG0EZcETuFxa3n8(8K2BP?%H67&C~shCM>hw-yWbuPiP>qzctcxxYXVqNXk;=J56$5zEZo z`tdj$*|ewEF2;v%&+U}RK#)jY&{m5x-4Fn0Sj4sXwOEOjWEhJf%$JjLeoDGFGfJbU*n1ix-k=+P=) zO3^#0a7hr(g8||%|S4@ zkN{9?Jw4`%JlrjMJ5k(HY{FRIsK*uO@CX6N_i`p@c}LC>BSg0H8&{I5a5@yu z_@g`X)>?=Ft2`7P$w$h|5UaWKmaHWrnvboHM7?MOR3C-?0^?cU5I60|51wvy^tr#g z;T$Y6rp``SOpH_*CQ^r@nmeH}h^3H1DxpK+9Yu*^IqGa!)nO)_>W;uLeKmEiqH`}b zleT^gq4tKtSTy^Z_uPxGwou^RHzvH#a(rq&v99vP%$Awck>nnSBRg~;Ik}7_5kV|D zYXujf&s0Z^d+^|iOzF$H5o6HaQ9d$*3o&`B({(+$(l^@jaR>LM${qj^@~PFy zStGE1CCR7ek$Jy9dXk65E>}<259S;7w)M)}sE@1h6$;J zr9^b=S_%YVs#a-$D`hGsSz9i0B;;PfYDHU3#~qENR& z)g&TgGwX`=&ZnLLl5!>EaPO;R*DZ~PTfZZso6b;GxbZ=`EDN6dg&v#xpn%Rsm~@oV z@nn9#)406d|Kio{Uw`ene|&ZOS3miI5s`Jdak+7GA(Xw}%8srQpp=+)g5CFK?e&m5 zs5k%YxR}`1S{NqsBew8GpK0#!bbMIuCEmgv2P7`NXmd19&)j zP}H&=1R`j$_I|O1Jw^zUS}>f92-(Omn&1rG`q8+U+QIplsmsO8dI!bKUixf1ZtC6l zGaZNrH)i9*GDsu}bd^8%ax)0U^rR{>HyavLxT8CBQ+hxcT!?in4{m2bxRk@FK&U{> zPO5BVIMFglWp^t&xRrDM=4@z=?&L(U{e0u*kH+U-Y6=M#KGlpHb!^3<05^2~K@%;2LGhn~mM!19QA*pZiMh;8q3%DA>?SNG;Ajv;$ee=l|~d$=$i1QZaJ<^D#qC2XAJF zH|8gIa#zvOt$ZmvVk=D{@Tt-yoyyJYDG@aXfe?TKwqIx{jox}L?7XFlZ=pd6c8NT%7myfJ7+0OBnL$a z2}gHxZZ$Wqrq21{!*ciCnX{xrdH?O{V~S3`BGz@t(KfJD&Q2+2d-R#8)(J}h)3wx3U@CnXWY4Gjd-ld8KF zw$=h6Yla9fPqSe)xR`XeqaYS{elng7tEeHL|4Q%Z)`FrHBLkopKifL^AX^oVZC+3F zvE^z1WuP$fC3v`EoAMfp)`_vrhbsyst0e@k3j!w6s0mAsHiE& z`xO8Pjm`CdDryf@(oxP(+|oNQG?s%jmK)!FV{9vG^lEpZq@|tpK_ud);t$0k5<;HA zX>ngQ2Z4QbG+pIx=cQU4+FT3I5PW(@HmiWRt(>LiAUM1|Up}qlgMzP4Zzp1;TgPIN zGJ*GgGGVT9dp$%zTR9HSWBY=9Y7og(H4kE0O8UhdwSPVWBIl?qcpDWUz*#zdSoC%x zE=Ioe_Xi)bq%$HGw{>F>q&;2DU3(`C8?wmk&ZiqFFmCDH_hy{$$Y{my9J49J5#(AnmgI zmE^mY|HSODV(;E-f1{%!!Nz|qVqGOjrd_@DT$(g%Gk%n44V9T&b_>t_LU;JE99)c@ z^(qqOj7Lr08H(E~OcYxPdk<+xvyp6V31?}vU#d`~T}=R^eU^|{QA07qPKS~ueo|rF zQiwPkS{>9YEe~4qv58Vy<(~JxFqZkmIO8>nYroKZ_1|4PxS25yp0srkOGF%8jD^IL z2L&f7H+sQrSb0lJ{#|<`j2m)3va3?iGPC4C$HG*8{Zh;#FScfH474*I2zH)t4j<;W z^7+hilFaPH*ov~#8o%az81fKwqz(iTY(1ZL&WEr3J7<1F=RVsI0^^pd=6>x;%y%hY zIQBvk5_>yQ)RfByKWQsK01xBCvbzny_Up7hpW{Sprx|UnL#2?A}!(>L^km6`(cbt>?BgY$^bF@7TS$ z?>@FwVHKf}IJoxs1TkofMppsS(r&*w2*QS{TS|i2&>%9S)~isYJ#7kq`L!0qe{5yQ z%;hq397R>l{k@+S^NF1uS2`58e)ve!=Pe11Jd9tzk_si9sVRyqDdHI_UmXU~ys3fj zYVK4dyr;=g)!7QG+;eN~j28+Q$UaUEt9)vShz9`0)CI9%mHN`2Nrplwta87YQPpST z={(S>-F>H+9hp^|f2Im%!$hLwU+j|_ST040R!%~;_06=v1xX@LX_e6Z#R(`nm zHZWyrH>+E%9U-OUgY*x|H)EFyc67Ppjo z28yHtp+jMfZ}rvMw(4)HofqrByd2L=zAG|XyW{&@;tvmp+xN`Y3&3>RmVM;$fD8KzL9!~b$-n;qq*s!Ctx1Mb% zYw@+j?9_}8$|ZS+DNE06D+B_-sza8kysbQQxHyKWE=zL1@p4*B?Q%p%zRt4_Qn7Y9 z$tTtuKO36fxkyE#)0Y=M(_mBJ@liD$n!9g|>!OHgd{6=aqdy<746~H96#|S8$||?B z6T<^h8H)LYv2U=382+mYmrtxQ-j?23Ulpz@9K+4cLD1QZ&guu^%-1ckU2ki#-(R9q5)&p%em9 zpbEwCK`tcjzvuto|E4^74^|Qe&up%qh#y>#saD{t#~T&;NCMQeM2G*sqz}@^d}kGI zdyIqys}R=WB{7hr3-;&&uhflRphL0ye#SvmVWOrd1^}9UtpdTmKjqxzW21uFNEi`J z;aC=Q@}Q_gI^~(ME+8ts7~KQb^D%;AW_2XShm{KJCzE@~WOQ!CDF%S&zS_O{m!qd{3@Q*Pu+07O zo;iGI4j-D+J!76`$FoYF|5)WezdrTLgD6oqzBybr=FJVQ6S4Dh^X?nt)rP&%mi-O& z8~?@m~Cto)6=u3gQ}N_9bNp=E0Aq zhwsh#eb0hC#Dd?q@>f+NUj4PT+dm$g!ks=Wh#>7~o_=tRO8`Wq15wjP2y`U!sWpY4 z9MwwLGPBvps6fmocH?rgtQ1*ZQUB@kES4_mXcdSskx4h099NtIUd-(JnTiQ7wsJfB|$un->^ z5t_mi(&VU|of>9qv(M4+e$Gh?%|V!ttq>SBWjS|ID*NYS6^N4uIjzr~#{P7>XvNro9o?R5E;I z!p}HnVf?vQn~XBp!kyfi-}tkWJKuYXw0}PJCwn%_9kZBuT^b)&M37HSF>|YtJu7Z# zd}ELb1d21HNl2*Ur2r;}<<5%@KBczutU62=?oo|}AR<%-JWjul$~uy#4I)ic)@6$z=an7UiLp>z#{=sT=Q?&iHI>bttOB zaX4}i%WCfG;C4h7Kk~6%{!&|>HECzH-O{0B36uy{&^UT>x}FVB7NTf4@uX>UeCBBLG~S5tD3w3V$WYH(H*dc$QMO^+*Pak8!K>3+c*;_Rea zyAbJ6gsEgM3?j^qD>L@x*u`CS>9w{FP)H~yj%_z;9p&Zt{L9Vk)U01gtnr9Y%p4I- zkIHK9mR0-ULhL>Dw_~xkK1Z` zV$00UX4WI@yxipLRZQIGwKQrf?+Fk``^9Wnaoi1;I^Lf#L^_)xBF+|a+8bdpv#qsYHZ(+ph*j?6rpzWat+I(CtIg{vhs}9kJ1&hL7N7sEje2Nz zQf)k!Mk}||r~mD>gZHz>AebIkt+kNYzwBa6j=UvTc{cYz#C$QQ3=%~I9!LcuX=_d` z@12kGnO(n}pul`;Re&rBT)O@-C(%3d&gT=$B2%ucm;ucd;Ap?7au=pj$DDKwOY5%o zcBld|U#xFJ19{+JTn&t9Bm_oHmCqc<2-Z>{0#i8lkOd+sAZdt;uQr2J3W2LiQUEyJH@YpjCQn** zv(0CoxiGeL^Hak@zqqNG1S+NQ?9~_wZ^>C7H&ijTUZqkm#YuA9^W-C?YW~q zWdWv@y0oV*?aA$-pSDCl6VXjKk3>IH{U0*2KRI#-ckW^<3%VFKv$&-uhh=*!)RAOX zyN)F-6pO2`?smAOc|PWz0SL!;%cUYaYMhl)3}-)GU{raj#q7i^%hzz>9_t->qUvcO zfJ;p-|CY1Fx|7vbj{U-PAeQv=Px6u)ci+ueyvFZrE4uPphgAh>SF@cz3K;K~t&NZu z$zn|2kP3t|WD37LMc#t<;Ho_0ERkKW-@KxY zYl+l2J*h??etL9ot1A5Lu#$9n<9aGJvJdj`VU7TYA7-s>-C7SBJbs{Z-7D!dRt9+skbt~&Ula5;DWQ_Ubz-R)3^g3YbS6Yq4Vy9H1^FYj!G z-K~h%G4^qPhrGf)zr<7%-er5y8HcXx@*0G>tE_dskDZYjzWaqcH|xLwo#dJVJ0ZVjl2KqXO=et zCgH&OvNRKcV)M>_`N8k~R`JKbmH+u?KbQRP`S1mygwmq36;_2yTI$>X^5Jr;n~#ms zn9r<`!aGp%BssZhv47FKk{(laBJ9j&9F| z5IUApBOB1HUrL3-GIMNhIy*H{x}b(4R=H0)3JBi#c8v?<))`?K4xPZl&~AWvZ` zKm7j48A>{OJ~BEIjh;?gdbC$ag*p^f?mAmx5X<$;iI8IBa#H2KvlS(6{otMHn}2q^ z{X$a*;{IFHMqhhNX^MHi*H1USliay*Mgt_57ul!_ueR$o>Qw0n~)!WJ1v`Pc5#YY zYVW<-nVexeJpZ|-(s<+RC(r*%clBudSEJtf==DE1obQ{-{c8W6Z1k|){poD7Tdf}X z&MOTR_}*Wfs6=eP*l?D9`lm;G?`2P=t}Hp{LSl{7tbC^am6-3TD)$d=Or0gpZu5># z9_FjEwMIAKF3yxbZmD~3PL|CoZ_Mmwy?Ox4fuU4_H(($LQ>g-Rd@py#hlzaa&yK@H z#x3=|f3?e5;7fp@yA@WMt8(933%grU+*HNP$wx)6#Y7YYA$A=XPBp_>iqaTo`q^%#mSr)Up zd(6j{u>0YTLF??8D_)N4m`2$^?}N2#EvW zxkq9Xv@&xWmlIogrpYWFEthQbb1x;6{W3c+qnqW;Z;fw%Z!$Z4dWDoUMSn~6wu0r( z#hoY9_!lId`W{=}d$ywa$T&ydQ5`3;C>wY+;M;XI5{MjCxqJPO>ScC0Dq}^qj)XNd z+AnKNXW`U|-@h2o$F+|8!mBMl+cHK*+=jb_t^DqLGd_SzueNn4K!8vfrmDzn?_4YuMlEGa zzji6+_#ST3Y)Q7FZ0xM2q^+6TyR7X{z>B}wXA`$`FEy(r;*StF6$+3_O!glEysrIR zr_t3(OOF@)f3~4ro}!Jbi4e#rId4*?AT#j*u<>%j>wZ}<*g;W4A%c)%_k&Dn^aN+J z0<3rOORu)A@c>xNY}!%0K6^*D^gA!6D3C+D#j};0X;%#{#GF%M4e3ynxoZvr2I2`I zY3n7sr?C+#Eyz=uxhi)ml+&ZCw-d1_Pid4A!$h9k&tLwfLE2VK3G|-42X@OIA5=o3 zHPqjUIBp35$-qPvABJJwVM!?zU9QHy4v*W6_9ht%->l{3Dx8D^)32vi_AthUy|6L6N4iiD0O zAq0txJ9^_j8Os@fZ87!Ev^>-rsq#+30DZFidMWIPC^f3va2KTOjm~)-J~5{YoGf zGuJ;Cg^A*ZyjYlCtzC)dW3wbf@m6a}U(75Kn9>U+Pym}c{Y(HBx9FpzN7QX95#4jq z^rRvW*=fZG5H{5AyE7pLO0*?ag=Zi7a&Cva#pJj;|EZ?8#KO|$VVKgVZEXt2rT5zP z;PhdUv{m^;oLn~aVM7Xm?e&nAs>^1WJekrXVmWs#oa6>RpBQFZF)y{qY-cl?99ICu zf$vfYRzEFjSI~BnF?Xx_!T$L;NFJ$$+^C^dy0kQ7riHz;#W{nN1yqHy_X9b2U+ui9FMb^W zlI?r?;@1IaIp%4HUtItE?D}v2MeqC^07ko|ibOH9&iHcfy4w*DlvBt1R6emsw~Ckk zMjsGQAC}W&lTYm7t>VF3^VwlFJ2KlZHjZxRXra}W{I%3bu3e00!)iWxrVLf8+8B`t zta!w@fINMKcj4etQf5|a@l-++?}Mxd{G^SxfYu<)hAvFS64WrIV8 z(&_I$Z~w>b>c6$QKY#u|3LDZ@t@~g9a_8_jHXr;~(;I(VmcQ_s*8k9c?|&ZcCV)W5 zp{{u6^~uKbsWW6s&#|o>wNxXdi^qp05g+^NY=%PCiDcXkn93(D&CX@R-Gad*?ghM~ z?snuVvc|K(+1XkGRTYk{4|xsWd9e|uQfizYS1h^UHEM7n=BvYJY3q7p<7%oyF+L~; zmlE%xDqQbeWJ<3B={>QhE%U!NuczME!MkBY(ldw&h@e7|*E-*`wPMi=NF7SYC8YpB zh`LgQsY*LaNWA~{G-~RoAypuBBy}K`dy+49;JyD8zW486+y1qk>ff8Zb1~_adw)*lH|G^eHYHx%p5UjCB2~rF3*6+-|e;okw z>J&kI@ZkUXYauT*$sZ0U@0Hcqx-yM6$M04|j=XcHviZaRIy>&{eK=Qvu;rPfEnlf~ zFEz)9rBcZ3*2!_nAGmiujv7h@0wwBZO}#UfZ>@){Xbod=bPMi&Bbo0%h41o+`w%|< z;Nd5Ovgir@;3q=!J~^!QQ7XcZhOk!gvz7lXAgom?){=~69`y75?I4o#k*NyT*$SdW zqQvP@dHHkgsHud&a%P>OI8_hdoprV%yI_9CZN<~MGXcnp%}4Y^3zyuga8e7F@!$RF zB{k9@{|fyx3qe3;TWW ztgq1xZ0Q@l;QN2D2LSoh3W=>jAOtqLdZ`g(>c?k)b7OK`sX%`4-QiPVshw9EpZ?Xg z{kO8U=i^3Slc8rxl&qogi7hh!x!>A2{2*&}uJ=GWI#6r8|Ym7 zV(0!3CXcy()n8|5+8Jwl`LD11+S;36KX%5m8;A;o(!!Sh_}*N~Iw$}I=s?sT3bCBo z)>^PiY_1B=8$;Ys$;y;S_|I%vm-?4Ux-J$Mc7o$o>p4C_nlMkXzfZ8M8bPw zJ9%zzdgme`5a}$Uj;+>vTai>ad{FGX(1=?qJ2g5G)8legPjv33W|7&OKOFO-Dz(U` zCP-y5v+S}|GuJ$E|S9C0knZ5n`#1t-{T8?|?%{Yiph+B=0PkurR#LJU>*U#bun{s zOCsXYop}(8*@?-2sM}&*MBH z;Ed-wn@wK%UoU;GeR8uf*(c)givWXETzRd{^dB9HdM_hbotq)TG8>WQJd@*!SzvA@ z76ZlE!#_Eymb~7NAXoC6REyf~48SsHk{|NW=mnGGiaRTQE3VA=dE?e)dQwS+y9+p* zJT>|{O4V?;IQMdssYXvVmeMUDm9Uj>uZJ!t0J!kQmMJ{zgHY6Z|3**$^pB1JKqrz( zth1rvH{=hVwAKF2xl*`sJqZ#q+AUB*F?C5xO;4(9WOy`q`k*-cV4m$)<9$1u_?LgF z4@fBR=x)CEZeC3t01VE@LIGn3Nn0%)?tozJQjCZMaCp-kyq7P}ST%Pn%voZ5LZPdC zIdQHc6g6ExJGFeY&eHC?Qx^Fq9nEXjV!8u56icN5bC(VmidX*Y0MP7dZ^?Tyr7QC~ zY{VHqIj#m5V*t4OqZ|M_Tj7)E{FndH7C%SxiB*9BB2&2e#Da&osklt9au+0$nUVys z`Fz4`({k>B01?JVB^zm*!UwUE8UdlR6$u3>kRJ`Hgg2h^I>tvOW8XaHFs=; ztTZ~qe3RPqI7n1BG}|vUo%Nl~Kx)td<`Ww?HF?OVF70S$E3?uHrI-y3i};+S-S=l< zL#EvzNQBZj9~+*6^v}np^3D+;>PXtso5J(X5;YY9mUEXhgia)LD#KJ3nF~T;N+&gr z56gUFkMHGw^B?R8i40KcP{b|8NGk%dTUKu;V)7R=t;mzJ01GqV*&>Iry%u)1LiWnA zm3Phyh1uA|EyaZ#IXc}dqoxuHhY#|#O9^M`0zjj$SIK%pArC*+uO?C=5J-tvKHrX8 z>c*d(0KnSyxU~_^PE7x5M6ULOBS%3ZTk9d8MqB!%qoY(+#hD);hg1+z+SW|6TWUPp z8&NrT?Tw(OqS&(~2nCWOHrv{HskweRmJ-XkWr)NSKI!PAdvj~NE&Y%G@K6X~OXDSB z+!|7W1YgUO87^_gdk4;VQ@9`&!-oYRsAu~JJ$(t~K!ZnH^jCg!EllJxTry~gFqN+I z<=lHmJOr&>BN52M^r+I2(4jcGJ7?#qWrNM`<{aeeDhgW)0OFSBgtg@>pV-!xU4MkX*4_xS zkzIBMvlAnP#+CW1^N$P6)p>uvdal-?fbme18h zDin-#Gvz;@T3IVye3`i$-xx~3{-%mjRFU8|s+ig`KeJP0LnvGNNQpZhqO8w0SK>A!H;tx3SDzc50rAl;J0S z*27fU%H4T=yr^0c0oieHa50%4SFR#jRLI?}C~a$&g07Zcz3s>uFojn^J(6q=!i_7* z2dj7vf`OdsN+#CLIl-(U3-8H*S^TFlew=V&JD^nE+ zelp2ZIvB;5%tt^Xj!bE%m7N+pE6vEd0syA-hmXoW3-Dfv_)hh|diiesG>|FOFj3WY%;g@mNTCaK_zuhsQV-Tlk> z?SJhT-M|vO!UYxSk!-%DLDaL6C3+lLq9=hUe3q2&qu-96(0@G(oT60$*OpBkgR{E#>iXiq0%DHY-cNEv*)9`^S}JR_Ab8CQVNgm%!d#1xTP8$ z{q~<97nwcxQd5WG!|#u3OGrW?@$MTFL@4KuYs6Q6b$zr~#4Xia3x$O7QDqBSLN8HI z>PP@W5Q>}M9X|<6ZN8Msg}=td&$d^YBdaW}bDwJhf(o!bP;pzXUruiRaL#T=gGUTzK>L>0+Dw0{kNt|6zQd3=?eh_Sj|1pOP9ZR{ne7LipNmZ?Gc6TM8Qz02xuL zayQ;D)rxK|NF|rK&UmTC8(%xB)xe^r8Zqy8a4|mf|3X;i83~2u+%acf1%e}T)2=q9 zYxDyE^p~vLOFti(@qRfu ztW+qxrPIBV1DlpBX=fu0qB>K_7Jm3JmlE3>VPj1__vP;7s3K3zz7`7i-_2HU$KLs9 zdSarcCPEFEQOI)dcF6L|G9mP%k(TG(%P@O9we>JwWTzq7%^=sb{ z`BB4=AeP?JV+a=tm3l#LMcxV-kt%#h1Z(R1!&G;Z90@Fz!ZKy zHc>+Y!K%*}0+6T9R>-j%^NF<;sbFE?SWz*vtG+EyuIexSa;viy^)IUzzS5hI%-}){ z1o^b?7+Dh+rbv#*&xCIg`qdQXU`q*xZ#m%h->CpK;>DG?E! zqcD||gAx&Y+YtaY2Z61KvvjQSRpBQm)!;%*1VJpKR7Qy;4=RvV?h((7TsXT9g8lCZcrL)X_euoNk*IPXM6xQJ zEj&fI;J;AZQuC2PiM#J*92A(1&81gc&H*AUNx_Y7z*=lx7P6s9J9_K6lz}Q%#&H$V z*$7wbnbvw3#FD5MJM(H#W-e*#Y-E@NayB%Z*VE~7$$+%C)aYqb_`$_Q2uwSg zCBV)QlhHg;b1mSdK5ENrU+zkU`PeiDfwh#hH4x-8x3uu*kgT+$r9^M2(bMhqFo-1z zC^MV(0wIBIcXTAG+@)R3V!HXrFip~|_1-!N{+aR98#u4DyAi9i5wwE2FQsvAS z3C=pKVniyuDV_af4y@*SbcQf3upGLsKu@EOjJqv&SlKD7nteJ$5jYdNb0TE z${p<#8!yy@gyERPs=2Z-U*RUa2T#En-@6=p=g;hx0bsmirvptG@gBh%eg^aQ)>pEo z_ByxL_;jF$JEh7k!sBuFLn#nO#)qoPJ>|AcZ9XxN-pjD3OcfSu^4e=*KDFpWQH9l~ zV@kTTWm^5m*)7Zkz3^I{J|VBD(v9}?(c>~78(ixvfFl9a?A*lLvS=rl>e0&it16W~ zm2PrkzliF5#)w2OFn+=5KzrvfG+O3{azYtVc|}sQ#u?@IJ}&k@C__QN^gAow`!aRi zWwE#>>MhO%#WTYCD|Ki5tbo{PN9D=uk|8z9ZqG#%&I~?xWTxY z2diDJEpTI89W*Q&Y%pFEp4r@1kBGI9G6-TSA{NAK^;#{gF(zsMVTP+Y3V#b1qI{FZ zBW?fyAOJ~3K~!RZK&>qS$ns|FJrt=?nUfI%LcD{;%klU?Q3lyaJL{|Sh==w{fNf)V zlAX0$lj>eLZCN%~sv>dTjZ@7nrr%ruwM zOs3|6<0l=ZMdl_)_N8B5c=+z*`j@*hV%E6*yJ=Wwgg`biN9l)za1UOYNv?(z*w0i) zC|4@otrjgWzS2qay<82n%`f!6Y)oowu1z}59%X;}x5=abjuO&ck8b_tptA71P`~`? zCS_#zVcl&>3%f&u$3R+{)f!)Pjm3=rvP~2 z{6L{UV~O&oHLQP|sGxtgkLtAl>Xdx-(*upIWwDEB_YNHcC$`^#ct zm?Vso(VoJsd^*&t*J_NDDk|@xxg@o6I3wz;hP_KsI@I8wROPC4x3gXsuHF@KTL?*! zW7XfvFMYZxL$>waq`4eK4Sw(-o4tnSQh+ak37U;fKDLxrvkP>EAVedYn`X?sb(9gt z31wtuGZq0odR!RgM8J@*2>|WoK!mip7%W{$uvE3y6}P@K=&Xf=!2P#JGGtcydRI>R zs+bz19hYS9PL{MqqbJe5$T*P^>#l}2b2D-0v%j^RjkF9IVKC2!s$9gI(WTEcH(svY z`u3o{DqAbT-5-tMiC#h;(Xh@oUaL%PpZbm7(N4LvA(l2oZ9f7Z=&}(3Z7v68W`mgB`Oy%smZZyhK(D^u;gbBt|F*UHdh76hUcDkoHh;cF z8L`L6lF$F%$_L*(r{#D3(yGGfz#YAyvQouPzOY7_y+ z$+WNWUv6##mmXPACC~Rta2N- z#L;$+v>InTZjOTniyAx~>JPrt@2rJ;AE)>xjP^@!JrAguYYWXry4qhFKRr&J809cK zQ18m=fhtE8Xj2z%wm??3@pDM>`9*Z5RdGoP_;jG(`WJ_1;6#*?=5jzO*0-G>T*Hvzcs>*0-?~qcOnx^j%;Tw zRJmcCdhd}oGC9<}i?J@<>a|+b5O`YXu18e>Q2F+9XbSr@>8f#2Hr8d(z^+DLj_u@u zTDlU?m>2VMB`!0^H~|lbcQcLzu^qegTpZSU|6Y!7{?SgUQfrl8yI#X^UzysV$p|BYSH(R+ z!h)Ff9~QIIng}TVnpi+(#8hgXaaDf>B`R~aaIgK%#p$8OJIk7CJjysB0M>d!2#P+Z z*kl9%AZZFL8&#?8u7_Ajf!>G7fszr!i|Wc36A{rf9QO;aG|JS3HP%=NxTNisut=>g zojeAE>6BLi=_>&(8a|rr> z87JU*nF-~HkgG2ULLsQJkN$ETH8_e&7)k;l=}=*~ zvfh!kwg3X7J;fw-4vcm)H?9ci;e))n7@%BI?+6}HXTe)vObj6qx5VzpsdHWxw$ev% zS+~BiC;=eu2*znTP?H_qS`Fy&z#wXH88PHfj}H{3L>CU#%%9H0IToE~X4RR~M2ELr$d(wegD3B{BHT+ z%{+*i%FNEKbcSlB=9;7VB-<`^g_0zRmalyOM6$8jnNx!Z=?RsXfK|S}F3_m%&^@|e zrboJ%m||jvyJcA8_|E9mhLkosymdiR4tSP1D?>aN%9!O7J?-l}wbQXJlndqnSjF@- zZ({z$QFI}>G-J`LY) zjUT@IB6uj&XqxZz#~=2`x6#=ITiB zxYXlu_Go|j&hF9M2gCP{ruVGVoyIjvnbMOQUFYBXJL=Bwd*`)sDzo@xJ4J6ewwkKq z6FKFXps2IY+uRV`2>=h@n^b$S|-C$(~DYCH9PTSA76a!LrukaaggZ~fteyi6^4 zkIO3nGdhzOg)_H@3cf;nW(G|zP z7!L$S+pUwQZM`sGW%cV*=p z3ym9rXvWcEv$O1(0)Qmx9k73Ja>9JA&IS2}|7G`P#eXC0$%Em0N>4)BcFt&J#Vqem24B-{Qlc)u+y}S^1}WvYu|jnlZ7+Q>|EYAC%Fcpty3){&HvW6weuHN-4YwefNtZ#jQ_=JIn6EL@PB@j=2`D`C>;86nB@WRwT`^`&BL(98$B7;nD-t%qJ)vS#V3af2&_DxByIWV{fP+K zaHojdvb!D;O76TdoG*_L+Kh36C8oE&J%H1>xUj`u`s=;BZw@t(yhPTm^sg{ezhYb`e%Rtesy?$A?~b2v$C5py7{@*yc=cyagTqc%q@<5dza(Ec0mY;kllN8q;kh4 zeejd9(T)o`f5(M2-dztFr&f6;Xf`t4jVPpa^ze8G;Naq`4PDs(?;k!S1hn$4<-i&L z_|_EBv-regf)Yl$Yhik1kb6o9c-isih38smi&+ zsB+)5Rsurc;mrx9u(X+My*(a3QiD51y(@2j@8}%2U_u+~5?|d+x+)G04M=MxoRPd| zftNG0J3lurLyAx}RU>l;6awA?YVLTvnQw8LPp5K8J8R*5iVzF?o?JQFYvI9zeBok@ zDWv(HK0KGsfAZ3EF`i^};dJ2;tfLASH^qsi@!a)>5di32h_G&T=~~PKDq}V|RMWmb zyqAjxWsJlv;k3W_sm98++HkMD@s(~qHvNYgA+UHkE~gg9#rfDEMLURDF|`X9BFexT zH{LI?p?tipW=~ofGejCY=f~TsyTX??#HW9yWsM&^D%6oJj*KoHq`o|~qX%VcIS?T$ zr-pHQ`LoUH`SzuD4g32R1GGwE29S#iKlS_<+fjp4PBEj3M{ZTvxFvd*<07kS7PNAB z=`u+the}8iH8>*n<^`;ZbGH^|Bf}*n)N?s&I|1+f(v?J)Rp(KyEo8uY7o#)3DME;h zS()3Y&U9hN2PKxXFi9}UyYtah1QgF&aYFzB)O0YhYm^)AmRJ#MwI3fS%1AcULCi$J zMh7L@pDCjVtR3%`WoDiABBU~6*+^r*5H0#z1t~KtLTX9};1{2Z!-mjh)eANqXms)tfHE^d!n_An*nF&! zpXfbc;VgKwn9?CN?Ec%MjTalO{Q=x^oMUvFXuj<;Tfj1V%~D+nbB8Fb#qZ9xc(56d8CWoD2JjVzeae#s@pDlw;h z?{Z8Tp$v@nGGfkw2D{G@xL#UKU?vp=#)(Y?q7Ev7~lHf(Z4SWrq(%%zlckv#`sl^-9J8!y!B zUAccZwb~n1A%u>>8Z{sU&&K$OZuI0C;xYiJkwYI1ww<6%d;)~V&zYN)IOmaBUQ8_) z)EbZS*2DKEXi3urdedyy*Z9|;`?)4M$kwja=50Ry3GlfHs5^GAgNKdRY5=hIsoIk< zt}teuC5{=x-YV~{iSAkyB>d=3QI4u_AzN>7odH0$r}YycGgY21sW3`Z=9V`TmD_qpKGotq zrxx{|(w|tpt1-jRZ!K4c-`>U88MppI4dIEMjqt>9fTYc@ zez9|KKbvX67hZ1c-#HY2g8xQxt^XTBax3~Yf zK2|3Mivd8JtW&>=e2?U z@=pp$&wgjl5ha#`Y^001vaKK-jqT4Hjb%GBUCIBxM; zTk6tb^)1Hs@$ze}1VG60^D&pC)|Eh@V!#ss3f_4k{%ez&4!}|*_Hzvos9K_jVgX+2z zJWj%;`g7qz>&2DMXKT?i5R#P#p=?vaw8=_6DfBQe`+0eo7W+TG`}dU@+2D{;ap3>u zsbBo%c=}P?I?NQX^jML^~FxoBJ%Yg^9;(KkET zTmYcVjB~!$5sjYYl2S(7t0CTRx^P=>o7?{~&=WGRUd_o?=W=(>vt0S}+)rnsd*1(5 zRV@Ek_$+_U&vM!i_LMJ8p7@`qS+VBp2`M4I6no#>Cy+5(U&;4X8&nLK=KDs$+^a3I2bfAs));LOu2Ir5u(w5l+XUw?1g*p^O5duM3j^9 zLD^UgM8wcvee;`#8!y$Fpl|(){iWw(LWu}zKCzG9pEec)CTS3JCI~p_u7_OGdvA^6 zrtkn5^mySHI%Q^8uO~XUjFH}@=)v2SMneVp)UPh)QyU~Ktn+&_Yt`|`E5Eu}PV}|c zJD7RwUW|Z%&Hb5+wD)|ZGRq?h-bXFI@=}ceIeKE#Q>{G-osH@qzgs?fFMC>+5X(FA zsVPzuH^t*yQ+!3y0$;gWyY{7yG2R;AS_{I29X%)jAZW6s&DdE$x(&X-{&|Xm6BVTvF^uL!1hs1iUxO zc?(!FJ)`DPO7e+u#sMMD0jqX7)f3-ZPYCG3tz4_gfaS+U(Ok?uF^(b0l##|laJZF+ zHI74m{O(bmJMH%GW%Foplt5i)cV)fYrIu2wk8i3boh8g)1l>uBAof0J)?( zcTXT52;-#8EtfQ`^C025!>V=JPc)#?@6M&`7xPPxWb2EyBCQD*AmYi&*L^F$-cPE#} z)1K|tIPg`z#-Da+VN;|&KBbHg)zX!CCYa9A9N4*_VnV9)uAkfIO$WNMAdzNx3RvcV z(34AIc{4#Bq)hF>hvn#js&%A{n0J0*BOL8309e?Fo^1G<1%Yc_IqB<#t5KsTi-|#u z4rV<%>mgy}_VH@@1PP2l4NZj|%R@88U~-8Q5DE^wwyv=#G1YbWFb9D38?|g=^0C?cVrw>Q!R6*SBj&B~JfK!NES8y_ zJke5G>q?|~n$m`Kp=YK)3eNe>&$WhoWj?V05Y+fQ%NYP(`;E3Ptx<0EYT~UUlsE_D zgOUr1SDmxoIY0u}Xs?LseDQJ=)hiB>$}9m;xhqp!YYUVWvZ1bqLlL7CjDqNuwPPDC5LCzj{3x?UlWY(fB~kw0@Z|mD}!xkTHURV)S%d zaSM^AK52=t#z*@l7o?b)?OW4@%aL~w)ES~e zRc@{E-T@Poax!>Sw3Y+#pbH0tpp<~8vfjmbysug-Apn%ALH@C~Fde9JYKo~*sWr;y z6VtmG5rBv9PjLQWl=H?r?}HXAQbSqwV4N{4)^60w?9}s!2h;m1dq`hrY4qO%sFqYw38 zZ(;LuEv?-6;B2TR>2bU}y!T~h@tXH@dcnNR;j?Um_JTZQ34V+vbl zR!x0SW1Y3I-V3G!4IaV%Z|kUU;>R#+=KaZGQOYN6$3)69TYsF`B2C6Tjq3 z5y}?xC!zz1_5gr&-ViU`q}`Mx3c>9&`2b=;oxUt?@qBE+0p#En5K30B)o_!>1L~~r zKgw~Qfg?Suyiv{+4i|#%W;l3U80Do>a%_<+bXLI1>{Ez3&S>Y1FH-xYB6BJagr0zx>Ie6qHIT+{)LxBdo29VE zkT0=!C#^5YV?#K}$7Tld4+P~Bx|ex#G3c&`7({T^Uw*AsOwE&51(WCBO+n1Sfg`7m zB*vD`TVu;fzCF!%C)u_(`R?GYweIHuV5VdZCLhiJtx}Eq<6HZqcRhGxi`}EQ?(Y8C zVDhofi^cIbmL~rrc$g2aUVg1Yjy|JR=8Ps-YfBk1ob$~*R=D(}$0a8-=_hIkXT6N+ ztQ>Z>@0t#kE}gaBJD+qU5Xi=6v|mPzD!*Jz^z!qGcb>or497dKl_x-O=;Ex8Tbwd7 zK2*+mT~@n&v|X#rrbCU@irzyxwI{|g57pF%5!qz(*9`K=8cTsYA!K2d1OR}n9hYUP z%-(%-L$ z`4|hcu+i-H_m8TQC=a{0)4e-)s_#m8@9T$tryGiPB-@m*!Q^%v^o-4wnPkO&TI^2p zooTUim;9sKjo;PrhiQJ`X;H=>&W8st{d~g|_QqGcJfL@eI9k10L!{K!dt(_h#(**y z>=Xb%Nwr_k%RYf)kH+te(bPk!c*Y}al-?gs?vAppX}&!z_XhWNE-n3HD|s$is9*Z+ zQQ7@C5UsS>&5HeT`f!wO#VVpu{lPA+z&ybJi2xzuFb&+}aU4DuP7 zxvyqR1L0i}!#9_K2zjh<{R1sJ)1`%m^) zuO*C=dvA@-;O(_?cnS*Z)!H02dD0e4kbGji1EV|->7=itI!9vYcmA(Ob7&QYbPq1+ z``_wY<9&6^t{hmVbeo@RaY<)Ju;u3yLaSw;5Rwi}(&D;squtV!4x4@YTX|(Z4=GmO zHWuXlw?(T}>v!x>hM8KNMQbr6951XHFl~eoh=49bQ#2FC*O^zk4_DWb;8wi98 z90!}u0-=@YQ@J571h4+)VrwP1{exlB7H|LY-r|iotn)BoUZ4Hde)d0Dx&Nc_7k+nj z_rvt1Z!E0csO!=`erNL3jCX@Y$#MJJ$nV_B=XYR}LyZqX$_b&+yBL878PUV79N)|r zf4Mi<&SgYJK)>}5w=RFCMR_GWUHfW>OM3s!A^!2jZ!E}&6_e@!-&mEM%OMaD4Z8MX z-B@R>8fHI;BDF03ZNK zL_t)>O@U|os3~;mzWskb>TX0q%oqn%*zQ_HD2xvj1}Ic+b>Uje!Nd2bl#w#EGG(T5sT`4^;+`i{b@NhKC5^=&iVNrvsO-*78|&|uPVm4r1;6Rq#+L} zZj_6Osep8NflchrPtyHc*>vaB0`GhU3Kb!h5zQxh-gq(#w?=i2E3WsTayuPpARr=E zUyxyqH5P-`a)?P5LJ8(yhI^$9DPg467IBjg9v2Ay7(B}3ra%cS8|vr3(waT)m!6A< zJ0%u7j*giW&7PDY+rO8gol~WjF*@^4b)OG;K;1DYs(mR00NG-wUUe@-<=9TQPwnuQ zuEz7tIOnFPtMsdK^XpVKRXelCRZbUkDCIu!uE2&1B$RM{J8jP1Aq_)3m2jy zwT+&n9J~k0fyqj_$VS>Zj|vf@k+`Ikg7+S^MU`8u2F^yvq$ke7bf9$U%G_bZ-YUl> z%|@C_s&eNY)LH^72&{305Nr%gkJRK)H5MgS*F_C6?Q2uIdb?7cR<6~o@ekjhgmoU) z7`B)vEdhiaj|zx$zDO;X48RweDN`#WT5HR=DUKeOjYWx44qn)pk0X?%M~ZPu2pHvM z#N!5+0Y!UbKCyVPCzPndB3B4;D&G03u0EQxy}Nv^W8n4s>@TtS<;kDhLY`w7DGi zE=A}|!niUbqJo&>B^1OJw1`x2afhl|XFU`VLmO)@S*A*v(MTq;p9*o?eei!y*=w~KQEVux4_!<+W0B-Sj-orjknR0vz-+llV!w) zJLU3b!X&FU6}dHKCGBNXS7bhE^W`f^|9I!K{$jn>5j(fjQ`je*1n7E%hq9l_{GDw$^NFUE%-$#*0U}fmN1O8-dqQA*sE`?VHagG{gg}`Z z@4zZoOf9l0f|z4lV!amx5u=O*HO3{)#s-T-aFm5Jm1$p7O1$$y#1NK;&o^g$J~8>& zq-D{$3;H!+C5#m=|Fq4*js;Y_;6)bIiU-8 z=MR65>*uS-t1F!|)|Jj{>$I_jHkq+SsVBJ_j$lod0)vM|SmS6aP7fLYa5TMhavekUR$h7iE?wL4;Jvrq z#Oe`S5M6(`lp$&p7wV<{IpWSbF5gTIz!FU zgfk_J5<;L9p;}Z2>!<}VNxX-_!#rtA>-??n3{>XUZq&IT*~svSMs+SEJ=!S|4svQZ zFDXuhUFef0iBMpQ-vIZf-*sddnKiWOKM671TMeU^bWB08#57G?@TZ(*<23F+yQ~8 z&Ke5=WdsH5AY!Vp`PlG)5>BJKz=-9e_osvsJ#lEqcMwK#_X_~vF{6|;7vzWE?R)RNg|NoC zAn*RGgEK#DV?`znwtPWc{X%QFTP{5p7ZbC3qjvAdqbr|jIq$uL@BQD8=Y?s5Pi+q> zwlY^2e97{m;p+?0`|Et*S#&fVVKbhKMyMc~%E`AdMZg~rXs?9MdLYDV-&zg`CAivI>&wixmL=n4>zy$gve09wOFJWQ zQ(lc^Rc`aC_Ra?h&qkU6gl&fFJ*DLS+haLXrUb>wIj-Wf2%#<< zlUQaJTeL;Uf|xZHr1yURUN(GOcGiR8Zg~uSkGwspVrVQ$*TEkQ@4=z$B>hK@>jL13RV`@?qkXL{ zC?g+yyYC%Pb`k@em%Y|ss2S~pxnZ(sP_0}(HZo>}l4)P9UaR@@Y+pE`MZdt()uh%H zDt9vGm_q8Thb*ArK_*m4`utbg=};d$$m(6OcQ=h2e0eiTI>H)X?}{K{-g#9xN@1qA zqCIEYR~5hM*sK)P833Ta3CqIT7Xkpd@TodwBx>-quSJsvF`N10noEH$EJ_k9S8Kza zvU@qgXM35M=|E?r3VO;IK|mD%eCF4dq8cwICLNlMm+BW@u1^mYfR7r22|68UnK19c znd2a*2WPwpSbC%hC5@ic<*B=XGg@DexFH_xl|s_@zIizNl`UKdDJNXea%#hv#7(Yp z`{2iw{BiknaaiMwLz&vBA+oV)E(VkktG(4;h7@a+vXN$t8s$a6x)&lOc>^KSfp*Sg z@=HXFaw0-nW)?-g-o?m!|LEof?N`nMl0J0l@`-lVFKxz%i+0unfk|Hl5gTro=}2Qs z0EQMZ%7h~;1plebPWw7QS*NeDiChqpHK{{(8zVNMg#}{5{BrQRSx7sm&LXKOzQKO6$Q_DC3@FJu| zYMaZ!V5gXELKiMXWoCO9BA@_-pqvyWY_wmBfP(i}?C2~+4T09lD4qcqv)AWb$c~L z;dObl1^}|g2_@4b)w>kO4Sw(-$F~%m_YR7w4HJen&Am&p_kQL8&BsO;mN0VZ(@m>g z+~7!00|$%~=RD(NbfCDT`NRYN1TAbtGZwfr ze(`b~x5OEl$(?p!p*0dixJEngp-e5lIp}*e#)Ai={o*xw`BP09Qnc{*E=J|lJR2C~ z9Z*4#PKZSI3$N5a34SGRbA;TVI;QYb5DB(AIJG?T{WH6Wq$AN5FC&&L3*4Tymjk?s zjINM^I9Sx%mW*;}c(j9CU`*(|{eFCn7>o;n%;XQ7y zuD{+DA!D4x4X%zgR-=5GTNyE3xH5NPlPp|}n#%zSnn_FaE<`G~vq>HR=*&HBWCZ|f zKO9c(=s$A%!}o4I{AYLW z{6+8Zzw~Ai02VGrl)|(9gY%(3ys3FW^NE=iH_3>}n8}!7mHcVD78vD{mN?kT=RJ>j zu1s1&mwwXM`NXK)5`fX3T6>|MkB!w%mv-g(B&>6*eWMp(HeAiBY+8#|(;-;T8cP6$}wPbT6Dx1t_m#B=xSGH$UR9erCS{0Gb|G z-sThASO^G#Z~dc(&iN~!X*CxEZ|dGdJz7n|CCMA1>RQt~V^Ofs=_e)EE@AC53LfNvm3>NPy zJux;nt~g5XG8&X-Y-}3K?qcf|=ZrFwu%!qkc!Kiu@j2@Fb20LaKKjc+(v<+Pcqy{R zI|H4KkTRlj8@Ct$C^I=tRDuh?I@c{Bi#W8Sa#L(>f1(ceBQV)TN7?;^BKIcgO10 z+Wy^4mreu}*+6Axb#4i*Fw$tU6(O4)bylv{a8HcS9cLkFaYEqEkA{>I9uUe%F*Pc4 zowZOEcDPrX($_k2_v4fYBp;io!8s?WS@bT&JfMT^VmeTlKGi^1PSoU=UTshc03OpT zM!9eO9}la?Vv{-R_wHnrk+>z}FvzzbhnSiYKohr_L$3G(>ngheDw7yzXG zQ_o@+(bXHZ-H)=@esgK?C|`fA#s%e)&P-nC{BsIPKo{3VZ-u)8_C8ckUUHOEox7mM z_dZS=y&xOt3okY}C*Ac3=i#f@Y9gfjcQY!;bDwV^d(!5PMRenpdYI63s2{vJ0)YCm z#NP#rXw>9DV0xs-2MTwqYd2~lWM@RTpuv`}Cpf8F+KeZMYI!pWYAkB-u*Tb~VbT=3 zbTdE$p#&)4Q#)x1CMe^S%sC@BKi9@OO9W!oyK=Z&o&d9*Z}bELgRHJf*=P8GxXvjh zv;N?)#&58!l6CO3V(QfZC%ODj^e_FPt~J_*!?gCfQz4PTzIuHn|W@2rIj9ORIi-%OV7omlEYxs zx7Y-_bUo;-h5bjxxub*mEfLHyu-2~Erbmh#vx;ZC6CO||3F9=LD;_G-N^qG6;X8A> zlyJUQ*`HeOgNTMTj($cwVbb#=-kr5*?@l(GpH;pp??p%hET;!pyd3Y{IVaJ80IcOJ zaWOG#H);p>^I~d5K*sxJXD#&3CmrscZ*+tEZ;qC(#E19u#Y-{cq?nkbBl59nEeA-O zYApv9MS+n0JJ}3|;yoO0<=wR~9cXntnXI}~eTAX5$^#+o%RzfJlralyZ1}Lmt?G@!KAxj7pf@KEmv@2YX8 zbKV|j=m4Nd4Hv{&-(C)la(G-^d@crn-la&Xib~5ki5fhcm@>6VM*u))Eo`rZm_BpP zuf7=R(#_9-7cNBQ)Z!Hu)j6dEzco0I7Gv)~m+ol0RJk1=l!p)U=2AG?FO!y-apmzO zEF|TEQbziZ3g^7lF0AunV*6XU_ugvHB|+LSs?sZ06GDkmE*)vSF~fusO7hfTPpHaV z+!O?$%pK#DaWXy9JfJ8906?P`cz|MR>K(}hwZ>zQnD;YpfDZRm zqbGSlF(`z*k^oPD9+1dsjgv7`nUxU*j}cw4rDu|;!r=qWd#{x>+Ix$cBT%_RQ%};C z$csUQKhAN%!_ju(T_s{h4PHzv!s*J?cGtonW_aX4dAC~KYOMb#ml4Cbt_Y|~Eg>*D zR6)XO9pQ|xbtHJOrZN#D@Y^ac0!j#R4!Y|h%4%3mkPb~TG2VlW8DWGHaHjHwjSdtc zuyVDAo;#!c=%5T69K5&M*E$j}UBbXSaF%@hts!G%`D)D?2LvdE{-c}=;vHD!leVOc zO#ABE>m5QNJ<^Q@Nf=n|7ca+y?IKJV<-}V*+*3(gIP0RO001EaT8O`p#Y@|`@8ts>OFfq!h%*Gv# zw@G~=*m`#|dya{)vQ*R;#B7zX_0CUflpxLb7QPJq45Xm$u-l6vPEBSyLQN+?3+ zoi9?mcB58IOjzU2p_|NNge^!o;}rXgXJZD82w7dBz`cV>U#r~44NeG*j<>8cl+V(Y z_*jnv6e#g+nSaKg@q-xcjPguUAW%+?jHn3dY?ZOrd+UGz1M>XmTS=Qw2Ra>UiXEWF zJ#*l4j28u1yc7?2i_1UX2x@Hm=H#cthE~ILsMEQhoG>uq_jKc3Co3B%ZSBlI(9Y2^ z5|(4n(t3b9z22qB14Iq(tV;)K7OHaAd*ab9TIN>gR@Q0nQiNy)qr56AEYVEBLej$Y zpft)iJ1pI`_kNJ=-O3j)#z4?|X>ivu+EL}$o}SjwY~MKT0f@@I&fGIxR8NlXRBp48 zndeuY`%zzzQJuZ{|L%`>?4$Rxb2D*P`x{^BCN1&k{mE=!G2YiIxBGX}rOiYY?&dcS zPmT-@tZ_+8cn94Ja`{TaB}DzD5h2wHtbZFihSk!e0^YSk&XK(bS_`1e43P!8Or^9m*sj?^`*49 z2-u95fW2F2AQb^Ub1yhs)dEfq%9$dN4~?@vA8Se>i0R-_u5%kCyv%KPJzUvL(xEom zms1-zMVPQ^_)+Z`oywdkU71--8oA?;3KPUxZ?vC{8LDWoI}szCJFXL$^V%=H5RVTP z0K_d(u{#85uZDz>c_=L!Nas_ov^dVT;IJjE^IBKF@C)7kqa0Uy=ascZ67(1g(qivm zbaQv`2>Ew&&j~#xl&IIL>Oa~?# z>$t&n>6oCyeYLn5i;z)@jOY5im?Kz>fkDRMo&V+HV(XRFg)dxM`r1n8Gu`@C&LhsE z&9%RAeEnu59?*uq@N4^@{crBd*Z!#Wg+J|F9~OG3^jPbuHkldH;@!n*zFX=MAh_)sZ6FhZ&Ke(`dQ%~J>W^QgfIB^W;HZp6qqh!V~O zO-Dv1Tr1B5+CE;5cto$g-UdRFmaxWCQsoENU#?L}7O%u2qHq7n{`IePxTNp?>x1@2 z$T%T{%*PA?;Pbz;A|v+Uclw=;&?tZP%Uu8{Gkb79`{Y#$OpwkJU)~UlYoggmC10r1@O9&yMBapZNA$)s!Zh>gK};W;NT|<|8zR?^Z(Yy z?Qe_$;L2N_`#+jyUF95J{A_D>Ty4LU5xC@Af4H|agAh2}YQOtxgECEY^U@jY+FPA_ zKbTnU5g_ZRm2=TEXo;kygkbCf5=E{l9N7j^e{*e~5xGDE;&e5YT zaO+04vK!5ZbxYb3D{Hj}2K+Q5AQa=0QGupV95`^v=$h8yV%jPC`Yn`n<>1H;j%@$2 zz5h-Yo9~ndp6CndWJ}70t z5wU+SFBeV-Ms6=t`IX%`N@advT3xa8at4gi5!4!=_q7a|NKD%5kXTsJzRa?k8)1^B*Lo0LJe!f(T!IPqH_GCTq4#)e|GJf0Yg)$UE z@lz%sIO~_ZjO9YJc`f6T^&jMqtXMC00;`pi2`VxSZb`&`` z=OgVc7BhzkVJdHZXB;(@HOM$?Y=nrAPYfmU%DI~jG#O7+z~B4Je$rCq%yI#USj;T| z#0^2Jfp@rhJzKw=khH!0ytIaSi)&Ys(SuTioN+ci(PWFe{PS%t*yNz1|Ag3cru3UH zrwkzNsKwB%o{Pr^r3^V^>}<@FB-++S6le0zI}_S~u58CqLoS9!DBfBRiGSf8(&3p1 z?!5~M#RIuyTQ6n%KbbEkcJ*9b*8N057z^6lEJj9!f`U0oL)NH-OfJU8J1i!4<60_1 zjvm%_RC|Tol#!`CFlcW^T(Z`Bz(rjzs3J}uwwPL7I?|5Ig;gQbg(ES&oH@=JATSP% zUOLHqeTCD4Gv{!b{_6<<03ZNKL_t(G(9{-MOpK}g z@>pBWthZiBW=e;Mv!S6y6Fqq6tA!(CeGv09_d;>!Fo?upzY0>3kL~!N3SvPv(qe4s z8p)7RVHw3KWWb84ZT7;^e%V-2i1lk{F*c+m0>IYw%xDJy)!d$YwL#~c#n=eJIVWWs zR?o#jB#Mb$BE5>4Q!)1*yv5CH>3nFee6dXi6P;VC#UN*EkZ{_>lI-Q3_ZIW1A>2Ly zgt2IEMC=shD+Hq>R@zpGXiCR8lZsD{s;sTN1FL-y3#u_CS#a?f(r)7R(4}T7LuT5wFji}2`56Zj5s;z5Fu$w^yn=L$-CPT z<7|9bsaP28t@fm_FwQ2&8a)8i$E~%C3FAaXWVK6IG7)gb>eLSbo~niIY)9VX#m}{t zzI&`EQk)AGCSn-^Xzhe)SH0*QlqD^Be5;@k*4bDYrM9UESQpM#Ud3D&HfpHGN|3fy zF}3K?Td#9x3g;b;_N$~RgSc)eq8&nKD{OCs2xv{6qs*tqj(mCKdek0^2mqJA&?eFi zX%@@slFh4Wl!|;}pIC?33pnf4qe8H%a_$ym(^w6k3S|K>4p}egU5LE{YWGe%%Ab+i zU#MOo0(GY{fbMp5`)lKiUuXlsqwmi@A((k3k^z$eA3dth`q}`%%bNU?{86L=0- zrb2E?uXD>7NX6+JZ?8vWW-+BNo@o_4{UlDKE_`b%Ji49t&c%1%8SB#N!jYPWh$3S_ z%ysUHsVye1x2?jMH#(xx=CgtC?nG5?mjRB+Q8gRb$M2SdJM}ikI~?3Dsa4!)KO4K@ zWBqX%%op0Pim6?8pwq8e{{>E>>%Y)d5vK<~cu`6bJ!UH^>#DO=0KJO|m!Lv^?}yXX z-MBp6m9d)Mj5H;B`76!!OG(;M(|!d2jTIGV(p3IQ`TJ=I%vp5$>4UOe^W|kFx(Xs<%U5q29_5WREHvNNQJ z2h*R7W_PCfqj_;S$saDt!zk#y@|!HY|2x&jkM>so)5X<4P_Ny|tG*IRUiFJ=Q0kGf zbHUVV>*XsOzw`OcKe!VAchCPIRxc(LwY>A~kqCK|$=r#Z)Rn`^`O&qK?lU)GltZp+oW7$l#-k*&g zk;nV!eZDA<@@i1%QK?6z9x=v;vyT?#k+$0PTWcZb zkaYtg#Si}}`_cdDe)`nli3RJd>F8s{qBFV>!t)x|)Ap;MNxQ<2m8V>3@l$G8XHHj7$nNlz8S8A1qdAEW|N7d&`(pK6OpUFKvF=VJB+I9UT6?`}o(y5t;M8=;E0&Ye_@0R$1JR#dK7&=RKf z{f9-P7lf&}`~8VGc;#0+hqo55|Gl2oG)PAo@VFrXp}ie-cjC08&Mxy|N2Fcl9B#kT z2qHe*E8~Vtn$l{2`&*-*+5N|W3y3q`-H>kLed)=09>m;PZwr6_+mqcln!w=Tqs7Wj zj2>rwO;cq6*u0iDR)WTAU}iq-h;y$u!bE)dwSlwfN{rfa=heoCe?B1b?&=piM|blj zU;m|FSqUTlqksOy9BwMS@K(!KUg!R`-|czlr$^QL?aYM?0hly~7XJ;lq zi0D0TTuHOlVDoxP?K})v+EE)v+`$l$}GiSBWXnDWM+K>eRbPUTnYCbm3;>o?DxfU??q|G<%2&p)o9Efzl zIn#x2ZG`#6Bu!Q8yc~*|{mwr=2x0-i9{hM>wQsHjqy3WH2Z%&9_CYMZ`Nw-{M{&sr zwKE?YXT7U%{6LQ$=o(0fkhW#oQDGtuZqA#%aN~M>^{vkLzk0-Yt^6*<3n4in9tbJ{ z0Q9iXUpu>^a}K~jC8C}Sof@zSluo~;eDY3NYGm`F&L`$$U=V04uS-vGmP=n~o60+j zH5JG|iR4f-X+Ab0;8bHub)}~CF7WK@*q0axJ~?ocGyBx`MnLSFvpZcxFxuP7OU2LPQB2{NKEAWR_CB01 z-~Y=hLqrG!Uz)RoVvC`k4KxL2)3)OB$-kwlIA^i573thD4(L4q7=xAbTrfI6Fb-Aj zR?kJ#zH!x4>rDGxNVpk_hB1Ktqrz%0L#{%uOIODg5tF7oxHaFno_dSDi%FP>J8w@2 z%Cm7LoeeaTENV!i?J|HTpsR?qU>iidnA*6hNZ6wM;BsYi#&gc%p6u>K)xr%P6_kc( z_5vnYKCl3w2zz01F*Yl^@!(Be&)BoAZZ3@Xm3*l6uy(tlX0h*RuEmo915^&8E# zu)P&A&Ybc0zCUpe!&G>WQgITFgNT3jU+oCVxUBsVM6b^$CQQUqj7I8ILZA)z`PZAA zvt^}GIX7I?R3jO1V2u2O&iJhxnUHL>UnXto3{p=V=d75Ra_-V@AQhhvjZkEjf?2;x zJBo~f&9#7WX!Zi{&^tdp(bP5w2&VG0zIFy1t08fG#>YBoO2+FBmSSo+gUOMm{9v_k z<=m!iMQ*ZkZkiiWIkzI<=%AQb8Sr9m$s^LUJnNm>lb@8^jGk)Dkke0D~x#?Tt|9-aE{vcJq2h^&rK}atXle z^U~IhY|p%fB`t;C&yKgae{5hfUA&C4l6R%>dKS- z9DtENXe%!SlZsPEWK}rMfqriDq3LW#j6vE_GUP^k&e>?cq+_871bVaqIwFw))=TR8%L!fd(S8L08>h^#&1>1bU%ML9 zj#@nzQ)%W?qmdVF@teJnaWIwFrDKepEt#S1JQr-^YKjP^awPd}TuF85emV=75~k>J z_m#%vNZ8dRX4I0ja4b%qCPluM9PgRQeD9h3;FT}7pXZdvErp0gJUlwR z%2`)Ai-177^9xN$z+f>p6vK}il3F-*?&dRlyk}1KZPb#^Vlg$kaAxsjRuQLSZCiD= zqxr}z*KXPvAi(I*9p5U8ft^1xOZ94e;=G6Uw)*s&@g;?7|K|LRs`c!J*nX)|&h7ml zP8UN50PRh6>XMGmW;`!_uI(L;&#YO4M+G3nO+}+ViuOmDTmm;Pe5Tdh2q#DN>u7qc zg=9%vA;9#cdS(yf5f?KzcwFtjpU;jppM1G-=f7Cp`v=*>zsGOC*doKZbiUnPqI>^sd5OQFfR{|kf+*Hd!b(9KV5VvG= zEiC7@o}yh$saHWST-s7bdl?8_xO{5zsmWFX&Y_rDtGzBU@mK%b!?lY^G4ABw z`OlK0|6ImJsVD25Hx|Xwor6E0=8u;gu+i+!IDfFxyn%?r+3gqK;;tCa?;VbQus`_j zUjI7>gLfYHzw@a4%b;=F^ggK4KNX5+T_x9kJXt(A9=|)7d^nol887Zl77yp;VWEf4 zX#jY%_>1;#*uD7Vj?Xq#dou)J<;?aU6iHKssmN9X8Su$r6*m=4R{){CrJsqag{rZ= z`o-<}ztc?5Rie+XJ}`D+Twz>cUFlpYxN4@mFaLgj?bUaM1Qt|#AIu(}#=)ld{Jc0^ zl!vooZ&vJUGrPU_&!_q0{^Y}1zE|1Vg{|Lc?kudhm^~F*{8$s#3p0fHv7WL|j1xXb zc4yBiSmeEMvmh&9@iwvsWx&@jCo1GjuvuRNtLeythvnHp3IZ|?Ti3Ib`vrMesB4+* zSA$0-ZDbc?J0BV@85a=5;zxgevP^OT0s;19D6I8dGLpcSzKpmjS9W3{+4NYG4SVP1 z#^i`NTreM+q@h$K&_jOO48;Yr+8^I5vX!8kTkkOKs2~v^er-_Y9zE{9k^#VQucT5! z02m#Xx^P=JG8wRH;lfn*E+j%Q8FF2?Dz`uQe~!QT$9n)EB6jifEg5nda8tOXC2xIm z1OVq=Zvuz4OX+-QzVU~Tul#)1J9zl+OvZu?uJ8P_!zV8n#oqe&x1&rP-kNV*%eZ8X z)u76qbI@1`J{EwroFZ;Nspjooc!5h=%srz22jF)!WqFLnRwf8Xm|3b(Fj_kTDoCob!#tgD>H-B%jccw6~@@jpHA{z>&o zXDgyg`*QAj=Mwa%4SE5)_6r@dK%;||bMg7tn#cF@rH6vV6sz(5zv%-5qdnbGblZ0} zqxb*ngv__Jt6&_6=177_J=UPzZNQK3<-ovM-`R@xf3hg&mNWR)AMYU`aY?N9&iSLq zhN+q@xU7wf8Uh`LiKKD#shsBlVeMivA8Hvg##whKVgeRpV@fYW&N!SrD4MGQ<=|Rt zLDmVZ!Ntg^Soj+63qi<&Q~Itp)PvU3p1~&=ChMK{ zy6{L-orQB2P3el6b=o8KD#mOX)S_B0bkE|#=|!>xC2-Ej<3=jm$L>@NPERx!_3LKs zLR>AZ)t=BljDdS%s0Lc>rDTl3=%Au|Nf++u!<+~dzLvvW+>+(O0zk4FL9>VM3jjzk=5K{LTOD+je03ZUEAK5S!osDol zG*WRcPVH1(LADwZaO%)#_QGQJ)CFyB1sm5>`dn0hp&~vz*4|>;Q7YoS^9daS(Zkk_ z?C8#-w;OW~aZ?h_lstnQSJHCkOyL+~b+U$mDeDw!dn05Viiur07h8kQ)j#K@z|BtE zc8aNyF>h}~j6-KL-2Y&%n%o*(ZVuKiCHcgnLsR)0?9FiZm4*tqM^qv2KPrjpUB_nU zmPoF&vpx4N_o)?l%OW!9bYE`OtXhqf~Ovm;egyt!#%}GH1LB zIGs@ufEe&$Drm`8kw8{cmbqe7giALNKRo8XMNI= zK_Unery|zqhMWOqSM#ZL)<>BD1oSXHsSwZ^pLT-9*a*d)^>j0oHH02b=^2A46QhID z8JrI_an|Mo?LC;nt4L77m*97Vf+hVO0EFOx(A|!xj?-C8+lpKv-g=Vxbnf)RWo?BX z=3^rRP6Lv~*anF}kMue%r?#~ohA{^QR%7iWws=afV?ihg^9%^(!ZH9AaP%5FIXt8eJU^r^fd%5%ZxT6$}v(k;-9O>!HrAv*-;*P01zo z_yRBpVouRKE&v@I-^-o#D&#@LXMHUdr=HWK9nkD^v|rJV@$5@ZMuOVJ787&UFp{(t z>A7?qwc59~gVhW1^X(QZm!sx-IDAx||6EI-Iq9`F!g~MhA?qq&%vo%#2J@jNV`I`% z1gxaUPnCObaB@_w>_%ZC7>6*GOFK+!Ev!c`Q%gW}!g6)bMGU}u%qQmBFLsye17Yvz z$hvkh2@`2bN734|CYl!rSgRCAMQXjI9db?BKzfraL^PEjJ}yZ_i!!+w8-8XcGV7Z~ z-z-%ja`|N)B_vZZUyKc%97m5og@DzN1XiyXL4!*U000<2@u+z^0e~8TH~$p<}_RO!r9VKPyL(?rK^BTwz?Cq zT#V9=VgQG?7c%6CU`jV1m}g8tN4L!M!0Ft_ZEE<=k=3sO{7g zE@>&HSTVDVLwhr_+E)ul)g@6wHdhqmpmVnv8ZKDUl8ccwrIU)A%F#h1h&TZ{wqI_X zwHB_Ni(6|!y^f!jR&fDdiP9_%bkPtp&_oKK|+#5&gV4IGKE~H~7x};5!Gyw~t0Y z8cc6a@`pv$w{HB}Z}-M~74fiwme_u!L6>lPT*-)C`-RTI%{e)N8@)g%#yCU7dq0>& zS@GHbWU$nRX8Ge;zL!@6hdM8h+v0k2@0St0HgjX=#x0D^jaww)>fLXMJ8zFY9Elg8)`+ItafrCL~>I~w2V9N+mz z{`Oz6Pa)1c$q;_hCLf-$Tb=zQKA$E0JFu_tQzQ!Uxqpiv>*T^`6)=3^hr*xTip9=a zv1&Z_vsNt0gQIWm7AH+-e0M7niZg&>YK7!Czd4MXa(rA0LBRw@U)}1tgvbTJz*}&} zll{s&1VABq+EE0*^cJI3TJ5Q5830=A!T7MEJ+Tbfe2Iu+Pc+NMN}wXa812Hby%EMu zH966Y*C*b%C52?p`ujhe)+i-JXZ+PKw#%7~JL;Q%wAWe>rziTxFLeixa_^9Wb$8zx zhg39UJ#DIt_9_(PgVGvL?~x$lR(qj%V>PJXp-oXO?5wZ5TOlcbuJUU)lDH+;E~YBt zQ6`eMk^zgG;)8$L-+Co$_JaO{;t89XLGxV5I0(rHk4qIXXK?*$LSc|{VZHf;YrB4} zUg5s*?`{xS{kb7ky@CqGj_&5J#7jTlmH|Jxn>TyGe5gP8n?V?htgGJt>p^!X3PP?6 zzjiUv+Q$v)9DehU_o9Y4xV30)g_}1r+Np?;zy2G&a%ML!*QfD|pJ_1$&cgD`5R(1c zf3%}Q9z^U5e}5yNm>+(1y!lc}``h_YbHT<(ReK|37QDsf0hJ7H?Tv79Tv_Am45?%) z;!z^s|EoR|K&QvmaFGunp7~(%b9)k*H+_( zy#3wrSx*+{H8hI0(Ub?=zMhSbN(ztnF2quD#+lXl=)IW?_|D5Ab@w2GRGc~%SGMD{ z69~x;ZqDz#GhUA4lD1mejk8X`d0hif2CHQXZ`RjITL!UMJs*dupa70gEFWp25uYuq z=v_>v{VGU=sl3zvwcqMF>%aR?59&PB(?{W9_F*C@4LUw5mtHOEc4VCC z!k05k{w(ycY!Ph-F0qeru{dPWlTyICx2FDU+2X^zNEJ(y`ppS2x>4EEP1}As(qnkzlC*}BV zb@E~H@H^9^+s{sJfri*^TK%Q7&ARNs5@A{iLt{R`2+BPM<4n2SRWF*#BrQ6r-+y zDtEMwTkU1Q>B(J8Y@A67eM`xrOsbHZ${*j)sqC`8)}?a>w_nOgyjx66cQg9Q*9YDK zdR*oQd*_qok@E4WB`s;FW-pu_XbOFMhu)xS@|E3)%$_7hFvey>Lpg$nKb{6Lk1}!L zGcA*Q!fAPrn^)7;T0lb@74hy)K`#Uo`n`EE8ulqXZe2%-P$q;x~dW=?jPBB<*BJs8eHM7C8JY$M*Q3x*@@cVY@K)Rp#_D z&dG(;iittuW{E@VwT{uHb&w|I`8ER$&s5wLmWbqL$p$s#c2qX|Q^S5%1FcuXK-!_P zB=e`Q1zvCq=}3*(HL-c&pVb*-atF8rWjJ6CC=wHnXKz`w?L(>ZH$8 z!eUQnw28jNNO?;xD*o%(nSsJM)MRj8l}<5brMEw58erm(U_{qalrxce2TQ(8(9w{n zG7QzhF5-=I-KFh-TGo!u4nM;3UtS zn`7HUntZlc44_4B3NcQ>WXGy9MD6fg#4aK__}0xz94&gYj{O|jKe@Wbj@tDJL|-8| zfm*_C<$HP;i>f{lEL|$CoOHTe6mma$l9pJH#kKxe?%0UF^=QEOdFj92_Gk9v12S|Z z;WR;qzuT?Jfo$oOP-Ygtp9;8eo1lvNB8||*`*g>tIAufO9v}0M?IeJgxpJoXWWb;| z5oS5An;jQ3<8RKDi#opBvYj{MR7cNP!Tn%|ox1%AB#N1ze3~s(!>VTZ?Dyx)Ntv2+KL(Rl@^}(^h>7GpY+B(Bw z2ZOy<{v|?BBusIZgFnR1W;nLbBs;V-tj#T!CmS*#gd6h&FV1{tI~<0Jh?KBV_eSAC z)EV~v=H7sE?Brcu3KLrxKyaqhc)8Q>!oulRF5tiPeiWcTj_UvCOTS>`^m~Q*uepRMKjWJ6bd=np3G z0^VaOV|%|*C#E7`C^iL|Sm@ds-`pxR`%@sBvJl%GFrWO1>*8Qn3pkV0cl2BSmb7!+ z{;_*Go5i5(UBGwNk^L*&g2^d`3QKt4b-~auHp`{K@VsLlj_m5PGvo6YH1z>Tf4|4M z>Z5(zqq;V)qu*ZlZHOA-eO3=iS9f$}H>Gq_&~*E$7K6N=hbj^sop}BqN^u%Y1C@6* zwfM||zl#EECr-4NQ&^3HVWB~KucC6){s(8y&d<;dT>Z=mKE(Xm2a670*K!W|0_r}V zHuNo0*((yUx zXo$7ET4b?EHoexzxr9@$gXU$!N*FSjK8}xXwU{0Rimz$6$DD~VISL}+CAqcQ24ckO zaZ+8Saty7dkcrde=kEeEd?XKTK|{tTI?HRZEt_W((^kaIzdgO0ctWqmg`S>4xFL~n zYQM->h;>;nHCx37D$0wgyxqBesx{mUDUv=bS{;ltT*%s176|SPOK{f5Y^i4#f;&NJ#CmA;SBl9(qGGLk>?i zQE3$UiN->MdMI#DtWb4*9S&l8K>-DDWu>&orqrZsJ2Kms?b`@fS8sK?9Ng`jnDlA! zzdHL3SLw@^*3f7t0HQ0dY5xm_%=0FMKyqtIWT^qa_RaXGXmT#U-_c_2O_izLp(cf< zy5oKqq8%PAWyK!$Qk7?=Qy=F;w+TPVYw3;5LEEkJKNealD!JD_h+lYCm0W3J;^KSNo63S8O1 z!$i(W1*vhjJ^cM@g@Dt%3-r5{$~j~Z|AuJsq=w4+@-23uN1f3IuFWHh$y|h9TJBpJ zP^<{DqMd^Finf;WKIshaL_N6qHB+P+C6(cI8N7WN?BdmqD^Rr$iOI3Mb`fhmg-?-) z#35QcqGFDqv`;gMCqNQ0y&e(KzpR5gvvcV@!Y#)~o0my~QU8O|odB1OVn{&-^?Hw~ zVW;@(gB2kJ8^(Q_=zAcp!(0V z*sbTt;wHkXL5VMl1k!A$Ad5%dY(D*h&;-VW*@ z1!lt00#=y4aRnvzoj{aO6B)UEHB;HIlVU0D4VANs!hfHh7n(KGXOl`5dSxyI8e5ZW z;Nkj*DI)()<}>=X)`*Z<_$ef^n}Q+=-&jwmLFr#K*9+$at!WT~%eBl1B@_fVfB7ff z(m5uuV2k?-&a)czznL6qoSzTC5>NCeXU%FB1+y{!UJv~$59Q6@-YBhO^Jc=zOFd#P zA3c8@nhukvTU~M+1`*goUe;zCX<*|h0jhDKkc8rP&yW8r*QT}jEdq@a147b=;_g#c z-%%eH<`{)s`>2l*QtBJ(()zKoezm6+g6A`8S0jO{i|^tR9}`!)QDHyEG39@57fp}t z*fANj=(%n30j1?J*jgh{o73kCY{30iEzp6~0XeD7wsQ4>sqOyUo1Y7He^s#-TE#-1=JQThlKkd`YKDC*e7932iw38^ zzp(ibq-O2nycewAKD=L$TgD@j$giYut=#+|bq}^^R@`x_=0@y6P)ksj?64+O}!LBg(Tpg;y+eE)MxmP~;OapK?4 z`;LB@aHQrmpv}i~H7~E9w!J4CD6@jvd8x5@Az~RsC-)k@sb8)~9V=iW4~3`?&n3jM zu6%9M{^*%fToR3CKo1cKtjS%@GF9WA4Z{Mi$9YXjRy6x5;38x|e)69Le{v?p)2u@I zjeZp~%wlcw7g-e!qr+%JWhpHVsC<=)viMwDL>%>C!|GTKy0wuAkVM*bRc2M?nbDoZ zjev1t!%6mBq=!jofvS#Y(*&E>KLGN2xqT^e(vcyNdKXHF#~WW3(4=r54jq%v_3gp>U63GAG#1 zZKEvbbfUE4Ki_-ix~{NG;uJWXZXo%(G${mVAQfk*7;y=$OVwZmg2GdB9@T4L83Q54 zVZuDxjA@5nD0aqm5g37$oowbPW7ZK`$1w92QofE>nO8l|SB62{@s~`EeCDz>19|4U zDYG09Zmv%y>8E`G>A^nvUDNtERmo`O^uORp!AGkqlU{D_9l({GOzE8*brHZ0eDYMC zb9{ugkS3%8__E`WC)-ds$wlrcmQcnP93Z^X^Jn1n&;d9%Y-4+s+ArXF}Iom=J93k{@0w zzdjh^dViTyW^*}FUWNc}<;t9&Zu`#QKEwv$skA0ZwqN}^WP=<1o6ya3XYe2Y^Lj-q zrgBgYi)0P(oJM8{G(G~u5O+r-aA(1CEjQ_^BgA0~jsV00^cv!K@YRui2-)Vv$2Vd{ zmXAh^W#qrmPUnsLCRQzGsw=JZtMsk<&XcZoBHQuC#*v&aUollR! zc%Kq$B$Qza{RBB1d{RG)e3EV-#q+%^9080=PyfCmTgS#txfTB=q=4+YaVgAPAwg$v zYc9IMR@fWM5O}l_c>`^{b)(>y|3LW8(Hxu7lZ=91A;KyQZ7<39W_Vd@T8ib3JLYEC2j8RuJ7F`NC($2%r%+x?EC496{Cs&-3dct`z7bt(0$YCY%7pVT8+(U6S=7K zH?T~4y47kYC0VWs7vIR~{UB4c_PyWaso*!;?vNY{dY#=~n&`KBI!#8&&0OKK<8Old zorDYLBa7bDU&$R#_RGuW&h0RgWVdrK-pX9k+;gw%a!7?29s*bzVTnH%c8=y6v<&`r z>g^~IK(x~z!zRCZ^trj}L{PLxUR&cH{|YZ7$7P6neeUu56C7xIqaL{PI891dQO>T<|IMZ;p7URW11INWaJPih%Bx>mtrUn+T-3 z7aMYUC}v75*pLxttgk_jpFbO{e2lynF;)NTt3E5OV36NhVx-awQtkjFn)g&nFaoY3 z8C@2br+I*Cr#23@UFjatbWWiP zgumu~eiGLG#nzP#K8i#kBmI1X(x)z&@%yzaDum-NkMuXSjO)mZdv{v~D43=Suo%)0 z=glbBUbiFntx*7um51!M_$`KQJ5%@Urflz1fjlVK=3M^h+qnJSUxF$`O~&zK2c#In zjWM8G_rqD{o=(kMADH*byjU6+y~_QvWlK7N?vP6&8#a<)#5`++5evUF`s3CyjpSyn zNqbK^)}p0QLnMVoG@ z{&)(Cgiwryz0&ImTk`3|$S)$B_2k^Gt^NJ%|Iv^4$-uYX&y7w>7z*%kOY$_Y2P5&Q z(Bn#p%kw6VyOl(nR`xHCT9%8j)Us|L8nbY!BcIY|jwXrC;kB89RTZr6MJIc$_`5XY z_eOPNGFcsDgh^&f>Iqo_`8IOXSJk?FSXgb-Fz^Kwf70=;3YvQR?Jq4h(%bx<5z&@s z0E0`rGVJz~yOeZT^U{G|7}5K}SKhR>U-u5XHnV+wkA210MnqeHcvvB$0T|G!A=kSN zK|T9p;6sth&rqZ|L3n4Drdd<^-yTaT;3wD!54UQ|5s)y$C>l8Xb_85IEPtDUt$WY+ z8!L+MAmroRSQRa_0w{l4J`tBkb@oWw_D9gkbxkD$}YN|Zy!0M`iEgL=Pbc~(SVwdo?z8F+ zup(d7{p@M7Z86;g(s)-b2K`WRI=G>*Agp2eqC+%+T@t})RwZYmRFAu$H_>NIn;r=E zp5vWF8az^4U>Kc9ws=rnM=uVCy}!ODb?-@R!XA}8ZzV^`-6Q$+)tger=@J;Pq9yG_ zaR<5;*Do7>uO}SZ?nR9P_F^}fN$%>is_Q_uVI;1?1R`P}L$#J<=h(!o?m(8P#pnbF zL!WyT6=B3KQm$SISyo}M-a&YZ!<)a=a4GF*l_$8^X>hzaCvej<8D!-c(&kp5G^!z; zOu&71T8vP5@7+?77X_?mxr&pwj~&K&yrT7(1s<9%R~&!0IdMLmEG0ef{SCCz11aYw zNClrl3&P|!B*(Af3w=L$5C>D=;o@fDz)spepCz2rQksAHD@jsc81TAW@h?D9A&m?v zI2EJTxwV$Zv}2{EjXLhXgoCq6?(V`!0XKrdd%SB?z={8_Z~#ZAIca-=TmWed(bLjV z3e&owZT)TPRZr8E>GY>z9gl-LN+nJkc#QUywqL|OF(*n%*Cc3+y z_Al%m494145~i4PD10G$wt-`dpBKvWPV-^v%{Hk6f7^EBXVzY!XGxn|Fki3Fhj{FT zAO2d@TSXm~;K@K=Npg98fS1YOGdpQ-+(M;+9>F6!9HL>V?$*udKTPP;49AlX9J<9h z=e~oH^B&x+*HXT&`mWu*VPtI}wu(;{%=DT?z`Dut2Tdf@-G2a2Jg(lq(T|+`dvq<8 z;h|mr5hNpJSWKhnmCaU!a7;w91#60CLVUvId;tS^XiuG1aFyvt?H*DdgjQ_Q&ZxRz z1hl>Q?9XE%`k)X1+bScs_O@Y$PjmazgtM)4yDFyN*hE z$EnV&-#Yk@c@jlX=av||!2+%qxHBxO&~8NpVjDhbdQY1Cw|8>AcuBe&i)7R@l{i|p zH&EytbU7D%UaZN~7KY<90d`6Rv&rv`)fEUM=N)W{IyNk@SLcRkax zH^W!omzg+2qbq$?)PL5X5R8E44I(xes)rlEI4DtuBgXLA(J>^Z7T}#PE>$)vr@im` ziNLtf_;0Wp( zvDZJglC1!t`297YBJaBiEp)9GIPxa)NM9b?G)XBI4i^%LBX%N2GM?Dn1J0Sol*u!; zqd$N>ydE&?U9y-0wk4!{gea)WPhE?p$~z5qs#E=3B##X% zKw%tyey(=coE*-s?|jJh%WpCq;kG0*8qA0~e;TMX_*o*>p5FTBa?y*oWM=H@HA~^P z2bW--4q|f_XGQ2~*$S_>0hV z7f1z$-&&fHhu6rGG1TT7Xo2TJTTHsr>BS)3@M{E!wpHl{T9!3U7}*A)bltN*3AVT5 zEWQ$$uL(<^%TI{K)P2M?K14Or3ryX1301b-2=b_(RvizZ*r~=KuotPMC)jB>G1nOP zcRArc_Awj%3u8ip?7EKiGw%R}ss@v`{ct3?zmNuGcoi6NF{#>MxoB#J68=V6)d z_2_1>c~Y=M@mo?uzT^+HZ^XIFmKTlhcOMrIT~l=G10zMBKumsq6lbNZY{l2>CWX~R zxe}xml316qmTI#IX?cxEkG@umRaD|~Zi{1qGJ_!)O#n7-xsu6q7?#2miBNjv$i^6H zdgrvk#sP}gQ?G8sxJW0vW^QcplRk!bWN7Vag;WFA*~QRKf1+Su4a4X-r)HmtjYidg z$av=+Es*Cy=$-C2u}N*lOoL+XySEW$o86anlH}h4G<0HVmilZKC=g0E%MeK(-f|O0 z^_q?0?j)#iI<3C#;iwS|r;eYXFoQDdMnKyW54r zpgrL$p~T=>Qej;ukfgr+9OpHru2B4MOjF{`*0v&Zp9Gu(*u75 z;Mnu2Ny$TPq|s+#yAAV-21~;t3liHnLIi$48C#txqJ|ve9#?9t^i9ylaw+u7;IW+1 zc3T{_r}^Ce@&>ON<9dlwLWRY!Q+#VocBq2M`B&m6sy}<-NNIDrQfz$o9taD+*HfI&t4pAAp$ArMF0R2>`hl#0sWKDv_GZY7DNrOdj%*l5(HHWV2ly zpB_BslkxrHkp7|2*4r8U=TejvYa#!(lqSTi`1afR-@>yBu9OE9nVy2rRJ^#SSnTqN zmceNHk5|Sc+&3t=mWR_CUFo{w@eowAN%eQ&>!AbQNmA44jmVChwoB2vz1eOThF_AC z(UKPU5Efz+&`A&nK`E|Mje)2e>5!tX60sL)f$>$Pi#nyEzYwJc5*trs8ZSZlWc!4S zMXXo|7ZAArM#B@Fuz5f!&6u7(<>3Z{B2E!#b;S;ON=&C6HJmx;y4mkE_5||6*%`#4p7%|=>tkR2xMZNJg zDO8VQgM42+8?x%A$8oSeFSSKLPhFGZ65Lo12PEmcmfbjnb^}jO4&y7K z;9Lzjncro!fD>fIUSBs>7DI0qvqq;-PEf5_Zus(S>G4RSTd7i&Z5fbEYJHKL`hefd zmf~N>LVovlK_r#6+=Y>MflP^R7y@1ZQs6f_wWD)B>d)?KfGo6_ z+B^@2qNR}9vm9-lGB6mwI4Zuh*CtnVV^*$7pT9n#LHy`_jy3aECne!glEQ)X#D2rH zj3(Kgs6va$$S_5EZD8a!;q%mg)WZH9bE3d!-h{iOGEFKqIVV=lYE8K!Bzdfp_%n~+ zISoX`I=@Uz*S?s;z5gX)x>PHwTNA~zNA#%>7;cm zb2)Zt#phze{4Y&5HP!=B-iHow|F4D`oR2RQO+z94lU^8ZW4u&FMY{=>_K8~rQcjcJ z7rnqbO%pvXYxJ|fAbW!aHXDKXDj$aG)v_&vk$Wv9yp~&Bq14b1xqSu~h&kAW(}Z>Z z+FvH;><&U3dM+Y;iVCiVKm8>xy^8v;>8B5AE?6Q4dr`xpx2+6Lm2gl+7f{UleRPjx z%BW&kXbO~@=DY~;%=Uh{rzNllg@fWX`@!2P=KG-Zy_clHP8ko+#I-E?^MeH=kGH%g z#}88Gzv1Qvxi)-koNNFmucnGNnny-1ln9zBz|L<-|6^#1sj9<+)m!}&2vw`CxGB#T zO_TtAIm_6U!)qt+i+eMf4!7CYmfhmp;_I9{>If*3Y(e^5Z+ITZ4z6{d$=~iNf|f>D zlbWiO)$jNx7XyIBxQk_(No73m&#@I-8mVn%Six0ft+vaZ6zeV+?%=^2+@CjU|ENX* zd&NRwTXxTnN9e0MEWhH}O?in00a`t>tfCT{SLPE~FU`MzNmQo(5LGq`d#2 zw*?uPr0`MVvXJn=lHy@9^Dx4D$hBviI4B$)5fq3G{kv2_Z~VG*$A-EF7PvU(fi#`g zK@LiH6xslukPmVfGad}RlAZ-U9AOtkz%KD%L$ zf_N??a4^;Xi};~Kh%s4bezE>iitKpZQkXpi6k)(d9@>fDYV4}XzM)V^%_h%kE}{dYd>|$jay5( zd^est#f+3KG;n^N@_ai7(iP@1I{zi5k#C148q!w)x$H!kaRm8|&RMXY7SNgmy)8Kf z7VFjC`i1ygFK2G#=qNvNpO{liz7#2E!<4WZu^Jr?zVm^f!cfuCxx-1YujLI$Q54Z? zzU~dUwcHgsu&_0pHfRLDr+5iYv;S`E*z3%l=F$FxuMC7&s_)R_fG5!ykCfk&RX@<) zepTM=Z>k2XWsMGZ4qu61Lc1gvT9me0p&5_mq&MkzPr9!UKkCyxf=SS|l(LfM!oRP6 zp7hduBrrUmJ~#HaSJvL40exi|yy~W7< zM|4Ks&sDqIfA%fk`R<5hvfAH^G%U%#Yyfx}+%I{{TL}z^UsgGME_Ty+Cp-BZ1B;u3 zNYv`dbK)3AS_;MVv8CIO!N25I65+8azo6@sZ?PF37f50JoSO32r-4N2A?n~MTBXZ1 z?#`n7!T7~;S`U6GoWfLDt(Go^*W@G=1{6b_N@k>2(?WypN(S5OhQI?t5<`c(PLJpqN4zXhx-uF`K5|29_7w_(T z)u#S9HasWYr-sT96S^f6HLr_!0FzQREjF7vS)h!BR_X(Xo_*)6yX)GItJ|6hM9x3X zbo3B)0O+p6DC)b7JmtsQR0A&TaSeHBP)^RzLn*P4cZcj)`FdjZwo&WX-Pp+bu2%f~ z>LhZw2$T?``Z-zZs+%@^85sTuD4IaGQTzLak+p0xA;1)rXFIcNd?s0!p3aN~=T z3JNLvsuow@;!m#Mioql)d0;@z$u|??Nf8>M$T#0CL7LN0xO_sY5Oxk-^#ID}+h!v~K=&C5u6LZ5S< z_d%Ujc9L*NTaZO$Aky#%DJp)hEYTIaxKBGTwqeF!a2}YHOSmlu$B$>R*vds!fTY0Z zAf6M6o{r%w5t(<&q2qU0weJPyDkjTTjKu`aAANs}X}PI< zSP?Nr*sqSP0get%Om;_1ZEyc7fszY|m%V5Q5S?g*m-XNe&4HfTJDN#V&T#r9W7^W* zMLxY4d0fP{yACOu)|f}&zoKYzyDyJIw_K;1!8AxpAmIK|-f5xajKb?VkrKGe5VBm? z;6hOx5bf24`zHcYbRI1_a_h@qi&8o&NJZv>ETI+cg5hQZ8@R#W7^n0m(|X7@c{!Vt z+q3OwdY#oC*qu_08B)UGyG!|DQjWFFgffF@3H}~B2nNqf8q|WeHPBL;cKnXOWMm1GTuT%9uzgn459nNW1qco%OII-ki)*2yVs|$2~pd-1iZ-%ew z#sm}ethsGxmMWE=QtmvDR_uGa(xlPHomv?d!;KTxsM&XJ^KTuF=0Rut%TY~X_}+2l zKOa58QwwrL(8(0#`c`>&BPZ~Zfk8TjZ?5_l2T%KhIvAO@Rr=960P9t0MW>WrdQ|vdW|bc8)C-m`P+PKGuvte+O|5pzmt_9 zksbwSkm>euH_j^hM$4j_!qx)cTIEL z8yx>4CNYOtp-#<;^P#(bb)P7t@)kzoUj-{$g)SrMx-e7#ZpFVL-`ZhTrRjR-EehtC zz4nr*Q>u@JCwS6Wuu+68@n>d^&8OXOt%zh05$ueBG1O=R7->x~7y2M-Oe|VJ1!82m zwn{yCXPMKGXJy$E-Yumtj#XhzefhmRO}mMCEV?u)anX^rFz$Qd;T9J;z8!`cp+2v; zxK4$Bvl{iUGZkLRX^?RmE2nPH>qhqmzoZ`Gx)U@ZP1#Q9OtFJTwBHX$re>c<|E>Ou z>CuYNI=tc+!nMqcsgDb<=L=pGa$I{Xmo(Hqn^+yc>FmHy_AZ!^U$JWg3R52K64HXr z9!%{mj}-4t)7nLy>*`??YCQzNZEH?LbK=zU$D>#m%Avj=lX}#Wu6S-{5GORpsPDL+u>}c1VK~33e0c-j z)a11;kFF$qS55DeDzqMxIOy-w!`xXEy?z`ic1PxCjdwv&(y)btSU3C0`S|O0)E>Ya zT9{EPxZx~lQ90mh{uF};j{>rCvBx{SK&XmPOiO5|9^9wOpMpB2T3*pojtqj&Lyt3A zY_yA{53HEXt4uQP0GawWW7f8D=zy)<6{onM8OvOZyx%)(_7GOoxm;kv|0sdSS4+9O zrP+#B6TmLgwcYJiF|Mv`;DU^16IqR#Ttw?eoLf8CTg;G*JpORyDOBF8&`SC2?NBF)`S+7eG zjqyrlegZt(czBm8RvW!2T~;{o3>6O~b5Ry5EfxZZ(^sAU!S&6=VFqCKe9hAjpu#@` z##7=hfx^qp^6oChm+SYGbl3Y4PfAdJWGVs2P0Ct99!I|(2krD2b6c>Sj!>^JSmld>a!k_Du~ z!rEG;G&NE4RCYfRFTt<)?5egLoGh@i>!i*6C)0WKU^rtk{I@_e)*)eoQkR{?Ua$%p zDE9>{Na7tnr&jMzJ`t7)n0L0{b?Z$mWWE3>)0Y{(dfVzI!T0r$b411rW#7k|e8Swa zSKwOwSbFLZ&Sh{hP1Dedk?bmWI&yb1a;o0_N~A@X#$laL- z2V!4pqc_^p&d(1^Hmy`wwT9$LkGV(6pFyO)t65dU80VA!N(Kh^-RlTTII8PnH~)?b zL1^Ww@h0C7nt**SGCbqk!LtMc7bZWfvtUVK1L^W?IW>}%$MN)H6uuja`kc_Mb+U2G zeXc*xOjkNS@-)>i6NekIC|TC-xVG`>Fa!x_yj(@;T+irx5Y4;de#7 z@wMGUy>g(@t*MV0YhgRvO|0;4;bg>Dy`L{zWD*?QTw**9L?KzEp``Y}i zm1w0Ex2l9OCJRy*SCA>%7a1SP5mBVjsZ!YcHeT5~DOrkWDVyf8a4QZenv8JEO^jz$ z=&-OoN=&2U$?|rL4_aj5j!LJ)_znj;00# ztOj*skQ$LST5nKB67Ye3EBvrH1bmSh9-#>F47@+uyNOJL9Q-H6%telFkd^`@$9`qx41!K)$X(&qHdqEbYhL@LgJ`&YWMowsVjVzKK1LidY_nl$BS zpl>ASs@R2yRQ@Z=n3PYEGQZ7e3kC2+vGXMzbkSq2G)2OwojwoOwAUtAV?4`LA;O4j zS}{tv_9=u9-n3U@4T+g=A&}%N(|*$oGWCK39eZfBZe3TI0DasjR0~T=Ija=9gv-c` z@1TvLqCz}e8zRuyZRf+FF5}nWid}gnr%6dh$p8&ne`2i{y=tKee}RS^q9C`)E#vp= z-}0}$lE)tiQmu+$=J}&|u^;o}L7LoN_vxvnYpg(=c{00~8jBVq=MF8NDF+iPCzGR~N9b>~ba@RZ4W1a%VyRbU7tS9Z`Zec6fRvw-Ct``N52NeXf&k z=5prgSRdQ#jINRdE0%C!4dG!uCu#nhfWMJLWq33j``xI!3}BOh*MIJ0d!1gc{N0YH zs=yYT4F(%j0Tpq`Biv@Dg@{s2UF~=r-o4ue(C`ofsy=q!P3@+ZPJPSg8i zmC&6B^JBZnvV#RfO5E`%7hn^M`d>V)y6Z0v{;xlZfoZTedcKkZd9z^oo1*h$P1wU! zxHk)@iWoD@)4U|%J-EAbp8@3|N~wzv6+>hh^T(&9JQ*fQ^yXaKT{b>}vLG$Ek()BS zGaQb6tgYiQdrM{7b3$IAQAl5$og|kSd9wKn&N^9khXyg%za_0Zgl=U=2fMPXnWE3X z+$G9}HJ7^YliA>KmdEMX2q(|gEwID=CKoUP&`)%lLw{fNQ_(#>-Kn8HzTy$f+t9#bws#hMEQr+Pk}@m0L7` zDio^j=8K{RY`qxK6i?iYS-1`_-wh}3H?s5mvmtxVZ549bgC7n=l7fYnFe=J@!u9ve zdx9c7pX)NWF1!3LEuO9n8L17ev44^mY$6Hp8Y=ET5aqs>^PvV@O!jZI`#drM&Cz>% z*40n)WmKU=wrurP731SCCDKQe-`2CJurS0Ms$A9w2!LBN>Erv$7tsFTmfh9gs&g!F zEr2^zYJSRJt+=9jFK&6UxUrlTMc&ivgBKcB)xF5bc06FN$BbTc@zD#febHjH^QJ0| zT@-{k1f^D+4>}&2nD;}l{>g?8O(=fR$-!AYUNJkTszl4D|2As(i29y%>=h0l1}8TU z?I^JMRwDd;)_})LD;Y7X%3SF6?a1@JE37**0BtH#E$yx{nzAA~z-zLtucW0mH}~*m zWZ-_-PW^G`(Vet7XvQKVwVUK&uoDbU+DFii&Z%XzM zqUSj_q^arcB$2n|;>}5R3XOL9iYSs0OS{VKYeDC0)+rXr=uwEy^D&o zPJs=-R*rQh2-4%x1>2F4wZXw^y>}hKB3=S?j_9M&?weR+md5Bv1~%Qj)S$2C7P==} zS8D+KnpcoIZ9vUPc*c|z&)d#1>`(=opO}CVZ|5}B@bG}G-JdO#O?&HpsSOCyign$@ zLMX&t_}h|^y^rJYJq`Sg=i7nrF=pM+N;3RVs`mXLCbZX6$@`c<*5_u;2M+Xmk*`D@ z96m=lnmeg&FTpe*y?{yu*@@xO}vxg z3WUa$+*T81q-NRUI2k`n=36ezRsn|%CVE=ixI~p&0F`KI4#z}Fem&7~Uzs%01A=ZV ztm9NV$WrCtd^5PB9=&QqK3MB?V+7FrCZ9>L=Mzt2^78J!hD9o)3%!!~yu>NZ>^$Z# z`<2N&mb6fejeBtRANY4E$tVFtBz;>7;c!58;h$JxYMV>L{MyF}2FP)RVcA6LsNH-Y zmr6sP?^b4r6=CJ;&bNoiP1U~|Xm-n1beV+y#SSyA>3xJAIJ_TE&>42uzBC%#P`D{< zQ|tRQLK7X9&gmfYo{)mUxpt)TKBJ%4bz}Hcp|XMX67hT;VNTt6=uw_fc-#+p zFVPQY3tC56rOpfSgGvN9Y{z#!DuTm(ogQvP6K7{3?-!iRwTZ*thv+5$&h|Re;D|h; zf2_mnv1kGgo$1S?Y?B>>fs>KzfG2uww0>mJz= zGEkd9y`?g~6Vlw~;wM#kQQBy~pr6u7Cre!{CuOOQ=VZx`>F$OOa@&&#meIbLvf`6l z3y94E9@n%&x?1-R?JtZF3QO{ zfG*UT=YwiYEBJoyg_jwTg@NmPJ>=!0W#FcYI9NIK?qGM4B!tYY?a8K^P*Ze}4ZM>T z!*d4XD$!b-Eh}D|hB$l|7FK7q(fC3!$IHfz!^DLRpYgB(lBL@S>-%6D-BLBi zCp4&MfNi$^gt8Ugz-U$tG+qCmYt(=o0;^_4;Hye+9cySbz#R0~`*!XYUl(?g$x2v~ ze*$5-TCzAGkZPy!95Bn9^VG{o?W>7(`dA)fXMSB${s)NGRa&hz<`(S)DuMuI&$8Rs zA}Ad=DV>B$9zs+LCQ{of@-J*NN@0ZWHgThUNalsE}a#(#S>Yc(qb5)_%|Z zyvPJ#&3IcnxhRACnz=+VHV?asF~k5NCNv9`<4rHR*4T3Sht#Q^l#G-!%1uHoOr<0Z z*iKpd?4Se-GiHA1$XP-fqHlL99DmZRT~bI(emp}Vj=XPE1X}t zxFoZ_h&7U|M}3VN{mXkxh|`5-{FruU-a&9sB!#TRbsuQAmE8o+y;ir1IJyGdW@ul@ z@^l#SQmT&oB#?W#>2Mrg7GNroKsE2a_*_NtCzvSbuJbG&QPL#u!HV_*ozsyc!uv-=)3ququk~C(^Nk4`K?d`ls&ip& zJznPMTsvWLq8_f?iKk#=8dSweb@K?f*m#AcW?4M3e+vjkMh^F^;vTG(H9M12_he`4 zucNGR`gclRjnX}9Mh>PiY|T00IdRZ2F*^ItcHc5u(6OD3HB{1ni8 z)@l@;@JlX25dqltrgE-FCv=|Voh7?UO%UO*SBw>Prs-{M+cjV|eiewmDbrv4T&%FJ zo0QWfjnA)`>oB|=(9YXdXc->oXCPEt82`niUQCLu=}B2i;b}b&8U0uKa$46qG)#0P zONygoY4l2Kd3D3kOWgO=1ISACwUS0*?cyiW?BI^^PpwP zw~Y1%0w)x``8DOq=Pd)7-cPh#m+mm&j6RN+AC>%GpA&(kF5&>{C-fj10qcC;o2Q;n z!k$#D%R;`kU3a4O>ALu+QiLLOSlaVx7w(P<_e&>+3ELLO^UXDgXAi`jr&`7A6 z+a#VK?QCwQ|E=4h4qay-?#=q5hlpmXh0d``8PyhSx1D}%Oa1dXF@N*J{^SAFM0(z&q;mJHcnzL9P2^=TlM zAP(b}qr=>$dE*kN0uP;j+l>GB+pAB2SyHJW)hyebT!5#_?Eh#wtGKA%uZs^MAuZkA z4T20QNGaXj-QD?<4coEo1#g(8pLx1NW`){Uc70S%<8l6N2PONc?h9 zBRUz75LS-mx@5b#qPOnoh;u# z%I*|-odmACtgCf?A6d{#MXl0631srN8VkSN0ql;KYV^-kvRK}7zD>MPZ5ln^HOf2{ zEd1;I;Mqh&EnwrovlAi{7JWabr3dSE=>hcJ(HVqhgJ&Zy=i3sGd}!VMIkE+~283Mz zkF7|F2c()YRE?Y3Psh8Gygk4D+x`xY%WD&~MKc^ zgsZYA>%?fPtXGc$EM}7J#m0Z;3~(4AF#@t*fekt+M0!s#?C%&Gm*-8&ZBMrS-8^CR zi;-U2PkAL^TKh5b-3xo``7ye3z|p9P-UAgu)$_=&sUd-Wc2tzb$^10F9mN0l0yxaA z$0;1-spkjaH_aZr=!a#YYO)K{cw?nCdR^Np?CxT@yO>|m3i%a32~BN?yF7}EQ~K68 zKQxaAU^7|7>Abn-tj2-&MmM-te5oIx#E*B|MWk&d)q&?O`R93;xwfc{i=3@0|x4wdGI)zRrDdWLZrVn*2>=%A*Z@ag8-+~g6Q&Y zR>#c*1E|5|TV&Bnb)A~meJ4X`w3qW^wctxN9r4jVaFVcl+i!MOH>Bb)8m|kj6D6R0 zr}+B)7E^|C{ws>9xWQTePjJklGG$OQ(7EO53HJ;0qQVmkNY9hWez24Y4y)Lkd9Z<@ zQ>^M>gV3J3VqB|Mau4nXy^=kk_kwwTDnPa84;}pY%mmt;z=X^hCrk zrI>u->M`%GxCQ74V^O4^lDP1Hw{wFZ^jm1lxEq_a#M!*X1R$jMsN~1eBU61&Zr*5A*c3{v+{+ie% zt^7s14Mcr1Fwkz3-4d}qe?o5-r2qkSf)lXR0O^X0Q_;LF_Y$Xqi7 zg{TT`VKq9`RJ<2lb)gNNBgx=3uYvoXXN5bn`o2$6*w+dG?y8Y0{^Z^*XVg&`a(hU` z4xI>W84c!Q;-a*+5{@e@M(`5-_z~YS_9tQbt^?FKL+20Cjj*czJDlPK9P(*WSux;O z5UR+q_W->DFB+A(G>mpYMiv4xAHoqwEMKg`s?qd=7rm|O=i`UF_^bUJ!-Lx^i?`C+ zc|Xj2?JxAj?``?$N8noqR?wc^BWK{l``6`9mTxEX`#~RM-fBc%@R2q|(%&l_FiUtp zziNm*egn6+5?!}{;qbAdrC~`;5dN)mIG7ug>Zu&dYbD}=$5qNJ?mSNmKdxw5)Y?G; z|9J&F7Gan`*wf>Nj6!zZ_InY@5~`X^E)zP{8Fh#dx*1L(Jo&KTn9gh%=icp3 zp8rcms0#tVWNTq>xH|Wpm9&kOh?)I)u`yXcD}XOAm-UGK`mk;K@H@&pSru*r% z;b)cLtB?Sh0jpu4`v^=zp_bmRVtd~QFs4?cum2)V@FJP80BqD8mR-zh#c4pdvNV09 zH??YM-u;%2p`fub-0Aar#5%KmI2V+s^qbr_9ix7#vx5MN?0b|Va3E{@Lu8?=a-i_K zBRhRelyCkK{`ISr#NO$Y9&DPMkPi`F9q7q9>Q@7O^x;)9Y)eE4tO40hbTXD(?a`E2 zLUO-6A};4w&S8;-fiXAt=+tGw;MN1xvrA67Kp)P(X-)@)(cj;>8Sv3)D&akc=cwsp za0vpUOB?#&CDm*GHE>vzLVA!%K_M=z%x zPwW0{<4aw2H~LJ=jA>*nQha34)3KPBkDam843H+b*2zAbSFS1wp$c_N{@-Nz+Y|Qc zZ>tYkMB;nUK{I5j#$wKY~S2kcS&N^6NQ(IS%s@!LAPEg$8Oh#k?&ZNgos_Q(aBW<-h)V`I6sZs?&jTgRY+C`f}MNmDT(HlI+e^&n8Vh zZ_^zkmxi4$;8cIFc#5e>jaE~sSqUTsC8j*@pKQB$ItjlqRVhxKbyxgMU;|7QL|g(7 zbWWA;IA2auxCpGstOpShG(#d#@rAv$U3<0)-{ZQtI`t4m22VX2T2#J0t37gR>P{%t z`dvM5n5r@SZK^CCV`Gi4&sgqrKKrrV^t#abx}imqJzmDy1Ty9q-l;&oT>A5m;yWf5o4Y% z0cRwBjjKwNE|<8hTx~6YUkuwy>a%T0G7L0MvlOc5%P)(~UX3`2PK2W+;PlSQwzU#Y zLl;pU>xA~o?ve>cu?%1LtHHZ;=(V;8_1y6pT4 zU!kc@fB>2vyGfw#YV4Qi_r6ys#}Uq5xJ#lq2uxhnhmeFb>?w`$WJHa zj>1W$+W8J1_fs?{rBpce`%Rkg2HM125Ml+ju$>4>c0dDXRTwA%&1cX2IlzSC!B5MQ z6i;&L*A*mN2McN1D;=onToS!^{^_aF;2azB9!&C_5oCo%9{5H{0oN_pRsTy#L6kQ( z1UuFxl4L9CQ(<--*MTfCR}r`4h_qJ5$oktRTVzvUe>=e5 zR9=H#2=5uYI{2QDcV*tjk2lNQVOnTSM0V5G-(~a3rMeOu-63VcGylz~L-kg?8R&^7 zd$NHbZ=mG-9x3K;1tH?<&ig?~=w#!Ilr-MhnKD1O6t~m%w(sn2u5>pxoHG?8@LrAD zLMJswilA}C;)Q87aP8?u2J2F4H+x2dFH-?7H$cj9MLx{jgho*my4`qq(!U+Tb5gvT zrmMuk2@n<+OHR)qi$n0=nOCo?RZFxT2{;`HC;L=cB||O6tZ)1LZE>h<$}GjSZ7Hqj zsKn2+VK$+N@l+rBg@0kiMN2NB*~9h_48{Nh+N9BxK1Os4c$t^_ot)As4Co#D!6sfb zf5^@2t4TQH&nN#b`yB_ju~=2OdSdOW9e8n8iG82?`q1licNXa737bRt4=2I<#5b`X zcJPuV$!cJd5(#Yd9KI!ie?^+mL1pk(}Rd|1c_`~22d7CL`(#GS@w!^}X0 z0a@1STT^6%Hyo4aZln>YyC&?cqgV@aYkbPsT|DoGsgV}`Z6RsDs|v>x6zXilj%HW* zY{RJh2gQurU!4sN8EBy}$Y}h-8(2B*5<>>*ff0eNZuP*2*!$ z#ky>>aZE-*f{lhieS#;#uQ8mSqI5vH{4DKLhg2+?EUm_B0^IlpQTF0=AeOfK$o?Jt@$|&%Zvif;HZo+mrFBYTu#Fe7> zH1p(>S0ulgRiN|H2=ZZAN`ic6_82fsXg>Ai!GjXx^CN_O%L(Go4F|@gF%HN9qbUWS z`I6dASOm5t4Jj$h$NB<2dGx*5!pT_>e!>5yP<=2CJh-fjffZ?m0*Uy@n3~FW4J$uy zla&-&oYmzi`g@Z_BPFwQSW!FZn8gIZrNwYm2eN{{)kJ=m_>0!TR*JP}-zk+>dgb%Y zt2>HL0&EuCO%bS)T{1F$LEaY}XKG^c^^PxAhu7~Lw0SUtxkT9}SnM*q_G8z5{(Pk& z)S-4iWrBoJq($L-N>6$LG*cQ=exC8bA;c_ErqUJa?;IU`vcHoJ@2gcZ-G`3J_z;D7 z-(@*LaNIXbS72&r=mKUImNsF4_~Kdiht0Oy8Xi-kcXWfA=(6Mu;xLQL% z=$)HF91sHP{wp;FU*!hpwe9RKqTz%hz-7vYs->h^e(E^}4vn%dXL)oh5-GYy$AJYn zbl0SC?(GFTe_#dh*2YF3oE120L}t8Q7kj@=|U zD_gVia&_GK?d1U)qd@GO_*WnT8hzjER0ZPVAl@>2ieo7=y1g>8Yt;N+ppZiLRh&)! z;IhO(H<~}^Yh4Wzz)lu-W2Pn&FR?aj*=d_HF}cz-BOWjaq}g|YebZ;RUrAmh-llw+ z!CFs4IUQw}X>m^W2$(K-2VyZFkGHM|!>*SDrVQ}o;=OD6h(NlTrZykCtT_VpyDveL ztALo2q^X57`>KZz40tOAGpR+&Cs5IsrwS;eQ)75&w-~)6cDha-W$YG`PA#qZ0xu!` znudf>JgB<2O^ip2?nP`9X^u@{yKk?$1VlzJ6>{I(c#kx z0xVXMmf8BoWX!A?$Zm?@JCM(bvWVZ0JHq)Cne9)kyjbIpmujCSYjagUr_U!@V2j$a zLd2O2$5u_viSoueML3gpJWlUv5>s4^$%sA^T{Y8=i~$>@w#k=KH7SI^&JWP_3zgVQ zR6(=~EFBH=Kmt1R(o42Zd>B&L*fyOS?Byl;8H+4#;{6H-fVsEje{^>dg+DW8J<>FE z5-SO7c}-C8538a^e^X|gQE!ZQW?93*nJYeVG&|S+H7P;g775#S%#{7ltM?tHTx5)f z5K?slwGUM+3ZYuDHREeXAo=CRmZ1XOrpmV^rPNAwT+sE4UUmb<#*GYp?~GlSPcJ=D zW}0uZR*__wRY~ds<_zh2VKc+>5=EvDzwCM!ftF< zSP;G6_mjf~32PrkkqpS)vbNJ1ZYt5Wy}4_aGkz?mBxKy-pTyGSZ>>URmI@1*8`vp^%bGXFqz;PzZMjt0?ZN@ z`-jh_=>N-hoEu3=*DcFa54`O7YDK#fJ&uGgLNy#M|5xC@xZN-0{Sx0QO;yHDOwA9y zqUZP=ShixK45yoIH0wNRQPpf5I+{2L0U#^0jz%+!S4Xz&9tY{c+!5eiW!Z`3BDHq^ z*G1rlYC=Nv5k*D6&WN{EPRzX?0_2ey*zuGOtXt_gq$-+>a;Uo^nPDP5iIfT;wi*ZogE zE%X6lXK7|m)eWTlT64}_Svl5-%0H{|ebMx*7j5vRx9*dkM@HFABbv0}|D>zS?{y0B zsMgMx0upqtH$2Mwv@GDyzo&JQ0)v5fGiZ0?Z!ao==7oMFAoY>#foArr5}%U=%?LSM zP6P(yBh6Cy#y3Mt*Ct;+Pl7#!fTz(80AmeDRi!4(M^`q5RS3YVkH|STt^+yffXf)_ zj`?VR~WA;Ze$0tZ)o!sd+NJT6IECOf@I_u0DO5`NSFk z+1%+feR|j(NolU5`5St(KySA3?VoSw9~!8DHk&Rzu=7t)ZAF{ zcvRcQq8C6s0AM&zV=T2KnYE}HoB2THqDkmysY(VN%!^hHSbt$CABHFe$>)Dttt29@ zi~j)hd5(|p!f%CU zT0jgL(E>g!2k(@_>+2|Zp!`ms7zTfR_@4EJyN<@xq_<JZ^=T_4#QTM~>3!5)vI4 zR)iC^=oHNTT4QW!9s~4d-S~O5h<~bl^;BlDANqmH62A$_CabfSbgD=m$=qqmR$tyd z101crG>wmzrlf#DcCI~kGU7N!j79^cN07W+_Xz>AXItnEy}6s_dMyyfiSn?T6n`)N z+EanW2TqN3<8hF_1hseQBorL@FkE-8UshR(wP;ydoXi6^&t-FJAx7W9)uCsvOcRF}KcZYyE{6`++A>$>j*;_V)SR4D# z^D2@VI`v;X=Y`O8!REPgF(`$#P#l6U$N4k05tkovK1<6Jo?fyl@LUj+YdV{H(n`#x z@Q(b5FTM2*1!;m!xAL=t#c&q*Xu+8E94BMl#jZP&sXwmot7|We5IJA*E6Kz3GzuVo zFAEgpfo4wUOU93z=3ec0k2z1fU6~lRG{#Un2e$&o6bhwL5ldL~<6_*?o7%&E-FOOq zUO)$XN0@0T^J0=S>j!`Ao=I>zW}H{fP+dPe4aWzef<&FAy|NX}j6de`R+fZy>DmUm z=CY@|?siOl$?0CRO-H@_sqj#4(tT5Vq6n(ZvQHoO+AD==q%q)72LA1jaQ`RmQ^p35 z?lns6pdiH4`s)f;23cb%5l=Z7h30bumAz4CR&npav=5esWBUz{`Dhw0WXiAVyprsdUA) z{FBpMu{SLy-u6FjR0Y^p>*r7#qoh?CfY~#G8nq^#lF5~k)FKJyHo70bu@jr4IMpay znC8O&$XdIkq1NWh2Zw~U&Ll)SrEmIGzGIFR)us5U&1!#5XMG5ihe%px!ZjF=8neP+qAx``O zKy|&p9I{#FQF~lkHbGuYYMifHbQZ_Tb8s%(M_=>)-7(Dc5W%nO0k`}Izkwj*0@8Wa<-6#kjd<|MRP=o6|KU@!jt^^1o$ zv+1xJ`-QlWhV+o7uK#`he;6q=nnDonNMhV#IXf1oWX6I`G$Va@$+JHV1ioi_Wq)Gt zFZ%uxky-@=HSsXA8?L09<2$4@jZ8IL-1thI*mCpJ7>{Ztu{4>Cq`1b#1;kk?o7NzE3Ky!dqST(c+x5^Ac)oqX@^(E@$8_cQ{=d<;d%AKrN4>q*8J*dY z-`_}rKCq;|{Un-~8A3h!RK(~i@wr>k@8t37w*->@*6Y*a^UgUV7r+aW;K^^E9B`7u zR5(7i_?(W6s&{13-HWtGmeI`w8#4A**4b_`Uh^wk9jiV!j{|R)^*RcxQBsycE$Pe( zzr~ONj#cNL-GGZQtHY2%*q9wb%}52WsLlHf=kWVJr`xEKz>6@!0%LiAqQOyKweME=TkNU_-9oVs0L36N&T95 zacVp6idHMq(a3~3mI-Mns;9*1;ibR44&dHRTV+bnq_I(E?E1?3%7dEkqmazJ`a6i9R%GSpXC3Y>$S<*_73;Byy3lmhMN@{dP(Ub-cIy z_fM})k3e23lF%GhpjTlZAu1ttOy*?|76gw_L&2efz2f4l+^-cuK0Q|(EuMJsu`_=^ z@6E->h;`C29NfI;-K)5R&q@^Pt1;Xe3x-ef%Q|8Q%pf{x#{lN)CEob5g~SHCs08op zT=RcyqW29DyRL?ZSFzLCN`C89=sF^80^pC+WJvfquX_b>jSBanc%0n z_iCN>*$Eo|q5PYA$pY!`J->V!jBNJg!%5_h|FM?iJPeUJT(Z&~0-{Y1m?7t6893OB zi$Sy>8a>%DKAc{oPhZa2n9I~!YE@k|1vUwY3a$jT>+NK4L%>257;w2Patr%6w^k}6 zqgn#EM0AFGHcwlsW?;IfIy_m^4+U0f!l{^b^gTPE=&((3I+zu8UB@WPlZC63W$Lr$>CZaq$VyX&Ov0O`^ znd-ID99TYjx*_4+bKM-|usoj>l^UFc@}b&Fi%{ zD6+hBhoB92_pIIV5-Za{WU%)O z57AjOy3BnpNSu{Jx0dLj?LONV-%{7R)898)p3ujsO5IKzMuiN(7;+5oySa!1qE82` z-IWcRb%b)8xkFia8yvB-f|VQMC8$W@oX}+3a}E9 z2*nj*k5sL6y?Z>P93qOlM5zuG0pR7Ld!K{jNcljKnY=mgxH%5Q6rWn_@PF!NV&4A0 z7l5H)reyYfrPLTV^s zvuCxulS}~1M(A^BK65F6@Ez~Cnr=iyJQo0KZcO=UcNv;}Pn73&co!P2==+|yQL~SD zI0i0`__0mOiaypw>llLW1e|T+qiBiipZamU3otnt068X6mOOa!w-LQ{^{{Q9)oTVAnTLntT7V=7(sPvuy>*z1Pz`L46C*78b-UCFvJ`W)Q{;rHh3@0VPf^RH+BL!!;W4XV1! zp71-88Y;iaLy$@_%pg{4v9%p7!BA5?MpDx?1rk|GdP}AY$icj(pA=L0PY{Q?S+o=@ zn(C^lq8qbr@!wqv>|KNg@_Fk+2h`k|FaJo#k2g5G7blE=c$9w9u%k64^RU^a7>kt6 zy0FhR@9(&a@Vd+$o?tHd`^y36OozR5jBPuCA0}Vkgoll& zZ!vG}l!9f~PDIL);Bt;>ok|#xyXl_mRCPj6!u)s6~Erumj=_{cI!XvWi>p^}QkAymKS z14$760!4hI*4~B=4DHv&lf}HAO3-Y}&Z}P~`W+=T^yFP`QxS!7LFReRDu;bzkf~`* z!8Md_A1C6dY~Bk+{N69JfkoF$6?_Rb^?$SkB~ZtZUdCGNeE&q?;!!r{y$5L6#6qfY zj{xRe)~auEG~;DejnMn!EQ^zb5WhWBNyuhhl}}>TfY3UI;WH~^k#&gj3ViTzjZmvr ziT@e1=7QL_K*;nA3-{rRAL+$~cv`H&1+mqHYZTgL0QH8}mb_KQr^7G=A#* zt$UB{7syyKu~ACy38~on=~=Q#jL=@)PjKt+D#Ne6p+_UXMhfIE`_m_mrWZ$o(19(d z^gF6AmG6ZPG?*|k{M=sV7P`*Y+iwTnZeO%s`^0?zJW+a`u%=Lu>JgM8gZ?Y`AXyN( zZx>8mIE!jqUBTA_nBK-kP;t~a*dUh`td z^Xoby2AsR(e@UcxIy(#bdOCGte-hh8hz0=K`7ls>I)^=PPpn?TbI3$)QGe_B@Zi$+RJigrNP8^c@KSycpBNPvSix`>hC^GjZQS*q2G|{lbE*iJxr=c%wapHeF7Jqt z0@u_+iTmbQzk>Pj@X|5HE@A(4g7!F(LDlZGyNM_5ycf{X1eub^BU4v>dJJx`rc3sW zRU~OI$+|XX8YlgB$KgiyV$ZM{!6&JdW#3OIc3JX0oL$q!JaQu4S)&Z3Y>ts!mio22 zGOAQ49!9~F`j`TPYa!nU?XMnMy?|Ig3_;SVj!%R2r6mlGmEmh&yjXK6%I0mg72Cw_ zk;N9CPP+W=8&X(UzlpTAzoKc)cg>P^RVi?%2g+{MyL6gybRoRV+a48+!zSkD8G)6` z(3dVXvNgouioL^~khZ`M>2LHnRD^7mSErgQe(I7Q)L$CC{C;8Z6=))({s8{Nw0Ot* zh3H#8r;nF6M8vO)Z^EMx4_I_lky@u+P!fhGImo)8FzF)1kMdO1e^N-0+ zXygd`dRnN+4bAf+6iXU1Q9Fo%uljZ$OF5dLV);$p7pcP8yLF*ID&MAYporpBW4DS8==FHp-L3>^fvAgLhno) zLqcqyMdbM0ko6!u9yKjf5mDx?biONTzdox{0X)v}ICO6&$S>4uM`<6{Lg{c>te7ciHhNOUWovC| z^^Iq)+@}ys@ca@ywua5141U^>fTG_oRhP1{X&PGhlwhuryezLo&8Jh%tdI0G=(pcM zJ8-VUl0%8%R2b#x;IZ%U+U-BC!XVaXuxvy@6FSm^=3rQr5ol9^PyoL#$odYy6d1d^bG z9QES9EHNzhLb2u4lC01_@Z)S+2us~pHLmVc%dC$DbsJ;oE(oFd^cG{peHRz<{6}!M z*~WrgbavUaz9u8!!D@!Y)E)S|P_(EaoS#%&T@UsmC@m!`Hxu=6#)6X+pP46!4E-BU z*>-3}1d9o{^L(0uuB`0TdG{DCg6HC;(OO-vD)<~D?Q;PYDWOl;F-WiA!89cSo42i! zlOr?=Ew3X6@BN@0<$3 z+0pIDp;%`YEqsanu(luRBV)`?bW+zd^QLO&&(GE7q#@+A2OHw7ErW-*z}~ynTl`$M zqSD2iWa2oWW5nsW9b+;>(G7NDY4W94SpJX2A^p;{T+H7=@`)u5mqS=jh|;-5*>r4< zXjsD7VsZy>*7-a6*})F-H&KF_II!)*euZjF$lHQJduF?~aQL?$DdV8_4V6#+hOud> zk6qqok6oXRt9-F4;;P5kXppX~hw1`aDzolHNo|O09z@TM?G>@JLE8PR)H=oJi%Sh3 zNdX315^WgSXp~BegF|Sn2{*TS)tcdt-QEdT(|XT-PR)YsPs%Q45CTS?LCc_zDE7`+`Q; zfSW9Jw~Zjyv$UR)8TG0Nlqxpd_<1^}@e>V11u`%dLc@u5c^O&pgYkib+*(qHK-hQo z^-TMP9ps$1WdGl31^M&Et=b!;LTMdAlEeA#=>swFO|ntKkgq z`6|I;(9F}sW3Iwtot7_h(f>A$5PT&{%CclV35UTQiKGu}d~3dj(hhdq@q!{3*5oTK zK$8z8)c2AH2OAMdxp(+$V79sQ&CO2|Q|=7Tm*Wqpg6tH7;#Les(er(|9{0DdE7*$MRr(~fXw{O>Cz5T1d zT;c%ONDxFTz@9QLeZt6{3pa7GGWy5OSn_Spq1z< zm>W~`X_WI*M)#T{DoC?s*H$*LfG!>ZD=V)~l=M(nh6iq_x`vEQjHO#8abc_#zy0@> z1xLrqkc@PAtP7ot2n{I`j?t2$`@wXhIr?^C`&|dnBZT@w{s0YTwK`uuaY^FZDU&&U z42$j}gjHRPq5$?U5HJ#IRiRa5zPk?pLT{<_6Q%iAIoJ3OWY~sDLm)4HA~#qKd1Cf5 zEl=*Z{o2beHfV|P?;Pv!+LO+7qJDKfd)JGQA09$eGXqD*G~JYp7jG)JOlUK8l(XWr zZ!Nz$*$mK7PC)^WpGyVn)9{qLUiA{Dj*JnQv733``Sn4*6}v9C8A%(c9LetaV{=EN zUd<=PhPjMIAknWqZY82S?{!4680<+T|G;2&bUzr96qDD^ARc*K^zovhZ7i-z<|8N& zRvg%T5w;nkvXr@V%j@vSK|Wr78(j0RW;j~0rJNhs(RL6q3c9}au8f-q7jzgchB^h= zO|}vt;e1*$@NO)W6B3~g2M)>_*vZbC9iSnjSjcgYIbX}p6==>ca_FE`4qC#>q0S=d;aT-iEcj?;v>B8n93opWei$T_QwgG)u%vE4#jz=@6%iu)TuU7?0R1 za~zQ-jS-|@*8**4ip4Wb@yXB%7JUi62n44WPNR6SCLC2NtrQ)#mZ`wGrT1{Tb@(zK zF3wg+zmiZHbTB!Mek@cLX|}yOx@9jHlVDd>Ok!{O$jfB8jN~>z7JHg*eY(0jC@*CyU9ys~J-+U_Ae^BC?#Bn+>zN{wR3(b~{ zMDEcV9F2L$=ON%PNCEH5ecO6wPnz9=T5E8FVsP-TIho)c@}JuYok-iP5eikUlIcIl zRvocK@W6cQoA%P?)qi!OI%dFtM7+1$h2}F3m!v>*5*B3{m`&q*)#3qHyln0>76#EP&tKYu%gfhum7dQ!Op|MC_6a=?FR1>{nbW*46sP zbLY}YbOb0-vVISpBgFp1NITwT4=WMx^LeW;6|Q#4LXTXmZgPX}`hppc3MEV81$dpHAU^8 z!o6&cPV|Sk36CN9RVGGS#kyku{{}vLMNp_&1*AJ4YVQ-*Lr7s7o00n;)1t9?ELfdb z(te;%5tL_)?=cUJ+A@BDAk;(Ruu>}RMS0BKE#hQCeae(7wM}^XhOAXw{_BtlV_`!D z^?b=7&NJZS6YpmZ!%#Z*jzkb8{KiRgq>Of$^=ag1OXm!xHPXd z{V&JZpQ^Kn48SSNORB+Zz^nyG+f(hz@ql59S&sVGl$)raM#dVz?Fg_1L`n1)Hbv#s-Hq;SG( zbUcLXZoJlX6|CUlz9rJllVpbm`Bpuhqerd)=Xx|`K7kA{?l$yjGwR&&|gBWe7Sw5V|iW{bXux_)yUB=xUstiRljPp2X*K zWV@~TQTFS@Qb!IinF%Q&s_qvcTlvj`>sIREhX z1agc}Zy`Dh{ZB(ti~pO?{6bw#{Z030t$5*8Yq>K=>Ha37)0CYcb;Xk@vpzG+dH^8a z@__^06buvQcr*is?S!lmQn#N7BbBr}y{e=m#o!htSU;WWRQTU*`B+)mevCg$%_Bzx z!G^^63Z1z>IKN0grcBHR`ttf$vhU6`*H>#;G7kDK%_wc*<+mHQC}aGW;{; zlOi;k5=Xz7-6UNc+Z441wwA^l7MrNLtzUaa{=2bnI=^H2r2qWn=l3IMIzE8!%|hiR znYC(ZF!P&Iyv&)1!2M&#inWMphEEx<^vX1LxJoim%pm zx?JiSn@cNPW?4vJrM;@C)L$S#oOr^xHwX?F?nsOy%1`{!0rAW>y<<0v88SVRhecx7J+NeW#VxCY} z`_cj-teXWEk;z5@a9Mdn%0^Liiw~y7tKriD-@bHL8!_5&J8~Ld8b?$;J+dD@{A6jv z2)je%$4zUv_D^%@c>8ArtK*YG-q)x3H6P-CXr!M%s&)&EB7L)HY$1Vo)YPX$20H}( z%~0Yq6A;y;u9Tmpd z^(bLz-APxC2GSCnQ!mKldRJOk_mctXhGyJWaU#b_zW-=Cg-0VDGE7 zSwkkpfu+`@VR-NmmCY#EuBMP$i>_W`b-d#Ku!~gE-&4!-Z=ae33sWb+N>@xNLVNyR ztd$<$sbCV*WJDD=v1S>>AnS@SIlbZgW>elGkyUNf-ekR#wTC*2u*rr633D!RWu$m& zV?H`@!E?Q4-dCfaITjD9TRnFaDZ#Q^0_OkpQER6%)DAO#pE(bQ`xPX}67?82;c@G= z;vsy_ikAAgH&2*`Bt$RH&#ILOu@w+3m+YQSr5mLaoFGs$TRKv~u6c5be-xtU*?|Z8 z9NFyrSsn}$TYXKCGOfgm8ple+ZCd;}sg#y{>W+xbKziE1x0|0M2Ga>iW(_X1 z1nqgw3rBwg`dt_oXNgoLCG#XLa}X;Aq6+eTGDl#m zy>w1KK`*2{z3J3Cn4)^B4&-Y+N9$_4=yi8{nv*lqro=ouA$x=6<#i2J1~mv&S_~MH zxhE3`xju+dinI%ymQY#7Zm*q`BoHk~ar5_ujOZ!p*uSj0E~#k>mAyd5eR^9?J(*jFsPv3V%US>TMw`cO1b|%<${^fglucw;w zv4Hlc@E7H8O@F$hWoA0a*X~T76zj=7^Pv?VGeAZ|&~0zZ5jC#l~3CaY&HIxjvZZ;^e$3zvJr z(j@k5Sv8*;sg3XXplZ)@#&%7arlJu1+rSNnXU|`q@TDV>h&bQf44!$$!8Lz69{q!% zq9upHn$O;6MEe?IGct?rtedZLit%{flnlbL;B6+vx_PY@)}nb^Ek$=#LKhaIFE};) zKUqa$FR+9Ud47gp)Sgh*HJVMH=h-7fM&Xw_Z zXVbL6YKv4R{f_5r3(IfwJgWw7osIhp#RX^=l9GMu=pnKv(%6ar)p4CMt`gs;z z=~zma7D)8KMh+)xpECVqGI<^9RN)$d&{x*`C%nKa5>q{7Xmd3jJwZ+q3;1B$)XVMOoI} zad+PLxq1WM3J;7WPSbv~!%AnS$TCD_dQ&MW{VD7^am~*uu83a7Td<@;1mq(jglr=h z$}JNvQCrLa*uP?F(;|aIUPkda2Tz6E~&vwG-)B?Wv!`qJ9tn^08@ftSxL%%Qf-BcKqCG@VQG7 z07NNQrCU2FqHi4^ysx-CPqg>mXG2|I3WAtV`%1=KmotyK`Sa4*jB4$GHm)GyNmI^e zjfA?A1Kq_>G^}>5%?JQkfam6sPI*=O$@JmKeCL!whFi6G-FfvBb?%+uneFN~<=xM_ zOw3ETQVn|J_a7X5eOf%u%fsH}{r=%SqBxafL($=LW;C@ei|%P*!ez+jP37v9nQPeS zB%6EnYC5xA)SkdT04OH5xf+IvK!&6*F=}S(iFkT)8s+FDA`ra3;JHRQCsdYe<#cJC z@!hRhtH#-0bYn%%t@pF~isk{5^uRPp;@1Zu?$uX&i(|gud z%j(|-05^HzN8VJ{+T#N09{4I;ziEVIqr=J?pPxMBv-?-)GGZcP2;iJUj&Va06(R`v z(Su^;N*ctBF&OTva%x5g73aA3!IXgidN<$#M+X({twhESA}&Kl!y-L;b_QKvom4|< zY&Fgv4*K`E;Wy>gJpgdtTBlNRMe z!Uarc4qy32Gk5S$SXMoW`z(NF=Q&eP?8nBip7zT} zDGK2u!WGYBSn1U;@ z`-7~AN=J?E$y9vC{G>yry%v(oLpd>XDLZoT9^$&#{o%B=8gj{ki2d-J{R_|5sE8-? zj-(ZEiB)DuUBwvr;G(Hqb2S8y_rE`0xs+rBP4Ei&!pev{3_UPxPOp)PGU&@$$ngLD4yPL{69Am+~bDz|fn(ewjLfQ_JhAgKhZOOC~ zaKVUPQckTdZDT3eediQZs$U2?7a}6%w$?%dSB>`GdguKce{iVBE(meuf~>bCAX0nW zS_^}a_wJj~t|Gq@;wDfp5!FOFF;U8$@kjUb#l^XFF=mXl*CQEmK(ugQZ1o%4>8tE&j!9WDF8oloulFTWI-<<6_$Y<%!5FJ1YK>lePV@wsn( z|Eq@&4*&FU_=CJUnil)r<6npA&xYZxNB{7@=-mGw$nqd*$qUca#>c9*6vTB&tQ_Je zlHnA2pU=_;B#UZdp1REh4tL9Zf7a@3zF7C(PkQRgXPdikWku%uy+P#;kekLOw|rS1 zKXm;Mo>H{k_*a-K*~W|BqjT00{c7A(VGYMey0HR`V=*?9W0kfgjhp6$rVJTDpRKi! zS`>1I76Ib{lP7?MbFg)*KCd%QCX$f0jC4^uweD`kx>U5v)Z+B+cM zgjssv;@--D+<%SsMdkoN2&}hwt;NqB3hU3OaYMZR&weyf9}#xmnryH;K<-|DcyVv5RB^d*2{P;)-$%2RnF{i3%xcJVRjxd#M9Zml#_39_LMVxA8*m&|)uzmbN?%rc|DTdd!xd4SPjMKc~!72msMsrZq^vXsLtCP(Hxtgd60;hsT}G4y!9Rc z8S2tn)f2;m&zyT-p|lV{f;d*#a6*`DL|^ zBtPu&K}BpPN(gN%g@{ls_|f2^&j8}` zc^n2!ZOgUxCstov#&%Y8-_Fb9tlaO9ZwI1&b^XhqxcVC_%@?wAKQ9lfBU^p@mipc& z(+7X++2S9JAKi4u%aEzkI!9M#R*u%X0X@_~%$qCWtZ#Du;alTcTgs4)4l25aWOq&L z)*5fL1NRX&wB8$SNo!wBY+U025X6k+i--sgWW-fzo%Lx`f(Hb!)<-p2Upj3*=Y2kz z8+zw;=|q53qLZZV!mYY4oCp~C%InJ2II8b zLBwf~qPx!ov&I)ALnBp0)TK4rS?xae%Nt~DM^nASdwH!BWJ67M#!*es;L2*JE4O*8 zjsR&ZU<|mNO;`b-dok{AMW%9bQ-(1MWA2<+xofS4B48pwT{Tj1DvO9* zU_LV4?brkAl3-R40jqT-0SEcmkS+b`SwGmk-2Aoemo80?6miNroAEjN6#$I(H4#FM za=Nf8x3#vcGIGB6ga8tyQJ?ryH&#NrHK!%9gXh28Oxwb0cj1{D0Ni_hG(Y#_raWh2 zuy#GoCwg8XhfT4lALL?|qyY;K?rS&Gd*2)V_#G&DR&+0mCx!n;JDuAw!g`ChmUyGX z&$+YLIlR(fHxjIK1b|x&zQ&=_PHC^T?*{nUl&u_A#`wY5%(dZ*C6K9{sb;#}{o5IM zm>lWo?Aw+vCBu`0qjMq3N7_3-I;g5K`Mb|ru=a&$w6B)7W74%PZk;-}ClE6<#iy5p zFRg`N*@}NU%0RD%D_X>8CHX{?;@3?*w=M z{<(=h`LA`iqQ$F0K>3`BO-g*y1D@)BXdJQ>kYzpqy0lSUwARDX(QK?+ zO${jkM9AX080}T{Wm#sXm>3Z-(#VGiZ!87!ghEIWgzB7w`_nc|MvigBC41@1%gyD0 z@+O>v`f}jCLkP7g&YmOo!~K7;#6KzQOD=0J-omHewzXS()_UY{{IFPkWg0b#Y@ip7 zc;^QfGF-lt(50R9^vb2gJ5Yt)xRLfBm-$e4w<0dsbfAgo0RWS}CN{gSY!Gw4fZ5iofPc zz&IX1EN0FHg(af6QLf$zy!X5BO-MJl&JG7H%)a}y>aX~|+@vVl&Ul1%uDu?E1kYiT~whxc>x-3Ve< z>&UfhDZ%`gUT%Pgu)$ZaB|*%`#|jyhu;`4R9O&gsG2>{I`^InW(0xm~V*3+K88ba{ z;9>id&2nn{JEf4Ub0PBHzyA9Nivt|u>})(!_W)#&FC;U{rEMufMmq)pUR>hfaaHRE zql2>6kwnUfYCLXm?_mEPzzQUOpWt9$=N*AZ9{h(&TYds=_svgPr##`mB!ZrGIth z(Yuq)=juVsOy$y+*nMxh^;~`Dy=ko-n8JC0*2M?_>MKFq5JAk4p-1@EKi*y2k^#rE zZ#SN;6%!*Qd+qo3*KVeOkTj*K+`Tu>Y+_|*y#*%V(OY8~Vtq+|@a;k4>Kz#g@5hs4 zW%hsO%KDcW@}fF6Hb45dzVm;|;q*iIsXx;F8^h`SygG!d_mgJ%3GrXQbmiCk(>vq* zQBfUd50uZlz#iY*`=dSaJ84Ud4yyic;XU+s3U7T>WApN8=TBu9+`aeHNyFn1MAVdI|jLM_q-HWd(E^)YXevH$- zfdH^{i37mq^C2Qk2SpHa05GKm@cBr|kXhx^mK+}|Yy1a)IhY*lVr+`BsWKPU1QTer zCx?! z3d;oE`g~UeINU3p@t0fT`2at)72QN=^wh7tRQuPi#QT{YIwju=VnH&dcu8|B&?k<#gqix8rhZ zwDRlMYk*jcjF5N&c}Iv?<&G>h=d2b0i0ZtzQ?^z^A#r$65pBn4Pr@s2J$Nr87Q`GG z);cmD>ES_Tl(WXY^Yx?o#X<0Ie(jLJP4Yi-3lWoZk!ji?=Q0;0ygHeh0sxmNBqQ@6 zWH4`j(w6WZWXMSRHzy990$2hUXnjCd-`PNynUOJH*_1Z-_r9I)ypc~1^~Dz(&iKLO zlD>}jfB>qnOd^TIsR2uyqM90V{;D#|1)KIYm&{aNSMJVthD#SCI?;6L8Y=-gyCX+y zJ=txv*2B?$MIXNZxMUo;K+e$_*WWD>XV<^I5t8RO7i?}!PBq@#ee%jDn`K5lGYt1D z?|s?{WXOnZVYLqvF+Ng8xwIw6hm}>f7@68qK(m~DtdAZP*+8#cPO99dEg99sq^Gu? zuR9CgLz!7!I-?xt7(}eUTM!Unw3`k!mw5ajFQ?WSAIylHr?V^X{j{&cM9kP9;K`So zrVH6XGloQN%0`;VKBQ_)no{K!0X={S*mR)!yQNx~OE1PB1H$sfxVKZ%{AsQ$1R7C$ zsB$~kta%4qF!}&9_cuKCP)7uI60G2zA0H|2f#^{rx~FshtS2A`0A0F#q(#7VVbzJ` z#5?aDSnX`(odst-4eGoD@LpGT#xqqeAL);6r^#Q*Q~DFg8~~c19K<&Vtef%WjN+uc zcLAa$KM)F?=LrR$)EYZ_ebA4xPN!$XWwprx?E~LckRM2*5mb34~Nrx z({i7<#^ZdaQp2s4pV{cX`oZr1)p+|q^#{MsIL;zs5$7b+AYv4i(^w8pt5D~IkOwKJ zn-1WuCewFI<@kkXYGnHUbk1qO7)O$za*i@$Tp}0DYF|!GKGx2G2+(SO;CW5vcwcQkTXWi5>z23UGPi&*cvO1pkz%l*azy42-|NP&N>iiu2iUf2?Tgr&*%28BzRF~t!iuh=LA^wUi4wko* zT1PqurgGz>*&gl{bT*p-oUF%r;2=SFVTM?Lg2>Yt6 zT%}y4-A2gJdY)w zt2Q}Oy}P9v*`Ue)AL8CL#$XDXt>BNjAyeyY{=^ zv%gzD{BPY_x+!ZMz|#^4cC)JM-gD1+m*;(+-!t6K>kE=DDaCB(7graqDqJ?T0N}A! zz`K&w{`!j(SI`|C&r}KooEBTtY|}Y?W&LMPFMc}oJ4Z*bN+$qtd*_db(~r_=kKH}1 z)APr6+!g>JY971b#2^Mc6U~WjKiVzbY&VRI&%o?XkGwmy9K`U#uv(}AwODZMrtOZqWy?}Fx`*-u1Cjg+z z?WNDQxn%Rfyr72MRBK8-C%Snmpx)l`UKQ3wGN`t0BuD+!bnJ8tZT2x|8;p)Y=rW~4 z)mRD$X}Nzli(B&aOQT}^h;LOo+uC_Oy8GqJ;y+$!UIhT(Yg(rtnIG(|2Et=P;CtWf zufNa}KFh{x{(Q0{{x9bsYDzB90o1ylt}K9~uAlzBZ1qZw;+ML#>8P4d7y!^&3-hU_ zF_#vv&bcZxiyILlOnS3R=`Vi>0Ox*s%s7_g*$|(X{hi?(XR3d{_2kz4R#Q3|CAW`A zrz7hu7kuG~w>Phwzb)bFp&;R0!*UPD2@g_r51X(~K&l>rR|j_z8s$DVMR*+Le!_$W z$IW4f@8tN8`Z(R{Z?0iI6p{QMc&~^3Sbk?}N*|73-DhXsN8*Gw6MNsO`Q;TZ5dn;{ zWo7~3{@c@ZU(HDkq;iQ&U}MRrcP4!%BP%zFmo@qJ@85owV4$wEE+DIV{y! z>0Ix3%Rl<(PoMjRv!CCx7Me?b)Re+!Uc`$;f9JP$=FbHpdLfq~j~X&hi025%v9lJY z50v1T?Wk;D13>Gv4*=b>A>$~0cJb5g`)^HzL_a*BxqTw+tcCz^@A|&u6XdhG>HOcp z{s->KpJ6-iYuVIBnIhGVCBY;Xi4N;R`h2oqGQqU6);c2M_wQA^H!3c0=iSm7*IMz3 z0>e1Y3qy%R>6|l_BgoFmg~)2R{b92HWSwGn&cc}|>+MyaOYGmz7uLh5DYtIS>|M2% zH)mVW*AqUILS(hJ4pYFj?F z9<1*c(N3Nf=FEckk`F)ke0`lm*pz@kJaR9XY4MChI#iTZ;R1u2pdFX+(HOUIHcEyn z9jP-pGSR{dnZ%*M(AL`^9?Mmzto&gT{HG)QtWYpE+U(^&N1{@OmZ zN7LA@D@%}gD*Q_N72|mS`jq4tCfFQOt1IgT;>eO0WXRKjy8GS9QSgK{)(aRSjQ6VU z>3}|cT9r|H-CAHAb?Ht-54LV3RM0#*0Ch7DXXZ+dBxZ$mEj0&n zZjGJxmC-h8N%|)M))zdh-FUam#=6XO5OYAN3NzX%wX!Q0B0u7LH`8fvMg(gv`+mfo zg<4A*+3h#S zocR$a`Zb*@F$RE#2rB2m7)RIHC^uhhA4u>{71kbKY9R-sEtU5HK%VHmo7uslXjT#6 z0IZ%d;3<{S*~7WJ4nx{^!g#oTI$n$ncEm};w`dp5Mj z(X)(*oznreMp_G2yD~A<1xy1V8NK`WilvJ&0L05OkdLeFpGn^Td+GKIc>TY>Jo)7- z#ecVIe$1B*!2?9}O$T}{&b@`V*AD6}Ed$tX_(#DcC4ylob;5sm=zv%1_?a ztB=>IfWj!N3UlX;WU^D4%ANmobF^CqH8F#5N4(0-bgx>y9Qz@gBf!ekq&;PgYcBfb zaArh3^K4^u#OO`x)vPVFasbdg?Jr-BlYz48-ylLL1bPua+EIRp-`WW65#ai~Jpcd} z1%9%|0z^YnwRNi=s+QazR7GXW$`+Li85rZ3an`!s%3V4Au`Fq1tarZ<0ZRte3=Rde zj*+z|>d4^cE29V3vRX$XLVdyO-z%0c#MZcKYAE60*LgnH%_ScY<~5!32QVL->BzX5 z&*1yIEE*Er`29?NW5oXwmbMR28%2M5qd&PZN^T94n@PUq%jRn5#nX$QZA9yH*^6~k zZOW`1B>7H~@5+Y~Y@M}06}ERTpMR89YRFM^und41TYXkd4D>;lsS!RC9?QlG8A_iE z54mKjFkB#Ix@YUmj)dd9d_NXs^~$Gu?eQ7_P>UDgtL9hi;)^Xx_S}ABynHb>%6bt8 z2cv@u8u|$YK0Z`n-3-Ne`f6Qxj3lrk(TKSD?$laPr4<6HjQB`^6pjI~5FSFhf#2oV z2Y~vWT7T`0-&<}y)2UxRxAH?9 z%U|H=S^FpfYvBVX&<{CsTsjxkx&;?F?N{Z&gWX*5XGJ+4f^))~6_hNj2l+&6<-CyR z6FuB6J8J=#3=t>$)zNyzTGun$HkW*7!Px^5$APM>7qEGgC;*`Bbw0hbc%{!6a=&`& zKiNFcum(Fj?{tU1*uKy>_LP2R^wfX$_QG=_EB6P}4<`BjsEN1#{BKFXIvyl^7>0Gs zfpw&SaQ?5y4Nu2xQ4fn*aD*0hEbixyrwHAnWTBHLEO#;`c-)G0?42C}S^fXeu#UaC zk4;A&f15|{Qa>}fH4gk(PS=Y+Skl+38 zq?j5?z0FQLkAI$>(*fh?`K)_7NczfICw#^@3ZG5;m9b8jHXT$8XF|#wcGtr)(dk&L z(n^o1+(@6bmV5x{-!G!3Ad~#Una~e8AiVhpdqG`LqcAeO{OL|((M!jAyjKQwE`1g? z<=(AK`m;jcg^e&D>-Gh|vE=zNV+@Pb2yb@exN{?oyHa>)wTqjxNXz-pHT|0463d|h zfQ^?LMPm97idsk37d$SocQ2=deQ+Q`w*F-O&RgTN&o*>v!X*7Z@1+ap zLsMDg*g6%^Crjom(O~sOFC8i-aMCMl9mzP>yRt}(KAtV7GYr2bHs4PWUA^nQ@*CR# zaQex*wUcC|P5-hs`8d1NAHO@zH@Ew*mTHU$XTG>oPP+Z=dx6*LJ{7mmef0XT?d^}Q z=biTeY+m)PGfA;s8$GS}e15*)SsxXfKk-+;a-Iv^{U{|Fv31I)=S4_XOtl|z=^--6 zCyLTN^#yOdQ=FK+mM=%L!Mf|AQLee-M-4H!QviVHGomb=dAh+R?%mGrzn%1Z!~Ndo zG~Fr6@$w}o)p+B1dHs(@vYGicKH4ftAL-xE>Gp`4lJXSJx*+CZT|_=xT9eCXqwXnL z>qzoKZ-1Cl&*pr8MQE7TDL?5|jRilb6T$=M`A0A0jU}(O5?Jl_Ze<(KHju%s*T(?x z#1|HJZ_Sjfd3=c~2#t2FzwYKpK4@KWm*PYc#Hx&h!{7;{D{sPM;(PE83c7fhna`S zwx=5iXteV}?f~MB)Rm))fE;O3MFc(YO~)^| zOR{bOfFB7Nu(If-yFLqUxQ{z3fS{~+)Gr`0RZoa(%= zzVriUm%n&n^+(UH{P2ay|?$R^75a`+Kp=PDR1-fbNl~S zH~S^>1qU%L=A5(SOX76#%hXW){BWyCM@lQJN^6WOl9}v^h@@;j3_YYz!P%MJj83`k zes^M(Q>7&aoVAYn{+i3aDh;^{b!CH?3lB+gZY+4ygC_g>f+s_+E6W6UA*bHSY^;{f zN0Xk)Cz>14Wp|N&$7#`L|k?N|n1ixbp`wxoxf=}N|KKE>_ ztHKCxHguG!0S9qYlH@6U<^b}ELBwpVqn5D7k%0>Ul2KLVrn&5=gUSndt>Xb=nd)?3 z0l=ltb;w8GT@S{)C6g!vR$r8UB#?pdnaZtmuFMP#x!FYJQ*Esik`em?5$UdLE_sN+ ziWm8WuyDm-PiM@N&x_@UarM0 z>5S8*9o#SK5r-1eZMAYK%Es#a3(etnNm4~R)MakhuGYtU)q`u<-mPM|Sr${XbE8@~ z6D9p>286v5QfuLHwb#-5nf|%)LL+X8q*wi$?m+!Ee}u3lS!>xpYMq|92dpz^o%0z! z7NbNk)+y~mgjT8mU^LN6yP~k3gQBw5LZxl)voAdsfB9Sh0BaFnKOle6!EiBEMWXYG zE)v~Z_U96eD(vD$2mtrLTSQG>U-UNLOIj;_cRlc9US_5mAB>X>lA#hlE2qY9o_ssg zo(Uq>XtUM==kfPtPcyc<`+DBLt+V`|3BG+W%IQiaWi_5;5B5gy?2oVSjoulhcPce) z#vAL4pNWGdzSx%=-|(J(d7R$aA6*+vZ!E%RPWW9va`FnCcS(dQjueL2Jc##+|xU0{~-eI#eetvAef2 z=`(BH!bVt3vl8=BVhL>Gz9#yV*5TGvyBsWQ9z zSglCRJSs#VtA7DZP;Q-mNj@0KnN{ z98`)30N%Uz8?S!w%ddaC&<rf1x`mlU=YTN=fJI`GzRD)b4>^~({XrTwMNku5pejs0Rr4+t0H}B5aI*+% z0ufYckO3)Ke#jkw7x2MWez1asg~#5nFAb5w?zh4lzqcUH&IHum(Rc4$f5Ysw5E%k8 zCTRb_z3Jlfulcg6bk_Oo_QQhuzdab%p>#CYu;${7J8H`Uc(^I>(G`U5IIZf)pS!=2hV@XK@Z;TA0N|gQP;CDAV=^~mos1J^A9P3Wp3A42 zY}E^^!NMuw304fu;AXY=UXk>xhZiX1hMoV(`ja!n%+`&Bz;n|qau`bYtKJte9$57**QN zS||f%l=VW+1o|<*_x7aT^$0of>TmC~R)ZqZ!!2?(BS9{hz!?X0)#n_Ia_|0Guet1T zf%#Yuw+lby)TZ?ApZC3pBg1T>*B+~Hf0V>sFK&BWvf)-CBzZubR(7~mgbhI{o-#8! zceORSaw%pE_ikrIH{W=nIoc~JPb55+4AkB4PH5YJ3_5FpRrcWU9|Ym^LRO}x*74>5 zvZyKQ3!XF1Y8TeIF0IwjUJbNz(qmCW80~s@vV5v&M+AtB!Ko|p{=IzdO6}%rqf?L7 zgvWaKGHRjLrS09z7tVy6?@cHBW&4!x*9EOpS1!hk!OllnHqq9)Gfy_6mIMb;Qy>FX zSkAHD74D$3`SKUr&-~;Pg`qmDffun!ukvG&3{}_=@BVq8gifp6(z(bgclNpFJKyLb zLSxBu7XJ8uoB7oII@gu6L~PwGqNXfUQ)_#>AEn>=*W3M@#hi8@)P(eTI;<8pLZd+j zoMI96u6OJ8aX!(tg}^yC&9<|$w>$i9r4j(ZAlZ0v_nqHq=4F47eAIp6HQ}*p1pDLb ziMgjtUa5)FsV5qO2bG%2XMYU2bvvZhx4Tsc9_waZ}PXDMMzAYb^RiPMHo= zHc&xbL{0g@Uk;CF(&MNlWyGb=xWv0}O?D0#RYGD^W2dhAwT=YDqeio`DzAQp1G6vw z{c!N0NVCzo7ripkWoEcQt6fl+s&b4Y=SY9^c(0T`-+V7wxDcNGRAbVsCVd?=xHHZV zIf3)jS)@0}r`lRb25RHk#_jK<=bmqHfy3?M@~7I{ACVmZF1^$;+EG!U7x5q#_peV? z;h4aAYPho&ga-x5j3ZH3s6rb6l7Vs-tg&1o6=schD?p%nP;1=Qd(+piC!xnG?FKi~ zNn*bAx%L-7)#^0mt8Y&|>n=%nyulkGztEP13oyzhebrp@jB+wyGGOHR2x@}*YZ$}r z8_CM$m~kBMmh*$k!QEr_D>?~e45J!bIxSlZ{E!u@++=9_+j=_GwI*MGCa!g*Dy+#Z z9j(3acUQ){)xyPaZpS-HaQ7p=_IQm8jG7{>%Y35FKHsEszq!ceoZ}vAulj?{+!{9> zsGufPVY+7`WZ1u-JL@{DK{BXRVFp_TA{2=ZVsZZY=H9I|YzQWh_Jk*3(oCQ#ZCDfB zL!;f&`Dpi6HcLl3*I5ezfI1(_%p!wHuVM^Hex39xJQ4<(vn{fb@_cTMn>+aCNl7o{ z#7e7oqtPSE9b@3dB^I@;_S0cA}vy&X||)bKw5?uFr!`6oOO(hwo8Ifb=Cq^S}qY8 z3^ogJuzWtI`Yl8V8=NX=qn4zXtt+#7xuz>iC4f}9>#VD_rLJs|7%~Cr%7!)J+?@UI zjCMv@RXJT)XWX3MDg#z!M&*_$X{xmOR8RJ+u*S>O`VmKjpe|_JPyVB*Ey?;c-m9#2 z3unTx&dbzz5wEpnnd$b5UlkU>QIfIBEqT7kS)i45#^s5way#jjIBWg_=Nx%{=QgM+ zGg`SKF|YpiPG>cs$AsEHhnod8bs6o7MEjxOoY676E}a)JsyIOAxIkn`XtqZf%n=$( zKFJMqP3ZKC+)|7)(#S}}U(d^4QH|nY`K8Bx zX|eU>lV^Xv+juN5`+E=W?S9x!2FWD7tBSIfy|_O47t(%;baQ6`8P+*-*3QHm;jqS)_@oaPg8b}|R)uiZAyc9S`YV*{}>CytuNdI2Iqo$-L1k&&F zsiwL{Kju+WrXw|{$#mAj+21CZAM<>wO=XR8R=Z?SIiSqAA#3MkxAN;`kaVO+&l+Bh z)1@sEL-#*JU;-J(BGJR`V(szTbWrKiQWP;Asxmd*(*be%ibP*{u}McnMWU(YVA?CG z6ao>9aWnpdgDSToWYS~FKs8CNa6oRd_C~O9CImzPthHq})}+TZmc5|HX`(dRItQk* zz`$C_N7~Jjp1>ue+qlXN6>XQ95g0kcifWwXyVGoQoZcO!w+7RXM#-&Va%-5}8l|@< z+5O@4<~Y5Jh}vXAglFVW?B2Y&{lQJO!`nWt#f9vnXhiyL7O^GUA)fD4~&BEz-EYt1Ep@m!<|Gd&n3M8s$) z7Cy^UP5*9`Dm#y8F8a*5OGR_MosCAo9tKVNNMeahw~|8_A%*4 zS+9=#o^fR0AZp3DB|ds(7}NzYv=)rE`Bb-80|!vtiL5gKV4Y$I$N}w-IFqgV`BUu| zF0K87 z+3a~UmhxHFxXx-Qd}g(4Ec>mMfXrE=y~=2JRIB42%f_0lywjc{^&%Nm%@x0xYSO>v zdBa&BGaX5deb%^3W@B)WmxCnVa?Uz%rk?JSnxTi_P{X;{3E~oQ7CtK*mZSirg9JKS#a!2PH0%}Q5qIJLc==x-acN# zdPJP?V`MCUAw`BdlaJQ0j>ie%cCI$(7f_90Q|QWuO~E+s-_7e?&jAR@C>=&sfXHSB(dM#u z^v!w!v&Lp)O@ciaj7tn6G3ixa%&W|#BNaA0AWP zO?wrct~+q)prZ4}$$lk$M%3XdHsBzjtsCu>Q9~GIqn4ybcITYcv-Eq=JU z!yU8vUS5nf0Qe!VFM4}7GjLE}@V@)CJpj1;nGV%&)jD$JxtUYdbqDUCS#$Zxea2aG zGX?-yzt=s#H{NRbZM^W+YWKT)X}${%l48e!&C7nW_RXMkLrotWl^<-pc-N2l+TdR% zgNk;8a|cZjbHB!GZO>UZ*)EHHy>u?J#-8xKpZ!F$%uIXD7ZSaQpSm31ePsgFrGgMd zZ1u62OJ=p*dOtn-jc1-|?0lH6T#W8tpOA95dn=Ox1BBsL(OmSxhTt3lA#4b(TxT_$ z^s2Z1aBt~ixO%mA_w5us2e>gB8P()sB9uk}|h$9G;I)1Z4axnPY8 z>%t3p>y)1kE59a!I{)ySqva=KI3N}~3#(Ua$j~~_g`M_F1SnJUSHHfc3v09!9!rNR zZcC$GeZj9X0}f7Kt>1fRDg*A3;2!hg_Q`gz(^u%~+f;+dx!lf6n6mVU%|wB=ph3AxAmcMEF5rM1`D=bCdDwhWokmNVoM z=>p~xO~A4;HR(u!18c!5S7ydJXRQT9Yn`qvG92%hc)+Nl_}EF?&O!1eYKn9?yK`n( zD~3i{JV2bdgL{Ar28fIwmd_9f?8F|J3kC?;OEg&#uSU)G_>A*QgZR%o@;am0QLj8C5DbjRg-7i$s&<&{>!C6gas0LtQ`!YTOx%h{>RmK64fv zATl74C>^M5q>&-c?mAoM)*2wot+ha}Fq^2^W)r8Cn&xGHoZcNKH~W(t`=jf7qqnyQ zuW$EX+wQ-%-G6<%|JpFQeQWz`_x8Run0}NNy9|Zk!BX?7PW^HmtVj`a<{^S}*4N7y zr~g`Qef8FF{TSL+&u6XWV-)aHmui!}G9PQY=ac=}!__?-j&_Pu7h~sO=cANvhUH6P zdo@T$YO+&3_cKf7MAzFQi1~%jw}ZN%){BLUVPnxRjppx?v>W2-$6^OytfPFZ zF)pucR@kDl*1DpyAKpsWLZ*zJ=60hkje!q$N|I)(%+xwkSGLLwu`lPPCC=LRsQ?i3 ziEf_a&1D|}&OF_y3d1EYmBroez1T6fTXYbx2tqp>-3l(#j&a5f4xbK zf#=~m0K`jN_>9ndAA1>1nU%e1wwV@(^e*1nJIJxUD<+T67j;|jmcyN6?(eWBtev6L z=tvu!)0I<&C0{TA7-iF;8t;}xV#r}b3dwA&&a5ACd*Gk&BhJ_{nhgMqc1i+0IR{l{ z$&Fj4=BO(+=~pxpWm7FZ1_%xuH3EkDutlstFmK^O?%a`IRGhV>yWF~G&A#wOXisj@8 zM$wS3%DeK1u086H-`^Ww+aF!?mv3a{{xsiu|G{r<^(3*cCi@L0nj9Jgd0n68f4w@#)Ak9nx(3e!oZ{4uZANwMni zh0TBW5b5jt)36>DEj-e~_>hM6XuWNQ=3UDHAm~gO1C_{!?TR0V!~#GlMfu@nrz7}2 zg40$zz{9#v8c+R*ms1_ocvu%kTRJll9zUwZsls{zr#8L*y_~UULNNdUAOJ~3K~x3; zqnsD=?GI8fWHMmFX9zIft;jKcm?>EHXeIIfxB66b#s!9T!95)BRYEdjT-=sa^cy#& z^jSLAAAEZd)`hj;tlRz|X`S-5a;l{6LY(YXGUQC)WWP#>Rah6Z_8A65PPA zJ;NA0`;{fmQB`*7d_=?X+h5yfv&B6Kk1d=D`}gzidZ-HH$Nbgb-Vq+^%GJBx>%TLb zKTch)6^Sv*ks#%)%M;yL^i*M^rX1~-Ry#_>2#$B&o`3@`ap^)Veco9Oc0Np3F2=&c z;Z`v#2v<&cj0>Fhs%)$}r=z$n(?RuDzrM9{A?A{0Q`KDZYhCZ`b4}+QGOSAbC%Dm=A~amMl*7A6!w1HVMr z#3=c;VDo;)qw{-z=N+?Adg^Qh=`#&XgB-(JOpxA3Clqb4%&}GIM>dbp!8k07V%q1_6B8Uq?4GV2C ztO&+-%-NTLM_ByGu4<)}Gkjq5Y5Xw|5O(N?G70f9C5GqwHVzkoI;7pSH2?~hKeN+n zIJM4b-^to|KFq!>z%LycXb_h$w@1t$?)7kx&~=`HgL0y1&{k29H-$+!2A&^~kiL3T zP+o_zNMsSg<8y}<4~fB3wK@;rhg6n`ewNzKMGzEQ&Rr+ybfwln)zth7od}b3KA~lM zH8)D@QV=|t(^meyT1sP7RV(>|QMn%YS--QKVlN#>L>?FodhJepVNb}0t$3O3WZ<<) zSSFD42vs}&oC`LsT*p;IMcCVz=P!@eNyvoOOfV8$k^ey7%$d(0AR+GEe4LUTu4^Lq zwPk(*i`VS&pW*{6{c}k26r1O8bBoXxye4lOeUoct{p zVYt!6)7;(v=+>{PZj`i;b#=LWSG2#4y#JM^?{kk_QxWZ~e;`Xs;oKcfDD${GDz1Jw z$2BDRy-e0y=U@Fj3AbzEY=G+z(-K|X7cXwQ%7!07w5Ow*0A=wo6+*VGGZ7?igiD|{Q z#8S18S3dfqf|2|9#uN`diJj{}<|YBghQur=Y?dIH!7eR}fpb+x2a4A~RZ9TAPo0gO z&A&LLs8V4hL!tUui6cDG)uP?cl`zz~eJ#ogEey;YVsIA3d~B2Vm;3(1Q|d%^F;dHT z!f@(o)Ww}Fb{hDsyMbU(IY$U_N)Skdj6&i={3l}!N@K(Pn!&pQEeXBR5iwVW5bN%b zof4pJvl`#wzlLA2KhkmvM_~%(>`W&dSe{nPLA@9YookjEad-P<)<9-N07KijdES?1 z*XkB(*x=#=b}jR4l-PydT~f*^{GjH3@uZ`2dOQD-?*UR5?|brb0enRIN$`z#PHhGA z$65QV)vW&R4Np>kS$T@?VyX-e)>FRyotFFyu`az){mvl#m8W*&aYF56DkC_6u&cn_ z@jdcF?S@j(w}*jO!`@YZlbqEy)T?N(wTw}4jU`ySd_CW%!K#Jv*C<1qBMb3n-po5= z1|_RePZvLc$sjT`0vPs%3a8FJm#J-%*)Y1L)u6vO0Fds&qEw>^2Ca0}eQBF2Uhu0q zx6>EIb;;?e50oFkmkjF9?Rqz6;Cl&D;!3c_{LeU5L|Tv__U_)Fnjn<;;#|wHPir16 z0g7(ypQRES?VI3mQ{}k~+a+XYhoev4(V86UDdYJM$3O$0YmiJiXodB$-|HX2z6DY9oG!xsSg^50o=uZh(Fh73d6BN{i*A_ME z(IWb#!E+dIh;+e;#7zSf_{l9=@OQgCd4XHGsc$)m_&)Lbc#thfT9BrpPv>`ZA`8T_ zP2oAM={J92XsBCKeDhVNCK|!n=A_I{(yH`^iXRXTUjo?#27BFztUr zJv8w9IYXjebJtEhnzYuMANL`lTe?F6nn2Igu6IiSgi<0Dofd^eXxJ?>`FaoaC5$&gP3UtQgw9mjDMt+mGzwUsAd-=@0x{G0># z60|oF2ab#l_^^3!eNW8TMwdXz@;v7n3gmeBBsEcP+rV}F!{yMc)i?)qnb4w!y&9%~w%-c^1btM)(})`yFabw%&gwEI8BJ z+X!yPS6dxTR^k}=QCH;pliglZ^o*S7bU>5BS31(LkEY#dsHR9}rdi92Lap?U@_qF3 zT(wpPPv=|@5Ba0EY;9io=TUPpsjg<752 z(_zZE7J>$5*yBTozo`m-Oa2`KsBAV?(|cCW8N4~y5Ixo!|DE93b6PQJ-&3GUH?MOT zA;EY`EQLBjWls6MY&6#tiVIPBJ5iz#!Scs@Op)VC(KW4kQ9z9_Pz71E)n z0T4;CQFi-@!hs-3zd4`7(;g_ivlw?b>0mo!pCeF)=EkD4m^{9^X39-a|MsUNn|LEh zZ2jvZ;}{>L)A>@7ba7-d41s^MkH;?WpN6sf)*1j1Ui4W0eamC#a@_;q@F5KV_`21* z8q8``j%#iCdS;7K9bR)<{5HqU zZ9wtspI)jJ)6>w5ko9!s8@P967ZysRUDq7-8U(b8r(-))%M|!s)xfm8%*1;`d_f%- z8w!H*-E-!5xHhc+IA^&se?WzT_m}1)D|tRYTb>Lg#BB6e3uz|xbWiW?EugC=vFq|s zC7Y8ji*2ZiJRwxVG?kc?{HIHc4;jbLn#ohccygL8=1$cJCSK)g7xp4k-C9uw<+z7!Zt`kyu3uK0iDgBGDIMMSYH2DBU^#(AtY6QGpk zY+o<^+UhA#3dx3f0=)UkLWan~uMIE+e!t!Vmnv|?3?liw=5D;g z7wgtLRmEo}g3RLZ^(XaElxnwQ8G`e2mTY7=F&koLE;p+X!h#3_f{3s<1ekwOCd4&v zf7|NZy1#Lz>PBVH<7=6J;lBzb8BmQRphSVbE{M7JfpxL#*WLW=#4Oz_MLbof0c(_( zC_A19*meS%gQnush|6N6JJjERvB^Jdq-$oA~w02Q2U1txfUxuJr{()taR4Zias{|yZR#5c%t+g z2dC5siwoy!-HCpJ82`eXoM&~*naZGjyFO0T{8y5dz$P>db>q+=V**Fq2br~E4=wX zyW`<~sXUhNzkxSVed+dNh1OF9x_6bsj#+MZ69JeJG1GSockI|Pp$o2bowspx<8|bokyJ>z|=ML`> zmz*=2PG1a2{}+e`r3d=gb z97jzaLmWd5o|B3G!gFQAUrI57>T)DyxLBX^|5a}Bar*L`G~re>K>qta!B-sk^ET^K zw3k4!UXt}O`#*h-c!P1bW3b2{sqmrmdAesY=&Kss?yZ$Q$$Hh-lxC)^oc<0>Qy# zPNKM-jlDv3Q)W5qEOemd&xD7YXgcu-Y$8k)^UMnpb%!^POYS)^&@Zb z@7mlqDBi$w)#YF2xdi`o!(eoE|84bTQS>MH^)3h%exo~AJR56Vr>c;3scP=x=LXcD z%*X^Aj3>0RfJCVjOgW_c+5|NY zv-1yax+5GpiDhvfgI!jZj&>Xd-+p-jX)O2Lxfe`ISWR)V^^1`@9CGv-cOIcDz0`>Gp+9oXECM{3I_Sf%Z-Ihjf%=UvXaV*^U$S&I@Pr; zrsB%q1Sgw~DgS^KI9Mh|v&z-J+)8Ht$3t2sBQfjz97j7z!8w?|0e4b8B`b)Hg6h1A zd`IT2pfOL&fqIFbOyg9V9|s*|^O$>U@4M93@Gu?VN`<>baHMbW_>=h0xDEfiaaOho zN`Tr}Ss0cg2b|KlR$1O;8Tq1>><-gBw@p4ba@EMcxSrAPApcnF{ENkP*fvMB0M0JmbB^amdG$pnO8Tq18dyH2kSM^u39DdvR7lM0+Iu&Mil(R` z-Y?-ev^tJ$l_C4?Gnv4j%<3*etRj&Z@E3?ubyHlUcksoD?n31Pvp*CW79@C(1lA;# zVybkOknt$X1&Lz7?&V9c^f1_22o~rf_c&q|M98m({rM`fZCO>`EW{G|>F7LTtcF}! z`Xt6bpf6V!eXjI#njn6QK`fUX8eZLSWxc^L8~L!$W~p3_F2$+h#a(8+(* zo!bsQqMf(SsG?>T`gU_;9py{7>{2=_PN{$lfcmmTNX zs>+tg$HPIc8$+AI@4SRjd0t_C!qf@v^YDnqhFwlY4f};4^WdUe%F_xCPA^0KXFWU5 z@@@vRTxb&HD0wxT={gvmGAnze>Y8@z9F=S$!{4j{|G1qcvrv4nxlzz#6!5zfi^(7^ zy5ZhbfRCvMz#Oq+skHelxHQ@*y3Tr-KBDwG^q;87Mvcka{zNo`$MUB^J(+X5Zw<4+w@Xr zm-Bz-DFOBR{;uQ?*mEXZs%Lv^!zRU*de zJ8E(k5sCGVL+A_=U+*_WMTZ?WU$bb;e%##6jbzxU#r-f_LN?*)LQz!&o$j<#h9JQo zl6Ld-lOPZ=H}_D&N$Vq`H8;}@cE03Y#1+_94ps|m9oyqU^$Au|{nbvg@@(RbLAxSm zxt3NoHwJ4OaN~Sk|I;3vNx= zNm=&Xet0!cOg}FKicpDDi4|?cO!6mXC0`43G*Yap4Fv@hW$Av{P6s2qKsXFcwndV~ z4A{lAs`;Wwv4e2sa#r|qlKM5{^Fu%|k|a4jne|}VH|X9e3%?DVjv=@yPll97A(tfM z9x`fUP-{S|#0jDdiyh?uozWi0%iAj-zqpOPw- z7+X~gPT?`uSpqOhVwT29I5}Nd65lw{;fAJJI|k}ZSqoH3iwMgKs*rmT3Rn5v9)M4X_Jl#W)x8;W6?>%u~I>RWD39cnYHNkj7naFWCb91yRF zjxzfyz2TGqo8_6cqv1h3?}yYsUz%rTq@qYyeA}Mr$hifKR}%THWaIn={_sxpKGZ1e zejcQA(d1ef+lr7Bxt&|j3F>Y1yb{Da2- zxzFXQ1={>ub-Y5;rSo<+HXk?Xwg@bIl0;eWJb%8w?(ZAI0ZiRIZYS>NY(j45oNqJ? z7u(SKZX7>YJ>q+}2>iJwALxF@O==v*p1z#G&z1!I6HU1ffLfoN$r7K~^vA|=M(6E! zR6`F;My&R^zX;|J9-IVwNu}M-{rRL1$|69ia0Q$BaT^DMB0O2FtAE&Q7{@l>QH$2b zjLQ86A%`iM+0z$SHv3QG7pEpS(_+F5{NX3F{0mEqIvbP8jhj`Hnru=|dxj1*D@%z@ zt^fUW9){BYvp_)NWTmcRkZ|ANaelB_CVw3dCwjV2r>p7r7Ard|DZL6EaB!__{-0Be zXsf&nAHH@sAthCu?oKf!<-uLYik&TGpE=d1Ehhb#x6HWs#d6A)=5I#-w9Q)_sVAQWs+~2~tbG3tjv$!n z33wo96w|M92T+@kCUxlhiRkz=NbnPoruXDEwy7OR+Q|_uhmo<{04iLT13HbF$JfpE z?+CWqTNEdnUS10AtZ)41*lpUXXi1ZP6p_UuaM6dtRqljddO1=x%?G>G_3;XvR504? zlnE7MH1jIY8pM1IC@ngS-D;-wtZm<*&K(tSL`pTv>*0Ywutv?umFvjmOYtv@g#U9{ zdHV`|ATxI3pVm+I1nLOtj7KNMGsbf8nbv+#C6~TkrnX!X_Ps1(FGbxI@0-fRydN>j zeb4~ft7UcR``QmT{O!_(Oe#8l(+d1N3-sAn^wuatm3%rrB;|vI zW>bs!A%mL}dGi}!OnYgT&$wCmmzHsqV!3W=YWK7h2nvjOF61Ms)1g!kKG&~L$TdD*>XSX@{(_FW=H!Q8DWB9ng?MC8Qyd zB1{AHu=AC_n`4Oib;R08N}GCbl~;-pFx|1QDr-EG~56yfJkrMkn@s z+)?V)G&io7aqyOh%Vd)(7Nyrxzr8sp3z-lMLD_f;glp9mkg$__bqjJEU%4RJ19M91J;?Q5kvyl8Lz_Vh@}L zx*||z^O6_3!xH(<3V@0^s8%w>J;)lCru>Swt%)5C!M0a0mI#)1cHDChQ@=~U6s2{O zEIRPpqK1NLUyV%-d}@ku7YbG_(&^Y4d_Xg=(`-d_IZI=Zy#c~&WK^KZ|C}ksyVkoVBbZM2WLtA8}P{oZ&^+LWJD1YvPHK0z0OvvY|CFgB9!+akN;JAlJihthw z-j{xjjNbF7j(Ouu$FA?LZ~e;P`Ayu13txDer`O`eX}gWk;jQg0=OcuyfrDFTpV9wj zhJ$nCTsaf~m@rwk%(%zdqmo&fzgwZpKy7XT6SlcBn+HE*{_%SFVOj6U{44e>K!_$a z)NKcNc8wk($FCs(zs)4|J^pI4kU4==ktM-Kl%Q@?A#}FB#piX@^1Nem&OCldx7arG z>OwIH)KSWqL_S_&`u|!06$m;3kA7%kam_cYC?_qB0t}=yuLPvZG{!NSjfEDk0*v_% zt@ZafugUTEp41mEGMhn}tZeWeG1UJ7D$Z4wo16yiW1P=CTh~*v_No@=o^5>(5$L+o z`%H|#r`-P^9ha6bgADs3fcBR0HHovIPp2mzL*j@10k4F``o+ezV1WPQ`*H$lAE)mt z7=tm2csqzfm*S7zln3eI79pWm@jsAOz>WC3iZOa%HQ47{p?7r-9&8p-wRv;%sP<&! z9Il2;xqUzNF4gLr&}L<_{R-!cZsi}y{jI_^M5!&;tvG)Di48uG?4_oooJJtWtC@T^ zeMJNfx$iz~R2@jL9Ja(#?MM!%!xoY7FAWb%A?ZdUoCQuL&Q#t!ej#I!5Z#8@bgqc- z@&Z>S>`;g|01NFUbV&Z_J#EOQFeyb0Z=BazZa!Axp+pR;s}*X#8Kkgb$Q{`073*17ZI7QW!K zxR1#pD=F!|1n13m@sBZ11xWb6xxDwU>3D_;S`SWB&^=VB;09rro-4{x-K|E(s+Bwa zO`M2%Tfj5Qe~LhH1Y!Tl^!?0=#4PkhAp`eP@3vpU#c~h^!7*Uhzv}#k4eT7xp&Wh%C7g5_0 zB!O`BB@(K^KrNGJL}n~7Z@*BKMN=~PBJAaB12eEsZlYsoWmN+sK?~QZ_Mg_J#n4Ov z|5;ywbO2TavaFM-@vTkF`G*Seo4H58%f)>LOkh(XZr#|?nWAqj0Ck3%z}p7jqcRwLD}5CZ@8i#`k6hDG01ejmO^qnE3$^G(5?>!E5P zS1^5^PE{kxs+<7=7S9C()KC+|!I8t5P(pE7*m|UU8aVxrZ8jjuI1LIcnKnH*Rm#P% zXpP|o{s-i=Da5x@-%GEc9|IlG5M{4P0O02HE5SaYVryEdpMLfWF}SG3HZvt^9p`5K z5I^`7hk%C{>J!_D*sXi;rD4Rj9P^oLlHI}i&QSd`MFQYasP;;{D9E9)>8o#!LIK4ilQRbfa8>Luuhv zZPfmO_9}q{*TbYuuR7mbb5a^xdtrh0oHSEYIbEHrX0Bq&Cj!*^T$lf#mYO_LsU#4z z`f+E3tNP!4$Ql06+#`5aXXhnaJUBl1-ojkW!|iu-FuvD4$aO{SR&6IwVog)>ta(cG zV(!rK)I$|O5mU|}^#`$4;h%b*Nzb2>CbZ#eV5yM#h)VcD= z2=U$6kFhNkH2XYvgKsRo=3B@nt9 z7{)yhE5`F1q!`WH&D#O&C=3mrgMes#L5BZkFM~;ZUHEd2%31IqPy~l+sokL`$!Gp9P z=A@!ENFuS=~0swv!3JzZhuG;`X>_Y8K`SX2tBui?r?&d6|% zuu-u#auaX7&v#}4``)U$w;EPiyc2E`C}{hMfZw2mTsMCX1Mi(4$n2Y#o{x-8G_y!! z@gYngWJ|2mf79x%W}x2uL)fWTz*sd8jOS`mp=F<5vY%fcDPUTMR<@!=n>|uytbI6w zC!(+DIcjve-shqe>`)e1y)6;1mgllwuc+2Q9N5P`Y}0RZTcG|rP$r>6+dX9}&jju< z_jB4COc>E1q&}ONpo(5Ypl0O7;!52o-Ij^!JMmHN4xRNkmlI?9_ zVcv7SOi5MN?j$^vMBQ%ewXS_k*d#skPYt+@o7)x}bxUfNN+PtN9x<%E=nK&1!sCumB{(n2#&0!K--ooHbVp$Sx6||#LxJ~0KrH?w7!elSLRRvv5Fc^&lN0}HmBsi4+)Y@fpz6F1v_uJCeM@UaQ%d-#l9vm@SLGKG*g!bg#{7IPa>6>_>K@G2sbe>o~PAJ0^I*)#Le&E746QQ`XHF zc(XOFCH@2~@>tssN1Rdh$6?Ub;mYuwp#ZToVgjHaiYr+eKCzRzneju?Xn+f9a3<qd!?1!JmrleRhW1` z)|2#{KAPFIBFVg`1a5b#Y z9GpI6v2m{JW!Ory=ie0C8JLX6^t9l?{G!mJN76jC4&6OE(X>4tW@-3yEH`2QY4g+5 zXSwbEIDur2-Nav}B+{Dvr&3};Sgb{>_m zvaw)@nz6`;%*!tL9NI*TcMYhz^VmFw3J4s267ys4H)LCbg-ONu#w3F<@$4<3Ij@+O zjts?79}TKuY;vck2l95e73bdTwL5V|AMce*TV0eu``yq*5ZY3(KR$gz^usv4cJx>b z=DCiOBY>UIw(^}ajntCkQ{-%sR%qgCk>v?;c=0ah9I8b-(V@CRsKWSRWVcdmg#J2? zrV>@UXTVIhLB*J;p-{Ce@L|4a=D6FXHL*t(tvxDbj8x#V)-f$9!f~No5XRjIl3(n*QTj$(yn;A8?eE9-T{mn2G zR$w&!jl1Ti+0up3H+{ZW)PFn1nt78v$Qe*dX!f6v`q}s4vg1ARPJRX6rbc0wd$i|E zq4kfckj<{94VA8sP5Z;UizDbrJR3bEabH4;`OSKwG{oU#lk5%Jb0!_DL`Eb9edK~e zr`A)mCg2&!tcz7(jNswT9J;hSNsFaE0S;KgWw!Q6^*afFS|ay2UB7!DTtY@k{-Z0g zbMxda=)ww%qLZenyqUEOG((+^h9?Lir%Lh<=-*fh?#2u65e|rGvDyZ^(NPq}za;{>$Ky%JEfU*_h zWE28EO+(>zB&8UFN>~l^qrrG|0}E%$12-TPRa5`Aj1Beqw=w=H&iG!iuK*%4;Nmf4yN))iK?#T6O>2_P7DALO~_dM0@y~nLr9@qTt z6%-Bv71MH3SwJaEcF4#|VdUdvm77goI!i4g%@Msp_a}V;$KjZjtHRWd28dGvp`C{D zZ&MgXZH=`O`f7J+{u*1ifdXmc+D$n{KZWh0P8lCU=D#uOd({YLyqO|F$^9wRTy0gn zj0(!`wokib)vZUY2GNWz{_H#pI^#Hgx}Ai@qn3n4_dfzeHu8^($ zcOenH6jNH&xP19{O|NX%%9)@gS`v$q?A>N4$)fl33!wi%#GsSVwD*|GFspwqGUld?UfDPt`?;_$1Kem=a? zGZLdH@ zz59|U46v*YKYoX5}rSOP?<BufjBv7Drx7e^=upJgnG`oWNqedA2;ZFq?h@Q+3^@dMDb!;c zezTWzFz~N@-6AxB<97)?9gOMv&Yth?5zKE8>VN&-P&R1~)KNHC_9Q2^GsyXsArhhd z>bPFN6#{FMi#HGNaF2dbsuGrwg~<3?BPtAlchWDkT}YsN-e1o6#9D&BiT{Wx`9XOI zCD&ODqOuA>IxKXhB~58Df!;885;Vway0`R{vXYCquP5CWHEQ#!ip|Z?MoQ6ja`Sb{ z!Ln85nyp$L)1k^MM%yRQwD2xKIwF~4{?CNUO~QY6rqqS8w;nN2SOxk`2VfshENHNP8aMnh+DC)G1z@b*&kELD#fo0Nw>wxl6Sb^-ydXrn=&Xh{+E z)WIud7X6q9QQ4kA!aZnYksw4HRo(cs3I@QWhcu>t2QFw+(fZSg1udp9*4=zxdaACQ zT!i}?kEFT7$yzj6W;0tnAF<7XtIoGsL*`%Ov$Kk{_v3f^9V&E5iamC)G=~GkeI)~G zjA$2wuYbtl{4Sx!Wd%aoRkWD(A^J1V~_$tVaUr(pMa=kM$<_2(#4e%i}Gn% zHPiI^2nOJQ2im(xxN~WR)#UPfgZ=Jsxk9^dwkl$EU zPeA$8%E>HssM>pxb&3EOYdr-8#?8#*d*Wn77Bj`7=}UE#FeUoioq!C-zw8N9JQt80 zs^Kh2BGHM|9|!l#UmRiOp1-G~y0JsnDI=?`%<^Dt6jyy%^`c{8a(k!kLRZG30}XsD zysyZc2w|95V8eONSH&U_;ScdCQsNysimj$#X3YED+PWIuF|qJubfWdUc*4#QVsl#4+<{lr#YyovBF9 zb0H66ikj+are4&lJQds&cr*L<%paH-NR`cIziObN5nj{l9uVWi&nM{0WoOl=ws_*x zvCYyT30d~}wDfui!9GUd#Rcx^tj5&zSwJo%LkO_)vAuiR_b~7HB6m~#!R&L(XfTWr zG&IJq_z!87I@E78!RJ_BH{_PR1|_N1teRn;oH0TA>4NPK>HZ&J2s)G&?pyXUO+C+j zL0C)8+W|s9^Vxe*!$;074s|0VopE^gh>7Ww0pvOzF)Qo;YgZc6&q8%(Tb`G+S|TjMsc_5SzVmMyD|J%L3p9(oNfc{vF9 z!2@bYHt9hiW_^)GE5l~q-*t`DV9na;=_{GgqwSU~o@x&W6hU;;#e2T^vxXa3 zo)8uWF^dSA|8#}$nN(TS1UyhqxsZQLDa~(|8<~jur*!(e3w8f>1vHYDP%*Bz+R1-B z3^?$;q^5n!WCI&IKa^Gsnnd|Y4<(#oF$GVl7c*Awp&zhH14KMS=rPwEaIV_6Jzi_vuoH1uu7M z2o`{#8DnWr)%7Z5dCC-i=zuch&F?8n;o>)4|B?!qTUMxL!LLI{TfLmkn;tNCOE_+# zAJEIO`W21>;PhSnP?%IXE2rc*E*|G0ayoWy8;WB^IsrMP|25?Q*V`Sa$c-$m*w~r! zOS?y7B7%_DjfF0}0w!qmzk;WdUJN$r>YxY*^i1FhG%u4Ls@AjV=7tKi9@%3~b2;WW zSgxjbi$_p@%Ef3?{xoXF-W={)vlKj$(HBVdiwZ0nFK^N(2gH5uM4-d1Hcm_EoJX#} zW0R1b|7VTd3$4b|trph(i2{wKGTGN2kMFWRw$4pxPKPA4r>A2a*&aGc0w`9+cAkH4 zG5&RZajkdcH_1gom!FJGf+VcuIk^7XsKcu-9^-G^B`Di2oJRG2lj1gRzVVgA#}qLW zsbPK&4Q8rgBEA{lDMnevfJdJvH&;-0w7=YQJqBSd^S5#-ByQScYVw2H)&qJ1uE?=P zxF_GX6CMsBLpwj!!%A@wFm$wM$8s&o!9IN7p%qUCGKj?icdTR%-O7^tZdq$#j136d z^Z%6pnlNKX6lM2UH;Z>EfM8t^`|bi9W>4U+i{ehdRXXXfl^mD)m0BQ-&NXKC;j}G#+gMrlbIEnVv`i_$L`4H>n2S-tE9?NXpm3DAFpUW@a^J zU^oT>QFjYzVXo$5Du=V9sA=#Q#J)!pxAin>!3#B%Dryw`f=4nEUk-zI9E!hx!(vq> z@YN5Y7-T!J@aekp5?^UA9;Ek+9=q1Keja# z7IYsgknAg3l;#Tteod$Q7AUZ3E|Vvu2`KJ#)!j^ z>SfCrq_dczZ=$l$SKmubYRO2x`;(T?yJ?1l%kp39!0Sl8LYzuE2cMIQQwomh&VsB0 zZCE*j)HK~^Iq~WBG7E%9NZ>ST@|rm+>ec@7Kj0_rCSiO{a9Mt|n2j)#YTW12Ib16_ zwanxhKLr!nY*VaqOMfmAX9%I3sNnDa*8=P*0Q*|h<2R4wfa0*h<3k}{V^$oC<*5kwxkd+C`gSaET;QbCq)Egm z&)=*VkUchjorDVy9nc~|(4UWsn^$J{liX-n1z*k|28RsS-|v--*fskw5DEy-rGXsh zRn2t>)azwWGG)Sd6COUx0ks48>}w>Ovk-eN1WKV2h`B4_HNM}>U$w{nPV(~x;7CBzQh-$9Y4T2;C1 zEJR&B36suzUVpu$S&$q@x=TdJPcOIc(q+T{KADs-T*S<^KRO zLCwCtRKv-KDoi;xGSg_HDl;Ps8^p{WyCs4HBb_d7KGLeNWva32D6>;%XX$EG=BB${ z;7&J*cNm#6)mdLrN@Q+TF)^55xtXB&Js)W%D1zWgQy61$UYL*dEE0h$!@`vao4!+Q zGIENL<(B^7zv{mTRu0LN9AuUI`xe_3`t~&2wq-%DbW#ffsDv#eC&aH*We{*_4 zTze?4Ka6kh2kVc#kkuA_#!1>!sG7FM^$zx?cxqVT_h0X0^)}j+jb&fv_QI`%@<}$i zD(vQaBPNK^&W{+5Hz_B}SEGqJmvP5kH>oc8^OwSWq|c0fMu!prP*JQ(V~w5AZB7r7 z{FuqYGC`b!DJE)-Te=bvfI__s05`tSBowL}?|Tgme~S)xBHEh?AUs91Izzp3$5xXw zDnj=}5i{9-&O%e}9O~5*23YR2oBO$PLVOzH;8Y~@Dg5cwEb&PUYgXh~f95bdm^M>{(O)_=~z_kVwKbJbS-xwSB; zuzaMwkOm18K8qV3}h{0N`k|pp19{{oorNv^yDh6`>Qq*yc*WJwhny?H1NJ<`eGG=~8g}@6LM> z?d=tqb=6o2im`Eaa@7SDR*ZF27axDOyLdIO&UxIYSzl2KjKQ!i=hj0!=V3)~p8^39 zFr#dJ$tRS^)OaDqapl~4h@7<|HI=4^?lY8;*Z+8bB4A;}XiFJ+{mc6}b(E!LoZR{A zPNn4;Woz@^%8i78^8z~Vs(h#jfx$tka`U}^yNmRzq$$u0wYNVBk(9YbUS`D(1sxI|{XCIDUe}*y7)gA%> zsK})rZKZ23bkTtxpJL@&>?~B~ywzutGBuQw*2Tf@J2y6deL#q--2RRiGOOL4Z+1jL zjk2G7t2TdKrM>3d7y8lqc2sRxH_V56;ZmfP#Rw;BT-sCkhj0AR{xiQchueWjsB?ht zVs1T(8Uic$*-P$(T8z+ugOwK&KVoT5aX~QDj0s|mz4^svR1;cSa3DN-@F2^_di}Y| z_((B9iq!atzzm@6J0m}0$k(|1xw=*^t_f9|uqL!Ljg`PTP^DFc@dEbYH#$Lug*DDS z(%CKmpuXy(T__XeXuF6T-q!mgFQ8lRj~1`Tc>B~>{iG>mVF@9Gkj?jpQH@s@{G{b+ zX_2ixIFzmR5F4cCO3=LEH&=sfs2L~K1+Pp^ce}u9gHUqwi_NsB;=1r~Dg*9tGr#am za<8;wWu1fFt^B|I<907Ke$!j_h~6u{_iuNNazVnK!y1vH7d>ZWI6+PFs>%YJvKtS$QB+`^Se z=JvrGgQV$EL7a65_tJ@HqJzeA;K!`e@(7zKti6!WUy2Al>Ai!95dsfUJ;6w8EdU3y zus|@E&Faz;AVD&5+yH0C3?}MW(haYhW43=UHQEtMxJR?0GRiSQhDQnjWNIiS!e<1)8bC9zVq_+F zC0gfL>n!*o1p!`9F&xayma~;PFRqIR-x@yn_7LsK!9mv7 zL4_A1&4Vdj2#T@xV-5hQ%Fjoda#H5HzU-r38?{s@(;x(7VWX-*zc6cDZ?C{BgbSLF zw6jhXHbecOPYHpz!KYvZ+Q4h&cHSSS`=?4oLgC&I`rM;YmE&v~Q%a{BEv|dmflvzI zz-otG#B4P?w;oaoSAM+S*($7Zm%mUOcU9Qp$c5ScXiQG=uYgimy_s0!F!(5}a>fZ` zxXchS6OwRhdQXmlLiEPcZh}~yT)sbwwG_}bdp zxbhYO=3n`G{la$VLjeG`dIXJc06?NYe@^!sOIkZWVkxc*VEf7X_xB$EV66X=FMXRe zUx&u#zXK18M^~1A`S#_1bZh-LSEDbkFZ}c?*Z#@puK&±ce_Z4OD|WAvOwJI@@SoN7BD$6tZ+YK*lNmLV*-pdFgTRxBMug@PWEHwEOfSW#2SpU zNH-%CjB?zgVTEUXh47_w4g&(qvDL?^n$|eyfU-%>1~$*uIA@%-(BCWS3qAp&l~aXb z9wEoTE_P&ES|cqG*uFEa&U^j0f4lQ$IY>A6dvC|V{6g*d%gbMK?dqd{b)(w(FVuLo zdHLhU=dw}_Doex0`d;J0Zq(T0tg`c!*3la<&i6|-$jiMKWyR4b+cqK{XM1#Ks}#SD(}k?B#$8!vrW_lsY+U22 zuxU>fsn&&Ex)I|Q^4u@a%iN;C5TQW4Y`R;MNl#-X*m$w(99U!fTO|N2--?+>orOWW z{EP-zr>=Q#!sTCiCcgD^ts>PMFIMxB`Q){pwJsl9t(|qS^FdJ#%>seYIcuFyNoXAy zCzYiHJVD}+1s=_Evv*kj$S18P{II9`T{V~K*37Pm<{o8g;<~Wfq7$MjO_6FVKYhuKgjD0KJaWd&1uy>C{2y$H{~BlQH{yT(x%wX_ z>=$OHHF5i1`Wa7G*i^?rvmRudl<>4T6g)x@{M0-nNP7nlK685yy0p4PrD3z&OE`r*$Eu6uo_g7o3DFdjZ92 zXJI269?98IzO!Tz0<-dV+TSnnR~N6wgg|Gz@FUIyEi)5Vxi!|AbDH`%jS{x*@YW+0t2P>XxQ1Ij%C#GI!hbTe^(Cz?Qa zO00MuhBZOX&ius;1T~w3c)Z|~v(m&<^e^Y!kHWC<%g!51>3%rF*@83YVHV5s>wToa z@an_>OO3r*4jR5zR#WcZ1-hE@#yA&?(F>fkCT><30!4^X7KJLpqeeL`trwt?3h^ua z;C_bM*x|8!#yMEL9H%qzG3v;igZh#`XqURQNEMD7yz@8*2QU1_{O;ZH%FRUhEFWo9 zmg&-RkD&Gh!~Pa8$Jp}_O2$1oO*flmY9b#qA8L%>W`Y>yWNC|3GeMb0C*r}<4iDvU zR`Np$7j);NF=MnyP23QKkUQV(1PQAx`cx33-2A0z_inm$H6jG2+9(IGe!E(XHCiXU z|Mep;=DqzAQ5!E}=>KA*J=)9(CBq{L0P~kZR2k<(t(Emdu1d3VGnr_-2{2A~?u;=R zu+s9%OmjiD?~K9x)mJ6)iv3w~oYP=%?^`)_>tpv)$^7zg0h zSo1X z0LG~oF`1iesJKUkPqnnw#q$221xwF#bNWVYX$%BpZW>DgF0FnTtvo*}2Hw@5-4Ts% zvrB)N5A}sxiSVfxu^)b=jqha=bTw4zkzBqJAKuFVfQOS?X6b7D|1fwT!ilh6Bj*SR=v%*zk*A>=(mNhF=FTVAyZ-;1|O)0&EX# z&Db8#5SC<#q$G-@#3sARZZ>K6%oRK>rfIQgJ0YQB$NLyMblB2kfA7%_7zVPLacQiQ2`ROQT zmWB7nyP1xKkT^amla{i^vq`hFUTRV621!GWPs%cPK_uh4+`3b9mZk&KSPhD)8y*#{ z%_yI^Ad*o{)jApolony4yrbFBu3m|qq0JX+2&f{VLxG6B$Jv$7HJE0?)*(ql5B7_s zSy9Hav2~WZ+wr2~z4>$P$*F0rMVvpSlsLLSTlfxaTu;)rMnGrjy>Fcci7aMb2%HY= zdk?bTe`4Ml`?f>?_{oXs2AB)6NrVVtBH5<*;Nxj~Gje4miDHHR!cBbrMw*Qb6Ei<) zCrnbYaY=X9WHe`aY`+?A-KmX^3X}Uc|JA{j&&SQRKx%ySlkwX1G-)aC;9LLf(Hp-nFgusKgp+kQ%QA7@2%INAOP|- z8yR*{oV!R=2T@YPSAS!b^Tryh!E9v7gSEs2tL{!b?w7+;$D|Kicpb^vzyjcca>Wi8 z{PWdlfyfzeOOHs|*zz=31!DI{Lx$d1X&$E17Owv!ch(27EN7OtZe)&;stlp?u_X^I zSjff}VLm?Os@;$^o)c`BDbi70g|P&Js4dc#W_cO`gt5H$gCTE#X-j*{+%(`pF#z!W z)PbzX#fV5mjwx>d08uJ~NHEXE8OlbMJgi?&_~GIn$y?9k0RX7A_1k}N#5jdi=pDGy zmot~F$n*RoA2Z6~3r+P$HKf%aUOLc|&%5X3SYTXtqh8hSc3Iu_Q@Wax_GtOj;w*}7s7yi?1Xx{zC$>X1lYmFOeqsk<~_~>UZwqMx!ZBJI9 ztS38bt=9tG$cod#45W;@joYuS{imyqU$un~)T;|(-QtP%mTH|qsEUzvfz+^EyX#OS zEyZ#}f+BMsUikiY5dgw%8XE7On+=P-d1qoj%NoAWUQsNg>6#9h-oB6>FQc zw6hdMqRhR?iECqLeKxYi)HzFxHM27sdm{66GoRRdZw~lvuHQ^`C{V!YxQuEN5v(O4 z1dGsxM4HPU0mwTrMTKkgre_N8tnWR^la^xmp556io1WYgfi>RbK8U5sytjV*;ctBK z_1*p6n}_|k@}fVUJ=yQQ`QhV#^`m?LbU58TxclMm|9*S--+Z;Pu82s7NS=fe0IkD6 z-uWaDN_3|by*nB_$;%`$_sc_>)y7@wyG&HN^5Wzcda;Fq3EoK87)|8MqKB{(!ur3*-W?RFcAy%)% zKrlSYn`@!Be{BG(zM*v}YU_IAcB%qVX3iOp0DJF^CquXJxbz-|2jvR+5Xe}{OP80P z2m&oUf%mY|(pPt)Fc9WvxP~nE#&~PVISRD+`OD#NU5mc37I+WN(CNc$<5oHy7+d;D z-%JO_WS-N6i69?aXK4G?FsezZQAffPsYp0O#W?-mKYlqIjc3J4VaLvw&X-wnDnJLS zme2eO{U;HwBLsIE|Jm)@e^aEZyajQyO4s-A&iExmk>9QF(+tcB=qE?hf*nB%z@p9O-^1wX8^uZn?MrdiQ> zFl+%|B`@s>iTP;?04kmdfuobs&Vr}!u5Q@BzMgPieWAYn`ZZo}h-i&(u7_z`GnI+$ zdxAtVZ6vBmrNwk$q!Q=+5fE0c#*0bp+O>quFXOtB8d?A1995A_z%DJSxgIvxLhi!_ zA}bVFI>$yETQAo7`#Hz|k*C3Oy4ktUjZEQ3$0ZjowN4Pkf*g5AQlZi)1hNpC-JSiC zsWaEF^|c@y8mTc%#L>N(jzoJa5(wUtj>KR;Z*GJ_;pwAnL6_aSot87tH(3aj5>Ixs zAQH}aAu(wvXK8R$paABsw>Kj;x~?=w1VJpAxd{MwezB`V!JAl_JMU<8QrN<)P~LxQ z7$njZKCbJ0VuirYcFfS#=%@^0nU5{UK7_G+_nRkdR>j`TVNDe?H#{j=i^PWXQB4uR zw|?(Y+SZ7mLvirow6z%qb2ktoaHX%c1O5gDu3n8%fDX|XzOfcajYs#hT1O*R{cu!M zIugzG5CMp&-U)=lAQEqV{g8;5ho83fd*3=;D7BZddmTvcKq_RU#+L*HQAf%E)3%lp zxOn14*yQ99fhckNPQ7#GAS>Qk^b*m__g8P`Xfk;>ZRce<4AWVZ%G&BKBGft>5UQ+LgktJ+B)y}!sbBexRaWun zhFA<>yE{?Z)@9}{_$~1xKmbA_yLEQ2#wrx9^v(51NYQ(e-}}LElT#D~9DF=$u7vWBBHi{9HgBJUTiwUEf@?eM5byL#F)DiBFav016Nbow}3 zKz=KilgX*cr%p()hO)6;yPgKIM1e%a6azNY=TPdnsWxxd@{vJ-D6zQ_mW3~KZ*rHm zwJpvQ0|R_oX2Q~JF8G$aN`{JvKnCcn=Yg3J5X7=F1tW0QFJhM$%T03APe5r6Yv>P`PA@S(rS$9LlDaH-O))>wa5&5}7lmo*0t#o{3R&ONEct$bs{1Fh< zWtd8abWuQ<$mzi9NDO7W26_+kNpNYU* zZwoIJqQvoO>Bg@d|D`9k&+^9D$!PZ2x*P!Xx>^6tH@m;IyYu%S>g|VzKgQPOR)2RT zA15YDCXZfx9`@Qf^5a+gllw=59~EZw|4W-@T@hXzHtziN`j`6k^$`Hbt=<&=h=C!g z#pJYPJR1cTQ^%$g_um|Dzg*|fD5|O9QCaQAjyO%Vy%7!%@>$OUz_p)maul_W#ps{} zfX?MuN0Ny0v3ta^x%lba$#Vj_FSktLum4{;yj;gbnNwf+wmT( zrD^7ldS!2Dvcku)Xg5@+scMP(RJIWVG<>!Fk#&aZp}5&qz{4>&p-cn{%hv4cs+RfQa64n^HhdnU2W}QTJC&qZ}i^9cjw6gfOQvP zXi6 zJx~5j?#tZsS=;Q^Uhza$FvKFzxT1kv7+FBue3ec@a0XkXY+#W`*?kb0UgTr2_GX|KveA z@>hSZG1xCIy;7F}qJT2<3wGzFhzsNlnSEx8oLO_J} zR>+760GP}PiF3MvFLO88FBYnqdF_h;5Z6^yQ_hl(r3yvW#sCNbN(*jc0bo%E)mH+k z#UhSA)iC zz#IfK^C}QRK<`Q3-i&l8obh2IbtE}D-8p*q8z&&}Y`aI?|7fz%OE%X+XNc27W&_(? z52Z$_#dJ{CI+`3k`EXKZ{(HawgjZWtt(u;l9<9Z)`CC% zy+>RMvlK`rqO%oscVZPvAn5Pslb+dmsVZw=dUJpC3G&sZ~s;T861S4D=dcXz&jVl2m#dTFq zosbaMtJ?_Z*Y^#%g%7JJX>U9u~IrwXQB_?(}gkB-+wPsYHoPft-zPm?(k3k_|-6 z#x|&80jQW+6$oQ|+R|Yn)3z=%pN}kg>TJfx4>Rt8ufN_D0+WWyhRkZAdp|fUu(n>T zu}~KflBQ~IgyiYL+e2=9gc3y5f0Dm*Y}%XQC|3XL&;#PzKN_JHD}k`akB-Y5pKoR( z%bhBh5%bA8ba$dj&n%05ewMGKt1i7%2ZY|^ys;8qx|2jT#kg&)tG$CTl`0VHx6?3D z`PlvGKYO%bJ$p-AFV;>UW`I!U&Xv?$56Qv7oZHW<^u`;lgO6v6p1-{nMKx9Cem1nt zwXn$C;4l}6YgZFzDH~gx6XUjxwLpiMv~)3ZjLT0>%hp<`0*0IL=>ClTAXI=!Lj{45 z3U^+r9X-g>mL^ZF&8VDNa>OMBp8<=h-pZT`kwj5#?Dzk2w#2Zgj!IK_ww9=` z1bZJ$f=KNCXjBObSj26}IpU~nB8cm%%zc@ArG=h*<-YXQ?&z>6bC*wSt*eKJdD_v; zepr*=^XapXcVbJ@hI0KEqtOJ;wc>}Iu=Mm!q? zy3#vKi_FdDN|4Qmuig=h2Wy>Ra8N7)2RY!6=0~SG@8e$i00@|k>}+6&K!;)>`1Ove zLC6yA9OvC86L@cau{Ay^Ui_5~O6)%=5a99`YQy~^YRkBxZ0UnoczeDxuK*|$s^zc8ST8%l*0_%b;y z`wxoop()1C_|3Jp=3m8bR=EEEq?^axuRPGV?k`)j%dOsXE{RheU3o5l$>%r7{7mjP z(`OnKm^dlrwK~AJtSow*0Hg%$dU5g5riEPs1mx zvv;mCKu}$eU!sb<{ILxC$?8YR+P#$*e|+WFzq9r$-@o+62RfSG{npj}Z^qBV3+nIq zY4cf))z2ovNK3hTQFPXL(ZBMwAI9DNh0lXZ^48Um>E1x++|aG@E0^Q$rTF?6n)Q`{ zh?s>vIW4o1#mYAj!c?kI9Pef}^8nDj8Ua8)wmK9?cc&^5X-D(gn2n5ErcD0K7*=yL zI{J9Fb|dkYbSQ#Yj!(*{Cda22(eBr8s;6c0+-MKS_Tac2jO_k#Ihk3d@Y6IbP?Ua_ zyUEneX6|%kzxTNK#)I4%-+xl9-%O`{V@q!ezi?J*u7~8wTOxv}DLMDX8Bd<<=#`a| z|0aoESp0?3PD?W~c3PN`b(wY9ID7Kq*4GB(d$aOnnjaQsP?}++ItSl^={NtY5WnE` z4~ph@NS^IB^*bi$92aonPgC>JwM)N}O;4Jiu$(TokaDZ%^BZROS2=6q(*Z1nwA92_ zV6LaNYe`g7<6emXtfR~)=l0KOudMv(1oEh0Y1RutETqP?t$TZ!DSVl^a^}j+v4il+ zl{l=aWes~&Q{Is&{oebNN|Zfs4=*&2EDuWCI-gdSTPT3TQdTa<;DL=hq(1YtoafR& zdn+OUZ$Th@5`eWlp}G3mW_8eB`Aj{GB@x99CABDXrvfB`vhd_D1_NJzy(t7#(N_q7 z;5{vL*FxgPjf7dm<6fm^bjB~Db{J$OPdcvV>W%df1v0p93X*#66G@P^1EDIi33JrP zr$z|0r7ttr-ip?)#8Ttvq&#Puw0H>DLm3DZFzFfg1|uTozFy!Mv&Z400*)K1-VOHW z&U2sr>KeO!2Z+By|P7qx7UccahMbE~t=$zE=q7zmX z{S8#vwbPPHaN$XRK~Me+3=5v=snxwRauazTw0Z^=E7%^XK$vl>I8{CxGcQ^N=oSpD z`Hf0%jjBQ7vrWQ2=|)#fD7`gGIz~{is$Ls@+}OC42C?K&PVXq6*kWo~Dpg+zl*YaH z$K}`$c8lc#=<;h#lvPyF?Ju=^ds*C2wN4-vPI?vy=B^n?mH^<^FSHNu&pJD?RAO{o zqJVe5al-!YTyv;EC@p$VGM4wUx6U#)kAMWgu2qZdClq-3)n?`H$v-5JwOWfzaa=OU zU^ft^g$Id5fJx6ZSHt#3q~==a$L~*~y7HcuRn|K%)d6AuqX||`h!`H1X2#G+r`{NOLVj){+JKlSLa^sCQ2#^Zz|8U6gcfF&BM};%~ z_(8^4Ih)V}KxaD=N+4pHxul`X+%q;;?}o#}g1KWV6!osIuLSwnIYTNGQXv6MdSzoZ z;5m7%qYjX(llLuS+#%j3#(e(6TmNbr&ytzuddTcrUP#5%sZfkhim0aI zy6Qd7R4AOG_Ey9$@;VWn?P&9bnovSWM1Uw&W#;*qNSlg1kF4=J65dlbvR6LW0D^-L zr!yw(kK9+p9(%9#sOF+MHhrj{Bx{+!82LZWvpy}{8*SzisLMnD)G z7Tb5~QC+cuZ~IP-{fvs4t9A9bS5Ete52;#5>qu>YVa`P2gE8Pj4%Y8>60^2W$$%g^$) zb~8}{_V)^B{i7d^YU_d2n6v|H{P3XQAz@ULx4zu&?_~?msXM>aJ-(j>iP*TAK6rZs z1SWSuDtSFj=Dia`2DP?k>I(0NYgZGYaCBU@*28RUSFglE;0NF735Ao>a&%m7y_kvs z0pQx}tzza;068iqPDs4^*@pLL6BG6iN}7s1?EQ3t2$x@NgsH4`bePI%-w07faY-e- zt!7}|ofrY4NG1*aba5{gGD^bO(4x@fmYz!#6f6y{I8zJwhP}G2@r*Y)L*zjQ!Wqv( zwz-E9ZQM#cKrwU0%%eb#G-W1Wl*;~oE)iF@^umFQ#|GpHftZ}wT#t&(l~eceUrc!i zm<D-4W%7jnOc-&a$jbi)yfsxn8-z0NWKbD>Fz|f@cF#NM?k3%2#blI zJTVuHCYW|@3(u}wXLg3o<1OeKcQLPi?6W3S|$EJzT+BZ5xp)hU8T1)iqm4`pck3TM_!;6;l zrtta16;n6un|psb>g^W&hsE%5aeObk;86aIO4EbMo%f)Yf(VyO)Ril-vm^vJncy4^ zPu#)X^8TAy|H(zcPQ?pemI@~Qc@QOC zHK~LxYlEZ1r%5G3U{sR?RApo>HD;?<&cKvfR}T&fXS^-RmcG^r_)xwG#yR5In{$=5 zD9*`oNmGZZWKh^yn)D4HRf|dWq-Rj#BCvQ4^@>_s1AtVO#Uv4Vy-v-y!PCbo)$Fy!X8l{|bR59~&&BU#Q|nL8Z| zK=h7G;Z!JQL(9bKV(LupRfLEzIqvTM%NIWB!6Ir5f1_`_G8 zk6t|=2K|}fhUO%?@y$osKY#tds8}{@Uzxr3kKVMUOPd-6>L|mswEC~=>)~u@P3{)v z8;t(1UX9r;r@a$1frCSqZ0R|Ah(G<-M%aInb6CXM3o+Yt@E~*aqzs#~u@>+qFgh-6 zM$c5TKj-W67wU0Mu3U=&NJtzU6l}+N@bNV3pLHlYz_c#f%`*T?NsL3;YN&QYg@JhS zdh(e&HBZ=WX#j|q_5`hjW=pRnYj4`*Nkt%ialdtGS2il^wAI_E z&p|uIdVksA-;HH^`m0@hP3-=v>%H;mkf;FiOA2~KARtHW&4?9dyu+K)ac8j*`}g+? z9gA#ig}`Fw&uO0!)20>@^Qp^5))^`@UuF&nrURowv30u^gkrhCZf}Js(OVkK=Q>ZX zqWKI6RxZUru-MEIk*V>WotQI8vytWVWm#g++ky~)pFAJEpdSoUDHan;zCLF5PWz^N zIhG1d=Dnw7fBWm7Z!$&e{tt%;z(#(U?k7FN z166Y1?6cr?g5`9T&D%98abYFP8EOO&rmB4%JGVY@!Cv_V@i&5D(XwIGQ@#H=dvZ%C&&rs zCJW2Nv5QnJ0;=D9A~m`^00OU1=Mq0~g}Q)8snptue$Fj_?i2xPSNc-n>`|;xZ(iT5 zwKYE!rtnf>HnuvHI+Ta^XF8H95M;p`Z_6{2H7@igr-tA1)(f?4WV<_&4h0e1`@uj+ zY;*&5zb?mq>$NnlskN)I3WSg_J}$X}lo}aCwx)_0V?hn~e&gd}xuPN>gfndm16a4e z+@AEx_I7mgD60@E2}~OyU+Ds9>Frlj$F3HlN=4oK=~yUeZ$&bY#ngteJia&WZpR2P zoS)xOO|qd0W7($gDir;_Tqgwt>&hA0yq)qh-dGI>`#Assf)2(0hZ9a+3{&}oe|^|o zk817U!P_Ht{w{N;LZL%}vSKN#KzK)g@z0-xsq&73SfHq)f0x}r77_13EZOUdhn!L) zcda@Qvyn;L+8GK{#e_TFGg})GYpITRGiK`Al6d0E7GS)R%bv4^?_P>b=IY(x!|(Rk zG|@W(pr9!>Z>QPN@Ji@C$pvDqt5M>lXQsWfy%kA~{rzI0>jZ?jt{SUhF>#Afq`0A+ z@lj1FEo|wDNCk8`a z<*xKX3L>fkB?Sqmwcl8WcD_E_5VOfGMcV z913tHNrkrb?adGX9=|)ndpn z+!VzPb$D-j+;GZu3?u5Q?c=wl!#PMVv;&bzYFjq^-!&qvl#z?*>94Vm01mrxK|U0a%oW2tu7J92ciYHnzOgH#X%QCa%23*+1KsUTP7< zQYvwlOYJL}hU3gTOV;>&Vi6&21tzbeh|1jG{NKg|74;eyAeSb5Yqvwpz@t$F}`;c)g(K2aBQL}oHc&ZGnZejZ{1GwC1wy2 zjCay%tJKBgd>J8NCkQ5QHk{J8|NL{U+$SWO84t@UahpE0l;39Qtnt+jA` zT5jE`A!2(oM1bKzK_wwTYco9fa2nPWQKcvFmc){(cjrzmX(&FR`8;A-4R{D5p)`gO zCUw#1$O{<)ydu0K@}!iALpkfY(?|Ar*PcGK&(CXKsJY40mDd_y_^tIDZ?taxe0%L` za_w`?wQC6rd|c@d@6EU-v4!uftF>*twymP*qG&Ek)v{u7L8GY-%-0F$$ zl)W0Cz5nnH)-wR0X|NzZi0H1`__o^kwy3`&JKqmp``!Y^Vs2Nf-Me}7yFd5F{dU`w zcA6EvS6}^$H{SSPUbyu?F`2?Ub0+@SdZ9*3gLXfsDLLc$pQNEL82Q6Iq>{snSt-xUi7O}_3IyP$bkZ}c zmlGaEnA}(GC;@MVi(iXAbWYYQo9Q*J;yCCw)5}S` zHY-l}_3>=)bo73IdVi81PO|;A_G`oO?&?=|+gBnIdp7)wqWK+DySMT3J_3>$13>!= zGZ`HY9zT1{2rI>?dCuT}+&tPnI6k>+Cr<9&PLKbi7QCLojpr+}X<^TTY#R-HwAsRQ zytOy9_tVJ|mD`t@Q(EkQFy(0P3!G2_K!FQV5u=l3;koiLxzEOS!9nIq2?!R0w2hnT zvpV1^$2qF2{*!z$^+Bu@f&u|0dgFsca;nnuc%!ivB7)R{yGw6BML+o3udPf^OR>Pf znAXHw?cV#7q^X&^Nax@G){8Zvka-gv;375hHZk820~rXGN@Y{W(}0Ca2soaG&PZFA zKignyY9WB5tW+Sf3Gbv7#G;tkg)?G*FH0Iq2SP~fT#DHTmlM#0g!3^GxOOd3f#6ST zHZ)v4@(J-Yf<;8j09Jh^c<|#h3AECP2+mTN2xooVdG>0%`b#iABKRBpqVu2>T*Rs9 zoLBimM!29~Eg4?TC3@%L2;uDI=VMq;8DP;O*oMxj0WaWa6+7>|p%;CEoUj6_>Yv#! zCwlSYx^0$tT%?-Sw|ZlQI#YqjjuHS6;RFTr_Vda$;5_c9lhTY8d?J|*K6$2r01&T^ zP@owq0I1)5#O~KTq8Ad`c*r@waw(PyAG|fX``y9h$fAOLXkFnMDV7QchdB^k`+Re7 zP_(zAFjXjUbX-jPX615h4Y4n~H}v8!cTXN=?d?cu1i;a8!2ogGR6xKZWoPN&aVY=K+J}vDLo6^P+(M32OmxA-5{(?-s-`$QkZ>M~?G&dq5 zGPyIQ7Xq#E)t@7fN^sPdP#6SqbW|?bRn7GCIh#N9UBzc++N~Q7m!Au3Bm^!INb3L35Oqsi+sjqyd;T##`$EQpV z$6{iqeZ!rSj%9N#Wc0Jl9J|P)sK7yIyeXY`zT5y=Y`@ti*BlfF7TQB;>g;cQ?4ksImeT4;^8g${iZ zORqFor;HMvqgq=NKo$H#z$1#!{KhI*ldu2wI!pf+Rr_KeC}vJ+1b`QQp|zkwoH2}j z#TjR{-Ef}YBsEg?X?jMl*p?z`Y9Xt0slE~fkyyE$L^U<(mEMw$gwmq36QxbjtCQsb z03ZNKL_t)=M!zU^0XEz66HZtB*kjOBVQeiQ*lU`ZxY6fI^OW+V&R>FEqlhe|cUIi!=s!$X&#}4Ja zC%KLUd#>?bosTUCN?!eJRPnbA#`Z&AxdUN~5+Q!Yau@w+ek>5=cQU45@!Fti@NeCIVSMOHzx`sZeR(gv zhO003yrVL6&JrS$r_qsB+wa6pB^9#O#sx7Dlk$W_0Q8Q^+*wP`cy`E%Qpu)=&eC8% zcNuMeuEs=uXUH1r@8w}z)>i^RaE=CtMelL(e97Lk^@HnyCyE=2ubka=>RnBabRb$Q zve}ijrsRV5a7y2MV1w1b-JLi`){#JH)>N8^?TxUs{&Zl8pq#7N0xi6!%bU^Vt?2rt zh*@}SEW6O(ADg6a)FuPAmjpNhu zg1@1V$ofilk6d*)(sRFTpx589PE%LElDD?TMe+F5MVD)M&WR*(1I8E3L zzAQXBn2l^cvf1Qp7Q%0B^-63CB2UiHbKtz{k`h_#2B(knc|a)<3M^(Ws!Ln?{$9?> zAX4J#-R$s#YSX#;xh6wG2Y09Zp1B!5yg%dpcjx6gS4%u-DyNpsy%=LUGp!(E17HA1 zo4PX1LG+%2NGwj&v=bm=F>_}TOSfue?#HKPV=d63V0ixi+e6+Emy79oS2tLQ0YDy3 zA7*?mJ4beD46^u0h=2*`|L-5>m}X$i2g?L zE4qkT!37Zz>ivu(e~b0RuNccP`2pO0a|nM)O&{oDLNCOkuomH?@Wd-b$L@Y!<0 z>e|{@v&mk>|6Y4>V)|;CiWP6?{B69`Q;|T4)5l>h`aBMe(rWs8;nu|KM^D`=divHr z^DDkKifc0O*8yPSj?$LqXe~}WU`ntK#qh9X3cyeP_=F6!cY-^=)+q;`6?{P~btsPR zWkhi4rTV0As`X5?|KYT`76!4*CzhY1)}=6Ms!7kV7c~*hMwU;5C{^B*HC}4rT?Id} z6vexXn*~+FWWSj6y!Pv>Iufn*aCB0l09#Tu%bm~a7w#b!HZu0+yDDZeU^OnBzPxp>@^ZtG=1PTc{5R<+M5($X5^wYixQ_1M+8BZ7> zs;lODH0hg_%klg?Q_lLRA=#i>hr$yb-kmnr!zb@gf<&?h$HRBVDA4A=xBJYlk_tC&CJYedQ`=gPP9Ehj4ab&A|!@2#UFZOEhJBIow=N1bW%QkZ_?S0 zikbWDZ>}kYQsLpkKy3^{lxZVl&-XD8QLcr*#0YYW0=ik7{4ov3T+aVCxf`~u` zV%#gQf4-GZoeBjCY^;P#I_U1i-cdfbQVZ~NMGTQpqP-ni>v>XY&yNQdO!jPSg#@9* zrI#x!dH|5}Y#HYh+uO@qo6-2BBoCEd5&-~A?!AR#>YO245DPhVBoUE-YTbbM?UgIB zP&hg$Ick=p(BitXhNMCOn$FXfQC1O+Jlpe@z!LzhT}zm02mnDMtR)o+At7!mQ~24y zhKU3L1bC-{ce9y%eJWn|nUaoTcG$!B!01B%{DZ)?PMtL}YT$!EKDX zdPj&T)mdTy5eb1zRt+LS9#G)$sL+wDh@4P)+Y2eAMnIg6%p3$kMv-huLL*yAw6~(_ z5ai&XnKPv`xtCHngvllOT?kn%z#mGDW$WFXepYqHjAT4!G2Om%OKb-vF z-yA-CXIxAjB7})rzn;bo-Q9_=z25x%KUjb1@2w1b?%?Bmks=BJt+l}0b0IU$wa^q7 z9c-WHAp@*&L_@z{c=x!Pu0>F5>qHo>DoqO%hw@-&AEBtukiqZqX zDZyav4{Kkzt0N(HGxg#9yd22ro|GT8)}t!Gi-4nzr50u8tnrJst{qg!0RM?2>A|NQQqzyIDsh5AVm z0Y58%rH(dUNTtT!OiJ{^g${bFtYff7qA$iut` zLLt$y3e^#Zjd(*_FVzSL1gJoSvFz<;aZ7PNj4Qn>$vr{miWaRTFsL#h@jO_&Qlu8!;|vE2l=D@;^BUwB!+sgiN4b`<~!%Q+b0ruot7 z=>6XK+?L9nKlo^}OvtsRzxH~goVwvrAp;>K3V|24 z@mfdQ(%F(&$MCcV*0O%^(#!Sfz~mDvS{vc!?NmxcwyhPIjVuvyCpmahWW6(oxvkqN zm)h*RAq4ZHahXO@%?Ua3tn}Xc3tnH`-!4Fi|ChNpi?J-r&hysV!x`^G~8 z>bcq7pvb03$}|iUA`Qua4Exo7u>4{OdbVE-!-fG5Z?qp|12zQ7v?bA&8nn8}Hc54} z=b@^)s&dZAnB&f8+{5z2I&tGhR(5rZh9CwC^$;1ujeE}7d#|S!<0^<`($OkF@91o=$i~KV78}A~H#$E{>8P!RK<{C+*O-8rF1gCm zUz%driK7A`mFR7Uvy*ChvEn{z>O!*gQS8-A;HZl> z)`gXDC4TS{`RZr)uvR>LFQKi7E=+zGohBq|QbK9@zsre(ue1~T)+9*l{CUj3Dr}q8 zD8~3|X&2{k_wX!?Wi{#4XR3x-qx+MH0(hTTcBqn@^M>j6k>1rSaag*0X(33i9SDVW zrU9V}_gaIX%B<38DlZfQLN+zzY5jW4mnR))0QlVB*!tjWV+0Ti?|!lG9iha!aNW(2 zyT<&i6>~d!QKo%uYL5a(FA4;B<2QyX5J43 zcm1QbeDTx8;A$)-E=8)XeuHn|91Bj(K*5~_r$X`GH_oII=g0@xzL#?16?eO`i9xQ! zHUplbo64&IP3ebMqm#!u04RmClPZYi-7oi9kGXy$A%c5f9t^I;-1rX?DFi>u2`m7svV_vShgQA-7}JbhL$Ii6t+LVz>$=f8izGfbu+eRNDs=K};zHRfDMBKW~S zJ+2lm?ntSzn3*7zruI4#DillVXAlc#Xax=jtm1A89?@Kc<#eSgT-wv`{LvW-Kmpf2 z(E)&Xpw_NNX;14|@^ur8bo5GAHPz59BL98|dlB4>Tn zmc`5ph0c(7q$9zr3hQXnp7sv9n}JZ6jZ9tmxUHhLM2W@BragrS$4~OQuxVfK|8x42kC@mJFN=Je`jrU6(ipgOm zBu3fTelNu{NwLU7zS6&t&T)zJ(PiP=PAy%_U$!oE8kfUdRt+C zJCsT=1S(AA^?w9&6RSU(`7E|~1`*R(MrGoX6 zDxAR9e(QEJIjYE0Rk)=Y4FwPpqd;ustIVoEL~RKOrt}*(V_W+>ztXeDBLWEMZAE+} zn;us@;S&s7e}L?Li7s(agEe>a*OR6-)}UsB=e(_*=3NG(%#Ld=HoT?T ze$CCRZ0?U=n3H{*&wUu2AG}HU)~JXHGVe67y$rEI1=q2-(CMPlTT{nv%&$u z)vfTYn+X8)H$P}UTeySHD|#lKr19 zR+WkTdGDHqk^MB@HxCg5+z)pX;Fou;WokoHtQGb9>fwX;V!=axJPgz?M*z}4+&t*6si23p*`5$|qb9m{8ydRtM_QD=MQl{eccI9S#Xu0+lfL8B{AdjXlPAO3guXZZ`~ z&7gf}fAnnv3Us@Z?1s8?aP}SNO<9kMdR*3{tUM{Iv)arf-K)BPHdo)CnTK0nDVE!D zS&ywR%Y0H-G�)MF4Q~b6xLiRYeb^1hh@>9`>fdk^KpI_rU&=UHj2 za+l96moBY=mVu~q8+Q~lbcMj_Q3V81OELSiH3+z9Z#eV-1<&7T=^vzWrSr!$hh?c2 z#KP8IthPJ>xEOHOTjNZ(RIAFZ z?&~M{(+~*s&HXTuLZZzy02n;syY8GRaOr752|_?UQokVhD%!eOo^m&id$kZ)&voG@ z!&_Brpl2twP{J9nv^aZS3W3w(I%=sf5oa%oq@%8Vwq**peB>BYLXM=y-d4z`AD*jl zJ`1sNgJ|mf??L`j=jIj94v1K}J1 zfsW+&{@{o)^UIygR9=VT=wY_>4Dt%jH}G<`9`43?*4WpBzg-wZ?z5|sibQEtwQVLVK=~2~L z3q~(WsgY~%oqMT}Xbq*qFlwpIn~Btzjq4zmK_U)5$l3!9JSMrYRW_1d00?6-eo+Cy z?k8G7ELy{W|H)fgjLh`75-V~Q8C;-+h@dXr=Iu0y#r(7mLV?(%^L*of+1q+84HLl* z^kQa5d!kGW2?q*<0pLBIGcl=Aa?@-Rn-n;YeM)-x_*zhIX@*bo@PIn4YS>+B8bRwj}qX+rMtwe>)zk_^YI1iVo`9A>YRIm$@ zi51p(r3D|5f>01Zm03V+uZQ{AeDfb3Fqm&KGCWPOwfBx@X9fVa@1~=@QXl|AmAm0? zBqg#7wLR2CAS9kWFA#woWD^4f`FVr2w;7t!6G4@^(}(%=pkl2Vd*6sio^QobOD;yW zHw{z9TTh<0@3vNFqFnt(ZB;H@KC@Nso$)%tFqRya3KF7Jn94_~ircy_908Cgo@tYZ zq^A!)$aEldBv1u& zY_8-HQ5Z`Wps^9sl>VoGGy;GtZ@1Y;xm4n)0G;tt!cwQkBNlF}u|RlyP-bI0I=06z zOg6iCl`6)QN9F!I`QG>PgC7^u$JOF_T^zdV)VUdH!d6#?u~53vTFda~GhSZ;bgW&C zeWUw>s3o2C2)Os|;(Pzs@sGcDdiuO@wU-)`uDbE*&aKaOmrP$%tp?4(+O-H*%ATf3 zJN)IJ^)mPgO8fd}Nye6WodD27xGU+_!o&f#QYp@lG~8KQQmPwVOG^#b!+-X$xF+Gs zSqUR!ED=1iZu-H4zxAxM88Rpxfkons@NWoO!Yv#2**WW-B~$dC{{Fq|8(;B9>E`W0KJ@@#?A&`RPzn)@e!M;U-fvHy zyas2#vGx4F-F@+2UYq>KI|qOF%Km@e{_cO~{@}mQ|M>4b`NMzn=$&Eb4I2eL08rOI zOu9;iqL@Ycwa3j%`u_pIvQ^a@1SsHauZUWb2(0l{=DY_Xz!`6ik2{J%t3a?A)vofx z-H6w^!EVG_Z>B5on*--$XChDv>%yDLJL_j>wGPF`Ybgua$WxiQv!|tsg;Wig)l^;v zuL59wY#VFmQz?g@@q$bQlf#nrO(#!_SN^o}YNCE~(_T;6CP@TE>1UZ+Wy&?b_99001BWNklAL`L};`^LI`f$6yF!#ZKJS0C4dBB8+ixHA0EA{WfKRJ=Gu6y~>Xj01z6hj;r875&erY{B}jptTEPF zB0@wVgpd-25O%nn$U5seLum=kNxCXb6#*>q{{YY$23Ou_zw~<-qxu!7bwnu}V3a;z z%m+IWchZAcg235ny_D~$Km>^_7d9IkUVDRBdh7XoxY|M6xEZrPWe2OneyKgz}rOPhJ`p{{5?b|(impZl}NHXB=R!H20dg$Dq^^CcmG z5%jk9haYAPjJQP4O62fL#D}L3zcp?T1MVmZg-g-z_T83H=&k4DelfG&d1o(<(JRXq zG2Xbh9kPFr2+D=Yrnafd5W`psiPOW1k0U%*k_wBtV@&ng^I}Qkk{WI4>HOHOBe8uq zMS;#Va{vzaWi9KnEbMNE?)=YGp$KAuh-=s4?nbz}1&1v@s}Ueh4l5L(Lb&>+mpAh3 zpOHT|WB6ZB2kWCm_f;U)NAy~&(yR;V)rHgWrBK3G_ORe`=jjr*iU==Bn$Ejuo-St} zUi|Zlx$t}+AAF9(<06L7=Rp(5pi}> zD~*8Q9jw02Xg%l7_eTX+@wKK@Yu}&q?}={AOnLDYYi}1#A7rAY?!jOumI}i}N{Or! zoE(-!bnWdn_p`u*cktG~vHtLzlM9h501qva zoMSjUtyLhT5Z=S&sAAj5+V!MZSbh_|B_8w*wnJ`R(JNSR7f0}@rBsOd)P}Jby(oo5 z0AluS)B9WU05A9U9K*#Cobf6Ut${X$=R~$_Y)1PcZz^BPA~;kn~h%J>)Gg?Q5Zg z5LnKgkXX!&4ulYR@Il4{hcK1-#4u#%JOAh~N@dhi)xu8pOQjJ7GN*>mg5C9?vle(q zwkD|sLeq33xFr1z64~1f&-RMAs}R5xPHH|Qg47tcq$!;#TxX~kV?&;vzcXJ>O-`DHP0~0 z-1WAC(Th^b71OK4bLR^<>k)D7Y7B@E{(S5#1&RFTKRj5!nXFw)IKrvSoC?H?pDyas zbJ1QGt~Cr0z}B=F8OF>PGYdd`hTeN;E|nPXmr{vhZdo$f9_lcWqZg&A{LbB$4jY*X z$Bmh)A+q!MU58?LHIho?)4I14O%BSqqfme|UTVxHb(qT0ei?TZ5JW8*CeoBnDijjK zRIzyw00uiD3K$=h#oP|BL_8ihrRUO!h@{3p```9;C~W1P{dji4F%bX)hgW0HmE#F5 z!IYy{b;J|`d3^rX^}n4i`=_gYe6 z5DI=|qL$iwXTgr?qet15H(Nt;N`^h8l0ZmL5IMfuJ?e z{hjdWQP$lEp8jykha~`N4+HN=0S-3R)lYPu{b2slvY%UKgPmyEN^br|0Bi4o004tX zBBIpD(NsK*J9}Clzn@=uvkeHv!ge-74vc0(jSvVxIuchFCMBGt~fpax^2eYH<-Y*ZPM^%42(upJwVWJq5 zF+MB@S0dKxF7>v~QJpzf1)k3y1lPUfs2I6(nHWilK%5vLE?TiQ6$`sWC3**OTY2l3 z;+?3aR3P|FDOk1qM;*ng%+>X< zH4Ffo4(3b8+K;IeQDC`nQVVBDhq#h{NK#{+dve4H4CUO-r`{Uwgo0Fr9kNA`nt6Ml}Kzb2Hj2-~FSrKlyw6 z&wezQ5~aepqqvk!x?1T=ucXxv&h|>VVv|I5thWAS^=me6UchM5zMh}f__KM{M6?Vi z+e89@x^%}AD+Na9S~f|v@sV%$TKt0_%EIVb=^X8qD$;itJk-^)}(PC8hcOnL} zI^%8CM9&k!=B;FURJ~MGdP~l*@EPJxLsj&aBNS_LluwOwRAuSpy*FOJ_BWiby>}b; zPs?#z4D(t3VphDcwji=M;BT%S{JU?~|J8l*pS0qgPbIV!%w~O z-jS*Oc)vu%Ds$wCTQI|G7wLGttq_37QI%WKXg{5)JTIFn6f88Z3vWuFjm#FCi!IfK z;|6y=Gkmu%FIIc-FUj*lV8ch9+hSq43C`Ph+)?Iy64SqaiJd?EWM^_#!?oD;g9YG8 z<~Z4gh{iKp8^1Bs?Nqi?RT(cO4*Pn#uvJY-B-@D$1Cd0+6BtVX7zE5MZ+5-yNPMv+ zlAb0a@Wf-7a^Xzr)4t|Od|kRKcYFW%-YQ{A%1{Vd)@QX{1iBrlRLLX>o8FMM#iBTv zW={m_LFevH>sP*f%zqr>ptd+(id-g)O(z#)V%i%ZGHJ`peE!CkE3d^~@^_lMc ztX82&Itp3hh`3PGV&Q|{UPi6q7b-9QG-5++_a5Nl8^WPmu_3;~Iw&;|f!}x$rYau^B52=V zgzdUImCIMqfAi`5afb+?KVyn20c6jk+)d6m1IO(Kau;?<0*VGRS4SVUV|p<0M&59v z&*fyT>yyRt#UdxW`|J)I?-j$_WjfFY4|1uon42J$fN=7(ur)<3CA2WLZ?A_pKG)G& zoP1C)&}Z#>;%ZWXc>2TH@M0!y1B><>PU+2EjJOW52USD3|R?nSp{Ms;#RXMjRl*f;AJ|rRSsc#$s;aa%<#m2_1xwGEq(kfr!SVqN;~M#wjzP$=caxw|#cELpv%;sh{> z3;@cp8$GHg#eL5BR$uX=e&?6^+__`%V30^eJb7C1pH}7W z(RU`xd=FlPbtH5wbu3OFly|<^Yp(}UOA>(8=pES7kM=9h`fXIe=Kw6^j;908?y!|_ zuZ6buQA@2~kN@<4eX(;tML<({&X=4XRX`LblFNIZ(ldd}JL+zPNms$SwwdXWDiGFs z6^bAfrt520Rql=+8yTsQ4Vd21=y~ZKg^8?kmrqU9lKIpM3E9N3CWQed{hcU?rP5fJ{^UuK z_Oz*dZ!6NFaMtS;6&~lquoosi%xAt0Ma2D=eAh^?Wz@ZRau@2iduM3;E0x z#NyF+r*-C>@#{C@Y-#}Djla5f{9*RWo9F7MJ3`{~4hItBPAHNMx(8P3hQT z7I$>o)4iQgNc03kAG)9&2*a!K^swq|1WRpX($i5}M=e#3 z8~|*-p0tKKJ6lP(bIZEUw+4FcMtt%#UsZ7;fT?}hk^qDPob&uoQ7VN*XGjR#e`k>l zln#ZEc=9Aq`w9T+!Vytx*wC7TP>%P@{%qGTJ@2rp7YPcKEPV1_$th?;21wx7OLFFAK9mQerM~`woIymdg z%ocOY0uw&JId>5j#8*Fvq||6@vX#dbZ(zBw<-#rdl8xfPl2ka{jinaOc;1+V1ZzAq zr=qq3KvPj!xTvL^C0lu0lMcmsAPH-4A?oOZ4;L(isWZ3Af$DCB9Ql$@FBDjO67Y^b z4hn@}EAJiEg_jcR()YF_sZd2I1a90+xtUIMX&B@jc}vy8RfT)}=TiW<{`rmyL=a2o zh?`$bgmE<`=ZKJ zp)X!-?XBO4btGBS*WZau>7thW!B6z`v(vi26D3`J`n0%^j3IBG%~m26o;=N+rMmP?!UBLdzA{9F z=kLtzWncvXakT}WCPx)wvp8_3iVlSegs$k+@(6xCT)9?tWpMZ zc2X=HcktOfl+UaX!dY)BU*`@HILbyx!WrUavs^e7$Y-jCHCEH~s46py=i!5O>DY1d z3qIY;G~wa(SOtQon`{E$?q?87KIh;4wSGFh=!@-qD&>qwq0rn&QlM0#wd5Vm&S`O3 z?!Bi)?w-CV`(2gB(mG%(A`l{Ly&vaGF2M$`j{Ht=g+*pv~@*gW{KRU#jmMQcOz2--46nS=UY<0zUTeXtP>g(H z_nsR6P1)F)hgYH?k~$PoOI5imrY2kY$%EZ!vR`thq0*wa8FKsOBjXzE??zSOOyO4z z(G0*EUX4xV%ek?YFEg7>EJsMa_6`7x?I~)gH1KuR)Y=M9mrN! z#3{xdWhyt=jR2b%UopHIvtW-ID?DdoX&L#3DKNMZ4R#_G3Lse0eB+jqS^!6t5p3UW z@syriqXIRR<9-N=m-jaw(I7(F)k}qBJ~2_MxW~7+9(IgGs{A^chQOvE5C3r9; zE3F|L8EgFfw06!PKgsvsU+}?Kv0}y2?6_LLk#J%c%deJ9uBa_}6vpF@Ae1^3-jWXF za;IVGI}j8zd-l9&{EwE({E}4R?cWaai8=ic|Mj=6&eQ)^GY411L@S-Di^I~gN%b?0 zgqQH@v;7$Tf;9NJ4@w@5CDRmJsn97^EP8y(QH|tvxLZU z&zk@U)Uc3Y>B``vw5y$8KbZcs;haSq&2ky_Cw|c^=)OHo`qP>d6mguJ*m{=*2l5AnZta4o#4O;HhjrGeF>sKYdoPSfI|G3WWEK z1Cx9smG_=bo)V&Z@<~HtXKK=qW zAqkSr>Y`yT)`jCP*e8B{ZSUPV5OAcIttsxPpM33feo~prOD%}t=y5Kk=x;|V5aWZA zpR!w@?MW?A001!rp*hkacp{W|^e9IF4sQm8wd+Z_a6$k%8XuP2J!aLHT810pdvwHh(E9q%dc%em<%6w{7D1^er$mA2_90dvci6CmpfBru{jXRnT zCDY?dNEEUW`;<9r>9M~XRhjjcxE`kSf^c>AyK_H{+j4SP1u=gON!>7vg}}Haxgd-? z>Kp&_9-Fn#M{|+4#O#|3o2F>uqg+kal868RhF7EUK{>n{Kl|}4>1mec=2OFY1=Hio z);+ab!Pb+~h{#Ute)7D58bX0X2^!bNgq4IMtr z0inGX*wQ;gQCkUtr_Tzdg*ATjW|B{8XDMl`monK~L!I`t5U~H=;!FR*wp3_JH#@1q zL?S>jw{cg^jw=M<+QwU2wY2d2)7uUKAxvc$%ewF?5Z%p)>1K=q1;o)gU%$5%u{>S~ zWE1}B)54U#yA?8O!CA^@#yQfVWYb5huK^)ytKrqCvmQtVQA_GT2ni|>JZ z#6)d{0{QhMU48U0+kUN8WtKNJlqeOVKx?Tke9~2b$bY6Oy^dtk)m84iC3ZND_e=8N z4e@QWem&u;gR${|Smlnnemaz5WpIRut)UJg;T^s6^-~bYW}Iwnc3*Ebf)__YB)s#_ zelmB4RDe85CP!&cqeQ912Y)y!kL~nvwQ(!m`{De?7rJF;SN($<_ZtO7Yg-SlMCIHT zb5mumH4Fe?_w`oV*VfR7e?FcaS5@w~z^)6QPwmdVw6hiZH8;t;)cjhuy!q;oz`ntlR9^;VX%HZE~a+pZu;kc|Ip^%JG%Ax-uOjT&YH*$ z09f)WoTVF|>I%`Q%aZkE%&mdqW$ylDc##k@c8s*J4w+{&sld(_I;e*=fyd zV>!3Z5_!1&xvr4#^oO%LcS0ZnwFa68EjK>ZWp*JV9zV)C9n95KE*xi&@mp8UErYQ* zmWOfFaaVEQ1SKw+!By_+!i`=OAb&$3~%)`Ylq9ZUF}%W$AXf{ zktzLRTnmXh5-70FowvT2Sz8kz^moF1Vp$j?B$~oElw8j)Bs)8)i?I~}u3e8g1c@&J zcPrSgRp);CxH7pPy(oFWFgdC6sbMowc50LsLi|MzsHXDMGkbbq%iI?;`*TwWSMej8 zw^Dw4&)F*t*KCztJvz2UMn~`0Km6*+w|;-0vqa;z@}8Du*yd~L&wc5ex6)-%$D`=e zr}@XE?PR3`fFZ&sC3O&_Kq*BSi1E~xRddl5KZti7W&% z9*#Ub{MsiMKiJ61!^+GE{O~IiA#whmhC(YD58AgMAN=9-lRrJ4{BW{(bUgjZc>Zvn z?`6edUY-=ySyhiKGp)>QQ63$feP@>MXXTM27wGQEw{Nk?w?W+lfO$Df?iV3*2XBA# z>aYF_8~$lB(8bI)=ku&(N?**3t-KIuNqz7?qeHQFEfx}qklAGA z!qvHBP!aE32*?TyXZ-B6O8Z(W!AIh{^mT4oV$7?ksl6#Zo89o^!Umgza{7R=DrH zv-s)5yr_Ix`bFlnWY`%2f%6~`+o{wFiC~sFXMHD?LLgb18Jcd#LV$PP+Xhj>OArDK zug2DrtGy7IZp}H5a@n7@b))@ zx4)_1{=aeekE`GZMm;dxHUwk~K-1&m%vtKJ2Raa7 zp|z&Pd7g=_FYqsG*W&(8G(D{t6j*1L2>`F^lr<7&HV!wKoz2J@uR=jQuna{xcgyx! z(p7coI1-0>9lUS8#BuL#gaVNqWtVNjyyJ8?!|7o?IjsEoBGBaUUe`f{QAaIC_57@E zWC1UU9~A}>#;NFC(fyq$h-8q+Vruu^nFD|bVvdDDQ+XYU*-6df2;QgpcD(w@wvGgw zDO4!9_0<|`p^&3n0HD7UIzzVh1mujL99C@ACIZA&ZSyi&fU3+b)408-d}<$jyLkYF zLR0y=aO8ny8f#Z$6$*~WGPSRA7p2mczMNZc2?c)e^$Fu1Ss>k@>ac;8@pM zd;XQ%chjZMv(e#e^hBoeLc$VZ$hI%?l#LCqCMifTc z%<`+PyDjz<0MKAJ;sI$sHQrH`x%pXr(f>y1ZZjv6voKI^c)~_N|b!{sOv$=xU#hjSNKE*C?>P z7FgrMRFVg4ypCjVE39(o9q}-yE}W?yF9^Iz=%I3+001BWNkl!) zw0h=N8uN*54Yac!5WQ=HV1>l)W+((S?1}T?VH3dTNNTJKM;;!3e|qK3whDz*g7u{Q zd8GvcoIJ?^!CMMqSqs(eie z&+}!JLU!0)d#jU8On*D5OP@~+3hb-}h#0rkXs>wvuMD_Pclx}@r-nS3$}N8g;wA4$ z(os>WI2h=|Z%qJTa3xCnn(-Wn$RHb~g{}Pg4Ef@ALd3gY>Q4^Kl*mGxD{r(+=~y-hK*tYr02p428T_$!Jq85l>0DGoDiFM{IpYsM%&>t0 zLEKR~6wXpMt^x7nX%V&5=AE=IoeYFjh!PePqXR^Ni;-ah(c|w;P3fxK)rF5*GMiX- zt(x3(C$~KaCI^+$f;_Q3Uj?FKr>*g2=1?NTB^kS3WsZ-$#mv^ZJARzE*8*Gns4c(w zzaQvCY}`s7es{7u$Lnr}d~b8(nV@-C)^8+yf=7vU;hmvtZ?(^!7fl=zg7c(8p(C+8 z)qV1JHl)Ophxzr-bf*WGj`&;m)5cK$*{)PVYMh^$-PhY}uWRObfw=l++j}ApLJ4bq zn8@*d0Rn}@#aYcM;6W^_+|7>b&U&aq!6(-2(6rWrFqIF#Gu^nE$WV9--qP%(3L;q- zE^eulXE^}qKy)|4jaz9D%X03lBUAbLX`OWR$@9V)-x}zRn~7AYG)j#}k8*y9guwZk zafYI{G^OW&ExyA|>8&LuYRdp8N9B^4y8C)tNPO|$0sz);#tb)DzY!mNxX8~;e>*DX zw!I$O+?&$(ZUo)!@X!AKzNyKcKY+`pyFCng+adFhmnT$~zHZ-bRfS{W0C#zW0I38U z8~Fll+)mj=!uig;aRh18k>}i4He%>RCLP@jF9Ft>_lHnSZC!X4P4Ll+fP}!!TM5@x zLZJ7gV`*z2wq$D%Ob)BwRv07_1=P8dTChy1H4K>IF>0D|#4OP|cU>7YAHZWI!Y*H!z?2pRV4V7 z%fdPx2%#FRzEH@)!OMOPEA)l9;Ag+AIXVv_{HSWil+Ki%*A^}S8j!7kt8cZ1Y?z76 zlRbT!b3Cqhv>2HxcS%Q$5A3IZcat+-_s>D*OhcO-R#7aImPEwO*Ah0CIzzLQnh`eh zvpPTfi_T06=#$poT2|ieD51+!U00dgSnomMR;XElgE=t%d*D9Z73ROPpt} z*HLGg`^LAY?>xAWpvI9{d#$x|EB)=eN!rthnD&&jB$cRg=M5eFq_mZ1k$!h0{Fzd+ ziKz;=bnY)(KHgt2h3kdSN460SSn`g@)9LdvZfhVq{2=RYh8*Mm($D8-#2Ts#$FXkb zk}g=g7Af6Kq;~GN7BqcjP+R}^bl?juh2ri~+zZ8>;ts`K3c=l-0>z;a90HU;DGtTm z9YTw{ySvN({^pry@+L1bnVZ~va?aV^vkUI`GZmvE3}}4}?Etpsgy)UUTy8UNy#E((##GW*NTUU^_+oV&9vuMORrwlRioPwS~ebCgzn+|Q$$t~^nc0l%KU!EBM^^r8;qfYXMt2tJcQSTkA^_rqO_3Y+NT)nTskkqKqc<1FUO zkjdh!Y{&h|>GOf#>tvD2O2>etdd1h6jBBZ_5HbM(k$MnP|6=MLxqu34y=1Ml7~vfF zq}7BA0L&ii!%gL`vKR%DUj)7gQfzC7@6ND6O;`=?-3!OA&K=5tu4KLxWcsXqL=K!@ zSF>QmC6F1QUX8OA{W0SG zKA7@YKwk%cdR`cq6odFP+bAP?9DU;k<7#AK_n|fOj|`Ju@Lyu&<6>n~qS&13BjE$2 z9b9G~6EV&pK><*dq@0~<%F{uulgp^O3OJ!#_Xo`ZiH$Y~TdeMIbxhuq)0CJaLPJhy z4O|~|mSVLHNJKfcf~h{CMje&VW7c1cIQHBu@~%x?F(m^E zomvXJjyGJ!L(7)e7(G6a+k}n9+MkG>8ys#i?b|rD7K>D>cWdS_czZZPfBrL`UyKgx zr=OPIXj?t1Nyx->wo#oe+ z*>rd*+PD!a(%0mRr0;_PdyoO-T)#X0)C>p29WbwP+DOE8f02+Pd6?$hdclpG4qF3f zW&8ZPJ_>dL4x>0SO>X*&=in1nMMaMkYDhK+m;;AGZ)=HWwOpzbF;AMBuK?J?BsxeM zz0AaL|2YZe(3KGF_q%+93UD0mtN=K+_^_EZhGrz1mE}TsgkauW{i_eJiKeBE(s7x` zjPGIg<%-{Kn_GNj?8l|#tygVpJt^^E?-O(b)E;eaRGqt0DI~1g(TOIYeDBN~drPb! zqI6f)8MEKew0V^L*Ohy+DuRQvOZk22on42gZCs@aE-2}_23Q=R#>O9rLZ?rKgQ&9f zvEl~i45)&=x!>klr@sr~#Wa;J)V}wBbc?urPG23Esf!xp0o6KYvyZ$i#kB~jpilwU z?0*2Uy4oG268h&pURiKu0@y=g4MkMFA5~yGSo%oz@klP71_M{mQq-0ySuRIu9ZDy< z38?tJsAx~xSE3h5u-s`Aa`80KX#VghW3ZgA)tMZiMFBi0K!*T)0Is+n5m{imkL=21 ziB!;a?emV#ce9c~Nk71q1dys>{~RV$$MtLQUoBZm$VTlgmHn99Kn zr*$Q=1Z(8l;_L2u(gzr#`Y0RE=Y@K1UcXJX$H*Sdim6(+1L2_-C; z3J0jl@_t=nuWev?)k|jgZalY;Cw7OSaIq!-^ONtP2cx?958wy|vX#3H@I(oiY}|8@RBpwL$o&?l z6~S-7_ZzTcxV~->3g!${=c<|ai`1~R+n^lm&p-=J0=+@}qYGT-(jvxuSv%1*@R6yV zZv$hN8ajA>wmt^yzhaC`Ans8igd(7!*s z={N3vBH{>rQx_5fS?T`f^WKN=UARlr=L?CPeF((7E=<89NMV=BBGCpH&tl{PhaP`} zg^B$AE3tE#7?EfU7LKmzUx7qlNJUG}2?%#9#gY?rXre>DTOf2wW06(ZHx zn6Fc-dakUy@3eO~Tv2&1#Xz|WfgP-s-&{<*_k`4zl4h+7s)3-WsCaaL;6^hJ?!_L& z?#%q(>5ofn_gf4SvD9_}X?T`+Wsn!tXODHfybB5hi4gj=V%y;x~{0V zU3Goo@wEH=+u+n4d84^_(<T0QOmxKX1m@R0@a0lp z(umbn2N^_o^isS|C5L2vHoWJIMsZlav#s{w4fSHS!o1koDof4DE$0q_2-@S%oj#2@ zp{Mk#w(}u_sI%q<)@UP^bwObRrbFErV{YzRgYUQ7+eNB#bqFUlo z)1pRo+9=Je8s)>liO0UOA z+#~eGF&4!REhjC(`?M}?oXJE(YR_qa<5`*y$phOn(Kv0Y=kU)5PTo85^-J_IM0LHl zpmg}Me|WL9{*j}MNyn2(Y0{tug*l#PJ zlrFh=BlZ-N^IE-gcJ6>#gy0~OGEbXTVakFRm>29{$@^Cx2``?*Utp^9i!4phd*IEov-P=7<25w%zu0w@h zjUKy#M4m@hFFmbU0MeC>e08u)`xl6eFIm+-h+!tt^dh-b66*IQ+~3w=o6sMP$`|m> zIz-i40u3L1)!cn)o)F;wLtpz{e;_|F&}R9`cel`>p#c}6v)|5ULR<2u?sl)w=aDFb zk-5;qWxr#8dkB88$Jw@uk@pN82()q<9oj#wxT18JX`H7irIgL^2O|s=qGo`KB)%m= z{Y@Xrwo{dTOdCdo-CNh7rAERqfL|7dvRoc1TpN)|E|yJ=qe#QR$6~Y3pWeU zHEJw?d4oSbsEZ5cX-e+g|G9rkr}4A+39Xa3k_^B61O{p))NO=uVb@7JYgU)9?2?^nVe=Zt8cP1%i2W` zQnW^`K)2}_Th`~$G}EC5{4f0QI}sOz?U9&HhM|Lvrn8SwBGuqVb$j znQ#BW!~E@y$kS1~@PwA_nA7=!xb=-QYu@tvAE(h#FEzc!NLuJrrjeBL?`GG{%xGz) zXzAfeClU(0*05e!>TOw8mksAvlr~qy7DGK&d?;IQSA+;#F{!|5ef_ya74J!K?>Kb@6p`Mrg_Qj9-15A}!TczHT?Xe5Zua}v5f22$hAG_5{O z7f&?`?_XA`k?%rFQ!D(J-higt>=Av*>o9)xMQsi2XmaREV{e-FchHfrk~CDk5&W(^Agfhc)b;@y zX?_Cy6a;ZrUv-K=d4e>zUWH-HvTV-$vaxZ=R%$x|6Aw2OC8A_ z?xR6X#&5pb#!r!rE<(qS{YoUeG)dtWtFN;~Bh|dQQ;tyz$ zFg48me(T7o3J1>1f1A@Pz3F^ah0B#xr(Mq*{BC3r#a|JbyvwATaLV+GVs z{yt{jtn`{1<0OTj<^E^M9Kx~-r%MjpjQE?dCDze&jO{NLqh{;fnd3J=zYmggqv&Q$%4Ld@F# zs8V$ZtfYEh8U#}P>UOH573h~oyb<+P*>>?MmFEH5+o1)V;$^`+Gn=+`iK-@)T8r#8<*ElVrs9evz?V2KAYu7Y$Vuox+P`~6z z6dT#G@i9{l8H7u;O;(5H;V=Nh)np?_WweS0E4 z0|}*ew%0}<58GtLvMr795%+cZNq4~4cU4^BCM}Of!ff*+6VoAX z6rZV}Rk6)O%UKk&K@T0G&kJJ9TR)=zjcGC$h#$Atr%;j?{JK)uoV+Dm^x^_{KNY;( z`AwFU!ZbO}zyiENl?{M23A=#2uJO|n!&CwQpIIKR#$ zsUvXWbG6EU?yz10#iG{I#byC!?P5lxiGw&2e(2Z-0oRGg;$Sz>?&iCC*TzfNIcxB0 zgs)5F(_j~xSEXq-@f8x{+|df$^Y7|o(2a7$mj1_meTT)X1@L^%5{&A=x@o6a!68xbXe}WoGEXRXM94|-ps0Q+| zIk4UF1Q`m7oysLA^_+I5M`80ktyd!U{UFeq$lF;V4n@5f4-h;Kv4VZpi68_;mK8|` z3pyQ;S;*6yTgpXuh1bZ^p(^R4(qVX7fV(#)uIe`l{Z&4jVhKzYauBjB&>3tN8Ckjx zh}@qX9-o`xlQgS2d+a$%1>cpk4VYn~ot1yk?+wKIxS_gPwAe`hU|jZ-QSmo%7{wmYv+DtgQV9mnkLw z(@nSZRgnFMbAhkgW$xRDtKPSK4?Uzq;CWrI_W9i&W=F-YkpCvX3pgJ3o8)&uygvv3 zosa#~Zp+13kJs|RPpT9=X-w;A^)JnDgR0Og;>G1$505`8Ox(1?6~n9I5KH(TBpQra zi=o=NT;Ln@@*KrtVY8@Vjnr#?;LJ03;=~a89HuJiG^E+Ck2EKM-!_o@-+N+8TM)|l zz%ULnW!a@x-77S%1#pe@Sm!et@@)4{zEV-%{~YY~+Q;rgLaALr57IT(1%IpQTI3Y7 ziSKe<5oTo;^R5E~h_7!@qKYWLUwZ|@D}7z#ggWpE(S$^AR@^9+g~uF}NR5YrBkdNt z0wr^Xn;^4zPH%68I3_~u#wlJ|pCPCY#NOz6pxy3`Zsml7EGI8)Q=&oT^U1%PID{BzJ4I>RA0Ohsp=rGzqgLR5P3FNKOrryXe-mL>vja9bR3Okr@%BOa z&oIuiIal=9@OUjE=&=cE@b!WiPFh0XM?dd3Ns^x-`mZhPvg(&z{x^riiy~omLC|lv zIrrM4-ZZXoeT$61z7S8i{^`<#QjUB#hy0H$?^jjou{}(;TirVFXci*5-imwP)A2r>^SEnO&{u^4uW0wOQMtwpe~?!%B_p>`94qR zNrss_z6G){)7=YHq*3x{x|qWJ@0tZs!pnjqxoqIKP*@{N#G`z6l(tEl+sHd>Jk!7# zTCzi3;CouXDv$~DdcB9w!?JZ2UCm)it}?)6E+tNJaG@EuF6J3}@Sf+q>~r3a!6*M2 zUK6%@lfwZAX(Z?vqvOzJL=$(&e^t)m#We~Q!$9GsX?}EE#e)+!`|I=mO>+3geMeWd zVCk=WaV5{JKANpIw-`lSa2bCmTxfS`pyC(&rUQ`%79sx%{d~S(wlBSCGKtgd_=ygyP<&3%qed8#eYg%}9_Sc6o?#W!Mg)Hyy5m zvk5tPA{hZW*{$K(R-4e#A&6U`WOh76^>yv{bmG3;IZEb7p?25iENooGc|_RsEZ~bo zN8#_)9UJw_zXNWEQhTpZ-}nheYLhMh-OGXeLC9r7dqnY&ygFZj!Q4~7CU-B{c9emuudUL)2P->88Wep@2{I!-kYWB?&Ni7uRTK{13+l|l zaz$}nXh3U18>PzSLkf`8z3>@&U8`C3TF9>OUTWn#W53C( z6K`R^>WjbNoCY-H0AtJAz~e1C`q_<629Mq@3&U(^gWx6F$Y~SbmJ*f*r+|vJJH1rm z4;<{XCl{d1pRKdfq9R$nIIXCRG{OEhDjdqi=B6-9ASUVW>87F$sL_LzR1aKFthJgP zSB7;Hn0SnZnLKDfKd#l5;}{Q_k~?_~kN`!#`loy%l-``NNKPXkNto{H@!7l_*G`r* zN4dqn*ak#o%wzRlzcWF-{)|p4az%YP}} zs_FnhJr=q-V3Ux~h`-t6>ixsnI;uuFa;^-qpR&<#@k@~0+=S3nP;G}0d9143Q2fBKSZMwE%lFG8e_`4nNHURPLX0_ z_V@9|C^e5h?ZZnZ*^OMUhB;G5y($=ogmWTxA>mBGz|)0|fXB^%l*z2AI8eK!qUcDm zHx|&=R3ymO)KvKJtBG(N&~?2zeiVO- z_?A6Y-ia|@VG?noxapyq@ay|WzmK6w%VUFvlbf|~GLL&wi+0X$qrs34UnUX2YD3=N4;JBOm) z$I_F(L%F%fT-LM2{9xtt;n8e<&3?|WZH#8A=#<0w?7wYEmO~qO;C8zOx$5{=6!A~e z;vXGW?d011OahpBa{PZ#8og{Y47{HFJEt^)2i-`cu=?!U?Us)7$`(Sg5|>CJ$}bc` zJTzh~ImYZ1v1ycXgp^~c2?X0;fW90QLCB}3qKG5G<8|D=^Cq%T+T%odJ*L=$UXE^# z=0jM2`@Eh8NgMjgmpW&Ah{8gbF%Vt@0f zNXoH{PCo)r{mIv^NvO$bADjGC9z$E(To$Jow?(q&E}&(#ogZKPp73MJ(FshVeOUVmB&l( z(+|mD^W-3esu$@ym?R+3!o$tF`84j80_ZN@T_$9vqLO6%xp#~=ls%arcmIV+Iq#ud=e!9I5KnEvU{iL*K z`EWBE=+GHZ$s@rC0OQ7(#lP2!yZg&);XNLiSN-L&<>B7NE`6*>i}6^nH}6%;b{$6X zTdy$HKEHrqtPEIb#v<*#FC`5948h9)$j()od^( z%2Ki;NZ3}V>(*C8P}P6d^y0aLyIt+E)>j&2mr)j4U^;nWxsp+H`UbP(&2U?-|oS1nF^vlK1g`=*BCu==8yu+Cg+`B)SP*K6;E&ehfd2y;}Bq)QAR)>CH`0woaRQnq|wQYK|^rzUFejBzvA(*~soo z$pNx;Y?sE|WVfuFS}*szu5V2`da5;b+DjT`K#0#Yh8=0kA~sdF@d#z>xk?1eFV(|1 zp^T~S7EYmJuT^Uf_A(VDS%r-5psVGmhOhit#WyaB>;vD2^j7|DED7Qg5dPwh9{eKe zk=?EjH*{iYzI05GRp^3XSs(tLk2E}P$->5xW&;vh-6mF}NLPMIiJIjrDTJ>~?3BB^ zYF^Tq1rs4`XtJ~0b~!#oBB`+%`uz^J2}UdlhbZvlPQ+*C&IsZg`WcF{w4p`LQAjg7 z2Rh!Y+K<5x#ukZbd}Un}-yzI|-N*@jR*2c8+~eD5zQQUxe1eK+c}pis4Gha{(|O zz+{J(9~GE6JGXw%WE6nf#v%du&7HX^j3*p3M6f5aRDK7p$aX+CS&0>#RG*wk^{tWa zuyD4T(TWT+U$3K64`L>bqzjh+LS=`Tg=>_n<$T$xt}XeY;qXXMZ8xXQb$C~Z#?eb) zA)(1a{I9b}UbVuRqXDCSB1Duk~2wO|ISPtmq zZ1+p0Kdd@?tfhSDjmZ~4)!aQfzeQcIhRUOiYaK7)E^tkSbM(j0HwLGF{bMM>T|)Pj zwO~s?Xu1hAzNEV2u^a&{buyBfyi zO)Lb|(dTHwtHk}j7opMb^k!Z1&3AI1@-|$)CF^n+CCfW5KXP029yN_q z1?MEs!{0d^wDjDp`Rb2Nw;qkpDwSsX)0}e}G;1CLMGdvBwZVT$tWQbisT90#AbmBt ztR}3dpSf`_zPDd3lEx^)fDI5AgF37XL~Xw0Bf`z8lf=JCBXY#^Ro?h zBljVnyDK9Y(Qh%4+ssvyXK?efpdK)g7Xt?5Z`4i|ruTS~QC-M(p*0dt!g@@_ic-4% zzY##{wUf|}&k_HDsQ4%b*KeneEj|thQFPqo7C8-%OrAf%V(ud>UN`smRyU8u)@H9$ zRu_kLig3qy8GpDH;6xz~hBlx}b@NT3Wn>9ISmwS3lj7I2wUs}62oQl7BvOZP#dg`_q=g4wdDfd2W}D zh9K`KZgkvc4-Rh_X%NBBR|OPDbp9i|Uq%{?&#rbFWO9oxb`W7T#EB8}^5jLzl)XrG zj~z|a1%nJ$)8=vp_qI05`x&&>(Q0Gad=iZI=yGqztflehz6(Y#lrm7)g@r(h z#ktglBdfpsc_!?i1Pz_HBBAQ=GvDI%|MtAQ9AO-veFVPZf$aB{vDL&k1p<(zg^GJK zNn}I56~-9=^C(&CG`0pnj%6J;(uG_1N&({2fW~y}0XWZZ|5md%e$jL=8=X#$kl;EW z%7g9Qe4WZyi)#KyOMwBvfG^|~zZFvy$u`}v%g;i|!Uq{i9Du5nE+^M26_NJ^{~cta zYg2X8r(y-?y?RpAEul(;-)R2}<1VLQBFvXYqnfojHoLL^7D_oIk^XJ0Ol!IZ3Xl@Y>yY~d&?$aaWM z*NhJ7spwd=|C)f>Q_ww9REVWa+gkcu&f!&Qhv3-09K~H|@ozCcNr}1}Ao`Tp^mN#M zU0qL%tBzevaEV0xtA(VbF!@AloNqk~gsN%4bd`_)$8IJuI{TPShYtZbjo^$JQUZUl?QBdou_lh8VQ|g_8 zDxt8Zs@Qg2)4cV#te+383r7)5+=SWk)L6Q5@NSwQq1Faf_5`KPi$941AqG-#l>

    DkGEL0CIPya0p_jzOifi{MJXi-ZST0km ze5`;YsfE^n{9n@n4+5&WS<0`*C)>J+B%!=Cg0i-@q4^r|Z z{tT8^Akcrk{N)1ohQ2+!SyCNqXQk{d&M|5a222ejT6%}th?<6xF_ehS&{&DcLPeE} zP1p!FkBOvZEnd(K=SeqW2YQ@DfY}_YXl=U^CY^u7BN}_hN^4JyCM%O5^f&faaWOCL zQjV78gONy#nvzZPw}lg*U9rNce;{%KIp7rq7Vr@xldgfxTtJ{NEnyV5gZL&>ef@RF z7iVPG%RD&Lq@$9#hUUpFJ&)YaD6*4Izi5v?*wb5Y0MIx%ICz&4j-pH%*eK~g@fdB9 zYA~onII~8Fd&S~8Gv(B|77*6^K=#@QfhfCHyOPJ)msjy*bF}NkN2aljR*fNJ*#7)m zQ?^=Ae0G6M=!h(OOrQPw&-7RY`k5r@aaI9FUb<~1#V*aekp)pFI4%;d>cNp)CcI^y z9Ca7eL-NcUE0otveDyoGB2t3*XF-GVzK_&}2`kjgVs4&UZu&Oj^vXn!&NekS*!*ka z`SfN8Hd!h!tn{Y(FYm6x_=>ZycSjpCTV5&apKVKa3mrj5?^c;L86Zf<@^pA&B)``0 z+m{CxLXa$N3~WL;eFyO&N(MwkuV+Y*wr5o_>f}%+R&zcSg(Zf{5W*v89&%ui%~MpF zwApo-H;SU@6Sa)TH{_5CTXxx#nBoke8nR=&0B^z+7g&k@9=UtB<sockCnii=p}5vR)fDj2uuY?l#2cxRRk#zPwNU!d3Vdi&VnWA_hWc7c zV<7za?L`@CrJHk)aX5bFao@;^jud_nn;O8nwP`c{re5>xjoOMV=5rCUpl~m=hox0#z48R6&30^1LFq*1CBpfe%-zTiI( zGGeyG3u4b9rzea|NKm5nNO4jGf^~V=zal6nc}%yepltGalUKR@y!p|_@NjB$Bf321 zP~;!k7Iy3xx96Z3<-RDEqE|ziHzM)&NE{NHj&L0GPjA1xgZUO}%HJ3lQbXKI93^Gm z^iV4oM2e%?asf3OKLx7w#zhHmFbcJw#hN~D5VL5)UVHxo79Ze#t6X-pDDICs^js4e z6w}SC*_cpaXGNTp_ZH(UOsRueu}ML3!rFD_%e?ez+eNAG<~JeP2uIS)j zKrzKwi0H%}tw*~)1o-rek8yG=CF5&(YfyOqo6~#k=pEm0us5_8@i|ox55_*+b=Fl$ zrY@%R5i%F&AY3^qkTLp|^GKkZB~V``VFHvG+DT?3;ESIN!-}yINZi`_NEI5?b|B;W zic^K-YZpxMBEaAOD*YSU&teqLU_;1kY1nf<`Ukzy$n^}DgA~P$8G*i9%*d!;%d(ON zNlyfh(nj!Z_bhYSaywQ@kcu~SEjStnSg5#?ZS0A!GXyNcikz8)KWn)A zxRa#hFz$K~8SJ1VM=9rvLwE7C7fOQ+#A7PZjKdMtM$fK7vim;fCv1ub2cOXKqo7w} z6n*2#lEMzS7sT^=0X4a<&7*}X{ezRHs64UEl$>d(31^bR2F@Z=Xmn*b-ot=>I=ul6 zh!j{Z->xq~IU~p)@&k5?X`jV7l7tyZ+F)7EqPiRG`9{zgGApN?@OGYqEvrbz{+!aX#thWZ zda+arp!c^CV@mxO2=mKzJBoCK%%~5`v_TNahh@6qFh+g{In(|>l{M%A0w}vdi_bzT9N%qrsYgE!!m(#)0a0GJaoq>O`tW>C^I4+MahnH7fQdnHIy$g-}37 zTsVb==dcWo)OK=ZuLYNfQbqB(;IFNftw>mU_b+Kc>O2Q;QvQk6GdsKf^dE}Yw7PkND=ujo?o0F#sYy&3J&Q z+y9ua1DCt$bZg-72bzl7b=)h`4pO(R+Bw$+>Y&<0H*BbaHr-2iZu-Q5W7Ez(bmU17fg=E`ai^D!+$B zmDqa7EH_?(UeKJFu_Xu7tyyJUcvYwqgYLASz@&u7tw-#97|qGibmzsPCT3cINb%!H z94VfY7Qq)>bJ1yiUV2vfv|lE9gN*neMT&=aJvEi|P$V+!lg~W~O#Ygl`nvr_Qb>%^ z*!6Iy5In`o8ZDh+n%yBa3aIexF7Xi)#J=X2p{;}dp777!rHZ<78}BpyVrNQ%GR<}< zQCenNe=R*LWOiWfH47kr48;$H&Ko z1u{KVaH~HsiF3Jx&&gdcHM;?3Yl18QXcED44nDB^^AXF{Qb_3%=qt}AwROqp=GGWf z-&&?QH$R<;XED!@vTf^#bF{jVuC5=AnJoBJojZ;<))Ymd53!8OnmtNv`z}3Ab6Pbx zu{>hTnR&qe>)}DmbcV*~RHNf`vWOsK#~;q=nzfNQaq>|8;px7N~RQ$N)-{&9k`_9H3+ZVP331(tf%9Z)(HClVk$N zKLm$sPamHc7dV|;$HwR$keu=#wC8>EV`9WBZK^zFIvY{o{3j|UR}ZI%;>$&oJr;VM z*C%l*snW7$`2z z%5CLSAwI*YxPeZ~>F*`m5?F08D1Bi{jXq@G?5jicA1ZO^YqkN znBv+?;@@;$%X@TrBt7vl>lq9${m7jwk9N9rB@Ql47suib%tTwRpKh#Eu34mus!6SL zl=y%9B4*W)iLAokrgd7>T9cndreSzk$II(OO@A{^0nT;g6;8R#>i7$OmgPv|g z7ZaIG82nbt+!xe%cv;!e!x;k=+ED%XmZ&iWm8>_rOPP8x>KRZ@)ML$=%>aEbqS;y< z_FWW2SH(N}bf2~*W6E(StLULI1I;bsWc80nPwq56vQcr_vcwDHU||)ZVz!xq0PUC80GjPme*qRoY%R9 z;k714+_(ITikP8PL9#j^@d@AjNFnln;r%|FYsU&K6#GJ5>xjQhx7lAVfR zSW}Dvg2bg~ z&dT4>?{DMMYjRQ?-e<-ps-hB;L-FxZ@VZlDR%tX-=tp6`GW!(tZv5~E@yWivPu-#D z|28^^L|DV1r~IQZgz&=v>+aJR(i7^z)w9*ylwO0!yfpz!Nwr+QE%_qhnIQCh?V|+ zB(hJY50iMdRV360P0HeIQ^m99EVIqgGz_SFEnh4`l+RpHUQJ(r;Ynd&ka<{`a{BT7 zCLB;88^IiV_+#I&y&Io)s8?uXC-Jg{cI2t zB1A>21%r6c2@emh1dgn+ zLcweT_GxH-n89ZDSj1OcUtsIYtBld`tBHs~SBY>$-Y%rUT^1S}7 z#)O|NLY|5Bk!+<^r<}C48%YQ-wN;>vLV6Bpj)2+j9}jCWkf%za!{{^{wR>IJwJcj_ zOp8gN6EIFA@Z(zaeNz;-a>c(7dPq%{KdZ$-)$bxP%+)sRv{o4xO%UOZfz(t7m+93G zyEssjW!#fUcC6h78C|kJdtPQm;LOUvsf$wj=}KRrC|7MrjfA4XQ$U2BNVJD@pIDT9 zOu5sC9JQgejGEuizj4S*I%-aw%6H-1fE28+W)<-6JB)jLLfke?WcX5**44hTH}o7G zEP1!;7Nj3)3bUI;p)9iY4tLrpO5Jk0-gK74f`SyQcR(i)u%}X{-CYdZGQ*~avwwC& zLKrh(F&F=}zyB0_MzJD$l6(QROs8Bp0H6;oK!OaqIzaN)UC@tbDR_2fl_bttB^K6N zqVq#4PmZpdZu`4Cv|fn|8wUqW8Lg8Z&UU3~duL_KPo`Sxq3bS(y`)~c(S}8TwM%C_ zN59UbJsR&(c^16(@B0@ZL}r8TtSooF{+6~`$c8;58VlE*Pk_^e9_4i#k4mnXfGP;(%kavm#%K@z}9@y@zU;l;NFshpLj>d zY9$WW6h@Rs$(1zsB)Xe=Fv6N9b-Uxnml-p#2|$K*=i4m#&*EB>?<;jc_B)`iDbkNH zoN=?02}6i5@J1YdOw;z_{|XEX<}0WQ`xn5RSvr$eE|QAiNO-y*c&MM9gxA7qoirKKZn!g9IM*K{nuaTO{9bi7< z$*7MgI314YKVs$!as9^dLNQhyRm2E-lk(TL!KFk0#rmXkLO6LUX{2}UGs(6A7b8zf z+o{X|{35{~LJz0(4_6Wwl4H4kJ5(EHR;M0Xrk@Jf_4#x<%Hbb8)}0xDUkp>Ien&4q zuCP@uEe@4L;FQ4Cf4F^z^wW)M+UG|A;^MpYAxvbc?%1GdHj$^Mf!^qzM0v%{qvCE) zwFs((r_Qj~tWn=AK1IIDntpTUS*{5=Sk>HJ<`+%S z-c6*PBcY32v0L06zGHa>(&BoJ$%%JOJ{?|Yq9r&=z2$%kBqg8l8Zz6^BxK7c#*?A% zsUkuS9$Uk^d$wFTLy!(wDL1z1`1#w9bwX|x=i~ZRIq=EMi2B%JE}ug}2EA?!QCb*l1~~>t?*E14dE}@u&5i&ee5;7?I56ilz!2E) zsB|%s!j}k6_0D|;2}2)09yAC4cqZ>WS3_=J?vW31VD%}sI_y1zif5|n6fZ}qP+`vZ z<;K2{jdIw2;S{Q63FoR@@2ocafWD_Ka$7Q|J))K7y3s;WBVy?_@|Z?lPBHT;+c^9J z?d<(oo7QW}iJP!=K`05kWokIr2x3{>x(7zxR$mpT4Z~2(M|JZginLD)7>0Bx;uor| zX;y-g6j;;}UcDdmCr&hgsa`PaE&7-3WE;8=CPX+2Z`WeywNS=gkr%(2Giqj3zGu|! zmm5!XKP~)YLLve9u#CizeK``F2J4MrwO~?fv+y-z7Ek=g@i4ku)q3}Ds&ToGb1ddS zG^$_>l5fBJ1i089diKIm06SoO1BJqYK_(yl8}ykI&isT2yX&Ihs^VB=O!_SK(w#m> zEK0TN#*tpe7H60~$9~Zsqc`^WWU~f*;W9ogMH`o%^nO1ljy_5nubhNoT&a8$>40G* z`lQ#1PNHp&(<{X%lX(+bHt-;v@LC}9E92#9ai`v)`r4HvMH|CN5T%sDq~N2FhjR&|U8N(ZHz1bs2q1*;5|sqMOxO_B{~vv(vvyUYR%2hZ2Q>})HrfAetUzK8-hdkq@L#>U2g^ljBs z$OY`D!c=plJ^U!zT)qBo9Bg@7JIKi<>BC=je^AYQNN0C()*#iA%A^Xd`9A&kbh6t~ zJWes8iuJYx8gJ0N-BZ=KBVM02(igpbe9GfmqenVWo^V5d@qHbD$A%Ke(9^6+5^!W;Rl!{!l4^pGt&Rfj*Ca_AV&+J8{J=Gkcoyc6k=+`*gh0fhr@<3s6&#UmO8|o?h-LV5F1Y*pjADbSkk~J3ef-0_j3ndnh$R2oiX;jw zfbrk1gILtUDe2F>32>JSFle#xACqOCzv!%W?ZIht{0vz3aNIWVC?9+2yv6fcnBYF478{>IQ$s z_XGs457|W@&k5KJgHJmR8_iT(@0L*>>N};s=eMaPeiOEoDIPrPe(`S#S5637C2JFU z%=GkUo%S2%NnUqu5#aC{Jn9vZG;nk|d)NE?G!b(5SQ_D*vHINh;u}#>JoC;dH)kA` zm9GhXb@JZf-43}eJ00H-85u#b6$;jG9s0G0{I~E`#el}5L{6^1ljQvzY*eu{q`_q! zO)U_J6v9N40(HvT{~V3zChlb3SF1H>C_Q^x@B9&uXS_CPB;P+XRoNF?m7@h!6fog?h6`CrLqhH^W;%9dc-t9PEzL#lY_ zC+TTt`V^tS!N-7D%A4c9Dr9U~tjS9<;>es)Ye>#9()6}%`h)7Ll`u3NRk8I^K8t{u zDIzAxh^wFZ@FFeBf!IELC5qy{NO{KhfGDnRXl`ycs02-}8ND`FVKHTH71SpkJwgx` z25{)5xtbb1;%pm+7a_fNKV-XzlAyps4u&;b(ku(%H*5P8rMC2B8691m-I2SNLDiph zil%{gv$Eg35!g1TpE+Xx^l2dq@qnKtkIw=HR*v;en>YHit;OSIZwR9Vs)WFMENZGI zdp!wfzSs=zF2k2)*U>RBkw>JT9n$Y2jHos)8XFq&-@|DC0fZj#C-ab0R8~G|48e8u zy{TJv1de22o%_i28WKSIwbY$Y<)ij1Sf93wL>N-4V@rh9-%AzH+NWsw3K8-Teod|E z5fvD|{fpBd2EIk%_@8Msk%jQU+E9!Ri^BpgY&5Z5^# z)mmv7jy7ZiZPyCw)FAxSm&w@J`b5}p`U3-YAN~J}M?LX>d0;ID&@+$(iWLh;Nv+!b z1fiWq{ef9D_(Noi=F)Q7#O?2S2O2>bzhB4d!PWOab^y=+V^`3hJTF+%!CzVI66i_Q zUpW7^#2W3*$;R;FkBMQNMzk_C60s~GD91o5oU#?C%4$ZYxRKWXc~ei8s)bl#(8-55 ziS{oQx3^@5)t(*gy2J*j5wzEC?~AuY0u3;*3Yk;`+%j$)E@PVbsZ^Wor$Hq+ffNcM z&;(Rv8GJF^dl%HCY`PfbZbVyEQB?}Zot#-mWefec@^|FY!=Dsx-sR7IHRGw%6LB=!#SMG?VgCmm`6MV1i!wh{gtUQKOH=+K%k zv$~id{rl`}Ev87^%$9+V42I+yEd7Y=A@2>oNQuZ?gZUvt-3mwg$WH13JHPkvnrL8y zyTAWxM57=^@BUF1k%>uw+PszdiM!Yzh1Ts-yy7|u-!xUiAL_y{?z^Wg<-=`YxeH%SYQuOF)Rg`GC+ZNLV@Sh zR^Zm&nW6Xw6XPM!xt%QwecxMBu+S{}z%y>S$B>o^wmnX*X>(Jf^o{u022iB_5wr%$ zqAllJ13aP5hS<%q_BcBEGH9gi5V0fwL=Vqq2Oo)kZlXWVu6{NRpB9G**s=4l7z(?x zZ(aakbB7MJFXp~=Vfq|ts>PbkM*VgHsmNc5Z>z}9sC98pKrbw4)2XhH8?Z1G1XOnU zpYFxkgR3FSAgfcb5(9QWU;(guH+LslAZNS0yc{K0DCZnh;H~)H7*DFXeiEFrsh0mz z<&*KWRn|M5=}i!joX*%5$gA%}hr1AS$`hYOR=^qF68!f|2(~&2{Km=jWV(W#I4%B= zINw%&XpG;)4DU8aheFCZL?PTGckB%u8i{3Y=z!o66f;a&hj|m$GL;v(D*QJy=|0NY zjE*<;cB1C}xJUbczSV3H;w>-D=}ZDt96DBzQKE(1Ee=Fkx$a|SJxSOcSR4FLuIkvA zYpen2&^-EF?2>n_Wsxm9!>a#7(^-a9`Mh15?(Xhxq&uZc8bn$^q~S+*r*xM{3rLsr zrn^Kyx$Cb{Y;e4;pWyTsR+D<1{c`RyH6$(wU(gC?X(l*+CC zS4Kt`Jn90XTY`i#SB(!yjYy=U6=@JFs*k@;S0x88|Mucb82R<>O`@K-__T+*o_Es6 zeE2e+Quv0R&|rv`uYmh<5f?e+Nx&_-)>!(iJb_ay;Z5>|xH)`WH2&cY@34_r?r-bb zPzobw-Li09GIJ$W`tdfnKsi*}?0yH1 z>CN{wpJiMa$W?e63dmOB!blALNIQs7(YC~U9YiDO-xh4?{w3xgq@u#)I-<*v%FtOg zDk)sWZ|3ZUJFjkP4%Q&}3G;YOKxzLemS6UIlqB}@ob?WgqL+ZGUQW7peaLBWgYP%$ z2@yn4R1}1_3a62ZL0bCQO?d1V4*?G678>%s`t2v84Oe?wXdq>&=K^`wKlJAfkxm0xacA7om%WE^-&fCiZnxZycajd|f5>%Av9^d`WZv3%QZ z^vMh31FdFC^T)tyPmCO)imhFqoZ(^rkpjDme@Xn>WnzZ@I&yXXp4azj1ZlzNo*;DZ z{QPij+lX>fI+s8cFfl$JBmyG&7La@}Rw9W5EYi|hW;~9m9aV;8a0CQBnSg^#nt}f6 zND`z5v^+Q9;ePvPN%0^2#;%6$GYw+O(9Q(9(X(c^YS411|Nf}C)2S#u!2nMC=x+rW zTck;*?Zn|t~l{8P1zRf9*uB6NFFOx|_-BnCUQUcT@ZquLs{!BzFQ>V?d`xUZim~;%`jx zuwKg|n=1oJ>RFS4w;;ClPxuBk&QBW=lpsWp+M$?O9)tf$vijk<^Bkz)+)Cn~&tzWG zPgRIjF<=+BCk7oHFc|`9WSTe0C@)&+gb*do%C%t)#{E%8LNxBPp&6jmy+c>MAr+uU9Ka_yTO_9qZ48bZWt2 zic!q0`giR`Oome3%%=?5G^jXTMvpAx1iVXkRkaPS!AoN$UyrmLN`raeTDSv^Ftqr% zn*`8o-ed-@kLfaKCXv_&A-BtUG&&9ji6cB@+(aDu^s;3Ha4bWAdh7YkMnOyXxCoYG z&P}-SG}1yry`f`_tX4StoYVhXoRU?g%E=Qkc0DNtW!z~Vstqo6xRgbKU)vsc0hwib zZ7_5!V$H%Y1g(D?&9~*Jr}oBMcg7fIJC`Ou>ZDCXObWIpQ6-Sm3yO5~0PSK^V48AF!Tmrc$W^M76$1h{E;$0hI2W%Tmt=IByiL^w7f z5Xj6-(#C-X5=_6X#>K_;m_msk00S4up(fvgx#T|{;=g3g z$?>t@@3uV<PC0@=;~kS>*$FPcT1&KO3Q55bG7JtL%WMl z7KJ+yOVC#o?oTMxA4pk3@^#=y&#Vzo)WCdzMxC{pUuay41@B>Jpm;-2$PULfCBVRP ztb<8t{*r4<4BtD?>3M9MDp7VwiQ*4Qc)b$?cXtM|5p~0y=QppH!J@d}Obs;?7Z;a{ zj#IzW#(87b^wHP5_*bNLmCE18LjC&~2;h`9H07FtCFunqn^F?{r7L-yI5Uni-O5DE zyDy*WZxVDj^9iH&Kf-A#a4Gmil;L`*wzQcxgN^8N3)DsmA=Ci(l!nPmesG0`y&emG zcXP0fw+>#6^7G}usMbXD+#nrleG04cG^ZzneGA4ztfj-Rs?7*=lqJm3^^|l`26+Wo z3wb8FB(#kfBgm3ssB3t_Azmk2PVsiq&|*9T+m`63QELTcVG5V{=l9Mbi829@PhLG) z`s+Fd377kWCPMy=U0AIM%%M`QBxzIK?@bqTig?qR9L1{2KNUp~N~0SERm$GcJWI+V zbf)U8Qo9q2!vhCx0HwqQ4RxZK3jHklbJ&<<`qL95s3}2*x_=sFc=aGYUh=vxRam;V&j+-KEj?Yk5rR zKhOl6Y*(K2+4fP0t>u#j4N=H3A?dfUY-6*w`##{vV@2zw2o%?`ns<^Cy@qQWIiOBk zWJB8u-l6lsh@PV`-dppN3NnH?-TYwz8u-n?UZLQACtO*IY7LcVMStWd@qtTY?!w*a zV%jruK7(9N3dzMGugCCRCrx|a0xM&(BIsSc_V)LC|33q~ZoT4+ImbfKz0pxezgq5U zhyhwVq#HMW+!>MH;%O5J!t=Q2gqMD)cvdj>h6jsmR&9Old1Xz?1;$44V*P%R`=XFr zB!MNcl(f${qp7yb>3H)a2mylWk1&Aax(S1;f`!Evpw0JC zu6ga{PP)Oer;h@>-&xrZo@n;!?Q2s8o?C&YF@dbb<6|b{tl94bL9QXU&{WE%U7wbE zqMA!=f;;Kxh0Vx^tlr7b+1xuh2v%cUC2hHBrYaPJnK7 zw7D5$yBhNxBld^l0p16WB|V;bEj_G^+KEBVCquyWEZnCOL@97LCekS>>-o-1izW0r zxuJDtEyBib$R+O0y7=2cco7gy^_6yD3PT~BHHi}Z)ja645$zB;7%$f)8-?#k!~u0f z3$D;3mmod@TDRW6_c^R;{ue7G>lMuJ<=tA`(ATNZarz56Fj1htPN>l+??)HT<(I8N zj2h4L{E((kRuCOoOY@qpO1YSla=$0tcCAy0KJ^uv;GJcQI$bo>9%sKVH|D2By)?MM zge5lV)L^pO1UkyP{Ww~Uz<}Y{(Pguu`*Q?bX<_!7kqdkoeZY)xkzP{`8`qgwWfdS{ zVe&#XZE<>Yv?%t1g7WJSF_zkcQ(Jzdlm~A|Rp1;-TIS_#Tn5*cikdu2%koBwW)0m9 z#b#+9r_nwYEw{ZUM%E{6t&x7t0b@HhxB%`$ol+r+JpNc?Hg+8!xgrH%cA1J9InV~E zBjSGMa_|q=eOvZ*_e|KDV?A<)&A}k7)hwr?hbqNWDRcY7imvH4?7uOA#Ypxa3y+Du zUwmHXB-9Y?F3o8+ijP3=g$u#}MUQ~Z*bC8%(ie^q<^AdDcU}M3cXt+r(*Vw9&P~OU zd^~|eNoMFmR~myHzX1SRWk>ff%;}>bbqdAcZ#B-E^-1 zOpEs@rYSrbMNFPAkpsppHVkT8(3$y=IMj_2a*k5z3X~99=mvFpFq|&OlqA0FVrYWY z0-6t5--F!bFC=F68}rXfRZv#cHTG-z)isnoCJ6ETbU}B0t*t^sW%ge|IYNXy(U|-b zt7I)`RRAE{)71{(76V-lVxDK~^-D5f)Cja*kz9=Rrp*zpNVVM@EOA0Jswhq*F<~mW z3MWYp==}}LU)2ZJUuZxBymo3xI?xOkaEds3i54}5#1~SaiE_=0!8>5UdEi=FVFe%; zf$0`Ru~>kcEa=(@l_~~V7raWGR;;g0_HVZt(OT=e36_IBY1?X5LO198@WOCPW*G*9 z>F*C3hCRa49V+5m{gFx-+L%wx5YF%DIpvu~g@P}Cte2)sBVb_X!?g9(DBWza^<0Qf zPP~5GVMk%-kZpTvDWnp5i_u+*_n51AqRzpGGGs#S$l7XWMLcxJ+a26bE$c61m8P%i zHIfnQCu)PvJoPbw6e5kanNhQ%SQW+ahyq8{HQ297i)L(WY#EyByn*flB+fE3pS()X z2*1d$ZD=o!s=26-SVCS*3%4N1IysFBGyP#kj5maPP5kNFqeL1Uy+1X}**G{r7&B*p zCyuIkt{MG9%`O)F8SYms^f95$n48co+9YK$tC0}9!*7dMjV3)tjDzC17^Y<_YRu0& zCNDccgRRmHsYhF4Ie&^jn7ko@(rM`d#GU#@xYlaJDt^F>Hpv6%I^7B+7@m4-Hu4rP z5D%Z2z*yb~{RQg&7sxe7GL7ltU%J)(kP%L3-IJq7zCkJTtyd znOpuf0;}UIK=Ng4#jv-UieEB#X5=qj;8(o-jbA3ZM^h8Q%^%jb_r`=Xc(>z{Lz9^0 z`*|{IsLb$~Jzhoat^NOyQVVzzpk@K0BjZPyYUv+ogv_NX3rG>7-TEWlghX7Kn36+d zO-8sq^oUtaHOsF+`HW_HLwozO9Y6Hnpk2pju!PZTB^kD-!bfQ)IYNkxl`;uU;4yhpRYmPg%#sRc5$IXMygAz0CAqt$W%3x%P{u%Hoq>2JA|oBBM&dh4oClAB0iCP2i%M zfrK>W3{ub9TzO_Wc6&_OUHw#1k7lm##IKO?;nLzb$YSe~LMS^NNgK zxsBcm?=4Q{3>`ct7TYdQ5XqJPrX^^D;r={je zk*_Q)=)Zpt#Mg*hu1G^c%)1YEn*h5G@O0JH08t_75P&=b4;wfUctUw01EAo0pI2y@jF1k>o5#veaK>Se%ePH7@}_-m(+v z;f1~$f}NTC@P8?>?nMq}l9Cjx0jR@QAiAV$=PE@{Rhh#3B*oQ{rNZ#+Pe~nH(q?X4 zMIO>||G$zI@OyzlCl#!Lvmg)8?CHNi4A@5YGOL`U%dT=RFwQJKM3~OCui^`u`9$hb z?84wg-)5}4_F~8 z;tbX#NvU|VJduor@F#{3NdN}UTS6A-OX@jnRplQalX6!FjqW_(NZCKxQ>8$!={z7t zz&peidy9RUo_@<`SCv(DmZvtU39~C%TOWL;#q$5X03ac75QV0y*)5Y6k!xvuf-~HG z|H}aLQv*^!P|Kgo#}Y25l1WYbkef+PFS7@h=zu)BL7KN<*=TN5Xl zC-Gcej~bQ@CCF0^M&F8?7@_QunLT+P9h$s8=mEI~FyaLS0JjB9-6Q7%9Y12R6ph!Q z;4JY;G}Znms5dwo3|xnzL}&>XL)D1xV6=1OF&)R{5GLL?L!F5^)RD77l*EX&nfI!N z^ZfTO3(UIg_GTf1*CMnYM>hoy1-A;SVpAT?oI&X7#AZ~0fhMlDPq7)nF`;>z&kA4D&5q2xvPW2mo*=ql5 z4U%?+j%R+HTwz#P7>H`dF!%lN04&tChcv^AIgo2WJm|>PLD)RDvVd4I?OnB^Fkg_X ztDQ5>PtV#zCfV1q&XXK0inyxYx0A~_%YAv>bnH*?NmWBceV|Y80(roYg1$gbA)aWM zjj(vH+7FnOwsLjSXzwlr#4vV-*Uf$CEWVdEM5||N^yg4lo1lp99|UDM9a^%UJ8j3K z+jx0_)jJ9x2matnQTc@62EXalvT;Ec`Ht&^iq2Zn=$=@+PHS9c2{6Eq-BEEe$H)lk z36AhY2NDu%p5hD&4cYtt$QaAO&An-D;93lun^-O9LhpW5XTaszhcmLNPNaIb%6V2C z-dpfNDYgN~A-j2~A{Gyd}a+uWwVESd50BWZn|Q`dPxgfW7N*abYbIG1bzdyB=$O zv>ejYjYof1K4%+=WAU~&p1DCAUfmh*M|tGWw}^Z9-FXR|JZW6>oI7GeG7N@lKTWy= z8!w07R?QLn`?B~nx%q7vZ~B$^p?S3km(KFv7`GCC3HMCJMyV)$|5&jVK_t$~SZbeQ zuer+Z_JD`eMp*W+kdBvWyCeCt<}#EbNN=0-1~bpk6;si&jjGN20PbyQOi?AnYZH3G{1quiamx{*1`>XhqHp*Oca#eV?*4ZWXV}~yPI76EL z<$5EP0i6|=*2-Sf)~?|X$<`XUrdS!8_C%$l*vR;W+3oTQ0_wdRSSD4o2UK3;C4CF$ z=Ybx==`(<?eH*+TA<>y=V9k<-erz8SZWICJY_J~2xoXkXD+R=(^O!e zv0E6;Jk3Cl$UGxb%3sCSU$f!G>Kdxlq;@7WMJxMnMDHfYOMlzIGyHz%k&i8hc?gN!^7kMT$#WJE%*quz(=1NAb95r|A&H}L3z$l z>ewhq`yqLoEgFBuoo#1Bga)NZ#S=_6%ldKUs8SM}!{Hf{tnBNh$MY zk&&d!?G{<5ppbZqpY3qyhR0*My5HYq&`JvM&Q5~Mz`cLoPq??c%T^|JN4fFlY;lA? z`7)S#ZFk8%Iu|z{K>Yw*A|-Ysw#l$cnt1$-BjAw?dHg@5ErX+B+@Clx9SE;TTE<5k zLNG%aOle-`lb=$*ixn^$Z|DPLD)6F)%b+8`!g2DG#DQs)jJBseB{_Kk(ZZiU5Pt_n zJ|b_R^ow1N@gT)L-!yjtj}$0e3#~w*Tm@AOehE$Nl)}gxKx)T{$*44wjyKwmB~%Y{ z(GU;S91wyiZ_C2=XP2`%bj5@rCK1nqMjBvOXQtD)j8rf+=UH+j{zX48+obLP3YkRl z(r+q}*=KxqbZf)<3s%KB+SCZQtGB0uLk=_`9dXxu?b9_|UM(Y-Co zAD?)Na8MVuM~^qOT{Z;&y8TQ7(LYZ?9zoXoV57Rp%Hu^{4kcIkZsPZCA&TLKC{nd0 zQ8xJi7ol&}2Kbwp+fgQkAhhSlUgsQjc$`b5wo#N&oaG>k5?fCL9d(R$kdW6%QP11@;-^#gDLS$ih%io@D}e+jy|n?J<8yR)!TFt8mEeP8L?O5mPYJcQHCHr+25j&!JypTc>KIIofP?4cAt+(PKq1SdhR>TNY3%5hx_7 zWNuh?m3AA3=Cbe+`uhZF;vP~2RKn{?=(znOnl?MAeB0k2@|6=6h=@Ad6-woi+c@lo zx97MKk6`v31(q$Z-P%D4P_iAg&nZM{^T_(;Iq{izA3szSxR6toJ^~QKAt*bu0trxd zRDU2m0N5>A`rwvx*V-CLu?Y%xpLU(cIRaKQA4wcn#zjwnX;e)0*F`&$0I46OxM^ae z40ffcM&_vNq!I+F#`6N*V*%;#nOcUP&dGsVu^OI=<$7v&DK}h%3lXLx?(7!GlZ)xL zTC)1^B7wlYTd`Q9iN1Gr^v79N0xe(&HEc~ykbKx)9&=`Cx1H+5XUm6lnG0L9>8iN+ ze-LtTLWD*I-O>NbW6*=&(qN+0?pzq!{XSfL-1t5TMILW?{tUk852IG|+Y2YbCs6sY zv6#iRA_EmU#$wsLm!AAaMK0bLLSGq>f8%cAEuT?Fg_Rv|zLgI=48eF7JmKGZd+OX^XDM| zrW;~Mkf^e%hu=*-+_l@_DbRlDRFzEGPp{cLr?4Ewa7@Sv!XU)@ww?&6?L zN+{EJI?ZT=GruH(6y);a+p|-jd9zjf()L`+A(3M_q{=}%rE9s;&AA$UxZ-28DH$xA z=bVlxd93s@j%rc6yfc~PxW1!H?LoPmemBIEzah{JTC~IiN{PCOA2USR&yXyb_SJ|# z8jX1Jj6%+wULOy=$Q+a|e3m2w!!vLaFiljD44Rlx_;yi=bXJpV+NGid6*fOBrL$h;z^AO-1sGnJSV~c4Boe-9r7Nt0@Gn*iLRuyP}UxLTO z&m^M89b@4zDJLh?rx{|cFUUO#Co`gYPOh`#h4Jm6ZV zYn7@MgeAmp`6#@{>GayN*Mdw#l#HL+w*@GM^78VGO-x>w_r$FY^_Hs!&IPh01}@UJ ztUTy-Nd&b(b|zQN8VqG8Cjn;o2w8A>+6br*tKYwXVGlA4S+Ln=XG6mkpi*|-ZN@Mc zgM>r-{ciTDLmbe1FFT=;x!ZS8OR`_6Myau>BXKdDi^m8MKI@N!_t7tMxD2|T<7wH7 zDxO{=vr}uNw&BVcrtK+*3x>7)1}?JskRfHH***!0j+3?oKR% z)R1lzMR27hhKE^PNws?f*C@Gfu%Eav4==|udGa5ZL6?wP|`)lq*${=O zaSN9_ZU4m6$WDfflDGab{F{HjL48-(njOD#F^*@a{*5U&Da>c%jZTlt5=C8$Lc75C zs4xORy8&>wFjT_-G5(BOjX=T(IHkbsV#Q%{d>pW*JDx5^DVd>Az2f+dR4w~Q_LD-< z@2P~$(C!T*M9#Rzn6$A+Fh<{SGaw51oD3Lahli)6{G0YiVrlVQ0((a?N3kY^GEDz z4~L^x?un0vJ}Nx(myhvjh5Xy@yghfBu8d0l0Y4uF7`Dt!MnWt4>rwsSq+D9z@@}b3 zD0hXx#rpM>t7`od{ki2v-&`+!ffZeIm(Tb+oBSMQlhhza(wLVyLerk+ z5=(>OE7vk3$4SSz~!)H z57VHm@h7O*X>7b!YkqUYW#e41$Qz%><;0$=!u)YtuS`=Yw?zJ?I9v4=l@$${j~Ul^ z+avaIf<4;6Q>d#n#p8x4LpNOOcxpzLjIOt8A)XZyP}gXyp35thKdpX8?4=*?Wy-ysg&%7P*{C(C&CBe!4-53ptLRUb2yh9TKx?=2Ej^GDuHR9l z^9EeD2Z`6cSE%gp35?;b*K3p4>*v#ee8RoWO&Uvd_#GPs%rR%|zRycOgr0(PBUap@ z*CJ68aA6nmxMY1gTy5!TX)YPkd|R_r7O@`$Z~U{h%BTISDgC*X*>gy2Qf1I^?TZtJ zB8_pGH_~&4XU}j5==uQ56>119`aMuaCfp#A&hep62WIINbbq$BWw(ig)mf#B>M9hj z_w+UaDv``$t#ocgm8MwpiyTLry#n3^bOUn|x;H{e%b&+l<4RZLjf`!aK9@)4(^%2> zXVY6zFoB{z^zASH7+Z@&W^*_U%a4qSb{91PmojLR1zU$$yQ5BcVX@!0hmZw4yx0rM zFGB#710;TX6$l@&UNTDYEfQViJvS{~aI`=D*S88Wu~#osd)HD_q#K5vsarw)K01oW ztbidVnR57>6;Ii2RGFU6&_hq}7z%abm&r$4Ktbwkcb`__qpg_#Evn}1z$O-<{OtGs>I>ez7j&s05W?Eq7LA49D6TiW_#^VbWucXEcNsrT8i0 z&9VYZ>lkLm(;ElN=rtL_#@pa_WrJ@!82Uezwq|XB{L3$#w#5QGRNx4RB>z2oVBZFH zb<;V?jW+)~M7Fb}xzJJL0!4L_f(&EqIPB$U^5y7Pxt6@Ve6i-iqIJHX2UMCWH}QXU zlM@TvGKS`aH1KFI!wKVf1_321cRv@y?u3LUF{RBbQ?ULmC18K)dO7S`ZS%mq-vkh? z(a}+T*lu1eOWJNdC}r~b!5f*4ey2xk=?~n-$fdWp^!@9%1g(KSvudnb=|gPe-YiQ2 zU-S4yvQty>DRwX-dO@wJ!ae9v`^wtVYVn_08&DL%VHMy&+q|#8S5KWhYO$n(+#GQ4 zDvGz2xD2)E`xUC!i=eU+81ba7h4X&P$D_G4xm@b8ZwN7(N=Vbucrs&%$xqsW>@r zt?At;216|Ri(I7xHV=CI^Dt9lp^J>{Og^Xi5+O{M%a0&A`*?15p|v;shL`hPxmWV( z;N*hR=mK zEv6kGD`r}s^{Sn{Y4_>xzd@kk3@>{R&_e1LRV+DxN!GFHq5ax`yuYbRvW3XF`!buA z;01JD0=f>+L7x8Vb$M?_F>-(=SkMCC-_`Z=XY}wO=;=6KYJP|P{2NN&v}oyobstj? z=jfI2OVgd^pA}Y<8qA+K?uz?9AG*H`D{|2V!8abbPKtqGQ-@k945^GvE)- zRp?FTiHVS5fWzWRc1QpnQd~~<77yfkO{rL?+Yc+ewalW=BY~YU`hcj@wwdvqD<7@U zB{`ogUjYGz+2XZ_V{6qQF!Pexh3OK%+b>t+{y4LO#z=u(IYzG}wDrtejnQu$0w-ev z9jdh~O95>}zdd#lQ|~V`yScoD+G0WDTaynC#q6iFn1(?n$Z;we@ysN=r;C=Dm&dGw zH{2Ez%I441_Su#gdVDj34Krm+kj|(hkX9`H>1;oPK(mHJ&fB~p-9kz^xN!i zl)EkvG60Pll<|WLj_4W#KJ`en?UYM(3&vP$RI$nEI-z!0k`z=0<>kz>bv2w6KjvOu zUO>~%=jslil2Vy^om~S;7+N9s5lbCH9|yzUf4vha)X~ zs+(};`DRdH4ilTuZ3doK6rB>A87oI8#Qo?ENxvckyv%1ci6Q!WN><`ZRG``Qt|&GZu~3 z%u?bY*ku@qZ`!-?`cb_26p6Z6qkZmwFUZc^wW0||hrOfeX|b-LSMu(E1>z#up@5~* zlSf1T0{LSprg~tdR?UZb!BZkpB0Q>J9|S+W!2kjN`qoyjzrV^s^$Dn6zXrc%jlaZy zfALDFz)%3VPf|e#Kp9P!2d3#pb}w=dc94pc<@V}BaY6#8o06_Hw^FW}T-pOUHJniq zB^J7C1`*4k1m^3z1a=M%kc<=+^?f=Y1WmA7N+CV#z$t~wIS+Jc2I(8pQS#eilc=XN zPkp+Ha(AfhPznCQ-p7=IC?V{E?jFZ1AyZbw|Atc-Dr@gzQ(g)Dl}7aM>GteC+IS2# z-k@@lsVE{P27Krp0#2)&o2Cx36l{WAWY48dW^RW!@;Gd;c9L3JT9KDET#sB(Ohwia zF$TWDGMfU;Ez}(orOd928^?cL#c4sxAC!y&nVQlocm3*$7saNj(R`=!D|?;zGj1pK>kC`UB_$?XQ$tIR`Q7VOqq4Kw_KHCCL7B5Ot5p>5*tTiKJVU@VkJ&< z^69+G1e}k zG7YUIUZ?y^{nvpen6YT)Uk9}g@9*yos}T5!wc@DsVewfLzr0~A!=yEEDNAsC3YFD$ zD)ZZ6H38gcaGQI|?z$)K<04*xbv0eneBcxq{8`5X&z6eS02wx~nBZXU`i6|W^GW7- z3D&<=UE-P7LDH8~$kti`y?(I%Gb0Hpa)3gL$fs8A5>;HovOqy;8jpV$scKndsF_21ov5?F_joSKCi$C5 z1swj>ZhCBbippI>CNiw#EGF#?qHo5A-uEFRU7Wz7b#t`X6i*erII6VN9i=C4P#Lx6-i|4b%{eC$htK*P-=~_>Hd> z5($llcej}%ncjEMZ12_wQE}>J#%!+_X-E&X+Pze5-kMjRm`E=$S(RHQ(Jv9Z=mtvf zH=V*Sx!g9Vag8jUMuO{4SjZ&9Ay11ecw^{9)W_uQ#NyBw z6O1U{ZljSw8q6gaQYZ|B`C2KxCe7N%F1spyQ-$L6TVO;VewB*D*Zn;@s%+IajQeB9 zpXqPI_I=pWyiZ>w-QJJJ)xz7G#Njr4)pTI&JyRzrNuN8tou8ivx(bNI1B+PnR2Aq7 zMEhA%TKW$MdN^M#A&U0-re{=(s(ioUm>+egrBin_@r~sH*QcT01R&6BYD(-8W>;;8 z?zhvr+VVLDEdLCV0Nq<%4Gp0ZU7)%Q3^M@X-Rv?SBw$iB8x21g8}rku1RyyR;r7BA z{oRoya~@6Ogt?97wYRo$ghHrwLf&N7Ye6 znc_NQT^@gS0-iCz#s`hPAZ!-HO>I# zcS7c3{NgK)tY+E&?To2cbB@9;mU_`1g$TD`BUk&TX*+|wS0sc@ls^_X3wEi^X@>ac z^8LM6PFBV)? zd$b(P-k%1lDygr6=uS6BL9HrCK6_GIs_k%;w8|k(1fODS@Zq_e_xJCl!7+HcF6Xc| ztw1)m2Sj8FEN`p6awETQ zNE_Sz9_I@-?rNIYw2ImjSea@J$-ra+&h_;Wlw7wrB18gpAHD%HtXt}H?EgN9mn;`3^U&%Qz6 z-Ft+@xGz|!pYt;Ax=QFkUl<5*0v5}k<>gSuByv}PO3P}WEma3K&Ej-u6+?aG>0b@2 zHepd!Ijj*m&Vt@zM3qMeVzkZ@c5yF#&?-e$V{U+%|DFz zutdlU#F9Q-bx=^(yNgUFX8Eq_#}8c=d|9jY+YSCWk1xNh7rrXJe?J9ON^MgdW`@~T zJ}j4j_PsK(b-F2)G8O7G@3RrV;^v8wL53(IU&VZGj(}+6u<|ptEzs;T@U_$PeA8Ou zaS@Dw!SU*vbnOn|=ElG4^u1d)o;fmf-4(XsdIph2;9s*pDf5lRNvl#S>sBZaM zr^@&o-Y0k8Y0MNXPso)mTJ*6|Ye75Qi@Z*u{R8t>1|$RZKzd_jSnQ4HinOS<#)nl3 zbnf$A4S$*5CMr!?@n4pE0&6O(Zx=l$B;`W1oS&;2&bS+?m3!sGJi{%BKJ2{HE58|c zhm|m^;hR+Ib)WldznagOJPeSsdb+xH{=??#R7YU$1M-!NcINXSJl$bDDHpQf2)y8+ zKPxNC(7?dVJ8rRob{31T^ju#mVz3!X`q_q8IuqJ#9GrbDVgyC94`^nJRvaYUpg!B$ zqSTH!6|SFraA2P%8z!)F!93vgTsadP&U^0_>b7I_zd?UY=3Z9h=TL` z7_hSfJ=~`7Ul(6i^AAUb_U81tbR3H9f;G39w@g=eSZJg2lNTR1c4y@~!Z+Q6x?K{P z?0lI{M@l<9am^|9sB6+?X~PCxGdO9PKN#y!4}K502EBtIOxR?|Ub76&=hY@%0E=+y z6EAlCOACzM<_}ley>Lx$uCA`iwMtEyU5@`W;(1XR)Z0hMR_VS6?ZWKJtF|0yYJt)w z&_lxMoqq;pWWv^rekAmT^9P$sl`ap5Es@?{x&UtZ(=`3AY5_XnIWyE*e9C5Q z-m}F^v>Q!XosZe)Ju6>yT4B|YWwiO2|J>{Wx4zhErsB@W^;$DNa^#P*_`rpz1gZDB zpvI3?u<4C`TN2`oXw$n93^(JnN%);kI*YNyl8dUlVLUy9St%;1H{J1UYFlKljrz6c zY8#6TtpM?*_LlZ3%jl6YL@NM=P@$;fi@I>yrh2Z?kGBr9mxvv&R;48+pvIe1?D=XI z+*A-H?t13CUaq%~@UWF_S8p=PQDDOAh{6dEEX~>GuTCFJ1bBEZmt80Q4wOwu;s*gb zdF}bc11xf#rIWL?jQ{9WT+2%!W;#JGnbQP9?U3b$;A+kWx$E4jS1U1xL%#23tGX`S zQ*{G$ow=uccoEBx9d8~-zIArPmKRHg`J*E?Oa&-`fb$p=xM3uB;{AXlR(`0M>#n;F zzMF-CX$J#1XyGzYbJB;)J`2FSy8)6dptb2=6XicEQK`gpxk>a+bHI9SSiOE^F?E>9 zNCp-wV&);}dPX1cb31KPK5~Qa`3K+z%y{Td|JdBA*^ns*5ePhhJ$IZDR z7Pentr)9pq9g^Xq*fP9G^?)lnhH1&2S==qxzs!4&lVIh)SjRIcq66OEYJM^d?n|FnXf|IQ+~d9Vg|k~}lcel? zPD%+)2huj-R>fe-&k;CW{;)Las`oWb8d2TbV(oDCjeeB-w~b`p^yY}H>O0lGtdKD2 zp-3~Fh+nqfBC)xq)gM0^<3)F8YB6XL21wn7qluM56cg3;QWcdWg}sE#%JR;tld>n( z)zyLj3vBkFE0aHa9H5%cs4+1xet^=7%UxB`U2s9Sp2#7Nlk2+c=j^k4yt^Z^)mmSS z`~+oRx^}wO>6cB<@Ba>j=lKJH{}tS9>tz>U=n~`YsYx&XoZSe&k-Xf^Es(Yrr2s6< zdcpncME;?|~ zeh%&L$PZVtvTM;_?|rVWQ7LHv`yMf~?!ll|LU;$y)NM{f;$3-655eJQ(al$?Z8q^m zF@vRMf>jPB64UJLGEO2fU)JyerB2oM3AK}A9gpsiBAo>Ni_ z^P6+ZRe~_-vuKwNZMB!nH}*dfcmkhpMI6%PDZGjn?Z8L?SXM7BrwXqWAI=GmO?I zc&=|}#!5S{Td2Xgy{KXHop_3ZIU<2&U$q;*cRZ952xV?G5s44EG1W8Ur zWDLfQS{R)YaF@KO=-(m|5@-l^PepE}i9h=wnc-uK`U1wPAaM?|rc|7?Oa$<~PJ$rx z3kuyuyME8l&nmv=fRn@F^|}?3vQLG}cr->f&tKQfPSS7-xd`|9_3?ioIE?9k&F=oC zvj+P5P?89%1V`8o%Pr?G^NiM$dF)g#NJTUzIFvy*sitD*>v}_iI9F7{mfQ~;dwce| zAA1KDaX$}CCDpVLu?sRjVNtOe71^dY4OY9n>%gb0j9B)R;5Yjl^wkjl%IY9dr5-mA z&bT!B;^k!XxIg|@wv3fz?+e`J7j4DrokKbzb1%I`&BlG4 z9$l(4W`W_D5mo3e7aQ zz^|Fgf${#rRV7P1+y<^D;1%g&Hyo6z=B<4GOhZMIynDpG|9ZZ+YsN{8p}F#Br;e5F zC8}WFktz8~MvdcS{DNxltM>Z$6H107(mbB9OWzZ2>4+~zB(XV7LMVUzJ_kAllP6K3 zST()W`Cb6y7KE_#Uor=fW2^m+L7g2sCIWT8{QE#u%x-~1+M`ESOtwI(V-a&ta&tJm z9-#<-N45_u^z+A4MJhtf8<2Vy2J??&PCvNc6(%)4Q)nCrUE zb6bB|S$&3#Ae`c1M@K>4zcDI4+K<@ty%=T$?YjT#5wF93$8L#RPiBPp>nWjj{lP*! z0)wX*AU@8<{?`?3j@t_hLg43gRAL}az6_Qo&^=rI9{JNHf#Q0`Q#*#zBPJB5M}kWM z6;t}XJ2&8=G$6XH7^K8OSvi=kpZednf$lkDW8)^3s1)ZlLMO)d^_#rol}*_jIGNMM zEVYu1`<2NElL(rSvw-KRT=aQdA-&LAXVJ0*-7cv9t$sicaR*nk+grehsWUnrOWmT% z`MRgjl4ppGkW|8SB4_^SvQlv>KySnOHjNYB8l4bFs3~Qh=X^p}1In{0bn4-5Iem`x zCgz15zuVV1>Ep+OBR!W_^V{CUh|pwk)W2gT&YRfDT(omGf(`I+kw(rJXcbLZhFCDf zMHmok)JIRqzZ?B_Q982~FCh+e;kr72A?G1N1K-LS#dH~-fMx%F>H>C8$?@@arPUR& z3+O_8_|$H}q9b8HASnbbhxVHs9_R>|ckW;72lS95Dtk<)PH(}<(jQ2Npp-L%8MuVO zo#wW~Jk#*~dsMM-Exh8sxhTR)XVtO)!r5s{VE&-g7gziN z50(zoV61D5xI*}h`PAW#KZF9sBFbe~3rC9uGhsNYhsH(oB6}kcnbHR0S4pK&5KK#V z<^2QNghO{dLc~*HR4EZR`Dmgbw7^s0WDR+B1KfX|XFsDMz>3H_>#YGep2*t$gykCp z0|T$W<)ylMdWYA-zxUpQ`wpl^07!m7n+6v+zCi`Z5jP?`zUbJ?U0ViVFBFEZju~>4FJIjfKFJQeWVPf|0OqIj7(A_UG~(dCv^nl*5kM zC9CZw`-gLq!j9JT8(X`*niE78h1?yXAJAbXT~ow=%v` z8rd4z4Ai7awkcc6(Qo?a1Kh9kJU64jJBSiA5IRLbcgbP>s0py@c_)03N}H>$0EK)w zG-WVmgeckX2z8~F@k6t zUrOL?nt-bR{S59SaW>IS!HZLn*%fO^+}3mUDZYd4?0t#C%VbOHS7m?Rp*Hz1vYd5P zr|(G|zQeTn1mH3^w4;ryyQ6M*7t~9&IBwe*Y1-E{BvfN!-pC|E*N1CamIomW)VzD7 z`S<0)^#*X9)0OC#e$Fnn4&N2)2Le=3WgHL(=UT6o@AQU{(H~@=G3(7*f?vS=@Xz8R zbYKhyx@uOsU1@TU@n(_LnTGHI2hN1axjNWoz$+L8baV6aIzbOB@MoCO(BghE+Q|CW z0wrN#1r?0AR2QM}&f3u!23i_DVlQ&Igz-5A>0V6D@GBd337sCinKNtUKw%;6!ak@j z1Ia3Flcsi=<88mpdb7vw(Y%d`nulv6qRD8af;ha^z{d|0t^p`_AB8Z;=h5Ir+iF;b zt{u#l!0opB?$20$%}a=~Iy;O`=Y%HokLv0!fad};Y|57n%2m+N7ejo_ZuSMgU+zai zy$;hGq{+UN;o!Z=&ouIn?w*4fs*a-TKAxU;+sW!MoB5fU;L!r94=^_Se>8nnSe0GZ zE+E|Jcv`BY@ba#o1?(S}o6r>xZyHhDaI;BCn_I$tp+UxSb6AxVLdFB}NPUG&a zM9cS{&dyNxq=Y))h6-*VAV$f?25Dyg=}Fj9Nd;wVtEhjs(H$p;=&xx>mNAtz*;mbh z^4Sv)AfD~{1VE<$Dm+13DL@^Z`C)%ulbh6^RcZ-*{+sfx;J5b3wimNjoQOqfs&#th z1YR&+cFs9i2)C8HXfK-&)s~V@ymk@G#@+n%fs?= z4~r2J>}fzSP5#{gor>i+9W~SF}r0;41)#mW0v-!GZg2TkxtpbzgxyeeZ^l z(!$CAk%S*dbA184KIR5u7x%r9RQI+m@k=@0LMh$ikeGe04do3?JP%L;328 ze2{~XFffhMMH^)2wmi^eu>x6Rt+ap>$oX?L)49D0J%f`J?AjvQp5d05+px2-GWO0^puqQ%!FKEF>3QvCS|xms@$u?W z6V9~6MDs$#gp~$&F0)ZBuyZ3oqpAZiv49nDAka}4!DLUymX@Wn)*Eht7sFTBs$4o% zls!>1tOG*>A6K2RC1j$nK)al%Utfx(v&8$)fnxI?dqY&MC5%&)H!1LpG`tZ8}S=JTO@ zNQdSs{lV14oF9d9$~;#xO^>IY6l3gAG==eohP|1N-8S~I}9(^H%e0aaJ`b(Isi!x`%U1?8DH$>y)Iu_*g7od^<# z{t1rkl8h_SV5u#S0ebB9eM_=_FA|0YheJYzv}m-ga{ItR&EDBO`P>91sxk6>zD>^# zfl|$pBlH$*UOjnLpU8;)*ugNK@TNg~{)=(8R?aOCW=GmSUo$>3lT#VZ&2Q@h|Dw80 z1E1P1Fp(tVs_|&+?`dB_r8KB{>+xMWx`q#icKl=8WP8H5HVxh%V|I|>BV~=7Aq4o= zn$DZwpqfcNp*hN_8vuZiAc_1tAnzpjN7!c7?z{<8*k0mwV*;}l@!s567Q^Q8(3$_g z#(A7a{|bK<625FjgV&${VYb@@cIGww*5(_$NQH?I+ zxa1|Oij|2@-t4k~#ck-79Bc}K2ZZ-zi{k_$&+9S6VSsToMr=n7f%{ZJp$-t;@Y z^1ZWxt4fHbEq3zcg@<5Kr24u-zk&9n zzLH4_Sr4mHqAJY@EdF0GL zkR38hQHVsroROCY!ZpAG_yrK2AbUH5j3RUUPdY~}*6#IWN?EPn*5o3W(YX!HA`wB> z{)bh^{&`e#bIu;zUiZ0cDvO-GU2CKYK2@~{j^^7T{Gqg*2tQmc_7K!~ zTjCU=gq$4ldbo5sh4R_;orJ4nt>$Ws*cRCNH1PzeECHPv?S9S#ZqefzJf4uUol3M! z1DMY%*}D4rpvVka?4Q!N;J;NXCqV26vljqQ%mP$!z2HkY$Hf1()C~AvrkalWrY6mV zf#JTM|Bf!f&wqiB=f7CalPGJX6DmNq0`vnGGe*1kQ98F>oQ!GI^0nDjFn6lSZgFkB zYM<{qxRLG7>)hqwV+!_HhLkx_I8{~TCOMK4xwq48dj9*=qTj(&0<*Agp#;%w#kHui zyfzin*3Bo0j|sW08n0(+jEYKG)|dGa;|N-J&lsn91~Iwcfch~L?RRHQ)o~zYf)$Df z5)*1SGZ{Z2vYFF*Um{ZCkI_!>hlIw?!-oGNjI$DB1K{0GzPur-T6{H zGR*i5nt6dNbZ9gPKQus9>DRI1atF#csgHP4lwlOX6sm(a9!2$+Q={2d^o`ufy}P>> z>|M⁡@z%VCsQX*tt1uOs0u@`&H`+U1Q~1NWTyV)0bigK%IhgqeUbCcZop$~H)J^qMl}#|!?qYQ6GB%~av1Wa4l~~h#3?}FPMI9G>)e%E z6Mp8h>lS=H&IFW$k&!=`!$1C<@^#-U9vpyb50#@Lo`6ztJ7 z2kG(o;Jvl1CtMI+e2Ls4sUd9K2iC3^fyN84h5297`Co!l01Za4(mZZJmgtRC<_aj+ z`HwaLF?%Qb;28z}j)rBh1K2d_SxY=VcQrwcyoYMIHY0l^d{8+aT9WU)h9$oHePsH@ zB2T2gjd_3eEt-~uj(^}j8G88AoGRAl>&p(EC|GoXpmulWQKm0zH#g5@jb^>pVs1E(1C(%|CQ_O}Vg8>)y@Q<&brt zL!wjWCwM5`kACeaowii5cV%u+DQ;vxS*81c>`E||=ElP$A`h(> z^$BM2Bd-`gE3n4NR@(7q%Uma2(bFv`u?miDi9jyS-%$i3lpZ{gn`M@tBbW^Py3yds zznC_(B`9VpJ@C@H>Px~gMEAz2t{P-`ya4J!1o9FOn!P|jo*lo=_+oe+!Z@Y;4P?IxVcjnqNs4nIRg$pmSNX=f#yX=L}wze`|!z( zmc0vuVD>3Wclk{R-AmTK?(4Ih#UzIePSl&WSQBL$77lrvk1NSO3vm#IoxpE>` zQs3Nc`7Pk2ZZ4bsS)BH#z&crXdDxzAeUHu+@sQjdsZh&z$xk};J?R}v*?i}6#*$vp z-#h#yjG5zK?zl5@AS~ZXCv0dXU~@`jjg@jhjpBbm6X1yfi6d1c;9@t0J+K0|q=-A^ zCsBOa1+VG)1#v%DSF~^!Rg*{f6V8H6*;`i3?r8K=DPH)4sNc7G^irTlI;QTz`0Q4?MyB&yx*w~SRzi%XK)-2K`N9Ho$kde2` z%Sb@!;BU-1ny}Q|$RqSzn@N@uQM|iK8J#stN{Rf#|7gJ3FhDnsYGAIy`*;)o zhc^bHC_acTdWOh#%-qB#6kmP~QP&xE`m-|K8#FhANtHilX9HpRw4IG~;^O4Z40-Y- zKaB1LBeg^AC!dV-KjZx-8Oss)hxIRq;IstJ0JGkOuqV;Z?0lRq-^Z1o#Pk^>y#M<8 z^RW=nTmozy0D?|V7&{)dc$KPB+A39ARS|6IUwRgtDCiLV#bqUZ56%VtuR?8I2D4G=`Y@BA!y9X&VFMJ$F@Wg zMKISb`5_M>%i=VvAzF!bK@8Km`27#EyA%4L&M!c9rsc)gin8B9*nD?;ph1t7@zK5>Jem`&AY}9Fvbo5DdUCWdA zuTNKC^?<`|s;|EUoz>@AQp*mkQLPN%g1Aagx&}Y)3*#uu@y!fXbtJNx0EudT${_n) zy;H#LBc@i<%-<7IlXUpg>3%fcm`S-rZH>UCF(!VAqs)Y?0hj8oPZK5Y5r@WpIyK@q ze@FY2M79joc~N$v#Cys^5vmyHpk6=D+9zFi)=S3Owg+~fRJmQy=nhD|#E+x`AU(~a zeb?2KGxKZNP%1|Rj)!(Dm5Ls4^Z{iX-x{Q7{cO>e$GH{uC_QZ{y@pb8B+)v`U!swc z?hTtvGuphY-$QCc?-pm0L~&m=Zm45?>c*>_=K%Eaa+v=j3mZuR!j$Rrsti~~L7XBOQS{j#i&QJ- zfg(3V$J@_uZH+E!1!(61&imtsEzhPgJ6MC^_be(kvrX6?dxG`R%X^N}FTEA-`RZxSeYK!GLD!Eq8( zmi$-BPR^e8WYF#R43?SI9g={J>}`GL;$KMz3(YIxS{iwa&4ki~akub>Ir6Y#RQ zDsfTG^O78PS~$|)M(DIeaG~H3d;09_hM}^a zSq?F|70hKLneypXL95cG))p#t9pQ|aTi5ytlclAWPO2-1GdD_rNs(v%f_ZXc2DN-;0R*?i+}*9RDRo=Rq|4LTsRmmMHTjS(LcQlLIW zkKN&=(#@_G)?e<+fe5g1H%&-A=#!7`aqr@pIId|Q8 z0#2Yrxdy-YhBsFuGB%2Hg+0s4?zV^ zXwky)2qVRH!;~#((DwfvTYzOTynhq?rXW$YL>~CR(u}<<+#tV%?T;hEoY@IGE{2Hz zV`6l4dPZ2ZFvF}lhe_qV zfgAA-Q^`K)Xj1gfA_`_MTV|&g*GuKXBC}Cve1{C}Eke}S5Y#1N9 zpxi)?T`v&hKiilKqYj`pagZn9@Khe6x*MB!$F4i|X65jh3E1m|cm(>>QNP z8GP37+_j_6pml*e@X2#QOdQe9)l%n1J7~+hx0|kb$DSp=#M(=Ny%mA|t*p?Azo)gVBgRqH&U{Yi5|4e?sT@0}EmxGU@ zdLXm2Ne}EH;5Xcx%+^W+NFP|)OD=%-2)yK^A+EdrNa~T&MHIi0ovfGw^IENED7xCI z2Qd1TL8#S#3Xwk<=mNIE-}FLgN|`l?%?mJFgd_-IgBn6^OXI&@8c1M7Ez6sw1(f2p z<7>YOa}GR!?g@=WtlGoZc4{{2%{3({!zIGIa-P;#_q6mb+qo9xJUSS7p>lsP_W1E} zSolv^JZW|R621|wAQzT?$ zAll5y?-jumq0Ac#(&L-rimyL?XdvQN}EZ zPL(B_u#ETtx2w*op-Q>G0~)FsMBELxac)8=N=KJ)2q=!DjQz^tlOwBj-`3XZ%Oq;M z&_i!$lCj}swp^VKe5w|RiBO7CMJ4O&KTj~XqD!yWc4oh4i{rbQfiLUnQ$FQXV#fNZ zc?=2eg({c;-~|xffjT%4z||QyQ4ZGg8GMI6kXW_43aU+qO!$O|rI2h8%=g@)2b{Qc+yOYHo*8#I+$ah^XOgRwA0dI>`Qc zBx!0MgEJxdY*rmkvXf={qvU3y?!aA=^mikFp^y|B!=C2ReZ3FyPhOQje-;g#tZ|P_ z_*y#qbpVw~X8p-?^!u~GasW+gsn zRyXd+gSk0*_Ui_n5|<-XfWA!o%zE}&EBrxUtL=|OfS>Ttgm_@yAKQ2Jnmb{^#uZIC zBQf$UGYPp9_ShqCcRqibDJ` z`{zF5pJRmt=!uJw5J{>0XzDkDdkB}>>Kl?2aWAeRA^6xPnRrvT9Y3Q~q}^r(;8fzi zhKuaab3N^jioV`YZ~urL-UjFiu5GJX`=3*wDE-e0XxX4!t^ugm3(%Be9~pA<3^Wp; zy$nQIFRC?g0yYoKZlKHq$1iv~AsEKfeY@NxzpS|xY;?#)CO?IP^tk&=3&*z3;4q*6 zOV0&yi!)t*?S5bpfYvkFQ|Y za=;##V~5jij3kZBHbFjc5G5eR|JREMmYu1*_w8+M_y2_wY@FnenqQuiEI-Fbj*#=6 zbNTEUhH~8m;g7$p9tevxecHMj=vR{XG*C6IVoX0<>2@AxQ?R5Sm8O!pJC1bbw^71m zAXO)=CMM`qI1xi(lN$Y;eKMIbA05w@;+nFFEqliqiIaUzO<*zpK7)J_W=r45_*24l zou$gSiDJ+cM9l~IaGVX5pVBE@E@ZmNOOz6D*F#H_(RZIZQPeiB+&ac6avRlZ0j=K$(4u3h&$(#MU67lPlu;W7*!-%#_NZi=mQ}LkV@rl~yoQffg*%wS^zaufch# z5ewg7Dgpn16$hnoXdKq>cK|@5{>|Ez6Od#sE&;hc{dC9D;e;(=MEllgG|MebMNham z_8>DgR%_VpJR>mv7dAfvIKR)~Fk@44HXY@Ve(@VPPPkF$V{4<$6R$l%gu|?=JZ(T~ zi(CoJYGAnzAYQ(X(jeQKGACz%doO1#TcJyC6z2J8{9B zv(4{W(D4z0qlM{Q0f?W#4f&gLej16cQR{}sk-H!`}xIo%) z1(emVV+e)3isiUm%A{arM#93=Tr&^gqb@vHiW&Vd`ZRG*@ysGj1~M?;xb+hjJaa~m zVJBZGYu6b1Ue9Z*x-N-r1>g5tW#;FDV$*=j4{i2Q)a8GkJvK9^3^lF%JQQfGh7a)Ivu1@D;c^5yXERU3+9{;+fAD> z_hU=_ZXb5*?@VKM^@K@p?X|Yg0@%^b$Ko`$pDzD6Oy$`>n2a82ZAJA&aVVxNQ_QeI za{f&}iO)Two=GHrB`CcgaCXw^-H-T4+=*0kyh+hPlO_wt-3Vh%^+8LV!KsTO)s~}t zxSNOr6Y;FZIqFz7bybNNMs|YTG+A!eB;vkkwxr62pn;&A&$VA^mM+wZ{}xisvaC0} z1{I9LX^f*u>pzZN(@S1M5?8=4NJ8|$I=bS77vE$KHBlL~3M3V<%L^e`eSEm#S0PMk zG$<1}cnlSwr&fwV&yUr&trE>_CJBY(jc|zXbTaSPJ|Nh!;eLBC-ji@}?KSjyu&hUc zcj&()rtnB1L@`2xK-WNq(%f%^hA>cdg6owv{3IA`;X!21c+RZceS2vrNeBov6c-7Z zzi(m*Kfzm!Zf=^i{{bZ;;Qrv}FM~?)J&S%kvRi(3g#G)ZoL}9Sy1eBLv5LSAGsfxB zA9!g~na_SoZ%}2_Uhwkx#puPnn}4<#umUJSh8;@qoD|_EE%WEf&?LMob5nv`mOSe; z=1sk4!~Di!HAuru9YV&f?s=LzML@APwI%iycWgwJd=f(PR68cd{@y6@(~ct}y*Vlx z)y}um`FBb!0}i}BZIQDY-$v$eWUIjVt}AflfvEJC`~B|c6Q^6R&i@oZz_eRiB#-;f zc+6xe7pNvl$;h-TG-(ILpiph!8y|y!9S}@)a&{K}uj0!;x9uT7o7k{A(c15{Bb8Si zcV6pXG}PA4*z;~~B)i??*{A$*==fZRdNhy;Q)4RVSqHmS^vAMcZFM;MymO47Zvo{R zX2Pxaa!8KLp?>6zZc>;!ESpt>FM};~ICKg$LF6RDEM4@wa*9X$S&J57emU#w5An<= zWo$Lk75&bxDC3Opy_?Rs){5Xg=F{^}{16?$>_Bxb=j{ z=FA4uwdjL5^Zk5mH+-xvTeD7;`T}TuOEJf`pzzU<&K)^dtGJeJgBBjGDbh#AuKGp z5RAD*ltI!R4{4||tVpQnWMQ89Y5_J4-e}C(66ne&MNbbD!?Jl>il7D!MxX_>0y+!; z`9heSnRd+nyOxAY8smaN>Z}Z8(d?rzKVbRc3`mOB3rz!^1fNWnOfhI;ZMMmeLD3Vw z(b~~9CMpca*ZF&6*CifkZ@v;(2mUp75vnzezc?LRAi}!3-}yWWP zjK00c-})h%(C5d=?L|=H9@ry-`xO4e{pNETJ-%Vc3qQ9%8EHwJG?kA9fY_FlRqHmP zCoSE8UUw*#_`l8UxNaDTN%FzI`yYA$AV^P7BD*2;q0-Jzy1KpkFmSk?G#R>Jy68Y^ z69TLYm+b+6*1U3Z3z2tnaL9e{t@X`gp9## zlQ~V6^Ki>XpoRV>cT1}7BGjtfIVL!QypP*`&w&G}?|8cHK7D8?M!PjV?X95sPaXGD z;By}~a6U8dt=a3#8*xQspc|66P?yb%sS_gHL%zciT{7masDZd{7OXW3lfc(g6k%1h zF>bY1ul5L6{!+*NHtyf&s5^%pQmlIDKv*i&*wL!zkGTkuv=Hmem(<@3PhgjP!BfaMj~XY0NN$tx?l=j)vU(&(0hNuWlJ&|&jFSio+Uy>%vDu;JFeWce*cX4i6`Cr8K{LFv(2N5>Z)62@w-~Y-=l36r+0EmMBlp^tQ zaULEXKz1emDC~X1ob%`8xo5EdH?faGu}Z<40k#VfELTxNRNJQC0Df3m0Z7o9W6bo& z!Bi$~F%mc>U_1ik$p-i9=5Q4Vh6I@#74ut;25IhPAPb_w-wzMm(T&IEks| zJXp#{37hwl)udXR!$S9&2QYu;K?0$daKPr|xt@KUO zHdRO7r~rO+KCaX6X5-VNkX^;GlDL+aoU;@lZp#ot4VQ$dZu8yDf?{#r0nv$YbnZnbI8Zi;NVc`y7UOp*^~`IV1b|-g6BO%^o{W;V`e1cUT1edVX3n zcan9o;)}*mb;TFp6hK*)UDKA)+r=!vZ!)&78YEkAQ@a!1y8Gbh6k@nZ!OJF?#;R@o zqV^cds;Biix+${?)^RjOgJ!tQzv9Lhso2z*gUln(impAmrIU#kV=t%qR48G?S2kpn zWcqKeIgt)-j(j7EVLkQAC&EM$>|DU?klZ`tN>-1c9)`bQ-=hiOy4_m`)lN>xcAyA1 zOI+1Ug&hcRQVC5%HfRm>1a7&zclwIPxEco31k$ljWqkzDy1JQ7{wa?6*Umaypcy$TafLJEJ)!7VGew5pTDTe5gBHR+nv8f)q`S!+o}P}-npCY)!M(PIyWYzetGvQ4r2Zh#!0_VV(nQGX)hoO7_QtbO~GQ!Je``l(xVspxUj8FF^ z3HSY}8_U^kdvp_^N^~Frg|T`<;4}bHQc8F$lmE#AddUy0tI+ZVpEl**y;rDN^nSix zbXx0Jc5HDO2EAZ94K>x(SyvI|DdNrbL-v-I@Eu;`V+srfzCqHTot(}jixb*P{n6j8|WPg@WX902G2izULPwsg+AsKP@dSzzYCFRYp>#!KwMu5Mrbxx~0>> z-pU*K^=*cH-!_=8ZzISl!{bZX&o*QC7&*L?f4y`YFAGgdj-J^dsMbR4-Vd&1Q@27b ztP`T?kOlUiSyp={XXYKe&N04h``Ku+(#c>vB^ITptrgljNyr#S4ERx-}sCANn_k_qi;2p*2H#E9xSF{iaG?DuV3Vp_Z1cBgyr z5i&UI$!x3pN!3Ks5gVTyc`Sr$`{Ld*4gcNA85Z@Q^&{Ek3G4F1yz<5}zb6()EZ%I} z{>aeQCqy@Mv*LHK$V&O8%^xMgUck^i!VG!cl);76=?ccYA7t(KhI&xsKZ#suX|>R;SGtw5GO+w3N~YH?-8@Nj=v>}FxcX%rJ0b_ zU6)pE-imprAbh|2g)Pq;4}E2jX#jy9a+t4B=&I&sw2e%; zp*#P9h#Ooq0RA1YMuLu6aIyUMv(06Ds2#o*$VVEMk3HH&Qjhy@K%^Z2DI1nUR(u`b z9)7OuK!G;B@nbExl8@+ouvQKG;|opjR^e@Xc;rlv7b;Q{XD-kML{r?QcUuTkjAThm z_A9mpXb&@3c=(a>->4C|9Ga#e?U!p=&4mFy7Yf}=j7YvU%W zJKVj~!`O;oT_LbiP(GK6*-$qC!BF@Um$nz`WiSn<^6^!rQhIMx8Re??_F%8574tli1I`;orfxX_nh77+B z@u_LNi)r#~6dcZ=7yIN^?iNN=K!TmY!^ej`%%SUN@B`xEb8wky0MA6Au{F$gMi5Be3-9rL_LLOLdqqs&^`4{jme6m}a&nPU z!lNt`Bk9N9c@pDiifavcEUt?X%38YFodgx-m`nA3(*s_DAAQQiKg7a}4G^jC*S#ss zb$Go~7^VDO`#h$5$o zXKdUzYUSL-YvIf=ErMcYVQn`7ig7G3k)G~a`WrQs*IBu_4!qf=m&Vs2EHHJ6Uh(}3 z9^bI-keELj*r^;drXp)$bV=YuxMq(@Q|zr-bf#f(6dPIWCfXPY5JsOoyEqY!?0O3; zf4z!qNQ&I9kY2v+bderglH8-;6~HcK>+b7PBEjjyL?%;t3u9PF#ieXFQ&~(|M~H~Y zAl}eYgZeHsR67fyqmu~!#e!y=iC6aZ_}IQmYvq5=&x0mp>0t&=zb!JcYck8#?|N1L z!~87>67;oruWKKp-ymc*rL1|>UUsnfZy?1lwlFDl*1-hz(hA&2iNbY-k=)RBw;Vu~ zUslnahYYX&XnJinpyNj>wBbm?f{|13O)kW>%_P-NHuLlGU|>e};C|Z+Kce>bgzJH! zu~Ak)K>%+E#g#MH0{8AOb>+Lkg3<#6|Li2Rtadsi=~@%c!$2Nf9hP~KT8cM z-EIo`=m=zU)~O#Bvo-yLtn#>gqe~7ZA!Lcbn_eM0x$e?i4XfMdwv7aA zO|Nke0fMz3kUic$f@Hr81=_Ufh`I0UXDurZK2f$!$b}+hI?i0rXs5{;4lteAV=<{X z0-419?-jmai@V534PI><#gfOriQ^NK-@6FD#njoXG!(MUB;WSM==&srUuD(qZE1IL znuU`dy5Uq!b-j{mcLmLMig8tJwR`N1hsMa%e4~D51h#J0B`K8Jkm9TR@CC*pGYt=L1P%rryh|BT#iGncd@Z#=OPzR5K=n`u!jBkQ(Y$*5JG+=NlvBSkUGBm zzo;>wvj7>wYwwWk9389G$|v?fDJKVe5sk(i#ns?%YNcUrj$%*aWj*r*6uUtUZRawc zu@`*&{w!SZ!kR{)HQm^h9TD zrp0wQPv=%f@|D!|WM}7q_78%%Fr=0j6?UDkpOjTOweLDd#E%M&X6}NU*j?99CK&66 z!P*DR<;M|D^8yq5#utuIM?e!{>R>rfn_K(EaRY`5cPMTsEl?`VwQbd!TdxYA6Rqd% zpWnY3#mf84UL;@CE9Swj2+Y5rX{lLtRSN|FX$dW?$lu%PNK!^42=qJ0L#QOf@|Q@) z41XWMi>S(cFZtJO7ay{|{CC&0siv%tL~z>PqB^kHR9BLImC2BT#B0ONgZeL`cl{@2 zVQfoVkjb1ub;DO?iWWpLlKpumvLn_FpE~cAO_hx#1o!XM-RGaORzG*PdO9D18v-4Q zFoTudI^Lig_6R(Z=Uc!!PH|^`wJevJKANuB);!3IaMyBLCQqGB+l<4_K;gU zNYTupu!zYed7m}Z$&r2t+*sb6q`a95zfYP26al{E96=Z>4Nw|DMS*+pw|ro`^ncm+ zhi?KUywE3o!O+Y9yg;qRgW~g&PAVEKp@5uIwtjT247>p6cax2|Ee4$t)Yjg@&(C9< z(h>&qox#fJ(k-F0x{o~NCw7}6nK}6OQOb8kY}v!dLjU2HYxvUAI=u@s z2=8g3zw6+Mp)+MK+;79s(er8HEJ@kK+s4Y!(LraHmhl{|Gt+QAy^h&isSQyi^&K9$ z%5&$Oh)YM4IR!vsEuSTHkr6zDYo|#y(YA`gGv|A)U#P97*sIiu>n49?BJ4R!lmb4X z1TmvKk8q%MuD9)*hQDPR9l1J{$-~d3Lby-Asn?C?bp8s>204p%B3W^t+oK7u49%nS zv%8ks3;Jrld9cf!vHBhHnK9(;``LLZQN!j#aeZD6Om+0L_9NYeuA~J!qY@0XmR&A;X2Mr%1ayA1vWm4uq zzOCp*q%!!LkElR4NzI~=?}K~$AL+o@L%mMJe4xIg?`4ZsN}g4?I%(p9dyRF-ama!a z(2aBq++!vPE`s?O1=7FmU3gV_#nv;(JSd6bpifwAv%Nak?0HT0u3639O4N`Rt}mz= z-5;Cd$Lz^1Q#L3s`G)PHCsj~Y5Tq=uip4)9C~{K5Pn?-7#;vw{^%0=nEFYyDIoX|L z@Y-wfuWr}jOU8&g?3;dL7jNqDQ&F>#%0Oo6(~;J zs)Cc(gsVOrkNV&^39#)g6ds~<>x$6B`CWz}<~?1#ZmrhcXVYX0G<8|Uy}#f zt|tArlc;z+@I`nzc-Ef<&Zr9_Tl1%Pg;Rfy;*R7L3#wWdox@E~O@Ft=A_x~CE*P8s z$S9BNd+LtTv?f5IJhl2$f9dWEHu@TDvK(u>3NEXFs+AIJk5Z4}@4W_b92(ou-#&R& za(~_L4qYX+oLq?GkcBy<7>RfZk>F<6`ZT+=Ae9QV$zGjPGpW|Zox#OyFS?xZNP@6J zFnsI+V|VF05KC`h>Ny6ptn(mk3;H_Kq`0Z%CD39pHS0P+$vJ@z=tL~j(6 zr=-(eadWYD9^Xm}I~Ug*VvBaq@P3Mvq|(_T{=WcMn6*xkD*<OeW}*$TAaRT^t{ zZ1Fx?r~>94@cB}(A#U|v)BcKfqk8g9EG+fLj~I&{$p%kOl*juZy=yaD1s_Wv8iAj+V=CfPVyMu*P+*$7R&(=uT(H} z9nu1|n9eaASh{nS5X#*C*G>Ju4h_J-1fxf_z;3{|_b)8q6MnmU22rZr>)jqFdUdx^ z)6382P&yG|a9(hvl>auD?u`F9^dc(EfdwAQYaqVo;l{u($A~lu*<9aqs`MkWkfjPT z-0z>7YD1QJUr?#kafMTzLd0;lkNDaQ){R?6*8hJrt-H!)P-JXGO-5VYo8Qi zU~}=4(O?y77w85zA~(Bslr-M1Tz&~}6)qm(>4*JZdY1MQ((M>#@H|BGr7XnxUM?b> zrn0pzSaL0lurkEgyQ~Cl#qYu?&2Erc0>k#sBe6n_)G^dqzi>4mWzLv=X?fX`%>)-X zWI^_|e@A_N(6@)_*QaTag@9p9eG}lrbR2@MY)=FI^ZlI`a;jreD>XHiV}7v@K~_A^ zImw6_mrnfS)yx``xRi}WOQgg1W=q$+JksAcc%cNCCG-oW8!~tnX~PW?@Lu#4bvWU( zS1Gb%C-zvS><2)Y>rI@e!NP;ZmIWSU4s3c?5)p1?N-gzGg>`D?2k|l)q z{x@V_=4<@$w)?dz2K};3Wl1GSU470s20F}Q4tw?nOcb&|Qf4&ejzB9q3pxfp?e+Md zGT{*AMd}C{6v8R#uW1Mk{Bli3@?U=6jAx1du+T3#Q6P{doFs5Lx-5W1+FPPsc786? zvN2en?kcMSWhtBDLl~n4H4zGLzJ?&z_0}H)KOS1*t#)C@FO{*Z_N15KagTSWc%%_K z={GSF1#+?n9SPmVROif?Y#)=$iPz&5I>xYA?z_Md4aj65%xXaP1To*<>yK*y9VmG0 zMMCkW`N~Tx-CRZZ4z!1e^Tg@p2KE7XIGH8;9L`U3gbe7MYGFuUdoigonMj`R+%RJ% zq>(}@{kla-&}Ruinf;P%k$N-nRR4<2Q7sU#;3p~WjKCBzp^5lO0fUT zs#Y~-l^e>D1~-WKsJ!w|A{%})J#&H`RiKHF+(8;K&9jDPwr1JAw@c*pPKA=1nZ?lT zNrU;S@u(+yhLvDkR)>RSh}+MAL{DiasW0|&dpA(PU5q-U@3TcyDYD zr;`fEref=Ux}=I14uUK+H8p{V7mPRSV+Z@qB}>SBPZ8ofFhOq60ZdOH^Q6W`M*`(M zWQY(+FYjPvqWR%APG36sT(f`8Iv^R$kPJ2oh}<#SG%)8eqtlO{;eOzG}eB z#kB1F@MFeF*MK2Hp|~Ge6%WZpj8>5R z$KHWJ0~N9@)LGO&>}w54yf8Ae>el&H9id#fY%`TX^vyW*giSi=Sz@@IS~9c3h$8oigHZ9&#a-x?SK*Ge6tUlX1p zMiRfsni)s3zNspO{6Ct`GOEfa-okWummt#Jozf-U-Ca_Gw1j|!bfPUL+E|tnew#zu`hq0&~SFr zyz(&C&rP-|f2s5N?Of^lnNFSiY z%AiDs6lmg02^dT~M`*N(Pseqo1@JAf93P1EVK4b;w%Fk;Qb z`#Ymgl4{+zoX<+^k9ad*nCA=la0IxOq)q=-tPi+W7di>--s!Wubc`$Yo;x~zHNw!@ zjb$mhPfgh#(d3AQ(GPh81TV7Ey4RQf3dY~@PRzpj_s4J^#;dQ@Gzp;@2GfMBxNdVE zOah|)X0$Y8d#7kkB0r_ewoa7nDZ|-fQkNG6aHzEoBC!?gc#*o3rCgkGC`W^5$=4OW z(*OLDdG%Qrg)PjWV^@j{0KdLcMr zoUUGUxhsW}=GyZcb}A(k{qe#yzmXlr#Y|OFwv#f(EdEg6UQ@9|Tu)?=tbB^?3+fVR zUrPEp?3)sraZiU-A+J)MbJvH3K9dkWgj4_`@TN3mxfZe*4$a4VQm}qy*XZMtJ?s>7 z(h(e+Y?OON3YK{g2kq3m+~zJpI5i&iI{gf~x@c`6NM0)o3ueK~ryfl!9iA6?gx`u1 zKuut5v`%wvT{Yjj}@NZIdQN8g#;VfCLeUnQcR|(RxlnB&O3lV;`>L$R5tywMI z^ba>OFQYRvI~NbssvUxSm>QB~!Y*hP%-5q;f2F@Bh( z7arNo^!yNaT4}$y--eS~Tl=T?C;M$3ejik-BjS35YqMvU9O0l2x*1~0M-thG9w{=s zPw_1LOSpfYWOGY5DpriFK0EiRZf=Pe`rO7c5tSPo>?%MsizD>Gls8zqq)rrbLo@{- z&>1I1=1@_Sa5Ch-hRny4MUlbe0Sh*W8&HT3+m(z|JaY-Y+vL7&Y7tn#Yf+})BkZ1U zk?19i>mM12+~oC;+S6{lVkMN8DdG05=V6RC$fL#oy7dk+Gqrq>1oD8GHL$4#3SSUv-kUn1>cXdDS41F!@Im(_ zaMw$N+%GoX-MdAfd77r&zP}shH>4Y(^{6vR-)^^pQ%Ci3&>vHp-f(zoy_yd&Ewo`x zdsrdJ^g%7Y?6NX~qja3e^_A=f2qtN)_^N0K=zo{bP+>3)oqH}$5iv*yOie5!G8(6c zWU_H!OM^>?loyYk9wwEP8%+@xm`PWjyvO1j#li-i?AFxQ{S8@SuS^Xgi`tt7GV7?+2pp#34~7$EmMCIVVzhTmc^#hOBEIv8IzV+O#*+pS|C$hNU$WUzQvME{Ddad1nVti9%S+}-oVtdDE(tw1+G5(6I$9>;oLvtlFz7_ z@$J6GAtll?0iv5_y_b?wsmk_K);zsJY80NGQ(F)CX>+lC9wLTeiM_m4Rs_wdl>W7V3<$=*}kRH_;RGcz+N zq6JWal#UxFgnW3%{<}Sp%4u=k2SO$@BhB)b)7V{)XhcT5*nuAuk{;y7?usDZ`a`c) zj-le291iVJSUVRJulwjudJB^Rz7jLyVp;w3wP6~nH#fSHYcv)`mxr3`V{XPBwc{t6 zznuNcNmX5Z-()?p1-Ct8osUiHkemeGsYcwR|B#iP4|zoUi8>`IO_wKVGqM{}-ElRV zp`-3+NvnWyHOIahZ^aiH>WWs*ra3LUo~n=XV}UJ%a9Uwxzkmw107FBNc;u^A*-CzL z{1dXYSJi@D(~7aRU%kKbGcaK)Q0r_{dpQVtu!l$VR6!(kICP!m`AXr6EUL;0O^n|$ zNntml^&GiOK-Qpr%#bV3iXEnuZm&gjWmD`i3;3De-RaIPfilJL>Qwi3m0s+! z9@LnOeheqiGpZk?e*lAHGa)22Q52OPQ55PWO1&W5ml?;ql2-j9K}mCoos!bd9|eZ% z!wp$H%d8$=ofDb(6-T9`f5Ptmo~=#PWx2}`l-WOD7jZVgt;3zeW@l=>9}9IM7`n6R zL1WVIkQ-K_Tdw7jLM;76JuBZ_<~ADs!vfxlDDoreS1Z{TsEGWFg98Gts-SZ5TTeRt zjjp`q{h-1@m^2NTsHj1+O!S*4-*d(sVkksW5l_X0HY6vi$HO5DDI}ze1mS;Iv9+2l zr7LfjViu~dWut_s({q`F-9*HFDZ{E`4Dru%utyeO;zw3&tMLr)>3h`B-($0XdGOi& z#^QA#OG3x=ERVAmkzL+qZ)$)w;6R~DwsI}aeM>e{;X)nzo+6}A%A2Mp7W0EAjUWSV z8I-xWnt^bx?)grFI($7|gu&N8mrn2J<&8LeR{pz__X#0kmwZ|Gy|ePawE|@I!Wp`A zRD$|r-+dQdU0qW{XXF^Pe`|}kT(KEX+()umd-Pe|`KSx<_$1aieiWm1=lt(Ax7{HW z$!F|=x;rw-5A{!K2hCh@bT z{jOUWOQICC)LxpnWMhcM*XfK0H$tH!uN)@LZwRvBs|GkkQ^9}SCm%*KkG@Z_b1~aO;eJBIHR%s?)5hlA%{QFH|U_tD86(wDTS;4b8Y#@{#-?$pWlS3NYg%u8e|U_ zqpo4%o)tHBxYP#N(+lUJeHu3U)dySnKGiTA)l1XhD_8lG>Z0!9g)XZ~nUY)E2zDC! zkHZ$MXr4#nCY?s9Bm9AP;S?V}L^=;{E9oRUja88Amr}BeiVVF+?6a7S<#zJ1Smk{h zXV=@lzQ(bCAUo@MvG1(@1yId>^XfgAGx&A?>Syr{H44Lz>vGbl|7zH~%8Z8~N{zCI zD^-SE_(heD5K(}3D+2-kg#BI=irtt;@&@yu%>28Q-p|pe zI8DeEcUa%Dw;$E7PhByVsnj zB&5)8?K<|%SyhkHW$QAj*U1s?Z4GAs8^SAZ^ZY#%d(Fr5kvCc+QtGfZxN`P*%rk7B zlK!SgTU~Zx?rV4(38`(!r}rqok+;;k!+hCOH~ed0Z9K>W^XG|JsSWkc<8UT=(Z2;F zN7Jl9`$g!X@~hR?M3`+DnOMN85hOogDtZ=3(nz6A%jXpbYMU1Ff zvm99Pxkge)KO*sBNPg|NNZk$j{H?;G{xb|Gc}SU>Y$E|lNe0FXmN3VLkk84XTf_)F zY<#Ifme5N?4AlbmKcNFHZmG#G&c-ZZ+yQTv8((T@#+baFhCO3)*>x-A@zs@c>n|+`XX=WT6gV*r@Krfe<)408h z(FhxI#3dO|z@q@8|DpjDAK43ci;8;Gzv&wqf{1yi@6+vn;xhQ9LXdh299O3*+g$~)cSKOy_Ovh!_ukDp1Q3jNe)iAKcDx;^fd*;_we(0Y|9aI zu9!7Oo7<0(-|q-Es!Nn+dZDe1KyvZLHU7L#92uWf&(c+NZMGBIjs+^T(U+tT7?kxLDHJpDu+7ZdUK99>5Rwxvu2^DShoNa3XLPYdG z6~2idVkehZPQy|DpxxffXP5EUBqugVZM-;|B{aZTLM;tw#6j4qh+reMwji2TeYP+| z$-KOzGfS7~KtX`Q$H(8k@Z==Q%*Z&flIDSoH+K8bu2xRPIW?-Nw4rvd70@0b|1D0C zC@MN8hA9du`+92&N^KPI9%ehoVk-*Dj4PY!d$^LXnS)etMRl+$=U7`M9<&K%$K)Po zp_6ny}qZe(r>v0{#`5`kNf+xuD4f!a0ACg(HY3R;H%_6_&nM;SobXH%9*UG zXBB(JwuIr?0DW;ZQYnNc{O$IssHjMk+p>;uEZP}$ie<(V^9;k5Pk$Pa{Cu=`qc{Bb z|Ad~CDhunpsTN_pW(VjT#?SGi+{Q%~AtxWh@x)o}xbgSD=ouNo&p?iUw3xdbJhx4MS{X$oq7E#ew1XX>*dLpyyZ!hcqpi`sQ8*UxRlVfKvti7iy#|G-x^|>B| zjg8GWQ)@v|fXdt&tnnSS1loU{VHNy{t33vY28ZAq2Hf6*)pmvNs;C0iDF_M!#?c~k z!^B`wcQ&9s)uaH!Eoe=9+XVbwz|Zr4J9~4ubp--+&;Z6k=PLvGvU#C-c#hxZZs{I# z(q5r0VSIq4PECpR!ih0XQMY}OL1XCQ&Khnc9^UAJ@f!74w zw)w*P%f_-+816k(-T&8z*~``C$)u+~ykKa+2SvaC_Qo zIxJfz=BaMREjk_Or9P?;|5&t755e2dD3+f+j3=%o3j28>efe#P@9IfDwxL$0yz!r0 z+?Ig)a8RbN$2(6^CF*!UoX>{o#Ql$@4_<5?!Q$U6)IV#StA7y8pTYdc$N8bV9a1eG zM;W_q7FDyMY+#AgO`Oc5aO~it>~*$MtD~v%>I`L|L|pCX-3V2N&th+KIJ@KJ7I7}m z4*t~zj>6$PB1hkQ8H|5tvNKR%5iyWEw71$;)MhUjCT|oHuB?PA%U!wTq=43m?9>KjWlVAsf5ya{6&zww(oX|3?3yL-2xT>J+T6Bt-aPoLKDnQ#zVbk z!j$oZD{^@vm2X8KMot*`f(L4T)CD+83=nlv~~?X%jXh!Yz9v^yu=hD^v}Ns%jz-Sg5?A8i()gprG`#Fp~*>G!-nfqN6d?qhGQ+_#A%j45EiRCACFj`ds#L% zLGx-t!`7>?*X0gqZ=S@BL;-DRpnw6=&hVOm1Qx=`I9LJ%FM|Z|UF}ez`oMeyl+=Uo zBU7=;u%i_$)TSn${~B7R(9v@JXkQ|J&l*;J$C$}?CXU(yyq*6Zj$W9Rh8@dicU>1z zPR5{bCQ%DKy1Sa2n_F5y7yV=?xwJu6+A#A}Q?6AyY=g6xb))gOg#s%te&13psP)E2 z@eAi+PKGRp0#Ww(KdwiLAN?ZsJV{&##?8e4UJ%SwW{dHy$ld-fo5~IHZrDvf@T*kN z-aehMxsqYp-0!t1N{IL13r@F?j{dtBdA4k!RkAv--d=dkKj4dHZ}E?^iK}0H?g{jx z8l1Morlp3A5r(L0dZ8heg?$b#=70tATFhVq2JZ5(+EX* zXxtPu|M+|+mB+C(ie$yKmT?-P7NuRN7~NAFCLbOn_$ zt*uDcNC>ZP{Gb$z$_hp+Mp{)>nxl8Zxr`(}U)m25HeaY~O8vBe(TDnn=xge+^XJc)dvc8Nk-6o4 zShg(otbL^@>*e=tAHF6?{EVqu>f}XYk~MR1_+&xSw}~Ogu4{Vny!&J_@a}hz?!VH2 z?j1D2Ha90EBxoF*7E`b6DQvLCr(l&6vsjg58S_g26Xxx|SF)$MNt*zi+gZatwG7%%`M&r-Q zRIelvu*9c+NrN2NvaH{}r{L>tQ&$IYk^A}i9nUj~(HmTmIaIhZrJhOg*Y1*Nqvuy1 zt%_33rCo5j6BZ|ZN6ptjA5hKZO|y$3_2BLv<;sA~bNS^q@p~-qt5F9HS1b%`QpsF7 zVISTnT?WGTR7?{_?)pN5D}UnT5`(V~FGxSq&!h6O+U!cgIUZH_TGODQnD7R}-}BL{ z5rJyt*(v$-GGk;dOM$v_+kKAll_};Tr6c1$#;chmJ)6iQih+G7yZ0)uZXz|#O|`r8 z5j}Z`b7Wdv)Cipr&2RonqUUubkf3;noWOj@?pTmR@6uUa8H)yu?<35YSyyQWGQn|O z(W0Et(NAz0sUNx48`=6HEH|^ZE=(M{-%;BHwGyY};@F8Kc9AY%{?Cy`&QtD1JND>kzbF`7v>PrX+EP$yfWZRsn+(Gb@^$|K%(O%g&hGuV84 zh-yCXJwQEv)f!316XGsQG`%QSsd4qC&M-MSbILCTL5wwwJ9mU0zbA*bX>w$9;gD6B zm}W~8W1Q8GND~Eca=P%p0jZPF#+R4m!_eTOQbE99wD)y2BOgPE@CnMMEH^bP3S60; zcn~Ze0|;as;Lz~iXC>hq02*JJyT#YNMS-VZwLCR0AF#37Y)?iF73!Nb*mUS-Prq)B zo;EQ&aIOT_?=L*IWN#fh`E8hKT1e{aUl`G8%o{AbRW2*z$uezKn~agxDlv} zg0qR(eGP=c_Ae%KwADzeCYH^3l!e`6$_f>vEsIsRd(sApb~wZ2*u1T%NoN+St{IqTQ&Y(K2OmIe3u7T z(=-w|X0Td@r}@pm&D0foEdKoj>5U;3LDedr=FZW#>k22|V^Bl|6;58kb)O8a4hjlH zgoXXiH+qJKhF+fTz+&8Z48C}$MaPXGL9;r!?3u+Jy=8V%tvGPd)6(kozR9=X+EKn;~F6su-*s(npe=T-|?-)oI6Y}2%Scht`#qsZ4j zR6eSx`fG6d_G6n-g~y5NzO^gbj3$2Rcw`H_DN`Uay1)(}D}QKgSkKmCiNS4gV*^Yj z_?03`gcUvj<57?KyYjLNPkT~5IySgPhu`~r3+>2BpIHBx!f^atXsyOmf!;$hl_1D$ z8v7oOtxZSRV?aAf0;j3^aKaMbJmpTcvdha}K$NfqYq_Bj{b9JpWeqKTAxRDX^l-S; zejH{wMSquM3dImbXveQCy~Xh>(+AU0@<8cOOa!?PS)Xz^vX}GIs10VN37kjW_$`vs z{t+iV=b%uirlJ^5Z3d{$|>@sf_Hj0k_OI{SV2>)54-Z%L3c^ zfV_W*M-EnUMb`0KsEr^g1#L_hvJ-(wNM%wP)L%{yt?Bxkp8d5StpH#AF`hG3;qgTn zDH2fDu9XMmr&^1CTweBB8Sj#s)5Y1Yhdh0sU+zYWgE$;4YIo5R0g6Q+2u_pU`%jVPzOlk;*gY_byYV$0|#UXII1e zT^>=enPKT)>Kbey{x`)fqYPSn4j-J2oqV>5yKe2e8bR%nvvW=x$Nf)mqXm?f|L$-Y zF;S3TUO*)KPGkUn=!bI( z^t|;mK(w!{s7Q^QHHJ+$AzDxW+6~sVo>SKgcS_8cf2%#m5FNwcs(zQWrMw@&a7>0S zs(7zR3_BxB#WPGIwQRB9Q0t|vb&^1K1goy*y80ORsiFY7!dXGN5SidK8;gNmaJ-eb z(nL}`ZhqXdSvFX6zAE8zbIiGjJ~_(IkekU?&&)kMa6@jYKqDzBCe*UD-%=OG*0Lq! zTZ7D!+GAX&OW9UsJ;Se;q7N3_X79Ozese}|aE8l1d`1kU6Dc!5YnY0Z!Qo`}qN5?Z zrEDBYl_pforVYT2Ee!x(Mszaa|HxCI-VWjdq)h|MH5>z^IJ6jv6U+EX4ojr7L}=n{YvpwBhGtVm*dl1j3fmWdpE^@epzjC9Z--pWeweidWp)9Bxkbw41DS5z?BFVIqt zeQkFOJ44Dn9^R_wp!xw%G2DQbE#VNESYJ#NCU@^X8;h>^FrfRT(gGiK_|J_&iaVW~ zL*j%2Qt>C$94_dtRO%&zwb&(E_kMUP3X|6k$4zacd3pLe+M;lS;?Jp%7P`iE1UE&q z<*a{?+4I=4l_h0vNCajhBd`^OS$IB^?u{3 z3(w~pfb!PzztOt8z1{fCN)#m;-tKX_3@kY&t^o^y&Tu-po?0ohpQz)ftYO?YJq6bQ zSAgk9F~cMh@B3~RINm7`SlryqH5dX#Wt|jd0RR+u7D}&lc`cTgmFtVmL-HH54KhMyEHOS7%9RPoB2$zy_C}7{ z|MnJ;zzvNn3?qxJ%h~r*q8GrF6(? zYIuJ)y?W+Yx-*c=37HWcY0-X4*>7IpP%v;Q?bjRlz88r$+{Y=kLLB%03eM7?^5ASu z2**Jr&V0`c%~dG` zG0X|cwt@%W;X8#=gSHI&?yg*w*w^^ef&nyIy<{xYMjiP>a$_3&)L9s#)`! z5+AFq%2?GMPilC(Z3$m_pP4xe{n=3kn3=6@UE7N=6V4orD$UcCHt^irugPl z55wp5QjYK2Bih<4|4f78XwN38+J8`=uhEj?p56Kt=ZX#maY|%wmD^7E7k2%O1$o73 zMtNLMXvV_Rh*az`IQ(e7KP zv_5OZVX#{D>~jqXkKf8-OC>~WQT5N!HifHSBFtD={#vzXy=lsCu^QiZag(;ew`78; zLpf+F=*7x({AbQ#vxJx`5^~<^bd^D6bTbrB6P61f^_7)C(CZTBhFE}T+4ztSqBvJ$ z3Dz?w?tS4HR5I-m(vhJW!I9Q z*u#r%G1${=A#89C9GX#tceIe3&A^mCY_;vTCL}dsvEJ7?mJyuw$-eFz*N>c!-L&l# zRGKJ~5-4pr?TE#ZEbvX;t~hmFjSGP2 z!8GVi1!4>j506zH;VrvyGq7+1+}+>BML^^MiC>_hf_DH7pyaZ5aM+yiiBmZgYpJWL zsR1Fd#~v+Ri6SG>Hv3=V@ML9YOFvgoB)k|1&$Y6gsalp>8#10s-c0EvXBjD}kPie| z;eAsj<9xr}WXL@SGH|5g+&&)3{VJWSEMiH$wLCY$c7M4a9i*}lS81>BlI;1!M4Vh~ z5(|e)qwA0x$fO@!K|Uo}yr2UHaa~^$KgxBS(2oqyk|({7q?r6|AzwB*ES`y`{x}vN zh6#UN%7Y^tR5NWCgzlbnxZ{l#xA6nun4_XlTbl@WS&N7sjQ2=Zj>P+bu1KbJFPsXjI3*F~)t%9KpKRlx=C5 z_aVLA=<$v_-<;3NxR{H2siUw-)|Tr!>!^KZxT>* zf_D!OP_GOgTK`$7!3(720gi0+{O{^&{#61|eck1PxnM%HxyFhiBqQl4B5M~!RF7+^ zFUH(hvX~KK3W`qIy?488l);DV(V7=eL1A9rX8$+g4htini+&(Een%$*kj1~ieFKJY zTk{gwqzz(6Sbv+yLf|zQ{-r`2>ftdyw#GMsEr>h+B4xD|zWW6Yz-I`$ zi3(-c+Eh-HQ1ET_fxB->Z5pz*8oJV2YZ6|D%P^fVuVd5A2@S;XlU1S zB>JdX%I`}?GzP3kfUp2XVZGZ%eh<4bz9(j2et|*k=-`n1(j5)F1Rd?|g6U&m ze50^>w%P)1{?*EA|KK1@SIl|#_X};oe5pKma_hsLwbQyh(H^+n4%Z!Z{WS1!W@jMHT z`VoE+ME7BKz`arB7{l2Af-JJ*#X}jfqu-?4oU-I1BTNjtbU3K8+Y&422`MzHyH)l5 zz_`$|b7hzK>%k)OaOcVpsk|O}?v<&hA!FxPwed#?D;Vm`<8L*spJ;+p$;UQK6zT~e zfA#!8ipTu^0VNX_Z=T!owQebLhJ(l)9DP6;Yk5`Gubdi%RF_Emu^`n6mr`>jlByv$ zeo$i$cLp zVAnN@tu}6u>)-HVX8AA1uS2x0y3Yp;#e1}_mTIN(2c`3*hvuVnI78_Js%#?e?i}@n zy6Dm**vq6F^8_&rgoR8Ok0mN;fif1_(|VmmvkFOR5n6W(>~(P zPXN%4*&e5v#DiMl&u?jlEynZv6aFiqWy{xTF^K7X=cg z_PwC?(3!nQO6Uz0Y`Q9DG95H7e@j%&}QE( z_N4L_R`KdS;NvZoL)5#}w#vxrj1;hFKYAp)|7dlkX11)^v&s5NLfeL^%V(ungFAtz zzU*GL-%Ot@k~p77$exlM`&P;!`EGHsb$VOjP2(`|@h~C7;(&lAHlbZKYNV-WZD(3+=&foUa(mA!u9{w;)CUkp)|Toh&})Ra z^YR!5t#}3pmi-VFZ^s5T)It|%7ph=(UThEfz2pOAJ`+`BSu8>*k|+ATGQr?h_GC10 zH9a3|Jfvl7<>)OLsV$l>X=DedM>Bp8ZwPKJjWqgC1|G>y74@={ya86KM#b_(a*7teNSOl zPvD3E4q@O{cx%rcRP+Qqv$wb0nO{`?8M7%536jQuSRXSpz^cDqkiEs`%Q4>kw}QcO z350I<_xBOJLz6Z4@IDLFT|svxnAvtb1qb5%fk+Qn$@oU0slmf0Hr?9`N72}r*q1n9 zE4Ru8LykU0*};(ijYUEF!l76I(!gRnAvP>RqPlMiT4^CgS1d^=O9w6?4ei^_BdI6p zdFauO+Da*2&9Ic&PGGWcvM`z~4%c*GVoammg|IDTuI8?#?A86n_K-Og^hbjTop6__ z>99czkA5JS}m@~gg0v}4u6SF$(3>lpCAOdIAq#+))t1C zEHD}e8#j2YvI~uAQlRe1mBlj0X!|O-t~{SSOU&-5NSOqkkw3r}yJbLg(d^ z9;{j4yE}f?JaDyOj|$6yh-EPtJ!%W=vCK0&RP5J4T10kF7^~M?oWww2fIs7OYhv@x zdnkx!LtQ8@)_4y4StA@Nu|DcJO6#(h)N2W?m12l7(99D&UK-6O0OVqnc_m6QBcpd3 zZtPYwu{$+H1h#W%T}E>W15?|_3>%d&WrE}N>W<0p)Hyi#y>++OQSQrf^{5Hk{M)Sh<>H>6yWZOkU zb2O#l#lrc?L?)A=1$op@SfB2HXwMx(SB_Ha8LS46`2FmLCp@@C{pzK*+s7~cx5Uk_ zoamM@B970xRD-lC4d=I#Nvsj0Fu4bG^Djd(dX4$SAdx<*%zk2L66>$(<%Ofvi&O<2 zT;8&AnSXr{N3F(2;mNdX@3teY}*FNcGsIqT>-lG zmTFGsjufOSLc>a=@ThRd?~?3y0sU)n89(MRYl={W8pg~LrA|39AQ5=U&!!z))Vp7* zo3%ulKVNBI7yGl$e;Cqh)B8GHZF6ElMozIAiE9m?t_sJ14x2K+59sj`kn32Xmd{JWVce(-#&L zJQ>zE($+q>djg7=u|aNGQwn8LXu(qqSG}u;<;!|q9fzovt;RX_eM5Wu^YhgN(6vn0 ztjiSD=$7_*hDc`BLaBHe_?}{M%n!G7x^T=?JGL!Y`Cy>(cdt}nv-Dcu)8v_dQha(p zP25(GY8n29g-{(;L-}QYc!yNJ&a0q|a!4#BN|$^wQ2{d`;_%?z4=}a%AHzAC?zJ{_ zD7(ZMO5!R}FCnRa_{oe?hniN^YiE+{5cTB{bFKemwYxST}9ItO7ShtJQ-y>fa-Vtu&qp;XpH7IcYL$q5Ydp|(814K zw=`7LIr}d$`1;mlzKP0GrO<~mE>TRdQcS*2Ki?jk6-$%3M6bdna(cP^TI-O= zVNaTSW`g~kdDn6tVp%Hlw#1e%e~E|+cO-)?(rBPVoi7(}SBJi;E%N--;b4Qql{?bh z7TbCz=GgI93to=-5r+B?Q9+&MB3kWVHROjb1qEE6NI7+vi#tQZQg_k3G>qv}f+(X^ zFsz;VF^;wvXDo;EBd1nKvoYB-L8}zlFqiDP2~Y^QDjS4^DN@pT(>ZDDe2q2x>_T*x zUq^N5M4FdBZeR?i@5f4GL3e&{B(TQ&gCQp0>knHU(gdT9)@!?J=Qft0{Q;gZ+8D#s zPRiUyN}Wu0q8zDS!Lb~U9U^MM7Ci`-$R+krJwpCS`tCKn^P`|lX-M?pB2-BcBG0EE zL&s3e&2%6bCbKMQ_Lq|^KUb-m`=;Hm>dJ{Iap=HQBpv>kSd3k!&5kVZ?m?( zZltRVF8$zyJ4W6MzwZC`;^hCd0{-SU9{3q>b8|zOTaV^J#p<*2;#wcflzPg!R&gGW zRpzxPH1DmB{wwqo*D|n!a4g~4e#mVd$9v6Ot}sy&6ck)tS?RkWM1cd`aImB!78|RR zX4P6ow|a8_*ePNJx^9drYi$JmNnVC2{@gjgq>gBVk~Ch7t6d}ZX-ahF&q3y=vGzv( z+wkkc{29I~Sr`6#p}mo~)uJ^9%L>z&I!I^D!2~LGWDynNse+{zO;#|wiJEcfAxRj* zRT78!G`m~G3ug7ftA~e&|2y_}B`N}HV@gpzB|X{7bSZUI((r~YQ<##H5;__hnCx6* zA5V?5c&dVuKXyy?lEP)P{JGCrbzyCT8ZdYNjeq@?Ww!XqzVa+|QPLoMFhA@irKxT9+=N`V{H%(B_$fwKl!Lc^Y|i zSYOW}{upN%>tFTcuoqb9Eq?f5L2q0ani}6HK=x^JPQD;gXJKM!ii6ccQS=r>-jchX zEt>m$?%LL0j=Nru(YgMr5&qEiN*T}(`6>DvB?`piY${@%OVy?8vJPyqf%M;+KCNF8 zOfWq95n6nI1JiZZq@oYUr*o&ep1I~TZ!4?dy8(^a_yzg_=Fol;wTFk^=vof?zDwQj zkeX$Jdhy1wDSl-N>vK*``C{qEM%3Oec3d>dOxq46izma8WpXTDKmOXsdZsVWxolW@ zJaM;h2Iek*4CqX#w1P>{pe*k75UMB-nrELFtz&mB&kvg9!g6BCoPGE_o0ykyPu3yeC6j&cLswCx>lJejnJ{h1Hj#?{Ju+>fsE!MI_R_i|)_;~g)r!Rgua)H7CIxonU70uA$ z{sl`?#!`VjXDSTElf9O?pjj6+*<5H9S^JVsz~J45f<`bZ>OIl#tE8LpiQ*y6(O;ju zTojAAYGOC7nH0z#Fq>b!EXr3tuJ`KLm7T;#mJgESayyg;CANmdD;Qj%mM9#?Z++4% zPtc=E)ye-}Jdhj0f}TUtusr3V#gP~_YjZgM5>U zf_JN~;ClqkD3a!<8Q-R1*ljsA**{dI{Wq(p{*sM<^!*9E3JwT4wbPhA2)`9b| ztq;2&EzFZt$c-{Ni5;>=aCt=(ErL+S-6}U_YLUHR=eA`>FchJNwsq6(b{L!1O7M>r z>j!2A7Y(2FgPmc<@#j^%@nN~RhL!}`_Zn)WL38X#8lw5A^b?beBA$$<=atX%f}zua zSuH~bakM|Y=19ep<6HDo3)yQbIITEqW2ACQ6)c7STDe^O+cPw3yfYO6x{gxX1IADW+tYWqPOd8unh(0_G)!r;ud`N zEiMfb{(XWueZ?@uGXHab%`u_1eyP#OBshTCR<-1Fo$;1L9}_0*2a3$5M6+=i<+R_2 z3B2m2RZN#9Slh>@sRg#R@P7whJ~)y}&X-#>F? zG=gc;xgYqlk(I#Bsb#0J_3;*J0;>CH8S^BS^Ii?VUYMKL`~B2!9*Tt^lyb6G$fT?v zzm+veWv;m0l^Mcc3N??hI;{NiHN2PJh*38Im{pKe#Pi%3jH>{rE@dtG%Wvne?&C8a z<43vm0Q?0Jiz)DPF9u3CG1#=-h#}O?F`ni#8bfOwlEe92e?8A&Fwk{gUS8&xpU%4c zLC^Ns*r$9oA)ou|g<}VMd*CNr1^dsfMnwbIb3p3j|GMa&?#?DG>%gA?TMzK53ltfa zgfZS^oz_xlui2SFCnooQjhR;cs9}keN^>Y4uHMQzJXuy5i_nJ9aYGW5k(s$ENBZs^ z9Y!^{v^O+_czS1v@(ImXuB{o01yZNO+u;iYiFxPnZwU$dJ>LTb$)S<2kGu*VJ``@{ z0%hc>SRj1hc8suoIsQ-jkGf#mNW^TNU55ThU71hboJ3~$K`bLIjmZN|JXXhy2V-0V z)Nf1*OD6`KITrH2UJoLmFb*khh-AA$uv9{4fVim9hjMma<=#^qL$qv$LI? zocu3-7(EYbb+Svp)dDYXXJ;i`s;onGX%oZXm}u}b>FXKr-Rl9cErkW!oBwXv!ZFC& zqUw;Gy2NG5@yV4dzo`b=KQHvE&T&dueDs(Zx}%g|(3Z?Nrz_SaDlBdm|3dlVz8raI zKHfe$!)!3aS3kZNl)d+y#(m}51U6_lRS93Kk+b0XhE+1H2ft?|X z=$qkX`MqELf6t@yd1;3*L;Z7sb+tOJ&is-5`)Prvtskj8pB{bGEu(x*{>GtRFRtHa z2tEh{hj!p2pB4EX6^&0!yggRE@mu&R`w}_Z|IPVOn#wy`mHqaRZDeTpdOs)zo!DQ2X^Y)Lq{35F@h0U;)E z4;FdyUe^iR`(%`y)eQWT!iv=7Dck9R{csz)UiuN7bBhw;$Q75Eis>FRPL@oiT#@4o z8quY$5*%OZvgD=hsL&Rv2H9#HzE*Rx4NWbX<2T8leu;7!d0G8B?c+qmn)k|K4xPwH zULn9CVIViwnlNKJGg7o!E~}cLh+L0P;)7ud=5wG^Qh~ZYz5A@cs#?r|4IX!dLFJe4 zPfh!GcoBxGO$kFEnJ5=EW(RCA(auMfd0Zl$M`m;4ZH$SmWekXDZNNYR*8LZ9{cyXn z_h>dIG(+Ot>h^5YDAu66i&zikYbf_fRnE7z?g9 z_VO={FGVlY#|ZA)ANNd{AnW*X_xBF{ro`NhOwpqcQmGGl|G7#X(i-1EFCHm&Sl?ld zXkL_l$ucp?minuKmF%!|&^4-J(tTaEQEo$BzjSc}p~1ktjNcY^c7Vn{c$yRm-<0sI z`&R*09iRJ5t_6A1)zkB-XqDl( z`tv+-{3X!yOttG(mzA7?#>6ep92wqMZ5|B6eg8L}xpXkT-{^=h+B7k`(xP6Ud4zFv znDS#hPw9nGT%2cS*YhsR-B+R0riqCO5XS))=Feab8%HFAQvYs3^)%rtcM*%{zm|RB zr=d_HTE6ya)G-#I`@f*B&iGfmMjNW>cXxMpcY`ztf}qmfY;x1x z4bswG(t;x0a3=2=-}=c9#)iGtn)iJrjQlnBIz_j*!SF?M{XbgVriOq1;YApnOzPD5 zj#Zu5H$;gIvqs(W()zfe>KaqztEdmP^Lkwy(hlXx&BK}sTaFRD0u(UiUkEFn%l~A; z>wo9(Cj6AH7OG`)%fdcP|7`rwD5|;n6~+l30X^$Gb>hkgP~=tX7T-tO<=F{{_+d%kyjd+Q^BAY}8!9n^K0 zo15F)qi9@7{JM~s)w!nDT3x=>9Suj9PFnXF+d7fIW>w4Ly`92WA?&Zc>3$ON*WEJr zteqA3_`0n5_;%cbpNpPKH~)swXaBh9qOM$0a9j~bogs`u@n>=4-?9fL*H(*FU{WF#@cB2vf8rmmzhw_%bisrSlwctU zg4i=*eZ6Zj^zu5 zepUGST===^`D&y0Rj^z3mP>POE$CdAS_$u$a@;Je&BBOfd>Al(ko?&RW0aGVBMe6S z51lu^z)fukEBLz}(s`^^^}AY~oIK-4I>OTQUHoK;yS=`EFI+u_f7YLmI9*)Ti+&$P zw1K>N&8=#oF9h<$!?&j0^)O9Ox$oFwh3Y?fMbm@h{$DLgk)#b&HC!(Kt7Nb4ciIh> zYwPjvbTmD5qB5`HGSsTYUek6Pz=|u#g?!>OPelDNn!c0qfqw??aEng;Cy$ky^Wt|m zZ4RyQb$+30KAL%HseQpBIPNN3s)oXA<9Dr*yLm(u*s4)OhxUYgr5<>51^+(#gG%MV zUF|@4!O^p`GY`H`??6FQ?r3h|>o!DWpXDf8)cnWLVf568*L3yq?xpk;MnxT@Egix9 zI-~`Qd;C2g*&CLC3DtsaE2-ZB#=ihqu2Wd03E|@6+1Ah;h=S%xbw)yFL#5;iE)x80 zZntEus}(Mm9Hibw1a?hAJAzm}AS=xNv#A5+CDpCor#R$%xulbRNQdYd7UgQI*6Qkk zD;|6uLC;TMV`^3ajw*27KL$#@O%7sFCrY49w5oj5THK>T|4*@@IKz$ZA#I}!vQQv8 z%15F2tAuyW?%6q{ftQk%QXWD!@{jRb}Ad9z;f zEC2U*6WsCA6~%gIVbJevk);|oLSPuJ%XwsMY}7UmxCAnViU#1T-Fx#Jvbefx09Cq%Qc(Wuu^;kXzI(@{YkEMAL9u8ckSv8#s2i! za#f8c<$KHgjBPE6x-^V8b^N#}1o2Nor@P>knR}BWnBaGs1$XIFTn!29w6JoyK-xZ= zuhy7GzH#ylE~-IIKOX)iPI4`CC$g&%Az0T>o(Q&Z;NJmu!mg`^s(`=lIpDQIeK-#= zYQ!iQ602x9d3M7!Pj}%3Dr=TXEua6dwRrLJN$28r0@4Y{)4}o|C2h};ZK`SDdB`{z zt-B(2#iUbWN0(&!+kxh0HZv!uz}7+(g9;YI=`YtJWLRn1QR4M>PhRyfOSWaBX{+*b zXj5PY4q!VP7MdD$=UBOLWEERq1yP-AU$c59)F5d7k*~JhBnW>+CiKM$j;>#1KFsTI zmEh;cpDU7zDQZH_7b|WD@!@h#2Cdl1Fd+dtnoTf}5vmpJdxlU!q`4bLvP&)TOZnW z@?-|IPq-=jltydeGzr5t9O(+wn=PO4 z<|!C&91S#D9!T9Nd2chXQ`1tU*x0IUb+Xj^T)*0o$dpQ?RHR_>H&U+lLgEJ#CWP9b zMg=sCY`!Opl>&r6;K$%=U)P&jTO;Cetm?P@pBA8%N7UqVs#sY+M_hC^}5(gO62 zK#PghR&h1e?|d~fo$+RFd9+{b589jLe9dP1{Rit{=UZ|B1vQP}P1xN0xoc<$$T@Wk z4d+q`&0UjwFvB-LtU;~ECY#VC5#CNx;a7i4Gb^my0jtPtoEj|;WeAF+V!ahA3i~(X5v=$a9u;JkRa0RBWs`NvE#!?)x(Pe1%Q$u z%Bu-<*}Y&K(v|ywU$j86(@G>=f#6!cOJE+3B39H{nqsyNr^~J+O?VLfWbZrE;`y(H ztJ3Yu!w@s2wknr=xh+|tg$|bbmqKgH32#po$fl&WTQZ|=_!74Xi%`aRa|70&S}UO} z8-*2Rsf=Gq^nDig6~P*Rue5$o-AOwef6?GsLyqY!UBuId)nFOEnhVs~uAe5V@${*k zc$bRZ>IZ14wKi|zvsSjXny;nHmiLnO2=)6PsHTfXwD(D#9Gp&Cxz8}d^OtvtEi9kR z2D?+3Fx@8tIfX@sPFl5ib(n8Ad7Esu)T~F^#86>=K_Tts7b{JJ3v8GBJ*sc}OGEc#1 z!1(ZORxKh~ilyjt)0BBpMUsA+@8l8$L5M$1VUH;4yGJ+wlYZBwe$M^sz6hgO{RJSe z$sVW3N(T+XuGC-$!=#Ark8jzXM?0l~K;nDSTr;V%AtuD@gWLu~1+s`ZKQAwE7*W3a z2<9Oc{O&Scd8dLBdzvZ}t(M4x!_{6>riGS33-k`gL)zh2RB0s+rpMEVZk#9R$+>c> z+%csVgz0>fQW3hxbcdY^2(+5oeg(0&_J8$S*+!3M_lFk0*t&RDf7pRlm>Wx0pgga%6=KyznRYfJvSLlwh&|Koy{gGi30%cd;Y zIT%mz5l?kmnHu|H8YImE| z4#=u)JLxRPy95H)oSS|c@SZ;>J%9U)s5|2WSzT?~No}XncV^Rf>WHaCl2>}RA&K%- z-oMpiODN)|CB?Xn9g|{9k~+dCXs4kIZv*(*)nfDKGcuVD)=j6sU06+1C_=1@1QswL zdMy{8O1KJVH#n?QT}@5JkivE80XW5)Pmhl&LANQOaVJW+Z}fE)LWVg0&dj{xz3kr! zFUE$^G&Up*8zIoAInKGeCps1U0TR}?<{2bhNonLL*-^)Meji zC!gEg8t0NF^IIqMd!Gl}r%=3`&3FcisFBloXRbVZbgQkU0#0v?K7?p0&Eo$J5k-mSVadP#0V10r`>zd+|`K{qp8u&h`(mnuEWv-bPEBptkF|B2~ z?V>$bA%5Bon&Xj~W}c^#ZbZ~-F^d{TGn*g@pS^TzUu=>*e8Y5b3ZTcm>Pj0yr~Qxi zfA}|UC%_?SEp$#$EeymhG@+H^$jC&9L-Q^uWFBV3T-q!#Qgw?m@0lCY{MmN`Xmk|h z(zO~#Hr2(bcu1P*XlQ6ypgmL|i$T}eIPz_FBHyT}m0-~sj`>jCXrGqmov<`v$roJEY01-3e<`+4bmF#ZtQcz=Md=c zWbLw-&k1-(|9hIg*HJH%=Vw~$KL6;3W6H=957)w^BavZ-guMAHLz4{>LC=L*Gxb%` zR9~9$V5N~CP)>hZT~38G{zC>gl=S<5Y)Ym)@#c(zX$s%-W#Wh%6M-Qh z2=p;K{F**Z5KNzkf&9GDWv|vrp`Dwb2=n5V5a;iU5#E=9<3Bk(q&x1>hU%^|#sl>02`dyc^7suhMSqwL9|hWB=aEhHBc#Cc*md*!L^z zap`24h9@#(LWDj_VNBIzpy~NqZ8D`Lq$uT${yQWdrF>l(V?Rb449$-}Q|HTV_$t!p z#Vgi38^>GIqkMV)xN+aH0XpW8s(E;Le9p(YpU*x#pMeBu5Rz*#tw=h}dm!Hgzl}kY z@-sYAkM%pR<#Ij19n_P*?p-mn=hy17u^+$zo`1ya6Dh>w7p3&5-Omn~c@p2$dcJSDvj1 zdw^iKjQWgKu8>4!)*>o}|JBtgXnX%p3cc1~2*JV{?=W724~QKXCKe5bLN z>DV{hk-p9m!Rt0}6KLc&VJE{&&azgyWO$@HDwH!FA>fUAIKS2hoq-C})eXm6kC>;- zrHp5K5Tqu?Tc;TbDt?({`ygy+o0h)H5ayG(RN+uSc}vaPJHe0h4C3ZZu*Yl#RWRzx z7QXaNKD{(pgEqWSv&T7Y_lpdGG;U=X;iZ2VxU_Ae*w)|g%u z(*lByh=1Q3Q3}#DHOE)7MygucG^mEiFnJLY6cH96z9zPJK&aTB)k=DPS{pwMqn_gxL`s#wiqm7MG>!LvNm9-2Per3Hv(Ld zbxRIl8{;AVdvbz-@ES(JW?i!!WgT0jW?(=v*!ZGJ)7)5ZPu#6!fC<$_wyXF0KOrRk z*A~hHm6T=v7+jCnFT{SU_enPW+cuNP z_~>2H%E@N0*;27iCJHfo!~CtTN?p?%`TFclo{k|NW>&Fs+B_)C*C&tb zCnO{!0WX|0(87+q`3DHQyT?uvhg?ijV&cW}j(@!4(j(T#{c6%N}X+)u7F^Hda&4rS!aa57t?=7x>p*-5|q;1uXKh-W9~N%wN6V1$7FT zKq+dsd+roE9Z4#56pW0-KR&YM@Fz(d5~Q@mjH;w67%;mk^P`RhbXV>>KkYdSJwKcS zq87;DF#u))Ru+@p>@wmi0C;YkU?&XlY3+{^yM1OAgqLKWlbOiYoi*DMuL@wn>)gY-^OLvv`YWI<4Rd$OtU^ zU82gU(8_$rvTW=|(Q>-YMgleQ%_1wmJ~_x4TzzK}xRGCKknNgTWPam!WdnS*#Gvx- zdi^8W8-x~2@_(j|j!eU%e%!H7;>byH!4CT;zY9k8q#vI|iKZM%SI_kq6AyZ~U*~^f zl$swV8&l!3EIT`x-AXvc8M#e9q-q&=J5kG&sbP_X9$;FPs!7dRQ%RkppEGo$W`5Ox z&hwx(#POSYM@{B!8e)Pb1w=ApcSHA8@~bO7mim#)9JK(S5LLtSe%7aaFpFI+0c83ms)gi{ zCU60O(k3i0H8Q^G%Q2~cg6+uLSm@T&*pk|C#H=cuI!!7l&dZK<*{ImB?dn{ZBx~o5 zmTp*b(kb^+GK2dM75Khih2AX|bp;Z1&q1Wd6dN3{Yr_uQROko_8l7#zo8Ab0_SS!@ zB5aBq&8I3E-Wr7)UcDIU;FjND)1F<{oOZHFE*6HrTtxZM4ioSfe6Sb(2`s!Ig$3}& z%lh9H%^cP@%%5C?#sMAvRU;R=>K-!;a$yt+V%mn& zl^&8lGU|jkdoI$_()EV|yu6~zoC9H0pnU{kB3?cCVf$6}VzKRDg3=;eZdL(1RLLY{ zuOLc4lxODEG#w;YlWZj!RK!w{QxU(9o>mv8$t)eEeOGryPFG)J zp&Z(7shkn4-QpHZm2{~x|FvFp2RphTD@E^wv78$<{b!#}YVIBuEr)~C(8v|lv$p!Q zPQ}^m!fqB>#b~j(a#}4#df(zWl`F7g?N5;G_yk_e=>awa-XK-j5q389iaZV zT_4kD|B=p6fMcBNltPea)<+Xlc@2xxAN0iPx5B9?U|Y`;ePn6F5=*f95w`9{bADhs zS2;VogK+lf@;ih7jXqAG&ZDI7zf&U>8clS!VS!(t#ki#eofsdp#89Vo6ku&1BS!ZB z2&P(%#6aXDe3m|!1?k#BFK`(@e1H!qO>6L8yo}Jtr7S+v!Kbeoox7a!)86auL4++7wSZ?rp04<5J=kN&DfP7awWs8R`g1nUf)56<79+TC< zyu|+h8NIrB?fjm1*~YjFR0cAC`0#CLyDH$1eO1>J-})QkD*X6@VXP5J8FifVbG4c- z(`Mhl#mt3AWkosO+0~GDnqv5N=EmsZ&}@yLOwuj7e+o_JZ7gN44q@+c(q%^t`FlN5 zE54iYCjTXj@a%{rrq@r4z725-UfLZm?Hi4y%~OUP>7nNE=35B_z+NM0k1wsFZZ_)t zgH{g5%H7-mp9BD`pMM)amhbNF@_YYnzxnkA9CDVHkc|@xM?7t;4UB$d zoXVH1?|5^uGI4Hbc+@~RfQxap{69t;Bu@9qctUxR*E>D^i&pp0AhX8qK4r z&P(ZtoD0?uD?MjINIu?*&nIYR=!DitK_3tCjBT6mT51CJnjwyli zqo|Jmw#8g6N+VJfqfCP_Ure@y{bh^|(*WCX?2aWk{L`AkjJBc207u?EllQBzA#xA1 zlRSvbKQ)(ZKxje6cNf?^?nr`v{d5Mv=Hq?gXWy@QU=sS@APx|L^w)+JP$)3da_Y0% z!*`Gz*Uo;FbX8CfuzM7jsXU4v$Fw`h&Uq7Y_|e9ht_I)#?GH9!*|~|CMNGTLSbrWI z9PGOHenvM0O=Y*v&wsiCwuv@$^z@e3*QJy*Ea@@$5%PXD+6jeOx>HRH3VZz&iDmO) zbwykm@zAeceSM@gCL;1B(#^Mc0MYeIZPsknoo_n%c(gWLNmfqEciE~JSKiR&xA_Pi z-4R(^1n;rwjNY9%aLzX0$_D>@J=HF%%2}!keQYKVw%A;bvYLgn*CrS&{yo53ljOBCfy z?MbTh(cmQH+cP_x>j#KbTJ9K0TE(YV&I%d75L(;YV|b(tZ1ggxC6&LqR~VFjP&{O8 zONl?t=nE#z82!(&qq+HJhemiwk0PQ01k?ccH(=QREOY)V_UPji6ciK^0%}yC z@#1ou2b=cQl~>osicuM|ya-EXoe{H`4_E=0vSVWa$Q>_QQmUs5qAZs*^&a8;7v@PT;9H zVtVqO54jleE0FlvjIgmEUu+H`K-OIj8?CYrs7T8qe#*|MD9Vv07aY0<>P$!Ti zvzxA2&Cn=$e=N&{p6wxOkdO@oXfV6PO!Y_Vl)_aYmvEVD%u#I}9Ur3xpdWDw?9ryG zWKn#_hlJr~wT@HMOkG(ps-6j5oa9-L<$bm!Odfih@f(PVfTK#t=ies9Ph{i&c+6vL zfAb~)u(C3vG0Q1BA>FM^5(b6Uz!HNhK=upQfFJ4tOO)1GDDDAk&KfEscWO)$t~r_B zA`Z1X*OdQSGOzx05Pe*+>b_RAl+s2vi6kO9k{ zfa6QQky?!@D)$*)`VWdfmjrZBTc*ZF(dCH5W=;=>=X&v{xM&%gaK?65s;f_!2P;Ks z_L@Gal+Dbje-D29rSQgz5Vo*u3s}O>CxyEj8xe$GU1$K&KkX~VS}Yae13f!4uEGnc z>@qv<1SxFYsZ%3{iSi*`YI^GFaS{5g>7-1YKL7L6p$&>|($z?iQUWw~#L;@%|ImD) zjLgjI;2*O$o&f?Qz_eA>el`M9St6fGp#MCJLWe>^^!$CM23$)2&2shBqPfNzCjIAt z{8g?hhWSnC<$qEE4W})TQ7VitgpLDYJaBXGn&eW~*Wv2ohwb}hs0J7UbV?sBGecoT z6olo~+J*juYR^3`C3kqD;f=&aRAe3(*~^vJE+;{U$}ReC64A&5L!#19U(Jqegu>%U zv2FxBF`Mt7<^>N4h_7FKbRnjN&<_6)Fl%-LZ!AEP%_#@n%@_pwWU@Bz&TXOw7h^ob zq()I8|79G}7O(X=uBCqEjH1b$CZh2u9-yFxNpHRQ+f=ycn|Okci%W3Oz`g%|mN$^g zp*BI8V_WE$$LX^oo39Hep@|9ydNciFdwqM(63{d_(JUGYc~@;Vf0Ztv7UqC7VwC-p zFukmGl*gyN{cw9Z@FDOtN!v)Yv-|1k=_M@n1w{Y=%mzR;=JS9w*MXBTRsr_S>t!Ip z1dYuN4SO9YwJJ4kypi;!I&_}P5e#V`KFYSFpP*YEbncyQ;pJpzg3M$@3{qg10|&l8 zXuwk6nb5niF!bE@Z5ko3rNr9*AuoGl`0I+=$v|rMB)VggwA9cmc#o>qnX3p_&Wm~~ z**%+$tC@pSX8W6(qz#jClv~ldN--6Vr~MUPfKe^;2itGNQ8qRyU%eCEKtJwxh! zffh(IciCjESIcg1wY%K4i>2Gv0O+RxW>KJ7?fWLe;9pVozpJ96$A$crcg256a^~rr z<@|4il9>bXgtDZ`2Mg)_97!q%4MW@FWt_X=ysIs!5{ut_nXT=az}}daQ3z1Ze;?7h zNFJpCArZ=QQcN*@Y#E8eKY6_^kG?;i|FwksNmz{xkMk= zCpj1`OWlSlD=$n938Zzbu9vbB{O)go&0M2DBgM@CaU(2D!oOqoxy!d3K={&UD62zg zsrj4W^fD6U0trZ846Y0oGd-roz7)acAHpUh5I)X#2Mo4wC4bL_P za>%k_ZKqh<;rHHnaE$6s3!#{hqDr%}v(?phV4@<7yvuO@{z1OJ72r=m#rV9p@sMFu z#ZCGxgu=MP50{2+a%Q?9Srm`OM-txN5Z^_x7aA>M*y08+aam|X(Al%=_tf)FPG3%mSrQkFSwJGP_bK!e)Hrm*!w2fV|>1Fc9eVN^gaGOzEvq<(sH zYTkTJgV0o6{SSnRt7_{IYV3>a*x|*nsgK<2>j)JS*7tYq5$Wv)LtX1UOMx16 z8-nxZv;zzd@Yl!#Dp5VQmL^}9cQF?w4U~B%_rCAZ#QS+F9{ub_Ki{d9gLt?ryhcf+ zK<-Ixf=_A1Ox=gkF?{$sZ~D)e?QFz2r5}JO=k%q>%TQCcH$TP>kLyxJ)Lc1!ZBlAm zLne}CS$Q>s>Dci;GM$+Q#v;Jg3Pbt}tdc{fF z>DgHf!lNsC8eF51;K0Yu}Lj+_71YTt$bOd)J-+M)f z0zNNm?9z>)B@mM(Mba81Q6nI?E=4&bOHf7a#84_%@}|ifIA`+YNA?_Kiy-7TCFvBy zM8@7Vn+e|zD?d$~JWPNkAB_*x2MP&2{q^p;f5~t8`0*q7`Yc6^7F?$Ky}62eRwy2$ zFN5O;ZU#MuYr02~*wHo%jFh|bD4}Wkv4^tyky~`h^A>EPW{<%0oXgO_$g-O| z9vG+9rB|F51;?t}$&+VVhu@^fm&8ELMhi*N`q(t86h|N!XQx|tJ&`TLiiuU<;HWU( z>?pUiwwP+*YeD#5`B>*pm96S>QdyqD`}^7(bWZ)*A1K()WlQSsFR4e^SwrRpmdiZy z93U%fj@dRDGP$}rB=6T5L4E}^tUo4EV9*%zelOEsglgzEwn|ZtJjycoJusCbe5zR+e14b`13I8{6 zdMj^iQ1yxai0Sjd(`)xWAmO=WG5((x0QK+q(A<^iv_GNi-@|J=I?xQ3 z-gg@f&OvY2KZR2+T zm(H5Wso{0R-AB%Ih()!+x)#J%5y7oN1XJg3^(>sGaCLo6@a}SI0U!kv6X z{P;TGt#N6&Aey{ud~(J}Zv#K=rU!deN%$&Qc@P$WAaoE=0!Hm=Tkz4{jP^ zRtZ_riSs$R-LIXWNBuY!5|?}?7 z_`xszHxUZ-UOPW%I94rF958bK=+Ud&Pmc8)=A9B7&@RPOB+e=xIF&r|`k@l}{ED`* zV3ZwAw}s&0bES>Re2M?L_}-MGRLaUp(U3u;eCKm7JIWqO<7Fxo`X$q0KOt6KPB|az zpA!kW$L`UN0)=?GoB(_kJHSxa+EN5UftL!%dcbaARHaRrPJJtIA3m*_7hW|l038JM#QHHx1ez!gM_uUehETS;k_O@_ z@zM2v#EoLVE!6*v4r3LNwz`S&9_`VLkaQIy+qGE1b=MZ9kr`$pzpLnj#{6{GNJ_%v zNu87|E0L2KjkukEPV7@?;Iqnlb&4d7V&PwHrz-P#yo~d~f~P!CtC-N^y1Pq_yGJ~I zC`3rb>IC*8nqUmfAout87sUs6dWMEzz3FVC;Joanii!8Yb(b2*}3jD zb1cL+Fb#&R3gK;Lgy>yZyRpZ(`mZQMJ{txY!&3roX;`6ST9gpkt!*1&+hZ91AV&(S zir_kqUPP-NsRyO5E`Ph)%FS0H!_OXkbD?-$W}cp&Ech&Ub)J;C^vZb}Vw)#Hd)9$_ zAiM#rZvgK$2J91dXiZqv7lD%ERMOhgStSP4(c#(%NnUirR{V^dfD#(U!i z1C+IL%9`(_j1*Cc-RKAU@X_AT6ID>hV%zIa68rCqo9osN%+-bD&VdT6mYIfmE^h8u z4SEb2S<2e=nVj8&|IPHxiLJ`jp{`&m?5s*MWGG{BDe}m`0ZqDMgDog023;F2JcS#k z<)MFOe+|j`o)gkO&k22`|0mzaxMHNas^>QIS+h7oiClP2%iwVnMY2UN!u?PW$@_~y z|5-irex)I1xK{5pX2eR#lillMy&ak&x9EcHX|;|qO15OTH0S)cZ%W_Nnau^snL{nK zl072?(Y5$e7?PFE5Cn>mKp1NMWqz+-KrZS|{)#L1>mIncHviM(d^+TWY1EGF-_CP- zeIodyFeh*{O@VNPECuj$wRDoX$2&`VaZ!qrZ?gFpk^hDK!W=agO-=oeTH`TS?Y!=1 zAS9Cyur4nVO-WV$MQ-gq?#L$u#YxGEdqo!)hw9DdLVg!EUnjSfHy2)@3(()w*jS`w zm#Gb*U7V<`6|YuX&w58`(e2Yl1>uHoN$Ydmr*{7YWtw&FrlE3F35g+o?P9Ok1joNC z-;_>$n19ou*R?yJA}%^ARE()3d&aaha`W-hU4ig(r~&=@PGYY^@DE>AvrjEM^tuY1 z6z$6%Vmkq*4@hzfHDV1e%sbyIV-gg@uatX!vU0+d?*fV4q zm)p*&fh=vR0IQlodat74<;WW~egY!rGXR2qc;4-LSlf6cISv>n%%OrC&=Rvc^g!CdS5AgBbKHv7OcWNZNWkLO^6{G4 zcVCT6NeP10r<$RZHx0u)glXy?$Hk=2! z5tvEbu;kfRv0_>e!?~cjdHH+&%QebRA?zGkCiPB;muG_p;>caL(JCi#;DBN9}CXh!l zM34@@KP=fD(|pmE`^!hg#)7*Ib7Zl=$f9D%Jr?ZfekxC@hUiHHo0lgBkm7E}`q!pDK^;7D-F#6}3+bxP%m;Adzyupi?nyP8U!B&p$RR}H`YHj3bk$P0v zk%dlJ{+PqpDMUI??XRhl+q)hMv>JFpaaa3xW%2Pl7sc9SRQw*ZIx5zqR5_}pnzQ!@ ziJ=kRRC4j}Jv5nhDt^@IGpHR8gENPa-dZU|4s9MkKYm$VPd()dUiS=wWuQCOh#G^F zpwxQD04iLl0j|L&%R(}^{@H7eq7>R$YkVNqpm4p+oIy)O>8LGxeU6%;?$~)r!l*O` zRiEp(lZnTKv`742Q1?3FQkE#F={J=R6{`8wV;d^#@Ze~I53KUvF!JFBi zd16UFn0lERErR!b{1&kzr|~FwQ}2Gb7}wgss_W=8W>H7e3zewRWf&yW>Ks)^b3Y?@ zinq2;9f*(|{TpaAWN$?Rb{W`!o z3n~#`KD@$rkdFGv@zXN=LE5JTRqGBbTxC^ZCO@CYmcGqXZF_1x%Pka|HDEcj2m^=* zF#8{ZnuC*#oN+6#zrvNWpUkl}{Lw4LEpp1ZyxAfExB~MgLaE#L{G^g;sLwQrRgF&w zWeCj<`Gj5>n4rN=(h*2&jb-4`9qp6#(gjtZhl_2lkBa081R?JAG#y6HK*ycr{a%90 z=;vLLW|X#<-(h8t6isOR!UIkrp5XV*k$N?jn%NTk&5Q1 z4575hy>*LB+9nH<)umNj?s(x(f8SywK1%Gru;{(}Vq8 z$lN6nId_iRDQ5CxFZl-{Cc;0F5jR#7Y!FRTBCK(<>WQA7_pPxFd^^FFzzQnuk`%bs z?D{%XlzJp%E4b)YqVYVXjdvVR!SX{CFs$;Z3YaSg|kK$m-454unM7U!m zy^taP&yPSOrg}9-sO#bCL33oejMh?$W911cxsQM=p_J0bby5=UF$h@F%8I)kwe8ja^(z>89^P@jB=Q^P59b~ z-XxSI)O#=jTYDM?M5aykB{%8d+<5ud+NzcQY_411&TBirYwU zNRow0G>tNWEd3|PfzeSlK3q%=O`}!UvSY#0*pltD$HbgsL~#Wb4duQ_QyUInVqpf` zz$m?J86*ZSkyVt=l$|?Y%kr4Au(DXH6RPC$XWQncG+AGwUKJKXUL+gOzR-IU?|Y|X zoID~SZ}lNdJjO0@SfETwnVZP{#}sF>L(J_{iy@yM(f9L=7P;HDS)*!=q~EJz!nud1 zXgUhp?OMAMma%z<;d>?Qgt6UQfMR63`weKYm-2|$rwG97sqE0b*R19ITQYLwoNSS9+^;)4w9d zOWrdIRIAxmp><7QjLy24Mc1G0zOy6Yps!|DXBPbSYI(!s%^unaFo**D6WkJj5C>0d zm-h*&_T1p0l&+vjPWreN`01{NQOceR4+lgR<=jF1Gc;N;sFK+ndK=wUDG}UX&1TFc zY7cTHw|ct%Fc{yC03rbx2Y`wUWUfgSsQLx~lLR>3Iy*a!NLyRvP5q*QR-&Ph^9yNC~NOwfws@DTTgVx)MejIAL>#+ z?FdL)Cy8~xhqbVCqWM1aX9JX20<8> zh`9yJEj=sZ$4CFucCV6|uvMFxJ7-g0ym?HoRbWGz^Oy5e`$W-hC}Q@@tSE^;xkD}S z_KS@@ydO>;twJEqUkTwD?Y^gPVPUR_iM4i|R#hTm68GI@#`+%6ZV(}qrjR-}P1Oz` z-_X&a$QBC!bI~K@8!7Vwz=D7)0T?NTL(4CYfUyP$r8|tivFU%h;HJ{`;Hi9rd=KJGa&vo-j&?;f$>Ah;=K@ioEU4`}t~gpJ_QM>%!zu*1z5j z)cuHNYKT6Jnkk$0O8&9h+7ePCqRfu057+w-6rhthGhbzbHzr4Nt755YVmh+7V+*6= z>CspLpDTwwlIHlDr-gUgUws+@nhRds&%QrXKY69(hE2&r-XI8JV&yleHNa{%d4Htw zi?Ca)+!YmVo^7?c znGO}R%6oW(Xo8Jm2cB56il=K!W|dCawpqjb_DVrd<-cry=Dec3i$4i_^L}M=e3hgz zMW4e~+jsF(b(!$WqD*?`<5VkG0v@6Cw;i6>Lo>g@5U7=7eZ9;l)-5;NZ6bktOjNMy z{hf2OX$Rg!*4s5JMi>f z&?)#1fcdGa<7%1zq+Q%@6cn>8%+ITAy)C=%rxB`YYqQUYvi+duT}6{fGKAAL!(gyN zY@nPunn?URHHd?7+^Vj}#03!AFSBRC3pTGvjSazSk{PaETdyQtr-@^m{X@^q>=QJZ z`%8hlhYjKV9|t<3*;kxaCkexF4t$GvZi^+yxayO8PL>uLx!PS9@?EofKx@5ydINk7 zFXHpQNDSUf$#%^B$b{jYo15m@o>O}ke6ThG*1Mi6YR^lysx8q#YUqbjb7J`z*@DZ0 zdQ|vsu$S!D+lJcOvzOc;Fxr4g1N=&$-`{xH!Kq0gQ{y269=wgv|_@$iCUuE|b-A0B6xV}#NNa_}D+cZS+B ztpa}zv|aHjD@5YZXlfu&bF#o7Aw1IqR;2l@H!_l>pWb1RdNDNDmoyU65=H`H z`D)TCEe=zjaLv(D3ni?P?OTg1aX)Bns6R~{(yz2}>tc$}PlQ;QR&e1VJwkM2gmCPL zR+$mGjx0V}T3UK~;wr9Vmj@iJRZvn|<&lfO0 zEW^M63qdAtBMTFCERI7hZ>I)e0h9&{Pt$$Fg|@-K4ZeI(9B_+NUR(8&0tsL)#$&b3 zB0mv+Q*|D7J~jJTrOl+~GICh1^$))KR^2&~+O6x`J$x0(L}*1~ znS*f}f;{ZfvW*{p=Q?PLz%9D!fk#N>lZsC zB!ks5R5HI;YgV!Tl-7)uu*v44PSx6GMp)_K>$z#TKRKRpdrto6&BIE~AK+na;_rfD zY&C-9u+2nPK5e<^fL-BXZS(*X{tQ*^ZjX1K57WR<=i>73Me;o;zt-w$9}o}#RJDj$ zK$G;L{ht`{Br1MHS&{H`RrU2OYj?FyNl5|Kf#aKG_rGs%c?}j%IWxvp>dkS`lq*4E zJ-&{x|IJ&67`BG_A6iTX@y$8g-dj?^p%p$#z3+tmVMa+OW)YH=_PN#-kXgOw7_=)l z@y_^9$t&0unpp)~VzFAl^OVtbn*o}s2t|U`!Rh!6C<^_~l?-m@#(A)C@7wc%#AKAdnr)_J_((_U?O&I zKOGEuta`=`|Gd)l5?{LF69;xzl}foBt_&<1dTp#CEQ`Z4;}2*P3Q7=}@OU=8)X!;( zP^F24g)r&F7C5VFwN~5%SgtB3dm<=#Q;24M0##v_f4AFv?fIX&{M5C{_rZQ}`1dhk zC{h!z8AZBG*@+vZIio^`_0_cFRp$|uY(>@C@ETO>`zZ2Q)&8+Osx(Lr&$5`K6MyU; zj}z?Q6O~oIa+T|J(sL`rTS+z6yI@ca9pR^jIg?hg$1>Q|7aJI~5LvVC=2gov#~JF5 zSL3K4X^6|)EKo2?y?Yg>C;9KCws!o;^{W$6m zC1BMOGt4+?m@=r+Ge6_5PAdA6`sGt!7mwlT&(J)Zu}qC9`2P3oZZu#PmN z*;MyGf{3L3POBKZhG6L=!MuF= z`iV)VX%~(ft5+dk7>WjV!&;h~k#c4#`SJ{}0984%NNjjsoe3>Dr$GN%Cu>GOQ-prf=<{6aB}kiVPA zj8>smyUhIYb_s(zqt@{28b?(Aoim55#9=MH^4NPs&qn^Z|7`ziMA+mqHx%lj5OaTJ za(*R;b5NifzDX(PGJZkE70o58RlaII2OCcWb)sn0Paic+k@q~3nI03A7H%Gna!7O{ zA`JQ|P~ia&GW1on6HLq+4yM8-IExf8&Cv7plCmJB=+qUKl6Ps7{s>Ti;?6~rt|!nS zaiqV|3R)w;gbGr3VPe&U>)YDypR2u{KBQOL`UaJ^H5&hED{s@PO3Q9wqbG1NK_#Fm z!1^ruR^mskc~7nz@*sX# za~{mp0Y*7I02KE zp+aR>|FbEi^tEZSqSbv`%z*~w2m2m@r*XHO#tn@R1TD?~Lxc-x6p-iGqG4@Ls{em9on=&1@B8(? zDj_K)DJ9)7l(a~94lzS_OCzn6v@mqn&$(@T}n$T5(0ue$KQWFywDde)|z#k zbKh6&{n_x%)Zr?gX*+5oc`ZwfRg%%wwNA-gl3zJ)e*zk#GxT7!Jd-O2=wRW{YTlBf z8FaJuiB(?Jqg2Fl_rS+lC!qtKtCzl`fUOx3*#}))L@8oEIFgF|pz+sK$?TgBkhQBhtP0{TPLU?zSvs0e zr80T1pWxP*kh&C0@+?{DuoHOpoP!hi!G}T!!Bs05d7MH*rOFYP73658aPs^>E40mt z4CF6!_fu|<&;J><)O~0b7V(Q%JkKxAm!S03(&$t09dTpX zzK{>Ei}9>ccIjhi-eYNb_{;y4s%W1v(VgZJBt@^=S);=4<&P8zaa4ko36*n_^SsK^ zcVL#Pw`>Dy33TcMEIi3e^{-s8t;LqJUt;j=>Qr`uD4cqE#SySX*(t_ZEKrL0*W~VE zSY{bdO+UL8(N9@MSR{8skg^!3;Gk06eS@Y_AxKEMrR|`yAGXdA>C24Ar zMfLV@{3@%YI9dKIwIrB2V1H)ci?ea7F)dB~mY@rF`clEF%(y+jc_{4c+{m-;P~^hv z`OK1t+0w*IboRtK>n|cU@`zC*{e(y$3galKcNvSe$-mOKM9fh{ecTFzfMP)|!?8&6 zIQ?OG8GQH_V|lTAV*i{k_&^Ql@=80ZVO?Q}(1+il4~78k;vZ;-{Agff0QWlVhgzsX zVYz=fM5|mduI0vC;u2PsxN^g#UT=onDE<3uX9tci1lTB-WRv_VpJ|u-W3l9vn{^)C z-1yrDO-kSPVXO+38sCdN&np|<_L+O;FkAC5uMMHIZX?O#t zJDzYS&8&RFUttQ)*yiTub!R~2h2KWN5#r%S=Ak^~Hy|TQ5-`Ynl(uPFU_(ac5UX%X zZE#AojYI~eUQR(ktJ@khpz0*pqg5-62p9EA_@~>y0K^TrV0ZQOE|P#)UcR7BJfL=% zN3sz6!6nqtD`aMiB>_Vr$)$2fGC%G-{=XJr#Z3a`Mxe#IqCa0aiL1r|9;E6i zN#VAI=~~g~!^GnfFF;+H~T;%Vl<|1wTm$5BS4vG?3C=&Snf^9SuwodfZ^46y%Q$w#a93^RCi;r=DR45z23Q#>OUlsxVA7XO zOK*=jYDIUY``-2he11i7bt6nvD+QMh+BCSdycntBd46D;G71nqRmB(JrYH2zUIl9e zbJ!BYxa=3MB_%S?jYbPMM2Fpu-y&+Qds5yYlM(%MEauH<=NnPhK7qx<1GMPcMRMK| ziL7^}=2KIalQ?4a^o_JRO6dvm03%Vg5^hZ19J>^YT;F5$?PB6h@6{D!B^=_hroy;4Zh)H?4y$=84dJR))uMVD5Nw(&J_S|>b!QHg zd(Oo4)^|1fMy*hzB~>6g$?EE{w7AVCP#Uo?77(i6Gfv~tx?nt?B74Mt#Wuk)u&Iw5 z9egU})d{t==uFmt9;ZMYF)BUQd8Y_XnBagV<8LlnAvKfFEA^hk`7Q!Ke6nx2nR;^PY?*=wi-QQ$=ptYU1r(dQ zC&ML&fTw7(KqeIEfe*Q@-P(PQcCfk0vv$ei2< zn#X__huBpkx8K5_9ex>+k`qd8dy10Dl$AZ<`LzlgidqvNety$vlcY|J`px!mcH-Wl zD(@TXpb~dC^g2l#C$^K71%40_`IE{@y!U#RENcD)C?CGwNQ9QV*a9#65&8!#!`pw1J$if~wpf-4^zFi-sC3#`f&9Cd6Tuw#M=K=ar)p9*^UMc zUqH2%Ws$>w>Gw7?+CzvOT?Y@!8=vE8rVpcCpi7GMjAHC0qt8O_+M1?jgy&_eX1`K( zDEy1K#j4!3{3|i#XFliTf>L%!Ti$Z84JM27=46TP77Bda;Tfn|r=JOF%3I7fO(sZR z`aWaQSlq1itZW5tkl?TeMW3D!^D|n$_IkR_ltO1)EVJ_QY>i@&IUrAm11V7Up~Nvy zG51wA&rDOM)(8BU`3|ZXn@Q_ImU2V{OM024nDy7n%vQ;ES2iuqcH}OD^4WOz4?&}B7NfV(wqod6jG>nWpY&k)2?LFiuTo&7fh_# zEzq5w>_wdzaYTsH#n3$hhue8M`lHr_Kn>GwQp7l6Xke0Hemj%#@0JRft*XG|zeSn< zK~?dLH}caL=s(4cPtnx~1ST*a^ybR8*X@(au`4+$pn5g>I=qN`bgoTU2=vyA@ z6{P(nZZaUh2C&-IM1$~Nf8Q_7PTPNkTvnU^OQ?~Qtcl>G$)6I_G9XiwwND-o zL-A;k5V(-`yVP_ap;b~P^b(Q}Q?b+3gUswXg2FLLh|u~~*nA7jMdAcY zm~xtUBGbsLlt-nbCiQfqv%RyEr=mhwVn}rnR()Q*1CL2>Uksdx*|d(FIQeKO~;7`8O~ zEKyG*xL(qqN3?UCk+E-Dy;1&-j5E2B`}Qo$LY4W;95s9K(1fv|z)sMcRIiexS*p)Q zk_Y#>dG4cw8cb|~XZY%479T3r8pisZn-YwQmeR9riejG{bmgi|UE!`VX!MbVV&uHi zpV%Zivebz>7jd)!3;L%JW8a?)Ko83H#VIqX_G^rq5 zMO-3YLC3PANStgc$J&IBHs$MD3ZmJ)Jv?-TE!UTAB#9(A{a zDlegKn)XmV5$)l@Z^qVwe_Sr`CqYgMBvvcRw-NG=T9uQPfv$)Mr$uq^3(6JBS2B}i z(<+jCiNI1)27rv6Z3m!kg8uek(*wG^pY;9vEMP%nrY6E~MqIyNt2Hb}!VKcUA0hgs zYL(Y@!h==PlimrgD~#UKRV&$t7eMpQo>S(DSvl7Z)Kt@__iPk*P|a@D;O!yr+zT!> zyR=8-9$W}US1OyEvcj=2&Kf>pPNmL2fP^pf?n`Kpt?lm4&d$yG{v_~b0jb`z#opxz7m#|vp3aXo4n-GVF&13-YO z3LWjlK>&p>(IX0Jat{uk5jB$4Wo|LzzR;Z)qtKrtUq}~EeReP>me&l|mpgOX=9#t{ z2O`g_rSZ=_YINXSvZxmzKL*qS_xa40(z8l;_Fgcm>e2~pL?)oI@w0Rr)SD5?W5gnlAqP3UwERVp4lqPS=GGpI8 zQWU;UjSB1fNL7+7>)7$w*CPTwG^nOizShrvt|EHM5ya+N2_NkrdhU$-<9y|8hqIVt z0C2Ysm2?(Xj~QpMe-c#~|1|Ilea9Wkp3o)4*b`nDW427_mj1QTn(0F{otEBCle+2H z9J`iaFb=++;1?-^`S^IdsT|fb$9h}ewgujK4vv&Oc_MrrP$)ei?W*{)s%-K3$XwNV zhW-V;(Jp(~hW*wHm7vdG?=Q+_ z?twVLO__TDBn}+!RZ2|wvhE)^#lW&16ASV*F%eZ}&Y?B$Sns}Q%GWY+SVO`b;$OXz zmm$#7x&^mM?$-n#{;E+l`-?!43wQ^#Atm=H<_>vYy_{_TxkQL-#GaKquB@*EK0Vh< zY*$jJb?-mItvq^1D*==CyGed}E$9(SxiNw#D%dAiC9$qvzP@Fl0Lj0ur~ZAO4pDzI z-si2`l!UBOiBhOPA*ITd9vffwTD0@XuesiJMfUKMUqCWU(Am}ip!psH^FGp1+e}-F zVtvqq$Lu2Wo*D+!mxlS>vhx*Ue5y0=1_DWeAD!RMZe&@k`J7diaWSTkaadeA{d*S* zLtu(-F`d06w_0wEH%=G9^{UYr)$m2zQA_YB`^?gzp)>`V@RYNhm8X=1(+3E&iR=OD zVynhISz(c5wX0~CP(UT>gqNb`M$U`q6cFIcnTJlirj9FHETcL(UlyS2dSppu_%`7M z*Zb50hoQl(OgZ-s zc|20lqrMEP;bgo_-dZXoFvx`5U5Td>taMt0X5TRcb_vl7+ZszF_TIZOD(kbNK(rge z2#m13ET+j_*H|$PC=NH|PYPR!t@92wf3N&#oX~Dy&K*PU5cAdWvQS-xW75Y=@4bE} z*GHM%nHrx!GpZ5y955}Hu(Yn%WwTAU9|9S)z|+VOKB=hY zt)!FlYa*01Xb=;8yR34-Dr%q3yavhjJ?x0~{#nR!6Q+BzhFh+T4TX&-yZM3(z_4AQ zZZzw7r!yS_Kqi2NKA@@V??je#sYykkc)5O;sYOQzS4DhpPcJ zzs28M?K$B!{u_Kf<*;Gfk6gpD9I=i9jbow>XLDo?|M{}p4GgB~Ehy)jQb?7n6C8cS zqf+_sIw!&ENuNPRvV!HHw7YFrz-5(tHSp4?(k!p7aj(S+wJpeoww=U|I}Z^P#EGmM zxArD@mN-t;b|eNEi-Ql;lYJ`wt`?VIrp$l*y0K9UF)^(BRv%D-XHuK;{qF7#=yTKZ zs@|Gfhu`W0g&a_l*O_%zsjS@Iwq?s16rcnP^7BLf-9o_X7SP=tpPbl!7~Sn3`7reW zvtKBDAz`C%F!PZ8Rinx~VdL#*zLl2As4tcO zXP*7q6{MpJ-}Hh*oxlvv@)K#8u#Fu%QdX#QbiB2c0wsxq<)GQ@TB0W~+g1`E5Rpt; z?cuZ9aqa6etJuf(wuA+2)BYv%mq`2!dv2@9j1qe!>)i-OjS{uuQSfyoH$w;z07MR3 z#$zJU^Of7WHRiIp{FIFEt>Rc^@!4ZkSY#G%0C7+9?bZjKCS3yb?T66k5pZ*i+^I&KEhFnhM!FGYN? zwWD%)c1|+JqICw>Cbzh`IGFwS_PGtYh(G~6*7`cnQe!D3DSj|WYKvl6eAu;Ap(VY3 zSWz~~zyfuJ;agL75V+CPgi}p##!U{R)gZ=NBlLCIviDTpHBsOGkKu`Q({wXD)8u22 zuMG!Gb(I*oG8R6j-tdjHZ;m@m72iqRcxRviCrY62K(~Liw6}VGC!4pgj74%=kY9i+ z&{~>0nG;Xr9KBDv&iT^IzM$;j@BN?9?YDOc|6m{gb^{Rg7h>BBQHly?ZL4V7T^Sw*r2DX5f?~VG1ivDnnN;u+A_5RRS#rWRjL?Alx zr3(eVJ|cve9QRho%hnN8tnB`uEh=PGpotdcqIX1rXQ!(%c~(R2@81B_W{X(WK~zzq z^L%Eerg^!!V|K`2QGEMqf3wEzc5Ln+@GWQo?h!5R$?0jjTrS)avVl=`m}nF;I9-hU zL_wZqD2FFWSeZGTzkl|xj|x8d(Q&V0f+L?ygw0F%250*MF`-onCe8X;kHE|Mr~aFB z>#7-s%@0Q5h(-+;LJ8^bsQ&0@&ZG0cz|A%5jpR6suk)FL#=T1`2$U}9^Nh>fkX%VC z6$T}uR+Vg828k+FTBR;r;CmY}M5?6ihL2^wA&ck!h^B--+ zfrQg1VM9JwHLPzeJ8hkUp@cfp2@x`SY4?Zo|Bml}6S#{DeNxyPE`Z|#z|O|K-}}HT zt6_m4>W^r}Y2)N3U3pJdWEcJJp1O68uG)=?T*EYxovZ5!pilYd`+&adVu7sks)T+w zkZ`=Jz2o5#JB>job>)R#3Rg2|=gLo%aHII^{M#tAsh3Hzvu?n<$B6N*k^+kJg3|I* z0c{D5hWA#N>`BAkj1rG8_0gyN2$S50jF%=wNiX)AXAM2#j^Dqv{ElO(7QUKtJtbvf+|L5YqJ`um-{9)1&#B~d%-1M}2#K^0JY*pyerKUm*$`um^RR)M z#xJVwtO*sL(<-m#Y>z29a>iApC@zo5zR!|>ojD|-9ZKR$VS%ui(kog-B>TmpASB^U zL&6P~>FibHLTNgh{#!6()=~jqk_C|3M$MC&IR0OWSw?K#d`eRbTa7zNCKa`4&r5W? z{jY#BY-LJY#U}p{V`GOH78AQ=GPv;b%U2jmir(m;&#e_zsa8Y=4I z7Q^iNNs`1|oq21|4}Nm7J{84ajF-2*VMHVg;AgNdbnIEtm+zW`@pgHBZVki%$D26r zY!H&gH_PH>1EO-2&l!4}UYcp72(8wOAN*XM`T~t~Px-U7=;Au<#gVN=>PMM<%JXH& z(*tIhFFdLq7yXdkAjYIu= zy=3mDSZ{!G4(OZK*4JIbW6#;sB6{q~RgS*3HTA6;oRA3C#P2v?+7@)6)O63Hn`}*% zuY4dA`kWXVzccE_NR{2w0(`gt&ma5+CH%vyjuR*Z{-2u3N{!vpjG9rOc~T{ zBqlKH`nG1-0_oZh?ApgOzwZ4=A94-g10HT~f#u>Bs~)$~6&PYs++NNtWFJu3efEGWZ8z1Or2wulz0N z6f}K6D;o@KJ^)i{WMCP$DIM5_bBy|vH(huF1P2l05gkDJYm`#sa%?N7;wG5|+c;1q z2pwFRCk5Y@#maS*&ZSy9D1aT}(Bu&3Y>PE@4c!nUMlB80ev^!70G(4(mqk~eU2a# zg}i)4u9GIrh$+Ei9epX{)#Knb2v;D?DqHm+C#RM(kd2xh&6s^^JRc5(Nu?3n5ZA#< z7SVJfpG47>0|GP>W8}}fD~ZqI-?=>_e&Fj%{;pwXYk5SUjqDV;&Pjlo+O#e17o*B0 z?q3@H{>4+n;U@eeR(>i2)wgI?Fvo_+=IV9tpf24=(;S$GsI}Bp1gS2uNYyu1tC|GH z?1pMOTz90%Izlv8MR(G&a#|hGJF948OSQ4r(SoeO?ZO;R9HxU+cA15*eT9`+lN&{SH@XZar*; zvu7Mz$I+Q-Y8u#~Ty@eJEpD$9SPu^=;A{?KEo?4BqXl3zx4#kVy9NxVaUbF#;GOsabcI4J1`^DsrtGy*&#lE?_610JQwu7j{tJWb znakX2%z`pgCo_&f@Jm+;v*HgL!3I&h4J|4IAp|0$$*FHzbtuy{f-{2NJO;~W$BX5H zKBOikJveS+!SnExCOEZoIjW0aU1+nF;KmFNdK02MH-1sAB+0tT>g{hV?TeWqnC!pa3~{%(g?`KMm!%QJ?q;e# zrHVrFAX`s#yO7>ahG}IVHJwTzS1fr$MGgriz)b`M>X=>ufITQGcOSY@*d&q77w z2ADVi1n$8qh*-{Q>ScqZ7Y|ncKts&}4)1I$UjhYkkJKkM@C}JLH?ss=>2e2^{Q^Wg zpnob{&VZ@6eubCI)Y_}hIA2%wd1gMQS#xq)k(kL&h=Z+7R4n|xKr$^>1X7Ugx_H&k z$H#VWYtZAHS@~#=?zqh!WWMO0GY?TCq+w4wKNIuA=zjJ#$k@14?%aAl%s>oE;7IY+ zBHQ=XA|z8I{Ce*=5BA;#_EHzg!xB>pu_78($aB<{#Sk062HC$ZryF%CF3!DhudXcC zkt0r|8D~nvVo-0_;$&x&gL_hLRxh*?3|^Bnn{@_U9)9~~;pL@QhCEt=|9>sOU$F?Z z3;h$Ou}5}7S0W!Uc^o*biu*xXCJSvei}90nZn0Q_@fB`r(PK|`YuyIKdQdLig4au| zVdQcu5)h^$(i$Ny4}*Gj290(W#JqlFIV}m5(;k%XvBUt^@g*^W zrF*GtY|7_5pq~B*A_KO$%=`X-PMT4FQXlUgnLo6xM*|b8*!0u{4@ev9BJVOUmA-vV zH%q-*v2sZ^!$G8h`hHJJ%e=CV!^rrq>FiM5x@O6Oj0B?2dl@(g_RntsIBs$jS*o31 zcPX0uW?QRMhlDujI{OUC;<9)IFA;IzjQG1&e@p-M^ zH@VZxWOez^-91+vr^0*WW=||+vr<4|ti#+Z;uj9h2ka;By<>stX>HEWgbQ_^C(}Ev zPky!|_i95Cb7Ir!166|GyA?!X`RV$N7iE^9Hn37zvI-gZZW2O+FYprpfrC(w!%GkPyoTb)F~iks;aP@UNMyscn}JrDtc|9e3}fTlW>#D5gJO%ZZ1mlBPdRid zzz$^%4^DvJFb8yTTkJH$o z7Vbul-IUf<%AmJGu6T69h7vdi$}dOn6RcOhSY2Y-EbKlKdISIob<0jdo^G4=al zSmuV!cE1yavPF+Fy|^J2sE2e3`2WBv%(h4B#XaYX)pL^wuFiYG9ALhopSdwve6nccA47}nOh(+>R%{_Dsev$ z9tub>f&Z%;K%KdM_X?;vfx-uHK~0Z^AOTF9rKpBM$;MDa@ag~Tc;ieDGEHzo=H+jGf?s^@@^x0P`ChK3OTeY zynk}v8}p1hc6;Pius1|tFrDqr)#ja>!5m)i*3^z`le3bYOgDU z^nkhXOl-H-_Ip*6Cg5LC(B^dd44eXp57`1kUlZniiDT5lAm#=BqL-qITHj);=xZnS zj^L8$r}OhuX`$9CDhhDU&&B_7;|c*&&@*7z6OeqnbJ+!G{t-xBlQ0R+r z>iELs!Oq9XnLox~hd5B5*O;T z-+wp0N{EZMwYK{IYfpdt4*4M(vMs6znunWYeXU2hxBWqlWjC1%jKn*w6F(|=ocMAB zm>>jub~y!Fpi0ODRbI4aq7*d;wVGu0v)z}|1Q=#s!4{(F&g&eg@~MuCbr%vJ^7pU--j%;4;>W5I3%1ypWUvo7HN64K?t|*VBho>(9eBk2351dV9Ljz1y z1BYP2Tjf~+By@O(9k-(TzntEYDOlrEik&CDmu*r|261$Gy>I#&`hJ3|12q9SJcUu(yAh`fN zx$b{J>)hPjpzF<#KRV7Q-rg^~eSV~DQ!+=kZ(M&{J|ny&Vk0G3z^+qy)WL0|3RO9Y zkMun%stS_2;pVK*jZ+u=476JSNf3z?%nJgh$B|HQdiua`YNly?%+@tFjNem|YA2oZ zUaTYAgYd>oK4?8eEUx=}LSj}3C@z7e=Wn{4&j1k@@aoXf)BiX=u5ecMOgL^L4SuWT zCoOo;Q3y@vea<8irC+UK`pue4?8T*{E0b&2uRRFtsJ--d_BORWUK-2vXf7A{3R_7R z$OK-w0GEbH4uEG}^>m8-N=;v?2cvC6*vt%SV0xFG_I=ks-nF^nNO>z*mE*?7rPGij zOE;gMN>B93W&`gz^irTky50$PL*e>ib!*#2Nmy}$+_{Z5A*0cuM8*cwV%tp$G{41~ z0nnYU61d4@;Jx_j1^@4{{t)_R$N?LO#kD;aflQc_PGWuz(68$d6U&qeN)Z= zhN2H4rq8?_vniOT2(T54`*F>9NEgI?P76Iu9QuC2hhCfqBwfH^7W*UJ#T*F&uN1mc zGl%Ibt?u)`{f?*dckXm)rB*NMGq@4BY3sL1DMR(l*j-3j@fo{DF!&Tf0 zy)Y$?HsU1~*~ZFD1>CBS4SVo;CU-1F6A8n1#$!^KIjRI9PLPHQq#K;zSG2j3!D*3d zS!Z+Ml_IMCC4%N4Up8ZH3=i4#ftW+$`5I}wEh2bk@?i=%_Rr2d&J^SBJCVrqx`)ed zGpi?7@PqhCL90UUhtfaShjzoJmZTg@yc5Mmz!9 z6jp5_r|Uf5YklsK+S-W{{aTMmN>}qcj>MDEqOd&l2Xq+XsCzWN6`u<8?fmlvOV$2* z>8r!TLm)63n2D!-y~+D}WB71r4)AXEWx!2&=~MlAU;0%mTLquI($h&UQLX#00qtz2 zU>NB2UPVRttwS1t%2JjacC_PuUCPQHxH5v@YsaQLJG;iyF~){?W@Op^zD|g!7n%7o zgRaGAwwhW@Mh1|!lk)P1-9VZXnrO5z#h=l}77mcYIdIGQfSRLw&C%I@=tgMUyRxkL zg$VRn1Rppi=Dm6bbfGzh&JOCD>Pk+RPFt5&Gf>u?-kjsd%~Vc zUilV>eb|*+OtLHp3SLeuBj{cj=|=b1<`74;?#wvW@hAW!UdB)#7BP41w18O zr2U%7?r<8%VooGOp4(4=4k_|Nw}C6GLaX|YWU7i`X3 z!k~mO9ympSG7A_@{+AN^l)X zO5mE_{>P3Juk%|8&WGh}f*oU+*94B1s`u(IS{v(&Fyp(T?>?~^?KoA=2~&_F6~q#F z?U8l4n)^tX(qT8Fxvh#Gdy+kmIYan*LoGcQvT0LXY2d*CTt{+e*d1*N>Rc@*SNGFTAcPh;Bxr43m{Uy4eU`T^1xA{vmIoMF{q)rF zH3FRmw~1)75pK3Rh-5-G--MV7Bketq$7;KmcsbfeCD<6*v;A`&WIYQ zY*by+|r4QsX<3jr|V|@P8>r4|jmEgS@j?&!@MMnsG`A)Q*{Rm-URI8gC_q zWn}rbB(!Gsj%}GAYMtaQ>qhfpmEF6jWnbU2qB&ai212x$1g z=D#_gg&GApgXf01TXUo7wC(w20nU$baUWQWJ%JJUKio>r+pbE4qrH9knqd=LQ!gzZ zgSGavYKGDAiZ2Ncg!JH$Ya3bW!oo0Z@h4%Ag~}L27di&71>p}(R!)IL^6wc^<^G7& z25s^!xS&@{(rPdUpO8Sor}m>bGN+J ze|J2wv@lA8wJ5gzHjGAw;adm%OhHc{Gb^q4CF78Zi>kge9=yJElO5ib0XH82>i)aCj%&2-ljXMe%Qt=iKLA*c0+5e_ zJ;s52^RyJiFtBCpMc_W-w#fDlulnWs8LZ96g2PEHzx5~X_x{hHKY?xKMVpnDrmtd8 z#vpb>Fvs)@X*@8*or}n+K<|Y!+Vwvs)v}_Qnwd<5U5YMYE{f0@)6;&6VzHzu65Yr$0V$+rf>@w#WR;fQ)f%C>3tapf_Atl>oh8qf zp3z{Cbe(Cnx?C5K`spD@dZ5nK9JbEmkpmU*D2OPCUf;3kCO8y;zZ)+4O6?caXJJ6C zkyvp*_*9J`nb2)_%&0+hJ+Ze&P5+tjJ&REDw&zRrKKZ9JibBY_bfeP3M9=&j(qDV5 zOPZq)vvwjWv@q^%Cy*5dR5yUe02soq0|bDLeplTjV;EJH8-uXQZ-|RRx=lxAsVNlk zDpp@`(pGvD#MC@o(bY14b$dtsF%`uUybG((3TwIDinQ>I<3HLlKn_C9t2G5_L`HA7 zT(X?8c~9(PkN~I!z`@DnjK69tOQ0?vS~&4U<dDNE7_9MTju^*~n%@-9)ORe`$)2-|kcH$xB$VKBFr5~S3xNRr>_{_^g`CiX)PW(skb#vIn63U-c_59i%7m; zBxAyVd6_?Kp>8`eq}1md`!C1nUM=*1?|yCaeoaUNa5MqP)OFyJ0+b@L^`+ULzDb7H zf;gDGUMnqlUUeOw`-`|+IEPp2lxAu*SAKR%&5Oc|Y^thaFU1PqJmy|xEARAJy|STe z4TkjY>P193ydAa@H!Z+75%CKbGR}S318_oI-g(*!MwzyWQ2I^gdUMF`E-z@xSNd+^ z6e*TgSvpnk=E*2jR4tzz&SK>rLa&aXX;FxA6fcU~AE zOKegZGwV9!gMPP82A{tDJKo(2NR!&zq53s`8~*#|e@8=afGFOCeyBA86k%045-_Dq z&Y$1HaS3f7qHGxH9`m5vt=bOv~+ae{J?j z5c0PXP2w(yd&F%#pOYpuGz7aPrPh})lSy@PcPIf22!_W&nu z7f=|{2mS1se7KvWfANAW0E|0j@OynmdWNa)c0nX~2J6NSY{o|G9G*wtXKtr$+WXq{U%KOX{IP2b(;xe7D!XIDYNXoG0kCNv z;AX0=ER|6x^l=m7$PoM^=T(JPn!t4<@rA(qA}lV@leJ7*spve1hm8e~)jPI}Bsy0f zcjuBtfP8V^uXWcibB+B_7{7!;!lLTDZ+>e)iC4GaWqh}DmbI<)i*N<0(F;XEu{POK zC118siKnA~TM_X`zP95PGPc4%=#qY>7&(b z0k5?kx|Ns7=(*3*>yfwb@Iy#^dR+{Jtj4AEemML61iW&yR5&&D8ijyL_(7ga~oYc1S>wg0zK=uNV0hK4-8=EcB z3gL7wJ*r7(#rSA{(u?3@`f%~Yk?b|+%ioW1v9G^kv3L;Ux^15n3_oE+{0^PCQBptmMmAb?(t=}0<<^uae%9Tkb^r7A{cj;u=8GOqb4+ns zp0eX}Rk5@aPcF?^uMzTe^9fxT3*wefOMZ;-G6;c-G#!%KksD8PW8>t(ZP=Sboiw$6 z3weqpuv_B0^(=tnlgVvzUnTmxh@y`*J5j9?sPmBQ8#JZCC^Wb2uJoeVHSbuZxzdq{ zjehU#)QU@%sK9#iE3t3r$)2czUriiZ#x>b0{%!DPwBOo3&sq9X?9E1YfJb&&_aDE9 z)1$?@0!ja0c-=qofYLPWQjtD>N14}O(UYOSm-~|)E!CUSqY9RcNV@3bfU#?JW6`UA z6}qAgW;O3V3|FTa@frA}Y0hsJRn`V(>V^X*Th(x!C&H19=TZ+)e%3TItm@HlOQUede{KB4#mr2c_}H!aGvjj|_Xv4d_$mNj%nGft27;3}CEWvDzvbFG-u0pU#Wu;O>u|MW%_NFP|#9Ga5GuH!2N zj!c6w2P_1c8c}+~+`f8fw3w_fSIjuES9!QJ-_y<}{jT^S+QXfL5TmW94TCoBOcMUn z%v6b$baiIPch|uD37Db&^A8>&nt{QL=dTj$F5E9xnmES{)zSNEjs$>QSr7O3Z3EEr z-UM|uHUf}Z{(?!0xX88)poRqO8Wc}Hw|VUYn-I-`__=|CbgUuB3J%!kvixUZfG#|9 z7QaR)v!Co0nq~O|@nF;tf9t3Jntp1J1S+NF&b?57IszE5RG#0f4b743zlknSXr>`J z^nBe2?`#&F9^B@^u-1!(2gWBNy^E-mvw2vUhHaTnI|%d;7ECrJ_bJx;t8C!L8MkiC zp|Q`5q+3eIk0?iBLl`3-IU(_UOHVL^4Y0-NYoQ$HevN=tin06VM)w(c# zr8B9jJCF!=G2P?UAz&;E<9A{H^@>Ke1-*+wk>sgB)0OQsV-DyHO2 zskYoLrS8-?ES(7uYlGF7*B#%9lHaRkwoC6k`}^%#$Q806_~zFx-~9|qiQ>Fr5j#0 z9u90nv0|2Np*dd-9Hdf&9YQ$hBHH{oFb0YcHW9j(+?6ZO2nlhUbicaoWb4zh@H$vZ zbV{8kNr5f3Ns$EVKB&>S;LJ;hCLU1L+;XvlLaHSkA1l5S_wPZs%O?XB(My7<2kN1 z_t_=RzRc9N?2}i(Sa|M;`DF@LwWD*HZTQ&-f7am}hYK<`jI3WDuP}tmY&3iA`UhL9J7HfI03vX9h;fM@r&Og4?kM3_nT{ zoMGKP8Zfan})Mym0ws~R10heRD|!|T?4-eykVmlme$tW zT9_91%l-AhKLbWjfNKc_pX`z5l7>mbUL~Y zOW{Dw)@;?GBjYE5`BXdvDjM#)FGT0yc7PwrKyk2FBEvkMrMg~t#|=Z`P)$#+HkfFR z#%~w2iUK)sXBao{Sv`fQEOeD2uy=I2J3lfxnb*T$6zTNP?tI7q`Cy|*9%AOo{?!hR z$5Mi}x(O4H26t{^0en}CHD;{-?}bXH8@3J3e6cG*hB${QHJ1B}C2`)YqgJrNl?f%) za=JEjD%;j))y{s@c%CWzDQccRhL-%(q6ul#HbP<{5{ACHqRO_gLXHuQ=+~bHG z^!QO}oVN2lm#C6(y5nz@gbC6ZSdyro4K=#NFD8d|=3G=6D_@}074C(LkFgUG3y#k9 zU;~4lfkB2r-?9A}`vv!zBDu3lF7A{Eap|hxdJpw~W3dOLoY(cvfX0efy&)hhrlF%- zxvDP@ZF>N8D1W*i15MOsxPvbByje;>ukz`bC!#by>~?)hVX+Bfi4*}OL3t^ zszb$FVpYX5FlU<07ard}wb9r5CYiYUafzkX*`dEAIY2euh7Ac}Sw|r*htFAlEYSA~ zwsJro5Ko`-Xw&#`Y|H8GwM>q?Bof*^rnT0Gu@~!GjyVb){QD%CCME1Jsjt2tlu4K< z_L?w4noZo%PopA*-qqDy;@=GuDb%Nq%1EWuV``>r$yNR0NoI9W_A{u}s!yT#8h%WD zQvzSf4!U(niOa3%$vCF-0Ws)=*Tp9>?z_F;GTcl?mS0jai|O{Wn^U4e#_uZC+Rze> zA~@e!AlFYolY_{1D3P+s;!enyDdO@{Blx=cR(W82ehRFUrevzB%$Iqi1X_is>eT0T zFDKgi#WP`|<`a&^xsi0MH;QJ~dSH)~xupo)*!l`xU++ELnJvibyJ{?fm7MKQL{9e9 zwqwf98N#jav)(4ti0wZC8&g5(b6Q18%}InaHJfy_)&po}xgbY}StFbzt0M8^)mkg5 zLhCoN#)XMi%U-b%!R_6@Gkn<1u`c>gQcITCtD27NoosgSz>UUEg~^D}R)S?phmNKu zN+;}V$3D-*DIb$>lriP4ZHBWB#*h?s?e-nix~XRMX|QC&{+4BXTN{U%jEc#)xbRr; zO+CZf-zcqq#iVm^alT@lRwzataVAl2;N$%z&}#&IR&-K<#{5%lxm;_G9T0K$F-g`; ztu1MZuR6VXIXUb!Rk6c>g&7!(#EM%!bUZNxRAfM76o5~kz=cg+KpDm|cdVqfpR6%Z z92D#QVPP0ELZh@2q1xpf>ZV^Ig91rorR`+DCLMKB-()LQOwB)A4CG9}j7e2TR_n@! zvM1prR?MIXGU61XED)ZVsbA+((g9R5^BFeBM=`B1(uYk>6;t_LWeKhU3?Lc>~qED&ISqR6!C#4drq3;b-LMmHOgdXc_B{H+49I zo$-7r0)%R|Doy1o85IaVa1K=b`JsH>X{DxV(~;M~(b5^sz{$_kv*kSO zI>gib^vc}V3d;C25s|Y?EdxU1r~XW(w1{TwZEO5!;jfGwUNE8+sLe?9P|ep8{l>m3 zBX@*}SBfqNXH>0W<7aJgz44T?g&_v;0;@ByTwJg#c1+a!f8v?Z1ff+n9)B^Q#bnjoWKJfg1Gk<-55z88!k?6L{FU;y&Se!>TzO~Hn|&A?P1M? zH(uRMS`Vv6+;RDwY*)RfwumMd>^Q@8B4j=GiKUzCE}Ecg6cru{6JAPD@e(0vY0piH7l#Vy&`6q@4T6ce zA-ITPtDC5?pn-hN`%e3ax#L$9K@C16=V{Q>1G3@{rATQ}u3?|*Et|Ixn*fHS*tP}^ zJ)r;A9|ra_YF7JT*Ys?cBV{mnU)d2JJF}kBoqPAP_Z@>66GFU!t5h0q!@jOt?z5ez z;?2yq8v-phLR6i|HZin4mGC%kMOj( Br8IO#;KzAftgxsQeJ2ERPU1=~nl=bvLL zM&AM+lzl7K-9M$-y9(wVZQZ$2tJ9}E6@2W}22F#`Al>hMrS~e3&_U9kBv(d zv`4PBu(uqS^z#hGi!MaoXtO=?BU z9suPWDSym$!R*XZZBo2FHxr#iYA+*pti=1`%S8SDe(IQfL!ZU!rI(-DXx3u9b+E32ZxC4?4m_15e9e3U1E z1_VhjudeFlLScU!(LG$<^ijj=>4{FUWKdO6X`xUwb{imTn)e1{?pHAbC zi~Lcq_(4pr`P5KVhYGb(nD1~9eOEnPR|w*SrRs|cj6wWr-918TRJyI|9&vfTLSfo^u1si_3W?mqlApy)wK-eqf zGvvEFt=rauAbOUk?OFmbti8SbgG*w8N&gNu%6mhlC2qK(mp=#;@jE-r6JG#s54U?v z-<}jNUR7`n&`IcUIcQIRsCE63*x`Et8Cqojz{g%dpYwqhR1gC zDW&s-piSiVs~oYxEK|$p@t>!PI5NmpiOr!_-?VoGz29>(ZnHTk`oEjyEbf#BktA}K zs83ec*z3+JV2rTO&b=_xBAV3B7(@rXDxvtMkW_5W*SiWB;jvp26=6CG`^-sEONx1| z@%90XE?_l8rBA8P>wn22Nps~9bUi9>`wR;+mhTu}WT7m=_;PaRxCK7qBHAvp{1S7J4?#nnni~iO5hMwDV>-okhrnl$V`tt(HYo#x}8U$zUzlAsW5qj>FzpXWEY=t`2X6HzDE|*EKGJWtxA6lt6Ef;eo!A_Kj zkCYM%f1%~7xt?IN$2~p-hpO9Ooa~G}t%m96np-?zKfVk%odh@1j)U}>i=b)PHM6^e zG6GpS8;q#j8Fr(%V(Z#QVG^rq&+5h?CrYu=Dnfk3SyFZ{G-w518LE129f){!%WOPE zG*EG$C5N7tH+SvZOe6*2;d;G@cpu5F`Ry(JL~-I^1+*Xa6s5R{m$HeROP1D=r--5 zs$$mn55(M2EvlUslP5o@>w0f3Pl;|^%hE|q_Y5n%_{YGaoj|9z47FTVSSF&)utpow zqrkA!6H&qc;){?h2+K=#C$`L_aa32;6~2212%T+o0roDS_XExa#eqdY*|D&Yk}%oS z+zimHR9{@~X1SHhYj+l1$+cF_R|4pZh32l77DASDK#3>=*E<6^cD(8M_7e`arr#tsk4S=Y+(jJfX2{2`@Zv1*z?E)%o8nSUKBVhrIB%C9klM^S zwfF)-&t*m`L6rnr{yaJF7u=$#G{wdmarm205-uiAFp~5PLvgPP2j z!~Xt}Z{uGi?d8h3qG~@dNDMcq+yQ#-fL!73?vrF5AfGz|sykO#;K>C9GbpGt1i&+p9Sz5Os>H;L*FrT_voDe&*ti zL#8L`#P@y(%Ui|aDf-A3;4&BWkn~ugZ>UxYAE+h^H33U}+b1187XIM3A9QZT?czA1 zG||Eru}ksAv4h%Ely48!_OMUzaBSYYCr4vTVO(PY-*qd@n*(6Fs5rcH*j zvw>|JjhhhMJqyb(3M8X;7D=G?;D1Yx$X9q8b$54$1v*qw->-fSy2##Kyc<{Gol?^r z12ej9z&63P3GHf~@W>}0b+uzB80%=_cOwPXgS?E+9V&YShKyHYy+KRhT&7;NF9HJE za9V|HmDO7Bu!_G3qRQQoL4jeU*s~7qrOpRlb@waf#$`2&(OTIfV159#G8TcoKERn) z`!?fd$%K3xD+zve^0&i$ON{YpMu&n&YO9nxO3fXh4NvUgJhXRp@t8&Xv-j#p8bQ~~ z-CSG(b_Mga#~UVgglw&CSZu*LHVe&4oCc5n0A0!7-`~dvjD80goyklu)E}-jo*Dw_ zR1yHs>i>eoml`V6YbCxI3NE{j{C(Cip4J~%t?{C*96o;wvn0XDHm2q#omADQC2F1x zU#3Sd6g)ruR4Swq-(BU+;tx-(lv=}wBryjMe9X#A!?|IOtXt(UI**)4C62Cp5n~ik zT5Bl0pwl+Ky2ijhUO7<8RbfvNFmcw^sD~q{eY3m|ScXzI!OEbid^Yd0ea}p2>nFHE zUY)vUSsF84;hFGQwq(-L%vY95NoeOXOV3CW?VHl6f zVart-)ZL`yk%Gd|!(HD}T-f4=7ma=eq)alkHMO;N4FJt?9q7C-E`nKVZRRx(FB5U3 zsquc%?gtyP#aI~n(4GD$mz{uuJfyuaqp!!JmGs5Vc?5E*hJvaF!Q9fX)MLF_j-9_s zTT8(-R&HzmT_D z()`qvRRZSA3AJWfQavKdLPfT(MdKnfu!|_%nJh(u=oWj-M7<1cBcFj?=xmJ4Ft^jP`Qh7L@f+X)lK62Q9c93ZmLz z%`@m&$&FT1Aa4Glf|0xC@h;G(vKIpOJ0)CBje)-Wx=1G(>`E%;Z4Hlj8!XM{Q$+}) zBmO%xSXIUR7Cpktcr4`TOpEve^&qZG@n1_!13EY$XV*>|W7kc3 zjbjUb{&T?47nsZf=^=tsvHvjjdh0;dm$R$#eBTzo1GhMUK0=yjcRjJOTyc}rTgUNu z321l#c~qCV$qLFH&Xno;Eo#m%N3~CbZN%!Z%^}I5EI1hz!ORbTo=-{lPoT9LDOvh$ zNrrg20DE*kc-%{ntb#jdoh>ztD?YKuq1BHYS?ZY7xA;3LauO_HrR6Qwq5gd2p`$OSkc2}pI*AN()s4`V{om%4E(_EdQE3MaV^ktp~g?J|g9 z5^Un{p#D5y>`vM0YQexL9M?QX4;=01M!^^E*1FG9)mHp`2*a}Ck@x-tFZ z+G)|PpqdbL>V;W$LE`6@KAhF+>P|!{us1&`A^92Vmt`xd6RUX246n=W?nr;Lp7Ww$Gta}zZa zR|*wZ!^&8QSNqtAqz2b|q?+K;By}S^B9EauXMpE98a)XwAOmRM5l?^jET$)8$3h8hX zF{es{J?F(?J!UI36k@Z3?QBOyui$g{YfAbMT&R_U)u|BPq#9E1{jPUY@(Wnx^I6L6 znVT?_ryR)+S?=ylvh)*(Ms~KfnPRu&;#NPBm14W>6!QftCdD>Dpn+?AIQnlA^Ka%m zj?FJYb*05cg&E?;h?^=8-@@tUaMRZpzl~peN0CPj0DA$qhocsZxe&n$0MQzEaeFeS z_O{*y^c6*_0!bXe8h%oRx{KMgUsb3!Tu>GmZv%RA9~OWqCtwk9!>Yg0C^V?7tOTal z{}DJ*sI7OB8R<}t!SqEUSuC(itAC^LD$K0PKLG>Bvv;~nQM|s##*%DK@nR~vfseZy z+ZmgHKVEf*y)$*$ASaq8@`Pt7F@63ut?dGt%VR` zFP+_*fRiBMUUQ9NBzT?*Evsmqh}4ELOFJZ6&LY(paGs4qN6}kWd_j0V-19T`^hg2j z{_?y965uHbNue*?h(}*3ds*s)IH7B}KKRu^XL4nTqw2@nR)#s`;3P-|ZhCl`IrgPKy1x!e z8os}l+VVr4XmOA(NoM+0>~h}WDD_ z@9=u;#u+#n1ym=lym>@)=X7f<>_6h9sLf?ckiXG+%BcL6-a)90YfyCCcBPH3PIBb9 zgtUFzIC9!BD+f`GXFAK;M3z*&bwG_)cW|I5-oLn*`hvt>BxB9NL)5pJU+jB_c4fD~ zX3c&s-g}CXA+FdZQJ*MUdy`p6CeR827E-TZ;)fcQQt(`B-}oLgwYfy#TWTCqrt))exb-+q?!w6ec~$>3Ib+2wD&VH!}NPg z*?q`MxNNKsR;0n`OX7g zx8pY5j*?lOf`4aH+2TY_Ez|sELWmp~gt}NlGu9BsGR55_gw7LBD%$;v_I*?g4nGwO z@pv}QMCSxf>8I9hxrGKExVgw{YY3b;6mFCsLMOTjr|lS{J6C1MhFWVdDt*V6;=j z3RVqsJ#eotf(Ycj-25U}I!aOB^ILQY0OA9^C=5!av!xr=WqlXcGsoCpp8b8bB_Z|$ zC+=^`jw^62l-{Y^*m*2OtY#V??3LO6ac@h1Fa*So4UKZJ39f$q?)ER z`o5Z>fN699UZu0V_Xt|+bqsN-HkvLIxoUU~Jfw(5G7*&6_&oFQ(5Wqq8beFf>$KabIw-vqyc#JZx?=6f}JUJlo8D?t{8?mVlS@pM)Wm)1UC-kbRmWLcp&(S~9eSGf$;(p)aZS90RDde;W zQK)QTVz=Y*YwvB!jwAZs^CdO`dbrqoro77EuL|>zEh+vdcD4igL`cIY_U?O_{k8Lo zu8bg3n3BnYEijnH!Iob~F|(qd*uo^R!r|598;&yQPtCx8LLcbEglDmNMikTvsy1oB zX>lr@;!Z2l)6d)Ba9(+}ky``@vPF<7g!;fvuWHeo;pblQ3?paIuNGyEs*8!Lnvief zRosdUOr;0O0zApR!d3tk7zWzTB_ZVe}WkI9x)DdW~MWnW8H-6mP0pnWCm5hhb! zzxZl5IOsh6rzGc!`~5$}yhq&$RBDv(S_QF13&@M=pHrc0oQE)B+`PE( zsjs>EJFC*blFiMP$Rm`;RuLOxvW^kmZnWKdF*+$8)23uk)oKm(vn6*?wrBj7=5ox>V1&TCy!(qBjAO|c zYFtPt-iI$_vx7@8#r(F8Nd@miN}rl}1qRqnRv;DT(+f2-!T6y}thQRv*))OR zh;|IR+02UJs-$_m!bjl9rE)mrfOHkqzzBU5VCqUeN^ib^SDYY~yEYbzt?UYv`Gfw# z4r|pu#i9PX&I40gkN^JDZcYH~(fgZossFH<|EX4i+6Z`LfGA0y1+s=j*SHhaEmnMy z*27roEoeHy_nw%&G;a2O{D(Xv85Yl+bmEHqJ>So#2Qz|mI>%nG`)~ih7GRc&(h-sD z*>`i}uZ~edBBWj;Pxkz4!_S_VEug3Mg3RPtPI@1^oD;Y%y;Mz_GFFzwX4&=MB#WG| zqw#@oA2nZ*CLDMZ4<0Rb5JO2G+H1LmQk9P zS|1{{e1mcye_YW91PCNUS@`;DrUqzdG zxI_4|jvs3gTb5bLDt)sgH?c;ev)$NR{1Gb$7DwS4xg8;$nGaQh`lN$zPKRjs0JjD$ z4Gl8T$W2j8;WMwb^u`wOjh4*I+Io#0B zPp z`2)lerzT_J)7_W2JT&@e*5gubz->gHiDg+Ji$NQf>-11^p3NPe;chMYz8IRW{bZ$X z!16s{@E_vgW{*Vht0%=;Wr%|j^q@n4h-YG=k12nnZ{nA;TRjG2_L=F(`zF>M&OcH8 zDFv+~gP?II5@Oo8T*H4(?C_tM4~RC5yBm)C^j})YU{-wf+p6->j2UVvx@x3w~R*f0lbHM*cPkBt56EPfDVt`gePVv&EjUm ztTw-60@H3&R8$V1spBO;++;o{|5PT21~pOsT~qmx=A6QTDB~iL zYq%JhGs{%7nURRSaeI#2Io8PXuxYZ= zgwgXRC2c29-wR2;-J2uwn(@eiYOfWM4Ur{wCFRiVSJN6cu_=7o*P;yB5-=fNX;W#= z^PpZ)HtG+sPO_yXOqI6!sUA4|(y&S4C%2mvZaA|{#~GT7rv%p_tNJJBZl!S1-YPwF z2>alVzQyegz8rACbm?R1_l#n)6x)71!tJ4P z`rR3K;>oNvu1Eq1mR}M!vt6jcg)5^T%UVg2`ZJoS@w(V$iz!#F`R7x$%YNzR#V?J} z%|6mlw+xG)d6XYvU&f_zD8 zC2txGxw=Bf89(X)l(&sfrxQ1^C=Ov#gB^8L>Dv8)8f>fTk2jE@bbbiLt#ogH|MUAd z0Qq#3%;Wu#^SJob5U7;^TLzF>AW#UL+Lo1#cduWRo!?e@t0i@j0^}$uPe> zw@P~6u?%KekhT3rR60Y}j}k5T%uiA+FLaY$L0fg%{_)bam5l6j9jz#?w?LS|A~%G6 zW+;E{chyv5Oq=(ynp@Br!W!ND2Tf~DYFhF|ngXV}jP3)o{7rSTLqtPZ1aB!%N#=Ow z;=eBxHoKXc&7MKyD`SEAonDl>>CY51JrZNp9shcXc_c8d%)D$k7DAQz>V2nXn0i)y zA-nD$^G{usnT&5|yS2|j#`?M=JCs~;u#NErb@|Ynu*_H~Pl1B`5WlYA4%NGdtpVIH zu0sRZ{oIF&`G&%s)b=^x03RI0I{x7I%iz5w^>aE+GC}C_u2j#4r7zL(tR9%ZQX|tT zDpPr}SOyC!Vko8oLhH4YxqWemC-ZL0a<%lEutu}eRii?ty5s|! ztz#Dt*ccPfxQf@qZ%s|wGT)!D@3K`c&*?9RTQDJlZdm>;;hYg>XiQ}a5LPm=bbpgj z1z&Ne%cqpYAeB6L#Xra-YkgF_qHtVcQq4RM!=}aMHsK;;F6;n46M)am8B|H!nUX_k z#|H6OBx2<(U--fL***e#sA);5qL{B*DyZ|Fu=1LVIcS^6#oA{#0mDg_Z&dVXNq0ll zT=fTOSkX4LTG99jf=fe zTYxiv;)!jy9b8gY{`|+VKJ=a<4h>0*%wA3Io;!AzaC(hbYf+Vx{b2d^H40;^D;P>+;)MD4hc+>Y>90iEzJAk1h%wN9*%KLh7EG>%-aK(3D??jQ*u+%9?pu|eVz z5;OtPNM|rkzvdN9xAK!iz_Hi+^%=1D&OEl$?)pJy7fMV6!nLKXn)grh1u^kvXQTgjnorW1z z)mlNQ7MiLqgB zg%i5m)uT)m=T&t-gFDHhFe?`CD40wm4z1bM`W2PNU(3dnQ5;5&>b%Tqp%FPfTUtyD zIcegSfFiO#7&QWCX&B{@0Pe+90ko={k^&E$F4AtCrf|Tq# z%X2OS9!*a`;z{Zsx%WBbkI?HB5Jy%&G3GT2_p}`;;H|=Gv)DSCI3mMBxDDIC@f4;9 zHht0__*lI7(CDd|+1Ho5M!fr}N=`f^q@=n#IaLNI%)6Z!J2#I9PErDT7oV33J=Fta&CbpQxVCUvPgxMi(B&{GxYi2@_or z6$h#i)ebA(tltH;aQp95z(*pgyTh)65y6@I;4+xxY$j#psuR7YGk2;R6S$ll;q#J` zG2&a$@p)@Z)4?M1XRE&ul*MwiPy?fS^RmkNcpih4K2}oY2Lzfkt{(H(LB2W1r^h%i z=S?~+-)nN6&%%im@39>gQ2X`)1NC+qUrETEkH^&l;+bc>#EdwEPaP%Cl>yy?Q0B}$Mb58F603ZtCmCyG813Cap06IRvhWUMTl-w!* z-bD!hW83;V57K?{XC4l&r!eJ zBg-}5gq+Ah@*CX~(F^l|od?h+n2~sK#jV@Kww}b&?D-VX+u={uMv1zRZ`+ONT>)cE z!0hY?Uxxh6`PXv;7!%h4aYf(0hrg|Phz#itT+@pkmuPox53TrjjcF4bw&U)h4XKxj z)w{#d(l{9`7g|$HEY`gRQqL!;t~(;xO4V%_Y(=T*XR@KmrD>5f^KYfE!ZGWSK{k_S z*&{@TWkV`t*qQLZc<=_sffI-u#mn=0TzHAY-the7TvM6AV#?afu@8c2USbi6x*PB- zMK8Wv%A$`HjOo^M};Xhh6EN)~0}0*<|01mvS>6DE5moR^!gXx%O48 zY6+}b9Pc}NibN$ju;i4;5~yA??wsmx#G;FD+KjVTa@$#-H>&9Tm*4y&&tB*sk)_+91+&kS=cGK#6=^@Un0wB)mtl)8$0qm8km|J! zJ1DW^pRt?Bdc`xLBdM=7g2JumjSaIF7{1JH4yGVgfI$&k%r590b4F}PiRp|8Bq`c- zp(e7&fa2~88i&0#fbn{g(~|mKD06)nsiWS4Wr{+{nbLcz!ck}OaR{k~S}U(rAv319 z5n44;QBW$sR`i)34oGkdbyw~6EGj_P=ot;?oVT}-#A2yh_5iV;Fjjr^3f0@>_dhEQ zY9CN$w@v_Fy$#6EA-DiU4y>BF03jl>5)O<<0GQNcbJ%ypPXl+;;~VR7^cpp6cc5TPPSctE+cK}hCl)NM##-!`Gd~0v zy{{ztat>JgkB^Sh{SElv0rfv%$4l%f7p;wzAukhc1Wf7!zBgz4boVoK0hN-cZ^BHg zYia4H*> zRPevgdV$+T_s}ZhRr=aVr5I~h#djbkBz<)bAvL6SSWRG;L@AFRb=4w0LF=xMs)EgD zm)5wjQ(jPI*v_u!P+kJFR;S1P#*MO0O6W|y;cM4+9Pab)HwyFpGfT*=>*d#iweQjs z`oVGuA;o2iitwk1M4N(lW#((H5X+3;niBYwe&W5YBSu(ehdP#{qfNd1IIj!%C&ea) z);QcPbf}aaqpkTjY^&M6Qce6=I4o(-J}|#s;20m53{@vH@E$a-lY8@r z=5RD79b9(>=&Sxq1wle2qydWn067HyWq`IqoE9DS##Yef;E0G7b(f&tDqILX9MtC@ zsTfg-c@dK_7-uNN$zN^VVcAmD#FQ~PPX$v4mkMJ2vX>q2efckthE>RvU#Y9)A+vLS zIIbc_OpW!iY02@;ua{d1R;xEFCFd=E%705str=q)ouw&`J9hLltn`TI;N}zV8(w!V z$S)D|r9rNdgzB~}Oye`#NXEvhh|tI1Fm<_`My9D)=?D+hC4G7iFua~0g+?8A(w`xCV3R*f~+&m;W1eh@Mz@Mepy-tpwIXMJEZ{$X#4PoRwB+(`4=^5Sz8TtHzrNOfd%;&M1B2xAD{o?#bR}ycdtEJ1Qwv21v0UL z((u?p1;>%*H$xh!oYUlvvfqzihNthSF+I(#+E{1q+2VG7DpXm&bSyn7is^HB>^h%g zYLc&~X!YIRB>(I#nFna4$dkOBoGLrMk7Fel%|xRN1qcPSnWD~L<|8SbnMlV^6u$e> zCis<>+w-63i4im;rPYE-%P0k!qQ8JxJ~4?XW2w&;Dda*}yi!6b-*fUv5&J>^%r`N> zDZe1z3^vjFbs8;c6?U!8yll z;%Rk*ak`#=AnPlc`4*l(!qj*vz?U`5c4!V)AfXbf$w_syeT;z>#tG}XEreGP^0OAn z`J|QKjo%Et9I!Tz)yX){(t(&~(~Lni*jWm;qY{-`FepL@CQ;OQ!()POD2?K8puwt#q5 z>sg)k(?z#N8l}!0EZ9jg+r^8ZH8S2@*OiRDx#W|5CS=0K8Ne)X1+v|K=7?$ygsXNyHW8PEKeThH{ZDOSq0)ri54c=C=KTP3e?hdiUSF)ZHK)|)%TmTpgNm=X=@pPNGZxGH|_(OJAAZOCcDP!%M4e|2G8cxUzXV$Q;a#zr`ul6CqF`VOM z3t8wpIDmz{u>>uU3$6UI_9?Uaex`kr$zqEAYI|EBt#*NN0SpoQ3p8ef)R|$0xZhTj z4~BXEU}|$5MAcQQRm8rkko(Acwzervj$Rl z@N+Uv!P~OccKa-Dl~`nIl7Um*eE5$ksX0ZFM2FKfZ{K@$Ql)bXoDJSL?@qs#`A!S9 zUa;yujX);ov+~JIf5l{k*KSL0#BKuWS z&Ucy5SYwx(Z`DT(9IjlHRhZr(iJTdnJO`OlnS|@p?LojNMG?O{X(HdPfT(ED3SJ<@ z$mda-UQwMmDBj@92*vu!q8~{EGZfBsbUW7PT~8j617C058reS0A_i@k1c;7ACiEeaqnve~_mR!vI?2)kZp zzH*#+&1{}IX=6%kf|Yjlo0@n2uLD&@_)nNDPbWz2pzvJt=t~twV3;#6KC&Wzc5xJUeMmFZYYg zS1=lBKpp|W3V?y%$oDOBCdC}~sio5AKc@$A_dx?{8YdvD6p&_@0n8T(04#e6{E&Ry z(Ht9u0yl)WZ>J+%@jRPcSd_~T^WK@_-bRw@2P@iO&#iXyguW;-`igfm>^RITpU!WA z+XMfV_t^Zo#o!ekoz$l*tvH|8DH-yHq`9xcZPI#T3PF{T3_RKgK-^Me9I!7_P7Ur~ zta*0(J#hluyMSy2&{P5DD#t-Cp;6Ga|2n6P>OiU_E%}pB?7@%1M5z+6g9*cH$Wt$; zkfB-b>LRXZbI;3M;MAYrmTaVcb{zP(u%Hh)F)#qL5FuEn;yRiQ zSDXJGpVX#&@IY+&J=hXj$fUAgPf?mK+D7<7iI!tQihjwWV&j&1cCJ}}-^xqMDopMx z*hdkz8)KpquzyWIFHZkpBoP3h!y1rkB`>+Z*{?XxNu%qcIwrlSSnjL&xQ_46e<7Pj zWRh!3dpo)igl{Yni(2k1is?p{n&U?B z%*@w2_J9L5ah}YOHdKgcYW}pY7#i2(BwYZZS@OiQuR)_oWB+k^rTjEqDG~Xu>J@Di z$!-!&l~?))HC|1`mzjc$;lByHf@`dxrpN7rdFq==rmw%%RtWZKanw{M{2{*o<9Ozz zf1{L}x)VwJs?cHXxW!YR=^t9!P3?f(_GE~)OKl| z1GCR!aMp2aMyCHsFgrRRDFPPoPF8!g&Bp?duyP^2zPYhiOezEvFu`{SA>N68r;Mes zVrNMfQB}+SbBc(wTYTp1hJs~OSV(#$>Gj*Dxf0&}^7i5P?^T&zulMf9(=@Zo3!RM; z3qh^*4h>bOn>?sKvX(JkU$-8i+#GM)bC^Xgm4+i$>LHAXk}S$MC*JVb;v5T8(Nus~ zmPNcC?_rvx(z(fE;~p4g$GWX3g&UP!S0RAAD5D7*T`H*=V5u#6nszRTVyA$E?PF1b zS%2Q!xe@s4o1B}HJ#fE%!r2X0$dq$^DA{TFm9O7~KNbo!H>LnaL6sM2nvv)JfvRv> zb>({iDb~=?aDRW_cjfd-J8cKh(WM9&8R{31p8u0<<$hz=1jJ}&P1r_$pA+KZkq zPN+tLq#*$T9!uUK29s^CqMR;(!9obvwi|6HKz{l!$s7QR0;Cr&-0{)kg%rU$I2ca& zg8vv2g3Y1Btwd++!U(#o^vLK(6Fjea)UWwu+i0|0g4}`CYb(lu$!iNG|&elD~nP!Ey8L342ynV*Na#@Xt9=>PHS}@s;ONd7sQ*xzDA$t~7g& zAb*U?xd6Gg&tdB|U3#4rBId=HglO%+VB`4Mg=lg4I|(hZq>f?AuMy$ynP+T4n))dy z85dP@#t4%3#&G_b2qNdhYRt{|)~e7{7fjo)>EE&V*V3D;7lXWascN8m>^mWg9ApVv zCI^7y;;=12$!3W2nUsgD;2T3pOPoFsN5oTvFu}BaldW6k(65oir(QB4!Sv4Ds`|L1 zaumDvPuGLRC|SUBy0kgF{RSJ*{q;}zu_{g^yV3*T4PH3{A9BZL;|u!HUsDgn`|N z9q$}WFUA{vH;etn<^O8|3?R>jS;puqpN#YkGmzjhqE+FMS&pSbf4iQ)gBzlMWBDBQ zQ*r~iJaY%0Cf%b8-L()FlVx>y|M|Fa={M<#<+kRGj&AFic=hQSfQax#&#^|xixYa$ zR!JJ!22!SkD|yTT0KnGP763d0h?yIIfXK4LAy`x3!`(FyDSGsi=S_A}5(z0Y9qRhm z#qo-0vl6RCVyu`l%P>~J0)Z;sG!wk1p@q6Umgqz6LG`L8RI>~^6jo$=T=AU#MZ@j$ z&;L$ub=sa5kl0eYDaDlXrKb4r24{Ho$6nAt$J{aC1wWd-+!tc`>(Wir!?@ zWA^WXdJzC)TJrgqM0@K0qv;xh>+ITf)3~v1r?G9@wr#Vq-PpFBG)Z@C+h*I?I?sD% zzWsO4p3G!s-RoW#dA(v6?!Hzbq%>DLu77-d7%?R(aLik5M$ek9Z^?ckHU2sMp4KW8 zTlt267N=e=IR)Q3n!_$Plfkr|X7N)JgJ_BSoWnld`=B&_=lNr8$k=vQ%B{ANM8Gc?x~DzN`JYP*a^&XM}5eCpg=ArRMsI zk_PjarYmMx%HWA&%CyBlUDc(UlYG+6-&_UiQYgo$?eu6rQ(AqQL=YZf(jJ7!hHqkp z58XuUAKZ9aiwmhRn5iqQ=~`*4a+)f_tJ!03N4Z4GL%C70_y0ZTJ$1w_;u$`)_ukWo z6IC~HDjI|s;xqy;W#EW*{{<+?RHC*sZULhbo+S0OGKuu`bYP1D;?)NBuAokeKdaN2 z-Wo)jBu8gLSU8>+Nw1-r(jN+?YD4eE_CK3huaQ=SfBzCOm>l`qq7!ZmV7$FA=heXO zwOPqF#nGO$uBFL`%Vg>rBrk0ZFR==%L7OP-zwgH!KpRb?h)@T=Of}tN z<%4Ta-_PtGRU@e7c?JO0o#WfEqu=N24ls*>tshV~_`Khn0yTJHM<{~x8|CT!5yf~+ zrdd;&_{v^8`Az|q2wGEP`ej2#Jg&d8lS0v;#@IbO5Ho@Pr7Q7&GNBH4dt$*IVguoJ z+D*pnO$gSCk(cO{zON5||7%B@FZ6bCnRnl^V#AG-pfm^zpM!KlOEjS;1anm`lNd7) z4`lvPLulhBUUOQQAoxAp?Vl=PA*fk==TP>%J<)6F;vT)evQIX@CUVTxv2ta(cNBOq zI-q%7D`YTRkG94=VlGJhdd|2&QCE%is?M!uC*3X{t-~<0=JceJZ!}q?G3w-h_m6eL zG2GtVT*Q}RWAL_J|2ue1DUo~HDpIipE*qRYVKFxG<%kELf`kVGViAAw5WgvH^EM)n z?T6{Q=Z!JSaREtBJgQ}XXevSyaWeElNJO)jRtSCe3uh~feE!aHo}PL;JZH6b#M|xD z64*~)v*`r6JRK*lDtE_8_VlA1CQc)PeB0s%qyi0J>V5D>X3uN|7O*3T&(YNIl~n$% zKWXOJF}?!Ic*_;NObZHYxtUrAVdIghN@Ppk;3t;yoD8q~VFPkgjAbjdxmp#zrr!sf zc08kcp#xld9!{$;&HR#6u&LMBei=XwiAhTgYoG}qYq9BF1w*f-vPopO$Wf*M%H|lN z0+^aPtHsO5*Y}TcS;n42Uo-Cl^|c-Y#gGvj`ISjA_;=z~46`7pp&py%r!P`>Ft}LP zxfXodxuZi0YPkuW9Rm@JP(DjceLA!3rZ=OOuq~0C4JI~VHf(6p)sbCkea`vSw(47+ zS$kYd#BITb?tX*Dj#Cfc4qT`0vT3qg{a~ph>KPt|W%RrD_b&@&N^z6k=HH@I(ZT{! zB~Y1e=+(ERh4UL}|C%I=RD?OWys+KPUMYzkt=Um_VMe_S{_xt4$jVY&gEwm;$F4;+ zr+61DPTW@_t@t^0u$;n>3?qWm*xUOtM3sPlMl7GJ6UL>7% zXg4Gj*|Nc$V31$+zk}za?>jp?eg3Z;skPxG*rtDm%5I%aO$VeZ(x%*a`1$#l9u><~ zy}N;M3jlHh0I-;K*ISBA-Cp=EAe)byi!1S1ZC?W^lkS_TlF?v8I40e^_nqdd`z+D8 zsBg7)=9^Jwg8>AncxjdN^bthtR68^1yi(c7?~?ZV_UtN+ik-Xt^Z8b8uKr{Du@~r{ zx(8|;-iHj|hRj&z(1;KtfXU8l-&)hOtDMa$>)~#49eibFie8-U+Giqyx~2}IKDm@p$!B`vsMe*_spEKEO3l(=~f+rY8 zS0a)b#ZqUa%be8R%T{sTGk^A}`(mv%*_6iZ(86Wrr9dskCv+c6GJBXv47nF$+OUph zjUdKDvh%)9D()xNj{Q%Aom4#;HN#FxmA(TmJ3Wi%2u-6}{Bfb86lnqboQb`jrv4$s z$xpRFP3)&l`e9`_==4;vmf&Hd@DtrtX&sR}6F0AdQgEBwG^HLEJIEhmDp-(yQztI3 z`@{2V!7G=k)?S1y)4HtkP)1psSd&O02JV>CK9Zoo4N{fd5>haP;-^P{uUX3zJ&aiJ z-2>&=k2-?@C*k(`mQ*h?TGxj2nY7HeE8bQV?|zg5V>&2<6E8kO#0bOZaZR6|?PAFU zpw98*FAxB#KK{TMwhde}>m98)m8z&#MQeFd)_bKP==5t zE@x>Q*yq6zu{f+$!A;E?F5dmgrOg>Dc>RRti?P$_B$OEMb}Ppt`hq`|QVr z%@hyx%jt4Dab%yhrk*PWigzS%YYR{c-mUyM@@`{&icZz-TtLM?C5$G6mKyh9e}!4# zhr_@wMSRom%CudQe?EZI7bn@cd^GeqD-GyVoYPqB;5+`+q6Ibs3=F$6s-mU3wFJG! zJ1RgM$f-B^|8dRRz#z#QHU{of-~;^UeF|b-P7YbA<3Q!N_tnm*&_SkJA&eZ^9VFKp zpC*{#$^ksToD_cZC#IdGen{)H#yDDZvSe;UGGw+f)0B?=@O-)qcW9_2Uvi z1c=^*IH!gbS&x?uE-$6dML`^RG+W49qe z81p`*(DKiRX4Cq)u|nz^iKjIvAfKI?;jZaUfL>6(!wFU=+ln8vtuMGh@4iL+nKL2GIE>K_n0=YT%x8k9cZ3a{B*nHA#7_n2U zr1W&={TuI$K5yP{d4}UEp}S;OylKd)KplPq0w|e^VAwBnPLPpk?G?Skcege+3039t zO70!+^Km3f0X$r+_+zOd?;m`ACK(0VGZSo9g{D_A!{hYW;LI@B&NyuIh&1**X3!x) zQLJ{}B5*`yL>dB1#Pu)+<@Ekq4a%hzvnpxOAB!AZE{m0&3T{Fy?bQK(i~&B|o#zEr zSzs(v0t|Yw7fF^JR;uiFQge?ZifP4Sc?}SYMa)QSopld*e;jCA+y?SBO_U&2s%70% zIREN;Iy+wjK@8E-#2e%P6=E&Yv1YP^J!eG zaha))Tx6sScGV9{ON>`#{fvNUjSyxfVVQ3Uip;7Rv$79YLQXDLOBpz?OC`bW#1iSoh#sR1`kwYaJXp{Kr|$(@dlelWnr?K2 z?2C|2(Z0rz2V<&k4ci#J_dh3*b;{muOdqY5%r@-sVctcqwao5$SB zBJ|X!8pedSdJ*4Wlr!`@W8k)PSktUu(H$P_biYWOY~VVGmQ%kid80i$e$v0{FE%XX zW*Ka-qm(H}-60)e=`#C7X1FJUgSQ3lLLe*|Se{c^q@&sCrML^w%oPs_YHi43Dfeu} z`MqxjADPrPIH{olT?LSu)ZN$TxDC;RB*IZw7Zt(fDM$~c?&8+oVkCp6i8~&O8^db+ z&J!|9mzOo11cG$MKtaHMS2C~rldR@9mWaoiL246QrFQ@$^Z8$p@y`3!jz5rYwiEFB z7s#YZQ917`a_PSV)0Jlp>|AGB1K)V(rofh1^6yOvTd#q;|M$8acC)UtJ9>Cbm-X?k zEQ~uGT};c-b56SQ6MuQt5I3tKqSAS6>33n?#Bxtp1k!nh;0NIT;Ou*z>gnmp2hJ>D z;_L|g6p*)czfLk)TZHma4olUAOwHOnuaK@<6N#(emn>sNOqYo)uedF>=#xQf>ER7Z ziXA=QDEd&U&+{4eDzLEh8iDC*!B{&+bcMj1lu_kDTWg&bl_6= z&}?r#f0F2B3RJL9%KD=mLWaUkZ$R#C$=9JDA(kN;2aZ@0GG^DRW3&nF?zAUkr-RIE zTg>X$d>$?xm2be~sgi@H1Z|HUBf=d$sEsjLet=n$U;GkUA8yHKb|XOu<4%5PkhwYD z*(;F5{8%9LVlbyWTVydU^RAN#CUcnUFZ7X9l?m@Sa z>m3#--N%Cwah8XGIU;Dwg!!$?>JiiseWf;1N%#lHd!#-!5Ve9Vm0&?)mKCoj*ZXRFKImJL_m&`>ja83Y0W^`OxA#y_T% zZvnp6pv6XckZk5ux*>aM_MB|?qYtMTlS@48!#{jJwlbLbk5T7i*PYwhu#3E-$!Yol zI*f)aD`)ttV9x+)bp__WjeM>tnpa#6y z#$sry+*Rp^!xSH=3{G(t2}f%ft`4Lq*4nSU`kr7VY@l4ozj(eBDe`OL>LHmbe(^3D z<*egp_rmma{8RQ_`_bU2WNfeG_nnPm9RZF+OlcHxb6CrckwP|uD;+#SJg0Gml5Xor zLKpE%aD3F)xL%;8k%tFhbH2XZYsQ+tHe+)woZ)Ee|6@|8%xn+v_O^bD%+QzOU!2wH zr%NC1a&A;JZOIX|@G43E-GAP{Lb(Ca-ir>k{wsD`V7V>k?{{5Mkd~X&F4~>tqr%Z} z_NlJiBe%A-PF85C9YqSqMtd1E#m)lP^jD6m8?3yjy>@%LWK3jc7ep7)mNa)SV%WNX{FJg>5Cudd zw~jq>R!h2{m`)frpN|TeypQ~3o9)Z97!~2V@s21iFLL?8fcx0F?zufVb!KZ}osb#- zLN(423!-E@wjzG?)9IGU^@z!X|9_kE$4$DS@88ydKEYgtz^4JC|0L-pQuUkNo(Z6K z45XMxk{>@PEtDZM`FPKUkS)L_`**u4wc*9m$%aDswq+*Z+m!Fl^^W*9f(@p>b|qUm zaP)i|F^``%`9{zxTPi*B7vZtd0#zx4OC$9OVc^zlv(>%QOY)xGkrpPnyPfW#0@qz# zx220ETVzyf>pbm{N#z#1fdFqMD@EnP1&JstAm>HA>}*-H2lp&<$2lN?VP#3T-C?Xp zoJ@5c$ofm3mF4koFnb=&03#CfvAwQ%LsBU@SE&Blt-&C-rNVs+@0)J3Gaz{jynt_k z-UpyFpo_KXw~{+MZk(OmZXd&!38ut%w@}il6W82pmaZ;#zxZ!7_AV$6kCMuI@l=^wYKJ=Q%*QfLDH$ z7SCA$1w~oQs|8YVbA9j;1GTmE?;d5);qEX=xVUxM#^v$@!Z&Q`d!VV{fux_H>e?e& zRq>$>>@Mp|q~!#rA5romn#mGt-otqoGzgz*mPYu6VKQvtY;3<0NK_&4u76qFdj|y6 z-RKk))|0du`XjfWI+XjrIQiKNqdn8u5!L^}UU(L^Q*1!taw!wrDRZ)MqH?EKoo zMC%s3%=4_cSQi22=Xy1aqs7WKsz_V6roq^jO_H*e!B~79Nz54*0G~u2H~oc3+Artt ztrDUQ>?0{*%p!-1;S4Jq#1rVeRk?15o!}b^x21EJ6GF1&6Hm75p3cywMjc773Ct)+e+=!%F&3K=WtD0`&C}#YuFn znV?|J9!_dl_D!y_`Rxvk;Y$nyWysLXPED`+LYpRs*DSyR6n+<#WUwTe}~;N@kNI z>`K5%zcKJqC6TFeh3!RU+SwBYu@HBuuIj8KzXqU(ax`73TRC>~?xwCkK# z;-A6QK~^56yMP|7u-)Fd>I44dsSs=Fkd)G-VD`YtIW^JGP^VFwE~&bf-lBZvc5e?4 zN=c7)p;#LDT%&>;_UJGsKRHkD$qvlJFG0&jIYVJMf#~mavt&uMS@T!IaICUe-vY0o z0~>&8O_)G&goYtYwQR&>gzqILpX5AyaSxC)_dq-~aFl@_<}`4r`jwR37XY>r{J2i& zt^>mQIswZPkm^9!2(WJs9DH4%VPBwB2lJN=Az$h@Na~elL1oQkFga#cKH=vKS}5kX z@0mvnx9+bG_RNJ^m=Oor1n;(sAtQJWjO>Jhyu7McnLTmp?~LH5ss7e`RN6W6et}Hb zFuzSCm~1a_hjxt_BPv=SXC2%93Up(ORaV4Ogc0$^BKKwzj5IWq8Pu%_XG9H%R( zymE8a5NOYh*o~Z>)Kn~yoi@FPg~zs8JXUlhQOZqQYgd*l&HP&RcRB1KGVhP?al)~j znY_P_6lc~<)`?v^T_c;oVXU&m6PBOGrniFRy)+@ikAzXEY9@A@dB{jMT3+Z;DU`ci zfHB!i-+GHN`Hi%#b_DV?@?(;4OkiB62WtHJpP000P7CTXscZ~9Z{A`V)FPzx3!!_f zv5oLUA{@9svSjKS#MVAR-&aay7Z}L^leiw!2vLd}X&#_G0>H-?&fK{0fk3yclcV!~ z18(EeOYw>#1+6w#*UkE9pR#6^>n7l2y0miY0D3x}>?uImdY{|h)-^Qg=8qXqA-B*# z(nZV!^%mA0Tplh=(ukP5T@UJ~?wWK89ZHnW6zj=E4I2N!UmY{S~n}9DK1jd z`pR6}sLWJfZDrJe#yh0<>Evi#{X@D83f7Pw-Oy;L+@c37F}W^{f)oe+QH6I|b^SrJ zm|HwlSn$>8Sg&3zHRKdqI~Ml2)gR8%n3XhO_)9f4HFD((Qs=RkCm^-!I~z@XW&)F0 zW9@-TLFfE+;RtnQe~RyRDs!=v5tUJp5wrAFHK(q{Zn0|{fR|+aMDWvlTEZ{m`I+5U zJOo9uQ5uQ|kenXomhSGNTE+)d_=2GuG%`x(@|9RgkC z3gu)QZ9)`9rDT{hx!SPCZKtMX9Sj9A{pRO)u9hUUnT641swxa}umn?>t7-tBew%BiqwX3I?uzLy@e^J zJh@c@vn*&Qqf&7QGLS~xlmmopMTTp08lsx8Pyl@JZZ&dn4WupsCG%zw0{DnP{vsg6 z2h`ty#q@J8v0%=srM2})xAr@_5YBH6H=0=Js`^;WzivFKODK{%O|quB@0IW8_db9e z@n&0&AV!ka7M@Zx1Q5Bg3dO8!RxffiKG9LeQY&`4ub3DAvfG*lhW<|r z;A1}BksBUTJGs7vwti(?!&-&=OPv)WWWsb907&1JX=Jxdf?3PmAUv%a_H&p2T{>&_ zz#v#SAIl9;dUP85PO_3}MNEnHbAd%IIvL}YG2dbSCB10;4gGwbJy7U{MS8$j^YfyF z)y|CzS6c$g6L0q+d=b8^fX)A3Hew;)&$BCnC*nft067a%by09MSF0;WLI7;EFe0RP zB^?T79D~v)Nm)Ae|LsR@K_FFOW%oT#GgVIwsWmZUj&SkFza1M4gtZw+m?eXlLI3+Y z)|e+(fieYvxdQqEfv1a)kIk*2J3kNqk($t}cXwWd!62fxz}I~cr0EY7_m{mT$Mn+r z2v>~W$^(@fo9>~-KQ@EM{Nt_A^aC_9v-#94QX9PVxWBHn{7|*Yjw0kM-l5}8=bmW1 z7HXDg)~e}3Pi?Zb(KcPHTGKw$Vj8WsxO?v#gf-1w^8I)8BG8a(kCy|+H*3;Lw-+4e zSaj!Q+#=LFcm@W2W#K!Ew_tWswG!R&_Vn*n%RI8luZ`x1w5B&=MjlXX&|mx5M?qjG zd5TCZ2^1m;+B5a1A?G}Y>u{7tD>9{=*!_83JYR>LF~_M0ZAy?{D-Z~s{R=?&-voU5 zr)f#bZkoP_WN)i(+t4zgpfLCO`8oc&4(FzHUWN8K!6~>>Sn1uv#)^rpca!&kfwWt6 z4e}cqTjBexik@19h?_kX{_U;v)7*F-#RdceL_C~O2?rZaMu@5+Lv6Er1t;`nm1r~% zB=U2E%LWEH+AM7vaC^93R<64 zZ_I*O+{J6p9WmDxJM&`iv0hM+kMHeer4Q(&FI%W|Y;vfKwX^T9HQ{#&b9Z#d1UzM6Ri0Ru%PeS&Hl^Q;Z~kY_&t_*udT?Z4+{XIPx@iEOi?! zokHx7rHAb&ICC2O^Kf1&#rDy_*bbjyJ@-{)2RdflBNE&2ukLKhv>kixrfwB_rd;Sb z0vgH6H0q(%60zOWb4n^f0S0R`1AZt%c7Wt5}puZ z>X9Gk6R)t!O1QD`qNci@TV9^#rsb!VJ-6Z*oMVsup0hqRYT7_NrOSuN#xx$cNYW;( zQANwgsLWf*>(4+-Wk>&da|HIHrMGdP)i6C zN8+L{4HE_7J&wfRV(L1DVSD)p`5MIrzRl%6bRV~1u+`Q(W#kNJdtV>+vikZfR6-Ru zO(BuAs=A~%+srO3Ooz?Xi`tdukzSjhL( z0#nr#9H%oDJm35m6noL~AII63JqceBE-r<1VeN)$E8c3bH6ljrHE*)H#B8#X*r#fF z22Uk6Z&-AzDKDe+n#Y4Jdd(`DM4$9`{DQe!b>enK%9KOnd@xdUo{Z*@6=gK48II*@ zE!ko#*Y%#=I%*s)lD;a)L~7FX1O#W{<*M8%dz>7-Vke`SQYeS1O~^Sw=FHxZ+afN3 z8!oR{3fyL{7zVxr`)XGY;!aOTM}z<5*_n0U4(AUHG}<6l{go*T);M)W28O}7e1-Dh z;X(g{Q*~#B{YyDYwA9XF76FKiroO)V;on2wNKhr%!{Vr;2D``|`nvKK7F4AnKLcl@ zGwMl1G<9^UtDyL#>*(9#j7*gF%CA7sM5oF&=e?7Qmw|yG(plIp)Ye%;4a`I{P$!OZ zG8bZ&aCIuyZ0c%6#fK>p>|9#5sN=Mq!+U@D07JFwj?*xASgqNrpn9WaM$K)7JNF=L zP$!bHHy&B3`PbWuF6!{6_QuBW4Eyz+EavSc^^_@WYecX*XP?WZrpXz$j)A4}U-3ZQ zJRI4-a*I?Jhjz)DOLB#<2VbXye(3?z z1Y_Isk3?9@#!4dcvYknUrER*)!z$Tw#9cVXS~M`>Qt?$3h<`l z_5EJ6XKp}(lt`+!`G$HyiLRXAtx{YMn<_eXg=9<)buu_Lyt8cv_KO70%zTt1oe*}K z5JN7?P4663B9vFzjLYVi8aWGl%Yz&*KU?5o6ZLx_&egc_jNNu`fQ}johYGB7MW90MQ;+iS#pciA<=dHY z_OD@no#(6MW_gX?>Rpbj=c-#unLqO1|5yUGT$12lq0bSZz)4_kJWp1YW=?_7YQV9! zb2;%YGtQ{kcJB$~f>WhL!D+wO7Z;Nis)-N+eTS%2n-O1V!Uy&MqzIvt`%l$6G{O9^ zG=iCxM0u->qQCsJz#1s{6Ayco&*b&Td=T|=f{>zcT6n5FyC<)(l2(-dw4)7by};&* z5!340T2fy(35TR5lz&I&kKyme;6lml<|rWgZ#V)m?)0p1Hd_CzYH=4%WdAZJJPPSU z#c=y5SIU&-jRqO!c!^Vn*ADWnAGPpVbXo)sdUbM}BUDm$I!=!7F0QCy5kdDd(f*+Q zo+C*jtzM|^h-(z)D!w zZz6%Ld{6n=ZozjP3XTWwC|CwK%~sGquc?pSyO^UL7G%Dw4k;HV3VCRXN-(`)_dmGe zQmh4Qn-Hdv>maqf%4L<@f_AOex;B4ZH(i?J1~}MOk*kThVnLeLF%Sl6M9jRSM`uu~ z(h5%Zx2gWozJj}XrJM0_nZBL$gDL?U$mFV^&bSSw`Hb|&lBcEE*9u_^zU2LJ_x^|1 zcPm%5=omRM0-@13vaEr6i4+cznrJ(L7kH)#3aNj2_*RZ{$`u<$xT(AK?>DPy^ZsF; zWt9jwU^0H8l81I2uk-1>cZ>ks6s*_Uc2?9)XUeShQp!CCuP%K>j9X zM?}X+oINPc+fG-W8~ybRnW|hXBcHIUEMwWL0*yPW_2^G@i0@Vx83{A#k8FwUMmR`m zQVkKV2Z-{hBbij!6;GTLT{UO-Pz%WX+9UQ`5efRMI(Hje)P4!?br7W8<%K6|=EVVW z%v@z%Ud^B1TeoUIC@Gb}@RgV+ut73{uqtxyx_ZZD8nz2scfBX6plvqMTDl#XP9(k! zf2mYVj|ownEMtjON_nsBfgmF(@dDo=H?kg5DKlnn%anuH`o7Y~p|JRsPbV(Fhd*lv zBME<1i?L)%WA%nx%d1V=U`8c*x1{A&_vf}DB=ko@74jYvnUu)Eku#33GK z0mQ{U1_|aB@e)`~B7tt?7f|O>vS!YHes8;=5Tuc==z2{Uz0c1g5PM!7N zmD*`B5mqLRZi20bRWp2qYQ-3_+ALPSN8)J=J+>Rs}jf_qWS#Br$C(~2ATiREHIqq!xuCbh?hL`C^z9nYu@}r;6$hwojAaU z_|!bCiVfLfCb0Sc@bFP)aZ=kp`AuoH2q=4w*;!fYo!b}5G@db|66HHdpa*P^z>9GI z5=jUL+t-*6ldnbb+W`aaiaH1grHihPKeLs{`K52#VuG)m5hd}V^-`KA57@5;X6O=a zyw9~S&p^b&LmhxO)uXO7H=4>gotk47Q-T;=XmaH!0cyI5^vK3iQPY>rMMcDKA(gML zplLZb69;R1KbUst?@D+3fsbBh1Z>$!;%SbW7}Qsvh2;6AxLl%V4;LlmSD`D2g&h7>W%bJ z6>zMDX&mutu$DqQ4%)_n(qASLAy3f2RBzf`>x59XVMvPEs||$alw7&gULWgHIcD!v zi}WgOwz;X-fEzEcb!&+%EU(>-JJ1cohLppon57qgv#@_j*i71Hg z!8`Y1@N#j9+Q<+c>CXl3pU0#LW?=94ng-rSj{%pD0RX@AF(CLB!XTvWb@PtM&07D*a1jc#|9 z_0hXXJ|DNSp+=qrO)v(TpTt<`7yz<25MAdBf{*9f%7C53KuI2_p`;4Gr|~_z`bGlD z9vlLD8j(X151SvJjIRDUj_XVi@;=&WYLn_2Fq4M!g@B%sqf+dO zn-tpA7?EEgM3--b`ito-tcuPBmLtE2kF?m&m#01He8%AX931T+S3~uRtf-a4fE>yB zli;?Q@igpviUsP%FK)G)?AK2U_WY~ab*v@6Ea!}MAAvwg-0nj*WQ>hfh`)4QHO@3} zxrv!$CNk@h`Aup0kOU^OeGIwTK>cqV4{osVCOu`4SXfOmBYx`}&(qr4zX2Jz<@`aP z{?$RE%*IkAN7?+BKU+B2_+XaS{v@I`m4C0K(`M!w5oK0PZ2pSblz_H8IK8|2>4$||tkawZsk=@DP+`N+*le92D+5*S_d ztAv%*t=K0LqK(uBYG`{*%6}F4o>2XL$cS0WXfH40DgAZf9#aW%7=8uDgc#+4aerDw zBEG~hWO%q-5K;1jLuDa*Ce;cB<&g*S8$Db5XvOO4r)HfJ0eHA5SkSyxXjWz2Vv;(1 zqk$a6Jo}bhmMy~{@K}!JMGwt<49)1Swk8N$HS?o4$xsuf*k5*9;W}$5SZJYi9vbRa zzZFmTN5SX22)pWDn+0E+fi#l;q!RU?FZE}8RkKG8+mXY>1-c$|Wdh0vqAa-8mYDm5 zW2h?do$mL<6%_1bC|TZ1H3LQbh@Ua%jL0!*KhnXir1;uGmM-6>F9ALL<3<`iSJ;VU4Kg}k&aB2ow2p;YM-^$uFG@S>z#jTR%x#8 z=DUD?v~Ep3YS8anJT`w*(7A=s=R}8quVyDc`uU>_tq3#uLE`U&!&Y|aJFX+vQrnQ{ z3v7!5=eTuzw&L$uD5$_h^1-T8a@^KQ+#M{Vf|Lc~tjb%$mqI6H>p-$6E14uuJ|58& zFi8dcC_afa_wQ~LfJ{0&R>$qzh#z=2Rwt%%bSSTVi)C4PV-agm7^d>ipG|a&Ao`IX z2K7|&wXH$Q$=*vi14Vdt8MGPNm1RDrrlz*G6A$xlC>YBHpp3c*S$;k@6VZll5eRLz zIJhDmM1OENrr?HDS9D>VO_$tMJ(|f)2KWmnmcQK4{;-+YcsjdIhRjDPvvSk{n+BQT z2OA=CG7V*|jR7NnJtamOGvLCJ2pGeA!1Xs)Cnemx{><}~*b$-*xErP#2Cf(C#FQh= zll+;P`Myn-vP)|mtn56TOzpA97EGJyz&x~MaKn6Fed=*_P{dodMDUlu9`%yXO3-BK z7VxeEJooxWc3S)G|S@+Gx>dhAorgBkcCGKTLEan5f60RGdVd z25>`orP(tcNs-hg3%<2ZC8UR`Yad3jXIc&Nd@9xg9teBZe_7Lk9LW_MJ{|BH(texo zMyAgS*KRe@lHWE`rn)>f%7+G&I&h;o?fwK;x`5NFdZ^{U5P^`SI`4qB--U4((!%vXQTL(5PLd z2W%WbU6o+gyxVi(YlAQfHtUT;bW7)zPV0haO z{Cqcrb796uJUZ?L8VWvgJ-=*>UAS5sQ)A3Afyy)8OS=zKXU;s^Gr%NUD{q|zg4-3o z*!JyUIg|#|C0+tOPI__SF*%RGo#6wr0Y>x$wR#+u&ne|rkD3o2=NP-4Ix38K zZhhz9HBgvp4jL?Q)i5```kT5GhYf%0Fz!IMyJWKt9=9)hbqassA4P2ySJ^nC)c8iC zUax-CZQ3+-1-H+1@??6tBX>=9R!XbI8k$Lk{gGnC(=_=rVzp`r2og7JTf{T$mP2ct zFkL%M*!AoPmSxu~A~kH)j2E5T9m|lE3_{>wbvjri=?))yQMafOjJzB}JaNGJsD`mS zXT=7=b>7Vw`4H^Tqijz%6=lq`+i|s}*X88|lv+fZ`$NF8)bD25tXNTckFBwZk!QNj zo~%jAEq{B|KKNpx84i3?ps2c4h#z)$#L)ed6_l7F^!@LNU0ZPh#YyA(>N7p1WFATE zT(g>^H6w=wB(AX~x$WU58c8kUzA=@VK2?xTzNA~_icjLBYDLrlOcXgR9!XLOW@0p_ zdYLF{%DyQ=pip1AhghwzMWVcon|`dzMGo1r$L}OCRa`eCn&};JJc0IAa*w%`B;6F> z%)~j!Wn{jDRSR$sl2)j^>iv?yK zcyY_nuIP<08y>rMGdP2eQ*XqpDybVwm{PcKILV0-HT}bR_2Hfo2a`}#$CyrBSVwu4 zDpjV;+KgJ*#od<*D};HHqI}=alz)ZKEH_binM-4WNe$_hQd+4kyTuJ52(i&Uwwk2u1&pqdbEsQVYVCfw$rAki*|grnvFvLfXr_AftaE-Ub_otyFOXpEM=o5#kNI zz=~RyeNNUE|7rKcL}{PVJn}^aN9doc+G<35ZH82YpzUBar@ioV^_p8FCJ74N)ee`P z2+<%^Hqk;0oT}JV(j4OpKx70w{?p%IRDeSjpx96j_q$NjXf1gYeuOnK8vD+p21}?r zCOc7-cW`iU?L~)IV+dyfxG8|87vlnVa^CZkI9m>5+yPKHbzu0L{Y688Em2PKz81Uq zKp{`6{6zVE?j?2s*{@NlbD)0S3SF{C1#C-Iq=c5KHahRPqtjQ)|L(_#O)t;YZSl)O zm&EFIll>Jkh)?rLqzYvlckOB+hDw>mqJCxX4zZcPayr#b9naDzr65#e#5?2XDK%zF z;-U|s$kU_7Oq@5bkwEowI~|`gb4_m*VRggt(HqSmr6HL9;sO$-6C#~fY;;agiDO*( zVy$g`irLvAG-}ir>v;pOht35YMTLn7=RO4ecmmZG^f*diz5f4=n6rohF< zcnh*=j7Ik-EO~(Sj!oM>dYtQ`zrh3}PU59nOSfC)EB-1NuITD&F~?8gK8t8 z%M<_m?}q#+`=+2*yS=o-CZF5*qUrf!{Qk1nxAL|CA-B9^w@okTvm%npgZ|_Bs@f*T zygWREPXj!6wA*M@ufuDkLjD(Aymu1U#0bVf-#Zk8N#_0p%&1@}s=sVQ-wV4Ml*0|Y zyF0^NQlx~19zNV41}g*1OQ%A}aJ4MSo)lE5(9_pbN8zSFdVY5-;8JLoq8so(l%ncQ zXswn-C@<-XZHmQ0SG?X*V)pPQoEb&X$yOwAq!0~`Ql`cRC57>9zxus5E(uK$sbYwP zHQp7w;TZd%`P+V>Y5aYjm7w%mHs-~iRIr<#5PRlfjEq@TpJj)f%atof_Eu5}9ZRHA zOBg&hSnlWU-U^6UH8b^@hmHo9`eJDb>sHEUk`#$i1;!HYd9@A2KW(ZvZ=3At_eWpOB{Rq9guzbnOsSy_PsX^?bBAL2 z0&x3W1BL8>5N+i;uPIvN7};bCA2LwLsa}90ttufqs~W=LlNoB_kw&Y+w4w3^-%0Bfx<%@^^1wfir&;^P3+T~J&lmC zjK5*}LU%>#Tw~;~84X!)M@LgSEBJ~k-x+UXt+A$>dy&_Y=zhGDsv+fG zsky+Nji-?+p;)#k4*QjcoC)X;zjbE)1^4tdc`>8PTvZq|h;@?kyeV4B+;2=72wn?p ztc?jH=pncMA?E&GrbM#G+yIF`-Ln)zrc&uI;km&xjw^=t>psizxVm*l%}A)1@VP?G zhNM!_&-|@}%(UvfasP=a`J%t9^0n|MIh)ElXjIP?cCcpPB*u_I{#`{ARq@ZWF&suN zJM6)x<8xrOdT^d~BE*s1YN}SJ!<>E=Y{tE&+U>p3)nduP(onrskLZX7LA}X~m%o3H zhm%u7O`5V>c_{nX9!` ze?`Pc#tv1s1`?;bw4p^L8|Deos>IIhrK`wR%o>Vu=JAL51!zQx2K9#wOhKg1cb9mM zzex0GRPy&tZMv_#$pCIaYj{FR087mb6EBGSU0ihl$l?W5FkXBg?!wrBt9dzQ%};54 z7_f5A6)m6&s+)ah*AK>P`O-hixSXK>Eci0~@W%*JA19OjJrVj7!ER^V7a#$^mA9S1 z$h8+hH9QY3H3!_0-vX>s-B&wPja+!HqQM+qvR$_Wo`Iv1Ic@ zn)l|}S>;o|f-#~|@CJH!`b%t;VRC$5*8!x8YE+`#aFO2K@orX{C}U&kPqPztGAY0c zE+s5|m}O3NA@uc;<3wjzMcJ25B%cy9Dc7cy3c*(7(xge{$#*bdsik@Dg$hR8xI>V| zQ-6zLx#IAplAqFNU)JTZglfWU!-&ZX+!O4WSK2e zXScj-F3m<=Ktt=y(*D>G{7s!5Qu{nIWKx}vfX66$>zzn?a8)lvTLe$e}8Me=kM04vs!z9@Z9%xt%Sqb z_w%S}q9sGa$soKelBwTqS45%h+S7v>)XKKM504E-+C9y7)b*I$p>9_H!ABU48A|HQ zn@`8<{vtHQr3se5T}ElyD4MDH5OK7Ge(C2ru8bCMLW~uY|2vRoiHIP zhlE?yjg6e2Zt=va^u|8h&+K+okob98%Cf$9jIuR@3TN@X{80@IyLtS-uIw8t=Dp3n z0yi{b<{Ej$@-?+}oDO=N+7!2y!CK*S!awi{3)e8lW(vA|svf!-8>hxhgiLZ`4CgBi zV|v=D45}K+thD?A6WRgwC6o(8Sd}&*ZfNK1gE*4XO@bx_n9V8}{`p3c3~FL2?#xHD z8Xe3QhDq#yWCw`_FshSu3#LrPyFb4*`+DZ2DSax~fUw)0`hve_DAwaH7+MX9tEhQb z!trOOkT)Z_;w^dTiiAR6;g#|y9FOLrt-9xI2$-K29n|wkg>S8`Wgs#USUp{Bf8NCT>zZ{EU7iD& zkLKl)KM$mFUNLJQqdJ)C>Ewu#!L!Dn=lMft=yH?P#(7Oky}DN50ZRVMTD$I>D6 zy1KfP<_$oC97x#XBNDvqZN*VSkmC_T{-F!Czz- zf}Ja>jpolt%XZ}2UJ7d#Up4}Hj61e>j~B)3S!`d=+gzWd<= zw1>Nwjc!9f_ivYF6Rw4(UwM-h3j6Mu)(QQ6^yNKVGJ-qlT#w(;b+OvE%b7#`q)tba zeFyh2;FzVsbj;_kzo8UW)0vNlEcAB#n0qOZs4V@_`>Qm?ITvQ*{6o|gND*oJ{LxgO z8FIm!hq)+|)6CjT&oN2vJJ`JTY9CTe9>;`v6hAR{IWM5qP1V4=AlZgE-^A8MUa!Fl zawqAryV1oS5+Bn~-*jP}Nn82uwPOSJ_mwtQBR$0(gI2@%dL= zg0!Dh&80N>*0?32=Q3)*NEWz!BDC&;koEJr^8D+M{`By%0rUt`3dWqq5#y92xkMS$ zI}|HeL}ydN<=$yx2ln*9#fd3sUnUuty@ku{deNMyP2*6+b*tM&lkYO7hpfV~_M1E-Qw-KAwu#gkf<6WvWqB&9DP+a) zkVOsZN5(|RWH|C2f!_;Bp;hJRb69CV$YhK4U~L{trz+RKiuAZp8nn`J!qb`=$wwn zPH16r6w^qAbH1SI$^>>5n^&*y1&XAe{#CjML`}@Io2Cv%td4?Ifaw5$18HP*a7&)#Qw-~0)JcWP{Kj?@SL35j zU`T0bDG^cUd*4}kP18Brm<^8M;xX1k@i0);3dF8&sa%wAD5BU*lT;)JgAAjJz0E6j ziK13b7?3%>GS9$B7uqEs5rV)|{rye97u`)sa)l%$(vH#3Ex!k@j~$LCd-if9tFWcH znPT}7i0ZIP{Ih=MM+mNllntW~`ecQ#&6uiU7VTy<))kjA4HQhuIZ@B)Z39x>yHId7MB~i)}NcNH)jn5!PnK z_A_<>cWAJY#^DtC`s@&wE|3c32}*3YH2mFcfN%VwNwOt}!&pe>Q?iUA_HYIpH6}ev zUjLU+?!41n3vvm+ImNu~^-J6PZY!0w7%yC#91|UOCK72x%*QuL%A+T zm2&FG#(e_dTtR?AFw20?e@ogR52q{%(Y%tOHd1Q-^)zeS}q@0c@`q zkHcw-T7891 zOIuKx{q~m;!muh6+2XQQ3LY5-1G9!Z=f$F)5`kae(zza^57mm*=Gpk0gUoEZtPhrg zE1r>q7|_X8n?hhe2<6D1bGu`{tPZCVeD|q-Am$YR(93(yYW(JKH1#Wrn<<+o@!@=p zM6*SQZQ4RN_H$DV^@7P)+a-$Ov|rk`6t#RtcED=dsO+-5*(Iw*qC$#MM?U2}oE?U2 zXS6@ujO~VwH_Dw{D&R3!zyJsJN_QPr#9R|JP`@ZQh_P&tktVFURkV+mMzJ^1|YPi8&%E+4#r zNgnWtv@`rF#nJBgMaL{=#3c7&jTM3H6!fg+69$Y2tEi$?o{3rA3}K?xdASWxAkqE! zKhpAl{g!oNNiUl}S`g~#N0wD%SU_X?8!TM7kg{`HGEW5+lR&b6*AnYI0KcUi>+l09 zM!%S2A%^@J9HXqN*=3RO7Zj#MzKb4lNQ@m`AANBfOm6r#?)m9`Pb1w}Jm@HMGcf=n zNlS7%vQ{u#AURsg-5~quZxtGftx~_E@*#Kn{Z2REJ7xNg?nia+#=p+rk)Moz~=Dzt9(=^NjN^k7jj zd4D07pa@a0T@?UnB3&kOs1_7*%&&g~SP(W8xho<9uXG6_LYLVbE$W7rOE zpe7$-IW_hz&1)XKvQ8)xNr(bZI}yXlcHCq2mE8)z(%MoROFvk@QBK<9??BzGl_W>D zJcOZ@I>D?IklMvX3=8V( zas-{kopY~D@qw`C`?!<@qYSP1Jg#>D3Im6Yj^}<1=h>H?Vob@*awtqLO^zC-8gr^d z+UU`Lh(*KOQiXwO8|w3|;d`+PO7D*uk&uKf8^%CQP{icBYf{$$k0X2WL2Uw*PKL=%q9>Wzl;s1 zh<0q{X==Di9Ff|R)h;2-0p-~E+jw#Bw4#tXOJF}EPScvzXx#o=OaXWblK*@jeurfV z8efHJlLLyZyh|s|HMfnK&BZ!-f7{~2zYp_x%lG0bM|^t9&QQRMC8w6!usZox|2y)s zYFw0m1mI%=%pe0@T}xFKYU!$swogoa){_IZq!N3&xJF;eA;o zptG*7uBoXw*xMpy?F%c&(ccvJAQM)ufy5Wn&NntG@giAY2c=#&q7LSXje!D+<=9P! zRx&CJx^V?{H_>Td?=1&lOkDkbdzugydG%oqdRCZfH^bd?lsR3$tUsf{ zXnYZ<`MGg;)vUY%Avh_n__OG)>YNfE*MGKdDV}{;{-RpwKky*%CelnEourU)X~ZC| z$C^nodPZfgAgKGJt(h*klmgLd{z2+2(CXiGv49nx%_uMe1&K`yAhos0c_T0wc3Y^l zizkfTG!6v?1&l8N9K^F47~Slkz|YDGvk&PMLE6VaEhZvHEwf2gdW?fPGb9oBpHPOJ z1W5dWrVi}$=lK1Hp^?23nk|XFSJVl!)@$d%hn{Kv&N7sZyFE5{PSVhN>}w;YJlXAM z4>A|5Yu?$_fa?Gdb_w|XdpIsriC+1Nydx@Y`QRfFy@M%}5H2n^e5x0*X2 z60(N~j-pi-^MQRZ;01f0JRqMGGCSG$ z)5}3K?T7k8eKq6KSMtCt7_@SWbt1IqGK~F}WhqT|y@FC#f&x)v?LSUk@Yb)aJ*?3t zmh&Rn36z@2eu`|;%^6pC+`9P-#LP+l`VA{SPR#d;HX_E%FZgm4Xi5?9>*;DW>@`WM z@xf*FLY4ErXp4=AHck2Iqf+!pQ=VU87N=)4qI)!Qe~qgk-mSdXZyCZ!&`mZ9Ie+SP zodA1+8E(FY6Bdx-&*^EFqu$U;%rlwJPOS_`Bk3c#`^aV`-^qu82=-B2SN`Q^d)SU& z^cZgr^K3l9=$*BODT%?F=lXNpuE@1hbz;PIRT-$3P`)>61el_=mDBP4_p4&m2C_8_ zHe*)urW>pJ!7jwJl;mOy6LYWBxwjkLwk*9+yA>>wQaW zE2Nwy#=X7XuPU5U;We4AMG&w-B^&JQL^ z=unC-7WeOG->%MHXLcQ^V*6cq-p!n!hVksN_2yA2u}F(TD8$|{ZXe~~R(>Q85Ynz3 zeIZHk+P|AaxfMDghmo6DixxsPE4<(B81a;c&n3+pX~}6Nh63N%+)KKRiTTNlX(^`P zZcIM|StBoD(oPs}VW@ln8TKRu{RG~I^r7066rK=E#BgyV{H~Gi_-|lmafEy^WO=Xw zSZjCu%Ey0}J;an#mmgKCw>c_mjqS&Kw<}N+a?|OCQ@vQ@Z2dKoBwlr#R9xQaO4I7( z!|)I!wWC}5NoJu#HY!zaq4@fem37keP>zG^!T3;X1+Sg{arj^CPD`_b;yS^Wr%^h! z`Wzsu0zT23n;YP2re}M5ZOy5%76x4zK07Dp!$6(Ek+^95s)qptK$*g?^ zoi;9ZlR-vIZaW?ibcc_7gqo*B&3ix;Zn`p8-uU!ye=P}+mUP=W?9 zT@wk)EpJ}Ad3lp`{=01~;_>3t!-C}GUg?|q7$orPT9eEo-p(3oTvaCAeRiq+0;LC0 z`1*7su^?dB7Zn93qyh9=>&^fklbgFcKzhp-MajPvvb9(-+q@t}=d;7DI(*k>l_Y6p z%2y~yd0-BW7Lva%Z6}vHAQSCShf)8PoA++^eQbhsJ@XKc8L66;HTG%mVkiGE+_kVW zRDUDpXM|kMKOCIp6?zJ_RoF1!5Ut>XGR?;6>Z=Ur0t6aI+p7U+spX1cx-;*no+3qZ922^7;Zmc@IB)TifNU(4d z)@UYa5Sr~LQ5h_C5?^NcyeC0>?$XtfViLQj23LJWyi^byr9H~jXI!5_Dd zXV5fh2>%QcsP-@x=_yo)>(r`lup!4uGkf$TIXN9LlcsTFgG9Dvt+{Ig{eIiVn8ZGD1C zM8lOra&4PPB+@>4I4J9m#_WOkLiO_&&Bm*aac(UTd%JGHaqMl)re^4x=^xe!Zf~c~ zJA;JdP`oJVZ(v9JA4c`>-^%Lhaq&%Q*conM`vGum0D7_|oATD9kHDuIU#&nNn0m^S zm&uc@;(J^XY!Re}|9RZTb$0|Mg;3JO5a2iU#>rBvX9 z4~Z`1Cy=>eAHQ)x&n#;MujI<@E1NJMxROn#vbkz}Oz2Ii4N~gdI z+Ub^|tGm1U9@|=@FzkMhjh*oqRtFYE)$lxb5$D;s8UFMWhDYR&84AzTC0hYI-6L1V z{tuseNnG1bf$#lXy%Y)Y^-~T-6jno@w8DlL4Z8f|bW5akmi8(+HqqZ=;EAfJ*6tUk z!j`2t!7`QE@nCbYN;I4g8}4IrMhhMsIuY#cK|m>n9P3Y%t!?t5??HvCMpg#SkiUg5 zs@oS)*Q%$zrCr{V-@ms9>J&{oZa5*+*Cg5mD$|$su~Q~dNW1_D{`Tuq3y{W0@dn!4 z-M-#zxC8)j8KD0D2cH3oegLeKUk&%&PY~>>ggp%lySQFYDn80R-lcY2H{usf@&XFS zUWc4O6Q1WX;XQtw(bw%m8ZolptLQWxe>>*y2Y@f3jM;yhBAd|k{_b0N)NRxK2CuR| zINVcmN{_pM*OA0F6kk^p5`~;V=l**|4fi%oR9W&9(C5hltf z*1wvx3+IkgX+xEw^lxYA37k`NxiF>h9@WOk6e3Ai!{oSoh`Ha~ueJ_@NIOW3dt9|! z{mhbU(v7$BfX9R~X$)9tA08eyJKWWDr;qPWUCt~CFGly^E6mjl-Wz~+lZL3LfYgr^ zZZG)p-9D7zb>>p*U&KTsc*ba2$640q^7+V|2PH&M75Gt>TxL}+V&Fz7&&mks86-5! z`{i67OvKIA7;CgDYTO_|z@80&paJ+YfL*)11RBE%=t13jMlR=Y z&)%CYVWQt_DevYHgt?y;)asGIjefiJ8w*Q16JxO{_ft7-c)wk=2tMxw0Rk8r6zZ)6 zpoYHQVh`ZAVf!mw#fHp4a<=?JWu9@|>F4}t@adN7Bd2x3{W9bn*JiN=v#2A25Pr>L)R&;L{)Tms#mgoAf1}u2DxR38uyu7$Ln%cMI^A z@30gmt>oql9#9${ezNtW19G-Z*efj)*yJyEvTqNw$oy_(x+6@BOkbjqN!)FX*eI{X zwSAR>Hl6^!tQgT~oF_o5KM-X5QStv-fCE#ObU-@9fCtp0EnUcSpx2oUequ-kQ~Y=f zee%4-rijf32(PK+@zebdv78&#VdInMZPbpS#royAHj@uxuT|hSERZ`t%Qz2P$8j!X zjguu2)C8v_4`(ZKwws-P3y%7t*9v(*W6@_OwTT9SZ1>(;719~d#Tw9& zg=0oSMXaoo%fsl=jMuXRxkO1b;0Y^CEl1gh`D)$gcnleaFU7^VzU6DL=0Vyc1MutRVK^; zaiIQIA8YnxNNhcPlRljcsYn8PXNzg{+wLK3?xc_$7%r$s4MSrT34v$|| zMJlxm4#Hs!L;~LeC>1SAfBDpl1n2X%n2ZlC5ORNdu(9|3_}6x@2UJ=Lf+cbDvIjk0 z4VkVXfCM)1&;SymYmGi#fo?F&ICvtZS9b!{P(3PrQcE=`GNLEOTe!wX;QmI;B9DnI zO`XAAm=9YZTa_PbjsQdUkBP~h{Tx5Ib+la5t!IRTW6p5--+FF2;>_e!wyU%Mk%N?y zn|$)fp%7E>TL`*8QmGP6jM015b$9s{EcVWhjd?8Gehn>PM^?DW6)r z-cB(31IbrDKE6(1YYy210CfN;7(mU4%+WM30D#Vqz#Hc237CR+<2{_&p-Jr4r!>os zp?)*P^ft~%WsMbRi)PW(pHaj?^7q@fvDHQ(`q))GnM4Cx(M+D zUq-ttms+ezA$G=cJ~t2V&+g#Y&sw{k>ViT__*#*!4j_6oY3c0j%!GYH9WSFlf_fCq z8KS}LajkqqdamygDjtOFg<`LMgr?+sTB2uA5bm|i(tnr$sq=L$fF-$V&GFft8nM5C zgkRcUxv&h90ABgLADnnU5H;155Ah$mN64$y5qaC=`HuTE>!?G%K7()p#mUPw-dEQG zGi)@dsb(j6(tTRC+gbLJg5v%Nb_eL|wxEa()iImN#C==wfzZnk7#<;ffqRPL3_Iid zHMkF~Tsk9Mc}E{_S1R5!8reXP<9ApG=4%v>;GIRW3Hf@0sh>dKjIF6wgzVgf$M^mu zA#!Ec!P5EyxMbv?Y*q{nwNsVm0gL>rBog*5W9pZMCGk4HpEDPvQ%F*nB-Ams=B@o~ z>0G6=0lY{|8$5UxbMb_eMiLIK3`4k;91Yc}cF(_E;34-C!@qdaEkvt`2Z7i!#j$U= zO}xav&>IY0cg=67+=(GT#R$g-bx40&sc+r*5A5)b9-tiIF4zrIrqk*>o=}8Ua3jXV zhIlB(_}GCL_)s;`mp8~=;%=~!2622V`hs2OQbGMywGr|N_27(2Ykw6pjrs8Xe&3=j z$=epy3Uk(f`hyIM<= zp)$a`L;odMh2x95!uIaI&*8K%`L}A^eINX-YWuY+DCjHBA++GFk+}iP*wKq|byXEG zc^E%^c=)^8(A31fIt5(G9?#@f2sQ={17T|h1_o6xki}A&`Y!4G={=zO0?rMelkdL3 z3dOP@`nOQgWsJGgA)kD<0>}TpGxPzKnU%2f1yqR$&n|2xkAh^n(ujCEEZh)kt8YPtGtt{dqU8f*mEHo7Peihi;A z&Xo(can`FdY4!ZgsF5UuiKIq*86IhxN4hFInvGVH8er^Ad$GnzQ{$!N?HaOgQi-iaopCw6B`|#JkbdiKOVfrTqI>20C(9CkZ?&5!TdzZ&&sLxlze|RPdNil`*_Unz$Ob z`zC<|DnIt*Dlgj5D+IIciS-oIiw^AOZ5huQ%2z-LQN4&HcD7KHv31{0_x6N6$0>Fs zMkYS`M_}86w?0J#w!0)Z>!i39vh0}I;`gC&Mco)#VukhOl~Q&Id7S2|gM(JaJ+392 zbS4p?qt>ZTyK1{CR{BaH`<%DWF)v;aet0|ov3T-`roe-Di8a|o|6(9+N!{sXg|1mH zOO|1|X8LEfLN(U)D1BNp~(W?3@l*Zo?# zLP3l4C>Qvf(XGM$+{#k05(vOqs(^iw+E02Yl{1llYf0&91i!-FgO8GaV{DxXym%ml z>IL1Lpv_w1v({P}>nVL*Qkzhwr?n`p7c&l@s@Hk=4SVbDee0!p`(I8x7-Rl7J=a<8Z$Gm$)t)d?9Bjl~AuL_p2fV!0z+i@{flb;o2m? zD%N|(3JFP~ekY@X9Y6cPE7@mvZY<$Yy=GIlZHg|HY=6F_Wh>XOU~uqa&ym8BdtC+`7p}&3PDPTBJL%FZ9%P zbP|%6__}@S;^pN9pvmsn5FvwREy*$;4U3#)kbIMVe~;MGtxlf6Y20gFnSWcgJ#yMc zv(>H!2C;xE$ggL{H>aDs(fJX3Ni=9&R7Xq8^KOdMtcAoY`~&DT0!oizg z#4eV+{$1fH)L?8SpY#1L+?7LOgb!Iy%8R*dc`7LMDW@rSU;Uu~ou0oG(&L8MVV>=nn)&65&uk?60T_krx5_{1&`)tjZ+8 z7Y3jnCtu%-B4|84_o(SkFXR$*wXh6q7!}ap5fqGMDKxeD1rl-AHAB?;zYikKSp1qc zDaCNeuG75vR>Wk}n(HUisSQ5;gGtG_K8t$RnP1`wC4 zA{5zMlHW1Dfx6f(T-%3!;MhBFiI!=9uh%!pIag&GHJ{A*sjb3JuPv;gM5I6JKCpQW z9GzLx0R<&ohngG?gv6$9d*YJDRMpPTW?bi$4qwSR*BXt)m@j$SIyemA5~Nm)fmDvxJ8 zd_`#GLv13!4BIg!&xxoqt=!$MOGtedibH}&2mY0(h<7NA9aVZpBQ%|Z5;euy0y>w| z0Iz+JrCL|ZM9JDnzm8XPF`IABg&*)kYMB#O0EoY{lewUH!Mgs_Vr*sb*(#lu1zBt4 zgAvNPrB7v?rv!-F)|XLoQOEB7;N^-QF<~!Y zvE1I;O1%!m*Hml455ViZ<`9O1Hz9YK*)5GKd6kTK28c+h93M;F~hEE*Z@RM%{!- z{noQH%mRmoD0xyaDR^WMTFP<5-HkevjIi=T>|XXuxtxG3%6~AAr)H+tf8aKe3BgRo z&urm-Ek;t0${@>bR;NY&N{XKB$IjCbjW*G|-M)xr38Pjo)ft(g(CZhS>-x4fY7Gz4 z6gH`QUk79Dd%c__=Cnz%`c|deNC0V9G!4Pev6QyFJ2Vsm3&yyAEqc5#p0h2ENBeVp zk@`!=HDN(*LTf1;(`&`tt(0lfi;vwrj`~M8@QIsLuxQKcn+(w;fEa>AT z>r~~KHs8sFLepF{g5USN-!of}&>QBD7nKFE&r{#X+R$B=I6XJq1(X;175jUQgAt(+ z2SixwdA}BvH)EVi{3ml};Gpgq3#Oc+sA^PmViO+JfwCjPu-&?6dXCPTHuGvxR8oh# zBL)pVGrtbE?%+OE5K-}3aPvI9`O0b0LR8y8K#Q{*I95xuS337tBmbeN=ow5v(?I3G zl$}G!-C5y@NEv=7QP@&bYTARVm`#8^s!NL+(N! zF3ecd+AHT5#XkEyIyF4Q=7=y}@m z1}dmTDz?W!1OcEQ17KoV)1z5Sm*Z&yPs6IpO52}5W5f%A@Y}}$rJ(2S!5BbVeCZS~ z1Y$WKT;Q7c%xyFUQ^7jrz=BqO#G=rpz-M=eO}AO$fLr2|*7zB(w1J$cV+MDh2n|Mi z&#rw@C&Dq}&U{)-B>k7W@+`wWC=<+CmFiw!M`wL&%kR9Z<#MBqRBaT%H@fhs$t<~M zFZ>3vuOfxfD0ZduQ3qEis#6~(n-B%z4v%0-TeSSP#RlRB#UC%Xw~4W{Zq|x-C4sdD zI2YWakX;f9NqDwg?+*Yc8DJ~}6n`K(;p*z@;&KlN)>_=Ql&Y#oGh5T~OeCvm^Tm|L zkmV5&ol=C6AM(nZw;|kA)V0(P7|zIP{`v?uk!fbYH7YlYw^}VI#UE1zN6S^_!P0q^ z+Rd^jI%}b-Q4Q>tt%lK6SZX{nxayKUTbi#0w85j?&C$Qw&uIpfi21R3ZNfXBYf#B7 z^G0Bn{;uvb_$&qMh>1aX$xGUGb#rU3tIH2cq#OFPrF=IuFmzS8Nhs?ClT7*VstGlV zuNN^XaW`+$0rk{<9PjsKq8J#PHS)Bpqa%sFY4o?1aHoR(Vw>cotxD!f_HN|VW8An^ zvcSCji$zUG93s<0qLnUQTrXiI`}3%}on`lRceTz=E|vb|sRGq1A_*fG#_w&eQI;5# z*z)Jn_q4zL$)?mEcxKCJkdJsMbu}^QvxMs)5TVy;RB?x$6T(K>6yqGOZkJ|@B;P#i z$Q@OFBml&w8LK_{O@2X*6HJ?WPhTBcg;e+TJfD*Z<8~Z)p`cUQ%2;F?Ywxa~XPHe| z*am1j-5>~agW&#Y_rwCLe#CCU-G2Oe#!Eg&4LK4r2eioBo%h90)35p>l$x+^RRJ1K z0vVSIDJwFBkmZ*o>J@EwK;1b+n%y3uBPZoQA;6*n4IijH{z@8|k@*)-T-75o`&?OK zKn81XnaV(1l1Y+-DD2282%_p9hv((ynrT~l-Y}sGoqs3H>+3jjDR_P)Pj+>=!&D~Y z2vLP9_QkC1Wcev&vdrKa2`m~~=NSg-Q~G>dFKtDjD%xMmNXG)SSV@89)=**aU}F@m zzM7JZP}VJIgoEHJQ1%P!*Zztt&+M-wx0XlY8ZgYfbJ(6CJjw*5oRx|a_0^HO!jQIY zSM@PAbSYeszhY(B$s07VO9?oa8q|rd^_Dk*eZP&tTgC*|nvbZ&S!Ov*k&M(f+G5`8 zZvf0c@d#Y!10+Q!r&|Cb4%~d7Qt$!W+?}1?SXLnQ`0i)mb_JvpJb;bLw&yWHQf+dY zBk;4#;I+b|R%gLj5jI}DU*HCmBaQHo_rBI~$d5{fEImzZ8a!=`} zl2PJRYneNt4rOh1bxH|{knyt){2c4!R4#f4?8rO@LCjPyN4rn)q=b* znS(i+vEurHa{j--$FOJ`U438)KSxa0@USo_x466LA_AzogwB%?n_oHBKf~U<)5<+J z%Fbu^P%I=~)$fM-$)$OtuQ15BWaFWM5IfIskNWhts&m_#;rren9pO1>P;o`z281){ zUaAmi&3;36l?6P|T){T9SDEnC4Kv12Wu4rGkAaG{L`HaGya|fZkX7aVQX9@(b*$*v zh>6kuhi`<1O^Uz0Ir9*pb0J8;?Ts<$tKj#}wt5j~aqHLQhi`=Voxn=|KDR=@GnYF( zq@X3kgBy~K-t9sXj*P363NHIU--J=o5NFr+l|v7YWA!`_S*E}kLIg!2<(v?2LVn&nZel!T{Ey|RQJ^#FQPgB7=3F;pOhV#HwuDAu57I(GL+*g&rS`S_;l(W$p+YUcy&njQhU* z1*@rV61Jl4q=xGdIz>n{tCcR#UA!1c^^5t+)1a1^OFFMinO+88NIZw?q3xvgD39s8 zbu+|6be5{>2e`qyv^>XKK)p{ayYVVrAu=R9Ru#Ae&o1c^XUJ&%hYv9RUEls_jZENT3#|W^0`Bqa}?_C^>L#m@Byp;}0o?G&mt3tVFlHoZ1Iy0UX4J{L(|1_GNoLNU_fyyT} z)e0V(YGDaLm0eFeJW&q^5&No?eWhc(ojPvv{2Hyx&5O3o%>m)UobU2JC7+@|IcIKD zrL2e2NFUF;A3~OH97f`38v=$Dk?gO=OpVQ$eWUg**hP{U7!!EHNu3v4d=T)ijC1J+t~Rfx z_hknmIGDTp)d}II|8VS4YgF79Lv&SxM9C1q+y6akYWwL|KK+}kv*O%3n5$kYOU;Ff z2z4nv-av{x5MH-C@iN3UYO`eeVE4^?a-wAFA%*xMHzPRH}_ zQUd{41K&yEwir>ib#WuE)7NT3^_8?$>z81y^j%#dTKS`XXOhtw$0~6RxgESA4-`>B z3cDY2&RS;ZGpp^#HtbX%x&owKGm~e#JN$eE9Qs5)!$L>>7HonQdao8Jw}U$ALEJ$a zSapgJ6(K?6%r-X<4{UiTeK$JKbIC~KU|Vtiq2*4$ONWIX8`qRQ2-Y$bVH_EApaMR$-cN zwSm8#V6p~1a7ZgDFT&PAL0|~d3~BZr-OZOUORjx!&sfwNDw5kY)5E~H+Tn|j&9AoA z?9&iz^?2vEE~J=k5bCHdbAjGxYA+a0-DF$YJ3SmK6l`gOhX}Au75IFa0d%swpRwzz zodoS`W2OZvQ>_00k6h2Ct@&=Lb))Fbf7+;yY5+?NM3rCrvATEmr!d;M3|?V?mU^J0KeZir2fYVY>nH@G)tz>(9d-{^dBYqi1Xe)YR%~k6_WLSl{ zu})kAahM(wju1epoR91GP+Lztv3XF+X~;(v6q{1f72h!9ZYm#_ja zzgdTpH(P^(?^!_N?o{6--sQxd58=Lzo9q=ueL&}4Xls3`YYFq|b#=zh4XHEVDH@zD z+cE|aORvS+N8G%GE%mhQ5KmqBAgg~@IaBTf2w)do zXFH(bNW2ss$P4bLAENuU`|wKotm~X5x^&l)XE&S3`c`P^#DNVg40{tCBRtxnAxWz9>P1Ad{HFI~UsQfAUi;FH zI(A0?Tl{KD=?h+ZdEXU?W+^BC)4;E{q1)>8op$XjFlOJlAjaXbz-LXAvAg8*!>sLKgTxtPdSO%r z5Q&E5x+OABMREEjCO?bGTgJ3pGQX2WwR!iWSY({kgI3X{a-Xzl+?*gsXyZ=uChFIW zhisbJi{(o_HZD#jt~wkxQw0xlc;ta7t#b))nZ|>I?~5%RG=D)~MbJu+nh;=aJBybV z+cQb)rXNF^3$;^mN5c8+bLuuxvJn1;e2WE}?MKNh5c>*^9)$NZufM!`-3ZAQ=qWdM zbgaXl!bvuvPK>?5vMZ)=EOckL#HkmuFP6oI*n9j7tPgS7{(yVX$}lfj=gFM`ver-L^y)om2-xzgzNW-}hCmF4@hM$7ehYaK(eLip<1;xZ! zW9CPc0()#nrV56?8iFN`9P1-IpI=U4y}S}=ehY>YSbdNd+&CgQa-IH;V$v+tB{f*D zO02t{+fsx*b8E`-K%8eJzg&@`kR8mGI~vBrn#rYoUwVh>e>|NHFrxYl4RM7{;n8}% z06n`4k89XzwkqmZ)`o-HTAVJKe_rS6~BJf$pKq^9?;Y`{Q{L+mT?sPBKdQ;9aVAkwtSky8Wb?JDfBHC!9ZMw zT`aIH-{b$Y068=LQG;@fINv|$Kdc}b3$|jyB>mkHIcQ$z@5?P=f1M?2awJqeAlaBK zF)ea3x*_cCf5(3JbD`D!g{gITIC&cVtNsN6J3OBVQ>D`TIF9s7v! z7EgMnaE+>7$oRq{H72({$}@ZDHEr)zED+bEzoa9)0wr$B2MGfHRPYdE=i6{^h?WU& z@2t-w6EVfUtfAZrMCc}}5P~!spZdZTOAx8}73O)HikYALN!$uo+6FF4)+?dXT2m4I zn=78M&-V7;&mtasj?9R3jIFI$%WDC1RDM^5#$l6x-@on!=_5<$oz=;RVZWEU*jFVK z*>V00r4k`gs<_Rmgtev^d%cTmJrS4Wbz|9TVtkVCeV+^qT#{zrScpD|^AQf&;5Zmv^z>PRtuOBbCVVI9(< z!JhJ345dzAl6izXSPHVv<3U)2B^FRC!Vt|@Ns(i2LPT3VGL73o36rN78o~xb+;JoO zlnOb3;2qeDjVL*1j9959g%4&>PgkAo6UIohhF||DnRyvgxDNxe5pBS5{QA@AN;l^( zPtCdC&6)eYSS?IChn#jDxp;zR#D39V_(WCDcu@51atWWzky~+=^1noKZ5rhQ>dyAJ zM>Md6zIwk8ql@`?{0TQuG+-{tdwc9U_Bnog)c59hbB}W5iO?&)$|P-4PM(DM%-UEo zd-8cha5E>LqOva+%k={zmGk^m@5H1YEs_H1D5ahUB&$?(SIOtoBG+E^F|NkUq+K>s23Gen#fGhvN;bLDKX@ zhVKgA-DC8O-pOb2T3Zhz<#kRqiImx=cExdOECix>%@9GM-GFyldQ+?PQ!Ti1 z%(F!xoR|ZNZ?jBSO`^@?>)?$epTY~xb_3r^pp{nXpCe%bm(OKFy@Yr$f12 zL>k&KCOH8^jCt2fuI&NN><;xC3w@7D+9jIMd)CTfga*cBgN+#40*rNA?%o9R6k4k_ z`PDPe6TP!h-4|f+2UNv@m+7Pl5P~#DG@DCGG2VdgjJfT@d0QN_<29W##CF+j>B3dw zZZf+uvT)6)>pOc`AV5w!fIb#wMe53F-3$F~y7D^G89p|uYk>+@$XQgP9YZIxMaaf1 z>Ky88MH(@8D_jgRYCFO@T+7ML1qw~^VSbK|DBgZ}Idk9BWiZl6d-2Cd=GcS~r{u=E zMJ*6p@sF^ezPTB0abyqv)=7s;ys|L%y;y5XR*S{DBTcmk4jHFm&rKl8WnL7XYu)cqdzTE7hntsrTLzIYT=J2uWnTj*;O7 z?k{np(Iw6WPaA0C5a*@;)kANOTA*p( zI7Jx0IrxDZ)|vg_U$HaUCu>iO&YbFIZMU)7RE8D(J|VdTU>{Gp0PgrIV(ZK+DXHhSI?phK7UfD zas>YYeCMvuU#hko2~2raRaJuT^MXJ+V-`rs{zq*z=<$2s+uH-G&$ERRHTqrB;hNuP zWE8mru?4x4l=g7#W;M2qpHuLU z-}FOOoaLKvInFAUH&3u0A{sQQw|${51DZO@`t{xpCw{YGbQcj$+s^KI!PsL;Yup(> zg<-0{%W}X+0v6{YX(a8qv@KW<7}gKY&JIf$F_|&P8!=b z8{1A}qp@vU6E?OR+d5y*S!XVCm1ND#THpKb{V*bmJfIVlXnYQ zH7rh24wGJ|M$Hm<$&H=yV$L>g^mi0g)CO^5e=P7z&#q!tL2mA+4WRoqi*D>c5JhC$ zYm@a7FdF=C`YiC_ecqm~h1!C=s>M+H*ZG<;RT3Q^M{mDy2hpkNociVH`>RQrD+Gqs z*`%_vA@;9FB6yc&6_GuHm}}D2R89CCCK~|u)-siSj~oiu+mw~QmFS$j%=P42s?GCj5o;9AcTPbcQ0;8SAHdB^w>07`b1Zgc zxzc@*6`xBg;JGb5R*^_e(hLxZyyx}|TExk!QRS}YaEkx!UlIu{9 zQ9FjPI{fOFj|sx;o9bxpUgKRwMhh57@qxe`Pcd+-}J zy!k?T^@tp%l;1IOUPKA|VxSz+T}b{#dJkd+-s{)?EQ?=!4?CQq+f8oMMeM+ z&u+65uVYiVtGn55>9&j^qh6DXI;hBFflamTL+n9v>A35YBj2(RUbAYJ-fy1!3a-jPqi_gX24%R;yQw6W8I6mqy6TJt633jNSXb-$~zDG#~2RF)|ta zA#r|TO3ib+0lf3H5VF-S@Un@N)n! zz|w&zOG7gL!R{Ojw;^?k9Fjs)(t8lQ7(LuY!mu!rDs zU4y#ia#LN%&-%n%_9A>Dbm;;w5ASgol=ViUDkemy18_`SzmV?^Cv8`X{?WbQYctdVsD`6<8Z_9)=1$Rqx4U_TxVX5_GO$V=fyvi1Mdcw9laDi{Q4h7xv!3l68+-diw(rW~ z-&B4R-IgN4++0LPx6hHOMaGuDOqbLq>r>V-6{D*Qy2y&vpH--fn?SvfME)}JT@jfB z-)H}BXF(JzvLo}&(7z@!@fcfWqlVznY23g>>pu(oubX~0AyGQ*IwB4K37-hW-^FPB z30PGwYh{blG4!WSOMEC<<6cuJ8 zqio`sxUnv~!psQMY>KlvM+Ng+L62=5XR2w}Tn;hn$9s}y{ZR%dds=5sJ(>{3rC z?-Aw{1hYvnFwh9ixT+kTI_u69R#cxN=wxDhIBI30J9s)CG=H_nx7SxLGLGHpAu}5;F<%`-TwU0HM-=>huf_(qTnCwzgU$dGEb6TO!y;<2B-eASzSv&n zoOqok2eV^~dFzI~J$w@@%REEkp^H_mCJW(#d?Yrxb~evDp@t41V`8G7$7ae5^reX! zqG=S-*Z;VtCDaH~TR&VP6vhi)ekzJ1C#zMcT1Z(A_#jL}7VS=8W65)1^rw8>+^}+F z3R&jMN6m5l{;n=nydEyHP5tWedbiWADr=>W_BGCw_`GpGq9{qiCb@|VAU_gCgT(OBf$L4H76Oxjvr2YK2AxzufWAJrv+cnfJ^fq za{}ylfO;H!RYoimRl{Z5cAox#=Z7BZHJXf|3F|D}&oEpbglH0b1e zSH%_gvgucA%PzehAdi_$Yt@}tH#CMBc>Z>bm^B8jlbV@VUyKQGOSb=j=q9=nvE$*RKtwx!odDmunsn1!%IdkzUQ-pJ#@BzwuX zEAkGo3Z$DsQDjuaojInSa;p29s;Ji}g5z&O(q-`Q#_Yjv%z$oWi{C>F*?XI%YIiU`d;aY&G|*JqQn zT}j=agG7taF|$DLOAw7A^9h&bwlDk5b%Y&#M=AOJkrkk+4xs6cxH9lAX!m6^Ls#qB zspF&~67P|y7~j3gY&vSP8irz2$q69K6*06@{$!0~N<^QpKFVyA@&7FITpA~J+Uf^# zi&#a@+hFk(d-cXcO`pG}vP?5!NuTP^F8R#cw#?6;J;Mv;-AoxOVq15{SJubQDtB( zUzIllH21HfWkHO#99}rp&du3@q+=EgHDlr{_R&}&oa=TB&$+@e8lF6>N-$@MKDPUZU`?SM)9D*-lFi1#>>ZTO+nQVs*H z;2}-FE63uS($58n2e|WLugflVO6e%Y^~$t~_rlI~oxr4pA}X)g`DWhUg{qA*0h7?H zA32{tS^utA#jdjgdc!Zsb?fjak`TJ_yW}#DU5|Y9*u>sae1tavb34 zNBc46UxJnK{7h%c>~)~RW`pasI?3}s$5s|fww)}UNDr?s2wFJ96WrH?G zd^{D2wqn*Px<#t6b$a!#&lAIKT4w;*;Q%X4OF0rYDOH}v&_eyBGx&o`!cKC;)y7a_3nP$E;-GMW9+fS=E~;qy@>$kT zq%r(?RGHrvv%~H*tLR?Y=%kisDFV;Me4^xB{Oea;+mLyo4u?8IBkQE0x)Z@8HoRY~ zpTG)=iVq-@(5n&S9VPB)YLZ|MX&V+Cs_b{@QSSsJDdrsNxqnH;yVH{hc2xnzH1J{N z5%>zarjdq1%cZkB?KjVR3NSUW{%smVERLDcE)E}nJ8NvIkR=G-#AVKOROD6PMRd8!+<24fR^FWx$lv7Q1q+`XK|54D5*3@?9V10 zUik)QD4Dn+r?MTi^PgLE^b0WdNj-{fKt99G1y@B?A?~f@-*V~CLBaAp(f4<|GMaD! z=?Uv=YhL#!3)k0msxcl!8txL(rI=;Xs{sT<2M~rjNzmZ8O1*4g2Bv01cDA<3rnr>; z^2nmTec5szc+lh+%4pa>Jc~&;(k*r}6QwUP2F13lpicf{5Tl@*N7heSiX(_GfPNBx z5ZNxc2uG$*s(V_WS6Gu^RZ!i5K^rZ9u%NtWt!8wY7zz-rq1dK0|8s*AC z#++NZiH4}NkDSJ<($ahwmWG_VpIpoyhlhtX@2fRFz|aXmX??sc<#P~U z%|V9EOLs-A1^eBjY9egX9<#HRGg(II#gNxY!z(PRtDYRwA{R*0`@~fOc~cqdm41Z;%kY_z6DJtYQv8SrHPsDE_-j7 z-+p8lf28zQ#0^*>coU^AWd`@D12?Wh4u6DGyg?E$p-l^YzC|&0bMx}P09k|H zj*fMDH2^$@b!}h01_+1&WmaYo+~>#N1yCjzx_Fp9wD2Wn37i##S%|lzr{_t+{TdVP zC4d0^b4qsnWGbsE5=q<4+I+C)Z@@46syRKp*cGP zyr^J^Iz&kPR_6a4f@)ivcN*q9lcFHipJwkQP9~_V+pDh$dp}a`6dHo==-2yCu4sy!B#7tPX&=(OT zjIjp6^1X|y*NoB_l_C24>oP@Y6;P;*%qd=n>7j>4lRMw{2j;GDuXkpkh-&phd$__X zaQ~Vz*@9);f(9v;gjOUc!3+Hxg99~SqLKsY*K#JO8j4h|yr)u2jgGyQ%U`z{SibCu z8A4=Nuazq2CFapmx?<;l^`ZG$NINZ?d@@QcZrS|%&D4w`;13rU7qH!sje3o(D0MuT z>@JMIRcNU-7@r9mQqXi%ylXf`kTzf01eycf1#DtqobieZ9_j)7ed%xC@$WMy_xl|x zA|6zDhWJuhcH%>2cRts_%i*fyRrp}qD^?ob51K=Yhv29dg2%x&YNq|lA98JWjF3*y z^yJ2{#uYUI0nk6^QR{|3o4IK9z9S&DehLcTIy&*vpA3)NWf8$=yV493#_5?0C_o`# zvGK~qRtN;^4z(=n*c7mxEAu-ummp%m#{0eg$2BvL6*T5#gRwgf=cT26L+qWgmNA~) zgb`yM$;r?Vv%ttHI4@rjuEn(pf*`ToSAjOe?JO@Ey;)&88gi-5VFg*^q43 z`%tGqOgI>qL1e>>zo-3OZX_*}(ZPtw2={dSvrX=I>(%q<1#l|4ejoqx9bkb${G#J> zv)ktt7{mdO{Jf*{F!>+8I)y^eH2*c@K{<|(1ofh99;0vao~eon){d(DXNr=FR^J^D z%tJxx{WcdL)1dqSp)!)T!NY9vH+eP1UlHw|+qIqoNEGG@@im?wKKt6L zu-2C2U>o^7<4ex|$B{$(v|Vy`)S=%vt@E^E{6vVxRH)YZzFBA=Lvjudq~(jF7_g%} z+iU!lV15wpg_I%A2qrv5HZX7wxUr90#oD-dc9a^Il7$(z}N5X3uKUZDz4X-)i#gmcnZ2G;Iq*afWrZWRDwCundC}{-q7;^cw z0MyP4_<+E|54`&{OM6>e0AQwwsn(I9jM;K9Om|=-09!K+tGln!t>f3J>!&#SYQ(b0 zNp$a0QThS`$Gk{#r!GfjTGAld)d3gWphrO$t4i93ZZw?8sTZk>>+s_UO5e4dn>)%X zAGJrdqd{eT7$_+-I}9BaQ7DH3G4*3v)aQ439>2_a7~R-{V}^OfsxKqQd(M~}vK;@1 za8bjgh0GUGkpns}oL1q}Jx3L07MCy=X;nWGe`p&23@Yl+XC5>jrHA|T@Zff_F&WZA z=V1zn6=a$Y74hAs>ep$-x)7SOq#i;Q*(!>q*>kN~{g7uA*1?yEo(DHchw&y)&_^gvo;iW8_Yu4^Xs)aYug!Dyq$27MZ~H~C~nyVqd?-3Rgy-P;jZ5V0oEM9+)-*3pwy>f8hrby83Wuv!#!!Q-A%+OD43lgM(sZ zAw;{{SIAbCU<%GG1lfuJ@0enq_E|njY(Y3V4Tg+Uagzy%UW;6K(AIW4}Fz)4O|l31oWQWV_I1>SANEAdTfbPG#NI>I{!yzAupl zr!0z8?5!7uImqFbIr+9qxy|6*o1}pcGN56iwHg=uKGAHwwWHpUUhFXt`Ku#HaFqT) z%PEO8`S!%@_ZOKq%3~0*p!Z)m+RiUFzdW6sc7tOVrXeQs^oz#xXF-0zBl`x#)bsZM z6Et9tm&4l+b8&XQ?Rwnoa6XccEC)o;zAwimJ>p<=Q4AaxfPyQV@8|A;`f$33F^zSO zkRS0NTGyO*p4BxY;9(a8Pz1pK2RL>q1|_{C(T3$QDwf1rt^b?)0js&qd^58wxoUd7 zZQIcMn?|Rg*^Te$@Ut9?`Frdrx5`!izns0(d& zz#$8Ks(+`_-Cw2Vz<>4I1f#%i1ocyG@d+h`xX*eRI{IEPN~GQOL~ciqhd60~@*7f- zANresM~3nRYb;Guk!PwGVkPn-u8_4k1wlGq+n!XekDywsMyMDeP!PXh zmwG)1h3RR8l3EeS`UoyWyGOtah$Pf17M`CyT2C(IZKeH5n6bFrpaVoV2Q1z>PC zHQhz%q7CpJ!St(tExgo}bAsBTO@E7)j=HvZhtm7J@|TZzdK(*mMX~Fn22j(^6xrS~ zC>CQAp2AlA$wub5h9~^O&6#N<23yezl4>1r=f6M|oqk)-Jz6@Z&AF=k?q&ep2h-($ z2gu*380Eo=H=ELSfbbwnUD%;I7R5M?=%;NPHeC@jBO6=395#g7ahczr#w z0Jd)sj>0*+G@?2>w`}Q=7zneB+~L!X4K5YPj@DzY&TMuqH0*oq_-&VLzJ-d2wN5Qa zru#Dfk!*qcEIoAOHx&Dmek z5wYq>vfy<>K#n0GaW)xB{pG_SU6^-p|E~q0Oh;+{&R~M9;%Y+09jEm9;P|@O(tSYV znB3Eld}b zF^mztfK7x_szimXnwb``nsA!pJE++lkuxQH`*|XM(%r!w-egEVIsR<%!pNYOYvv0& zc09mT!O%Dn>aO~c@;!^j`r(IzunX-0ea)FjZmJGXc=BG*Pcbo-qO8ZWpL&Ty=aYq< zL*FvmQ*A&re zeC%w&cHJPrC!v)YB&#L$m&FmibyD+sy&lvoH;!;b4-{<2sn_TYE%g|IcbYFsn#}2A zcb;;76)c*_oc1kBfM{!<`fct&V<`)DwPC`N`BTLpo&*Tx)9q({G87G8(ABiy!6>oW zR!VYcGiWpVuI}mPhAOmSMslkeNX?R2LG9XR2bkj$6NEZRnFNIYFKUnDQj1gtBn`VQr)}Et?j@ z26E)!hE3e3R^3LwX%a8cCY~ogicNJ1xD*)s%NxxK^W6Se*x#Gpui-xq_qOH+xsYWp z9RGWjja_ott>^u|cH*FxS!LE{Lh}lstIuJ zA<;iRJjni{;O#}vLSya$0$~)du-l;Lxzk|Xc^>alof=3tL56;l9=`(; z*(TEdMPrs9ggN?4W{_lSFVDjJ=K(IsGM}|EKIUqfn|Pzdqbl!9qqERB=INl3%KylmGVw zrINzfj4?hf9!a^>-GTx7UpQuzv9>7I+J>HL`!$vq7o@0%oOv5VB$arxgC1S^(~m-^ z@Og~xcy2Fw%|X2CJFLm`eZ~hC%LT1WUl@>QS0R`=#(^2}pB%#vAdfswSV#@r`qH@e z;X39#*$&u^E?V?zdLEi;LJIx~!T`WHOTpB!Nw4NM0U-Ok-)<)MIp4Bp=x~vjfr$SM z6_L<=w2S^~gpIGCaqn_%)1B|-H2_%s6A)JeE5mNc1|JOprNfDGQ7{SEi{?F zu!#xjwt+orwVf4{%`78gh*gz3mDu0mMf#6Io>7Fl$^;aa$QFv zIZzl(a5@thJY{mN43>K znzd(=>eZropX`p=&Vq$(`4oMmyK|qn)w}_>iXa!Am%BWaamU5(NfJCqUbsqQ_d)g~ zbA+TtES0tJx!`)H0!rl&k^rYcvS_4k7d3 zffR$bokXlbYyw#T#t184qe%1i_{%>C1dG*@P?}oG^ zoFRz~;gnk$2|CwHC37DtB`!?k$V*CT3zht_S6 zjYZ%QfHeVeSkP(i=FSLsr(2lDTZqgD#|~Oymd^y_t|k$zlMiJG-+{i*ap-OCxLfJj z#0P!W*UD8@H`LtzMc4X?Hkd0%AOwu{yhnF!>+O)M#JXd8N(*8BTeHRO!M&alHZ7G` zAW$2N4WD>t!ar^MtV*;!NZ+Lax)Kf7(^@f_Y+vAFG`3igG{AOjO|R=hCstrIuZT7) z5cN>`?m=efo0w#m*rc)p2 zLd8VcO&em3VUz3S=IV%(DyRH-T1^=Wbrd75y1jM2mG>ZYGUGlfimvwVesN1R8E7Wr zp}`X?!gbYAe~wP69ucNZ#DGKW=1X}_6FN9X`w1%<#3tfh&R`XV-L*igNkei4K;i&k z^a?ccUK8|O6Qncf>*);>({-x=MUa4Zm zzlnJK5eUWjC(k&vy}j4&x!3;podKzyJx{w)0KV6e2-fs8Y5+d4&*|5Q5zvtxjlmNz zIph;1`@UY&8VUdZvI!dg=`?^w$4P`yx4~23L_kEaQ!54v*le2R)ZKA`h?5AnkY=ef;tP950CD zcyxB)-1KDL^=cK#dnjhXig@x%L;Cci<;EQB3Mz36q1*1u2Z=~;it2d}ME|5Je;I%gJ|sv>>OjOl%|y47T(K326Yeh%ho zmBVGIBb9TyquZ|wp%v|vGVOPexXK}HH}(# zn|igez)?l$x|jScwi?24K*%|XNip=!?%UfNAk`6RIX{>40}lc9Tgf6tM(h6urDqGMr`sL> zfpd3=oq|)E==1O`CDS`V%lcCUaso6rCu}Jru=dFa{EdMQgITf2mM*ge%@j<7n+F9E3kvpp62Wvsn?<} zGFStX?ef2<47H~q39X-vD1K5})d{Im)O9g9o85rH9w974s$TE;A*%8(STTefDtp1X zV7p3WvnRb`!58Av#kn(FZ>AUXXXBLSM$8c#7dM#3{2ffEF0<8JkiD<7)`^ClBA9qG zill5Y85h%TNSf%(DsPGXA0&?-yEqY|-FSkUQG0Cq^Xuv3kNK@E@{Y*|YL1AAar8xG zki3@=Q8@|S+sZne0zb_Q0~7v~=i?9&77v)3+NPWav_v?4Wn>D~+)39-grsy^@^}&} zyWhuag))Q)_9?k$h8(gq|SX$VyyCG{;=;LYc-wg{4VEW$IL;CLv`dxTkH-f#BDc!se zV(F`L!~8KLjm{nrR?Gyrq{+AjaGX&Iko9jpP`2S=E@6J?Ku@% zwUp%XG~UIn*j)Du-U_j!(yy)xLwR5JslR$=a{t*+CyAJ2b@xtw9EKEa8i-{{#{r15aNHF-!cb8TEoOc9@%Wm<*W+sE()2bP z;m%Qg1LU?&%ZkWFrQhSUXQ!U4NxiwFqf-T_@Kj|C0h0}(*m8NyBw4vJwNX~_w=7(6 zww62PhY47TL(s$oI1c$E5^U=jsPwWKj7&_R$I7N7+*4q(VfOD8K1HLU1f-bT#|3%V z9QEazSsL~C2@GjM08k3R3mqm14Ssd)Gqh9#AWJ)C60Hl*^HmPnN-${Yp>!ET-*204 znqrfqA*^&+B3GL5WO|04*)e~Ca~=3wN3i|(*2BvDN+BCL7Y+XIn*~xns9^}V#d0q( zREe9;wXq3OzB|MTzDX3Ci(h0Bt0#0*6*_C!t}}N=Z5x&3!sG@?<4X6}hQ}5;;q;Jh z@}#=I_rb!IFHLzzZC>g<1!(pyZWFAG%Q`E-y7|>$qN8s}$4W?d26H!4=OYTZg>S(p zjjqrz=k-X)XRW{XG^J}Tq&JbIRFU;|ajDjnN`x5KAxlFka$ZS#$)!6LMqqT=t+zU! z@5Kq_6toS|{564Rlw`oRQK?MfVNUOZGVOIyJ&_YI(1SV@0AV_0UL|kf3v}|lJyd}$ zSL3PkBrTP$pDjw+*TF5iI?Gj^L-k>?`2%k=p`F?zYBtg|Lyt^3YEwI^m|@tOL45~V zgUE8jX-L(5Tc<8Bl@2&OTaX&*Xi!);BfUXA@2Dg6%b?C zfPh)%|KyVjRAay8JRIHJuwfPf0tncC0IgmdK(3tL@9Y>_)%|_w+RUx;nzM<~gXs`%FO zLfnOwk^?kYj@DUIO-H9KMY%POllntz)7wX=4pKCZog`<9own?1s8J}xjcKK^s9?~5 z5K7>~0;qBpO`rPP>g84s$+h}-G|GhxhmoW5!VOIXPo02t>+i_-q`@&?ioRsQ+54=s zMwNqogHvwFkKWKoLtW~k9^cP;d#RFT3Hd<4UVQm{DQ@{ zOS*JB(|$|yFPM~cR0j=`mqYsJz4lOkA9QL47Qgu<`8n#+%1G{7!EPUT+*Ck}Ko9t7 zS5&+3y%y^;`Lx9Ne`;nYxuiyI=-B5skFA)h=c%UYuTGwx8NVWadI18ipIbg$YHHmU z$saog7iG0>*T;?I)eY8rJky6JS)5lMy)jp2P3E`s@pjEcu7i*$faQxv5#_Pc(0jJ2 z6=nO$qPNPbTyjn^R#&l;M+E`f6*`VKcjL*1M!r0(%C6m0K^>igbVqpdd3V3siMsg& z#7k_=xuc|((7UN^-HNGH^itT!%u?{(TeAL19kvsbrNCkAhOgjMr_!+aU1{joa!mDT zv|TzPZw+LB@HhcLe55&Yn)NVcIJG_Ja;`#@8mFmsIxF?vYQquD~Q6^!_ zYMX9NX3;|AN7#f`AX?G82T~>SX%G6o{z;N}udK#CNI#fm?%<|79OuoxO&iNOYUfa; zJ8R4NEy3}((I`DKsQ$Q4Aac(#GVL(Sz5(g&n}P*h!(w%e3S<;ZDd)%4tdW>vZgA*b?a?q&`lC=fEaRWxHVh;%dkY?lsu zVH;{k@Eoa41(<7Keuqdq|D>MipFjMsC zBh$z;s*NJ0(CI;qv$EC6BMrh&&XoCa#d1lKSB^;y{mqlz-O1@o84>sIjTsAgMViH-{IN#d z#Kxc}En_ zwolrdC9C}nZyP@F5pZI6xnJ*IUCqGVJU{bH{^r*dMg{PAT}P$bLNH;@&D)Do8SyiW zU~d9M101TqvnW6k?RvM*8i5uu7nL2XP``J)Z1i`C0kC@8HW?T#xs6m*BP3pbJh8MS~wdN zsH?lXB!P8Py?kt>W*!`?GuSXLd(y+u)B9DhtP-aC_*Kc3LEBq$^Kzi-#$8(FWqgiN z_UOXMjK>jIW**QTEd3XZvF_;E7`HYzkQ#4W9~)300No_IJio-VRS`K@SdT9;yau0vpjZx4w^@6&JIm2Ai=T`ui>U z1$A#viK1hqL(LZ(`4#%q41fTu3}!#bY$&A5ggogmpB%%Mg!Yz6zMeJil{z0K@-sp#Y%R5<{G$IhyI&uj&NLb`cA$`$f@n0!^JJ_7i!#nUE7 zD{e&WWjlc4H&X{eZdV59TJa`SM^=nu8_Jru2}{^i zX$y_JsT7#;EWJvuwHZa~5`E(!k7XL?LJ_+2nPt418?LO!86_WsE8S945_fo#ZndgB znkuQr7cZ3GPwQKN?Qt|;hl_v1Bd=InIU!tzX?kpeaxYIoeTSVN`>sk)p^vSp?}f$* z@b;QIc|r>}IPKDO=+!6(GBJJteknllY5<5lOMOC4+GkmDRc?t zAaP|M4|7a6-Lq&p<1;p`EtRK^BQ#|B$Ux{{;2qj(`lCv6Hu$%3cuQu8Rfx+_i1QOR zi#KqyRKeKi{m|Y<)Vq)u)U=7Y1O>yjZASnS(q0V-GncijW|DJTQkB+7&cBl}&c!)D zwaVdm9b~uAYp)biUQ$#*WT;a$jhHxsmSc%g&PuryLgA5YcSm7 z)TKo5ecFqQBK`sQhyFL{BsXQVsE;$*Qt5KIOi}G`vE5=^60F+TPxHZ? z`$Pvn?&t~jKAlI+E%%bE{}wH0=C`v95$_}Q+uo$tgJtstRcDj#1lGAwt!u$I}+ z>z-&jq;Z_oS!5Y6ttK@T!Y`S0znL<(K~;KBp0LZ7HF14nYAI-mkm)A}BmCtNpoD0D zo!wPeI6Puktn5OHPB!i}=Z{ts+L0{>!aw$=27ird0sqCTZg5!FMLf54ALCn-MgJ+!<`>lVLpof;8 zY=^ox3TuujwSS_oxnCXee&YuG-JztLZ^?N#3k9tD-x|$aLP(8X@fc5`uR?Beq3@;Q$&;*oQ1NFcNA*B0j#G(cfRW zGcViTSorZvGQDOAYP1x&+4}ge0g)&j;{bZBKWkal?Wp{+YMmzUj#w^Lf1sT*`iftc zXpEu5=G&wt4a}?Tagz^~A<#xN3T5C?h?eWkn+t6!zB?x5l}g7R+fN@- z=9k^C7Y`4dWY>Qdz4gA?whr#LOuvi^tp{OtH=!@owvrbU}jb# zu2X%L6S**2Re-j7-B`7a%vAkCEW;yhtUAs_>_Pclv6L7~2(QJNF(2Xm^XC#oV44DFRdKE#gHi8nt=}N4gFu7#}H_N~V1Du0LOvfiHc;g~N zkr?qla9^)^mp3+$Wv3H=5P_Ekwz`NQ?dxImwl_7ozCN4-Gc^!hvhKO`rb9@|W~9vk z6e<>o2s0DJ)8+ZoUD1Ae3oo}+ILRY>r=jqyL_HVn=*iukOl9-onPMHdQGzACG|7(@ z?7qy+YKd--`j{_ql*-j*)J)oC2c((iy5>xvps2=ZUx-%wLypU+52~qMs}0dqm{485 zMZIJu-~1qQg}5{8;w0#>bj%q~dNn-RAD^wj$Umz!_eLNpvfYckS6*bS95~UQ$QTE& zNwJk%%8;->l}hiCKGEBrOmbWOR`j=pvht70!afXStOLIL<^)(>I88$d=UT-dUp+Q? z1ik3*tUV|8V3l8Zu@to$*{5aX!qO=nBz|Qzh2Tl5k*bH+B#Yd;w5?vD@7kw@$nX>x zrhy{$3-z%cG`WqE`z1|EQTb0QQ@X{$8?sAOKoH(e) zR0)$(^Cy&3r;>7d1&W&ef1c1-oUg4X>VQ^NQY>9~GlxT_N)9o`OjLHJV}8>nAV z=robZtXxbffklne5b&?1(0EMj^?rSBaw$&SKR`613?I;;8oq=_g=WDqx3;Fs$-`5@ zr=n0WXASF0lubNC;_Xy+gaAcD=P0(O_%4=Pc>`SRC#dI{%Q1!}`{U~B3W&$~2gU#z zk@J&(yAVK(P|C=Pw|)3Mr}_aat^T5NN+c925d!yPm?d-nv!C_Ihs-lVkiZO?a9bKd4@mtoj5R0LMsDx`LNot|(m2>(<^P;l{ zqh`LcM+9Tl;WYZPD@eE!(jVv#Tnd?;5eK_$M=d(5a(PWKQ$I&Qv{xd*DU-eLGVce2 zysO6cOekZ`twH!;=Mg^dG`^8zdLG)?gqoxn>Zzp>Tf&ooboZYoWZmsY(2pc-1_}5+ zt1|nFe5Fvl#vdt@^JYm`!P)8R%oAmifADpjVM|m4zwIgyXzWdo&F7*k6%7{%1-$H= z_ceuO!)n00rT^E+wG?(8=Tj_jPAy2JSL3?11HIfBxE zdE{K_pLz|YynjKNVhx%aVe0oL9X3U8 z$u|E{!Iv|=L&Cf3H<*O^I?b`U)%~ZX`@U+NidE3u<#((k&IJ}S+diqpWO#UEt)U@!ie#!c zOe**Yxsr9ll-kU&(b3r&*EQ+Wz=QaNo{mMf5avSLhBnXb$#WJ#%>52lrGfh>3Gg4# zsvFF%T*EQN*SHO`A(`>)1AV1M`eLDpdXRm;} zVJD0P$U$|eBqkyPyozvk8vw!Qy9Z>z``!H}>3Y5B00ySl*H=I=1Z4GNI{aH?`1#)e zo0N5A4nWT$k!8b59}N0N-S?8m?4B=e-P6f%4OXO4YeVQn7t*@8+knch-)Y4hNm3U* zu)HQhXR2{Z7&ABGVkkngd2*6fqiZ}&pXF9PR$g8b9B+bF#yRNf8KMMW&CgYNb_HuE z1w>rT@P~Gv54_{XvWhYfG|J-Gs=SfvRxmpif4vm3y(arn3~rpq9MwU8y&1=}C4Oj4 zG@od1ZS94-M2_nP6lef=WWvhP1ESr9)}@hj+ZXd_!Zg%LiOo9Wx#+7cx4(YMhp|7< zKtOEjOe|k+SW~LX8i&$}c@kB(82b4TJW%4tG9EQ;y4*gBc+u{RrqQ<}Ir}~MtF(^I zo?7ArTupo!qn6f@UqDn}Z2EOsZ3?xt=0MqL;B&vpWV$JFE@ZhGeJH4Q9y-9}S;@5` z_Y;0mzioiNiW)h{Kj^*h3$micf$KT0#~MvaZ$=DD+g3#c-$=W$l^L4(FqR=pTE*X4 zU4YvDjfuQP0lGtPhJVRg>pLwZkGWKBMlAm2FW3B(e-J>Fek%DP3_$4HO>vG^#DWrh<^)%FCAuK7-oeH0U@7 zrD4vtvSgJTewEDg3wp8X3_p6Ls(3MY_X;V9te+VKggEdB;?#Xu*eJfTrQ=9B&OF@kn1_Wblkv}8k{wiRRSqjB)RDX@ zW*E?nt>vY&B(74R0G|FBL%I5bAg@RR*4)Pap7A6rB{2R+MZtuh@sSp7kuOTV<~bs& z-O1N`H>OuiqIWx%8e=~ZkEtslUgl`o>E=wyH7l0p6Viy;rd{H+o-tA0nyc~%2)x{Q zkz4jl1p~@6%z1WvtaX?ea^;+*8I?{uHCzS52<5aktGRXLGhX)n+GEDDV>%fhAuh+( zE#|S`Hp_oeU&FzA*kGQ)oX~K|OhD*KI;Uf>-hh$;L&)3J04k&#DOU935zt$8xzX_m z=$L{BdbFwp0S;0@=$*ai;1ocE0fSPS7PH(CkZj?56-4sie)XZ{yyDoGa)5zJs=2d| zm@xTkTixA(ULoq8_u`-FpAhF(5||;%9Lk23vTI&C-DCfuqm)A3G!rws z4bz!|p)&X@8k(Z(0M~DOo|3VciUd+NhUmr^|8*)X5@{J&ZJ96INd(%LR<88eb( znr1g@0CO(8x>}11H+ZE>-Qkkix~9(~$MGyOMvSa<2Lu;@W)=Y62?YfOLN|FN^0nfv zfO}6Ei{?5BUc5MRvY@%W-iR2aMb|S5Z%0Rg<;3Ac1LmM>HZyU3XjqK9Tu$3okjRrq z1|h4g&h-804l7RzE>(eK#Kj58P*@BPY$4Fp%y`h~6xK@QvZtd%+n7Ho)8b;%LM%up zP6#e!Y~wDaQ;IPgKJDsaVy|W8Km0D0}v<}poP3Jx`mykYUn}bRhIU}o3#hi z9X}_U+EYP3K12xIW=i(YF9=vW5ackBQ#7Wfa8DB8^<73WI@-l2_H2t_*bjgN3sCxO zeZFr22=N$6E)cle^Re{#Lh`xix6cP8yxVPc6EQvff?aWOatt+uy*O^*7YJHM)r!_Z z-yy!pF#C~TO6gIE9!|Z0WT()9r>x|LN`BJ^va9z+#GhE{FzA2lirYdm5VApa;sD!L(OuiyplJit}pRJsE^OVC<3qg;j4^563gtxA&_7tOv_K~njPb*r~ z2}vL5ncx+`SLiyro4>cxv?@C?7Zs}GAuoRAGTtkRb6@b=3{`Y?Kc$a(Jh_iAE?60H ziSV##-RjJ{lo#N9i}AUnt*!U|I9YL1n!5u# zFF{ZC!}3`KW>km-c1Q3E5i-FZ3chc{);XW01=Zuq)i(KR;`8M9Q=A6&Gac)jpH1kvx z)8R_3Lx9ogH@X_A5$4YP&UPtw!9C@^STJ2Hjw9Us+2efD>mF8$+3JP5an1bFc(ZVh z@=u4XsaAGY4qd!9&P|BwKYkWqiIl^7W6iBN7UG$Ny&SF9qwVZlDxvz+&C&8v3v}zG z%D<~&YwYZV|KrbE4-lVW!goF}wtD^i?CcnRLY53_I3Jd6IXjzJ*cCcZpnLd3h^*`B zY7jB!H;;Q_p0)oou3MQJu@zO@#fBc8!e}u>S*RRSP+nC~1uay*g~vmNj!io-OSiN^ zVv-rc3>f&H%XC>vd}Lx~lYY;&(E% zI`)o*+r3;(0nt7;cB=2VWKo!&Ie$6j>n-g6P$HM0B=gP1!z@OPf0HqOx34rh3kB^2cQoo!5D_7 zC23~NJ5w6#^a!@EHKJmm-9xHpu^m=q+s@}3p?OSb)C@RCV?mE8$xcoQamaBM9(1M8 zU^OMA!6&jmquJMwNu&?sDiPxTgsc_JsrrkSTO|2o2JNfV}f zqifUuV9Gk4(gUs=HY6uxYCnfn4Q2ehc4uqLS>v0O-HdNxSbwd@@vt`sP1?i)|KKu$ zz_d5SUs`TsP@5U(pV2pwq3BMwaeU18_`s^EFyTdP$s3E<%#VdD1_T-zOX;F}8TQ{o zekDjaaK8ea8doR(4TUMc%}-{yLg=z~h2b8R%Ld6(YX5~LmDQvcirDI?PpN>)z4&y< zJpsH6m+{M2RZJqbN5{^aB064wAL5Q2#-*E0gHv7f*6S-HRFh)Av>_&Cwg#$tI_-h1 zUgV&0&Ljz16Ezc`h+H)-3B#EeU%Zwkdol}JrO@_P8L9BOh924w<(K@|!}D_s-i_&1 zjgJl>nG0YD7MGJWdrs}ul$BIZAImYgG_FYy<1X~6ut+jEGX}-*BNF47eaIlIMo)QgrH; z=eVuWrYk}yuKXp=4mq$^Xe%-+W++)wmdplovz$!!RBKy$TIb-&v^h{|&tkr3M6AV= z>feTo9k9woXvNgzWPZ%6Xa!2)r&CNS+L~5x1Qd^b7rS-KWGwwNqD_JS{PDpXOe{k2 zDq8NhCNMqcjD`Lupe@r|DHQG_^(M;1j)C2uB?c{$?^Qapd=L%M@Jx5xESHXdOVghI zNJ9u*Iz1H+_O-M%5N`p0?GspUeogwlGQ27P=}6#&o9pwm{$Kp_9w?YwFK(Zw-wr_I zwB0IFiH6&2PCJ^^U$ExKi4PSvMXPzv@@6UdV+wi*hC8wa3_S%usO%h>tTG@Kcn0a$ zF08snjna10Qcc*c5r%s}hbcL*4oeE(q~v$AdxpcN@$GZZsv8oL00)=MmfCl)Sxk&g z>uiR^1D10)IpI zYigqDr>%6s=cxn`*)>lofGNpBpgXrE$oeN41Tu>v!m;)Am z|B~C)ydR|6n?SR2sOQF-Ltc15qv;p>iFVZu<`W-ZvP=WmT#w(NX0J~1x)|V;c8Gsu zF`*~IX?rQ_R*KP)v@?qFjimq&tCS_ZCkB}MGza^;>A46o5`^j`u4UDo<)LP+xr*fr zzbg?%nVN-lx{g>D*PKGk-th6(DRBf}Op_pspAk?LKJJiO?d(J}ow{n71`}>7jIcin za{tB#M<;Xde3Cc|pU!x)ND0}o=KFgjPWdowVb3od6)V9i7L%mQl{)zPe(O|_1pP=N zs?4Q1zRy4A`e~VQxmx?@`uZ5jke=r=bJzD1&1NIWr06}6n30NwUn0U=We3rz!~7)a zyF^!Ja%CVH&Z6sR^UU#V55i|7bVe3n-N3MOL@e9<&^B#XE=Z=j57;}89zKu8_(ZaI z-ZyW=ggd)})!(&s$r>`tg@hm1?LU!pSJ#>QR;cdpYuCP#I3sge&?&N5m&!HB zTbnMKSOD~9c>(_|+#nH>8r{y36;UfUfI{c!m=O9gE#D6$@qiJN6Fz5dVKZ|Ii3#ou zB5pYJ_mC{J@1R_APA<~v!vpJy<_$ZYma~}ELHkdG-^x*UOuQKA;%Rdjegqw$9F&#Z zb0EQN6$;26*0ALUJwk_)=};m!J1bJxRI+HBnt9n_fzxo9>h`ZMD*#T$V* zD9}8*yr1*%Nio2<-yUq>J5spOCoS9-1|!H{)ZXXXVEms^#}fqV7q=_pRxRJXM20ZDEol%Klk5xZq4dt#5;sqV^ygRvrMtE z0mO;4s&(j95(Tzyh%@zz_lbZ<1g5bhArVJtRI4l=`}_u zt4I?e$z~$b1sdrR6{2bfvp7((K=ni&ki>x~;<8v}(GfJ=M6ZqJ)i7Cd!KM#C>`4!_ zu`YmZJ}wM@lO%iG+4YW-=YKUm32jTJ(^Sh(#(LF0Jg^64c8p&HLBu#m5Iq)}wIKKGYgz1dRDVT^^k2s{?i*o5=&_w(OAu=d;q(O6-&wS@Hs?+C+ws8w^t^^1@If5>oV z!l9`Jo`l?dJ>6{J>i3>W7U4TNEg0``kG^w{iLrGwfk?mdr>e_mAug*GQb#RkWwtDf zu?GQP+?SM2; zbKx&v)M=Yw786*aKEMLU!@3MOr3V}2UGJklW$Y4?sxm-|bcJiCr&X(^|QH^g9V@8>+&qOdy2e2aW3@*CLf7Dq#D*%lS_m8-4q0+Kmpfl<*Z(F2ZL6QiRE6Pm3HszI7O~T%q5c3 zqo+(&eQ8q5p3Mj(sD#tq`sXMCv{{69@vn`s0^;=uLp=TWy{?If9qp*-`gXksOm&jL z#3L~mB<&$W)XoGhfNP_M(=M1UUlJs6MnnF)YKx-^yKz$;6=es7QDx>vOfcI?(Qfp7 z}gxO63H0 zy}rNOFkea5jx?wDgSRADhS+t-ozvf8QM_)$T3A4*AP2UV< z+g5Iwo_8@L%4WS+J9f_$mqq=hz3&-V4BY_sK5xtUB#v%4Fe29<{*Pnw`b8!6paF&r z2XSqHf*5+O!K{&5$KT0ERpkrf#4$T{MG;cfS4g`z$;%n#%~$qyQCT}6>aXUi%5+%R zYf2G=pW#53yrNr!XRqYA%@{pn2w=*gUk3(Yo%6cLx6)5ZOq2`!TvhFzoiW(4PLz`x zPTcNIh5a23Qs8ZIiSYx^;;lZLh5G9O}jAw-+P_@KjObA+{+o zxonURAw;_(Yx1(XnP?@|fm((PU1CBjc%?mM=FA{eh<7yl1$(s#Cbu1;xo?I}*0>HM zlEb#(i4zBVJ}Da3PeI<|_|VB=u;dOU*hwM1y^FpYzD@9~=_}nVLw$;LzA`vPOMe(4$m6q0}0`5N#yzA(tYA2o>!G3B=p7bPfEs&}m zJN0H6e0V2|`TvF?<6*m`#_2fR#zAku-+DPKjD@306JPxs(ddIfhIdDHic+6BTO|IS zN8#qO>>gxDW26bEZr|L7CM0Qka+=5>FRj6L87KrV@we@Hkt(<6_i8{c5UTryoJssG z@witzF(93qkIeTQ21e~@>_h?8HYpgVNe=xDwh*XVID=$9no6ZQAO5gyb~{uhD!dYp za6g~A!L`ZFWWPV`*hf(_Mk%J;zGrg^c~BEOxpKDE2Et|0i>HTVwe|C3u27x-QWYNt zs0DbzxkhxbJ~nRGeHMBha)oZy@>ywNa5~%O&rwwp&f|QmSdv9XCUW;daREg%&olt1 zqJRld_MQ7i!GA0+)c1V8k#*=4GjDEeL|FG*mFrKR<0|UX(3BP&Q^V9Y;a8#xX%r@v z%hw8D0Gp7bqa$EyG59C(B(`{oHvorW^`P;jA$)7Y|F|Wg`oK9&65C|~lh|y07N%S! zKKiW%JNJQ_M5*{JL-P2Qj)S9ysHHovmU5xyYuParFH9p%XRz^s7hSLP00Atdehio+ z?+&|XHClpp$qfI)|N1@u`L_*lk_U5v7R(Jm!36GBV1o?U%?B4cEb-d`e<2VO2!cii zG!#cMG!Y*kxi^o0ymCHm~625uoJ!a!!AHS^eM7 z^t+DJ;Gg>zH0thhq12ayry-bREx|y3?J_Vs-nf@KQZ&t5v@%EH_uo69D~c-*w#wNd znK^UgJ5h8Sh=94;0MuMCm35f4F$B8=jT1+hfGGzIUqs{|c{s*w?7x4gTTTwlqtS+i zK9SAlUcxa-ld3zK5WO|3; zp?gte{uwYDk<8Ud?A|IQNk>_a=q-!-aviK649bnDH+jEG2(6_XlwY#Ty;hGS)1&Dm zI`no#P(T3g+oZ*;x4oY)O;^-?`e8B*3$oOCNL^pbvp zB6)7o8bq^Il#7rO%n0?#(snu==FsXUYHVv_aK&5`w(=*2N4KnHPe^#Qzjw01Fz4v< zjn)uxn|&~ur$1%<>i&0JJwgE{Pl{~49WtItW1{Wi2UUHc1F~SK{-BX0GO93cX*?94lJH_G^$VJ?x0sV&dtuidmfi(pMFygxa85xh`GAL z4K_4XUE`Ikyd;rgjl3lpmoLP{*G`xl4YCfXzE-p!rKMbP5Zwn-sqq=qP}ATy@_leQXI{G#z7`|T_9?pXcpq|YsSD;hhMl3v*N})sdNs|C z*8~W9c4$=x!jztkGqZGpMva(x!@}i#cc8q#^v1$|nuZGLj&~Uqe^V$hAR51PM`n=5 zPDNDnUOO^;Y)qqu&P_J~XAjVeePTnvz$aZJTKXQ0Mw~R!=UkN0>F=g-(}Xi6rJhI) zwlVqePd<7G{sg-lAT)jfd3BCpMqtG;Iy(Bx_w|_QbDqfOkJqktwHmNs2B)T+_~xr~;KHRbU}m1;2>w9pPYpn`&hfxsziuo5L8OT^O0l5_C%;}j4wIgqxTFna zccFSmNK+Zgp(JaJnk-MO;e3XfwPrA)z2N1TRy*P05%-WdrG833fgWnZHcBx&2pm8>2_EC1vn zPD6Vv8}$CAnfR$W63JD9Jzi-vXu)BDOOc<>7iLslUtG7#zEa!>+rss+T0jjuQnHab zC*ncWh>PluU-NlWYw8G95)^*4t;;7@3IE;0nw^Uc0BqDrbtS}(X%$fh-n{*urons1 zD#GsCnD`^qH2KRg74-ZsKa#aG4lNR68Hq|BujIiI1$5xT$ z@ifBsROkMsWW8TX{)+xjZ%|cQ8jGoBj}1$-I*1=n{LN7AL)IWzNjf{5LO#$rXb8%5 zYDC`?ZN8+k6}NKa#~mXEDMp$wyd3)BgbG(g8Ti1OTq;M6f4D4J&vvVL5?OOn{YC||T$j`t zFE%|X!_GF2gc6orgHs)uQKC74Z&;YeVdUgUw$mruSX?j;Y0|0Rx|Cs<&aJ(GKT8ww z?;1Q)*uw$(f#OkShmShK{|)iJUP zlu@M=PSL%Hv^Y-E-bA{i!7=n|P~wvzakj5IF);W`TkswT)wXv8mEmcPEq`(yxpa6p zHrA7|e-E7PmEBrQd@jUSy}5TPL_qpP?MGy-PSeED`}5ik!@U99OA)uq-4c+aqsa9R ztO?ls1Qb009ZQQ94BTXY09Xw0-j&)15Kcg1j)E&l4!JHQP-8p~R5rU}w|7eSJ zN;JLRPTZt=gI!rI>w{4D=U99MGF48Cwxfe^E){G9Gt!)CwgG!Bo7A>anv*DtPR$vz zE5wPG!NM>v%LdFTaDaW|SYkor_K@cQD>CtIc8;lHi4BY$3UpV6;pHXgu`HXN#f zmz*_SqW`3ooe<8oUc6wWf~zLx@4+DOkQHy$qI-_2lZ{01@b*faR_R1XIU9yi ziKyqhK)wka{hg^u|5o!i_n(#79%1z(k8!h69f8ew60}{g(jN{(_i-mWAQ?=mrE;KF zKloPN@DF06GIkuLTNiGgC*eO3zcJgYM%<=l21-^deQ(eP<1C?XHfdo3ts+ry=H@Su z(emjx%Ol|knblhob4rDag}TvsP^00((1w`Id7mUT=ue!vs#GC?Rh87>liG4skN` z#AWw>39x5J&mznrTSmuuJ>&ViMu;O@7lgSb@LzVz7IW-gjhStKgafKrF1zEhJ*g`Y z({44zPGrsgj?V)w2nxBG1!nUD-gwfsbr z_wzHK#y$Y;WJ-5Z2to}0vHoBS!Id#)U!NufLN?*b_}mlWGC-U5=s&arQ02kr_b-bv zm>2AvV)~_$q*wJcXL!1>=txlqy#rNX{x$8)(khd#_HBVgi%zxNrdgWdZe9wK<@{{L zEvY^{Y^oBq$x~JE`r`5Gw7@XAZE9HUMv}UvtGxonudJmq8 ziY6?)6^If5v=;A=vi$BBryVB8pv?3H!oCen>lZWaTif>{DVhVU(*=_YogC&R98oeT zQT?Eaq%zBIL6ch#>k6uhHt%3k;ofC}UnEP$tq4m4lQTcTTW$b}Nk@l(kZ|~UBHRg- zex>}F6bL8ee|O!_$b=`EQKHpaq?OkG9^_|05G6J5EutaK4pQO1LJDihWDtEngSakfk^f{D|5U&D zF6vrYrs2b>H*e`33d9@w7%1#$fnvd9nBIxDr|fwM~&IS^P1VJoJFG!Rl{zDeaexz z=JS=BaXC?@#f~G|nUhL`spD-Jl?HC~^&`VG6y%+*<^lQB1dWCl9=%*9vA?X$wdgn4 zETTaJJl{m+kCP4hkLib_sG>U{WpoKN6=mh*9OS2bjr4(iFFGgID`Y(4Wz}7F2U%aW z=H)RUdsEVv|~N~IbZS}KA6p`I4sX?B%Us1j!wtz_{7csW{E80wuqe6Ngpy(7zp z-Xf^jG#T${dGeYdSFR$3`&DbOQ+ll{ZT1XcmVx|9(l70pC;)2=)HL@I0OrHL90AnB zoJ+jeO-E3qHm*iT^K7xvVr~9=$|D+dug*-mU8eM2nuBV(9AWg2F!Hix9_#dFlo7la zX^mNxGhnfimI#NPBc@>RodmUe3ijO4b$Xw)5Of3k=Gnqj6J*CPUcl}~#?@dSFiF1mX4E{IG~GXeTXuyNMc%? zwMXY=m_Sy}vmBrbmJgB*2t>YPBbf01^5xH(FO#pC;C?uAVV%5+&FDx3_Youl#!KP56U^jvQHV$&O0s2x-|MTs5pBQ{Zx~JHKO)<@`gj!kGSeyeU^2-VAp%PqZDNX zf?-2kY~96I+_f7{XOnIp0;P*so5qn9V*2tH^%d* zL|^Dq9%8NMYzHKtG{UK0d{l7g1%_jd-Ep!u-jJY3yikImx?Nrg2>Xs z?^Gu;Hj$`{$UuXg8Y&jG-=2P^TBaFJ*WgPcm=lVsF|kV)a|$X+jM494SB=8C_hd(NTlpJ6w9is*W8EE5@iq!AFi;em3>SRTa zht?tX#(K2+H?13QiKVnv7=w?yk0*YGPGd;-SKXUd5wyD5Z3t&V9L|q;F#@$+L#<*> zn~%d5l@jDPt=laDNX8ih{{%IO$cUrYA1_x~xWV52(ILRVEC9cdd&j?YC1YHqcx`{# z(2lgMRN;Xr7c66PZG~7+25Zn01hP|o`_ee6kY?6TK6n|1!Bn)ssTZWxZjx#OqW`{l z;QCU2qB<;EHawA@A{fBA2_rjCR+71~$YwhgPrFOejGcfWz>%WkSh*4`gUet3O-NJK zK2i)gP30m$bT5XPDiz;T8^C7YEdLF9WlD!iubD~hC`l93U8_ZqnM@s=hu;&NR4v_0=AMTVdkFBtCx$CO zT@M$P*OY28zBdeWplJQZmYLI-Oe>S2j@>j7tWkP0!(W}E{R3+vga6WdP9yMogx>Nk zc0)g2)7?b2Gxq4rO;DVIh&t0N`cMN}*~RX+ix2x(ean>+%~Dxdzz_0N-Y;8e%azeG zqIxR?jLYW*9E=@{`a#vo(L(pcAJVy&GA1Ix~vo%6Pr5kWs zM|il2wk5MIUQzOT?_y_OwW{jf^veIPs&C(z%YzcKbr_8bhk5BxB|HdE9$(qt?(qgy z?v1Y2NFO%9r5pBFi-`8tt8|ihMcaA0V$!9`2ZGi$2@KZbH+A8VPj2Pl1~Inq!ru1ByH4#JQ(3Iqd%J{Q2Bz?ftygsR7=X zfP)X<`TYY>hGHFrUe?FwWqGPbO0+MUV7RQo4Pk>Jh;SCDl}?o5B)dNmxhe9*d#*0h z!s@$>G}(=*Y^|+}cB21H%CWYLM$~iAW{U9*um&3@QcVcZl%A>Qvty{JZxJz*+5)@^ zZ||&OKY#<(M=ImYcr^1KB{&_iei;Y{3@u_+Rx{`I}78B{^(x+q0oLsE8FbWxnn zTi#%Cs!YdkU>xj_Sa&}2b_&Tz1vX^PopRot+-ep=V-ZKQFSJAH8*td*_qh9k?dK_A zA_A41*E#cb^gUSacs~H%PGEHkN=jbgO1Htbu1|ty8ozQ@_4>ENvV}kA>5xh8gfLxZ zOF~~GY-s@W_Fgz>ex5EzdqWFeC&n>DbSXYhqpnJl!#QO)>}j6R8MthTX)6v6SqLLP zPYw<)f7&{K{>!m#K^C0Vf+O$Y30qqEoVHzc`_d5V0z;#T;>y4}Z4$|@J+NN>X2?zk zb;M=-`J}Ol6Xt=UrzsP8LQ+EhDmY#{$vw`NOAAC(8h_8jcgohVM%@ik{R=C`w_`lc z5|E}i^K>Qd>Dalp_s2~!ULHGPBDr}v5s z4(+P}E6+bGvY=X8rwYc>7bY?xNcx`gD&k?J7QTAx_n1HO!gjEbJMDG9Y=*uvi&LNdMq$V2peNC{57QB15Bz$V|f<(Mq z6jD#Azl~-D6A)q_b-P`+W@yF2@FsLkTB|2)CxU(BOcc6oT3d4?h za;&Kw2|4N8U?1>xZN+#uq}rQ4nO3ek-As5cWKvK&%6Riq@A*-S(fB1Yyv(F9qC*7> z=}pJc-ju!MTX>xobQOG-u$}&x>f}gMth3&;p4m?Ui|YA5cIochO6x(gD^P`{?)Rwv zgqE?WQaTzqE1W2#I8dXF(R;T#)`p1yqtRFvXo~hao+ zajO%PydybN*rR z`d%b>cbRo5d!6)j2RM=NiDl?-snQ77g#(D!8>YY=Lv{HXX0>qfjn0HBbrM|#qd!~` z=G{RWqX#2{3x|XsK{~G#ETp8*bQi67p5I?(b4-Ib)u|R66OAbkzRhOaKdCBV%Wl=- zP#e8(!9Zc|&m`%OqHR06*AFd}DGcL*q%hU}y*bq+zITZ*P*W$nP=d;g9!M)Ht0k9_ z9q}jZ%q}++&BQdPLMZoO{X&Up*f&!amdqqjk|s9TRd0C&1Z0GaN(0tMYhQy{^ksJ3 ze%!xUT=flUyeH6BjJPXJ;0Q5HWDjM1C*N$#9VbaW#|Gf#DrjwuIkBxh`|7iXOw>Fj?j& zLaOqh4*Zbdsq!e^XRxLUnzoTKqUG+&AM9<%{(AfMb$Q2a;txKfd%?a}1a_~m#}iq! z;M5(4CCp_*jN3GmKGmefaFV*57RgzYxrW!@E>>&3VJL@bR8~MUiPyzx7_!}FbDLIR zugr4sdjTR88h&r>7S{Nnezy)E?Oo!;*?`9$bXqV}`l6xG@rJ8a>CN7Jd1!OGx-d{^ zdi~})D@-6T^1Z-_)5DTHoFwlarue04$J=VB`HboW)<6>thm!TeawgoxLxCki=@fbn zcfpp#()K)SV?%_7VGF}eE*t}^+}36gl+pv}c*JbvVeQ2Bf{2Ay{mL3wVzOSZ! z?V!Vyre*^B7fbl&$tUHz**T~Mj?%;>L) zdwv&Cb5(>tp{k*7+MvR3oepTd?YgzbxK+wcXcNQpA^xjaiN^nNyO!}K-- zcNb>)Mxii1CEz8*L13cyb7TBGVnq{#ts-z%L6&Vlz>~#Q0wwH{b;1mfs`ZffSiV}{ zKFZ&o=k?vR@p{YkiWb-mEKN635CdZwZ?q8Uq&@YGqgzj*tMM3DC2!VcBsq5C*-ls@ zEkKhx@bESnAteJnW0OQu^W?O@v#{=wA5!jKVysM^T1w?|;L3B`q5cL9cu)@;PU4d* z(e|i0h8hlqEi^1bKX3Yd-_zAKwG+5*vQ=AlLkgfI;qhs*$PWqk7@m5L?e3I@f8ElJ zfK$2`K!*jBoKP1JK4%dlBcXb&gPfbu@*MxA$O`bBU60=})2Q5+XS$yK0!pcX%G(ik zTgB7P?(S?N(IFd_M354wcgoCceIpX58mA@I*MIsnP-*60vek@(&&cG}O8r~cXnEHVHE3DA*%A57r*85r7rgJQdx5f51R=DaEIt5@?U zHe?AQ@bUKdR9HdM`Cq-zP#Qb##dZl3bteG?{Glp^H$D1KoI^@Z@x?J&HZ?7wG z`P%thYP;Ip_Hum<2RU4d(G1jDx57Qq*yar9E^4oKWuCjU&6Y02VRK5gUVRqNjGar} z4DUBVPMZJz8G5D5%eQI0xiwUSyQ9PV;?fheFJt>-|G1?)ts{*zc?fqfo_99W zBJ0=c5I(6kOJ!a7+)fd1bDm5SGDf2If?k#F9%-94qmuG_;X4GYgzJQUP+6r!wVLR9 zIleAJw-|2`#(}+8f5Co7g+gkn*G{kXJ1awG+U~BeWgBNNcy*WhY;_E8BVQu`#~u&SnH!A zrNdH&&03$OUk|zeHS7T4GQfiLF;Dav?@_DL2NZ4qpX_0J8dGnM5dLvXv1(n zw%Q-3Ug>gm>H7LZB1!iH_llH^CS3{@;)~RZ@kEnIiyOa zd`bMQXRwn~9`QA&_d9#EYr(_dycjV}dH$%Vh{HB`LBhycaeSwfJV+Gk zYj|Mggv5Y1|NQUYzkrVtfQ<_X^j-je2rblF4T}G{PqjPa^pm5e#txr5*XT_IR!j+D z+bB!}qSJI$?g(L2LAQsT=`_LAW?u9y;=g6wxt_mjrhR#?v?S)<3 zZB7zi(m|^M^xXnl+P(!9y1k_K*_4m86gP2F8M*M+$n< zt5OHf+Oe2puOl=flKbyFZA*JE;9j)aeHr1H@Yt4=jlPQD*e_f%)JMju>OAqU%}SNh zaDr5WU61@xCHCEkM%^lgX}liY`S#Za^oA7Q1tZ=&tR2^Fo2i@qKqSf#_-xO)qDVSM z(y#HP$M(BM`yj(6dM{lLBa}tSF%94KZzd9xN4~&J@oEI+J zY@48OP6=lWDO;ehvueBePeD^#M^^u(oy3?-|93O#IMIv>spKoTzOc9Y!ef3a2PpH# zI-651f|kf`6f;-iW>2q17Fv?G(4jH&24k8hD$b!$*sb-IA;8=Kc~9WP;D=a)7n_{> zaYW&F2Yds7A&Jo>rOe=dT<`<7s90JEYog|rzaE`VMt1c!!#`#lDYf{#{@)8Q;({~l zt4Cz9P!M!?@mPn-Q&D1)?GVjxlkErRu_8}NS0lm652s7l-gVOdd}3tWRaM)@Oa|(Y zsdV=h7*;Xe_ttTC6Upu^R?8C9ch8%;l!Ln_Rvau0#9*myxFgT)Jh)K3L(xB+kDT$v zXMdhY{XtOW@y)xLkkWwj%IL?hnO(#41Z%CYM=g$`a{qRh&I68?@tiWAQjNcDq_KVI z2~rVwnUxW{pym-Op9Ry>!!Ajk#kZ?aBj}On0kMYjQ=y)bE)$c{_RYIYq^(oy6~`TQ zp#%ERR?|j$)CR1wAQZwkka*+}8 z)qh1>sU!QOlH=t@@6*;*iMkXu`T}I<{mr^qx3ze`olsT&%XJ$4hr^Y9t&*8c-~@u; zvo=+@C29=`k^$2T4CMcn(`RLU2&mHnR%74>MSPx+$Y=A98+a+=Z+L}ar`}hfm$j9R z1&NaK^ZyZd6ZAA4;9t2+J%>LC6+0rNL@oOQaCxb^Xizbq#nr%6XrEC{5{A>+v?nLB zA$TFTo^dwZli5avLSU!Tzj^$byC3 z;pF6Glt}gIA8P+uOp_1^>4uV1nhX_EC7_BZAkC*o*2aX_Xb)dX%K;HbOg;-)rY$uh z%RG&<(UMOfh`Ujz5}fm<=4_IjmW*}~YuE3ZPD2M}vvE{;8(%Kzw%Y2+m)Ck1Yc*k3 z-GF*&S-_ZJ-_x8bRBsoR=&1}+Of4rWTT{Z5Z51=z)m}NZL{RZ&>5bde(7EV6qQkWI zkqnur)EC8N=UsJ*yL-M8co0i63*baVK-M{@z$lv{EjMqQDnI7_=wiwa7bA}ignVMu z?Y|)!8v?a~=P_9MG*@D%5rwKuc1_F)yA_aM<#{x;m2Hp7*tXX2>|wBtB*ZFudNJ1z zKc4dHjp&PD-$*&=YH~lwJ&p+56I}iQIU_%y8q%Po!GdaV_NyP+_ZAQ^-k<-BW(H{h z0(S`J3!F;35npY;6~Ci>YcN47a$sXwHhEA=^&Re&SVI|}B$EWiND7kKigwns-aS>? z+t!l$dSqy6qMKYLFI(@qZ?$W_|NV}(bC=ksuaA92V1xWY9dY%-qRSJLo7w}c408bU z`d{z%4-ETiQ|rGMk6X`<$9rg+ZJ^ZqnO3%ha5~sHR|^E|bqSH0p|S4#`b^JegIT-7 zs)6MGnVBxo58tXTxJwXE+vTM3jd{nDY#h+p8mmCm<(9ZqXrQPG9_&6NeOzhtnA?w1FaOJt&_6-UnYNabFR8( z?yjpv+$v|Q3lmW?MXrL|qR>nINiiiA#V}P#lBe|hqP}8bS)f$#Zu9mu49 ztfy3^yw!O<|6H)M*Tz=gwQ8+@eYyJW8K-o#!r%4BbJa8Fy&aiNvd4aZ0LX21I79Ft zP(&;rIFl>;QVXtgbRd|!4*}u(|rSiQj$wh5caZmKwBfPZpcWY|2Y)V27BHYWB{sfnnLvYd05eBdD zRP99XmbG8dxD(0e9dL!_i-R3BDr)#1-w)8IS9SbwF*M3OZ|J_~glK;Rjn&9~`qhF{ z-0&p6Z_GsDKijpP+==VOCKs3!ojfx6UUv;S%>d3evzfkZ6=C&P+{f5`Pqf@(uXCVQ zVcCHZ6j?RNKyzS|%n5<0(j&IKa2*r3Z|yWgLm-v%>9-r6DZmqa!R?%F7y=Vvl<(bM zpB1;5ZNBsX>b{BrQ)5#5ohT|4c?edp1z~4chuYM#yK9oLO4xY|&|6NeGnMM{5YGl} ziO`N;8)D;w5b^hRDw*LgLTo))VLV*ZAl@W?GnMaRceMO#KD_Qz+GA9Sty^&~n@kgzC z<=a$JvEvStPoDlC>O2~TDIy%kPKZJJ7|lK%??QL_Vev3w=oHnv@NF3dRtz}Ch7sNy zoY*pJCkY7&hxIMs8NIzNE6bR=Bnw0T;YTBmE2YuHghZtG0UVpIJgf&_TT8)RK(@=j zQ}GST%;u8r6h&beYl0u=TE2C=R7p!qb0*kF;PTbWx}-Cv#P0%K7yq^5{WoeXokh_*8-zYQr$G&SP@NCnpCG0Om#3+)#0hdgo z;~*pcl068a5u{9GVTp#YsnvlvKSCSkD(*jD)Ie`&5s&+0NH{7aTL15DKd^Y4_)dH_ z53r5R2)66H5dR9!jvoUmNDq(-0Q}E8J3BzRubZP|Lu>0Z(3261TW};viibw!nQplm zn_HcyR6j-IR(nGd@oRVX`-}CB^z^V(Q}H@{w|Rkc2cdg<+;%`e z6O0kwZ0Te-$e9%$()ee7JpTH61f1C0ooe&M3@`IypHP#7VYhs+xpdrp@F} zRk7|M@8@Ma(xmX9>d0A%3ynM?e;d+&B()El?rD9qJa!KfL-@%oBw%x?)^(@&c7cvK z*LYzsnLVt3+#)wqvXH92O6lqH{xyH#@%gwK^lqpsm@F{DAu~h1KH)diq=(r>m3MjVpYVJ;o4JTo z5&EhNTNjp=OiZu!JJpV6ADGtr24UM33Xw%|#mE(wM`?(w*I_nlXAdaEw~Ranao_Zv zxvRJ{1pLvyGx$pN(Uolcii-&l zY`Q?8Gds-=?blc&#Nnaez?}lTr;u9|zj6qnBabaiw}e#9+2tY`qNwIaP`(6h z;#XsK_1(DI*GE?Gr!u1dC1Q@EX*8io98M#J&$+w04*auZ;Y``zvq3hLHvz7Lz7`Kg`Ksg>xXSfH(?b!RucPyJ<9;#u|2 zB_SWO$TuuR-##SBW?S!~N!T#xqDP$uMVd5L|9#}3TfCsg*4EbM=KDjkf6q?;o}6Y& zZ-U-uTkTd?R#&yPwK@6fMWVIlKX_itwz8McLTAduiEHocK(IoiUJ`nU^TN=ixS%VX* ziHS|F`C;O+O!C)x2V!}$DW8|=#x+C7=u^fo;StHV6au2nq~GQBKtSO zA~tdysvenKmd*bG54T73VJ7c-`l+!tv^M^J#9^Xj-xP&a=0uN{I--H?RqN)>UfQ5# z-ru4moTM`t$8;KzWale$KqRA0?3i37c2hnY2d zetyIaTAwF=NHvR_diBwJD@jzQ6b;Az#hPPuI#Jm%Nk7Z7%4IezhkV%$#PJG&-co}= z8I4C=GaKi0Ou)@d2F4RfXfj{(=&V+dXCTHtec-hnHGv`cOZ3@;u%-EOl5Gu~n|5M4 zNL@vDZbv6S;?)(!8OYna0ioz%?QRM7w$j}En?w_`#?dy%9yeEoTsipL0F23>Uugx> zq{i#5P&2={vWda{8NFSg*kmO!8JXWhk_%TFC(!CpsCnn}BZhypVGMhxSX#c;;FFHV z&MsXqM~%gL9lHLNFeYT6W4we?09zjZQfy zS;72BOL(=GkKGRAHjSC5zW32A#^Ax4#0iAhI47#rQBM9jOqk*vw9orI7tU|nUEw6= zf>Q~^-vKf04K{cuRn+)BX4y(}C~gJvPfD#=+TiMMcPr7>O$!r@tL?0CyfN9)$eJRl zrA=!GcM~D@D$D#q6FEY4aY8#*v{Qwdb_aV5PGwJR?e(#5ML=x!3(!l7t64Sc3c+6i znRv}b9~WI%NUFFioEyVe0|M({>P{z+-N+Ce{s&zZXPZluf8=H(7PG|WJE>?>(tle zpFQMgJE)~~;}&-d@~j^>QKANVdjFjYn@+tSv;W>_zk>txc549AXKh;SxSMlG5fm%u z>duJWT3=kyk(Fs#Kzf00j*!v}oJ%&>URd#|C{FWCz2!733yW12D#fI`#8#`8mKLyt zpP89SS$GqbBcx2*G9HE)8R_WIc~-f58x=4(g;;@X8P8UMdsBvIGj9>G@oS2KGNLrH z9!Eu`@Plg@V(!Vcz>d~%$W|YHp}>XI)E*Nv1X;Ol&+ANPrVfX# z#B?@1JA;US#tBqNL@N5WFo%hJxXt^d80mZKK!(hUBLUi`YxzdQyz0RB9}#joRD(|% z6(Depc3%i9>lP%}?8>yB%4Oh`tFFY>WYg+{R2?V!udiSO%Ax}B>#cxh3r^jB)X)%h zR9hdQe)xyOMsxS%S8CcFb*PO@mc(vVoC`m@*;yaiZ zh<$f96MYDq=pzu<5$-wh))| z*`UoGA4PD+gBbZOIC%V6)_m27=d2l}j3Xody0{uSiw))XLO}*`-*;J_fSUb`M<`1u z+Y1!+cr~tcls`^{?0057^ zzFUUXLz(LqpWsO7xTaMVRe(`ErDe29TM!E-qZhGrS#ki2NXX}>X%`#u4OHIAc({wc z=c}&zIMu;|(#kGtGaUOOc~jGfB0J!{1|_m#oHA{$6^?-#6Cq!;-Ew@y0?eQ{q8 zyrp+<4N+@brmV1>-L!bl&Fn7H#dA*>X9>=Hx{|mqiIVD^z zL8J>j#>PpO6i@`$o22q5fDetSwyrMM{*=@yUdoNGS(yy&$25EnojLp-+`00%o{2Z#=0_az#{Th0YWUl# z--}(*JKi<{Kr|oF$^bOwzoS9#qs64=n~%3W+IDt!&)UAO*GQwn_K3gdrE<0G*|ihS z*Gzs|yIt!JB&K>dn`S=s#wW;v%8MBaL`*DACK$Erj`~j=BPlu?8X7>Lmy7jgU>5>V zuY&neSLCx;#24M7_fJE@n6)n%3KP~PD?)#C%TCm_s0_q9yZ9kAS9L|!NLikY=4CW5 zyYwB)nd;^<@=`%(-Yqw()lH-3nAWh%v8Cwt(4t?Bp)56w_tlY5*I9|K;V(5^E%Yt# zi=;{*={EDiTB@xJi!(HRD)ADs>cHy(5(aUayBYY=&SObAHu^IiLKw3dK0b1!-C_qE zW0N?WG-%{riPm}9+6zJ)1k}#hKs_up6Q6hPOE|_k(zS4{akqSVxwM2=U8;&zqU6+0 zH+fO@N&^(UpKgMS$2gxxy+Rhh=xbIJcMcNThKLn*uoca%qie;u3Ubu3!gr3ZUubGD za6h<3$1hVy@OHL22ggy%s^I(URxdEPAXcl`@Pj9xaa(Tqdeq1c&{;->74eC-#)*|3E5y=~z%rAJC`1}lNu6uv} zr8;{J?5#MzMIhsaDuF@KH-)2RMm&=oz!ojaVlO?@TvyVkvNxnf@bqtPOubGP#ZH?q zX>MvS3LHP0C_Wk#a%+gA9KQG}?ay4T3B%QH2^%{nHQ%Vz-^TP~00rA&t9q)kvNfzd zo^^%yJ4xGRbstCU4I$lIUoAZy$;BS^$!)67P$Dz0fATKx7c)mC%d#~yep@K4G(*=t z2Ybmsu3nLsW?5kH;hyME^w*{dcrQrJc)DyQ*JYtG@P>2#@5Y<*r7{a6He?a$&s0^Z`8 z`~Ly~PA=PbN!e@tcY$kdd0A8ISM%l;Uh--VP8_27QOFmcKDN6fK0gt9Zx#7>>0ycT zW{-CQ8Z*oKnM!fbN&D7FRNz7Siu3MHOLiZXdWMc5n z{~BuP+06K~JRA>dXGQpbFUl;G^FB@CR{+0+K!IJQ@6PPVh_rt_Fn4Sn60x5vv*s)O zHK*#P`Ll>QN_-QHombT~@5(BNF(P`z)30~TH8ni-j{m2QG6*6uSp8S$lw;8~rd@*p zE{}3FXL-Y||9l$lP_vDNJ;k@=rEvTiK0JnErwq#J#S=k^DS?ZPgS&-==kkOXd`ic+bfWr-!eH3L-&Bz;7i#)5BQ}3AlpV^d4o}Hy$1vmoc zBPo~FEj>O`3%}Z?qh)c9=KHrKLHThw8DCRso?KmZh3k|{Zaoxi7Ok1wRr&P;pU$me znrke=K`e(-bZmA@!R=WgI8CIj%fDj&PAk!6(CZ4_Kt&?;F|!cG8?25N@+8gqm0KlW zoPYWNys82Pq{INaJpaw@_yz4WBci2tCzwRxr?E<%h+mH;i4Bc=AEoI(uMy(YU^{Fv z$bS_Mwb_U$K@)I@W62?s7j{F_d&eUz}fN3}&ARIW7NN_XY7t)EGY?uvO#c(1f` zIyz4YV$40G_XH&(&AbmsMgnWhNv1~Rsq_}*H-lXD8PBUtd`U0WMET_l2Vpy+9-&|# zvc(N>e^}B8NIxVx4%HDe1i{zzyMs%2-OjuW3N!P>F&L*lS->1z9LmvfylY%|L?dbe zt3bG4j@8Php8KQS>LP;Es%d=DS$m&hTynK(tVnc}?BhpOV(lZ#pHSLD=p~s7xdq!` z?qgr+?}L)Eba|LK^9T6EnA!3LMQZol^wK3DCaIceHe2*n zWVPE$jkxNNzlNoqbl#i+2RktrATzfe13ke8XiG(5H&!vzTXnb8*7_A ze*R_szK|?z6`drT5z%gH&}orKJqt{LVl$seOlqM=4xVthg4y=7uS)ah(@W3NkM~FW zT(b1F;T^_}wJ=Pf#94c&?l3Rk&sUMJ68^)83)GfMWb3txUa^ zwl=+Z0v%4Y^=M>+Fr&D;*)zQC>q%Uti^{A`q;|!U1k6|=2+2g0aJb6;c zy*)jsGRqo~gywHnmbX7-CnX<%ixd0ln1@@hH)Ic9aK=1T*LwhIt^M9T`(w}0u`Y-E zlt*dt34@cB$@TEL)}=r=p6fA>pAsI+<;3ka*Q_4eP0+8bFO5CBE)^2ILFN)eC($*o zVGx6(C(Uy)f7G$j&5)7NyE;}e1k;z>ED>e!$JNus61ryOo9?Z%;X*L7Htw!W*beYT zW_D|VymcthR0o(7+GUG0VbL`dMLXm&UNLH2>h$KUu&8G&Abk=))ie*WM*IjpU`}m-%d+-`3&|(0oo#0OG%M4qF46|~}arfym9pBjyjbGM&&OUm&dTcUX zi(rL2(dFSFmcGUqa<)=y2^+F|NGii!Ci(bud_%6(v;UNu7$ERTKml|Xbd-djjaj zp2WwhnIV<78L&2~TS*4^p*Dm7)?F~!-9`BBNd?4W31QX7E)06Vw|d>qd3|pW2=vuC zk9X7m4-5uiUW`Qi1*pPG3FY-yLn!8rpZ(905$3Qm{CH=bev^H!Dfa~j?UQWQGPm+4lmql#a+Tdt(KKkwDUp0_9^ zd~I7^6ggut?ji0V`r=FsVb4BjWH zbL!7Lw;QBls*!y01-a8SL8;GG&7Z*E8!9;`Nt0cI{(D5jLWqaFPnN}#;Bi4WA${Ii z!2uy7&Wztg*(I5c$>wYUX@@xiq}u0>CP*$vX%v&A(*M0@lncW}nC%ox#c96y=_FpA}|019yO%m zDz2bs03(Ou9G3(LGnt7OK(mr!7@QMY)WjgibDc1t?qxNzrk63ZI~0YF0)J(?CUG2| z7IzkS^$^Qy?(WU;g(Jxbq=3wfcc;Zx(UTa7tTp#*P)3kP&8AxBfXWm*RbpZrYR#A) zzWW|)^N1#VlRYt1T6LB#xO4b-n;h9A+@lL1^Oro8D^Gffy#4~T)Mu^{y(Q~@I% zN?B=pT`8zmng|aZ=TV=NzbsUY6j@6v8Y2yIaeKX{d=^0;sZ?{28{i5BxXJLH2hGSE zkln>H@S}lB)hII%#-!i82>a&v=m=(9!q*(R$GjA>2Sf zLsh0pvsz4O)9VonNuk2$$2-sT7~GM z2kKJok$T|*Su3v#tr|w7rqez77p7|(IDl8Ew6`fpc`onvhug5=%tVrwZ>3L8nzlg$ z+$vmZ#uv#QX4E;~4)6FznIv@juE0VEt{2=5=2zOURHSuH5v~`HV?SB!IDg0!jc_#g zpKKdYhj+JMNXQx{)Gn;af=KiD*h^yMg9zstlQ5r4cCe+F79zICJgQw7cZUbkCQe&mx@p=S z%bED(KJmVaXCK)R78F&DukYz7+bM?BW-m_=ms3emC&#GAs%% zv|~fIg+B-p;^?qSckt9AtQ8? zaF0KaAmFNevWHB&#zd9h!CTwdAE@-Wu|~t73ZrCdXWq|Opi%wk`-#9JX-nEJQe^7l zk}{9IJJ2Jm;k$whv%qj%FHf)I`Uglq1)N0J?=#o)pREl(H{^w%M6`WW zlXH4%h#Cx^vAJ2?2~}8?Ou2BPo8Ew|%(L1qqFd!O5|?SMDB;mcOdHj9BD*{d@jLAX zBb366Hp7V~Tmn$p_A9uU?J_Bc^yO#1%0ry*iwLNXHTJeTfCu$?o~vvN#Y$@a_aJoB z%B7)H9~TlBgxMg$3n#cgir{c(%au-jas>@oF~ru%SlhF{nCw&{AKZG6{ID=t$;Eup zWjkkkwrViRZg(k-b(t zKVzv@F`alC#m7{m{rZqA819NGFeYwC)>oKJE+9M0Y_SISZ2?&QmkYF1szR2FO1-g8 zaSN&caX1d1@g6lXfxmrbO)$zx8OoM1v97(Fk%zL)O&Zi)SLp(2OVhMg4DTN|elrNm zavfkf-uAKjl#!-qq5{iJX~&Cho@!Jz`tgtnO{~RT5s<*HFH$|3J^g3fTtRv1Uau0nKq+=Dw1jRoKBT(`TNG z<{Opj`6bL7$s^G5 z_$UI>HbJEM0rc7M?6-SpVOtLmZfT04gwe^c`LttEK3>6U`#YgcWN~XmD<6i#x&zOa z(3>sMV02Jm^|UQEUlNR3k$MG9Iaw(@PlINzxc28MlDyvOS8i$!&0@2y(|KPPsrPV|d1lWw0Ei?F!q3xH_3xL3v(R~rB_&O3vps<6W)2Dzk!JIkjAZRO~WC(#8ML``^iw+X`;HX zZRMp%O^cp76sj%zV(_a>iX^y(VDQc3{R(?KIIj5jV=7x|{>jEKg|9#3CZ@N>Tq$&L zOf=C;?`$!YEhXin3@DrCd%{Uj95Hy)KMCzg)aD)*4GU2GS;yD*#nvx8qa*!oP*wb@jyLM{G&d&3pJ6=b8x79DiCgil_clpD*YV zT@~6yWyYmH>425AFi25c1BXc=3sd!hPwx76 zTX0umEQytrTB5+ifa31|SYv!_!CwR*kFu%ltv_L~&ek8T4EjgUAdr8xPT$Q!}4&aV^K zTfRu`{Wk9HZEb(=SpVG(L?ADoJpfi-K!E=DR7&0Pi2?|)D$wnq$i>MbTqT1h_?F^es$cHSa%N!ENrK11j`)F_q#k92I7}(k3Yyv}V zLG_hdL7R^ zXz0+2OeX>POia9CHJY9wPlU~c8_S5x5StieBNlZ{PnGUO;DzN3)%YgAtfJi6FWAJ~ zO;49}%ofw*;F9oKTlse;fg0bM153V-eTb%p?I_8yQ1+8C@M~*v_wv8s-e>6eedxkj zs+uDtW$Z2Sc!-;jPk#-~O&AB8z7(aN`Ks6uhY}B?YakH9I@5mVExYQFWlhc8*@7|2HE4f_Dl9a*(e=)*;9pr} zVpwr#Lzr9M`f{(%hVx0~IFs8rxkbD}5!EzY0j9&Y{m%cm+T(H7^|^kFDaa`c?w5)#88?ezJF0!laq5p0LcURgI56gZ*~)i~6?E zDW(P<(cX*aOWSjIWGA;!_NHqRwLpBlGA0(+A6oZe^arTtfgh5mwgO4>%h9DEzVaip zz`jG{8{;<1161;^s6N@O86Mie=ucj_;mnyO*gm!&l^lS{W!n1!$#KRD| z_1Irm1|_(2mQr~aG!!nxE2cMMdk# zaTJv+d8ml5Q+43dea$~SwzZt3h7cEGd~ak9|CHJ??B`RGHRf0nT|QAwXQrA0D~*}F zPIs)Q*N=2;Ao3f5iL6qVsWX}%)+U~!KH`*p61b@i3+mmNYeqr`LI#_q6rCdcP_MP}5dQNb+(IHA7%Ve*^tP<+vh#tq^Uo>kt^<)^q&Ez#uNW^H$ zG+A=jXwG$VhA&z?33g~7c8T1LnvcJt)~wUYeZIv|lQmWqplEwm?If@o(_r&gNhsH7k~_)2GJk`0!ZLTA|$o)uXojg*u{(2W7B7MxtX` zA31``4DiW2h@TMDWjSyz4G6r&ksG91Fj#GAuA7AE0%A7J@6D&L#eFNr_?=%JqP*&* zLNAgZDx23)Hn6F)IOp>@`M{!y@rH5hj5+Q2NMg`9$wKWTx%rB(jJCGxqzN(IPtLVC z=Nja_+SB}ul+2ncbeelUud``WexUV+B0Nyme3!7IJoYH; z-e@IO`~^Sjz9&>xXXqfGyF1PprSEXa|MvRLEiVrbHznPHy&CnwQ_p2t6J}*_CJXi+ z@L~o4P5~hF!fCfB0GQ-FXlbY)rHQ%;1ygjF`72{{F(57HeT+gQaD#*6(ZLp?@8AYhDC~#(hietiKdZL<3(hfQ73AiZDtdzjB#{9* zAw2$@oZa#XkIfcNo65sJ8PitgLaAfZ_)4BXjI@9I`yt`Q1DUBHCz^q^e6c|LUi|#^ zlkcv5zp&ROMpG1QY$iFe8(1UgV!>PP2K2w~q>mVF3BJ3JcfUw-pVfN$5iapN9-t15 zaO5{to4DJ;pC0{{5UIv~!yF#`7fPTla&`5mW|WNIz&u8CxU3N)jk7xaQK#e7ytF;? zyJp^J^81HzHA0f4a2s}9JUrIzE}!N(#yY%NBejOOm7+aW7m8VOWrw@_TRjzWtnGp4`XFJtmJ9dLgGIyNBZKTv+8f zOHxGC;p+t3Nz<^`3HPZ5+B8~jw^blM^HzVON_SIxnn=P+?Mf0FNUZV zf+}1|KR>V5R@*m3B(!>K zPxFlLJsiUS(#IYJo_Dh=xJ*|m1J+Vb>j8#ot}g1&Ku_q+_G9xOE>J-y>?n??=9SNH zD%tclI_Bhdi8i!VKSrkRQ9@-~+YpUZ&S-cin91yicp zG56`hH76!e?{DB-&GPc{L@X z44csP;t^`*W-aLD)*W*W!x`<@=CBSZ+yW!ShCO>8^VEV^cHzLW=L_cLeJD~>SWV-t z$2{Fl%~IcM*Gu*SrKG}t=tZGJQ`yL%?h#{KRNMB&dH4L55_hgvkvM?-meKw+WSw4| zQ228OCxlt)SZhtaAH%b_O~a?9qFQ?Mk7eC{!KgQ>BhFHvuRsj)soABLU~+G4l;Qk2J-1mUW0I84*K+QYJyo^>_}K&KJ-pG zDPuj#6T^`6Rpsb9nU;OYj2o^3IT2F9LU++gw1wcNs~S^c$+$>_k>$Svy0{Ly6)QgN z@$(%kS04Gb^MzTIwov*+A9aCz@8jf8C|ouOv*f~M>r0)rN}YL}-|+c$BPMVns%xjG zIBWT5t!uTiU`-<)1=~6rCjB05lsq9ePAb`uRMcC4FAlK5!?HHR^%PvnGMY~^#4PQS z68QXk{jJ^mx_uqU%O~;sFW~h64sif|d2;>l@AYh$l~?+ z9NsVFR@W$r-&(O0pI*3bY{r|8@WDiGE{{U08wgv;@BHa+OIw~Lt*#-2+tWNSWJ12) zm}i;lw!esBR>`9xd@G4xM+Vo3DoPRQ1MoY4SusH0Xl)*aKkvhNLL)&)5~YKa*f} zHj%E83e&POXel|%!sFK8j-QJWz=Of5I@rclrar~R&lIn9d$P*SV#M(n8r)|C*3h1HsrwJdCezmq+&P3= znlRKdI|8X42JKxEsQm^F=nN?&d)NSRa*JaA0%J$Q9s=X%)cw$&&KocgAZdM*Yz9 z9Jc&taPDiM(LA%gTM^9wu7`grO`Sod*wLIAtZbtybcy~fYdvW&0@cld+B`J={)@0@ zLp|cF=I22x0h83zp~j7`Q%=rtj+vRWGJbQ{bn-*Dwu*E$!irmv}jXlPlLmge;~QujFlxBaYY*05G)0~RD( zvJr7&(W%$;Ae8QCw{MxR$IuGC@zyxgq>?=0O&mNCI0z+kh+L+c(-Gp%EI~ zg2v0e#nB=e#4K^*@K`L%9>1XAWYg)^d1$v|F(HKrdY)N>`Rw_8(E54BGEsVM!$o6F ztBlcdtW-FeVV<=41Uqq+yXzyfT(^eP5bwc~Ih+C+q}L_}d~o(ZVZXP9te!7c%!>5Q zS7InTe|y?PK0`+V5y{i@M3#u{k4U^(j%rOt$jhGMs_n9 zW3qxw|ISq89B=K;tG2yl;1>jE_oOgQwzrdY^c`U;(w^aI=F&Q$i^+(s5?HSY8tHP}qodG`6VgT=mWS2PeKl`-t-@B~+OgBrwQwh|=Kn7(&F9_Ju z*x%oOeSHNMBI*r0+dv>)BW)CZ=#Y82?%*^L^EgI1bm_09`(7kcbH@v~08a>J+^i5> zF)0jD%G~zBMLYjy@waFj0(*^t)^A#&@P{DhZkUa6i~pPLx`d!HZJxrBQ1~G>atG?& zg2Q)GO20-**7tPH7=;-1&_9?>$7mqMY|6a$?06f%>S@6<=hpJP);q>XfBbnEJURuM(z4d(#3_>rtvm9s2C}5=uhhe& z=V?eDz|>|_VA!aGb4acgvxl#36jK=E{P&Ya zqua+=uND#>bX_j=8s}g}qp7ZHs223Gjs*e|mi4XVarQLnh~UZ4mHCoj-C*JqB^Q4@ z+MTFEWx3RZx_jB!jDz9QmHS$XY_XqSiNr?(6vx8{~ncIf8uHZ?i!#!2wI%4 z`4Law<&zn?s*sM!#V5A-nx{sNbHDBNz0X=1SH?71YHGd_|i(w(Dyh)8)@h}nv2k=&jPJjf*LB}7c#`b;mlg9{<7CwcczPmcU>V( zx~mMu0ozjdtki%6OWVN#HTBGrq4nQ1beO+2PL7`ssmD-;Mog!e#{+pZzFeLUQIjPH zemRG+tS?KPTG+R2W|*L?!)`E0uut6Koo-}0&gU?pnY1u)iC%ZU7+} z#Utk1p>|qatr&3Aee-#-c7>^Ef>D*&=5#$Zz)_q5^ES$8FKK+gwtUON`*(oX3xu&V z_t_iY4-XFmP6q%FLevfd`Gg10uDFlx&KY6bHpWhUt3i^4yHyUb%O6fn0KH5(FXI_{Arc2oU z%$IuN&Lg;DdLOHhNK`dvevQby&QdHK_SD?aFgP&%MzMe*Ih zM;rm>Ek+f5WwrP$!(#nYWAGIy@XsbEKeaN`&G>z>Id0`H%cnRJDAQ-*fE|sar%mDw_3<`_aF1~^Dizg*t#bpv8K)0 zAJz7cI8VM7OH_z1EEQax7YYlcgX`@VA!s{7Z<m6(12R&al z$xrNB0B#WQe6v44ueujZyr4BN;(fCR44nZoPbO^xZ-h6>?r&JfN06Adi-##W);AS= zBnuHRocP?M*;D4g{FTF}HK@O+@+lV#l-*s8={zfIy#KQH^^vBJkB^b@Sdx8arALiU z92ksgql_o8C)dGGzgs=x2|PX1-4saGStqTS(}6fOR7jXR*ZmCw7T89)?zlWOsZ>MM zQ45yqge|*4YAMq;`AR`Lp2myWIo)}CJfuNS zl6zyYx(XjQrW$F96{8m!Jmb`$mgl!`)K{wxIz1Ov#f0#aG1c`^D^xecxh+s_qeRxdz;|Y^|+$%)bj!cG*6%xD^Q;7E@^?- zql>==EUG|RoHTxS=W23`lB00!7VDzqpWB1YhK!6%!DYEG&Jq2-zVNmcfeo=f%HW5( z>x(&V&YIj)u(NZ-RE=Pjb1|EKwQi`aq+}L=W0coV5~tR<5_*InKIL;eY;C&gp#nAt zqHDjDO4wandu|qeYX&TYb#-+ka+K{=cwE(~+ zQ)s^2?(6l_TCU(wFsv2n^WZVVeov2Uq$ls=-3ekUy@jXZs*Z7$^1nEG-%Mc zc9?A%#pK}X>f+n6u2Wia*;mF;7Ae%Tcpf zvgK=C!_Qt4j=RxhN=%n8tWmn%!4$FKjX8{}X-0sogG9^1+Zf8!t@dFmq)kSU0n0F5 zE{?l(KPr+k{#?QryyQ7!s zX>@L`f?|0W$#GzQBs{D(>|V~lZVax_ueGtcJU=#gM7g})0Rt{Oxw4H~Jx`Ckhx;Dv zv4g^1g-?A&n=15?;|4Fxx}TxuiK*Xj{ePJdkk>V)5$Qif>}Jy(HWzY~j`gO zar~!yYzjlcSgC-_cCqc&v|+k;aB{ilLyid_dm_g%E1zX&l+?=L$-Mt3DKSxDcLoRH z?C$2~1{m#IY!~u=0RiBok&zL=uL3A<8ykdppBcluwt-I_2*K)7O1}&LUGnRDQiMr{ zT{aEpF9oBJ9=bG&yEABgEZE63I}FQ?6ms{n19Yd^6;n4&0f#QZ3GsE`L4Un(Y1(M~ zgewhxSz5zbuvARPGDe08`Z1spR9u!uABiCIMIMyCyw0GrM6q?KcVF%ebDZb6kTXp<+^6w~w)z>uB zBOHXBt%j~Op?0}@kIEsFYu}pdS^^rsi3woyJr$?=_qzQ^?a~VoII!c;%`Qx(V6{xC zVRI^*%LA}F0SAzWrR6a|+ZaR>eP5pql(vKw5cMGq)Vq+NvtLSH2Ed~ryg7JeK%xDZ*!}UFZ|gwY%`V_ zx%nEWbJnFtqeE!OJkCIsGv1tkFcF^ypl^-5@27bQLNk!VV(X zg?_i3x=$q$mp@ygs5bUU4#`kmakcZ2+j@#J6pxg!ZYI!YLX z1t%l^3Y-$n7;m}h$Kf&OCXeL-NN}dC^TRHmM^{&(a1z2(J=F7edmD}h9 z-U+vS+Ns%t5weA6argMZEMoA1SVt8{Z>>$!N3tD1WJRk85 zCFwZ@5u3e6bGB|MH}>;R=6~!gBRQu`Lg?_G_+VGu=|(BwgPIo>5ST!i4~%9n{@E7` zG7sW4PfX*C9s1-^C*%PAZ%C3~;9GU20SoP`De7fBRM?juM-gYm&mrB{{q#LuRLVjK zh72Y~FanS0zx5950k0KF>`$J0iyCk+1qO+x9)uK468f z%8#*WI1qLD#6HDMhx~|3hDDu2wF0crNZSh=rKH@GJ%v378QxS3QC~_+607&BR}gUj z_+I&S7jUMG_%vK=*f3p;ABVG`iuXiMyW}rU^G|9)5Jr@3lok^g^GuH~rVHOs0z((F z_kObCSdT8J#2@SSJOxTW7SBe_b>{zk=O!BLT>GZNoN}a-l$Ub>$R94vp^+nBC;A~< ziD_Cr@Xgs|zdm-u<$sA)uIb zGxz8alVb~|+U*0f(azvrwduK-CqX-qpgxTiMrQ@68)v+MhrClSe}0>CL)__}UMZ&K znsXWODMRQ`uKk`8cCpk=7cy<3BwP-q?jm*(j{@sme!ZOzBH<1$ZS3a#U@s^e1H8~` z_+7LkOFhRfc3H-|PWKu=9k`}+HEu!^E*m*`hn$bJ)e$p5t|={wKbab1-gZ(aaeNIc z%T?d!O}81)HrxF;ly?XI13I4-F%GW?(R5-`jzUwnNJVch-Bnf_pw*YKt9A3Wu&mB- zA`qR0bGwxi$25-Z>=+?-{%1fIEvALgp}-C|o`#cx*KFlR#{bEV-pu??axZSLa^(kU z^;vmexq(kWrnWOXWaX0N->JvdC(j+ z^%%v;E+Ooal$3PiB+e5d3%z2o&FSW5x^4QR4@U`V!z`6>3E!{MjlhnzRX2nF^#5o& z$LKuTwhPC0W2dog+qP}9vDG+@?Z&**G`4NqZq&HRH_!UkJ3sO_S(BN$PV9YbcwEY; z(ev_GaDxhPj0$eBkc^lvxYN+i5S+PQ;#e+bX2(L1R&7Qz1p;iaDvJ@09U+05o-V>k zXpu(DPvcvczP`$Vm8j_N;hN48l1EhoEV;16G{Lz2nRS9`|j1u0eY$%y+Rsi>&zlMY_y-%!*s*_`m7 z9v(cd$gxARqJTS>!}anTBa-uY)lOg~^?%AEO$eB^g}v zNGF;O;-|myM2;G4H39hqv@Lvy8KiPCwVbL50MruNSUsuZ4h8dh7a`J3X!wPV?xq4+NS- zS9Qw#!sEUYOY)W**_4t6TBRL7_F;@4Fa?UsytzO|3gVD*JNIXoc*yc5!;f@F&@FW=8wkqHfj|(5!+-jHaaVL70XEsa?U4 z(1xfzZ=*gz<lp1G{hHXr?hkiL*k5Ipz0*uySY{HW$Ea;G)eJa`;;dodXQ z(3g&%ZDrh_Dd?vfgEqs#lmQ>&pO+lBppm52ip@g@Z@X71?E=7N83zsj*4Oge$_vhM7t zX^*43J@@AXMyv751}}v_kz8;BJUrg-&$mG1&%kKhP$$G(X>v(WV=n!Be_=X_^-ZXu zNw5?ok$iVFDI_3J%65Ytl}ktUZ_SiN*o%}j0ZI0%D89ay`IEvEBZ(C==p7U4H?3NH3N@dNwDvplcBv=RM1;UP0jahpXDD zHHp_APU3mPGagrKY;{NlxWOnUjnnurjo&)YD)U{T4?-Ja;~wgxHUIi6^{^%Bm6lEL zm)uF!zv+@`PJ#BxLDE)0PA%|D%MO%xuqF}FxnuY?2BaCpPMD-i>dib zrQ#M7PtI{s$bXfgF=ioE^4ZW1G;>|%0XH`d`x~;s1o5}~Z>@9J>v^?Jgw#V7+gG5l z2mmh_5;}{XTo=W{Wtm zplNy)*3dV1s{H{=YlT?)i^skjmT~OB0!7HC-}h3%T1o#vWU#Apc2je6bHJlphc)kQ zWmOUyf3lMJ7)_ko=DwC&QpUJCA@s18w?Cm8TX0EQg$X&{!p=TyC@{;a-VcYgpni>F zScQ{jST+75+HyefD+I(K*SA@o=b#QcAk<+3Nec2)@(F_GuYcTmZFmVK0SDPcM{Ua6 zrLZQ}y+!nmJFotmM&n(>!hwXV3D;lIC7^Ds5F1{R;}BsajYPiGC_g}yA2i&-6H7i zC(2njt*<9*g?cly4Mgaup~#c%u6E_$z;6j>wBv$Kmrl2P)obk5WAD#+;kn_2BJ>N} z@k5A#=P^v5Qu_@$=D|m`uHrDRYnh1SL3V2lZbe$gwbs$S7teOMfVy{A5rA+I{i=j* zkrpBTJ}Qf9JLAdxf%a=Z^pNjtJdNJD^L7}Z9Rvm6rJk-ngd@y_rKvk+;+3Q|?u)P2 z>6Avd4~9eL><6>ja@{oPu`J|g=C4ZL@41eY$FU$O)=F{J^+3Fr%vtw6O+ONTj0;_# zA#LrXmzc$eBGE3l9GiL6g)>TsmG8JYqKhuBxciwaYL+R6(*IPHiST^NOA&&6KBp!L2;+Je zlgabBxi4kurRmBf(xwexeb*IkGj1ilCyeNVt}QH$IC2X{cUyak!(>!mvCBOhVF9x= zXk?@^iO|+l)m=Dtg7BDUzI}UXW>u5ro_707IknOkndlUgM+akfl$k6Kd$6P{>mbe5 zTYKoyf)DGY9*RT9k4xkxY-kLB_&Ta$h6Iyri?gn4^?)B!dzG5 z3}YZh};?+HmdnT}oc-T^M0#_=)ZwKVx`}9X8@o3!pL#I{pKb+XLUwal`44 zf+(9BnF+C|H#0iIAeXpGaf}xu-4m-N9pTdsk)hFN*gCuclb@aWW*9vtM}LBhvjCX@ zn*@uVu5lVFEQ>*oiEeeKgBraXlX|6@)5QAhK>Xa#t-od5-E1#j-YTk|v+Ri_w#`-t z>3W1KU!mfa^GMPhyf(e>x5Q$DgD*;J@~87o&D zN;e0n3BH9EycTYGcl)Pdxeeyk2bbo6vk*|5k#6ZwOFU^%XWTlavR&E=1;p4H#_Q^` z;I7pWeytBNs4FCXkmo=G7pI;%AP;U{?ad1}92z@xaC2YV$k-~9w*T4PaZbbD*Ve+u zx!8F2y-br-Izqyaq)?UC9I+>YEKW|AeXFLfjb2coc0R;fcYof-DVtHnmJ7ER|0*Kq zz(KUv(jdzK(#4=Sb2#=E?-c>9}@MsFg>5HZ)%L_d_hR;7RpEC2B23Xc133v@CBIgG`QA zFa=$3*|`>e$MO!jOGgGzg^3J^wu9fzx4up`>6^W5-I(hS_y^Yzau2^$oDCwhxbx_( z#iy{6@PwiEKF|8QQ_wZTzX<521Gf$ROdU7z(I0zSn?y&o^I7Enr)EaKHTbIsQnEAQ z3`!Om3l6UKb783i%>cjpDwt81LqcMrJJZRUfuZ5A`4svwwL>ZP*a##gHn*>cME%~r zzOVnqrU3tq_a=BWNifs5^_`thfa^RCJ!sx1OPc8wV%U#Y&x6(iyL)y()vofkt7F&G&c4SNFr0fZi1irKz6Ne#J~Lx+mRrsev}&Yel<*C%5&_t6f(xdeug$HzZ^JAF86 z7GeDgQToDJ`~_^S>68dUx465sAq#2ECan@bcQH)1khR?pvxMAm(Jn4A5)B9t_58^R z{gr^;ZwHr6(b9Z}hvKPw?ST03M?iBqW4W(zN`&}QT2-2%(LdtYG-^B^8BL1Ip@>qA zDGO~s`QQHM-c(?E&JZB_V~0GUB($)_!3~-wZGSDWuk&>N(qWl%7!x$IEg&(G5dr8O z<{Le^EH@p{Wi#gDF?KuQw-EiX+olD2XU|ARt&{19UgSFPjTO>ZzMAd1-lTevw5C^O z=@CJQfYp}HJZ_#xso+WrLm>4yH>XsVIrI2Wpeck!B_2FFPmy6adVl{6(QorO03z&` z!UqAKLU*Gr&*_R(Ev3gu?ACOp`xCgnR^KaYn_ym~`0L$-0=dt2{6dl0Fe0Q<%Fcux zPHD2okJWCG95ygVKmHOduCt1+h%pSYiOJOk^Ic3g8Px^n_MYUC4rFUK*a%wciL5z|T zz+)BqeU`q5V^wYIjlw4~2806(bVDz0OJc{MNvkZ11F=s#~`N*|QF{PU;h z-{S@$c;62(_)|$#P^xM8?Ese5#zh!pO z1kfxxSfQn#Uu+>wG_m)0N2Dtv#0gMPQH_0$(tdCIUOYeZ;IH~Wt2iwfFfcP`I42)f zJ2A$GEli+wSucS!NpI$)Kwc!R288}ff?FhKa3#M*=Dfyf`@b(OT~GZ*-&cuL+<$*{ zSj?Bpj=CUA8nHcocu_5z^SV-uKU|(!P3PWYE8!D$gFS#z!TcHtdpO@~ zk$Vwu$qK7D<$Yk#5-*y|R5Z2S>i=^0AJ)drq+{?mR_FI|bB>(vN8QWrzf!5te5^^5 z5qHY>b<)N!1uF8ZZOQWc$kjh80xwBWtIQtrVkLv}d|{54rzj)bbK@CVaG#%Rr_PIa z3fTwQ>o41hnESUXF;Bi?@rR7k!!yV9DnkngzUwDbJK|gaN+DtM{TCo z?WF!s3-G*}+7RSFm3*qRNq;VE%;9{SHl}wml_h#02IvJ*^Ay#PWK#vU!|>@c<oyRi$n zbiLITP@D2 z83cVn9l0wEd9gah)Fx`B3ltE%sR)rHL$pjhAN-nl;dl_=uxNEd!mDf49uAwHHL*=0 zx^zL`y4{r7Y}Yp@I$0jMR6n{=>rV?>de4^TF~WlTWc7qNok@by44!b%&T8GhsaAPXM3-Sx6haorZHtPIDR2cE5F*= z*^y2PO+)%BQ7?=7zSbyRUh2P2gDq%PVOBziRwu<(EaJc`-DEm1I(z7Smu+6H@T+Ef zR0qN@s|SXpYH-;QKYX@?2<;(Q@QKlm93}mAQ>|$GEj#y9QaK`B*G4b2 zC?mZ@;Stv%(&wrKXh*zG%-eA)3S0_(L2IT=KRypT9bKPWbs3lJ-l?&+7N8vd^(zAJ zekSPS-tXzU>v7$FtzJlqH`6cKrReju{6BBFogN9l)Cp2G!sLR!yH@&;VNF5=<#zv? zWnGa;vjmS6($h>YQMaVhN!_LHnp75aE+oBGbz*3x$^fH}tCzcue_un8IN{Rrr`U*& zKi{%BQ9CqC;1mZJ{}?Zg(af!wv4jh7qGoJpXo8JRL}+Ftwj?VRnepo9O zLD((2Ra8@3@|Wb#>0Q#N+XEzN{2Y9hmHtSlZ>h}^kfS4?)Qb#(L-{KMf%=39JI}tK_pv4* zMJ4jenOf-&ioFi_mM5C>rs%4pQ>E;VHhJEATvu7k`l)eF4{an&mPGP~K5inz^5U#O zp#I31`V*s2svd{1POwe8bouCSkz<_?7{;;-eRSU7ivyQdh}(wwx02)EhWi+B$pAbI z+tpVmq!%O!ROS2`^LE{)j3m)RTp$cd*8j6v{{moi1DUkIb?@OqIAE~be)PG{vA{-; zqVC72u7BW{c0#HBlaD*98ch#X9NU}$Ow>>E#IAJaoA|HJPQsSx38mMhV3ome)9S;z z-k`$o#bO|6X5Pr_W?Cz|jYG2W+h%}H^l+wLt$6ird0s$dbgFa(a})?q040AWP8h~| zGTG-}f9c@Up>r0cA5N}AtDD&u9=WS4<0#rf$W+2-F0zffrvqN5>d-OJj8^KO#~VOp z&E7A!=-?}=+xI+BLU_nCJ#acu7CG*XncXL?IfKJ}39W+Y8SLomSnaBVXR3-P60Gury!ZY~d$tfkMb3n924m@)Do-<3q4Bw{U zm)kTgh}s-V;PMx$@-&q>8@zeo@ij~&!?&p@Ov7P7JKO_kQzE0YoxYiy9{|6J);v8U z1LUT1me5rTvbl^FE0I?DW!`Ov!-x_SuPa@i(IobyYLl{KMv?i(wW9OVDU-5K@%mjv zT-&&+cxIdzRq6~?Kjpk_i^`enSrmTsWoJW>-r10*o<-TctF*jVdQ&8dHL!9owkvr1^y6oF8t=K zhBVAeol$u?8>4=ZDqSMu4jI4;kF?9nXdgGwkoJ9w6x7M!$y;y2*|qHTiV_ofrMo2- zadf-OyB5V9itb0YBZ2Oda!2CuXDSU!r}CLB(u7Iw+`D=detvUrkT>#+JGhdN!b(lr zs0&!CZ=K4Tew*@+Sp9f)y}@dLrn`NA4{k*3rmKKua_q(jJCVcc^d)otMh0mFQ-Bkj zIqyOSG_F0WZ^TO+71H|US{3qzMDeH$&3`U*-~z(CfmtEbC?e+BeSdA7+$v~{nsCT6 zKZ8LYhCH*wy0NdL5&mnRP9R^VAIS8lFQ|q`Zm*N)S1O4Sh9l`E)bD;#cv&2M*n<)d z$)QH;d(rVhiIv%4$d62p=h-ZR`ZL37g?a~eg9nHHMSvaqHG({A!^xx0&!oczW&;^q zq(I=fx!X#@U2H*$k1yLt1S)PDzOl7Gr#FD=E$u>h+-&zd3l$w}i7zPTN2B7rOaj+S zv|s$6v;dvj?@VEjX7{?Vb{d5j}&_)2uq7=^R4m^e(vrMvV1oyh;%na`{W8~C8 zI906Uyz>AqABk)e#+uglx%(rj#J$3}%B`El9@HAFhDD_1MKKv!>FD4uh5qL*k^Vn~ z2{5V;1WpzoKt0#-r<(xJP-#!Oqi?&_74nF5iNz%?jJyfQl9msi^$FjF&=}(MS?^)RLatcdjX}P#m<- zz(`wYolgEe!y}ZR$*|qy^Wz`T35m>9ri`*Y>71p7#o-{;g&J5FCKZFNmZJuB=@dom zL|uGEEJ;7j#8GX6DR&;t&$wU?@7a& z8tF{t`eA~DFUxFbc!LU77X;echW;~Y27Pur@&PNXr^iR!vW}LlNZ{m}HXhI)~>QdTF&s@YMJ$XQ~k(gO_UhglJoYr4_Mc;G}RDw4sWeURJZQs8=O zS*Q$>!k0)Wj**sT$ERtBhI6l?_t8_o@ANxFZ@7+{8=KHrU5WX5muoko2=zVpH(){@ zxvI0(8Gc888F$*f_L)F4H#Obs=kC5mb|5!p|MA0V8(;3jU*h_AQNe!HTipio3U&Gw z+2kr+y7N+~7s<)IpS!8ez%|&(&^$YV5jJ#VDziD(sU_<$?u+@eT)(7SizHrXsPbDD z^R)003PVxS3)#i82abC1oaQ*CDqhfH8kyYpHj-(oI+>NRJRbiz9k_A1=hn1sOo&`PEGxL{TdST({#dnMi?K>f8kd9YLB~ozTG%DA(*q) zSqx=qgWUjZgfM;JWFqutcB!7ZjWQfHN8nD^I(P*qvHjkd_7{DWw!hyCWJ-QjjB7#h zDd`UM6v^FW0^WgRZhQn+Gj8}jwK6dK%mQ|Ls@2|xFt0t!Gk;0O!)d~*c1&9fAqy8q&Fa|x`c0;s&!zt7vpWKLCF$G)E%Tug4zDp zBdnIcDN-Cc#C{NG(7P7eqkg8gP?<*;z+N2QWGG2ck{>00?-X4evk1+2;h_Sja$dN);q9OTG?Uik*sAFzfsdg#JSu*w0I*<=PEJgWjQ=sC$Epw` zb42ku)A9)AZV`Is%dzBtd#n*3rY>o?qAO&ByH)KHonYxf821wu{4GIOEF;lK1+~d6 zQ~Mt3?$rHM%vbT<&&eB%*)6Um1q+qTksjDtyzFd~mGGoRgT&i?>|Htuw0)K1;M0l{B24^!Gi;nt%_Ap)DtP>yHX&GR6-YZ7IA}jd0kY?`Ez4*O)8&rsuWVK z9hv-6xzL)RtpxA=Fyh68pTRZ2K<5Uydmtcwfs; z)01DWb|)r!iG4)>5Ld#okQP`jiQ`Aq7g$EZOk{861VE4zyX!9JlUQQ={!m3*29VK6 zr=2mYn!G=9T_l`8p!+StdG8HAQwg- z@1QbiKmWIg6r~}}lvWR>+O|S(HII-a9XnZ-I+3L}=?MyM(!o_|9r-z1I=E+evuiy7 zCB-6|tHg{OHBhDVasbKJZuX=LQ(@Df{B8ugoBJ1m#?}E84^ar2&AWoyeQ!E#fppL& zX_%|%zJYS@@BKTg3>qkw0zx)DmlzXS9euUpqM52w)&<)Q?hbYG&*nIa|?6Pn97sF$RO1IT%fNc|0E6OBRbXq~)2*W5Bh zeKwO09v4R;h7JdoAc`+K{%JPP_OT6B(CXU{!^s2-jz+C6rU0{nf9GYIz`3)rx%mOe z2?FxgdY*u>clXsm@a~ zv4|LiNW@+EFXmx7kAKMsIzZpRfTI8T;Q{l<3LqLL#+yi9)pO@*FCFU$vJw0*dctUlfesT-$e&u&$I z0vHRCbfE{aNLf(FJJkbUG0t|JSRohB{{o}DuCo6smRV&ZjZNjFCf>y>*h}ZE(h>Pn ztm#&h4t;V$KyFWX9$MI#AqoG9U?)1)8UULm zhT%-?Cm~M%uI+BSWM%aVlXdSL*Cv3H_ifroWK~P|b&aDv_i`d5579^mI8DD+sic;S zDB<7_OVh2;`T9e9Z?9gHN5;_f@?IynmEXD(95CFx3kIpb+(NsgYLjqp5%6t>-(l1p zW+d@@d3ga-GmY_g9N_{=rwFG|2%3pFwHZ{Z*jaVUZ|Yun6{$;`W}S`R3QciYN9{O6 zG0^kgBCMbg8jy?XZTH}7xW{*Kb*d;X?%VGww}qGTDEbT;;wLR8HfG$nV{3zyI1hnM zcQP2&C+BEkjQBE<1y~wpmfW@h0!6<#eduDBgLR8RI3^LLeuGpdY=Zu-zV6|cu5ci_ z-{2isg4>+yhZ73-h+3VO{w%!^J2!*@J`=lP06BNMKUhs}g^ z=GqQqym?rwwGwPrp-kBsz;^IT(h(#EG7}WBj@--q>}YR)1tvbu?(X+@M-zY-2()$y z=(qv)$J|A5>m3&N67~Iq-{Q_pmbd%=+&m;K4t1{g z-;-#tw>W$&fTt3>&|EGqOYtNb>Z!Uel)(!`kn_$_hVWO%#5(bD&1AC&Vn*m{D4Sbb zZCcsu(~)6+RkEIbW!DP1(tVDm#F8-5z4CzpfTciJWTt^HP9v;KUY)uOhPM2nbNxmH#|ngZxaXzT@--P?3!N&lI5nl1GSu{? zuBHZviQrr9JL?q)qaW`W)iHEBB_3O~7)GBz z61vw(MU01T!k#3#xApqu57{YbV#yF?a5fyvHX6q)4 zC*vc}F%zaptWh*LdZaV*wr<3Qnrfa+)AoWOHHiqx`ryDE-4wxDWfDG;QOyQqcp|29 z^!ol6cacBjI``cb-rGTD@(Iae-Ccg#IiIj3IECz@R^rc5+U|XKFKMnp6HXY(1|@~_ z`HhJfC2p&an0_KErsb*7?jsM{D8rK~Z=yu6$fJGLE>S^(G-cLTBk%`>RJoiN_ygt&A8ef?Ojp`m zu~`%M7Ek`W*6R?&0h%Sr%zuaoLCu!VC|1LF3`(ubZR<=PYJ#a3pFoohn0&u^dF{{M z?w^1@D<5$o7WemyQ$RjUxQo^gMAlPr7m5NXcl{wF7Z#NpAIwyWixED73)W4jPH`r>|W>nFGz%8F;M|L{xbj;W0lU_6b9iea5&8)uc+mzsnW&g zwiO9FLb?K_zI>LRicpj#Z+#Dw<&c0%Zm~1UL0X+ISU72kpLc?v1rlB#TqDWe)lOi) zPA0zC5AydC7?Pc7GJO|S79aMRAECpcJ}Dn=+dl)m9LfPE>h|ROvQ8mIy{PZK=vm~< zKY9&(NW;R}q3DbFr%2FvBV&<6SX1c-GSYIN0Si(W;6th$3?(NaBy@0g{(LAG{#PFK zTK+j#9{`-$=H}*r$C4ZUl^_kPRb=zuJ_V1^WtuZPcWxi2MIDmSA|4ix9pl%FwkzX! zRKwESYh1*6ucoMmbCbT_k(wKCC^;6NyuV7KM`;6u9;xqfU^a?1eUVZT^8b7+sPJ8B zcuYK&L8u;;+WvRhf_rVyEPUy#Ds?ozf+{t4s~ge6KiW*N>aCc<`g}*=d{^SB|1Fd& zfAQ2dV1F`uZ1;Th(1L#0@NhvgbW1qwfdPw8jdO~&8EqOZ+*R=0BQza1&naM8XI<&5 z5Z!AL`NWi=?Ayb+vsuMOcOfjI4=Yfqf`^%sxH&zgaY7naynDOsDk0u<;Ex*G$Q(++ zear%T0J@SrpiloVd=99qhd!9GWPr32E-n{+Zp96Df*UwUk)NWie|z~Ux6mLz=H^2A zZ3=luq`lm}=>zM+4+l$C4PBa{5xk=K@rip^gZ@Xh`K(;U7E5cI=VAV|0y!A0R+8^qPozQDNO*PkU(JCeB zIi{2;TINQ45~EIOT*oV{ykp%amwV>><5_kTju8EVF3%q(h0fz$fLRkasAc) z4_x?+?ed}A*;#XNSSnG-*3hBpCTS--ab#hL4tbBdH5L2|k2cUF8C8Sfb7dGSkULx@ zs_yEKxaFndk&9YcVIN_}Zk)G&||OmTw|2cY1NQOi!m<>YI(K zFlz384$Md(weE6}a532zd$qK0+)pOaozwD7EVpFlBuuGC*Rx-H*E=uU5NRz(13)n> zpgdsY4eYS4{`?_G^t-)ZlZOrno~xSEBgmXKRI0|Kp{t1L_@=A^$}eKMQ3Io?^i9Ev zpK7qZ0?wn|-QeSv%W9qUN6Kc`Ff!0{c7{^ca;)Bn7Oli5=Ee|ZccL=k&ZJ~^E^-TV zHK}mh@w?vPk8g=}>H9**_~zZ=K1@=@7s=cQl{F-EJ|j~UDtZz=-UxBHB>O1cCamtX zI(Wsae@!^h4%PfRN{AWxPv+8kyRdV}bky+uJ{-z&W?nnBN1Yt1Dwky1B=Zl(O0k|e z$$$AQc<>?LSi6Oki{@A27tvn;(4SV}vGS>HlyQaYc-tS3OtLE@Rdq?CPceZyNC=s| zGumE`j&AMZA%+$i@*J1KZ-SDTfr(q2-m&ZeeN2uyK|FF_T=7ja%`Y7`ygtDI;Gyx@!WgAKzDB`4Zg z1d_QN=xKk2)lcL{MTRIGaho((b*<%tarY+E#`KuqTt8Z*BC^+7mWM?8o0L_CNHhY@ z61BaP49^v-*|#c7{ePYW>-fOd!-c8+##Ye67-hvM>o-0R&Cta#^;bf|o1C*=V&GPeRwO)SbL9*vum_PfXvVVn1Jtjq@DX0kEtkbI z8o6uFrQRgrT6w0<$GpJw2JkzRjo~u~3S|_i<{Co|Ai>~RDBTX_tyfDoVFlE&o#VCQ@$*-MgFcD4XG3$B!Xx zySuR^SC2A*bB^JnwSv*^2724?qJK#0P`nt;GTIx&g%LYW+VE;a{oSAU6IW6uUQARY z{RZ0w!)X6PBHDPni^9`A_}AM_^A0^!>qDi6#<~0`%O=gHh&Tbiw935>F%Ps=xV6r! zITg+cLCARX&3v~MWnJTOUcd(IUkPMh*_X66v-%^z#}F&So&@#8CvLc`pRb;^Cb<9^ z+*{F&@-Ml+_h(-jmz^%Q81We97!DQmUt+Tt4_yF>M(XR0B;5i@a_5DlfQ61blXsWTF}D=9O4LS8gBab^{4c+f#2hx|#$9{_9W8tscxB6L zXU89FuVN%Hd`JP`&ACx=BA7h0=YpgIAuC&xK=>%?)tsxQpoGm3&rX{=g=@npYoiUU2+!VUM1 z$$y-0KiOCK6(xR&baBEvWle3(NIq~9v2gGDFpH8o(BYktl2{emU6e+&7H@y0(=(B7 zC?>n{K7;#noJ{ubg!srcc=|{fS}zpSP3FawU{x^}O|CU+ zi_6WNwUL2AXW+kAfK>@-Q`O!z7p4&{-*9hfwXIs3h}-lei$5|IPTM31zI~Xhndfy& z_BOI|QDZNcx*Jkouw!yg+u1F^j%)A4QQ%|*X7sNh{$*}&O75uAqp8osJU|Hnjn~J? zbw*OZcb_=F$TP@KT=s%9dCK0ewsu5%YWBM+V>p~?-Y4B1{nh!|sqrmP`>ZFTwDhI(tt#uTGIRl6$6Jug-C_<>5txKoXVBqt9wAv!c44 z3m$5OtGAgSW;c39^a&hcdGQXJfDwS*D&{4HA71xAl8Y;2rCF%+?+XhH8>C`lVgiUn z23@|K3DX8aCYGSFyYT5>#OD6->EG8Y{Mm8j5=TJe#k^@ERT-(H)7=I zYfl@Uf1|zP>PV@aYSYzxc-vCnnh$YV5wQN5bvOstE=}*|;gMR6uMko#T@DrcU4cP? z$zgY#Dl8#Y_H9$bj{b7Ijgb1zmDGYcqS!RS!9LNHaRC>4w2T=v9j(c_uBFuwRvm<2 z6iON};)5YrF2KhJh+rpbCy9UkziR3L3yR`1*O9Rh>`l4w#y?Qt@(z)gekbVjA3)6r znA`zU%L7jGzV*``<^LC0?BoR4>zjym1b!N0f%n91j3cB#<`pW$c#Bxv%ieoHRqyjj zr#doLoz%oFARXOYTHNG2K`C2C7d%h{9}+-x2L3j$Bc}0Wck*-(?4pb1W#hGVo5}mi z{gWAAT`Zxwz~kpy#mShDQZF|(XJA(Cr0mi0lTL{bbKB;aC{bt{edfmPnuS%3^!xNh_UgiS{O_m!3q5=(5q<>#$)|ur zQ+hDRM_30e7XI5O)(8Hr2F`@4M!*`$go_Oc&R6BJ3Y319nq`Fi$1c6y|Qr7kTA~kOPi9hSbBm9$5&NG zc^EyZAxk&?Jc=yNT})l3O+)VU^0?vfc6GpV1%aley*(Rc7K$4}^Phx!dPms_Oxa9n z2D_JR5=9RXplPGzZ_tY?i zv{aw_m0ZxwHjsC%RVz3l?MqtMjKO2i&|L5kG0d6gm{D@L(6Gm2y5$y}dd)#Yo;wQ_ zLv2YVA~VYB1r@{s*I9X_Qctg!^(_W*^oKXg+PG7T6mgzas$!0P zU=XPMQvRN}#e~y&0`Uh*ioW7cs}kZn~bIH7`>?eaBwJ|(@}tFacgCzcZbi6gd) zbD%;m2zXrM>A(5UjFxOD4CExOueSq<0WdJgV66MrsIX5ASs*3MCJ2$T*tNfndsHPR zBFu6TFD`@~O%S4=v=D;kLvt$fbI-Pc%t-~6E@|hR?Vj`)BTh74^NUjk zV!^u`tKvTOg={$mwIzSclbLgKy}J0y`lfKfP-@1LylBV?9cRf27pNuI@ff%^CDpSD zRI>7cAhdsgU5Y}fvQAD_UFT`~!W6tmiNkuXI3Uk9LSR2vX4hD};VPA_oozW{*4r?V zOI%kt*~>eK;EsUKqV8Fr#G3N(jw@VEl0+v(AShobsyzVw zT)1-PXog4Ij^_|!@M-^1!s3{;*R|wUSoEPk+@kB{7=yeB>dpD%ahwvf%&c zPd`_=){E~OMB;6|9(tn4gCqEF#7q$vx-_hmB@)ax2WC{R^|u_vm(Yqv2Z5W8w$~_tHE}MwVRxcXHbvvUlaO}=Ef^HI;+Pgj%k8v$7=p!8lYwiRpV;Hft1I= zol1C8LxUi?-`d%kJ9CoRCvJw&Ca6pL0E<)n;%YUHRGFgat1)uV9~VqkhG}{6_wV1U zE62^g&XJK92zya0M-ziC1Ew!Jn@8mEAh#6Gb@{kL4hECNbeQyeUiyP&q`j|& zlP+@F{`*Grj5&I>0e^jOwIepGZSYRU2@POVRAD$|o&BgupcCI=ASVL9r96EgcFrHf zZS z6*Og`aht@2=tfAEyZSta11&z-%Ba5E&L06Le*lJ7@P0@Q;0<28cHX)yUK}QY6@K_J zKnBfN=b5sTSP(1G(btbPYnSe2U>t8@%T`7iXdt`Cx3;!!6c33SHCHxiYi|#gmoe^3 zhrpb#_(-u&bNKqoroltyySveQ>Vbhl!Jp@<+11w}Lo-|$cKx$_b<((E4K3^kwgEYW zhOZV=qa?Q1Sx$z{!Z6#2$FH&0Mrh<%OJlS9RQ6mVqZ{JHQ5fmS$ho(>^?Q}XYGWfO z%%66?6;iP84%L{{dQD&Ax4z~$QNrcbzC_*t;$50-y80Q1Q3YQ z1W~R}7&lK0x6(;)=>Ieq!xlnOjJq*xq3hAx7*BXk9vP7Wm)F)h`pfSY*Y&EcL=Zo2Y?N`-E@m8U z+}BzY&>?O8(AcDibrLQ9s&r98^*l~E*dAOqeY!Zppvw=Rp#00fZ(RLnyH~g3eU5+6 zG=W@fsoWEWOQp4$+hqkv3sd@(OM?EHT;uZWon>s2H~Dk^?rvfF0`B5`g1N{4@lx0B zInia_Sv0vzV!Rr}N=KjZBY~Zuo+-M%b3Zv&&kH#{m*%znmf@qf(+K%=4LeVvOU2Jk z_p~4mJHbF>`VWOQ6%s*+r!c}*)%z|$76Ukl3uwYE|qkD4p z01EwW?IwVGD` zGiJYqnq0a%qW{N64a0IV=ut96$;>$QPTmbXSeENh2p4;;DEF^TlZj=T!;;}z+&`<{6n}Ca1gw|ZxR`^UrzeWu#b7DIWejpouAXu z5x?|xqB|gyu~ATkf50f%CPvI3m!nQCOHD3L)GJuovlPqipgYq3{qhyE>O^QL_k4x9 zDo@{$;F}1qxI1=3Rc)i>m4&RI`r{_f1L-Ht?~D^9if~g7@S^a&d*xBcc=ubU(`8Hu zK_zp$NXFsE&KuM*TpsSlD`m*sO&T5)w>v=B|mGy$Omw!HJ5b5GYTKWl7lguRQb=*LKC zs8M9=@0xa7x+mr)p!!BqlE^&S1w75VwG%UT*FY8U&NenSX0sXRBE7qmcKL8Bb4R=ssLSON9ATQKzyJHcfBg9I z?(Xg%{m~!&{O3QP&*w=QfeU$(sU%IB^BHU<$C8OjKqIu~2E*3L--msT01ziMx}nw} zbAOv|6^u>`i}DI=;Tkc1uUKoS`&Z=o^RH&`nZ!yfj5e%~3D>=(bhdaac!;FOta5j@ zOLHNGVtz1eyQ`}!t1pkv9xg}AaoH0q9&7Qt=VpLk}21-_CiUcKb+D% zaS}!z4vz_g*h+ZsY;JB6XM!V>2Hd`V`}Fkm$&)8P``OPX3MDMz3dWZ7mR?xfKKuUK~wFSAc~Rd5d`}eDp-) zUq>0Z8n9Y9sE=3HP}U( zsKULMpAXBRB!QTED>!>Zi>nXhMMa5}Y!> zW@BR`*dpz;s+DS1i5_8PDdo9bTH8iX#_29@5FFO~u2gPpui@sIr?pa=!N?|b8+R)K zYv&b(CR@$TT>Bc$9?57c)#Zumv?^(QRx)F8p|WmpFPY4f1j+Ni1V9)2V4B%VF7_R- zoNn0|q*lBAI$VHIU*EWK@F0mLy9%2x^}%9nIi(vX%uVBZAI4!! zZRODKINVo(U=&*&DbS@zRf2hiCW16MGJ3RlTIJJhz|N;sooW>wZ0@i!As9^%Jagd( zg5+eW-<1c4t*=FvyzNG%BvMO($lF{SS-qDF#%1i zEo9R^^flGxetwd8st&r)zMc}GK^Nfg@bJl#CxNcM{lxnC^_zcHv084J=s_4=1rZ=X zLn|1e2hTW^F9Z%##+OZOE|qArMA^s$2b8w##!!SoOR!tO&L(0t1?>KW^+#wh0vXhJ ze03C}L!4UF$OW?)$&fszO&Y;9lSpOuBp3XT|M-v3pFcl5Jbd=-*^?(v_!U;MwO}6` z9F@uvGj?7c==tpIjAE4;1fpvibkj7&LXi z#SOGyPvuM;WOTow&6@3BRt#Rr+uPgw`}_O*`+213F6B+Z?1NC_o}UZIl7sPfHe1S^ z0)uX_pGFIXnpjWl3cAYnp*jlEfr?YElUaZ?oUN{42tG9lo^ICDA>W0N=#^~soEREr z?`MnUs-8Z5`s~@W<#LJ852tU&>sA4k#)sE${Y?cK%ix5U ztkwM4EDWa^Hs-S?CbM947Mb2!TU*=Q+?>s39^_!T^CLnGds?!?IFMvaLEZ3 zyS#i_tD$SM#%PpWOqOcVIh5HuwOmk{gZ4Uci^8z-*47p$6d6K#S_wq3N11!7X}eLR%84-ieHwT)Z-uX?B%)w&(c_X+HYrx2Gm_Zg_yc0`PD@GZakwWEx z{oFnl6DEJvpmBA(t2f{$HX0%qx5l=cC0^t>?0CZNqlCv#yo{JV%uCyqg99->SaQ|U zE9N`qj3^rx>}c66S2Vm++iPTqyT;&L6HU{!_LqP8mqcNZSHysekwkiAUQChn+{|}z zRkoUCLSbo1gWn!htn<%==TV5NMnfykqNL!(Iy!WY$GK@!wiPJBFOzJ`y3X>+H7H)c zmnUYS#F0Z$rrl0t^Mh%CuzXpgmJ&--l!UJUGW+b-wOQlSnV&UQiEG9I3(Da^`L~a% z`R?|NM&ktnj^bZ-inQ2mvWnzM$R|TG_tGsF4}?^yjdPu8P=xuP9Nqq`PUb9=d3t(! zaB%SS>C=z6(ubZCBp0XaVwa+thBgK1TJ*f$^YIx8IA!ZSA|54Kh(h$StMkT$F9&w% zj4*%awOz12MiaIMABFko@SAdLImt={eXe-I%Sw};Mog(0gd%xiGR_PECGR9nPrP#0 zVrnq$9mfI20X%DFmn)9*N;2{a;_VfwW*A|4K^a>}S%^Z)?c29$7+NvP4%xYpES}I$ zsL9c9iu<~wXI~aD z#!@cQ?4uM|Cl9>%7vUI&aJ06z#&{Y-m$X|m!1DI(+vI|Q%gHOUN@1u0D|nC}H#c@P zL$U^&Z1R=2gLYDYl{}fG@4Qe#CGRU&SON}Il};DW&(A}@N~O26vlG-Z&p*G~_lx{f zUUaMm**;l#uuaJ#?A1W%o32}J+KHHnGm8o_2%M}5qs;OiPt8 z1JZ93SV-F#z4_#mPlD>2pXH2V6iq9i5XW|i04`9Cs(TjI!XUnW>U^?F<5MmuvQ5V9 z(IUJwf%5R#tsU2N`hK=o3*Nqix zu&>(Tb*bP)AU>c69y~Xz0|2DN@=XUDZB?`T$P>l^a0^)&_4W{0F579p!8il`(7}HB z>VNpdAC5x(rgi!3;ny=NMNZG>j^W9Do@uZhod)yxae~aux3Py%UE-2u^$Q*;(8fC} z#G6VwV&SFbRG!u=M{TW)&Tn@+-8Wu8SmW{4s2_`P2-TJyK`$`mPhVcv4I8frvGz0> zZ77*GFAg1TNG*a}e$^#8VQwvZ&~Affg_!$E zUBNbVVT`G>uaLioDM0DMhN?*f12l%fO7f4amtHheU=-v$2iFw^6MLA54O_zt9+{+g zu>P)x9M8_qqLD;@6%^hbBpy4?z5zZc-FfoKgQ@6B!^On3hnJ;z0?hlvIffZpnbn@HXwl$9+ zg)~|ZZlZwpmWWIdBpoquX*3yxHVJeCl<)an_JC)mESx)(am^EfGd0Nxh_jf4p4+iq zqs4#{OoBq@iBT$BTHZffV#$`kgBwyNylBC~-(kq~{QP{mTw1*-JP0~!6!x$=QlsM1 z0B?o#iOv%d&*P%x_xwoCf@DVo2f`o*Z8`BtpG+iSi5B&~Boy4lrgWjq1LAiNl9h~n zG7BloCQKY_h7$0BCS9<()tYdc)i|c&{(eV;(&FI4Mg@0*K+$q7dEtL5LNp;Ur$d0< zBD=AeYcSkn#fhbnTy$fJ%EbmF^-mq zWoeHkgk~7oW@ice7-Xe`b$WX0_<*BmrgSsa&Qw=4hH~$OQ)hZ*6zd(0u%MUIN?rEf z+8{!ex}Fys2kty2V3|1+i^yG1Pfr7IBySuoiHdVKs#|zeqGH7)SJUa88>Yd*5``>5 zj2huu2~CV+Kvf`H#HuX0slMF?DCcq0L8|>w#&ND*i=$WW4YnfnXb8g1R{zNNP@Ys- z$iCd255BUOk}Xg2@=AOJ~3K~z}>AoXQNC(TRi;*CR>mVt75_RTln-1z?YzhBG9 zdR+y|x>o=qZb`xsIr1c09Ro!kF5KsuSE3FQ+8wS)y$~%xUZ-F&Nc}6S)-5e6uc0y$ za&O;!AKNdQEKL<^c-8WL9;vmGg*})(M(6ozT5t&#=~ok`OD~MGik#c`<;Q{sGfUhl z8p#$dks9AC@zJ0q`EbMp%kHB}wR?OLh zxBy)JkpS&_>hV9k&3?d|RC?4%d%G_iyvMu80X zeu`Lu+HwBIqGrHDMwg0KOil?E5rS}@22YaX65Pb_1pPycc2geEocHr7A3&RD<(GOc zo?G+yt#vKEqtQ(>AjS6a225QP7`K{Fd?3D zC;IpH7PPV$=9_c^>=ynmPo~oWv53JU0#kUec%Ax zcuHotm=x7}W>5$<9|s=;WU#vGRRWoPyZ&@>#EMk-t3LdV8z3Ndxw7vX`O}aCyumf#bWwL^G_&jGi|fmEcGD_5#;D)<+#d=OFU-78se$ zX7}#h%bp7K2@;fLfOmFI3df34NGMp%a}R8XnnEq@KTlM+NU!cMNm_L~2p!Z2rm>e+ z4_QGe8zdc~F#vnRSPH5RJ|$`36|Z@krW;>;@rC74?G9czG^k3Q(B;tSlae~2f>g-3jUm2DncAN4y${ZR^u#7^<=(yKceT?!PFtv?i z-c!CFt0Z+m_=bwnUKkD>&L@ZqE=r4BZQ3>^F2xU;FK^zwSu7UMpFe;4^yy-;_y{(A z2)>m&!`=?1Xznt#B+p82(3rJhEN`WekIjepBpA62R&O!tjf#!yNp6iryS25&Vn&Ce zTC#<#RnK6hPIkGgaDH2@BfrjWiT>FlNsWS|HnIT53J1!%T6Mk@`DN5a8ZVN`Aa~%A zb(rK1o}O*e-|g*fMt(f}Z|QVm0?#K?38A9Uqoc;~d*LAvuX0Hy-s4qjJrQFQp`q@jiu*Y`n?E zhUcEp!1BpeJW5s<%b;dnNS5-rG8~6OFi!>vp1gvPN*G9CcFDMp8+GRH+3}jEnvyAJ znI%ig$ca-m$Q@b4^v-M2obH=9Z{quIP^ogN;3<^cxKO=$^9JkjRQ>>h`PIJuh@>!Z zO>P-JqqVMWv`4uPy>T4JwjTL-Sir4Ik{wvV)HT3s?w%)WMgx0~@4~OZb7Tbxj|?;L0;kMPmr;p^h(U-OwZq(IF1*jisrC!1neG~F zACWA}4_SZKBZm=ixPAL}T*C}d<{Mz**h&&I(OB7<urijtF#VSMeU#^&)gH#8%)uLmGQU z5UJ6$(IT(x?s<%`-164Hga3jpKXX>Sbg(Hu0+EV%LxN4VL;S z^(2>_hKtu-9?!*uEEK~N4dvR-i(~TyDjrK^AZI$CHGXSZw8Y%Q!^2H8%;g(+#bQ14Br4*7K#7Z=gGMja14G0mRvO31*>w1o@iwmb;qICBJx(^VE`;UnRH zWD8dR7M#nph>-_f$+TzdiW%+Hyfht1);)kv!bI|9XUXbMcphPrS2R>U&(8RycA7!S z6uSVsk-)xO+3n}5icSa&M4cJl3eJNyNQJnV>6}>uEIG~yQys&FDe-1hQ7p+nP7vf9 z>@AIa6$+&Af^4K(0_4WYv8YA`qDmai8E#+sg&^pKbP@T}f|ycrGx6uZ2< z4A}vNR$5jGbmb;g-bPIEyW%QITAJi}GAy>-!p_c4HZQ)DU@^|Y49AojpzWCPaPcfrk@H+Oe;BbUp7oAuhE%UNbI>$aK@B}!PG44$n4 zk=k)A`1kp#mDjdypb{lQf(TRT{QUgYt5-;R@yRJNBSOb1lMRS)zLj|$2I1>*#OG-n z>?n5XsB~T$(xa9uB6m=|$Sd3(&!V-inVnei{jm53tH|yvnf|jNS9SEw>m;VZ+$47* zfpNpku2xl*Buaa;SVoifQg)oD(Q%JK5kJ2d!OBq#7rJ61#`gAh{8d8=%Y)*iE>Ct| zx7VcWL}NX4m6$Yy)aJYUAM4I!t~Bb&$$9c;&qWnfWU`yvIlLxgMx((Rk!>_AGG6aU zf}sI{%N?E3?vr;1b!)7hOO3kxshu!eDm2q@*e;h0A7ECJMwGK^qSoyplk8sO#=05XB5nUi9?N%B0od3J*t@v=*AvNeDgGeWlx+Qlr`-yAJn5q zk6iq7$~uMh0aJZrPiao8jD)@0Yu=Fd|8pFDZ;^5x6O;(UahzS~2W^r-qj1)h%XU0_cJGD?tWY>D{qJ-Z5V-RFe& zf{~i>Aony==8P7LMR{nF#$~b$@uoz}Xv#P~TX*1nvD7D1d5@0jITj*u+usL&5+G_J zpF=R5`LrCd;r3JNm;a*?z~Z-7+0PY1RVz;=?kL$t(a2Mr#N=yzeI4^7f{A^FI9vjg zxpedhyu~$`6NJb>Pum__Wpg>nGo%1eCX|Z+@AJ1Z3?G*@OG1^K-_8t9QAn&|T#XY7 z51Nptr>7K+=4Dhf$@C&0zUEw%R<4I}7)As3@)q;4TX_zx9UtGOO%dBE>?yg~_|;!6 zRnU&9uJER^snJs_?V&QwbY4!A3<;84TV@tK$dF$Ysu72>Qw0K} zJrFz^b8&GI_ydh?I&CQHfy>(%&Z;_&OUyF{nTjY?B3pi(Jsy&mjd4c!W2`o*a2%GC zY0!XVonO5B%3dH!RHxcXVNqj&&y^q9*w}#PnR`za?G|qt)YQnNGh~D2hoc04okH>>tHo*Qdobbf9@t;US7`U^GFo! z?CfB4P@QHoD@}KD^Vq~{Y9BXE@ls&0kvL%9JvEz~scuEQuii%A%1?OIhXo@*9J9;~ zN5?T}P+$S|Kni6xP10~}QEO`o5=}tPS>G&VOfMA=?fSG`*@^K%7Wnew;==l*)r0iL z4_0p1!dtg)Wx-&aXE9%Qnr-fBK}Mfh`PCs_5eoi?yNVZqqePeT0HMD*EP&d>Wkxt3 z!J}#q=AGupP<<#))iNZK4(z$-uZp3^Grh2Ce&%Zefn1?4v}N8>rrEHQw&I ztC}j!?_!?a)Obf@zldMy8~pj7|2aB*Zab`$hPAv@X^-)X4T}O3)=;InFuu>XZ{O0~ zo30zxt(+LAzf{V>HO0otFl&ssQ+Dq~Eb@d}jb}TF;Ss@&8jAtglD6q}2hVA7ephkl zY7sloaBD?AH-5Bo=%cy;J}OEw-=KS$KUPDS=TI_I({&@TG9TeFatzbU8V9xsUY2$% zwS{T$(5<}6bhZ>-oH1zL)3-0_E>tSv8@qvEqD{iY@$vEN*RMT*@bT+67oH4)Q&L3K znbFWOuH@*EpQSD`ernca4HwrSbIvfxz~Bhps_Af2>LWhop2ny^$5LnV%k3uOekNomhoea!l1&I6L@J*)<6g8nQua(}u z`5anJk)EHoT2y52(NK$TZcs|O0TN!(&SC8B&0*)LO_LR)5 zhcN{LvX3)v4dn$6lt42%aB~?>RV`v#eH{qYWKsC~;Sva(7p5M1WO-%IM%)XmDIPjf z>+9Tg7;L0gh4dg z5mpaAa(Q_fQk9iA{RHfgka@RU)va5%*s!^mi;D|H03k<|AV^8JIWpAxG(v}(zV+bi zM=a$|U0sd`7J$zKPbkPFa#Wu|a#K84_EjBz+sM`#VIRG+8ZgY{*o&DuPb@DwS3-7_ zx0bD)DwG{TFgGE66sf6Rhc?>^`;+IdJLx8oaJ14ac0Jp^^UViOz8Z z$~d5(o3m5zXi!e}9Xd-lZ{A${i@*4badN?>OZg_c(ON+nHVUi1AS!cZxoCeB7m61q zk*?4y4u%?k!%ThDBOjYcBtU=~E2U~mBx`gru!ypEh&9g`8L+;%P2wH(JV;oP-5!%g zxf*$76;nKLVb}RFdK&yH@q1eXybp=5VZ(CnG#Ko6n)pSvU*t)ryv0GNfxdbm?{k_! zi#_Wc@@Hj@yy66c&CSioA7uL41(u6WTWT~1W)2zw&oC7$v8I!}L$PAkQNgm{u@5T~%jL&$?A>qwS{ z42=OSlS6G+JWjAXg|&ybeIfFY`FjxC>OJI`#5s|gfypBbN@_mQ%Eaz};Bf=ufGal1 zO0pb!r*7?L=jI*NV2h2P%sw+?E7;1*moGz~i6l)ZmdNmfqC!OC(Q#g&6QAqE&1aH* zyJt75dxTWBomt$paHxmW#sctDb+f?%)>GK7)+_?W=$T(x-UZ6s4yx8}$aC;ko!;5Q zf$t>2wXF~6Fc2YlXj<`U@ntgtwpv=w=>#W{lG5Xe@)Q?Ah6w8@b+n`OaWKcIk<2(c$FS$<0#aRj0M?s5 zDROvT(=_ex@87(6GZs{|Cvz;iOULo;9bp6+CX_uK!H-H^$Ot%sRwZ>m20C*y=@sMh z?jGdy&h6W)(YYe;9hRcq7&3(DbkT$zhy#$#%jMlQe>peR$o5FXhxInjV#ItcI3r++ zm0P(H{TFW$A5cQ)r_Ns8o>UI~~XCxL`uPQ}~k8kG*rec+I zMX9j4XFMWng<-i7PIw3W&d=zPUA55BNe93nj9U#xsm(+rgplq&MLbyOWhuT0BU0Qb`Xpa5|!9d*MI zcMDI}?08rA^d}-~II3TH(@iooqm$y*NX1a19KM7PMg? zvc_f$_P)5dI6gjp^5n^j7cb&4^$~dbu0{oeA*P#+GB?_#t_^HromUK#$O_+{&M<&W zt?Q9AHy#U@FWo3YFwAN~zi+1o;!JGxmc+Wwv-jK)d(E?cV6x>Tizs;AyA{DG=|lF; z|DwPOAv_Q*Ti8RsMPf=r6&U*!Ey^B^IWspY-3~N>#x5)Iyy3?3pIoqIHe3mzy%6=5ZI6)s01j4 z#zP0SZ*WWyA4~qbkQh6qrj1yYnb}4ICDd|^XSyt@jt&Pp&e@^lAXr{9aKW1p(Wi3Y zybc+}zXec(;Xdp2ZftC@2An&3c!Xz*Jeg(hjW5&b$@9-IwImRV(InPBZ5_VU1FjF|Gb3QTS8v#s?Hs{%wvLjf01AFD5H@`f*bUz8xE!Y2YPl!do1(QjhE@b* zr|a&wR+TEm+14TkOxb|3YR%sO%yHMHR-V0JMU=={Fmu2+hwVY~mTWxbPjnj%R9WEF zgG3{8WDTt9L%Z+j+Mk_Ri~*~~*RXlDk*vx`b!Kw_e{=TNH{X17w%xDPLjQuQRvSHlEbAS$pS+U%LS)0SqV}j2s(4{!JM*zDL_0LDqBFcyaG>U?LQh0mvlqwgi1nTqod>%<7hW(kUMyMW- zLW&2-)Nb1nE~vqZ_eyy{IbCJ~boIk41cL@1Li(yuBo>U}1`|KQTj3F>8ezG*0pn4W za*nRX;Rv^}s@Xo-_^5pwZ7-5hQQiFqPB*%(QBJT0fzw(KixrQacmXPN(eAbu#+qmYAmv%$$_Xtnief`@ zHj5WmTrDYW_DFG*a@m+oTXAn=V`Da(k^it7$uy>Sri!H}1;$#l9SGhzk;n^5277#b z94=uAZCiRG7lz%F=WrcA&GoV5#mZRc#)%PayEM>eH3QmCphT6B;7V+rg|xP|cH{HU zKX;_7+43kmV1Bqj)?Da-m zI6FIg_3G8nfBy56lar4E?cbrwRm`v>?+v=-Hs)wM071j(DwT!x4$6qM)m9nue#s znK`vRyw7g*xtP@jRx4tf;a7GCVJh1#KWKJvmTs;VW|NCyXrv(TN%%+@%J!aDmZ=%` zKAqlan&MfO^l@uzD=H0nN7(|kXf0h72`Xzij#4{LS_n-gLlM3tWE_KQ1Qrygv%7QS zqza&u$eb}xK{{$awUNh~>x9QjCNrK0gvV6Bkoah}Ih?xQWAEf=-=`Ir#teNs0#x2q zN^8s<;b|IPapqk84>x*EqNF9jVZpgTv_Vxjm>PF#--(jfCFHUf2-L>B%x$OBV5dCm zQRbz1e!oyT7Yi^SOC}un+bbuxW?<24pcV`vi^b+q4>ylTB#VUEu#`7TCAXEFc)3zR zjI#83?5K|$H6}4I8I6GKNv>*j6F`8BIeJ*J_7mW(A<)6?V=!vfmr-D3lmQCm(`bkV zyja7KxzNep+uPgP+Pb*70LG$Gk;uPXE*YN9#ZdpFFzDCKT0$DaQ;=3lHTU^{UA~>j z085>iFv%SP|IKQG*4T}i(L@zDM149JGixQm)57G=aBzS!`yu1h zscirNAOJ~3K~z*Ex6NoJ!_zwxfSRARhpDIbKnZAJ8nMdXFBS{BAcR35<=M{BNx&b# zbKemQOVOPu=Us1q9?*HKl#&7&fpXv~tlawDE0xn}x@3FOS#+-J5w6k1&=l!kX$@zD zaLl3o8mgaD{1=NQ)p*@>-E+`pWr{VdHn)GxIm#hn zB+CQRC61m@8_GlZO8We^gD*snlBSxjd(+k{pX3f!S`5`{rhY3kLFmei z02JrYFR?^VsY8k}=&FqDfw^nwGyLj$GA_x|3buZpl|-_!J$0XFLLz8hXiawH*06LL zRpB{qLmoajIQZGmeipa5kHFJ+b(C&zZ)aLCoSo9zC@tr*p)Ky=XjV{TJ2vuQ_tktc zAA;SogD=pMQRZa-=(71)wFV<-+WgDj*=&~bAjxj=q)H79N!{@85S$LwHJi<-Hr@QEAMQ%YV+&;y zX`rn%l8YqeAN7WNE1Bu% zEDXuQKu^M5hBI6My(kY9GlJwArp9lp+-0d?{lPi}ru3YVh44J{=uE()h=m%bU;{?U zC{xaw{PxSs%Y%c1=#_X^BDltKr2rszb?*&rnlkma$`VZBVgT8l)-oWzFVAsU#}Hwu z>AD@8HCc?=nNnopVUZo&>L~5qmBGOqpDqQC3a6*1aUpp9`ZfD{eSLj4o9*rGVFi<| zVF5Md$*en3h|_`E*uHPJU8Z~F%5HRBC|)Xuoejb3DCFSa!fxKYne#etGtppoch{^#aI4%@ z^!{^GjCV0iO@388$Mo17roO)Z^&QUi{nkiWCK=H+w1FTTTLT|u6*|rX@tQnjZ}#gfXYnIwX+^#L5833||5pLF>hv~-g+7dN~jm!=SeJ+Pwl|9h1{FHqLm$FIOqf{rMB!sIcW4{t7}%jgg@L{EsvL(ox0oA35FNa)3}fIP0Vvoq|X3J>K)6ddL=!VN=z$S96ej*|u%i>p{pZDR}6 zjJzx=vsyrV38aB+2-lv1A(Mk1OL|0io!ZGDn)6gE3MFrQ^X3f;jJz$Y9oHmVbXi0> z8-!Uu2Haq`!9ywW1kiITE8v(QVn8#|^+#GYxD^wo)+n%Lbsh!46Str1^o%o=yoV`R z@Cb4tXpk#8IXO8!J&mTgRb7i@R|@O2`tl=Ks>2ZXxGt;0WD_0~B5rxe#IbA~k0JtV zy5O;p5Ie;jAA?-1mXet_?!%Oj6+C$kS(a9qa`dpspy`m4%(IGi%HUy`xzVKeEP@Lp zPkaXmVAa7&L+-tr-iENLPXHO2qVka!9JZ7b**>&GSblhka9DfvwT2QP=9uivhg<2j z=GMzH$e6p6QfpB`{0V57CwYE;zE~`rglBEQnk1|x&6v;U*;BzdYJRZPcKq0F8RlVj zPG?IU=OT-{mt(q|>|Lt(u3fvC66knN#$w>rhYn~0aoeJ7MLt00lHDB)uAo>bAw+wq zC`F!fj0IwYS7jW(CV?zXdv_Us;+fi3WD7r;?@ILQ zw~S$x|MjSLow$+Szm-+&+s4}SEIe+@?%=|rq6RNEx($~-xIi9jaz??{CNC4Cikwlh z?zJyUl?YsnIiaFA+6tC#bcJQBjslye*~zmip++j}3~&&2t*f)SxfzHSujFdQQMMS6 zvQbGL)lBw;qM9arXjfEvh}A&r`Ocq2sEOG`i;MtLC&mi22N1 zl^b8~StSpyfkck9njaZOTkYIY;`es(%zmIJX<<~y+?qE`K3B{ylM5=tFj9_T4YUYS zOfY*lia8a65V`kzd3lN6dCrXU^YciJT7{kI17m+~5fn)fdWff>2{D=Cu5B5BzydVx zt%ZrUSS((?eEHQ^U!9$ueMFtUs{=dw0zo}8@WM7s>P&9UtIVpX@eP`ghFxlS-u;UY;Eq zuq*|3T90gz_kP@xE1Ab7+ z2rr_yhmp4WLt=Pa8;60kDVF@tHf|$2!+aDuPgjR2ptX^b& z3iwMK&-Grp6OP>Ql2aM`zBCc(XFxZj!CpGBFtbRI5`sKI?0?Ow@WdIn&qMQkt3MEd z|9otWBi*pc2PU(57b0O;l-9juu5st&Xbc9XnkYjFjtj07TQfU zw{q7687p1527wam#26=T*XHF%H;!=nu|!NG@!UA|<>h6XQXEXv;Eg+CQq|fA+bXgP zzi92pKmM`T@i@QAn_D?QXe}Yn;g4d3765a;=tsbVW=4=<@Ruhypa|fl!3#+(S1~P3f=0=m92je)N zcw3>Rt0s4J&^80B8WJUk?@Y+JPv}&sI+DDG z1(VwK?c290jX<@KVNUE~G#hXV;c8MG%P>`u;Dd&^TKa3A<`_B4Wi)B2js(oIcNxd} z&{oT(2IfO&I#&`;My`!t!G1*5$chiCb@M!vgr!bMPmgjj-y9Jrw=OJB_sJ)p1SiVp zqgY%y1E2|EC%53qP(Gh!2Ev<+lVgZ<1!oTybBg4Piwnza)mvl11H7J{on2g9WJQ%v z4*71d1K$^{7N}=wEQPu0*@Q`E#GdmCctmI0Mh#XzN^M`}52n~qNm8X}JJ>g-lvQ&V zE=9m5fbC+ENDI(|mH@$J6NH@wcY$Oz6_n>4R#u+2JhtOU`EQc^c>d8w^6AXEgKMbW zzT2aJ6SRWGVi6_aJjrPN1VK*7O-|1nbjq5G%t(H67%N+od*`>qKm@$V{sqiR`@{@T zL|CX8Nv`nQvaAV-pSv10vBF#}aWWqgW#6=30(l!FE1E+-|Mc|q>gp=AP=0U5Hq#`t zibZSsqpinl;2cn)yrdzNtI9QaW4oF?UW z9TTpztcpb@(uESaq+(B6$9sARe=-)GG^>4|f7a zGQb05kHF*e*nY|MTA4w8g@w*;&jY!O~=1b=X5rCs%u3ukq4%6e$*uGI*g3FD6TG>rl~ zFmh2M3D!Zo@%iVUJ7q7G7FT*DtZu$;IdRl5LY03t!c*E+Wr0!3h@;+3%_-elSImgZOe!Dy7{A}bLbBfCdW{R(}X&bghJ8#XSw2V6D+v0KO7 zCL|P-y3Lifnix4Bf*r1S4dJ_eYRd_aH;#iXEH+PiW>f^J5pqN;u%KT{h{5XB2JJj9 z7+&T8nR+1c4ix@IzSgrDx*xf9jl zw{PEuK0q9|60I}B>cY9l>+VV_u25!R=#YKZ$3aGyigF<}8azL}5@ zfd%=MoO}$yc{iC0U6GdT0pX|OB(ANkg)>DWLd;1QrJ5Gm4#&sG2L}f)U%reA)tx(c zc6WETx3@i&!>`~VFG+aQ&Mn*<c?+RD^AIff9r1-^mK+u~CQn#)!s-*&1p}H&RkT}{$es4-x(&Q> zLqk7ItcTw3lQFkYpaxHmYo-}vmr~Y0*dO(9dN8BV9YR9@joTN99AR_q@f`%b2BmOj<1AClpw1pen zMki@(Ol;e>)!1z8#dV zqYS#bfkm9VzJf}%puF3%EyRupC;y;E;^t@0BQ$8&jO>#-Hg1_?G_V6rTJg+i)0f_1 z(|&I&D@-IQQj65j*P0QlJbK~mI6rt*MV9b+cB5-AGL^}}*t7D9gO3FkH?*M5G7K7E z4<0x>5p-5`X-NYM#~lt8VPyv#*?lH;C*;+36kB*~JYmUfrTFTE-|tm_>j%VE=~Br)1WV6Dje9&&CU&^1P?lY}{B819*jqsb<{&gEYTnwI~?v6~oE zX%I;YN*q3bv9z0%3P0xH_sr=xpX#BLkG)r2+}j+XS3HdM|4v;#{ltPFtlMO5bTi5O zeF7vCoG3_A8MzMgkjn$_6m2>*tJ-xEwx;OWabqGuWo;z-cOdbP3sXulxfK>)ZltcP z$w_rOUCGZAx$R)Gub~Vm0>4+z*k15n7(b%??*60Kt2=ojZNMuIPY-mxWye^>s`-PQ zk5tmM>c4LlrByqNWV;^IsQM*4a+2E8#=VM>diuJ|a^yIp`apJ}v5VtA-tocG@h~H_plZYfiZp zz(<=Xqa+Dat)q7Lp=^02D+!xGPf;BKCqieP&+Kky=|0SDkh4_-jNVml(jp(#Gb~`sK)|4QgF0H8K zbMp2V@F))vNZChp&K`_oYDIET@z_}X%it?yMgEG>peuOCi~oi16nANP3e?}N5G64#AT zAX)!j^GQY@^Kw^}FQZ@M$-yN*b$DOo{)q9x+1VK))AV7eZX>Z72_?PrLs#>wqObIEPO$Qqh{|QLR6^Qd!JSwai-I z`^%-r`K1;)x9fw5i3_ryFdSb|djSS4h~KNOw>Q6@!v?3$4v(%*uUuu?u+EYpqJiNX8`tML$cFPu7tZ204x0Gc6WDkQ_f?|z>ArPmYx^t zr3NN^(VO!zOw)j3~^;&W_|cvTn}b z`X{1b>tp@tgpyNJeZ_C^*wON2oI57CMt>|HARGB0W^kZg-aU#f4E8j`VioM+k;{r0(b04mNP99SciQMUwW`7jVAaMXUnSbeDnE$vVMP})%DrTt zrfbb_Xr!>iQUtuz?x8&qF}w))x^?i!WZ8SA&fXNq8^Fx;{`Jvzvy~MB?^w-4wuJ?J z6rMq^1cZfV&z?&E#bQ%|SCohUDz|0X9D*a-->5-z`}vK~R$8CWMwGY&6PEt2o~p!> zO){4aPno7=v&;c)GkK<>8wkuC*Ai_-t;=Z%vUSDtUQHlb=hlYkQzSDz)c}uK<{89# z9wB5m_phUr#+a3k3VNN$%SaiO!VdYSXeUN+U=85K&zFcRkU}C^D)`tmobZ>`pC5J@ zmi^$5_gljl9&lAh9FG#nH5jDX15+-Dh9xno5o&1A1^asE^bSeNan5X@hF;nT9kp(v z&q)=_x%~+$M09a+N$O&9qg!> z(_P@I%&~M64nZ@0GoPV853J>8>EUrOp7=PW%}JO_c#t>BHTK$A1v$&8Yn-|E8c%U{ zRgH2KSM<>;kIgOWrBNwJ#0-e{wsv2fk>JOhE0K4~Qrc_)jw09t*?XmaG(@?PF$<2Oa46phj8{flWm{6L#F11c(No=|{4AY@;zR0GNz z5SsA*{tm3sNx87e&`WqE_ik*=e32K3_P4o1+d!MqM0xP~x-kxYE{*R?z;MS9e)^w>Y=EiG@1dE3ATksnxEuSMY&7%1FfSwlz`9QiUhEwPEG7bv zssU4aP)(okA_$oyF!oSR;UJ@5_2)A`G2hXG5OrR*wT8{Kq`Qs_Xx=4hFK4q|oHj1C z(B@{|FHRQcQ#M0}eK|v*ova$#_L|>T4^5hB^GSU!bTyVqWv8lt9}j&Xy!$tbggcc_ ztXER}!&`Q6`UP(-eFW->%akJh>?`~mO)|ATKL2M+Z+ z_M=DbG^fKMeKNX_`~n!kgaI*#MKjOIe0q@%s<6l$odVhwE$Rdj3i3Zlx7TknhKeh& zr=XoiA|eEgSh(tU7Yd=}sHaG%ay(;1ncP!Xl_W4xjawWd>+kl=?CD=|jeH-^f3s9? zmi4$M!ifJu))RR}o|wW}TV$}_@)G*Cb0!m<^GkS4*O=?zJAekOsp^EO4wNGe+|4tv z_`3tXAN^7ixI4MPh7nGF%!#P7d-?YI!%b24e7%X`&+2;1h;L9VVm|~24Ph9ilosN5 zZti=z_m^Vf!0+L={n6X0rxMyYtH|LogPSh`*NB2vKo}Dc)XP)ON*Z3*vhe$=71``P zTsp1wi%+g)cvibUKiZ)_F2pa0iEnTRKT*t<>7ta~h{m?AYA%bz?$c8c=#%Vh)Zu~E zbs*4NbSPxYeCDLALMLz7a0H}IxL9XelF$u(@UM-W=?z;;Z^4W(4dF>6?a9iT%lyw!NyhrbU)wBB{u2*pd! z3{`d~F?k##ek0*YjDyD0ZErNOfx%7p)||9O5y@f$nGgoecd1TpjqtWpsbx%&Npq^w zW7@yYp@=~sNv7*gaR2-BaV=nO1Oj2NuCJ#p*(jm}D9uGOT{@Z@i^-unLaIyx={Bb+ zE(fGWx^vYXoaWW!NVBsvP^!yAK{Vpq#R|&7{irIem)<2TR@Q^3rVXy=ic5pe`E;S+ z*4JtsRKgo!n-+B%wyyz4P>$Oj%|PxgP_laga6CYE)`&EG02pwsQQ%x z+D+zJku|J3$sGP-z>wFC_8qxC75HX=5?w`*jl;_j-?+&EWlK4lC0Q$u*e%4>`9_rd z0yLX|vUCNeXSpRSSq0Y33Mxg{+icq&5^_He4g#E+W`Xm&i7mzZWkS<2NA??;or6&5 zC<_H}N3JF7hB6Cx2)@i1N!lc(l}^H_u*A3mL7z#=)ZlQ}P*Sgq%220ezuFPe#v~^i z3PFFgye!$U>P{ADGd_?sX}?A8usRdhB&jpMqSKT|ou@@?^@eCn2MO$;AJ0o?CBMKDx%lGRQhE%+P!?;DycAq@CnAia55SC+-tm zZjX*t=Vkjf4e@?`U1uRLskFxUZujq_kywM|F?h|@w;ohAf8wQQ9Uf0~+WKAP0p}}R zVXwnyne@IF5n;*IcAyl6LVK8GPz7-vh+3C9*|vNQ{JrND3(M5!I;{l}S{?qj<$^ z&e(q|1wioF>1;lbLS^oE$}TGn^p!oHw|Q22k|*ltqv`ZgC}?pL4?R~08U+3ol$U7C z%csssTVE4t)h)Pg5CkLGq98sNq8PA06`YJks$*3>%zIUUXsdURdvex$vFXZ$ilL{8 ztd>~4pvg$v)qGcSrskVkzk|yuM1rPh@jVtsi;BoqPveb9AUhB*5pjzV21mRTe>Ig+ z*RaYPreL_ND9vcK@xaLIrBHvqQWAWjXfjXFC2o2-shjRDx0h9=ASc0$^iEC`6Q`V% zlBUTX7M4*lP3&)oQ{qT0fb|lLLlG6ULi+M&o#E~g(3s!$0O0I=yg#6fDjEA_ISVZNnO$$T7PxGn_J`?% z+RxePfU3_QW`06Q_FiIYUH$2=D&MT!*31lV>8on*N6Qo!D*8W%5P1Qy99y*(YlY+fr?fm*&7b z2G7!hiFvVL&YtFAtzhncId|W!msH4Pn9bO&&*L1aX-_uW)Pf|!fF|QlDIzI_pl-W11aH<~v&EthW z&$lZy9-;|`a{qmnL&Yi~-4;lH>R-H$mA1?kKG|cIANNmFav6oVF5|qHYREe#`VvBA z0_wL6oWKN}06{s9%DNlKh!UJW#K^77y=rVipfJz@u}-L-!@v0-<7#kF3^i^D@$lI@ z4>@gvCy(}7oo4?4=9DbOq!12dHCA;Y$#CBnaz;YoxUZFtY^0#b^Lz^VDe|-B3uh;< zwtXO;h*np@ZPX!&b|X1!4Hsfa1ea-mTg=X0JGd^k@M zMCk;;BquK7jcGsdU)JD+>er?B8~?N=UeL+HcJ#mipRQvClW)#|-QhcV(b(d-PMPR< zQj>!+@HYTAg+j4!8NQIeUt}#Hf(v^6BK3+$jc4?-I$-*{P2P(8!8ZA+!mPXzZxsFB z{T~=E?~ASx<{Css3b8(@#^vs|FTdAfK(aaY9clT`dN+{o9Ac z0;zvKk|!3c3h4K#eduxIAPcIB0P^JhOU`_@uO;FYaFVavNy0Up(DPj3dp@p1HzE3@ zrli-4@11Y?ufY{Nzl|V6KI61aG%RT1ELg%>{SL7tTTmj&d;IizXpO;!@&&zq1YpGO z1WU`Nj#v;EUNg5jN zx4e!Z|2)-WyOqFQda(ciQU%2S%#z^MG$N&eKK4TDe-p~(@~<(Er{D(7ez9b`7|2o` zx-@0y9`nZP)JB||BN5?@uuxKCAqA_vQp^mh?+e75`ouId!FN@A1nrkSNeKrC1;rZJ zAWGYVp|$!|MnpAg%`y64EX0|En{$OG_>?o5l zsy)BeFAsO}JZkL&OFQ4UB$0;glTx&p6G|^T7EtO6ne510` zrhzVig`fpCRbSi+!b-Dd3$)wgN7SpE@fX@A+7VX~j`sr~I+@eDm>0aA5op`4Ek9%^ z=o)16b!Bg8M*ec!mK*Ja#a<@JJqFw0cS%Q6JWUz@5O#dFR)-!q-b!%_h@1rUN()X? z6Xy@^f|ekbC(=*`62oN}5`)iz04t9u9wb00vt-F6%t(Kbv&iS9b4i|Xw&djA&#r-^ zeHh+E>o*2y!azb7VC}dA5C?Tm@6C;k_duv~1RBZB^|cP8g*kLg(kWQ!1y?+tEv!y?8hMbr?kB~8F}7pt?%wCZD+ep z$b=9v5Alt`)Ap_DTM~z2hLuN9F08i~{Ck2rUMoUZV9wP~yND~CA6Iiv(~t9sSEdJl zLkm<49u|Fc>%il2%1HbgYA|Krq(=fVbT>}>yss9+f;G>*&Dl2eU*Zj(k#Bu-v%9-{ zYWr2j@<3e~4ey3-DjE5n*(2rz8%FRr1zXjEyo4!9!iI=Tk~ZHLjJ|=qq?5GL@bOWw zw1#n6HrH|%69EQS=QH&ZN)pX~D}57Z>Y7#c=9aLgInt>r1xoc%`U64(}^YUOUcjQEP|~ zGI1x~^nI!XDb@m47D^3w^s%(v_4WO3($6^WeBlBDkj5moPLws%r=4HC92jd!C-{&R zHzKosz+ztN-S*fGiG`%sgRx*gYq-epKv)yTW@a=NWljIId(t+&fE$b?D3hnlnArM< z++GX+5eB_aqX4i!Bko17am=o!=y&ZyT=?i3x=y(oYZ$)99ziy@wi~48;Kx`N;P{#H zy=afp#p9WO;bRTr?aX6K!~u_wq-@QW2oAixpogi1Sx|Wc=4BVst~SNS=8zc`M7Z56*xXwWIh;rn<{YO}nb% z)mal`n#(`#%5uvU6$|Kk?Jh!USTe|Lfz)%XNq<(|edwuR zw>-+)oc__K@pyh=qU~1>mGd>+0=wF+)T$g5S@2Z(0_70rkk-vpMs9zVfV$llA)KWQ z11{3#uehqh-OSp%Yv*-E@YTGWZj0GL`Y8!_M)Q7B8mW@}lj-3f(OFuvvxI&T<4j40 zK~@rb9XX!G)|M8_MgXO+y8yx>mwyOhwU;ioYZl=|;$b}zJunabVaYPx1slR94531f zhmJ&gcvm_Kt{!j0?BFGbHJ$NqmS$Yn5hsbz|064aej@LcL+_@}DlKqfOsaU>Uu!gj z1%#8YO)fo*nIimFY7&=k{G-d71ojDvUyGH{`$~VDG5f>C$q9XnPEF`=N6*Np*Ynm; z++zTPW=Fg_sgQ#=nvo1gTr)kI2`u+9b=!$K)bPnGzcz}%>V&twdS9`Vo>!?aSO$+& z!gV}yGvfk>yejLh2SkL^$iiTzjt^sJh03yfH_~8Jk?Byd(e;6!D^GyW2sfw87lO=cT zlBN9bAd2@d1LlRH8{GT~*bl5*1O_USs9E&vxR?|AidWil{`c*4&@$r}H!~K2$CmUFGh!h*w;T@#u@8=&sLIAkg0ABr{bc_6vbXDs>&8&pv zHU9k8ADlJNq&vkpZg`Tg2zN!z0_pglBdL|u)q17|sKEI`7wQ5^v$ds9e)a@d2`YP* zZjr3?;3Z$Mm}E>aVW@>JOa6B&+X0NxCaWRY$*)k z2Ole9a}&$_Tlk6R`$jB4J93SmIrBP>Jt~@Wh<~<*`&Z2jMKy`4{w!1qD4ecM)@GMB_Gwv zYo`qow4hpd?bJ7~n=vTFG-DmJ@c3~(E6Xr`)+ZkUJkphUl$4OD&30p}Rdc6<%G+M!2;`1gDst)KYiu^Ea?yjs_c+OpsSl zS1TCtj|gh)cMxbUyY;>Q-#E0k_n!|Cd<-nbo%$1~r5T1IX-g9=<&obPb!{-1O>h^R zeSY}G9?$4I?gE2A7U_KU40hQndQMAO9wKj3+=(ecWuGC08q#xM5O8tX0Nc{lf_5j} z3@&q>;Tk$kn-ZI{>F?!me*t)$iOmI*N!CeBACB<>#?0X-rNWRv}&!Tz?X>O^16zq(vKj z#lRckSl~ABym7KHjB2EZbB^xp-xtr1;Iu}NYmed#=QU`}_RF6r)i{>?>YcP+{gYgd z)0W+H(g7Lb6o48%KWFTsuGXU)Ii3JnH^(mCKnclRia%R`d*9gI1)BeTz}$hJ=SmyL z1cuY#NuT#PL>7Y@coZ@OEp=1I^`R&8;Hh^>b3~{Ihj2&8YU*MTY@KtMrDWw$wZnMc zkE@4pSfABHHW3MMpPO74?t3W?DWyU!U~Pe-Sg%mi`n`=u`q>rcMMe3M=0-!PwM}1) z**|hEm=f8&RralS9oMkrQ2iWbJ|6~O9Ay+#s(~!c72a!e~sLYW*1* z#*Ad-D({?gh0v-4MX7J0@mGQK6Sk~?b2QXzQx6(Zmn7ed#FM$X_AFk)CwHK`;U+EO z#)xjQllPKMKsA;q3A3eV0`t<#BsL!wJMio@Fv&iID@j>jw`%4{OajZ z%JR3`if?v@0(=`_&Ekt@0tE{_akc3d&w*rqU5*;5q9GMTru%?S2sRPhRp+uzx5C8t1#2%0dI6hsh)nDmE@W_v#p8Y!}Rfo&%aj&!|DxE)HfW~i+)(S>1k>_y(MZsc!DXa=j z^wHjeUn~hi;PoV@5&37#TtO0vuJzh6LxT^?2^xev=QU(JaLG@5enF#UaA%UEpL+ki z#txHJ31K52D0&nKAZ9`i!|%m$erooGv`3&T5Yr!~7lC zZ3n*jLuOoD+!TQ)Un4*CHNbvRZ47HedQBw8#ZA`H)9d_w{xkm-n(*9Y(Y=y9;ym?$ zA@n<8!F^VNHPj?wQRcAeZ$R_|D5rp`T*~%#tzs4s@bUX_6fk8?7cqqJ{~=&dGyPO! zQ!I+^*ZXJ$gqPyguueRUIo1=>)>z8vK^*hUzNrbB4ed1xdZ_EmXKkOhYATICo3V<| z1;c=864N(EK-``a1GI9f2Y1;-(6(bd6FY-!aRcDdHD5tATV@Br|FT3-47R(!aaC0w z1?zy!)gN$kE_i$v=EE+M!psBuim?^{MzXDw5`W6h&Zbv0>{3V9XeQ<$B%!Dk{>RZL z;Unb+K1=Ae;zcfvcUJ;f`xEazbH+!Cye?!UlkK9+Nd3B8-Eu(|;`h@p2YdT<<2o6G z;Eaa9(x1GI&EM$TNw=*JzEeBr%)9U=DealW%O_cD$_NwW7iZ$eEPyZo{+#s;(XLe2 ztYru)Q4wZn+%{P+;G^)oA&)Y|ycyA6gyik|Us)B!8 z3T*Yej_v*|{^Ht~#;Ts8U%k8=cy}*t5K7&4d?xda2d!AV*0=#kCgFq2zvtDuGOmKQ znJC`lXz%>*sk^#55_1w`cE-wc0<}r4RdI)-gQdF@rF!ESy534~CTJIoe~OAtLX4{1 zz?wU=VKEiLrb4lD#4Ak8tM1__-~ZzJbvuIaK*%%B6s|D1A}LS(Td1B_8|Q@@Bb7-D zgrvIbQAVQ_Sn=^9!8sjBEc<)hK+8JndJxc(3n`Cd^!OHyL#+s0%2sM9&a=3&>i!kA zYn4i;bZ23qX?Ii37*u~1Mz8H7{7p0|GpU<+z1TNNkXz8*+>BE>%Dxkc^OS%5MQ?+0 z6t|SVxL}d)@@QA)!6t`p8d=2I=6RrNfQPf0Zf6CSN>*b8nZYX>0cpJgSmD-RE0_XF z(G(G-Kjo0?zy@lf9;QIGoi&_HmoyxtE>o;g;i4P`rPvxaTiPCElY>t&-oEm(Q)16B zA8@{c^ig%jPTPlE%z=r0Wkk;}_{C ze-QWB=WcEFcn5x;hcf?>NGNy-1;slZ&{O%mtm}ogFr}niWII6C;N^`f+4B`_W&b-- zI|ncH{;&v)g{CaoI795kZJz8ywPKVMRvE8(7`CUK3{9ahW_5K9Ck_H|G1%^OXA<+^ zOXxM!M3*+J9&5`ZF&KBA4ha`Kg9VZiAzo=|mG83_9NEVQDAsk?R`%n5NzL0tmW;u& z{Xr=;tHkn8|2&H5-ynd(aq80k_9x)u576EKem6&8!UJTc09WDT-#);93wY@}fpi0@ z^QsA;LDeN(8GO?rkTH@DJe9#(1h2@53OVf%%n8vAvrt2lXd88Pz|lM~choll6DkNL z7J7=DU?1mNV0AL1Yzht-y1(-myuwC%hv}`f)_LWEKd>Yn2zOXtnltAwn0OGd9SRe;_X!qlZle^NDOh`|5`}9GR$#bj(bw zU!s$D%r6l2eixQlAZn~2dsw4xr!Z}a9`J9*3Tu%mJS>0zkmk)g8#M3hw=5dxg ztgoOqp3&IhTWwD1r=>T({SwJkDf@4?gr_+AKy3gl7%B|d-r0|I2K$6+_(W;A>aV%! z6O8tD%m@wGvuKo@BXgXcv@E>M6ufzg-&o{0f>Qyp!)e4jA)t7Y zKxq1W#H&_<;&;$-2FMnI6H*sW@n^rVb>8vanYeD*())8!QBjWRj5$2G&)%{*n>+?9 z?lN7L@Tcd%(=gZFGmKlA7mphhpcc-8_EmpV0`M@>R5Y38B-x( z2NF=Ma7D(YQ9MmW(^ysL1#p7sH#CIa&y~oH9)aU|wbtlAyI5syk1hkQ^TQZzQUHq1 z$>!nk2H>EWnF#?NbwS@Yz`uo|Ia`iXI}1%lGVbvA=n^=`0k?Gl*Nm(?qUn=e_v(PM zTnxgMEA&j&mgNMLadPEcRrW*T)nr1mA)-#&;jtI}Ybu;yEUUA$aK0r<_i{SxxyoT| z$~;yUaSm>zg)Up64{m?GbtS8=bZU7AGZPb}0fv;Izh7G|uz#`B8}Kn-Bn8M|GPGyo z7!43bI65rhc3WCjHzVCfx;>igO+p4dOQ9zd&X=L%nOK`Ekr&)}mOB>K3#kuP23`iN z3*ic@W10wx9*M>*uYFxV_PbR02OcpA%n6Qk3=x<>L7f{?!%t+T$rp73kqJ}Vm;Y957$6o9p?)_ zMds?U+vZoF)C~?&>PXf{_veP}t}08>VCVwx0z>V$%ie#N!0Z{gX4Uq*(kbDe-Ua`- z-RbV^?G?(NCW|4&C_5YYBrKLrN~qVK%=z69K;FP@B7O`UE4WCdYqZ45c@umJMldoY zV`SBib&%)?k;?w__QqdW?Tt~6U(J&Mr3&_=s#DnM)ixx7kLLoFYRx&bz}-XND1nz$2TzA2k=M(BKsWUAO)ll znWpdsy9#|YW2TR!G=sfNKz2;d9e0H237BpPi!re`j9;&C1EfHCIhocvN-z)%@ciKM z_rfd?8b@?2+Hc!mOc1U1kPBCUeKlOz^@8EL0@V(0nVsRx)O1YstYW5zCVAzB*Am?6 z3fJTX)J985^kYo=gn(chky$DN2GyIk+SjF)nJkUM{g+^Slebe=GGz+xVt#MP0@@(t zF*ZyaOj1Go?p1!WlR#Xk?%LyfuZlI+Y8)iS4Ma1;%WHY&y<_cr@>H=SM8H(F4##I%=(x>XeKPdOB_*TOx?Vdc zHSt&5801goTu3awO}b?`;2)2dr6{FJyjlAGGRln9g>n#*uO5iyl4zLg{)>=z!QT zB7b{3yRA-7X4DV@jXoY!hE5l^lbI_8UCaF<$7lmkV9mUAUgi;#Q`q>C94W{{6a!P ze0*k@aP69bLN#CNY4(9gVfbkk*#hOvvaK>sTkOwXWCN#^;iieYlRZm;MA&ROj~QME zuh#?T|GYtaKvDhoyd?Zy2`_C`|MA2C9~+w$F_=F50DRc zer{di>Ds4e4jZ6Ew0mxrz;K3no+6*b*xS~&x7HkE>raP7nt#rY@CnH;lfSzVf-tjz zRE!flwY@rDfZ?|PC<}{q#0nC!cE>eXlc?%p+jUxzuCO@I-yBwEpqHkA4gJ#sL`?e0 zBXIMu#5mz=G!0ROiJ<%|wOgm`n4w7@^lcFOL_N-9`=q&^($${E3C3|ibhUQV5~hd3 ztbeMYzPG`v?Cr;JW@d0NG&Q71-ly!V=DpiGTdKCX>&6&-5B{Z(OGMxUASF}RP9c`1;4*kk8%w=Bx*%=G3vud8yO@6&(gqoXSm>QVUI}o<1zS{qyA$Q5UCV z{KrRTVO@GQCnv^=o zf^es`AE*QWwfaE&ume1So26?SHC3{V{^EKgKh;7PoUsm|?O2vK^B#}bzIUO+U6P3= z`_-rqG$j03g$vMOy8EQJLhJgoFb1aDJLhkdF$ga{Rp!ZcOTL?8DxPJ!!d$I^+BOo5 zMM5z&MVR32`h0wD@V^LSyYE1u1X>?Jbpvd@KpH0L)8T5wKfnp2SRK71)js0IJNOSR zCW@3jkcwmynf$151Jfq?TsLHqU#|kA596Lm;92r9Qjp1@pW)k#x~K6JCv&$+S#(>k zv-%P#=eNZk^^(jar_-FiB$SZ}+A_PPub&C<$x0lxyWef3Rr4TB*oKZ2sphBP^lp&K zh9$rp0mrNv$E6*xO&<{=2zl>7Vkm5EZJu0#z+eH>?(3{R8Gu8%*f8kPwOVcz9r91lRHFZ%SA zjexfk?7r-tKN~yW92If00@Lp%a{;QKya?EmWjY@_)h%_!hLH7Pgkt7qYAg@paGUH- zYkxI4M88DtMl9d(C>7Qxk+)|v4$+6_U zzTQa6uQq?E+=`NKnW6v43|&Hh(qBqcNjHmq@xlBAg`~TR(>U-JBqA50&>~qa=9Gj1 z0f*k|NIDn*3*zPD1LB2o0It|?Qu=Sq6&7(ggNEyOrLhUoCm1FvtmD5X=^*lA%mgw% zzAB>MeXKx_f$HHP*CQL9zj37S2L1JhAgPuUj)>ou(p!B*m5?pnd%2b%s{hdy>o+;p zS)UcL@K)VbB*V-^$hJ)$a?0(Z3+_*`oVFOCUNHewiHl5Om1jwzToi>m$RF2v$3{(4uW_yY)MFB5 z*0d8hvJL@CpJ(GO(9M5%rPi3UU0WUBC+&}VqTN&&`_47%_(pt}17GVBf6fc^qtf_| z-7lX*pglHpT6Bj9IQ?Bjr>%qdkK}2_ZoKAlq9#HfattIunmQHb!cBK&n)-eP7ZBJx zAatq4H?R*Uu~x$(XG$(Ap6o~U3G-nPJzTOTIrJ-sa{8Yj5h}J@fj>FjtA@5U?I%aX z?`R+ULR;;w5o-4<)p|hx?*%9Rxb3<7enc(Q4jem#;cIJaZGhSU2>T!bpQhHg{xuORrldJkZp1!Z`O`cba%6S?yWG9uNSfoXDfpp{f?oC%#42#B^3-~ zez>*gBXczKT6M#pfn8vsWNEcsAXXNmd6uUN^B?5w%=~sYHf2u5>T@JyGPw7)*7?QTifo zUS;^n;u+z?Evi@$yk$i@fuqNMUE|<~)lC1FWSLz+K!77uw+4Bu--G}n%qHde>k(~V z0h7b!mApZXc-smrIW98sHJ}y*^mcY`+P49Van8;nQQ!9w-l|?5Q=m@|(QR+OGyf0^ zj%mZJA$-gE3x(Y8_nd0izljEbxSS%V1UkDoTxsZ~9Oq_k)n}5kNgv~VU(XkRqEP+I zqDLu%*^AMO5K5$v`lZVH`KKLXGhPm(T*p(}U8li|SodV^24<_qL*U^z z1C8Kw^{hq6HG5SwDw(*{NjsH`Vv0XjG=}Y>7nn4NeWDua;*6tt$z>>#jkUF4>5xz=FaPDqk(q9k(#o z5*^x(ZgYk9oA{S#x^(7xUETXzUUAjI8#0bCuZqeuG7QTLbBE*nrB~x+oH>GUxoYs< z%gU1+ZGBL0TRcVZImTAvRX1cAK&mi=5YGcB2pLgeY3ZiEdFtcN#m zU!kqZc4fqft(UiLaWlnnZfNsCNHt^G_4&E3GJ6v@@UB7mMCpOuM3+J7wGXnku)&#% zqrw*B#YKm9OaguRnE&bP>>Nb6z4%iJus}cV^@pJPGfg(Mw*C?NIQ?LN2@R;7^G_rf z>_|&tYP8A5Ph_aMwrwbLV#eubWd;+_8-2UZx+cTkbxa-))W?kP4w@e&bZ_Nz)>)r( zUQ7t7@-UZ4-y%^oKd?#_+mNpD^T>V}zS?kc5GGO#v<;7K+t=OuMnlAuuJLOe!k;4$ zXi7fT`0c8$`oqtvhLq8d$bs#WkHdhscx>y>dAZg3;EzqMS_blLYE>w zTPWPJ@|qH@WH>`ZyuWH8#Nbs`j*fcWtX$vCz(2-RRQmeh>8cicM%QbSkzF_LM5ea| z$BSNER6!AOxNCgXD8LU`6xCX$cscCB-|%}l!%ybfuQHb3k-{aWl?}U}?=Y?JHA4=^nAfK*1LND?wwh^# z2dy&+|9xj;)?7`CHhnM6#+9}oPivX$J2Q_$Ya)j|d1yGjTDDafW~a6K4lf!fJP2?Z^5W{VERnkKZ=~{yIwWU4#Jj2RK!L!5oQ@|J9@0-Refw zqKPIp7>`$Pf?)Lr8}(hE&(T3W%+?;NOe$Xy8pdA((&Y(-09Fy!=Ad_1XWR|YayWXI z<$JcckMVarxG6#GE_& zz13&7f-r;3!2Nj9 zb(=-?)3$p_#^)na>LR(LTFZn!(`y~#G`l|~efq!up#Egj05o+8Ggx@lN;PlcBDDh= zPpcI=d6RFJ)1LHuo39dfWfYqCxR_T5Y6Asd+Kw=AP;+q za%57*DLIZkJRnkYzX79QM9xDFqe*huo%r%=%c!%J%BXbh;D8pHj;%;)@Of`XC15}| zOcv!MS&9ZdMD>TfD}9^`vF5Qr+X51wa)EX)pz%F7=D$yUbOn6;`|t4P_cC_1d+tFS zOk~Zi&qJZeK|$#S?@Nte_qg}Zs}R4oLDs*jx?2?>@-7(cWkI8^VQMOe<}3g zb+*dq-6C2scsi{qHd^PI`?dPs!MyD0<$|i?;mT4hb|jFwQtk17 z*G({;^7P_om?vKqYb9q}p;jG-<%t4*RO zCc-c;gIm5eNx5Rl(sVGJl(bAakkk%^W@x(r{+tv+9!P(#;3w%MS~qA!#oIKVMxvb% zHPGW))7lF*>h>AtO(8$|Oz(}mY+})?z;Q_i=4G9pwqsx`6NZu)6oZY+U^ zPXz6@oKZT-7@2nvJ|eLCD{`U5^*Jj=Z)6G=<}vfm!(B9)w70qWcqmOQ+7#vSfs}v3 zp$0)Kn?Qd&%V$e<<*h$e4JJ_6wPC6P)mqeWtv+v{q&|l7qSPrimLQI`d-?ZM3o8Z9 zBeZ_J8$rPHCmP zq+?*{l2p-22>+{@rZK&o%cs*Fh6tss z!WFGxh-7=|43M!98yhR{D!|YGa5JO)_7w1T{>$%f>A!Cq$jSzsO3w!eRz#`jL&a_A zMMQE)We>)!as?J=c2g52et6Ugs1yj^d|*}?(i7mH4ld3*JLR8T!i1pBYgSumdg~`&k z4$LZI>(z$52jA8@pFCuYtkF#P9|4X6ly?H?MSx_(S76W&jFx~|J|APVy*WB`_4aw= zLiS|VVrS$hONKxpS ziZ+o)75e_iK(n+OcgYZLb=J9RBzw+Hv?1Na9O(F7jW%TMe0UgT4k3vte}y~$#@`UA z763aoFu#9YU(flZ60ZM4x>w!$;_GP`HWG{5@7bSq#VIA6#ft$ z5JK@^iythD8gU=sQMR7Ko}@Z|Pc#w7LQ=jER;^yliK|*h_5Ad`Brr?<$XdLCEfZ{t zz?3y|+5kE}vDV4dgNAPl@Oh@meP+$wC7!9JX7UnIRd+053F3u08o9eWd z4c1s#Sai*8s1_pg!t6CF)7$v?_&hJS`V&7XSI7!rmIlUHBy31F6hXjJCQ_e_2BH$C zZ^TO7^3=cT)MrlK!g|)}TbX|?CYIp6+~bt#!nB-!z4S1dePo)6N4P_k$@!8&Zrk5z+{vV9y{$D1d&7 zaS^fmfWEoV(K)sk#@)X*|E^pvxIUUphTs1>iE$5`y8$}mIWg%;iJvW5fa_2 zF2Gs?7M#0FOT@cBxn-4Cr_#Luif$jOK&5}Tt{;m7!Z?eco6*%&B2r*If#1ee?vZ1M z$_Z>l!1Wlf)u1M^mWb#%ayaM7{iW!fmZl=2u3V;ZP8ybMTaZPc#*;C7wgK?J6C^3`WBdKeyJ%FUbeJ!b(kV+)3Z*M>KDU;DnADqWYB;CU zgw5HvRt^smcd`b?=^YIJ{%%U2LE6lIN$w}RQf@Z}_|5uHwY_3kJrgjPZo^eO` zB<`;h_I!gAe$+oU#5s*cf635o!n;|t3n_Wk&`QAL0|StNj>n^NK*|P8q_7{u_MFD% zNl%gFNA)YYzrOG7T9jUuu>ZmBM$~rEUOk(3IIpohE%IOx^^IaIj;*w&SGQ5jQwfe5 za|&Kw;~!GK7O>0%&V+#Y-jL!03CmQAQ@BB{O6{<+Y|Q0LktR^A##^6TDR?B8AmxgI z-%p{sk$@uB*%2i*c|qUjClE8-;&x1cFHx@LhBz0+C||z|g>kyIOY-^lZE2U=mm%&H zrP6gGjjk*{)MW5S(!sZVZEU+g@D87z8qfJJ*i_0RU?;2qX(1si%O?*q7A%UNn`B9H>|vqVqL|)-2&#vm&w3m1x3s{L%W9%o3iFteCZ2)EpZ8n30-dmQAQLE@$x8B zp86Dt!w4ORS7ax;Z)O=QPYfEHzHvX1Sbt=woBz$P;YfKr1;~E=(S&mWHMutGO2m7J zlqi2N7VgKRoU}DoPKis5!_fsV?1>JULwa^h_2wi~Vt9R3Gh5TDkUw}UrN2uG0@)*g z;*>iL5~Vzo!3?p2Fy#S~@~LVl8L6=vwk|G-F{`D91GxfCzvaw~1o*o( zATD`~FJK>^OlAVztPEi|E^l~IcQe_Ovokfb*1zfB#cK3)oYr@qpY?qu_&|%HV*THK z?u#p8)}y$zr_-n+rIddZ4eT1)w~5$}_xAS(s27cOb-k~;tfW64eZf%+4jxZQfFo@TzGgmXl6ad=+5u0Oh> zghMkCTLHVFjkH<6@Mx$N>c0O*u zZ(59HVN*moG#T>u_V`#t&FeUS6$XEo3CvnTY#%b_c8je>3xh32XfXd8s&D-vvOgZ{e^USu zKxXp1PiA4uJ=XtU3&7DRl8Kr?PC+^S&NL!{x}wNHsrS0DjZwX9b7eg^*h&RMroWo$ zq*=d_;E=F_znIInjGi3XF~Nym>oslxDERrOUK1wE*Z}7JBtS_$R|-7c7pInr%nQZ*gYy1=oeT_0rH0%v~W_LRzTsogH42nP%r6+cY&4B^)mO0c%vNv%15} zZd+Qqy>8WQ&3&!ugv~%5b{5teWZB$*DzY@+Hp1Da00*Pv*O#npC=JVxfj}6zcq2-= z*J==)eHI^ad9qXo7*V=3+oh7$SHKPq=l`LY&ejU-$xh%y3Sw=A{_3vO+E=1hL5|c~ z2o5pPbckf><78wbRX`+r3l(N9Z84rhcU57(BP(vgrC=`O2fj18F_H6~|7j!Q2(R&G z#Qi3_3Z4O~{n@Tkc<|h61Y|~TG|zO`J*A6T8xv6kjM5S$_XBg~oTOU=ws4ge z8Xabx8yT&gR(MvUxcVXY3#YJ#AIVF?bTcFGnS#+~r#;6RzO)^c@i8yTQMT~$(~Y(J zqWS#-A2v+lW2QrgNkgFM$@#e!a;(wz72^=(PkJy$2FpdCtV{9{FUQ6&{V>jzwod%L zK);r>kqKNoUnC{kqr1HNv6|7ict%MJz4sWX&5Iv(S)Y=)`QeMPr;}d_{p)0Y&Db0d zT&bKNO~#eCGonuWD!92iymN%jxLlA(*%V=M2ptgo%tz)NCY+(aF!F|u&m(Ks6OYEp zcbunHa2S4*r5pQjzPrG*F*yOHYcDH{txY%FG(L-*sjU#1irU^b^A}BR8ZU}s1U_U> zi`%pF^E!#s3EU36s;bC!*Dhe2NH z2!MsQcc%9^Tyf|GGQH=sGT5yoIEe%8*7DY9JG$f+aGP&z%&EMR&=wqEIhD8;o7*kr z*)AFUgMp!G5MU@05g;5Q)-YJPoRQZ4EpUFDQ1)Kn1u z8QA9ks+}#@)q7BNkZ%p?7m~*yzhfpRA$ikrvLf)BgNbYh(gA4in=m*FulewhjRc8w zr;@rjpECkBj@eM!No0be8?Uz|Jh>c$Tpv(SHv9Yg0g>VRz=k8+GVIz8H^!LASWlk# zW?)z>6wH?j+nHVhf_|uiIU`!4&Vpo^wk z4cf~2@msfXhRkp*Y09DuzyD0CjBvGgy^ze|$A-R;Yd~XC@}F)m;Bf}1^nEY;|F_-; zh7kY7H-CK{eDl28L3vTDE45F%-5ISOCi+w6EQC1D$!hDFiUwKH%}|xbBn0pQ6hEKa z8b8c6o!z{OWMo}I=?jdOXeB{aVO9&>R(?O)g_4*JI6yCxf~((gx15XVl^0)e`p~@Bd7RX`D_!@ z*gv%?_dd@#gA9j@m*u?ni=D2x_}|%Xk>fu(W7A4{n@x73L3w-i$^jw_kl)7IGK-ZJ^j%ShO?97H5WKf&z)S&V z7^_H+HM*{T_nYB>98r`joBRbh_vA$J@f>3gfx>DrksI}JSlfc@NC63+`(ew+&febt z>GVHA-850&IFMu0Ko(vj?9n8!ZImDxIzZchk1Owi6pkKNcz&cUn|t=Vfk`i(?N`S` z7(I@j8}Lye>nxvYd|v6|TrBQYDWZx<3o$1>!;PqlX1->TA)PGaYBBE?vH84^P;_86 zH#tIDxfx3i$GCC?i-L>1>f*B^O*OKlwV!(2CZz?cibbUve%T=|TcKA3@yK02jZ3@8 zQ|WQf>b=7#{L`>A#Hbv^&G2u3;3p|xv(v=jy`!Cr-(D!jp5|qZ);_;4%R>4?~*Wyn|&%{ zsQ7*wX4kw=I@rTvH z=|b$su!UYgQBfM`vA^3Hv5c>Y^i4e>`q*xF^}zDXbqYv0wL-!qp(0GG-J3u>U~wfh*$ zn(H&5wVJp)gyH+mWJ%!`+4L7L7h)gN5nJyrHc-d1Oivf>sQI`5)6~s0>nEC zTF3*zz{rE!?(Vss%xczIy0 z`dPTklu&u_P_G`0P0t&}IbfrhJ2K@ou6oON1Mw&hfe*V5Q-kvS&T;gQ_P4l6mg!tB zU`N@YgC}1WK4sstG9Xx@)RiHa_^_57f8~I`kvMD2mwz;)*zjninFnmt=<)lh4>@kF z?>;PzjHb9w#tR+dfPKoMfI+`CmsdrVK=wDH{XIt{PaDO-Oxz!j-SO|t3@nhsO%gd$ zGOc@~z7pofKg}2)b7*`!s67+nm2`YYRT^mbeNY>$FBYuiDCc%Eq!hIq4`a*+<@eEM z>~~@5YS)fpU}93KtH_+6p2nZw+38S;%@ORARgL$}4VKuFKuBu$yZ_}O7Sp|(*wq2< zdM5lrl9o_32adr z7`)f(eui9~Dvjo$JN8<)@{U~U+stxP7gO$^e>m^-Q!EPj5KSBy~A(`l#0CS z4oc6XZCyQ4xO(+|<1h?P6~{(N_(3!n|<--I0UKNe69o`%VkVqo$hYA1~>%Ni%YjQmK;sD9O#bRnm;!&VX(yXI(y}E z4Oq{FP7hnx4(syBO%IxklMyC;>b&IXPvn_wViTr0B^1w>XTD52_ek~;6V!>%3{yuW zL3C&wf@N2BD4kk?bTRlnBe|{ipCM^ym(#{iyUl_(7*@CE<-5Da9nrHq$SLUc73`1i zO+RA&xJj1q&^dfZ^d2;$LIAoZKmwv~Xe&-O^|DICH4gnHbLR!twtbQ}RevrAz2ZHP z$cRNmgbTRUZVy_SbIH`}@C^Fyox+=L%OuXIHQu>YiC(yCfR3tJxIRPt%l?mFbC$3x! zQ)K00u1N>p&@}FA%Re*7w@lCP$(3bll%pwWdOj3=U3{ey&yRno=Ci! zxoUfx8>th;{8}CdaVQr!kgVvLW23g~_y&Dr`J<8fvv$Fr#_Gi1{Cc5<_x;|E4HXwsE(Kl=<`x3==5p5&VF zIIDFFx=8b7eiX%-r)n<{ABm=xFR9~Ne5SBgAH%FrLulXcOEbQM`uOp)Imsas2VCLN*>roQVm9_pDmU>vXh5bM(zlAE7mGv0!4a zOLB0`TdThf=FXJ7^ZSo!M z*ZYkSU}&6B@-EozrxjDP#7X=evPpg9LHlXN=hB8|sRX*J;M32th9o=VIJIQgZ!ucCV+z?{6Qb8J$W&GODaQ=U#K$&& zW-aKIl_~bcw-ksfNApf_$8)_mjqR)YjhkTOm1{;%wja_{l(g-i{!A&yR;^d7RB}sINpu$HTxol0}x=xtQv;aqAx&uoIXO=#HYPl*j zMY_;`%O;JFO3$haOWP|rKSi9jK;3~`|4Jb>MALE}D~jAjVZhMBLyDk&d~Vmkn^|+P z4&R|Bu%V~wA*3MQ{M-~&>~i9oqE2ciRK>J$d$kLMox#)l+dMrwt(vr}llfL&y;z-K z@2=uW8CO9j=iEBmz?MUnT3pp>W~BHCyarSSC<}7k!Mbkmx5ceBmFgOc>Jdxk?Tz6d ziH#gp1m>5Q#DA2ENsU@$I*0Sjev0>3MYC5K@J^aFt2g(3n{3UK=*?IuLPfR4gd#Mk zw^`Swz+|tny*(Pe9seh;eJ%-jED5*|54hh+RDRv0eBA_YGbALW0*b$@tA&_@&$$B7 z@7#?mM1#cn;%9u+QdIFcEKk=l9;Inz9+PqPk07~gK$Rm^N!xP;k|Ikge_V^Pw2r?I z>*pR?w&LXL4H?%Z`(|~Ij*vJWfnlGzbdl>_qf%-T9F8*b#3e9WACw&fP`_%r7}YK6ik- zwgXrzu~{cPPi%!s2?BxPJQzQkS=rrCtdWWn%<$33f}yiIJXFMC#``ADHNN zzegw}D(TxijrB7PcO!lg5ZLk%IY>z^uo92bTWss3CZgqKi7&3)R4wzJ`WMNYeg~!=frRk&uThekF@nzg~y4@R8g=qe{AB zCMsLLC~j~6;N)Vh#nQKX*=!K@<>W+RU>=|t0_C{>`^Wp{(GktMS93V97x;^^?p|Md zQERzUR;j0xD*k)uE)@R9%2E@sZr+zWzr>RZC(anl>5SS-DL*@p5JN4{2IQdr-rhEs zwjVK$sD_w6PFl>|cFkQSp(l*$fv$KGlUc8rs(VOnmRF}g#em_{O&e6Gkl9&Mvx`^S z`imzcRVfq0JU+q&-ugNbcu`?4(aI|vL%L4W%qi0u$XYRtt+a9G4jL!b1do8G9tp=e z-}XbCy`5d2K@ZI#Fe8hIZ9>NM8R?(K`LDcgh}-V+v{Gt5Jq_Y+ zrcgKAL?U!Z$|8zl*G%OcfgmkH=Kg36w+Yx<=<%jw6H7?n^qVCMd*Myk>~QI4pNxZd z&@F9DCz^br>VYqKUewWpR37^;f|{$fm4kknE(SjKpoEX?FT%y(Es%5u*}m3#=}mhS zGHAh#h;=UAJFX-O33O3%_KjlxB|F&SZ@4(rsr;7rrQ<8xkmIf(=CZUNTehF2UdzD1 z>P_6QGifY}F{)@?jc56?3J%A;KOOW)iFJRf1-B-BLjwK-Eqwar>kQbVfd2BU|1-c} z8U(uH$6;mvtN-wUnE}@hz}e^jFluy_X?zJVa5j2Q=BJ4eio-pBGeiY9S_;!Gnjv;} zxdsvX3_Rm|jmA+t9Tdd+?}{}e-iDKoJ12{78n>c%BM7>|2e;t7k_iW*|NTfOKl>UU z@uVF9PhIY9amhXSjoCgrK~v*xM8n_f7^H78PxW3))18|^D!QRSdF_aYcz*f?d}o%f z6SAsJp~D;E)XCfEnoM=P-ny(X6=)&-p7uW)G$8YT8|{34-*Cg7bt8+5^76k6V-mPmz%9u_%oWL-Eu5xi&XIi(QOorMR3@xLzNuGfsbri zLKrv+TatioN8?SogBJm3)!*MujbsuD`%6wO-z@}>rM?D{fb=oYjjY5OBL=D4O>U-o zRMBVVbd|cLhqpJX*`AtlXo#;g_S~`8v0Ei0KL{%Md*R$BJ`LCoM~=tPHumtQ{AL!q z8;G1-LXY$$Q3bKpy}%3$_8&?`%{1n{5l)b_|GFFp<0_x3G5p+v)tsV>0I}l6Uy{?f zfFOwi#QSD?GveZF*39ccPZht>Z(F+RlVgQq&oE3xh3kFowttA7pOGWm|GBs#V<-_y z5D_|n<<#1G#(wJWQ^oObUokiUf_{;4@ zk)GaoG)6V1-_>!YSF%pArt`68VyL=HO)&Ags9cMg#(WesvuV({RI6TbrltlgJHS)* zAXWD98G7J2gR|G%Zo5ysmVo}g*taL(*$CcNnMw5B5Qj}y-T0rj-P924C&;q7!>7ICS)qX)!az{Api0#N^ey34T6 zny6xBZLL4m@kT%VB>Omgf}0)$KTf4Tq4V^S{K0lK#UsTF+8R9xYPFyUxKJ1s#u9|* z0ffMFNCUNPw_-)z3hdfJwgff&=XnT)dp{Z!tgqnjP3Jd-QjZ}?f9R8Sh@gaWUx=Xx zOriQ2;NO=ohP=4t}MoDv~z$tvB@xzi-T|6=s;fU(0N)--e(_WzCYMy zf`iWkgEzm*FUnzcb3i%j2!TA+P=F;@`iW zKL1!lCbdWeer($8qC_93{wht6nN%j!c57wYk4*~=Fl1Quw);`Ej=dpgDT7@#C!=Vy zCii&G6WNsJ5Gyk$PJN;Rd!U_l4JP0Ir?=?iG=oCJ{TGDOystvuAP;7=lF2!>&da1Y zk3G_CpE&8ll!Eyy*`Y9D?1ig|Off*FE6|s@9dl?VFZ$B>lZxU<(oQN^X>EK}$L#=# zzpXupj+ho-K>6E%f>^~7mR7J-*}{POHioNM_vh02TQhrA0i0ovPl|u`_?4N$XY*oB zoA*-13z9k;lw2fHkgqnXWeEZa-Z-IJRf=mL`^Ojm<5R4%=D2+tlb_TyL2oel<)7W@ z8FPcuk9}{mN5sgxz??8)QIPk04l(w8Ml;t!spz3gVV&^y3gBCa4soVmcQ@ z4#HxyI)IuaH^ZUm(uhYvd#k$YZqJb0{WMUOmDVY_wj?SEoW)4F4Wfl$w`P%Am;iZ5 zxVO)o5iX6*{LaG=1(oY!dihwtBNykzJY%6fe#7T)+gZPU)%{`AMS77gMB&ocPBidx zcSoE<0JERLk1=+X?F*v@s&LzRHjAQmpcTbT`EsYaCl${pS{5G2$8ch*p^=$%FdO|W z8Lq=po{Ap9iQX?FB8cuoQFL?!fdLv+ixLT%T%e#EpA}>sm%D$UtLn?(%ZuMQ2KV+z z%M3Z3dNc)-Jr`77Fy)}cCpa~ZJ4tBS{;<2g(%(Q;T(&*JQIxB@ImL{Y*s5$EwGKWf z1>R63dsfO%RUi|enDp-c{(fUahS#hpkgu-67`1^@l~2RIZrY8sp#`nxtJ{O>+HmX8Cb z+Nt^4B!zRLXwe1gjMQv-7F6q}lIIGGoK|XqoPpxJ;o`A zt_xOnpOA#Q*$^!0YB>&m^&U-3VP(ZR+A%@^u(0~-j<5X(&TudOxD1x`!;$_XM2)$) zAw08R7py?(5lhI&^DMR+N>_Zgh~v>|GmnRP^+RL4O@kTqr{X1JkUr!<+dt$}nHRJw zHJL4M$P#x~t)iWRn%^T9P1{WHwkE6E1!C(1(U%qsQfg>IJ!ePXkW~xy1yjhZ`U#~w7tXnSoB%OxHU z8g8#lb;54cp_IgcrK10(uqQ!`90j8OFz71 z{4~_gQ+)J}OV(X?H%_GOREp;uP7^ooBQ>RT#1@0$kH;NR^z8FOD= z`y4jfF?wv%)MTj(jTVAeYqE&6vSi1jj8rX{*0|qlpje{=t?_KSY{e=PuSYrl=> z0<0S~+clxvEu;3=!1G3gfvnEEKUd>ce4_@nl=N0TnHub-(4FOB)0I5xB#%NFIzmp7 z@yJC3Vp~P&3CK0~2j@3~5mI{m{kRH_Ih(>~F1~-nD95e}pyMB6nD|$OEOv97dgwvb z+?Z`%Fv*>D{^BMYmFQ+3&~Wm>I2Aj-2F<)c4OiR9=RzZOiYS`*sl17baJ1vXo-$g? z^Vpx(0r-)^Q$Ju60PF;)KGia!=-IrX$)hw|W4CK{?|=&N6nkEDbp2yv3(2oZ*@5qb zv5VLm6KqFaCUx{#HmZZ+TTkNNr&QyFvjxyz70&7`B5v}XY|x4Q*tT7~rD?*qS9la; zd@6sL)8Fmwc7cpG6RDQCcN)GDh1yOj^h$79AS6HXUhyC!sR)sZ__b+m+;~E z5b%|*yDh72vHZtwSEIzZg(8jRASQyj*2du4d>yPX|#QJ%BsogyE3&;+{`fcyE<=B`I^&$s}Z|Mm#q(AoThC9|;L*CNi=4{hTp!6<6d)*pr#w}hxlH7`^*%`HYF99H#idzPCB zb`sukBsJ=`I5`i~ZG06fG3Q>cqZFC@o!Oxo$jH{4HI|})$;MWNk@u>u&R?1GqHO_a zwn&70y8U?NpqQ+k5~ZWF6#ny-vb7{qDI(UpgPU`P56DGTDhp=}0WZMv-f3>Mb(`DW zOVCFZbBXFmL#K{LLI3X zq#3Nf5E(->s=!jKT0-3XPbv&#)9wr>{(8MB`4#Z`P|LiGj{9%uB?D(+4{paG8@+$; z7*kl&&f4!juzQV=6*?+!HQBl zO5l01{usXyN%D_!%|xY|vQJlcgOiH-o0PXFFzTvG*I~n_Ou9027cBZ^`dBHzQ5|jj@bkxZXNj8Un=`Y2}{0&)pL4--W)VwhxnCF6E)9%5N@HsabYc;dx^d zTT<#9UulLJ3^>BL9;kKa0!E+zoUyg~q|W#i6*ePLVpC;l%PMA0`b|-8XREtVy`o+# zUxpoPW_b}NELaOGOq758eTt+{?Z(}I?^idQp z0?=835Q5wOMQ%vKLauD5B~L-Ys#>}V%w%U#F%q?Y?9KXwvk+!$@-)Xl%W95?o4-y} zwo6sZ;MF{gcQdbdg7-_v{_(9i%}JKOI$J7bYE5gao)btoBmI)VQ8rRq)6&BfjQzsc?^ zu-`SN#7>RqGGJs8k;va2h5sm?L*9D}o|$`HRmd%*r&chz)ci>L^>He8naI|^Y#S4i z{)mBV`Zmsro%4vpiszl;vn;p7LeF<`ykbY~r!MF~xg7hed6$nF+B!$;c z*0uUu{8JFebcXquUi4Rt1bRea%v1=jh6fM2DfH2sUe1?ZPOYVqV;%G<+nao3%~(74 zog3BKGEZb3?m?LpN%TEl$+S6JaZ}sV<4u!BRP4Cz1s*}Oc~XEZEwOCNRrFd=S7NR zvLT{FoyR)h8+x{3(fF~cR{LPoW2g^PpzvFYfS;U9FaAAY-81t}R69RA`q#$;YR<4= zIydxf(>^kNl>83(zx zdsqi1#WLya7dY?rcFoJ{ygoND0@@Wwf zKr7cNG47SP}zq^KT0<8E;G9QKMrdk!Fa=ryGuEKpMzlE>oeri;5h;jq|VM)OW%II{Ab&IdjRa% zsh!V7mD~b9<%%!Wu*tZ7YT$gY`D>!|dw@d_qfOtPy@|~bp=NrRHsb}t>wZB}N5RV-wYr`>S=LW3EPoAkICL;AEwgRUcjTFRc`lH?XmO+ewNsS7nbpX(Pm^)~ zkC^`-AQ^yv0|t<0g5TZ~RY14<)%)fENJm>)S=oD+%;fCFoJxxrln`pHAxNSwX)lgy zDM^-T=*s%X8m|%NBe`i6fu%hcX+rianAo=A!;!?+mLx{q^>}Cl(-~qJ@f~u+X*fNt zpye^iKY1@J>IFkTT9%b`u0yitO}V%XHAf)=V?=MEmayiu&mI_$ZrZW`q*)Sq7RMW6_rk0bT>&;?E-8&fp?oM+`kOhQNvLz1ZMXHkALKOCOYQ0 zt^t4j=aJ<*6UiBG5|RTcmUr)Kr-Oo-h040&09QE6D3pb`0@!)<&Wt=6iOZe=>##;f zRldGU?nCFPxr>6)-NVC4xB}eVBIr`V6&AKVk^1KXmNmNiLiRM%iWNX9&;zavIB=w- zSR-6A6rf<_IZx$u2SqONguMjRdB8Y*_-ao`j@*C%tXP2OWN=ZB@dYwkF%#jgUP|-y z1j!@Bg!%?mtPDI5$jxn&X0XtF5)lhNPgZQMy<*-Ee$#Ni1PXJ&;n5!k>&{1aIB=W3YQTU`&?VBnn!nVhq%8r(ylwjAD12+$CF` z{V$ZCJ6@zZ7Mq7h{|$8+JtSB4wLmQR7xnsGzg+3|{P0{^64zS`T}&!J9z>r8OY<&= zXb2=~L(Y;>laC$N&V7myW)5C7R`Pz_8XZ6TKVJ@pyx7a`8N0`#u8^eI^olxoYOJsm z1AwM%G?Tykv|s)C(4fBl)b4E9DBzHKLfgNs!F=S24BK6#Hh0v1W(u5-g`ws3xJS9+ z(n-|mZk4wX#%?|?i{+@pCL$cMWFN|t$=%xYh!)|ohw*yxKVASkVItu5`ae@tUirU= z-vBD*|2z-{O}X(sw4zuX2xZfDTG;7>IPl%HN^tTt6O2D;PLB6kQ;T9!M(=XhJYsND zQr9Or5N&s3+!bT^9c%K&FqcCIl_gh5g01PVM^K;Xz zW4FuZ-xfC!v5L)IXk6U!cLNpIR(%-zB*f@8;G>wTdAu5B6MC`<%D;&{p4^_WOqidN zO4bcj4ZJK&a{ENPVOsd*o~z&fd*xBKE|RMPW;3HGdbyQ&I!B9{9H`PdcuL>GZ(dy% zn5BvRBu=;Q{-D><(*Rcx5rK_ZF5g9v*as^aanSv`Wq+Z}_(q$sDaQ>uRwsbk@i)9j ziKT^9=i38WHbDH6IM+K|^YeKcgo$7(mgRD1`|NP}Q-dtHMB%Nv`EW7?VFp-_4!A^3 z3%uHMM8=;KDfb!dHDci@BCB?(DuZT1S5hgh5hb_%+jlC!U3(%3;&_m~_;jTe6`b#W;0n1fEJ8fGRc zJ({a(^=X{Nw8#`{MZu%S>NbkO@j)QFk@Gt5la00e5d+<9J!ZDnChu)v37joSc2eSm z08-b@MCH}idqyh}>%GKrxuja*LBwv$b5(W**LW zrl8C1ct{=zZ6G{_Rd0yswxrx^=rN}u`^($joU_7)C2YR=edTy!P8KV+#-a0tV15oj z4bQJ0Jl;~|@Bg2734kLw?vImmva8BaGU*ho@suLbBe>>_S5luambr`TCetiNij{Lt zF-fN!IFui7z^UMO2o$=41{KbB;f zCB#wCSwio&sj@G^-p41!2g5J=jW8uYiV%u0CcG7Nt?#wZKff{*NV}23E`7A3x#W5V ze~~^fe@EHz)ZZV<7lGQ$O{CWJK0~S@g-e^uVPgXSQ@%csxqWTl3S%`kJYP1Qf}>Fy zxLu7X@+TB%9%gfzH8q=AM<{jHA%cKZ+$X%nK(mc{lhp8Q&PFZ~V67Y4WWyeSNEv3= z-Ae(Ix-Z_=YWwEnT}TbsbALXL6)Y;ZC|LMH4T>c3A4ssa~wcM18 zvX2&t{Q7$-(hT+2&y#!?EPvBABIIq~)`Eh9nBe6*hr6CY9#N4lgA}X?J1;U*5pk2# zy|K*T+e*iKZeJ(U;FfzJXCh0~<<-f@$A=492oG_CmCbsmh9``C-<6)oQNkuU8;t}8 z@DwC>XgUQOe84i&vM&wLey2fe7g_(4Bx%$F%)Ys&@FNh#b2YsU+Q7^Ul#(>5`iALA^zP3U6fjcL}^&Y~+SkIEzOq~6> zan7l!Wf5-W+d_w>&o9K^Kxx6a&c<2P9+J5W$hm=6{O;#@!EgP}j@Vafj|uXHPaXOx z0;e-NdN)7lZafLZmn@-?ci)75cBU zrh|66%>v{(iNV%J@f;G_BsHJmgASW*-y(NiksA6hpL-GKWjX3chKIX%K4dpXja+|%A8ek^E4HJ_LFlz$1o0GF#jxoNuSxHd6VJ6Q!-V)e%Q!^x>K@fb=p=a?kHwSo<@tFjLD|_6Oo}0_E1+y z^$!UGZ0q2hAms_Ey$pZe&HA8g&Mx>9YqDLFHQ9Dewr$sBTaz)_wr$(C?V336`L5r3&p*&wea?BX@4c^04NXV;VFfQ* zpJ6REhV4j%i5izO<#*RKH>$WINZw*jdzyR#?+0luGMZfC;N;Z5q0|k8%x+ssAsOc` zv5L+Ix!+B_yznml=lcUZ!wxcSCA!Ut{kvp9Xm!9jlh%H?8Wb5S67LUZ0~d(wY%po= z-#58LOngsV_7)eWl25jWrs~Bw+hb!=d}-wvwr-h+S$~Ru1p>=yXydQ{lS7i)0k^F2MT&r6nG|{J}^k?yEG|hcn%L2QbNoy*;&e2}LsJ6Z5UiF)wo*(6%UgZkn?*D-JqUp2p(!E-TZCtIqynL%n zuc4juvU!%dtq+DB3Q5)N5$Zo8lDwn(f0bUfXDv}BL3N>Ox?q`pj9)CGQxlag>^kFI zv;j4pz}wT9)UIKguBB<2L|xCW5ysLDOxrowlvzelaDSlS?EHnhrAQtyM%>60ubnh| zT_eL!y{NGT0p7A*HnMY#SFL-?q z+I2`9IdgD5I@7jGUJa6)eh<8V=lY+tGYLxE@Rdm~i-|Va&Ysb8W`=p%k4R;@YfpUY z!!COYKP**ihdsIR=VsT01O%#=!her2%1bTG!G2HZ{Pm%)dHQr%9_7}7I0atb;#8F1 zAl!U`t*D?pF-hUpMrzmeS8={0DWKnPx)}x<7%B(=Dd2^l0%Aq?z(%Tv{~s6`P=wbu zHozN6N!-3B+Duc6aQW6D|J?Dc{9uW=XIal}NVf@6L;$0S(^6DT#w8zj3$ndTYLjX| z2y6_I&#D1=_Vo1_%w#i8FWuriraC&MU#u`R_=rBkIZ7rg(;<-h{tpbc|CH4VcJKRC z9-c0JveaBFva~*8p@>1&uJOpg=?g$bkxszaN&ziI!#qr_FI}Ebfa)D*@bnsq;DLfz z_kQ?N|Go28VzG-V!Jb#jZ+BI(9$a(uqd4=F<3|gd*%)l-5m~JQg@xe7Z9`@naS+FM zhqUQ*q0ocXG%GVH)`AIJ)#Jem3el3dkJ)jXG9zU$UDyVMLC`-ah`q@sP!Tm_6gc0L zme|aLgC$OgD&XahWb;lR_;`4nZ8Yt9)Hz?`G=*u07Z#Mwi-9l#U_}`|*u5i(9Vkue z8cbO1?aS&q-(whL_dm9J)|SM}BCkbpz4%4aH*QH6ptW~EV>~{wOHdfRnAKY*)rWN5 zle)LRC>=PT1)*X{cl=um#ETTjE&LkR{7DKeiJ0IC%iKx#vMJIBYW~3IFaPchhVP`k zc)s84J_2E7{2TCw{cV-8cx%D|| z(kkGpJZ-^aRW zlug!>`#)cI3w4$H0kQxpKZF7mg`9C3T?h!c=+)FoX-YrMM3}O zz!w$Hm>bpL^p(4oN&P2omZWYO3B5l^&}(lpj&vA00$P+=%+fdH%9uLKavQ*ayq20^ zR&80zM@QWvGa)D4yOvT+T@O+PBI^8qIbDj-vM5EAcq%u7MYl7#vrg7K9eT*rmUm#G=k5wObx3J0OO5cxL6_yc`^E0SJ%}F!=?R&lTpQ&rWv}z?mj4 z3jmmBO*SHse#P-8ET~Hrmdag_BIU)l@?3x(`QG{j=i`4?h?q91*hohOxJ^&DG_9=D zi$gZGwM9tUYL2H+C4WERUp;YQ?nsRxCm7IVuufb7-HNRi<_+vI3QUShG2bOV)OfBN zIkdN(=7uh$T6NI1F<1RYiy=#A@!mY3R~0D1oeMgEC@j4r+>|;@ zYh@727f-x1Zn3;vm&EKV*J&`R^mON%v{6Pn!U5rUE;I2)M44O_UjB11@I)U#JQ%F8 zc3lKHkel$8YXXC4`be!KnF-Y3qR5N7Ro>jSp~daSp=<#^`M$DwG>i^w1V|koR)%un zje0X&j$Cvp3bY8b;-AxyJu}$EAzf9(-B`8Ztm1pgK-+qgZ>ukb0ac>A6?gnvJ#8i& z4f&q@zp2=Hb!tt{nSvCo^S=g$TDv585E`0h6c_pgw94(E)qZi(doIlxfSPX zFxyR&x#jPaYNWxMF#qaSC-ZPDS`XqZ7&jgL!4~ZYqzNm35=K&uNf7x!Aj^nm5CL;p z3#(y{{e*DIQF}yPm2Nugr~UoFhFl%@4JbQ5d6YIUOz`^oXx{$)c~V?%s7eF=T|rV@ zr7KVn+l_J8357v!7A|~YKC*R;mZBMHD9>6X>f4g9&@uLcspjA?Cm0BduhfDXZo@mE zV*wt$9cBuG9C{4Y2IG*RdZ{3^{3v53QK*d3{2vhD)kTV?B8YgZ?dh3GqWaZ==$d7v zDcNLLHhGP`Y9nTb;L-zATJ>|Lm}J=>-#D%}E_LeMrIh=M@u37|xM^)xk z%JhiZWCu57UjS|aP_zT89TqzIp|+8atjx^;S|C7v-)sXch9GM6W~cUv8MvW3IRsS+ zebqDawstC^Rz0a7-SKuV5}&YTgzz;F(#u!L!P)>F4L)r4-D&NlLP%~rBAp5&z981D zciA#_VkxExIJNXU*Z$(GUR~&-sr9j9yT#QrpymheM_W{?DHlKr0R%F@+ApD(+D?_=5wt`QdFT&FR7>j;IlMeFi7?;PfHMYRcpa)Hd%lZdEK8~7-oN{ICIEb`t49#tu?f&3=H|>Pdw4C4!U8FFLe;&RB(k-Vj#rhscKK8LzPl0VX>7a(T zr?dwm4KL*Kap&dmTj`=Iq~Ka4=!yrx|YrU_A4EWMN-QrY{tx*L~V-S zGx`@NS_N~a#aooXdWHScS&2~9WQWH1uNJ8uhLklFT}m;$@m4~Nw$hA;VlR6Mw`R71 zBDj<&Bh^HHXjvX#U84^CH+SE{gS`=7C^M~4)nb%qq%Q=l%b2Js7b3Q)ZTy96LD6Wzt$=M6v(djACCm4VN%VLzaOtvW_4cco_u2+>&LVA-5XcY5*TFjVo`F<-i1o z#=(P-T;awsO7$k1BPCPK2zRA*>YNt956K6W^YO<7*JIN5&wB}denX~XpVNk{KIJq$~|O2sAn$aZP2JWuHc(BD9V=Bf$1G>P6BqNlrixCDKN z(n%P=r(364ro=bw+&DX{DUf+^XNkyTVH%T)KWiwdc2YBsenVYO+|I@=CCt2# z+wRvOBX4&o{KkshrLN9z5G(GqtXQsk*_+wqSeQQ~eML3Plw=XwHvh)2PCjAu1#p@G zF!_H}O@K1dM7;m*!TgH66B&#bi_s;qur@uJ@K9Emdu~PjhC02${3C-rkAo(jRV7&R z;3O&v_z^}|I(Cy8*=EyfkWKH{H<$1f|EgzR(sdG~Z;tC!j9)ll^`6%7%8J&wQMNSC}!Hncz3!_HyQ zsiP^pm-vntWhH4xtEpn=t8kjb5@>w@aip&azgNb8Pd#7iCu$~4O}meKG&f)fiYxkhZi*b4D}ylKSc`Pu8+bLw4=>aPfY*I$l_;v~fVln_3?K9Xk~j5hVoh)B-`rPM}Jq*_7p&>Yz^!eHMK-URogx;-{2(0q#$TP8uD9wPJ1| z3|k&$8wxrWD&M|_;(aIEhn7Lr^V`6`#Z=RkmR&2w>!^6p4M^8`GFiq1Ny}#774j1T zY9XZ*EsK&2pwdle^Sb{r4F++_2K0M;>CfyvXn)b8Qy}!wC!ihrChdSm&h_SJe$36q z-$+q)w6^BPzaCHFt>P~~gVh|%u=&}1EsRe37-++iBHNuAdf+r&!ph*d3cI6juOFhdu6WGrnp9|x=BQV@T4@}C+Oy33fr}MdDKwTX zN@88~{2S*Fp0GWkbFrX2o3L5q=WcheT>n>Nv2Veb6HUV;JaX$b3s!BfOIVH1W4@RS z#Cofj!JsEAc<8dSQA8x-i?_A4wVz+k0>nC~{ zsumrBW+fS!t!-l7aXLvKJC#~R%V(@CTZv+*@-zmK&i|Hj72!_xtj8Un_hjOmTj zx54&rR|I5oDlmks=q8c-&VDc`wSwe_u*XUyOTLWK7P=C zB)~>kMfdB>K9tT_e!%pCjYSWW%-TV8F5l5EKR2d|~cjqk;f|NK=eDE^RzfYt(eoS5NoZ1E|3NiEOS<@)b zKt7#iFYU# zh(61^SOGERb~i-sQ0(#{*r>qgyYknI;EYbW%9)#b6o!@#iIoSJPLH@-w676>kC3vNQ{}=AqGi*djF5c*)N`<5T)csA7s#bHa4( z@6!~$mu;yxMvm2;y(Gb@YSdo8o@!K_{%nC!+U5Gh(}DC{3+?=J&Rii{d_q-P%>G{v z92#2p+w_$`Z&~d(@xN!60K8HUK(DkuJ?~Pi{%@%KUrXSx8zcFeE(24!`tmOV$N0d)4>0?whR&ixwT(?9Rc=`r0Z#^m!~mx+ycpggV)#mO{$Q z+wED7A7Aq`HHXGs?F1tP&U$CmbzViFz6mV#E1Wm64%5Y9r7Az(LR>}6{{mN$H zg!URs<9t<;2^PD3?%3q|Z6>5*a-A0-ji?}|9dTydJOGpd{jd8}ghGIy2s~=lOY0d; zd%d3RPaH(_!c=gABghj&`jUoeL0yil1yN#b8QIYeQ z4l&)ni>aZyvxH9(l3@B^O-Tm*M98rOqiqBl4z?PJd$!ZmL8b|QL4kMN+rnr^qmhfX z#jsJ&E)p(`P}+2(8B&wC;IcO6DJE9_k1#~k9WY|LkX2H=~UTU z^)aqP-%}}#l+?&F0*S6;5Lxp}Hv2b9mZ3g;cD*mmI&UCwp{!&QQvtr$T|29CyHnlR zDXXZlpincmLYWQzGtt_#vest(o!TELtj6KLW(@zyr&P&-L@io8_a~1^DmBy~q5`G? z6^WoWV=`CmozbYUej1v-81H0*rDxTWJkxOWw1pFO*&W4S4R7<4kk-=jl|1xO-h7dU z*AOYek4kbXh45V8=m?@EDDU$h5I|^SKvy4|ryA$tPIar%;)t#>3B*&%$g8L7FRLC7 ztqLsKE_F6RlVT@ys3Vq~YW|G7nj9|*CSOi4_6**tWYd98-N>u;KBpS#bEXXd%`f)W z)-v@195JotWPYWg`aR-(_OZIZgI&eWAqj?7Yov<$S z>ny)qoo~F{{8o@UvHZJ<8vj-k`huougXgr*rfB`lv1Uh6sQlaOaI>4L1JUmWB)Wu# z!y~wu7McT3pbEjin(lCt{nqQ6db@iZ)trH+B7s1G+V_8GZ$L!!t(yDt)dM_N|Me*Y z_6I<(0WOEN9UU@GWJ$y}q6K<&zsu{;`3%3iF+^k=TKhgp{3(`HLSg;3ay$70@m$c+ zd8$uk|Kt*B0+!^rXJyL2)tVig?dRBN6z?d8ngd|J>_q~e2q01ptc_^(?K*Z{wWth-smf8+S$w66Po z(3yBY41zl1*6~UZ7+rb<{|;UEV#} zUmSu&I5JgI`=8nsFhNpNpZxSfw>j_+c$pJErt#oFSw$QYQ!chZiL%xALYu%-f5?f+ zU{Hq@1%9P&K^~oW{oKqz@2zH7N{xnMv8C6CRT#ib&ruK%$yL5P2a*T#sc{s)+}wr} z7$}YSs1YNdjOAf2YynDZ3AI-&+ay*UJ+o|F@)Fjk<8nvET#}6k?f!7UC}AFS@4idY zB&QlQ2NSg~j*kDjMmQW3Qa#D)8o-7r%34Gn;PIQ+RDW-s&O%JQW~MzqsGj~q&U5`S zJuOevRpO6U25E&i`H41A>C32>z=w+bhj5Sp;gBr&T|Q5t5)k z+x9*KG8n+n4R{bfQSsq7uNf)cHuRKyi$Mw#6m9hH9%ttx@W-pwF~##7endnO{=Ewf#5z7 zj457EgSd(;q@SF%`^R6$t6LM1q++)4kgJPvG)u0z{pCT^+n|(EmY4V+6AGwm9>3{* zRD*EU;K_P)ly_yxXrAYm>q4Y`nqWp`(6ysGbvvHvO+8%x2LNcid{$}%POSmnE*Xv^#DjdS`6r6ITPCTAy;ZKp zXoPTzJY!0`=<@ob$_@Pw#h1#lILQE7iBC)9hV#ExN85^hBuEt8%9q{|aIy=OKfGv% zft$7NgSam*6hi6*cfH;D{Z)mf)x;mx#Wn%o7?;j3&3yJ|DIVNS@a}|`32j8JJJBNN zFzyJ@yfr^fVsK4y8;IocC;>`1+oET3wOHKI1eK0AI)1it zp+0mXM`%JHr3vZm+zF`g!6ivH(jT!bLHnSCk>>x2D&$25j12blDc(vHpZ}#DCkMw^ zT@>u7NTW)*6O65OIl!Tjee@tae(Jvy*|u$L81N~t!Z>VPI(BfqNn}AOfc2P}o0ouz zABiO_=BFO2?#+~vqIv}z-2>fe7WDw2R#2o`hEWg%-hU{U61`>Xc=q|3J#yVQ1PHg} z>bU^^?Goo5cW(s@ok(t(<%vK!E$)(}YAxZpt!shtn20<%$Jw{1}YN0U6%W@XaBx=nUBt`@ypu=uJ~% z0T1C$n@T9+n7pZj=gF5)94V$Xio_}`^h>;M07Mjo`mY}PIj`wg;^`i#CC$w&tNp}{ zq%n2Ns2hxI7_;}FOeF_IF+(K<@YmVFJ zbt%h4FC_?vpWlYop?hCShR@#$^k?iFt3F7$tuYXEQ%n!+zmDzKqparIGje8+(TMQS`QafiHtl{V*+it+B7gj_$YsU8Pq6 z=>O7JD!Xo?t3pZE>;m4c)`a8cT)i6EigM!_SFa-D{YUksIWa!MIQT`uuwD*V^g69#blD2zu=f1V5xESx zVfv^2=;zKUMKz}HoP{AITio#*SuB5lbPi0sEfWwD0&wwrKsE=dTmnf*J{yztXL(U} z%ooNaxKQqO{PnA46GwPKA1 z=0oTkX`V^%rZ`u(%#jWT1!bqMH?7Qtk=ffJ@1h8{5YNa%` z2wOE|feUm&b6hNt&IMK>wH2rajfOq^}+H+ zSP87abo$yeR+xA;kLi_{J4M9tC-T(i9B6@n=F^)%R5EY20VGvP(>$Xf&UjLb`Z8cra#)a`oKVhdM)O*RUW5~|r|~&GjThS{3Ge;@>osI!gPd?Z z{|ELhdsJhQwN`H3DTuFu=T&%I%%2}PjB;_2#8S15kJ#GV2NihPc@(RCD6J1+O9uG; zX8{0m-#Q}dH&;y!4G(~D1dx;tm`Z(}RgqP&ai%YJdBg&a(EU@Io%6dvppj9qxjeI~ zQeYY}PA#X@&R!VKg!oX#bQvbj5Le_^@_OwEa#O>9Go<=Z6=ov%EuXU@j&`_L`z@J7 z0k&5)32>Ee4n~*oN?awRL+-Ks&ZsHvZ*crF_POI(2y*xW^7m%1I+3y*5k&Ig6hV() zsVJUOSKAMCY?m4zfwh9Xl%)glqBz~%T{(T41bEcj+!nZxtKI%HtHahG= z&f|NvfsW^?d(lX?(Gq3ch!Z8xR=?{(6hU&0WWqm!zU&}vMkvvc7?9F*~#exHYa&*tcI&1{C1V+wg)=_6>>xSHm%*{PuE1q@V zU3MK1?y6gF`TO0!6q@m>)JDw?MrQPQ1V~r$eZPiHts7*Xg-F;y!ngp2HC=xH_-)gi zl9C*g3ckB*32M%uFq84sxCT^S;ICTr%-y@4D&a^-MG+EBA-63_CoEA($s`i~w1a+? z19P+e(HgoES@-N}^2`OcW~%{(f{gA_PtksZgahL;j^LVpr)zK?k@*%wyy@YcF@xO_ zpo5|OoeT7DQ0L^okYe2f^miP2^kys#kfbJPt(XQ;0H%nNOUjM69u+ne;4K_j=lUA z##hpg#PMJG`tsuooDBH?djZzNH94+h$D)sT_GRwg31={oo3Q8 z|H;+!r7)zo|MaPp*Vc;Llky{2e>bKoV_(gJKKo{rO+vJaJA8;-kI{W;)wlt13<1em zau8s^H9k03ZP+f0H)vTNluUZUH-4jx2G^Kpg-jTsO<$VlN&ob>Z?Pqv5~1< z=7;(9B1Y{8>~;jFa5~7~zwnz72uywC7&h*zU8-M=wroSwUr;ZC0`Ot;aJeIeGGG|& zF>(>f_N|{jT?f{$Tu`g-N(Q2f^v9$%RtO^%5G=Y&Blki!#P|&2Kq=5Ifxn5VtEt^L z5UOfWs_)#!8^k+kLBSGt{aaJ)BE_l6GmToV$RcFTBQd*PCZ$CL^qvJ@41(A6+QuCn zXeR|sKyI8;54FiC-gOrEKOL@YHds26wAb*vGgK3|ge_nU7@pNLS1R1{RP*Nv{Y&8P z;8Llk$Rzu|nyQ`SOqk$ICCmDYBZPh;lED7Tp^C0Q)$=!QPU4$R-T^)@;20<=ZOMlu z6m1;)%C9-Rt-+7AN7E9D0&Wup%yvBVxM6eW!JZGrn}ds)j`zn3&jwN4u6KH7`t5#H zCYvO8TIa0C;y1+Dh$F6`UmT{hQ_$dFO0DO?YHR9gGgCg}F7l4cS1TORRV-jemaov` zcozAnZa}*=VuvA(0=%*IUpLvj=%(4b9f+3ZC!MwECe<-(8rS5*U{KuEs)tR`Y-LO zgd&{VK*ybbis@drD~rW!`qf?Snsxmc0Ujz)^o8&J6kPR^FO#1xJ~l+~gi=~=9e}qG zKJr}+q%G?XRUCT=EFiiUT__$Rrv^xI|WipHE1hmgcT&%Q3UM)AHz5iiCyC>=% ze6!OHW|cr(V5I#?aPfVfHS}Quk+fYaAs|^L-GZTnP>^rMLMB%Uxq5N91SkBUYiSFM zl{M_pUZ~7U+t51Zh-TbRSM6gs)u5#<@dB~9T%;*h=rMvZey}WEq$(Y%ax={J=r;9i z0XZG!T?9mR2Raa;rGtne;wfx+@ykJ_j0Bl+|o3h8o`-~b~`F-v#{%x4b|2NOfAbG`KCxSL|U z>tSfPTo_A%Qr=)!;z`Il19=exeSX~TG_!BK`lTZL`fc+TPTEy>7%=6v!AXfLE+H@R zW26)#ZMDL|jii;lv|>LWV7FPBBBkPQ8((30(3NbHkNt(&IXEnh&e$#knXl`jac&`i zNqD4&D$=AHrgIaJ(kOow)&~;DkRlNJ2G$w3x6Q5vgs^$s*MO-87z;A$ck^;`qTDZ> zqNK^9h!(LMG~M%L3jN5QunrPsx2c7ZPC5E;aCUwGGP1xM_X=bPkVqt{uicbJ+*=82 z@XMSq2>6Vd8NXEsCxzWgN{aqV+rbLf+J>thQ{Tr!EaQ1sB9^mj&#sc0qzG}<>+$vR z_C`<{RH+%b@5~qlBmPrs(VYqkEt(1y7=V^2kP7Jamvcmw4lKhlyd-l9dSSR+D(RN0$xfkcQZKz^Z_ z#6{s?^r+r~vE}9RGP*h~jWOdztLP=H^ZaB1bL-wMQzz#6EpC}?bh})0+#$Ql@(Ey% zNb{6Vnd(=A7Q7%NeF&;p$ci%T+>E?v*B1Gb{kV8Jz50tpUn@YS@K<`opY6Ey?w8-o zFZ%4%326;XSeeTYZjD7no`3d2M3!Vrk@f8l`s*_|Dm6&it3(phZ8RxBl+)g_44p5c+~EFA=^;I3bG|B$>NRn#54X4v_QAqsZO-+N$jg2iPd!D) zmMGGAdQ50hfy}_AX#?u5T*3bx8vE<6d5>qnjss{cPUbwy94jPGxEVU|_H_I%rC6EJ z?c_5V6(~*m<7almugh=@>#EVvWO{w@aM%`sn}5aZ3zz!lJ{!|#o1j*LIYhMs&Hs3qmeRyy5^H55pd0QJm40qZQ8j?-#);5Z`+yNy)2X*P0(*H@}_H($ZeJb=024_r-6s zGH}7-dYkSlT5mP-@~IVAi&%2 zbn|g@J2~DvN*x}uJDCFrIb{cWs4OoCOgy3(?HF*4Nb^Ee=`&G9{vwk2@CZqv{cP_k zBZMeC6raSK6eO0#be$ii)h|GBEc(3vJPFyz2d>!SwJ@$ztwM1?n}G#Vwm*<06$}q` z=lR*KVGTb{hsYH!+Bo_N!$ff``!d+^_PP~Z{mJ}lV}0Ivhcu};f&lu`Og;7 zn@|NsB?;w5m>hz?23}s;4`qXh${5*-V1qdMaGthd@jS9cN*ET>yVw@=a`RnSU&TB9PwA8O5M8``|xJo%7p%W;M?$URP zV%!^ID;xqebMEA z`4?<(>x;}PG`z&v^T8rSb)Z6nT#;s=tLs`fb|Bq2F>kci&pxt!(!27=KFy&Hd`2_l zMViqwC}0|tKIj9=k$DK1?CIBsc0YrvMBmD>)5I!LvY!o@(qt*uW4WPY9*hBdVT=97 z@ld8aT3KT#Gam6fQH=Pf??2$Ig! zS(ehpU-HwW$@mCR2X`8&v|kf0V35;N-7+#;_^o; z`=e-H;Ckoggbz?cE3l7@kHfWqB{S%$dy)&$0iAv5{W8O#D~$Q6L92yCa12-p-mgJJ zTByZgdqp=wO=&oPg81i>zKuAjIjvJyvW^R&&=OMof=UyN^1*yQKc`8QhV?_qTpN7%>eW&ddVXvt@-9-qq-J=GV|C?<CJZow0efK+XA$hu*DLA$8?=9Zc}8^Z82ET@?2eZbvo|zYo_nH;@rF zFH+d-Wx^o|My9T+ykeW+S|Nwh4{D%(4&|w#D)cZ4orgs0{-{sUl zR%>3Z#k(VUYU}Ik|Eqy6QsB*TWS4@|isK{Q@=ochgJa@{mQ+{oN`F95zDTWB4N0Pg zhjPVi!>hP0WE5>*qF;b`N$kjf{jboc=g!@LH9J>F5rq=RL^Dvrb}X=t+2UJr z;>0}nhz^(eIkhtgPW*KVY3Te4tFAmsS6`!4d4Fa#O2vjt@+w746ucxlh(R58>VnFTb>QPrd)p$V0nijQ!O`DmR@(LKpR4g}{0EP4BVCBQ8Ic}GC z`(V>Tz{X>>;Id!~HP>V^y=$v$Gpj0|B3HOh2_NW{Tu$mCWdQHDpL3C!x2I3q!5|&K z#mRCjTowS&T;<9IN=^MhPBYuscbbnO9mR?95S>!hRjgu(WHY6)RaB@a1eQ4N-)!1o z)Fo3_mHSd;gd=1c(rc!UedLUj{rtdIEgr9`_Lf`H!H!dc;Y8>ik!|6cL@5+2f3Qtj znEw=0jBzMT825>)J3wzl-`_P>W?Q)aGe_ELG>PP-K(pAScwD18J=m@~?&TX5t4etQ zE&|jmeXCQGLF~$;D!KD_#b~f^)9Z{iYQeN)8N4->AbU+*36NONdk*1^J3{H5RR@~6 z*_r_kUS|P9zuP-IH-W}yw+`4d)T2UU6sh_A@CoAYpn+vZDYT?KOl(cT4$PasDZNBV zz6p+mo+eKHV@Yp}^nkbI6oV0Fh4`3qqopGE@Klol*MnEk@OymhkYwPUq&_}$AUrDN z3?$cwW@1eSwK2RUc62L?-!$A#8KIdXr+(g)dZ!qzdxA9nbcYuF!HmgtTIbwXcJxVc z!6da~@fPePo6+{lP(s7IUJqXspChErO#E#=CNp^L(88o)#FpY09Z$EV;aP+M6_Y@G z+Vj_^7kNwXX?=7=N}8YPj~avV1+vVU6C~ne0t*`dmC@IxMDkCySY9~I(|}1!)0Xvl z;#>I=JnPGosMaOW|t{2jc+M(%?xwI(**xHsAQdz>kCH=*k%;X8XJTKKcCmxj0@-@OOYQ~PT|yD_dO+&=?>Hc&j?m@JZOQ%a(;y1fY_g(2jP`@1;?JC&5-RGZmQ z`gvZ)y@*V`6|?Z_+blSL9@T|6i*6ZO{qRQ#YhK}r@o;9d+op~e0%;el^;BGva_=T;UmEA-o9m5vLMwv zDke#t0AV>_Ik_rXI3F_BBS4OzK(k}p}fatpw^YNigE9btO%ky68=k#>w>%1q75 z)o@+vTq_q>RI(DeS1-Rk_=%b?&xiTSMVBx^30ashcNUFj^s1$cVP~D6L}2rq%Y36? ztH70-M3MnvLk+fS60%m9^_W-MZrz0Cn>RWbu={!g${pY%42HM1L`-vP_^wQh!8eVf zvSh^Mc*L_hK^^ey^kHb8sMu0LqJ(EX`6wk_R3|7msf>#F;V0vip+~jlWT? zqDhP10g;Ju85sus4x)630kVantu!??wcn7JWfhGVosx-jL4m9m5R&iQWn<_WWTRr8 zzlYT6^mYtYXsz-VJ^9Lq#SJ8nR#K_T2R9NO%(htV84M}?{0bLWLB-2c3qV5ItC}iL zi_7RF`G=LD%Z=$gutmKVB4?J<0JC+83ZTQ9pv=LYpc4Wp;G{Mam4tG44_s&_e}v4) zwFx4rJ90Psz;suhcj6n066P;+@(gl~)fsT7L9JHEcv%iz4xc~_0@;DR!il$FRQTA$ zZu@@HUhR+e>&!RqwwvOGvgLaxsEBHEJfxmPXOr*;e)Bve>jY#}kfx;FDsL)zU8b-T zoTAmC&EZ$3$4N;US^HkTHUnLq-UEtUBgJHL^U0<*7!*{)M_C2+z;vN+@7!K`(uE&umW3(7FL?#?=+@n?LCG6uV>y`}Q{lgvaN^j2!eC z005)Ophxd+`g2=c(u_Mpb}v zlYH2hI7}G#weL0kilbwvkg=H=474$uK^{t!CYj>^_;UE?^jE?6%;X3Q#qxZOkAk^y zCAs-}uc<#Hl`;g?&!n5A{G;o1)QL(MX=sIeu}zuBFBKIPk}XMY(yPT_ci$%b6P=O+ z6a%|FMJiZ$USY3K&|&!QVc=&uSTc)`*H8br8oYU;Z+A)Q6hTJLxA|9FHEFeMh%t@o zCfM#t%bYXxu?w)~1das9-c++z5TvRJ(N3gZOr>=9V#1Gg^c7HB9iZ=9KC9?H{r>5c z*;sRaK3av(AypLr#ZoS*v@A-}*Z+{ARPE``)BoX1AybXeM&j6qP>qm@$|Sst91t=<54M+xU!lN;Dj5d^Nw%0PIX$Q1Jpa zdGR7kD*=dgFDS+}g_)IW>N!R?QXjjkpXEY&(7F3Rur?GhhbrMgg*MAc9c^u8Cz-ew zSRsv2bD+AJA0MeIf5CL;9z)wF(r~LDR$2O=PWyb)E@=@n;$$U$YM%s1yhBK?fa>an zL)@L3R@#`JN(>B2LFsHqxlWQZNs#|~qfNzVf(*RMcXLZi3GR{?lu>(CRrKLXL7R64 zJFQ;xsEtxc(qpSR$Tc{HCD}JsJe3dvO?NOs^2{^-GIYiG;ywXBi)hsUqv;yh^Xj5( zY+H?OH@0otwwuOI8r!z*G`4LtXxP}8`^`Lae?fBZd-mCT?S&m(RH98-0c|oBqy!BA z8{x4p^;a7l#p2#Euj!0PQ<_YT1SK4S($n-=Qr=zetl`oASmp^(bysy?Y(-a%1P|qE zM)yTR(3kno+CfDZH1>YZO|*^LA3W*JeLvqGpP#vspixwOETZb0VdTn;P}#E#h_m## zoi~qF9~}w!g_RnUnPu2$IQmD`aG6$jI;-K}EtnOd12DKdccN}4{Bj1ExT4!__M@RI zpYsX2-zI|wcd;#PFyQY{SDK6~ ztzM7#8|eO)QcDnMt(rp*!(^;zddsGj1$n7R)w?WvbFLpeVqub5RWV17(MHoL{&`Hs ziYn0&IUM|k0HrS|2nR`(fEsYsA#5f?rVm2@0I3BzvvuQNu2OwbtId;<6g1RjRb*iK;Sn#jq zL8t;vH7N+h0&4#r&C<+#GLLWWUi6st8Ny)l{iJtrDGvZ88LQ=F(0U;9%DFo;yqC8X zlw=VqGHQ*3PeK3$A{6+TVe(T5S8JSfgfBHQKBePfHE>b-4@pB{S(^r2Zk@VaAEIGP zJr?qAi+qcrr|PPyu4Z=1=sWC^%~PJQAnKqe&mpMeC{==EkUB%cWKxnDk&GZ_7U?IB z=Wzo!YR!kEtM%PHe2?-(A$idxf*xWiJHKsBSK$^-g>meHxvg%Z=SOT1m;HhRSDqPT z#6byCD&4Xp2-nO+*yM|Uv-_;Lp7ygrTd78cGs)!RA~_xq)T9A#-v?H~WoY4Go9n`D z>;HuD>f!`OSz=nVYex8sCsW4Jx@kEhau{&i)u(!utR$6r)zkT$u@@AYE0M$q>4~qi6zz3S|X`X3n+?bvLx$mGBS2(ugat zo1vu)tYK5kq%OB!(WV2tt?<=v#@PH?+|W6b8D!dxU-qsIyZ;o+RLl6U6`K#mJ5}>$ z2H5;fUyLb8-nc9$u^3OEKy0t%Cp*a;|9W5+P{@(Gg^J1HG^E$4&26&fXtmmRj-Q|H zxD{tv2r!}_T!F!U9FSKV4pCl|4&U_=Y7IX%|E?M!V`IputQv$v524k{?g$y#hR9Vee0=>!O@z{CKX)|27`Q?ZNoTI#x<0@+dx|le)*%2|C0&edY z?^gLNlb-_#AwHr|D5HWDJ}rksY1&2;;P7q>4!S<2Sih7SNVqjN)}kBEbhpkQpn`>2 z8aoZ@{_7$(?U})>PiABkvqZGHC(YC4R(g~QrbH5p!bi``{g&yyI^7e(L@ zM9gS^R*OZKd%eg;V)oYX4uG0*r}0p&dk@V8GU-vNgoi#97z>Ky!rezjKW&+1A%}}j z@M--vBDM3U3Cyj;V9>aIfqc1QRQQ$W`WFuK0pK2G4MwapbXuVdB|SDjZ&uXbp5$TWWhi~r)%;>n`V6%y_#50!;>ULG?v(*i z#m!mH?}kn5TL6b(?}XKB_TjNIG@Pv&>hfX0efw>UnNJ%2LjK_Aj%0m9%m?TB*uA#W(Bmmk)yp@=4gpb-U^Lcn9>X_#M1W~CQJ^LKtN3s3?)M~u6?GU6xGa}NG!rp#=1nKuy=a%U-;z=*j{|trvtg5moTt}>rXM3Ba&J&57 z;^Mz`9g$qQ?(JwPkwAv{+1Q|VVfePOy$$&gFWqZ5n%g!{nP{=hd9~*a80NlDv{dw! ztO9iQOqwL-3`vjG`5LMId=(YxWM6(&b{Y~4sMaF=lOfCFm5$yb@aXhe+=_kXdl~)nvx!j;5j@h7peqk! zeHnLzsC1<@Z;-Qxh&5_7Wcf17ikP}o5APx-3<^g^GEHVqT=z^PbbOv<6r>Mx!p#{K zD6DadRI59U0^R9|DvHdq#mJ|%n?TsgG~F`Pa_-rMk3!Z_{2E>c%%Ek&_a`jxOTlLk zn!Qj$8_vjF&hC@tYmz}Jhqr4bj=K~rWusr^#EQ8iUdI{bc9J?;QW(CE-cLTVB8Qe( z;Tr~<8G+fQC-G3d!@UbLk4lxqd>U#yk^n_cNbjcy z2}@F_(qqBZm6mDY!frSI6U`dIi0g00jC*yPg{P)JyIzl)CT&LkBM<9Q`Y{<<+~`Ef zh|DU?UN%ND03~MZVhgsV4Z;jlXb2*|nJ){&0d%66XJgO&Y{nbb{T77GpnR4}OV zQz>+PM@L6n+Y^8~zrYU@1fEr20v>@B|3RoFJoXCm3c4Mk*DGoTgbl|sQyc(ygD)zt^JJjm_O zn^vvUCcNv-VW_h5pwAeMRBkT>BCTa4zC@NA5dJ_;iKn40eK_-Iy%D}SqGngV7Lxw^ zy2y?FX@>VvH$YB@s1Z_lu-^zU@na=GN`njrXhA;um=EcwQ(h^ps<}7brL?s48Vbhi zsS*g%{!+pvwv<1mIg)Nyq*pnpTuBvqdTsHOT_Ww!3n1jOmrzZ)UD|%nMQ!8Vgw~(= zuuIM4Bo|7DA^>j1cL3PQd4QvrE!#MI3x%Wb0NQs=P0bQ!@(e2;;3CfjYb;Y!QX;eG z`KD*CK1hTTiBbRKmKyT)CH7b|$oZ_XsxniK@xM<8NeYFjuI# z>yrBng1aO-#qWV)zCiDl(_Uw%Ez6w(ver<}tg_5xcn74DE=(C38_Q(MB_r4Nqi@ zU^lhQX`aTI$QjGFDsM;Hfz(3vH@2Tp-4!TYIyNSjsYktwmu>1kgqDVK(R}`X@^agA z(PWnS-XB#}yHUKew(Yv+dwKnRD)Y6Pt=G=UILwLBDO?vx>f0oW-kvbG37NH( zxO>_=9=9qt9^X0tTc9uYjo)R=Bx$V znhJ(dD*MVK8r_24U?chFKR%g??MCheo1v_V446M{h^TnF#axWTFDoJnm5GM=h*T8N zlNZm=I4C5Vens;@Y9#QC;!(nj*eLgUHNtk=O?zfDD22jn;jNrGr|Q%|+~2j2@A$Ej zL8Q1*Pii~TFwjK&VC1%hFO47*CS{UG z7Fed+uB&KFFG%gysYzWW_6zrkuHpys7o&)LLx64=2|HlV>b+45ToFh(H-ITMz@o}fD05n@CP=2AwqV0k>oIWT z%qs9NKBbtm=yd}ON+(#zUC!$(2Eq+sOl@tWf6-qj*lA1`XoZ~8D6|Q=3B{x@Xf~p$ zvi8%6MRe=?YFAggvQs@U8-d?@&X*Q0n|FnTd}wiZZs=ollJc1Hti!NslvnJ4qbjq9Uke4V2) z5m6(*u$JJUz6G`;(5-Bsh^=fQ5zWcz$Kg@82o)r+g(N*w6KWrrts<+RPvIg7bB&9X zIaGsLxj7L_4gp#+bd1NCBJE<8)5gs0P=HZf__qmOC0`2rJV>Qs5R;}ka-@@ZnMs~R z6vBhx(`A0zWH~EWV(F-o#vG0Id2R$a?W%ssTsV?YlOa&^R(#h8ZB7@V#x;&?4Ax%w zx+g>KuA2HfnUHekTgC{T@6)<^t(rO`F#=LGuS+0G&h~v{l3QjEEmKNeyh9%N0S`xM zhFCLQuv#j~yyBcKhb9;oqiX8)#uw%ZDU{nZ@>}q)ddGDYt5V;hG9+gt z+`cTghx7jeO1s<1P0u}`e^!uY4@#!C+>%Dq_6R^%%BKak#sBwAg5`y;mU;2}+?Q`& zIygEmGE;?v$c!;aija*Oz}iq2nYmoIre1P$i-1_pJKcz|2fksR*Dszbg*59hTr0^F zu#>yEb-u8`Y73i6e?6R?9nO&oV6j2Ndzi7b73egkPMY;FTcHFyp|QP`m{;1pKy=e5 zEvTz;L%AU!V>*ZvRz?0bhuy!fvr7v4R(>Pb#ot-F0e#&UC47N-lFra za(u2OjU__9*|#7HB9_`A1?!7VNO4P6pZG0qbZrhJNEnBx+84akyU*UKY-4>SjX#;K z^4$P{>C2;<@tZ|Me%wT9PkL1o6S+z~7o3c|~!rN^@~& zr-~EMU-6q5N&=y6~X+N*UL+uH=LzKeIzLCn73ljki(%aaQ3>IczAe_DB6E3 zj~XVmadkxxIRY4QZvj52ik(1k0|2<3;WA#MZIO?V8hIYa?eg!xd|8YtSK*VB?Xq z7;AN{c=CUgL?1@XC`Z6y297i+ zFmk{r5+C6rMxAj4iWz-3tU-j}tUzF^oKv>e4f_$C8zVusha6cR2?>56v|e-$?v|3P z6p(m+e*WhM2SU}9>o-iT@L|H>((rHbgGODzx&@DBPp4dvTi?|3cPq}RE_kIgH=`&bSv=rM(;vKQJ08e?;&`iJ z20NHfZd9;(-gcR#>}wf6CcN>Ss-60tOv&fwOQsyt#&RUb9k188DVH;TK!DSmH(|9riBYEW?&oyz; z@Qdp*dW{|f7a-8N%Be|4_wS)Cc@JmgM>c3SPxk0i8|)7D3IcZ!v$Y}3>TEm%cl4fZ zTS4a;J5#reANcuMu%|un0Am_d`(AUJntsbfYLRi*cxl@&JW7PbCqdwPhBpUgd}Yzf^ac-*EmFMNRFr%DIC(KF6&J7<2GcNs-5U~%0G z#pd;1i8;5JS;;#y2G$dI9P5jhFizZQU5J)K+c_N)R5 zK2HY}NLZ$@HJhj{w`9$*YR;Gjk-f=Q-OsK*eA@5t0Jt(uO+{FkXI2fjfwfYu;=9Fc zN+7nO@m4x`A~f9NCW(0ow!j3k?$EXl!+C~2RA=IsdLR&qfQ1nG36u708HLDfxW@(p z5A7v=P{b_T%P(k3qs0(rPqTmjZ}CZf1{*VZg|D+vq{}o~+tztETa8#8+eHjXW|e6q zFv}?D?xlP26s0A;q`vYc1!$!uAC72>wzRr2(VZV@3{xjJH#UO)?8!CLT4*?N(URPd zG`6_vrFnQM2rj`xnN;9H7NRM04yR0@lrvjj<4J@pwJ%f+??6l#`4B31(*flT(A=A`MDtYMRJaS61Yi7}RqQnG-^cMSFHP$6^ z6L@j!c8!SMW;`F7`!^>B8b6uBQmEkny7m~9?Lzq!esCN1v+t;1a-3|DG{SsIFbU$@ zU6};8j`JBNi8AM4paOn; zEYvA^%EZBa)C5cDKoPxy0`55&k`J_eF?NWy)d~#cdS$wM7VG%HHA&C=qB8{|f%pA{ z=Ju`2Q9I|A$3DN~Uox*!x+)@wb4z9%@}~X$2UOAuFN*leb&>s=3mc3rwQjqf3Ph7i zz+%6|ExnM8@;7Gqt9XSM%Okt(A$!>;14*R!>j}mmus|I@(n*4Mlaym4UG`XU{-in1 ziynrrqU+%eqA99u3s1s}c?0cKbz6~y7MSCKQgigF?$j!0eq}3L0XhW21Wz>@X*UXqWN%kIY!l!I8WA-Ehf;VTziam4o z1n@Ta>};IYs4|~U>IfpvENWCSn7(9n*BGE=o%wd$K~~al6_!sfNNPS~eVRC?+`>-Z zxOw>rF#iPrqGLwQ>N(dsHeFt%tWxb#gG|bVGCuc$>_OHc@gG+eSbDA(aldF69ejXa zz}DBmM4B>wLLI+v0)p(qn)VAFzCa|^N^y83KW0^@Mglj_v|F`%&_{K=q?YZMg4T7# z0G&hvFWI+)A6V~ z_##1fm2e5mw-BPzL1THk71#qgy<4RE(GJ4ST^%3M`9vBE88}|W+cY!? zacWRWi@KX=7jJ;wy?*-+;3%dPa}>Z1AITAt>knPNK?u}98yN(y^(Do%{+d{I)j$m9 z7kv?K-`|KhlWbA}!!1#MI&Rwq?SWka7njlELMgDL&#s&o7%jD1x3zDl=yKF6 zG=Tdg2%->o1q>>VTkc!xJxic$ol;(VOm=+#dR*nst?t`BI_$JZ0_&rVG0s5Hp__NaZfY??#~bslt=7F?OZA8+WfP6@-5%BvJ-oQmfB|6pfe zp0;4g341qMkF(KFwkmo!+(9Lt=F!pH^=XCdS4cU=gzu2+;> zM7i7WfA69Ob{28n1mmpq30fg`_D430+Y7wdCvi$jd}vI z+JV?%hqfx$;+XY|RG3uR@6=;fK$rXH#)}zeZ~l{6=CMgw6A<5^-1ZZ}v--Za=xWjh z<+~I~=Y|!9uB3b|F94BWL9if$`%bJG7*a<71r*R;1H>{b4XOZJ^Q<#AKZ;)=TfwbL z3qD2Ht`({5JEt=m`cyqws0yD!-syfQlc|@jp{|r|HJVp3OPEwE6oDBzjI$yY@aohW zqxt&1;Qn*i!B54trJg-NDjDEQ*U~af&j9I}N`!ay`qQ=kyLY98HJ`i;OeHF-b*Qxw zW7O%KX#eAccb!EZ2n!8qy_BkcIgYox`$N~i-Z#L8nGo2-e}23f)QuLpbLKI{cR94d zLym|He3iQA*XE_hj@wPY+#jUSV%Q;3wap-wES7o2zbMrjY@Twy-%WFXJzhf~H9ui6YxWq1agHd&Ma5nCWI{O+> zdyuyB%1XaJ#g<_E)U+DP+ST(40gH8~YygS_Hsy~TG9v?l!ow(IygA)qgp;0b=3rz3j9Gyg5 zn%l}gRzEOzMgFr=RG14#sgW0EfexD`EoapmurxCjMWTlDsMDMk3OCe0g=-xoq2t(!CFx{JjfpJR})MSR>&7 zxuvEUC235q0U(^={uFNNAX@JSfKV!YkVF9yP{8FVK#Q#h#TW6|Yj9zx9y6SC&6_V9 zOcoBaQ`QeycCvwYFq3qCC;;6(zu)`wdXwc^b>=ik~PZcen&n@U7ym7Pf2Ddq(b_HDtW|&46NPlucWdzcW_S6KL zs&QZm4L-f#M$m+x{V&hYrV~FN74NUFqBX}mmcf|+^B~dZ=fAJqMqhjTOTaN$CZ>Ft z%!(batE&s}P5@L+^HztfQYVg+&uT-|jZ({I8lKX@=JHWS$3vv(J{>)c@9$Z(Py>{f z@gb2uxvWA=CuS}kwfDHrk9=jKv5N`Qs=MYS)V#o-!YSzm8qs-KP#^0Baf0cc*^hnXjQd7Eu<$|k~K2NT?lB;2g0v*{V+ zH^tL`hI3>0#%-Aw4j4z9TI2ty-tQC|0XU4^6o3IhXpHW0e%_?I(J;#D4O97#uGhD;S4wmuH$hq*4-G)z z*&?ZR9mal}Z2s&P*KIz=n^8dL2^fgH~nKo9ZsX=7#E5HzA#B3B>NmE5A zmoyIHd{ehO{-!DWxX;W1D#anRU@vFEWsF(h1*OGsh;UF`oPf1$13%QKWpv?Sc3KVb z+V}{&Fv@9}PSl>u8y+asb6_K|i3n=)Qy3WR2ahOtQM`+U0qYNC71 z!!pC1x-&k!;I3^!Ee809LNu_6xFp zIm5+`n*kdupyD8DOltmzC$f(0G^&0FJzJ>GNrX)~jri%OP>P^ZD6vf7g){B+KPGEOc@>Z(43$!8TN!6n{=Cl|)D_=wit#>IiL z2tWkgUjDXF&p0GX=&V%1^|u#~n~@5R4Txew8P0vSzW3T;%L<@jQzLnu=MiXAlLD>5 zW8BwsTrAJ=2f%Wd^lMwUyZZO9sO&en?yrD3X%;0kXL-M$sEBn8X+E#Thv}M^++IX) zkF@+X;2guA1)YDA-L>MWRJXC3IpS6;0`)Vwypq>)odtLt6M45q$lSH&}92D(oq&_NMynQw3JN3Eb5Ir%0MDJSqis8f~n*dM1F86}lT#5CL#;r^GC_aUgFs_2G-s}L8NYHP~iv1IaEl%RelLP@R zsQgbIr^;K*om073ZVW^%MBi^|uPI0yHzDE1jbbbZ{L3^zXArK^W&p8QpbF3&uo3$a z@ie@OAn0(`+kE|N z{k?Qz_B7+v$#4!9o=j&J@+$aP>90yocg7!hj1d<^ksV*iri5x~fOHEcccz=%VI5%m z5^te<>Wrl8B#?&;6--N?;gT()p#F%Q3)l;z@(V`bAMBGZCT))WG-7Fg`W3j>o&3Rb zL-JvfQ^pHwJPj#Co(!(OB*2NczM5N^Z`zI7>S^~~_ZvNxt?Wx=ML9=pRM9+yeAiFM z=R;75GV?MkXf;{>c%nQ?-otC1^@aRKX#bFBQ6^rhO44(4myNU zB2XmMzFDMYw%C7&%&}Ej`kzMAR?Jb@FUe#?OiGZZPdi4zXs2dsz7ynZ)W!c&huN() zS5yCveB1>Kt^?Iw+Y-|EIGx7d;cy$)w@vuDgHXNs>&$Ur11*NGzVATyJtgpe5qpzD zJ6Wvnq{;;YNfeUkJ}bcS1H!u%DU%%9fCDQVUJo*mDol+W07k6W>r=;BW_Q@_J>3c@ zBP!#f>gO4XXpbsz5uE4LRb*z=4`e z2U(iC!XSO$;^#Dl5{`J1${;V_DTVmT$>u0#}YJd0aiLc`d``X|IuV zqFL*DxE;nQJh;$bM0JI%zj zf{Rd8Hl%u(@IO~Pr_zG1(!em7Kb4Yx9>V60_3v7R{%>vmvTVNv`cR>M^H(%lPv{ar z{f>}10U0K5!F^)iK$&h}xk5mEfcHL3pI-YoP6@{Nxus2dCQV;T{9Gb8LL>!`{1i=H z>0rB~yAl)2rjGMr1Cc7qdFPZ2m+WM~a?2-as0nDgfhoDN^7ZrW-`A1hr??3dDfaP= zF*c+xNTFEG=YLTMUl8AOa=qskPchhOrTeWl`)dy+0!5W|MTi^OCsK1lm^85a=ypT8 zoIO0kR1{rV9Jq)>Lp27DSU0G7?RP5i9;uxDS1kn6NSle}BXRA9HyCH=cUp!?A5M*9RojZ3*S6fll}!z#U{BMus3CFUoa=+S>UlMUU12 z>5Zl12bU}>1$qQl{WvQ0S>zah4 zmKw6v$T9{NrQwp$j44Bh2yoX$QMPft&aiQZM+lmTHgVKK2!VN`ctZz^R~#RiCe8;OZ&-;*mUY9RF_^fT+m(7y;o^aD zUxp{f+Yl@CWUNnE;1<_Rc1~$^`yRZN$SQ??s2_XZmP149tO~sKRuHh%3efpiJ{U!s011>$OLBV|dgW;P2g>5NNWN0-!=m8+z3Hs)$$ycZU+&l$$7aiM#fUBx zs4&^!`OwHFWp#({-G>9l;9Yy6lIg~Ne)thhEVH^n=C7Q(0jcQ}OyvnI-i6p{;Bb0= z>)xDk#T2BPU^sM4#03=KhNT);CjNffT=q4LWaFZf1ezq$6JD;>_&$Stc>6KeVG~a5 zwJsi6s)xzH$D(c*7te*ycnRrNLiEVVdfbE?cNKIfp@q4avhOhzyl7iYTu_|5SnanS5z&_3Xy25a628t~n}5q7uiHkQ(Ok{MU5ItRtgfXaQ2W z0WVJIE2l$7BRjR?#=2dZ-czMEF|rMyr)B>Y5K+BZtkT~`G8SFi$2annN$Yk{G^NWn z8CkbNm(#U1HNdcAE3eXARG&7Yh!>VtNvGBch|=b*sB6ts$0FIH#Uq(qg_}M32wo>|vr<^`sPu zstYF}8jrUCnOh*tDEgIAI_MejAI}1yi&)Tvru7Tpt5#!S-7c@mtL2KxcE_`tb;P`A(u9}O{3o|cVQa>aWdarsFE3W?I{NzdoLLx!ScfvK z=E?13b}$tbj_i1L-XHbUZ~a@p?$C~6q}2X#w`=1pX(xHWR#Qcj4kHzwTgQ zm&N-fVH{O$Ou*GxQdD6Si^kd=eG%`-D7Iw8BE zqz%;huB#xCXKeEF^MIP3pCqOz`H+w*I7#GMZKC{v?N3f^WbR;I^EVSB6^H5UY4t5) z4FW=<#D9%tDU0g>6VqC=E0jV@c?Y}{7{5$OE>aY`joy!{3HvNq%=E&Azu|NQLhxM9 z%Dw!KT^HCuKs7B9lV)MlK;a`XINB4m<~l~sy$yqzCHoY3S$!qt-W?Im^O}j`kHaSF zp9oKVo~!)I_^W<)u1Z$YOXaG-`xmMA(Cu0|%DvG(CCd!5W`x`FA%Y{iu#&T$Cb8$M zIjIk;H<(HkFHo16|3##tR5sc8TzmNYuy^S>qMiBhBUtc`sD$sN2`(mghrXh*yTWCq>T>&(n z2vBtfJqw)=`wta{ISMC$d4iNc*LLk-99!F1HJzuQ#)VGd0&j_yJa?NLGL5FBq+~$x zu$a2RFNr?@BmfKnI8T(%q4hyLNq8z|L-e%hM#XIr+l#=|n zY}0b;wsHPIj9U_I-|A~`i+#WChOyw985BRri)p_+;Il}hhV^3oeUC1qOq)RGf&w#} z2tdiFSiy^^4%GM4C2|4ziVxB&TVvqDHFcmAIub)(C5~}lzd;&6~E{U|kcw*W==hBf{ZC6@fQY`JHpEOGcy8$?U-P%_xXMzScSR=|C;X|0c@_t(nU&2HX(g+CuK_qUW88Wxch=$Tb6AA zG#}N{V*;QF`SNlU8?MXn1n^+IDt!|> zD*;Illr#tzXD_ez-rgPHFHP^?`1i!dK<1X0oehv070QZ4<8SHy;3Mt_{i0ip&qM8p zfH%bo4@N@N0CHCbfg}mx{MGZ1BPRcKfNHe94hjwGm57$2zivkWr;E-42;VN^ZoIN1 z(fyGRq{l(0v#Dl8=Q~P)y_tjcyff&%PPS)4rV=jh6yly;ra~D|{=faTVka&1d77D> z9sScVg~~!qg|k2mq1@OKVEt2FeQ+NI3RDWQnA}q@liUU>tp}YGri*^owgBR^6AXHT zeBDQ`8So1z+cx8Iq5!eSm)^xa#;1IO`(k<)Ai(AGae{lg1swAC6%5pahQ(L;*SiXP z5^v=;T+hI^C^!NbjWmn4Sp&rBbR~(#)*CESQ8`L%bZ)Va&1=1%lIt}e;iK~uU%PR= z_K#^er%#WY7Zu9Lkfk_8g%(0{cXrWlJD{C*#yk{D>$uX)f6h0eO4e9gmZU4B< zz?Nk@R8v4@isH19qk7iMg1QYC{MK`?4Z#_fcNGcxsTv$}sKKcF#wYC|fq!3osJ!Pu zT$wa{UO@Q5eJvSf99m$$!9yeNwd9s2nxvG3&Om&((4{g>WgHdoM~Y5GPl9yK+k}7h z+}*UDtrT+ZVVKRzYjNHsnIWhogy}rKszmNLI`vQh2 zZlZ(o7+*yNJGK^jUN(Cl^?&q6PA|R0s$c_cP^+aFC7#qDt+7rTz>sJ5s z3|;N}pmfQ3uH?k~Rj8XdUYn8Ro>?Y~`8a4|3CPrny>C$x1Rrbxco2xQu?ckkv$7AN znj1Y6sw0xlvbMg*#70+%1!YqU_ZNJs6|iXm2tP}Ks{-d5Rl^eHtLG**u-iT%)C(*W ztoyBHmhh;qOye~KQSmYyZ^KubESn+At%!T z3uYt!;*ye(MF=-9M()C$ammjPE;W^0y>>(cJ-zoQ|F5UM&-1>|x4y48Ah7QB!_TAX z4v|KmJh%9#UF=8gfWu-ze4?iX$e#c&2d5b7Srm#}Q>k?|8O z&52?|p`t((+)5(4i=dmziNeGp!CqBQS((>QH=ks>hT)RgIb7V9TFEFyQ4g~o1z8N( zg|ztfIR;SN@-i!5#W1dZmcX{1Yg1B=1<@q`9tHeOqjRXw&zSsQCV?8Y-w7~yL~pfa z91{zym(=yoRgXQ~dA_YWsRWoC2dDrN38f6B-`Bs4L{W?$LJs-^&xOGOQcy(#G|o|; z66=6gpsXzlu?wKl&W&c8EdFB&5(bRw=;i$^J>dX8M%&<9Ud(rAo@1OQ7_VA9t*kmo zVH?)-TQdL^Tw^k7K~`5K(y}mI$H&MSH@|k;BIyZ2axpOC9)zoI*`{F|;-Ofo-cng$ zVic82;cB6A#`%R`7+r7nno=kNL|E|bkX@cH-|{Q#Me->iBsQ+ z%8i^H)n_pZqp5m8O>XPyWxA+~ca@y-lp>d~oza>q>MGms4dU?|jrE%e(8d9$3lk>@ zWIV!fT75+VCs53zo$sM98zrDp4OUH||9(>Lp!qe)n3Un$na4HSo9AUPQ|bRU<|Peo z)?YuSERWHJw==&1>wX&R5P|37=Ntd^S-`n7!795(jwJXKld3s`v!K;bjV)J7oX0~ zl6`!)|NnK#J+2JwZG0dUfT{wh53!1qB2YI5<{xVq7hPjaiq^AL^%jCy}f< zvuZS|HZOV5#%iqgf2oPRIu~kEikg5%kX>8(<1jsY8vq+CfL#x0p|>5{wjES8$@N3! z#G9Z(kgab`Cg&&SY&cQXt4z-QSMbGeTUJLx0Vc;i*((eTLxRAW6sg4TLYLxLDkV%d zpXVQ%MV~OC!|FO=R24(6wdr@6^df9cF~JA&F1YXQLneoo;|h{!!}2R2;xrAAaZzQ- z(3vc4o0kBbjrb=NdolXEqy!I$fTS2;i|5dgE=NB@>PlNO?VBSaOD!xxt#kr&0|`BK zMAW=JO>^sgXhxuL!s^(?o=1T3_lFDyc3oRRnq?)CzE(U2e;7Hqjo5)j1M`ec|DkUC zC?nAaETWrUlC^$bGcU+o5LvZ(Bpb@m{18mLxDg8XnX;Z}PAsAa3w+lrEGy4hzX6YV zS*)6q5JC1Rzvtf{XKCJzcQ5b%B`MVc#VVIlDFOSBghESxYG?l0k~_0=yETt@(yhv4 zysA$qc}^|k9GqRuX+I7kNNZ*K*<~=05B1~Yl>=R8f3@5Hi|{(aB^IMqqpBheRCuvN zag*1&EV&dw+RV-#AAhztt;>0kaG}1sl(fd5P5fL&*cf^(W;Qw!$tJNlydFXV-DJa; z_wNEkxRwF2g8+gC9$|<)QUUg=Y}2i=c7b`vv@QMZWi?PWdYzZkC~Ew?gK$d1Wh^s# zr3_)51)jTPodB`WUBs@D4SR2w}*=K`t-imFfVBKJ63)204utVgH=c z^ToV$jlti*zHKvvF9T9UYW?H!C;T$u3*w7X)$+uKXk%Dt;fbmMi6FlvZgq7vpZ9I? zwgY;9TwGlAW*`-HbHw1_;JlR>-^boB2X;KbQ4I)(*t|^ivYt#)1G8|L52SeCFBH zBkUs14iOn`3TrS#T#m#_)5{!-JL^|byaE##mEfz~^=~yMlsXGGcBxS;M+qG(QFcH%*Xj{as#w0_*XG8WmDHk&Wf@Mg5+=IhFigV|rpLl!qUkn^Izkdr;q-N0pMYs5v#oRW>^G6kZHwB^ZiZC4DQdgCAJSV8m%I zYCh?eol>A|WW_MRn^BS1zFbN&0?n2TLt+>?)K-HpBP^sA12~hwt-wXMZX#955CF>s zmoTMgKCyS)+toE`Xfh_xL9s86A%_uMNH?#W8yg+S#Hb751VKJfKfB9ooy>GjOKQIt z-V&#bXoI3abZ)aB$2gERU_*ls*l_^B&wpJHNIk-KD*Bdv?e0k~0b@s$y4K|wFB^Td zVMM~so(mY1f`0@`;4h%t7jE(CF=)Xtv;JAg@&b6_{^-edVpc^(y_YXj#To(JZu*8* zmSEGZMud&Z$`()Sz1nAeQSB%Deb$()4~rX+cx6pp;27e;x@s08xU5{ttLj_+ho-Y^ zi)&$;HSQ4HA-KDHaCdiiXOQ6T?(Xiv-QC?GB*5Tq2@pum+RwS(`2q83t(orXs=IjS z9XY3!#4~qD9h6xi(nGtLWOXNi^SQMhT8!;oB!La4mm1!52PT;Y*g-oPZN`pX6{2j1 zrmNH&zGkdm0vCL8QVA;Y|Cdi&xRroKYP6r5fZK4>XMs3*$<2}vCgHJ=qjo6_lM9xo zC?8~*%5xX$!o;cE4#7oh<)1e;WsJc<&ZoYd@t}j}Xz97?;@eblu1VJ3C+KBO*5ktv z(n2L{gUl|^AuX6l&bJjiOKUz>X+hDXh!c8)kt%Zcmi48*uYeFFJ3)yWjoJb4qX(0q zVT=;@mC4}D*-}G2zWNIkm`7!4m$-tSXH4_9Hu2cFKa=@BE)&e_O8p8qJf(uuR&3oy zvCi~R4zb$>qeIUJek2YOh;J;0hctQy^utHCJDT}7(A?`&U7pU;x^$lypq#XZcWWnj zul5@Wi~R4y$7gCtX1Zj`=E~seMOIf=d0#jKjNHU+sX3l?^8|NVeBY{Q7>zoG`Uima zV)SM}K3G-x!fev>r$oChAh|={rheJBZP$tTTXlLZJ`w9cvQ6z?a~si8X~cbKzwxcv z;e?GhFzf@!O@K6GF;|iyn%Gm;$oWz^?eVsm9Yvk9fr3*WDOJZz-3sf{qFE*cIQqJN z&3tb)%5SBwYpTcMkrE_>ordfTX61)n?3wbs^iqI{MV9?tI#N0X!+xY}hIG=LSS_1qjHCX#~E(`prK z3VrMAnxlPkkyDIeGXJGg+Mf}+8LNDW8!Qn8Jm!*hV*e6Z4FqX=)d@>elIAZdk_QaJ zGTlF)441ScuSYpdVPoBrhbcok<_w$JDBfoCtGS;f<3GX`d~Gt3WxBocTK6B^@< z9P2NzXCcyTDKyuJ!F18i(5hL~>>kQ9ozS-;Qa)&88=XygO^E?Jl_O7{N)Z5e9P5mH zPgN2Z&*vRR0*pxQ-<@p~aBVJ$y~lRQ;*l3Ih+pLFT5H=3m9=_RC$VQ)U{HCNDTlEb zah=8rm2BCFg!SzS1Pv+SdpFIsJ2EqlQ0O7KHgXk%2Hql>UB`(1{w@QYKu$HS`%*{I z9+q9O{3#dG)UQ4b4o>VUaiIpd0zCSg>0B;5E{qnVbO|`nO?YQY-$ELfU*?@v`6nH- zTI%r(+=z5Ka}h3sZtud|9i`~n+3Oa@A^P(@Epk~fSlxw+WYwHsSQtoqte!s&a~#{0 z>hMob-V7?ir~jW9pfVJb=bJLT7w#jcpbb z*LPr(YcWf~%0<@?jt=pSu4;FdZw=aI)1Jr)*QgbI`Gz-EacFGh;9qFK{B_8}5GuyB+_dn)&wc4-XFmH5A4J{`{m#IgBOkmd(=F7F0;d&X+ui zhVzJy)C<<)TZ0BlAUs@WF|KeP?BlW!v@NSCeKPb<}pn132lo{PYYkb+9d z83Y~;Ktr|1N-uDBa$05takn_6o}atP9i!}wz=f~3_w>ZN!C|Oq&eFS>b8*yqr*u`7 z^HvnFFl@x{qRJ|VBiM?PX$`Zggk)Pd$S+syfQh&DBH;DdH#WW|hmRb|!etsuITIJc z;JznH+A~_$ZWhAw8`^AzlQeKf}!8!h)^E7VEMl^E@w7 zZmmCY#DyU<1pKh1Gb>wZA)+pBw4{R|#D2+&$&l3IAMj`Xe+&2y2AgMD4O#gZ=QZih zp9(dg?=3SHJ4`!bG>YeE=rP<9TS$`Nt-}5|TTA0w`yIRpuS4cRE{i?f8`1 zF7*I{%VOatShBESOt*zhSh3qw@mqTMmo@s|(%*t-$s=1i>`u!&5#>Vncu_^&1@m;` zCoP;rr+M0ITEeLHK4lrBHeqL2G)Z6;G?Zxlf0GbC03w3P?yd94tj^A9h>{YUGmO+k zVl8tp5uYBk#=rda&9wo_cl+s=e&z=Jm%~hx`o=sV?=NF_H&1m2$pgnOYS9!f-3#lx zw<3db!I#gzKz&o8a@DVp3VJI`6-)MBb}Ij#J8kwj-b-q{ryn2Rf28nA5JtTPUS9$N z|Li{oVN!|;f^3W*0+MO^GA_E*gc!ucl$S`K_o80@)R@Gl4j;zy)w#wfLrwa;K`O*f z6ZnVL^6cw5hU=^UvJ_(9b`m1}!GRh)!&bs5gF#zByL+_F@A0CBDKJ$#kIg*6!JcZc zaG+MKBiBzqb!YJG(YK1}M?ki6 zOkADjEiPAhRP$#SfGM{n)T7jsb>|pp3fleUujroxSa5Q{q2-45xo%W>(-dNjMT?F2 z)l7Gq%u4Uv)cVeU%j+qf){Nfu^sDY-L0P_Ap)!#QwMMaWEau z{n}k)L%`l{Zp*j7h1V=G?O!q@a?el@=<)Iws~V++e}@w8yfTy6?`s@Ot=`Ycb_o30kPx$j(26NSLQBt6K8m z!b1M)5pG#6ruG8Cs1gSEl(*sMKLHhr|GBzuQn!>tz?BQzUb!i!+vybCqm*zq4cc)< zkU$D?Z9S2dBX8cfpVTCZQwNT>u6fzk)k}9-i+y5q+?0za*u7rXLN5J>b+7^gzK#mP z0J0dppQdXIOuXe;c4f~X!V5t~f!`1wxx-9Cru=Cr29xO38(5TUk`ASIs#kJ@*qQPs zCwOl8>W^TCqm+qO7X2=y;@T`awD-Wni=$@5tnpXj;W)D@w}D&^?1D}2!OQC{CU_t^c@slCn1 zFH~pFE}lDHaqv;xV6LlXo1?d$G*Q6nh4=8h=Ix=py`l-+ZdaciYg!>*)%54yz5ObN z3UmUgC@TYwJ8se>9J%9ICO95~h;97BUVh>JC3ZIy;I#9J=AJIqIX3m$D^F~vZ)#4z zLAz}EXMXaQ`jZ3`_Uf6yhn1{@tPEKwPU6F-Zz@Pez&*Nb>WH1Zf8&ul4QC_cNqCd= zPZ5^@GHF<`7K|Fv=a~anS(k&#ekHgcjyyT@-t(MIJv*uXG-#zK@mX zQ0W(C8ta+jL8>j)#$tHRZjhd|^XE63dSCdB$Z{|%=OmTEhP`{Oa~bAMmfx)T$4=TS z3v1-H_VfslCdvJ-=(zvAv-e=I*K_5ldZ6*oy>WNH+&axABdXDoc&;f9Ek?Qeqy>z$ zZyD#VJmBVy3W{HkP&S!qXWM4x<-~NMgq*?bA^&js2sU6rIL>6~{EhR+D3h zo6{V*ygwJ4R(NeZ09(awG$p`plC%N^OEs87F%JIHzOcAU!qbz&4~^TRJU6`!yRrgJ zLC=s-z&m{V3+ zS8`M1ZseztGvxvBo)r}q0^TV1g6P}Y2s;JsBaW(<=kQJ;u5OF`JYSq?mK2X-!`xpY zUsr0iTwAk!Ym((*B+2tmtn)Hf$hD6d3tgI0qY5OTAQt4v4 zRPC!ThWuQL3*)Vp_^K^eX{Q=<{)v*(IQLdls$p$}1c8|$VP#~}gFSy=AJ22%g}>Dk z)#?WRjsGVdQ_{(%p}9JzjF>xd}EOZ4-0li;*zsFb=5v>%xJG+%18KY=u@liwb zS3ToGIe)0q3DGWsRY8=s`HAVT4oj2;$wiiZ(4VOgcifj$>Tz3w<7cgxy;uE z1qmR^w=6typW?lC@Z%6J)z&gxRC+L(nE<f9kUHR(_Xz$05O}WG(lMc|g+6$nS&58oLiaVU-y>+!tw?JI1Soh?g z0bFwE*>WJz@v9r;9dM!3x((9_)q`mdOJ*vp>qWDm?s1WNxWIVq=j>?v>*Wtxlmy)B z-iRUfD;%wsnRCfNJj|;BG3~{7uC;31Os&Ml*#X-gwBwEz+1Z;$xpgT%je>!k(6(r)M4{k>3UA|u`C>$A`reYGlSEN|h^ zf&GIA5wU2MLFiIJ57`Uw27Gj5Vq~vc;=fY9obx;2XbMF9D?HayOyc&&eZ(ccs4|Yf zOkbiEjH$yM^!xYs!$Uv`V!`Sgq<^Yb-MFKCvfDtqYVW-3tkfMga~)wqC(xsU z4VNi^P{v1`&|}DBo3d?ef4`zIyLa-x^19?!#5QEzZPFNO-ncs;%?}7VO#1eI&LmMZ zsISAO5O?7rWaP>@eKnkp7=?E2_;9E<%zK{5A#|dLj;`3;V0)mCgt?C6ywCLZf&t724E`1Qr zELXD;NsHt+st}RBn|pI%QH^U40pL)mEx@3L+qYQPQ_G9zCw~;p6~JpUqb3A`R^#EL z9+e+n8axAk-!3%?|GPCmt*XFo{p~_a`at~Z$S#bYDVIsCJWAU zJLd14`E36~wV!*~=S=1mu^4MYb>>gf+yfA~)WN+6$J*Yj`RTd$_dTu%t#0WHi?=C? zIX$8CtqUENpKy%-%*j%M(i%ne*fe;u6RUWrt~)tr6@#omm&>+PY71tr?~E{z1+yL& zo?I~$ISU|n?0nY&1eK__;i*}^iO8V0zwI}*N`EPoU zLd&1M>BQ^K5ll}Sa_Yvt$XDykz0>$|Gdp+o^yf}<7ux}70|ebnyXFkv*^K&9)ikE3 zuK;zwf^dv?rpv(}p{Aem>Kr2BtH*}Uh{t)Zvuzq({PlA9`}_#K9v;gw#k3d6 zta3s6fukFo#&>6xL%9_$Q_;IIE6-QU5L#Welcl%F7c!I`!2Ocd52&63a@kOj;kTwR zu4in_wx%?$6oFX@UOqnjgbAPplE#bl(2cvLvKJyg=gfj@FFz}*{|FxN4D=u?D_9d* zsj@wSxqxo(w^xqrU_5}7Oc{*pe!wIxGAWW>LUu@W za~L5plJn$<+47#3Hdp8SDckqR>Z28PTvA}4zp~&IpmIXsIv$sfSD4VwLzM6qqKT?- zgkhR1n6>9>S4>8(3i+(=4Ut@*=l5nuD{Vn)rmBPgxEeqNi3L_T#O#O4hIae881*Pe z(^xd$ozPy-wEq4+60>O_U+z1qCQdv|zbW6trLvJ|*AY>Fhh-UMEYHa6L@fFCQw>w% z#Vq*9kh29lz@E!gvZe2f{5kgnttB}%BU^OT<|ODFhm|=jKw$;^<)wJ^kz{!o%fs^b zHRsNWt0@u8@p;%^syO+jyY+P;5fUmM?UtL;iKqwc1Uq6OSsRl9hJt_FbtvtVo$jn2 z5>*Hd1Fspzzs)H8{XDTuX_ih~=ro1&W3!vRq@Iv%!kR|k@3{H(d71&UH|m@A49Lea zq+B|19)Wjg`^&T_;v3#Vl|}iK`$ijjt<;)VaPF@g_U#`Z0U&NASHM~?5BpzxgDbo= zXsafZMM1o%N&%|#iUQ|h;w#GC+lR7yK$fzw zrI02cziIDXqx_H{$p&-zs^qB2DT1c)0bI$JY&ZoZvJxW**+IU5z@FiAw>J{4Cpy@e zflt=wz#t{&VT3B9FHNot$OvMG13#yiI*TfLu;S%c(W=Gd4xsr|*m=)Tk~{cr<5i-ZcgbKxs>=?lVW`` zDHmerelF}sY^77fJI6@QP)Dy9;iV00>~l)v*duG+{ktJ|^If7!&~ z-LU-U#A1ce5KNRQW+iC1Z|hwdv?jl#v{zlpl7HHjY5AlO-GNjcwKz+dI)-*P+mZ%~ zkjacHTZ41pPj+2Aqxmsaic_C8O;)~lOnCvi*x{vAf>ID6HVW1#9C5|t^# zh{<;Znh-52Ix;_X*nN^9t?K;g&7QqJ`G-AE9t(=42XJQtkbT4w{^*-bAGEX}b!z}} z0d(Pz5)6Cn1eZt{3J zFZ^4VnADa*TJ(Ic=v(Gdz=v%i%7O$l(XaJ6eB^{|fLPa9XesUan^0p1ifev}afnV$^F|s!C%)3luy8sokoBU= z>B*YmlBaDm&jKBZX!Va<#Y}-1x`LCW2p1TpzKB85s_F z`nytieJE6hnUD>%wpP3E*M}{mzlit_T!h2qDm8<&dMi`H%q!_}q`(*sl;?EtOOHN2 zUvBy@;hFf0)x^v6o@JyqG978~Qx9DYTTnv%D>MG~`(m9D2L@Qg-!8m*uf2%iJsMJm zFop{ENR_+XeZTH}B%k#Gczl3P`6KAx$Kxr0(hJ(RZ?_#-UJZ5*W(c_t{ah~k*sU*k zU}&ptmU;n!mqy;om07x^nA$Jg1HNHMA$vA66*s@e1=HU!n!5Y}USc{a6WA2C!F!N>^I^*_Pxvi@40sn;rAC#UaU}*b*QjY;u>pEt$zIX0j8US@=!{4gVi6pb04rdGU_s{phyeWBB$1#>IW#e}@O0L%55}Kt3JE)J_1(u)a2T_ojdTDp= zuFFXO#+4uT?f(maLK#?&pqG>O1xZZF8lJpauqXL(ls!@Q4O0Jf$>NLt; zZJN=*&a22JS5b2c`bEDIw_`0IDTqf$rpbe)Eed7TGs_1d4;iJtcEG8KQFCX7q@Y8_ z2BQ>dY9phtYAM6G&z0!S6^}YE0^KY`a&E#!uuG#Nq1PFNa>qGWmsgV)mtzHrY3YtH zmo$~JX)d*=xemM6`7jsdr*Yr6NU@w3)FI2WDFrE8>8ri`Kq#m(mF(km@#PG(83v^l z=t(Yx_8aLK)MSTG_^fdF3mTC!`JRctx1YkUi_qY3@gwHtdl>OQuAIP3unKsXe}OP1 z^i-aSq9U#&=Rz5OglZ1uS7AM3vg{LRilcpY^O|dEPE;}JMCe@z>stB~%!>e`Z!qxv zo{5>DTi21?)Ra2(oBW(Sah=BSBJzOHHe~@wexpW*KrprU4tbQy&RM1D@Mte6W88=6Is(H{Qi~s$ksD*kKZe!M z%_VMD(^}1E%SE6V#H)k}HrvkdV5HXJf<2!#PW${^yKWC$S%ByKiL?IY?-#xOuSK-p zUlkjgK;K53`b2--CRpNpJ9bHLEp#Tgq~7pKv*o1F(~g z;SCG#wKZw#LoVWrW6l3L=nCgs&~>!62i_kPFk$~x$o*Jf=YVhD`Z}L*>dlQ!0hAM- zoyi&vjb5f<+5&eVATxJnZubd%<}r(Nk7q?PT~^Y9c?@_{U#f!MXrIV%9g7(N4_*Cq zZxQ>#?*k30^Xx&8xA*)z)&Rd6;%Xs0ysnMgEnT40u*Iz1xj&&iQg4+lU>gr zCEbcsmC<9NkYsmz)KaAcPTnpfoAULX1=TJmM_i+BDx3*533(Fz1=j4^)Q2Orb#zSn zyoa6CYDHzfqXc7yQsv=R1O#g1C9R}r(Tqi#gV2pvoNIQ6J=R`q4?<$2uFw&JzlqM+ z{&kutR#fCAW^N1Kb+pk7ERX*979#kUKA>j2yrrMDI$g4sSR|wTP<+feR#82VRFo&y zDql~myF<^8$&@iF{qMOHQb7W3qxaaEQpzHKs=of01xwp)ZkiOaRqhbw(gfe;ayp#@ zu5TgfU6CU5psuGpXu+nE(sUKiB;22=j8=*W1yk3DUo#Xg*{I3Uutj-_cBq|U9XL)m zC_iI4{Vp!IKXmj=)E)eB%2@vF!f*x34ZliFCqh_MLukgXs~r)KzSUwDT86>a)!9De zpv3!Wpr>cou0L;$by7fG%~#C%`57DSjf;!oS^|%cOVzC(z8^Oot#beBm=L9%jjXT;xmlTkS41s^zYnojlC3Dl zq*WRkozG z|442lJy?s^ap3i-oxeJLjh#XXqc1?O8>hp(&6^dKQ(FjJi5q%STqQ2)lzi7naBvv& zz6oElw74(iL4zIC4KI{IDsGWD+KGHZdI{BDdX+tusx##(?5-A9f>7FAV8(tz;Px$l1=e#FNBf#^4Yx zv*(26M&vpO>G7UrdI5&`*e2p%xocAY3>E8=TdzXhQa#NpVezQG`=x$8uVRuIbyn%5 zvWlSQOt7!0q4;CxEi<2im&3ldn&~e$4)?*cFi-r?9;xc1S*dU&=^kX3vWKi>eC=2Z3j=CRusdLdj8j3kW&}!eVE4ceT1g zUlCX44YEk~qd4I!V}JO8Y_9M+MAF#!%Kgp^WH8ZT#wnfAZ?E3(=N=c&JtLn33=jjl z8*5#gpGi{A* ze&thmqvJo#+sXlY1@3`j3;5V%D-BwOUa+i>G-aveB<0G)FA%(F|)}8qu>MaNPA@ zS~;9nxbl=B%r_ViLQxP%yg(xbM{OYIVEoL?iPG>ZRr@a$W^@ET(QHlOrr77`IP`oK z_*7~UkGTg#3v!|zi1LY@Ul;I?XY}lT`f?Cn6)m%$d|FcPf=ecg-3RRP2d>_(uEnu3 zr7*}eSxBp-C>@}zE<}*)l{$X(!otGO-g6vk6B^-w7q16M_dRf#Op+)Mkbp4@nH;t< z9b9tcSv4w*gshNC3{`SsWyH0Z>F*b=?BH*qEIC*k=ksU#UT<0*LK4h&n5oWO`SH-b zv@uqRxKkq_hwMHJ+OoX%G7w|T)1L`msx3N$;`sx=GE#4UQC zPeY?=DRd7RV-7}OYo9pmLtK{&qNAZFcoNEEIz>5=WN_Fde#j2!a@2lB|6u*S9meF& z*6MacYi(A#Un77g&1Lu)kZ|f8;z7C;l*@ZM*+xq_2vnsT>FI6n?*kkk-Az47Q9X)$ z5M({l_ieY5iJz&0E-YC*$kH8}Wv3JAN9z6T4$~s1}RL5lW_*qld*$MtS4Z?i{Yi)&Yc}C zW-@Z_6Q{mv|AqT}-+UpdEl|g>8fhYfQV-Iy9!v0B+_t%G-!zWn3n`n7MH<3IIs+)$M6 z;td430F6FqC4Wd`9<8sW1Bp8aSOHxIKYn!%eq3jn1in6Rnhg5Cf<%fmcAKKyEn}`^ z>S%l*t)sRxjzxiTr?Ta<|8iyiB0unl{~~+?j6Q&@+ki_TigS3#Pf8I(^E^fVFK?BO zx6mUV_~yZn-9at!x*^{T<}r*br(Jb9J18!-t(z!M8jiMFN8Rf3KaofJ3!&hI#H z&7UM9od&F?omPsfwP{qgJLOLN^>?xF+-ikzU1N^v{A7+WDJ_PlTfQ9GF}P4mmEjOq z2uVN`w&bkMkkoo*51|t?lA>?&7brWl6B=S-dDI!AIZ7thc%}NHHjNtYBN%dzp@>F+J zpte&3Z3a8}=e#rF_s&~hBh70boadZk4;F%;Be+yno~^tPtSi*1K3h(!5&z<$;@*`H zll^;sb_N)*F~4ombh#0HqTiZ0Vs}X-#%w1*`Ij%=0>kmYUr8z7DpcrTR=xk=XPRB%#@oF=EI^$F(vlvaw%f~c#zZee{N5D63<_O5t zaMky`I`X6mBU$>mxrxodtBWR>wQEFpGBsda(A`uS5tDWbnG|N-W$G)7Bl6=o_-UCd zo40IJcy`5S&_Ksc<+p~1zMSEMUCqU^*VUH$%h1vb$D443+E?Q#Xg`5=^b??3=@s@E zB!|=RseOc6=}9iBhWRV1Cld6-6F*}r^pE}mwNzN@NV5swq6~4VYSxZdY}27U0UYS_ zcYc?4T_&2en2~g8PK$Q=bSenRTd&@RpZ)QeZs2?;IcqLPtSCmrBg8Sk$){6KG{SKY zO8iT)wydH#$O}hSL{WUX;E`+Grr-UvGj&!Sh?htu2lw86DULza2g6q>ts|?)+gyqg zb6}@qTX*(|TAFXSnRaIOjmL`S>`+V~C3f?{TK#VH)K84Zg~v3l_26gjC`_Q$^dI#Zmkde$j1A5iA-C5k?}@s2;f=TSYE7|MY%($As^+Lh^> zw|6aoe&)He`S?J-I(NbfMC@-+!N%>{f``=Yu0cF>-|W5Cx<`Re*QX54b~dym4aQ^wARS*t%=S6he2-)f|a zr23~+Bij+n&+D(1`O6yQrARt{vq@t?(}fx>(ye>kv^)uLeuurPvSr+5PSt;Ov=E|RBSv2m*Bb4fj#MF1#x4r>|AM-~ua$8* zxg6mIul|XL8S_5Ix&=IhsJc3H@x_l;!#|(2F~z0iqQ!yuIT$=fZtFXxwWTMJ*R)`y zl!)^Rd8a4hAgAbW6@wz~R|qd@x*H7ek?HJ9f5NFnN4?EZqy@mQQ&8uCW(^$lu3c%Z z##F0t7KmWeX>Lxk9*n2c%_

RDjVhSHSVjn(~!4lF5`qf)EaF0~gUDGa6Lck+(%t z9Nt##Y7LVF-Q0765#?d0a6so&2(J0q&J1z)AQn2uSurCKYZjqx1hsE1*h<#w_NRwr zK%yiMRi?62p{MjXSagl+EiDGq+SH&TSa1;Lzo*x~pmz~Cxag6X4-WZ*u`@{=Jg`#( z8d)q#cqIBUpK-%^w^P8LZPnhz_~Penbonp2iHF5(I!excD`}EG(PDg}Z5niYz{tDi ztq>U{TD@1kfG$`Nk0-cF86Gz=^Zt>V@_ZE18V$|J_wo$df8F+k5!=r%A}Mwn;Y>q> zJ=m?*=8YNI?Xqf6M$K_Hr6I1j!e?|(x72(Jgn?_-(oF|(s-<7eA}AyeLivWMBKPy~ z|BZyicQq>@H%}lH6>p<{t2X}r*0S+=Fm#4D)&nZ?`~o%0A55?%GvUwOa`p0t6@Ic@ zC&mAIpgG2TR=Tpq;TWPP#4=MBGP*E_J|9KgKV4eHd2f?47he_nVw5Kh7_ zXH=eACW?$ZJGudl`Ns}AU@rt@)(sN7r+m^Vg%)NFIynGx9^+w5uyShJVQy7_w)W#_pxM|T~yB8{qlHMy`yX!=& zdsnOHlUA?qtqj>VpG|Fk9&G`!Z9ym6Lb}@aJ!w1ey^Sf`9=54H+@n1*wmtepdrVh* z+>`c%@9j0A`&erwjY%EJ-zCywJ2JaEjy&mru>f4zi@BRF=6PH!h`m^J;$lhH#nLAi zPyXlYk4;?{Ji6LqyE;yEb#`@iKk2&sy^Al~-Mgu~&!hW#Z1(`n3dpj$*w$^}P<1=j zYeeubonH9Y0WKmxga370-rp1pdANU}%lqFF_udh1o(x$K zxAr9*_x^8mdjA^t{&yqrKiB1*VqvuYs>_?5InDhCU0(g0>e9dI@(M!%G2H}ieZ7rA zkYAF3hS2H-i#5jb%~uKTxJp!|^qI_ELO}O8!czSLGr3uZ%jy+25|8Z_R_|aX3FZH6 zN^MNheH*-OEb?z7a7>@&#ZAFk2kf?;`930O0Ngy&DJ=iQT#!0(LbLrtlAl=`Fg(}$ z$Dw<3IkXn|`uxeqtCAB<6dIW(2;iYWQ-X#}lw2MKrD-9!@n!VBuw710sG%D&1|!c6 zwELglBUnRvp=OaZcGE4%4+7M#=OfTnKBlzr>J9T87VFRtd2luV}7@8a^Kv z)*V0h12IP$e~Mo>{(?LEwn6~Fg-TrKh-g_(_{w`-#!w?rHtycPCzKE|Kc^Xmj}EiH#qM#U3IK{+J(7Z~U>Kkl6F%)9{}6 zai8zI9$Z-*`_FZGu^r|^zy$}3A0J+i!;#Kc$Ib~}4NIZAj9-a(4*<89wn}_dgBzaIDgrOR7V|J8N<`pTzl=2zF1=j>zuS6yDw)?cmG&lP`kdVh_;`|e3(N)DLI zEO0r0bb3Gg^Wey|nexR-7STRz+xLz6j!OWG#9YY5ECXh0JcJ6aFISMjlA{1bdz>Ev z#|8m4DhkNs!P|FL07csd)B+gpUj8;3e(*K0kHp<)gE8XTXM0kS0DREy1-2!9764>e zfF4L=3p?=;($SSz6F3~rq#|W%`N%Kn#2|N|^r3bDi+7kEw%HHa-@Q#?>hGQ2)m{x+ z{`fA^_hf3?1^|qWL7h@y1e$IdX4@aQM_TF&#B7Ke=B!CUPXExrE_};LMzBsly*0DP zkCZIYK|*ixt)sG>AsOCyl)Rpeunm3qD3_0*GLb+f1@Z}-Jn^D(23^T&hQb-7xJ?7Q zu*4D0W?sejdwhIM#K>{hCxn<1PAH*YQl=;$6W#a9O%pz&fxt0=p2FtLDN5Gj1tk=O zTN`1leT+rMsun41)zgIB+2y;P$IM-^N?l!T)`iFs5TlXv(4K24YR1$~zhDblh*hpB z`R%Tz`Arphu8XY%hlN_ld~9g4L#b1AV6(>)vgm5lJ*J^*12wE33MtmYv{$`PXXswC zfKrb1J|k!iGSVm4+{n5ue^{Wo%*%@`u_D9_3>-BqUbUaSM(RCh9C?+lU?HDb~GhP-WtbjTKWT* zcdOW_Z^8sdXp_a*Y@*)r-Yvmpv$$T9(JJr0J30P35AiTfH9x?L=0$MCv4>&)*}S$l|{XMy&7N9j5LZj6umQ2PBoxMbXjxn4xR| zl~Qr)v`<;Z2q)nah`g=_Xb(5+lvJ_!{^@lc`S4Iw)li&IO9hY}i&Z%5o z9A~|~et+(Pa3tYD&@SN1e!!H~L|8Fs%3s;brihMur?MIw&Pw3#-!4S3UmNN$*yAk) zq=Ih##*1(A!b|QVh%*R-E7CjH?_rfg#_D?UG|+u&JlS-Ka_JEQVa#U@u10da&1iOY z`zDf+t99mGBrL0-sr3Jl_m*K%_Is?>gyT0>r*tX;R|Bhqdx$v*#ZKPDU zqa2QrafXo-Z@8^=Op9o){P78_|Kopz%WGe3sb+lQd;U2v0@U$B|EPpB`wd+5G*GJA ze?Osl&#UFeA;`bYk>>p|t7~hdYAhtndm)*8yFjUJASwWyUZnISu?2LFbB`-5(Q z&WGZg7h&`f_Z=d@2V=naFb2{*DghVqTawQRwKgKixS^7GD>G~;{C0$#3(LI?C+$Gi z{6iuG*?{YeEO2BLgc@$1?`%>=kH!aSV?nGyU@#19x$j~2&O|^_o4~)(HTiu(`0LbJ{ zZ=owVjwSx)5NYlrjRmQcg{X1r+TuXyd@nH4io-ArSB8Nn8?fvHU0{7OIPKFRLdo{} z+eVf0Md4MAgzv+cqUD6CW`M2vD8o{7LZMh!or|Ic$Plm z@&Mz$G8}~hldWZJr#}-7;psdU&zP0W+?LGx_f78~b#JQ_zMvF=tQ4WP6p@t_v6B=D zrpHnWk7cYL%Mx^XzFCj|)a5EdTj&2v4*$P>cBw!AXAZZ5{h7l#{twIHj>jev0e|FhITr#rnTqrxGJ-mNCj+E zevi2>9>@i@ky^^Be)^rrMh^MH=2|J<{G-XLgjuYNG%WsF_*SGj`{H(HKoa6Z zUd&a*PH8Lwqzx|ijz(2Nkg%1)??=a0MZ>Ry_KKQ3Lz0reinYCa>fv4Wb%5c|9R5=B z)0o`X(1i)YDe8Zo!^2|uc1ba8BAs8WDL8@s`18+vXR*)Etd|Ia5QymEMUk-4YR9kYEy&49gh-t+x8ovor|P$UoUS-I7G?0$2`W?SJI(>vU1q{Ix+z>$61J ze;!Rzl2Z*Q`2YZsih_ah5I9jdNG_6x7EHaR>Q(|~0|1D|P7z9CW6XjJ1gQxn5tGhh zqjW$*fc;(~cEkj+=>{0FF+wDjswV*?ARj|}VM&5`GM5eT@<0i=L~zpGb|Z@)^d8o{ zB5X?pw__G?RwrOwI(M*g_k1e*DLMmAiWGA1VQJVP)xXqKn_=u zX#@ZwH$oAKXtpD<_VJUmd4NV_5qqYfQ3M?KstWJV6}9I-Q5GeUwfYwO++-u6@z5w=~Nxcvu<1%OXmnx->crqd(2T~kOBi2!I# z0wGRs$ey9(K~NZgxgMac8@`k8bY^3u>!geKyP6N7MBt!=GBFiS;)T>F6s5#p*lNl; zoR;1@nw;YS0e$bI4X@Xq1m2MXh66|k2~b>xynq*gN+JQrun%)mUJ28GO{BKMa-l&7 z;0Afel1Z`T&*)YFE$Ma;#+@-sV*@}bRCg-R`dDe4Z0=+XD_w(y+7&qbrhI3bpB z`+OthLw2g{Keg4>3B1Fbs+Z&k%xU6COQih>%R2xtsPDV{A?RaNA(Q=11WzH2;iH#e zJ7jE}jO=GSs*dGh{iFIE!YRt2V|8ijsJY|(znxu1HDJ1GN_)L?uly`Btbu+VXD zAH~b#$_D^g{$A%6e~;(E(UXIXwlgLOzoz_*S+?E0Il0&w-wS(!w)$_g%YU$SdWx!- z91*)VC?x4YbU!l>99E~i@7hC4&IksY=-?Zh^(NR*w$DH<7&r>St9D|K)v{VuclEp? z2AH|tsKi|eO0wU5Ddqrf5>btwP}z+Q2E3DpyLH6uK(x~;5DsKjnRxzZV#CI#YqIWr zC3lG>y?Xuh3XgQPI6dcxf?zZHE$JR@^q$0M&n)SSM~X8U)=sAvtZ#RT zAqH^^9^K{*!|=t7Vy%26?$GHDTg!IedioRw-S?P68f>C{EXdc;g6f@*x7cYLYsma?#dk01bdI8OAo?%;FjJ zpjbV+Ss%b8idWTjHG`IF&~%>fdatY%lbznSdBlu79{P9H8RrWFdI_uklEjlCqfH`- zpJg=inIQO2+Mm(-o#}d`rVeebHe}y)iR2KsASq(W*Zb2S^lM^fp-}4)r=`sJT?>SV zNwVyOk(w$NZj+CX2i>{Kl!{b?&mDt)z~i}`nM_&|*pN|4)Swr9ssDR&I8$c0LT02@ zW^_;{E-N#xEi+*yGwCD~&yaoB%L{dtD@ZW2UkU(NR^iDKk?8$MIXZq9-P_4YYfQ@ zKLQ3o#LQY1oLkABbOf#n>7V;Oc@orPgWrt9tiJBCTN!u22;MZ8lGtKZ6g!kJ)0Q-- zB-^hrYbeDll*x(Ur5VMig%Jq}sCl(gJEewDRtP-t5c?lJv=^llrgmi||L!twT>M|? znpK6fxetI02adn(wOv^;gaH2VNH8FdCOqGNC2ds4Kvqz5)WSf16iUZk7}~Dz4_h(M zwZ?r4Q4KvXDa9Hc1dxIAM3ArlMtQwpwl$M%zXcc`49ln{9E>HFPaKTn+Q`38M2zbB zn(D3Zri^oI%{NTRh=OEvWg& zpEvdzF+{0%sa&T44?DJq(h7JEi~d}HtE&Fro;i$g{N$hargZuaz%r=l7DX?43nx%B+6Pqo~K z!Mlx{rYE}%OVy`(ZB+B8UwSJ|+f7i=r*GcWoqNvj56Ru5{XR7=2R%3w)g5Qf^wTrO> z6~O#+n4Mrg=vh>6t$-I6u{8qWM!$&Hs|{yN9f3)YsIH)IlktDfhqG}-Q)eT%c$ErB zVKjZ0+H0f45(-qCk^PK1*s#n0`G|)M{t7Yd{g0 zu92dlOaTAo25$AfrxI_;0IF@e@{S@YbnDL0S)iPJHGqf=i6wOr}=o1x>*; zquJmoaF80MrvxfO;O&DCKB}q*7>J%u(c_Z;99QN4&1L-8)Q$kpq=~A`8CZRWdUsjY z>!>0(!!KLmU*MVJ0ThN2MBU<||_iXo*#;UC)*B*d8j zIXM?5)(KjKgaL3ICN_%vK3D@lkyHStSU9pmF$zlxOk*-~=>SUv+SoBWmtxDW7&e1~ znF`_0ta>4`Y&e)KfF-Xr<6;`&0Hh4DourWv=0Mb?iv5KMi4n*pw21xp8z3q_OaaEM z6858lru%521~Mvmol#@)b3!F2%X0qB{ROL?NP13obd{6t`0C;xF5~kBZep&f<%`9w zMt>LzCXZhu26~@YE{wRs>KDPQY4rel&-QzE&-!m!wXy4>cIr9CSe$w51(}Bn0S~kH z+wqR5mntbyizN2ubEFIkv<8mFGp9=N@$BppBQZMVTo&B1*Pp`_y|AJq_j)MGQN-P` z#tVd0Keo_Ia^O6jCesYgt-_qyA#S~3-0kDhzA-?~hbQCLP)~ z<0G}iRz6f_-9@9BFq;Zjbs^jqBFMmFDWZ3kH zH|+56$FuBJj0%of%jkhRn<*zk4L~9!l@Hwx5KJNh;gzw7UJay#la+6DNUv=l4d#Ku zZQ9ev{d~=JX-{_THt{0WNB8~ZPt!;e4oAQMHo3Tp4@4VTPY=fuTkbo1=A5qY=>HY) zub7-bzI1#bcxl#7UmsH%tGz?=eCFvJjWmQ3>0r#O^sq(i`Ve4h`X083lfpUhm?`i3 zqz8Y1FdDyO4#GeYBfn?>bQE{J5h->+jc)S7g-E;vgz?-h%Xc#apnVjta$j34ZUemv zWp~VLB4r=)G5SWRYS_Uh^BISCe5bV!i^Qui1n zWEWhyjO_CFsM|pjIyjb=@sx%3?ed%{{KW93c#6Jw>q8Su-h^Lo{alJI{BeIhw11$! zWyGJjIHIB5sAjb|aNpHxTKnwmT&(6Bws2^>x z#|8GEMmMCG-WfCr;Z1t)2lkUiH-Y2*7$5!NGH%0@uiz<9@aho{5emt4R>|}ytj?AU zX-FVq8kmtqSWX8K5e8Fl1NFUy=1P`$ z55CiE&6=MVbqSJh9xHuT7Cp!C#Acri>$R~M!e>oVSP$xrM_g?LJUkalj$R@@v`_lz$jvNy0q1feLybikGZ+g)OS2O0L+ ziml%)rjY6Bl;q7!m!}6ODv2(kzfPV4%=uu&eCUmQqToNaR;2CuB_$9vd(-Q`AO)L6;Bu z(=Bc=-_eYzkf(baOXv8jm`K$QB5CK&ET$QR5PJWpRF0N$KUYK2^hpfiGGqkCIIwIK z8<65YDPS13ZiZ}wBFn7X7Bbi`jJ&$T+FgbiH(JT^1?AQ9ZsSWlH6;m#61dC1=Qy2zpB#vh^0=f-w0N0 zGc$3KRKrvsq+@gRE2{UIYYr4^e%z=z3a&ZMuKCqobGBOZ`(LJZ{{cMnZ(J1?MsNQ* zZzCCI76zuZIwVUy*OhvLl!h;)ULdDlsH0wFtzPW3UV^1T>Pmx*b%U&NNP~P%gJMU6 z(ptmS(*_hvquP~54eLhDkVbS)qfSSo-ddynX`>-alkt@%Q|l)4kS5E2?V5#1lS`D` z?w}#m%>=!hU9KSh^^U|rm^2mqS0+td|9_b@DgRQzF0nb)Om%exW@#tB<*VWBJ|hzJe-BEm^ZR7s$JM(TL& z-qc@2mp|`FRfS{bfAqOLJz8dIEPX|fjC3~zO*x3sk7?*$-euwg-kqje`qc# z^x(O8%`%fc{zd4Hb!gqUA62@Ky1uO5<2X5d9Y7iOua1V6ufGXjnBo^_KbGzh>bzIGj9MCvJtwb9g^?ElF=7mXI%2YF)prp!Un;JSFb ztwP2g`5}pvZ}FCmh0IHq%yezkz`X=+)(-;1inHI6{8PDE{%|z>W771GI}!uQQ&IVY zq2c||Gb;pz5<#Ch zO*jLQV#sdV6|nSvK#3V*1HLryFz@qf2yN&FJ8cwveE#x^dW9fm!aTBTmsi_jY&QK5 zq6@_WksS$^!f*!!G5V+(>^gx(<(CrB(CWUQ##29;mY&GCiGMuN%{0Z7liwDCu4WmO za9t9gTGQ_H(gu@qYUHub0LoVYAWBmM!mvQ1teXAu@$V=iuLqf`?{p#xskfppw_%0S zPGFDzv9f{jwKnlJ~OYciHtI@tzN7iHMdSy@#OTbz5aF7(o0e86|-hN|1n)lUb)&QWBe~i zL$zP2u1y5Gv3+^6+P`J|)xEm%4jE&bZ1`*+wg}Y8K{Kcp>`ehUaGTo=ItoqezWKHK zv-^1R-hJ~@$axY@jdj1`A@R)tj#Nx9Hy2p-IRIQk9;;^|&;lqzt%`6s%naO**}-72 zjB5R-br|qK5CR4tFo;Zn5H!nGKxmg;Q_S)YuxQcGCdNNsWQn;~^54)9%LCR8E|%Aprxoum_ukpNNh>pS2L44WI%#y!6pTR%5|K6pMat4I9D2K`gQh=4 z_1!RW{IX5_I_snLTBPA_XUT3Ick8_+k3Blpm>Nt*?mGHG;%^jkb!bxzX6O|r|Rn;MlC4HgsI=}V5`UU z@nAYdV<{FZv8Bs`RgkIu=qqP$5sz92`1QZVS)aXQeAzk_VnRfg{(_PvL!aEzZWaG0 zzSE#>%wp;wz2j_K;!)d#v;OyNj+iHamUf%R6g@4^8c(VD&JEvSya_+_sl08R#$`8? zyua&DzdQ{zIhV^9i_NGS^Andl8NYVRS0~wLzRWSZD*o5P=-PJEUr8W@-R%#LoGC1~ zv!>gf{{`R4-XkG@Z_40rj)rBkGD;NU&T`CqNOx}IUck%K*QdXK_EL54#~7TwW4SmU zG3Y+XczO2z%EigFL3g8q-9(MnEnz-8Ku1q#Pfj-dsq%? zEqy3K>A3@?yYVHY=czbyxe@g%Y~$&hr{b?t?_XFjxZZbO;Kw9Lf)o)%(1HNbB@l5b zbs#bI!jO?X$n1(gone~Mz6^%_&pQ&q(J){E8imo#r-uuc8N<=E>O=nfTVXsqH2gTa z_cH&SG+jN8Kru$D$wz8fMrsB|qBA3PS|jzA|6sWoGDaE8N10kinFmH$W=7p;jk>uU zWqTZD#~5udADxtP!(oI@!7kc4lg_R6zuf0aQa;8Jz!3jIpX)!mBlY|Q+=k=e-{NX< z#toMLmMB>W3xVSQrG-Etw6MN-JVWBnSgv+M$z+ba@2BZ0l_WjdT(_HDjH{H8$2#NB|cSV&4`_H$JifKzknBQ2HGL!9am6N?XeD26T1dx(LM8MK5ye{0A`QC{8I zhyz@RHzQ>h1vvbFHAdhV?Q@ffSY4rlTX-)z5(j4I+Bzwm~1t?i4HT z$&^1yyy;(_``{>d6HRZ=c*2d>Bmm))(dIKy#=_h?FRuz6N#`klOYM*6c0qCuJ~fu9 z8)PkXn4?rC?fbA@nDE~J)zu$7(!&h)xv@^HnS?D*Ryxtg%~E?)YAwN)+~IL{AYplv z2_P4AC{uoaF%y@&In!q6m-xQouG=|)GT?Xqu~VL%?G{&(oyVo%Pz#df9E^4a0EfyM z8mppGvry_`_Nc~La;0C#bDyiX(od~a&XymOvpQI2JF$AvjepE?={35CpKq^tj^ol4 zp2k-ZiR?AGmv9cz+av4qTHnj=N;vul(`seyS2NwKyVS#?)x}E7RMa&W{Ap9wsZSD* zzvgq3hw+v`E|m(o3c>mnefaE=fU}+AFe@X&xNix=-MFEWpJ5_AfD4+AcvhE+{Ohzq zzxO_S|G=}C2{MF4X>-1@Il`p!b={ZM{=1Uav?8SU`!ss3^6L!z?G>*^U3Cu;W~EB3 zAhYVh#SU6Y(zESwBeHVgk#ZD9xw%Be+08%M;c=D!>@4M8bA2^YuHP)jcZ&KhKq;|& zH94otd+YYVjP8{U*6f{D$S6GIZR67K`M0+oC;Goke9ES-XHLX2;i7BmJU<&~M3cXibGFqa;gYIQa#21b6W5 zChG;)EB6#Yr<#nce!LOnu!LKn2N~sWKUUfzPmN|0Vw9MqsQmV4bGGt{i039%J$&=? zz!!2yZQVBaNOX@M*M<+&M>?vr%?Vt)LNmbrQ$R-)fh?d8ntK$us~>gbThL7!EoJfG zQ{dJ5x4j}Ua-&%ufoZyShx5JC;Gq{LcGCz(Sq&nIV*y7mc?jcKLzEEmdCWtBL5XT= zD$&Vm5tijb9`CtFLA!4Q?4Zo&MTgB&Nk)$Mbh*F1gDEy8Px&bo5yC=~Y$2!XqX%cx z>@TM!Ib$i&TwLm9i1cXFY0}8Ygw_y;eS>a3A~XhUYP5xt@IpavPA@+KV z4;{<=6j9T=*pWwPI-5g=PQzR!Sez>(4|B@xM~W1Lk-QAs6!n9_C-t(Sp7oK_om{oZ#M)Wx98(U=kvpy&vSmWX6;fmL`SN zduR%}2u0IW!aq~Z-4Jwy$*_|Yx9FU`n~#9OjN5|#Rq0A1-f4FF98}$uQKb(Z4o4V~ zjK$5B5_#M;6ldU(LceA8YpQfZ2eqBMIo#j54)3w3%I5XlDqC8+7gsB%NK?!RtM!i4%^qeBOAnsC_u<4jiw=T!AK433uA{ALCOv(F=Q~|xH*IP*nDOH~T1Ly^p4y`UZVSkeZEpq^(?&JQi^rbA@b!3Ksr;w9D)wx;nAyH%3Xf zNk1^VX}jt>MqsXnuoOi1b9^*?5&eXf`%o0(@=dqrw;Pu|u3%+2JC z@FJtoyKCaaJe+0hMQ-Ny*|0(AMod)Ms8f~ooqNYGJGZTC4;Trgc66F<_mWy0i-;t= z;F8dnruLkOYFBhX&3x03;*$iYS9>1!y!`n>=1A_|NXiaOBMa>1{-6|2TwCIv{#vSu zq7o_oBR8?iwrhyurcK;iGF=y~iN(opn|{>jBQf7OnyX)V8>U;wFEq10Ot`-DY)PDd zditS{?0Nt6$3(x&0T5N4iD!nTq|x?lWzDawzvXdHl%4Li&IUZ=3SFmu?C2ytI+svE zo*`;0P*XgE_&j}2EwflcyuN%TxEwNT3@VZWY zrBi0FI-ZuSud|fK^7!v^2;Sm;EZrqy@clQ7ZG(J~Z?>aS!jV6fV{muV1La|lwVyCl zE%95aux&YP8CI+dNi;gI7Rz7~G>r}NvVNE!@`GMM;3qdbx2?OW=+g|LY8v0W*Svl^ z>x|Qj=MY=m?sZvU;IX#|AZvXPz~Dw$6nxqUrn8JJn7Q^a6?>gqi)|i11?~58)A^+lT;GX(er1drl|!u0w8T3;T~hV8*pD1sBcy#RxJ>ZxIMIX@f^I zFsA73)fbw9hwARLbCL0vqM{^l5yz1&#m=MA_dFw_0Deo*#axt6x>VX@=SF`;!~6b{ zTiii(0@eVa`aYT*?x0$tb*TlWE&)x7j;Vk%pHEY+J`Ve&b&mrc{!jvk!@wgg;Q%6h z`?BHDhj7g!b1yTqlY@KLnkAJYY@#xNJ^^(yaXx6G-*3U4 z`L`+=ld^8}CmHh9TDtlag&4TRw*GM1GJak%$f1K&fz7I(!qm~rppr~$mnM=!-gTLit(-7+u^@2Sm{8RsqUou91JDvc3HYqm^# zf+V#FA^{tvv|7TAcEWC*Nc%&~JumB*zr&A|%ALzUz9_Ty47%y)V88N?Lr($1*pWhRZedUUwhR>mC&E%?LGs6d%Hk4lYVPyq2^8JM_cwVo-hYt7exv!NQhwt>`TdUIdwc zU`e46!lJTyorKlBrxrGtuy6JJCV zoqfNT4@saG^2qRg{6@nHJX8Ky5piLZ@v0e58SsR{)tho2ioz2KDpqWKqPL+%Gdz<_ z_#Pt@{H#i-)R(lfevGUWK}NV;1Z0;MdXcp0WJR>5eL-hs$dq|*ci4SvS?DD3=enn(K05XTh&;l%%tC>8obG*SY&kA(u1j znIdzga&T!e8PIe=TGKU6wjbAiu9&vEMpAQ1EV-bb86;Z25*})jkPOeLxvaY|!r8+j zRG`Jx|GCldZs&_rSgLUqX{PdYJ5*^OQZCR%8G7lHU1m~48?rT1VYR+VsOEsQX5(%t zSh9ONhxEyGO><`V=bRL{sY$C}`efw8Q%LA2IKcFZRr$Nvv$dW=xlS7E&Xtj#7i(Ur zDaz-%T)(N2D*GUZU%fgam;8-MX`Y)&-me$XZAoOREFN#(I<4R6XzrXQ>qqo)=hm3E z)ra1ICq!AZ^ow&WYK!SvKDl!j0Lrzm41?=9%j-KKtmO~iaa4`=7s~fSSO=g=BU?dn z>iYyO0>#8d(?G%m9pj0ZUgq^vg|zA$q^=z=Y<36xQQcPV?b$cGizQO*cPkvp%R;8R zoh~{4VrUHtYV;L}ffV$t%Z^0uqV6t3f!^o>DNiM1wERT$idt_pv?@Augw=~Ab!}u! zk8VeboYAtLP0&O}G40OH!LO@>{rJg#4EgH%=3Z~&RaA%_)SMx+;`cLB_{RnCwA}|f5ZJQvSoH)W0GeMf; zqEKu&r#Zb*29e4G#qQNyasq?!UFGCAp+0%tsn0@VCpuY_i98&}me?x~@=or=o3{q? zTfMlT5$V?(kK%!WRnhQgFYgItoa+tr-sEy`g;kP3(N$ov4KQ2BwEi9~{c)UTcxKBX z)+n?qE+~G?HP^iJMRw=pX#V8N#Hc-6%{#rcJ;qWV!7SHA_$~{Yy?*T8oDf}UhJk+o zI9aPsrj#UKoivaz5~m(5aUo{_m#o%F!o60$y5 zrnUaT^<{WhG^%SIeGXB=L->24B-dZjP}2JQkOUu!rHiJ;H@(V!KvFop@PqXA3i)aw zMa}BOWS3Xzrz=@itMA(2rJji>FXfP)eu8JANyTz)QgJ<|^37$6&TfyFR2|VER=3|2 z0z*~V;Rm&Pz3Z@ZhzcH}G(AsiyDg~NHIVXll_Je#g`{L-!G^UVTkqX1k#}pIqjh$q z+q1fx!tglyC$qI5SeT2pi zmY@C}ljcyD6(kWqt>;woSzDKLu?y~xG96a&oKy4MXkpzLi4V|7*y8nR@*@$r-n~qA zbDCp1IL&sCb7mmZw%&UqnI$i&DUhTXS<{av-(p|f+#9_0Wb*d!N$0ENC0*TLcitui zkvwF^&F?Pmb_g~PS~gFKN9KGcD_{BwD?ht3{{+5MGx;XGdl;acK#fXm#VTuvW>f~@ zeVC9sz@EzVI==*QsPi83CG|Oqs-ara^1(vxZ(wK-zpZuMjLd_O_Wm7ORXYCdLeqEzWdF;AE!e{K&-3z5HN{%LtT@kdz{916F zHl4uB?p`&_ywWt3f}CYwgP7BR?Hn-v;!{m4YQoWW@b>DeIMw$Y@*3vddW(d~0G+S# z+aL2^lNQ|kDscMU`7G?bS{DL}L0=4yCN0aJZKA%68$Dd^KHE1_shT@}bEyY|Pb zgx;cpib_P9--a;V{w0);5H+N|;su2iK%F^gm@v%0imArx`Ctb+lv7PuX-MT&!w6UvYK%~^E9nb^z+2G52j>?~uRWLF5qZ9*2>40Fe)HJt z-C!aIF$wg<=RNaX@N^5m^Xt5;@swR*jrdt(%O`42nD1LIR9f|TzPj}~< z;xTuf!-v)AX**@=pZyw(y}?xk1^{4p)O1*Zp5#Rk5TzUJ{^7 zjpQT`N~dZ3uBClNaCu<&FMRvJlId1|Yu9f${poV2?50SqY|eJ`{urNwp?;Q!f3rAH z_^Qns)^JHLAwPx@+(=5n0>-hV*fPvauT*WMd^j#n&9Aa>?z+E(wSIS~r+OZd@PvqR zZQdl_?7p_eg8rJ4#hoW^jJ8)xzE(wM&|OPC(fEDE(b(V%$$r{-c)El$>{G3^pc7@P z)3m$OZhSb+*5cY=VU*sD0!faZ{wWoU;2-yc%oZFM9s``i1b$TOAXJ%XM)!;a8*3qyZvFok#g3 zUJ%-~QO^J(soiVHs36v@31`Gz-Xs!TGzB6GEjI3AfV?L}o=Yd4CDb~Kf+$W$O8kuA z6e&3K`2v$6b>aadvqNN7i5~*L7d+w?^KKTl(h~{Vp`zgMB?9&}qQ}|` z9Q+xp_P*_hY-VR6GWOMxG~Q&p){h(EO&XbPdd@Lf_LpkVWt?aE@d_@J44<_M=~?q> zn_k?JN^8?|l9k3%Zw)g1vXmevO7Ud92wmtO+mtl%YsiW8O9>2|iHpzjN-0Kf4f}6D zP4lLSet0^*+0H-^cKWDebrNX|`^U^?Kc+FnInp=_W{;lJ8bk+iT&ikq%=K49x)O58|Ux4Jv zju9Ex5wf=T8#N%&`RW$=ymE%p7hH*+-tj^COEb!ur;$O6w;U9zR7IU0ymwO*V~Ara z*xrCr$GR|5A4brIB5fHDU2ZJ2n>RNfa#QPRqTgs6*Jt@9*RGZfX7k6Tzn1ZMhh2N6 zbDNY8D^co;u(Vr0xm++tBTZJfc=2;&Q0KvyhP3LlQf!Ih^j)({PNf662&tH?BFYyq z9wbOZmq*h+YyuyJ?nf!OS*Yq?Uk8HMAF6vmzf*yhXqq@=Z=r&j0(b) zfeFGNPL_k;Z*UC$_KSW%y+cDgt3GY%t&e*C-0`b+BiZ@mvgD@4_jY_@fL(Q*ZmI}E zKWDWzE;)f8`GUsM!TR^nQqRSG8=BSu`eEV#i8T z*3JeGf6ZY@(!_H`KdEwEsWz{W>eR1FzdfdFI#sgNFz5DldiF}S?UY3mjbow)!i&TK zygaNz-9r$FRzH^*S8ziPKt?)zDl*;4_;(KaOC++=eR07OxZ<^;RfHi zycX>l_pHjS*&Vb`ZHf!2qrg|Qz8&mGiQ1dRH5ziddoyHq-4j~F*M+_B(APQi|5P6< zImx>}q}SMbS(kUHtpcpTOF$uZtKAnP7C3ez`*eEk>eG$qSXsaNv@Uli;UbPt_&ze< zaEJU<3PH3_B#+>ASH5T4!mnd3(;Mm?C0qsP!@T*+$)v^yE`tDL3Eqf4t#{^Mr428e zd>c=-{A}X;QsS$=TZiM~^aV#N&_l%}%VfQeW!Z?}n2Zh_;H};b>)j+v`p9hqGF(#2 zM^G-6ri;8$ndffueZ_!FjM|5-kT>A| zr1DMc_?zv&Z9k02--@hBUltv~&>j8UkF|L9$)d(X<-L(Q_s>N;&3gY~m83m^?@iiw z$vzA;f0T^Rl5i0H8h_>1>n!Sq`l)Ng98({=z6UjAg*23WLY-22{a}CfO2&!e8l{+f zscc-KDWM}z^XQmNjc5C`EnXO%bVh-I3X3~$NJ zW&V)0eg685quZON5L;`83n9Zut$TYfmK2npE;jMN?@G+w2SWx5`Alm^oeb8E2C6blAWn%iwNJ39@6o#$TRb>nv;E^Tin5W6%2dkTBqal! zN9fr)$SV`+zW5>Ba-nReVjQCU(gl$P0_dKpoVS69!26w;z~yk}v8xm^ncW{zEkF+s^^0#I)ifIYZ`Fz} zy{kXGt19oOGE|$cNQYBZx;*GA7fQp$JKbRhmd`)UdkyJ()}aul*0A6L;!^64@uHx4 zD~*%KLeNnL~~MAUXW&J665 z(U{bgeElx3-B%*?LWWu>Z|=%yc3-ASZ;^RIe_?i3hM&;7It4XJ&H5GTZ&__f@PKLo zeO_*H0IfXH=(U9rNt$I$0S^{;jHOo4Ia37gyNs0iO$-ot+C42-bmyS>htKL3lp3h57#3-` zTT`zWt0mGc@E>OQ_BD@H;YaayDCj{z>F&+DtYrcug`ZT z>!f{!w88gea}Or2g{SZ{mClE-Hz+YVQX7o)Hc>qo-7lOGH}0l6F$lT)@(C^V+PVso z_34G%3x3w?2L9R^EM7xY#}$Q8aYXW5j2*^Y{t5DMPQ^y{a}H!o##oa!h38TSdQ8^y zPQ3=#bCUBU>n!6B+IjT$rDF<+&XA|Gi11lpj@O|N_p9)t^Ldc)kjC3VqK|pq&j))# zGbGi}MMZNwk-AFPvgd;PN}%&L+Y7(Bu#teweMC4cZAx8~W%^Y9n$3LuTBV>hBX#?w z=eX(?_2;@2cz))DaD2&oPKC%s|i>sUAB818tsG@>k0A5Jv2 z1{p<0k7$=-tQZ{T(tPI}ZKrPem55v!_+^@O+-Tx)oLtBw(D!>Lfo@i!*?JP4b?v%k z_=8EmNsh9YqpUHytel_oZTkwSWD{0#$`SGOHCPx{yzF@XjlN(xsYQe^1g$^UbKZ>x zu&MX%IHuUF6-dXXTcmxMV{^}cv}TohJg2bDk-s<{76ES-n7r^{FnPs$=3&V|3kLFx zIf|#fsZ0g4_$s?W8}o)uDj>L3dI{;m(y=Y!A?=-Lpe4u(44&;S<=o{7K+l9u8}kTg*JlE8Z%awQuhdSS{ABw`N^lkB@sRZik87TJNM_OZ=Udq^!Bz zFVJ->lE~0rcA^#jzNjkBmfm%2MS?q13X=ssfcAF0 zXnec_dM^eJSvFmAS~Jz$Sb?v^grwG14wEv9tgB3*MCrLTm*c8vs3Mkk?@L8EPX4l` zQg29iIDSvtBUiT;2F(gVW zI4Z@ZXWezmfvLYq{x1iH4&6~TOHesB_HErtYDm`=v-4@vb6e}@>9{AgqTPX~U}F=N zV((N4wHz0Csy_8iIko#5O1+R6BM?&M|8NI=?CSQr;H{lZrl!96@7FWF zqwNzy4u?B0o;p`;n>~!ADmZDN0;wAaJfVj^X`^!XVKf&ITkATWGJfu%zzBY_xjP+u zKd=2AFWvV#J*z$mPo#*azOoyEtGik;+H=s3>IGUyxWu!OYjR&>xGI6O>QLV(+abWo zVLWK}TzoD3x^uKMnoc|RM#_($Q16UJ{IEmL9M|{MhdfI++-UN}fPIs;Y)dY{cI~0t zdaGvy+GENg>m_uv<>}@z=bj|gqx{6dmC1B(ag}L?M27q)G}z~H{92B%x8l>GU#&jJ zpBl`X4Fdw_XJ%eTt3SUy+R4!OdYQc$N4A#1h?ZoU_7$L=TDFT< z)I-jYOh4S`hWTMq;&{h-it>HPZ+hbgCHnV9{^>c~Ga}T+ zEh+j*i26Xa+PmL_nU)rgnexO2c>*J*oWZ%=_}ijdLlSk1GTv127aZ)8V0sjU_$Vnb zA0r>%+j49wH9q7W@CWkiE`Rd~o%#!3l@$>>5}}c8zHW^5VtYEbGsxsj>BT(S`{FVh zj)-$;nxtA!6^?JlF}TKXMc|EdPhf2~LM;&HFMfqb6`5K3mFWu5R!#dRh`hmXg(orh5@l$FQb5GIea5tCOpxL3+sLoOP;@AY`jdK|W- z`~)K57lJs-8Z6}*(0}_z9DeaBiDd?(EPEr)3^Vj_KMrfSR-_e{+@t=>;diN!=uO%O zbpD5>pSI7711g0!b+xh-Jx!+~yrSSwb79ylL-pw)Y{r{FkCG!HFU2lyYXt!i`&n@F z)i7KA-ygNyqaF#w1cz1F1loC7s-28T^6uwX-PWOLHM%tHnJyT9=pijS7&#dbKZAYy z0y{qn0NUb&+!u=gqh8-M)fJjQL>U7+0!$xIBFrB)>~i_~VLO2l{ORu58Rd6aXvhaq zTfOPc@oMYblLrc&N8DD6!Hn=3?OXxKL3~*RfCb=~NAMYd&S=Fkcd`=$obiZaxHIxdEUj-37I@|J>cz6W|Q;#zIDJin8vG>A?9|-Ka?eE z+3dM}xS{*-@AqE&<_*D5MJ7Re!wJ8V^2*R}&K72)6XXP?XhMO zy^Udut1sU`N~6_nqrV4ga6nKG;D0500s-hK+A?O0a6Aw=tM-CC#k)F7yp6xG+qgRU zCxW1EG)ss5yE;5GmjvsbJcQupaDklv-uLrsTVoYknG*Lqo!&e=Xq6F3{Ia!D82^Zz z(`G_)yh^X$F2!c@{?v2(Cv>pi*#k64bdH$Wc!1af4ZE~iP1?%E@%GHkqCxvs5gNei z)d}OcO|=7$GGq=THij09fYFZMyid4s`RC&F*Uz7Xo7ksSQ`Gb?@8ehuO<0^+3~zwU z=kIHYr%!kpv7R!T8`?5*SPuM!<^-dJg`(*mZ6G)RAx{8ALdk)}lK^Ioy|C+3+Gq-8 zvB@l7p)@=rjgFXa9!~o&kb}|$4$$PX$}dO5k3<-d+2%H(0y)<19Rj()$=gv$!p-iW z*`ANE*P32#*I?G4D>nD zd4dhipA}b9jZ~-2ecz{Sn8!LFvNA7|#gp9tnPIU}hIbZW#ED+A@~ z&voK|3&(+*5O2AE4F=5C{pkEH(S0za^fO!f_}XKfcY*b8zWV0HT%j(!D61*Jd6F^q zUChR$&-=)M!WY)h2YE>VmWws2B~gJ2lU32GiS!!=1N%N~yPH!MHlcVdGht_oPZVuB zu5@kW`h57cPYO3H$8z7o57?eNlP_FNhjN9`d(jI{Ua<=F(rC82mz}&2Y@m{yO?5SI z8AnPR@)rwRye=v^tCO@VWvXzNS7Q;F!SOxe#zPc3B@7$&SWj{HwcOW;-+xaZ{@wbL zNS7ckY(M+^(-3`n`^Je-fJobqpklJye;40IR$ayBh zk|O)6j;>?#7PXbxFVmwu>1@rjK#1n)|o#`_X{DtCu1v>YZd|<`P-euV{@72X7%?4IkzncrJrz&h9|? zmvPK2sv%upn-11nEFv(4(jHYB~Wj;2Q47Tthd$Jq( zWAt(T^_;9%;waY0<3hGNzu6lYvHVdep6_-$T}RWKnS)dn#|aRQMV&xZj8bF_!GowV zAhjMmRC92Sx;nPHVeGv`Xm1q=Dv2eTpaX@^qJBB=GlN*0wL5@hqqcN?Tp327&GxeDaDxxNtbrXM%NVxq6YkG!H z)ZhQ`NKJ{pZ5^G5|7xXuzdstUb3Y45LJ5Fax02ehX&@&y0y6iiViLkXP0#6Mf=g9J z+da8+;`QOH7Y}1@nG$>=-!fbkL04cHXiud$EZ$d|e=#!43e@HMG+}gI5e2;*OAeV) z<1RTCQ)&22<(($WzJnidImXchVo5k=jVx;}MdxS7TU+^Q?+Dp6W?Bn8eqt(MGyW+^ z&H4tDp|?VB8P_uJiM5uZW;aCT1cdE2Y3rPN?PYhre({H2TNf4W9fejSWS@?(NDXvU|&Jg0X|I7S;Gc|3F|J#9YXlvnzf1ePdEdCgVH=`z^6N}Z)l`1_*w zZMKu*m0DhBDF6h+08ZTdVmmD9keIxI0GQY+ZRSiD0oD{JQZvp*nq3=PXXX@@+scq7 zuG_)%FrD_7NiK|K84|PKFGF+qm5#n+P*byxVzLR=KzS?C`L`?Yz2TN;j=i==y>PokQ{<3*V_b_xBOV%5e)n8)2)pqR?cW370UNYZ2DW?h3BcVk}5{^IA)l^UtfeFwv5N{77d=m5%HPEsx#d?m zin0yeSsM0J{JYo8`aE8!bUlt7)f(oysW4>PaG3qFdqd)p!tgzbU-@6UH)Y=_eDZJj zRs5^_+YN%kSd_$3IsNM`&6|qjnM5MUwb$DQj}#}KNF3LizTUBTqd4`l;rO}#>s>p7 z;>=r#lcvnq-<_{^QGIGSdG+%353ff`3+e7)fL{tCJ#_sgO9rm}S40KE2mnIL03_C4 z)R83;98v}f31Wjgy7tmA`Qds@A69t5)p-eUV=`ViicWGSthxyU*C56p17YmC>fQ6n zFcTU|H$ZU5h)hfm!^5;M17b2FyJ5CU#j+JiAvk)m5=KV>k$gu90Fg%6GKbQBEKdLu z3w3mWzk72jbY&$`@eU7d77_&md~oxH=j0Sp>H@%i?B10MNG1U|S$mA;C$7@Hio;O@ z*l5v-o-f*X)L#(lvKOGmV4P=QaeDXrZQDhFw~bw#0?0| zNm)6hoEEx*VAG-HBJj{}E>la`(`%NGOmO`LVJY>1Kl&&#N}Ckza^^WbxQ{+e2Y`fN zAyzc!R0UAUBvKR>IuZ8Hf&E%0azaHwfA!BL1y# zz*Z@ex?oGBkKGZ?P{#H56_Uq}x0V49c0>ytaRFEyc@3s4|Ld+>q#&Y?K@Y`(;l1K@ z3#129gY;3F^-*HL016Ka!IFvb<}0YG1(fUwaMKC{Osy4C79SYfxq!;A3=<%==v0B7 z)N3|mJl(x$2wI@1j{)x>04$RpeU*w`d!z@zu>dUq?97&Ic>?lt1CT*gH!P5S#0@wQ z0Qh<-koe>VR2%l4lY$?kBDLgdhLTZKPj*F7K8z-nP=_KNlU?7fb0V{m{J@<7&{7P| z-V@Es0rcuH><(Vdt5Q3a|5i@rtrC8nr*XW^Mc)am7;%>q8~ zIjC|HA!0V%`m5_U63*%qs)A!6z>^mQ!SNsfHSLW&d$6MkH)t4zWFVlJ0X$@3$w2z4 zoAf(C5^^+x1z6B53|P`26v(j;&CgB5^Yf&!T%9WAL8yZAmTawnt?W&=l1-VXcR9rX z!7MDerHuI9ahg53PA>$M$D57aTG81>y)swZ^=`@Yz4gqP|8=4e=k$p!b7Z_ z7-UdNi7dpmUP=s>Tn}Z7a0!tR~#czwDcoJb_@~3bO>EJ1(CqE0wv zswQPgn5ZF7-P;=1$A%sXr$rVBuNIJ>xTKlXAUFuZHN_wx3(JBBjJe#51tWQgNJ|-1 z!!0l{p^6;a)Yqvs?q5PWMmnKILdb165s|#_gz}gKxb;AS7&p>n?wZ#k5z_qREwzPo zXhGsCp))?YVjF1|Nv>T|((ib=jpB43B^~C6|0y*mXM8tE5SzmRT;Ck zj>N~?>i57&^ z;7P;p!4~Msd+`wLs%;hkOU9_g5O$@QL^lP%Jr3A!AUymI&`!t71Ymh5a6J5AfEPsh z>B?)aHLx&RKwVW>1}{2C4~(e_I-;AQ1%m20!C@@@8H#KnrcXjlaGa~*6NSZ>Y71L=eAJPWQ;)sWm)r(K5W;RD6g z$*^nTJ>T;F-UV6UE!mz2*@89p`(yx=941ph^mDiK54{FaKumWkCyz9-Y>LbJisKh} z^Y;AI^Tj3crOoF{d*WX&s2fhimrq6@M_+k2?=k|*OiZ(MTuAf-fMS>*roI8sa9-vr zhvxABHAo0`-)pmZ#yf`N(p$s+6$c<id`&OFrX3VuU6?uaIT}X!BMXUBQ1BNvRgRsS8R!QiIO~(IjRliOuh>3}{6#R=S^t z$xKM?j^r72UxXhv(!_^ss)U-M3_##$#(tpHcbtz(5Bm6kcAWC28*oTXDF&fia3Om~ zkc1BJe-m(}=#o4!=HGI{f*)W}I_g$l{Y&=G16}cYB4xIUkgW@SOACIS#XxIX6TNQv z-=|XSZB6WNq&NneI7X#7r<*vxHsuuUqU-idwn?=o*6B2xY?lvqRG06H0+h)c5Hk>B zbn49m2&*0`pJB=GS|Oenwv6j{nK4-Q?{%U@B{>bgE;7Ets$#-?T#*m<1(J%hr|xnh zy*aHwJ2(_Phz*3=JkYP$wb>YKIGnS`0T59BIF20-K;oP8^@(p8>>aj9ddZKZ3r<&m zAI|XnL{p0W9Knn5zep!%W8&{4^|+>n;8QbsIm?JgAU7dM5Um~n&HDyH68!UzxoNS0 zf}+z8Yk=}jx1~$rd3eTBcP^g zH~HBL)C{R#->h$09Kp0iig&Hnw{sQr#^%V5bRj`FC)&YbUY@_P}ewlP}8$F&61M62XAEN$jjn#d_VV<-X9GPua<$pzaogx1WHwwEEF}zjBOr@g{Hs?{qx~X z&Ko&c4l6f?EmcchFdTcFZja+~?DLX68}E35AMdrY1cSCzgGEcLKjQ!^F;KTOAl)9v z%$Z|T4HA3DzV1!jC8v$<125a$mBUjyf|CbAK2s4QufOH>;tdkOI}~l6q}zhH???ie zdwjc3n8e=ECcDR7gD^5JBc{vm1k5e>0W26iA`0&t_k=4wF=YjX)F9c46%<;-K7iF9dpoyjM8$0NUd)3D49XYKPyG7(R zpc~GB^Owaht88s{55{b<;6GQhB%;Yt0672>xQlQZp*N+hcq#{X*pUion zgT1lzSbj(F&g2FJS;O@7J*w^jN4~$+O3K*XSZY ziuQrkRRw1nUw{%2S&Ark z8G6_1(1YZK#ia38BZU~Wfne09Xf{IF7!Qfdx-87b(h0f^*u8ywvibX7fXO=XBo`R8j8 zk2ab_xkj1Ux;gS1w{RcBGQnd)wCCgGOL8-iKi!;)M7?|I+6Vuh0Wt?Bf2`jvnPuQD%nwtmAZw|O`rs>G|@!cHKw?pm~fD!M1 zA6)yzy}-`Td&Gk~WS>3O>dmoy)TOTkxJC-u@W6gucMPhyo(Lj$gq{7gQS4C#K{`Ys z3c8O9x?I*MT_cYZkSJmnOT(x}!Dt1|+SBaS;%Im@v*gnqG?JL5oG04T?`b{eR*hv) z$Z))sNmISWY86LQt_a}{05D*DVWyn#=FwL3CnOLJt!vHmF{(PII*2*;>sMpswI2iMdBKg5Zk}f98o}y6yZ=)jjkkab!QP0MjT&8=9 z!%owgrljK$ARsi7z5CH~;%(dCM?Y5va%oL=?J%8VeH{z6Ap&06e)O&>l%+4rN=796=`=_p`2q zB~VlD5R9U+tdz7!%4d!hQbORZ!Ds+@5CF!$iuN4;Ae0@ZhGms@Ln0(0TQpcgnHU*} zw@!~A4o6~}K3@B*ckLA_WBIKRT4I?({rXLvXaPL{AB{yQwwGOD*{n1jQzd)#QS4>B zE4B`rFP8O$421+ok?D-#!TDoXKq^`aKPF78hlYU{l+tII=TtI?@1{wLY1?lQ`!?oN z)^6A9z}+%NsFyY(bI1;Au`v`0kg+y7b1!|PCUK{cMRL}qJjKE$RT_j!cWWB4n7>a& z4#BFoQ&}$fh92iE_oIFC|NJ@G0`Y0S;G72 z<*4G@9`O(Sg;yw}c~Y$u)F?kdNN%N#Wh|hiIb0JS2~b-*PVLk{0Pr|~jf#B#qm~Zb ziLzhMchkI|CbAE)UeFQE2LmkRM7dUZLjSP72Gf}Jf-1B&da{b9tER`di^Vj4z zYJP+Y2(>!yPj!o*_F2v{-ft?j^t@jYUds zSlqK3HAYUBLEzkn0w|+nG-Rz9UaU5}>5xexrM{v6LMWH!hPL_FhY3Q$C{oTkjOF<0 z=Rp2j**_kVDqBH$+vEWs{W~EE*&rU*t2A(m0KkgUfrUkt$}263^Jp2S%7Ug%C2A*R zR>+L=(2NafG2#I$6!t7?te?_iueYpF`R1u{?xn@49Ien0k0p7i)8jQ{R%z4o)CDBc z6Z8XC>C0I(L=4gs&0AI(oANZoz0#9xk5-v`Su~|m)03TK)>uF1XWBRwVH**YH&>#bV`85zW4 zUO+1UmcCa;X7SOwkSeQ=acV|ZmCS~SalVduLq_)VfQ>8mth&~pGICzEY>4~j>)P&R zk-T2BtiCP2wH#G?`~^uQud}eSB)q~9 z$?J+1s&U9zxG|Ss1adV&7z_-kx&ULgiIV-oYsoU2%rHQXJQ|wn^WAFgF$ziqn5Z+k zt*2`X))J9;vfJyKMw&$Ox|xOBMz)nR5s7yvXnP|U6Z`*z;`IL(iC0&caFf(O?uB-% z6=}G6x77?4TNO4k7QBK{Gq5=-BV`1$s_w?Udl&!)#8JBlGU2SGJ_@l)$shV+V+ax| znKQt<0fnEwe|t6P9E7-zNnv@!IHIaO`LeBqoSX%k}-2v{n1&H_caEb{b+A++p zN1S1lSO)#?&)7xPl4fm#Z(UhDn$T6DLXB&mGEq(5j!c#rH<_2Ep1zCbyiQO3b*i6M zK5bE8=GK$qp!+I-Pt$zJx96uz;Y1|f=~paF;%qsZ+3Rd2UZ~-0HCb+th{V&9IA71Q z^g7?T3&NdmqFucZGzy+vf{hiq2I%dY($vnax)-UTyA8Lg!<>fudp5r3oO}MxZl7mp z9<+|>>B@oaR({|Am*R9-?k7=ks`bL>k5&keIHy4BKbK90*)~D^b?GbYctQ;mT^(6QdkgJh6nLL6RxAp zh}?HUC&2CRivNdN>4854kd1xIb+I3ZqO3p=;0>s8Q+Pd|>^zn5T?T)|MS z{a)1OAkpd{#i^?#VDvZ%L;1vm2%(WK_;Qf?c$gu@Mx}I}=u9o#epfM6vWQ}mU@dYW_ zj+fqUCJbtT@sQ$x52Q!6hB!|=NpTS##b^YgMghPD<(8V556*yk0u0Px6S(TqD9p;r zY9ZfHSIdCM=zuZ=W4yYSpLWKBiBi!R5kL&}Ib8>XWHhSeJr&8#&LGWRSgkdR)0wDX zJFd}o8sy5XOD_f^v&r)SK;8%h<&Y^$Tt{hxkfw1y%k>DN*2_e_la(Iwr;awIV_6pq|2rt%pC?Lg zCSX$6OeFDIwpO5GTBHsnyVk4{nzlR>KX^ofxi2gV+6OULW&{YaZbAAK5J-ZjIg)!H zYu4+QM&mhL?MP zYzibaW=1Uu3sc4RGx;oOz&tK`L~!pe;KN)L`Wag?%d>|F92XkM!1g+0O^H4Vp7@ht~y_Sa}5> z{yP%SN|THuyvT|6xvK^Q7nQe$fJp}DqbmTEn1pdEQ71=WsTzdJ7knn-{MICC<^ApP zAgtfk`6!l}cq*&Eg=W7Pi#KSgU>@1pypG|qDpLbrWDJWy@(|E+mnUy4a9|pB7=A}k zKnMw={LXacTfn9wED|(ce8IB;!F$yw;Hbg_zX%z7z$}u}$`aqzlKgcQ`Opb^W5NJt ztntxi&IgTDWQme!I60{#+T*t9XMz1d)jzeM2!|uEOauUNwK3{lEl^nO`Oz^wvKQ3# zdvQNC_?9wYUJL&CY*Y5sR5fXcLR~>b^7XN4uPCB(sgq=f>B`GD1+zrem>RX=wvDlv zceOAEPEsz^IMZnn=^B<{oK4)V&j7*sJ(f&E)5PKaGph0JxP#xt0l1x+A$jZ;Yu=)GH zQY(eUywNtozgcW3)`RnB1&nqroqjrGAyP0$DDM+0Ove0IgX`_%z~y1?W%zNqYyGYFAU%iBcrrs?y5pY zVVqfT67FL^J@o5D%d>mpX%b?DO7luoWMPc)qLb)t6DLe@3zTg>c zCNsZt+F~f(_yy-sSjnxj8z-A)diG?3#HI=m&@f@B0?iKiEdF)oYOcBoKD=tt@=PvpgF=VTPI+{+VGXd zp$iUfZw)KA@HUSkT>+D+Sx^i4bA=#q8ouaqLuDf{%P~)4w234JUJVAx5Hb$q$9-*Fw0u zCgjnAPl7;#SYsZ%2ej9>qK1`NjIr;>Jhx(l3P-*SNovna>TFNyj;D8;Ny4)v_sJ*! zqgIL+x*qhO)Jp$SoK9G!OogP(%04iP?*OZkZu%(rJ|f1LW}k=2 zM_W23@`qJAQ)v1>ic{90L`M+Z!f(Fcx`@%@^(mdFfX@wk3wsSqf4P`8xE-1ALslQ` zt5>*dE5;XJ%rX=Ycsw;8q7cxl$W)XMC}1Y(_f`UhV_G;4ZquF~P#$kURGijwY|3YQ ze+Fs0{(n%M{yTa7|Fl}Ed$zFWybvFnF2P##pV8MsMD%t3{|@?k34W`&@_7Kt6TVMXk`Tre#{gcv#h`v7E zUHdwE_x0r^0G+Yr@F@cUIA}lZ00)JvycQ1Zn`?9vOhjJ?5R9y5UluQ4D;2fXny(*lMy&KZ90^{ASG)4e{?=YmYfptNT%MOlNm(5Hg_u1390q z9HfOqFIfo#V;!Kaie%Xx;lxO$5I#WdhC7j9YxnQy>v86t8e-0`OK>RyL4msFPEpqS zhXfEnS3O0JsjF|D6Mg15v*Yooy;D@|#TzCM?q|G_>7LE6*>*j{hax}Mw@e&%?!26N zdK$w5u66&>Htl?6FZ6Sy$B*_cKWBc!$<{Eh&V8Mn*!0M$dDB-1n@O|X$Ik9wn9Y4C zuq-P(9{as;p=bMjlycvF^j#{;#hQ8P%o@7JsgHKv64BR9ee}U*q`>XuKL;OL$?iyh zaL7wO{McmPbjT$B*7KK#^kco3pCI>n-ZLo)eSH2=j#)o{NSa1@Y*dHs$B~QnW38hv zW>GoUKA2iQ4|FyrNejgMn*pjRu*CM!-(0He045G44D3g$3)UdoP)Y&vX;dSU1fhKr@!G+YV^g9oMZnWsR@Dm#y=+6rX~hpBFS!) z`DUq$K+D~f5B9I>r}cp% zNK$ArM5Dpm%lBLD(WbRVF>OsGjAzqmX7cEWmX+J&?pCj85C7+!pF8+YQ1ReD=X^a@ zF!jqL8nKLO1v|=nMlHhq(kGQt z9=K-_$aOFD&V|k9Ag-U45_xDHRFvE^vdyDP;Yoc_s2~$0XCJ?Wf17Sa z^RPXgSCT62Q|Zt&J(uwYH$80m^)~BtPn*U_^>YEB;KRs*xlsz5))z;D(&nP&m6wV$bPerE5wuo0bbyra;1AslgC1u9HS6i@& z8u;_$sYAB_aHBUF1y~a;^Z;=23|V`WAbn;i9`f zwGV)ZFuPiiwV?jqonD~qm$QVhHgQqVqHwsmA!MZ9?sRCn=i>Oq+YSh@M?TZXcG4KH z|IC5;<4nKeNmE+NGe@C$b@IR_9zwgAlibHy5dl8dx7tu?l%zElgMP^_mX3zhL z?&7wMW#`Ouub>z8i+g^jUGqPlg$&d)uBCtP-qimY%3QH@QgQlvGbRE4P3i98ztGn& z9$rzDzrT0-26$+44Xn2eW(h(1q8Nox9 z8;QCklxC-Q!bsV`>*Ia7@7N!WSIenZ1N8I_) zlwRzK+b=*)wZ4MNjA>D!P}6szzv`%-xVH|5Eu{u*)Zb0{`SADeuK-O5x=_?7YU^C! zE)?4UB2KDee?Y*@aSwe7ZQ`|s)lTZR4*&bRHzbr-rB_eubN_DmYjyK85FVdGB>-Fq zGylrn2K);*oBNSj98>qmY$@)ff!Sgucw|t$*>By`*v764@(+4bBT=7n!U1sfs{kmn z!6(V`-JEbM3MSD=Dxy>g=1h|XPJZBE0obo>@~U0d6+g&p;#c4?s^esR_o?9PKOp&7 z&d0+{{pS(<>zNDde@fE0YA5%Bc0ZjP-7a7_gyaz(i@Jk9ergG!R1oexh(x4|Bki*= zGbO{{z0%q$D#>G^cp4+?PVvefWT0?}cgvp;K>mi1MGZM8q9T%P-}a;#2W->Qg$-i* z$cXC~`?}e1TpsZ4qZ}jI9%lsVZx52E=7yZmG?-mD6e&IKNJtpc+DMl%`yE)Iq#D1M z#)9JhyZ`vjpKqnAl-RPtBbfO~5+CkQoQ`_g<|D8?79z|PYJ@F5G$21SU~IuswnM15 zED&2*Ds3EnJ63o3F1%ehqz(7)=xctfNWqXu;Tb8j+(@yRNQtvZ$t~|pKLj~lly@Je zi)0j#26ZFaxLl)Ld97-f;j>2MU|NcbG0G7<#TNir1fso6s5?miFVNS*LT$MSZzDMA z7_*fm+!7In!yx2jW3fDZ%s%dwX^jQo1%RVu-7V~0cjDaN=El+*J8~ni87}wk zeGBv>Y%%l9MB%p3VPx1ku<{Xe%wWn?6Y_(mpfN zr@^!>)xxo529(=O`G|D7a(Lo0bJJ-YPXe>`@P3wzgX=Y)U~;1rlXISM0EkM7nz(M=wz9QU0D6o)`dGKuR!}DD1|B&+& zSg+Qy7&qqW{!9NAPCfU{bC@+OAagAYT?YPz{4002m8~ z#>#_e6G)N!u1UfOQq&b+?R;OpdoP%Ry3X_Ee3Q8(y#_-3n2;WtL7;)wdtA(3e+P?T zpC6l6yYD(PP)d6I2=e$9?>Tw~NU!?f2|1vJK_4rZ`&A+S+(JcfZ$%{V@Wro}d{-zv zvMxOdEj>F&bwL4f%jACN6cYPHC1}!n)>JZkkA0C+*Wq+XFP+xz%rpJ|; zAo7Azeh^5_2l0fZ1X>=NHQ+O}Rk|hXW$(ryJQeoW#j{QJrZTZe=DEj&FINV98A$*& zAL366HmEHZ@hy~n>Q>Q#2!A3A@s*2x8)|Yu!brTkuV@9g*V>N)RpjK87#pI77=tVr zE1*DETNq7KwiP1#whjAj5yVyNe3%p|)L7qzoV|z)z!|}v3lJmB)$O$D7LA1(Itb6Y z>ZYbg;FZANAMTSG`$rbAa}$<9f<_5RHXL-h<>@xHIS*>{3Tg`y`JS}@n_;P9hx0)! z1g%(CQ&305{XLtjYq+RuWUFshtZ%WYZ+%eTUQplJS>HWZ-*ZuqAEN(Yoxtu>{6Z8o zRL%BisP3a88*z4I!UN#+ie6FH@4|?nEHJ_Bd8RQCk18ZNh+S}JeX#5Xrp;XIWU{@W zi-iNGX=F_0Ft?%X7TB};d_+=B2GHm#g#&3npnCuZNl!IUA87s&4b4t~Ts(Nn)tJdo zTMBC`dD@;Z2rZQ~_C{zuM@l8GK=0jT^Ig|86%H!$((-ued<$C8@E?YyD=bo{fXww| zS;99zx{DMkU;kxcU%^Cr(Oi!l;Uw|kWD%{}sB=d#`_L_>AU-*ScXSJq$Db7sP}kGT zxP$8Y%iS;}=OiTTWg&0e8=!JrY`>WU(w<0Bu-@%#_4?iFGXBh`kmb26tGHrYNMYN9 zuD0;`wuisluf?XK3auJ*#N&aSTR`L3Sd zU3m8HKBew=x4Zkpx(5rphq}6l=es}s?jB=*J+Ab6;`ZyQu-7w%ujjg6FU-GQ`u%#D zgS}@}sb~Fm&*pD6%Cu+Se$(!B^>BXf*{i4h&jYhCabV8--x!!xTmMTB%*?NyK9y_` zi!rURrw;d zN$x zXhCYC{U62HHWwT7(@>`zcQd!mLZ5z-Z$)o#zEHreh_=6&b3_UTJQ^3-Dw91>7>f^{ zBg4ltb>N)JqBTX`Ow+*Rs6wow;`Y-bKgKvVt02*x8ZDk%L?!W(Ok7TF>&{MnV?Uve zv8I`*B-VPmRJYsEebQN0*aN-t%*rk3%&o>%f*dF{4_EDP9E+{x;V26V*?ux@VPn() zRbl_pHsD6F*S};d^y6t@fAY_%d7EyxP>-KI&o@ALF4fEEtD0`) zGFRWgs|6b@4%}xeSFa%ON@o@ll?E_(hy$}mtlr_Ez?Y=M zk8+9jhrKdgl)pyin#eO)fDjEe6j{Tib|iy>HlfuGBK)-xRRA6JDDi?P$4BKlDs zEpeI2J5f(Jr;UrBecX`dLwDk^Ce(rA2i@nz4&r9PiUZeE?&s2V>#DFqSJTuqUdz1CN4Pk z!{}=9#qL^yZ|rX4^o@DeQ0Jpx&8??ia}hr4iCr`Bg9I6%MJT}KMQ=$I3ia!@4J!cyLN5^S9EqZ;KmQ{-{BC5|JtT%5SKDap=#JK$k zXZIDH-p5oqCRW1Ztr=TiveLQU1D&ce`Py4N6%s2aIp*ch|KzLc*-^~4iZ_;$V;;q{ zg{PZyqJ|f6FIl+sQgV5PYx%=rDps^73+d@WO&w z&wTl&O^xs;z#vKjf`zWIYflU)p>-VLx-8l}&!j)-?l@7PB&!}Bz5NjRtd57E`vG~g z52EH!mE91|DO9>vee*z)3Z;BkyF%z=B1$Tg2)#DPvJOwselaAeEtEdpd_&zl$~RIu zh{$V%@K9EA{w*WFUZ2o$)Am~7bgz>fpH_xoq$B){A@ZvAEI~WSp+V=-#ixbAZ)rWZ zs72Jqs?m>T4Iha%sN&eRcHD(&rz3DFS8lnYUxM}6fMqDv;vg625CeySyLZX~79xuR zKh7|V`@CzV-giD;&|`wt+cKdq`=C*H5pY#UW{{~t$TZ&dpjvw)2}rUrjtrNoHA+ch za2zs=TmDgNJmP*k(PlDk%&Z=xlB5^vKG|3hc-3}tP>y~)T0nT^iIAi!xt-AfJFxOB z zin;VGrdFQ6&;4M1(Smxf$i^auV6kBf8#bp%J=X^R(yr;e@8(T#*1f<14@9^-bEiDy zr(UP-(#Z|}uGyG|@I|GD;yGxd(xlhb&5Q9OI`ErI3G*Wiv8RT*)&Ih%qnGN5CW`l8$5 zQ@T;K)indU=ZLhNivm>)5L>K{$DU2~8l0&6 z`8YW#vGXDywzlLhes}wp*5_iK{%U@D{vO}$D|1V&B(~x?K1p4{1D9JJ)A|T!-DXlX z=eAeu+fJeLw~>=QaxZw?ZZB@${@UJfs@*e!a5g=Ga1Y{1n5aQx1%gXp9(nxR$~h_& z7DVZK=E40CLEPh@Uk3ncK?A{P7h=;wz=x3Xe%Sep3P+A1&kK=hhcFZtQeoa#uJ+3> zf0P5DK>;M9`#7eooQcxyj?s~503uTak&~AgSNY{f&*89r4-EjK%X3WYSlF<^$VU$> z?3vJepbv+2>9U(0Rpd~5h&!Y5L}|X{bJ`JTNgw#(#en){J03#lT80^(^|4>>#~X$> z5}uz4epB5}@orWO=R6;}eR-HS`ftTpiS(w$;DZ~67vpbq|FPHYn3rBmcJ&>}kA18S*|LS~R6}B{A^TE8WJ!|jsb=h38l|jd>}x{yq#;E@S}pn3D3v4$MJV^D z`flf(?>Xmp?(?`G_v8HQPs_Mo*ZX;0m#b?y=+R7_EdeEe9?aP>@~yue%&lSt{ITjz zv3HJw{9&MGYpi~S$Pr4|b|=G3B4FTaSe?lm3Li$axZNaqRR;ub9R%kKg`EJ6LMnm^ z>ZPCQx6`&r^0YPgpY@>Da7SKhI7=yA&V9Q9PX(t?rNywen6J;c0Cc}=5 zB$qg)ltrXejGoehAwo?cgcGFOOyV#|SF|}&BL_(_ z64H4LH_^d>QEp)-MGOEkaoobgsVI+Bh@1cfflAP6<-#N+n1Y@J#i00|bRhh`wK6>7 z0A;8HM^IoSf*UC=jTD`yZ7~RZ8v&_U^XStNCtjksZO|5E+I9ofKAfxk7Dze9epAlo zTnGhmqxWrqNLFj=wn}Z?Y!ESa?&ra5{6$w&(v-_1al4=`9}6H7p4sl{dS6>gmV#)R zPUZA4^~I;#zEucEu~Af@17Eh9kSY7Ws2&V5!A!CPbvS@<)UQoBjQ~~9At&vu^#)9S z9S1Pa3e<6)WM05{m_{Y5D3GxL8RZg$Js6a&atu+l8*#x1DM~?7R9FCVIxSL7T-q{! zET`zLG~2dZ+0FYaa&oKMa%;wNE63c*ShjINd5z9_&5?PnIeG1EdA~l43FUX|Cl58Wgcx%MU$*cTpJ=5scMVyBA*42n3*i`8}UQchHT9Vz9QSae}5 z`xbrymCZ?g=imop`KTh!!U8S^G9d;rlUz0SO zl*8To5xM12?d8$qv$~a;@WCu! z=?wsS)|iyYN=_c6;(X>M-Kr9osOE2R7rpZcaDSX@ZCP-DauqDR^`xyvouC76%NZQ4*ncG`z3-o3(g zFt9|-f%aP?Vpc9kkz$%6&X{GCB95NnA%Ky@Y2rBxdPXH2*Z1^|$sp6aqvA{e=TTjfQwSe^~dMBIcUWhxzy0Np1j-sG-w?G~K zkX&_RBX}90Ao%IvrXcWBD>Px&L>6iG)N6+Khz}lb_RVYdzt$Y^^!vdaB+?SB*An8| z5_bImbTF&9U=3VZ2teC8DvCfzkQTsnu>u5U(1KqZ)d@0i;oZc>mor)b)s-~K{pny{ z!^`R;KxaOPm>Nnp?ZC4ma=?Aq7uwCP&p%q-N z{msE#`}@IsymLCQ6TX&bpLWizbUP}JpSZbW{U%Yg$56k=$gRgXx`&kC zW7g4QG0|g{uU)#gZjuI9_?TzPiGjiO^=Vd{TYU ztyKIr|B1f(;@&faT`8i!zIk*0Z;tc*WLuHGve(-`z0=Jhb$y?EKJNw4HpUjd&pqo@ zBBv8OuODany|{}Vi(6k?Te)7~mn{#U@O`DA4L=~@`;%>rVb_FDczB$zkQ8L$I~m_o zp9r(92S1-l5KEAI;khOe)}16*mV`&iH%}KC9_wrBN>zX23!m_>D_+7UJpAVUe`j0U zc!fPLw0Vghgva@E12hE={5;_;i$JWXZ%+j#H)?@}A`*hpbrnZ&&+uLXdcZ{C#JyZ94OR=~m?x$>HYe#Pe(jFUNH6%q!( zmVm`U?Q$p2A^i{b)rZBFq7_7+`HQ-85MB{!99n)7OAp0=35sP?%1^Rk1DpmQvM3Wz z6yC>54~%g*9lw47lE^y^jrq517knDn`(9uoc;uo0JojuV@O|$2EB`a4%=gQ=u6+Bn z0jaAFAcqwDP}yV>TW0IaOq0;o6XzUjBlk{a$leM=P&>a&nEH`YzWvq zTL9{|OXDO?E+FX$WQE?V>szB^)`$p@)`@nZZI;sJ{;J&96_*`IVY%;uH6eBLL>W{X2s8+ zv~u6`Pz`Y<6p21I?oBCq7gF^w<-uoM`3|e8Gg53N1|@Z9fpk=YG`Fb4LoZSqu~sI1 ziNqt@CPNCFN>`f{m$lEnV-q}lyi7`B5uo?lA?h+~rKUJM+mxL8D4i@DyJB^W3x3$4%&glU^tM7Pily6mecl?~|R%whq+Q9*2f+iizmf8Yl_EJ z&bPwIWMw$nWvK{1SYfQye?L9SE`0-_=zb=~h@Q;!@zZ-dXjt`g?)ekjPEWIkx#CHi zv2=%YtuB=lIjVkVTP>?>v-<7gtcu|izRIrL>~WRLrz)pcf)5(}FS`fxJ5$*v z9DB{4G~|A&@wKdW5%Qw4+XY{)&n38JNRPCQfBN&AH-)2yj5QzaK8R*Rt0-Pnp@O#_ zm~!e)B7qo!bFXe65@AC{2uK1t6fyx1JhCvehCoO{)(PrEDT?HA%3(H;*jL5fub?g}!eEnZq~K~Fw6eQ;>sH%_VRZ*LvO zI4wPICM%(3RB*clyAg>i$2t(nO2sr48c&^;gbKhwlTs0gZ6%2MCQ3pn!zc-LnegZY zFTfk9(AF%Ca#a5TarzL=Cg$N@rrrrQ1!_nD8w0Je6Oxh#QDlEI$26 zLuix%tDpKZEz6nb_^L-1{@!K*$ukbuRv*`;H`Vx9zH@oH`lNNJsWyD@-M+Qe5ys~S zLnzy#6?VPRE%2U9ZdYn~7;;QW9t#YC@BLlZ#^E05=9ak;a4u>NjyC-M#vtsD*JA;}*A+P44=;>(hdjTOmq<&A~Yd%i8? z{XF3_(2KcSy{6s^ww*{E$^?+x*XP`C><)>Zc=Kkb#4Nw7c{wzDYu`{gpW{JD00MV0 zkR&Z=$QyhRin)aae9KQsaGP*)BMnsecQRew0hF@?G!_R|mg4XvAqN5!!VKKvD}03F z#iokh8UcUh2!~Ce#x(D87(agA8DHljTn4qY#AbMaqqjg|8p!1far^w6xo0n@go6kS7MQXM^04JsVGZWo5 zJ^HC8i>-av<^DxdO8jsVoRqp<;teOIA|Hz$11JeGWSRu5CY#^>`XChY#QB_X*y}H4 zF;So2zA2!z3z*R31YG!X0H#nP-25UjEMTAJGhM>fO*Iw`l5;65OGa4B7{=PlR|OW# zeSDY$IJLi}S4Zj2RCm4FI9g0Rwd7S9ljR~mTweEC_>gtWC7~(0?*MnANT*DmYem22 zn&eerU}m;)b3ZGk^3g$&O$B^|s@0WEtW!yw$1fb3Ynv{so@<|Nem8e*{SixPx~q?OgZmS6iN4yhp?;Ee#t99$vc7 z;*q-a;9UIOrH6MKfKQLo#{eEKRFm&RZoBZywrrXdv0cVm05N6{EEhElEo%mC#sjlT z_fH6QSuXz)J$8EeS@_$H!R6<{UpQ8nhgqyvCVju0h#gNdf2^6X-zZT09_sMNRzDFM zao5X!Gfv=M<}qbm$JO|66?|D|YTNDY1MdG)T;03l@w@Xk1KVa>wLa;-2SQ}y`P#5I zGT&Vn{Gd0FQk7U=Fy!Wfi|j>8^cNrf`=rz{WpHDCY17GLUsvATi%ef#-akC{jg3Br z!V}>V%~KeC!Z)4@;;L#Lb^bU3^;Gr-i_3fret?eA>g(c+s@tryLSDtocJt)U$H`d~ zvO4y43$)M2tNf9a(jF+}4Db7MQp#v1GDZ|&7;v++#Oxt%#+ysIabP5y`^VEkX~m*%NWHq_AJZcSip7`vdUveWYsst@ z6R@UzhQbT9B#RPB!8?7%x(gY!v=S*<(>rExQYw3(L`Lh*9jmAXGlw;=4#O>G$J&^g zzKW&tj(7SU+855({gb3rnMxw8Cc|EHc&N+JVb zX>8CGLYQ_Rs}3_Vojrx9$a39{Vrrb#A8K;0;SxZW)gRjeajK|adOv~F)0(HTme>&_ z2LV%%VH?x&NNU?F02?U$AS{Ymz|SP2#fh|&Ro=%G@h^#_99q3bPo;Ph9OR1E2Ndlj zcEUYNUI2xM)FdHH@xcOgs?t1{r2gqQ7y^yjtl5b6+n$V7WCesIdXQqnuetb$SpqBP z;{Yd7vMdi$c!G!#9nCkvB4Wowlro&@tE90x}&a_7||goPX%fo+vx}L1B|Ck;j9bv2sH3y z66+%xZe~2(EjBPeu_c3u(WishARx&U0ID9_pVjgs?gN}SIwmcz_(hcNle76OU3utA z^c(Z%tG^PI%XgoDTZIWq&N>PfCMXXX8+=1B5@r^qkv=3oAZfQjgaqvn`%7V@ zDk-}(xM+u$-*az)j)J?B4Zg_pv(-!^1gGDWdZX@HY(wR9F%9|>2nMFRUe&NiA~U7$ zW^N_6N%g6r%-uK$e!;mT*wt-yUyD;bMDi%EJDMA^24@fIt&I(*H#e4B{)L)s?X{c> z&Rd(9wrXi_+J&a#J$_-_&n0@&?IND8JzE)S>0BQCm7r{8V4rmb^K@wLO2=jJBS1d9 z5%%;6HoeU!gOUQ6r9QQX+@D9<0=Tu(59|II3wOtBL!U|lHx8TSY_WZPK9G2y|4iF} zkJV!C)AiS3UX#L5^r9;($A;e;fQD zl=l~Ea&7$Sx6iHjuFr+vTYI+lZJEK&-x)O_m zN*15Y&HBGTp?t0`@fTU|9ct<&<-e=R=}{~S5rX|MeaEk~vRoUo8u;!lEwRG=ViiUITFxT8JraxH!cEF}ISz2qJX zN6vrQxryhq0jFeHMUmA9u?t-+3UK5+5E_7Oxt)U&&s{~Buq~%@3;ZsmoNd@(vS!No zUZpCH2FYg&pez;rN|OR{OB3ha!oE0OaEXE==MmI4=^Wp(I|AAM&2ME~4tBz1jqBkY z?{kI^D&Jg+{`}S_@Ry6=?SeP~|LMXcnW`UAl<8ucvHyWfXC3_CmS#&v94yNZlOLg9 zO3;-N4k9MW0_8h;UmJNQ&CCQxc5KL37az}WJFut3FuVL5!PMqf4Pz$kkd3W>h%sIX z^TU?Q8><^Kes}OPur6U&|KOmxNGabPA0>k%x1#s0Q=WW@!q!D>l-gI#hoqY4ZeNqS z2GHa`T-WNp?_T@)#k(tMekjHH8>s40iA1!l=!-5^Ew}xdJlDem8aN&G-Gyz=R@L7U zT~4gOJs+mH&?ohWE!Q%;a96>K9l(1r0*)OecbF^=0Z9gngMSDqlI-QB2Nqh}U9eUr zr(HOJ(Mj$U;fH79nrjQjfqKm27$ zu<+H!Wv%VR2I6^4c$6vMQz6k4DDVBO~eN`BavU5bg6?c>JU&d2c86EIpU5C`HQMKs#E=1F%f zXsi+^2d^XA_I1b2(|-sl{@`w*vbqG#%)&RpKZVq*1~F(uR=Y!D$FTn8s(kK$jH3LA zocG;Qj{2BNM%^cIO2(=f9!WzB-I00%QuwovM*8aGwms|X(0*VO71r@mh`RwnoVJOK zoOO#A=hMpd-3lY@mSXC^9)I&I8H5{Hsl*DGl(PE-P#w#&dw1!AuN09|4X zKat3DfyW3i%D#i@(}5ImUWiRf=@|JsDk}~}5x{K$w$kA^0+}F0pHj6STo@m2IC{N8AgrA~Q zm+oVZI0wS^83jPQ&T4dH+(A0-I)K6*GPouG1R;X++b=<**?iX1Q1mK z3a7E}*apE)d0SyRu}@sIi_7iYVyQ25hj#@4)K(a*ocD16S6)M>1pEwK5^-< zGkIhz{iGE=Sk7O9t9=jqS@=XfEchH!npJn5v|s*4nN?Gj5$Yk*wg^=YAS8A)DRf4pON!_Vav5-J~kp_4UKo`!2^OU6JdWFIsa8iZ91FZAgh2Gat&L?T?g7g5nRZ#lyODEM{fVSTUhz9$3 zZy>n2WcYWI?REhGY|%+MKwBI2@XWm_^HggCoU;K;R>Z22M8unpv#O$Xe1#n$?&SH{ z64f9MGMYQvo^>+HXj({u2*Iz|Hh4GoE(gnqc&F@mm)3Z<(fEBU@nn30r*^{s)s|aH zq~Mccw3FhTk}ectg*9+12a+N|#L@-^z}z~%Xl%PrHc>8tsyTUTmxL>tZ-3}+yEJ@C zk#@>=vZgg2QlWhD;e94}s_WHB{VrEKIY_nqlyG?BtI&OVAMHkD`GmEP=+INbBEZ-8 zL&_u4`m+ChoM4pw)IV<0GR&ngC@|UwJLg&i|#A`FRzJjybTem$ai18c!n@*;HbvUbyBa0#g ze90$J;uXx8mt9m0mD5n$M3mP7-y4gFFC5;<9yVPV@-@f_&!QgL_M&A?!4^ zAO7w%V$Sy-*LYpA*?02&_jhZDkX^7qzQavr`N5iN!>qaSf8WW}ZW9+&(KRIs$eDQ* z11kR0C7G~5PEAr4dRv;GlH*lQPk_<$?^$i1f=gBMN40Bbs;FsZ8?ew*zwKgO)%d!K zei=1c_3p}-uUgO*hQKv)jp?fYY{T-M{@JU5S(Rerqy9GmO{3}Z0nr~bJlva^QOnPT z9=k7Z5}Hb=o(q{yF_;T`(&qXLalf6-R=_o&ey)>o{av8J$l%=%jGhcIq2&Xsoic#n zot-~|*{t}Xg?DE_{gK7hyt!MV8yD(3M8f}3AglCR$gsJ=B~b&~g5F5rFm4I~Xhb|J zvTy;2@kDQY#^MA0CUWdURinc<*>>(xpR!U%GGm{p_b`@5bee*i?03a-$VAy^%QTP4 zYfX%e2ZXy_#D6~N5#CwQCANGk?CAyvalGj5_2rusM+vlFP}cU97qL2DV>r}-pqo>M zBaPc$W?!44qDA_cO?FC+ayO^dyaL34zbbLHz#fy_+Y`t7Ktit53gFU_^$zPxR@XUn^* zb?Yg!U77d3t*^wE7=BxiMIrdt^zLF;Tht`-<54IJrZH5(I0sHrI26Z__q!Q57ZpkV z4mw8YY!^q=JVA^v4ctjGj9F(;%;XALWh=UQzWor$tb65laXqL@P%07q=`_|^2d+tc z+vtIeB$~OlllX8^Y5$Pb{*yo^s!<=nY4;kcO=OBl5(m6)w?Dr=(vMvX*a5fVGnuFF zn!hCKgB<&d>?b>DjCku3Zc^#MzY_t+J88WQA$fPs*NX95gyWSLNa$meO6 zsUX)~a!rW2LzYPU`VpoUM+<~iRA?-%2AhrS0i)052$-lu8UX+f6$6&<;Ab(CmN%#9 zLOK>rC`^5o!_lZbHa7xN5W-;r_ztsUAT|v%(1alHVjvwMGzuGibs&d&55mv8+F6M} z;~L;+@yI5k>0XfBQDSYdMzu445GZH*q~?%&avFg-(zcI$`M7iv8c=X%!Fkn-lP+WX z#tR0NjgTk357V`o<1rfn%x1N-mjlD^K7F?8VBfWN*wmJd(up8~DeekLpw49?IIbB< z1&*R$P^ZZ>6gtt^xNc(+d1;B8%> z(cMlTfpY3`)kUYf=zqS!)6#Qg!fXdT{ef|*RK%X$?B5I4f=Zm%Me zRX`mw`PQB$GrP?@Aa-A&DXxwB8I*(mW7-+V7v7ayfdN+OrGAoe99j_tA9nlUlf$?4 z5V_pbVN|WPA?eZ=w?mhpxqf~i?mEMF6F|MsDfW7Xs`#X3=u_?SADv8YazlHSwq>=p zHZ2nAe6FLcJ)LHga~S&FG3tZ^@&%fRJy{FsiF`)Xqt^$}2;chSyTOmVNoPZIse;wp zJBir<)~s>o)Ph~5i&){~Q}KJokpn3>;oxdDqJ-`n>#I!I4vI%oFt&pPX9C2uEaZ+UiJI zK1#v0QrJf+oG^O+TPKr>Ee5DVdXupND`Kh)#Ofoeq;|}&S?%A^b8VYP<#_2&F6)_9`TRoSM*z ziJg=dXrgTA%qIegK94vedFVNKLKIQE(do<#Gyk><)DyImrz^? zQeS{4dicJ`3j_ar|2mTyESRM<@#5_hy?rJhk> z5q^e?M|vRQ;MF{O7<60vTxl05QwM&SK3DINe0z5$DJRpcEz@Ew)9Op6HQdRhbKcJR zyhG%9r<{M;$zlcso9A~u*3 z%i^3JV}o6&IGg6oPaETryJM?Q;tr)}oF|-dyK@`|1_uZ6%3B{)R*gsU#j~o~Yq##4 zf%yZpYHgZAx7Ot-}XTucvv;fTk+sTq;n zqs#dZbS^$}zW9XYOrm3uZn18AvA!<# z{F7pv4CGGM5-Zgbqo@*6Zi!iYiN$z{)oO{gaH*|sshvxyLsY3#ZmCOqsoQwzzSUB) zaG9rWnU_o1!KgCd+%o_6vVifjz}0_`o~L~T7W^vMGb&P8s-U#-3hdupNB>1*?f){> z3pdub|KKoqPw%BA^Zj@}C^wan$WeL;Uq=Oxbk~;WE6a2CZ1Un=`ndS+-n~QjzHI;) zIVJ_QiZS`oSo=2|hPKmAfrAwu{u|`h$wWe6n6am99DE&J@c!Op<*#m%s&ac&FkJ07 zs@D#RZuw8B-oI+B&4Gl27}VRT{y~Z5mw;A@HwE2a-kiJm1L%!^ks}8rA!aH9Bd1h{ zH=S|tFDkik@OzWhP=a4M-4MS8h)M9TipjnpPurZH|1+2?|E{JH4(48Nef=YtJM-=e z1EVlo*CTM~Ur@ahVej6zFcTEuU@pvI*op=1PTTaRna!31RR}QH#K(vaxdC4ZnvhxR zyAQjyCYXk7viZZ^97>JEjBe@IUh^zk`Ah_>TI=1O8v+t(k2&zXar=9D{n!`!0+THk z?)c@TE%bX;4lLZ=pFE&CpnfENz6&8;GjFGNVD`Wuo9TB0-y%My1DKxJHf&+8VT$9| zQu_4BPU{xCK{vCAUB^EBbY|ziM5WK8XN0Io19{qIO>4DbTK9NRuhQ~F$jIU4U;ce# zZCl9hJtre>UJy)=d>wmaD3W>U)VJ{IqGijdx5o?8b)S8$om+iZ*Q>lX+c*-q_P+H^ z?f2_wZtVjDyLJ7aJRcOiVqHNDV>+H(%ZtSVxQExTDYpW|YM@4?^O_#O9N6k?U4OET zWm$#xb+OL-Ds0pDY)jOA_*E#!JaU^Ewe7}(5uM+RyQ2v#A9$oqwZG@!(hf8 z0r1Vzao?%l|A52zy|MNXKZ`Fw77?o(;jy$wZpM{x?9G47Lc8$u`GCC`-%Gl!wB>SI zZV|{43~8wU6At6!nfhZ0!l_+}sNq7HXn2B&$COVI@}yOQn*cjH5R(Z2cmQBm-vVe+ zh=ja}J`|wRpBNB~Fan4yRdiD-j&S~5oWZy-{j3EKimhB7$AhvpBPAR}ioovx@&Mq; zDTNfO0{~4X$jP@Y8xaW@=+h+=?3lT5))!67v4jtyT-N&xWQVf_C;MIkKa+tW0DzA_ zIh(mn#w;y|inSwTi&JEDTXHt2;hx*_7^t$Xg^N@+%0meRJQ^g}Kb)YuR46(nZX|Km zdftGLEfPUd=hdZg*d5E^`AFRHNr%Q6LOjdDQek4xYMG9(D?v!SCD{q@%~Iwq78xxw zk)RLy9AuOo$e^;jFk|>o5MXGD#`JcT0I#yoBB5 z;_2;*2NaF%!kuQjD=Lv=`;9yS_Yb+t9n+RqqDJmM``o^Kectjx`HMp(GJR8?OM_QV z{vC($Ym-%mAXZpuWtSg71hK&h>UN{uT(!g4y^~1+nTD{fzIz)?yZQli5h09?4iJ>i z_oK14KF!DCrSQ|0+uB2LV=cSvQ<*7_csb(!I+Y{^h9-nD6**JiKz%NWVkw>NCc<@B zdxH5DYNZv}53(UzS#>0@Sv-|iW$9;+pwyUOGBZrfd6-?*w}E`B_*!Lc3+zjqXg(b;)95!G5^x0lbH84fakbB`mI;RRTImOOUVQ{d8fwh{C5m{&A_Ox~j4$UX%txrN{ zT6<)zKBl;?zrf#Xy{$F$G5z@ZO9EHh&*y`D9rDKAXLpVt=%n%myi)mt!_dChHWWUz zDD}xz)n+=9gd(s23|qpHQMOJI!z2Y!scFM2Nfj+-{c$0#5(3r>_BoPRz>SH_SzkcS zZ~%%Fa%M9h3GCK~B>SpIBsD6Z6hEV#_g}o!FI|pSrtLND6u$VlgYk&#M7Rg1mfSLX z875eM_OL$%$%T`_;tD`cXz|j%uUpidpq`sFtc19{HRX(V&FUt`Iv zvU*Q$jQY|pYKXZ9$6LeL+~xl39d8`D037=yA?$pIfp*?tu*<$`%$>zY$%X^Z%;>da z76(xP1DP#cG9pmH*nlDkgDhN=2z`PI=@4)^EOyKs%-9mqJiKZmmd0>i0#R8)Z% zKRhdk(1zv{Arov&x(DdxZFLX>M4X3$ZpWPc2#S*tsXnn6KOWa#i6!FW47KBooZ^fl z;z-$XX034+qj6R%|5vIvW0B;a#N(I<`Mr_Vq=Ji%e0l0I_JSC{#1s0Xwsctt3fiNs zdO|;AZy(>DyCss{=Y5Aqd=GD|B+>B6->Kd{Yla=j1?)Kd`gp4&?}sHTVxjGo3*fM3 zbhV%hn++)Q>V!_=A^8_xJHV5Z*rZ+`-)0xi^XI8S$tp0!Vd=O}qBq#Leq}zX?iT}sh z&LF zhkt0|%%7TA^fyhs*`8m${=e14l@J_qg9B|qPnX!GCp^m zHp$!kK!6`{-UHP#Yy2pNnAzoEG`!*_^}Qe;Ofw*Th~~ zhd+<`mS6rn9?2CsZ()-OEvF-19NIb*F`mBjWZ2Z%EX&AOo?GD+ zhy3ulFK_6H%B#~QS%Ir>E6RT&HUC@_N66H$QN%_#w_fIu0OnH{9z0=Z$RZ|z>x~Kk zaC)nq*U{@&HAl(Ui7!ra9mWDnK*N{2>GyUtYA`?UFv8$fHm(}VNhlKTJU>H&6hA(% zUy@}Ygy$(Z3+60rpKp?zr$T9Tlq{)>_0Mebd@O;z@Ly|UHBXdAqhQR!B+b^2H>r8! zWNRf)KIO-X!>>q{d$&9w8DsZ-a2J#WC>fdgQqmc8((W=8 z4V8i1Y)*zOqk_*Az>5#4U^rXFIFGEP!0MO6<;yrPIK3J0)uD0t(j^31iI}i4Gd6&X zjEQ9!DqDk2`)@?z`6cLRFC?`4NkT>{9+7jK=gnd^DRdyMMkKR&4V0kRm zS4LE>8a`(oQY`9JVd(hwr#oK3K;C8naIFvN-ftb*UFH$BAOW*;7rd(wWJDd9C1}n| z?D*l1Pay>(hz1-8^W@gWtg1%<&&mEhG0}`de&Y1joy?fa%{|Bu6W)e!3A^=<2EwKw zy0MbO)$lO_R;`Z;%UCslWJ7phjvFyccqlTZSiZOl(4k3`}8ve$lJ5`1&P>#_?NY{C0 zoYHv}2^uHKuEp*Fg+yhOW`VLiSE8JDD`P32#KL#q5bFyP@kB0dUv3{AtPT4;>9&<7 zApJ~I)j%dk=?_hO`fu6fr#jlStQ$h|b_UbDSUoWNPYViv8c<+tLSTV@>Llm!mA_|` zZ$6^Llc}66)8^vkbuNbZxJ-r46wE%?{vGWe1eI)xs0v_K<8(GNUlfN4ah^)Fu+5yg?$~M(o%c0MMYq12-~D12 z(F`IF|NR3FJMPX!{RNx+Z#1!A{z3iIix@A}>4M%rkearB$DxG_*VbQY#I$&h;}*}r zON+p8330kED^$x13RX|z_urRsU=u2f#V^>95Tp?!_f>9ZEn^dQ3&f5OB{)#1l1CM3 zEc%fIcR-5Z+D7GYyEx6!b(Lj4pUP!4lH+}nsOdOnM)hK3j~Z<=h%>ct>K~V5mR!rR zyi7UhkapFptBZVOj#pwM zE2~mpn2BdHvK#HZfAIjW#!fhc@L{^4c1;D6aw4J+$#xp3Y=Q8;w&QHhBS`|bPSSM@ zmc1XT*me#IAS{JNgNR*OICP=T%m}`kKZMi3#L*hSuHb`*fsUr{4)wQXO3G0*m5e(A z9blC>g0JA!4GObU1vv;jFeaTFL5Z`IAzMh0-Lb0CiqrV-n+UX%TCGBvZ_Ky< zcbXVZy6GWf0-Si57ebKK7|lY&MSH%ql4CKC(6iwd+xsGM+*Y;m(dzdjcV<{MOu_ez z4=@ijZg_z=d!imLCuBM$Ux-M~&QA6$F%uxTc3^C(MtFtJ`|U8W89_zgmUh>|JF`iI z3t5Nhby?JUh3FfY3%#;1K97(A0Jy&rh=@Hg9rEnvffy=osyx}(hT7MfHsCAV{v^%& zK6nmy`X5&u{{Pj)zalj(Ip@wF@KgI6b^IUmH2>ScdGBw)xvV*c82ZkuVgGlYX1Usj zDY{{?_`L^WXKBDD(hl!)O4IPh*^QvRD(WfS#k56Hs?&fDd#o(j-r_w(5$?-Za+>$7tZ3q-|WnZ|f zzIgj+7mz&>Jg9&3^FCgLec`ctKazXD0_X3)t7F(Pei+K&S3PNc`O_Ya-*yg6G>1b_ z@VJ3j0*`CU;fKHN8U*cPJ7ksFVx@}PFhT-qee*3(^$Hg{KRB0(9RNZ@&~VQ@0V?^2?zY*O!gGABG&C z?a1meMDY(3yY1xSI4JM0E!VEQor@#fTo^Xly4`yKl44ixr)~TC`B3TL*JWnnkxSg# zP)W?n^cm?0*0(JmzOBvoZiSP3BS$viUdar7vNI#?I`1w zx(5qK8q<_Vu8TFHgoP!Jj@D}B#s|&E3R9_297RBhI_yi-zKgNy>rSbui{HMv(0L#3 zX4W0+c#Q#%UA`4J#f9S%cd$zW8x*;0K33HvebOYyne3aJRJfD(z#C_WT6?xM)TKB) zl6cneQypJDD~eZ2YEw0XcBHvp6dLLKr^!8=9SYha!1!>}&XfG|;GRr`Ge~d~+Tny?pbq2v zw)nA}MT#l$6pM>z9H`v&=a-vsD4890Nl&v~vV^E*$|cvl*j9|-sfod3bol;??9!658MMWzEq|?SZNjB|M1cuJrHx+g%!hJkifILTEmV) zVB3$r2Kyp16(S7|O2Qa18Y+QZECA4-Hc-gl1B2|b#_&I#<{dq;yaWVbW*uM8Y6Jwo zl4l0wT4U>|veznI=NxR2JFxy=({;G~0T}#*JOman>0Xquv)d>a^f80IYPODx$ zt%e2tU>}@C>)7Syar}y_%WFWt>Y)Vxd+HNB25OM3yJe%S$j_+BI_vh>D@^OyUPb z-{bHw^!^Ynu>n)>2<|SRYf!q4@W8^9{~If16LBQjm3hoyhOqBpL><9X?3h)JHNP&w z2+d0gF4RF%^)|%~)4Jk#_vt@3+5$%5u?D1|A0()71HO@Pkp!m%3Ln8xzM1Jc&6=h2Ga&=ia&1C-_puTPy)^4w<4 zd}`>_d?B6nnBKc_R$wHq@A2Vs?txK$<>sqGb(919kAM0i+WJQi#12J;nx!ag!{?{L z6lAJ2X%t*HrP;};1(9g%VV+LcF%%1-fz5AM_26F&K}vK< zIKqj7iJ;)%D#zb>no(sZekxytkrSNvwWe|fhX}V4Ry4xJIV>2TTX z->Mw(v1;1is~j~+g#B z=aJ9@nkET|gzzg(pi6_H0L5v~Mi`jaWbdNp^4i;w76J7vyJm#D8FvB6Xs<{?uUp=c zTy=)i-cdq8L8lSP#E4U+C~_L{{j&Dx7=% zD^H7hCz=e11YO{s4cOPetuyEXN5&(MdV~fwPi*B-S&a0#pX)BsQI(8{||NV+1Av% zx9g5HNT{KA2)zi1bdVBy$I!cg0@9@y0ZHhcfPi#C=^ZJ8AciUmVo-VqK~X^g0Z~y_ z{&POZ+|P@>kGB16uT$i9yZX)ycrPTMrk>tu6j$PXFGN+r3xC7u6PIVxFDoC4{25$#@? za&)fqXC*3ETnMao4f>IOivpCcH&v|hvh6M;as8i<48J`=IV@SE?WI~Mgk!_ihq!1% z&U>@gi!}rj&{xkQ*jxVfXE}v=-a#bGQ@MY29~3?K)%)Ol@xkAp4*>QGuyO^|zJlyd z1-!U|;%NodQUwhuPs3hGuUyG!U&(yuUwN7ar{3;LL!2`AD@HE%|G7NP(j&EBkI?K@ zn#xt$_Eoz7(|H=vR{%<+X2P=uX;$NT2l?Nr+W+Mt=l@)2pmaa$lJnI0Wd_mUQ`rZm z|H$qZI&6|5(n{F7kP9yoH1O|&w=bC|djBqX`!A|?zUJkd=dl<6qH3f6Mb&PTcmXVh zG>I3W)n$DVN8$zW5pa(>-q3SoRkn-3LEC1Ez*nfQMn4ch=E9L-N%GZywbsaxonu`l zm;W!>9lyE4KYEgTRw&s24@J)2Gbm1PlEe_e(Xj7w#{7$_9Xk_d2lFoNR@pM^lc?H% z9|8O-sxJR8XyE_D5x{?BcPnBOnol<5J^mBp-`+C5%2|nIT<`#}DS!xFi@toPix$=S z(!o$K1MJg1g6xV9k(n%ZCXRqe?}8z3oSne{tHSPp;UQhBrBT+8?Cq>p(Y!}24yZl0 z7hLPgMNkOl!OB~*uu;Nr=fAM9giHSkkx#}CGJY)1Q@$>2N5Lyywl0cd-tbEtu zwr#^vT```GOP6(Xk^;VXtTsQpHgST`5D1~tUhu3fE0ltYYEjB;)k%cgSx){Fi;)RW z=z~;V;D4+;O(Tb=vHwp+&V{#H{&fVPWMFboDj4yAM^79}yo$}|l z`Rh3p-5>qwNZO0L%vn!4E{)i^liya+9_6{bx9B0*+TS|KK$=|;O4t6J0JhnGj+bte zsM>#^fwS%VxBvd!t!@4LYw!Pc$RQm8IOZZqBHXLdmvG7xY#P2uFmMizyLJyXuX}_D z0RVE=3>VG+ith6o7m@k7K#&vyPNI8-WaR&f?k8P=ve1yC`&3oILP;PE(*oHFp@^qnkE|0_n#wx{#1V8AYSVKDsujho}^Ig?eu@slN@Ga zsjB{O^d#Z;*uHNEq)Gw+-9LZmiEZQ(lIe6a03fRgXi2@L1kzYjc%hofp8F=KZ~#3( zTmTZN`0Q;M^bw|nHYs~Fsfq=DfLauzv_+$sWK+n3_%GiG^Ux(poT2u$NLoc1>u3Ng z2n)ikhJ4R;B4C+X?20alkaQNn6w_xcA}CAOZqZ#DI z1=v{|u{Z?jWeq^k666nobvS@fF2rieVjt1^63P-^0_4C3j-BL#V_E=IV{g8u;AD7I zU{@0;-v*+!WvI@p{D73CcxOZRu%_dwC?JNju=CnVgPUo~M~O9{0T=M9I1VjU0YQp0 zMF`?OEdys%A0E97=RK%Hiz9I~#}*3CUEVh(53aR;xI&I}t+$)Mqqk0nx_38K*x`jm z3K%X>)?8}91t1fj(eF^yJC4Hylx+s!E^vJS3zii{4pEFixmi67Dn8pLa5Dj^qh%bW zpOYSiF@y8VQiM2uAy?|rWwrbU`E|w>|*aTOsUZ4qj(klSZFESW+Pvh?KZ5=d44MofSFeOOAlo zn*h6OVvcYWFBL-_AWJFDPvaZj=O)+)mXvyQo*UXL)++)nc)3dH%h=0lbvyXaZ%1H! zz8Z>?3jDUUic82xA*d;_!rp6$AE^)yA-K`(=goiXNe+#Lq;T|(J*L&1@b#3dk0>sM zJ>PA=&3>nyJ(NfcfL$+kyUQLqf-()tG20?( z23bZfbHNk%8-cW`@j^ONNt2hkU96oO7qEo%!MQOjJnQ%d6jINw>5II1e}gUEhnbG{ z6oO>{5#R#w?*@hy*m!2`9kb;CPwdc=C2Vha*p27^#ZnfC+U2{1qjC^c6lnm7hH~~jR1N?ZySZc_&}7CPf$m>ojwCh zpbvjbQPfjPPU4v1gmsdR+~0%DSSs|ccj#-kmxA+TaUF@a!Ab64+*?5eBVBttlu=u` zKpRGP4I0xQWPt0(pzNCT?D^yuluRQ(yC@BUk>Eop;L#MQN)@+7W`~yMm0FQ0s&oY7 z#?Yl8tPTJ)Q|PIbV?fwY=zEm3O}oECtv&ACPGP5fLXl4+G9I}+f+Bv-kOn{qfnbt= zD9Ud#>TPeKD>-a%m@cp8hU}T-od~d0|G*BUoy8iY?b3`E;6*+%F925TKLu~3 zA%|7@s|PB2J{EJu9JT4WT!7@L2KuVOR0 zEE&lkWXtxqCJ9nWZUe-UO?zjKa0Tfj1CS|!Nb(gr)+{RwMWq>OOU#-O+jNm*3)`?y z9}R*A24xCR07%OF7@B$%au`Fg2++JHl8*AJV?p8I={PHWq~3{nSmLGGeT}yN(F=v$Awb~jbJ#XuE2^(DfR%oXgh|SmmCMOwIJM9)EkIzZ7a*T* zXMl)v!Wiiz?=XPeL`0FwfQmml^&ji{#??<}j15dU$OR5GJd=Rfv= zV&tl@q9wYgF?$fJa`I0=n@n_)p=NGYahhcABFWd+szJvIp);cqnLilabi6XgoJ+?{ zR;=O>hvv(PK`a}=tM10Gc6k<8_^IbWOtR)+J7=;S2rV`vBG5VHC#$@Cp$ol#lARDs zQDMenVO9|j?~aS3yLXzPS?;X6O<0(CN(?wK=yDC7yb_UwDC|V zNDStUoW#$DEFG-(W&)rL1Q1``)m}lf=sLzun=5WG zGJljKyFn>L2#*-NMjslW0+5Nh*uPdPvAn>gvtz7yr-4{3sG5b2?=4IUfJi`?obj$V zh$ZZsw*x~drdnK5#Q zLnV}go3)(DkP&)f-5hMpO#mw{ac*0{6X%w7n|4O1D@_MSM&RPbit3NY4kks*HK(D>{vnNnq-%#enpsI{!N$VKGU zRbLCbErzbVo+j|67g_99e)AWfOq@^5JQ7<}L%wCki3c$7T9X^nlp5C-*f^hh)k#j zr#Joxh0uup%U5s6lHS{(ZmvRyd_=mXo9#6G1wl@0k*bC_m;rNxTK1Ou`tD!!+Cs=g zQO+02O|K|4QUhRuPnuL7lD7~IWe9lU5`*V2_Ig?P7bu`$MIL=0A+{v?Z$o~Vl*HUf zRvXBnQ3t7yd;n||E6&#zlAQS!p(9|E>vEhEBcLjKEiRWRl_%~mLz`uJVZ!*P!5nw; z^fvB8h~WtYLfI}qR7s`bfCK87IZ!Y1?wrlHf24!nt)>tmwDEDEX02h|Pms%F**sF9 zw3<3m2kxGWUrs}YNH&*8je+%YQS`Lf$Lb~gR~p@>6gokg6_0Zaf2DM)%)M=I?icZBZzD`8TFvK2Frkg#tm;Pui?}fD04M9$KA9hXGIQ)vVFcZfkZKN3X3AW zq(Gu*GLrxh-$O^SX;1QY*Evgn5+c>B(0XwxQCQz=B7$*s1R_X`l7u-*q2yYxwo(M- zuI&WqyMV+{PeG;aVRC-p%4|~%@P@faG%!YL!+tLfN#*8Av3d10t`PGtP^z;l0i1(* z(_?Q)WbIk9CylMHPQ(x|k^3&Cc5jeo zwcOO4EEpKtWs*1Mt*h3Xw2By!RZh(E+xbek=mygAg7RJ0rqh9=)S$cArA_#jo6ri`PK!NeKfOl>OMOy}S@1oZZG^b`f%_^+Bs`xKD+ z{Lt%u2RS<=LjaCtH|I?>d#WH%6pcK0e;yt_$#Mb&HQp>Xnm6xwS3YePk$V4v>h)DW zFcRZ^aqOt3aQW$Ahm|Av$dJy3_{1=V9fz8utE8x_%Kq}P>%JeS8yui#TdF;L%g#Fv zxdOT7w^XSCU92(?!uT;wo8+amx4dSPL5Nl*&i?$}N_AN9(}!J1^>sBBm=47^qNjDv z$uUa(T3ZU5g`a$mvo^iA{P+Cj1c>n35eU7IqS$XQSd`$TrCgZzG3D2re_r!SRLj*?@_g_h6v~2` zIf?F&Y0uaPX7cP6lSi6Gm~E`Nhc+ z(=OYe`@~Ch+etXkd%s;zyW)ZVEMkbUjJ?z4>G=#ZjUHR1{HqTOC2kyQ&-rLLWOvLJ z=|kVcLO(P=vsnD%&FuAJfa90L-r8=a1@|W+_x@Y8{h90gb9eU_%J-KB_E*;S*Z%Hr zaDUxW`?`Jo>xa8vcgw$i9{9Sq_Vw%EuLs=Uj?}&#U;p+kxbu{oO$qz$=U3MAwQm5= z0a*P2>U=;JdjNlMK=J&5YW;xb;sD8WNUwg#=zPc=d&v6Wkp1}~=lUV{#UYC4h)?}U z!1+ih_DJNxk=XMi@%1B;=2?p8yR?M*cUkA}^0D6)AADDS{#|ALyV}KfG|#c7`f>Xq z&~19G5qPYB!C?6Om~_+oZ*>_QB*Aet{?I7N4 z{YN{}utf6mz4`l3OhWZVqfPcdjh9pN6SrCe)XsmOEx%d6?Tm^&{7H&Q1YIzZynM^l zq?kl6FR3o$9E9YGXS6O{3PyT(x~Ox8?eZoA(Yuw20tFF8Ng}U)@T&jbjlXvFV;w(9 zJMy+JTkUs<=T?@ASix5IX6OQ+>Sx)ThPoRUQD$dG^DI?|yClJJP-1;0{^#U7 zQ<;=1vqaY5p(`ItvM6RmIB(S{y^xBIgYVXq<_d}={5kK)R{dO+OAa_k^CCHc5xQh_ z%g{gCk>-b>7tP%tDD*hHYd~YnUI+BqYMg(Ev%|`S8k;O1@Qw4TpO*3)a^6VcZEOq% z@cW#BzRMCC9Y>!VdIAZRNsR%=zkHZdIvKViASU{2kB{dXEjq|ghiTQ`;oD)4cCxOL zbFO$?!asq(d9~lWI##LMNO`mIE1Okbu2z>b?#gd>&R@rGe?IBRR*vfI{n@=jZolRdqgB!a6b_^ek`o6QwyYq@;2-h`N)br`2z&elShp@`ok{eDfi@ zvq(oAkcFc2Sr}&b(E8MCU}El~$*?szDtY%Xn~LJm--FE*Fxi`E&%FY6yTW8uMY>43 zXnxK|5iJG#lV%~BR^0aiAo}cP>^Y=L1UB=Gcj*!GhJKY8Q~j7q&*PlnfGU1!vKJ-! zG`#KfHXnR#pUYrD=~}FDl**gKJXuGDKM*(7_i%7&eZPE4Uw8f==-1w_atki!2}p*g zwpc4Qm=?QfN|}+&O+V?1cF(h6iBj zoI~_jR07TQTb`B1wVI8OCSwk^C|A;EWu`?;?%02)CDmof-Bdz4+z5Wq-)Z&AzV@Yy zWF-Q<5U+NQdzkptQu)=ko=n#6YwOYP9;cI{au;pnyY6hQ*AB%4{&w`&_^IH!3&*zSH(uL`+;?SoZN zK&zqm)3whN)Y1sUFh88(iTmX9;xL8kX3rV;lghhlk-$X8bnDa>aQ}}|@_D938SRl>uxtG6Rddk;3^L;%M zKB}u&Ycg)Pdc#pGq54_@0Bc>UzH!q?czfm7fJa$Y1;33w*=>{)4fv1O>RDp-R`(>5cKu|Jg z3-X1zZtlD!lJZ4kcSHEIIeUw(Dr|yKUIkOMyJT{*aWSvISL3$K#;cau-kgwn=-Ibsa&p7`ZX56nOa36(SNd3sy|t3x|#u0ouW z{c*t|y4z(S@eR-qHe%e@1QByC&r3J$p3L|LoMXRuDrnfFW|j|`i>06_{YsWIU}sO> zWRF3^hHJYdxb6>g&qaB}o0^uO1{;YqZ-=PaOJO68ybiCoUrtVhTC&kNu#f>R0YhKQ zz974S1SJ9_N>j4Cp9A6)RbddUUlkn6^mF~iXS>n2)}dWSW)v1xTO0MLh(<(4ium`u z;?(ZF9^X0{<8J>u`NaWSA`*#WQm&N!Z7+&1WWMEUkv%=XVAW-a(-Y1YY=0_Pv;X{u zvAafk+(x};;?&K`;Ii5w#>TJEVUDj0{yyn-vMrCQ1a>B5N~6qtmNd6a;n?;r$Qqe+ z?;M-OZNv6{(_1PJ=G?w~`wHfqZIFzZx;c2--Qo1HMg-Q~I=Qb}HT#62iGN1wuD>*; z_KRVie0pu(AlDzazN9E*q;tJ$#2@^2!qAM`UJZp)>o z(!95mwvB6i>ef1iOj0&$wV%DCI@4TTBOwK%ahK_jrhgMPIMWxLMc((pvR>k)dcjfF zK?fmljiUSZ0LwGhq~oZ~$nsjg-Il2%U0&P4pRTzlrm@d1Sg-TU>rDT>Wt#_9oa}wD z))#yE3YV_f`p>gXVRO{f-|!CeX)CTb1P z-(}C!V1s(K-;&6!5m3Ra!;bE97qXlbklzYWTi*^k$WsG0eDf6CCvF8?{D_7rQb84C z%E|8p{kTOj?x!WFp(3M>gp;)-YiQcya^;b8xnd4&P%^`79Dl_YTXHKtxYn=gM?lT}Yl*|x=*SWVNC1kZu!)Umj`dwbX{c&d z)WKFl^a3;WEF$xV=`S*ejFa2qg<+Bl(Nc<3FNrCc7x1JRn|Sn-fMv3qR|`W_-UV&g z2seMcvnlMA!yIabg1&BZ?3+)nOJT;j(}qZ!Rn9ppCYoLHjC_bsnG(ik?f%2%xuwK= z>;|ZGk-9rAY3ow`BQo4va8HsHyM$rRs348*R-H&Isi@%P4StG5LO{jw%<&9tDpIIoC#M=%a@Wl zbW_c!GZVw?H$k4|C!F?yjhVzY*+QwBRR#cVd&yA>%oju$?O zEMj*exGs8f9q4QiHjJT4(PS_6k@xX0pCtahV9Dx9p(4ovhk=;e$=J^kNwh!Iylpi~ zzvpb+&wyy)+LIN-`Cwuwir;O5{0f)Fi}J1MbVcXwudv-Pf2a9wB$Mb7xn3Aq$`Yfp zc&}GK{&sl$Vt1B@V8*u;gMh6Z^tffreV_0l9|0*V>t1eqrNYU_ronh$0b9JQ!M&>P z*p!~&GeJPga;l{~mCh_`K4wud$cHOsS0cP( zlKoYfjU|zkIMKq!-ZDL2{a+R|<^j6DF68gEcUb@~VOVRwr$q&C?^9(gqzti@9w`;Q z4aXL--PcA~iYMefK;&wPB(w=5^O%iQq@Y}RxneKND3lr3dTEwM}|e?XKuv=7=)KZngkO|w@yphX2Ku-yaTp}na~@PvPy{<;kuh(C~_o2%PgpTcFCAkNanE3O4jlT}^=)!`dS4J`rlg>P;?CD;-|- zsi?B=WmQI9?a|Mw?{*J-!vg}ma(<>(L*AE4+^^$(nb%e;^y#$DT^Xu=0O3onxv$(L zu~|0umTJ>Zt?XBQ`-uhQii^RoSfkJQ{Q8FBBC3z@x)$qH&j^{MR}YUxyk06sRV@mr z&NZSj;GKYok);-qoO+sHUe7z4CJn1ZZIPk&6h#WnJ>vy)-bE!pA_Hx5Y;^N#K6y539)GT>pEtr5j^b!V{ck2YS;cvH}*?D5-2HW4-+7J zoHCZFXJ0E>SDC(0waxlq-oA9q&TrhVI_ZP{&QYmJxW7W5kl~Sxxv)(hb2}IWRj&YX zDt78zeZn5td4>_?D#Er(2$QkjZwO}qf;nB>dKwfm;i~6D8&LS9_+}i>#FJ~6kh0+j!As3$3O)MG^y|}{L(Gb1{)N5Vqpe>;=sTGnA;U1*ABKP zeJC!-MUJOzB-ZWX00QQPK5}ik(P`zj5me(78|8r9{q%H_yzh;0A8lk;x6gx5Jv|%M z53+t=%g+sjvSOQJQv2sO4 zgY@K(wJ7?l0_-0e)eli*QoWtV6Su*1kA*)JI`*`lzoJyP!$QXk{EK>CEOx;hLR=i; zf)v$e&AZK|Yeucms+VAJDyRwp5&;9v6Iw7igSPF1{O9zV6=D^YxkXDf=J)|pg{I=k zko){oR*EcDn}#>HhF!<+)ruuCD5WOIhpZHkL%#R;X^w!59U-OuFaew3*^z4*HcaSz zxFM7EMd@hm&M2;$#t5jYv`(ydNLfv}m)bK{tkCQiJ?tuy<8al}`a>6M;tPfC=b=L{ zK+z-SLH#$y#>4UniKP%8JeeW|%A$Qd!`J@9GVMp?%bUhyobE3>dZO1;0%TY4rJUHw z$;jq3Y-sqD#R;nWP?^2qkZQ#&(0@uRmONq zV#oE;6>I{?YRB-O!d~q~&a&jSHuP!hnM5L0=J!I_?%y=)9Wl|gX%)9=-y6ZGObMfD zQ%fgyOQ*1d(4DBxk7&WcQf)_zs`2C!@GU>@@Br2Dx5AlkgjL(z&z!3CUe6kf{=MpP z?;?z7noFdRumN0b3<0Rp!N~hP&_1@}_=GV%8p8aCr8I9ECr53F8Y|qM${~My*c9Cm zHVf5zLvHg1K0kXs6YH4%VA&cDaJ_?=yaShx+_AK|Q}r%n6sr2?oeCZz0f4@UHJRoN zvWg?w9Z7>6lD%|>w9$&2oZ;^j{OuzBlT1{+AMK*!&HF6&Zc^C1^mub_qF--hCnkYZrPjkYp4vMGhxXT-ENNnvtXS3_8_x>|K!gLxp6vBn4^lySsd_4? zw(*;>otwXin`8UWdDT){HLC<#RwT=I&YS%lC0{$Ot-tNhqV#+vt|u((6s4T`?nS7h zCh-H{vSb{v9}CsJr9UgR}$C?FO6Y}U#M&}wK2jn($md8Vd8;R6CoI+HFI0<8o;oj9$WKkCrsI&8)#I5 z?(71(-_a*0bH|2B*#{?XtMi$w^S+0(aS5!k?;z9AtIelA>mU5rzixB=pmLeuzx5-$ z)p$QZ8%moj`C$KB$39J~McQSP#LHUcnV)Z|IeKIhA)rkk=i_aTZ-@*V06$0zKqI(6 zSMWS7Ql@nv3RSnB&rdBpOgeF^Ep@&yluocc3i)z{d$;4chR4O_rPk>8+Rn$|!QT|; zBT9G($=|nQ%&p^et`l|6F7TWA_Mzmr=^eXk3C>@?ip)mHoC1L#sMzA5qnz4j?h`|a z=2cR8Bqtk#kWm6KSZFq`D`=D#-Jg>4LZ6=J!^!Xa=GEE-5>5jNY!)Aki{<>*Mv5#x znwG1^{Drbx?qVM5WOC~iTYfUHF)35?t2h5_*d-H|G`bGiIpKSmV5`*G6gP zJ^6jk?#QD(9EU>7vWoA=y3AnfZ`TK+Cu-O@3aEzSDcIzrQ+g0O>1=XA$8hQQ**Owo zBj5FyK6^}+sm79V*&lnptu}d}TgDDp&o$fqco+U5eW5k(0+GdJ8+Lh3G3?`b*_RTD z>(62{znnUBce@PTpyDyzBW{kQ@p4h-oSF5}f61q<(^9fJi8$JM{Xp-*^*?t`_amPs z@u&;#sdqq@2QvFEm-e5>Jg1&|(s}xe@=1FZWN#pjMp~qDm|I)?VJdqt6+e)$U@DCQ z4rodbtb;CV)9DGcYcpKazB2k~`{rR+jQJv;I_}_}S;e0)juwT@l&g(sNbEUX(+B!r zTfGtjaTw*XrpALIs@`Q}$}1{XT^Xj<5osfdC)b&Z)}*p~iKjGeoxV3| z?#nd_P#TP54ATFY7LBhK5WE3?MIm?RaUZ8Cb|WK3?Ogi8Oozq2(@c-Y#L(EF!&@&+ z_LjDV?kXVD(khRTm9j7%roY)Xly?453eKWQuPj6FY5hX6wk?xoee%yuEwiitolrzox~?03FOg$K+C`o?@N_-u?qz>tvh{G~O}G zKfO9sISODjt?hkA;q%!lV00Cy{TTpu9d?j+!I2B~xWvbLTTk9S?Hw`p8Wq%kDAS}G zu>AZNINUPDz>nsd^+^Jan@x%B&_g>tb_8%|f7Z&H`*i=udLB(puSd!4F{SAQCQ0%X z^V`dX@@bb^7W9<9BosRGJ9*cweyR%YdMIdFLv`WaaQhjHb4~9R}k%VNdp25(_L(d6r1C7Ecxg=n1ioeZ$V)4R7Q$@X8T3g>z` z&up&!q+z#WY<*&?w)NXB6>jBtDoN0+Jsuwl!d7V3`T|`-0$3emJ$Z| zFO-D?q=w>%llfcE|A=SnsYTBJO8pp|Qkl(t`*W?rQQMa?e@y_Uhz6aCMk}FRXauBl zzqt#zKfMQso&rigtcY*%p0K1k+v5 zQKfJnB&u<|{gTI(MEIiS1?$@(xB+iQcGJ|$nL+|=&fl8em7hZbC~se#zV`qs`1@!# zSM_lcPrH;wr*SA!jK)08&|x;-oYg4jCv~p#3b(tE!Anl5gMW(TsEymm+jS)KUTAwr zPsh9a*dYN)QSNfMB zLYVEL^p4WCJ7Pu%nW9CRMsSHL7Nf79tKZO)`oMRs-f>0S^Qq%b3$XUM@^A}8Jsk;w zGW&-~XlzgureB!Oy?ew1tABi~#1wn1#r2lc)zvnx0Y{%3i%6_LVKyY_$#=S$vpZ7? zH4s(|5^}{sL)7+W#y68@>hyFP?&~Tu{i?8}nsemUg0c?mxk#C%Nz?4 zpSwM=Nh8W`*%{RN$Uo8d!c8!Wy~ohqwcb{f?_0Nt-Bzf+!}b>|%9IJc0`V|FQNw$X zeQtI7fXwM#Jx#a>ltB^9bACqdpRR1Tb~^V2Q@^ALlL)LJynfW5!uIL{%P~G#*Y@U>kuloUzjOT`b-rQZuJYWa(t?YHAQQ?TIo=lP zyglVNf1~D7*Qe7Te0c^Eh_;d?M$aEG$Z2JG@OYd==X=by;5YwwS6wM=3gh#u-y|_h zTV2`f8o1);R@+tbLKu75;w4uqY%S97MOLZf9>ZaF7%&DUJ^aQTbJZj^tHx&V|$-nF)^nTKc;ny%`@) z4M*z$Kxrp=x&Q3yd5rM8>it-nKT0_6IKo4Wmu;eqJw+ZXHGAy!PINBhaJ>pqa0jZC zAq^gK-i=hxC#z3k+-+Exc8>L`_0If9-5*zY{XC-fc*#v%!rFO{Jlth)f{;B~;KX6o zoP)W${tp0%0k{haH-tF*~;p}nK`{L^eov%cJ&4*dF8Xd@yBv* z2Nc-rY;tA(AKYKv+jn?UbZC~s zDH639biK~{iJ^UtvnRjpJJV;XeAV+$=e{i@O6PZEIjQO`k}}XZ*r`kKW#^r}>|~Y0 zQa0Zh)E3mxvuSLE7{iveG+Z;#YkDie4{irj9viBJuT1Z7)}Tw7_JZNd_B7OKyn4K^PqTE5&G zykE7$R)-!O%m#QzhPXYLe^2pzi8_7qz{5-7yZTmpGKY)Wr}41g?+&j`(L2<7KO}o_ z@pxe7Vcp8&Ksw#bDQb=^@{HF2;EDu@qK}1~B}WfAa+ur&AaQO7GFU2o zvXx5D#m+c76TOEx{jGUEpTMx77A zYU=gHP`(GE?>np*+kCX;d>zm_zP&SdfEPt*gUM$vUxH`>z*S@{Y~+fG_VXCeWW_Tq z1AO#L1pR(b$326hFGoX-S_I&x(gEf3I5z?ajg?XCbo3p583*1?v$-Es)fP0jzP7O$C{P|Ts)Q>3y>)S5LPTR5*9&B&b^Vj zu?PYJlAOoEVr}D<=Mou=k})aC*0yne(M4%T^=#7Ob>|H;#m~qR4190)QnxAll&BVQ z0+6->Qy>}P+h5jMy7~!Jpl|fh&1g;9aC3>=)E7)Y4v0Rg)0pW7y_*p2=%$DOpdzHp z)kWa~6mtTFj9O4dz$Y~^tSvdFt(~GXcheOFxPaI_CnhtRo=m3g3?@fxz`{GI2+`Q5 zj#uV~2ZuPZfE3mvL!@{T5Je~0vXWid08QVE^NKL$cxP~i;$|RDUToxvPwh?aOp`|! zl826yUGIS^ddBhefZ$R9ysevDiuBGwSCB9_fIOm&JX&!oxG*V_n5<>T8iT$TgI0eT zqH^MjOQoAS3rU06PM+{iO@;6|Iuyn%kjJzoZ#S7xfxvnq$)v|hK0^Po#3VUlm{U^? z^WMO9YO-7&{7$HGv>?Xnzd7kBm>rWG+H699d5e5C; ziglSE0dFtOzLn6S7M<0WguRmzq<+NsPFn6AQU5Bh%DW3WcZ&`CR{6wtiZN+9x$l&_ zEUFhCU7dZWDv@?l!l(wDK{uxcj|k6i=xFH7Xj{$bxXZ8%@~c& z7|+g_?97;+%v^)bVwh&l1ZU0VW-WAPEv;s)+-I#rXKfN^ZS!aCs;#K{h4%ogdO(6K zfF)H|&=U*P3A6SlY5G_)U?GX74RoWc%@_kJKtT)O(9}AJhf^B6RGdqvHJ1fInzGa) zQax9#YZOWKo%0mGv6O{C@F=zrmIg99wo zB^ADaWZJ;Viaes-#YQ(vy+T9SFj#E$!bM4;?fp84PD-3IiPi3ba^bPxf7t*P@v?u-Yv-$zbLMd_m1mz8gP6R}A zJRyAF=E*}4`#6Yg*M8j`ghYXHo0K?WNrh37!Pfk|fpEO%U%-t^pr?Nt~y4r@Xs%*m+ymfG?PHPA> zSm4ZoM+A4zJryB>Be)Aa;lmC4EX?j;txB$cE}MN0!_w^96%^Va+OU+U@%5$o0>yr+ z6oBEtnG%n+TAn`*b+&EBPKBmYqCu=!fawhA9KFJX0gwRhUiAbd$wmPHbO?afcmnA< zbDhnH?@08AAXIl3w2{{V7bohqx#H#o5sWJc4q?T+Q1Ao!p>Y{jfb0Q?Rc#(zh%+QY zO#%{O`dE5f=i7fIgaZ(Kidz~1u;D+mC^aYEq*-M`9J(%Exem$|0Dc^5H!eXdj)q>$ z0P`r|`Y8b%m=9NzT7nVcj4{}6ayKQCX2EDMGGzsU#YqydvVlNn#Ng9N`aOTJEH(HhX_{J+kb&R>7L{^)#z{aO$&p@d5eHRe*MPo&s2X zAfi9Rq&~AhPhNqbj==U-dw3MUz1IMEfGe=ELVuCY|p zCj@H8U?D|n_>(gyw`$_8(5fkKhGFmJ^%&Dt@8#6ttDdR)&c!H~MSho5MNccA^?d)d z;;~PK)*r024DN|5;_f}e=788dK`i>94Jfv%AcZvo!H&kMcNiDd;gGYt--}l`>##dc zD{p`T>cCXeg70}ZHGMVJryEPtgOz|Qmi6r3ybEZrtuXBB!;;dddVpZvTSdD7C2%Vh z?JmU{muk|Ft6zS4(lO);CbWl3!VliFaIY2v_m z=xg~|1w6d+wVhM}1av@k=9d~4x>Z9=Kw+3GtK(Z=CtO1L0<2yi{?3405Fj|XZWL<_ z*cCBv)?l&g{;A1fJRnpY#uG~hPmGfOX5MVAg@1HvG2PY;1nk8E|O=>#xNF7eL$?CVi;(;^${y?qwSt>uL3j7_gBfcO-=*(RU5BVbBdO!ceMX%E#R@8>!0J|eGFA|mdY9^JnB1rP0Sp%O^ zplfN{wy%XxxduQ}7vlM``d2UHv^F3r*$A$KFBBLbHJwE1Hb_Amnbr@b-&vNro`?_( znUQ+ma~(fG%0|ZtV!A+Piid}|B$)m0f31N z01=%`FbSd&Au$SlDgk*H7%BIE+JnXtEF$c=i0xn^PD2s)l^aZ$4N6v5u%)Ap;>f(r z4Q=y7oL9HC?!)s90{0MLtHofo+ku?W7iWra3e zvCZ$^H@WG#h?VN!{qw({DYSa+_z#dri)(;xeY}1q0iwc#W@*kxY3V|#Kp^XnEEf{p zdLLsG0o7a4s#X9D{*&SiN1`+ZfOxUO1w_U9IM^%9+;*=nj&=jYe1MI~{50uokx33{ zd<9qdg797k& z4yWZd1s2*sz)%7Oi?r|V0q;l(y|8(c=ON!%2D?Jg-tHm)IG#^0SKRB!ZAdW?^Vs)O z?j{p(<>Y`3ip3xjxTOK)!I3brf*YaJZui2lLOGfdM9@YhBvWeEnm2o&h|M+GKMCq8 zCLF5Cb$ClIa=fhhWHR&=Mhz=`$e3lDc`(>$1{7 zL>4CV@3wD|s%{y@svf%JDo97Ge^wdH)qeAu!6#Wr7#T?WBeDmI!i$(~KgA!;50 z+Z6nP7L2+n`TpKUlolB!7xJj-;7+gR(nzgEtN$P6)21DubV5ya7zQ7tljaT7ID;;% z%{%Y8XvT*CoQmTEjT(x-&wu^+{_WdEEQZ|@L>lVYBT#V&u^yMW1OOiorZQCIO=Pl< z;7wvnVuSPZyka8qUaYm8j$l0DB#xZO_DiHHhu(_; z2yr54xJZ%MRI)-#CHO-rMktyJP!tnwsBfUyLdCm*S!--IKVf*`(>SzdQh&-Q%4P-x zB*V?b#K?J??ub8rX{e~-Dj1PMgwgR8;28qw4*B&s7?+UrbYn0qJB4W5`|H1$JjAIU zjwSK{K28Y>rGmzkEL7QSjp748KbMsGPFfK`1THil9|GYx9ef54tUxz0u_fTin0%4$ z8Y+<(jl51PB=`LetJ1-UpUn|h#%T4a4s%rk7m@qGhHE464_B z0OAU==8$&;0;#2`zcFQS=~+n9vh*L>88ahQTSg0q7`ZvSYhCqoPEmj47F^R++ge5@Np7H*CJB;MiE=kj85I^?ifV&Z2y)*b2=o|Ji22ZXja~!bBG(P7@h77Rl zSjsW-7o=iHs2qYRg`Djf(Zh3yr2stn(5FR&b^GNd9ye5~fF@d)EAEz}5o#QyOW zJ<0CY$BTs=U2>|+GFT#RNsakhR9*F=eKJ>X4%O(K?`L!~v06G<>p|CYNr zy8X3NQwq(Y>r6(XRH9|OR`V4&d3mU|_~Z6W2R03;5NRz#fij#p>_qlm8nUOX38`l6B!=u%V_&ncr5ci@5R$b;MWl_ANaZuV&N;7h&ij4dpZ9rR zzTaOym(S;4aA7=dbGzNISN661S0#O9nV-s{gSQIyalsVnZ=3T+%`o@1894$U2Xf}o zA^C5y{4uOHOoW&m1;xsjKj|)yv?~=HhN_t*dTkQ*jk7o-R51Y{5JrGwenaWIU&g$@ zvM4aVcg*k?6L7RDS?oFeuHqIR{;-;7N(ccMkVHj^iu$$nmRJe$OC-0Dj4|j$-n(YQ zQ4nMxSx-$y;>+M(+>*Mh3-szG4Dcm1UP@&yZU&)Jrqfnp1yGatxxJVQB1CL~H&lHS zR&;Wn03{=T!<-lPh^djN3RJOXIDz{Mj&$`{d)nre24X_MWh)oPK6sPN1u zU9#ga>umtd;t_*!rTGA%Pczw!4i$lFrXs7kXgqn(!HKperuTe%KoZP`h*ol8nI{R? z&I(-n%Gf)Qs~Tx>4^OwZR+L|n^@R2;JK2`7Mi4wL_O^S4hFXQLL^3{$FaQp>aFoW$+k=1wila#v+d~XMB?T5PB`0uAWH^TZiPwo z;McJs8-*~WWJ!t6$6o8_y53`kwA8HDf>^eEtd@RpB+L<`NclwCu|T>1c;Bka50i&VMSK z%95#n9iY4G+G4~jbrHjv>b~5&oaIc15ILW&IZ$sc#DFie0Y;vWfyomB(!~3iN{y15 z)l2+?hbBZRr<0JnxzzcShHU2F>2mXvhXE2%p~xB|zcWB-^I*ry2l=7jOul<$bNHY@ z5&>bGMcIx3Os+jAYx2iTj}GvP4-(n>sin}5nKK@_Y(m;yVJ8zKSUkCJHF!&eLtCln z6Xh4^#4)3X`ep$tX!LOEFD&AK-5$6U=3STmSoYAUv^k1|NZ}X>xO|l{lXXFUvS{h|V z^JHQY12#~=8u|J899|P^>>$9h!O8A98Y5aP;%ud`SBoT zjBOG_1vKNv$9oJU9fUo5#Y)8X!;l=@^oDMVn62(<4saJwf4?*=NFqE{in}C<5RHqG z1?ViEF*i5F)NaO!HCl=xp7TJx1*rw@-Jqze$mp6Yo?F*kRKEZu5Rnv~GF!Z7%txS|xsCLn#$FFT5Q7eYgW-ksIF6!&2W(2(i72^`S z(s z?NeQ5aT)msDpSiq(k>H{3^(t6Hh2Cl$?n%8 zGEA&EFXfmQ&{RDy?thu!DS&)++(B0ofgApq1+XOXlk51Nc*9DDZ(mAB;LPm%J+=;`xWHE^ti!Cz0 zXzveK)~=t9c$r=nc>|bh+Dg`SZ|@UuI=6}WqzT8^UU>qH^Z@QW^3#ZKrvJ$aC=@2jaw8f^PUFWv=s<%u#awTbB28P1jztr(u0-D%;-Tfdk_IV zmWzEF&xY?&&>dMD;(S8|;4)<91(f=EA5)RIKx5=EW*{Urk+Z;R`Weg1Dzj6A2}6B` zM?Onif5cS)ya+`KHcw(!CM`_z@f(7#zAPCx$*dPZWD1~@HF7OYFaMgguInyNytDG8 zdpM!J>{4%)h(Amh@YZweS(HDjJh!qpa~`oUG!Is1=srv9+_jFD?Q;^Tz9ReZ7}>~^ z?x|~QmGbeD_FfW_K&R+bV`9v7JKytW!j6V?LR`nU3?e!6T$*N<_0x zNOlv!vb>VbSAc{*zK9!8A*&h!3H~D}6E~HQQYcRtX=<@D4KK+7vl!e!{u&&}K=_UNWwTcZQG_xHm_ zhO))vzM9MAVi19dfgqmI%6)zDYD|w;E{70y4Ni<2VQ!?>Wy+yLO!|d*gM^mrB&nKv zlNmG}M=92dx+jB!Mq+Q@VUCjd+J{t~^?4>spFGXw(UQkZfgyfz*^)8(r=Vr?k#zq6 zo12#e9nFUd-Xoo*jUgCw)BPr~BO_bm0h2NhJ!otigKlMX*PysonZ65R@_a7?M%75D zMFO9%MM3-3V;`^U2fU4adn6!ou%&E#Jcee{OGZQhOhAv@q?K+&##E<8>yITQxrf&k zV4)Iny+16Ea|p*VU-yRbl3?j6BMhC^A@kZ%RcT!r;+5VHNM4wftZwZX1xPJAoNzhh z`Kuq@#IyieMd^m;@-Axz%;eU8Dp?{Lb|qOQ|l^PjuX2w3^+07PM#@oGvM{WyEtXziM=yvKtO zB+AUoJ5KsKNOu6QD>XeFgEcH;6QjZit|Mr=_7OB)EHMM|OapN$X`r*Y@4>bEeU7P* zh7F%{>-Sd;{?d}#QV?P=w;%u75ArpFdlX^Pjj;WSaCJqkxAAZzMY0Ov;wb>z_ka#9 z*hv}{T!rQ6=*^H!Oj!?Pe<@q5l{}7Ap23 zCvEP09^_pC#LOym>~x=)ivubY)Nmk=iwjg&0SuExG33f9b6+EO5Qf zRBxeDSH3uZldFthOBe@+aPdsg49n}&C|$^yFf9`D;68#EGBA@Ti>(-hAM%~?gcaJs zWYh_jJyfX|g+i=Euny^Xo(C1c(kuVTg5_ftnGnJB!5IRWI**8P2FpFnN984Y8W{F5 zdXo)@(|w-|HA3@SkFn~-yT5&eN?Qo`bhQI zblb5Ps&30|Zl6?-e``Cwt4cz*li1bV`P$w0sCh`Yd+b*`q27Mtu$re)yQhVkmqWYP zaW!wBcJDx(n$OvGpNnd~iS54WYJR!xehrI$fh58|91H(nYaIG3Zt&!b-%RyS3yfpo zzu^XJk3af-EWE~Gs$1N>^K)nG%exnk?%rh(t^cra@-mKvkG7E)Vpw?Xi43NC)ij#Z z-j~5t_pW-Gz&I9unfPJ^qzg%88jlGD)2cjDOm%B1k?O@v{trq6BIf`|@`|nfHuZ|VcQu2l9{zSImz40Qh4b1s3kFmD z?VI1n!plWrQ+~@={|%;kmc9QUxWVd+K>@3K1A}PmZ>u`)6aR)AjN@|MOX2en!N3?W2S+BcqhI*Ri{oGni zJJ&M+z#bZ623RN5fm?%_sxZ-{dWQOfHkL|B6W(r$o=md9k7SxmHIZL4zAOG z65cDc15X!}9QLy;!ny}mU6xf(IQ@nPhIuKmZnEaSN1BXkyR@Bj{Htu} z@t1KkE6T=%nfm2fj+bn4F^_Gz4D?t;9S*%$asD@rLuW4SzWny$LTw-X#R+TUi02x6 zE}VUpGCdOUI`lAG+1AlvZ zY<*DuQ*>c0y9DA0kh=4OewYQ(7b1ldr3z2F-F=FEG|NB+-c1S&VrH6S0oYaryJ5iC zmaYNsdf~}f)-~q7Q@?gr0U(N`1oZnbm%hCYezSvX%Ug=06zT9sl8AQ((kJRb{Vge( zjJLsSPP{+xa*#@uqJoxG_Nk(GA z{UZ&9V9Lnv|2tFNTEf4PrQCEA3oxEB;4njK+9roq@{Y6#wQlg)H_)V>Jflm~PmjY9&ZtRW6K zCqRM`>nY=fCRlFrK$IK4-uI`Bfw%vpnm>Szi%-)1VDf-T`$^TFAkf$46BB?U(%yirp+8xBBbvh}>K`H}lZy_prj>5VX6??pYxDsn6jaeia0Z%z8 zf3q49?C`P7v3L5&h-l8ZNHzYae7$>*#w{o{54NRhF`S-%SdAPni9J`OVvSX9=dai4 zZY|^~c^n!A+K#2*DA)Q94{(29*a0)5fOiY5PU*T*uDQy1t)9k8Q2~P zwZS9J;;hk)i_gTihkCm>va!oP>lIxY8>{29X7~ zo>#|x$ys4|k=BMr6Qj8RF2zbhzsVEFFZxwtqW*`K1g2_Flgok5Kon!NWO-V(oKNE| zv3%lDzQSgS0J%(BbPex&DWd*b)(TR>d7Pza^75H8YGF)K$IkEUya3oc85Yi%R>?Y&u) zoQ@*=$98e+{Gqw>nOir1B4Pz~+}0`GJg^GJf<~EchEwEaG5XMJ1uh)B5?Bsi1S$yy zcc?vQK$K$DY1=zvPp2x1#8+L*#IGvkxMdZHC0FUYZ7jGo7kYt;RDA<#a&}X?C#EL+ z+_}aeDD5ceY1DCcR6qY#ui&q>B#Z7>e2=#J5B^%GrvIphL?bu2ZSc{Kgr$*EtZu-s zFK50GhOEAv8Y}#@QDt#^)#1_isawCkHm2Wx?_;quCc_Fmue}}0go|Ze{q>E`erGMw z;>Rn&-K{~3JD+nuX?MvbjN?l3OI}|uzqzE zUo!kD0rAsLy%?}yLt5=_gcufEL%7rIy;jf?$g_s0EgIr9D0`MnK-EAL%Hxm`S;XB& z@h?pEh**t0d65MZV;=kTtUx~lh-w=wxE7)13Vl{H(k9!6 zt03F~I7EZ(4FXSg#HosQX{-@8%^jnXb}ScqZ+l6l7`AA~{TgxU9gjJ)q2+Uoox6rT(^#;ERfbNJ zo!pkiX_b>9_nme%G9{ccr6MzB_)|}Lg5SLY#d7R)#zRKlaOvBbo>sMfxyu_Z^@h_Z z0b(Bu!MAhqmB;9=<6GXCEE^aZ)57j1!k7r>0n*uh?ny``aO(g$X8a^f6sw0%YIQJ+ z%R1W&o=0RP)A=x_(%=vWcrOv_oSzwKMUk=!4a(<+$bix~_|fq{G1VjUlJfIXy8gfo zZs$??^D{N`vz+pCBJ=a|^9#E2i)Qn$ZRgYY3raK#%A5)+A`7bW3u?Lw>Shb-w+kBi z3!60yTb&Bq|H4%7D(s#uyt7?M=P&BjEb4PA>W?fM%rAP-RWv+XG`d|h#(#A}^XjD2 z)v3sH`0@S1g*>7WZ;8J6>b?Cz{azm`DD9wsh(EXm{6_<*`x* zP3SK?@_#2F%w8PKxO?~F41dwu3o@bxMWkS)wq{XGY7CkXWGEwQw9m})hO z@IiN>JmOeiyo5j6gD6rl_>vGR#GNRB_s56>L0P`9F9+Plm8PkbSc#_*P)FRlY$(RCG-Df zK)CtD;$KRa{uU74Ruug=N>YV>&l{bxXXP%#;z2sU9{`~kwALd+0)Bwp`v!naOlTS7 zWKO`bu=>AmtNN)yZSc_-Jk>I(;JL4TF+@rn2yU%D)c|O}``Ga~M{d9WfnS{;ySLtK zz9IOLGd|sIsJ^wIj%ayx?p ze}t!=xtwn?^?`5)3u7$PIo6AnZe>W4c#dX;TBu+oVjmJp!$QaOnbpF^jlZ11fVxH4^L% zaSttrMWqag%IKN%qQ9-{_^4&-)2(pJ`oZYwTNZuK>(5zsv2*V*0>b_uYkhoyKh_7O z8-9EqzNglgG-CA0itC7R;CaJG#~aQYm}?*Zxw&u{aWBL(EAYa${7>jYxFSXr;mlvR ze?R1-gv;OAc(_~jGxI0?-Yzh?=ge~--e2Ynh4o@OP^w4&zHg0!RKg?pWP19y($QSD zw#Wm6J#0~H|Gkn_WB8?Mdm|E9vt$H>S9QC2YlmV97D@FdV4O-0eUi;bF{S{4>ncv; ztFUK^?c`k2=jkFIAtL_NmLqTZ7w|P{1h2dX0C7r&H?9Wb6>vimQy`hAwaGtF{;wjX zmuXfHPds(T8!|*nREpW4sMFX1{Y@jL0**3*J%BN?HqQhUiGrvQ<0GdRfs%*05~rl_ z7E$_G$FR}EM_%(mK2e9q|{E>}1^^sv$u2DH2{S4=b+_7M1zH)vL& zoI5n^t@R~;EVV+V^6hm`7IFT;#tOBDp^;NjErkm|Dm3nyj0P996g};hGH%T`4@>(} zunds3UTIoHPJFqxIqY-jTk@{Oh1Hhpz|TsZYLl@T-Lgc?*J53+2V?PCt;Nv!Dt&R& z@nmOi37(NEUDgNVX;B-cc%CbqdZrVZ1si2D=GCSS4<>SMZj>t?`m3vn5TF!q$C?Tl zW{&TxYzQIBfk7~CGHaEwd5!f>b5nWDD#18n5XsoGt%D1pN1sjdtkN)tJfGOXtL_oJ z0RS>HJ3TDXN2sS_D1DFIRcJ)E_u<1;ZcplPTe7v75#bfS?$6 z8%cX$g~ER6&=Wzi`I_z=#%*J#yqAF&s0yRO3JnU7x-R!vBXU|R#N_?YTyX#v+rSG} z@BOP8i@M!0Q7}wK|CASO7Ej2LakP9FKzZ%NBSXgLj=bCI_d(Y6E_4E9IzmDD+1nKM z7JY!gXlm^!82l}V_?~6bLr!4`!Th>Kf%snQSPQ2<+)JpQ^jwz8rjjiwP(?=(n8{mb zrvC6jDX)>Y7y}hDG6=cykjm1n3TM6`hh{v6Wo?TQOr86QY>O18h|YU#^<=b`;v9CF zk1n75B4%d?_z9!KQ5%i1=n@dM?r`Um)jlHX(rd$Y#vmN?+3%d$qL|?JpmD#QG}d}h zqB3p({3VYr`2hfm#)CrJ>ppElBow;qE?e61tQ*l@s;J1`*!U(w*wc(2w#{7_6cmc! zSD9gQq_@KOLkbe*dHDxvNCjgGc2$acmnRM-LwlFWY7KYn)er3+1`*u2E9?Y(-rRY) zLeW?5W6m@<-;8dwur;{DsXr(ZK|tTBqj2@HH}0#ZQxM9lF;v`?`e|N(n|5cs9qCOM z!A=LE4p4xDqHec{Bd<`v&5E*sC`mFwaV>F*txcRXNW?~A$asBEX5%V6uErsLAN?l2 zUEYLen3=pM!1BBc>Fh~XWrW;8epP!(W4H3FTynmWTn@M-SVh#Q3Btltw4eNmBq)WV zzka`5zO$@feqDd$7Whjy;y!liBxOtM0(&E2K>hTs1Fy0~S#~qa$Y}!88PtU;2|iBj z(Xq+uJ5S+M-oX-KPPop%Qxh+MEX}3_X=4zODt+%`9`3LJDVG$hZ7`pC}2C~UcOLZ0=XS2oP(ecHJY{4 zd$Sbes^Z?{BC&i1^r|R^TONCpVh?GYxGw1(W*8eF3bMx8k(b=X&N@p3fr^$e0s5X? z)o`a3?rk1BUOadVkKS(cfGIIp+wMuzkQ55gu>>^<@>~o1ZOWZ&2YK;$wBlG4)U$^K zz!EZlvE)Q8Xg;!Jh#EcX>kNZvnwk zL6jkyYBZUx5|&mBy}WUm0rGhhk+zbTw%VEYekScBBOp|zmR8}KdD3-6flL5ckc6(3 z^A&1vSSdnosv(;*oD~M)m|)ii8R$Y4#7nlDdO|f8MMGO)WZT6&gCs`)_E_~2lCidT zgz3;ig&~;mnx>8eRoaRYz2vSnh-XYHc@;@wZ|q4@(CJ+b68dEVqW^fS12+rpc*7>e zsgtC;1+XZ4vAiOk+H#^jiIukZ=B~_?EB3OD%y!JrcK$70(v9Ht(eS-;{Ehtyr?_aZ zY^Il_u&FpTr5x?SxczUOjw}sHRg2igrBoSXvvA zdCJcWbe2^F(QoYc;C?HnPB=j}ULd-J!KsBQufY|egQW&A|NdMFrAxAa8)gWSzQ=G` zsegKX>Mxe5i^+a43i0VwK*cOii8_xX9t!*xe*3N9T_jN2nSMW6um%HAXf6+{1>Wx^%NxXs(z+6T%CW+*&U*8!zIO%|I&! zqE9f)QUwM|IxdxN>t1dbRmmSCoJ9y!Dfh#ID&9f~TNJRzUNbq*DGygvu!cbGMa?1Uk47o^Sdb7kc~ z*5 zYIT}?Zkkqf&eh)eUP~9K>(#33bFS-;sv9h*dvLREc&={rd)=78jR~zAlg>A$qHfF- z+?cz0Rpvo7jN>sj;de1S^s{n{^R%hHGziDS`8b{4VzI7TLlf@ zZ#MjxV;E~10KrDs!A68jBkEiurm&IeRwK)NBil|RB-q4xu!-BHiT7L+uCPhqR+G?t zlgLgJUa(p0V6%ivv(&j}nZjm{9-zIZnR~ohL5@RFu!a5qTPFNJ*HQI)@Cw6G^>1au zYn^$UYp*R5;XvB?&JzD@c80SB6L)Yg#0loXuu!9(8+!*8wR5B z8T5M;p>RhV94udK1|=Tp`zo2gOKBjMO&LRuOSL02M7$-N#LF5Xd89P$&6QG%-;Sy% zW?ufp3}caGC!{sY+p-9G&alNS69o;bpamlndN8YLl;^^JXF|`M-y+_M>NkwisLL^T ze{ZB`-gXzGG?Mz=H6cDEFJC9a%9n{z3`bRQlAEnhNvfK_mCQ?83=uEs21b;^&SXp@ zXIQW9O}`3*%8%q2%B;o#{txy7Bc~gU(=W z%XkvT%&=BPT_{9Xwx#YsOhw3QGePl@eAo!|DPZH2!sl}v6C*!a2)KIXeQkmLB`-H7 z9p6pS2*s$PuhZ$O@XZ;|+*6ygzLht^`-kd2Z2Ax4Ce4&Xr+;ofE4a@p$SnA5cgsfc z?7|K2r>7diV_AV#Q7SVqiML{s$-)3^N$e7lX3iUo%LEv|XoSA0S#JLm^AX~A{fEj* zeeCchygjoTT||#X+Lnz2E3=r^%Pe0;I%gg|fTyzeejAHrSBV~lpv%8{z8Y3HjNT+D z$2`%cIvl$OZ9WihHMmFdzyQ}7Q{eCHkJHbb|Mvc1oapsZ|F8?+8$w_F`iZ{HKJf!y z3{8FCVqPFX>*(e6x8gszl6LES4ujXcurCE)h{)t{JON31Oh5K)wxT)Mw1W1UVJ7!1 z1`*PYi?Mp03k00c?H3@8!s6G1bz6hQM~q1-{J`rL^zFlFNeFtZ6VSUF3_9%~J`r2( z&SbrCg*VF>Wtr9U%F#G>5vv&X%vl$sR|O$hUhmN?J;Hhv%CgX>r)b&o@v-;DvWJQ7 zuQDzb;(K*7ePliD?D|VKa3NiBLQ){2dk-(4E=+mKONhcvgM>n0dZXp6Ms%Xs$mZ=B zMP_jp+NC%C8YTw}%tepgV`AqkF?xty6u4?8>7cL;Nn&22wL5!Q?KB5It9oU@+$Ht% zzV$jya9#|Lc9O}CdFZO^Nj)4S%yRK9o#b4e2l&P)?13Rf7U^e(!)Uc7Z-#HEP_X6E zn0JbKBO$tdk($*K?D;%LgA2Y~HMNo^&Q(JWOmVqu!X2~6UEBmm!ptix%{hbx!+=!scChEz7x=!d_)?MDdW@UakJ={C{ zW^4QAXa2IjMuPd5GdEkS%y0NRJe-@lx!E?kSJvD8$b8*y)=EoTxujm`Lzm0%r=&YS z+z8^~eEL$rL6l#kK14Y4>5|r2QFGxTZ1ncik5;yL>$SZ{t6ZLK9^(UMmy$PA=AX62 zt9Ki2lYJka9Ib0sZ*bO6GJjF)S~Q{F@#Vbng-?aHdt||wou!788K#W82L?~>X-$aP zf+jFS2}CPEk!M2n1mgfkZQ6KJb44GBh6!JJta#GrE!KA{hRF$P^4Ii*3mRMF(`btYxqZv` zC-rHnbw2yvIY0hB)jq0f95nLIzViDtovpnw@#={v&YhXTqwUSPBk#Qr?#wc@#jTYi z&g_=A&Kt=XzpsCGo9)1Q{8P4$&H?j}A%79^`nl3i^VaMB z{Jk^+5XB2iL}_5{L9Uz(?B&F|3s#B%@sJ64KE5PDWj27nngGJAKvbqA2MYi!0=onT z0*C?$#|Z(lL0wEtF<>qif+2i`vv4bhQXrzFJ!FiVx;^gAykc0eN%q;nhI%#|K+^;V* z_S-A>4xIrABsk9?FfD$aGQzyLp79M>mX3*}5b&Sj8QMgZPg^68u6=9xcKc0X?M_bF zwJyN&{O98@To(!@BUPe}9gCwO!9JW+TB|nJ(v8aAC;SZ|O4)tU`H9N>^cXy28sMz@ z1l24bGh8jd_Fi)r~KBiRTmcHYGHh9T^Db4T1EG zIDF`ESwhHBh{KKn23zLRCx`O2Qs7OZtdfk?C&W;}8aPCk4hSLu0JeaOB0wo?D7X^n z(-G6nfkF15uMq8|6x}tp1Zo=jkMhNJza*y-gK^(N@xF1L#%lnS|3@2|>8T5RJqz$Hef6#E87a_mbw( zGl>_r63Muvn3+VdB5}SqA|Wp+r89}a5>4CP`i+Rq)JV>9OwNf&&dW zYq^wMqLEVOm{JjuQk9od)0t8?lTyEx(ulj%ta0hX>mVB_wlxXIOAlqGNCFF&815%- zK8pQ%D2HPh!yBmX5n{RmNjb!#i^I(GE`=+di$RAg_eKg?9vZrTW@0e1*@p)m5#c@^ zTwi(7ozDsL5?q}LegY3CFGo*mq;EK;Z$_kV<)we$^0v{4zs(n2I2~m(6K$h@@y0i9 zn~131vs894x_&ugNHuN8myd_4i^%{vx4{oHp+Ba%ALK?u5b88FJX9T$#ES=`ISPz| zwE<9;aaTrG<}%@zK=T|Q3x)4mB}pbCqt=2BbV+tPVh?voIsm|72Pgs^r{^aY3t<>J zn9DNah?BUrUsj}gww^UelmtH{F+{v4GnUUasb4&vEZ!>}ebyo8KuFG=+#LT%v4Y$S z%MRxP|2HDu|4Ql?(d=rz3{EV!|5@^P2S_>O+NZN*^h!7nlp|=FITd+*>u)07l$CVE z-fK72(>`~eg9qn)jO0eXjp*^AAu__Cg0o@YE<~e&HuQyG)trmpXaF@HYlT!^I}2ff zCw}n}4pHVkaLJ%>>69o}G+f!b#9l^x5dl98p|mZ*dhu)gtDFXjSdF*PHMrv81tfMn z)Rvb=*b+Hb4Ta#WzIDfQGYn9Zr0Sz)zp8lX%wh! z)~aoFu5FL1?Tq5*DyZ$At9>wq99*fb%+OVq{jW2jEZ>=^8w_hx2nlz88_c;`C!BxP zwi3)o)F=j%KbUa$<+@gViHN~O&h#0#uHiuqU`;Pl zTCG1wj9?$j)}~|%(9dTsQ{FwP%M0RfF@Z7_8ETfgtvNmlREeONi`U{fsLhv~n&k^| z%p1*#?qHs5i`va|EgFR_TDMxX=Ua4kS_p!zx(8eJU0My#wHg<;n%-(Pn{Pe3(`qT$ zW__^D)}_tHtpX-Py?1;M65k22=VW)#E*co%MGtQ+m;aq1@VQ0#%&eZwNw4F|>U{~hBt}K_X zoO4}ygJo=_-p#sqT$uTr&_Bgl3x+Ty7~b|j z7p5G9nG7|TKg?A;@u0}0rDCK|BXsrYP)p^b>x5V)Vbj*C@lxX}vd12@RzI$^EH%Aq z+E(+V*0II^*@L#)=?2oh6yYQ7b+awLk86%SY`-zz5%l`O)gvAC&u&G0S$+1fqv6F} zGMrh&th4duy(BI`1FDv%e?1kcjx;5AkO|*8%W$N7RKv~cZGx)!W6Gl z^gk-jmvP*G-#}*aB?<%siUWzFy%dy?a7ERt6#4cQhH|-Ih9OLuVpNt;Dj$j# zwW_QlC8xTkeRZ`~NNo3&0Ghz@8eP}W^xanU@+>U_D@#)xW7Av=>ti$W6{T_l67&A3 z+GHkljlqzq6AQyv0@G)djasOL-6gSXF=pc>Uo3tLtq`8JAA#$uUa3 z+dsV90`CG2ZJ+jleDAZw5j?$eK;*EyVwBl%ha!Nuw9;r~j`99y62a_!Bf<06q^p2~nogBKBAb#DhCF-?98$`4FnTnCkgR11wevyS+s?jrI)5S=L2+bg8iT598E~^`jIW0YW z&l!A=v9>f7Ts+BC{O)Yi(Z?}iQL6}H=v=YruQ)%WVYfRwYkbMXAM5*mo~Eu3o-;N4 zGG?^@{PA;UfwyfK73U%1ZI_L6oAW+NA)YM*97Z4bDUYJJMskzx)N@iE=_I^1vVTQb zb7}qcW8~yqrJ)DuIo}rF?ZbNm#o-8YHwIVS3zB>Xfmg9jm8Yl|((` zKe*2iF=n<&i8_0_iq)$Wnw8DsUgN8A$(&c+FmY}s! z47FWi4G4Xia2Aw5LpPx zQicHN1Z)zG!wlmILyE2vlTttmhEUDmED#7Jq=+lI66mZpW3r^8xEJ9nOJ*pVB*e}L z3jm`V6rqA_1Uy^-U;yQy=@eIdJqtjqoK@Pbay#PxP zPLfasoPYp(eAf+3D+2(;7Dj5vX50vnTcGsv+T%}1)`dRQ;+%!$+QX^|?inujCQ%FU z^q&Mqck1xm`J4Rv6mZ0JsJ{G@C}t85kC_D$6EgcHk5dA)5(dp0q;ivCFh-22THGaq0(Uxo9hL?4A zwjYt%T4`wW67kZt3OK8egm9 z_Vhj$$`bsiGJ$S14oRdedDWLg$S#$RTKrVYej#vhjkVamG)VV&Y?<7WrB%J5Co|A0zmx@#U(VubF$m09NzuG{aQ*+V7|EfE5Du@=ZoCPw$D7|bCXy@iy z=?HlZ@Ui_sD}wJ|Rh%CV74FZ@OWNhS$)0&v%5xS=Ax}~dfmO2QFiA%>RK$bnY6~8~ zcuNP>?;X?g#`evkI>bi;e=-J;iq2?vr^rNCK}Dyr?6WWs{9<>?nBp{v0yipt1H9nG zz$~v*eCp&JuSn1r>b8rK$%~QgjFF#-;SCAuuybJf<^o@L5ma=+RR)h&xQyilKQrJ~ z*>dStwb$5kn$L#VlpPMJIq@!lMzJa?oiRtyfUG65KgWJ@DRABz#@0;wdEe`ZDCj8T z^5u*QU<@5}0HakABmm$g>niv{7sqV#7os^u5!MUPYiS-G`Z0r6$c`_OT@=er#H7%$ z1rSpl9=eF;joJl(Kzx!=u?L^hSue)okz|`W$l+6o;c-ts5sajeFo6r!g?Su`Yv(zY zKpZUvSq$Hl{=I=@SS?o0rf~E)`m8|PQ=rdMurmkD_>7Ab!AX?hib%Mm@G{oDhjBm! z{;W*REd~pbsS^>GXYwx3bzXit^G_SdKP%3mR;OEoY3Ij1*EDcUK*EX*__kcIYIonA)2{if5ch77_$f`uFsvh3ZmXY-2W&o{C{^y|Nq}1;S*$DB`J?^ zBnkk1?qVsybP6i@fA@7Q7P%X_4qIEkkWk0 zg8OMnQZ*|jh++_3N}bxQBKiS9KR=0@@wS4|;ux0E5@c7a%5r2K1+M$o$W~Ug7x35A z_wPnI30!&L|L#Vose@mA_vY%m)V5!;0UkYUC*L;>O4Yt^Hqm?~5PujMif(zt^Nw5W z@-rHvaFLOL*whxw4A`A5MX4NsZ*W`#yJ2pBJ<$E`85U?=xS=OOqwQzf-$>Q%RBysV ztiToo2M#gXnVx&Fb!1z}Gv;-Iym^39^Qc?hdcV-w_rWGd2J;4dIWHD*alQ2lcq}6B zGl>B9!}0ODKgmyeS()CjSTRd?ufZ&V>64$vP=1%*u`7RULK_|FGlSTX#}3$|g)kC& zV=O<5beVK!Pqwj;m=|N1rH(sboHP|_4y+p}9`GJIS9nP>vRJI6L=zwvRd!BugvGTGm=%r_XmEI0 z%+TefAganr;s8Lf?)t)8rSq1hwpKbrF!UH%FaVFSEn|wSX8rwzJz0|i zxl0|EOtL{+w-roy!$sEKGRB7>D+8g%qgabpqh+vK8ds54Rtd^@sHGqqEJMi}qc&S;XPAka z=M(UeDn-jTXD)GE=f3 z$ulS)PYTjwM2TB4qAm{e8N@+X_NkBI0ho5Hos@)+x<=0kciH%uvwj>Zp8%ICft80K zSVU`kc}I^xUeEigada55Xn`d4wz$tmOjpKo_!X~@ex-svXXJ_0LxKE`_76}EKBZY^}#n^#g|Yz2K3Si~RP9-{8{{1l>{8yR85^jG3rw50Y)vsqxi>a!U(w zw9q1i#=}WmK>TY-H zR_`vF6!o!XAVVCJ_l}2o=#xzpYeL5=fR`C0?k9MB# z{PP{s?w84*B}vH$(QUQuk2B0MU*a8UHBS3_?6X5C>?|&L@BRL}M_DIqgz@L_l4}%# zBi?BkEAqWPTchi)IklOWZ?68T8lXVfrL0}V*FL$ZHy(~+Oh!reFLUf)NI7_CgDG|{ zd0tL0zg}3&<#=pI!R1i|Iw?Xkl;qyP8lGbn_ub$T@?oHVt8U>cuwzuj?WrWL^>gU2N-GLB+TmUJg*DN-By|8U=$Ah;^pb|wjV)~ zB{1=f_rAtA_>LVY#uvvgYR8z;5%@S5U%|7jM>B?J#xl_3GRO;)u!o5KU+lekIFx_i z|9_t6>|;CadkrCbL-tf-4Ozy%rXg!6Dw0$)b}Eg1X)z>33nELYu~bAFLbQ%j(JGZB z@;md{uj_N&_jTXj`@ie=pMM+GGc;TnP zg8M_ncGAH;5@}j>(a7fAd&ynQjfQBw@S&AynhcO^DJVe(dsAU6X1X&YUH;{v{6e9i z;TRz~Pks-OIGyC>2Z|)POTuol^soqz49Z7vWn|)(I$tFgcs1>CnU+tx@{yadN4g9D z1!lNBgNq9?9)(D5ojY3m@z65~Nw!-i6HJ=?9W(r=9FmJp_`8?lBvu%<&Q<-^ksFg< zQY<~(m=I(jvVx;|@rKW(SjK`!me{^5iJ~m2qJ4zDhi+M9={x#HRSMtE^ZAyVIWFe* z+CaFPpZoOCu}q-r<0?QEIy;do zkl!qvV_z{Bz;ub3Qnc_iZBaZ-V}fikv-o8^?B_mRb<_cI3J`|U?D|1=4#Gaj1GEz$ zMKngtXw|8x$(~n*Na}|!kz$G9VgGhy2wvjHx|TNcqxx4&y*e<8ka?u^>}zU9S^nhPzHm!-Wgylqw6 zxuaKe-G{dG?fX-j=Vsr0xDMddr`c%n@acB^a%AZ1aJ!`pU~yz6pSx`ipDsX4r63}@ z1aqY-P90_4v_6whN45?Eyzu2oH*f?kS(&?Tdpr3w8zMUhi0NMNu6_eahoC$c?#v5t zNK9UB1v?bq2DUm!z$r&W$IVjBMXqlvz==q1dIZ2#7PqH(warhJ_F~qm1>oQqQ&0pDayBre5EkV)tPbu;v4RJz1z*-XWB+pYrP9_YsTc)xT<84uBmyDS*tfP8ppGn9(m!`CCs%P#FQ_d84He}OsjcTKigYuJ68*Z`& zns>?9pHS3LF}2y!!Ji~#s2JfEiDop&ZM*h%<&*rE$U$&b(NgDe9!u@?Xn+>TnRu#= znIQzBSMj)X2mP2<(g}dryPkDDMVgH5&z$*Wn$_2*=MJRpO$k|=+jf9%qRAHqsD%`e(~s7zxnm!)Ya|8thl@cOUz>AyvWj-Is*wz*gQ;18$3{O3vv zUo|z=W~fZ+OO@w738#mF_Kd6aU7HmPcqASm70h3%J?>PyHQgS*5cj3>zDJ9M{9gu+1zh^@Z~~V6y)okj4^%dYH$ZlCyG#*zijW*L|w>m z2QdH=XQ&5&03=U?Ysh9$Zh(F1hFB`;~d zB^Ly_fvvFGG)7Pm-9$2$g4HB37|4O9~h>ntqrHEE@Jrj68LU1!3r^?>) zbe4mXt!3}VI5D0>tW@POjlBb#ne0>Us8$R;;)UANhhWN2Iriu88h|RB@$}{8>i~c44#frL5B{!eD8CPsAN!v?4kFdcq!m(reD@Qe>`j~3 zCB(?e`wAE%Cx~Gn-p|&r&P5qB64w1@G@U7BtfMp-_6Elvz!XBex8sW__iRYMDUk(N z#3tF8%Vh7=JzPKWkSN+p4#*$IMN9ei#H62il$f;lrl;MHdwwMqfkDo5YW3jH(XOkK`Q{SZ|O+3AaR`& zQHzw*qWnO#y{_rGc^w9ma<1!OPVn(`odOQYA0fpqH{E%+WB>Pu++{p$$3?MP(kmsa z)?Qh8CEJ`pg$d;)hnCy!Kg85|pApXl?ek4} z7@WMvgtQAzlcrEci=AK8_8iv@9OoH>C=(6P*_jlOwWsK`Vy!e6h&f*5EudrA)Pm7X z6!&>vNp0?e_EC24uL7UUlKZfsJ4|k0@SezQeq(>^%A;5IUt1q8zK<=*-@nuDIU%(W zCCZ&n!^l7Xv7HM^!BNhm-|5$PbFXhdl*V1^e}s8;KtpIUa37Cpg0Db%>#4oB<3Soo z*ki(f`6zOu<)2QWh+o@KMd9z$0rj>%AzLwTi^Woz2i?(FH*(U}of}zpD2i~`N{$Es zzu`eq#(F9R9CPT;(el~=DPTX zK?Y3Wgm0ZC>+f6zgm*E$MarjsOv!;+6ZkFkJwVlpbZ#haZiQtN{hbzmCoP`8YK0Xi zUO09|V9c+x{E9gSNg_esAVI++K`Aytc~UVD04zx`l>`B72Nelf(;R4UH}qa7QKu@= zcr_%Fgi7;7 z3^&1iR`94kOrip!25^QxjHF{e6eRlx!My(9r$A7g?jw{EL&#$I7kF#CiHNd+z?(7X z0kg0|Kgr0jz43w$%?-Fg@!AQdGtaAiNM^*^S*K>42i&8ONPZF zNk?>b$&pwx4LpL`d%0WiNFIR~BdBbqYzjNzw6xoXL`3Q6rKZEEx@}`~LR166Bo@Ay zMJOf5n+C(3n?!4dGuMOOxp{)|R54Hm$47#b6P*?!=fB`V!m2l>qx3}_P%D68laNioGd|?i{M))8Q8CY5+ z{2~wJC5LYSw|inE*A^M18srs4N}jfak-STiMA5!1ys$Ow`20BC(WgsN0?`T_5IlOj zM;xBcyYpW-1fKqgh!~BG zSZFU6Hty%&h}g>FeZb0s%;^pVeq>7dN*r|DpF4ELMqpwv1^T1aVUT_-uK({A_8K2O|IUY%%mawtJyU{;-KEa)J=inwmJ~=!B@yh@L&qawzq& zNFv0l9bFKDD9zG6GOUA&Bkfz13O8m-zB>70aqZBF2#EGd9A#Z6cPeS5dv&h*ytNW5 zS#P^?y0LG16(tmyt~gy7RQ=zZ4n}^SAYN9#aaxQN#hnQ*H>o&zMeNNMsdgdnP>BqP zge|%&rKYj_x_#KY#?hdfcb6ai_ov7i_(dd4IHwz z3FYluM;=k%4{>mG#N{KVS(%&z9#8x<=n!!5uo_eQW1++n^^Oo_zl-d46NOS>eEn4X06=Yp!R@t7??WYTND&Rw+hg9$nFUJ-(f(@ zCkTMAih{G@BuFh|Ki$Zt-jpaC6G zl)rA842?yTpd&(q<(J$c)l)+5o^q`T}`A2GDpOI&TQQ zj=zq*RgLY=gP%Z&BeG&P6Dg%nLrFDLLcZO0$M~=yX#m*1mWo8Lkp}KDz~7;l!&su| z$%)e6VT`HXZDp&|i333Rfx{~NdqzmoRy($*_da@Q^tFX^XV~oYexWB24ONSP`>M?Q z&-vV1M((6V;ULB|#A-rWzmMM6%OMWMT$LuBi!)?0c+1^TxA?4MkA^)OkrHnsw5-8x z=mkIJCu4QeOn63>m=Xc+Nr#@xY76+ITso5Ws%bDF8V&9UsRP5tQOQ2}KENf<0};Lq>b4Y#kI+KPc`vIXl;i{(2h@TIfvvpyyyTvHhZ+}bQ{VyT|BcAA25h0}!PoiIuh?n@-U(P9ZE;8O^L z1ZcedxNLn85GlbPT0G)IFhz8FH0_MoPKpw3jFOsig*e_B;1mMM8+kb&XhT$JcS6%DoB;VpH#Z%=>X*UT z<1aPykExblo-N0iGD4?VLgjg+9o%Wk1f9W?OYgI9Uu*V=3YYIf5Ar(n?)q-yai3V; zn7nl7ZP=N%M?=IhmD)VIi9`+KkypV**nruys_YX=a+EFS(BGSA|G7+hanj16b@0P8 zkU(j@^|o!tu4LoS<b!14%?|&eLVNJ=$87W6w)cN?g7~RIySwlbF&z+8 z5t9xTyNrIFc)uJH^8>{w9+X!M(E*d)D36OH{^C(_lFV%m194*Q zC>S<3NE4*G!qNGHJIvvo z{lsYcsgTHw>2%}qgM@)(o?u~Bz`d+cxYHs@it6pz7_9BM4X2%6^C!~*=_MFn;GU!y zq1+s8;OO5O=<`}J5ZY`73j;Qn3zt=BRpzD!nY#zT zzK}ne4*ux`vGA`kAbu6i>RINdER>*1mbqh=7;=JW$&wk%TJbH5B$+L5_?rstcMRxT zHd!)9+b~DRGe>VdlqpbEH z2-TNGo6^x@&0=V*QWeQVTKyMq*q@>L-W#RJTDxytE-jJ;;!>6W&!Bpf&=Ur~XT<*j zs+V+?3N9~2GUERls{chS{HJO9@bdEg^seoRmP%Fh4$8WTCFVWBbuy*N6q~eSMx_?A zjOT$*ays}rFH<0*K3Cx_LH`67B5Ic#aRj`r4!hKks5UtLK27g9VjJMGgEpGUGbE(> z<0lFKxj4L)Pw*!RKmPsQ<(I_IW?o`Ccz|z>aTf$A6>^1%7oo@xZLhr!n{`r>VGTsV zudbmib*ZS6zKvkU)NUZJvcDC1>W!GFs7c~XFF6ABslaApenfB+Y#wD2LoJ=|+w#Dc zc`a-JHfzV8FNQe2#0U;(yGi5Akc)f7mtoN?#+MPFU&X>PLv}|Z^i0ioOJ~OX3+~K5 zjJ&1MG^UQKoqgmZz-Stc+qtwl>6H2NDhN1qJWtEitLDpxCqsnxHJ+s2MuX==>o>Sf z7rwv0`t|+y z4}W;WQmy4M!0oli7Cv!S?%Rt@(>oWxj0WEo6~Ku0x6WqT_dg;UqBxd(+$%xzQHHSq zy?bi&Yp6C8-(b3s^B$nDy&mAG|0CP0y&W)65#!M5Bc8q{bgBkg@AejiJ4a=qbnjD` zYjq^JXvdkhyFS#P+&R|HzeTWkI!W2Kl<3~wK~BH;?}&wM%Y+L4Ni6K4&btch4}K2( zX#D~OhdRqzTbhKza9ZTz%=0v012PzQoh%Qg<`NN zB#4PJ5drA!cB~wUssu~29MfUNM7A)pA+sUf-V9NIYMnIE*htVFVr46+Ff7R24c2-} zDACCmNHUdyb3sC?Eo`kUPezc}1SACjC`5JV%pc$mZ~$}}fldr(6-fdWI3rqL_;y6j z3s+c|g))dq&hp53fUTYCePsR#5}>CUzv)@}b()@hdv&t+0K`53hj6eYrURhUjatEc zWxN(}WK8WYY%34O8F6}(toEE*c_3sHrVQjSY;aM~n%o4!4vBhQWh>!s+yud~zMF#8 zh%_M{jJcP@0WfFpu}rp;OexuHh!UAdk#d9hbQ;bK98s|-9_u^mOCg@!-E9fd`w~ru zPy*bl?>doCT!liRD21xOjhJ{&6U_@y+1J%sVp5}d*yz4DS5qo38mXeUb_$8r0g-ja zLKKq3914qmmcSEk;)eG;N2#4QP5QaRo`Wnd)6s|d(Y$Y~JH(m|b5yxAxKjtLV02m2 z5HVNtvP`$Xz#G_f32!cN`DmJwTTQ;Lj~|IR`8w=PytA(`L`ikzH)od18}vOKY8$d@z<-9b{FIB_dc0z{n|FIVZY*84XLR; zAnx;>iwD2SpR2G6w*6$nV-#^z$ z;;&2FWcy6$_*|E=eO(!`^w}F4K)_Bxc>FUgtPEgA;)$B#W!4EItW~-ZTGTQXhv53p z#gC0wn^3(}@9Qa^*rQ>!W?khtqmlN1Cs@^5V&`T;T^*)HigN8DCo{Vr}Aj>D<4`i2waG{WBx(-PHt9B<>!NqVY|j?*{&DM*P-Ltv*tiyR{r$XS zaPtVs;jUF@63Msd^cfIfq9fYuXX{Je-Ei0c?jQ8v&Z?TlcaeWO0^Ggw&$}9L#zJqhW!rov`wm9e>C82Ucl4R>J%Ylb8lPH zBqVHPAM<|xw`rQt5|sS9^_AM)bZm;lgU90Ndg58OW#Wk(^AD=GZ#v*d1)hyw-t^NO z_M@Qw!eXTdefIG!Yvi*Ako$(lAo*=T{eM3e5&!eDhGoOcW04zXc`RD_cVp2nbTcv* z{iK`!FUKOK%sdB2ZKAZ1KI=oCH zqi*v2N+Wm2eD6$|fY@dx_m2#NIH-rY#_VeaGr{4Sn0jaD)b>IYDsGq^Miu0csJwzZ zW37Fw_FS!~4mk1~cr1T??4tKi@VGa)Y~6hWoy3-|-Uvws%0!hkbW?EStG9}Gp)FSt zzo~jSRRDMt_IZG4xAx1hNAUTdW6>SQ65mvf-_$vWH7p*4t97A;t(uO`itV}|@%3@+ ztMy5gs8>j}?fHY1d}iFVv(?XSC?_mlo6v;cmlGf4TO>U9va}zW$Spv|qHR0-TXNG+ zBV*B)WA^hShfA(SKm9kxqNE6urWt^96d8-8LwEc(772`8L#wnm&1R=OIYDTKXgD73 zmHhc#dPx9#&D7=x)2lDuTr))kD9?FBJx4cA;dQ5z>1Cr`JSTm~*p?sg^O+`rDH6x3S3T&TR(o6C`W+;P1yGr&vO*wJZQ9TdWvdr;0@E6bN)eGlL`! z09b$u+2zymQawo&qkT-)SqiQgt*EF)w@K^LJkIUdi@_ORU zbV$1vWP|{aBnJS}&h}-5vrG`^O9F4n^oO{RX!nG!F5I_66*zw592=`m1-IztC|na! z(o=K-`68VQuE-T)_q>4jcKn_-ygMd4erm-uT?=H<2>=}>${N)MYeC;Q1PKTU!J?%E z`8{%rN6-|?+6*Qg+W-l)DVrUzX7a+jQLjX-DVSZ339jrik%(@?vr_{p*=IbpLKtm& z6g`#hSX=L~0uGB2YU zG6CrjCVqS?UaN}ogw~vVf`L=5f-I`p=2Opu{EBQc1jSuv`MAa zY1QGN+d)X*!m>KYa48+kV@Dk~e5svNQ1(2~hLULQ3wW?k;|Gu`a*kV?F@UUQKOK*n z8G4xqAU`|LTHFY>sG$s4P0=wT=f{$fP7Js(*isWtv2e!lEXhN>JKpBnUn*~@IB2sA z*_U~k{oI#fB0zH5M8DS>4CT`Kyj8X|{wpf=>tiB_=l@XW{Ohsk`=d$wrq=s+-ovQ( zhu>|u)94R$#4dBr|Dev9cIXk3D;iSTq{Q9cFbAM2zt9P3(vd*|=EsNH*eGodiQ(@h z=PTBI>!_)1_Wa;8z9kc;F6sgJSu9>#>_AIju>GgvhYK&2KGL<-Xq;`PjaQ{!Se;6A zdRe$mWKy(_j)@O_btrWQLtQbA;`km;7S>U9IffS?F%ucigQW5sY3h00Ehh>rvQw-s zkKON&x!g{{neF)Q54Tdwdl5F`pU0v<^)0A9e4lyDIKE14Uu$ja%r1uU%Rh}pzh?~( zJQppUKO$o+XO>cD=R)Zn@lJXzB3rRNG&}m?Z=CbfTS%cc%_imb$>SGKz^*zt5l?8aXp(vXQPu{(Zc7A8NC z0xLD7{#z0VXH5L7ELerd;<>-hNH5R6Iu$?rU(ZNJFE{$s;Sq^EJt`&F#Y?q1`ot;0 zo0ULP-Pzod1i6&limj_S>^s6|nn;`g^E$u{5LnU7`ud36+PV)s)yzj7G9 zsrF%ElO6Bk!e=Q*Ei^!PzPR2(+H$Mg>?y-*ZO2!pDWPGRV;>%k1qQ+o#*C|;KKd4{ zrR=rv<#ve-Jb65DW5`Do<;Uk#nc1uthsfg(y<*uYX@hCTnphKlqfKnCM6EhLJ{=nF zNR%<2PV}y!6=+Xp^HnI~RxEH)8l(=vm*#r|OiGEeAuVD%(v$T1#_i6P|8pnR-^@se zk3s#gNPYJW&DjjX;3xlS_G-(U$#q9+g%hs#r`;UhQhW43nD6doq7&Q_c~z1_UM4z^ znWKt-Av!5r>E&Z9ej_@qCi>{JWMhaGmYp;vzh+<0;lN!K@4h~Hgy?iILWoY!a)juF zZHot2;gC50Y!w-7%T}OmS7l2O37kZ@GuSV{yxhx_=$N*@LOQHt@C(cv_BDZG?;n6&h%4;(n z>W0EZ zE;m9eCh3@wYOvw8E6D)e;|ofAFuGmjq-a#HwP7Rg=rwZEq=?YAT(6{9Zez)o^Wnjp zA3j)m;AXpc^_``cv^(HJN41@KgQdM;j0ANxU$eOIojBtKGz?#C!%)JGKYYaDcW{hy?Inh+~;u(PB#fB+?ljo_vcQk*nQ2P3uJDE-qP?RoSfCEGFzOYzS=c( zQd9SAPu0|_(B?n;7=Ay*B6>kL-*j|YIqiDLo?wZ~ltCu;zNEC-nDPyZ`M{Cjzd6Jr zt0ObZGcWrEuuK|LlTKe2qEksDm66eMyO5%Lqrpde4qH@6bJ>a8_Ky)+jTdl65i2i+ zi+s&0Bx#>#qYRLOz~p@kb}s-)F(vCV!uimOH6Zsy3rzXn}9C5}So%cm0b)tgWH3$@c1n!?~>L zP!)zikHmT0dMu-kda*( z?t<~Ipz|w{H^G7kFc~b)5UksV8(>Jwtuf`=D1=Dx0YLV2pa#-Og|~YXl%Sg?wUXr3 zpZAaas8wN-O>>g%DDv@=M3qQ(GDvpuNOnUGv4zP2ei+-+$%n_+NWMx=@C)=GmAK=c zlE|R=rKKbZ?h5}Wy`ZoKKF&ip?F?)%iPdL-)Zx^%QM+-1TQZV`<1O4*ehT?RFKANe zCDas2d9jO|Cp?Xd>^zg6KPtE}1{USe(6Pcc1t9NqmGf5;6PlaF z3K|dpMLGZ9Wx@XNF-S-z>Sa>=*1p7xyeRxlIsZR8#C~JKl37BASt6dlWx@XSAvU}& zMdkl3NA({FB#tcuiHAmi0TL^gfyB8#fJC`X%RnMy8AyDh{|k$l8j?0To~~T+#V>7D zg0j4fV#P0BveP@&G76ukk^7^5^^z683sE=%uuTvr!n1$?8O587@?6DJAQq6;`g&bTob~R~ zo48AndoOB`Def&gOGity#d-D|9Y3P~e$FP;Skursl(ga7i;X9betT&ax`8@zB2{yK zvb0i9!=rq)ZzWp-R|b5Gv}nj zN9y}dS0}*18Y|aVn^Je?f4N`sI^OfqEpyASyANJpZ}&XsY4jZV%*BJZ-}ZjKAue$J zqSoixSI2}G=f8eH+JSjl0M3dHNlnx7wk$}zn~gP^X23^S=+##3M6c-tiJ|mPZKQfB zV>{u-C)Q-<>W=HlwMj>uJG$-DO!GgclBi*R4-Qu5Ugo=ro`UGI*@|Yz#&`ieJP0fu z95Bm1X&Va6p^dJ(ny*yq66Q=}MC&=`M^E-)^`?(g>RoRfS%d*ufFf{h^hWR^j4%SL zVxNIPB;9;v{x?6qX)>%)o%ORTHiA1OApPKG&>(SC)e5CXk+%=jq`RbO82|990q? zUnbe-u$~2(er7Ws>{H=arjZiVkOCyu5`$rINsl#=iNRMWVHA+qEd?)Gh}->Cq`u1KK^LsrC$9-E_~STkgnn zV&IdAnq*K!9gPy6Q!P`6Z`NQpRct@nhtXuy<8KbIT2d7-vf?MODUPeM*6 zBFYw1@2JF6q>es5X4Wj8C^ZD6Lz3xy&3NH93#ZDHqM;amB9J>n$x@aBLwRNx?GSCL zRd;x`wIi37?87}HWmSu1lDbo=1tqw7c0H+gn+Q9%O=X;Z0P}2X0`~(h?7~wVjSY1? z!1Q|FR2m4_mAKnxkdJ5lgN^oP<{GAFlc*s|z=euo7|6-H(x9^arsyn)j=Q88ZR*QM z4^frq+NT28Av@Y?8_VUr>}{U6?05sk#|rqBN@i_a^^dPHwVSnZsVf54et&Sl(=Ecz zbo6!wT*Qr@bOHlAU1U#j8qrkcr zmum0D*B%8%JSFcdaJlH_`vdI$mi|1;oRbcp)J@Qqk+TMj(mD^o^yEW+rL;9&&-eVY zE4;kqiu2uMkIjGbwN8P3x7m@7gSO7y+|MiQ4$$S5q)wPCLp&Lg#@M+4UBAPA zx)DZ6NaOGf9}{nhZbet>j?U63=~$&zrHAD33TU$g#W|8Y3-3(Xhtp!Hgoy6b6~2Ls zDUMDANVt$dUtpSU$3T-v;pJGrE}Y3B z*lQt+tPshNF^TQn<)0apYBK-|);dHEZ|8A@aL^-C=rN$P z12=AK;~{+$3#bNXntlwPF<6DZ1@FBn%`K#@q&cq#Jinv~%fY@Qe(B(pki}jmamm_qT6li)QcG^nDu_}w~2$4CNouv>_Ion+B$Q1^rkV1g` z!mwwNCMEoMfXwic3&EL^BTz;#HWZN{@4YUFhQ8*QMS-s_O9wToH${^^hU9Abfl2_d z!WtGMkQS}-P+5DZ--OnV<;@PzY2Q|6u%otpTbW3XxEGU;(vD!%=7guOghb=p^k8Ah zf{%ib!_?Yo1(}Mpg4G{$Z;eB)G&lM$nr(u_-8AX7fC^&hypIOF*fCixYUE_MuA5$6g}nRdkhH0V%^RAg-4;T}Oj7}|yhZRxt--9WB~^mh?Y z+s2(+4Ucz)%4zHGNB$21aOh<*{IJJ~XQdI36%qqpoU9W52QZ2$V{TYV0!zh;y&=a;p^Q?(NBUG6;^C*R6m=%d z7TaXyT7%osa`}Xh;R-KM611=l&IPJQrP7qN#lnLtI5fy4NkwbtqR5u-Xz)|f>G>{a z{b-U+obaqJ?Xabwwk!BOKZQgTG96wgSPOa1pP@-r_#0IONEIXm<=J;T%7qFp=BJ|> zKK$d`GA2b-#FE=pe5Rw5cUT^>(@hO5PT`FNt;mT`7FM~|K^;ic@^fxmDiU;fEj*+m zcsPbio<{jiqu|Kxhg#uuCc%-El@jUP*(3F%GV{2qAR{sdU{U?Q3LOo^Z-}iftOJNy z@czfkl~zs6Le_UEBjEJW_UwT9l8x=4eVlW4mOnI}+*(|7*@VUG zcOHKmW%|12XZ4cQg^MOmPgO459pCcOOXhYQypmi!6({|%#l`2_g)88`(pGrXOZpyK z@V!y#1_IC&EMq=)^t0-|^ZNK>lCohjESi*^S|e4#)pG+G-c;$)iBzvm7ac0TxY9ah z=j~+7cbPWlJh>~<;+*XldSJ8ZQbli>bR=j9LxN-Vw+BF_B}%=Hw9G?;i-zlD79U)y zE=8I41krM(*L-n*LA+oyzl9RG^I~aiJ)r^8q8YMD}(gG4SE7fWi zl~VZIvj%OXvqT&HT4TkuXtSY6>DbxxAFH<7ICT&OY4mfR52YVf;J>Txe=*n6x<~7<8>DbCeP!UuoD?nr9zQa(wxl~GvSNGx~p|dAgWuTaSsK}AR#mxQ2hLATWQ7< zFCdyrd=^WDOwa^2X@{D$Mc(!MlKalzm$}Gu?9{pnMh&D4tncdbefv-dCgJE{Qk|@)T*h8&t?n#+jUE{j3YwA-?wchK( zar@1unmVGcVN9y7*`N;^!wk4&HeJSkN$tYYX1I{je50;=oQTSE1=?=Z*PEc%rNPj= z(|OUGmwJ3ZVVq%dTbmXW?+5bM)O@s{U8~z|7ajb);+F9_N%DxxjqgGGT`LpszU`)Xg`qrU!yK903^uDO;YYpA2&9n_P;zLLCEQUV=Vc4p?}8s?q{F7v+;N5PTZZpdUxT`-5(2g0a*^T zo`c@P!5-k?PjZND9Nxzq{zVQfJ0P@vKxE5+*nt6wlLJz112T^XRxA#XWC!Kf4=QXK zR5~!Id~#5=ZBYI3pyuKrS@xdx`g=Oa_sqE6qk^{$4hS2y-P8FCY5xD9jzpLJ$LZUZ zxd>?q;nH^#jqwwLv_`Ctk56&_L#}>)Ma&~LO#+)_J2p3|D}!We||3foirEg z0;yed15;H3|LA95Ld15=Ad2dyKOpn#zd+^_Z+?Z$UFJK*nyOvjR;gS3b}oEGylvh@ zvg3JgyV>fSfXA9qW?0=bJ#;va1|Yh#VmR|K6C(mqI(Yj@Ez=v zx*i@y_;T}>Kz9voVXsPA-LW0+e0v|Ay7Q)t2;igKy7rVTshGC~sEmFsq90S7<2tO& zjJ=n!=Es>QA-eBl2eTax>O9R~Z5Q_P#NPMcUa|hPCPB`HNJI4>r1`oOCo7Qh{>oE? zH21j7_gh1?H1^xeo^7`~cdIqAv?MI zMObUX^><;nA-<0fap;CGy@mq7So|JMlONqB;RoH09|YJd7f3xz24<)^0#&|G+GR!L zG$l>sLV`pe3#iXboMYdse%4J)g&neo5<@U~}u^eBo?Vyi1x^GC`6D05bbz zgrrwL>kC0-FQa`*?n0nlguM#-N$wzO1&rw1FPU$ctkAfdu3#`vKiOtNw|foHl{uG` z6Fsa5N~|S-ffha$UgT{uS;>gLR*udww%Q0%8EzXc<^2l5?;s}O@$Hi$;vI=RT|$6S zVUMY}P@lkp5Nl_hC@x4cVSE1sB#Piy>I4QcKpRDFqbO~Az{&7oANy%sS0~cr1GRIc zIH4xyo(zHRAxJW<8XGR^3QW|mqPwuIc_6C-{&MKr)oRV0^ubHvtV;C9*OZ2C(T%?J z6M;WU5AX)zG~Z<1D4s15g(HGNx^2!b}#TG|Xj`;VX9({DW*yotI$I<%}ILk;-X;weHzM@I8`%QP4`cm_dzP%6YtX zwH;>H7J$B2ZdgVGh@ZOU$sbUo@a=3RQeeLIX3YM@2@ox0#N?T#qvI`jR0yUvPl-)( z)6d*n{kac=20o-_MnWcUiF8N;BG@bfhqk6$eq4BJ9`|Y z%mK@yiWLH=btu>?-^0vo16uKl@zgkOrTe(;>DL;Jr&Wn6Hd^U_Q#-td2PRt3uJ6bS5>Wc zrB^;va?QLV5KsZwKa?w07(|w0drv1PR%~JLBobuYjJ*DOf9&B{b zH6ct^2!lt43v`&_3ro-!^~AIAb?5e&=&=|nzSO~0WmQ{Fr@i^mC#S0UzA@J6arRk) z^ky=5jS$)91arkY4Sm-%r=7yiTcG)|=pv2Zbu%#z#5AcLLP!d<^gSQR#QXgP3fJVW zcXxFtim|8Z`xCkoS`45P$nq1=>`nbd)q!LN4ZMjvdyXw2j7!vcME)*@Uo9*Y`Lz67 zs(`+g6jCZCjbh#Q9yxjmQ~x&DOP|)YG^7Ww(>mI&E>;PJYMaD8U*+p1-jbDIVIdm^&0Op&s8>aKx7HPgqYW^@q!j1Q0pN=wYI%`?(~ z%Lz5(-2mBK3D4QYXG=j@%`s8~*Y2%z#!Ns2)cs>Q2^kL;R~y9!?8^M{l|}trV$>5g ze)iJ9t5Q*@NX8IorCTa=$E{Md!mEioJP```F=f-v7OAn_qVG}uoFtnzffKUjtnpoK z6!_INuGstVK}wT|^>&v_heuNKTaU$wSUKz_Y&|nN&{*~EdBiv6(G=e6#ges@ySL`! zN`1s{quSZw(iyRg2`+drb@S3(%|>xUz;Avcn3{d>?vL3kON)Qm^ir;6f zDFuYi{HzdqH7x8gZCooBx>+lU#7G2am=qv@Vj!X#nY6CdGA0Y}iWhypN!SMuRI_8O zDlEN5lh2tXhe(hXb*wRw`+zyBDPwO`)V96~*rPc`!4YKYyYjSeO1dQ|VkIHSwvyw3 za&TJQq)@-efzhSCu&;$rZIl;5%k$C%sMMUcnz8AzPTDm=`iC#Oi${g>Sh!LceY!BC z%NZA3m9eM=>SLjruPPg@qz~t&U+@qX7^QZ8mHw1}nA}b#v%n7`GQQDRFWiwer7?K9 z#FlXjLrcfob3%!13!EeV`nbg#{iAE^T+e&p)?sDVb{UL4CYxA5`ds6yk2>fQcXGvM;`5bdb z3thB2>vL(S7-8kNJr0uJRv^*M_aG!e0lX|>)e8Dj!ZFe}S-Hqe+x#_DS5T86t<#(> zKd^iC(sXiz3E3M+)mv6ahWYa$dEsRF3@8cZMa2dJ7zo6yqhb%5BI->Ul70j(T|t8e zsYgOTcCG!99UMCYu3)+Vq@b>>ymKSUqGVmFa&DxgexpRe@IVGyFlA4=tSSp|358D? zNMFk>kgB5w6jI&4B`7Hta!Rp@itzTl)QoR3cQ*M#Aeu%ErRhP*5=D=-Hm|J3G~F!f z%Oc!pw}@5QS!OL5c|%(0GAzwKcDBXx?m%%}54;<#CqaeCWYD1il%^b8T~|Pea#^7T zy3&q?I6@m(2(hcxJ&{v)*5%=8hAWaDX>e8)+|LU}-q$?|J33$P*loS^k#yk_#u~L zFAir{=Cxg=P?E)f$!OJS02>G`DVDBq)M#~v z*AH)&)pD{01N+n9V-3`lK=^!F*`9Q?{>`me6Cj%-)ZHRcuqgqM5~Kl;ZgKfFhGmXE zFlP-LO_eu9VMeU*&RiIx;uCAnH258Li-U#f=sGlN>6`mi6^rin(;EqqKLV_$QZ@fuvnJNMER*nQ4d`T@{LiIc2%wJ!k%k# z+{(bCcDz1c^)ZW=K|qrsS!UIQjf@=i{5zsd@Fer2*TsDhv^&%*%0v2^btzNISq!e` zjXDHOAFgd@;>Nen+Q<+i&wiV7Dulx?MPVw_;ojo%-MQx>!OSbAM1UP*T2Q_{7LHei zqsdXtjEr~N&xu;Vczx+U0(2qxOwH8)N8WipH5G<^`lJ$i=p91u7?cu_5<1eP7ezos zDWU|WN-+r~p@Se@q)G1rQl&#^QbeSQARt8qR8Ulq<=uIAXFu%D?9A?`-T&asGjryC z&hOm6>q0W0;nV9^L2iSFFvW6WTV00*%>R7@_A+nhwZT0sA|$A{(Mb6f_L3G@bfn|8yXj+!?=Gn)yErAl#a_k7lxQfs?#Rge3@t0^f< zJakT?V%md`!=Jeg9+aXGfd4Y4m!M~i8BE3#Y*yKPu{V-%3<;F z2RWQ6E2Wm!n(aht%7ci_)xO_eCd9&`X#qlaV@nF6WWFMM5(Zgmmw_{Vuk6Z|hw@X! z_0&I_o^AE}Z7f0cDscT(O+kI8m*rbAUJ+a~FVcn$+d{nJ@cTh?ue?L(VZlG1ULmz! z5yxJ!&|Zn$Ua5{=nWbL2lU_7$-$k|mj7c!LeX1ROYD;|@Cw*Aner>gWU72hq>;9yI zIzwL0_~w4IlYVpF0ZX+3YsUfG&;k40fomNDj!OehCj&0LgRW|WZjOU@LI*u^2faE5 zy_W{>pA6!7haRX6`8f^+gboGe4n67^3SAlsKN-UFQiy7lNJmO^D21F$iDm1c#4k}2 zPbkT}!%uj1cPQZB6oemj{W@41eSTKkdHT0)`%BVCpR=i?XDcE<>QwJMDM;*jh0^@H6~U9<`Nt?QiGrScP|A@*mv z5LdF?^xHRRa2tf`Ee3LcG!+xIKgYu6F=pqB#n<<_D23`PWTHNs zb8@{Hud8*+c{RRYekj2*p4uSG!)#=$I02lmUve8<7sW}=jYuNX?RoB$-#UH!QRAn= z8iLn3_l$6-B;$OOgUgMq6P(p4Mdw zUMSqv8pL91vLqYgHR!$-#CfS2Gz?q|o$MI;xmz>nSs|&XXqZ=ZIIZj-g5!=^zKrZ& zgLk6q?v9Myul2~6_bp1&`17(u%ZH|FFwsnPo6FfPRpBje=-G7CSCmk6m2W)l{vg!m zOvb#=bD`}^K|;1^y*5_(ukr%J=IH^KWtmRhQkvbe#mLX%Lg_yG)XPKs&&B@*t_Ckk z!8tqNckAagc+!qL_Ep~;wb>YgCf3t8YcA`;Kc&*mJPmNF*@DS)|Ltof*56sak2zG` z?H$RhsdhGGy4uw4UaPLn(fg9b*%|%uH@2VAE%cC~HY@an6Gy-5Z?~=*$=2JmAAM__ zml98Zo_txBy%0hBJd0Z&na{NzO8;{HbS|poBCOKU*CP*`$I(2eNb5?3^s&E2C!HSc zNBCCGsv)(a6{2b_pfWC#9s}Bq<<%YzIyc5Qm+38sHbme`@vK-!i&sa*B( z*>&XgwH-1lEVrM?dCouOeu+1j&fg756h6FZsGEHeds;^l?tWGO@CDlYj_Zx(Gzkr! zX`jUOG46NPcJ*88G)a@AIUE+7ePaEe?vE z+RD(SNI`!O`}9q}==wGPvDCa1?aR2*v4Fx&?Ru1s^eC)ZWnC-VHEx~9Q~#_>!?N0B zF*mQ8!M~;}>mEaQn%x?&yEJd`54u<))x{52EWQ=*a$TR~+3ZdyCGM>j?OBy+d>9zM zZYiICBW*QXVbDNB)hks=t#r2k5az_n3>a6GnRUKR3O=Xt^b^-V?*5)C+$+G>y%pEw z_}nXL`z<@2#*uT*;8F%NZPMqo?Y3TQv=pk)S>;2yef`5hw5)g0kWht%ma0~8aAOe; z#<%72erA6ANm%pxXDgqe$vH`dM`_yPiLa>@}O*L92DmGRM{v=5LF@f-($6%2guj3nPvaQypE%W3Li&Dz$S z^Qr5Och;wBmD@0*B(4zxrsMMjn4xt)F4|SExD)e*Z0z@GSQzdb zc8*GOk$WFKdFmcV`(9$UVmvgw>AsG7K$~$%OR76rR-^aNno{5Av-m>J2glPntHWlt zFQc%!sn5sU#TomVto}jJ96OFRJqJ-9R!e?UO~%eO<2h7LA6qb77+(7CCHLPPdOZq^ zxnNE6e8jTWLjHuLy&gOfYNpr%{e-ak80h}*=`-Gq%vW0}41@01>~aScB};m5=I?k( zu&Z;}V`)}-SKl=@Xr>w&P*QLHjBif46z{HHbd7axu({%e_f8U#{RO>s&S{IjYEbZa zWE-^XVYx)h&C9Wt=Nx0^@A&Q8i#hYLClIc~EeZOo?6(S)yqb=7*UiXk#M)j8vr zdY*?K(9f%}Av9Yg030>;F8l0asC~a@*!bLs>?SIWzWK?{cP=6EcJ=4SQBemI<8|R4 zR%)H)>tlSBZ0?f}$BY@@`>K9xkyZI>NbhCem_Km)MQNfN#FG8do@{4M(#O{MdOEaP@qC$ z@UyM9#XmO;1wPjt)+q8;JDsO+A3R6b>n~V8qr!F%tp+l3g|HHzCYJu-SH13)r93}8 zSJJU@Nr2V~^Y}-##K7i9hF>KkiH;6*e|>__lEQ?XZ&{2}g8tRSe~dw%Lv_ zGc@!!t%I5ZF}&*#5^4?CK)yt&C?s8zDcywPYY?yFxXDGKPfFQ z67Hri(MW+>cxJxhGUREAy95u>K|e_OEsz$R>rjAt&5`;9;pHwFj3x)1Q^2TN|3jn! zOwv3n&Hg@+y?n*-Vurienf~o%3{_BuG;>+XAqE=7WynreWlD{|r0=h@0{XK4l#=z_ z##g`GT)P+I>4OYDRo_$s;na53|${r&uVC3J3ftqxaYHq8pQzd^zfkYc6PZQliR=Yl4EFa-}@2;yXYC};s<|1 z{VSf8yU@G<0Q2Tj*0$35^y2E~jH3;rHC(lpoWd_f;NdE?L@Fw#=f$+l=aHF|!5ghn_JII~p(c~CCb@*S3U5qj>6 zcg7l>oT0LyIWJ9LGESh}^SJL7&Jw>rt#HBBz4 zKKq^U-wnO?Pn9nzP@TFQ>e-y_mCEp^g;C%a?3tOLNd$1c z^rsAIuvU^b4gx{a#$rkygtSTaFpjTy{yhvz`9(Z`K$YQ`@VG{TbOGC4VfGQXo0-*9 zWsUx=HC4e)5k}_8(&3g1(6(Vx+jJ#YS){;kNdd1A%Q~nr02N0A6tTLp#ZJ)_qpq{r zw(pkK+S1XA8L3|O?e|)OS>oEywOtX$HJ^F#8SXT5N-e!18RBpU#NWH=qlq@}^MrFE zn*-x^Ipt!mgnRr=(?0L{0U*9&k)=uw(H|^5II88#=#xoWH_6w#XpME=55tSbgMG=t3Dw(oMktgprD#K zF#Lc@zEI${FBq5vTkj%8@Zj8d@P%%$ByK>t2dsdEC}1HPxDn@FCM@u>w!X(1xbmo2 zX1(&2LLd(2nGbCl)yi&Ea;K5Zz1Q-kq9Q#eVB~esSbdOZtQ4o6T3J&RUAMYP1F)20 zils*jLzcrDa(Gt9r5XP0bwEifniqiQIVe6H|d=yCJf`8~aUx z&r4J6Q;gs0U>WN}d)_s0gJiTxsg!JS=KJZc4naxYf`=+dsugU*!@nbPcfB>9nNq5 z7OZFF=%AqGvQRwzQ`YK8k4mUEZc2F)EN%|sLg`vPn|oIetp-i&ipAt|CG*D>hl&*p z8w5XnRWVAMzga!1ACjHhS$}Wb;mP~PP;Zy?y9?aq9Xe+R5G-<8+oe-X8d(<>GJ0*X zDFMJ?joNQ;Y>X{l?}66Tw|#n9QahTBXRm~8zoX8;jfc%keI2B3%ZHOo^JMeuViEJ> zflJkWPP9->^ePs;Tyt+3wJB+|GSeIeRtAP+>~mR`*ksKYGeSQx-dwzJ0LBWAd=F#N zoa9bAruvoe%Dp@z(4pz(+`C?r{4~>9>C-wGe|=dD4#KxUUU6Sx?)Y`|ww;(q9ZL9C z0o6=~sB}YCzAk9T6J{!__`<=>H$dN37@hn_)_#Y-KI%ey;XVPzZY3DPr(UzkR6TWnHTq}EBA#9AA zlf`XdajX8O{s3;G1O5X%)n=lz#=X{c|MBc>ac48jE#vNr`2e5tP|$`at~a3=EK&-OyoZAhG5#)lp#RWC zVsAt)W8eIAG3d?MreaLY$k~S_2>-5MY;TXu7<9X?{Umjv{71-n3vc_+lv&&?&zykM zUp?m+;GRhHmO_`Ezar<05?Z}ZU5`(WPjxcQ1+@WsK8;9Di%+_-Y_d-M9v1KfR^|{O zD8*vk@QJ8to^F=qhEclgjn|P}R-a9>74I$gbG>}7fpLCw0_C>e%2M!L;f#WaznR87 z{I2%l<>thUHkntY&F_kJspSikFw=KN-j(*Z#|OC=N75vk?|leh-gqi=!KpL)!;3|u z8Brj3LXEg(#h#o zqc^=~t8a8g^IiYxz0h=a@8jSzp3iSE5!7cIKXS&*3w2Y(Y!+rbtt)J5opzwgdv;dk zy@`6#vyUp8t{1h#oYieVv~L7A8NH*P%IoT(rB$j5Hf9-2e7ufOZ;eVGHAO@6uf`09 zudGH>4ClJ>n8Q_4{tW+&tTwfHah*2pg?_XSy|Q1mK)9u+Hijumc&~IV`MOu4N@mfB zR8{`1O6l6>qNy~?g;<8Rt$?M9YRlf(ff~0bT<|O>*DDh#nxAn==sxIW8F|S}b1+$8 zZ}dVV&+)BZO{pjx9b$-P>;eQn<9ncmP;q-{s{AqXl9|e8@sH;4PrrL#G5vzxmjDv) zN-?t2`tA+vyQY0R)8`EwtFYh;j;E!xMaw+M{GsbxoU9oY!7Sg;Tyzz|A4FM&4Qc0;hh&Bzri7;bTf+MPRmV_Kuz`YFx8vj*SE87vjZ1-rHslqioL#7Y_@dj zx}{!KI-KO%Y`DAhV_IjO@n`O?!bo6_i}p;gsrpf5i1X8<5$V5SyHN}mlUH)X=`=8c zK_-c=_XLG&8;Qn==AHQ@zqOxZ5Y+RzU~!vGF#O~(POsC z0@*8TjaL<$?B|j|+P283p zJXR*XF*H)q()t%M*<@#+dsN}%{-L7k(Qbum!@9mS+r#%c!U?}L{5fVsBaeHqlYo!b zft|rP$kvAEJ` zII(jmY~n0J0D2RlA_7D5(=wQF=7$pB*ZkPNa;r!ub{lG=$!(@5rJTlfYP~7MH{kL3 zm2}+Mnxc^e?8T zC|-Bbc2}b?`XdCRd`wn<&-_A8KYin8(Q}LcsLY@tVfS*=%Qs&qtzyk2BpExU=?<1& z^yjik5G+E4M4ZtBpH0!Wc4MxzLN5toD-oW&3b!QmRE#X2xM}46UNQSu2gNiuJj{bE z(#}&!u)Uj3f7P+EeXU=IAH;0v)nh&O`G5n!QYRi%OoZKE(KS>>!!F=mLtwXp(J{55xH#iy#zviONmQ6&oRai#}Bg^A6I_M{L>=x;SF^X*#iMICb#a^=T!({2R5~25fzx<)m zb!hn~4I3J0ad3xyAW%4Oy-=|6b#^h}0@&7{Rk z1QpY-`Yoa-0Fz(>_|l3JH4a}iCkl)foqpzcs@5+k+2e_Dg|}yZ)V~^+JvI?m?9pc1U?JtI+@1d>s@0;Tm`@-z2!KQWQY7hSde4W?P zgwgdm%Q!xLI(n5)*XQ4BT>fN}^bq~9bdlP599m{n6u|bQne4urcdhG${sDbBuS*p1 zI$~n7B;{e}{eV~PH`@mfG;~uUB>g?Bx7^C}pb-3p;;g8%fb z@4X-|+czwJZqDU7zGuUc2?H3=R?oAXq0O!W954l)CG`hSLYjJ0B9x=Qf~ZhcY}1nK z59As9d@y+vqYx6LaXj=+q^4WSQB0oht02ewL-UKOV(7<`slFJi&(I4k1mOpIchTuf z=lVI-XiK>#bkFhCKG2|X$N7CcE$=3kc&$$2vpeP%F{_bp3vDWCzF8&Qf$*RSRAPyK ze3w21alRrv&-giz?Ec|^WYFO)7s?#-4UDMSU6M{h{2sS1);0a!+74!|?A1!&2K|($ z*1-L0-wfNY_~|>i!H|tu!1DbAf>&8ILl)lii@BLn2Ye{&T`4~^*FZ-Lcm3isjw$}| z;$-hMO}leu;?jqq0P)Uk3)2+=I{}>X99}|WkFg?R`sYWg$HxyJlm^iwW6}g%mu}F54o%(0W2}BQ*dWy{-`j57JB)cc?4d1w z$OX*jzcqjLxTRMU+P{B2I|vDpp_RX2qWQ{8^Ds+g?f|K0@}KvhFZ~? ze$m6O%l()x>0}k0Ttue!7IQ0BcfeYqBVdbpSx58ex~_yTLQ=9i?YkEDTMoq;te|6O zSKK8t1?|&GD4 zq0hLnL};lW^A|9Kc9!N8^S@2P(KZYo;JrE3G>Wx78izu78(+vvA82c`YrhVUAfJyT z=`Z>|x$=Lel}ru?WS9mw7x52^=~`(Mu2`bF9~ztqn}hk0MD=0=NdHh0^a@pKrqh99 zcyY($NO{thR<24pQGqguXo~c!`g50J+ou^)z%iLm;jff}e!3KI4d(HXBiavE(+n5s z8f}kg%eT-WFKO063|Am{en&b1zu}A-yBTGqtbNVvG;Ui z3b~p*i%O=EhU>q(>rC>>FFqA5HUZ|i&Yt&EWYAz9a&Khv=mgYs+U?C}))(*|lKLF_ zo#VK&7vlPP@W?u5=zXdBFvodDcj=^?kxc0kWSK&Yx@+f?bWpn|*)dagMJ9K3`}X>qYv`^H>OS?BW*g@0tcw(be$U}CHy*PF zvty%w7hj!FYl!ZiIAxt;dXf7=E1e~o`S5ZDc--v5&8HC^#YSpK5jBI_L(Sn4&`Nwf z!rz2j79^^>?Kh;7II{D0B707dyPw2O`E4v!;V0XaGeqHLolrOe`W&1)}B6Kn*js8sqc zIX|K$$I(RXuEY(trZbDU_~;h2Y88j4x&Z`4e7It+>`%rD&plCepmpGWgpvMnH{pQnSb%3^D+}e^4#Cl z-c7XBxxvR4)338mkdiJG^VUlqxI1$XhNq$68_umKQGjkYDPmrN=bUVC3@drM*guN) zS^~=%Yj7kCQ^u}sd;-xFiAfho4R_nCdL!zp@cq^Jm**FNttcU$1)pgV;5ah6o6tJ2 zRP`hIPEd#4ALXf?y3X<8*HI=lY^lGk%rQ&&h8s5;_^tzUfIn)$lFlOG8VJC{o%7FM zy`^Q@bNJ*H7|Ol?^vEIN`x|LdYvBAs7Q|NbPS3Ku?|`-DrQ%|JHGl}h(_mQ`w++X+ z3ET%C4)|K1VIx0;2zQ3r@hoz+-Le+ARaHQ}G=!%^ywJh$cA{k$8=}tTIC!Y>D;HQL zzrE8p(G|xvjZjL&q^k%QZIe-d|DU^xUDftM2~IidQzxQ}H0H#B%q9iN6-M~#{J{*% z7PC^wGRm>jFaA2CR+F$DeQB%5|I^^fXT~7M zJ>%`XpPttlwzh+}U-da0*?4HNCD5P&2qxlg9ZB%#cG;e1>MT_d876;D&qWcuD?MWx z$NxqFkU6}jITd`$ySqncDN;}-Tz3W3!1p#Pev%3UKq&c`6`3yKG<1R)k4(Lvo*@Kw+5!QHaG)v!rYut)TTZXp8+lD7xd zqdKavIVu3(`SQ)~Y@S!oox5SlUx^Oc3re2v2fvO*e_i_g^=$d)*N^bM752SVvAs`9 zdu#f8>$ZCvclJI9>}^KxZKdyRm+b8{?|m8E+nwF}`gt$Y9&BJ3y~plz^K|i>(*6(q z{X;R~%VMc3~>m?^W?}tO&bvzZFrzt zrfuWoxNvzP8bgF$Jm}|vV#hwxl^xJ$kg0J9HUOXl0KPgo(p=j?jvIsBHL>h^g1Mm!n zSUubiC>5ZNBT`d*lj_ zKP}IGJr4Ya`v`E5g3id!$B*BG5G??ZjPGl2Cnp`p{0i#hN#OnnL?-=8y1I`Ad}Hh6 z7yvx=iccyj__}fM!=Z-{eGs$VY-dx1w^0wCvVO_{)RIV}_%q{W5;bSRM$Xs8L&7qI_PReB%(KEen9 zgiugD!=EN7yh8W!LI?zK!F3IR0SZ)=OjJeug;Ah%l>Md)!LI`M{=;)y77?8f)z0_R znIwSgf~smeC2(YG#we?EB|;{F8v6(+^B+pOuebF>8WqXaLe%1nv^uYKQ346I$szld?dMr7|j`pLWF9V!&D^*iobAtE`jf^-WLHtZ1z8x4{)4VqM!tU?jU%< z9E8k7n4I|oD?YcALenXc(LuqaNkYuI+C}19EQLU0_`8)v|3x{V#s_gAent%-=+J(s z|JpF)hjU!?-Z~KMCo_v%R(X6A8jR;wez3dsO_-7_Wbj1B^Sj7Mnv`9GcWX~R6(gHk z=%l$|L{z5OHOr+HK?p$0LMKHzXduE7=Za|bNaGs(yp4umojg}nl$fY^)Quc$!)gFI z>p8r26}(zPnzI8}usT|0GA;-G(@czN@C60U)n$mUbQ7sq!@b?#m$oJg4N~Rq{ZZJNsjz!_|LY&c-MI$$w>9_vD(x+`1^(Fk z`d9g2rI*BV;rNyJM`#WQtMF2S!-^B@It_O00%(JVnG(h)2gyf@2-W+@x*$3qJifUlkr-7LFp8_zWdSAcVey2 z`<=ROg~U)Er^^>Qj~2c#3DPn#>($$FLVM$rEpohX$Bvy}a_yj&)HI3%q6eK!#%lGQ zxisgbcNiTknnuUMF|!t~l_L*F`PJuzN`!Y@96ghL&!q)TjzVk0+3MaECCinj5um!Q z8z3t-a^7h!JR#07DC?+dpLqMIUL+l+Tyw%69Z`O#|IAO*h@-{F<_^=7a^D zBhX#Qyi!H?6z1vcQA}(AYoDO2$k^{5YR9fq<&{`^*W^Y5Rbs+wj5L2P!`8i5nDrE6 z4V8_jNlJ+uS$E~QX>zX5IKg>w$v>K!gThsJ@C4j?kbw8(!=!TKGy;{Kw%B3EWyxNwCd9vIdz}=T?MgfyQp)qbk_+uC+ zu^)Cr{z&I1ClXfy5ZoFj6BZXAcXgh{$mkky_ycH&fQYYr@B9T8pKdlm0MmkQL0KJ# zprDMYq}fQKpdCtA)Un{)80rdwc~g4z>$U7yQJ@=HmeBL9(QaKDc@xZ)*C+0E64r$v zi*6_aHK_L3v$iZy|YpvcT?|Z|0R$iOa70j&ds|^ND2DCxy?L+96#* zw2>$%p9>!#h9)BDsslq!Xhj66Q#VfQpQKwS3>o5z#MpPhy1477%^bsq=PLFRwGB`B zPy{s+FZk!>QyK%wD`&s+8`7IQMCBfqkKXv+knuV)H$mh<|KEXc8G~wKSCIh}9qwZH z-}PAGU=E{9K-42mS4`<8^%Kqw6j<00M6)swS?-8Rc)yejRz-mjx;tQ|Icml?=tx?i zKyq_NOykEDCiKrM;Ws3(;^xIV%i92xg%BVLw;-8d1l|6GO6W=!BGfSi#>k)uv2~n$ z(1*7VGY{TZgL_D-)}QEMTVTcx=BcL*3O8fs*g@>c)JRmtBVE=S^B8_hFoY4mLMQDTr6o}arOD4Wf2qn-qzYwtnGGOlE`sPx@&Pme zVlqO5iaF2RGRv*-zW{TffdK}!>Bj!iEq&LypwBv<&t`icPI!g31Q)(6(n4Aq&cE9; zTL7tQ`rSv<@M$7Of7@zdqb|o>*s^Fg-=h;?G9{Q^JRaa>x z@z)YSJh=UdCabO&D9uvs0_9tuPfd1Krl>fZkuG)(KACoxDJ^U5QeNphKhpeX=+6hJx;Sh^h4nB9J>1aid7e4V8V0?=f|q(^*!p#jUR3A zU;k6Ai;&&D${39haJQ|PjVN5N-Tf~(X~ zud4zD|CUdf##_Fm!D8PIh6g?jeFDG?SE-ce&9%sAf&tqrQKSx$hK$;bmSKd8PIecy zm1QG3U<(W?Y3+jF`Gc;YU^<*&&I&ZEWMBK*C;?#V&IKbV6VwER9;8sWeZujkB}yXC zt2_S*mtY|+IukD<#RS!;8(q_=O$3>mk>j{NxhkB-x0XRy(i?-NB}< zyIHe>FAZ3Ph~RX=Rx4hTF%3cj!f^aqS)Y}i3<{}b4nY5f9<}}wb7)?8&qjGI1&dS< ziN%5GQ{Lg3B{TP;Crl}nSVH`bc_=%YV1ap)by1mQr6Z|Dea70Ax7YaRAnz6Zb&sJT ztvj>Q?KVm-)5i)%9n#OXFwC<>}prkKc2)WHNku^!x8XIAE~4Rs_4azFoeZZ9e=bEkk$=Rj+I*i1CO7uBJa=1mQ>AgErWTzN;yH?<+U zynqL>CToRkLtN<2XXGEWXX=SXP)|DI8CvM~%evi7&#=e--65EdjQTgP;0;36fZO-3 zIHCKmQW8DxVaGAKtkJ7iP)|713(N)28Ak=&J61yE3GUYg8sB;(8aa7q1(m)L=F3s3 z)%2kG0)bh};qxzt-8u7I?B7#Cp+6~9YWS@=erVW2qDY~Lem~4Hp$Lno--Z4|V{;^W zsER?%W`z<;{n9XPp+;sz$F-eEZ9WNYlp`JU+=|44pr8nHgq|8o--{Zd6Aw;H$Ytgo{ZG8KYMz*lJ(vJ=Jta9WD20}9**wE)0C1Rk!{3sbHyoZM^VY&0n%Crjf5=E}0yX}bZ>EQ9x zZq%vUNmpL4ughfVWE!uo3Ysjhe_Y4H8kzMXQTv$!X1zB-OO#*!SJew0W|H4z*f3bF zL~_VFn@6t>W8FlakbXL*K>JOs&M|akH|u}T;S$|eJpdI2;LN{z*T!`78v~@fn=7Aj zNCN0cTeOqQ=W*#S$Mo>H5NVh)om_h*!2k=d%Z-aGJe)-9r`Dol_^~ML$7c-A-2FT< z@s^!h7ycE(%Uo{;IGfy?WIH@_1s@kvKPpO~#zMT2?ABmr+>pWj&%awm0HikG48hwA z40>Y-HNo@uGViRf=!z1(ZM9$1!8TgOezDz-kj-PT*804SrDnxKU1H47<$q9T-F`#g z09|U{0w0WZ>5>fy2|~C$HRU>w8q7ki@pg!WFZ~EN{7u6k!5hR__zBFsTl|!B06NX& zSr^6OMS?+1_2zWj1lhIAK4P-Psf@6Q6GN7KEVK$wG?SRBV~lc=h`v)6eP4nUP(})u zAg34Gu(E{5>N=(w5DRU)1h2&Wp?DmmIQ@pEc=WsB@Z&&~<(NB}JC6#D2crmPa)dEc z{NN3&*b~94EoU@<%|U z0O9#jb9veVOsv?2EU~n0LLPeBbv`Ly2`h2VDb)qFb47NjRcuQ3UgVGCM}k{(drv5~ zLY+N&FU%O0`S>`&t!3Jx61?TM0?e#5a5@k(@6y)TxK#(&&Ti(7rfJj@fa)ab&Yo2L zaO9pRp!)`@FhGJ~Qa7>DEgjFb=qw{#2XwV7-&stfQV=nY3(O|eR!fEf9*JVA(6N&< z@zzI9j81y4HiW2)y6-$EUd~D%dZM}+Wc(emHq0`;%lad?b+3t4^-T|6m&rp#yKWvN zI-`bRtkbZqtv(tab;Y;SegHIH27)oYu3P>&b3iZ(3mvl4&rO{rVBR`P#l;qo++R_6;Lyyd;$yYgA2!bx)9EN-K+l-O2k^COL zJO}`Ou)*bmfAnF3=K%CR`;OQ#z&QteRj7XV-2pOJj8GZ{TWc>efk2VNUHWEbT#*10 zD<*>%g!WKLP!_ot>s<)i8%C&HqS>i?$DJfLB$#h~1eL4J=R)G(+pD8L6Y40#*1F;u zQ3MVd(>pf9+HOplT)G9v&p)9AwNW4@1b{$WH2BukDVmxxl|543fW=Q~XwxC>_1;>W z@xC)LKX?Yt?1qg|?ZFon1)+S78A0yeQA^JXPo z>XAf+l>@Lfvb2toUf9Fx&IPDfdxc zRHx|3!254_jAiH=XK&Escns`{BzdlfX0&WA>jbgv97m2J-;l@p1%5cNZ+;X$Ti`Hh z5WNKNacmG1i00_~EcW=jQJOuo-bD$B-N3XQ9hSDk#Yu>M;%5uhcJ*yZVLOK0vFqeG zs3Bmm{6?z-`qV7(YCt!HbGr3S!($sXz)9ddbPm0-j2ixa{Tr6E>T?Vybe-!`U?+?j zMdV&7e~#$Z{vf}fMxE;#e{7O@a!hmRaw%~8>O#s4+sYY@bBUJias4`PoX|<8kVy|+ zqw9_2iUY49fZlBH%`LfwF?_a{EypKMNJGlw_&GHEmZHm;EB1=|xCSbToY z)M`y?37Plmi!;O3sP%+7SmA6Unbi4~s20Q-%W&f4boX7xxM!SE0{M0Qd?P)YI#Om`E%8Z(zc3P)yh|Gm0hY;Lv2+Ps@3n?sz0jMY_`?xtJePD zCjNSqbgt19{BJT%aX}D=)2R(~9R#_8Kx>3DKdQ zdx8fyDGi+Gi{N2YU!|tZXjQbG@7+DDGcdW=#&&~tzr%0Xc)!zUK5qZD*Y>E7jmgR1 z$+}?ECHwU4~*aIp3?|5uT!|Yodj=m|=TIGvfuUf=hfNH!e+S@$7S;0*d{>GszTzgFO3*p_^` zjHf-Tcp6Z@1JlJlab!{sTkCq5nAz+`=4N@YLvEl`;8tOu>7(tt&);Nfmi>?9xBt0g zoFZO(@_kHs|6HbNaN+d7$}|h5&(R({4Ng8gJ*$rZJbJn7Q5~(YX#)e$pYAMm3=Zox zK|7eQYLrvmT2u!_K59yxoU947oQVGy_TI!F>c8*%{>;AEz8H+98v7C<HNrmJkRUC&g;G&_kEw& zzu@s0kMHyIdcEFHrIm94LWWxG7DMb7Y;z_3Frn%527zI3Q$?;=?vub04MnGxbcgQeg0LXo zu%NMw1K%r%*9{HGCBd0q%F<#FYx}ioK4kePR*Jtc+^4C^k!e025C+XRcYXYDB92>z zgi$o4&V68}npR1P+!`?W<3Rq=Ye;>K!?|={NzQ?Mqg&lsq%(_Er4qr7;tFs0jtA+B z0SoLltozAAJt6L`mXIEx^T8z(H!57*&6vhJtI4oy=!#6<)}e&tQosog>9~1-B-QFs zRY}HL2iS1AW&qsll%9ICN=o?8P-uXThi2j9GO5bFj&f)ncf=+O0Fqhp!Grx}i$g=I zd6nxJC$uDg`oP)4N-#Ryv{$DDN|i37-*FdaRmZoJN=l?4%(&Jla-yMgX*h8X~kH$%t@Gle6>lj`wX+^jQ?x zCX3C~BFFfP;R{v9pMiat(n$G8a$UHPDN19BjzPAk+%z4q7 zWJ_3`z6d!(&RMD&ip}ZUvrJ|L!U0nFWuproz-3Hna4qQpWR;UZ@OnMvG(wTVyQm0l zer!kTNTS=SxZR)O{Iko~#PTodFkU`5NrF4P3&L^k-Zh6_QtXYV$gzjGltnHP*>rr( zW+s;nrJ7uH&UZ%2EV#nBOrm2>3r2aA>&=3Tv%S#mN{HxpV3%d}3+BqD zGKr=09@~}<^DP(MAS?vOT~$6@92j|ZN%O7cq1Q0XKJ0qkh7~nqr9~(pj#dMW()Tj_ zg?XweK0IkETn==Ecq%vOt!Lm5>%}9Z0jyiokXI@-m#^p~NftE6-zu4Uo85qn*`KPj zC$nCK_)b!29@M8B=O`Vmf)m4EF~qq6S7daYjD72k zfsHVdWvV|6SN4KoS$84)NG})nm+Y4bW&8t?NR#&EvhhP@}vb} z^XV(MsG@ETq0c-zW>s+EZv!OHq<57mwNQ{U$UzQX95BM*eI2e znb-@bid^(2Qv_tbWGg9jlzOW{3WgKTs_W&9`du4$hTSs~$DjBm(>yA-K!WqG(i{8^ zR$^_Kk|tlQxXg;o(ULIGq&z~8+9(pT^~b_?_jrLCvoJ`t{I&I=Yxi54!Wx~QygBen zcf2@sA)7$EwBZy5sY`kL$Xi2d%Z3=cf?Y85ldg)8JC~VTNc*q+)iHjee7OJA(vIA- zP}P13ENCw#Ghvvgi$Q&t2I}`+^?9jsLUOOnbBa4yRu`U7Yt)SbcP)Z+4}LMCA>#u5s<{di zYebnwNP0wgiEW@CMKa7~XxgXH$Ldpreq9!41~qanO|xJp9?~t;==aKfi5-OYd_>26 zhJlo0seHV!l)c=FRKUdpt9FofLA*qTotQQxg-OtgOgPdTqU|89!e(q&Ae^(0xj&;q z{hFW~jEW9I3mtsC4a%y4 zrnUITHDH@GT|9)7^jfqxOw*QaVY_S-Ns_ys5e`Aq9xM6Qm1r;?dhlhU%~o&177ti# zcqAf+CbmvLF0I9X0t+@ZYrCV|51~^^I?~D}(oV0Wv54th2}n2|iY=iiS4&AdNX8<; z#1$q$GT)w*gja(lIE3TJ!moD-;w?~@@1vC10GpiIR-W~QNJyt(hS3tQOK|40eW%1}{JP?UCXHdR7oC07ZC*s`uI zp+Jw(G7_{PZn*L=PYxDyv&H<;Nwm6j{_+g|<~|erXom5^MoTgl0YjW6o|MUnLzIK5 zhvFT3kz{bvK~&%w0VXmEn|JW*W_W(yR-nSzA1GQFqEon|7h~gS5<0nYSpmwGb&4-4 zoDKGM*R}^snfP#Zu_b4E=LP{tay;LO&w_s2+p^vhCe&FpW(m`mhmtRPYU+q9q!d@^ zlvFvE7%@(0*q{Lo$vHzO1pr^0qB ztx4M;Ku;0Yb~6B3%^$3e)E<>AE_+bC>G^|fBI(dW(T$(N1AQh>-C1`<2z4fcppz}Z zY4;UR<7RR?Z4Y*)oL*Fv@Lh5rC-~~1PJJqt7|#cQj^rD)lFkI3xCY4$cg4&T~RN3oJ~IZC`Mq7@nU50;R)3Kim}3Z$4(!n}p0sCP@}NuY)1J z!ZtAvAuW$=k+kJ^^P6*riO^_oe4sfSx8xgHJ1t?{qZWCF{Gtymru6MDt(4>V;liUZ zL0t9t3~a!y+NrDBWvcq%n!nAH2 z3cFMnShZ5-`$sL^Mo;K`*st%zpP)-X*wr3-4K19keY{?d{ZtdMH8?Jp9+2r&$B1VY ztV#4MSc|dFNCqd#mel2{F;&$nf&AHw-c+&lden!S+7FdZcx01OeVbE5dvrrbNkiX@ zdbj$9{+zQtYYKC>AhB!pz0r-uZk27u`*rEaBVUifgG1lxh~1fj6w({S$vHcg_S;N} zHAgq#j}{M$Rq;=XFbX@%raSKGlmGA3lFE$Lp(Z&5tSZ zR0|wZQ~Y!U>Q>l!BxJXhBEGw>DUAell9b*W1jekMug|f}iG&6p0zB*FWwnOII{UVE zNR9*>@M&r1kDpB~04yT~XHmf=Roqkrk0nZGeYLfPYMD0exI3y`TU>m)Aau95cp|A> zmr}pSkElyCu{#N$O{yTWOSvS?A554UeIs7+ro+czy|H72fD0R<+Fa`FIAMEM@uFYJ?cFDt@F7~9Lq#h)zLccqHW1#em;^JG@6nT z(?MFOA?Y06K6W@@a=#eOj#^hOlBRUz5x?Ll(#Xd_Vx>!--%XSap6hm5x}F${kwL{Y zw@slC6e}Kb^PO*^0wVK3=@ABa#>7dwzWDpJAmXpee_J8??MB4k@fqDh40s z$Hapn7>NIV>I2G6W{EbPMC__UOQZ&nt&&N}D^4h>0&h2;O=Y#u)0NxjpJymP0WUH& zHrg==nsc=;eqsL~Uc7(C{`M7f4)z<}%NN#}r%AYk-+D>;24k0>bT5d?DFBg^vPHqE zY5hf>{fcMxydO-`5`q;5SaEJ696vO2GEI(^DC|2bk@~dG<1|;zWKB6Uw=*Rn##Gm* zs_5q`Mz7TKwNF`UtWy2iK<)WMrEBGDbG42CsTXgtWk9ZBv2{r6&EkbogU!GF&;jNJ z@MfR055pTCZ+gtTyzki40*<>PiJ0Hixri5eefe$ww^C_%5}tnLu~*%DYd z&h`E(^0x32WhuEUu$Q}1nB0R-5(^ab0zt_{p>2&V-rspO_KAt7_=`!U(qqmJDC8BW zRy5QshIj`8(0XIb!$#3gbwP~_!#hmAv`~WF`mY%%{v-@-*txya_s|&FAKaj66Z=%F6zG$b3LuCUzwmv5Ue@e7EWbuAHRm%(#^71 zP+bVn&EBc13=IfjCRQkdc=s9CjiGD?x7q;hvR><1X1uvdtittW_0a4u0X3c%_if~@ z>HYQ|iQ=R1wjHwji_CAjZqLIO^MyIJ(V;7RGRZ{S{AA;Ax1zUL`~dZOOC@ATVCg-b z=qS<`sou2e*ytvD{S1Y;4?-yEb04aOzm^i@LCz_-a6P_Nsetb7$3eiE_85vIK>`kB z$)2M_+B;S%%@*Ftdyx`u#L82FVL47*nWeYh_pnGy0*29e%s-N@hu&a7KE4b293p;9 z!X2aHI}V#pxEJbgRIyapU*#xrGgVk2_d}**nk)BkYQL7*%eXHHApXQ~Uu~@#WwrG1 zhOf2x)4gMvjh4O=HAlCo+sQa;q34Xp7Ey!St=OYQ zKb1VmIk$#RNaQJ>^Q-ATeM{KaSkS4xF-_7hcQ~82P@?!q&UEyl9`FZc2il~}N76<@ zpCXUR%zJL%sW4LFPdWW*$P0z}xXvIrTAvB^m!)8opvNe68R75pRB6n!USmhEtOy zB&W!4f93E%f|yt67=kT7T7I!5E+wZy#>iIDdY3unx`@p{yz|vh7P8;1ij`f@dKh>i z#7UMU+eZ!It;F#c`R5T}9%d-Sb;=5EtKY4zKs&um5Ety`XFT@_L^lOi_WJe6W*!XSb zCWV9jr7swg+ZM5?s1mLk&)Ha&DAJwl0eNRlUn)7T4mymq7F?3ZmEB!@o5p*g=%(qM zdg z;%fmC&S;}NCiwst3JI^!yO#{W9t6PY4)p2S0Kh?hK;-mlWwIF7m14NExi%B`02IT! zgd{l10iP@wH-UDa^%P)?>38&R&;9aSR`Xqf@v$DjvwG;|+W>4FPC|$^x9?GIUc{3g z!QrcH6p4-`lf)!tp3~8)&4KRH&M*;D&gGnAfpf;&pYGjgi2ld}cnI!Kg{QTsD*^sr z2#-i&OJA+0&Mn1XO+kECH9T7SW+~nI`*Y$Q?GtTTg?$3ZTVg3`nDlPg@y#^2&^ko} z0j3wzPPj-zo3O}(s!%*v;`8CSDAdOdM_-w_OhCIY4e!+Z#5&62tadtv54~gXDNqob zrs=KX`z!9%B%w7@sa$UIOk(qqs9VzVATb6KkNhs{7IC!Pl?DaxVa-YJTRtbByOems z1z|{v*`q=E6olEZfWxpcF4ON5Qjn8^OQCmRATc@R5hClI2Jk2O5L~7)&%;ezkCGB3 zR%jm`Zmtzp+V7gY!bTs&P(DxG9D7;e_~0ZO-~nl*(`1&LbCZbho;ycLqxS>nrabHh z$1oruB&$z}Uy|AdaUG-HN0jRi1W3POXaHpLbQ|l4KvL6E+*+fN&N@}V656FLN0`2o zrKB#Mz(wBuqcQD=`!%pW8Onz9L5uFm2iJ`~16mQ5?$w7WV}zaNN8wEmkL!iN6_`g9 zwU{vpME>{Gznr<$j*$l9VUIu8!>|?tVR}?)VP4o;mXvV(S8eh@68%On3cG!Gh zFhRrN7xrs=`%mU2G~Pw-T1lV~6ZNzc^&Jv-4IppcOvw2NjQ^D%+NmSSWg_X|yy$iZ zC8d2%GAYoQT1?WcwS zA#_-lXN*m`Z&RwT;x(U~6evp$k!67Vc-ALb&d=y;8f!pUI>KzgKuU-i@+#D9x<3F4 zg1yRzZJG|aT_7}25R@c*Bvu|8K*RbSAW@oAZM8q1?mayRyY?V(*pSh?vf&LnR=79# z&7b_xt*#+i1^cDf6hpK0L%6Yu-g`F^w4D!3-+`>oulb}f|v7Ie*U=VZn02&=g3d|4*6bfQ0b;hc#pY;)< z2f(9X8*!X(4a5NoQUoAdI&yr*z;ULp00Skgha|JZtv;YCv80WPJ22%KK;H4C5-yqm zSwh(Pl>Fc^uA%|x2nCvZC>;O5+iu!7w)q%V5&#H$RSw!_RN&JB$Rr#@jRPz^N86Y{ zi}TYFK0+zvRzsmbgx{+zT;#_hXA0p|tOKc#^RkcRoWREwGc415%i)3+84Yq!Q#h3T zs`%ARcBBy`U02d9TH2~p+U8i=9#z^=T-w!H+C5p?vs%g)ExV>u*5_E(A5}I`TsGKQ zHZ)l_vRXDOdP>@kqiRKX&@gvzZBS#weNLWwx_W9_^z`#}ozt_9r{|(h&ljJ5U3@Cv zNF;#*(whONhJ6H-Aj^y2;0Qz-76g?53MRBX7B1*)0q;?a?F%~2n{Cb3mc6z6SD{ykc$!=%}k4cWz}S7 zO$KZc%QdhJkp7zWqCIao)qn5YkykeEcZ*=t{ee@FM-~g1Y=;VY{z&ez2n(lbyXb0% z5)SrrR5w2I5#9(dvv`l}HB8_lAv7ojS|13}suvV63}$T0WxR@e?-lwJ9ri&E8pdWj zmk8h~6$t*|J-(1CbGKpi(Y?{oVt+)yx)`CbA0Z3!{nsiuM)$RCkWoD_1c>9t$B!kz zjugU0Mr)6y^S59SO$8+=SET6xL{8OuCL*-K0tI(EfSj@H%}cMI5<2A|bP)}ld|3R! zg_rBaj-x@*=$RXX;+cw2@)8=?+;~}%1#d}5z{>C9#dGoCqBne67|y(SZqi9yf(93d zDqeJni!qrCQ%&#InwG@Qf7Cs{>~#K1^!b&N^J`t_zfW;m9_N90Gkkk9(zzKO(~K=` z#$Rsce$>qStr-$;5!l{BaBdNfX(5)ju*xyk6l@r)XeXoC*cDqe3hbG<#-ip)J71~} zL?oRgv3zpAh9h9LoM&J7s6Bx>#}WIM7be5**VeBZAN?d;d+yeer~O&z&PcI30UrCX z-7QBABYZTtz+?20rGiQ^KWP9}%y(T(w~T1SwYxjFd&acu&Q)iHhn~Ynn0^gOEhtpU z3EC0mEkOycS`*Na&wDsmbgJOecYK}7Hy>Gmra6T@a|l7GX`6Qmy!!%bWiRPcr6wPE zmx(!fHwe-!4rIy@-sCm{7FMdXGx@`&T$8Sd;DTBcBE7S#iA!1-f}P)fxy|`I}hJ3s7e0$HVbI)8%&wOdm>&rchk9yvH>sb=N`f>Z!W#_A3{^zj2yI10I@5b-F zB>zLJBG*KN>tuHDbFd%!Uv*9Wzms?E{VqO^9K026Kn+52ylb5FeLBAL6ni=WQbkh} z33k{Cw6JF_Cw>2ayLat(`d%>bOTNbcx=!#<^0oEQKHh!5lJ){mdi|f|YuDQ;aQwDu znZ-ZkYyKSh+U3@hi%rV54R6~YhrfAyY1(a2zeDPPN#K5yvW!tKt>u!&P9FY8dR&yT zZ$9m><=kP(V07u)9%Vp_$L%VgRsx?!O5b0@&jgVzB=xxfj@#ZJQV{ks%_Acf_i$}} z?yanDVPk_F9#Ht&wtsN;RL(Pwd~Nxce2q%Jt$mpzUt1Te^2O`?EAQGqm9WA6rU9St zI~=tMd*BlBD}CQ?qYhpqXMKh|BeKG$Sd%7|ziey5H~cRtB759*93o01PpnseeQLeV z6FDBwcd+KMw@~0O?^=(>lk9C-4esmufvYczyqZ=y-nFM2E}l+N?HXsE_^qe^XYblS zr0)rBdPAVia?jFbhANW){5Krn-3ZufA8#Fg1#iyAw!uH2c?alQuez&geLdX-kykIN z-PypU!FvDm+aAe-%tuRk5$tk}vO~M|^EQ`Yc)uMrd0_vai^uN4o#QNjQ z2?-?ba_oQXU6a`)&B;MuytFXwLjc0M6RUoc*oRa@PWoOr&?l$+AK`IK&1L z1F><1E%lyQ!fiu}1`~9Q`Vt+_;T@6YmnxgtCK)ai&aM!EYt6=tc{~uK12RXC#LC@GLqpTQyp6udoe>rO3E#sHq6MQ^&06lRlKWgN{ zsgp$ZgHb@LRlqofVKoAQd$w1Mk(V&(uS1k3_KE^5|z3Kv7^a`C|{EEp7^_BA;qZ?G7WeCpu7AvgI zq2%--V$el|u*00nA@VJP0v%&)%f<7>I6=uS=lomF^#@?FH)+(*;hI%Z-xnjm;QVRw zkOdz#;K>sC(_F%$_bG0uxP6ygRqYGpWBaJlpk(bs( zsTY}+a#U_hrml94K*y6IMfHSuzC^8#6FLDNff+7?4kWlhhlfY^)Z-&#TcolCQ-vDD zNrL{Lka{nbKRd&o`*`SxDi_bzYL^5-KN zX3%EQB{l{g$lvTvLu{HLHRH0IeZNc324#=`V^*${cw18UnLZaNUFlOW zYe}~+yQba8xWQ$N04@g1tyR7K+mhAjsxZ2Zwv>1^WT>n^mg%|VCI;q{vxRJULD}J3 z7TK-&f5z}34>p^`40#gWngo|pl1VtP&z_L-N!R!5=W(UiAPe~_z&9Th(u~SV?HL}W5J#)t!#}39396N2LjLl#I{JnaWlrA6yUM57RD~S zX7ObxYDZ-&Y9myIuN1^xb^rn)uJ9RP*lVB6n8$ zxBvXWJkdQXZ@xO{{PSbco$k49cUCt};=%j3-;dBWnS$>2%eCfLUfbVUdvN*Z=jIbv z7QM{BDN9~aJqfW%VwCWB8Vre3i+O7#MIRs80FJOSLKqogjeLjX^dk(dx56W;zw-lI zo;IodxUbJPRRN61z&c+&(;JGNM)1n6e!@kY*=ucG6UI=cU`r-}B2|;`Lo^nN;=xokmB=Vt|GSzaAzf?*sb$NhnGiHFY*6g8|gHLG}>Vj)rAeV55ql zgX{9CI~hp!Spty_dmiRQ1n^L8=&f)nf`R0rg)s++lI%UU9{WqtAgDSWqXv)KmY&au zlcO-WTwzO?jO-a7q124-iHx3=3^p9kS;p^sJZA31k!}yuWgjkVe6A(NQPKu(#Uj z&oz!m$v}n_!!)hqc|^fv4e0BHU@U3xfgwftvV^A_O5%Wj`IBl4vLT(jx5UJ~17EXH}ceuLxcW<%qovIY*9vT*xd2 z%0<1bvqVe&lD^kO zmDCoO)OVINPL?#S{?B0eU7b_oj;9_(oth{VV=k zP;fo8$<%u$iTM8wV8A;j?M59GZ2=yQHM`3iEHDySnd{x$H%j&JyFS#P=SDvABkO6-i`gJGu!QTqkYJ*5 zAK`W%H}%?d1-Fh+#A2SX(B2mx2DWGI`FKl7l!2fsk;eP^H&-feHC7)5&D5O$dOx(| z>*A+>D{AJcBbfcF>kEd4iNc()od z7N;7mC$F$$?N$u}T3z@@QS;lmr-9^`U0*q(W;SNaUq#K*9(w1%M6ce*%So!t`xYi% zd$8a;eCLt7_VP>eje%De@PP7yOUN;V)TAR4^^a{|BOG zi(@&&RLuIy=j$qJd|+R5?@0O|z>rx%IBR%A$;r~`_8^11>E8l_X{Ff1fqt#P5nLeB z4DN4*0s7_H`knDo&lSXl=oHd%Bpdmd!sJ+#Ip;=tB~2*EEO$Lp`VPa}Hmrm_TIx(< z?W|-D-B7=)FArBt=VdPKtwn-(D4a|K zuvHTrb9ij9a86>D1*(SFp9d&T43Y;|+1+b#z$kTw#rYFjBI{!VQ8 z7{O5c@U5~~pJ_YZF`#xzeVA(~@9)5{v95rj6Te&bIU@{h4HErrweh2(sh?UQ$TWmP~>TNi59Ezgy~FTpLA#R2VKa zAi&J#Tav*#Z=!(B4Q>V0T>uf`IWZDxN}kig+H+sjgeK&`ADPC@Cz+f~0})^lq0VSD zB{n%1^Ky7MvDRrANB1uvd#cmKg|0 z;)Ys~Hn7N6j#>TZ+zwU=HwE-{km7PQMhxQL33)=~lNanX=vImI?0~Z}vlKacyrENd zPWtRD<<}F(8bK0wlB$=+Jm4kfR3>`=lWk(UiTAbqLUC<*piE+NX?#MAn#$V+DVjIz zvPQhokU^4=<|(J!3PcAydJNw(>>dchMVc34H8+&`yt^-TOs>7PaCp&k`?pD{FKntH zzMgqEzwBDyXY;y{G1K+7s%Imin0Gh}|HDqCO_8rq%CBt!a4s4xNQZZ$jY7Rj%M{Ly zLUL@_{d(2|^IHIEmSIBfC~pv(kgJzm8i`+GRi!rq@}*<2=sYn%o`>_Rf<%*>;z~R# z2(-V6eIku|QGcDzn5_DkRKTOpy)2ySD{TU8KeX~vNjpKWf|E+bJyyEH+Pdc{1$x!) zaRPTSUTzg~NyGxcpj1=9&rdbV0G&(69)+>++6WpnqPb=R|G?a~gFtN$q|Hw{4U4^jT6jz z`%Gr?eMKq0$w*1gskJXiOWdX7f|BN3y;j!^;*~n$l_%m=SK{TL!;%v%@YQB|d!ZM5 zeTR{OlA4g(OAF15gpXALyM;`r`d}JD*1c8McS1KO_eGLxA^R|B(1U@VfuFs|fb$=^ zZfB?HO~^q?qLNIAUND5V??~0Jtik@`0loy-Kt8-zI0Tt9QN@S-|%Moi4gmtvZqirxAN?d{#RH_ZxQozZY^o-zO0Kvz@VR95-N!p_yJf`RG6^Cru3OujkpkO{fiK8Ihh(91^8!jV=XiO-@z7(p zX03^A->CWcGK2lQw8L=P&_R?Wci|SkRDrMSGI2U;R)Mm98#H~NBIBd?G5uhYUolzw ziX!ewSw@rjW~=!Ybt+qnEN;u#JV4uN*5)ZO{6wb%c1hY`UukVs@Shw&q_>3_TEJ-* z3A_sNh+eHhl%Q%<-gcN|Y=MQp!&(_dv> z(S+PC5%s*XhYG{9Tf$x%8mA-SA4E?2=448cO>$ge{L{t%4+4Y1zXpagA9c=fM9p8K z&a4!lS?fIWee%rD)iXeh1=nREoml8-7Pf?i?_zOxY252z{TVI(&k}It%H^-`r>|$M zZ!+)cUi~zGui?<0zo7+Z3AncMY2EAs>O+de8cJc>*t?J6fR^XxWD)16zp{w*_Fq}V zZ?tf*;t~s=mvn_RKFs_FOF&K~F#7u!E4ldKm(hGJ=Z&Y< z_@5Vp7vXQg^q&@kw*_SMyEZ)uO5jo{3)16~-mCGRM`hLoj{iJGKmZM_Oak{J@A97B zjWZdxSFz&DoC}59GIOp8*q4di;A9aZ{bCW{g>P;=bVGkYz;Y-^Up}wn~nN^#z?L}m(@rYhVJ{;@Yx4KFnLIZNE>dZ|jK z^6{wk8Ei{NT-v=~0N$%|ea`=3kcwK!am2|dM1_Fc@=73Raede>{uP|`TsZtyR$b$T zDb24U21jzXx{ne^o{Glu<*zu=5oGnr%-xTXw=)BzS7Y+6H~P8k5*&{@Zbk1Y+F)b4 zQ#aPD=;wo81pofF>88!Xf%pr5M~i=20v>)~{`uujjevEb?JKvC7v+lNOioH82h5Z#8K6&%7E2-i;E zoL8peP9Wj$Tw1T*u2MeahXmtdx5{po`{^W)SIHszjpkxo>4R#scwjj=hjl$bG28(3 zjPl;7^)uzXuT!)p2bmJnpfab5+H5E2tlOWpEakpsH{56#t0*ZgIcL0!c6Idk__0^r zD1I;?`cvsN_gU?mMk665pUUP<&+0zBH4@(S>C{r@*&VNp?nF<0I{mjSV(rrzz*9@X z7>~w_EwixuYxP71N0W7z%b_dE}KD`cIm=s_kIbW0ZFcP=~r=Z9y zzKDZXa0ZP^az||z2&FSFn^Ee?oVuB+1&mk1ufB1Ng3_{pF*xNvVQ)9I9OoJwn1&0~ zDg$LEY)p5ywcs4^g|T5gJ6L$z`OSI~vkd(DM0xaQPPpP%|^_3@afjtV_QJ;n`iIZ3%YLJpc%EtJmGNx@P{hc@H%H0 zm;W@PLufP52s+fn-H1{(WGtfPn8$?@(F(Lu1%4|;K!0Dl>JNbIQe+B*K4=}k55TA# z|D&k~@C_Yo;raz8K9pY3|M?w4clr=d8SS|4!L-25)1;LtJ~UYvd!#a!;Ww;_!cW6+ z(T{{9ilby!awi{pcFrXPDXbSCLDSQ%?~WA+P)JD|1~eV9bha^)TSo!*Bp%99A(h9| zXpTbd(93wNfUNDP5{P5=CInFL!gG)@wp$-EpaOx25u{n;=t)(7Ck@D31N;%|oDCfQ z9qZKUJ}B?i@G#BtyZ0;BnGf+`KK6U@xxtgCm?FE!*|u1ufcckA0yO zpmGnU^i5yBXJ;u2rqlLtBl+MkeI9SocNbs^OcDYu8Gjq26=w~c(rj`{wA#Me2nk8|g) z^!u#Bx_RfI{Xwe^{zO0JBV)%#Ml~Hz_0Fkn8~p>IkJk=&x*l9QU5lodyy5Qpq=&ZzeeCG#v_rQORi|IYlNgN$ z00TZtg0>A@x#KYQx*Z1K8%!=P;uQUHYxN0cT(b=x@_y(Yl-agD%pUQl>=shc<3V5H zp4?$dq4;f=phHPr8Ry@IlwNindUxU~ybh#ne)9rn+ukN|FxF@LV&p4*2kEx+e@Bbs zgNarwh7F~OURh4?b=!}i28sK;_UuDZlTOMT8145 zBp6%`NwYu+l95^VaWoh_gy|p0ysAbD+wF)iF|7ar0KIAyRj78Fr~fs>(HOv1qrK2UH1VBvOPLF}kalYy`U(~Bz@ zg$}m8_kf3N(!Br8n2!DuPTAWv|R19e227x$h4xOw2}ehxD-5`Wm1aWAa4;+MM$rS zOs_3UukT22oJen4NpB`*v^rSi(?m{^K*A_+GlU!f97j#Q;2;QR`2=IZ5sF9=+Rx5A zsTWIF-g}&P1}#Fh3oIgpV!(Z5q#(`QG<vdhhF zG$A?1%Fl8d{0= zG7`FMD0CbJ0wi zWnc~=T%AFG?!K42 zWTP8x9d+mOt`sBmZ77`dC%F3X=`eS+7UZH?xzW;vy}Nq~GZKoyJ|BtrfRd-YMEknxw>`vPIVil0}4tAq`W#4 zMqSxj9ZRgfLbtxkslFz<{+DF3tG;onzG7gb9Z&mjXRxt5Pfc<TAGK$XN|VM`RvQz`Rp#wZ$1+; z{7?C8{lCO#iZ)`1-i5icwIoR5TCd(G%#FJZRh@adWuf-ov8hefXL9S6!fNdBl=|cF^&k$PJ@9>Vu4AtL zO;h)m*Kf|V(VG{W`-J`e)nx1K#XBv{V~Ly?3DZ7(Ei{1#v`KQF_{T|>cm)|O;GN~2 z4K#IH=Ij^XqWpnW<3%njE-fIjhg-gniyx;TlX;Cxxr!FFf2yCvq<@m6ec=EuQ^x}lG^Lpr&S+L;XP$Qj(YC;!6mcD3H4`aq=b!yc8g zrE6UHw~KeLD`c!((Eno~#ctCx{5_D8QMmq4o%#6vz0LQ7^eoQkTc}O?A5S!X6m(PN z>yfdcfNi!f9-rH08z8aHxc-#B-DAsLhDhMbOsag-%Ja-^?^a$g_o=SV=GzB0_J9et z9=Ec$-|DMP3k|F6QwdFH?mW*j>v~mlDSK?blux@dU?2blo1g z9J@yYMj7tFT>ZB6ZsvC1dsoq`g&%Kk-7SxMz?ISB_}KG(175Ez>B`q0Jb#bli@axV zzIarhk84`2T>tqU*J-}~15BJ)|Ni9RY^|N%)TZX2@|2ICQ|KrS8vIoX`|n*bEw#+d ze~NzoovxUqH+*Q45w$!Osnqbp{^N}J@p`bd0a$egQL6>LE za4EUFrrmbECXi3-S>ciQ(rWH~hOAIk7V}CSur?!X2lS1cl1>lx>FRhYBq0IMzA5^M zFOJNVfcPaf+1DxksW-ETY*5J`F9IWLyjb*ixxabVAd##!goGsH{AZ8uKw~A01*DID zuTt1&G-y@wF~8QdTFL&_pk3F;lg*jc%3emdou)n(bPQFiM%=o6aP4Cuo4babVl?C? z_Ni#Vv_`$~){v*}r{dAf8jZ6?!+WAwB@McI)Pa}qP}fhEPb3B&5Lbu)#AlshTg%@5 zM|@_%t6R<*SlvTwVx=aImLoZpHw+Xl7I=~dM_R(L$W}{62Mh^8SOXY~F5rSh$OvHt zLYcV4c?wC1a}?&Fm~}jDx*AD^gIRz;jT3;rMVb)O?Jk2&Baw=Lu}+s2Ul0rVqf)^~ zHHg8@DZ)wo>cj!SMO%jRKcN_+a$!6{pCyGmlzEPz1?NrJ}Pn&IBuoExD3Nd5A%H^D(W4T-wH{JW8Zpg zH<`Ly@};fzoUOuSoh_iyIG0fzL(NkiOxq+Eb;huer zK9-xGHI7HCd#2&kg-YZqoQ}5|Pb*_!l)!zeq*am}Hxb17r;8!=(#G49Ib#UAS;go{ zp+^oH3XwsOpD4pqnNt9Q&=S;SW*Lws1GTG97v^o+w;vo2C=+&-ot9R(UZLHPreLLRI!;;O~ zDny3o4Yse1F|*sM8d*laV)=*%N0TaEx7F_3|Jtf_ZM@d(V!i$FYrD&9 z_nWgX24U%G)q`Dnp%mbTX54o!y#e19kSY!==&tVx2%<``ZM@TXB_4?o)LSszkn5i4 z^65qo`nHFVGb51CzJmEu3Ay$S1ba>2vPx^Fbn!Uez<-4=9&Dh#o;n1|?w`vUrd&zM zc<28IpJB{6J1y@vb1l{2J3I$kH-2ru^)|xF;M-J^$>SM;`)>|z%RZP$c`$vTjtvRq z!k)x|!O26TSDD(fh{ zWoqQ&rwBdGx7u2UOj3&4Qh`5v0bT%jWm92S=RG; z@uiUtHJtZr*P|crBJW&&`t^ULD|Tp#mxJJ-jSL60ryu(}VLXOGT8uvSbrv6QvGqT6 z#ikzp{34gz=QfZXQ$%A!=<+@9k5s<**{;uvwA}8s;dyu!F^1GH@2kf=hd70IpG6ke zCPeT0p1tghc(KucUH^PEXM{#S|18|_@I$ANmD+fSnZVP#xTT<2Zuh@+E?B>0}%}HBkJkqgtVTil!xBhYNZh zn$%ZY4I@kYG}*=akvkdqK(MQ%R6nP>^DtOXKafgW(l4*q>fIO;>F z=sKinYh*nJv!xy58lzAh1T@11y6uGagz=-GB;puAxcbFfV!#sG)9DErCK1>97$rd=L#AkcY^ml&BdRjSRE* zu%cg#&5k@+jB8vlVW;RJp;m!I|-bAOF~&V6-yGv_XnBKT4Bgc!+1 zwN^0qB+MBF3$afl8@eU69={W&Ca_m9^D_v2D5#O*06ror)a^@CaR#!Y0*a8$&FnBs z97=67E-lB$5@;Jh+(9Qc)(NLsBDs|>6|D`J?ny0Rlr{S2V6_ux5U7V-enYUvy zZ`W!bMKoVeCtu$&-ykaAusGkiGv9PFKfrox!>jx~Ejx9flU9lZ3G0*gw+MEfCl9Wk zq=^=|=@hs-7I;P#co!G=b{6&bU{_PUw zNfcv;5^DX18=Py4s+3SYu5HjGI8Na){a&*?$D+ceFwnff=e*Qa&|25({@0a9GMA#@ z^W?;UP7M{tJL;B+>4w%<{gp@cUsfL0e_MHQxvPWOWEIZJ;}B=%arz0@@0Ew$4gWKW`aSL{4quD^ zvhpzJtUT_;^Zl&;z4Ex5z9o*c@{m9Ek1LNJmtQN7wfU;T|7_)PV{;!jMO^dyY4Lfu z5sdv{?Bz5JY!E-bBU}~vCY7?;@Yw<{(Eem1{C~A~9&SzTf41J~jj|ySs+!Py6Qzg{ ziWqvRBDR2ZP-#k2OdvEHp@Rh@B27d@qzEb?DoPO)6>J9(0UIJJU30e{^?2I+$~<%D zK6B@f$dk1{-*>%hYtZc%c=-M;N2VU1qbAI~uG^CJXkvdP;F~RrY!e*lrN=D_*cp2? z_1{DY%--N!7Mf&YZGVNfp5pcj9N;1q{|egro8<0CyDItRWu@~(g19zF5OGM}AiNad zaeLxjVZU#A92n*XGZLVH@pml`2-@mR0gm*+0LQ3jl4H(rIkE)|x_JVFD_N_(xOmAH zHg%o`%8=VQ;$RBErwoF+cko8_03W(A;V=k8r0UYHjEWzI^n7U&JrLzZXAuB0qM(VX zY*Kb(-$rT{A3zny8gSzB?_^2ReN6S6Sx)dlxHR1-(PMqaCKwe~=#qlowG&3*-hp?C z&~yw2q#ZX8!WcK7tCrpD+Wz%rW$fid4?6E!58^fgC=;24F@*2tUFf8ud-Cn~zb=Q= z1XRq+R2~=;!-X#$l-ESbIK*SKT!6u`wLQul)@XVz-lr5}%0Mydq1YNn@%ZomyyDx%t zJi8Q*Vxn_YI1H=h@{e?t04CQN2%aiE9p;U<9k8#Xr;}Yil+u)i5h`(vJ<4!{X-(=b;Af84(WC6P+aV8!F0I z^K8e>q~?24>?8E=-s~p4zIR+&e*FDlgA0E!1HmfLae8UcgZC$wS=$9-kb79q8`c@ zyyh1d6Kj|?b28C83{H2mM%CMceEvr`4;4~m(-}K~W`M6oq`38bH^=udH(z45S>dJ; z%wYcB%X7--uqqNK9j3-+~ zN3=MtnvG=pE+&fE6&>JaqAU!=9ap}sxlU{ZgKvlN#Iwly!nzBym^pKq<&Gbc8Ovqt z^Y#hOrs{vlE&63Iq^;}Owl`g0SPP<>;`{c>YC|oakl0WZi-Fz20g&RtT0OgDP9Or- ziV}N(PCanb3{%Y0Ww#J~PoKTQpfiQ(U~!FgxCN$A1&d6MFYpW~9gWw~|1Mj|OE9cY zFzQeES+-yq#ir%4t?Svge=A$CNMhpnLs0olm{dD!01cO-*;KCtEpxJ=_ZK%%a1z=&qZC;Zn=M63*(;+g(A&k( ztFU^n{elj%n5$A?S=1eA={Vz3goVP|{S?5+60C|!=xpDc8%2VAb9>mx{VoUnC@|6_ z%mgg~b*3LfEsyWX{hxuhkn1_EWzmT8*TT2fLm>X2jtg_LlfTKd! zCA^vEMvq3^4;VWZHCi@SuzMPkl`+fRu8FwB7eEI6KkXD9F*1oS45T(I8ka&Y2h zFAk^yE6nA%40XI_6$gG!?;O>fPq$~#y#6fwUE=v|c8#hw-A-NI%>Y=5FN2tf9}#I!MQtUd7mvmbwSOCWP8D!_C8)*53Ef$hu zhowU>;5}!Cxwz7ArH6WDMA+BT!#~W=0+H=km(EWnQ~3%(UNWss25L!r?`xwPk+tOl ztzrQEc>coCHWiQGkx7;KbpqbNuPy0srH6~}4u%{!DLqEJVfYYolt);>gIh5G@I5E%+FL8mI4$v{#AAn2r0Dx~<$G%{$SrYQvl?-}E1|oZ`$;5qHB75_Q{j2?w2>dm*8p6%J*!Y; zb*a0qB|?mrBkhd2!%BF^k1~)q)gA~#@L=4EJFVht{6i3u zQPg53N-in7hohIblcJ&|vgR-y#KgC3cI}5d;dBhMTud`fz%nYSHqp8qR#1auQ(uw? z(k)J?+A}Kxg|!oI1x}ym@}KcvD|M9dJdLc*eZC3TdZzkNg*+g;Ez+LA#PU|Mk!1&1 z7-MpRu-XvusZ{E9FDktD)-L0yS&M38?bIw?=uiy05z{&f!jK5y7MP?DFb=Mx=UT*3 zQ@Wh)u-;zBNaEgIUD?^OShlMm-NKb|1uDnfOzF#@biKi**j7-)aiL z!?aj;AYFjS2;Vkq^CNPd$87+z=%IE?Wu!2{QTL=oQyv<)*y0J#MgU{}e+>fr|Pj)_K%+Vf|0;iDKQW$v9ad-J$QO=_%A(y`(=#_reroTR4zer_~LCxR^T zX54^)r<;n&ADiw}RieAZkTCTFn3 z#k5s}0;2Vp_8E4YQbx#Gwh4SNblBl$FmBJwa~oUElCh^;iVl{3vPYuAVgNIZN3W}U zSmc6_`(@Bh%rmhN5A(Bn&1OI;bmS7x051BPktB-r-M;CxU!{b`@*bU-f;#!r~ZJ z@M2H0{fEMD`Pos=I#hF$GBJT|uFwkY4(vP`sDQ5&RpH>>skyo;^$PIcvJCt!MJ@63&%t-z@9Ir_8_K z|G>!9WfNSho^|?DkxJD;13TKQh$&0$>Vn3{kv+0(3`lR0V1rwLJo3!NwJC})CN6N5 zcQ-$-mFE&if69u|T97+|WL*BV?L(UPtGH+cy6N$3xRRzmiF}&28pfl8M*o z1RlyM5=*pP6KUw^*x2UM>tYk17d?iF+?`|H>PHlyiAZvRi)acd2^rQJzx(cvRfCxaz=v z)RO+Y{Hzp_xHFB`5EYM>jLqlZ8#sIe9Dz9w_@Bwo!awEbbLUcZB|zXm z;q?9gZp!EXO@QCM0Lsb$lY&0_Q%t@d>BnWqth*)#Us66U=FN2+Kgs!*V)9o&dx1PXX~j6FD8HLRRe&00g`dc55pDCJC-AR6#Whe$>maSKrf$Q>@W) zvUvWqr}d&7H>A=|8-Sv&PWzxbVDh*l{i6G&)0(C!GV^EGED8jNY(g!o(AtR8d_C#G zZ?aL8C~WRhbw$W?W2n7N@N0UTv`5qScC4KZ@g`#b_&ako3p$Knu7_Lk!$$PFT?z5% z%`K&&!PgF%Y=&kJ%@1jP$5!vnhu|I~^$X6AY`0x--bH7U>oB%^=Z)Sxf~8I>boKF2SF;~O>Z}?$3IfL&mRh`OYNE8H zAI_R815Ue1A3U?44V2~!C4?JpQy)uSv9+bCSX^4w-oZd|BaB?Hbo4mvL?|#z39{?{>^#SauyR3NGl5800fVXmdEmbj@V0(B6+w3O+d zde}%1GKsp1(ol!-%#jmvrCvK#O&165$Je`72y##CG zn3d3K4H~KAUc(DfLTw0Y?=8&ZNXp%jR}X=8dR1NXj%zkWE4MhZB>M-1z2Va;Fb@eC zw{sp`gjhfP-BKr(!1znJ|EX69L;42(qs?c!?W|C(`yQ7p9jWL>X__`$*1s4=ZA8MB z#9^E?0R2okqYVnW+Mr$szxOF&n7M#8qn2#pO`!EGmCPMh0%%_6N-0{f2(QG-2-wx* zUlwctFNI@;ZH|V@`;K_Cu(UyV^!(d>XWwgNo^qt@c4==%%53Feqpn-au$uIHwvd;- z09F03${7!BkzF-V6}IOmnUKzjJT6-!)*zL(sFQci$X8pF(z(TWd46o^b7@N552x?1 zfXMlRnQwr|u51>Z|D-8l#F+ipfXH?mgwnYoTa!`{MYWYjW^8tdm4`l_Ld=XS00V3r zKN(wEUSdY4AehZ+$KDv5f8u1Q$VER|v2)#G156;wHPPf_bHrXl*R!8>&*mSruCaS{ zyUEfOVP>~E%Ss(QZsvAo*GHyvfYdh6BMXnm?dvW+=$hDdI=S*x<+cs0na%A8`mM;O6~@@AXa!#g(>DIg=kb=@QdK47IRTL56l0n`}9Ok!J$_DpxFxq31R z%LY^Fv=S5;F~NX6AT*fWy_OllrX3^OYo)+-jCa0fP+{`!0amM3IA?Y}Sv7wC?ZAWX z>DtCmZ$i=k`VGM%m-U}EYgKs^xo`ur~JK>BcC{N#KC4rU7DaEGtMnNcbSlqXgQZ#(Y6 zc;>Hu`qHw6Np`&$5dEo)7rfsIhOQTTw9D?aX}rfvR+01>)`~Y89J=_({@>#!a1%)zVfd)Obo&15fXHT@ zuNe4X(*9o0G=Js>6oRY;LtIP376X@WI1%oNNx7nwm~IPgs=g&D_+%Em1$H}pU4^^{ zc~*EL(PcnfBvI7$z2g3FGNGtL&NIMgBn%|)FcxCrN@G=YQ&zBomoaucsZTNBBmhh} zSstW4-vrRz(QDF_&bdKscitV5EyLRL%pI2i@XhmTnuKJtg~E)VT+e*EWmIQL0gRTtgNRB{gcmrS5t1779# zPP?BEd~)l;=?7;SSNAQksjV0|?|-*^Q%CKYM|C03ZXL6!t9;TJ_5S6Pj=HnITwx*z zOKt0`hOVX%RX2CmpL=$LBWqJ&+fe8htZ9|W)sI|2t*M7fCCt&$E6L?e}jg4U?_(}VfiA5ONO zA!gU##X+swt2hlV*}QxMpN%7-JMhRo5;bK=-Qw|~ph}PD1*f;Ke^L2L!~M-=)wgah zCJf(Rau!{P=hp^8u3ot~Y$I%=ir>w_kb=qPSI|WH;HzGH%s?EtF8JLw1DrWWr$$Rw z;5wOSv8G)vH&}%NKfVAI>V3mzi5cK6a$Dza-I(vAZ&1!kr4 zGmm4c+4rABJ>r!`dhDLD^Lw(3U>q@+w6M6#j#W$1XO?dNd>T)72Fk^u~uT(SzC zNp)eeRBWMJDjjP7aT8bvs+HZaJ{Bs?Fo%q<69y>coen&<4Gv5)sRwW{Pd6Y>qLisC z<;C)Z59W(eM^U;VFf^IMS0|0F0=TfSFz!()Enm~6RrWrG76>V7G4-)BCsd)$>;V!m z-V?w(7Pgsrj5|`2rQg$$5Io3T5c$@=)iw5!vwkwcxWTVPgumznkfYJ`_+Tj;s{9^fh=H11=o{VL13u%f@B5me?U-GLD0%85o=XRw%sJoX_a5&ptv-Ojr^CF(Th@+^c3=z(ZARMcX0#GbB0{ z0MNpr)`W#*0kIDuF=|}qQyGgKYjvh1QU=3!AmhwBD2YYj5Eu6KYt2?r4NDBV1GW#s z!789it?zCrU&~=cG}B=W2gJS%C(~-%P50a0mHIx&(fM3sgWqx7!7?48Kyc^bh@xf3 z0-XBP>{m*C;8Cu8oQjB7_Pb(XpmyFXB^6dRX1GJ~YMemL=q%ZP2BeagXhg)gN&2n% zBi&t7tk?CzK6d^tSKz{*=2^K*#qG`I6d_^W%RHBs=Eh%v3VuQ`1FgAb+p$92k}@ZPxa zWb#m5)7z|`&K%dbIz2zP2@uaCU=?0IF~yaFL*P4xPYj&=s><{^G6ftcSht7VxQkkpkL_juVNn)weG1n zMT5ytZ$o7khopG3?GBfxa&Iq=uHw!0q+R|{;_&I^2Ht%C?aR}3w?9q9@)iaKuNcnW zaQHlRgts{EaAp3%?a$MVyib#9R~E;93-2?xd7l@4rMuk&1nD7&`n~9=z5k00{F}(_ ze=9PO6EK?ZUtIQ|oi+cT?@4?D5^b5PAMYWyvA!V#kSvjNkFk7p(17Dr<_}ro#c#62 z@RI?0>!Zeamm+?NQ{;~tWV9Z0&6C)%reh9@Q~wyb zT^szX81ZdGv-zeu>B5^ z@_57-)u+sJfP{ycaMKda-nnj0h%lXT$Oifq&2Ls$h}Qs{1%kwZUC{DR zJJoZ^!4#p{bs0)451dp{W5F3*G(h$wFRKSE-sfwY*|+6)j})UhAtotW9}rU&fIVyy zCdRoFsxUBu6rqD;qi~8h6{Zf`N80@E7J6lhm%#22L|j8N3NF-d?)LoN+4zsUHy$XG zmQ95N7MiktgDiYGBi(Nb06hKSKpPWTgts^gsk-I9nhm|u_K_j8A=v-Pr8yU%S(wiD zxQmq)RxdA<_1)43BNz=99FeCin8nHn<}t`hG?*d3j^qBCoSOIVEToWdY&@@xuU6J0 zQNmYMG!Pi9t=}XdaK`N3pvoBTYzSKE!2Uwn$(#m-LYTY5U_ztW0}J)7r1SKcClg7& z0#8?@H+aGOCx6~I`(2!Rnt+IUXG7Kpny(;P3Cw3826(^Dq!6I0X*eE&a3pbP!%qKj zFF)Y@tQiT%0Jm6w7OQKocVXfH5FjSFzKfRZ0g+^15Sy*-rb~aEFy4F?jq^K@504Ll zQvqc37oFjW)shmFp)6DVRPF#fm|S33dCN4?z=j!0RJ9=Z#2y6aB|u@L8ov zd@sw@tXNI84iR=G&mA2Wk$Nc?7DHtsPmNUm5>d&U$!#)4!nB-vR}z4*0!H~Mye;h_kh>$@PjMKb z-9W{%P-%iAc+^l)$F{pnI0z}K9bq*%vm2J9QDcp`7WoxZeP*&x^h);pUS{(9ICbRH zYk!BvhriuI?Yc+J8y1p0v}cb$`Eyy$BqQ1@o;jNiRowtBLtwlo>i(<*C7QjHBL!#G z3Xk0M%x8{x0%%#iW@OnYwMA7>$gA)v-2bwox@Pkz2Bnvc5J*aaje02wS~0$k2tkugk==-Fni8hooC9?e8q3EcM)M#YVd0A zVL`A&$BSTS^~~Cuzb&F0zCL`i&ViGyFyi*4FG7QklApA?UE+^Tcb>`>xtK3wOc#fTWW3toVu`Gi6sL7_dFBzJA^1xG+-RzeL6xO2kPX_9QM z1nLRI=^0U-(j7>;&q{GgQnQf>O;U&(X#S6p+r-VYi45^1Fa0EM_axt_B>%jm!1|=% z{-o`*Ng?9NVNp>l^^%o^Lhzp6pgd?WE387@0SqSWQW7rdWAe#6gK$_w?Oug5>oo2(@++~5y)*76^L-=%+1h5r>b>zz;>3Q@CXrftlRUYdR+u%bolafBlD zdJphzoOy~$R-&!9up-0_rLpSkC;zMBok zVs{A4KP*fu*!4o^V_mjMu~d1?E1#Je!`J8T7EHgc9jjcJXo6JXC$_XLK=Y(xI~L!y z|H0?CZpWvO{eEY^`25m_@oTYt=rd1G9+|9P3XpB*t`1F1hvFKw?#R6Y7-|bwt+aa{ zw;$8&QT*z}W10*@PCN{^I5@oP$U<**V*)z@{PT!KpUEs zpiiD;kj0RPc(y%BEQ=7fh(R;V@+38ZQK3I}+AW@uB7_XIq~RoP^7D>8i;o|HVT>wL zFqwZ)h5vN~hPH+NnwtH3QM_SX>F65QbQggtJe`9QwoiII1Pb2#4F`}=%2Chw4{-o% zEs~kyZh#7U4cwY55(HG}fT=YX@x{5|MsJ};-~g=cpv(;;1%OIL+NzD@63KADnvMb% zg#kE6LBo^WiEb)F!dv30S#unM3pc0ei{~!H9{A$9qiy-&x$`eU>GbgIlbf8$i;IeY zK9_}YIe{OvNJ%iFvyyZ^921?SV$`(g{H5W?)rR~~Ps{3Ak98=L7yQ=tHY{;l;f*Mj zElZ>C0|o0poK*Sd^Ai|PL`aO-liF!H-9$iiu-V~F11mR%c}l`mg`REbly)og_khPuKo4g0Sk;cm%U>-i>MlsYYgUTeAU<; zjkGF>(#)z--J-A_a@W;U_k0{z-+xTEPQ3R`+(+|xBH(mI&Yy*`-2filTvRRRc~2f= zdklI9CMJtxmm=XQlGrH4ZF$JVM(3ne(iRdxd&uTwuY*F7exi8g!u^>ah9tgC{GQKA zULt6PqYCK21(il9Vgv1KHp9~sD@J5BDIvz!)BR8WH1P{v6o06~eeET%lu-Tf{M8Z1 zmzPTLfB@Q6iQ(NzE4GXa1GGfhYDYY)%}k`rAFWvoV{Y%CGk*>=8wmW_7eR7Bv>geU zpWQ`CR06zIDB#Ck7gdQD0R#Scq|YuGfafGo9|LeNIOCpO3lPFm1<^z#GI@1zDG~ly znCXmpiYmj%#0FL}L;=Zu;50d;FFfM{{ADLIE@7UT0%st=6&D;=O40?}mhVyOV%kVO zd~+xeDA*UILO;2u`Et6 z?>KwDbfQmXM3>=oGHZJQF@}2M0smC__U`k1ysp{0Q_wut@%JStzgZ_aj)A9{RH+%(=PhY_!Sz?Qs0e~4O6f6|PHhy!e}D4m>?*faHd z(@o?fB0Q=>Nk+DabU~U#2F>JTDEnr0hcCf5TLWl9)8=+jfScMSd*hOL!y>g`6OYbA zYHc?TU(quA4F~x7qPU`|io$99`y5ffw09jeQ`A5q_&L*3%IP z)BED8YeK`9O~N#M!ofV3m&J~Q=ulE~1Stfz7-947zN1s5!xXdu>+bNz+tIQGSThEG zsEOcD3^$yGEo5z9I_a#O=c4_9O&3pe(ob}8PYjC>^+bgtPUyR!=$o(xs--T3clJb? zq_v?g8SWAXi_?HA$=2VcH^P)IDwb z*9aW7PstS~$lQKSB-G0_?1LQ9?^LMENA^NL*pdNGTda3m0bVKMP}0L8MnGhR4`EKI zAz8$Wo(w->BK5U(woiwpFhCN|{wrU^v3~{!h$az9*{k1axy%urqq994vNsO=SNS5O US^xw8{3Gl0j~V1ciG9`o0dpO;u>b%7 literal 0 HcmV?d00001 diff --git a/tutorials/files/blender_procedural_datasets/demo_blender_woodland.gif b/tutorials/files/blender_procedural_datasets/demo_blender_woodland.gif new file mode 100644 index 0000000000000000000000000000000000000000..ce48e6daa95a7518559cb69f09c24dbad14d7f91 GIT binary patch literal 756691 zcmeEt`9Boi_y6o>#@M&PU<}4s8~e`K*J_llvae&SA&EjW#!ebbwq(s3nxqKz8kB5F z6p}O~OG%Ryt-ihgj_>C@?s?q%!};l)$Mf8K&Us#YM>|8K05%u{+5>0-4gg3LLRe5( z7|kytgAx@M6U8CKBqYT}#KpxV#HF<*a3W}NNwlN_T3Q8-=SQo;B_*UJCFP{h0#cG_ zDM@K51zl-LDQOH^8Y6>|!eB6R7@UZVw5$w9Nk&ydMh`BFk(0%n%1H~#Nu%YYF>*3k zIe83LTTEV7{(s_Xi<6PS$;#qn6>(T;92SeiD&XXCIC(`JUIeFNuON$4l*KB_;uYl- zm1O0VC;R!l;RVihRtg?cNvJydAAERt4M8K>3ZyhpMA*iSj z)K!iJsYLm!ViZ*gYN|R;swPfqcqui!vYLvzx}C3vnx=-ni>4$-Qx&hNhSoH4(lj}7 zNP~Dt7k$WHjHs$X)YKyCC=#vZw23;}x+dD@&N@=cI{IdM+S+W0~;Ab17kxobwiT3q191C7iB{?X=99gJUNiS2MQ@*|!LqD>S-$@5Q z3N1jvEWpP)(9|XNN`w4LUGt3i!eX?upo!9P)EvHzwoe#2z85yQ??Ny zP7z_wQ4y4=({a&J_R&$tPDhC&Z?02(bVjh>j1?3$74pP8PWnQ=PH*FP^O z>2glU<=p&&E4f8^l;Wb8(vq_BV(PWquPU!qRhPuo)zsHDbTs9i>Ac<9n-SV~zwgn| z=+xBIn>R~aTid^W{`vF!?>{;Cb0B}fd&Ji5xV0tOR$G$@1_A&8`5zD{4rK}|I8{2_u6vw|)`?ggxn2L{3f4LY zYv1!!%{k@ zk+}ZR%x6{Cyv_{Li|*c>yX8NWBjbFp?bRL1OsmiMz4q7L)OTaoo#)i%di`&$G~6`U zdh>t==9P8nVJ#13iChxvc^Nu!ZDe)SdTs4vwdI=T=yLDfuXP^RP1Ix$_jYa0G#>|V z_bbofuGMy%uT7kLjx)R!{$zIO!qKP>&l7L?Wv}gjexr4MZ|SL_QS=h^*OXmhi5%K}$3CDo?*00AK_T z4I)nA(Bb%IPAW=&gToNCBP^%EE9fr9n`L!}rMfk=9phLO@RQ8k7eM=rc3S=A?0d@| znbF}cE7uH)MmFR$7Po`?%HQFC`F^0rXS?rF&lmp6x2r)U)9Ur(f}Q~ z0vmXqX zkMX;&6rO4B&09N2Q_G&`nD0}U-#(>s+Rjdze%?C!jC7zLH)SIb9rxTpu03wr<(jmU{9oI>dy~IDdwfI)^n~n&+u=7~ z+_pE#VOM^AHC!09a$M#TW@kicT%M<4_YL^yc;4>?IzN3_>f1J zSEZ7uL7NzY*VE5x_^n4AJ5Jsj!Qt2%*Tmg4hO7ChZF&CZPsa~^T8Zi&#Hw@db?~cF zB}ynf9S5R3`GU#YRvQqj-2MIoql(A z!I|xZwmq&37A);2v+EBtbBR^+rZIK`hifs(1!T>fa;2EF8S=K4j^5~FxEZX0Q`Ao4 zMTa3-P08yf*~)y$+{+4AOY@Hvt25cCMq;MpL?DQaczjAuwz|;VUTda&c^Pfdc>hW~ zMT;+*IV6W1fE7Q@6v|+~lPQ;cYEtpFa>J#`cy4quzW3{OZeEk=y5rHaQeUg~Cz}3l zWgkp7anDwU(t^!iXWKeu4OD~mnjk-l$>+wjL&sk<*(f_b&pEl9J)YMrdA@*u;PO|M zSfaHw{0om|*{*<`Eydb%Y`Ua(w}E)M#U;#Xrea~Y(eP=DB(r5Yqfs92G}S`>pSPsG zH9H(`Jr>>yQG!^aEMHO*x|+;%roPlid$oFWs~$DJpvULOr{?uUb+)tcTU+R1wUcwL zv-di`wV%GM=Dn^u*E{{KBmSwH?_TR%SHzWD)N@0AzmQ&oQukO{W^I8Y54T5njxWsie!t7Q+#VI?{CeSF z;rqRwr|qZDkH22}`MsOX*Fnv6UR;sd>lr!R5nDRGxTfC?no8e>HcG$w;6wsTF-bg% zY#&5$O)rPBkKrJahs{*A-8F3gQDeF)rpFdzLnVcGfZ&xO5*`%iDB?2W(u`*ZI< z06&Yy?p4uP8kFYWfCYJdx?hj%4zhs!u{DeOn zKqT$7(vN!wh}3vJBIe)Dv%sYCDAxeqKJJJ&nWFRUCxB)5V_@3ccR1-EBMwJ83rixS}Eip6}W zkWP7a^a6F`h+Hqqofsp8@_|0X)xyaHM(a2yU2i|}xo6flv3}A=)v2GecOKsD2#SvM z`So*-ow6%DM%{D~7}RHY-R&Hwri%vOe<(&``O0s z_xh8nNL{=(~1qo%{!0^gs0PWkogE#PhUb)F;KRO#Ow z_|cw0iAipT31&F~|D~>g&CtukK}|=zh4dfB*xF+sqWl4AVD)9&=0MT*1G2qInqkhd zeR?ag)LJ^BCQK`85mIl6ZF3p`AD0;5Rmu8%(ZZLb``Q5HOMW~Wc6Y}+FHrbZ-u>?# z+^szi8jml>QjJ@{3z;&2w1*D11qsrxoH+p&^Rq_c$mx2I0DY(U2T)_AvptdQ1$c>1#_*g||u2Ru)9D%wOsU#ae8);7Z%sB!qi2AlqarL%aF!cGiCvp%dn@ z4-W;3vIJqK{>!N3t{~BrtP3wfG&6A&EL8s}9W$bpqrbI6!*lN+NVw2^WYe%9dGar= z(nN}^p*d(u%>1{W|968(4ziwXtJd~1=fbKrI+q2DWF7`PxCaV?++coC0Ph}6;0K2` z$OL%sKvx00hq`&=JYm$*5I9%0l?-vmqUy0cgWUL&9)La~-vSwWHViZbOUT8d=EFc_ zDowgMY?2J+5aF#%UbAkP3=NXY;@y-04>0_O|3;rOLnk+B-6a*~^%0jUO z!DrW_E=d3fiEsotMn^Di5)X5rCC`Rk^5iNlP4V9+A{MX$3xc#)#fT&hPdWB1Pft2k z0$5HH_&|iWQw4Gbfu`a>GL!$^Jd#CLoS8xjkE9RupsHPS$C-#vEZDavK_D!umBW|9 zK~1uFS7}D$92AF&;w$IR<@&m1{PQ((p$1uC2p5pdo}4lsWT7yx6svkJY}Oz*i3rrD z@gR|Jh6;uL2$?&d6ng-;wDkla=NUic9#8TFnkJr?@duUH03+F81eT5v1g9_oIG#&k zWf|^lr3L@9ZBM`rY#s+@L=hI&PKG!TDP$I;JM=6(;k*M8;rk@>^p6s%WNEBXY2rra zO&+KUfcFYHWP-|xaCZPNZ9hxsKCGRCVhG|EIDD+sTn-C@Hlo&)@h*|9%ZbQb z690W>j`p4;x%9AZW^!Vp4p->vlX$@w%oKpyl0Uwcoy5QbVr%$j zI4IAl(t9m@zU=g<_)Ff$kee)C`)Q=O5iOF)_yhcXOa%5?8P(^&PwwH@COq4Du$}>vv^%T^S3fPtf z$;I-#Y&PpKM5NTz#WF7^5fKbQP^=(WrG_tsd$lbKl0rtl*}Gb1m#LVM(FKEkV)4fM zE15vl7@V>hvcOLs-X%e1{%9TD1JaiXi4`oVv@Z=bZVW!z7i<^MaWDOZCK&(tbQduC&p{U9stY$y?KA^b|z{_Rd&_0-h)wJZq5-Tpf zLO$vg_(c^k3Ih$&j036A)h3_}oZs3jw}Hv4I+#4j<^hqB)Ow_dn~f0;ruZRr1i{}h zQhT4M#;D1O#PZB+me0OQ7bAjqu&8g$q#~@qI2P~)3LQ5tYbV0Tr^QSIl8K1+ zkEUGca=6yz)Ym1jp5CwqtxPrk+{3_Q^JO?$yY@8;Sk$C{taTsC`Ck^i&$4qamm#Jt z5s~Q5*v%} zE|#Z($XCxodHPpAIdS>k2NXI;qwnYC6gJO00?z=_FSeVuN8;Zh3b>Kt&X>Q^4MVu&fkb-<8R<*zFl8dvFJ1{`BHs7?yPMkKwA;Qld~IGZ z7T{bT85ubhVV=;W@e#^k^K23YS~<|wDYajv2!lR2&nnMc8DfWXC)OblL57sG+wP2a zN%aq476)Wa6F*g4b*(t7vCij7is@^nBzi!i$q)pVBE^9|6$h!1fnCELq0-f2^GLI1 zz9K;Kw0-g`-EI|bE#C*@SV2&g7}%71HZ3zmyCw`J2#%b}yJ8SP>j}e?6(wkKRmRPc z8I=Ororo4>hdiwn-tyA1+6V1tbsye*93lbmn{p3fmxg&~`GhDZ&CWhJMR}62_#~t+ zxRPF^gvI_?QLcLeOr>HjhN#H%s=bQ0t7`Flnn?ZLppdQQ2e`dQsD z(7bfc8sZ=FLBBm9zt*7gf<97gz>sG=f*fxy2_%mKoHwC5fUC}TRj0oqFd z{%)1JaMS0nR-x{me$FkufcP#U`}_Wlz(1x*KQTaf&9khwqVp2dv1}e2o-1z=Q$v}6 zKbWa22dMGu;#sET2v7eKXEqOu+!tg-F?j%=Ve-=ADc-#oZ4xIY7GE6s^Mc$?^`s=6 zafoa`4=pc!N@l(Ee)IB_8O5J(wo!jJ*k?90dA1P-Eols|2$k+ANhJFRnqpzJvZp=g z6T4s$z7OV-p1zc}52ww~rM`JNlo380AEjHH=qm`0-WuM=TuMp`8T3rrbss5Ceq~?k z7ri+DLp?nYA9;^=fkuebR*wuRpSf)}b-m|RQr4@EKMO3G*PUjsyL?{XOMdOA9CW$+ zb^n{!5+&3uQ=iW-9~bXzw}Cg_Jd*`nb^fQ zZ$Jm_Z#XhbD`rcpK1*wdXW-YTK0H|3db70sXNfEG79kV6^I&Pw?9wmjtM6i$p1*(d z_s?5^EC*!Hf#kng@R^2GagYx=s3i{nUyh*cvatEGsPD3P%JSd#CG^8(%+fN(H(pkA z3XYvoNLj+CtPp&cn&O}Sxff$r z3IZixx}LFi6PA_K7?JsXwt6irYqljzf8%rtg*qQ@x&1Nh$EurbCLO=k+c^JNmeTP( ztYU9#sw(l9bL744u#gkbvapY>c~MV7rE4xGR=HEId%!A7=1SwY%Q6ych5=9jG?qw% zP}V}oG@||U?lCH&?^zW?MB=Fr^=o0GYBzceEoU6hpY?GiC#|H`R~M-33=M#%C_shRSFA95AZ*nB{NBZrV$ z4!aw!z_VU^WJ5mJe+%n2lem}FubG5}^a7NHJOXS>$BqTCp3fFwfvs`{1DbRZOAlJ~>xEuMY zk-W;)JXv}-_|RkPTeru;ro`5UuUkmmp)kwT-1+ryZ9{j@zKbOJ3B9vt$!$CTQSa4m z&ikf6@i^hO(}Vu6`VOr(`brUwk_4|>)XGrqTS^fa*$NL?5?r;PvDERBO+V#lD~&Dc$S&esa#t-x>D&er|g(w+g5f=wqtxbBu7-3 z5Oi7ZgN`LSVP}A+I%&kQmLT?8Ft%2EjG{1-k&$-HLF0kikvxs`8$09jZ@(cq(Ziyyd}!O7 z4ERcFG2K?C;YFLHh`Z?Y9aZLPL)g;u_3Nc16%`S$4~|XOFUF4s7kVrd*k7{^6r%{I z#_P2eyRHiE*oLvSqD1{9PBb44DGj-IBCI-H|77@84TXZRoq&)R=kGy-g`?S8`LHWn`BLj+#^0&*l3r7q!4dgATG})%nBT6r> z4TP=KVT)YyE?sM_;|tii-<^kUcB(~Ak#d)@NxRRL@WPcB5ssjbIdLM{jh3$gl(S3ED<$ z$ohF(T2e_ZD%%lNIbKzvt;o|M|H!4Co1wExh8Ckz4;L^N%Nn+rhf zt)Z>T$sAx*T)p_)=G&&eS|Ir;8pP_ZK#Fc*!DoQ243WZ;*sPb;PlYOckrzmu0L!)} zxZ+C!`h3zhJjuOcrr%u!UQ658+Ia_$by>r&2N~`sl8ADN68*OCw92uLu zBJ+#=#AGL?<2*UlDSDpX9}9wN87hfHA0*_}^-F*iANj-ns9H&GF^s~Z1jLunX$X%Z zP(;-hS%$>chS6ytRG=hW@Pzrd`$tnET)>JZCrF1q4ja)J0xHxuSPvcW4UJ`0=(S|)PIiAPgAWx8_3{n~w_LWAoW3iNTrAH+yY0n;nl(C=enxVM zW~;{0g7XW|m*#DY_8Tf(7B}J^pRmeG1Lpcv-Z{$xWPWM`_3$@j zG?uek(n8PGuY1#DCcSLdadSqBR31!9nWbyJcJ|~60i{nQfe#)OtOdmyTuymRh|mGE z;z>q~K3OAUgPdlF08t@5{a~8eR6Kd^NL?QRbo_aJ?J*i7zBSe9_kh(jxlA+s@Y80gb`l&1Tj3yK0JB{rLj9UUn)Y4U4v`fs*$HKbQ8Xp#&o8 z#oE2>Qii4SocCF!Ceb4hpzg`2M8B|#MIEQMiQfV-C5X7;)@tG>RzBw zD<{}&&GpKK5pXfY@!#M`9+f&zCGzR^0I`#e4vr91D^l>cWY)Is(-YC#otfkr+ z_K5U3;@Sg;$1Y*2Hn3@RE0g0j$VZauGW8s+K*i68)J{tAr>Q5Vf;D{RE`fr+G~1ZP z6VN+Ye+dSGWLD}*OZmPq_XE;QO7|(|YhnwmGQmcoCn1BH%AIkRpDzUzrr>c9v>aJ%?s=bkU}}oiD_D4l^&L| z?L8pV5xVe!u$U!!6Y%8Xz2lX;3HnhE8V#-mK2^I+uB@p-3i%RJE} zr1tdnT>su$cXx-7t{RxDps0Hn&KR+QQ%^02d(Znj=aAGIEnUPPJ31KhIrlex@vA>l zf5xvDbMoMIt@PW&E{oT@4W@q@*U+eZWi!K<%uGIocMVB~)ZDy!?~zabYt?UMBIqD@ zExuUVfkGeu1mxt)fSpf?)?y3f_|>Ypi^%dy%sAJ&>@*@>kW#;psca7tJvxz5o(@dl z>+JTb;x{h?*sNmhrBV6}pXT}u{26c0oR562sY8LWG>f*lC^xCdnix)*4%H#kmYNaY z(-Kz(u_%N6ddCRofUC#SAl%eA3WLZfUxSv#srL@W;x@1-dWb+y<8QE6=>GH*C=1jpfHEit|5&+le zEi}RXyGFZr{iXE-tdWY%5A$aLY!3M5ab&rWDp9S$Y)D`7B#7TBlNj9V-2+M+gT$Yd z(kcTs(WR2e{Iyv1apTtdI9P_Rj#G20VCMbXWQX=tD z^XJXfs;>nVchH1!%=M{^aCS?plzpgoM$8Ys`ZAz-)+416V=W>uHbCiA3!iLOb(9Em z$S^OQ3cK{8LK|Lv)cx*gyEn`XKI0kguHoM%suB(c0RcBq$0=51gbcuM94ikz22>0)q;xD7U;N7G9ZdSEi7Q!=e1{oGQ{W^&bSlAy&P zO^JIL>U!)q*fMy)qOFd!Y@g{Pn@M<;%Eo~#pnFehV{KVdIq>c;{3Wfs-8Y^d?0|yC z)6isekx?;(*r6yb58D73-5C1&LfNE$h_*mfbO2tSfi0GeF!fuzqom zRRB(>j(z?j`*Mtlrc~?084piD=7o^56tH<2{TZ?28;4<|E;#B%27MAZL;?4nVBiw2 zL0p-wLP+d|{LdR!=5VGqu_bzy|AiM=5iqUkQmOKVq5Vqr9ak9hMc8PH-)O^XyBUNH z0ckap&omcq3Nkj)g~}QNW9Z9q8)NZhJO`M|eR^5+8}nE^wNi;7I8Mx29-T_aqdQ_V zWm;U~7oYFdV7`4(k0$0}>DTorP!TWiOBU)g{mIu_Aulr2ot!OwAGFpfAhXN>H5Vag zGA>dElN~b6-Gsy>M`z}thXiH(ydhW9phnGOkDg2U1#7a$p+Y}|Jzn;>5IbGC42f&R zGEAjqS*zc`q21bByp^o+6Zz{ZH8bxRek$25PTD8_6b`nyzjkCxjiCa{(j2)jz01<( zg)_WqQ0jGei`s`|nU}|2X0vPV@(Ti*SsHENIW>UiA*PTh18UyfYRjZs&O@)NgNz~= zt*V~x9Prv0)O!Mo+|fGH2RMK+8KYmpk|)v{fnHbh=)Lb4ULk#!HT742%eM;C1lct8 z8SUmDB#&mW5TrAY0d<)^Tr!>cT`P~cSRgnGS#BF}2OYU;GxlD0q5jhyeInQqebvWU z*Ken!IKeBh73^xHdwlsw8h6qK{Os6>yZRyzl}N`q02csF+5`~sg+aDd`b+i*%Mm{T+KF>qm6padQv-2C8Q$JAhf6S|5 z5PbWzE76rc4+47*-rn`Wxl5V*^WSWKvuG{3RED~C#%mimbd^rA0lc$Jj z4TCd68Lzy`=H4(R=>>naON6wTF7-(Lr%U3A?nUe#_Ay7y4+#uC^-I?Xj?U9OFc{CG zn>-asBQt77eYkMG0glL2LhU}_@~dy7UxZK#Z}|0V`MLA0D0%-+00A#4%|itOqZKw8 z_59|ES0pNYuyw-jq}12R{%?G8#v{e==+b>g{M27$#$_#qx2ATGXpUL*zHd2whiRaZ zI&a=U;K<#+(weu$nZ8AV4#} zj<`lYa1^8==b^GS06sPV0Z6+-n@omhmo_sh)UMTO4|~y}Qn29b8gM_OJPxYF75gNx zyujA*$c=NW_W9xsd}+}!3)Yb!TdYGfx6PJ{@Tm(XGa*XkEDVXZKxuOMnqT*UFoTn& z3WEupnqNqDj(?f%V(HJrGzJOavi#ondx%Xoy%4yVzG(&0gE#cPziD{q$X2Dtzdr5A zJ#^}oDxg4kiu|Y-M`^xQjTZ6%ckC^6eW$FJieE>6kc_np+aTue8?MK8NJqsBoGn>T zY+M&A2|F#Gr}BI~S)bpCaD7@b?NU5u)lBBBUDXPq@{-5Kdk%jU+VsYVe@SA<0ikB& z85)~GhG%<;XVegH^gCL7aWq(_2o{R)_HNXj6DQoRIr@!qb+`~`l@o2_6mt@kbL5fg z)N6YLPy|k|THCCGMO1&^tcFD-UZ-D&MTlTO)M`dx9D%psADT-dZg_mC+AdyuNfU?D zh35fQyo1N-ulk*{E1q5rC=79aZ0oap)kg?N0QS@8#r)G(?>Bx7RROC3(oL2cO0n6F zG9Rx}v!mz;G9YbR{r$;&d6-Zh+KG9+jFPitmk4Vrx)0JIfK;0|b2=!P<*mu@ThCyh zp3R10TKFgP$LnfR1C~m!6F85n)<@$DXeInKS>qADwH3bTXZpTtBcBeIzJGeV9qpwb zy>1xB+1^^Q-CkXbeiypE2K)43YHOopd$aNMQ+)Jl{PqX0)QJv?V)N!F*k>;PnP>5+ zgM4_#PcmP1SJ#?;jEWbOA5lG9_?}T;iA|&~#=dOXRQJ7g5hI zVn<^%IUtn{5c+c}`U*(M4{qcD*5LxxXFEgi zj7XMI(^uo}uO?5vn$CSSTmM>}{05qnZ?e~6Sq-r=*tN3Xwf5Y#3EQYB!?rT#yy%oay{&0_XI$__t>nA+DFsO;(+I zml1Wc`c1~>r-tTj-@R{sJm38#J_jg&4>b55WdA+b^LvO~d`@HPn13n`o{IT)TBAF@ z&+FXNrPEOY-%sy-Kf|*}mDr2<{LLmW{)t15s=%4g|H7yVQnLr)nCHDhLHOoWQNt~a zUb%iVXqlL!M}AwhOt)gDM`1Ifn9vhg$f37%S+dVdv$F^E6+T&bs<9V@*N~}1O%>xX zw8r1Cs=KOs z??(;K&svEK)&KpdsLpUCW$jU^9&dj9GpH~9+0yj0wfpDICqLWfezvdw5fh}}M&xK1Y=rQdg?qc;}&p8VCS{o=sm zUn}Lm_;RcId44x;c;7#hq>`DWaw+M_tzRoKN$e}XC+2=XUH?6~_xl;opDBqy&#%Nv zGUbJ0i%Ll+O7Uh!ULwuk&IHJlQpvtL~Jc)^0A%Lu)aoDj_`qAZGY15Tj7($!qqbwo& z7O9Xgb&rnKYoG4Vim6x47ER|<5070?)bkzAa;-mhxFciIWx6f=D}J)l`25b+=2zvZ z3NaJmmtHUGp5Jh=e;n5s%>?jC8I#+c&JASFf$a_#?C0QPPY&emVDDQ|nN4O0a(m^k$iP$C4KoQc0$s&upbwhyTjQydptsofB5PYBj85ifa83 z?QFVq_zfpKL$^i9rd&PHAMX|s9D*-O2zJFE7&_{Vq9d{frZIuuT8`xC-XHkNn6c~` z#kYUf-&~hnIbr8=)K>4RJ3W*orjSRTvh?x}3CcIRm{5?*tI}2Q8t1OwX{VAq!g5e6 zdPGwZ9&FYg5pK_NO;fF}poOD+f4ZJfiB|7SYr1ebG!=3Ep1zd&{o+Cfrkpb6i4RQE zb?_T6zCA)n5d}K8rM+@rps19wHwm3P#8E6E@rz(*dtR)qTK!*`bnu0iKFz*Qy}va3 zzl@n2dhl)G;-QB>KJ*>>@6XR)huFaXt_`6UHyul(wHCr<6YwrN&oq6f(rtwDMy#%2 zugxp)3R*bia8Iu2@YIBI9;xxS6cCmBy^9*$xZ_~f*L+q$#5RtZZ@$_!jWqnxR=_x~GiylJeVZ0^ zMCU1aCeP?SWyXa$sJJt!leqq8(!@D*+R1DW?t4^i;)qo~C-vglowsxW-+e-P!kr1t zK|}B)PVtrQVZ8cftzoAKZ~4skXDd>SKeTkef>ph^AOZG0T4XS$o8lzaTq7k~VJj{X zRg>zKr(TgO5zriBb+yqN+Vn6k|^#)ekDAZstgo=Ln38`O8=IwS@`A!Yw6d=lUIqACrtI zP~m&Z8OOM{oZGz^s1`^eR}E z;U(bH$j#Ub9+EvZVl{)&M~1~k#yEJv3}NzlK5YYf#i!ErwYB)lTLNQQwDQb4f20zD z&R;-IgEj*g0;17C+m8dn!ODF*i$U4tWjuyQZ1OvjFJty8jKPUe;qK&m$)%|b(&8{* zIO>t)AoEdyaJHf&!Ak6Y505!6QNUfj4!1dCulVJ*VGbJ?v)^OCe5@hoR``wM6*ouA zF8DVZH3y@}4&yFv%Hszorg!4nZswvZJG1VV`3v4vVZi1BZ)PuN^E5QexSh`IYYpar z(gPpCjhS@5U6Sh>7ABO%;XxPIisA_`vHk;K^Q}5~IfntuyPB%Tb`dj0Uqzo>h8}Oh zK>}&%n0{tESYuE!Fv|tm%F2**10vhGLuZaL|0@Wf!m0|uu&V~0znAZzJV&rwC-1-x zLAv;~vV8CTCSJbe%dP7fO_Oudg1dWv_GW3xy9BAuluvgx>i?M&iEXuF+~pz-6`tV~ zVO7x~b;#RlpvPHL))#|=Ajh#*LM|-SG~b}4UDpRihwi-lBLNZ|TKUud+cweO&jl<( z1Vq$p(+FM%Rzh(EkXxcZ9T7r+yU|*u1WG^_H>{;Mz3c**HT1aMce0xfPt3jp>pP!Q zt}MXqb*F1bgKQKqXTgPUmTE^79@HZmsEf)LMyga7YxF9q4X<|g%7w)<5~-1ovFzKZ zGbCY5JJ)XQG%nB56eJQ-F(lT{R`+_**)wdWd6b(a8Qo>YzlzmVU$~8OZv%?YpdXR! zih1#(b||LNORZ?0=8$9Q5N{PXkT#&-N{b>~ z-t^yS|j}kh1lhUS#o;i z=zCKO|1`r#LUKLg@;pUYu4ZS&d)q8|5f`ljqZ7j+nnyw6tgLCAU@;b#WhorTf{3SZ zkBgC;#l!_uXLc^IBo`C-&RTx3AGPFynOduw{b77R~V zP!w!m|FY}Pd#wi|UB%H=ooDM^871U^&;F+ezoXgvDkhWQ!DCw{pXcyr5>TbU!*n53&u5ccpML6&BEg6Qvr?| zR`1WY#ewj|e`)*mm;O?fKq5>MRCVK0;OC}!G1{|2*NGpAZw?x&pUV&Ymj6e+WS=-8 zbFr)X-x=5{cTt^=(Dj(tJE@z%@Y1l>aXYDNIMg72tnqfLB30_m`@!;naoe&Jja^nv z?Imx|A(pNV&K2jX$S<`&wUo{q5M$e{y2=WP%ah@+yD39bf(Iwn46mGO9&~eeQe)Lj zn)(FYSgLNT+D|7*?*sV(IfxOq0AN7WKUEGumov2zBM&I-TMCSjzCN}M22}S=E%(hY z_j<|2&m-dmC1Vogu&_ETe;|A08MYWG=SBjl14VV~6wCt^rkyT`zEC(8sANU|^`KBG z!%{4+PC2$tIirqXTt_IWQ>h62{pIbi$JOUo-~N7pQy;EVw;K5UJWxX)Cp?Aw?OHR) zejDgwr4B9BFJ|ZgMi(o=!2z>xOc^+{A(N7P%v4u5i#=#k0YsY=lX;WGVana{f`~0z5qUDm5N8u5D7pz zb#2l}@eFVHyeGtLC7APAEfDv3gpRr4s@@17^4nnbh78-R7xTczSzxm=upZ%&w#}e& zWsTws%lmo4#R9Af3mSMyHDJ(&YOGwnN@Jbo`?nHAX&c?5jLF zQbuy>P(0qN=wcrDTdPiC7{K=)OkJ@yPq0S04TuTW;4iEQyA8zhH$2x1Q^v2WXe*ub zXgXIID3oW_RbXurY~}VLPn9xsPRvsAf~Dk?pgF}_a(?Asu3dY9N?J=zva{A*wbI?N z(!^M&tbvlgTVeqqnm!P#Ybi&Z!eI!h{|dQ((-0{F;|S=|U{l&`UeZsxQR@IYZ9v*( zP|Kw`Glh_q(VUe}$S!Hlt|H_#Ze*>c{tHwto|5Y^E&Qnj;0EYk&UY&wz*1P zr^=HC(Ubx7{(z}h>y2U6w#nAES=IKX*7h~kj_uZt@2a={w%&q$Z2#NZARgHu^|4`T zNb^Orc#hw-BZE?l{QeVc{*A}{TQt6T0J4@`c)A*ubQ84!?MeOEn-qCJBl61S$o{gM zeXNgtJ&`E3TL0t$Z(pmL%d5!$I5&&7)gDZc9Qoa#L_o2b+&DFrt>0 z@&i)v3Ld*tk~V_EOm~TGkkjoA&*ZCel&F#76UD0_BNx!=%c;Xv<#McvEan(tMP=e- z7>dR)U1bCoTE}FJz33`1=2+KMkc_v6-rTi%r59B{#;{OqpZ;!b@q5UE7;V92%=~3c zdqlt30bA@cURr6)#kbF;e46uUpU-JG$E3=TK#DGd7#dA5X}~N`V{y2BaZ=;WZ2Oxf zjit5rrEQJ33(>|9(w$?raM5AZBVW5^K<_K|-JFlzW5a!QH!)+m{Z^VXooXmHyZ@eA z?}v}~;}101E*CFYrjlf{ki|wt49o(IpUnX<^Gk>w~s&dY^#YKDoyCw5W)J>?((tHE_cf;D;Ez0uS zj5Y;a8ZamKO+*x7T^o}6uglNFpK8!X*D0p!Ll*pE?a}j*h-K$gt3jo<7n(qu&kQordB(kPkx_Bn+9m5a)+ksAojJITqhrBL6yz|05T^$Fg98Ik1lXZv=Oj$h!*% zq`r`k-5pSB+ehx8?K@mYT8QTM!)=k{UpBP2-)Gb!9Tqn_Bm4N|#AnprPXhQiZuVCI zY`3=qerNPG(0Kb#_l-bBuHEM80R*>gclXlzS~O1uXGlbzUd{N3>H)}s-=fF0J{aVI(}kD= zueXWj>vzmQ>sajR%y)d{IiL#ioc5-$kN<3rOc)T$vP64Z^0RDf2BF;P+cr&X;ZwY4 zGj9GTcEvb!jo z9jBXd@*hQ->_ecvtPKi~Y%Dy@+gd-Y!Mz}lM2!is{`!Pd7AjIi9p5DiOz z2cLN+Sf!(N5G~x7^)bZ z(hCDvQLnfik{ZgOR>tG8ekzip`MdBNG2qX+aK9h@~rv+Va6IEe)c^#h8$Bhg#{DsO=B8-Swj^R1GyZjGyD$03sj zjJ$_bMXijy>6;mr$az5KI)MMTr4Ezr6RyVKt>zOwXyOy3BUb+(L+2UQ)Y3-bob*oU zflxv(QUW4P#DuOOMx_ZT2~Ct15H)a7)9DZd5v&0$sEDD6h=`#I$ko^o6*Uz3P*H;w zuZ1sb&A+qO`ElmVns?s4_cNSSDi>Ev)t-~#=Ro{annNM2xPXfaySzoct!lG~Tz{Ou2BOPu>)?_d_w8Kny!Ae1=uq}Um}&(eT`G0k`6$$gXJKsOGCFzhVSC(fY`*G zWi`J6C*5v+y7};5koAlK#93Q&_kMFRfX?Tt zrvVR7yZsaAHN49!PqSyD|3LnyC*-fz3?&s$l)1+C>vZ|LN&0p2eN7f_IBW4R)Lb