From 4ece520ba87e1a813fb6d5dc680c01dbb94873af Mon Sep 17 00:00:00 2001 From: Carl Delsey <carl.r.delsey@intel.com> Date: Fri, 22 Nov 2019 14:03:12 -0800 Subject: [PATCH] Fix parallel replanning in the behavior tree (alternate implementation) (#1371) * Adding the PipelineSequence node * Rewrite tree to take advantage of the new node. * Add image generator * Adding documentation * Clarifying documentation on PipelineSequence --- nav2_behavior_tree/CMakeLists.txt | 3 + nav2_behavior_tree/README.md | 11 +- .../plugins/control/pipeline_sequence.cpp | 124 ++++++++++++++ .../params/nav2_multirobot_params_1.yaml | 1 + .../params/nav2_multirobot_params_2.yaml | 1 + nav2_bringup/bringup/params/nav2_params.yaml | 1 + nav2_bt_navigator/README.md | 32 ++-- .../behavior_trees/navigate_w_replanning.xml | 11 +- .../navigate_w_replanning_and_recovery.xml | 15 +- nav2_bt_navigator/doc/legend.png | Bin 0 -> 7285 bytes nav2_bt_navigator/doc/parallel_w_recovery.png | Bin 67499 -> 90147 bytes nav2_bt_navigator/doc/simple_parallel.png | Bin 20032 -> 26255 bytes tools/bt2img.py | 157 ++++++++++++++++++ tools/update_bt_diagrams.bash | 11 ++ 14 files changed, 335 insertions(+), 32 deletions(-) create mode 100644 nav2_behavior_tree/plugins/control/pipeline_sequence.cpp create mode 100644 nav2_bt_navigator/doc/legend.png create mode 100755 tools/bt2img.py create mode 100755 tools/update_bt_diagrams.bash diff --git a/nav2_behavior_tree/CMakeLists.txt b/nav2_behavior_tree/CMakeLists.txt index 0bc932ec..972fa43a 100644 --- a/nav2_behavior_tree/CMakeLists.txt +++ b/nav2_behavior_tree/CMakeLists.txt @@ -92,6 +92,9 @@ list(APPEND plugin_libs nav2_navigate_to_pose_action_bt_node) add_library(nav2_random_crawl_action_bt_node SHARED plugins/action/random_crawl_action.cpp) list(APPEND plugin_libs nav2_random_crawl_action_bt_node) +add_library(nav2_pipeline_sequence_bt_node SHARED plugins/control/pipeline_sequence.cpp) +list(APPEND plugin_libs nav2_pipeline_sequence_bt_node) + foreach(bt_plugin ${plugin_libs}) ament_target_dependencies(${bt_plugin} ${dependencies}) target_compile_definitions(${bt_plugin} PRIVATE BT_PLUGIN_EXPORT) diff --git a/nav2_behavior_tree/README.md b/nav2_behavior_tree/README.md index ac9db1f0..2d7e3971 100644 --- a/nav2_behavior_tree/README.md +++ b/nav2_behavior_tree/README.md @@ -2,10 +2,10 @@ The nav2_behavior_tree module provides: * A C++ template class for integrating ROS2 actions into Behavior Trees, -* Navigation-specific behavior tree nodes, and -* a generic BehaviorTreeEngine class that simplifies the integration of BT processing into ROS2 nodes. +* Navigation-specific behavior tree nodes, and +* a generic BehaviorTreeEngine class that simplifies the integration of BT processing into ROS2 nodes. -This module is used by the nav2_bt_navigator to implement a ROS2 node that executes navigation Behavior Trees. The nav2_behavior_tree module uses the [Behavior-Tree.CPP library](https://github.com/BehaviorTree/BehaviorTree.CPP) for the core Behavior Tree processing. +This module is used by the nav2_bt_navigator to implement a ROS2 node that executes navigation Behavior Trees. The nav2_behavior_tree module uses the [Behavior-Tree.CPP library](https://github.com/BehaviorTree/BehaviorTree.CPP) for the core Behavior Tree processing. ## The bt_action_node Template and the Behavior Tree Engine @@ -58,14 +58,14 @@ The BehaviorTree engine has a run method that accepts an XML description of a BT ``` See the code in the [BT Navigator](../nav2_bt_navigator/src/bt_navigator.cpp) for an example usage of the BehaviorTreeEngine. - + ## Navigation-Specific Behavior Tree Nodes The nav2_behavior_tree package provides several navigation-specific nodes that are pre-registered and can be included in Behavior Trees. | BT Node | Type | Description | |----------|:-------------|------| -| Backup | Action | Invokes the BackUp ROS2 action server, which causes the robot to back up to a specific pose. This is used in nav2 Behavior Trees as a recovery behavior. The nav2_recoveries module implements the BackUp action server. | +| Backup | Action | Invokes the BackUp ROS2 action server, which causes the robot to back up to a specific pose. This is used in nav2 Behavior Trees as a recovery behavior. The nav2_recoveries module implements the BackUp action server. | | ComputePathToPose | Action | Invokes the ComputePathToPose ROS2 action server, which is implemented by the nav2_planner module. | | FollowPath | Action |Invokes the FollowPath ROS2 action server, which is implemented by the controller plugin modules loaded. | | GoalReached | Condition | Checks the distance to the goal, if the distance to goal is less than the pre-defined threshold, the tree returns SUCCESS, otherwise it returns FAILURE. | @@ -75,5 +75,6 @@ The nav2_behavior_tree package provides several navigation-specific nodes that a | RandomCrawl | Action | This BT action invokes the RandomCrawl ROS2 action server, which is implemented by the nav2_experimental/nav2_rl/nav2_turtlebot3_rl experimental module. The RandomCrawl action server will direct the robot to randomly navigate its environment without hitting any obstacles. | | RecoveryNode | Control | The RecoveryNode is a control flow node with two children. It returns SUCCESS if and only if the first child returns SUCCESS. The second child will be executed only if the first child returns FAILURE. If the second child SUCCEEDS, then the first child will be executed again. The user can specify how many times the recovery actions should be taken before returning FAILURE. In nav2, the RecoveryNode is included in Behavior Trees to implement recovery actions upon failures. | Spin | Action | Invokes the Spin ROS2 action server, which is implemented by the nav2_recoveries module. This action is using in nav2 Behavior Trees as a recovery behavior. | +| PipelineSequence | Control | Ticks the first child till it succeeds, then ticks the first and second children till the second one succeeds. It then ticks the first, second, and third children until the third succeeds, and so on, and so on. If at any time a child returns RUNNING, that doesn't change the behavior. If at any time a child returns FAILURE, that stops all children and returns FAILURE overall.| For more information about the behavior tree nodes that are available in the default BehaviorTreeCPP library, see documentation here: https://www.behaviortree.dev/bt_basics/ diff --git a/nav2_behavior_tree/plugins/control/pipeline_sequence.cpp b/nav2_behavior_tree/plugins/control/pipeline_sequence.cpp new file mode 100644 index 00000000..7c7dcf70 --- /dev/null +++ b/nav2_behavior_tree/plugins/control/pipeline_sequence.cpp @@ -0,0 +1,124 @@ +// Copyright (c) 2019 Intel Corporation +// +// 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 <stdexcept> +#include <sstream> +#include <string> +#include "behaviortree_cpp_v3/control_node.h" +#include "behaviortree_cpp_v3/bt_factory.h" + +namespace nav2_behavior_tree +{ + +/** @brief Type of sequence node that re-ticks previous children when a child returns running + * + * Type of Control Node | Child Returns Failure | Child Returns Running + * --------------------------------------------------------------------- + * PipelineSequence | Restart | Tick All Previous Again + * + * Tick All Previous Again means every node up till this one will be reticked. Even + * if a previous node returns Running, the next node will be reticked. + * + * As an example, let's say this node has 3 children: A, B and C. At the start, + * they are all IDLE. + * | A | B | C | + * -------------------------------- + * | IDLE | IDLE | IDLE | + * | RUNNING | IDLE | IDLE | - at first A gets ticked. Assume it returns RUNNING + * - PipelineSequence returns RUNNING and no other nodes are ticked. + * | SUCCESS | RUNNING | IDLE | - This time A returns SUCCESS so B gets ticked as well + * - PipelineSequence returns RUNNING and C is not ticked yet + * | RUNNING | SUCCESS | RUNNING | - A gets ticked and returns RUNNING, but since it had previously + * - returned SUCCESS, PipelineSequence continues on and ticks B. + * - Since B also returns SUCCESS, C gets ticked this time as well. + * | RUNNING | SUCCESS | SUCCESS | - A is still RUNNING, and B returns SUCCESS again. This time C + * - returned SUCCESS, ending the sequence. PipelineSequence + * - returns SUCCESS and halts A. + * + * If any children at any time had returned FAILURE. PipelineSequence would have returned FAILURE + * and halted all children, ending the sequence. + * + * Usage in XML: <PipelineSequence> + */ +class PipelineSequence : public BT::ControlNode +{ +public: + explicit PipelineSequence(const std::string & name); + PipelineSequence(const std::string & name, const BT::NodeConfiguration & config); + void halt() override; + static BT::PortsList providedPorts() {return {};} + +protected: + BT::NodeStatus tick() override; + std::size_t last_child_ticked_ = 0; +}; + +PipelineSequence::PipelineSequence(const std::string & name) +: BT::ControlNode(name, {}) +{ +} + +PipelineSequence::PipelineSequence( + const std::string & name, + const BT::NodeConfiguration & config) +: BT::ControlNode(name, config) +{ +} + +BT::NodeStatus PipelineSequence::tick() +{ + for (std::size_t i = 0; i < children_nodes_.size(); ++i) { + auto status = children_nodes_[i]->executeTick(); + switch (status) { + case BT::NodeStatus::FAILURE: + haltChildren(0); + last_child_ticked_ = 0; // reset + return status; + break; + case BT::NodeStatus::SUCCESS: + // do nothing and continue on to the next child. If it is the last child + // we'll exit the loop and hit the wrap-up code at the end of the method. + break; + case BT::NodeStatus::RUNNING: + if (i >= last_child_ticked_) { + last_child_ticked_ = i; + return status; + } + // else do nothing and continue on to the next child + break; + default: + std::stringstream error_msg; + error_msg << "Invalid node status. Received status " << status << + "from child " << children_nodes_[i]->name(); + throw std::runtime_error(error_msg.str()); + break; + } + } + // Wrap up. + haltChildren(0); + last_child_ticked_ = 0; // reset + return BT::NodeStatus::SUCCESS; +} + +void PipelineSequence::halt() +{ + BT::ControlNode::halt(); +} + +} // namespace nav2_behavior_tree + +BT_REGISTER_NODES(factory) +{ + factory.registerNodeType<nav2_behavior_tree::PipelineSequence>("PipelineSequence"); +} diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml index 458b1aa1..a90b2224 100644 --- a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml +++ b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml @@ -63,6 +63,7 @@ bt_navigator: - nav2_reinitialize_global_localization_service_bt_node - nav2_rate_controller_bt_node - nav2_recovery_node_bt_node + - nav2_pipeline_sequence_bt_node bt_navigator_rclcpp_node: ros__parameters: diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml index 9a45958d..f366129f 100644 --- a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml +++ b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml @@ -63,6 +63,7 @@ bt_navigator: - nav2_reinitialize_global_localization_service_bt_node - nav2_rate_controller_bt_node - nav2_recovery_node_bt_node + - nav2_pipeline_sequence_bt_node bt_navigator_rclcpp_node: ros__parameters: diff --git a/nav2_bringup/bringup/params/nav2_params.yaml b/nav2_bringup/bringup/params/nav2_params.yaml index f3a336b9..094c3db9 100644 --- a/nav2_bringup/bringup/params/nav2_params.yaml +++ b/nav2_bringup/bringup/params/nav2_params.yaml @@ -63,6 +63,7 @@ bt_navigator: - nav2_reinitialize_global_localization_service_bt_node - nav2_rate_controller_bt_node - nav2_recovery_node_bt_node + - nav2_pipeline_sequence_bt_node bt_navigator_rclcpp_node: ros__parameters: diff --git a/nav2_bt_navigator/README.md b/nav2_bt_navigator/README.md index 4c4e0c20..8f9d0533 100644 --- a/nav2_bt_navigator/README.md +++ b/nav2_bt_navigator/README.md @@ -46,7 +46,21 @@ The BT Navigator package has two sample XML-based descriptions of BTs. These tr </root> ``` -Navigate with replanning is composed of the following custom decorator, condition and action nodes: +Navigate with replanning is composed of the following custom decorator, condition, +contro and action nodes: + +#### Control Nodes +* PipelineSequence: This is a variant of a Sequence Node. When this node is ticked, +it will tick the first child till it succeeds. Then it will tick the first two +children till the second one succeeds. Then it will tick the first three till the +third succeeds and so on, till there are no more children. This will return RUNNING, +till the last child succeeds, at which time it also returns SUCCESS. If any child +returns FAILURE, all nodes are halted and this node returns FAILURE. +* Recovery: This is a control flow type node with two children. It returns success if and only if the first child returns success. The second child will be executed only if the first child returns failure. The second child is responsible for recovery actions such as re-initializing system or other recovery behaviors. If the recovery behaviors are succeeded, then the first child will be executed again. The user can specify how many times the recovery actions should be taken before returning failure. The figure below depicts a simple recovery node. + +<img src="./doc/recovery_node.png" title="" width="40%" align="middle"> +<br/> + #### Decorator Nodes * RateController: A custom control flow node, which throttles down the tick rate. This custom node has only one child and its tick rate is defined with a pre-defined frequency that the user can set. This node returns RUNNING when it is not ticking its child. Currently, in the navigation, the `RateController` is used to tick the `ComputePathToPose` and `GoalReached` node at 1 Hz. @@ -57,7 +71,6 @@ Navigate with replanning is composed of the following custom decorator, conditio #### Action Nodes * ComputePathToPose: When this node is ticked, the goal will be placed on the blackboard which will be shared to the Behavior tree. The bt action node would then utilizes the action server to send a request to the global planner to recompute the global path. Once the global path is recomputed, the result will be sent back via action server and then the updated path will be placed on the blackboard. The `planner` parameter will tell the planning server which of the loaded planning plugins to utilize, in case of desiring different parameters, planners, or behaviors. The name of the planner should correspond with the high level task it accomplishes and align with the `planner_ids` name given to it in the planner server. If no planner name is provided, it will use the only planner in the planner server when only one is available. - The graphical version of this Behavior Tree: <img src="./doc/simple_parallel.png" title="" width="65%" align="middle"> @@ -65,17 +78,9 @@ The graphical version of this Behavior Tree: The navigate with replanning BT first ticks the `RateController` node which specifies how frequently the `GoalReached` and `ComputePathToPose` should be invoked. Then the `GoalReached` nodes check the distance to the goal to determine if the `ComputePathToPose` should be ticked or not. The `ComputePathToPose` gets the incoming goal pose from the blackboard, computes the path and puts the result back on the blackboard, where `FollowPath` picks it up. Each time a new path is computed, the blackboard gets updated and then `FollowPath` picks up the new goal to compute a control effort for. `controller_id` will specify the type of control effort you'd like to compute such as `FollowPath` `FollowPathSlow` `FollowPathExactly`, etc. -### Recovery Node -In this section, the recovery node is being introduced to the navigation package. - -Recovery node is a control flow type node with two children. It returns success if and only if the first child returns success. The second child will be executed only if the first child returns failure. The second child is responsible for recovery actions such as re-initializing system or other recovery behaviors. If the recovery behaviors are succeeded, then the first child will be executed again. The user can specify how many times the recovery actions should be taken before returning failure. The figure below depicts a simple recovery node. - -<img src="./doc/recovery_node.png" title="" width="40%" align="middle"> -<br/> - ### Navigate with replanning and simple recovery actions -With the recovery node, simple recoverable navigation with replanning can be implemented by utilizing the [navigate_w_replanning.xml](behavior_trees/navigate_w_replanning.xml) and a sequence of recovery actions. Our custom behavior actions for recovery are: `clearEntirelyCostmapServiceRequest` for both global and local costmaps and `spin`. A graphical version of this simple recoverable Behavior Tree is depicted in the figure below. +With the recovery node, simple recoverable navigation with replanning can be implemented by utilizing the [navigate_w_replanning.xml](behavior_trees/navigate_w_replanning.xml) and a sequence of recovery actions. Our custom behavior actions for recovery are: `clearEntirelyCostmapServiceRequest` for both global and local costmaps and `spin`. A graphical version of this simple recoverable Behavior Tree is depicted in the figure below. <img src="./doc/parallel_w_recovery.png" title="" width="95%" align="middle"> <br/> @@ -92,3 +97,8 @@ Scope-based failure handling: Utilizing Behavior Trees with a recovery node allo ## Open Issues * **Schema definition and XML document validation** - Currently, there is no dynamic validation of incoming XML. The Behavior-Tree.CPP library is using tinyxml2, which doesn't have a validator. Instead, we can create a schema for the Mission Planning-level XML and use build-time validation of the XML input to ensure that it is well-formed and valid. + +## Legend +Legend for the behavior tree diagrams: + + diff --git a/nav2_bt_navigator/behavior_trees/navigate_w_replanning.xml b/nav2_bt_navigator/behavior_trees/navigate_w_replanning.xml index b0767dfe..33c2c411 100644 --- a/nav2_bt_navigator/behavior_trees/navigate_w_replanning.xml +++ b/nav2_bt_navigator/behavior_trees/navigate_w_replanning.xml @@ -4,14 +4,11 @@ <root main_tree_to_execute="MainTree"> <BehaviorTree ID="MainTree"> - <Sequence name="root"> + <PipelineSequence name="NavigateWithReplanning"> <RateController hz="1.0"> - <Fallback> - <GoalReached/> - <ComputePathToPose goal="{goal}" planner_id="GridBased"/> - </Fallback> + <ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased"/> </RateController> - <FollowPath path="{path}" controller_id="FollowPath"/> - </Sequence> + <FollowPath path="{path}" controller_id="FollowPath"/> + </PipelineSequence> </BehaviorTree> </root> diff --git a/nav2_bt_navigator/behavior_trees/navigate_w_replanning_and_recovery.xml b/nav2_bt_navigator/behavior_trees/navigate_w_replanning_and_recovery.xml index a646c61f..28aee8b7 100644 --- a/nav2_bt_navigator/behavior_trees/navigate_w_replanning_and_recovery.xml +++ b/nav2_bt_navigator/behavior_trees/navigate_w_replanning_and_recovery.xml @@ -5,21 +5,18 @@ <root main_tree_to_execute="MainTree"> <BehaviorTree ID="MainTree"> <RecoveryNode number_of_retries="6" name="NavigateRecovery"> - <Sequence name="NavigateWithReplanning"> + <PipelineSequence name="NavigateWithReplanning"> <RateController hz="1.0"> - <Fallback name="GoalReached"> - <GoalReached/> - <RecoveryNode number_of_retries="1" name="ComputePathToPose"> - <ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased"/> - <ClearEntireCostmap service_name="global_costmap/clear_entirely_global_costmap"/> - </RecoveryNode> - </Fallback> + <RecoveryNode number_of_retries="1" name="ComputePathToPose"> + <ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased"/> + <ClearEntireCostmap service_name="global_costmap/clear_entirely_global_costmap"/> + </RecoveryNode> </RateController> <RecoveryNode number_of_retries="1" name="FollowPath"> <FollowPath path="{path}" controller_id="FollowPath"/> <ClearEntireCostmap service_name="local_costmap/clear_entirely_local_costmap"/> </RecoveryNode> - </Sequence> + </PipelineSequence> <SequenceStar name="RecoveryActions"> <ClearEntireCostmap service_name="local_costmap/clear_entirely_local_costmap"/> <ClearEntireCostmap service_name="global_costmap/clear_entirely_global_costmap"/> diff --git a/nav2_bt_navigator/doc/legend.png b/nav2_bt_navigator/doc/legend.png new file mode 100644 index 0000000000000000000000000000000000000000..e2f5bd1d6df70f554b93b6beb015d19dc2cc08b3 GIT binary patch literal 7285 zcmeAS@N?(olHy`uVBq!ia0y~yV3^9lz-Y+9#K6Gt%c?wtfq{W7$=lt9;Xep2*t>i( z1A~l~r;B4q#hkZuD<gu#|FzpkdNc@p^Ifp%<T4Gtt&6U#?dmHP*?RS2R_@lti?{mC z4U;XMlUaW?>g}RyOBb(=jxK#8Vl8q}ODs_2$f_L;4IG=eoKysyJQQxf@0aFOXkj^A z^rli?UjE(9^R>n2_i{d|iHuq+CX$p`{+&U?pY^M|*%kSl1-&}cBda1+bl+WB7%<Do zDr1`A(Vnm6e{Nmtw!G+XDA$!K@v?v2{1oTE6L}#z0_q8K_H)<sZq?Y|`=@2y>%gTi z7WMV~{kzt4%6+$+rW#oXgd1`hy{#i|Ep}`>U|;5z|5jnOL!nVuutGuW`yJ|SRop+H zE9kcNO1JIh-qxxYTf@&P9#AR1E$)LP^LB&9zb>r^s9;>Ab44Wik67`!MY?Bd{%WS~ z*vGze{{eHMhuQ`ef^7R3t@B0Zw0r&A(yOf^yHd5l^}!Ug;=6}F{0U-Mp?mypMD4C* zhF|-b82-i^hsiORiQiissNNKIdE&w{hRwe&KYFI<ar(odq8ql~Ehe_cH4A=YyTa># zb=w{;Nq4J=>A3|{A4V}XG|PJh1=e}bKewHkLEC-u??*RhSRLp~_Ny0_T%p%+J|ZGw z`<bE-&9@u+w#VonJo`6eg6-KCw-OK7e8`<B$-6UR`k^FdhVILqbM0)O?fE}-Idem@ z!|R>v{+8OW5INz`5OHBu;BNu5cORtr*NM86f6$Qb-(>Ko_D*lBhHy>vm*2uUdjqO? zw?2IkrTAK%#oxWuPRmH))PW1-6Y5xs4BPgzZ-~mj=279qGowAby5P4#T*S4mZQI&- z9TvO1%UmISU~^;G<(#D#R|J%BmMVF8AKdD6A>_sm=~}1W19Ps&-&JPVP-Yb37Td3F zec++ugH#qj#~0ZGsfu5{SBPx*>U5J=Lq)@{@xKd;>%wn}oBp#qe7|#0Tq%WZi_`|o ziV0kmqNmm!&bOJ<v><Tn%{3oy{8swVze4la-gqC0ZDGyX)eBa+pV0m=pX0oEK>XtM zGh~^k*S)Y7K75b0yY+Rvb7=md3Ac{U`8R{reX&W1n!RADQbp@)zDlMaz0G@sesVsz zeejYPL(TDnm*n=cHLJI5`O+y^oba62yPDwxPdg}TyB0k$n{C>8Px+x(+aVR3Q)Xp1 zR98+AIaobK@AN6ou>Sailag$9G)?g@EE7Gq&MB2oYRQUy`L`zUB%k|w`IzV=rz>Fx z0&k?ve8t4@;KNr<zB-10SPq5+Q|+9@R<=xO-i;-!Jz3X8ew}s6m3$}T{G-~9_qG#@ zN&T5b+j*|OhB<c(|I|)Co?!EA&p(+zj1Ea3rWh7a4u2V3;q>66b3(ge@@5&kL-!h@ zT6-3|ZH?DwWJt|EALb?bWNLtU{Dd>VYxRqN70dHP>x;x@l`$t=SP@VrTk&U8?UbeG zgF=`af~Ea!t0LO&g_Q2Od0c(V%S_Q7i|*@meD2ALf564CNG;O$cA$3PgcbgYc0LBm zX?y=~6tH5?(OXy7+QoDC<uwh(bBBAGH<U3l%s1Rn=>Adl@1ck}Ox5x>;tRF!h&&5B zza{x?%P*<Bk=Z&oe=JG&*_?ZK#?-A0QF>SMn7?c{IsCS|pRK$1PJBRRxOwEWr`qeA zyzL__AO4F>`6tewukfDd-9MiGg>G}a7C)@{@v!~a6z^TXlLJ%Jb|0-^s@TiGAS!vn zx|x0d!Y^78IV`@7Ta6huSbUIRS}LPDT~W9Bhun^^7uLc#d|kmGKCm%tuoS3T@Wkj; zK68T`FMGU3>V!~-7mVKSA}WiNm>H&&ZrH*epRpoxr^HXr2_lY58(KwK*8So?S@O8Y z{jTzr&V)>UZ}!@0$qYv-KgirVx8bLg#TUn1&92FTRkAgTSH2eTvE3I7^DE$Pjp;ch z6LPP4sjbtp*Y9t(Rn{J9KPHka`Sb5>-i^jDzlZOd^kb@9<<HnZ{~k)V{Zf{G)t|G% ze$&E#CrIP;{QWKNb-pEzh+_1L{7t;2?d6>R9=*$4mU_Khw=kfm@oZh+Y1w-fH_puW znyNJU@5<BdE{2S9??d&zA3x^2t8Nkr1^5;Dn_o)mP5oPpl%+QNFMs^6?w@4wvxGAe zdp>bJJ9qTe)gPa{|GbWWCK*<1yDjhNk<Jg_udBPcJ!<B^wI<2pdPq`|L6(S&tYH$1 zh;P$|xE&4Q@vV!MkM%nH^lV(a)k=2r1;P5MQ#-m2wed!5<$8Yp@sC0oyPk#48;jLf zt-ifJkEh0Nnyz!6-j%G{Mcd7FW*<q`$(4)R>iRC&C|AmF9!tZUoHenl{pD??Zf|2e za6LZxmPvAScBxg`!6!dfM(I8~>+Hw3F1Gpb<BV(_v9xn7?d*JVCbv)gsIjnKyvp;$ z>Du34?8QYBUk2UPtTVc<!_mrMki@d@uh?Su*STL`u`=wfo_+1s<jaQKYVq}jg*%E^ zwZmRKH5C$UT%qxq=d?j;>I_@yez{WDcy_)6XL;Z6>ppb6FmY!L!-fq80V`h{{QPBI z$i(2*n`K*mO5`qokmkN0OgUy!QWK`OP7qiV#cFN+=M(p%$A#Z?CQaU$Cwp#A<80}& z_s0%2GAsy4c<go}rJ%4es&|)FY_=4y-yDY;8!m1^@%F{;6X)_;TkrXAx9`WI)V%iU ze9`c58Jmuk!5a${{pRPnMn~65&fshKRrTg>_nnwKJDH=Sb8fXv5D@k?$e0}v|Gznc z=kR|vUZ#daPR^-a-4EaQ@BbfLK4UU-ef^Ig3l=bxzjIJvX!!cN@VD8wcdQMH&I)4A zDu*U0&ajUU*Vgs@?v>7W`7)z|f<yU@FVDqx%D&!vwZ3<6{U1YyJ)iwfmoV2#&O7(# z=a0AMch4suKXjDU)%ES1%4hMpZ&&+How=v3$bvy(y0q5jTI)}rHY7B@yKqxdJABas zhUo2!!u9X|eZ2SkgQu-CjUPU0>fvFqs1UfmKKZ6mtggI#MfL03U%r@JNxpoi?`z(S zrQU|QQf2Rt-Q0Za+?4|*mo9y{TVC;y)xzq~MZwNafzAn+7TWJIy%`@Mz;I`8_KGu8 zwHXqU7yC;ZGBMQs=FJe2n|tt{+}E!R6J~Ij)axabzqspryefbCTx&srhSbv^J}eBZ zm7L)hCFSH46&E3_CSlqmHlwCZNr~aXEz{=SO^gdxc+7wFii=^}wzjOPQyDL;_49W= zUX?H2$Z)@&f2U0S&u)+beGxrPP1CYxEPMOn1)IUm`)eX4ECi~*E!eXsHLTXQPnNmi z;bBGvySVwGK}-yb-KDcE6&9rGGH-~;-8cPJ#C!ikb1p1fZmPhryX@g3*Tuh#4CWqi zIPvtyC+}J>KfZlGk8OEqIO9$K*<<(iZrE~UiDyUm<+(1cOyc@U-*WCQxL+%-sQBYo zc1XyJthe|36Ay355Nw$CIy6_8VMR#9KA9Ljvz!Avi+8cjoZ3}cdOC$cp;o5u?sai~ z`9}wt?<Ru6`Jc*}-@+4DL?(rZOw+q6FZJT|ff6;}rhb0AzaponD_cp;HcNaPb!P7E zS3mRG(>~t6`pViX^|#}pxpNHa?Y2bCvFY@;JNW(n;}?MiJ8$d|tgB-<@HFXLPDuFU z1B@vt3YwhTw%yn#D<*bhzx>6EyNv$+e*D1k&mUt3jj1!NM3avxC^O%$Y5xC*Juh#? z+M_={7L>PdHr|%!nx&PMotWJ{K_DblQJsC^LJqE`m_Ge|7oLB6-~aQo?>k$YnC~?w z1jO6V&My3KS5*A)DXYGI?X?#dcT@zH@8Ugk<*KOuz8k+vYHAHDjkvfc&gkG4fAFyJ zyj}C&y@iJ?YAg3d_O_q>wm&c9hyLGxUi|IHt3wqQ+>fseTR>__kEk7_{?E;ML45NW zce$_jet&f6>XX$sZj~iYS$^zb+uQefvjivqeQF!>ws*bhR<WZJZ9hK$xtn`S|2hlF zMSej2vn7uAu0DLV`_TNb)t!I;@MldeEEKw}@NF~a{=e^?je9x1UrwsKWm0wDX!&Dl z<q)shn(vo(doC|OduRI@&9u`yerFy#Rvy0kRsOu2V!waN?~A{CJVx1M(z*}fQ|gu} z{m*)rZ@(>m3+JX+X&>*l`rVV^-nX;uiFw7XDc>J4giK9c?zTSL=R1eg*GJjWj6Ja* zw%$)je!RPQ$De=tdv#ZyxSDlF_WoYmU5Db&Jw0sJ7x(h{zNU-Sww~JELi~Dpvy93f znmhm7ajj?ZrVS!Y1@DcOeqY+|t8be9JC32nZ`slE=Mf*)=FB;3VWa%Ar2Y|mc~0z~ zU;WWxv1QvWj1SJx+VpDEkNWe09=nzH{ob+tTlDRnu{N8WqE>dlKbKa_xWUp^d0%z) zj6dJKmra^kl5j!(-eYc=OMbPp=56@Bv+nWiXRD-MT{{0aI%wYM?c2odcRZFgvn+WN z|8D8O<*RgNr>9P@$w@u(=KR(u--ErvuH}!G_ILgJv0a#93fIft%h8cK+uZId=$$S4 z!Xasrse1m@x)0x8KC=FJR5Cq2vi@b!mtBj#RAgIkzqtN=**n>5*FLPtiH)y%ePHF= zz~|rgn?C&;Kkv%5uy}?LucKdu<+Wd@hMAp{S{rq9LI3-8Vb|_k?hg-|7#=z4;P!3Y z^-q)8`}>ZT=eM8R`%h%+)TrL52M<m@jco6U38*q(xk+WOVff;}xj(bEEwL#-^JjhA z`9CTOHGWxNb}i~LX8!*{jv+hxddJQA%n2KBtlM|~zPIhN30({tuTu@9j}=yiIWPWa znRBddWBxl$FZ<8?&+40=$evT({xr6CTIlpNHCYLx%C{e8&R*rUIjAlowPM1%e-HJ~ z{ICyv*t>e8baaa33-8r|^KaROu3S-Dc<!2F@HN){idemi?kxNMJeGRTsNX;5_tP!= z)f<l5ZB5=4bWyW@%k`cAHcj6D+Wgu1Gw1&v(|H#0;j-|)tTShA{`=nC`^0f_n33aN z=C~QAufE2<`}fd)n{vU0<K_EB_s0fJ6#w*S_L+rCdp|Gm)Lz=pl{fFE+J^T>@9bss z`!l<Darpd&#%o*jrmDU@Ud}JO`$+zWEniyh9xb1BwA}nc__d?XqO8}QkMBL3!a29L z<=n0x?-n&}dGq9b-Jgsb`%?XWPqVZ=;WfqEmA}|p<o;e;tHQrmR!p5K{w+59-=cl> zf9stW|5M%Yo^`>Sd#Vgf)%<GRN1w5@ozL8U^V1$}1|6NR_3AJ0rCT&~{oc=*urRWw zeBai+F}G}(3Z;AIY<G^CRrzptdD@!Y2|n>cj(iLY7ymPCKYA&aXVD>PJ~_qpe;!XV z{A;H=x8m>9<$rAyihj;74>$WK{rg#5Z`906M{&*QIAx{)<x|EhBgJO(Iz+AP-<hXc z!kUoyHRR)6-5*UKyY~lcKkaP)^6@V37uD5z%nK%L6}rDSPHmc<R)DEV_xp8M%QW^? zSC>q)UmI5Z`+96`+qs-sFRU|GO}$|G`jKMlUY>@<;TjFn%eR~DTfah7T>Sn|QHBVe z-eq6+Un+lZ%;ZqmX1Ad#_bM~Pyo1Y*mZ$q=T)v$3Ud$lt-nmUOe@l}W=vQw)AQsts zV<-CxsVCddy?VSm-2TkTJsZw1c_`_b{`2&1sk7o15w|Q%U-z7@)+<SBj+r#^gJ{DB z&i6%?*M4T&&%b49Yn=K2>kj|Cc{l&X+%IIvnOplx<>@A^*qZWV<;_l92@X%<Wo?|^ z&H3*Zx43)fys2BxpUscBf3cqJ!lPih)LPw!uz0RBzlGCyGmexOguL+n_2V7eFDZea ze6!E)mD;^g<@Fq|l^Umas!X<FQCO?<NzTCY#hc>CSJFM(|IaEn{q?KUclzS%tZn<R zJ)E4`koNI@@4}EZ`{rFw*x_?<?d0k8G12Op&m*~F_pqBT6TfFQwO)CdUyz>Gj$_Xv zzVOX`VVf}NOW?u9i=r1bWpC4~b6$MSSbo!$t5dvB70=o8>-KK;RZ>sP&({Rbo4#tz z`lpdMtt!9rcUA1&x6bPIBgaBdx0iQS=1skO;`+9YmSQtKe}7)*#+*>BGiQ&}W<9x6 z{=X#~+}0L-=T9%*;p;x5tjN3f#l9sr;SXM9K3>uP{+*!BDxK#+4?gT<xFM5wV1xbE zThphm&0c>%{HUtrO!0j?r&pahbuBbfzk1#MifrrhXmR=Z8%|z2)x>`Dx%{2I3I!i} zeq3H&^ZMK4-PIOF^WGme_G~}-J3jt&?t=UAFIC!pe4ggB<bM25TSt;cmQbojlYiDX zFT5tN8-}QyU-jpl*<YXH>+4(lH#pbyKhNVwkCN`OoqfN4$r2Y8qpZ_s?<+2LpS{g9 zY4?S%lS%CJCDdz8)ly#k_eRfov$=Brw}q~Y-Cg$U%ggxszoG|@bPC5;zctOz&u7@4 zfB)aZcKJz@Cm%j^DDCVlQ9;3rS*0sOs@~k#`1p9gwn*3K=jY3xo~V|3c7MORvGL^@ z_xEd0J$2%QhqUx;VRgR^5x*A9Oxjp+tVi;AzkGR7kx_u`fiEvFuU@t4#Ha6X{`|Xp z=nzxG;>F3ql?-p*zGbwqu-J0DDL~`Rl8u5c{k#8fy!qzXf6cd-Y`@zpd;0nL`GSCL z#fJy$Vs{4x1<jc==i0hhX$grNi=Ob?|Jjg#f1jjrT91rnkkUkn6{?d@^2ytsN!l2q z6<SxfZ~glBe|~<>&B@8Tvtwh`*DSs1yHih#)z|-jdwctQ+v>6h2O71*)_nN*acBAa zd$UZl@6~+vb$54HZogvs<;C>MfPf3@_y5xp>P$*X64Qy;Q1kQCpFe+cZ*SYGp*Gd) z^QTYW-re0@^77J!3jxeqpA`L^r0V^n=HH{E-S_K$zpelCSbn;GeB7RjjXrA9CK(r= zoSb|$YwP~~`yCV_wq{LjZf@@G?(XmBXQ;2Q*VkXK8N5uwa*5tz_us{3Ai!pjf6vC; zeEW$L9_;MxckbL-mU`;csc&y?ZqB)BWN*K}EL+yLYRirt6|b(W^zp2&{(U{Ze(#no zUp_oM%&^RV{=Ewq4%mo(uGq7$_IKQ_5>LJ9%pShJvi5a*COW_J+I3le`svzFFT)pK zEZF%gbnns2y#X2_T2p<4udRtxo__l6n>Vx6wuNfj+R8R;-CCL)77-!A@T_*p_U+#v z9BfWbPG+1kefsLFSyR2HPME;(;LJ?pi4!Nf@vYQ;=~w^m-Mg(@b)8>cyK-gAgv1$3 zy{D_Gsma+^U72y{O!CFU?flZgGuUGr9S+F&&9}4F*VnhU{{7<OV()1>l9oj&F)=ZY zj*Yu_?_Roe>Bq&djCNg)Pe@1z4Gq1#ne)N3v$L7mcntPU{P5vJ<>zN_Z*PBpYO3~I zv9zdtH9w1zy<A;c8=lXvpJ&<A(NR!ZYFqMRg44neA3t_>b)7nQ?%uZC=#Y>pAHn{= zf2fta(&iq!e9eJ9_rq6)tX#R$y6nvi>+-zhnQd)p8&AD{^@?G|)hvcHtCn8P64!|^ zD0pyySK7?vUi+<8rs?No;^XhnulwbxBW4_FXlS@_;lj(y{nPnw=6su?8N4oLr&0Pj z8HU8f#J$zu#W+~x<m8U=tbA=~`LB9+hl^60*W0A*Z0oc$Gv>^hqwL=2;_m+c%VmF| z&XljOuKxS?&!=(542fr%O@|+Td3jmg%xv1vElYRpvNAR{R#jzX=s*7X%NG$27EUnG z5qtgZ?QKs_PycH{D?^&uc&mOsoxU_EGbbk}E-o%AYF2OW*;7-sXWuKVt*yP9Rr>hu zxl^aIuB-^`y>FeF?V&YwRsH{eGJMBBOqsbn()d#D{P}<FD$DHb7tdfNb6g2jpnbf5 zvJLCNQo4>%=aSv+7r1Os-~ajfdHUH|N0T;2=v<qm>OCWWMT!2`uU}`I<w_YQx$OQu zvxM9B-QV3YdfT^c`}Xado`%MYcN<>>Xo$?4H!o@9j^%T;zifHU-!OG*=;QykEZ*MU z;o;Zc$+^D%Vo@(L`NhTG`?qvCExfTY+1=0Y+}h~vZ{EJ$o_kwNO6pX~+gn>-pPH)e zwD7}$M&@3_3tOUcSBEAgC;QK{seE;1<(DsCM76_?96kE=)z#M*7CJk(@h~b(KYe|D ze0+5D>sPN<g{@9Cirnsd!{F9D_J#)!9&9TT*NvJockbCgHi?H=%+0sYnkBV1Y<KZ< zKfd<h$jFsfv+RF95oUP5|Np*5Emc)jGcz*=yMI3(A3Efe#yv6da9ifqsHtA2IX5=A zc8eK?e){xjhW?APTRql({W8I~|3%$hqM)bexB9BzT&t;P)67jwGPXvg*-!ZJq2O?6 zQ&ZEdsKVmn$De;jtu4F0E|y`_rcF|tXS|(iReVXdWyA0LS67ESJ3B|8N&NKWB!iN& zvZ>VBlatjM4XSJRe7WS^wtCBrlSdC8Y>X^@{P^+3Kf7Pqmf4$4dRMPBamAiJfByab zU0Pb|`~AVi43iwQ-*e0FZQQh}>h;>~lO|7oe|Puyi|+Dkqqp-pq^71uhu(Vi;$Sno zkE_4``Ezq7NWNI8zdEe)_uK8izrGF+58s}8dfKrgYu4zb?F?RhRZ>!N<;s=wYrjSM z_?)r-|I<IsyaN=JtG2in6c{i(3wrmm<f>Dy&eEkz8EkBAO{IL37r7`!?y2~=r}DE1 z7whKpHxIRP_sdvrs{8wkQ&`R5yuN(xmx=rL|Nr;*xBq;*xsxVMnml=N(8?`QYa6xB zaNWGYUA$Fu>Z#f0`9(Wp)YX??UhaSW>eac{<>#(l6LYAms|%ms_w7aGzjJe~ukW}V zSWxic#>V91eX`ObB1fKoW~}-Bc6-#?Z3`A8yt=ZoudnajyLa8<`eL0fK6f{#pWn4} zr)h2Gt{ppM?CbWd)!JSDKCLVF&W=E(i8=T8&9zK13-R{y>gwna;A*X_tD9|}FK3!{ zWs<75kdV-otWxuN^VMG#&Yxd8qnVxGuIfw1)m5PkCQ`ncnVCsRk4{b1K7IQ1?&^%W zp5^-+&K!Prb~d9y{y(Xm_5c4ZaBSX{?GelDd0wAwN6AZ}2HWayAz@)gnwgoI+1J)2 z-kWNF*hcyF@(7)O9}e^T&$Ee)in6Nskl^oso>N$D&&OlZXY^j4H#pz1|Gw_|6Tg1$ gZpAmCJo`VpYJdpmFSV_r3=9kmp00i_>zopr0M4M46951J literal 0 HcmV?d00001 diff --git a/nav2_bt_navigator/doc/parallel_w_recovery.png b/nav2_bt_navigator/doc/parallel_w_recovery.png index 24b608276155c9ddf00052fdf6969747216a9290..3201ff340357025bdbf61e6b9d9895399fae7e07 100644 GIT binary patch literal 90147 zcmeAS@N?(olHy`uVBq!ia0y~yV4Karz;uU$iGhJ(ddd7$1_lPUByV>YhW{YAVDIwD z3=9eko-U3d6?5L)t*p56bnpNF*L~79y-!i)j8qVCa9P5|(IxVsV^fEK!-R%wa_g@p zSKGYZ_<W1)^G8=!|1JBy)qelgdDp_UJ5vi8PCsH(()Esr5m40OY-xGZ_~y5f@qPO= z6_u34vndaL?%46>jP3X5|Mu8BU;XeYj;CyQECU4GX}Nfn6~biL!KG3KVK!JRUSx(a z?{uC7E8uZyZEc-7bLP5rNe{ZZyJwqZPFlU1fq`L%@5C333=Ad8#>T}T9~}irN9`zB zcr>Z7RFr{%VY{Y~EdxV?+|9RT;nNKSmM&YiYZnUxL&I&U-ym%uJKnXp@PlXuh5~hL z4&dyRgGfK{^Y{W`F_b$kVuvty2!kvDu@B6hKuseXvcH_Oey<a?<wSyk1W#N2pU3jk z%TJs+Q&O|5;NhYD|Np+P<+CV!bVNM9X5)9e-DPi$BzPPh9g~mu&9x|8bTHw=$B#2D z3LnidOs=V^;bC)*jJ&zkmXCpf;SMXvLkCP}+1LMjb#=Au`ufka@5kJGI5j-(<JYfK zzr0$#-tNbP=32fPGiJPa`}S`2{AJ6QWnNx3b;=YO%c3U-8kr{v2?_DZSQLDDadFY2 zMNghQId<&W>RJI%Y=}=@&CS5TP>^hAXE#aBf8L(l+uJTL_ve>3d-KSB>C&ZBr%rWl z<FTy#l#-J2WNOd0vbVSFew&z@?)~woyKljU?h6+#<k!BA_Vx7*kFf(eR;U;h=IgHS z|Mz<Tt(<Ms<LiE2I(9v-`fc?6U)Ol|Usvw8F)Ds`W}e;OZ`=3JoinHAa6T6ULjz+g zC{iC(ot<xQZ)f*Uzy7CpY3bI*OV_S_dzjyTj&b_Ar*n&oih_cJ|39|>r>v{{wvk=V zqUy^EmDy+0Hb#W4i?J+y72+AaEvNF^&Gg5Q9<5rvI(%J>q?njl+L;;W?SA`A>hJGw zZ+G{fI^*oKGiT0-$5kjA8gAUN<HtdE`JVp%_3PH<<>mc*s$c)}jPdz9#pi8})6dzI zy_vDN-v2EF1B1i~aAI0Fy}kYT=kxaWFI@Pr-2U&$i<>epFFP(@e<$P3v-Gv@^0i++ zJUndw|L6Jp6_0xtyZ7tG?h2W7F=LKJ;iFeqSD!w8TD4c+zV7TS)7I8jP@1U!G<p7> zKc7w??~|>5xAXb0HB0vHy?goc=dIV{PM<#Q?eG78{r_L<+vTcG<e1ezx4u8qJpbPO z|9_tQ+x<L}VRCMU;o^1c{DPn^<SE;I_o^ua0|Spm{{Fw;9v$so|3qE2`C!8K+u2!J zNy*91PEJL|#lC8n?f+i3UmLw$Pemo=$%%>T{`2;f%(?&X+xCkWFM3bY*?9Zy$&)9a zpPQSVo4eN{#LMecr?9%p(j`mgSe3qd)EXEV*tfE5`u)F;RK+dVtzEN*hm&(+$%_jM zIfd0qb{5>;mizGG!@Jw;f4x||*S;t#Yn4j((M!*#GczzW%x;`)$iTpm*RWv0g5~q7 zUX}0vefL<ebZ}76q)C%xGH*SNt9aPj*4B3a|G)23r%u(?)y>V#y<281!83gyFDIv_ zw)XBrNix^tbRJChx7+!+&syemwf@&vtJjy^<^!dozR>Lq3=HPS%J+SiU3~G!?fd_} zO%0E${P**D^{a0u)#vv}8mnn)zC3RKZ{z;`_4XoRfq@fe&%S-*Mn&f0vuUqa?v?jq zVqiG%RRL6-?I`Q}bNb`;#KUc8=h^;#aIo3c)pfC3Z&AsPn!9;XQBl#+w-58%uld(? zJ}4+iN?N-9V|RQ^j%DGaBiiftTnetXp8_hmULRZ)&A`x*{oLZjqBU!DtgNCgaqI8d zka~Jre*N#;;?^c6CLURNdEdT$E88+<%9JbDuD!dl@$sLZpZhi!^2=J8RD5{w;6Z}t z)~#Fn@?y80DVB-2c<)}G(ac>u_fjX_J(?{oCH3deAC<GS&Gj`kU#i>x^h`{A_~qqg z|2Y<gFD@+Pl{TxWsw%r(r@UVQls{SIR)?)ED&=KhU|{wO3%l0FD_!;9GxPK`-T$BM z|4*JfxAxVQl`B@PICA7jOG``g@xH$w+U-pwc+~yoRQ!B8{eJEDSWin!%ZCpia&mG` zVq#|g{_gJYr_<y0qPOX2YQB7Mu=)A9xz$f5y4QW4egDnf-P_l#)6>w%`2Oy0U&`4W zv-_pjW9xq$mX|pmux0C3-<d{71z+Xf-}g6s|F5g!@il?L!NFl+VgdpaCQP_+<HnEA z^Z);uTYhh1$-_gfJ9g|?u|i|=$uBpO`=360mUn+&?elYUH*Vaxe&4Sw4-XIjx3zVa zeMw@vQ6+ot8!<32tm90-%f!G?^7z#GU3+;8ujzuKVPn4>sPJcCpl|H}vXi_D$7h`$ z0|P_CgR0+ex5vgFatMitkdT&s{YndzkK(}<pl#HiijAwiB^HS3#k_bW1eRdiefQlf zDFz0H3+&AYH`M+8<=QQ_a~HVGmmBO=Dfxi~E~7!(=}_T=tT`}O;!WA^)!7UT3=ZM_ zHlI%1+gq*wZ^gAsmy*n8_qsi=@B8}Yi%r>^h?0^muem_Q!RZ+>;I`B*!|ZEozTdC^ ze`(sbZDz;0n-3Nomn|1~&d9)UXIn%mHv@x#fNtEL8;1`szTIzQV-vO};^O(Q;FJI^ zoFqDwl$7Ku9yI1T+wQ*m@5kf*@AaObdP)Ht25c*yo}M1R@9D<&_TxR0#!5;`F+re& z!Nvq?{xmRV9c*G%3%(xP|F-P+r>Cc5gFsCxHV%lSmVrURwKb8kPPUtG+T`D}37-mb zd1C{picWY?_35Pg+OXG0x2sLge0OK(zkmPqbT}Cp81&phZ7hR=v-50kU%&qSQS|Do zyK-(CiC+U1{4mX*zI}_^kkEKDr)<yH&!4M*JZz7R2DvMy4{W$Y^sbW3=;+xhn{V!^ z_?V=xuOA-H!oa{FZhYfyS@?AZP}4AS?X`}Mj#H<+Jgv*${rPo$|GQUR3=9kplFon% zZHWsuHa64rVzo4NbaGx@S-DOR)bLxEUR27+z`$_VB5u$Bn%KtGt0gpo)ZAZ*`qn;~ zw|BYuu3gg@Q(kqruG3>=U^rk34u7^q)3+^ock<qYS6Xa5yTARD@2w1SbdHHV>9FbV z?>{o!3=Da}Yj&|RFi3ph@tU)4fkpUqMh1q4#zt@*l&6r^v|5{if#E>IK^a?6T47+o zQ2@MI%+A2jV7KMUihVx4&qe>5&fF6d%gexUAh#bBC<`XfVw(FiKy-P^r?4v)H`f|T znC477vv1wHH(FC`mR*)#u`}xN|Hy?W&mDV~HTUkyL(E<KqEGgp(*DrZmbLQo%(q#q zLhd}79j*^55k*$#F)}b%adriNvGDAgy=G#6cF3w4r_wu*UTs<z_oYJBZ~Bs^GktFF z6I6XB-}GNB9-BEwUDF_pt(lE?|3_CQ28IVx;8t@<XtCd<Lv9xL+tgMY9dCUav-{O% zF3&4JA7`z5m$Bw#_?1|rikPDo*UYYpWds!6w`F8txWErinY&h<n0C_L@#DGezEi^u z=jJ}xaQkXO+~Mb^@`5iO?E7{~#`RuhsdMP_Q)zD_c7fWa*OTNyT>`&ZT30F@CzhW| zn6hM<*4%#%o|kuj+gadsEi5!8`;WP5^X9!D_ng}NM0CYAwwrIe>JQw!7qITr;!ivQ zM>To>%{t_^YHeVu`;^b~mi=izQ#YyPlkC<jnK@DY+cVY${gazov#Rrc@KMjXb@7J6 zsoPg71P9kCoM-U-^`-u)<O1vYQ<mIvV&w@-SkojNQW4N;obqMDl37l@F*iQyOuzmt zCH$gdWyPwcex^S^^}iCy{`Lh_zb=qBaOY=WSTLD;xys6gKJjTUCWlYm8h2Pe^vjPv zzNzU`_WEuV7BTe;O}}#QO^&|pnmcp5>K!hYYu9W!_pW5ybot9C_iN^LCB3_Pq5jgw z(oMHhzFmD#oswOC&oAgs%2ly%W!&!tX6{M(7GAs2sa?Bp7h8Y$C!LvlO7iA^KJ?_~ zIn~3H^yU=2s}VPMU0bSUujSb*{zUvCk9PGc-$`p@-LIe04+?y2lG1gmzwDOF`sMkc zMEbWGlH|IACpkWzANs-|^ttA<xYqu6KelX*JAO^$r{KvIm)~oaE%LFO6cWGcj;z<r z=RButoJ>EmdS<N(x>nU&6Qic@Y4m&5+Q7A?lTu7H72J5Ao}2jETck8RfBS@xXqEep zn<AeIFH-z|+C0WcBdN!D?c|i~>kAU&Z9TR*wR;9Vk*H){We_|`t5{^(qc<14bC;W) z){i;JIq6D>=I*`8Cv)|mGBPkMsE4G(4UwUhZj2W{@dRA4ko48EzO>T$-0rSD!M>qZ zzos!IPyIAwvu*Y2wmbJVZ-3$|+veUkHGjtDjq4)P;wxD#?^pd=z0_?|O8Cv`UVp0c zw{N%|GI#YhH`ka+23}ozf_a~2t(&xDld@FNewD3e9%VCYRZk{_yip0A8(Q0`rRVvj zYSmh;@T))16&I;qeRBH2!U;?4_JN9-FVf(Gl<#Wgrfn9_7th=yYUn1q+-j}X-U6q2 zj7Gn+&KU9TyuY)4&fR6NHlLHsoqHp+a@S=;5pln)3mtvi=l#oCId#dNdX2hOKKE?z zIR%}y+`3((Ea<xL>n7nRiD9mNv$U?>Q~96axys_^ONH(mokp`t^5(Bu`{~R3#oG=s zckSGsoSOG9kM;QJ!<)B5;<XbTug*s`J*B>cikbb$-V|ACclzhHrEY6^yLS6GZajD3 z^ff(C-O^3lPNoMOw<z1KVtRemUQfo0=Z;;gnkswogS+*vnYCAgR(Iu8vTJ8}fFg6E z?qW~D<XzWt473#7N{^npd(m*?x;GxjgFQZd34anHDj)PAoc+hQpy;oWtVb<xbAMm` zaF5gE)a@tpUaz%bU|@iR6NCEhyE_$QFNALl&)Br5IrPuU&ueeStL2NzPP)5p8{5;j zLD7p<Dp^ly2R!e$-fcR?Qvc(p=_lQDeJ7=C*Q}l$^sHQG=hP=J*B|4$Dr#MR;q_Co zNm|7w89R#4@77~VF17Q%r}(LR!jfxMu_wY3VwT%EFFTR<-s04@>9=xnS7}dM>&rTG z)7H~Z)-F)g`sq_voexf4_bb*!Z9N6<O_gl@J>_Z4(U1Fn-?dm<YPB&ibmyd$+|Yy` zn>{H8E7k_8&R@AVGEq6j;FNw$x?RXmLDTCR4;^RzRXLduP|#Gg{q>*1(B~)fLeK1- zl>9Ab%el8<(Ti7|%lL3z#AwT9-`lT5O<X?mmu&e`()}%M?yWT~nOqWgd_U@zuCiQi z=$&e?>f@eGI$66EqIdsUY%S!l-r?$Wjeo04H|@RhOmxAV^3Vzg#%59bP}TXXwmN<c ze){lca;4tJKl?)UcAGOWG<ZwC=`&RXwf0YXM+bdR$uB4s&3k;r?WkXfL(l5hFXC_S zKYxBB1H%Keqo95Y!}qW{pM#v+W9P6lFcerD@7x6{6=J$q8EgG=Y20X3nf>89xN>6n zB?uapXoxndJbg`Ve*v%5!&gC|=H`BIDSs!(q32!9yH`q}nwbk+!+{J!9(~#HN{oTw zPLr42^}_C)x09Youj9Nw@#O8Fffp5@{*UE-{#1VDl%HIZRlSd&?^&)md8)zND(~F2 zlhYmYWl!~MeOJCJYJLA#>uG(jwWXW3YUWHyQa_>nq6*X$Yp71_lVf1m!RmT{t@XTu zeR($PlV7Xs{+xSeuhe&5PpR)`OpjGg>f&Fy)b07Vxcs@kqNo0p%GW9#%Q#e?`mJ!^ z+#mT;vzM)}jczPFb$222|NT<u<MSm!!zB8k_V$BoB9+TkPAYgl-(2$TabJIplj=$9 zAGg@$jY1m>y=GO)e)W8N*6NS=R?}~HFDFd7dH?6Fj7ciZ2Q6(kY~6QxF(U)RgR%pl zz%J01{x#uTjfQ8sT}Z+lHs0w^dVa2R|KZWvzh|9bR95MaQqw81ne~TLO{;6ShHc;X zWtSGHg>f4^*tUJs63Hx$(3gTY-&*|&_x%z6v!$daYx~PPa#L&c-YaZ1J9TT-ij7_M z0dD-E&tJZXzZ#?K=`0`g=z8e9rITli%vtiFA~nCb&){?T+`RCq+ME0TEdDL`{|mcp z;k|$V{TmCV_Ihm6uJ6~IGsS;H)T^mR`-8W}nuJ-z|8R||nJ1^OZ?)o*@+ZEa(s@en zE^KH|{V?H;){XU_BR_G522W*5o?;U07My?HE^TJdvAlPa_J;o4J@<Q6!PHGUt4>~? z!2U#h;pF!#mWEAY;|)JmbMw~J&+}$!l|G;Rsejk5`@Ree3>J{o@yJa-EMbkxR?}Cf zubz8sBvW)R_?y{P(d;)|z4c+dPp$qo_C>2`S~wO?o_m++amt5)Cv!hZE;01isLQ%8 zx_evM({~sC#cQhsn$0fzv-@+n{^R~QmHCe6POI1YFBbQ_v{Lufy;UcyO|vHU$o+aE z8hLwHy+-tIzj_7Fw0PBX1!mt$es0`qwa-zoJmX8!Pj~J2@6WaFir=?%@_UU}dc83V zmPlIt-pKdYZ`-$f^X|U5_&2ug{7Z`k%Fk=Jny=jIcyzwjBR<~R6F2irPMiDu3;e`+ zaYgHqN(Kgo>)_Vzoku-scee(`HBJhNULq`QZC50tko|4yL1($N=l`lw<E`v_XDaaf zdusi2nUuvPGD&4|<fP4i7p>V|nzsAaEY;?k!zw2qEZmq`+jHObF{@~bSNz$XpLv75 z*M7b>{nsbm+HdZEAJ>=Ic?XtfUfO?Bf6w;Qr~6kvDfaA=(Dih5Rymmw^fEDBRq^ng zw{DwXb<ItT_dkEnd!m|tdh15vlJCY|e|EX)O;~d9yM=Z5oS^E>DyE^D77KstgDSZ2 zCQx;9=hvPlld{&&KAn&JLwDT2X;-vwlKjOT`5t9g=M+El-L`(&(V4X(rhb#orLSD; z=*liyod5lCyoILcwP}6(Z>>Fb|L*Z0u_4b-=1qPQqm})w*sRR3rtekP9Otc9tR|m| z)6=(q_2$7#eNRsQSO4U-6K9=EFU>NSNc}c-$>-zM)!(!=jTGG6Hn*J(dJ*vagr~8} z$!qI2EncO2Wx<no`$4XZQT%q1nSo(@>jFiosjHH+RbO67OJAJ7BT4PW9XZ+P)sD(3 zUtUy&p0U-k(wH5}`ul2-_Wcj<*!$&{H~DNeU%hQZa`~PGKlUBpA5uK^^U-<pOHIsT zU)(xt?V&9G;`DZvm0IDh^DQ=So2R$^_T2TiXU%yyw|qj$Nwb<`>+9sc7<dOg4ljT6 z?dJL=9*0x^pR`EoIkPV-JLKi_EWaxgPR3e;O2$<aUNAB=+;;tPca?tVJ-wT2&Q1Fj zRQrv6tJ#Zn%SG*irdr18b9POSZ;?7Rb+_|k@$VKzr)qe;0>6dH)<m)`-qURQBin1% z&F?>^@7lqC*Y^C^jT)v!YZm#hcw+2%>gKW!6F>31`1ncx-V`p?mHS*4PWS2i%p07$ zQ03-YqZule<q}{1W|i;HoB#Jz_ns*im#iq%y0Ltf@u&Wxb8nbI{h;Klx(p0Emfp19 zD{bceaIw|Bd3Et?c_)cX(pZ^nb$h9d@dKZ@u05NN&o&8P`G$LI$m@UdnaA`?{`Z@F znV(`1ck#!hH)dO}X(nt)nXoVF@auxYV=>d&J!ihZGj;u1&*j@Zf(mNBPq&`7&&z82 z_QiX*IwmU5U4L6@?pDjVm|uTm{=KoiyVQT9@SJi^@0Yuc85kI<z+KEd-@X|uSFQ?P zd~kvFv{Uw%es0@)^yi~5zfV<$uPr^dUEHrsCF5fG>4cCgcV$-xt42o8)tC8vYhOjM z>U?iD)36l_W6oYZ_hH@lkFwbbs!!itxY;i%uy#hZist*|xwqCVYCctU+p^cMY^$lI z_4aGtlTLb<+dPc9AN8wMZ_bqXl<(7z-(B8ta8k*?9ew+jeo8)dd+F!Mu6?&9?}g5r zw&WI5Wb{+{wMSmc_E-Mg{JmtlxBRuhMDc$Yxq2p-PjG54|Evk>hjkra6}mbmmKii` zu-iZKT&T?cXQ#XEuXgrkWncLzY$P#<eUFudFPC@V$>&}()c$LP&YyZ$jo)9@Cp2Nr zs?SeFS1hnd=TbX)*n6w1*9@)m4C$wL+D@Mno*kaC=~MaYwSi@;z3f6Amz{eXc+v5v zyLM7Z{^Q@StE~L5iQQZ)Wf-m|-`YFr;EHKcq0d%qbaGbHPU_JrE-6_nb>2EZ;@{F) z*(Mn~_B5w%U#S&7Ny|?&qvMfUdGXGJD_(ruv~A^D&#$UkYr}tNxb{w6a$<MNr?8vT zSDg&5oTl{t$_({6?LWVLc@y;AH7!5*sAhWmuOL>J@?B3Jl|QxiSa^8d&+@ISpMGDv zD>0dofnkSe^WNo8<v}6x`O>s2wl}3?VvkPEvRN<uzT~dj`Sc0P{<L><NlnP&PW@J@ zC$>*<TmAg`$&3sKa=XCe$m_!Y$z7dudCB{e_Fj|L<Z9V1xzisLdyOHW(yetSmv7h` zm&n^96^|d;fM$>+LG6_TU#;q6zLlBIn|?D~E-uSv{jMa}{_@gD<^wbNLu<pH9v6|& z_V3%l%D}M05!{ejcm0Owsk`eQOJBYBCMLqFVo#FVu3c*w6)LBF`o3bTU+;5K({op^ zf<{)gAnL;d<{Ya%eASi5<6tM3UrDJTXjV&RF?gB<)C4LJ1*-!wsW(Uk9VBGfcsryr zs&S*y?_Im5G@eZhO<a}}#;UGiaS-Cfv>BkGh6gFzU%&CI{inXw?8|-MZ0@Q1qv!v1 zbPv0~CVGqMs|Tmeiw-Q)lKnN;hIz^dg+e(7h6e5lpqVlYNgl6R7uT0>xm}X7HA(&D zyL8i(Q>DD2bs@dtyZ)bevUW!G`s@$hk<njo%8Ob%2A1F5V93b8P!J0CuwLSe>$|sJ zS-CSxE=`h$OS0<i<B<7RFPd(;z5D-_gpfB&vgP-5?};_4(kOexD-9Z`4DYV}!obk5 zTgzs_A!e_6OAj%xvReFOrPrKyIrbX^zwgyp?;!dv{M_zc?_Gbkt$boU_x9q4n?vU< zomI2dT>Giv&0H;;6}Omp=dWE+cy8ir?~*^crc<<&dV-#v%qTOPR=4n)m1$VU4;faT zu#d~Ntd=a~*L-gKvnAtAmz?+3ZJPPhZT^OYE4^1x^_zZh#jIkjpD~k)%1;~){usP_ z=Y_o2&-7xoID0~4H|D(6x}m<ge~+`(*Zs!6uI!;Z;)Ua1Jkw-KR$cjGLR8k380E>+ z+s?myoUQ-Qr_s>rOPAC+?V2S)&rUz7E!|%TnuYTN4_&>}%3AZPD<po^#!RWtOU~tl zS9dSzdzq}JuUaEIS(2wqV)3q|t0Eaca(sWROHzB`vCGD$^tzX-{i-{%vdY(=yk0j| z>U)pgoGUYBCtbO=#Q3&p&NMgOpce+UAD6u`Yvl{|-M8v<$#Wyu{`YIIywT<A3%`@n z8?)e)@u~Zu_JD|a<fKVyW%AE0PrWOeep-8D<lM(ce6L+--}TL0;)(deU60<)Ka@6g z$(-D--TunrCoacN`c$s{IsERQRc8XDC(l|fBC&e+yi0fQhg_AM`|rW4`sbhqb1gW< z-I;pQebON}PqtRR$#<7si<)`Jx_noP=-QLsla!8~$e6TbgW##k>pQQRDn#{8m9<S) zJMm_@g1xHm^_#I?buOvyA$301|Mo8SuU%Q(6n!P)XWQxRr)%{Sx3793+&e?tldU;P z{l%FwRhx=b{>%yI7x<NH+7v{ps-E-O^;Z9+@qwR-=Kg_;4n+KHd3k#Ot3K6pDF*)- zkJ?|TwLBYoj?Zng&EKgOvFY|<r;@|J>44$`ob?Z^J&-VEiQKn|uOA8pFTY;)dg*-2 z|K<i^Z+$0S30U{y<E~`Sa^|mFpDkSKSGIah?zyYG_dU#7xp$V6_5G#Wy?(7)wLJT{ z&BDX^8lSK4`s~Rob?^3yxJDz1)Xi4&RTaW=d&7f3!-9D#prL|-?oHmWK5ppHPT8!b z;5O;ZJ}rB#-EUXFxUjCx=%;(^MTNLVqpB7Aj#$cH$U7s?^BA@kU~2q%;a|V5M61@? z=ICGd`w>3(#scO1R|n^>PzZKq-@Vi3sbQ<yY5OSN=b|F&o@^)0-`tuHn!dl@25P_U z(BA!a()B*cvUu01H2cswll(hAzv#SX^|Lj8+Pj-7C)1{0Jp6N4@|Lpa-Jcdq{hFZS z+7tMWPd0jWOXjA?(2@X8<2lS_v+i7%Z4NXP4lOw`^F`>Bj1zz3r(SsWXLa(a=<oeE zf9l;0Q#z>~&?}zuZQ{-S*`a;MH%3?QF{|J1rWbH3S<6}}J34=Lp6XHi1&f%^xvaPH zHx&L=Q3EPZ3lK9^v2X2CEyD}<e79?zxvL;3O`i4GDuv*wmPWHgjY8NKpV?>ixAC0( z<p<RvwP9-ctjAU*%-7nKYI3rC!Y!%L4gOnMKN*~~_xiazwAjyX;ivvdJX-e4ehFQj z6Z|5em2a|&fBjF_6<;=-dmHFHb5hy~b(hNBA*F6*v;QcketWz2%7w&LR;y3Rn1-Er zvUEnZ>dKW~&%dqM7QohA!*=q`<+H8ZzO5_Yxku=D&;DsqPyai|IqoW06kH#@`_uOo zYVm6Mt-TZKL(H$s)q1n>ht3JQV$rJd^<%WKz}mK=x%TUhac_z?P4QZOmh1QBPrt)< zK05}g4bwKnKaUatO_)Ads=Km!llhKaTs#@5UG)a($Cr##^trmO@BM#C9yGoB;F}|8 z2)-cs%%7>+`s@r02i_ij@d~t}1XSC^u!2$=h;@Lhl@E|Q=0NP#=^Edar`E1qU{U+l zQqops<;tLR`>>0SuJ=|hnfa-IR~O@Lsjolhn>^fYzVF=S_pkqOy7o-G8J&Cf6KCip zpP75|KJ<dd3GBfoLqYGK#ih?DPYQ`%F(>z&+x!6D`jAO(dOLPm_)j_+ZTLOTTlJ~? z)ry7NttQJ&TCy=yYO6=`<&^C&Z^W;E>c+spAi)8yT-G%^PHH=QY3E+8-<NKteVVAU z`TbS?w2(JTR_|N&Yfay}iFfZs%lDtV{BhB-m7mUp-sb=fh_I~AV`MmR;L?>VTPi<4 zo9x~#dddC#A!aR`1y3TiY!<9C?wY^q$jfv6Ui_<fMych8&JDd{(Yka6-il^YNc^Hp z`d6ZsALHVkzxcon?NyeEvtD(T-dWUe@DuOrFM-p&4!N)Tv!ZX^#QYt{Y*pV2OqIR3 zQg_$y`A@|cE^5}gv%XW`W73;bb>V9HQ)?IgGV+u%40nF_KJCD+q?@-wH~7!1^O{xZ z+8+?E^4@#jy*z!*-$A^oMzcbS{XC6D4I(D3$vt&j)!+W=)DzYootIM$zWs3dH!;?o zPh!m@|IiW-XZfIW)t@*6GdB6<h7~Mw)18t(L(A{w4%c#f?foC@_I>WkvHkz&v%k&9 zBTGCd^ROKj{c8uBlF|al78}dztG^z$%P(8H)YZ*RFMi*jHyc0K#tE5*mAbCdzk0)@ zw=yVw+v>fplWxtLvNewLvWT^3;rEwk*o`Da4BbkPuF|~l;pVIlu}6I_Of0Fac(rb- zS6#?X>p9}{Zmvt*Y?3w6sr_ZQdFp1Z`t3&bSI@3LHOKF0Pn631fZCag(bevcpHB7Y zl32Xs<fg4Bts^GwX`X5l{BNR>1gLgOdcHN)J#_B!C6ZEx{%(_({r7Qx_rC7Hj+5v1 ztDSxGPf%}_ekiD7a!9wobmFJ1Yh2yQ*2$~vRxg?9HA79Z<Xdw3bJRNV?rq^%yG?hO zU0As4WO(VkcQMOeeC*ooKQTFVyXEA7$^DO(f0KRgxoO+0$Nl#6Y$`upSm+E|^CNFx zx95E}XbM&oT&e3#n>uys#EBcLzP`G2=~Ccgx4$pk?V~m(9i7i-yI<XU`FC#F?&!nF zRb%S6LOH#}?C{#oSKg|Y{*4_H%8NZG9dgrn9^1+@bxA{pX_!~gO~I-1m;379?{KZ{ zd?X+6hq>0iwLP+Y?UjSmOS3k+=@pojMRzV~S*dknb(ajU)VfXjre6}%cc(iXZ`fvL z8aLq$SI5M&TG_jMp2@NAS#jHahlTHYt?-@lo|m48r+#|(cG70+see{{emi67q}WMs z!bEEq2^OoKObB?xGWX`X7WV3zMR{&|rDDRSVf!9_;+?+aNan5o(pSZ_48oqe&t?9m z`G_yK-dI~(`*hOAl$4Y|UzXd;nr4M$Wo1Q0MFj<266FPrf^7rk-G=NZ&!4Z4-u|xF z{N9Ok=lnc8A~q%+z3gvqTl3>Xw)EMADRXvCR;g@Xr4S4%_fO`%Ublbc<?P*|lcY|G z+QyaZ?A#{wM0Sz&<u5noMdws_CYMjGVAJ@dCz_&_(b1DuIb*k^ZqXVo|JOTQ)#7`j z6gHn1wT*h;FHk=J&*CpP<)`lTT`cyk%(K?>c=qG)`=Q=*--JcpPBHPGl)ob?tGas8 zy{?@p3p?t!915E9pa1U05VO^1>h6l)Uwd(}d%v9Rul@gj?>9C!))hPbzW)F3>2Xz= zmzH?0T)EPFx*jk8{-%?4prp_Ns%^il?&|95l{R0te0h3WT3cJ2Uc`n6U$4i{x2gQZ zdxz_6-evXmFV-!8BD|{Y)9M`;-mLz#c+>5Dr`X?SX#~4&>*6cBYzeB(%X4`=FLhK} zZQS_YtIg-)!vCu`Tbu4^Kb+gE_S0QEZ&Qz4__vI2a`F!^DVIA>n)0V(({@c2&x_^X zD>`rbi~DI=9IOnjo%u)ksi?-{_E+9>ilyIP^E;iaU%$w%d#A?3*T3HIOPM$&YTm7v z-fJw?8@$YCrcvrC{raD$-`?IHtusyj?+f?)zwdot<~w^^&CgG)++sg|#`^kjFfbTA z057h1!Qb24E7qNQZjNPOV4(iKA4x$$m!6%S?d|RT|HpBAznMl)Z#~-MoxZ|S?WSeW z+G|!<r?2|hv?h1eiD^r|J@dPL+jEldrSR%AwWfYYB(`38btCF|U$wf~sV8fHu$SE5 zU;g>D;B(V(&!FPc;|B`ATk_w0u~Nu=W#dM!uJG8x<pF2z-TSCx%4#)#DfjWv+OV~y zwLC9GR~+NcTKoE+pi1Oy)swfhJU<4D8oH^QSs5S9)9;j9|7X8;{q|ShAr%h2PbZ}q zXr(Rc;<M~tdE(-P-_~9G|8(w>z4`Ad(>?E26|IbpPi3XTlj216_19Y#KU=bV`F#8O zy0^Es-n)12yv=8yii#hLT)VgB-Mw|~T3PI3W(Ecx33x;1!L+NlZvDDf{r>Nl<@U9| zUM@G!yJJ!E;==zw=l}otJpccmijR*3mE9zIZT}rVdUv_bbFE(%uNN2ui~F5=v-m)S zXv!)hcel+>ZKvKW-sbl7T|n->B()W<di3T5d2d~H?nK6<_X=B0S0&8P;(n4isea0* z^3~7g)HsP+`TU!xWxJ-h`bxmEC6cu=7X#u~{kgkJcgosW#*4DnmwBZYuDaZ{GhFTc zx~U=a!j4Eh-(tOay;Iw%@(G`{;O!XJW2dey+Y_txFXZTajr#3cei}JT_B8F1->}y4 z=l==*E7(*|>o0n(d}X@k`{b+BSMH6pTlncq_zjM!a)BS0f8q`=a5A6HqJHAmqC?DD zwrd(Bj`|dcNm}`Yriad4e2i=69+AtHO^MUhKYe*`waLHZQ`yQ_J#Wl@x}SP;yKwDA z=X;J^vbTP}uT($%KKklq_q5HGUtV1Fo~~E>Zs+qh9?4DR@9)L`eH9K`3zV0a=i%WI z6C-o{F%tvB_OuPR-`0L-Vqn-IWj6cl#`QOEZOzu!(pr}ozZo*YUl80a^T5k)^2z9j zi&a<d^(<A*T6N{Y`klMh%vO7Dd-VSOmpK#ca{vDe{UcNT?#|Aw+1K~|d^TI%f1Zp{ z$_ZhAn~g<JPfeMU9rcu(f#E?Gcu9bHP*~WtRiUdVO`iOI|NnpecE4WSzW=Yx&+pv5 zz191F-+f=?b8u>Qe%LhET;Hsfq1BsToen8=OH_`Dz2+MnuH(Odb@%6W*Cr@B*L`S~ z2Q41Fu`$`-_Un~jUthcT$yio>c@ergY_4tfH??~b3=9v{62S8vj9lE@vd?2{{{4Jj zSXlV^`T6*bNk{LN->*H(Y~-$=KmAnSs)auH4suDaJhHw#YH`(R4ckSF^H17)eYd&3 zG3O^&>{Xe)dU}4!v76I;Q&X2FOTFBbdiv0zL+dJi7#JGroI#Dtb+MtLSFf#&Ha0RU zdv`}tM#iT4+nX(0w!FN&JpR90s!G-N{%ck<|CaLppT2XR%lk#srimT@xMQ|iZdQK& ze9PjrtSl{1v@|e+m+C!OWomAoe|J~u#YL`xfr01key`cS{rj)4uf4s!FJHc#erCqO znan%1<}qFudVW_!y#KhamR8l<t=Cm*A4}iw=<M|L_P)KVG`qUGdcHDfKG9ytmVu#Q zX^z?LdwZ+r*M7U%(b4hq^K)@=@&E72_iO9x-``c5ot3p}`SRtfxmni51_Vq{KB}#& z`}e7S{mj|3t@H2MxTozce;;>kD`+`kD`+Xlg8azHNJ&Y_)#2;)bag@1SX9)lE>Z18 zix%bGlZ`Cxw!1qabo<^D=g-G)&$}D{@6+_)<$gzxAJ>oE^kn7oc~XXtuGubNVPM$7 z4|3dv#e4Sb`TF|${*T9`Z{EDg$;sI*uK(|t`M!yB=G@`me(%T2{66vb@7tvh*8aU7 z<Ng26iHRA@moJ|_Wr~H++bvtRym;~A-%e`=h67JQm8V0vsHkXPbGEUu@#4jc#r0xl z%$j9Y`6<Qh#NoGZ9(~+V|MzwL>Q$>`jz6~h`DAi48*fo*CIiERZQ!V!la-zQ|J(Nc zkvh}(?S33Me?I@+ot-OJuH2k<)@Y{BIz3(q2R*s|-Gz_cR$qN(Ay@wJQ0u;Z`_}34 zGBDiH1KGagZfuXbS?;YX_wK#xP#4pQc<}uB^H-M|7}qXamiGDC*_H<k3=95))_WJs z-nFBp;O(ugAm^&KfGbD-^3u$P*_wKK+ah$tx>N7(t8HfIFVhK`Z<N}#`ZXx$>VN_) z&pI+PQmk85Sy|cKy!^_Fz?CakYKN`y@bM`rjcvGXUHR$BuF}`n*2PwTG?=-3eqGg% z4-eO^<7QyElLdBTtcZw6&aEw)wzhvipSSPt?w)O5|L@dP?c=@D&tL6oh@SAc;?C98 z;nSy0v+6q@yD`Z%BxDN2dhlwfyu#4X(CF=XXHT5Cv9mb6py0!so0~6Ry0pxH{<(u& z51f4#aeLmxi5v6o?)vrXm*-@)rAwFUMs89uFt~7aDI){Jceh3C3<uV(+_|&zc%Q7K zq~vV#d^4$D<Fqp#-rlp#^XGw5qBnD%^`E~S3=DY?A8UrKF8%-SucV}8_VsnSIXQDI z3X`IuZVCI_2nq;1cy)<k#jagdr>E(PbwB<4{XRbj#|-0izpSiR%KbKv9zJ~d>JkG3 zWJUf1v4i_!8>BV0v~F!kY<^sEXU2>ftlVM+HhK&UJBmPanLD<lBu7n6&2Dl1xNSL+ zMMaxdzh)|M^_yd{vF`7${r|qMU+zC&&a&vqBG>L8(Gm;{U%*QWwui*T<ZO)45%W$< zODie)a;TMi<^$#(ThH75*0Hs%{rl@{YHI4^<NfjbYJNUC+C4Lkn}K1M>mqiB2J4k8 zSKi!Hx%p_)&j-!?fByV=c5d$MS+lINujx!a`Q+6lhC2*7t(*)D>sUYow|NVeE=~RY z?X6gM>g8p=Z{NN(PCw`4>l?cvp>h8F`K!H|3xdJkdcg`(%{={V+UYZAwnXS;UthO& z#fljwnL$}uuOP))OsrHxT~KJ~*3#G4dU|^1T9>o2v!9=5YptuB`|Ha~w&sK2sGAO& zW=&8yb?Vfn2pvgD$(=iQE_Unn^7REJlBA?Xt6wucFludWl{U{Sk?EI~mj3<YasTFO zH3o+5x}b#1HleAh$#=Hd(&fwR5he1@qNh6wAIHRsH!wc=@$oTeopyBo-qL4hB;6nV ze=^yhPulFv)lx==hJT<u+VFbgD!v1z1v34+^X~5Y^r`6h#~t3&bUJ%_N=joH7#=KB zzR1jQAoa#ixdUG}N3Gpm_SVbazyA5$@>#QHK^tg4KR+)9#rJjtkfVOhzM6G+e|^21 z+p$|)v!$h_)&1tom^SU(5n=xi$MYGkFJ8Iw<>G$3QzuS<7Eh-c%><?MdKCtS2VtN{ zbNGMq)TvV^PDJdjD$UH)^nSu{M@8oeJHvx%pqZHizSE~q-(L6k*Y)^%TXl7HRn^pw zkB*+6rt9tJS5_L!kXJZee%t1xqg}h-@4F55<ZF<j2hIjT)6nUCwZGZ;<@OXjJapyC z70uvfJ9g<YY@fSkjZXK`NfRedoIU%sg`ByruCAu$NwEHG7f|-%4GRw5T=_Yz`{<{G z?D9W;{yaO^+T7H%^xB$8waF*1E@j-Y_GZquGiQ9dj~2cBxWnJ(ql=46%W7|C28Qr< z7k-8Y>BR&RSA*X!Te<HakIR4m{=FPrgm!_3#0z5e&Q(T&Ys;rgJSPVQ2T#|H784VD z_UaPD0)Ag#-`m@AL2LLw9Om~`yZq+n=IQ$J|2`b%pM5qhd^#HgLlr2F511Cc@t!(w zUfs7hk;nIiz{@s<f~#8E+U7YoCd`{RZ{|!%A)!qL4-Y*(J>7qv&CJJzj0_Spzy+LD z-)80T^>MX7J|rH$IZ-=&os4<joYk+H8l)fG*;)L4&*#3!@`cWAJe6-Y9{=Gk!@$5S z0LmiaOIEGQdVOuJq@<*E`8ysyzInFQWl>SLzP!9V^8nL>X-7;_7#P@$K#8X6@|`<- zl8^WG^z@vaZ7$t=Owu@Q$<n2^-)<!57_mMmD=1ujVQcpFu#gaoZCtUtN-`@dc7Q_n z!8TCo=U~1j?DfCDzm1KIuC0r`edERp3yz|He||DDGJ@)on1;uD7#So2Kz@0lqOGm1 ztepJy)zzg-mqJU8NvhsT%F3~^;tV_-y}iBf_x;ubwICiufyytBOD89*Utb%&J?-qQ zIdkSrRCd>k+LCc|Q|if+CqcCU+X_gh%c}1<FE4NGh6F~C-V6C4+qQ3g^eCzOXwt@r zZ*Om#SA2NT$}PTZ*)qSGMn|ufGB(`CR->mpJvCKRQxjx#Lo{ec=|NctfyCFayGW*g zch%Qdd-m8I|F}ate4USnM*%4N-f03mV`5%;S^SQIh3nU^U+vA@5Pjt6<HGA}B7-9% zUs}kO-`td%n3xC(sfK9wPC14Hv5{-T`1$*_U!IiLXI${V5R|#i`9U(ed%xYvPCqy2 z=TZH-i`C}Gg*JTo@?~@Sd8=s+Ya=!)85(Y^?_y!-=;dQz*ue?1I&ay^l`rT2|2hAD z)$6qzHf*?b=~CYEm!jYbGxO`KtL^;qeUJ(>*x$DFdTjaE`mGEN-Fk9vM?UUgV2Du{ zvSnzn*3{6LVO{=iWAgD^w{NTF-rraI?95DY`?af9-P%=}?dEpu++1sCCnveuFBc&V z#n0)k3=#pKK7G2jKK}nP>HL)RbnCw3p#D%hzx=ybyBHV>q(PCpePjOpeU+b|UA=Z~ z+t#g~Mzha?8vLKnn$Mm+yZp_Ki4!Moto)qD&)<J@bGm-~zCRD!<;`ZFU8g6>aAEeE zHEVi$dcJ)5GHKGJz{PG$!NAqsefKUs1_m}Oki)Ah-fq1<ulk+k?z?$gqx8*w{rGWa zwt4>RYirl8UCVF#<-(<<-p|j@K0fa?!-F`P=i;d;DQlv)uiLk;?$Q#^%*;&hX*!%d zJbNZ(`_Hv9EqZdIZiO&ILnCMbrNM=*TejGIzf-(^|G!^P<t2IA9v*JD|NrN6x48bZ z2T=?K<$add#kx};AL|WUeYMc$-Jw?Q+S=OcT`AYs#TGw1Q~CL<xwu};jrmKN7{KYg zfpP7Q9ToTXRJQZW?<>i==c+dO<->OQd%H@r|BJIR?5JF|diD04n~yByuHV03e{PPY zt!)4Av-x$Ozg~~ue*3NcpNIVMRWDT+UwkpCiIL$&x=Iy8Lu2;;e}9XgpIf_fWns>o z>$;OqhD1eKWn5VBPlt!$f_+z4ms!q@1aRgM7Z%=}aIgtdCR^C$=H~KpbFW^#dh(Np z4-Io~ZP|Xm&RRv~$Wm2ih70nbgvA`<=61~ZyiM}fsNHktmQQSNKmPyU`~ToQA=?iz zF#LUgq*M6y_4V<a(|rB>{JgwQJv!PwT{n8#)Tv*8JnoPGBiws4N6x0=!?xVp?{+-q zyB@~PaNw-lBK8I5()NGPeth(I-8!c2va7Ft`!~N&rs{u>3jgN7vXd8T{TKJVeS7WX zWcBwqH!qL(W?|TIqLG>X+M3ACb$@?-`t<3?j~|a7J@S5DIQwkc<dah-PTZJqu&KNE zk4<y;zwC8Kuc|T}=ye2Hqo3<}ck<qYS3@6cEB@EA>U`NAQ;F11ulA)o-I(!m@ifWa zWA(qc*MI)-;l=z<3=DeL@7>#%dV1Q?Zt?Bgx0nAskzn9a_3@~9{kP5YEw^2L{9H0- z%irIBeu^K^UG)0gCI*HbG2mrhi{^djm;czj(|*Uvrwj~iGLuh+L`P?DzNz>BgkkE# z>-+zGeR#P2`uccz8JRopuQD<eTrLz50S)1QpFDBm!x??obyr{Am3@6(;p1besi|Mn zLm3#pfV&wC40+4eta<ak{(tp*clE7Xx6ZXLe|N9?y=~=+9rwAIVasP33XET0U;n=B zWUjc`?6n&=7M?wCR9x=yW<DFkj@Av3tup4DQ%+90xj8*P@p-u2uj&5h_T_Irbz*)U z1H*Q%e{<PDOWe=8fI&>+^9dUE^KZ?L;$vX=+Z(!_;X?1TtXPYcO+Mk*K?`yi4y4Xl z%zohSmFXJg%TM*4c(V4y#;p8l7ndxN{KQ*aw&KLK&fZ<$<DW<t^lo3Fd*$T*llDP{ z-|x;~T$^k4ci%0k)a>A=nOjY>e&ihW-+SyL1H*v><=TI5{|~DYW7uIj;RR!X{lAM{ zQmZ#9cg<b$#9d|Or!9Q@*PXO~apmm2?{znAyLLFMn`xHZ;FUJ0UR`t8<kA0)<@X;3 zPR;y(V88L?d(umsg%lbcgq)n-PiV*xa_G3xu_&mlFtxC>H2!{g;QhaQm0s!XTFtbG zV~0kdh}tD5(}kQ1TLpwJRlm0luB$(z*z3tC<ag?Oaphan;%9Tx-xc@0t}HrVZ12y( zU=s51jk`hdzW<=j3oE|A_V@qqci#0T!_0Xa3k3yv1J>+PU1YaXN0uRHZ|n9nzZIHJ zf9Glzt+{LXHvfY8{{P>yxh@89p0<|U%bsuW-%6*AYyDTBgx9Rb$A9Pdc64-9?f>`X z%ljWOMacmY>RvG}F3jS_RW4W5r`~B>sCs5j%l4-)FPOIc`#bH(y|pH+R=@7ve0%Mp z`@OBtw);(1y!?LNw5wVg(z}*xDk&+wa{K%8<^6*@MUFjw)}N~_-O;gP`Nmh%I)2S- z^9p%(sFLf7mPS_Ktfn8e5@zxf90J?d6z`}NIQ;CeE(1ddm&jeGKXyGaES(}pJ1-a? z+)#OT?NzbG8jPpdMAQ%Et12)yTndTU<*1Z<JHc0Q)47E<%+1FSq^ab+X^iUaT<@Ut zdWqxo$d3E$%*BbvB!k<-(wBS{VBo!a!iwEic!kJ`-CW%ZCH66}nisqlxA<|`mV@EZ z_k~8>!vF8&Wt$$Idpst%qsijM?1dYpvP|2~y-+a#c_^g5>eu#iz3p|5&m<Wv{>r)O zH#gfeh#XzKjKiqb<k|u)ek0qSDw)!y9{o=5RDFJNcjYU-6tEFHbZ)z~zJ=h$hC_x` zE?2&b+-JLT!lpSn|G^vg6CG{Gl`Q;O8DyCkW@i|C-H2Sp%v`LI6%gEUFxenSE~wu* zP`xH<QqK_%3*VNx`d*V~Z=b%DOLcp$l*y*Xs~l679<0$Q(mPmfsa1R-;Hpe?HLsQL zu?a6ddK|9(+_wDkJ;kj@ckC1H6MkUAsrF6de8W`^kJ1D?k>0BtN|+g@GX1=sXu4?e zHLG6B_gq1J$uD?r^dDYu(ZlwhXM&51%N0>j6yDp}6T_0tf8)1efw0V<g<%iBIfgt< zJW*odci@5HiQdMg+6)pAPVVx%)K;8ooN68O+)O-LK=5Mi0|{HDSJhp@j0wM@4K`f( zl<6w=#V7IFqx27pSQrXsu`md6UeQ`1#mH<D^6*&wgZ*q1lwK;#QFA;l!0_r+VDzOJ zn@h_Mu8NU}TC630Sk5t4Go|W+v9Mj%dPm-Vffb=Uz8Zh=F{toSZ(k9*<CpH8<^}m| z3|~_xc(m5lq?UbteQ0*Tl|#4oPQGT<u~Um*bK;B->K;oN5;9snUt8OYgW|L6-<L1f ztMs&3y@Cy_LMmq0h@4_ed}ze5Rh1#Z(x)PNBCm4xiYW$Lj!bxYx1_VPgH0>#OUH`! zfr~8!k2P;u{+VG)`hjDMLu)fUm3-zd$mU_V+IqpbZJs8>oqwX+?yb;uy_6WSBjJQe z;{Qz|FQg70iK}it%6Z{p`&AB))D>qMS2C-V+hwgksHQBwXrWLi`>fvw-^xz<C++ig zw)N{-i=@vA6+M+SC~oUxT;O)C(xWut;U&*(*&}l_j!$^G_SfrK+_zuu6c7{)4F9rx z`Tx7mgJ$t;b?Vq@!@SdQ#-HiW{ub*Wu9z@kLCETWX-vt{JaV=Br%&qWh)TGsEBMuL z>duT6EmNy^TZg0^N=y07>|t3BTMH2FYJ2L^?C^ALzlN>tA9iWTRV}+<+H~Dm!f3B$ zy1LII^^2DlY?4dO+)&Uuk(VJPWviCN#ajt(CEX8H3izFJHKnwyI~AWN702&1Vn52M zdyFTIYkjv+LIx{$xJRjV*4pM7SGA@rHT&;*A*i}hP*5;%`LD~D_fIbNY?!(E!|u#y zkvD!j9)I9>=H`jrN<PU<3v8IXsw{ldmN#{*s5V&a?o!*c?8&y~uUE8+6W;c<Wj)Nz z6uP3d@b;=O#qUOKXW1Km6`6z_uH-s1r)84xR40oiI#2z6zuLw-O~rZXkqg$PN}`bl zr6S8_WUfCr>Gs)!3=>YYc&1ocxCFMpa$4x(y3`?$=gO;RFN;<cC7LporUqyR#Ph9w zxMF=n)YUo$*&{KWsmeTSXCDq;ZN1Y1ltos83d{#F3?k|W(o{sg251LPyJT}<!$zr0 z^#$1+s}ln>85dXx2Fdb#tGbZw?cySJ=7nIOd~g9X!<ji->u&|L9+SEfzQ`*6#-fu9 zv-nvXmK-kNZdoYG@M4z3afX}wo!7c0n_lu;w2_TLDmyTg;q*fd&$dPTa+{BG8f?sd z#}fY3Ny)LY%AGe%T;ZSl3Mod1wN9S|cbpMqW7t;S5yiP8a8k=IBNf@Ej|nec9IoMD zFuAs1p_CQdiH>6rF0MG$+G)#`=b)6keJfwmHS^|ul3e**@}bX_p9i^v;|7$r>e-(M zg}1$8nqjrbfKNzr3a^H5TU6^Oo+JNxzAKnqbGXj&Gn{e36SFmU7cRd4IedOcM#2M| zDwiwi8d(#Id|vb{o7?a@CNXN-w3I4?EiQ>NF=^b<Ca059;v42^>cmE`Y1BUaLcQR% z_>=h7R_QiYr)By%<_7Myl0LEvk{ME+SF?2sB|N|Ur?g6K#i_#`$8Y5ZENy7j=2=_t z*?q;;fNO_u$({?g>U6v=p|@G!JF}0hVVdM6zk@|HK4k9<5oZ(Ip?iGBaz@TCJ`-vg z<NV97M6nxst9;;eK2-N4wy}}bNA`im#>LAzIyzPagG#%PJ59oz&r7tL8)g|YROq-g z$w*$@Ak!AutvJ!?y2Q~=iH{N@r5fiO(lt6dR_yk;GRyFqi_5J&^$I3hAKf=D-cfJr zYOz_+dD&rQmp1`&4qw<MjHY@Y$~3=Q`|^KFOSdempy1c6+Ku*ym)G-K{*wCtPjyjU zQ|NY=EAvIw88YTwTB^TF+c~$;UAqyKx9txvw-*#F?UJ-rdUd{Ny@OKY(%Cl(Z5kfA zyqJ0DNZ1>Tj*gBOi4QN&@93~P+9N0UHF{=xf(^&Fx)b}=$~3-ff7S`=b6o54jdi25 zqLR|0_9p*&C8bwf>v|kr{!aTGvQfDr;au=6_4#T_N{bpBAd-C-m6f32mG=x}PDH7< z%U$K~MtN<{OBomzJI?sQRl?KKzp38+mu86gp(A3-;)jcF)NZT)t<dJvdio7J@79Gv zRm)`G1{5%Vv|qT8i{Xop;iEu{AIk5gg8CNiVqo~v^H7T6xn{uX33XB@-4kCiyiZTe zSZjN3S-y`|%N5~6#}4?G*XHX4^({1VugJFHI98UiqGgq!*}Q^T9JQZ++rM6N*u(bT zyYTYGd3%CgTwM0L^xG}2?r+PA`DL!QpRe<Y9DmNmok{);9WNe&>m#{uj}4w_J}mWB z%&XyF(Yn1)_`z=_h9CP%=D)OIu-w0RpN!;1eyQ|a!*g|4PTDmeKcE{>k(<QMUeB=M z^T89xTYIb0B#d~4G?!Qv%;i>={$a!Joc*?N+n-|(xf2pD{`+2)_{i#o6j#3bUat8D zKmH4*o%85C^0R)?vJdzCwk>_wZ?nYSY}ac)K|#T<a<;#E-q{xEE!rjEy8YeT6=rj_ zzp-?5$nk+{ncFw2m>E<U0wk{6Nboi+6m9666ggMQNI31>+0Jdh7q2)xHUC1y<)8D) z_Dwj&us}!j6kForrL#Z$E)JEG(rWGH4K>)1VYk(+@ZR5EqrH9m!j)Rrb$*Ci#mpeo z`9ZkcIdrvmm3+w;`4=DbUQM%hb#b|J`^yXCUEu-Tt6!(h+u7dy?%k^m>JBbn3O2l& z*0Jm6hDr}RCWe#l3D0=4%Nd+zy?5l1YIR&Jx1#kISIo`6SAX>0uF2-e<`=ow;??+w zh36X+Ln!l<QU(T7uKa_AHVh*7MC|rjpR4|LOs)L-&KLJJlUJVFy?vR>#|PzI9UUvm zU%fv6qHn6o!gV|hUBZFEEXuRb@n5`kH4z+f32yxzyJki+tol5moHxrfY5(CP_J=QQ z`Wd{HOEU1pULNLRlPeB48LZ`b=CZEjNzLr|>-WNoZ#MgNOO1}hYil<YG#?F6apTb4 zGLw0o3G1#lgN^U^{9SVRtnImC`NL-<7td$7;?eJPQCA{r!9Ff!adY=<bFo%)#svy~ zCvHAH?sVTtW3^^a_PH08dV+i>JKPTaduFk<{;}-Wr#pTspSqNg(|z%Dg3XG%-ci9i zdkp06l*n#vseN4i<QT_%|6j(B>fK5i&&++e(Zl<(Y|M%uwI{69-<W;Qz4M22siuLP z4$IAt%X8N`9Jk(n<(Zw3px{@|*c!L&lz4}GrV=w2>+m)oPxzrc;RJ)J(fNf2d~IPX zbX#XC-(ga``f^45ldn8Wf^_ds(s2Kkf2jQIt%e;1Q<f*5;E~`zwswACJR`%kcM>}# zv{>`xU2-}1%x~?STi{WrW8);SpFcqPwalI7+w<Ps{doWGRm0MZtHKvz1lFqGC{%Y` z>-H;C<f!v~8PUiUnk^p_d@A=^zmpUUtUtIaTIp5Y;^_y^a56|`7yOM*+{x2>n|-20 z<0+XRHthSauF!M1lz4}Soq=22!e6w^xVX)QEjnK!>hNn#p1C)-C510_@KQNf%i<lr zBBY}x_Q&$(Z|?SrKBeplpW<7dL>*#OIhFXD_q@8o)Q6AuFUS%3CTSvN6w9Eoi*qX% zLy`XB-;oQ;wyFrOa?_Ar5M<)dYMT<Z+G1;6^5iSR5>Gf?Wlvoe{2#nqJb0<Yr9_4c zrcK!m8v?U$B+tv~Q+Y47XI@jUb(iqR-{~1^@^0s_i)USVe8F6}?6eKHG`~hx;Jm(Q z`_g}zv$ZdLJeTnw92a%5^=`~NHnN-7A9-LXv6n~fn}@Zk$g8;fz0vlE^K{&F8>1P5 z{2zQjzaXgOivFZiTk5;33qH@;xt-rJu)8hmNz9=Kh7xA}H}tNyPUQ7@laRrAe(Bkl zd)l;KNE}FPx-k93z8iOxFI|xOe>ZlnnQbGV--gG2POl2@{1aU~?a=E?pGsNhbejiz zm6Tq!&$y_(=$-o2qc@(n#znc7tuC3GHqjzh*&}7bORmqapT>*ZmCn)dF`iy5$Z*Oy z@g>_zy@KmsiVLeJ)`;|$Hn^<dnt0-Y@HNlhxmQFKKkF1cFE3S=z7oz6zxL-b$Hj~b zHi|7hxk9_yg(;Yw=NlVCs&ZHUVhhG*o9L}KKblnP?qolhx#>c_p8xethrizKxY>01 z{UQUtvSh=bp@}ik?1|=QZ`kSxv|THh!@<xMwZwgE?w-foSGV|Wd_Cux!fB&jUm(Hy z_O82<(xQ8B;^tpuHJ?x|$-vgn#_(B@LE)<7J<*2`vn^w8=v{S9?VIo>dwu*BNB;$x z=VF$3N_-cJd7f}Zh@n72|4qys23J{zE7J}gTKco6Nbg{w%@QLEe>MhJ-A{Vv^|#{w zL~VV;SyIy^TO!1j#HjFECZu<QhruJm8$DP4mAbevi-G#H%3sbt{5<Ev)zdq##Dp4V z8M@hU-4|yxJ!RZtxAfJy{sX((HhgAnIAmcGru>^pMm-}xelyqXP5XY<U-eq@9~6jF zmU1?~H+gEX>)4@VYGui-;;e-y_UfpdF!8?6q_L;7$%04j@=@<g)6{}jo;<i!=GcuR zwh~is9@4xLZt}nHZsrZ&-t12$3|gCRncX|eeO2p3^`9-;*4xYFJ3Bh6HdoiWWq%50 z_~OHGAXRMHfAg5M#RluHmUW8ka${(zw7>OQymYC0!YhuIdTsg*R}B`XZf9T!(3~LO z-K7)JpRsYf)YhX0QY;L9!7cx0t7WdZ824xHs~;@0@7(pg@aNog!PXc26Y8QQ8a-TG zbPMHdm0oE+bABM%C0)&6a(+dU2}hssM8Q_+>V&t7Yt(N~dR&nb-{94Grg+7A0jufd zo4>n0i_~}(F!8EQWB1Ps=Wge(To+Oy`1SuR^J`+J`?tw)#yXo^Tl9gAXYE5HVFsPp z#EjNkLL&ECb_N%#@4GEIBl(I@%za*lrJ5)9X?%HX&AZz(_@!@h=<WV@FP*;5`Swm( zP%tpRZ2kF+tx*+sBeb7v<2lnPcKL&8Z~5gjKLU%NZ(O%E{>s#O4Nulhly2U;AiL$5 z)RS1Zx!P?$x&KzEa7I3#Si0}(zp0iQ-mR_L3?bqf{riLG&P%9v(`$<AZHl-Ou3*R{ zc~N5frlTpXE-ptvZ6=N1g)2@u-|}2B<<PWMHb-hY+p>CU8Jpb}J}JBHe5U<Sg~2NB z2|}G0Pv6R|e3BH=@3Kfn+{{_2wUJfk&qJ{rmA`dORrefQpBq|n$wljMf_}>XzFkE( zdYfG)f17mR9>3<qj1?_cIdt7im80cv9Or%=d#CTfg1`&LZ*AVF`8q%3S#ztd#9w^X z^DU70-&tMd7Jrv9h0!52Z}qw6iM<AWacf&#*moG`+<$TINlDai*Vy-*TU4$#&eb<M zzraLNt?bYVyWTh4Gk*3>Sj9Y{G;W5G>gS#b7cZM%m#bfHWqa`33yA~jJWDk_dK_HU zUY#oV9o`dL$RF?Pa^*c}L}u6QT~~KM<c>OPGQEU@_bNleORfb!)n89D*<bYf#o=qa z@9MAAcKsK6WqRVTXpS2lFY^;`)Oak3&6013YHjnHVZ|Wy!0+vHx7qT&t%ssH=ct+G zmwXV8%eZ#nE!SCdEo*IG)?0B0CU&<zx_K;0MTUW)d*R&nwU!@WIXzr^^~1LKOGmk{ zUcR-vAJlxi_}6Z+>C*KKMvG=|HxD_SHs!;vjcg28vL3pg-go)#-$m=buxz<hl6K`) zSn;K+Qy1>rWI0#8W;YANr{utBo&|S*L|?jf_2ntftkPU{hKOB>kF=fk<{pkcT_Y&S zTkvOdXUDGIW!jO^x3U(yG#UCIJ`z^3dWCqLitM4c@fQO$_vr4rddGX4JbR}|+2g3Q zJJ#d~#AVdo+PjN+=X6HStggV=hFwOA>Q@VY`|iCu#be35hLyH5$C({&ajLv=|HgXc zZLamxIZq2-%sf=(@;NAvfoE;vL$1$?x#7jTt<Ra=*O<EP?!uLiwR6H3Zw$L}DS(y1 z>X*dlDHEQY+TFD%+F;vTn>SCCS7^K6@?<dBB=}F_g3tHGKiBo?hg3Ue9gDhmd%5hp zJNIf;l$2hT$~};LYs0#Xk0GE!c;oKC0_IHhKneEWg-&^^RX7>6j27lJblS!|H>-bp z_wORUDkk6a-`jSp-C;;b;x|s0m~r^j-pb@xoQVo?!nMYVQCqoIsxxkpwzqoy3Q};c z`rLZem?80${n<q_E-qJGwj~~B+nB7d=-%t?EgyOw&7S+7{Yi||AODOsj)^uZLWzPV zyes)~+?2i>#iSiR!k4--V70>K=F>hiEEnp?{z@|_7pv-GNcpwmMB8bf#FNGhl7YI{ zR)-$WV!2fBoXmU0>q(r`v&a+|#otUmZwxC++}}#yUZlf&s%pj54;+nsia9ol6Bq4c zQr#XH+@lzLn{W4IkAQf-Xnl#>+ivlh@~pizZPy*y^x647*1d~<Jd>4LHEa5{wc71{ zc1hnCJUe$_SJUei+U;Add2|+pEi_?e=n_t_V>uVRwS8`-SnpMa2WH~t|C(Rb@JO-F zH+UhT@Uq~u{?F2<1>70mou0<$o1ZwAHD!7Em(1M2)!G4*?p!?A?6$R9-dguqrqPvK z#mkNh$KIXY(ZRN4-S_lc!9~9t=Uo)ieDilfj!Uxcs-lYlt&a0Hd}d_0z43yf!@trg z%NHu}ZM*lO$}2+C>G8Wd!3BGnCrdOwVo7XYWi#W}b}N?!Z4*mBKlt0ie8Q^xmXOIc z4r%FC6Uu~CJDsMj)e>h|)3#l@e)c-Qb4$0?F8t<a@Up;tE=wx&m!5zM;mYudrE-3g zA6T&qovgjLZ`w5fn-_T33J88>5;ARf76|-(&t5=k>W{@Y0y6@GJATZ+eePdcMsH?* zmq@_-g0jg5<)shQHafqY#lFA)^4;nG{5>kRv%9&t{PkS__PkAvXygS`p{`c;WsBE; zd>^m$N_~eBo8VW^mw_7R4?Nj_;0PbXl-?6RWi^i<;amMZfZO=Nm!dtOJZ-yHMKUry z(Ui$=@`9X}n+$%>1qHvVgGNE-hg1k>v1V~C%x0Nsm&Fx0lev2TIsP~IXQ?e%so6HM zcg4aI-uIyTz~9@hX;X;EoramhUwW+X&+q8?#RBRi`G2b9({wNVtgi8@<&hw}y@j8U zwNBttmqqW+ZBp4@e{@5o!A5b@1$qy_xh7LtOu?3mcj^kwmbvS1Toe!tG*5Kv@A#!s zoc?2<Mw!6go@j+TOh@@1$$bPj{!F;9Z(Ds+NHEY|LDZT7+9Os{+Qok6g&+)kRb8`7 z6)d&rpZ;^9XXod?fBW|B)2F6sXC(an{h67WH#RFN?ed3d3H-l2pRJntx3Ie3pV#sK zSFK)s`Qk-MyP6%-r%zWq`26kLx36AlP2JSj+wqGn?Mnw3toXmV?0DbxGKK)HsV`r? zEG#TE&%f8x-TnLD@Avt4cP$NC`Q^)(Hh%ec&!3xDeaZ0m_ph(7udc4%xL8f;QlF$P z*m+7)4k<=6XM;d=LBWPJZ)fMjZ*Ol;PD(Pd+;?`i`SWMbm^N(L^5x5yoKqiv{`w^) zE!{0;EjY0OuK&W9FJIjH<!r0IyjZ5Ybm`K<!opcH@jgChzP-J@di83?8@F$ptN!@& z=Z{;TjOOH%N4V#7u<614&=Iw9%a%E2xwp1tUN*^}>Xlkl^y%yC>&eN<`FD1FyzFnE zduxm5(jZAm$;@N#GApX9r6nahr7Z<{1wbM9RW(c0YjWZ%me|8`f2Q3M61m&-d5YX0 zE+r+UMRqP~lXvb00sYurA)A*jTc)O`=QsH=Xr`Rs{!c()pyK3{ZhbN<PrmDwHqU!= zW22au*dsSTm%pN*mf-Wyr%F#HKCM4|NAh2`;#5Y5T+SeWh2Km$dmoB%2=A`W*szgp z`u4;}yYl*s->OXFb5=S$Lp{-$>*ex^H7rK86)guqCE%3hkFT9?U|Brvz!}eKiCJ#T z{%p;4TdyVV*&ZO#e=zQXsY9|X&)NrK9I}6_`!=uRdAVQlvrl>2m#P<&KwUoRyFWC< zPe09-*v)jQ`j7DD_hmvoJw3<z<?ZYK{8*-IX=!O#4qAJrug_n;s>F216*j?AWl#n< zZ@jVn`{s^6+FF|mteNDv84q0Gde^V`o5@YL@ty57yB87%3J?8t2@>EIu9mo&@&8Jy zSytD?&(=DzikDlX8CG#msF!U%?x4iT@Oh!Z#^V<x4L0UWy9J+KS3IF4!uzq>w}RR2 zhbn%wa7GL9Jvde_@%xbN{MJU+IqJ%v&)CY}X#BlziHnO1vx~XiDc8Uv>7$(|cCsw@ zocsRHrqfsETXFJ%f$!?vCr_SaT)WxP*~!VzU;lpZ_bXYYmxH9G=FOWY<m*16<At2z zVt1FnO)Ly;`Ul=NZzyP8YtHaOf@#O|5;=xW5x>drf3DaRa^xTT<hZvP^3x+v>}#0g zT`-fE!8u*wJy(%l;tL*zfYlcwbeDXNYP-1V>9^fAo38DDc>AZ)v(wdf+>KxA_;Zf` zjSW&#TEw{2TK*}2?7LK+Z%)55E&N=LORh4DT~>F;^Mc9`CMG76{L`mTCnqPHD*xz{ zwf^?L{(tn!kXbWlR#sM;s{Yt<j!m#s*0{>$%YseklwaGp={Q`goT8Te!e_@hQM*&S zn|2w!kXT?MTDEV4Wak};6qkdx9IS;J{_TtSl*Jv_I$dK8NjYT8QMQjEU~2cC)fp>X zd=2k3CqBEf)FUQsu@SrZ;lx)L$`-`T_F(IEa@0xs&%D_2Lo6e+_mg<%LySGqtd9?# z*w?V8c*Yhvh6Qeq)`RMl(2%Fh4elImKG!cLr1FJurOa!bXLyHc>-?sPygD%xOXc)7 zGjP5-rEt~pTczUSa1s7&e#L~XyDWRmbeUIZIxUiUnz?pene^0~1{-qfZkx%ur^Gs( zbKSwJq|EhHazjDm^Pm^Ax92{8XPo=KZ~OMWPj{Al$oH<EKC7eSh2jg_zcbb5+MJrp zpzz;n)n~=4j+Jb8m=a$xFr0E*GPh-(p;mEX0^jwW6FhFe{W;^tw%nUn7%ity_-oyE z_VC+ggDovrIaJ=Xw`$u=KXiiaDCZ8zzQWasHXa>ocQLeGlX%kk`M<+MUY>7Re81mu zM3?2nFh_mey~XX`!L=v<$$ovh0#wJ}X@384ntjQ$XU}w}-&(P1m6wOdg`Nl9ot-y# zm1f7r&Yd^!-iL>W|3(>@yg9jZa_0*D*Y6S~TueUP__@GHI<)cwXY=*V9(G)=whSiM zl-{xLIMa4H#lqk5Q=*58#GBSrGE>qI*>VV9KUk==?rn<?fAaj}9mgjKY0Au~5jiY= z;4^0g@A0d$0h$y4NuSHR^vVC^+pvQbc8t#2G51-gE~<QdcOrwt8`kG5156JcU}E6W zc_79i9POcEAlGwB=HZP$5mS~P)Mb$4R=j%f&i{7B%UjJ~*o6Lw-|p~s`GSWJ`fmw| z+-Gapqg}x7RI2DTiBaLX(3@jiySMTzPCYFZYALasDek<2rO>Iiu<!+1{7X-ISoK^< zme{)EC)bu<ch=W}8s{BO=2qA?pR9MRWqtH*+uof~=eO*&zIX52wC9)Z*}aX;0u2f; z{{AI>*DsCmMK8oo1w9nwn0~W?Wu<z{Tw(qLNg8vOCtVSmqN4oQe8Jy&=kMyS4&5Nt z_Nipb(u2PxZ~Q)3$(2*PAnfkS$)-mx%sl(jh9UC#0~^U@d>hK#Z>@axHcC0?=Els+ z?=MMJvd?Y5Em$zGDbRaC`X$}}Vm2XaYHD?Lb%}|Iv(5AS`ug<r_4_+JfByM=KK<;h zsZ*wWxfY%8JKyf^ojWymb`<LG{c>q~d|l<wPfw2>bKAIBZBblH@|TVmj+tH2xi*ZP zYucRGIytkJusL22nDHcHsY9sVs!t3Yo2~i338ndN`*`4Oe4-@}gU{Q*U?zs2*8>We zC$2ZIcMa8RJ14-lsnlm#_r~*&52dNRIle;mklWgc3<Wbg&t!<)Z`*49X?^ky<wIq* zm!GkP_O8%mx?)h;;>Ed?Dd=vQbk3r$A}0Hn-u|WVP&{RB`$pZ8FAohEJ=-VN@*Oj4 zVA*x-Z2K0T#k~jbP4Gytl*v+kr5(lVq2ud#%8+5kukaTVC35|bRbEIrUguDjJNz^^ z;M#VrpBL+dZ|{8kHaEXgPxj5?uR+3sg0?bym)l?d>R$P(u&2VO;`LXP1#Apkg>H&J z6l7u$;+&(V^iv}yjq&Z5nk`%AsFw)6sYx*5aBF5bP-=Frwy8^JhUG$qu#AAk3#Eis zUTBxJ5}v+&p^50UbqrhFZ@2}kFWh^=`h|_etp~r#B|a~ip!(+WmoHzAf$GaUJH+E_ z1RH`@`uO<lDSCQps&=?u>@E>Gxwyc<#Ds(gj~^TV<KyS&UpXbY1XACxu=ZTy(0y-K zqo~n&r|SY~=K@x5dAt7dtF2L-3|Cn<d_O!x{k<_8vv)<iVj8zjOmxl_vCes#ImeYg z>zrwKSj9ba+n<SR`Mo9;7|U3>eTccV=TOe^<<|~szIc(m!Ti%Yhx07o{!Ms!=$!b? z{m$1}zCC{T*2i@9uT|0IeRG!|IKpQbJwbx;{L;C{FCV!h$uNaCSN-G5A3nG5eDvF1 zzQG?-ZZT?3y;Y_7R(Lx&NJH~Jzg{Mq_F8*knA1&-KL%+g9A8Bbxkpvo$sWC_6q%C5 zKYOBweXpUv^U|EJ(ka&>m;6`jS$^5WUNhy(7PlMo_>}T5J-b$6+o~P^_>KFAI<af- z=5D#a{Y1*9z{PI8Ql_t7E}wrb=j6$gmc`F}N=ix~O{VPZY+oOrnwpv&C)h4Ffah*R zwsML8Z{4V!kkR_8soEmoItS~<fYt9xZe3Y%&b?4+lYYj{$|p(@y&1bNUgDMG7W^Ol zd?L@xw)^(3uL>=;Y(6n7gk9}h!91-c=dJ8bOLs3%NK$|E$UttVp@yG`SLPfwrPnf_ z)|Ht3_dfn|qnOTJgGYfXZU-*;o)9XN>33kN-Mo#N`TcLTd+ck$h5J8^si%scpL2C_ zIq|gUb)Z(Wp3Z?)Q#Jn1)U!KP+8bEHEv9!UF!ZOv#@2n3ON>IEawW4}Jr(wJWBK=* zT~|CA7<Qa-JTra6w}!JPp7nxOZ74lB{Oqd1qwk8ZZB~6w%vo*gbTC$ScAs+o`6Kqq z|J-A4H%7iMooDjqvW$$3lQRe~nwXiz?XUa$=xDdNew<C|t0`#{dmWqEGLOCc`TMv3 z41>fE4-O`^`?%Pyj{k4o-yzpE%|0x<ZpyWii&9#FQ`=`Ly_mVkLXbhEwEXLq5QYUo zPFlio%o1-}r+D1C!94wDfab(n#yrNkAuF#;Wpap}X<*93@LY4n89}SFQOXlvIw>{J z6h70w$Y^=!^uV<O=UkPXE7iCjCuDHi3QOGN;9UPr>WaCuuV4x9*7;7t+U62bhYrR^ z?6`JCFwM_E{*u|`t42M`rj_>0vcGgjbj3d7<OQ4fF7Rx+eE7ml4R7~9{szTOA0O~N z-g$Yxo`3$l<^DUwU!BWOI&FRL-hNKq^Glyb?alpmv1(;!N5?zQ%*>Y$54ZEnSQI=t zG4ax+Ab<b!4<0<=x;;bX>DoU2H@tsmR@Y9s{af)ZOG$5nEmP{t3&w4ox+*~yeoo)s zJH@T}QMS4=^ZmP@8M%?Q%Nw?<dWX;8cf954Q@6G<*-a#8Z?taSYa`*v=M#!#*u=}V zU~2*5{ImN7GTz;IF>~9i4;j6Cn)%#*<x6a3Q5IMHFEyq2ug&7?lh&<UmlktxmT7i@ z`oZOr`^4qs{{8#?eszdeb#=A9{r=3$%Y5frUA=$*{(%DvE~j;_$e);dV}s)xiH;TD zf9WdPEdG&p{CCP+*NeI@qz;|ooS7b2BpnnR!PmS_Q7U_aP-j<(g`Z2NQI}9aeA}fI zkJ5yc-eXcJ^Bi5(QmhO%I{(VoINz{PbWPjgBVv`|69ijd)$Cv``NW+YDtD>g*;Oor zYsM|}^A^c(8!xF?_%-x7-uCdCWN^d##DbSn2a6<n*0e4T;acLp&_>pZ&7inxm0+g& z#9~fM@rnPWyB;SRbNzaDOFCzb+pkQCsDo83J?z`-xr8)cJuuj38NzT)Iq^c$+?!^J zCLx@<(^VEdF<a2KRQuB6fLT19B4Nq_u^n54SDb2J#Mc&f!ML%P{nI+d=R!T~2M@Vc z+h|Ul@bcglMk8C35H9V@rXfmy%|lY0t_z5*3%Ih?_Hvuolsngoj&DAn{omYiZI<2i zPdp;(SvTF4S~ta=UV1GvmZ@g@!fW%4ZRfp6QCCuW^*$&l=+NQA<~cV$wA=rAxO{${ zk+E_0!&Y&--)}aT->XztP<T+Za1Z~N^iS`92If6vO10f|PWe5TkL*K>z>HH_7GA-D zMbf56FI;R-e(ls^W-D(yd7G|ul+s%jugMF;4jvKP<#zVCSE_+Q`&EO7xrs7D$_uht zikCl&^L^+ma^ESHZ;8>4GZ*C&Yg;dDG?crt>TvSgb*i7f<@LIB-MBm9M8F&d>-dOW zr8Vu03yj!bUi5NzcbAr)eeU}^>lCAz&CQ3Gcup46kK0rB_EvaYW$Lvxk!59Nl9H14 ze?A<3KEM9o$K&$yHWdbXdh6D#IdkR8l|zRXeRk_yaeeZNtFh}ID=lh#{+D@SV5fbT zZ0n4o<ORtMj*A%`0=rMeT$y&@VEmg6yF8z~p7H6r-qbBNEZ@slF5j*Hcm9MA?E-Rw zf?v(NmVSD5b#>8B8zm(rHML`>PG!Bjv(wShQBhGbS4iy5`I70k*$qpo<mKGsCEA-7 z^I2M23aj}<?5p`X+28Kw`Jn2kt#caQKRVjY%gb9<R`&1TzgdBGmzVpeH}$XRe{{;i z#pP|#6-7On-mNRvH!R`{{i)&G*4us~u~hgW``mjUH~anHcg4l!O7E)GtDhGA1l`Rb zEBp8F-}1M&OiN!~IdS5|o;`c^R)246Z8fyL=&V(|ApK7J<w^#&UbnQgw2+W1H#R2! zf4%?T>2v4w3=9gMpPPI2>eZz7Yt1IYA9C;Qv9z+<wPeYYFE1~@zP|qY)vI^6<wkpW zboBO~y|FR*`kKhkZ@1sSx34z(O+x1jxq==!!P1ufnak(8)ak7HoS48kJFsBx<yGI7 zybscxSjKeH{h@_mpKxny-qF(f>9dl*bab$FT)A@P#0ig`F?C;F1TGD-%)GSZ!Gi}A zCQJxi>{eQ(^V^tT<GoZ;`QamckFRf=WxPb+>es9f-}7T*=f>#W-&y?p;o<h)-d<-X zr$dJhJv%qodcm~rvuDoOl)t;v$}N6wzP-G#aBzHles(r!j~1vnnP+qJ{CWTQ{hK)h zIy`JZBT4Qzn3u(YhB_A2t?`XryL4%)gG0l$UAOu++JAl^rL{1-scyoXtWz&cPo6z{ zcXxSyMa7Sq#_4nB%$ZmDY^JDoSVaZT4ll-5r^2_lw!V1r!Z`ih9J|_G3l=!IyB|M( zJpI*`m6w<K&bBO86F;x|Di<^r*SCS)XRnNLm5a+?|I*U0ox<u$N=ke(789mVfBx*5 zn23mojEqh3GoRSlyT3Cg{FTfqDtBA&nUnKoUF`0EpXdKiNl*8mWAX83`g~ah;kTJr zO@7~-X`H?;X6K?voAAv=@3v%KuBokE8szuTRmCXnOUDZ3H;lph$9v=i1NSf7y3WkP z;>P96pBbam>f2_OOt^SCU}Z@9`FVG@W?!FYTb-4am3DsK-mI&uT)V~Y#+&V|*U;9s zuKxCBXYunzix=z1?TLtu%}q^Rs(Eg%UG1+QA0L1H^5sb1#0-TbxBd>ROV6tg>@+mk z*t~M_jlwO9w@EPYtUcPdSROQ5w!%MnWk~qCn9NnHP0h?edp$BTG71VdEM1yfUh6&o z_4zL?T{;p`&esFpSRA>Q>9*dpwDjw~+TUewZWO+{qA4vc?Q6Pj`t<Prw(Gw&MY>jp zub*dI9cJ95udaUl!i9oIM>>tu&de}OKDNYja!+sX(Y}cp3qbS#Rz=3oV-i!B-3To4 z^bEXt{C$pfxzV%!{1)BXcYzxZU(7o^|372GVf*XdvL62pPh7cqIdRjCKmoyvdsnVp zX<7HD;`FYlvn-XLpPzr<dC;zQh5hB?wBDF+=j{L4R3CJx&p7v`;!zy`$#bBMwco?z zYo|_`^5o@9Ninf)Nk_T-w3aW_JZB3&fBnnZ+2*N6H*aiAHl4b&_}Q6_+n&9@;bPkX zTA{;#=<s3C-t<{BX4L%sdVO>Hc`@rbWwsxW2s3<pcUQYi!NtWz$-~>*y6Ve{7`^_U zo)8U@<l}u;eI`7A{#?B*<L`VIrJoPm<xOG*ci9^n8b)u=ySq8vzqa=8p32XM4jp2v zFwK*$tgH+S4AfnI@3PA4<$iOms=wu=r>AdZR(X{VN|^iBZrM_DcUS4|^7nB&i=G~r zug^(JQYv$i1;t(m+pKA&Tc_*Cn;99+vaK#FDEM%wl{+^#_h?@pL!#UI-B+$&J^A$0 zT<dZ<tCACU?$o@zv^4wLnvY+<idwI`w{*n{4J)f(UtV4g3=9lk9~Y`MRZdRs@^b(A zhRMg)L~fpOSNW9~C_BoReRyzis&@FR7cX+|@3U1<aClQ-1xmYuyaK+ZTZ?wun44d} zdezjxV8ioQSu2CjyeQqhWy_ZQ{eR1zpPQ?xsrm2Uzw@@=?|{YyQ&UyTV)pulhF<;o z`MGKG_eF~rzkc=V&Ye3ZQ+INU=_Hi(zt{&FJ*o|=to#}O{}*TzPg`4C-px%*rPa^B z3j~cH2L7KmZ(iM#6N1;SesenW;_IAcS$Epn+9phx@bvU_(ETDtGkxCds9JpM)~y*c zB+g!`4h#(Z`t_^t)Sbo8&y|+ES$q1n;8!n@&+Zrh`0#M5cDR;Emu~d7mX?+d*>kp_ z^x5%i{<l|I&Q4Bm-n==|*T-_^#n&yXR;~K*;ltb8+vi&rA3J*VX{&f##Kxr7$&)AF zDEt~{YHFH(e%{rdyVkY8N|KWotL+vS5HKiz7t>d!@=63WHaR^cBxKLOU$1X(%Z=Vu z@=`p$=Hl~f=RsMt<5%ypUAH<qI_Aug5f`6c`T5z#b=$5dxxHWL>EZF?+3bAK&hkZz z7FiZQTNAZ4>*1l+KlZN2O{VTV-Y08a_U6V^?Qn)38Ox$uTQV6L85<iL#l*yt*gdXD zgG16SCFO~?{@#%A@b91-IpX$2yeW9c4l3)eTu)6&k+G|Z2o48rz<T}q^sZZWjgouY zeO89dv#Bh4eQmA%|38~ouFTBHcyViM_TIgFkM^zR*U;0mtNrz5W$<#pITnSVpZU)8 zF{}GiarVaElatkp3lkTqfx=ckAUOE*z3TV5x3*-SoTNIx{@>2t-rgI6chy0o$SeB0 zy1Tjg`LAEODkUX#Zl<xi1qj@@cQ5YEg%#d2E(&}5`JG!AyL(&S-C2_+J$n9pd)C!e z%jehKI&#G2&5mDfO-)U~%l%~S>;Bx>n5?O(sivm3IqmEvo;#nvd=as>Qkn?z``)`V zjnl){L<EL}fDZF{dU|@d>^Wv|*7-Hz)~#E{>E}*7{Ul%iXJcyY+dY+^zkL0Aw6E_S zuW{9*pp_x&esgZ@EPmc^|8K?O#hWuOF50kRLqh|@#>cO`gMxxgQg<Hjm)F<S+_-h? zT*G8H2ZsZoEs{UEG7~^?TDAVxty|^yYs)V$^95Z2u`TzujEu~Yz88)lhq>&HcXT}X z@Nm1bk`kYsO+<9`?T~QmygL@1E=px3CG%%oe68Bm)m8TX-ruX?@kfsyt*oqE8?&?M z=clK0)Zfk1n0jh;`1-6()w<$mcsV#`*w^oyIdkR>Mj=}jP|)j_{`>Ru`TTl2ef{@` z`R!x2W=*~Eu!J8R?$^7zySqC&CY*knetuqRZ0`TVJ#qQP|Ni`3zwg(p-|zQ_ufFPU z_w&iCtE<(0W+;>e)b^(xjPWgd|LN&zqnT%pA9tU8ceZKvw7$N+8;n9<6+m^_^_8nv z-`<dT*j>I>L_%Um?(J>=OuFWQW*T0F&U%$q|Lf)QH*el7bZ$R4-+q4S*1tl=ReOV7 zU5|q9xi~5wAG5dW>gCJDS67AV@B5*Yesi}yD=X`A|M_-hZ*DAfZZ|SEUb}Yf^D{Gr z1q1{{M6U2>)poo)2Ab&CyS^^A`rXdwLBYZ1xwp0yJv~(ycK2`(s1eBKTe`KKPj=PH zm5H%$9S-!w>4P>amA<}qcX#>elugU$Rb`!>Wx8+Qz9jam?MIIt1MOh`@bGY8U?5lP zq5Jp$Pjr`y+>mha$H&L1Ml)|*6f6Y=-iqxRIXQoxO!oixy#8PMwKb9PwO_AJP;@@h zx8gTAQk5=6g`d8t&CFt4RqIq)`IF!N&xf1o^Y88`blz<64z%$pCr76&rgp|Mop8PB z@9*!ox3%4y`QTo1zwNUZFEq+ZT=-i+6_03Aa`OD@cRO2JTDIS>`~CHL{B*CSN$yva zXIxZPTGYN~<+`%_`)VU2BSHH&pG<U*2)AZ1Tzq|dM%$aWx3+rw`{&=>l$w2g-Pdp5 z#H?4?`EQO|2d<yitY82A%NHI#K0XeP8J5M%)~#E2<D%eQ<Fqdw9w}U{j~@5i*ZqFG z{dm9p|Fh=zdn62<-gHz6fJ%xl1tMZ%a#kf8N=lDDJUl#g>eN~GG0ja)%lzh^+I6e3 zQ*!UV6<fBHJU=&ge%-H3FR!k&6ZbwnJ<ZF@d$e!$`RpkF<p2NvZqK{BY15`z*5!Ka z?*iw8BC1nUPw(B&=kxo!yQ`niE&uiL!X8lBAsE=76&aqLkYG^y>dJxz3zm9M|CAq+ z<hK5O(8`dB6DLM*%b9rk>9lFnK%<DWOtXJIWiegU(cf<mx^Bw3ebJ&tQsC>4oSdAR znwyXJ$!eEnxXcBW>qi!bXn|^o@_UuXuU{`e-X|+3Czs^@#Q?Mv-R17Ob?fx3tahzj z2deQtKR?gU#}~IDfie8d616igzB1pudGq$RT+q=Hj*gBV9w$!g@3*P`meaTEt=`qE zSJnOIfG7AmPMka`X_Vp-5D?(uabiv6W(#-5uYPA<2u|dfG<kCPnux-WkB;(6o9+2_ zE1Nm}pe8t5?%uF&+B;6;s=sYPD{U%1JOCY8@aBeLdHHwoxQfKDudafM^y638XT-W| zSXe-c$&Oi|RL4IxYVEykxwluZ-)B|x<3s-bzt@f*cYo6%2io4y@q*Fx@7&6FcPwjb zYp-1m5;t6Y{eR5fs;}Mp`+mIJ{eDT%%V2-oucx%v_sH2sy;<;Uc2iT+;dcJ^_I7tS zH#0M{U%!5_v9hwVv;Y42vr|?|5Hwi=x_@uqheO=y=jK#?y&8VM{{LUb9ZNuUoJ)y3 zD8v8z`TWcopKDhy)h4*D->;>we}7~0@n>ge2L}f)_nW&b@9wUn-Qurbyy%b(uMZ9m zF8=eQ@GQU9&Ye5gty|aF*y!l!`1$$y>z6MJTU$vj0JVbJ9gR)i>(~G6UcLJD_WO0O zU%%Eab9n@c(2iZ}R;+mO;9#?$prCu7%*quj5@L02InuuTGN0;I`shgK+1cj*f4yGM z$HxasET{GN=Oia9m&N>@5VX>!{N0=wz3Hc)e*E}x+O%ohVmc99GA=Iex61-$(-M;n zphRJ-XKVZSsCc|h?XNGOQ#`)ktIk*W-vt`s6D;-0j(s~x)qBpIIY;<<e;K5GVe443 zWXbw{zp`#`%e{K_s-mLe>+9?1+f;74;rKP$)6<ikPiDgDr-6ZiRaI4=pPjA#^YM6d zbF;3l?oqy8HWpA}n*R3A&d*P$$IBU|oamFa{`2?mQ9kz+P_t)Zm~ZLU{eM1rySW`( z;Mgoz`DEgQ2M^rkDvw;b67uH73i|}Ne20~*R^8f~eSQD`zwdYK*s(Hr`MUW1br%=8 zGN&8vYG1!(iHeevlkweoP76V2A7p^Qist6#8w&&L!A0tnJ$v?qt`3v6sraz<dR+DQ zyX8AySc6NQYh7Jke)DWJr=R}*{{H!0QLh5eyx?`n+WPCs$;tEUeyxnrlea2)p}l_3 zr$gNOGiJ{0lnt+6HZxD(#^%rT__~$r)`1!n1qB}-_uJbg9pTvMytoeB$QFF~@L~3~ zH5<2V`SWac{xbjhdSw=SSwUqEi-M}EtKM{X7neC!rC#pt>9@9IIyyS`+yC3KdGqEQ z3j_Bb?YZYLZPKJorLV8)@Bb6DG-z$a#-zW$zUt}eC9z*UfA#8BS2wq|_V&|HKW*A% z<nMp}!i5W|r>FHwnR>msu;M=`{p^aYtNS<0H2d58`}>QYp7OW**&=*o+mRkQ!HW$` z12jPWRYAdzpU>N?tEp{TH%-nc?aPWqiyncRWKSmhZ`!m;uJ+5t(%08mSy(z`L;f$1 z^i;O7sd;~IZ)Ig=US6J~qvOJb3uU@}`TexY7+kKbZ)tDumo$EMYil;Bb+IXx`*Nj= zi^%~|aq;%{_V(7+n>TLw%(sixo30<X$3ja>OJ6_#`MJ3Z7cTU9E_m^9Vp`g^yt})u zT)7fo_jBov9To-#7w+G$e|~N*SF6*T3%`tK`hX_o&(1baPfeX`Q~7D*ak<;u^Y4Fo zdD*>3;^VdG{G-Q?b;&AxO_W*e?s9kWh7BM1>wg^HSNl6`UChsq$K_|wn9(5{n195u z%Eg75<#pD|?GGhvvy|1;KnJ%}e|sZol5t^G=;~{0qmPS5$@6WE`uqF+{{KH7_g8;^ zclN}I4`062d^)K<T{rsKyLWnJ8CQ;jve4ZJ*W>GBcNQ(3H}BrJx3{04o2y-Bu@|%x z(dF-qWm~kAlpalwuk-Zq*syV9<c0*tf`Si!etxzTwe9Saw7sNdYFc`Fnr`&AoIni` zfBU~*R<Gap>fuAhvH)feAD=Vl=2{;<e7Lx{*tGbq?e90654ZD+TkE}&25oNOU$SOR z&evC09UUDR85uWj-01UMQ1GI|<&f~~+}yP*SI2J22n-1csjJ(!Y~8e%HcGFy#>B?j z|9H^6Wy=;`X)_tiq7=w+Qnuyq=G-Xc6{)MMo7Hq@#flXT4Go|p%#L&jE_Uy~x1%uG z&#&*s#lZaIhE*;l|M_ICwiG?}S{k&o^!2p|4-z&We#va%*59$>e#WZRwza>uM6I1? zQJ9pG@#4|Z?sgtYrLqi{sDd83Qm=&pZ*FgY54y#$;NhVjN#lDJk9%3U#R|T*wR;+0 ztG>Q2_I~~U+R)IePfkvDc6Od$^T{(hI(nn?;(HyEwo1F?pFVvGI^1V_-d!mvsb5d0 z$45m*cFG3omwtJ1QCQv2WbfVm_4W;|+~Q`rGmX>F?Wz3i($Uk=@h&zv_U*sFzw__z zN=;5SuKxCB!GZ;@-C~6ba$k$iya>GR>h2C&*>OF-Ue-A6O!oS{-@aV-2bbVi4g`gV zi%UvM%E|rveBS>0wQGK}Of+?La&B%)efI2GQoGw;4&y49lJk9Xw!bcU>zkUG)ckxp zy<1FI$a+rP+b=IKgPQGEuTJ&4eXeLh&`K$3Y0$>`;%7dANy<u#^t3cJE$ja50GHFL zsi}}Wb@1T9&1q*J#qYclZm`(>yOx<*+2v)v)!*I}mXyToulsvys&;Qr&k???11ndp zvMP9R;QRgh`X?s@SB6N5h-`tJPxs>0t1elo&VEq1v74Hj*8jeJA2htW)O&i}zn{;| z%*>M9uiRdFHOt-o_?<g3Yv<p(c{4RV{r=oH%1VpwJ$Se4)`JHRKw)&N;#K#Ii;I6x zo;K}UfBm1wtJm){GBS$VUG{eVzc1?9+1VSLr8>O4y+Oyl%(X6eb9If3j<)}LCHVAo z{qNtui(Bgn34{8Fp%*V+)DBytp|Ah{QMdjyok*oJi`rwa*YE%La`}8S6O%1B*DYVZ zJ@4)=&^nkYD>^znRxjIii<zD8$noRR(b4B;8mnt)WIR07x~6oIU9Y5Vl|XB2>;He> z_uKz|v$?IUO+2pR;nwSM#bsq;)+-pbw6$OFe!uVcuh;8^g@xVwWOnA<-1K~2^|`B8 zL*MN1U;*_bo@Zre->?0C*LSv=Zp4O!*Voqa@$n_OUzr}Wujc0Y^XvEa*VNX^7umSD zl$c+;8npj-kDTp}RjXFLy}iBu&&T7Hm6f2bgmnHM!>TVC8=IweBqb%4y}PqB{rtQ~ zj~<<ztlr+*YWwv{@Umsgl8(Fb^MgX6v-tTr+y8$)v$C>Eo998gE?+#A-FiH{ys|c5 zJbPBx(lT;NMMsCn;?&r+UQ1`0WD32`TDd>Tt$&wya`NMOw$)~NcO>NH|KCXN|NAz- zezs9+*9}MB7+zjp_dc1MTeGkK`}=!oP-a2FhO|Yt|71)B3O=bRWrfGa-kqJl&$9Mc ziMjc9Y4bdTx#jog)qcBaHu?IimoII<-ziQy>g-}NL38S<7cX9z->)hD^5Wv*Hs0$0 zf4}SM>hAybYW1T>k3drQDw<!~C@tc9@#<AuYwOWt$KKuEzJ9}of>&2ShiF+9K5Ds9 z$Qw{qRdw*-K~TAQ`t<ERmBoI3=MJ@UxAVz@+DF>q>pEm*zv_TCZ@txv+414e=kw2> zJ*)fiu>H(a+XYXaJb8Gyef!NB6DB-(_fF5t#>Is>AT#sj#^mEB%AdTvy=TA5N<TN} zq$qQy!UGB0SBlI1=Ki|>|L^_B$NT+fo4uV|evgxbL%@1b<GX8Xqj#6Ry|uTx+|8|R z{`~u&&)ffhv-x~fL_~+Ic&UBgMdd}?q@<-mM-tZl`l9IEcI4PGqq*N7wDC$md;C~= zqK8Sos!(TtKR>7<<9GD(I`!=AY-VQWw{PCet9rF^%9JVQ_bQa_?CdNpD?dLw%gD$G zDuiu2A~&aj#xBmxG!_#RYiw)`Ugk6L^wT7E(*?aUmY+Z;6l7(+>J(N#)+71(+3b8P z3yYT4R##WoPFbl^P={s3)YsS7gT`F<e!q8nOXlT=hue2{gqCx1b5A~*GV8k0%pTS4 zE-tq2D?^SQIg)c@!@>La>u+pGe82bmyroN@Zp*#h)zxKEx>eb|PsG|yX;Gc)<P+BA z@8)dX`W15O#^J+<BLy{-R)$zre|sZqUH0V36VO?VKAxU44U^m2+m9dXmFDK+I?~s- zi+y!or^kW-4ZD9o9&f*2SN-S5N9(dTJ9c|bk#ot*TQ_;~WUr-63KKnyjE!YwWsmZ8 zb*zYAxo(|Z;UgCpmm~lF{{H;=b7Z*p6`|F6FBk4CdwUCX&#ip@pNqF||6aTOUevCV z%;1$=of>+2dDqv)-rknGdey2~=J|0E5jP(9+ut*J*6>RSlu#Htz&C1N0%dE^X_DV= z=leV_wXUxIy)t;Y*V3SsAy&D!OqPA_=-B0*mG$b{+UVxy=Cy0qi0Q}4h>L?xXqs)F zziHjH4i6DKJG<)d@Ag)GUA24n?@g(vkM+r({#dp5;ERikLG|OCH*fClF28>Ds&4eQ zGe?g;J!^j7$KPMv+625blDCAbHR<uO-nzQFs;a8+^>MY2d(D>w{hPkfT_=8DjM798 zl}X^C7;eG9``0$DyLR^M+x+_9vllK*JiY5y;9|E<S!KbC4bR@b-CO?tUiS5Ml@%2_ z(c8`(Kc4>l+}v4BqCyiJ8yzz;GE!1fYHI!%pSJ-WXtI0fPF6Oyw)S>y5w4Ak7grx% z6}^a2*Us+W&gb*GdwcJ0NIaaqe(y2I>$a=5Y`JpnTG-mK=TDzTMn`wc@(BjszZ?=? z{op|3o;^0#t_qdPuFmsxG0(g6<HKS8{lDK?`}?229$)`=X8OE`_ht9G)YkrOWM<!% zcem=#k3wtf-5WM+2wfevbLY-ZS@BX%<0=>CDN*1~*{`p!kM~G|=486;+<)xpXFKvl zDtsRs!+r51eUBGf{F0il?{dX9C^%SIS@~(v&x?!Qr+R_TjB08I0b5(!qkO$9&L_C_ zyOjU^^%Yc$-QQPx@7_K6nhyv6{QP{huVa>~D)?}n<9)KMtgQXE-)?BH-(yt%F2=9n z#_5gQ`Z5%}JUwUHR)0IKzyHs2`@fo2R#9I{?j1<9=lfQd#O~;FMSMlbs%fQL*YEqK z)sTC8o2Zyr)~l?U=aiLRMeo_W_weDv>tlC6d-LYc3FUqk7M3GNj&#V1aJKQw|EvH1 zy<SpMvikeGwJTO|@bG;3^y${7RBvD3-Wv-8ch9(}EERDj>+7|((X}--Uf$mNF*`mS zWS8II^D<HDNvGqSo1GmiYE4Z|i+0w0eRZ|3ukYW#f4j@xe){~`y5NC>r)Ou39zQqt z<}F)58B}Rkee$s$%Yp|7b{0REl9mRIQ5+HWS5Z~%lojDDDJ`9@6It}?%F5N@>;2|f zd^}(OZ}aBOpQZEnOq@7Tu`FW=s7Jx<5fv5X;BWxcK>{5N_{cRrK7OOJR6$DBgqNMN zEP{dWCr_Jpt!VG988c>FT^%03t3=b%vhwsa-Gc`YR#p93uPzw)-!SvilFQ5e<!!6J zTw5DGZ{EDs;p@+xKQC^rk@f8H<IT0dzumcW2Q+H)`~Cj%($d;To$7h__Gp&HT;T$x zi>9=UdE2*_*VX;|`T4p1j|a^EGF@C;9$ktG|NV0L{IvA+_+2HLhue7T>gFtO=vZOT z&B3vw=I5vV|Gw()jIpcv@xlCl&E`#;g5E4xF|)Px=&sV&lO|094G&A3=T%fz>PBvQ za%rh|(s5U&v@adM_TRa4XTpRDpgQkke|?W#_=NSawE&%+59K{vTvQe<+ZCm*u3lgN zf39`;ub)5P-rpY|9KJj2surkWnXIC;sNKcgJ^kvcP)|?K|9|iQ|NC@$JfE~#&gW-m zL7k2rD`u`+mlqKc5fgJqfB&CJbLZOD{rQo3dD+RQMH?S0tt<7ua=*2`eSPHSW7n>g z9q*GBR`U_Co>Rs<VQU_{$huN*7u}`Hm&;ogx#&%IcXQJc>Dril95Uqaxm<0L+@{3C zZFlb6S+@Q6x3{wm5}PJZ4!%4MG<<XLpkvR4jxE}HdiS<uUbg@L(_dVCy1)J3l6!k9 zliXdRT)<6MLnWo8Q&TiS$F0t>EI!hg@gT{qe?@-q>Z@<pYR;QKe}C22SIq2uf9k)z zv)<FG{GRzoc<i>PYTvu64<0*~uq$(+%9Q}7C61>KPAuX)x%A%0WfOPD=<S?xdhf}l zpVXF2a^PZg%2+ltPx|q_>g`X}BE#zcPtZBNNrn5i!p%Q+{QUi8TdhCezIk(^&8?Yt zH>IAoe!u7Oix(Bm$-C9AEG}n0VWp7gQf~Zb(!po3-`}io?-y7Uw%XX(xc=|g>wkZL zPftm)u(CQg-@g86m#B95x-Vb9ZY?co=_v#q`g%Kmf9@yA46UiBjvrsXZQHdw*FBta zRxDZa<fQuiJNxVZ&n>_A^V#ftsWNBb--XZ4%oLBWF*G$T{rKppb=jL4X1TN0D({lK zxFXug&9K+4`1{@R*>e_rX_v3-=<eQK^))Li>y^8FZOZezmDio!O^xi1PE4Qhi|JFn z%RT-R_qmU1)O@R|wetHf>prh>#g6<`f9p@*ADu8h@l$M*U-sllr3=3poa(#V@y^ES z#91Hvb!HkG8kUwnyY=@ONQHaft!%l&P=2>moS{`yM=bmDGT$q6-QNVexU_t0d$(rI zninr#OpmXNRGU2W&Zpb?``^BJvE$%F!L?JSOnH2~f4*I9l-_jz`F6Dz7rDNC`BH3~ zzOL@x#Eo}tR=D?12z+z5{Qlo}yWhXt|G#dk*V6c#SFUU+dwYvl+H6hi?r*QIt}cFl zZfjzT*%K+2{VEI`vs!PMO6=$3b9(YO;q``fbML3L=rJ_B+FYysGmm2?f1mK9Yt7G- za)b056AT^*ntpN=a^h$>b;|4S=dAFxQB&v51D)@5db<Af>C-QN&f?tpanfW^$IN%% z(g2Mue`{NAtZn5MPfJbR`|VbC{@$-)H8p=4nb~{HG_<v=KOAI#zxR8bRC$K8rl#h~ zl`Gl#WHPd|XB(xSYU7pm^73NKn>KT%W#J>2swKxd7R%W>xvlON*9Ub{7%pADe828@ z?%PxHbw3pC?Cg}4AHTS`SibhlL<fZpnLTFL0$Ca6UEJlGn6m%&9k+?!igvUwvgEgY zTdQrY_0U?7=bGt~#X$=;OUX@CmQzrC@+|eoo?90#Tu`51BlKlYl+&AI%Y0}1^zGv1 z=JxjS+4J$EK#{M7%(-p3x4F2u($36SIJau+nl(QE-%Znvp5pcNU^9Ds^;=VEHctkf z*j-;PE%gSqYtNmNv#<LDYNFh^v!*_L@kN_I9}XvNtay28si~={Sx@nsg&;pI{r2tK z*6iz9@vE=C0?n>jm*>5{wpQ9KCt`2a*Q=|;Gn;}K*19HGA1IxZ7pS$X?e@(#?QYDT z#*4z77Q4M|-S>4-(hrrG=%BZ$0jm|3$k{rbV9=WS3NmOOmZv|}t6$D`SMF^ysc`QO z+ug6%?H1u`z39c){`mki{|yy6r#1xzg@o(tVvqOBuV1mEqrV^2Q9GLSab4{0py1%C zUQ46a);(+$ulxPhJi5JdbFzU1sK`Hg^5>V!{@>r+6c!U(W*f|~@7F6(<S=FA=f`hK z>2y)rSh^vZ-Bz-BLSW|ARiW&BG8gQx%{~0k!qSqHrRlug@0=-i!dXY=_bBEboq7G? z<c5}B28CSbW9l5y4Es<1-Il4@;?;Le$>$!^m$nOcdzQs~h*>bfVe!Eomb<=AQZq?y ze%*7;>4*AZW3jG0leC3D6oTflALnG?s%u)q-8uVA+QrLlr!KG9-}BOc;Z_FK{fY@z zCRri#T~8H1uwp*&^ncUqo|bCH1&gJ&iW~gni>Z>oyLQH2SsyWmIn~ma=QA{CnwiP+ zX6ZK_ZC%4HJ9UCd;<4c7=?6L%s3!{;MP0de?Ox^cx#{QT+}xgjze`kGC+FssE1<#m zzrVlB+f)Q-O;uA>&CH)Q!z5G4_k?Rlt(S+#iIXP{e=T0WVugm$q`F7Si+h|FR)CU! z<x^36`~Az7E$i#!%RQQAG}F(|FMM4LCpY)z(jFFuBS{~l^Y?yTU;p>?*|TqtipSsC zS6l7v-Tf_P<IOiqy{G^Ca@pTU?QWbI(+UAj$y(52j5oKp``@3-?yxYRq_h-t(DmXi z*6*t_G+7utmDkmEdcRjLH(xaE>+5sEQx|2}Gc7-8&Y8P3;M<F9<|&KbNE|!ccweRB z=)ylU@@j+mxa!;jxR{nH{Rw+g!`>?;<Nm|HF>2*$K8FiBCD$TOHNEFE<CkGPQYzr4 zSi<;6UAc(!hE2%Qmt{RM>!gi%7O2LXe~t~{dJ>y)iml<Dm__CH(&saKcpIWR-{e1h z!hBzaW%&Zl-S<_ho_RG06b0Yho*y3*bElPC{6@~Ve}8}b=1rbG`}g_!f5xh+N3UQ1 z{;*wsn%7d$#JaC<Z(WRT>2txP?Pj^RjwF5cy>u|aVA7;XE3Er_++_HkuUtM)OGoF+ z*RNAORDRWEZH>Bn`7-E`)pzd#e~9ea=%FC6=gTGUqenppvHt$?xc~O8TVK?@SBAX1 zzrX(Xx3}AR3(hP6<<6O_!`It=y%Nm)e%)2R8JqqzES&9?t$5(TleGeF3-&TG20s+N z{(W6c&zyXLogxW~o+vOaZ+^?b@Q7`StmB!tyUrQ0D=xF=WVmGZ<el3ask^~RmVE&w z&i7aue9Y!BD`Z|;s<W>By^D7w!;3Yoi`lPeS?o}*Fq7HKz_v&IMb&GD6;nTSys(|1 z#G%Y^Af2f~Z-pf{!=j{$V=v4$2t+^BFZk3H&B5T|dLiRi+np$meu1LNFJ8X9xh?nh zs?gQDcI^`3Y7JWX=i_ntuk-bP6>e>8Z2b7~<Nv?!>mNUQ#B==Wub)3}n$<aVn7-Th zJMXajij5I#e!ts&zU`xckx%&gINQ=!Q!W-1wK_rOkJF-EUD-Z;{R&!gm6o>b;am-d zD_LJb12iYq=ikuUu(74;3x}ldk))5WuC6}IJ1yNnVzycCq|;B$EwrqcggJ(ArP~+G zeK?y%O}aPoubGA&!+aKx+Y|nZ#xMzP_S(MhML5g(ch|QcEx)|>yJySd<$0;$vKD<0 zcD@qZ$#lYsfkDb7&h>@vv`rUQT#RFLHQ&QqCBgVZ#o<!RJTr!jGfp3J7$$f#@LKdS z97s?qV7qlnah>~W$NqUcZ`?X{A#P>0pI$?smqA3qd)e*;JsYPJzKa$tNH{e`Q@-Xy zqub)Z)mLv#)z#H?@0SBDJNotY_1?XE^Y?zewq?r}(DANz>!%%meABGR>4fRW@89QJ z7B8!7nC-Q6*W*6x9BCm%=WBQG?oB-{cKEj6*C}34%kS5I|M&a-{U0kjEI|YIJ1=hK zxBpX+mGz3ZFC9|sPiB{|*|2NZtry{Zwo8L%PM`jL`~JUg+1yjxZ)q=>^zxm1^5=)P zjB8u}x=r2or1>>ZpR(GW<_9--{d{bawPpJ2cNwqUnFBrd9}n0fazJ@k{zUDDHNp&9 zeo1#?HvCN6%y1!)btzAyagX}iVs6In=4(kFt^r<(ADA1iHP!KN;+VsyCLNj?aPpui zk5Kg4N*15D(letgx$+(#coe0@=ybw2>H4}@PfyR*)>b!pjTpV}+ivGof4S%$s&%#c z{oe5Sc>l*)oRZ9Dd3RRqZJFuw?9R?&W+tW_SwThTFORzQuU)$)b+0VTWAR0sk4J>l z&(GU?Fi>#vw|94|zr48E$p8Fe^xmpcPtTLRJeiQt=miDO`FXa?w_U`#m;Rl5>iqfl zjqGwA{r%frOTI1LD!^b<_50AD$qU04T83}ec-;`wv|wfd=atfml~WlMUN?C$viI*R z*;4NOt;9*QwfOx9qn#4HksVRjwo4ut+~l`KtnoeD^#t!oh74V%$-M75j~N=zDByDl zmp#?@<!;3F8CT0i7<MrIP+9a&=}wjWgKWiZ-->pyy}WjPPV*AULmnAdF09aPb?1=0 zZDno!e$VG~zu)a%zkGT61NN>MJ$_!^+|10IyUX7*^V>Xl`!;v70;i&K_T62jx8!Wu znl~0cc8hLzJ|SRgX7=vh-srVq#xs5R+LMc<d)+o?U0v1I)+Q|@ZFuSK-M>#J`$zq- z3|JaeT3)UnxoOGb#gE<C%#H>0%PB5)E-U-CE%)}9$GMU`ZQqj5T)q1BT6F&3-}nF5 z{rvQF*REZ2t;^TN@4vTf;;ngZi)T+bw{`n%ZwbzQ(y#Phi&-*l__<;)M=u)}r&iFy z7i<jkxGVHB&Rxz`%e?aTkZ{9WhE@><lPr<9?q^=@Q{2w5gQ;ZuqSb!p>Ay7&^Kh z3ND@f`CNy$!mQ$h<?WNr8BQF{&}{M!*q_@Jyx`&&+f&z^a<W)=y;=~q;Fr!7uMIy7 zc-?BPOr*RY3OXIz&@HZi?D+BbcXwYuWR{wmdiLyDa~&0@6TAu{T;h5$ClU;1_&j@c zb#<;RpQ7`V$B%<!V`HPEf8Q;?Z~N!NVNOoYTYSoT(^ubjTN<==`}XxQJ13<nZCX2T z-aJ|BGMi5)luw>KdF!WDgwC{wGnp0yXlQ9^U0V~GoW~(0DRTHuOH7NvZ$+_gVPWCZ zr%v6-*%q|&$;S#!P0j6h%WgNZatjFyA3rvEzxe;`lw-vwcL)5?mNH^g$Phau*6^B# zLA5=gj_2TJ!M#EZvo-~OF#fTwfZO?p(uS(v*R8Yye{k<O_h9$IoAQj8OI}BF1(b6h z;?SsmAh}ptX!Z3u-Sf&=&c51yDMjp*+?)!|$JY<q-*ow~b$Y<WF3Ebf$-VE=p8RJC zG(2|p;EtUSc7Dm7_LWu0{A=%IQ}O6pE3WU2M_n)Yw46D<bNd6Ch8dx|91lM8N??(# zn`IZzu~A%W>Z`5S<Eo!d4d1d}H|J#1#(VYu|E`VRes9GE4n^}r*W>GJ-|zjtE@ETS z{e89D`dTLlDhqX9x^(H>9LwTIM>@}(@o9BB__RortJQ6B<(rMiL1&;wvwJk$+qv-4 zWe_+&*LwQo$;#7DZ+(1bi|qP-n@=3R4HhO>7Q5$d3ID#<I(EzPYk@sRmiHGu<ceW> zAjq7^5_7yUGs)~m_O{xi?{;4NR^)u&<Liswte@3_7P9A(Q;TLl{Qe?VZ(@B(gpJZc zfg<C{TdvRj@n_+$M<xtDYSKJy-<GlQGW15R4a$svWgyYGar>QbFTR^`m6^<xIam84 z?BIvXH$OFI{OA-&n(3tW^ViQAmf!b@o6UT8QTh7aYe$=&aJ+kPd*=6t?;m}+l)d|; z-_i-D;b|t*;#TNe-j1k>Q=EKe_y5Bkny=f0kIgXov$^?UZPCiBr@sAanzm}qv{h@4 zee%vN{h2j2>DjOPzWLt$T5@wPmh*4pbyjSNaK6WSzq2DUxoVD@r17kx2VzELyFPO$ zesf+r#W(8PoFKi>Q!1b4=}leat~mKbwN)tB%%FR^)629{g<5@-Ugrg$st(~=xxy@b z>4c3IUsgJwxN-2IWvlvn&Upo^*D@<UsY)!Y*e7UQqnxI4?^lc4;=I-R87of(trqc_ z_EPeD$6AA#If)K?3>56Lj@iC=`yhMmxxf=DGV>;{T`Zjn>N8g#FMT)Lq_@X5cj=0~ zEYlq}{9M-lNXY4g!On`dT@`J&thk&ydVQleH=ixtQYzANhl7VL_=SDk3;TQ58Ydil zY5gNd_QVPo+o~3UB<~!%D_j<p2bFJKTPWbfp_uaKk<|{qeS(TD6D~Gaec@0%GHnj? zgbf$3If7(c1e`b|LysL&HsVwSvBAX7%7A`3FbhH~=Iq_2dPMH)7Uw$*D>)pEeRU=+ zTxrvJ>hgrr7h-pv4nA|f)$}eb<4OVd(JAg{-bEL2JUw2rUVLxn9*Y`XRt@W>KCQcp z3}hHmVhi{W@7P)JWs8<zrTC6>3;~~{PxbewRJ2G;+;X++)u-K2+Q-lTY+jqJ*didk zAZ>zxQ^(oBez}eDvR5_!%C2oq`227-OD`9Xn$om}Vp+LMSLgKa@}97@`7ukTv`R0- zgfHwB$9ihwuDw{}c<{Wyj~BZ>^oX6j&@-F+f6AN+Nrno&+P~$or6>MXO{i7QbH4j@ z-#v%LM<0IfX>1lqzt6(JuBc|u!mzYGu#AN_+~BLBMJ4~FrY)l4_YUs~XHZDud}Vy$ zvR%@{iL--4&%HnTe4ps{>!0S@>~aZx`?ZxJulC9A1v^~NhK8T3{Xb`R{FxK~G;iMv zm{R>{@}JArj6L2lryg2)?w+-Du5T`HYiIX%)%7>>YJ;}2s-LU*{Cujvd{Keqn@5J{ zoj7?ceVtBdIGt56ZGMurY>K!3``^+1E=z(=z2fpet+FU{b^Oc?AN;3%mzwC^AF*EN z@$=8s+seyLDq4MJ?RisK{{O~m_j{*pKXNv3a{r&Q=h1o{v-L0jY=61`U+l^kGk1Ti zZ&tsPrnoh*{MQQi{u}z&6@I8L+$!L>S)fpwA!Lctdv=w3>A755mJxRxw@vh(@Yi&S zuEc)6Lmqcet-7pnhdurO!nQhH#u-m!`~S!*_89E-XzO{rr262q?`uoGx!<W0k(Ee^ zH{&<@+<o}@lcm)M-{j6<Ubg5B#}r!)`@SF6x^Gv%aeVgQ@#5X>X&IvZ0&C?8Pk)>n zy(>y9?f&Qd|1T_WO|@JpKllFU@csjw3{FDRm)8ECQXg{a#Ix7Wq)ihKD*s$w&UWNX z^q1rMUtbpo*_Vj1MNe)Dx_9=O6;p#7v%}gjUfoHK-U%7M4k@?XFwbIJDXH@0P{00; zidNtKkKZ#aiPf$CZ+2Nb<<f)Qyzeh5U)RdHwCdO;?w#s(elc5g3;r-M7{B}B9{KBh z&br52uCCA6-Z`r-{Nm2_kMk>U6qU;*{Q7dU_^_*O)sc0X?21)xuf<v?);i0whtB6? z6W-@JZQDfef{*qWRv6|=@9?XA-JHJIP}*j?VoOaf<BZF9c`C*4DEsJ761;MksZTlP zc;oY&*8vj8w0AJw<$mkC_}K}oi9c^D+!jdMD_3}WpLu@p>Zz;eS)UUB!uzvt{{F2> z#q$@h)^F%r7L*yjx&F!=!Sj1}Y6&|8+;KWQRjyGuX76G4yW4*p%2S&xYWI|nfpOz! z^EW3XqIj-NIUpd>=FYJ({R&Tzu?I)Pr!%$P^1s}E-#U2HIOS1M|AHfq-=)qib#FUn zp5*qfv%gwJ>8?@p!v~L)GuL0uzi>6^U`nBr&~)BeR}NfGf6goZ^@ZT>Yf&uQm}8E= z6kDp4U43)b=ZV|dH~+Ufk#;lQ`Bs-^|F_rYE_X@&sgiGGIFqT(Jez$w!{zQ2maDOC z`9c<b95eYDE-d&ZGpqQaLdzCjJw}e`E9IBxsHT<WoO8XVmvJRwli^231IrWtxHkDQ zNbHw8RFG27yj5tj+4ryaUuvrC60a%GxU#~k_ZQEHSjG2kUVQgmdS<h$ajUlf+V%O| zUe@UfN7lagcDdHL$2Mbq!({$PW?$}ddURMGFVB0KqZ$A4isRw^kG3pZR~Pwv(ZVM> z?fM^h<o;B@-MZ?mHJ`(8VeN)*znskXXY4-_+59eI>gV4x^XKjPoF93(|KKd49bw86 za*9u?7N<>^<><svP|>vM%ltjgleczn+${g#1KXdA9&Z|E=Zi3S&R)m8e(9^O6?)=Q zy<UpRg%u2!`2QGJKK;+5nEE?^2RH*}YVV4EFqwf(m|;n-hGokJ*1y{_Pr8?LN7!iW zQp{uM?!IBF@k8=zCPP6H`y;ah_L0-0ycI)=wumKu5^HFDX4BF2P?CAOfbh=Oy9F6N zW?h)VyUsX@`{8_^^ARQ67d(@(TJ=Dd|GdPL8tz`U%W~|^tOqO@5-qg+7ymO_X5V^^ zY096r7q?5lzvK0ZT)kH2UE(fg`5hUb3aW0MdFFH`&?~UqGu%tBk)hzLwn?1povI)H zj@7Jsd;6y``PAlo@Utzpt~z?Knn`N&g22P70y6F_e(o<584CDYn+5b5Kg`crWX<mo z%*S95Az{vbls&Lgh+&y6-&U!W`U{>2sGRNCFI@QgVj!odFvFROQx+3HJ^mooKaHs* zM5$hXlDt$^;l$aFq2CtnIuz_!$X$DA8E?&X>yoZ-uFfYd_jg3{sCoYnOZTqyeOI`2 z(QdW(KQ0}wV{tCOoLPGAVc)YNzVn`Hf?KbOZ`kR#`CU!0&Z={k{}Mm8zQ2}ZA3L}D z%cp(&&qsWZs`wPeVES_<Q{sYevu7?^uC4y{@RZ&6886(7nOFX5^Rup=2}hPX7Iyp9 ze4G%qHty@4K(%h>2Y2|-XRG^wnlO^D|1F$S9{=m<)sx!)W|iCyX3$A7H^|ZUW^kxZ zE<8H*FW<R1)5_zEmfaT>*&nfc-<MDKUfo&DcP?({N_pM-R}0Edq#XY6EU#w%(Wl|5 z|L?`jEc|WUK3jYJoV$OwtS*1@sC~cS)n{{lWzC*E`~9M|wZYZ1bR4ESh0QHDdAoag z`nvz>lTWTY>HpNa+9&SYp9$x!6<zvgIcBkOUi6CivV6<?d4)ya=Wlor$nfjqvuCU3 z$K0A(U$y+-rOh>GCkd(uupM0BuK)YRZ^7VeQ)B+@+r9bV&E%Nq*nM7_pZR9y>^Oa( zE%nq}eTjK?U-HAB=hfI3?K&DcA*aRihg!=G4{t>V52?bh-Z543J9i6i<*C~nzR0cj zQL})#LWLRAvP0H#UtbpRvo_2K{m{{NKSif1`1)LRE!T^6EPl=TLbtpYzF}<G<<0QG zx^RNQtfGJq#!W#22BHtQD?PW)xKi+?#X#t-Xn}0|uG1bjI@Vd8IJzsghv~uY=CjQ1 z427~SfgG_5UfUSW+!R(_x!-V`Telkj@ff`$DwX0z``vHN-gW!w7Ad2P6`~F6w!}6c ze6nEmy7xObK8v^)_}fOfH|o0c@i%`3^0k}Yn%|}EVEO9ptLS)AG3KvO>;6NQ43o_c z>$1d_G8`ymX=W8;=W}A%<)hmj)ptO0SNemp5Wao3J5P$v{mtfZ<B91s^K1>v_vr@J zA+;B0cH8e0nY>BUrZTs-aMqsX!VPX~cYQg%deN>wKYm6pPQPcZS6KP6_3plhml-%( z9A)MS$3IY9b&|7VruoNh>bA}5OafP*mX@0^^jw)6&9`Uwr`!KMKX6>CtuFh>#oICS zdPLbl>m09(t?%=0?g<W=t^79Y;y&x-yRREJZg=sC-T(9NwH=l9Ju^1(HPk&SE513C z=k_U~6=$p}-u-_5=viLpyvp}ap4MA#d@Z;&YGv)~JN)&%b8G)^F|}@bB%bAdQnF3l z^6$9~o~xJ4_2pwaf9_e=uSJ(HzyIN09Gd1HoOy9){^Y#sRqH-%F_YzHJ@M$noI8I~ z@4l7oRedZp-7o6fovF_G+Eu&OSRHQ>=w2bYByEDg+8a0dkDaf7aj0KkY|hU^1$%eC zI$l~}xaW&b{N@yv!U{hd^@U6J@;L;%?&=O-vF&&0r8s_t#|P{uPyfz4*ZBGdiMe(> z89Q<c62cb9*(U9e;$~!1%WpMcdMnB?gKPbcedXT#&Z_TaH90+886L>-F=VOUI`u2< z{^ah7pLvz0Gx<!Bad}X(LAK$Z=dT{C;2w|L6Lw2)%s%jpk>R*tSKf);3=T2;?ED?C z1?!|uq&Dn$@U4%-jElh`U023-LD<2AvIjRme37d8bRM6FYwh`i22m#E7HY+c&kE)U zSl$0|^WfQ?yTor<Ka=pe+dOslXEx8XpZeY{Ecn3C(8j}%p?}%7Wa(Ow+@&8n%=~&! zwti=6x!<)@KjD|~u3-7yQWL!=eqncL?$e4jUl(QgV`7%IfF&Qph2Orj1vbyp(qrCW z^KtW%z3WzQy<}gttt{}?)k(j8UejD1mt+t*z3!gi>>~T?2SpuzHC`7rDtz=P_tx1X zi?kSi**8RIZHnFF6spy_*}dS;pY|>FpRPVz&NO3N+VMTV?R|Fsj=ldu(y_4n>(8#N z;<>iYE?X;4p8mfmF#AS~yL-6&+i0!UH4C5Q1iV++I&GB>d%C`V^UmAsY3X`7*<K4) zZ+-P-djGjypLO}-85*9eO!2(6WbWBp<&}MUOQ(Nlnz84PzK#3##)p|Eub!Rqd4EBZ zcj@!V;s5;IlQ)*1cruB5_wsd>u9xE0|23|@z_jM1J)eTwQ#%G8Hs{4*noonc4TYW7 zxPV%{EiXV#wa3r%{BHmCNxkNH`0KM(^Diz<e>h83`E;a&M&4@H3AJzj{$TCrxWmj) zQf^`rp7MdkDSZCE-N`y8I&RC)uXwo0|H@+bH&dcm12yOTJy6<~FEk^^M5-t5{R*er zUGEroM17Sk_;l&)rt4u`y+U$<yS8`nA5dq!WR_CTI^E&OnoDcLy%=Z6y<HLhMY~4m z;SK9n56DO+lS8)R4I2*SgDDGF^PT(m>!Ro}#*8Z&`pt`^?-hnEy%WdQr_55fYkQB_ zS=qjmF&&mXYBGBTwh7pA)@tvLF4g~%oU_&ZXgUA4=vxZbMgj(`3@)iF{M(~7_NX&7 ztYF~{e_;NA+qj!~I)g>!ciWlb4U5H@mMv73&&*$7$IQ04hC|Y`C{vw*y|KMDSIX<$ z$2oUe8Fy`acImu+yV_cj?P0R_cit?Hxpe01f0hd&6XS|L{?=p*o+c81<LxWqg>(I5 z*M^x*nKRY%mXpvlsbw*f%jX<SVLfst)gW@+y~Kl@+c{fm&84qDk$?Vyh0*ZyjGT2V z%#JG;FfA@OYWg+FWNMI{!0O)<m#<W^)yP}8FVJk}+>;yD>NIlO?-Q6+vb#HcMOk3T z<g>*>Ry$wLdfDQ7`;-6Q_+Zyv1`795Ds)35i!$BI)06MqIm?j6?Z4Gr%>DeW6DgZs zcl%Yh`$}$MV7&5dc@>-LCssKIt65$@nf%$s^N~`8#H^j~zD_uj`uuyIc}(WIU(9=+ z?1rrckc_PoTNi1xiAC<<q;0p3ZR&ov@1l*n`SN>md(YheH+9Ps$-imSq{S9rPQOxc zQ+<{H5x=eB4yw%tLJT)*D*PR?7rxu4!f-YHp}AzvzPyc_#dv4dJ`RfJdMI?|y7Z+< z{OgP@`eqdHH>H2K4ZL!aogqam@BDR#kW1^2FJJ0V?mpG4?HkvQ)>pfpSY`j>Ei~m? zu$aqBk||xn=FF9vQy0$9I&QEx<6VKz6Q?x~Wbd0hF5K4~dinRBqPM=eebe?`j@r7o z-blj7p}8sk!F-<g6$}$foit^a_(%HRY1o{<;El$jFr_rnh?v#il%7OorsutSm$PYu zFSrRb^Vj+%p_cA4u{9Nbhoa?vsMP%n%gvrz|7vr`%GZ`Pca4`suUbDX?%r$prMu@Z z-Ki9NQMqsK--P(fY#O4ryi1?kGz)Jv?_}thxz+Qx)7l`7lu5@nb=OTa-cs+dEhN@( z&V+qx-)CIkp;Gt${`|93UpBJ!cbb4BU5l}I*}4xUH<sM~s=cbXpGB(XcK5u({_+=7 zHt(KqDjpa6P?O>D^Sm^J$gHiK7Fy^kq|I}XVCh}9@5vhf8&@2;11>7(Y3+U@ylnQ_ zRch}e9{h+t!{)=WQw-ce@p#wS|65F=Co{XOWNVmbwLTa3)$<>~jh2b30&JR3FZD35 zKYss{0K?mS#ii4~?f8BCRejEZ1-ixmr(K5S{g7-$h6<NgVt*$u4Ex%fo1_1FH?yCj z<I%zb83ms9sHL~B8?$*ynrNM{Qkbrgp%%kbDr^3$vHe!u)MYu3*I2K<IDwPFc5Z;z z!#lT`P8`iRbIF!DJcMg2*W<MB?}C`0H|*ncKg__eMXd4UwY$@nrYfesz4-FjjjSGV zU72$SVmeG~CjXNAzpCD-bCEQIiPT;0^&gv6j9&EFgva)Zwl%-zX<WZf_`;XP-X?0- zrv72u$<mOw$)k5=E<?tZ3FVHdM>Arae7HPg_!cO=Zn*gC*{L&^ysNjYm-agM)BQXn zL$BMVxcka^opV1gNH17a)>bh!XxUvgg|vBPzvT+Euf2c&LFVq?ML}1*EE{h95!Nx& zPkB^ySVyYsatPPV_?C~KWw<YuZ4HTCsc*G5?9}6D`B#rW7M!wR??jec`j-p2MQxL| zdND58s%CCbR@Wa<Uj6pKn=`GszMLLbuby7wOI+~om~dvecjPhs;PCxS3#^`RShHJ} z=hzn0^;<$>FP@*8ED{&{(DVI;l(#%*&x*d}nyHd@&5a@VE356Ju=f*EBFlF_Wm=<c zwKz<B@8M-k0jsB~ir3HBGv`^edP+)wvBy~j#jULBU#IgksCA!y$o=EouKOQ!L+lTG zpZ{d)?KW+*y8*-f50bayU1VbR%+&EqFRpy_=s2(W<~tiCw$5?monE_0&NivvL@L&O z_P@r>hde&q4JeP?zGBkiwIWicR;wob7hW{Y`66$hvefzo%Vj62S+Fm#6z37MKptT) zjn!pvdUjY>MD%#z{DrUOUuL==<ur-AYOB|*&TyNNOOqkvipH(}8CPqa^H}%oI(d<y z<MqLW7jo7KA`A?HhBk{zK0nQj^oUe!-NE@zP++Q)rg7Ys0t@D1Mdp|Dn-h!JtoD2E zva<-}WGD%9R&77PzmS{Z%hwyLo*e6*R(^$R1{VY4UjN?DeeBmc<2Kexd)zM3ui78@ zeQ|u`C+RN!7t3N;E(9@T{L1^HZQb<gae`5)<D%{7!~YvDiTCgD<m{IJ&O3kJ*WcEv z)9Wr|Twzej-5TD%Cw$&c|KA}lk>%CV&I{v1ylO8>w)(tL`0(Jv-0pL=YcH;-KC(8l z{lD(yEzAKYc1d@g&$_Z|S=X1%yXVi{me%g0^vIgi`*J-~Ky-nULfO8uZ>oE{w0|>J zw0^Vg^jRB}BL7?A{Sozh3xl&h_3i$Bd{@OQw~DP-pBhS>S@y}B;mD#{-;O1nU(j;u z&HWiVeOp$$stJ~sn{720$uyUnF?Z*NwVI6V>H6!MSNmLIb66V|_v2%0r1ZTj|Nh*L znYq%IOZ~e8-~E}-9~c?fEM2sG;ggz-OK<mXoLf@xQS8@o#tfa^FP_L<xEG<5xmtD! z!{>hH51ezE6#ibXSJACKcJuH9#<wjK5*L6w?6;)3&ewcSU%H6B!ELSA{r|U)9QA*d zf7&$sZ;zfW_jMh~LZ(E4^A~;Z*Plu-kd3Vs&aZW<KfQTcYunKmUnEUq%q&!1Z(zUQ zGC|t=UhARwQsD_xWt?s>70f-Da3J64RR6*P`9<MMzsf}Zb*(Zk;CFwMWiaD`#lo!| z6Hi|V<z6Q|>$AXaDTWz3N7lL@JfE?LX}dv-KGW*$=erNOd~#l4)%<F+#x4FnWtmov zd26L#aW@=1)UrG9mvxI^z&C}Iy!$C-x~(5fcVy1eZrH&%@ic>j;!E*{P3*Fv68qQP zH;nR_d6MbA=%zA@-_2*+z3$};8q|Ust!`3AfrU=rqi(fn&p&J`vG8wuhRVJERhL)n z?)g^aaa+Jh{$clll*La1;`0;!^*`ACHM(d2<u`p*^BzBxxnRESmbF~g)OF{@9ilb6 zs-NGUTB`I|xJ9p_I^zDjz|#{y>!!rM$aB47#PKI!i+qlph)_f0iPRH!c~^4eE}c=p z@72G+{rgs#RCk3BuKxMu3(caO&LkS$^q&7i)%@$@J(K6h-T2MquTb)lqjUdL#k+Sk z7`o4j?qK)0m1Wx`v?W>WS<avHJKxXO_x*p-Jn7kzrRR$({20>ieEj~|e&2-RN6G(B zL>im#Ihe5N2UDVN-K#61`kGa{W@#G*y{o)#aDUC=_hRvPcpp6S*AI`gTo9(YB=+pt zsWZJQzfZXx&k``X+@_@HK8OCk&Ee6pbx&SRXFQ>zwC})Xt>52gO5bBR@X*q#nk76< z)+6Q*3&Z4_hBsp-Cq@S|`G}?eW0qeoUvbwyYg^2%i5oun|Ju35Dq4%{(!PK%C0os> z>HIjH?qgP-P{DgNQ){V?N#@eB>7ap($Ko06yA5aP@LdmF`a-bHe|ta!!>Z4Hj2a%d zpT2nXSlUikqt1{+QMm=wk3Z?_w{*%+w=)IbB+8%7RyUQ}y2xEdz}VmV`Qm9iU!|A4 zjNFlSvZMGLM_2p@j_U_q_a9Tw$+~mLUMe?jVPfE^-Ms$u0}rQemyjw>-p;YpF7EF3 zcO@6)qTL-C5`K5xEna;6wiVahqyHEE{C{lLVSoPbpPv?W{#ktZksxQ=1jEIPSH5Wv zUv}htea0`@`t7AU=DSZmywjeyHP0xdds~fyRGm`G9h()BTk505xhE;NnZEwqzQ6mj z_uImZlM*ZH4%=HV@YlO-`0JhH;yg~!T!I_#+XQ**`cG1dEiv|2c!Z=Ey>frU_4S3I z6Nh3;kCf{4Zw3-R`%lc=#@8a?l+!%RG08dPZ$~U>krjtx%Y=)H-;b#0*$Ga(Y&K=- z|D4wm9EwNSR!FLtxm@kPAzfv}2D0PC3jy=|?zPSeEdtSt(k9#x2(?eje<5cJvI08g z;U@g*qB4BCLovk!Y5~opllo1vI=U84xMjs>bS?8rhHlfM+t&&Oitd(d4SP2C*BQIu z&Cbb>8QP0QLK06%7-y)4te(1+RXt_WwuxQ^TcoAgD{T9kUI{TS2s*W@xIe0X+WN_I zg{yO!H~5zom9?dvcs`}-ONZ?$57%GECv>|jXf72oeO~a;)??P$yvu=|hiX^&Ie&C4 zx!UWnEG6VZMnD~p<a`IcorN>Yt}XZ^a>?H1n)r2XZdY@?Kh;NqHb3K%N=^~Fc>aG( z!fOq;wk2!Lp8u#n|E}&DU-0IIf8Xn@KWA%Iu=lRq1JkP~AIh+X&X|2FBJ1@T$t^-z zCa=~wzyI@X{?@R6nx<)4rl!r;yIx(AF!<x<uQ@$UrsnZ?ezO<nKXsTaDav&J_j2z3 zJsUSH-gx9t8n5beyV@(xzu#Y(-p?4IRaIsyyDa|a%f)i{^X40zNqBScf>-H-n;Ua& zu1Qq*wKsr#%e6Q4$fP9e1J;alucny?d|U8DKxsN?-d9}lzxxR*H=XjN^AbEQx_cH{ zW?eb)i>cArAXB?3xNT}ku-UF?pZ!OlDJQ(zAoPCvt%UFkHx3sTbk3{nU%OaB((fJP zMos=3=~>UF#Q)s7dFP*BOZCOBmY9gKA2}!e<65t!gSO<f!x)}7k~p(O)xSTXNx5m3 zqwZ{zW@o?8&(?S^KK()3*6g}s<<YX&m$z*Cvy*S#LQn14+Qz#1VH37x|D3#kUB#;h zUCa5-?fZV8;nb!2SzF%R+<N=`n(B{-c8Tk&tp79r!jh@iWV>RGbwXdi{%~Nkv5a$G z{koF}img~ceO#er72(HLkyYFOSlBE&@PvV3GV}U~kfpsT?~bhN&G40;vWDCCZ9?IJ zgafuUFJ5k$uKZg%!(`e0R0Bba<QJX%DL=WSs%Q9=y?Mi)D|@sf(IB#H_ALkArO*9q z_JuAEi`}o|rT?CDZi)5elV(5PeYJDYmYjNc>osW1AD75}eMWMRkkPugs}D%5xO#<$ zkN4`*i+L_mwrq>z|97^UtY7)(CzJna=`A6tovv52rk+wZIH;a8t9i3H!~Ydie*EO$ z`TO{;UoJa-xtL6g<(a+b)~?4JvVR5by=IkDQr4C;<8A*`pLv%R4em}6PU7Dc9q>il zO3NTm&q<u2VT)+^{+4i?89F9$txGtK=QG~Vjo4WdqHyJbo9=W45qXy<mlBtHu4|w5 zd4*;F3Dp&r{o5|>iwZ23`&n)HIr2kHKr!D@c7xB67FCPvWJ8w=Zk6%f`C>)OCU(Qs z3j!BEW3pN;xK(DK=dLM7zn=IlH%YC+-{H*LUGHKGZKc*Z+-rRo=CZb7v;8Z*#ov?; zi7)=4AaiG8#r&HAp<E$LnqIf8tNIWtxQl^D&1zM^d`5;;_XCfT?!*XNXI)V%GVD5{ zDiB*5pdC1ut&jP~yT9A~Z?xRvUSZk((tnl(*K`Ml6?-`%*{iG$JX6d%$}vxAwx-SR zsY~|yT?#w?kbBwsztRkWv2ib-?!9#G*|}$*US`LC<(Lyt^6&Pc&GEi*-|ifZFSFoo zR$8{s|L>pvb@v3j<$pyf@MxX>@$=8Tx88EMUq6!$o$)R8-^>5ef2RvGoHDM<%-2ZT zWa%sVa`JRrb)F9S89UNHxD+>v&iSeI|IG8?uz&ssXX?M|zO1J6=kk&0`B(OZR%Q0@ zSljmc!KHvAyP8wC7VL0U72kK>^KZeeS+b&$?6XekYgbvNuc?k*945NtZPvOobGD_q zSA4paeX3SrX-w7E6V)}1?%BS52W%4_<<?*OXPNlPpjU~fZ~xU(F+R)E^s*NhUyqu* zHt0l=f8C+tqVkU%8<#osJno5(neff^;?Dd@)9fY}|2h2Z6wmw(D>cjazkc#;Iq&)> zm*(9p-=D1K=d9L!>&KDa_>7RPV*d)K@0=t#W5G_TMf&Xf4k%}yynM@Q=c}E`%%3;K z$ba&yE6Y0{Uvqf*`F+pt>%}cJtvv2m|M$qH<Ml;fI~Q;zr?zg?zH%*c(Z!e_KU4MY z@6`FbeA_Q3hRg3ObnE_w9ritQRhwbatvkW-w)gHuh*%XK{Zjfrq4)=Lv%K-vS+fp0 z&T?Gky?9mYoAN8!ai-!M+!kLmuM(T3Q@pCEE`RmuaBWep$ona_ZJAQ;Ndf<A8jmko zdRR6tHoRoj;*C!pRIk1fbKLXvJl}{P5)6$79{U@8lwM_MeB+yGbEd~FAoSe(_W#x8 zN3ML`{JwI#!Q0iF@7qh;e!llI`~R_|&wg*Jj@;E(%RG6RS)ccC(AG^nzVqfb8PA{p z^V`Z&{kVdXuV?M|etvX*{hI2JP2J%y4w$7R@TlFEe;a95`IUE}+rcxIvP`?&`)}wM z%BtBlaDHF#g(IZs?x`Er0^0=ceH1WPD3bh<x5B1%bN;L!>RQ|Mrn?pJ<T*aFSm<u@ z>9|wdd2_+otper>g~Dogx-T6LIK`k)uq%(*j9+o@-4q_SJ?aZq^T}TAi0aF{EnvVK zx%<GQq(^@{V%jz-*J_rBBt81;ajRz<(-b*IhE|cK?SdOw9$$BsXw;tXytvIkMs{k( zdWS={A2$CejNHPX_gKJ$dt<humg`eZh5}x<3pxxO(J8yE{iU}B>M<(^t}c1Wa@Ofb z(&M+1JQkI&mo=O0)Ngq7mt$7vjja#37<j&OZDJR%ugd&0$9~D3zuTHOt20EFS0DR# zefgT2#B+P!v$~wO{B&_|*49h<Sz*CHmmb^Hz1`+V=94Yf&T4w{_UW60?&%irvnUks z&)M=tvV6Y;Tl33j(l?_f^DeOZp5grR=aQx8RrKnb4kpA|e(8I8WNJ}yW2<l6)u`I7 zYxgBQoTi^w`QdWU-}Ty6M{c?J)qRb4^hiA^-QJ?^-Luob<B|<#C<;&Cel5j3JjEw^ zZ}QdR<BQVsY<`{mn=|k7qP6k9v0sCZ9W+1lbYAV7W?SoJ{C~p3D^6+5`&_*pG`416 zUVQ3q{&ms0=j{G9wjMU=x^SvE(a5wolHaDh@bfl?j@i3YKW%!xR!88mg=9~|j7ne8 zms?rY^D94G-g^7I$1Q2U+MnvVWs7dbEM0Tkx}<BT#aAD(ttW-kL$;oo+H;cS>{WqU zOP{D;Yxeo^oyop%%cAa`{2{gV*H(n;#Vusm(U&JIW|x&(K5ysdvfxmOYUkX!t=rbw z6vrpOY+a)2e?H<nzu4^Z|GT%k#TppIuV*j`jfvax_4IAIpZl!7do0^|D@oRRJ*aNE z#S;`O6|0-Ff3cbThQ!6`>#ofV4zJi{^*rOzBlSts?1WPdeqA!~eeCh;dgAN-t7cB# z@L^+hoPNajOG`JLT&?%-OVPKD{5@tG=kJ*3J=&DLH}K0YuD<=I8hMJ%2NO0{K7Ri1 zpm~ke^@FX4%hNXPtZ8&Vbm+KGoK)M=tcbQ}MTX^NNkQ+f?|blp_18J0$+;&ENce2C zza`=mSNkk$%G1wwFD$nT-CgYdW_mf31kVn4hs8~6g!|?dd}v@^a8cnq`wlkc3^s<I z+0BK;ZS%OBFRp)?++elqt;lUg2Aku|JRHgk0-f)1ZoByQB-`>yXPFt^b6()n{@CO8 zk@0Rsc)ERw^q1RgKFr5C*ZFZoH+%|l(Q{1}n^jcsWahryBfPt$@6-rCe8KAedAn<N z$cnu!FQzgaNKhz{^5R!cnODkwvZ2|1e@xan{*EPa;+-eoG8W7&&7Wn_RkefV&_Utw z{ceBe?wWTnG0ySZfuq`Aew;h|`Q7jQJA3SzG|vB6s`UE6^8Tt9<{7KCKk)dm2$*F~ zU0uFob-6`Di);VWd4HB{d*I^m=Fg`y@oM`2SC=KTr{}-z)^5KyYu7K)x37Ql*Q~ji z;iIOv>hyIrI|0zdMZur72?l=_KVNb6)Vp(T;rkk%zu5Nb=3<5ru9+*$wy(95XK2@F z5HKpV>^{saU{QDQ==}JP-E&wSBqZ)%4a(H}&dDt|bHjs)j^3VYgGA>3PWvUhE8p8t z^LwgHg>B-)WHtWFDJ|CwX3pBV#_+)%$xX`~e2%?*Bgv#-_Ox!^Wb5-MYj3@pUjO^P zwTKaC`}2^ZkL?|r<ukf3PuMA(J4d$p;Umeef1#&UxJ}a&cnxobhpV$c2`zZm?U<eX zXwmWdnp{8ctD@&0bc%+5Q`gz@P2X^pfy}(SXDu8+>Dq7Ulv1<lj*CBX^n|Z`qUGBE z?Vg4$_g5~5FKc{j8rkC?7=GMlpDtUMf9kD%-_<DJvkw-WRk*tJ;#DUp*{!V&Uwh~6 zR689bCdqz(#-2ZwZ?nzkdmP^WC6lk`$b_l!SJ|Gvk~MpN@BfCKd_R|$NvTE@WxoHi zbv>Vb_e4?a-;Iy0&Cf@C2c_W04}yv^&rbn$g^$><hl{lzfAj&Il&v(l)0g-ETVEUe z_UeM^%kAWf!{_gmN<CY-y})m+i*41BdztSO&Hu~_oZGf8>dcSNCw!Woz2J2%zrSda zG}C-Rk7+UCw>*W;oKa3s6EE9;UFtBWWR><LZ-psA3=>Qa<{Lfo{ddMDqJ8}uZYj|a zuDdT{-StmctyjJ9Z)ZeT%7ztZ-daD@OL=$XX1(IWxC)op>YQ)s_x{TN{dcg<cKx}S z4VCE*XZCz+J9Hvb`dOaQNAKwm=a}-Hi%Xmw_H^#AE7m46k3QVIlg~}M`_-o}>mzT; zB^_{jG|lkW_SAE7k3ad<9xE>RDm6W&s7|1^k0C;5UDQ$uzjq8v=K5w$by9tQ?O*Dn zSF(zk`3*A<Z&7oa3~p!eSd@zenMEpGJMvQ0h_fN+-r0v%)8g*!ezI||SYOonn84Ym z^Dexcz-C+C(>T9u+V(B$>^PVoH9Znbm9MS8$1J~cYSF#}hYuZVTXE>d`TMJ@u3U>0 zm{n4p`|xCNeEwt0o#*%cmYuiw;~X8aSE3AV@533-KTz4Z<?yKozMEc0`JP=M3XT3K zyH}3P+m>D1dM%~6BJKC@H9aXTt?Ks!YaUh~Hl6fs*Sl}OvS)QZJ;u=$eWbWVfA5~- z)+#s6YofeU(@M`>Joju<N2c@^X`Z*23{sxnG)%e?7b)NTG<$#isjw}{ZEW*`Utc`y zkuqgsSHLG}rRlHoe1o*xtkW*o`k1=}u3pWj=lE>9TA4R<O!4DPpS4ZJ3=9P_7sI%E zcbVt%9yxY)Yov|1L8QR-@9$POT^4w5DXTN-Am6n^`!3IGNH^JJ*B)gl=607U;_si% z1s}QlYD(67DL&@3dDVUSi~LEc-d$_YeR==z<7fF*r|jlbzIc0Lr8L{V)8(I5oO>%h zZ|z*4<G+sRURV+O``#{Hjl9GkQ><@X|1|eT%DXVWrv(LH6F2Q#bT8wo*3Q}fEjtg( z6t$=Y8&BUl?cvVLveU2L{d(=_$%2xvg$3VM>06#I|5oz3*GPQ1;$&CbCrO6WA1Jt+ zM_5M8OndYw_vy^vUV1h1BKuGLYFK$FqF%&YXlv=STUKK2&jkhM7d_v<Y;B!t)w5%b znNjP)tForvQ7$-C(6s$ID3VM;kra5{iO(jBSy{kf`ujUk#ibb&Gfvn4Se(bZQp70t z>Lu;nf0AD;x!peD%GYBFo08IUwLE@rQh0kBG$}u;u-x&MxU8@0t=W&)>@m@~o_IRl zefN5||IaTR;5~EPz#v|GeXZ^5^S=)iXW72GsQk_2_s%teObt;tze`Cy`O7fff#oa< z!&I5Ck`m_Z#`6t7`roL&zV@BayL!*Cc}}%fplW4VPHbP6>a3y?XTi?BhB;lO<u|_0 z3+@w+;$9fG;GGh~iQNs2d#ke+Y|mO)zk1#3SchP<L*mR0-&syrP5itzPi^0yy$PR7 zIkVV)f9*Kva-if&+!ftzV#*a|`5ayQ{-2dg`yb=u#?<h<>7Ce#-99c$ZDo2-z1cT) z`GIGOX`)xWR){$7X?o-JZ6m)$&B30p>sN~yEp?Kbw8Q68T>YcZ?Jip_&x%TB-nTpY z&^p`x^w<4P*_CYSRqcM6YxiYYEba4By`Cp&nS1!^;{UU2-!KQ}<{g}=e@nWXafZ*G zn1nX_FPWRKwOzb>^GewC`!{3OP4UkD9L#uP>0GU)IS=;T`q}X1<%~16hnn2qRebz& zp#I;*;$PpcX3X#@JF~{OHGTgjwb1Aat$)+n8E4q|Ocq=f%2k{7jPGVj*0W7=74H}< zcKs?bo9bmfyJuhBOdWyZ!b1<LBZ7~nzWt*8Yh&88M<zOYlU;Kk9+3=P+vpSSZESjE zgG@qzdhe=@J8xx_%&JjNt7!E(W%VgPcj|^7t)6{{ZYXBG*4a{eR#b9oc>U@#Kld*D zvS-Wcn-*rDLvL*`VF-!2xnA~wsam$FY4bIc=8)-b;oO!VRwSxD*cX+u@7hcev&yei zo%74LhA|0ruVQ>L|G)zO%PA_qK5f5Kv+%o)MC-)jKl_i0moW#N+Rc5b>}yB#mT0j# zKWlEyl5LBg7I#lNZMtn0!=m)uoYiNGi@v89%PvmOTXW7<NWeP&_q3f_=@F~i-ZprO zo#Tst5IDKqXXOh`tM8@^nc>1!+>!U&W^^A+`JMdkm2voDojKnf&#(L%p}+snrwiXy zQZoER{{>u~m0mgf)MNosW~m+Ri$0m$@;aE{B+<F6BxG)zyNHUfz|;kgEbbg)lT^_b zUHD7qmKP)2k9D=dJ)ujSZZfZr*kB>>V}TX#-Ln~|+&<`7+`jmD_PX_!7hgNsJkF7A zJvTi)e&Zg;vyodw8XhxDcL<r^x<bN-@6O?a2~CeXCOK!EYy2;=WqR}3c5j7MmoG%I zs7d$91(Ynd;+=anVWZ*)*Qc5#AqO2f8ubr21oIvF`eH?sfy^Neh6h{^p7gf)gv@PQ zBACei@IhZ!$X(rhCiwyx-Bzt0hiFTeqc8GUXSX-31Z`uynptwK;b22EyT!4?^B5e~ znw(2bP`PFOFJ<lu8_s#!QJ;S2t`A%E$;3+Q;IqTVQcUr}ztiej*|^uXe(-IozM=5^ z=pE6N-d^MQeQj%fR|>DZ<bC$s(RJlD&*f+6l$GAw*r8ee!}VNA0jRvv*}KR5`H%Lu zyse(z^UA()oU{5AS9>wDH|pgx@w3Gx*WaHmF8bW>RrrzTqTZ@0o8~;0H=7#!#A?Tp zvv=17d3^T&AOG^Ht(+sLp|LrW#Ecy`Ev*~=1Y55z?*AkcW7{nJ*{?1tx?s}Lhriv= zJ+j<&a@TDmzI_)%>MYZ)9s9NDvgyy`M{>7*J({UwcK)cgi(2M++n<HSscPMa%fEM@ zwEI?9?7HiK@(uf{ZM);QOx?*mq0B5*{{MoVM$NBZXz_G#_v~G|@k>nX!;|Nh73tmA z%sOVvP;+RRR!Y+1!%sfV?NwT%ZS_>x&h+~e^<P(J=$tzs<GYOQfPL1v18dmlSu;%f z_UldZd+VL-SH$P7(zQt3=}>cM*@>mHZiQ`XYj=G5ZJpECY+x|&aPgaWIXp9W#4MdM z_usS5nbP;3e42aqXl6tV<Hh1u#yR3W39z*Qk9)hS5;lfBmwlO|m9JxKzadM~FtYf} zRROliOLf`P&lj$<6TD@0^3jLv&%x4O=U#p`nz`(v=k<ANYTe2OpTBo|Z48KBaY!Oe z;xy~h=lUtC?geY_+-Qo|_gs6k=av<>h*9CShvnVp>%&Xl&3=>oKK!{HXJ7o9Ddqf8 zOSfvRdn11Jsp<6PzunG#>YvrSF=F*f$t}wym+UeL(oHF{xE^nD!Xf9h-t<$iZ?nm_ zS$<ey%(u_bAmOmv`jvlzau0G&-g+)YY@eX<kwve%?e|8^ES+%jQJ3r0b@v_~YWSEn zHD>;@^ngd5=l^GH`ZL$|I485t--B1LM$Ig*O0T_`X&~YEj`5c@*Ji%|(Ry#W`r_BT zc)9D(>D4dU?@cH(+j=dffBx=B34^%()$YljA6xS$hwn=$z1Vl)X5-cQF*5rc^n}%Q zDyAHL_;Jo1QQKJX^!*Hj;!Kv~`sb{_&fFKWH1_PY(--dCOf-<NQU8AW_rI{2TkW%c z#qutFzLRg=yhhIO{=e%VE?;s|!fA4t$L^?}Tk^R!jT=9+$JL76GAurt^m9&B+Lyb{ zh6Pd~PU}{~ccBO{+}M}&{mzT8+xnc+Kkk3?;-*iEi%ebBj`{l2y`RX-Zu|1Z(8=f5 zm%#o~{kRSP7OqRaw=_PkcmDpX2cJqUo3(Ex&(1?We9!GlUYq*gH@+~9-=#U<MMrDj zhS{$lSm`}9V<^gOUtzX=^-`^(Ukff@=!?9<Beij#<dR(}DH)}iuagcM)PMN#p?ssM z{cAp#sr3O!6Bqu+6j~-MG^lA?Gw-#9&(?RIlMdgRdqec_@;5Il+tt?B{Q52}f2KF_ zeES;NmkE_DXTK)5t6q+pe73yE{EzjwW9*sjM;E2v<}%)O<85Wgmy)^vs-jQbeP2>; zvSDXm?pM~Yu9=3K-(#=)yxnG!@H#5DT{XGZc*hg}>J@sDQl+|23YfM%7j}H{W`;9p zbBB>g_q{Do-yK<(Q@8)>HN`s_Wz{FLmfF1ju%GdX%>Vo^XL@h7-?{5i7HX9G(jK%D z=&pU)(fRyR>-K+iycN1pVpC<SWbB)7Hbp<qO`dK)zy8(c&AaD|axgbP67${jm2=+Y z54+N`wl7Wm9F-fcYTS}G;nk#hXJ231DwTGitXhfV#hV%Ki}OzQx-HIo%ig<7^|~l% zU&ym1bA4;l{ol5jrW^qs#_&eowAn22aNzco0Fzf`A&UdIgJ)XIS!Y>;Hn%QLn;>A+ zcClX+ED9ld)UGUc=KxLKfQb_sPPSDo5li1_M0MxLvcSbTY$clov@0tr-rU&u_@cY~ z)>4IJF<Z&xH<JG*8-jImD7MUS`Tj!CXveKvQ4>8x<mK~UJDhl-EV}U5n$GLy^W1m? z4Ml=xvpPUkr!2X!Ige8^#?OzB;nl_6Cr#sAPv*bKYrLPbVaJ6Pin*@oyvNoz`!~Ie zt-2Lh$#pf8W7f_0Ung`*2Y!;CRs7JLlSgfeZ2`Y?0GCAAod*#UyCyl$_^D&T=gi+A z0GV&<um$ZwW}7~D?%U_jpFez<_}ZaE_oqsO_JODWmHwUEH#Il)MW*>~?)$us#sPEF z{#2b{vEzvDcouWyJ}ZNiX;Jy&2kJ-G8SeHDHe;zP_~P<HSHsd|%^mP;8i!)b4Nj?2 z?-LJ-ii_2KW+c4U=y+Q=xA*#v_Cwm&9@+UAuW#=<`nvjTf>MT>)cP5BckGq9dEdc2 zR?9cU0~!L!talf?pLkGIRP^l3%;eV^d1a>01B>M*dIuEC<t~*l7hlL-l5d)_Xt`{T z-K|p(XS1A_xUzilE0aaj7Hf*jP7U~`kS1!9btT3j-E`5k!{(d}N4{q4V5$_~6)m`x zNw4v`K)+YxF`W&SALcEHUgN=foiq09gWXCcj1pqM-}~g<pVO~x{m`8A@%4q@l(_1g z4urU@WtiN2C;#D-?hUQSUY<DmfWv2cbGQy@W8xw!-Wc^3U8aV2Vj_RL`nu{^VV+1S zStw`g#I`VO_2<u@<tv{EMza@f{_N}WFRnv+!Vb>0M^F6WanwxsykLS-xw+ULJ_aUx zkv}Z!BP#qI-sP2qC}&yD$O)O_a7|Cewxjd=Vmszk_Xo3CKtqlbE94ob$R3<}e&Q$b zkmU=%HFe%e4s(=PSzY^N=Dx3;vrF{5z8$odle>5!W5Ped88R(rHkVkaZU5fYn$B~8 zVRG++nHf8n%;a<I7z$Ya3SC*TaMI$%Lao0AEMyyA7IDmKZJIA=!tEEgOZI5#j2{dx zt|$K3vz%w^uGW1HPe8Tc1QZw*r8Uvx#YPFU<7EsC=RYzqAL7WkGNHWbEo&e1vRr0{ ztwN8gI;0sIz~e><n-~umOC4ngEs8x?_d<-(0W?zdtMq*5Yr{OgW4vY7&lZ_8I^1kN z6}-z-N;FGfu}YP}K!RgV+oi+Ps=nyt$XhVqjCb7Wb$xpH{LT}p0jCZWUXbm+cJcXv zCkGDlI&LmuoUPN|xJMW?tHdNFnliWGi_DV*c&b!<bx}D*z|zvvN3HnJkB{5<TE1N5 z%eeYQ?^EjvJMKQ_n5G4Rvv1A2`+ln%E5jtUAHMIt&*;uR^ep*~%n2(-hik08Tw1I% zWEcv*Tv}^>{Lr^~h7bPOSAUn451qQ5@z2a@K2`7cmNT{ZWjJkUToAP8qNr$ic;t1a z)vteVdiAa;?{F;lf_+V0tbr`r3%3V2`Mxi`R6YOSKSO7sNheht4mo_Pv9J4cW^eI3 z%ky)3-h4W}_j$ykPcm<69tt!(GrE$tXfL1KWBu2T;h}F*4^+NT5@Fo2WuF}6hSj?{ z5f_!E9KgpgHB6m4b!GE}#3)|B|KiE@%-rr<LgNp%3VDYtcUrwOME=U6wOpl^%=V?X zm%g4DQ5?<Tnz8o6eYO>$<@QgrCQSUsq_{_I@f(#WErDGOr}(DKZMniXjrp!+Mvh#> zPGuz!kcx!bCS|^Bui%$GFMY}<&s`U=G{Z4l^;ULbTJtU$hJezzZw*=u84M1K+X9x< z^Byo|WA*g-&GfH$L7;P)P~&H|idSKGIT^BC-#>lM;#A?=_-4vJr|{|A_a&$E^6DzQ zsLNer`@mF^wfdnL^F+x#Y7cKjchv6q9UIEdkfC??{`I2|Y&uj7w!2pAs)z|hGc|;< zGDwAf&jz_qNom(hiM!nsI~ulZG0|I8uB_qB)^KWbK<T0%91JJ?92d9kl&x8&Tq+%8 z-<oW&CZ;e^yNi#Z;f;#bs|#`6mmV_&)Cim^n=+T7;gd+jPK9TTTTT@Gihc5rV}9m@ zThiPYq8cALGfem`d@H+pzw|DKB<?3~++G&Wh&-&!#~`As;mg)AY4M8{uj|%^N#(6i z&f~r>`C%p>!?bfBW;0G-;Vro;V23<IQJqWon@tS0&lSHGXIv?e?_TphV0!nY!wdmc zGOPGRWLX+EO}?;#-SV#s7?dyzX6&3G6!`y1(azr9v&-k#?W*}%6r3*k@Y(;^gjXCU zN51Vj@xN9P?0qS*J?{M{W~^DGvoz>r^_PxyQ#Q%w@B5inTf28<vj8~7^g670At*U{ z+BCI^9!^fb-gG*+xNQx25dZ(z^!fAe%m4e(zG;(D@NuYlfe{y#jnr&yZEbAsoH>*8 zV42I6=464c?(X|FpU>v+`>AGNU|?uyXl#7>%0kFd-EJIVUpjg`eSM!QZ+8hle(P4% z)m5RDm6h^!KN7vXyh=*G9BSqEpJS2uDhBL77js*XhKFw3U9O)vb4JI|&`?)5_xZWG zrlzLB%l&%$`|t0qHvgUq_Mg(OtTitLzpmc8b?c5DGem6{Wvh#Dm72d$RaNy|dTIB& zUD=nGcv_dexsYM9tj`T>e#z%V*ZvjpnVFeUYt7Wuj$Lugc%ot5xas2GD=+s{eg+*N z@al?YeEj{?)6-g8TlfC|_xtVJx644+y1BTxlo$(s*r~qgU(UTfKYu=-pP!c}#ufQ{ z*}{!EH;owL>;G<D*?dQUi;K%F=f;PJ?ebAkQR^Z$KHB+w-sdl0OiDGtj$SmI;kAg% zUoU_E{=U96%l?cRENpCfH#RI>vEs#1@%THtO0~Bif!vWSr7}&c<JZyNyv}vZ;^Nb< zt_~L$6U)1`<>i-`mv`wFet&m28y;+WVPBw1rHhL{A31X5%a<>6t;?@nzpk#L;xoe_ z@%6Q}SzB*ixd@4uJPS~~hebz6$Ht!RlDqhI$!($UH^3J?Oq@8e-}YNXM#hUaUg;gB zY~XYf=nqm~_VJM`!<rX@GhJe0?p#|Ny?OIyah-?{r?l7q`1x~f<mP3I79F~>6KVqo zNXN8k)1JL~^XA>VyjKb?i^Br~Cgi>DNuO8wY;nIG7YE0KYm(q-aY=CPUtyn_nQ3Tf zxXjPdrJ%4da(7v7VBkg2QH{yR`&`}KK?kL}_sJNR>Vd;iX>y`#{|SS<ZpRYmjhi<8 zy8FIv`sB%<uZG8mhK8PnY(tN)`Pdq?(xlV`tYgvZUQt^m<}FdVRaI8nRW9aI6Fs)1 zoSgLdc>nSxpo@7`)YN|c`n4{0_qKie?!iK8oqX7r4jv6Xy}Z1<G}rzYZA))kDVv*r zpXe@E`Fw8qpFe-X*2T=6IyDs*71x=yt6bQYEM3aU(sbg4M=-mhQu3d_f3L5N4v&ce zox%O?=4N#*Ezm6^)!*NlLcO!-;n6O+iHw<<nRa$|-@biY#^>b1ym{ls$gNqSb#?#F z&9#=6k`fXUDk=X^*l7#)kJL&~c5INoD|EM{#p&UpR_=Z|+gXz)35kksO*+bDZ*Q-+ z(H$JT%0eI~6)cWkG&}sdP<3Z#r?gql1>KF)=g!TAIor8S)OOLm5UtR#u&|JjDJz== zE?&K?yD>Z@1a!PteEnZjEv>ARlT?wSV3Fd1F1f(`ojZ3H?VRI(SE!evtgK9b&j+Wt zxO>m%*XvC_nRafDq`3I@)YD=+WAa{QfF0u!-Vd@VC^*<vDKH{p2FRuh0^LVXPuKVN z^YiocoN17FDA?cj>Fd|K)6UMibSWs<9a7)yk^*J-Y4hgE2?-@7CMLd8a4|XZ=+Psy zygLygAz#|<|2*7$-j17(FK%1T&5g;&edcz9)8dO$8y2}=iO$N>+J00)>foI_cf!`k z#Rdd?xS2kG>a=Ocjvx1jWDu{VmtfJ()(Uduj*Ge%GZNC$ww1gLy1RJC#EBEN!`57| z?TU_zgL{WL!L|Q|k*qA}c*r#`1bgKQ3k##S=jm!{M(!+n+Ad!wAtA9N=jNu#>i)B= z#38w9f5b)QT|RDZZBc8Vxovk@+}qxM{MOd&RHK{Ad}nXkv}u{o%th5A;Y)*NT1i24 z<ga-l7^`M#8mcvwjg@t#6^G!=hMhYrlafHUJ@(633Q0)(xRKod^XJdCvAegeTXzoT zkzE@XxtGlR^5x5k6CM*iQeG*zq<DS&_%XizZ>gW(xx@VSf6iIIuc)q8S5sTIbm>f} z3k5+jtAFRkw2oaYY;5bIx3Al=qvCKIZ~D18ot>SX{r&g%)$Wd3YX;3)QddD9;xXT) zx+pFuCud&Gr;}H%Tv@V2g`K_q>FMe1t*vY0_wQS{@F3Jx8B>y6`&UFeJ2(5NCA;=_ z{1W17{rv3g?Y-6IWo6&ymf!n%OgbM_ro`+t0@WsvQY+&MsPLYhH&G|-OUH?h2@@vp zN}ElYK7IekW75^%-gNf$`FVKU*jv3lY_%!OVY(3)m0wMpHZ3hZ{rTIsxvvylN)~V4 zx-}M_tr&HpwrJ?+<Q#6}&CSh))f39{+Ep%hFI~Enl$6B6)CfwWXB{;}^kQ}xXllN^ zv$MGP*_q0xQ^Rd+ZNt|_g@%NrKvTELq>YQ*uk_wd61aG^v$yx|j>6=?z>BB#_wPwQ z-uK|a16A*7GIljLprvF+N|I~8+t%;*s`Ia}i)CeH-Nm}$(&fvM7nK*Se)j0mr&p`j zi;0WZf4^Jq>+8EY?QB;^$Bhk%&e_?kS1typi;EqHy5xGZZg0zt-jWd*5HMlt)X<!q zHGB8gIyxS_x3^kbTiaK*w<9l1X`;t>jdv@9m#g{D+mm)yN?v~c^ZE65>gvZ~QPPqC za>|Su5}htg3l=Ya{OD-+(W6KI|2$tWBqU^GWAo<iTXFrkH9;$V=1%O$3lmoN`}1V7 zKj<`+b+Nzye!t(|-mb2ql5>CG-1-gR#>GWbu;*5+STV0%YpU1EkXLc$rl!8LOgweO zW-Eyc_R4(w_HA|8+Eb@b-`<?w-`sro@Av!fpFiJT_V(7SSyIqkzi76oc9qF0S2wq^ zsUNC@I9S%LTL-#*VST-dlGMZ&r-yqgKkxhZ>-Cy7Yue@Oe(eAMcYS~V`Aw;(`(&-t zppgQu_1(6{eSc9Z$iV`-a!f~8cYU#(lGMkh=4MdI92T}M^YXGebLRZ`@q<%XE$7yj zm3#Nzg$B)wWd}iloR^nZR#vvxughi8i4!N-<th%SOzg-onc%gwv$OO0`T72yo}Jy@ z(Oa{oPM>~#Rp@FiZf;Q6gNmR$rZq1vW{68l-hAB?wf5il{r`1EKJDjIk}4}KER;6S z)6vq3+MIUw++6GC=4N3bp|bb))?Uqm>yB9yc_BkwT6*>EcVX^I6LlgsB)q$`Q?19v zWpVH9*|%R^UCqtKRrc-<XTrrrt_v3~e0_cW`t|G0p?P4J;KoJni(}U>{bC|@_Se_f zzM^d%ZpITmwiG-(v}DPWGiT0NzuWQntoi*fpFVl{`0Oco*aS;my{)3QQg5sB%C#qY z%&U5}a^LxfLV~gWiHV8QW;q)A`u8^^9^P5}{8*o?b>g9xwb9$9?#!MI@^FWnB4hZg zg@Nl<tvYr0ZtVA4mo9Buu;9SivuC$V%uoTHAJ#5kx8h<(N&C&4HyI8cI#kl`wD7~n z<MPkVbW-kIT<m_o^7-8N`+lE0dGh5&clp|1FPGQW*80kJferWR6tz{lar?HpscEOn zqW%BAuGioHXVc2Z7dj@*nq`%CMnaiaFK&;7uyFC+PZ!Rv-m|CX@-pA|`~TO)#@>Cq z{r<kJtE+YvKj&g$3Vsf*NtJ{XT>CjLFZZ{v`?F*D^7Oj8eIZ(=r7}{PhYlYu-Tv&W zsF2X4$&-uce!k%AyD*^U|KIPk&2n$;F3*pMxRGD~`?jcdSVVO6Y-r&b8=e%*zCdw8 z;Jld2L0PXv%niluvt^Da*YEhA@=-51eP^RfrC;&3k7lJ^6BP^%3*X+_S{v>#*+XUj z&$IbHLY;YWX=!QR)AeF^mAt&UIURIN@+s~0pzCZvH#%)TZznA)oBOH+T$`56{UEn@ z;)C8;@BSw>$*)ArH(q+I;eYT+I-}jbYll~J@1G^Q?aUQTx28vr9yK&H?5n@Q#nSZW z&!2_{hRI77O<cHc-Mh#A_I3aNe(&z;dUkH^?=P4A^<#Df=sa8h8XVSc7Vk>ES+vbt z^inMQ+q&n^kB^CoS^xDM3)8_CPT`1ii?g3RdGh6wxBk<oPv73!>a8?UCvww~`}gbL z-r8z3^UM`!(JirYkvmH}gT;n*PKPxO4Fgq#zS<}YbqWa!`%Z0llUNwABjI4v{JLK& zmn?bm@wj~b|G(dBYiostgtq11Ul+F8cWxipHEnX*RW1S__A^VRou01${_B;sZi^## zm8@L(>4L}8r%$(*y}fnm(k1=<e}oQvdV2csp+nc!$HxZ;CqoMYlPM7=6_ljP)~#E& zIqmGLUB3P*LT6_h9|xt&l^IJey`494%9JTHXYNcnIcfX7s?*1hr{CO^3T~!B+K^J9 zCWv4xKln7U+h64Bek2OFEeurB(aE{HtJG-bo6G+8Q%|OFa&ig^3ckL+K0hPF0G18a zKvlT?C$%e27krTjDGGL9`1;+v>US@1HHK)2=*8{1v86KO%LK2b-qZC!cPDyzojNnq z_<qG>UVHofQ?<kA+1JAwr7yHLE^<G-bfrkTy~`zUiw{yp`(2NfrMzp{boa`}bumXJ zWqxu`igT*X`+oAATgp3!OWq#8nLa%`Sf-lq_)kvcP4kT!i%FMw&tALs?c42q@$REZ z8-JX$e!pe&X5&&NsZvOjN@McLfB(Mkm$$D2-6t=s=5u39W^nay-yiPApsMHMi(_4K zyyDjK6+O%h^IvxCV4vun_^_kr?Xteor#6oS48$3{`pf4}xplanPbI7)immwe!LroX zyp0Tg3!UXB<#F-bewh%pHf;4(e!CwFR&KuVA~ikz`;*E3%a$!$wq%Kmo7=y4<@-N> z`V_UZDAmoa4OS#2bo$CRxNTY{#8AL@S>CE`LBV{^$1!`4Ia#nQP-C9kJK@%Ae>2g; zwK^<|v|qTdbt%@|vz*8Mm~@EOyhB$6^AzR@eqI{nt-D3;A?KW#^VC>o&$K#}AtElm zz4Z09?f0s(PfybY9sd37?Cj^~=Kg*%*<UYiPlVD$iT&G_E<Jke*t1_xR6u3MqJ0q; z7bk{HXWq#A=FgXQ*{|UR*0+0|SGz{@D!n^+l6S&fmkVoueg3-h!;FH|SW_{F#cjza zCZz8v%)N6t>lKH&*n2~6hMJ-X-h#AUz8qyHr7agv-@RM=_0?6-HA?^f{x;9ORr3Gu z_uad8si~>``?h`m*Uz6{zh9L;zxLYItEGQ`ePwEVP_+!wQIrk)lCh)Y%EG;3dC3X_ zOb+hMpXwYR+_{&VwRvIK0zLLZe}?J*l5WH`zbct=+vz6TTCqCgug`C<3Y^PjEPW;Q za52*y<pnwJS6QF@Yx!Y1A%fB2TKR<S3T7McD_Thh)Ub$Z&iKUiYSV=8#(S1Itaf}^ zcw~LsOkRd1d-#o|dn!2?W}QxW%o&}3<M-k>DooEDHJBQf8M)}Z{HIg9`DLb}HS0vl zC%PG0ZCih*rk?$m*5I~kL8mv%AH&PN?iwQJW}D~V+f!*Y6LjG9`~Cm_-Ok@%ds=t9 z&G$RS++sQ}Lbqk-<ox+`TK{QLWn$vP^!c@EdFQ4&c7lq7b>{09yB}U^Ce3hbRl&#L zId$SM;}yU7RU9cbUvb|39RG)TJl_j5PPDHIuHW}bhU?qGd^MY6hgDbocD(z_B;{?3 zzs(*s#TQ{qYB|@k33*rewYV*n=W94$VlrJ)+UXU;MoX1z8M^Js8cfd)8S^P_ch2dX zl>Cd^S?q<pBwN7jmGM8%smpbVg)C=ssMcK*^Y!Sdf14ODteEhNb<Ldzc6|FjuJGHN zBe)mjV}tV>X38ZR`^;@x5g!*9mwkPmuCDIiPp9?4%}*1PlE1&cnwpx%=5EWoyDDfU z!<#!hi;wk4Zr!?7t=k(^(3?bov%H?PfI^<CO!LJEmi3+mov-S`FLrIo<=DwAp!8n7 z!oTqb6GN1C;DnYBuD_CIwkj{P;b)NL_4v;v`29tB=hO(Nn|!X^3>-%{d~}N5y6^cl zt{wfRW-JY9k~(u21Rg%bxX(D@B@@R3sm1HBF<w~lK&0kn^OFOH5)5~e67sq?J!S}) z&;7ihmRb4crv2?xx!?R{T(DR!D)+nccDF|tIn+eDTAl96_?lZ88*g6fJzY&zH8m~m zUiJIE`Fp=kgEY#%y}Qf(VDI;PmorQlLbO14l&bs9nK65|b-;9xFI`NgfU?!Xz{Pg* zW^x9b8-H7H99^-iAhP+6{6jM~SzeF7JlpPZ#ILcRzgc>pvEJ(3mt~7i+~nOJ5n=V( zf7=x2B+g>%zYAxYKJjH>&|Rgc^gt}xIm0wVr(u)qI$NzChC9a=td*L}%Meh?xX+lu z;UZgx;zkyRMuB_57Xv!3ab5Yk;>FkLYZo%~9{p8Y#AqVwtkC5AfWg?orQ|UOH+S^* zyjV}qllA{T&;Rr1PfJV7gb5SgyvbP`wmN%3h*ql6%_}Q|gM)&6q^E*XXGTb(Yk!+- zvf!1Xzkf55G-Hwjrq|vKUb=Or!RE#zLWcZ@%G>JxTC8R3ZT)3^OK-7jt=yesUv}7V z`z79OPrEk3oY~=`;*YaU5x3q8FwF8=FzIl0)_d32Z~iJyTA(K``!%5Sz%6EmSDW;1 zpEy*_)si$tra6ky_%-9EsdF2yFL|e4+|7UZ9{(cm=&Enx{T(mdl2cQ^9ufARV_E#{ zNT;yV!VTB`c6cq_v~gqMu^!3Y<?qcxoxmmA#Wqn}DY4R<3=c|HiaoPrlrqh_^tJty zn#QdM#=P6^{c4)-#>((XY{k?K1+U(@my3I(8;8hl_;_J{$d*N~n4I3f$y3|dvPZJi za>A{{=dRxnV0cxeAadArS$SHcfLUCIrn_U%_ukS_@m=<;493|zjxPEm@<#tHL#9e} zvf`VXFV9a;x){cMTp+{rLRQaFWu;w-tnBRKVq#iTPsKgInzc1XFMdzO$LjZc(<dc> z)68OC?JAQmTcZ9pm6T0C71yUY;nw0mmy{!gvOAVenA;S_ohseM=Wvsc;n_BW?XJFU z`y!*K{u3(B?$BNEhJj%%o29+NpLg%v^B8ADF5b(h`}CLSmmVI*1$N?o3xAouuiE(4 z&DUxP--aSq23PH@;)K`5k<#}oGPd50zA1HbS>U3jGE%Bu{mzS<BDk#ML*_JwW$Vb@ z6}csqvh-!OF<*VkhYxHEuV&54=I+-26H@bVX>~{xY%PF#aQZ^Qq|?)MW6$6Iw&-e> zsnl8H^ERLF6rX<?b`w12vFPDp)?1k!no$$>O26I8FyT8l)AK`T*q9h?9tG^+zqwnW zOuR+OMc4V7U&!3{T7@Pd1tWHbMuv@@C;rJzeXg*zy;psY8gqj~%MA7j|FvbB7rtuw zuk%-VW30|xfhzTyW##i<=5vIq&+-!3d8MEt+y6@1>*)`(*E>Edzp!fJf9*eM2k(U4 zKXy%e-Ng-GFUd=t6x$_mb9cZFdArLG?AbR3udwL;a8#g+L88z7dT@1c>bXw+ptAq0 zQES~#lxSC<@4I%Z@7b(nuVUVJL<@!0r9HVdYtrYF@$0vJ=jflabJ6>UrmLneo&W#o zeAe`GuO()Vh2`2-vs{HfZ`{5&<GGZ@hoiO{*3qlE{p9a_y3NTQ|FwJX<6F%aHI`q^ zx?lS}c577bo}0Vh?~9I&-CO!P%-GoYu`ak;c(ID}*Y8y8yDs-`Z2jVK&U~4lp-{@Z zhVLRbDtPY{nN*ZM4BvccT5Phq|DJGrmBhBru*LtLRLUE3&u0HOO>@VVCyABc9<Dlc z`Eg$L!5>@aujlOF_jKirpZm=#DtfujzrVNr=fxX8SF7p$l4p2&)4i|m<DX4io9|XS zEX@#~9m$lTasJN7=|6VI-Fo~=-dyEi+sS9kW!LYW{KqTQSv#Ls+D%iP@9(#VKV#dK zCVD7{aIrWsF1VVtHEONb)xRe1Zg5`yzw=|XbaZvFis~*w)}7t5Ykn5+2nq`FO5R)S zz9f7uTXp@k&u-Iyed5{b^-gx@j@5J658Sg2(U>H$lglBvw9ehTH~ocAbNlsmy9`(z z4(!-n(ymvRJUg4~_Uu(UZ||_}G5h``+-adk#v>sH(aPgzb>76(9OtXJ$}yp2;b)(H zhpuS48M(TDcx1{R(p9!~Q}D%mOG37+7I}N>T-ee*p-W!`Xx<Wi>+4lHJLsNTe!hmz z${LlA2WRr{&rW=7Q*hm7@qtr6uL(C*KGp)eIqXZumh2PlZ%lIbDo#68+_duYg|DI0 zHp(}YFR4?X@@<*c%HGLK=k8uQclSqb?azJQORk;Uw~>v1eQf15MQQc;=iXCytU7f0 z*|cxdwyk51i<tE7^~K!t_rE`DT~}vwIE|ykze+e(+L+rqeZC>{c4(G4-X+&tmZWLo z6|wVx=9w#jFLr64zM(F_vG-6q^Mw^tpV$99zU68D*PIIxQ=?1%v2#mL-_%pPF!<f~ z&TIBX5i_U15wzL6I_TQ#3lCbS{!|Yt`@3|l<F-FvH}5hFWnKO%HB-=7j=A8?Y4O?F zTzU21q8Vg$O-nazIWbe)L~81yy(^9Mf8Lm`e?<3(GE39Cf8LkBnOqg|I<xjk?pI#X z$Ry*{FTd}dyQkLo*TJ(4cJab?uOF5-tLv{mVQcnqoqc9Vm$Ci2^Pd0Cm_OSl$)6{& z?IpOmskG>I3#coev&Z0BVsN`caKNeCtGN8T&+1Oz{y%VO#%gVE{+`{t)0-c0+o#I> zE4U{dts0cQ{eb80|CPs^UvFx0GHf`tM|k39x%XK&K^}YO7@YLXZt|9oj+N1ScTQdG zb+htKw|Gs`7u7>6Zu+a`UaA*Noyor7YMRV1gU1)z#mvr?<t+@JzV7v@Wmi`Om;Jwb z=8#$0KP?8|tE|h*{#Bk^EY0W>yKCJ_t@y0RHoqr+XS^aZfAV(oD%Uf1U;n=DiwoQ= zf4Ahv=JfV_J8&NDc(E(dwZFq{<)=5wQd5)8+(}ov^HqK6p0`i7uV?Lvz40~AJND#4 z|M`)7s`k5N@gBHyD)8R53m0ROQ{P{_7I7~q{EeiU^Yu;F7f$3}E4#Pk?b)?5-RIsG zec*VXvF=*z)qshjrms2gzTR|(nc-di=S5SS8&hS^|JmWEnLl^O3)8!a*|nSu{TC`2 zvX<^KdS7upw&Ll{_MAC?PHpC6KX&)+EBW$w)9Ziq?yU7#J^@shcXaqPN9PG%)KESB zCeFn_DevhM*|(3(*S)?w`TjmJgS?4ry&K+b*r#*#&Z?lC*0#%<a;wRv&)ly__6 z+THZFlwAn@qNVkDQtq6;I&bfmirQ`sikr31+~%Jk!-cHWNcOjPns}#uUe$f>$=qL6 zk7DazSxv6~q;0)D;qIY&(aPgjv|7WD$oyqLW2GX}x#o>+iS%8uIX~B>pPU47TwdHB z_kM;2X534UFPL=rkYJYO625|7M_;QshaX5Jy(*X<yyd`|V-d}_bVO7Zu5_t?A;H4% zNz8)fP`;QB`}UVf*EK5b7Z>dRmvZR#-q|N-7yjU7DClmT%U@K-z+f!><Je+5@voHv z(Fx~XAC{iFE-LewUFVf!rUi@M1#F);cV1ZZyxNp^UH!YHm#bICubLA2OtqTD|Me}o z@0*+#i_eO->{7k7Y}KB=YqvVf_lAWQtg?Bo(XiQmuj#vQ;-%7Wu1#NFZW3Ppw&=F^ zvxogn>bjFXzW(REGA-_m|4l(V+raXOY5UF}&7X7S7H310=6WrQmy%}Q+rPypr~0`U zZ>|1tC3}X!qSaTfDXi8%pR-cCZ_ds`S0cgT;>Hp7#m#yv)6Lxq)}0qvKg?cgA33jS z^XvtI2Y<5N)>*WePyPPEH}=xmk7f9{-DT>f8FXX>zl$(DdGF{bq;)>|(&i0P8T&8H zTg-C5uWR#*9Fsdit63XXJpJWcR4QuQ$;y=HctH2Wz1B~c!NF4Oo9LZ8vHs26U8NtZ zGP73&l$cmnxxePKj>_UbSGWJg)4jV6pW5@JLvlYO!&)&W$MepQ#hEs2`MzUA`r%mp zw~Psik8fR!nOa`8J3V7h@8tFC8sANfUcVvIV2P1_<+H>8ukL-9vv&7~*Za@t%Gx+R zHq~kk$O)UaQNQ4j?WuEN6OZg!^<YVqX1{NR-}N02-uV6B$j$0BanIU=cTPQgrQWwf zUNv+7Gqw7Qw=^b4S#G^D-6Sl9dB@k6`n8LMvb@fz*YCY`Pq`*TyQ+7p<x6(+bh)1r z4e@Veg^XACO`FyC>{Z*TH=tTir>68n?8!}ha(BPA?~eO(G)chP>-+H&JTay7!L6~s ziLUuuPT%Cc>1okcGW|0{g<r!Frsvyd=uJ~x<u~WIy~b_!yv(PI>Mw?_{y3|pNo9pq z;12nV-(zoTC~f{1ot^M@q5ku)q9*cFpSK%o#daSmzR&#P{XA1{X>nt2>&ocn*4}Qn z#a2JxW?!DZe{FS9*u8r<0%pDyl!~8NeC4Kj*y6zNHYP<2`)0Q0o>=m9*RQ!t*JisH z_wHG%Sn=r6IyTqm^$ZW*m|sgUSh{Dg(f1wI7pBab^f~kQz1cPAU&sGFU$Js(^1qqy zZJd^whds6W-J|LE*RtYKP~<m7Zt3*x3r_Ch_P#v%*!_P&#~$|YQO*N3@Waxx-~Q{L zpRrPR*2f2I=QqsUH93>rY~GJ&qU!G@82)W6m;3#Q_56h&3uUk0vo%S3cX_6}-8ZiJ zb3Z&;9{c<<UroZ}7uGZ6Lb}Q}&Qx9S|8I}m;(fbRn9m)!`mzr^dv}FhyJ~S%vf?Q} zriS#G_uFF@J&>#ZEBw{_UQe<7!nIiiYgzaD&xm{-FY*52DL2L~QGXY2V(VPG;iJro z?$y0s*OlHLIM!W#pEaPMZ28v3{r_*U?v>(jon*QHX34YTrSldVi^%#WKl{5bd#26A z8)t4ET)o!u*%M<orLBRQx2olsUc7gjd*EaD;^%g2t8*W}k+*#PaUHLrh^+7Px_{NB ziChib)&Fe2U9*1?cKmhbt4aIk{P?zYOY>|S=VkuU|E4);Op3CemMS-6%a8ikUiw~Z z=XwX#&)xP%m*Ht-drflQ`zn)&r7w2u_`ZMgyMM*knd)7f7j52JcK!DDOp{edSAX|f zyIY*QW8UUXFYf5wE#I-yYX9P;$Bav!P3VscF5+wOzp`hZ`rJLqZ(@G`U;J~@oyqZ> zt&0|PdNWkGo{9YT>*ngy1~VjgaM?ZvjaUhOJ=%3|g_<>M2IGNi#}DjIjODJ(44l<7 zt0cl=(PGAJaU4Dk0X<*V2h3ZPZ}hr;!baxa)(vIuUuq{rC_QJtlIFO$#oOf2yQUL7 znemGr_3ZmQ<-YP~>n)*&&#@<VCq8Xj#C+nf=l{GzxA*dYu6wzzK=nWKHoJ}}wv50U zmaUN+Hni^%eOP{Y(fsQEDY?JIgV-}nH7uLDHcz<ac#&@_)4PoyX7eswF+WgmqPgN@ zX%n%7r+5QTCq8BBRNbQ{J^SH-oyXJ)4y<rncQq@phGXkYgYC}6lDD!Go_1yG#~z&1 zlXkH<%<X(+=AK^vD|_NnnPfN4d|I0y^Wy!56RlRsdbVub2d=3myt=f%RCZS64c~pw zdryAflc*AU;fU(qe{KIC?8>>ztv=t7f9?5qR`)*##xs21S9Qf>yGwZP|Kt89*TwW| z9xk7ERA;Vd`TDDSSDdldn;2#NoA2-X&J@YJzi%^StU0mmJI7~^nRX9aRWtX?-Tn5b zHa|{c!_x*fW9INI4sZ-y^Z>=cwV;Ld7fa(K{9~m9V*c=iiVJS#nJ0WPqUG}YMP}TS z=eb@fx{~I6k%{4``vaM_StTYS4<0SwP}1luz%XTQ!yA<&K`nX?UusvJzPNq;o`xB} zCw@29(tmKJUSPk}zv6&tJ$-C{7wqL*JZ<4hiQKCU247kKo_rIlVcFGD{m_<GeA|OB z^@g>)E<()nms;^MuqgdF>+;TD!;Xbv^89AEX6E&Z@5Q%VRrqChcyWp59scPaSJD=) zl$dF4@KCd3=?1f^->tO`8#zrPuDq7KdSa_9`^5j+%l7hUi)U;-@t1LHWVo5Si_7&D zDqp96dUMz=@beue-akc$O&#{X^+}D}<o=<gG2qJAu;Sdr$X|6+H|^C){x5sJj=S++ z+0#o~Y<*2zg^IN+qidaAr`<S{^{Y02`?cxI-u_qk{$%?1JylCgYV%L6+wT+m>-qxD z?@St}Z4%zT$bB!z<#6-nq_PLiKiL1VF4(!u;PD4{Q`hvr$?rdOdRgpvs@dzdx#DZw z-G9a>Z(m;`e~0J6XVZtl)BpJ{&9MLbSGtfpUb6f)H$xB4b@Oiu=?o6Zp?Md7%IoCB zoHF{>>bEm~dn#|kpDD6SUsmhp#9ZRfiTQBIf8D=A+s9|Ce#B0kxkcsc^;wTLcgNid z4zBt4BV7O1&bBlE-)^gly!G&WSme#!>TCY&$rfoAUJ-W6+xVN@?@vcFPhaD1eYEKe zbCC4%9oE-lzMh{8s;~1{oPyaEg0t3N+%GWu`|V|)WLD`hH8>kE-1zCF;pn}yjy<BY zbzkHIn+pHdow^JrQ<eVYRror6$o*9={ppMTu3PM?2M&4GH_u+heAJ!6p`!AkXT}!3 ztKg+vUv9fcSUKOjQ?1UGD*dVM;8FjHd!^0dB>r2x`Fk;lk3q<r!$rU|;UR~^f5~3% zScdm2e>tTGe?0KEw8wwJ#}#ht*7~tFY)Z+PBETU~q(0{`yQ#X1i?gbFrF6rA9o0SN ztIt?JyqGMww`<Pg<@^5L|M26;0?zMYPvnA2%$P4^U0J@re(^pV<EnF~He~YuJgRrX z_UF{<3n>iO`s{>?wO4Kpu8o`({^QNY?Y8gVSc^H-R=QOOt14K0_$X}u@Ao?We<sIH zy6?}JyVkoQ{KuPBO_SF(3K#p;Ri1t<fBp0&tEjBf_kOXv&RIX2_Q3PBT>W;vtZ$Qd zwd(Btw*E!FMe{~>OXj2Ebzc9fO0TR@KeWtNWc!1D_U(3SFRm!bSIw_iO**!C^83oW z>Q(dJB|e<@(P`Noaf`Y__u{RsTZ@Z*16|Ke)b#!r7F@J$rIo$<&+fwQdjsaxx?Jy{ z$SLA^X6+l>r*C_GLo4exmiO#0{`xci-^w>Rl2^{p0LN*_nisuUvFDSutbgSOPhMBQ zaCg7ILdy{$hAbn!>}9v@oOG_rzl!r%^QAp2^?hFHRjXK2UWekFqHgR`-3zWVOt)*z zTXSsDX?MfsY@VjPqie1kJpEq4!`9HTTd;`z*jk1y8Cs32gc(d~g}yC4y++$B?$_=c z2iPnd*%nLfymm>F!K?4V3o8-%rl`&ft<AH9l@=`wik-rA;As7xiDtRIPjyR=&Py~d zX_wXA%5E2FS@`ikSIeTy*75xv^;gau;yW-?{<`MVwHrT&znr!8+H{5&tC+7%TY763 z%ZjUB((3nLSo*)zir;jGnL+LT=U;E!?K|op+<)g7T)XI5d2h77_x8eX>!+vsM0{{x z>!xkCdCQjK%X^oGozni?_dBL4Z2Pt+O|8A%#r?WEzxb}lzd3lu0n+K2S$E%FB`BNW zSy<nvZEbyNf7f3*qnrCVxQwAA`h$D1_wRilw?z5+ezd&a&^h&|y4szu%a^T+3ID%i z&*XUDUC+<w_KNPxdfXr!F>R;3L&YCu1{S8qu*G4Tzy8bDfrj{YNq$&)JMio+;kBU* z3o;D<JkV|UX7#swox4kEf5Eove2xso)_=KEUyH`yu6)^eN4fs3-Oa*Et%)q#;`Zuq zDQUc(GDXJmmUsb|bN}-LZATT<FC>I0U+;@&Tq|~U<pgu(=j>Btj{Z<*1LqOfix+tg z9J+PVWA>>%DaG3D>vWU+-p5EAyjyo|*Q6<T>kGN($k_h&WVq^@{>iWQZt>RRcP7W* z+{yZS+tdpgAyX@l%icNs=lGqAo1bs$`OCEMgm%p|2aQd|ykBICXK!6x{(bk%->T29 z#Xa2InzXqpa@OQ>pX+Xh@IKSs#L|nB^H)^H`u~%XIhXLp@!Wxv`SIKm+gD@<&-%3~ zq*(j-I^7M&Rn}PTdi(Q%=jqtLk9m%**4??_MMhTsx>-A3m@;g7bNH+&E2zNK5D9-G zQ^-5V;sFcOgjBhLZ=F-4tQj*_otqwI9erb$)JY#u6WH7??2DV}_reu6><pzlH+*~X zd7D_2uFl-A<`*)r3UoAjZ(klM_51hfgwnf`>ZK;P&P`aC_25W)!uxtw@oiy`&aek; zNqm!B(CJY7PL#jabzLe`Z;bXdB{M-@))PM&&n|tD<MOV*VCR<Aucn^k6ucO^p`3rM z?#>JMVsi7YzL$SAweqCg!OOc=WvXU+8gBn{?arx>)9&ZIi;C3${K5U;<Y_O<y4eDv zs|@W^-G6*>xtr*FQ8G0>`$*66U0rz$A*arr`je7=KjQA*B8FYJvafh;^$H9v&{Fy* z7%RJW+mo8}wU(zYec$<`cXFK8;j1F^Is5CkypC-?EZJkbLh?e^>COFTVm}66@4WOy z<-PY+D~7~i`7@sP%KogLF24R=x<Op!w?u}Co8`ngT%~$f8GVm9G3EDK+1dqH!=A|U z&#e02AiUyD&RRVSSyT7;R-Mx~p37EtKimQe)soK-g10Z8<;`;EIHSW)%@v~4_b$Dv z@HhKP+CfXFdbgW=3{h+UwR%4><z0J~$>H|W);}fuGt2IFE~{S_di(0Gax+)%92-VP zhQECRR(s#e?D^v~chCHV8O#jr4ewOggt8W77=GCE;eg)zf(^nM8f_D^^>bJm+8uoA z_!e?AI$UI{-tTyZQ}Cj|$NpG`1uqWu?>%>2Wd3RUzrF8DQ{y(J-|%6$kab&1+bTL+ zInD0b8|l@nyH|!5#Y(ULaC6tUxob<s>;6vPxwP3mV~^WX28Gi$8bY&w_s3o+?l^TP zIcw=1<sIL*ZHqj<?b@_C>rYrN3e;Srmzx<ITyySZde6H$s~28TfuE<$T`RR!$RRdz zSNV}S=feKZpIY1gTK`)@+Jdz!oi1K{@<Mj4_5F)M(FNardzSx~bjZ9VS6Qvh(sc6s zpPk#D)Lb{J-}`84x_lAuj0L-!*Drg~6Le3^?r$OkuW01lwWaI+2|sz;drW<U&GQv* zi;H;YusAFZd^-1*-1dgsNuUKicfUkjlzyx9uI;zQmavC!(oCj1u5OHK+?6w@j=xW_ zptI$8MeW;_cKi&pycdQYxW&v^%=q9^eAXA!9qX<>Eot4b?(n|VSDyawI;SQg%fR5B zUg68cFx$I-?lc+KgZJL`=55~B9(MO{Oo5{i*Z0H6nB#;Q7i8FP+TZ?0<<kCZ_b*;6 zO$^^NZ<pV*zdd*4zgE9@3TM6iP0m&0&AQT8c7EZ#>%)1stiB!BEH&TZabR!E?XatR zx3>jzFzj$Ucxvr^OGPEAqU2}x&*e;>9$NqZl=a@&)mIrZvM0p)R4xB-NAK>l4WGUp zYde+Gf8j^hoW)+1t6R5DcFCGN`OnU<)h~0_?%t5zyl1UoL(sjrnbk3?1H;AVTK>Cw zdh+|q*n466TZ_)vf0kv4yym#R!*ZAFi(Mjf|1&mtJH%X<?2Vea>;2xI=Gn2#YSU8R zlz-^iP<qY&#jSvOiUJ&~x&4_l*6L@kIaT^iGI-9f%>gPeGgeOBes#NfxOv#K7gFD4 z*X_U2Jd+XD{bgq8bu0aJ`}#8d`snW`a(zEq-d(<-=)*LR+%vj4zmElLT5EsyW9f-5 z(Y&q59Ubm|UV|Z&b@>{ZJyNTSZcC*w`y@Q8W5{C^W}I{L@Aks-Jt>c$n3vpV0#yn| zycch6&Gwz!xbEu1H*Zx-C7HJyyJ$2<^W@ZCxXBS|#5F0Pj%}4+i{6F%=IjS@b&dpu z#JU6vuDbltjLq=7vxeh0y(`aSUb*wQYM=6d$$xv*1F6<8Z!^}iFodcf3A*un;TMZ3 zxeNjp;+eNEgt1QNIHLBd{L+Tcj^36cxdB@aRU27JCA{aKpIN}u*2=u*&V>k;tuj%j zhu$^aU^+KZfI~6gtyb^W>j&1d>kKnaxIg1NF`L0b*FD&93E$o728In~?#YT<q&m(# zu;<=(FGHtor|z4YgvU3lrz~<_aduD1Qn9XU@75+;&wj9K|7#{y_X+=3*GXD$m60uF zNO)>?fQ3)u>WQsW#S_vxXYqv0bHB-1;qQ1rSAc`({K=~`CAVF<Z<+O=%<Zk+*`wDp z6Uu$JNbI=i5cEk@l=oHk`*t>e1pzkyI6bq?XKX(noq4zZtmVeFyB=)$e}nbm$Nm@c zkyo=m`PIG^v^jfG`_!FNjtU|-ce2jC`S<#v;``f8r}cYQgk?QtIB@FT<2&pB@0sw$ z&pr9*mekj-NuTcs-&P5lZTNX!VA(d6{Qr+<{5)^@^~TOehvwBUm%p>*>WXadbJxY@ zYg>GdJ@&AF()RxwO>+Ie=<YA&pEYUE-~NBe@4s-(UYb3>`jfWt%G@Jojx%hzA|^Wb zf1rXupJzpwf(R$e3ICglhTE^at;jCe@h^!#jg7@=;^Od-TaDkJ=6)5mbaz^Q=e^*f z{p$^^e}10x<U9*g;>Dlx$L{}IG&kDgK4{pq$iL3=abx}L$Qw)+pAX-U`Frg5(R-W= z*6FO>_G3=?k(})ZJl)g;4t#u@E%LTkXr*s(=)A@06%T$KJ^Xv?f;t}#qt7KW&$d=~ zc64Nz2xk1Qel{UbF8@tbmCAGJ;N=oi9_KG!E5#sm&#Y8L>I7s#(;F%4%13*DDRMe1 z-+s1yeU0W>JG&oSzxwP;dQj%F*fY5F;5U2!o_U|IOi`^jES+{S?`h3z&Vy;7mE|rj z%Ix!ZsR}2m&g|&OnDJ6>=hs&o#o0mQ1HC+JUR*4_x|Jigdah@&fS_P6Q|0pgf*dV! zikE$4TR^SZHVN&jlD{G<FT-asPx!4IrR_7Tt)nBu#oK<z&3n2QDW5(y8C(0#Z3U~H zapMYOh6tyRLqgL^XOMAxft%+Wl(K*_o0Q%j_x_H&FsWXzX{8?b?pb6pgNj%|!HX}B zbjb<cU8DD|^7-@scP`%ysusOI@AuF5?c40`UW>4+VU#*$JlV`{M)|AP*^*5li#j@1 z=!bpjc%c?tQCD8<tJtt{yIp;$t%lXC^M5{U|5(0m+ota_`xyA<2|oPTKkwhaudBH| zK{cw2%N5Yt_7`bEGwUBcP}klnWy-+85`Nv&z1WmNT7CaRzJ$kb?q55hn*gyTqoXjL zN6AQYt=a1v)8;(Mef+LMGxtBc>CyDNOzKDNKjdpy^E3QhzCSZp!+7(CwP&maO+Lom ze-ZuKEBLBc<*$WjgR+-@EZ@VkV5QpsBiq-9iqGkq`TNX`+y4rjSp^<wW%ofG<>Izs zk-LkUsz62SdAnanxi_tG-fr`4q1VNKuYdE){QFYA-F~<8y?YfeHmA$q4q!ZRQTx}8 z>H0t2?n{~e?tJn#dr_Kg;&ZVzuNUmosr?r`|FjYRo1YI3zKEVDG&^$HyK4R4H?Hk- z_Kp5G4OC}GWw0_m{J{F+<I4(p6Hp=$6y&uH`_ggZNY0$Uj4ns)v+|xM<UKX``EINI z|MJeDdue%@`+q#$%W%c3a<9(bg-VwnJY{_RPKcvr-a=!Otkme_rE{|r&fHm^{LC&l z<;b*KO6=!59&%q;oF2c?<yKI5O{xD6A&5PaM}E6^yg2sgk-c1l*G0Yq$4=@${^0KV zynOeM-pl&2*ZCLT;9=M@i}82<N^QTp-|x+FH;-#)a9U{baAofCeHDQhFWMv+fYOqZ z(jv!4wpA`Aiv=TY?Toy!Bg6Dn?Ef9P|AOb=w)klp_VioM!q#giz8;&uYir@B&%Hap z-Z@{tKlP~lVUY#PCtLqB`8n_US)CmAoAaRY?6Bs=#jBUI0_L+v=X>a|=lP_>g!iu5 zrQy2$u}gJvsdHsovG2mx-qkvv85msMH{UpO=+e2hJFV{DIdtyMCAo$u)%X9lM=>TG zSe|F=oIdC0!~DbI3%sL~U27}b+%x`|`te=-dNC+GX4XFQqGw&w8@5YdIPs(5`X|jF zt)P8IMv8W&-r=6BT_4)bxy$2v`>XVpojga|3!gE^+%Sr9*0^0*ba=woWv?6}jr{gC zZ=0p~x_HSc%YT*b-ntAMXQo#CS<JBJjqRc|`@#qR=iT{#k?Z^g$!~dz?El_#_C`rc zl%M~&KK%41{-y8g`5lfu>=%{w6`%Z%S>g2yv0ksl5*Y@8&a+eJuD!0<;B}A9L1Pln zQJ#yv9{0lb7ype3UM?Y(%e!gI-}mzWUp<xHU@rXYVLZ3j<?r8Y>kro*(EjBYcY65) z@wSeRjuTrd`sHF(8yOluPuTzbSMQ3e4-Sd>R7>tNz7SF18ymX(&@JX^U81^Tu(bf^ z*zO5=KQw(g%WD4`bM75|j?cC`Uwg<QX7*N*TRNTLon!DWKfl;rd9N;&?z-;%?|I9+ zqf@Hy&nbF8d)M`ipX=9G8@~G{e*EsgN4~NRd2T}7w>M<+&$2ptVMEb}u8#kp*+%n( z{J)wu`){ArzI9DCVaBigwffnsPJQi~argV$*Pj{LS3b9ixmf-w%8qrv0VpdjJ6iqa zg%roS*BPJ0O3a*88XXwg7p#82e51h1+Y8>NOPYX|&8*+|dEc2eZJV|Wdak}&^7r>I zf!WcF0cG2G${8x%Cm)$}zhR<}hKT!_iZfR<+j<-{b|qH7UTyUM$U*-wsr#FrNj+U& zBWzGNF(Bi|_4$YYGP19{ZWHqo$q{Nts=v5(ZxYt9Zk%vCu#AcK=ZD#?4Lg5*o@s6H zHg(4BMLLo@?UQbu-caIpRC0=p;|r#c<%?HJtnzEoZwqVQG&w`h^##+8{>$I*L^bxT zzZk}QU7|(5DPWO(WTjk}*p};xC5kyVf%BMdYO<Vlf9JoUz~PPZU$;>0z!HYEu#A-r zSNIr<6$KWpWD!kgT%f?IWc=f-QNhBn<b)}4o;iCj2J!WBEj_NVvEj<YP2ZA*6s<cq zrTA3dJFtAiS2l*5nkQyoxXH57(n*}}VSmPyODjagzvVDY*!KVLhD`p~-)73@g?*Fr zyJuLre1GSRkFy_gFSwe;6}0bbr<cSkzD$o4`TuLyZrrnWVT{t&Yj?9F<L6DBziIK} zoy&GED>$_`-=gyPlQ}<>e*Z`>EMEtjWi{)wJ2-io?2jj&*4H2W^smi(`y#lY?0IK? z+}^)8Wxu^!c=Nd3S({Jw<^Mk_G#uJ|-#qLY$I(fz78w_ouPgh~_3rl0&F^pgYf6>9 zJE`)^<j(THny+6>>$;O{__@yf+qLJV`A_HnTefxKnKOsB8NGM8aHP6+k<cf<y18W! znooY;6Ib%^_^U%Asp+4uEPcI2s`T2%wWdd(tKI)xb)lttea4r4Azgjlp6@-@&V6<2 z(i+)4$L@V&k3D$w!SOd!FPQ(j=Gd3CVf(+fcV9QJ*7gn6e)_WAY<9He4XdC0X--wo zduGiq&GGj8w5_mw&y;Qdn`b@RoYy${k^GPCQ}?#(#oc?EpJwx6{lB7bDFv&l|36TA z{`FVZ+3HIN<m~>I-nehRBwKFDHNVGs^?~2##_XwzzrV4kUfzhWcFLc#@^_n;ovA2j zUhC};d2FBZ{Qv*@p6}aS%>7I}Z9=?+l9JM**PY*A^oqUPm@#qTR-uiZ9hDqEs~1dS zZuq|RIrq_LANGf+33EJ<YMxePGF7RBQEh$G^^}+!ToWaa*>z2@4xDi1ZgH^TF}tq9 z{>5h8KRp>1ym9y^$8x{#L}~%gv7i16t{yPt@I9KLb7%(pL&0>NtaExdejiM?QhMiF zYuClk+%Q+aW*M_XLes;dd3t5*1AnPqT=Dhq4<Gjnf9}0yWs2CjXz85~%P;(mv;WTi z!^io^UW3hS4UZ06{M*)8|Eid`eMwwP(&obQJzsw8F8#>==k>2CpG(B{eVDv-u6uNI z&JQM&uxCG9&d&b(g5CLsdhG7t`+xJFoDu!V|0nqSgspq_etg6KTJ7G~TW8wuedL-w zbIV7?Ubm-$R(p4SC<#5dGFtApLCUAvf63x5=W1e>W^6C}z?Sg#f$hJ(=`uElSeX{? zt@enG)M~i&W$)CV>c{SW40`kDJ~zvu&-?$JE_nWT{bvb@?K{?eNpg0*wnu&2oliH~ z)9WLaN52h()bGj9|Jx-UOP;t{&j04u@J5Fh_GON-ky*YMZ=NjQzpvu!z73iD@9+Lu zapR6w;?wlWV*lUYoPY0C{+BDY?`uE*nzHZzlyv!bQ=cE{3y)=1cRN>Q^RKaf+H;wU zYo%`9KmKNF!32Bm=DlCdOYYB)z4At#!R2g~(z|n}&2uK)vt(sj|Ka9U*YuRg_PokB zhpXdlZ(WP1{BimI%eK|im#%*Db{(Ve@6$JrJ_wQibMWi0tgq(AY}RkyOJ6eOfBe2; z=WFYm<!c!C_fFg##&YcL+N&!{`IpX$ymkCcb=ridd;ZmBEq=xA4BAmT_oLk2i%vO= z4Cf{`F!UX~khLJA?Z(qjZnpCliOyzj$mS{Gm$qzI{O<mD^ExxRjP>vHUYbe@Y2S!c zEYRcPS9rn~66;VZH7V{@-sPy3`wyPA6`Q8F;f-k?f0Sv;a=|ij1`d`F^LqZ+ewc5& zgI}|u^>XUsDRW;;Ug9+WNJ2G3n%OUN-kL718&!u7Ns8OMf2sX-YQcS<A7^D^Y<5lT zIIHvb*d4Pq&K4Cd))g)MuLVj(b7Gmk)&KeN#{FLZtiLLtQbauV$H&9zb9PCYOi8!= zeT<1iX8(<IrYFvsavYe^l75*#cUr3Km#!JX74LrUU|s)0D*DEbS8;RxKb4>S?%(Ej zU+3J<xs<h)&3e85`75ROrq67ZWw`$$T2Y{)?d+9|khf<;%Yw3ty?-Cof6uxg?9}Vj zm%O4g89;-h|B}T!RGu;HQGPz}*3b0*2`?FB_AZXj>i#WVdtmN@Qj@GyzfapVz5j7J zC<wG2w=ep3yfpclZT5#`DIW_7w(8gU8DD<h{Ax0T({RS+V>jg;T>dP67RL81jBoP$ zxZj`ar)xaT6)Il6C-`==y539ubpOA97gY1B3*4|`fADGjG)K36mbLp8_pZBIul~Dd zYH7*ohWp2Ev^?MU_w|`ulRlr@m)w2szd_o)gzV5ihYA{5m6Vir{foFL-OJ*{@FHDy zXPus4{I{sv#iFykOC6%~S6DGDSSux0*kM-j`Jh92>#67kq0Vcs*ze7L$yE7yD$Cv) zkz`LcudDaB8h(F#=eWhc@}5c#zlGuRdOLiwzAcunug(8yp6@gJ_mAUo4>wC|Z+2GG zpFj0S-2G{`;a@jxDCCscZ}Ip;`#MHp7on9m&MXRl{OeQCy6Z}J*Sjz%&y`*-|10R} z2}ld{nOK=#-D940OxH}67$%<ZSsWI3`UQj4tktGjOQSC8P4i&9v6F4PY1pFq{gyLY z*d*Vq-M{eS^Yrv3>CM7MGv@4)E)DG}>ztWdcdGC9{JV)yg3Dj#ulg;WcYyUV+n<|X zf3-<mG`*IvkH0T2&@Pa3W%d2Je`ohfO?Aq8o3f<P|IZ;%>)*xYy8QfIstmtA-Bb9N zmC)nHE3MBkA!3oDeC%zWjI9}KWpdP?Z4>Ca5LNgx%5=@I{R{IQj!okElGqz#{quVP z-{DsO1%V$|MlYIu{%$tkFPC$^w|-2B(lp;*w(5lKwXfx+Yr`%F<o)Pd_`=eE>XLVs z-%r~+tLeV~z3$4Xl_q<uZJXM<bQqf7-{Dy6w)eIC_Ma|ixo7QgsZkAOZeGm)X=OCG zwfVvuYyJgA^+qMW7rS%+_?}lS;3PG7p1t+o=TcwZFK3$`oRIlEE%9;C#PXP|$2sri zZpELQ$K&@k)Ze>amhZz$wps0t-z2T;Lm%#ptyJItt#e<Ksl(4!$v?{#l$4aDwAQ@n z6|>#`@yh+g@|XWFd#wqW&f6>WbUA~=MW!!n-(@nq5TA7TsdZCU=r8fBD>-KIGpsY5 zV6Oa@`>$8cOlyT{udJ`|eVJX+C=eH{V7=6S&FR+nJ>G&-?*4!GJvq*<>!1q5ncRzU z+^*e?A-nn)hkmcl{g~KsR&bw$l;{<&A7_tjna=a)u|&~I=es4b(Oai<w0XVS_gy9E z^~%%NR!%LNy6Ld}w{zQ$bv4ho3Dx&rt!Y*LrdwPkNc!%v<FVggzOeXxY!{o)8tuI| zic<}@MlH;iG^+f0bnk!PyWivX>e#-1G40r@7zQ@$_xcg%ts6?5Ungxb4>zBZZgyQ{ zm53~8LPbROY}V90@3-zsy}0X_p+(i1JIkm4v9B(d6A#__pYf0NZytj;n-=GAap<*h z&t9}+>dxh9vr<=PMqd9ER+eA6c-P%sSM@jNh2^C#O?_9rsHs7RYlX(|ef+<T)@=U& zPeOWPssjt#lh1Wucb%PM`MlEZ`Ap+`)9=rFKBxZZw*SYEmA=}W9IB-@`R%j+F;!pI zzgpIHS=pvJPHhpN|K`IjUadZtqtch(Nz9&GdiURMWhGl>@50Km%{%s--Mq?LX2Q9m zpw(Lbm2rQPi|?x`ot<?1T+ueUb$snnr^T;7yOg#5@##&IwU>Og2w0uH>1^tqn^$i< z%idJ<QTEw~h(||dUwJ!O#~94wW@BJrSnz*iQ*(3aTt>MtmtPN?R*Ag*E#exSDpkmm zlHuNZF=Vc%58q4+;bu=6+f%<LYfU<lrgZh0&}{#<vJeT^P{|`HljljEoVCKB>qzU7 zq{)q<Pu&Az899AU9_Z?DeCl~cVbLxoqf)hCaV4d7j4z`DUixZvEIDRWG|Q7o_!ReU z>!)WAOtPrDwP@C^0AIb(^q^qTjg=|ZogFK7ws9$W#<=jXah~b8Ty|7iaAMHCZPUMb zUNQcsl5~n+eV$<GvU}V22l@S+7&6^I$8P5CNsXcG$M5}|DxtH=OI=&vsPNUJ)tT#- z9m-gBQY}f~{)>CQzt~z=t~)Jr##V0A#LI<e_X@Ge<#MZ)eVJV6@bP9)pzrn5-<`g% zP2F^(Rdaf*n%-8qm+Atuq@#P!^x4l6`Bj^nx$C-cKG)ec^|(J#Qv_EAo$6g1TUn(x zE4lL5F|)-?JZELE<ck)02EF+H)bjdHCg=VGrCgE4Sx@?Jesn+c=J>9kYt<Hg>y?h~ zdt)FfxYX^9w$HvJ!V)w2<);hnTW+B{=jg-RJzt)`l=PmJl{e@28XNO_XY03WC~wmE zTIB4zQNy_F=rc*a;t3|#)Y{*#I<f!cqYu7o?!Jrpw@pd^;DMYSy{|=tv#;lU^K&`- z=#%wAYwb_@1z&r7a&6z-X+E_n+3V8bqfd9n?E9y2Kh!1VrHQ9nW=8R>n0*_34^8Uf z@P6)j^5JgNwT6*%zS)-DkP^JvGwasA*Wd2T3YuQ)dKdFA?EaCkDRO~x%3OapL|FMw zF}uF?<jWVP|F5;a&FMRE<=o`Mm$QYYTlUOfKEYdwf8V?BU!KS8+pu}g+V<1eOfOt1 zE1A78&t9ihQ~c=DovAlBzSUoAX0@ltYPXYw&$KF;mS@U6I<Z%-t8^dM_v6(*+ja5F z)x_Dk`%1oEKax_&)04Z#oi$@;RKdY5`x3VBPdUbtzOFY@oO>N30|UdZ{)_+E&Kta_ zDandVIVKppyutnK?$7+JyY%W$xLtd{=3SNg-IeQ4>HF+6sd{zGY<=}yCp}Hi{w)O` zp1mypRsKWn_4ds#CIxAVr@GAKmp^{lxNZS+`TnF|ANJPQFH}_AeOdh^Q%Tx+wauyj zcU}A2zRT{@Bfq*QmbJ|XE;wCxWLqH@Zy=o}?NjjZo2v=~1B1k@4=Fqsdas?IaMeJ{ zaq_P3347aZWEwi8vb!cb?f2fdsrt*6t!v}$Q#MaJ_UiNh=xrIVQ_qU+-176;{CJhP zA6Yl|ughHj;^{pL$?{jqg|6#PFL^36Z(oq&`t_$)>v+uB^hx{paj|dbBd>H^dgTAt z`v14e>7A!%=xo~(nPYnCeDW=C9=Ge|nLA`ZmHv6zKmG6PTg_o#+NNCNm%h58V9tgI zXSx5%FRSNy5*)UEU(RN>&G&f@OkAn8>+p5+%-D0U|4(2ph%hOsKFGkpz_6vQOYX(7 zHRnq!Eo>$g<<B+S{MAI}*^RS*zxw9fWsdXMw`up;*X>6HC3gK<o3*#~tf<e7|9OvE z*YC2q_Hkn?)8WMQZRh8I`%^xvcWLBBUelv<WiP!>PfU9I?CX)}pWDy-M}M{zTsfud zLwsDX-Is0uyY#KBU5r0He!fSr{@3I7m$e!Z-*cy~Q~t7@vHFzPP7}ivc0twFy63O9 zNBzBX>7U60H#PN#6)*Ocs+qm}ynRmg-o5{w`Bo%m`aT!uVPIfz$X@Y+@xbB*Cf46h z`AbjxqrB*KY;>YQr0l*r2_LoFwWqpstzR8uF*j}8@Yc&*J3T(LJL0tB-a4^4Vg98l z29b-G@2g0B-gQo^>U*zE^T!W+nZHP@&3<kAU3dLX*|Wdos^;twkM95SocrwV|Ie=m zG=qy%Hj$7o3=ZFm^5?A4J)5w}@@XaKJ^wt@tzT7?c5eCk?dbZSY-ypco@{E{9?Rc9 zl(6a2x_AD2e_cMp`hIEbUHwx%QpTUJek{JHuxQmGYp$6pmNn-7=WiUiVrTm+{Jr}2 zIQyRqFI=g6=51eoW6Cs}tE!qeKf2F8D*C7^X8v+Jqs`Kj1%F4+HnX+~SQ@m<{qH2H zpN}8a$0#mpTEcCry3%W>k6PxNgBwmPJ-gG~ujmKcE9>?4FCt5J)H_~ko$x+vmrs;k z>ecX<f&1P5f84hE{$@M>zq5}%i~adiR5;swz52bJ%YMbRs`nqfQ`+%nhcd6JYfNKe zX4sm~N0zr$pS##&bN_(P-!sQ|b-lTfeEU@Ky8f9PGygn}t}1xMut0c6xf}xn!vTe+ zE;)u55s9CcUV0O8KXtyq#ie)8-~Uxyec{$#7m?~OvF#r}zq!*KqV;sAY<EP=zZ)~x zTUP4t`gMDnRN$>MUw?OBUKev?=ON_++xGkihPkz89+ulMU6+ou=wAIvi9bj0^iH`i zkLE=MR;BxvPIJE$QvLYM@>jF&o-Ljq|L5V&r}8Qh{h#tLr?pG)EZcbX#HvNsE+LcT zB4?DGtUvnPB_w)U<?l=8uWH}L+?y$P)zR_7`<Lf)VwSIp-@dQ+O3zpOmGL$gB1^XY zFF0@cP0m=7hpqdpwCoNu^@kGS2`3(McXs3_T-)V1HAr!~+0>`Uj>=VD*L`65^+e16 zU$?rgU0hPKUQ2%c9evpL`5oz>``-!2$4;@Se%$!z%7zK=!z<ZxQ;N6R-H`(2JO&0i z8LcXY1<Bk0{n_u?Z6C0I-oHb7UzvAI<%)DW<2Zlme?=v>=9gk0{`791-#7QCRCt1m z%VFE+0?mn!twL8$G4DLx^MmdCtYib8v$CBhUT$=C6FcW7c5bfe)yR2wq}4wQo!_=@ z<<%)mX7bBl-{q^jd~u{%_2WC~_deeX+;6r`X64PqGd<zQ&Q!Smp0OfdSv6Noz4hMS zh4-50wNCqccljQHUHNn0Z}Q*C<lJ|_K>OW^Bd+gHM@dyMDT}o)&rE!uEtbO<fB#Be z$pfp>gn9EmF50dyIMGRMrJmn9!KGz4wl2QT#MYc?oYfVin7u~VbW_2lx=j#oe^?N3 zk(ohuwVvn2J!u=?hfSGv^r=^?k7908@eh}jl!uohqHjGrusho?bQRz1t7|;o`US7O zI&E41oIfQGimkV9xhWg!T5e&}yzcvJnec=cl3$7@@92^HqqF5r{(Hmj<>`}T>yI2t zY?}J{$*DiHTRo>A5w+BtJU{QQQ@i<c@makdoi|PkOYllRTpFacg(YFrP8XNIKU_T0 zwg1>lG4RBwvF&hFWME+UqW0%6J3~p&`uwmNH5V^sPWqMGt8w<oE#HKclPSfky@S@e z{}P@Uq-gptJ8-#})~f}(zAy0o$aChC(D_wUxJv)}Ee*QXb;&p9j{KKBJ8BX`FXn!I zvhUii&9A=2DKj~*JFtO0ePL=n+vKOu{>MaJ(Z70h<>cu#3b|s-UEf|e-)6SyMbfhc zUMnrW*7u*kSK*LhwrHEq=Y9QFQa|g=vSsSSZXX1->=+m-OcpL;zc4$*Yt>1$g|dY# zyZVeOdglE3vUbAyiYm2jd5uqZezai@7S1+Dv_qRh3aeVuFPwI{QWZBNNKskoYW(H{ zUwU+oKD}wvC>Woy?&p*atL#^C*;=B860@%JJ)XCx@Z0|Ix?2``=h9kzX370M{p0xm zb?;m+FB9Wx4cWVV^7lv4^>vw#twJ-*7A@R0q2tQ=;}`b53cD5L?^2W*Jp1-}+ZT}; zH|KZ6{0+Zv^S^cRbtbd$^H=k~%FFxA+4#==?D9#^tdu65j=J*sx5=y{Pfb-<KI)2T zys*f^w5Maq*(9^@1(KEX<{1iVKABYgfAxei%OqG*ia2=i;I4BF{Mt%?3mikeuK(s` z&=M6r9#p3ix-1}7YU;g3T`5V09_M4OpNz`XSUg3!<T-<Bc%Um+r;taKf7{{CgD-yF z*c0Go=VB(@xw`)Tw<-1-KLxHn2}(7(`>*v#Ye?B_qw_(PLO1>1OjhB~U-jCEy|}+U z=SfLS@$}yjR=$%wrGk{}&-B?RrP*IQo4>Vc_t_OIQ*RoozI^!TQ;c4G{gn4wN?yG; z!e`WUsv8)|+v%y+_!mZ5bRXU>`SN_iCaG-Ka=rT1`8lyOYCMq|oO4aD>geqk-nCij zKU?^D4+Rr{zWZzIa$iejWLaBT|H}w^@qO#kmvR1kG)<)EReXGHmRshbI9;W+E`DC| zTy29dGxjaq7*_K4$No>k=M5w8w7qgt=1vd3eX-}<{{62WJ-IEuf1Th`&*)dZIx!W$ zzL$P+NKedqo%metN?pAv-+c$IObP2`;qJqaU(P-e^~#-nU9!Opmk?#I-Ieb)@7ko3 zxjEweg`o2%f{I0^>rXMcddK2>WM$r-+5fWw-BLW=S{7gb^X%6t>*@PNXZ34%@#=c^ z2doSU)3ftjc)!zVozV=P=<5gc!nO5hbO>31WAXrV!V0UMtfD+h@^hoaW)`|!*W9%% z=;GPECTHfp`TIUEbJda~^G{@&MfSbDuJW|}#DS=2$-o$w>tz?#obT)i@$#~B(UIG! z|I)2lYu696pL>0O9e#IP@h5-LJl~pRrA6KOckenXE?&}X@~$#BP~OB-zpDJ-LWk>5 z`EQ>1HTNpGm#{nD@M<Xw*fk9YSytyQ{Qo3gao@+iMRI~KXHI@@9HRf~y2RF<CC?Rp z=3Lyy|N0)Yedj@yYWrO~w_mopRm)pu^!wDU*Ljxj_r+PHyua>xi`|Rq@3OCx3ruxn z)O9L8JN<75wPYC>8WysN?p?S@V_H{I<`dx%5pUC*CQ1`z((n9T@kMRx6`|SwraM!f zx<1QO@mkR2A!XWsYVu0G`A>A8Z0iW|(%R+r$Vtkyf6bnb4k?$As_rFUuY|ZRel~ew zY`EmQi#O75=ZV~!bfK-oLvisQgGaA|_jdendt%Ytaj{qB@yZucQ;$r%tfSSjWEYcB z*@BDSo#`&F8>duF`EyTgo}%c{fM+*%8$W*K?V-8+kjA4|lP|Byo7=jj(W2gV^Omy( zyv6yq6$DK~gN|jcI=$Qc+%jcrIpMS4zAZoh;>FC0wUbNAJU*6Ax)SIuyRp(FtImI) z=8K^A^Np<FFlBflFME~eL12n$->dGG3#S~jbx)qR^o_tI?~aa?vr}q1WR^{ytAF!% z;J5il5+)p#Sf#&k7s#V(`D(XMPWfTHafeAAZ*R?{BE5UI2G%Vx^A=n@eez0c-d`6l z)~D_PU!KeU37+d&#AzB{zUjhLN0%vuT|Mp-_S)~XcfERZiu}dBDm+Hgo~5iIb3K#8 zCceM#skH2geMiTens;XBpG|aru=n1T$t-XGp3Dq8p1yEl(4;-Bt1fB&y>fT=-L3NL z%y?IsPPy<yJmZYkseK-IYYZHIU(R1!E2P_=GEcGEzNo%y2ix4bV2DQ<3@Q@)?gbna z6A+x)ua-1nCHKlHDx$*G5``=#mBxY-gZy}vvNTkcl0J8I=o}N6?CX;9&TD4+$s;p6 zJTiQJue!LTc81Jz5x>9dx@&WXo6l0gU~4{wwdz3=gWQh1e-J#isq68HQbs|+X2-J0 zn$|5c%SyF75A<}LxYlk_b>!mWiT;;*?=G2eXM5b%%||!L&TCEMy1jJmktY)l%y{$n z{k-t@!&m1WjYu*$ailebYf{JVx_9pB%hzAD>zwAy@~q@HL*=?1(OFmO`e43!v0#z8 z$ja+!S#q6+%$FX@c*Jqy!n}}Eec#gWe~((Kpp>Pfo}K?G=HgwyolcKl1UgI3<g)$| z66CMNs+n@+iGbisUggdmyFG6iY*JSW@_4`gMXA&8$QAS5FS<=XymVpRp7ip0wwIs2 z-0r{V=>)^`7tYp-{AKN}op#2}_JcVz?JzLQXjM7S_3|wIzxbp6gacEgPRl=V=#!gz zUvcWE^}iN$Nu6Gy)!endbi?M`N=CAt*Y1T#_%74SwV&$Uk?!FmX4>)Y-2PzATXx#t z7!5koJz{+C29%n|MX&NZf9Sxf%iFf{UU#-J-Nn9q{oe^E*9X56^!n4etoFx&=Qnom znY;7v6=6tN9GKA9buZvzmD$a^D|5A!lrn8irvwG77Pf{=b#zh5-?{t9S2<O|i9wD& z*X~|-Nil3I(hItj|HNSK6fUiOZhppF*X~kPdLAkA-}Y&oT6^Y^1VO=*vo$~4L{?AS zsC@HRz{jt<zph;6BW2gRqE>a?VwL*2SMSzee|mrSd|CJTt1fvaI4zPc_YaHx_DB+B zEsN~@Rx1fX&Hu9)mtTBXu+ieXRLW~X!Ie*3T)ckny)N}hOi8Kr$-Z8mwByUyt9DLv z{-k{3uVzuSOKRtm38htif0G}}G_NaXf_Sch{U8?~-?dV<iU`4%?cA$^w!9A(@tvA^ zL~z1FSy8v(QZ+-%lt(@?j3;MlJXh-ce6q~wYD#dbm1ovUwb?UrE*UFF3X8f;+%X{{ z$7sW%KOC#H6&f{X?wZi3I`!U?CXXx~<>fPD{k4;ePNWH4eHL^uRBNxN>c^1T?tGU$ zGQ3?<UOAcW44Lcc8+zo~#J4Iznky70tuor>k(A(SIlbek>O$U)J5<)HcN>;hKY0;& zZGOl^7c=3NX47xf7)d$usCgclBJal(Y$WaZODy;NqJ=$0dO^XgC!;&mRpve18=Ua@ zHeYzDSY(f4<m0<+tBqG!P4;kA>zg9)X?pWW!laicc7J{>by`z@%8^!;Y^8mQAAR3# zz4Px&=N8qMZv>QfebzRN2$|{^7MJqKC8nA0+(zqVyYz|;zQ4G(4ib0_7y2buy}R?2 zn{8XapKkXVi$$+Rc9ne8{Z##1QS6nI`@OmK8W&1;u7ed34$(fb><kqV<=vMwe3>C; z9JtWXCC8KJ#riZ(N$FJof?ZCr%ON!e1H+5z3L`e2JRdR3v%9`)fV#dQJq_-1&tAZk zFz~3Yi2B2Dm4QKl!PCVt1V!S7qki@}waV^w&OCm+sY`-hSV3w!1_qvr9sTzfCv53m zzfSp1=#<FX54$tYGwj~^`uJ<B(+Z0xXz%~^#=ls)dHMa1PhS_7$hLQ6%(xJDT@YkH zXl#+0XR6oI*E}COEGj=eIW<+AnTd%{-YzF2W5sKW=JRu{%jea6@^p4ST>ShTue@E% z^+Kq|goZ<_qF>1FE`J}ltK_Bed7I*IZz89Bu1Y&I!*JuqjWT@4j~{=2tXFzhA2fIv zm_@XzK5Pil3N0x3(8eo$ulD<0+v;x{ZbqECTWn@#CMYQQ_*gGD506dtw>9e?L#;XB z&=R`+Lx76V$yuh^eX`cu^6&2pT^;t)>YTEZ*3@;;+uuDn*!=(Z{r_fpcUHWHG)5R0 z3^pWKiGGPGE&aO4wR_T}Nls2qOw7!svd=Fbd|LGV{r&e(o_zUqT7UVnWp!V#hV!sF zUtb8dFJXa$D}R-Sxq11!J3DoCbprzf-@SXctMBuQL<5O~2M_Y`@#*jVGRZ^b*U#tk zf7a|<=M0U%0}TzoUpV^5?613f{CNBE$FX~>M4#^2w>j<Xtm5bAT3cFdem<GJb?a87 z@L<xa`f$K+j)h_EuM&Oz^(RhvfR184UU}r~97|&(BO_yDV+92Td;55JpgVjIxY*48 z`Rny~{n%Y4PftxvKQ~8^t94hOu}Y7mv6`9Lw8Ia7{Q9M)qVmFu59*^A5?WOkVzs7f zSy=q|dOg1W{oe0o@9&*Wd#u*;_xQ16YDPvye|~(tyv)}cIouoc3`4Z0t}{NMpfJ(n z+L}nv8QHbJzpahg8Fam{O=D-wzRb(Z_Evwd`+U|MbnY5F!W!}tW{H-p-L<Rg;v!d1 zPfu~Z7!DquE2VQ5cArfHo#=J#+O^qcxnADhxA)arPwvdz26d-1pH|g{);V+L>@0rn zwe-@97a8W}=CQ{mUrF$|6%=e(y!i32udiK|E}pmlf9Cn;QdusjzF(qhKN`%guZ#Ws z^{c6gNl#~|qh<bsihn<!pPz3pFC=7?e5~ixDX-Y$(1>cNYweONdG+JtV@F5FxVX6K z`tjSgY`Ib@v*Ub^r184Ay-^_{A`%ia=FeXbPfr)>11>iAy}hw9`Q@dh+TrVLil6la zXk00kdC{<ZdAg4ePyg}HA3u6}cw8uzfjaAj`id8h(OOfpUSC_AzvttzZMnB0!JgL5 zJiWKq*Ttn}`t<OGga<Q?(@SL8p}KxCYgHA@pEhlpsCF3W3V{QS%%BcZA9Jj+fq_No zt1Fw&+wIP{xM;3*`73w~f3fu0-&DP7)haRFs40^s2?+@qmA(pzJ>K{(Y4gqd_5b(o z-u-*^`hBzJ&D&S|yG%{^Xcfe^26r*7s)F#cvTt{G7N;6ThJ=X7Wm`++-rIBY$dQ!4 zzrL!fs_y^uiF^L}>!nH%EetP&XPjVmaoM<W<Gy|SjvYH@XlSVMoHy>g?e{xBKR?%x z+hc(q+;)v!au+^6KHl5}I&$vNp+h>lx}~!0a$W%e0U;qFfq@g(ug?z)n+8uo4)2{^ z^H<#7n0)-wQt$b--)<_q_q}-e@}(8u7bbrG{u?(UoShGA1}{5u{P=4`7#M|oY13<U z`nY}n-?zQy_ik*<y}d4W_l=x8As;U$=H|-E$-R5~);9Onmdnfik+i9Wd}&)TZQ8V{ z+TrhRZGHXVU^67V_ntp+;K7rVlUIkYkK0r6ar^zc)ri!PZJ?X2v1-+-s2v4~Sy``+ zc8f3fnYrk-#f9()oonUyYo9-R_U%^o`qY#Z&`FplT?FMJp_g#M*){*f$#duG9(AgV zaJiP0Y+1c}^}5Fn^Kb8|+}zuHw)ng)=zQSQ`ujOpm}1poHG6v#r?s<pPR^S3>(_U7 zdiwbAoT_v_zA5$exw+QmKR-Q{G)@Z%2|;9e8<CJNZ4(x|_p`CG{`~#By|pzmBI1P= z-<Q=dFE5YZTeWq`k|XEO>l+&f!%LP0&jT(>Yn8pZv9ador?0QC%iC6k`1|``FLYqH zv9U=?O6uw9sj019yl4?3u~u=2?scE<w6Nmq)$scjk9%`(Z+m-VBlCGTiBoIVu3aCq z^U>qS#?{~61TXh{iHIncF6;gs$BrF4+AaS6=H}<y@7HmInk_OHY?+yxC#(D0{r~gX zdz#MA`~UwfhX?tG10UAhc8^R=eR`;s`|_nrda=7i1OyhmwlE0T5V2;ib@{GcyYlYs zu{1U={{8LkjGdg205|A(u>NCz(}oQOOM`BvC5MGgn?FB3Gc&WK#N<@vg?rD=&IXl8 zvAfH3qqnWuxib<G9J>Q9N`E<Z>XevH#D>(<)2>M;CneR?*82MTCMPAu#Kx9R<z?HE zdU{&yz8Xs<B_$1w6^j-*A+$$>v~SD3eeKSjJ;}%W*6;rpwfE_Zi;IoZ&de}M^~%Ut z(c0RY_xK>g^XJdS<>d5)I%{fcjg5>DfxGKiz{-$a=NN3K&zWOW_9o)%q-eJ0!Y3yt z9y)YLH+tKiU$0j0u#_r^&&&j!S^nwMC%<_%FW<jMlvxXSwW^w<0|G8wT^*ikBq?Yp z!6VkaG(>CvpHHXH&NhE-CB<XZ+uN%hwq{4k%S-?M{+_NMzYZSY7c|d2lse)!*Gg1O zY?<D3!HHf=gI0!ARaF%~KX*0PK%(c%*RTF_EIvN!)?XL1^V977eHRf$pUATpykSN& z&s@D~YHz>)Y;fMqoNc|mzA-T}?-sDzZcaYVr*j7~{KX(~;=}c?2eY1^o6E||ntQ6! zMP>SFSEY-8etwRQiYgJ}VcUInwz<4jNyhbcvEI}5a`W=8!R^W5F8;!{bk!;?b#?WP z5qBOg=V5bR8f5$ZPVw*W@83U9_;8}5uP<&#!NSd(Kd%g4Zg3yk4M=b}D6`k`<=^l3 z-xqumX+Nx}q^`c)-~R8H)B5}0e2@9?;=||9-JP8)SFQT=_3POaClH1D4))?NZ1cBl zG4c2JZ*^LD^H74p3?H@0Cu24w96Z)5oqlG<!32Yn83J;WOP4PF{QUg+vuAA!AGtU< zG{8$Y2Ek`9c-_|T|F`Q|C2Ne{^bQ$WS^IxKk|%nUJUKCOrg8eBIqZ9no;vmF)Ku-d zx;o?Zb2cR}CLn1SjK0qJ;9yHjOU#af#*PRbvB@W6w&mOexg8Y!F&|D`x_;fh?$3{B zXJ^l^d^U5>o;_=$x4*K2w)hSNl;2-<`%Tc#qb@cIr4NF%ME~D=p{(Vxc|##z%!f(m z&rGdiJ63yr?q<>IYZi6)xAHfi1~t2KZi3Ds&bz-a*4SGFlDQau-LEbFk|i~T^JY-2 zYolK3k$=nbP0Q{D$4Bh^ArzP;85nuLE`IZ|ubH0>X5`%4bMxG}ysxjWva+(W^T}Me zeEBl0QfW|pwa>EZW8@`yC#jMdY+Hg)E%h<met*~JvS)d7k}u@nJ-9$XSa@^6Lnn3h z<-yDSAcYyk5eEWVmKHaA)=&G)VD;qnYiU{8*x1;&uV2reHxH4Rodvb37(OJ##Ka^e zC9PSz_V1rRO3KQmuv$0agrh4zgWQanGb24bJRBSjtcl!Q_y2D>yvZOD6>yQcVcvzy zm#xd*-1znNb@;j%Ng0_n@Z93ep;filVQEm8cJXK7^H0_1T`m=C_;)yI<G!EIX1~3? zz5dHZcTlr2MlXN!;ePvnH?CY+GC2q01BQNsZ->nTCzL1}Kil4RD{0@p$l6lJwHk9f zp6&Uxd++fz?fHBBL&eqa|N4A-j<mW(&BD#!lQK8YIQp=+{*SLR_j2|u_iL8|<_VXl z{y#1JY`=BVojcd$Mb+Z>Y$$Hsx3RagclVm53w55)n%KH|<=Gdf4juWmifR7xe{Utf z6vZEBei1y|Jb&Bv?e*Vork_52nqSUl#q#CL@74YI@NjGPbulrqf3M^JU&?iYIJUw4 zjC1IhC@C%H?`zkuKQnt%R(tR3kgvy<Y>-dt|8x0Fo=^UfYK@{y;n}N~r?Lk}^Si%y zwKVtZnfL3_k=Fl8iza<J!EHTVpTDnuf!+=#=dV9+?O@$@bD@Rqo%*BV?}FnL7Tp%# zuXlQ<S>3s56YaD+G)nI8`u6*Ko=wBQjVUK5UAS<8m0QebzTMw1FE5LUiG{C^tNnH} zJyh$e`uv(rWpATE4d`@e*Qlc8OU>0>Z|A2g&&!L4KhdlCy=d7Scb9pW%_A&-zmSal z>b7Uz={;pDtg{nN7eDSiaWT8`*V_$(kB^G(^es*0ztyUtJxkj_%B-elb}f%j&ef+j zN?KmL%1Y7SU%uKNrnhg|wRg4R{0r=V{`hg^$dN18uKoJ)qot)qCt`!c!T^DZP75oZ z&n+*R3vGu#n0V=PSKNzzUmu;i^HTrM0ds@=&li^*J;*Qm>Y(P-qMcvvz1_t%NiW9s zN82~af-Kd{hfbRxKC2IXbgJlaMb)vYHnCW_8_T*UZ7GnxuF0de`fT1T*R4g7-jUx- zgQNLvmA$`CyBK_3sQIG%M}}YXH*YRZNm;UT<;zK`-mhN2zA9=v)2HmgfyNy>EMk{K zJ7g6lUka|~9-M3MeM$L^ZCaF-Z{Givt&d&KzP`2T%%13UmP3iIn$z8X+9bcXoZV5B zH%DVf@j|8l#|~|G()yI|DqnT^MADNt)A_^1)m{JWioAa#>slML%aRG6T)}#-fB!AJ z|LMQc%r}d!80@=n=J&~R5hKrgZ#Ns(?=dd=)OFI^PG!-H`}bGr?AZEZu7OgQ<sZLK zQ}4QzJdoXf;OhNV(|2@f7k5u`e!6MdqA3@4u9pp-ereWg?Nwcq-TY%$hn!mKTe>vT zFmV6>yVdvXqr`7<O?G;vRb**X>zQ2ItI>P*>i77Mm9zC?)bzzu-FzcH%nQ=<wfKF% zXGVN`e`U?7RkCZ3FEP=MQk;HcC;L|Ub$snBW`DG@HnaYhk@!iqu^^)82LI=Ob>|Kp zjNZHVa3RABU8jW;I+g@wzFwZPA!3d1Y_r(iWxb8Bc_F!Cf%%sWi>3<}Pw1GlXL`nc zUHgwQUPtE5d|m(S1Fz0pwYmR_-mUV#Ji}+(<>c;5i|Yg>W^`+Ra*>>9=WXBl<LlO4 zpWgJ$xW7m4|L>`PrLVScwy>#9mi7$Jjg7qa<M{Rn3ty`r=PxFw=REq*D#j-qCADge z`!B(XPI@PI7GBbQQ28}*-)XzG+NYm!pIvVIe{NN`#^bC{Q)3;oznfhTKQi}^$1SC2 zTs<8tEKGYsR!#X}tNE~+#i>~NG)P<Nr?@qCUQ0uc%>Tz9o?wypElp{a_W7N4kD6a* z*Ja#yb^Yh-8N7Dw?=7#@?M=3Rov|$~{K)$CTP3?5T`^GFBz<?=qU$#WN+tb&Z!~QG zZ<&4g{4~GGM@4VCiJiN3oN+<8#?({k^D5O04L6>3&VO1|SyS`p;$rvdda<ik!%M$O za$#RieSXxLG2?J@)VG!EwK)E#US70zq0Bx;!H-{jReMd(KH{oP&YtQOIkEoo+5bB) zy}7~3eb1Zg@3}(<tzX|-=;>|e(S0ZX-mAP4*Od!hmaMyGD8U1s;4S`f=+z<>w#lis zm*#hH<^9*pUAMV(_A)yc#mQ6BT(g&*Fufk$_IJy}lh^$XXRO&FEWe9=&BZAjub6ME zes+KRS6{0gx%G!``ln86>*U_P^1fM!xWL4(D;mDVPFd2<eb#Nt5?6~#{cQyw_WgYR zzgOb7%j|1iL5FX|G%o#I8!WYzCvf`5E%K)?8=vX3&w6Qcv-+NWMb$BIxa|4&>vj6M zIf44y-hR0J^Yio16?^LZpkt*UUc7u*`(?@5Bqbq<8JRbq-`bel7st)pZn^4ynE2g? zFK4fM?K_pV^U||jYK1f1A6O}A`Sq{RJzerO{%p!7SILQDe&5C3iY;%OdAt9y^bEnk z*h;he2VxR399^DPavpZ8DE#3RwDQuTZ<}w}_-^!>BD!>fw<-UE4r{?TFSagNxJseq zzSU>JxVqE-tG8!PU1jmMYvNMx_OF{h?P*!_y51+|!@M-_XIq`!rs=&>uiNr+k%jJ@ zlSwb7qgRV>f2JZ+E@QvHG~2f{)l_xmwZ+Re-1t7#cni<OZxyjJ-X>+&o?YpXKmA$A zC)akj1bf3h0U@DJZ@1qs`?k_+sg|zp-&d>G|1uVW<f#LTSG9}UCa(^3xuT-?zJ!13 zDizyHFE_T%;%z-C{`Q|%<J2YY0vBH#DCJS}UO8oYn%m7?zQzVy)u(z*5zT#R;<<PB znxzYE)X#ld&lDecD)sEDt6hIszA~3_2kUX3b&Ig_Pb>aWUhcimCZ|RG|N5+C$4joZ z&ffF(WnSRkZM!`G!X3+XyHs{Y#;lup^SWEsk+|uer!8w1{>n{#`1Z|@#b%3_ZF%pc zIC;v`7~?Gkf%gxu+h(#jGA8foquaZ-KH8$~a^;&^RaCo2wawe(LK9cN*Wy0jd9nT8 zwVanZG7MEm-`w2H&BbN+??<w>wl-Vy!KAIVUOi3=e>`aB_wx2G72=14!Gpj{hr8w- z-cji?WqQT7v){V@%)VLZ-mzk%pGxjJ<E^``9oOvKXY~BoN$~OmT~Ge)1#=e6yBIcc zy250WT|d{WEs_e1@^+rudYHvCSXXdrN=&HMQ!&5E9Ud#Eq{rI7v3)OF%6;|d%5Cc! zdrgmW?cB04EakP-jgatVA*VcJe|(;ynVlJ+mD0O)(X=+N?<@6Z@yjo-6Ikn{7r1>v z+~us-w?2L@@ZOwca&^nJwpB;CZ&y~SU0cjFr6_Z@-l?K>nkkbCH~(99&+_>(&i0R= zC4HtX+30rp*4^1JwyxSyYUy(8ai--q15KApA>KU4o~X))h~3Frw_Zg__c6nT=$zc# z?Rj@WLoq@^n-UH(sZBolupsKa!t~SIb8jzOT>%LohW;M8urJ5X{hK{?v;U*kw~>YI zp<1efrq@L7@B2~u?riWm;dx3*jRg|n2}{;xX-@r=eSF(b`@cJ@d{@L=3z{YR`bBAZ zU1VX@jsq7CT{+g=ajIzD>)AK1O-nVqCL$bIn57{YY2~M~sO9qfinF!e8D>o#D!o^A zd8f)WCI;Q$=SzMbCaymF#;)ggtq!Mbl3vxFb=v6c+vCsfTb@rTWMNB_*=L~qtifw( zPUZ?Po|}r9YeK)zE`QA<II~~k{<k|F9Uf|#T4#I0G)13Qa$an|H*e1qXU}BQ`1>Z- z4=ZNtbzMHp>QsDo*8M|Ix|NTe@$9^@TF*;p;+Dvm8AUUf=O?ASytIp3*ZE4SjqdTV zC-+0-SLY`kf5=_Q<g9ebh>u}!_tB)Yb1XmK*qF@9$|_&`W#ZDMOVdux^HICKJ^%jO z+uKX$Lc0VB1<9=J?AiCGglG$GT6)*A=U~DvpSoFRub%GttNZXvy-^bXwC6`Gd*(kE z`>?0VQoZ@4(blgXT)+J;Md+UDka_yK=a;4!Xpzpm%D3M&wf8^b;_1|Qct%}JSx(yU zou|?&Ew5E)_GiAf^WFQw?AHhDOUt78;v>SRrDi>T_T`3>Z^N1$_FA9v{o+0ew&zcf zEsuzqXr1`aex{CJZED=TwVQd^ir=icF5x5Ae9~xBiJ!&a`FCckOJ{o@J6F}aK3^$! zUAO(;!gsxsU6zD+oPBd_g}mOyS^GAAJ<A=h7WZe@&afxj|LoT>(>MO6(5^3IT^u}H z?~#99%F{>dD@EKsO^pq8EqD95#$;=u`l2&8?ysNEu}=GRfTpO-JiFQ20r%MhP79Q( z&zttpx8HJt;AidTgJ*V^KHI2%&t#L#%6t3&T9o|My**=-+Kz(V#kLGv(lat71Ozrz zetuT?_*iI2$dji}3oT??ohDA3wk_?f6uj{zaYRCEs@G>VJMUl49?g80w}geyEB?{k zIq$OhFP*;;*CX3B^3&fPv&`-8<bRcv<XyIMPxz+;3&J!{?f&(=Km7dP8xirJi$2IF z*WR+@mrB@Bur2Al)bZ=3kWo>IOE-4$UC{hGDf;&B_qOcKeq}57%oetP7?_@H|Ml+j zzxU7WueGyz({w~<!bzDO_5T<$%(LgLgLID%Trey6?>1Moyyaj*RR5RDr2-5uOnt<T zU(9Y?e4Qzl9XgCEair=;O3%J&HL2S-E<JtXr2li3ITuRBp!t%afib1w+{Mo`wjrh( z7#P?VF<QAp%QglE2CJ4X(1J6tmIDc(RcBkSMg+&qsL@nSTEDItEY85-z|Quf_6x&; z^`a`VCwhLaUAS$=`uwo?*Z^%W^+lHJ|Kz<lT)pT)*ctig-nDn#{9|u-+g_WNrV@X1 zuGG%{4!54!ryssDzaDPVeLCCg^6|6xY!d(NzMH?w;_a!c&Cz0eel9<7VbSr*Ej<qX zx1k+}7wjuuF!EUH@=jg&``Y#JXTFhJ4<9RCRh1lcgMXv@zsxlAwhozNwvu0O-_Lbp z{gSu;SlHrYXDU=pi{`Jry(Lor@1mRYM8564P*PDIHNkuKjTl=crKw#VQ@mWyPb#rw zvMtt!dfOr1$(27LBQtY_&DWogy_VKoyyjiQTzt0d{7dOidGjtAZ&F&c>(iTOzqn=x z23PO>-qkeQCFQ;0=C5wXyA9pM&c({ju6!#n`DD?&9aB1T?k>0g`>=Oj>Wgz6UmRY; zO2}HS?-!XRqMW|36%T*rSO2j6+EJaYp54t?^}RMPvaDhL{P1zr-tUj51SoBiwsrm+ zw)eu-swMT)OSd#F;ST5Dm-txh#|Oz>#!URH#2-VWzJ#;*3q#w4ChPiXOWbc%pV?9} z>(0Mm?&F=W#Fs`IUeo)>qvrj2;tr$j8kQk?*;-zlbAR75OftA~n|rboW-HyfG%@JK z_nFu0;y>l3Bz{`@BUt{o-tYd;Ez3JrXqcWkaOK>MED^zzQLiQ++Q%QUb8g2G(Vd!t z)!Lu(EP7^Vzc+k+>R+$d(xQvkynV#lJCgYJPp(Nd7nH3yezyFkdQoQZos<20p8vo6 z`s04#iPPTQI{xk%hd^L%WZJ#8#!L@4EShq9am~Dq-{-8oH&3>Hi^0!H4i-9=Z`v#C z?b9DVxN8;n;8lKPOx?k`+@e3t#rBB?O{~}cbz!!fm~#65nhm=wG#_0*`|DWPW;2-! zUoJgl&`OzfXo`2>{{1hv|Jm=Owp+urN8jXg-KV*7_3t6+`9p`JD}MsV$qq{o7r%Sn zTi%Dw61BD}nEPxk)@FN%m+POG{|i{#9;fB2E!y>I&TDnM8T+2GD;XJVeg5IgPqwtH zuAbZSE<d@X_W9xC&K0{<mabfP<-irYocq7j3L`@=&h6yhzH+yL%(INwX1bbRc6)Z; zKfmK!^@Uxv^?U3W?%Wr2|HiD2n(4Js;nU8F&+@PSXRVaAMzhcQ=fr0}Mdy}YPkfWt z=TP@(=addx<Lm#=Jd}>G^0oT=^iJsfWrj0zKpnU9k<xYBN@nS-I}xTYmM7fbL9mPS zJ44bztbKWYj&kOzwc4kp{{Il;Uhc{M-?HjWkFU(W4YT7-Ac19bt7PY^ZTqzBRg>Na z@G)FCkLW05uF+k&{?zuuxr^#<$HYs1yWG~<eJ|Z0vQXWwgg@f2sDxl3xarPTYTDHy zwTipr#IN=3nIU3#4P~CK2sqJ_cGz}#en|MfuHeHR8J{NcFJJr9F5zi-*tvb*<TjiB z4HH-AJ}bMbJ6P?^?{=@1NyT5k^yplb*G!poX-&rO{nuWFiK%e496l3mduUN@`P`%L z&T(7`7j5~!>16%U|Ajx;T#j5epK5Z=q+9#S{7+waHb3qcn)rQB{f93-w~q&}oFe+u zTvtYYTH0~Hh!1hGk;__}%dc&9o;<DQLWFiuxb$wB1B<Q%C>3#6%<GWgY4ch+!F%@B z6v&WigQ9D?=-y+q9xb`>ei8rPyJ!FA&-<_R=XtnPw)ZbR2Vc)uN9Ds(WB)JSzKcO3 z1Ky8VZlc|`JU=Px^};&oa-|y=vmKp79bfD#eWtwU&$R#3J5GHT+O+P!Vd25*S&NO< z%NlJe3B1qe4{BMvdP`-?96OhLw<yp{qxs~fQtlLkNH;OR!^iFN60*wQU%nE+cmBY& zT&c-t*XsEhZI(WqaOW?x7r1AUdw2Qj`_rDQ-l#rvWzC<r8+P+0mlw0FlfC`y#nuZ2 zGZz2KExjl^Z{NzQZ3=?DbGKTWK05ws4@+?LdA`S?Vk%y<U(Y&{D%beBV}*t7qHQ{t zuhyGRJ}H*!5@q50rih_)g@x&vJ9RSm5A<}rI<@&H+cPF-Zrz!XQYyjYVx+78{Ug_G zAGGGZ)5#T6pY!v{M)mElq;G$TWe}Dw-`-$asBZsetsVoL)K}g&vyMEC`lfldYh&5R z%ORJ!Ch5JBjQaG&w>j>{Tg%$!U47G}HeOG?RCHG9!l^^IZ+>*ob-O$FTKL523fY+j z^FJ+G_QK7jDAGH#tmo&4!dE+sT%J7pKj&9#km6)dsnbR4qWiyuUcactowv14&pq(d z(?sPxKkBDG)cPd+CdyWK`{8$1J$Kg%2CVeDq&!zHdd1Cv88yA{qyrcj<P$ty978U? zTc0H>xbxS#O$Bpq{IX};(iuKU&e3Ht^L4`+I!lA%W=W>LHamOZ%DfP*z_2Y#FE7z! z4*-t|roSxtzO2qwbNX91_EIScNUmy=i(R)XxAuPR+gV4Sx~P~)U%bxP@{F%{>!N#a zSrZ-<NSOC`d=fgp?PlD>dSmN%9luI5!+LsOhbSpcU9~an%B6spc3)jTKYV;;zj$lR zqI<`$<<6@5kJ<y!6ck+^m$<Q#@A31k?-rRDdnrzi*!^SsODo-1&rdZ)FY57F8uQAq zwpp!z=HG~~HC92>x7eheijtbbB`Fvxs(O2;e}3kQkosHucArZsPiK*O?Q-dvRq*cJ zpWn}VtzDcqXU>)%%t~55ToX;M3N;&6o@AfOx_#DbZR?)!Npg7)Ee;+!IQz;~H_yeh z|7R(!5?s2~BqY+pXM)MqEcpYIdRBWay>lp2NKkX?r!}wJ_db8P5gITB{{GrkT35F| zet+NQ|Iv%}zu(_X*_J*zGUx`si^_Df`xd|NPx)Xwkv(pI<-6jkK@0EMTEFv1IuX8d z;_pLsH7gZfI_a~#pUuFNRPs&mfO5i{H~S+kf2+jZm?v5uu{201FxmIx+wS=1_iUEd zS*%&Ia@#VKyHz0#8jn}`Tv9MFc>JMN(vUqwE7jXMH0cDNXR@x~NfqCvGcRf_U1X!L z`0K*$$<u2zGS@tNJv&WZMt#wvE!x}OUA}6*@bZb>rEMK;mQ~r?G(<O9PcL5<b2Im$ z#YPR)D@Tsqz3}Iq)Ad=CMA(`m=SjP}@LqM@nmY5@x8%?7=cI44IQw<#q+_qt3M+Fn z+p3;_yIU%@+ge#cfbTI^k4mqp%aV{&>t%00`~T(nE7k3yKh3YEFNAh74uAXjWYe@u zYa-m&x7Md}i%Ue!xK$w#7<sO=R`~X<O=phHdZfo@U^=BkM^;@Z@X$;DJ<s-Cef{4S zI{3)8RnG3U+4pBFH@(T`zW3+yrOZpMbG5_jCmw$Gp;P1Ai`{&WpWocczB1%gv9;L7 z9e*|&$4@r7+V=k!+A94md2i1>o%=G-e*62Q?_Zw3QrsG{<kA|(H{A^14N5FC1sAM0 zocU(w`uRS5x2Fp2dw%O;t_^drvoZVm1-<3!PX#yLh+!7KeQZ{e@$ZeVOcw@+*9(6> zZhe#U_?nnMa<hM%wJ-N~+2?KFXS+@J<te?{6aUru*B?vR^n-1g>&nE*Vte(oSFS&? zTX4gx)z|*2wbe|m{3{?BYcDsa{`Hz5#q4$KSDe_dIo-@R=7+wLmKSH~mwnqWOx2eO z3!Y?ERA?aRDYg11+cVa3y&txJB?SvBs+=}I{Mng){A}Ia4y!kPC!du`?6y`ukW#p8 z{|4=cZ<d=aUgk0T^|5m`p~c>gg{g5-SL!0YYjY#7^=z%4nUnXsV(H94uAN6f1KATM zec||h(fCSsourRg`|9Nrw$88uRl7=BK0AF}G6U^jOGZUm`fvL_#}`s4FswBQ(VF_q zw`SUx_6cq8WTut=?Z2`3z3uPJT}xIzo4$5&SpBr4myN@;QtbC8{=f78>B{cxn;+ft z=lm_X`Mc01Bz8_t*6W26JdKk0-TrSZeQW;IB_w=W>5s!FU+-J{YSZpRPr3`$?V~=O z@7Tw;Ammj2J)=h}b1%*ibauIS?oMwp&#rs^tKaLJsHAvTtMVTR2tex&ElA$`DP0-t z)B}fKJe09@U*CH4<wHSsv(I0Am#w*T?y|AkqO`)DL5jg1v#+q4DsxXib}Q)XKc~%t znu67pOp6nh_n2rW?q0c1>;Ji@b1z^2bAg|6hR?S(z3hwYs*N+=#;rT>p|OaG!N%t6 zr0CmW=O2OXVqnNv+%9S>)}EgB+Oq0Z)Yo0cri~L-K{cJ{R=Jn{E?%uyZd_{Z2=O|) z@_%*Bw`0ssn+3O~&U_nvdEcwB46~#kGc3)|*9&eb%a>=(czf&OcQyT=0#9uiE_ANh zq0GZ}xoXLLSWoA`fvbnR;#}|b{<;19tM6NuLy2x;=a?QEC?y%)%=>qKsr&y`dMiYi zyH~L7^>Oii^l8?lkV4mW4jF-Sq}*ICr5VoF-eDc?w^Yjb@l-?OxQmzOo?W5InQr%T zH^ZylF@k}~Ygg=2Ia(FsaK4R|;X$HG{LS2)mq|G<CrvI$n(`jLKBj>YH15{t5D`16 zsPem%k`i0;4UYAoPEC4>Y30ZE>;8M{-`+4=IJ5b{fitO>ij*#yZ~Hc5o86n^({*Ij zd}4N-y-}2MqyKg7^!iysJNr8(t^4!f*?*ha+7~X#cAuTR^-g*7emgFO=_W#glaIc< zxq*SfhNnOCb*U_*+Gb#Dl(Umm{(MVu-GPiFH;#9D+=>a0of8uuX>cjsReovCe~xZD zt_y$LOL<r;jMx|)Knv@@QT0M*GyCxqQLmKwbEcVGHMu&~YxYsoMJ9o6Q|`W45XZm# z;Io&jf4_arFzJ~Upa1`dx1shiFuYK<jVwL=kbCd*y_2Ojn*X|Rn{8RyH@VHn&R5P| zo`380Lz6GPYtOzpmU2|KaQ-K!`>X*gr&xYG{>C=#t6K`#Y6b>|2D^)gL%09+*UQ!N z>o(Xfzc@eXwtMWAj!Uz$T(2!=Dv-A|U9*doA%lN)9@t`s=b-NMzvItdt$aW0db!V< zyFP2~{@TI~H?RH5<ll%TfDP*wEP|~OVlbG2oAV{x)qmv_@#U@Fv$B3~zRW1fut5B3 z_|xSsZ?0}?4${>3+pUzj=H*&8_TBD}S$;p#DbNKwhk-}$Z`8%zvY)>G%%8U9O8B=2 zH)cQI&+-4~)MK|M?c)vzo>cX*Jv8$A|B4xU2?`TT!sh>Y&l9`+MRc#}QO||<UFEBG zZ<Y<wN_{l{_WAnHA>PiR>rE^o=G?SfZ}2nd_gm&~Eb=dk-ga+3uocqBHhA&H-Bthl zwah|SJ;C1jpWV(!O)%>gK3DVU#^mU)y}7^i8ajJ-M<1BAW3v1=9TgrKnZ|{y?`wf< z{H3<-9ix86&BlWXRkk0~^v!N)o7f+-yA%)`5<V^SwcXmk?thD$?p~>qkwdq#(sey# zr(uW}tDs=>#m#Q$4IsHMOw3%9PnOO9v}j%M7fZIuSFg(Pf9rm|>tK8F{r-*lDaYjt zYjPAPpM3Y>@;<wRd0EDM{8c-@9gTbt1zD^k5o7hQdcB!eXw;Q|Ju{l)itl@I{oSYZ zzisK|B@I*KUrI*{2bSHL*fvXP-GL1z+Se){1s}G39wK@#@Px|Ahr55WrS+e!o!#+D zYg2N6uJ-wzc4^0!eeBPd3}BSFa(I@q&5|!K;-#~_rLw&&YMAFQ|L5z1eTQMym-YAj z^Y+$#a$dM{@98B^6Yck=q&zgLe$2=m{CkeHdQ$(M-$%0Dd)K-xMcRaTM_N7G+jvHf zUu9g=_sP+|xwf~>^XzJB(hp+U1Q~kP=e(Kt?7hd=tjVrdX|1)dJlS5^nSQ$XajI_8 z{nYuZrgUvtF<%=zu($AY%W}CD-*<<s%2sdMS(E5@=%ZAil;BUDzx~g@@UAVN=si0> z{?DxZgs{*lDG5o||32!@n&eelSaf84{c7FQ1v2*c({HNh@a?bt@o--8uAjc87W3wQ zz4t8p>K}>9Uutb>e0L>RZ?m*b%l`ROI56zaL{07O<<mBA<=fx7?f%ObGjrGNnyLTy z&dn2B@;7YmUj9|yE6#t<%6&27xqI*I(|<eN%j?Iz8Or}R6n&eyDXaaV!SO{?PETZy zoBw<JW4CE~bL;ANOxslp%PJ}ScJBQLH<Zo}n>RgRju>b+<MMlZZ$(5)eLTI|MJ00; z@Bgn`3pdA?&;Ru3#evd~%l|pM$X&iBJkk9@RjFxj$Exm0>G?JWe_LbC&(*3;Hxs-# z_q26?&5O(b=1=;<@l{bP$WY?UKJE*z-hB8Fe|JaSpT8G_ud}WB6Qp3GuH+f~w%2&R zU(ANwSDWK+@ABLG<M3v$rFW{P)K})kM4tP)K>T~poIQsU|LnOKeEsB7UpBQemz0F0 z?>Fvj_gQlnX;0;hnw2Kj*RtP5KTg|!F2NxG@6NrCk3GF~uF0}ef0fprSY@x-JL~E% zbXVui`5AKUl7nn)4iDSq#6NphEwUD^G*{FAS8(y#>2-Ch_20%Fe)jVGtq-r4xW2z{ z@jWtqZ}xxAC--bZr`4W)-DzGsz4lPj=W8{gcb2g@yKHp7zqMeNg;hc9fm8b4MoRBn z-d(8)nI~?aeOSML|0nmvPe*6hr)K>3e%Z%&JlOkv?!K_I{TF|qEZ=1rmRnr*@3Z=% zSC3M5E;)IqFe%;A)as9z)gQmxF{N{RecE};%06!S=j>U$bKCpXr@2c@9z?0XKdQC# zP{9mk!NRXS$IskZvUW~;_R8DWg}?>v0fz4niobNUJmYhDBDbM!dH$ix<}>$L{P^>K z+9{P@8{5aO`SD6htv*4qb7GXe-hL=>U(d?Jb~){e$Wo_k5z$#G4^7gJX(y-cS+w-{ zuTwU{(%<)SUs(0@VGiH^eOmj|wQCk0=V`ZWdlzl~_UC(>WqVy*cAEP=Q=NBr^GTo0 z&c2?retsx)dGh6kk}`L?GIzR?l=bVaPd?l|ni-yRclq;sHZN`8&wn+S)rtFScXa)~ z`%8|>uZZ`rPn_<x^woxsuO@|*K7L!s>gHl{r<l)B!fajeRIkd(JI-|EUwC-**h6W7 ziHCnw>hSe<ym33fqwW#&>xutdQnH>$#?QPT`TkZt6W30cn2F9>Q)kXy?xYxcBI-)< zVv{M@H?Pk66&(Km`46_V8s^O(`|~|{epWp?RA2ge`lYz`$19h9H;d2CzAL$!uej{n z=jR{3Y+ff{Hgm_8&2!e4mho<R+jr2wq<qQm^}F~ocdob<Z<E`%w|eKc*V=Di{nOLG zQn>kF*&F*{ZSK68{POe5U!S=#Ggf3tfo|#Ns8`P-!STfK!pmQ)Dwn6YqNn4@B{e?( z_zW{8)g*oY1e2VW>EEnn3~$CLDNWsU`rGT(pWesZv#dSK|5u>lWXkzl6$Y=in>Sy3 z_mqog_Zhamskdgy>%FP@b;7;Q_}bgerL)7LXW12fy4-mFZO;Dm*T0K7TMp0pw|{SS zf7Yv0-x>CO_G|EPny}nv%5o;9N5TTRYqv(deX;6V-_>nV)?aUx&B@Gty=G?No04n0 z_I^t&71_GfZ|_yB;`M&{yQ8!}Y4CsS)cC|B)TqSSGO2~Z^RvzO{u?H|o*arCH{Pf3 zjCoRV?%&^Y@83+`dSl++^JhX!m+o|&oNgEqqc%Hz`(~%8^uIF?K8dI+xVR&`-1)zS zjY&rOW;c}<1Bsl?Cm%$9IhnaXOMLp2c{k2|6xEB^KmD=thTD#-r_J_dn;e%cIrk%f z*W2*YKU2Q-7oTKSzWn8uocZMP6N$F5F57pn(TggJ&@TV<=jFHb-yT|i`qe+TY_`d@ z+|70F5brLnI}4^?UH5rMLhn<*a83^YE{~|7*n)zK%aqd=&wH(2w9(ixzG$<4q6=g! z|Cr5sAETu|f3Sc4A*{Li<>~KoogP&hY2T!tov&A3)Uo=0a;(4QlkP=I!PDaYKf628 z`@prQm+QSE_wXLB{C@A%+@pe*#h%OGOfY(3QKxisZPDxeyCSJ!Ub6PTC;vHc?ft6r zvG%{~?#wA={y+7#cGl{%+v~RI$ULiitheJu&N|DUcfZ6EHdrkB@MMkp{kgk;oo(sq zWxoC7C;R1@IY;}`6U|<-_AQH><y&=e$&`mG?>Ed_xA=D4wcX3#d^`IhZeDqQedJ|U zJ^KIwq4zre(R}Nhj;9u0d!UeR9wB=t$N1~Rw`Z^K&)N0IUht$h+gah-lXLey`3Fsu zJ!0qGzpUBsbuwB@$NNg=m7=9v;_hC}xsrYR^?ucs7hAJ7pM3CGe$6!REm=EL1vMrI ze!qNQ%~nw*_2V|v-Fm!#gr`l&<rEa#zhLdUgeO89UWK0&xwPxT51szgO!HRiok=YG z`^^61wv!8trM6sL+5c^I%F+2bp<Aw(Yz>(<zh>&ur@>QZ3MAD&I;Lb`WSa5m&AV;0 zx1DZ})LVTsrDOK)cWDP3UmcQht<F9CGkMjy=oW$YUTg0&-y-F_GrXnvtY<F`zA2mi zvh-S+j9Ymvcgfa}ZTJ2x+p4zSxybYO?bP|wt`}dPIdW$CQSrX$ZQHxOC(Hlg-<>7k z6qQ#qbzjo*%}>s%HE(rHzgiICFMjc@p0?tVD&rvgdYfyBYv(-ml)3xwn&$R%pSG-> zad`EEN3(8y-PI`bJwko%@ojuZmhHavwIE&g>N}&>Bj@Hz*lyOUpZ}HnGV2%B@?X$$ z`Nr`Zd#ks9Z4OD?rB?W>iy?Yy`Zt5fJq?~Gb^7|<?n>GwvnsZnefrwu)G6cYCuc=F zXG*8`rd~RB>13w%*1h+`#pRx`yWL%>KdH-Gvx}>9Zg_Bs$F+)iZs{%RIx;10v*T8; z(>pWs=L>1&xeeQvZ(gTjUVBu&E#lbk;0T7~FrDfdy&)c7jGjIa{@B%L=bmnG`xRGm z`g+dZ(+@r}vnm!&>bh*|+8!$VXiKW~k3}a|{rS7;n9->mkruUrnwD$HmiwAE{8+=; zcyU_4+TwM~UTpaDP1G#k>Cz!xwdQU6-pEht3SQLlvQtu;Q;}I(oaMNs_nLiQGNN-C z+n>uz%!~@3bo*Ywp@hQ2kBltsn0B8lTfT3D|4qH!q305c)O>obeO;a9ZTBW?@41A+ z)`gu{TiJI<t^3)jbXZ7?!&&%FPhR4Muc32)Ke)EE-Yo9Vnq40fqI2s~J{@-3yKI-n z^3_`>y?rb%FwZ3ORrB0Q-9d$&QTNU~`*rMm{i&*o)4l6OF6~<PEL*W~X5vTgj>*=l z7HNLDC*7~Hz2v!ez^7^X8N(O9-n{bU;OstMCUN)OCLyO^p_^VEYTkFKVCIf3dl%j) zUE8$$%(d)lwtE-NKYhD(_n+G0b#FG`PhC^pe)g&L>EPAVqP4~5Z7@)%nRPc*B4XOM zT{T<x><li-Ojy79@rGc_*ES|rhlAMb5~kD_tXaC-DB{kyU-{Ov^rDh2b1r|=Su?%! zT*6PzLwA0z=lHVJ@%N<#rYdp2@*uqm3BFlxXMGg){iXc;*Bwip@2(eb#ZHgiA9As~ z%4+t%@9T@V%e;|$$->6=OVztSF+VnIf7ky2*>kUpi)Tp8*;)ECK4)J2l`rlbidDJ& zi}r5&{`>u-XO^|^U)8>stN-6q8@|6n`)8wgg>VzwUE$i3ed)C)weR;rDyYK`PtG>f z37(^29+&k{cUo#ckNuZ>b4$#UIA3hBjS&7j{p7daMPZJU(`~mYzrUxReENfP{>{#} zk*~jJRawo*kzcyT@mj>Z8DGzIu*q(|s<8Ou-{fqbuw}pfOs|J$SkHN`b23$bu2cLb z(_OWYwe1NOZ8nS2&0eiO_g1;(iioV&i5nS}mJd8Wi?(#BEj5X?H7z~3Y@&C=qBGmI z|H)1?`SI#g!GFok{ArtZ{P`kk{o31p--q?r|1zn$s_4$#_@!LteuE&dRoZGpt^4-d zj)kP=#sA*(;)Ph^jVn{v&)InQos#Dl)zyLTy<y&cxaM~C`4!i<m``DITk?bJu)9V} z(6t4DC!HQ|mRa}f3wKN8c826RVY<&hF=v{r-?LTbPHW_Lux5i-HZx1DwPxhVpT6a< z>@G1&gU46qq5uO!+>>*+D#1z^3jQCQEDK>WFfcskbo&D59GhHd{95eTO4XHjA`RbM zJjcXvAiJgR$9V&=3W-#Si_H^7g`4akvn31+4}9b5E-cu-d+WL{$?vzlj8$8_ZtXUQ z>+AREAMW*X0c&DlVAwHz&(A+0`#0@f_97tnqx<De^FJqTmb?5_d!OZova8aq*L2<X ze*1N^eDx>0h~2M^j)%YSQ_kJWI;rb&3ESj=DK}G63ja>I^h<Po&0EJEyDs%-ciX>t znbS4@zsTHk7rvEk1PA)hMJpc8UvpfY17_>vZu9vUKZ~~cpS|_uC|i5y(b*Fwe4O%D zOl`J#_EY)0`3v71`DR_(8o9qtzxwd~&E|3uKYaQ$l6LLcd1!ON<xTUWH`M7Xs#G8T zx8`g0^gRVO21UniGH16Jcr{DD;)HZa85j=ic>FYSyNT7|-MoD4bI;A$m9Y7)o7CC6 z!D8_i_m*eO-v7;hW{&*pjh!?7{p){hmur9gu{p>7*!kb3{V|JPzAP|SE#Fb!1aq>1 z9B=J4U02g7^4WWSMBe&zJ*$had}|n+|IEo-|1rlquDIJbY4!47Q_64b;gt2Ao|I-U zH*?RHhkrKy`aJ(k-5Y=2=lv)1rY^Vna;azOe)SfM+kPB@9<NnImv4QgR~r6#&++?0 zzFwJoN`h)0R{UC=AM^9k`acaF?RB5;`&}~WK5f5N|M&4%_9DVg`&OR}_IiERt=aMV z`)8f^&fK5>@kl-I9lPwO@|v4Z>h&HyU;oI_qVjX-y7?Wir5~(GY7zL@`uML_=Ki2l zkA9u4{*%v~EhJ%ic(X91@L*tQ_?YoRxymG};?bhd>hZbx8kGgb>jKxGwBEAs%jN0Q z_SW1g)1T`WTJ-1X+21KG6B<4|`BcA8Z04R4uV1S^tH%ePl9H?X7g6n87<X>6C-?mH z!oPEJuV;o#jo+Iqxp{Zpv$=nirRP<Aj>@P>yV?16?)LRIJ1oOhg{}Q3>v43x-WTl4 zF|q6Ptt>91`8DkVi(c(1-TdJFwAxkN#Ydj<v9TCmdplEN?!C*U)(SQ!%XaU18s&dn z*ZcLs;Ac0MJ@m6!y*hr6>rCI;F0<73il5*9FE+k;PRosB=ck|X*Zw`_Iv!qOT)#in zeD|z1)tfgt7u_sHB>nt~PiZ`L2_}juS=Tnp#48>Tw<!PmE}w6W;fr69GV!nNWaJO7 zy3Wm^sMhRvF>dvgtHMq<Z0emnQa%MaEpAm!nSIu+ch}|lub<~s7e5u(4UK=kPh*qW z>M3R{Zp(z6mYs=tDlhU_UgWWo|7(%!r;MvFg}>SIM~9<t^ScR~Dxyz4%H`|7`mIc` zYmsqX*!%@AzSK?K@?mlM^*=usDX84j>vcRF=^OiDjhpWERlA>@4eu^8*T3~8G2uu_ zyQp%D&kT#5FJ4S@Jul-G^+nq0#DQ5FOTIR{!K3tdoA|v_Yr`rv#Um@O-{^ZG==5XJ zid~obEp7gH24+sVnNoh`uIP7-Q%B1}+b#0m?P~RZ&ckE1g!T8X_aU1t>fXKg=Xm&0 zy{M*@E3-BuX4%`a#0(|HBSv$c>-0Jv{>kd{gVjaAY0)zKN7@|P*8ieU$HcaaMt^xT zanGF6<@ZiS?0K3|@kpuN^y32-$T%AVL&BU-hdSgGP2~S4$ki`;t9B~q*QdSia`&p5 z^t*ye?|oVm+c$s3(pTB1ayIeI37itCD$IR&8Q)e}v+4J1pD%m*&@Ngp?QWZDiht~e zm&a~?f9v)oqvctlMLW}><zLI{-DARXzMgyZdH!F!|0mjdt5x{2jh1x4Gw-^}e{msQ zcWU?e-3u}-{`tDxJZhfKVvXLYbyKdb-aV_gD!2OY_7;J?VYx;x*0j&|Wpm<iomp>{ zb>Q2JEAGETH$C#-rgbZOSCrOi|9z((ebW7(a`UX|WY7GY#a_Q&NvGd`|29vx<%{Mm z4#jEL-IwUx+m?2HX=D8%p-r5MnWxJx%zQJ+KmO0c^|x;=+xEWNX>p|S7T@Fx1uX*2 zamlvR1d_~NW$(8Yn!9U`z@rUGX_FW3GH5^gb@u-wx7C`@Wn8dY)7cI8O2PcZH~045 z{^hvJAa?SLyOwJ{osm=P7B|qGdGzDO71oQ>*C@1PT>bQF(VTVHyteh%dz`UpUbp?z z8M(@0*Q94|k;yZ+Yz$faZc3N8h0Xs1C$8+8bmv=}5L>sj*z}tP|01Gu4<2}H_wQiS z1PjljFJ~<}yo#^z)+X7Sz?9H`b&<)Esb*YG!WMQ;>5{X0cFkIJ_|xt18+$lC`S)B{ zKPmQSO?dWINvr0&%QHUncX4vecU!!(>Or4h`mu9y$!4!sbMu?U|KGHB-G;pjBkq=3 zSO2vW>(8IwX8q7AKYpE_&5B8#`}6nSyI2xf^!EPOrS8ni!Rh~BoiAbQ2DNy-c6a&u zMMu`;XwN;Evs$}n?p`$$z2@WmTUK`}Sm>#g)y-d&yF%S!#Ri6BYa+fCM8V>oVg2Gj zGwqw9CNKNvye@ve;f}a#c6sbK{yy1_M-sj)J-%VP-qBArFxAQ3>aSniovZcx@s*1g zQ-5CzU%lYuX1UuF%im9iC1eJPOlP@^#?oIypMMi{%Ie}%P087^=S7)FuH_BeAAT^C z7`}Ha_P@9|^Uap0>zC@*=c;Ui8^CbgrvADvT;ZK+iHpoIo`k;v(unuG3mRRU>H@ya zRFypzc!uqm$U=ErwIh?aE5g(tIPvpl2Xt8#0|P@(;fzxFSh~Ty1ZYo{fq@~x<{(1d bfr?N6^=nmTY0IBE39{JJ)z4*}Q$iB}&Zvl> literal 67499 zcmeAS@N?(olHy`uVBq!ia0y~yU^Qf5VD{l)Vqjq4{#)10z`(#*9OUlAu<o49O9lo8 zmUKs7M+SzC{oH>NSs54@I14-?iy0V%N<f(LUYdLb1H=ENo-U3d6>)F&a?X)?9=kxd zDC?(~go27$VG{=nchgChqb?`6_lb%ff8-%C%|a}Eg5^|hwcRY-k6i9;Sd%c__1wb@ zVW%nlX487-o@tWR?&H6CkHuB`HuJ`%6HTVMO}|?FwddEWcdOn>)&5_#ec7^Izuv7} zwQ^n6y!-b*U5R!Nzy5Wf|9<ziyIB|@Ae+&T55n4D_TUKvLuN{0;l~FDoBM4h-T3jm z-tI|FC<6mSgGBRWW`-qwOP6|Em%X{Mqww*xCq^bFDpC8M)FgxCXEcH2xdlHhUApxC zpR;d&e|uXzX;MeV&%^yPCU5m$t1vP!FdX5ZBg3E&+p+N4nWg2bcTcY0TXve6-!5pa zZe-NEC14eNU==#Lv8!fz@Bg^&zR#Y?^*<ZiPq#%HPhX+M&cM)c17cHP$l`5ZUVD~* zGLNr*YhU|xVbIdBwF{pxFfa(j7Zfoxh$xn2>BU|;da_>mr{BN+@AeTZuJEk>X%z+X zts$#AJA;SdqGhJVD}zigKX{THU$-G(-OEs6b%YfhPoFGWnOX4ZfA00kkHH3~gAHz+ z%nb4i7s#cqpde#l*vJGn&%%;{fx%(Tfs>33K`h{470|}i!t(mb_y6~-^z(P+UYaS$ zTu{Woz#zc^RwuY;@@^%&%G<NU);}$cju8bL$ire`$>7k%aq%RxVAdQN1_p*8Ha|Xw z2}+AfigrJ$nR$Qreb23#R;%?c?sq#6c8`Goh|*MYQQxi>=5k9cr+igj-0aA@wehSd zCf++4{$bY^)8nGK-J&=1j934Ae--Sx0}c(K*zCCQ>g3x~`PY}NU0JoYO#ArlGeTg; zdPqVXboS)cBb%bYLBnttq;W}yz}!2puf?4Wi|D?^nVZJhd+eS*ij9{~N^9*2zp^`T z)!8*_=#p1YP7U16xh>cF$E$t2XKwW}K7NvsfgwQw9G)&4{NzC44-YGlg$xWw$c_e3 z5Rn*j#A$h0`f09pxm-`z-{0T&f8YDQR88sO*7dT-K%P<f2Qov`$+B{3R^7Yz`#!v1 zxAU8?(EoR5^LgyoRXpWi6TSVNdi?+3eP1Rx?YrXt|4j7!nKscH;6N701}755EKtJE z_WoIvYqoxV^olw2^ykmww*B{^SzbuJ{?E!}h~DDvsXv<nS6u12B?L~28^LK_TxrFk zm9BTsh^-dai;Ai%TUewfo!9g4qwb?8@$&ZXy!n;SrD;DG*S>67yD&sIH0!FA6DY%c zglP^fUYRrFXHo9Hgfq{+&fKHOCY|-?qTlJ0`+t7njIWX~oP0g~^D(E5TJZt<(t4vn zNxQ=klv;KP*oyj^W=)$WUV8dW@zYs<q_h5<Y`0VL`*&tzdhN?Zmvu3^Az7+-r|3s) zm0A}aFUi2bpfC><STB=2WlA$Wx9rK9y;CpH^l)FaU5@3?&UF7@mkxJyeO+H;x;ZUs z?(>x@pqy&~E~farPtW~$Z%tMTXW*BB$I9|IRsH_GIT^g~%K_(FS!*3h_v4HVzZ9mQ zo@-m)$6>vRn|s+ynPLxPkUOh3zCN?KBX+lrx_xQZsp)cA3=9tP9V&KTuLQ^cc_jW{ z?$DEUyWd&W{McY&8O8@n+bw-XpH{BaOqXI{Nb3BNc-3Tn&8L<9wQrI?y=eRJqkI34 z?);j^1v|6CE`GWKa-G8qkB7|a><k^2VRP43daj@4Z}U;bPtNSollFZddyfW%8oQj% zJUlN8l+`$7HETd&V0e6;%Knf`XaE29onupS<mCUK7tGU&suspvUc0^J!gH;?AVmUJ zK|erQC8^J1=ZVC))w0J<9(K3<d9(GD)5R4b(|v^1{lS^BrBB2Tl#pg5>qX`tkI@O; z|M9GP!KV#^>i>T&%=bAv{rTsrn+Dm}eml((X3PXRwc*0VL+pNh3<AXkpELsf{=Hda zHr?E7*V`xODjTkV@*%=c+a~Kjd~)%D#ZR9~v*ow_>NwT?bs?bywN%+J&Txf#KgasX z;@YNjY|f&%oX<~A)lPl=wT#{K;!ynWZu!&c;(?RO2TDI#o<8Y|O`nD34h*x<#r&rD z{aZcz+S=P+R-bdxH;LW&e(hIx1^M>L&D@|ovQW7dTthu$dG}=6?y4P+etow#E-0EK zV*@jJ!X*h%IHWrj7KI;K+bKHvZFKhRbrKya<^EWVX?gu*_r3bRqS{*BlOI2M0IIkU zAth*08N2pp*R`l%zI$x%N{#0%-K%}8crEAD4DbEEf8D|^wOUQj`?qtFR`9t!yUuUA z`DOL1$01esA0W(e?gD46Ih_07{_6TswIyuIP2c<#-rv`(`&Saa<zGbHm4CbIvMQBJ zqu0#7`mOl&-hE%wzw-O>>A@mo2?HoW9+|n}c*W<eb*8IlUW<B}wXteuS)lf>v|rn| z8QuM0sVyJSZoV^7u-@sg+iym7c5zS*<mApJA0%=3BqPHkACbQ&r^jxK%U-)u^omxU zU|B@m7ROn8C%svhU7PmTZPt|z{mpw8)MxYV=ldc4f_sik3@l<jGTA}dz*y0`a_*g~ zE!*-|PUZZ6iZ9Fcb$q|rYL|4Ug6p}@pOnf!nEN50SG|40!IO*(3METEfD+u1Ia>=q z{b~(cCgl^canB;#-L0<c*WB76Sbi~V{_PE0kF~V1{z7&vC~KeTT=ceT@%O5&H@!-y zuZ+GoD^>qVbl}<W*H?3o{@h)6$olH1;<uXRywdO8u58-J`ilYCvkf5IADxNn{g`%p zW76fXpT3_;nr9iOT2@<ebL!Lon=YL?ewF*PSJhp;Er0Ip>Mw|h44bw|?GN`C9^~+r zfrR&gxiYsJplR-)v7Oz%qlepgrH`C6&%gJ^C;#TA(%09DcD~W!WneI5Q12Ilg<0#v zhl#tV#uvM}yU%^fz@Q-a;7MQ;)R=_^W@gWRlrz7+zW#iQ(YYc91_AzpPZ|eL9t4%# z4I45-L;X}O860>Ho?OfV_1K|BnW2_bpD-|dWI?iJ;;~glS|=G99&!4~slqal(mse_ z5;u~d-aV*b_v<H{i$6a<H+OcEfo1VCAG6&BS?ii6GlTNf!$)CLgFX2e1k!cX*U#!c z`s&e98E|PQUTk^%Wa%86tB}04YSkRCB8CQwWW87+^>~fY%-wQ~tKR;4;!`Q6?r#fD zvFC2wkN`Q?kX^lB=;;&nWranc^3LhmgM-bJzScca&g|d5|F3wh=F6U=M_r$vVqoZy zw5Xg?F?UbE%7;%f+0@w?I0P^6Dfua?Uwv2q&w*#<{{$RkKF)eCsB8X~o0&l&@4=Hm zr`x3kptwHdv~s$|&-}NwpI?ZtSLe9+iNE%Ta@Ex>h3kYF8fG+1cISjdtV2XcX=iP0 z+hpO>ihgyU=hy965-rZ=#m7*X{4+MgqEcjs-?`lv7(jNj8m?QlGvw0h>3e0=)#nJP z|L-@yzbRtXw6&`~c~9BTpb)m>z54N!$_|!4H(OYOLPb&0Z{782Tu*PEE+|T}JaY2? zgMK@c$>v>Cqe8j%pF7ILAi#}?V-8l$n=e8?FKU}CtgYzxZ{Pnf%g@JN;TFBTLU$&} zbU#FD5#Ty?QrtUq&YS}0Ie+&4f9d?_$<CsyuY&x3ax*+)LB#OF1nZwdets3sbN<-= z|LA{SKdflh+b15D3`aQU*mxBbfdk6vVAbLtM_bE4@zZ|m9zS6aa7K31(<ecj4xZ#R zpE7xV^op36vZAg81_60w6{k<Gwy+EofAr*iT;V6xxOO&BYZ{j58v+iT>^v6Wx9`q; z8FluCibh1ZYdm<e_<PL%+w=E@?fb2NziR7|ZToNNOy0l$z3#uGmqaWq8IDLIxl(bd zU)}ky`+wim&ENgAbiMq~gQaIH?tR|>w*CHxO|S3$e!TzR_54rkXEz-<$*6D+IjmL| zf2v-$|7CD~-R1TBZcTje7g4nDXX^VOFRuQ3t7279#L!`EQ8@)#F1I*!&G|F$b$$K) z=v~_j^-rCtf2wc(d;81_U}KjYJo(<PD)Z%wyXTI~f@WO-F3rME_IsYM1v%i>hspYd zD!UmszLWp8a{4y&Z{mACRNDV{KfF&@-3V;e$I?%?<!A3L@timP^u_(5kDmxQgDUd? zkLJnU6Yl?rzyF|PYy0#4A1bfk+Y%Ua*M8A$+v}$nR@^?jzWVI`{f8n;W<KBlpfdl? zx5K5}>V^;_ONve}(m!ikw%b_q&c7RXf?}QcAHdDsH~D_?-`#fK-peeFJGSZL{aZH* z3rZ*cjQ@H1?7mxHO)@O~_!tV++WhifmhYXgUTBU?5(lV?<mxQ{^!;w-T>n+^9~M3T ze#Q6?|G$T8_nE!buXy;`&2G!d?Gclh)Y%&>gzeSERo^eTux*R}_RRIspWZ3w?Q(xr zSk$2iDzr6JZl82re*f1#`Es9I&sg>A>g3m(XWu!;9slRg{eNG!?mH?Z42tTRH!OGF z?fv7C-Mp>!j%iNxp}CqfA9q#Ey@3dzO(2iF|94jG_`=*>s}%P?|0VnXzW@HW&#uS* zj+Wkg?eD+c>pt&0^XI32&An;&Z@oC@8}Z-?gFt%HyC-GGi}I)LP<>c>tnT~8WxRLS zicX)5aN&)U{~yTT`}O(%%dLIRx0P4#fA_rp!1f;dcRS;3Y7YDFTjE)|%l5<U&APM2 z_x<=OTfKxo18gwc(s_42W@YE?ZM?4gK6AHT<7DR^P|@S0c+l_PKkN0M`R3g7U0r(B zt#&EjpLwtE|NZ~>i?v<V*79|mce;GnIu1&xN7mc#+-~`cE7oG?)<<tX*}OWb_zYBZ zES!*_UjJUa?%2lk+2ZT!_vJSp6L=kVc<0^+uIK+h{a>@y;t&7+hpCSqX1$ZY_xW1< z@73lj*K%^oHORu^<aD0VyIsdmO5a|0`%vut4q5f~8KBy$#VKj-o`0elcYkbNzjpVB zJ<scJufG4oD4+SOolU&}Gg!B?`u4SdCi$O^UBB&LhSjmz;n#KTkDpY$2632}`g;?V z*&IKk>z=#MZH@o1$NbI*=j(f)o8JDH^tt-q_5I)V+9oqItg+l!QY8KKYF-7;-D^ea zcaFVkiaogQQoo&A{o^MB$>2nP;AHB_`#)!A-!;4nN@crcPe_B>s}aSIUO(}KR&xp> zm+sB~Gw=2G`cJcX?SBeII&2NOU-#SeU#bnLC9%d5IrBEny<`6F7kB)hn)kntss8&g zZ~MI;@%I-z>zcs-{||pj#rDYByVc?P;nHWo`5C#G;4J%eEPVRkKk~fmbrSY>{kfW7 zGc#jbJ&VQf&?lwbw=X6(bAtM+k9d&E*9i&g-$S#x_pK@_e3O0etMdB4H^YBjy%o1{ z<qB)*O_c|`=ilGA@b?2YP!?l@*U=3D9-AiLzP9$B`MMX|w*K67Mq4+W_tyRT>!t53 z3Y?mx*Lj1J7g8bHnqpm<{ItwmU+a6=hSiPtQ<UG$z9hoAPGvf#H_AWh$Ng_F-~V;` z|Ib(ZJa229{nq<EOq{p(UaiUw^_^fp^t^uZ|JN5|P><-l<BU6n$7TP2TATmyi2@{s zE7Yfd=sl}eGU3%Wzk8v+zZ*cEhe9{YpGh0DPCe#SdYBV-{3Ii&N^CW;*x3?(8Wef^ zA1@C7Ew-Zjn%_J&MTom1{PZltS60=0x|v_|SejkYXWzH2>*v~(zPfqy(;ADNeUq0< zfd*kjf*w5)S|#|KJMPb)`2VlXf2RFpRtM#dV-}X-E4}JJaRmH5sh(Z{ZY>;AwDr5^ zTyn82miO4aD=_abn)By~i65vx=V0;RiSMGz68TwEcCciF3peDDKX7uki@JJv$yJ^@ z18`z*p6t$<dmY@$;$WS#r}9qm-~9StxAG3{Pf`MxZ;yLEh8;P%7}}at5Gg2H1Sxjk z{XSXviKAfdobrXBF*pG(3(JcVpt1~9ZB3bM-wkd+2?#O2dZK*Ya_%nC>Gw-|^BI#& z8z(b6%t5r{6hzo=oLqlrN33sM(c`BXl?yQBCp~z=JNbwf+`Z72i-yXjlWRTOwcVx( zM=#CapLxPlc-`$Sn^NXJ$={WAch~B?Lbcg>?n3(eUrME4E1i8SU-20>qqoN>ip8j( zIeX>S_O7hgdE7f+U!7)V{W|Kl%&u>fwPJm(y0_lmx1F>0weAsnaD9WE;gpV5d|t8s z>h?W1m)w26XW^_}3*S|_E|JzcHnn~Gt-8JQZztv+4E-`ym&XYsO&?sZzW>=R?blid zWc}k0mZin7-O4pT!CJGgt6JyQ<L7I)-9NKytyjg?<g@jH9r+mAmu!vAe|2x|rQ23J z_jcXA74vV!?=@++^P`0K?fLsl>=Uy9EGl5_97Vz8JvT$2YUiGwebvL<H{Ykk_6}F} zW}|Ss?4{EyR=+hbElNLbc51(Nv_uOmUBT=4&Vr(R*OJ=cveh>$H<uLV-=4qr?HZ3A zSKaQuzIrW9ck#Edp6$2lg4M&V)lAk$_2*(ZH^pM-s(o?my0>k;xzKUBYz%*R)Vl}k z&u%l1{_YrNa=$KEz1-&h{?;AftcILoB?8pt=WLi$vq1`4E(pDRQZB!DOUakKbR|Dn zvxUh|E^mvRu--Xv40kS^eE;8#IW}tHi^_K&JE;gBwOZIPxm|MKx#!G~3U`Lp&pXN6 zt%J+u1$E<R<{Z51K3%W!+QE~G-@t`H!(`!Jh*^6l|E}F_X<^AD1+LH^JaI_|`;P6v z$^819vZLGIW)+K`&fK@{o%_48IW?-bW_5j#UJW8k%xqkxKHc&i&(GV+w|l=nnXY$s zRi^jL>Hp)hVX?!gt}X>m;KJqV+k1Cqx^7p!_bw^-_PXQCHLYO@9&UHit0$*<FRH#; zy~8&5x@tj@L<G1#>6kjXKW2O0-O|}LofliaUNj58`)K~uL*Urtak%|eR7bH~bZ%9V zL<U&-fs<>0JUMn+xwd=9-@Yvz`&a(%Zgv%)-wn#2k}B%?BKhU3@?<RL$gnYh%c+8* z&bQ{gYop7LdN^18FFY;!`j%(i6u*1ttuGaVnvu;<o|N7Hr0lg$*Z#ZZ&rdpYWY`#C z8c)o%*|lL`RKJrRI8-H9Y<vApXSwmui^pGyZ$5H+-qU^DXJ<A}cGdy6AQpzJi|6k9 zvn)I8mQ%IJt@JDJmP8%>7AGAo7_KHA_EC4I(dmVL^R6D7yK`<$UFzwk%^PBS-&_id zpIsOBxbJH1sUr5$`@62m@6&%5@c(kd)fM*^uJ3zyZTsZ&xgPJq8Dpk|Rb>;jcgfLe zHz%gR<h+?%_|I7t%WPkAET8q%YgziGt!H<s?%(lp)zkfZqqqIbEBKnX<#Jf+^@?z_ zdj_jhP3po<%Vw`o|GxHh{KlW#H<uOte2}y2)c5K}_v_&i_s$hXMDO^sOWVe~?B6UQ z^vt+WUj2JVy!Q4le%m6Cn!lW#I{U4t^0b<&KildqMJ>&J`mLzq?=`-Dv+oa{+&iDO zIoWsaoz3q~ndfd6eEt64s^fPz)K^9PjJc|@;IsKrP&*2_Cf`{8X<>H$r25)59&75S zhCK|9S3hcaPj1eg{nd8U>=&(^Z2tFJuGu27)&4IH-&7UlD>t>tW`hzpN{1uSVa}eV zZok4aMH4M6yJcUWJ!$Q+Y3qgy<+n@MPp;lqIvbp-knJrjD{`NDJ8Mb))M*!Y2zs~4 z^1r`)^7fk<rmL;h-}_D49eYNeS3mZ1&1*Ao5<sp2m`aLn=g10fy)=Dw?(H>?W`9}t z^h@iuf8X{dMqdhFb7}ilv&8&6u@~>|Ful2a^7fk>*;>D?eLXX0ui(e@@~L{OF3)b? zx@fn0>HS^4;H-(<bYPf!XJ*KX@L4xETdm(@qgfw+?~iMCR)LZ0?qAQpZQS(qm)PCE zRy$p8%We*|dlS9AZqsMCmV4SK=Wf_P*E!bu+cgZgR+Sbh@nVR=t3~A6Vbh#D@AU8X z=-tj?-`J|cg5C^TFmFx<&m0*Bls44^tDpS;U#yP*xp?~iSL*A29Ncn@|Id%p`u`_R z-}9z@|M#cT@w*<bn*RIQGOc~TQ}0)PuK$<+Tntn(DI;0k^z=#F&WKfZm2bZ6+r59& z_dfmlKkwiFzH$G4dGxGD=fB_kTD<?`zti=9q&j=^e^vhcE_yin-{JQ)AN2n{le<5u zli%{|{2%e(|DLzrU-QN3<)20Kw6FI_`SCG)WI}4kO_<ah7rkpm=z0CHKHqHrdFSdM zKRLSIezv!#jg{g4&+GsHGqwMFPQK=_{+~zhYhS!OuCDTN^LM#lJKxGr5%K)*U;lF_ z`~R;^<x`IwH}`us&nn!;Zf)#_+u&}vd5rr1{r)zkA1=D@|8?PTn2kq^5Wnr86ZZ9w zKWsL>6?5;v$zVQkPi@-d@Uu=k%_d*=KR2yEM&s}6n};T+bNSEpt*d#pj=lcVTJwE> zwnpFk@Ol5gn;VZyJ&*hBy<fGszUH+4-Cv#hHIHwu$!~ONoAayQGTNeQp^0huyt9%^ zz0PXYMOujSFdUeb{5;0Hd+DnyKJTKJr}4|5u6cW+^?&h`Lyuh!e4Hb5!}++8|J+&j zrqT1xN~_*ICo<<V!%9#qo`bdc<)kO;XC>-QSv9kJs`1TJPkPFdc9kUUn)Betr~f~% zzs~>h_WkdL*Z)4qUjK7*|J%=JzaCru@4EfpBl~|_Mt(ZAy8fB|_j?a#&px7IYaMMj zS@-nOg22^Nc{fK*zNGKR$6$CU_u<z&u77WoXy)qfQR-fATm5mq|Fd~BPTAM)E2-Ky zM^|E2UQ}gMv7ACFxK2~BT%EBqFj`A;*_8Ze+{a4R8O^<{dgRn3@%yuE{{ODu@!2}= z7qig&|Bw4+?5$r%FUY*}Z|C3jRcF;ApSs6?SNnO}+}v>Cx!*qbCY(+PTs=+8bZ=VJ z)hCdFoHO2G+n#1V3=PrUGcPCOxAPjcClmVS>)O<=D@by)-oL_oUx48Wksw}hj7{3= z^(`uT*OKtFMWrj3%>L=68^7-9mMFh}z5!=+#Qwk0|NrZE+`flL?|-zl|K0t*;!(8l zKGs|9YyREO+x=J6eoJ83{V&I|ztw-7U&F1U_+&};Ri~wD(;L%fRF$sGx;io1{tg4f z5%%JjL1*_Yk=z=x^+Qzm1-0d;gNvUQb5Gs5C+<r2wb>RYM1pugt`VEGv#Y#wT6cq_ z>E#tsf4>Nc#moF&E?@QanE0L-_xC(o_3-z*`UB?Mf1eQD(tqby`u*Rv(@!p|`}8%x z;>ASwT5c7kBgcFft2yPF3T!RZ6J=<yP~caM=Uy+ld*=BsM~|3&ikcj7yx44cdbiuc zr0;2u+HaMBJEE<p;@>Kr3p%^y)tR;RlZE{4O#e-r|L^<x>VMq(o>#|zx?Y|4`RrT$ zXPdcq=lwl@|KI;V(KpxR{CVik_e;#f!K3oJV9|3UMurZ-PX&|icx{Q<`avkUB&tGn z-NfrrZDEs{qcyIZ++7ngeU<6vw7qT3J&NF27R60#o`$)teqzJ;@lGqZ^}WCE@~iKC zR&lfc(D>$1Q+{J;TTZ;$@BDp#Z>RoN-v7nhzqkLln8clc>5YHuU-L6G>{$3|P0IEU zU7iu`+taR2h+cc`?IorqVxVfiWQ|gvbaT(L%-!Yh|Gj(v?_K`yZTYu%mA<~X*nO^~ zV!^{ht#5B{Kh4gmtgO7;Z*EZ<kKVk~3=9g}R;)SYlf=C~qV;Zd{m<u7uV+{vmk$Du z!U%>fvp(^0seW(njStPQuhrf@)@xt&|1Wz@v2$1O@@3m{e~bPM=zM!Se^-Ix<LHD9 zObiPDBF<|^pT63BI`^eBi`+NCZAR>$+NXd*+=2br@#EWbZf?rEyKCXXg|^k-ELI9C zSsNG`DOqo*`}^zS#fv^_kIyhLG!z6Zdco3i@YKW7K1;CQ7^0NE?M^<<H!;yMrJ}I# z;>?X=GBy<fe@zt9_GMpRxAm?hL&KDW>raIivNV9^(i_yKoPK(DcR4>VZzps9-Cd<g zNrz@`yw)+3pP&D9+{t~NGf&r98H3g>unB-BB>wdD_U7K$;JBy!@v&ZZKAD1`$1QIb z8ht*kw>#(jJlh$diFqCk&?xen4bNhaS0~-ySNm!^vtjYi+n%6>8WJ*~S&0oDq1Qjo zyRo}`y~WNq+kX7~_xJbQ5YXxdM+VURzV*hpR`+Z_iGF)?bMcv)ii(PyoHH{S85kG@ z@<GkP5aIvp9^c)(W5<r{>v~@wA9{9nHou(Bi!&fsc4&jzzFv}R);+$foVKs{`MIyJ zub&Q|tY7isf?_%w0|SG@AJABK(D4UlvhU@7_I<i~rCdf*Qc_;NJPl;P5l&DFaaCFH zy29Vb*Eje6zSx;Rx8>eWxdd?mKgb1JCM;R^*w)a{(9p<e(U}+#+sP*_z=3oP+)w_g zvh{U^{|Uz%yGmEfw0wPiy}z$7=^4oV>>%ALliSukwk`bd!13$nmKi_S#qPFHU|?X_ zunko9om9z<Jzo9jKqK?v!-tDfp8V*Td3s|J*l8}@etZlQ9D;6_?oofDaq{ED#U(dW zr@y_qncbM3fuZ3As6i^k8hgAt6%^>-x#5A{!2<G=;)T*0(>FIayU&T?n~N0Y;Q1al zxm|tiP2Uap`1$*Ldo979aROBi5;-rd<aD~byLXqp4NBWr`T1EhJ3k~vIDsNdBIJdY zoZL*Gw33pNzrVf~RXkOYw<<XS2`o@TIPk#n`p1k9a?dADocQr$AtVkQKwfQTi9NnJ zJu55g_qVsF&OGIxSpxRv8c-M}BrJISL(0g`&JGm9HOKp8XZjoi8@hoD6o!lq>mC~( zv=w}PeZ9P_?9nrz^$Sx$hHi9Qb3WI?_xi^f1s@(bepjCqySuC~h=GA&0XXf<2-2H= z^!t?y_e*5^6_b;b4<9~!>P-3jd%Dk0gH69+3Q9jRH}}{7Pn{mCw$J_g#~F{yK286; zHT}HY8PJ-LDp0oR5O3#`y|t%u^QzjVuYWAqkbmFqt8~|ooqygg0WDc70juGj>63PQ zTkfM$rr6``eMLL>q@S0&e&+bGV{;@yDQzt%zOKpb>QiSc)w;_4q`ke}u$X~?A%owK zk72{H3#B%dI(mA$>^J4y-1PLp!RB*3pd3;K^1W&Ey2mHgCZFu->)VxPXJ_{goc1F? z6E6|WFRbRt?a7}ZFDZEt6f6fosYXDvMAlzDI5_y-dV@tTj9!A&H-Jlb7xviW!RLPb z_;KPyhtX$Q>#`IhNpKu35d|e0t`}B(dPRmgH#fQJwIQWs$Rv;Wu0H2rJ~<l;8ylVQ zqZck*SQoo{hXDfv!zE5XJ_Z4?64~~?p5ES_Y5S_b=j}`b`+EW($Oi!nUR#u$-&gzF zEa!$ocz29(^|v=*=UxI$W(gRS$hQ9jl@GsU-T%bs+y#{#4KARvk%cYxc;eJ4r=QwZ zf7_8}XJ+;c?3WhMoG%MQ>~Td0F>&#yMN(2ylTK$=R7ilbhKGTLCBuQNg|97I8fW}G zH`n?qzisrk9LtIi3yeWajD$c9-V636vh5pArWh?=yf{y|2bNS-nC8eZEResm?y-_L zNWsimvu^FH-5ryE=)?(*xylR-3_>6mUy#1H?s1a4lJ_~Dh6#eA)4ly>?$oflF2}&& zzyvC9st&xhva_-A`5zY{3@Y67?yfphQ&M6AEjSVwK#5`3p|@6ge*4Pb$Ek}Z^jcJW zcrZ;j`bpE0?<@=q2OL1YFFA0#wC4G_xhMFKv@^5w@$mDXK5A)VvL*Yvo}M2ALqj7d z%Vu!K9#2$|ke0r^qj0g&XWQy;CrV#~L+J*{43qYCj}0Q;+}@slxQ(~y=&91vvwt!$ zFtD-CkzqK%AA3BpKu|h-ziQ|F?xof%L4{U0D8fWvSn+W#h|%kw$<NDsa_XMK$Hz8q zGz6y<@M^OIP3s;{FaU-9q_8wQ8=IO32N)r;paQjF-Qx)nMl;X6c(LNw#>~^xbYt!@ zFfbH?#t}lCuNQhSCq1(+do$s6%#B^8uYdg50ge`MVH(60dt5OWUJ{=;apK647Kk)x z30n|*>~Y1jJ^lTsQ`et~5t;j1o`E4D_uxrJh1d(FG7bX9_cx_>8-2bAt1%fGGC-2L z7fNLg96#91K6U2$`2BHb=E#Av_QmGO%nqLxzP50XK6dO_TYLLcHc2U|TU)cm%{dqt z9Hu;Y!Z0D_g%#fg)ud<AW;p?A`_j+L?JNf;YXLP2O9mCOU46`7PVKAxeI-`;f7eV% z_<?$?Dgq!G-<>gH(&1_Q5)ZR&ECGj33xgjYLub>v#|(`Ne%12u@~)hwmYkdn&g&c^ zb7UBVm|~AJGNl(5UfjF(1v3)^g8&=IBF0^P%q{L}lO<(kL(}%9o)*h9WMF6jrJ{rl zAP<;y%*?;PFZP{jVoFL%P0bx};kKGVoxQ=ab=_lzi^is=OW#?iJ}VJoWMGI;wXkI1 zkt>m9kBB~Y{P@#r!D;(yf0w;;WMF96ckm=*!hr>^EgXC-N?u$5CCIdx{dIp|yvR_S zTnH+#9j=!Yd|K`obL0C|^|clsT#{`}D-Z4|IcYL?LhF0`nnSZc#caEf70a3aP&NJG z<MikMA6{I(clC3Vy=RwObL;ER*N);ot@ZBJrqsw~Px)4~+RCeQ%iG((_w%y(xAwAb zxc!Hg8teD3K9&AqPq}1Q#jCw4qwdSJ{x%nX_xC$3vlHL5U9R|Iqq)(pihW+h(~FzM zzO9kFb}@TnYoELSzr4-Avik1nR)70@;n->yh9f8KzpmVy^|Rh$$EwBZ+};(zld8Ui zl<fL;=J<cpMO^+rbuP!es@XIrIrZa@{qv?3l!yMC+OzoV!%uS}xwWTT{@9ZKRkf5M zdhI*Q&0^P1T76iOUb^t^$w^<HUY$OtmET5F`r|r1`HN|#uPt|eDxCiA|1r*=T=%X% z&DauSduVa_=lHr`Q`i3z+-Vs9W0CmZKi1pt*PVBav~6?ue;4-tm7!(TKG9H%@?W1` z8QN4C-7NY#L)JF?A+!If{drw~E~b@w`hU4tY}6OFy1e+yt*1uWwO`iQSRGlME<fSg z>f>)-=vMa4+k9|d-#i_i=npv)7N^Va6^qWO{gSfZ>hh(NskJvZZ?Ac<`TgFv^X&?L zPoI6P@v!=wrMW4ezWx8pn|>(m)1N*0qWM3>>}(3(o&WbvF#V9)?CUkFD;B>z^l80u zuJY-M@Q<#K4{hQ<*K$@|?w9y|t$P#lpX;P6$1nfb@FVP_+Xi=k-8Vir3cl2=u1LPn zKQI5`4q4lSyZ7k-vaZ^{{daxr&X;F{Ueq7tjyL%w|Nq48(weF6{$kS#)N&@3f7x^K z->u1iC#LV4I`hWPhRISIn<7sxt$TX@UC`v!Hj$ee@<sDa^zM9N*wz&~Plq#oVXBI& z*(0ADC)_Khe|LR+sF(f7_AYZJyQ=*Ed!zTg?+QQZ`|DBt=l?nXcE<l*t#9)}CtbLG z@$=o4$)#Uv9!6WVxv&3QY!v41udDOl>ay9rr_zTbGbBA9zOcM(wyCFFG~R++S6MSq z&i4KxnY~wKY-di<wGcLwvAwT#FQfF!G?y#8HG)mci&i_N%}P%%e)ME!&OuLBh7Ors zeeNfJJYlVT^Ez~M)^j=UNt0Q+rf!Yd_2p^4O!-_Hp<|F5Z-LZiP($opJg5wC_;n%M z`|8tE#p)|1b?4N)oFsC>&;Righ7Hp$l-eXsnf!c9R%B-70k6EjAv&}FE_Xh@{o#|& zwD<S+zB)IxzS3Edfnmusr=?NXminZMHr~3hX<p3wS(C-}9z9{$p!VU~M^i`3pFV#2 zQ?lK1Px36B7h^PCzxM5oZT*j)a4wJ0dw+AY`^=whywcy^-hK|MBRtqAKYwoj|7v}t zPGqR;s`y>TiyPJa_H9wo*2#2x`(h`kmQZTj-nU-y)XDQ_vTrU@+}ZGimC-DI`kEDL zGrQw<|K7ORqS9-^@AB*GVx66xS8Y9g<Hih7fvxaT#-irY-2XrQR<BwdwADM*uS(f> z&K+GdSxZp4TXLba=4_y!o#ooIqF*M(P2Qt$;M?nEl`FIKJhzoRUu;piOThU4&f?{} zw!Um<Vqnm8ob#tG`n}Eeh<z(Uzpe_s{P0Z1f|Zl?JuQ8_lHJcedcq(eSR&iceClMs z|Maw?s+CH9b(#mBy-xb>ma7@R?%nZ|!Jf#)XE6hVhuNbi?{|DXx3V&KVMfTCXRp`J zlHXSHDQW31ldn%01nf#=`}t4%txGMM>a;Y9cZ>JV$4{jE=4CBgwrpGeeZB9y4UCM8 zplvY^u~R42mv8;K=c?+3cfv2ud}^G`d|;O2^^ZFi&iQkrM04_GRq+5nxsd5a+vol1 zYqqGoHFL%c0mbsObNaLx7$(?EnLK~SMJqG=BPSUXco)2`uqmAT$7x;Ankzc$+ohu{ zH;1$P@!7%K5x>8^wP9yqQ1H}Hx1Xlz`+RzL=w7RxEB^Sz&DWRm(_(ONxKL_yZqA&` zYpOogEDbR{T<|GoXI0%s9m~m+xmLQ%F-337naF<V*VotX?(W7jdqA<3Fd@*-ZlY$@ zY<a8CuQFdgnU#0$Nx>)62cV*XGhNB=NZIj(h6S%H{#cr>mYsiX*;}_TMT?y?^{>y1 z-cqMq7Q~ptCu3n?W3%SWoOwD73=<e))ZgFuv!QeH=_1q1S9)&M+&dw*+Ak~n$zf1w zq<ZemkKzDNo(qreeOq2%{+Ipx%d3vMCrfw!-~TDS+|xoh_CtTX{i?qGU9;`~PTehE zyKBMAb8jBJC_Nr_e!=|04^G!VIwofAt4WHQeOg-e@S1B!7O(X=ICHy|inx&abQ{ki zHNiUdt)|=mzt69b&#T}0|Knld=W{A21ROhd%q;JY27lMWg$rYMmwjBoz|e5e)$->> z?!L*<e@|8y6-DmInQ^me<Av7A-j*+Q<$tU>^8Vk|8I!m4sIX-e%Ky95{3-I>kyjNz zR!&x`78HM9^ZS05d{t<C>7S(^e*Ii;v-A18^{02e+K~Qv)@B!nFT0Xgs~<4t%jSqZ z&fb0b^R1IRKgGmd{}T1UPjBbMR}!I@tgUxe%{n>R_tE)(?<Q{l`||$DB{pJnZcd2# z_V)Jn#KUY?7o?q^XZwi<T=nwsO@977fB$#StEwCH)#G=CtenNY^wrUz?S6VsRepY# z-(Ppdb8BGH3!fvLnh#IzleMThG&7Dn>aFwoSF8K>muuKvzclw{!;8}63@p3)_+=hF zS^muHX42N2D_P#tnM#Uo_T1$-J?CuahuNTrYE<qwN`G`|X-?elvv<F*`MFqH$vG#+ z*7iyK#u9Z=28M)!89M^D#HT0oUcNkgGWVvOqXzx+_rI9DcbNvWO;Ode-1=YT`~OVT zuZZ^b-gW-bzw_JuR(tVt=I`{n_GzhxT-~cBOIGiHU-u=G^XvAcnomu;P0jBtJLhZf z{p{2e_Pqa_-rR1t|Gr?>>ulMzb|H`C_t$Ol&E5Rw45%(jKlJRw5zENaySskHZBqZV zefR&j-w%eyZ#Ct-uP<vSH8&<~ipb4<#(RBczgM+hR(9$4!hMGyy_?~^db8#Uw$QE^ ziFa&Qb*A^7-r??Z@vK?vw{TV$w%FtBf~N0wWmIlU@X!m`{JA$_?w&QXzuVNUnO%7O zX`{0BW1kx*l*5Cb^p!2kePa09?#`9sGwnJG=ef2v)HteNbxYfM-mr2{h5VBAG%?k} zPk;6p@9nYac=C8o=eGHJ{jxU`E8|WYZJMUDU|P<dWjfcsWU@Uiiab-3k>N2<McORq z#{T;K;EX6>F-=o$zTVl0uTQQ?<a4FZYoF$~F8u7xn5Wt2=e*W1UMK7|)A`?ru=A&u zTz?e8_<Ha5zms1)0wvO4w`ZoG-}|rm_nvhc^17Pu#GdfKzxJd#g?s<b-*Pt_<Nuuy zzmk4(TIlw&pSxeCd*1X2x)Ku^{%=}=eaN+`M?i^hWyw$HL*Z@3JAYn|pV(Vbeetx` zBqdk9^jp^wJOf|7dsqLvc0$Qdt5+*d&0GC!meI;*W|v+(3EK2!?WK>^C)?|O6!Wh- z#<!`#YF^QiJ?Z!F*0<jJZ<ZdccDug2@3cu>((&AF`?VCLURc@fIC1%9<8r_5$@(Iz z*G*<`&GE7PdGh6-;K_53Uz;{NJTEc*P}=#s@zX`V-k#&s6aKD*bLZKoKNX6f#=rj@ zU=wMptrD9XV74gjq;Y_)>XXie*QUxG|0^3HCzYjZx-y{iorUIG``CXIM7DcRY^kdG zxlOZ6ud`>tO}5ImH@CKW&;0q}!-pF)_Ai!UU~sSzRGdHO;<HaxCo`_AZs?t?uPf5q z9ko68`qB@I|J0VLq)KfUa=5fqXVE_~7vH_7)`pc>hjgDhwIo_jXiBu!LeZ4qch^E9 z-Pc6;a;-{u;#2ZH@?O(ir!KFcs^Y)CUCWI$XXpMp+;YqI`hnEMnNub-F9>4MO!Ms0 zT2%QxK4UBYrk*9<l7VmAa>C3sG<!p}xxQX?`M0!2Q!zfqukp?1Xgv|DI{mK;KRLdO z%G!MI^26Kzzq#+2oqw@V^1gam%)ZB=jET<IKe804MF)O;GKst8(UZ2!^04>Y-tMZ} z<hdgL&Xde%b~~Q%?>zW)<^#L#6vN18hfmj@Q;ijy@OFp4edL4ucfXhYS$J)#!1}Pw zcig*l76%>Kl6omNd_w76R;#*QRZ5;GoITC-G(WBX_44v>m5}?V{|02V&iMJ_#fqvu zIrsL=+-JbRAW*NC?xmi-HfidV`dcNOId{wMzVgp2xj#Q<=bS9lw_X$fye-v|Kb0A) zIW?)*$7`a8FISM<r)zUgFT1mL<)Z%U5>x-~;{N@iHY`|v+N7B(s~*kj{#BN@@ND;# zbt&KPNb!FaT=gkNmRED*Nv2P_SD5bo6~AS%lVh{i0nL9OU%SuNTNzOOg4grox_f88 zXZ;B%wOX>{rH}cW{rq3Q-ktmAS#(LvvG1L-)8Btx)sV38b%l||T;2Jzu8MV4d3=5H zYN=e*_2fO3&T_NYP2hgD@o~1{I+rM2HGk%xw}1N-{A{|*bI;t{R`;$}_SFj~e}4!O zTKDhWkC&%TK8>!JAGK+Z$}ZkhF&o1tUzq5lwmJDYU*$Ot&{#vsiwU6ItdQn2Z~p!2 z`;)^$-7gC4%)6{=kf1IeqS_#m`XoP8Ch#R!q>q<V(7H)Smxw5FSE!ziZd~AHoY&f{ zFuQ2`vS+(K=^vH4Ig4ZVtdK1~*DSMJ!{R?}iqll-Uh9`fvmXTYOm3YjcIvrTmsa)3 zw702$+isS~v)oT=(z%=_f8}HN*C(IWi@aa=|AAfpRB!Y9t3NukdQSAU6h1pGv$#cC zJnxT~?DUVi7Ycvot>fZg-qokhS@>z?PJy|5a%R|C?zB0p62kfwRIXglzdNh={bApE zjgwZ$onE!J`m%iJ)ybEm+1CX~htz8)P79d)$~`^&u{9{UoMd15G&V)DQcp8K{HDw0 zc-{rP!NI||x95ka*&!NC9lSwBJANATmt9shII-<@R?t6ziIa`mMJ!bAY6oU{UR3$% z+&Ram3LG9&uI6&<{+QxpYBWXU<}9sUE9IF)-rBET$-i1kG&1PfuS3yXUlwHrPHFU( z^nSbZkD{vaPv^JJm#gX=&2I1DZ^}1xoR+z3iBoM?^`B7N{_Q&*p+S-P_{rP;g2!yq z`(2Nx)^L}^#AVcnIy?Xk#I4x&dQzoD?)B!$MK`BaU3^yKIA_oE!s|~hl_%%%ZeB3Y zY0@LR%ONY$H$C`!^NRcG$Vo41>$E<GSzes~_pb6Mj}rNpvi7lNdfX?HvM#xbO(^-A zF-d)S`RohAiykRGId$f#qf5FZ14D=OWaFi~lBQ06v;3|^ez5V+@AZ%N^`)|g>V2G+ z6Vloi<QTqaO8)NV*Brf0Ps6-U$ZuM-d)=Ygi(Y9j@p&xPyvO>&$IU5~_uaX(bhlev z<=r$tXpRtb_|?a&%5K>zC_T@cyY|6vH{b7$A9U4zl-+ZG{4u;rC*Iw+?DJkJ`;dLJ z-t5=dZXCPc=eY8n9S4trOB5#A>G}1c4jV3%+D!DBH^2UT?)P~or)_q<`cbn&U0k|8 zqvqAM^Y(9+Y;${8zH{;1&Zj(wvNycae3dKq<Z$*CyIJQZskf<|Qob_t8_%n-4c6K_ z&)#b7o4;<`wHHq|{nvUNP+zf~vsM8-fRXy__V)bqDOUXQ91IKsyy|IQ!Np~_zt+7z zSzRqYtK2Yrt?J#W8cScq8HczktzW`<>iJcj`EFHHeMH;9dHz~L`5&F9Mf>!wt*TIw zSN#26rL<9Gc}j4RKuxY-?bl;X<^Nlk{Z{xPCVXYmJ>SYqn}0#8ripA{wS4w_)#6l9 zORsZZihTRbkM2&E?cY$I==ym3iyb}rjeV!L@7Gdrcwsd!<jVQ(RgZ%!{OZm>7G7N` zKI?Z(kp1CG`Cz*{%QqV5ru)D8?qz!V_vV!gZtbd;4{kcK*~aOrdo}N#$IG`D6*;B~ zyn1=}*sF!rPaKz=srmcs>*B?WLDMBi7z;n;wY|)|KL5{+%GGrX_|?Tj7Uyw>FLDuC z8ln71%Sv5UPLuQG{Y?$)zbw{LRY^(QZshVX)ad7q`&+CHs-3+ov&^mPru~`%s?L{K zs6MQlaQkc28^2T0K^&9w)w@^j^ex=KGWxn=s@=~L&x!SWi(cHVUwGB-hnR56_EgXN zjYXMNf9_}RpX&bgjJQ>u{!f?EBPp(tZlXS_7puAUSYP|dQ7s;3QrF#g`iIzy9W}pK zGch%;dwkN(vNGfE$+h1nXS=<9=idMA`IA@TZk1&__ZzH=cYP|Ta-Q*K<<Ib-J*MYh zC2E{!tlZ>z!tCxdd#@hXolh;*_&v*mv(|N2ojCn`m-enL|4S-AortNtvC32bm4&xS zo^aUV8#iuz_^`p~bL{T2i?i7n7_N!!p0{U;?w2_KeKAu5XIoqkwcW`vFRS^vkG}F! zdC%|H6g@OuPU)=@QM#rcq{aPX79ZE9u6)<l?Q0%yn>#IcRe<Q5b(>57=xEw_c10b? zK9}VhDmG=({6D&^M(J_JOENT0pI8=hx7(>~*+=b)@9`H)<fX(X$9{UdXZo_^@nX|l zG&8I&&)qkDiT8=Xpw^I|(ccb+-+ps@BfRoulAZp(BJ@Dkg4Y#N6L!1h&78b>)~ipt zT(S!$pFWmVX8SX?zx3&oqH^<ldnRq}kUL#xb@`idK<D-&x8KM)-&?-X=J=DD3jDS+ zwY5(fyU2x|+w-gR>Eo13Gaow2ecIHM6FKjO-=uc4`Fj1SKkpnn7QnT2+ILM}M@8^p zVr2v`FK_3}>8De{0}3r3o)1<(PT%!X=*FFsYgh5?E&Fn&X^O<7$m1Gv8mY4BNs>!D z>?XJ51^B)5;n9f^Rdl@m@ymiae}0r?nuTkItqLv7NcUstm>hm~>7u-QH)CxpH~qZ3 zUuyTfi+2yD+}~Gw>Wu#GH=As$za>0lU=T25=bOLd;Wg{EhWEVoTJMaW`q8InZVd1G zzx}7zOA7P(&zbz`Ec>*0Ha^>lJnGL^fhv~eT*ptQdtIJ3`TDA@s>VC6y?*rF?W|5n z)^Gl0cTZj|{I_BGV(XU1iXAt0R5hL4pY#$m9NO?fP`$pr=#$_2&6%&Cq;K9>`sw87 z&--s)DE@I?YF4!Kbd|#=cWO1c^2}NHIMaFOqm3^wmBi_{K6>J9xpvq8i^`hiMOVE~ z+@8*U$a(7*NhzsG%Wr~)J>K7c4;uF15PteZ{rRa!Pf{0Oi>@zv`sAqB*OwC4Cu<)$ zxP)b;(z)M~^?h^ZO)OAjlUdhw6*PK!@0a)Wk6RSWdy77C``!NfV6IL4x_c9URTWj< zJGHP(O+o01<+E=GCFSJgq@ydjZ5bFGBsA3L&$*cPxyo~WXOjBmlZ*-xOKxZh`Cb2b zCFuQ=NtGUb3X&cMQGJsS&zgKP#m(LQs&d}vXJ@}0XJlyj5a5@`dwH^X*RGq(R)Gfj z+xJ#~zf@}T^udz}Y)8&)&%dvC-YW6*G~ISSS@3KjOMB6$<e8UB);Ui<FwIYI_1yRi za@D`q{FaJf@X$(n@M`J45?OysR^R>qJ2eYG`Rof?H6ziYa$SsVQQgPRlRcBUHn{ot z`mX$L&84iY{P^)>a1<y6fW`#M-U!{u>)C#Dj$ORToDc>Nr4m_o`Q^{HJia_nzJ$4~ z$T)tT?e>h&L)I%9vb$F7sAA(<^rGYjBSXW273H7Gj;>Pk)9b$Kvw2DQ^G{XVB1(f8 z6(TQ`%FHrKwf>por@!L+<l7dX!`gGa=fr$cIXTni$J~$xiGmjw7V1WC(=fijueMsv z*_w}mAwu`m$^N*4IeUCRA719C$F@J@+S#0o5gHGlFmSf4dwikm^5>`N>05U;C0?IA zds05jizkz$Po|~6x#&JOq~XSceGEm2LU>KvVd3X?KVGh1RrSd!(kpbY)z3>yy{^V+ zNQ#@zkx>Y|P%3jv*{?3k@3h#LO^Mg0>9M|evT5e5%&fMnhF+I_)kPK3dU|_Twl4us z=f1ee%)n5q?3BlQIeDu<j=7J&wtD<3iDxTc-uZ1`7;m=T(wHG(!ot@UB`Kf&{Mntq z`}>zY7CRMpI-EUc-c<T&Q=Xkk-7j#x%5-E>?eA}(33s^}&d$!e%irrwKMjtGb(YgK zW#?Z@`{Z{1?@89ku=TT^Z(izu|NGgdW!5Vh3}##?mD!~-S+^$V%?68~P8(lYRR)|m zHf6HCp=Isy!}p7V7?XN#pLPFtcXK*_8Xp6LZDG!?ibHbCmZ!|f-Nmx4@YB*(rQGX` zplM-e|2ZeaLTq<FVOnUhGx3}_&#iTb7bwW-nXQ|*2-HvAo<ASdvRxpop5~>Ve){Gj z#i#RES(L5!d-p{>y~n(vv31?!3+&4`KV4~=yKqH&i2pjttv~lzSSIf|sIU<{iN9{) zLdDc)&}okbv6RoZm>;LFUDdZpvFL8v47oWn3XK;^Wqz@#vuCt!m%s4gg8|6NxdHE; zCMR7@TIoF9;nq549*L(#JA0Eam&$~7X6@b=u*M47T>HAn_tv_@4bUu=Ty}bz?iWrb zhK4Yob5nLnE^9Zu$H3MTySuD2$6EO7g;JR?PqpYDKW;oUj$HmYSi(=w?3_gY1cqhH zz@vQUqf?)OazhW>w!FKiR-a>JxOB2}=A|n!Cx2VbUbdz9)8ps*`<^n-pQ<!#G8aR3 zugLF^r)L&Ax6e_L-qq)<(BmIB;dtE*a1-LTUDfo-Tm~n0$hNZlTznBUF`P2ZW4AFc z14E|MoIh7`p6fNP{XJRw*~a2-3rmL@jp?Vo_OSkRR=rdz!{lOFd6$1zqt#BS^1ttn z_dR+tLB-|h_Po2R<j&pRp8vf}s!0CU?(+9#lNcBjOmBRBa_x1_E%DW}EOzQ-&$=d& zFAQ3U*YIOQ_I16`ZNYcye!ne|ZBGdFt1H@OGynQ&H(wDe3)Sgoo(7#=r@sGn;2asD z69=2wx98kkH1E81*_#t7Myn>pD4x%X|E<Qr;9;}Mey8obs@;iIQC5{V4f^LTohPH9 zw`1+K*m>XgJU_X=M7EtF(625DJUACS$L2uRC+|s{L%_Am&liGoWG0<zWM&V!yTfMV z{`bH4ov(|s&bhH+VT_*jX+{QzOO^#cj__{3chh(J0X4t8S<6<Ps(8lp^$9~^;^${) z{WhLE{PlYL`!j4DOi!O2U+!&exp&FztG9w0!t(TDjk3}f2Ho|ywN#nAapT76`@Sqa zH~H4#Z*OnURb^mMc)6l{;nzt2yjk9Tljom(^n{@>;rqM0evRwqeSLl1c#b|x2c!&* z(+|y3wD=k1xB8wV$f%;7Ywk5&Jh89#_ncM+28D|n>h_k)btAq$F+F{9u4P@6RprK@ z+F4aa4H5>1h7Ys1zFT^=`Xa-x1BIVnUTTeTEowBF1F9?vCsY-ASX6&|Q#kJ;FAp!T z;U9Je2dMx*JIml%XJ5}sG<7|Gl96rdvbERt8srJExbB^NJ!{$3*(<-U-?g`Kva?r4 zu;;o7%dKQjGcpME7kv`GJj<doaQiB&f})1H3DN1fpq+Nl)?O2Jc6N^5mLn-E`*p2o zg2So<Cly00=9e-ai~nDG+N)@K?C!Fk*P<pffGe50nyA^^x<hkk$!{zE6uh~0@AtaR z3tpb%X}I!Xx%@xj<#$+KU)%fQsJ>Oz7me2KCKFDIeXDu7!J<-4e%j>cr>?H|kNI)P z`TwgWOfIJ{c5+rOv-CHQ*#6Ex|EI9rdj^KY1#@D$LN8bDtp!y|ajUMR6;1t_bk&p9 zgEvXxcHQ4&+xNXc?!LdmR`KJjhv7DVPAE6dlsqzf^5$C`UnZ%AYlfZ?m~-dM^z7&Q z(_BH-0>?z}pA+5r_Wded|H1ZYko2U>xxcqcKfO2Q_8fN`28RtA>hn*Cgno8DeKJ}E zocPl$cgD>=`#N%tOi<e$)gY^hMqGaH+AMyC%hxQ)irW7+FwNU0xcFA*%S%0>{(0p! zn+l(;<=a`erhMVl)#7?#T~>a4fy&o6#+>H2{nKG{xyFCzm9{4(=KpT>eyW(>B;Q}o z(2(%avU2vSzGZ%T{b`$XW_)H%W>jyVqPV^DjzN&y!IO7?JbV~_=l|7q?W`RhUAdm= zS#h)HfJd8Fgg%{eduEeye(8y)%I4vL>!YTAu&{LLi#fh^sds$s3&F}|Kj#&#<URQ^ z@5j~htTxRkJ##Dm3Wf%T!nrYCcCDMHtg0$0(rgV~^~~vFgwDe!6ZD?A8D>4Rt`}90 z=hWPP@AuU9B^T1RRIXQ2X*It2>13pCw85!1O(tb^n-!b&W*15)K71lzTg2K`Y4<_F zZ=cYl%YQ#@D;FybUhidjao2rD1_cL~6ITsv-|lAFR`f}A@2--(eLr6QmUzq?)N)5T zNMmC6|F-yAb-#DV_<8p~lIOQkX*DY>dhO`6Qg>&{rq=#mSv%YHsoic%wfyqtzFpwA zGv`=V%hK8RZRYKK{4n2gB}1TMc*53gU#7ClA3J$>!kl;ZIlC3(*L6<5TqDb%P@twa zrO$u*vf`?h*Z)0fdi&(r6`y~9=kL&;eSJ<y!;)m{!;@BU_`TyT{Pe%}e>3au3vH9t zXP^B1`Tf4P_dqpI#MUZpma1*3$)`@rOU>W)^)tUU$i{yC#c6UswEXr7ojO?@b@dl7 zpE^4Ohm_za;mfyT?rBJ-&DLwool}#!FeBzl#%?}MC(E5P)WOzl)VGgV@!-kI2R_?s zs_qpPon&<?EUMlh<ZC`Rq+!K|xiv5A=G+nPn>;<cY`4U%b<7MbXF6wIIvJTgL(Vtf z+{fQrefzJ;(^rYV^ykZDQqPz2v$gb_$LE)R8r<)l@ap8zlb_qt9y}2+wWv%6Ep1w; z<X3k}D=hT1+uE}Rwr}U&0p;WePkfox{Y6im6z{6?@LMOjb?2O~*&8Qw35Y^<JzRJ! zc6-}P%{3vVCc4pE%Zd(5mCxPwdV*HLr)7<kmvh}d>3#2vvPMess(E+v4!YV}y72nl zlK`!PTH$kUO33sB-;S;-OWt$#nO1!DvpI1~&6qDS`Q0-q`1B><!WZ^=R<&x;=ftk= zzR+ZIca!eUh9k%P{hrUOGJCv)$%PeRP{yiNi~kzfzMb>uNU`|+PmSl(HnFOUD!ha^ zpa1b>@h2Pe|1O9YQeWTt@X4ZI-)-zRzFk}nN)(Ng%|ZL}1hm5HKixbR%M@+3^GWpa z^N*iQ(1UoPT~xjNcr5?Hlkbn6Ow>JaQX14g<`9K+tDioZ{^VuNn>$K=d@GgG{Pw+E zrG1@q`u!5$!)rX4)&2QTo%Fx;UcLO)$+?z{3*N1t6!*LRctKGF^R-(icULdDUvzYr zwt3!n)iyC`h-BOiDK#l9iVO=)m9gF4Fxh!k$IQvzF~zw&TV%k-ss5jF_O;UaB5Rh4 zZBJiK)LyY7{C&+A4L`n%!p&8m%KE>6cBbskoBZ_2r}ygSar@qNO>9eL0w0HA!zW`` zczA7jnX!+*u)4W#aA>NGrMIo+lI|atJCEGTw)C4PH)XQ?e7&>JdKcw|WqUJ5?aXya zTNrcqKd2U6q|WB2ck$gsyP~<Kr_)~C^8fX`O%UYliZy$<*Xpas3+Y}g`Fuk1)k($J zBbQF9UW+(g_zBeSi&$nd_p<lYs0)5|o;@1NL*H9;Og=0nz^^_%<EIDcY@kUkMW5`B zR|NaTtqGZb?4)Aqk*g<FuLXg$Kd|^&^3rLY(oP2nzj^xIlP{OaUTe5vvD0O;yH)OW zMh2m_qEC}I->Nxyp=7h#(~R^!`8hHPty@cr{CPdC7hNx!V`F>8dS|SE-u&Y9Z?6uV zOw8@Paq@S~660gi3=Tm7etD&wCEzMe@4(5~Y<~0PYW(7i*9y876nU^UKYVf#oHXQ4 z`^C*ETWu9JW#ui)pBtYSz5o5A_U4{vXBa%JvR^;RZQk};fOYco=jC_G))#$p+9@?@ z^8NouR>sb+zv0Q+(bX|`PwtwJ8j5+KT=sAwxQ_bCclgVelA_35weXpsNmK`}j@6Ub z7rx|G_ZL-9H$7=%w9{*4Qrp8PJBz;FN!l5)5|mU0rPcepCxCW^GCW*3r$#9_=B3b$ z&68h0%ee>2t4A)KyuR;C+vMe4D=pvt*kU%>-06kCo?D98sjbfoiXyllJ$zy)R0LWt zrC?LzcW>FM#gOSz9qDH=aq${qb3+<L1nkxOUBRvh{(Orw+dyb<%8V?7NeOfJthjEp zsZdtEeMM*E<m28aR6(n@K76pM{H@n`c5aMUV(Q{;0VZPJ7M4poW?24Qw)#<E)!~!D zM_*RHeX?enu2gDak>&k^mOFRt_u6GS-MpZvW8T)XPdjWb?FH@LZRz6Jc~#Zm{zC5r zZT0v|+1|$Dry=FR6P8RzOXoSSP9_UlR90zZ{9^W>E2t~3UVi#Tqt(u<9NC|o-mL_6 zC<R2b-##e>Z6i?#ftBT_llPRqf70~yN$BSz#p0FXQcJkz?8$ua<fY?Y?%XWDXq`~) zwka2zZEkNe+}V(_`MZtX!QB@WstP_GJ8+Vb!RcwlvXZ2z%~2ey^cv01+3>%e6LTs> z-1OEu=PpQU(K?rMdinFMtw|AnaiHGe1)j^EtQ}l)_JDSVHUwB223uKb`>o5a0+pz` zb7Q=cxm}sn+d~>BoAb`G37vCp8fZqeNw975Zsv|GQ0?CgD~&*trCV|~Mww-SI!tAs zR_zQh(la_Hy@V6&gO!iI>?z9%i`IChXt^`(%Cn+t>yP?rIfOiT0@|&|(9$kdephPQ z@!+c$x8z*CcCy>TatSv?<Dqrx-&5oc&ds|yZI$}`^PmjH0Cn((6VJA?A6vVy*t(1} z=jD@0`4{KQTw(*4#vu!TO}_njoj&WkCt>wPg`b#muP5@t%EGB9C4EaduY_(q<@xP$ zUeET&&n3%cFR_9(epzrV*4{Qg?7cew;gd&?NtVlAV}V*1u<_UA@{6h)Vr?z`_%fN* z^Q9~*t0Kxi8N5DO`uW}Q{zp#)Y@xNxLM1;t)9d>u$4^@R*>H|bkXyW8-Px_->!P1^ z3I4yM!U8V2=5I0TH#io%9aPL7J(=kH;_k`G|0_TRj8kfnTkzkLbGN<LowwO{PRz8e zv&5yIT`cCduw2r0Z|)tvjj=lmchB1Mv}@{qVG)bUDp)Id68DL>0uOFZTkUQZu_okw zm56$~=>m6k|D%s(LG^h5Vd3X_|IRe0Z<@QC#jLz2bZX;d=UXpsp0wZj@l)yRb-R`- z+D0}`Uf!One*MVF?y9X?JKK%b8J@f{%u3q_D^{1AtNR~^nm4t4;n#;xR%tn3KC7Hw zP~;(QYyDH)Ja%i|-CeKEOqWC(7R}B2sBy)#D#mkv-sNwz+wNRlTXKHcp2@jpr9XYI zSD3$;yY<W|t+m@O+ZBMz-XA5IR^ggqS&yDDUYj!8d-{=++@hcRnk_8XFxp<5y!_F} zzRAoCE$!g)w|KU=U9p&Yd&$M!ljHNJ?wU2Vam}NN+fQu0^WvhOnI*Ti>k7YCv;19O zw=e&@<W|#^+iN^`hq?ca-F`zie2vPs8-BkJoV?sz^eOq#lgiklMu9msn&ImnJ=vi4 z<;9bg6?;HupFLbS=g*ThX7L6lch`7Y-kSM%`P|9&zP6T2dhF)h;o7|=Wphl)=AgE9 zf0vXqnr4RXu}Iai{=>TRm{as=-^yv3o4lMSpWb#mQ{JMos$lM)rf6un9^f}``<yxd zo@`+I^6E+0jsD9l_V)^lpgoRVCfTB^SA|~WfmRN7b7NX#LyAu2ZjVWv{&3F?)g^6@ zLY_NCul6mCSh~>RTAB4*P|a<pzJBH;<p)nD2>dE65<OW9asS3QPmcD*GTlb6238jp zac=jyw&li?*aXX^yPcv>UkdGS-InK_x$nTq%ZH!*{3*NrZueworI+_lstWxAr^-Xl zmOEbwMZ7wHGIi_BJ>b!<1`&Z7lg&lWO*@=*=SK9xwNIC=d6763;^S2omdib#O*|Ry zC2Gv0etzoe=VGUo{(v$)%i|{}t03-!R|~5rXYaC{eE6hd?3XuBwqM!1@tT&gWi8+9 z_?+yiSLf{On3sCxzV=eRY8%Dn>kb>Qe!6VVQ7P`+-t|}CZkhY7aq{x6;LW!_`ea&d z|I?gzz%TDq>z6x=rW%84p^LL8FMkY8H|I~@hO}4KrOlcZIQzWxO>lRM(boFssRMh= z<}u9)_9*(WO)JK8f6U(J$HHF)UD@lt{OYnO(OXaQ-)rSPT=TT-7Q5d(t!2+nt1sKS zb5Ed=kEw)bfuEjRisjGN?x&ObCOcpG^6be=MEZHbdio@Hs%Gfd7f&`7+%(t>?g5!x zY@fW|sAlQ93O2uaT7KuV)t{d#u8h5$eb8!Wj_bDc(w<W<Ei7I9*Zb`|CDC!*8nk{~ z?&hAd|C7Pv*oRI|*E@N+QZ4-FE#v23v{cnSxGgF#A2@m0+41uJPfxC_wA77WGp%=) z)?)T&Pp<t<H9Zt`=sijkG)6=2v<Rr&eDtJAC))7L<LCOH^h`WNA;vUUiQjrzsT*ye zBEI5gx^;xQ{_AJ9{qo6oN;~9WrJ?0K&71GluXDfp`vg+i)NBmdyW(P*Y*5Qvo{3gJ z9a#M4fhwFwPq>e+di}&vQF=1B$DBV;O5UwZHwGmGmp4zC1wjq66?10j*;=nYE6THb z-k#Ly2g>~R1(@hflPH%BVgVP*A%#}a^JZzMc58nHnX~!TN#4tOyYsA8G6ce#!|G{X zVbc#Z={=oq7RwZEU3oP|qjPewKc6P3GhtD=%EEU2T*#!h-@3S0j`c-wpM0>eDSY?r zyv+^Y=?Av?<z1cp_{jt%NL!j~_q;okD_P2SrADusC!^kO%BY?XuCi^^&Yyq3_x;Jd zT`b#5icW5S;SZ}3Rt5Y$xpv#@t4j~ez4OXn&o53uefe7}<X%L^s(CTtN43;%`g^NS zKV<%Ro%1b7^(;5-c&vW+<lD0I;k^f>z8T!7VfCN%cCl<*t$zHZVlK4Dp#9#7d+ofK zIe+FISFaG4a^Z*dHP&1@sekhFPYFLhO=yi3;8$1V2d;Uh|2{4C7&KdjTyq&&F7`b; zRjey?`P-`Q=Q+aa(^J>3;yG+nmB$Eg3D|0=&!3}t_F3sk)+c2gA97A#RhHHX%__HT zn|xTR0oo*x%j(%~4C<lGw%!?<b7{4O<q}?SmHsmE=1J4SPmAK#dcAvihLd4u)v9Nc zVm!)&{Q0sOq3*5#Esku9e*fn3$<WZYWwYJSJ$N!fZ;xNySN*>atnI44-a58=-M@Xl z`*$3iE>XMZPkVgV<mD`&5wGscJH0jr39IvOSav67SIU($PDk(53#hl79w;pW4;frM z?!WhOsPpvt-~Rh*5BvXr*Z(WcRdUkhhff$76czpc^+msb^GtNJ?%X{QD<Sm@s0pn0 z|M9l|{9Aiomga9rs?dFOb^XmBpxt)YZ~nRc{!gF$zl-u8bp;|%2;SK8bNRfQv`qoW zPEPJG`jmWm>B~KOI~_Ru_D#_a|88H!qTc>u<J>zoMUS3b&HuA<e$4LUyN~qq#(&Md z|1I|w=lY6=-0>RyzoyszPo2L1(bG={rnA<pZV}Y#|K0t+Fxv0%Nk)bycgvqAC3Ef8 zPw$QLJ$3P%jQ!g=e==X4R7~xtJ+XJu^=Y4;-pYxy-yUFT8*gVSo+)Ej^h@@3o%7U7 z_rC6a|8MK;y7x!*<MiwE|JC2GIsU)y!1e+bMfV3gkDjVIs1cH-6k<`isc`O}rci&m zuF20&U$tJL-oDjgUFyyy-n(Y%hCSU_rWXCt_T8e+&d=TU-yYj5`hVU2|5I=NuC&wT zb<fLhp8u`3=iOKPuh-^R-<GfY;4J_9%>9#}<HNq>W`!EAKKc0XAE#8ae2;1AymlfF z?(#7(oCb}C&bg!U^3fAr`OOxV4zgvgr-Cl(ZHe8Hk@@o`>*^O`zBNzI|NmWHcYT7$ z(IW@se;(Vv>WI49xj*0fzVA+}yKY~5HP-Hp#q70n;@9{*|I!+?HD!CsvJ=yCUd@d$ z;y)?4=6>Rwo2!}C+qWJqDyrtVeKaUkF8jRht4|%DZNDgWysm%u_LD*V`4{YWMJjKd zK3so#fBkCJM`ri`+TQ<tO8&>e|IhE&wHxp4NfDUD{pXkOe(PVyw|m4DJh*uHom&;} z$y+MTr(>=>?+)F0^XSQ^d`}tq83Ytgo$Nn9C9SB+)BJV_Xd`dw3a99s2A`kasyR60 z>}%snXRrLk<J0A<{v2OlwN_+j+^<d3|DHepcW?f>BisGv{N4L~&;O&Zb&cyU@2~zm zeczu2`HcoiYU|HG>upU6?Q1hNX-!R^a&r=oA0MaNx|GU}&{fM~ZgVev6?1Tc`<(X+ z#mj15T>Gzd{=@vgt=oTJ3Y|0a<jK$fkHuF{PhpwXv_ATKt$yvx=(=ZXt?!vz{c^WX zUF#dZ-*IX6&xi6mgN$13Z&jX-fA_N`h4=XRb3e>(o2X<@=JDIKb57XhlF4ZS3=EBn z=fsq9hD?pNwcfc#t@3Kk#eyKlOO1ClivD`PbP?IIB06oJ_Vp+CKO}wn@-zN-@BI+h z)&GCEo6ny;@4M~;-pC)e?|&cux@~6s=V#gb{~S2HkF}{cW@prjD_*-a-4ECG1$0lU z@jI6}sWRo$)S#n0hfh9TWVJs+OtUD6ago!y<ejsgDv9Xozcj7faq{Ym>KCn2<$n%~ zKfU-@*#6_Kn@1Prhb7m%{V;j^znk+<A1Zs6@X<Jb??3&2zyDV}il0~c?8fF#AExhD zJw2i4!BqPV2O|$PFWLXNP5S>6XZeZzwLdnl|81tXaFdxO$ES+xq3K0EG7Jg<QzrYT zbjj`p75Kj9=|vWnOZavMhs1haH7kx?lr=TnscZi)`FdNE6w|Q!&s(q8y`HJOZ|B-a zZ+1Sv_n*CQ=IJheyDuI2jSHN-)>U1V5<OXD?3MHK!Id>-Ho>#b>Hc3Jy<u|n{$ki% zp<q(>&aa18+dO>wFwOpvQrG|AM<#!|P<JzR`rL|dOY*~hPhkId|Igd!_bMOvYHb!+ zx2I@v3gh>C<@?Jw9^e1%>+bhIFX_tvJF)xT*V&WwSMVI_uGzBWbl3l<=l`#MB6ThA z%9<QMzE&9l>-WWdLJSNnPJ1VB&#t?1<Yca*q3L3?`R1FBuA0m>L2AvS&cEyLm;_Y? zv+g+X_;vjM=hyl8y)9pEI<5EnkZk#nXJx|A=kNZ|UT?9AEAD#S?xzpk<v!|eI2CaJ zF5m7Q&t&90EP_8jg^V6X_9{R5!~QM0C&uH^lS%5H=TyLrlI~qg-m32rzV|%NL$Uug zue8~T$5HeC?2EKLI{p3rc)8!w=6PFmtLNr?5U($Ml5hXr^5(vL&(5E3nx1fPuYVOR z|MSGU*X!@EDw2_(ZJvK`SLy3@vAgZQ@2q9#m(!Vk`dlItLqq7|Ie#$PVXNg=PUf0m zrz6O#s26i0=l;IfsqJO&?(E#K;YIX<<rCKS_E~|J;!JawvwRV)Frnc~K~<c!W%#_) zuV=+^-#Mvj9wfWi%gT>0yYu@`v9gS)$SdJ;7w7-F5_f;izQ<QqYTlgnV$0mg5j_0- z-ff@G|F1c*eTjab+}sH{PAZ@soRd;x%5J8f`*oU!m)CPwO3<b=jm+%Fjvt@v%*McA zYgAeH?_2f!kXWYQE7hk5MJ&zIo3cvW+rrXe0%)(qR{JSV=Z_p|nY=5@Xr`61eFbRm z-U9a{C;iV(-E?%-S0!J~Bka$gY?9n9IL&gl@I%lb?2^s7x6LYzPAlJ<$v35Fr;VAJ zTGQKGTmLA!?XCa+@90t2^o4#N(-cp4xAgb)c<?RS_Bi$NvEE5~+#X_T+}?eU*Kjg0 z<j&j?uw~AjEX5mnGv=xJ>7Cdldf2A!pVH%X%q&M2I=8n?mtO7t^0+6j$QhZiPO0+P zEjFM=WPtvD?rSGc@2Wii_&BIpcj(>S-A^0$l)es2xAFn)v3eXbcaPIQvF>+|zsH~S zRbii4TK?{i=FZOBQTMu+<lo-r>k?aJvPqhuVVTTn5zrQfHC08~J?5>(=bgRPudjZV zv+mQ@^m8vmqa>KtaB1GDkX~ILUw%=3hUFJu$IJ2+ueKo1`p%zo&i1R$*PID8$BrF) zVyWXK{Vn-^d(EAFwZC0v+)aFFmUCl6@^QYK^RIr95Pxo8@SwqC$CHdnJ6FUUI}O?f z`*ITF+k1PXH_c<X-NeYiqoMR<vhl5$IDN^t(7ED8g@KFTS{+!$v2tUTyFu}be&d^6 ztJJ5*D2S+=pZVG3c)QfYCTYVbmTAxbU%4`6@)j`}tCEc8=jPr^eCX!p_U+wW=@W6C z551o${nKBxuk>};Rk1VeDytHoq!>n8Jesf0z;JEaNzmB&>IhXxb9Z~}_Ft2wzo@gn zn9U)zx}3$hJ<bw!5vNr09>+x!)7ML7*xLEWPAmv46fBym%%SvZlA}l1QyoEpPmZ6~ zf_DB&Pp>)t_Qg9TYlW9Q%IplC>7V}mx%YeCmQ_|=Z6``+>or<fI(%@s6R}r$hGj{= z#m_4;etZ|~pKda~u*+h@WD)f{;P6XG555-h`u4Wm+uQT!r-+?%a#a4=SF^%nN6my3 z=U2shPn`4E^<)Ovf`=cD?3``?Il(-ZDRVcUfI;?Eh}q3qyY*(aUoNw?(43yTQatxk zne3$A7wc@&o>sp0IWBQ>iOTs;yxiNXzrW*nwNBN0QclMEdwZ2$O;R<Lb@MArOG$AN zOOUW+kO)vq_bLT9w|5)fTbB0e{r@AN!O$g44$+S;fUVk+`03A|>b%|GeYVZfUDfA* z(0b>MAI^`1x7YnkR2Nl<?09tQvgxeGYs@Kyg@K#azP-JD_u)gHZfcWP%ZRNDzmxdn z%InK_=N1MYK5;T8((RLe+eGGu8O2G<Oia_a$G+b_4|LL6Nq0xy8c5VETeF8-*F=5$ z{Z=#3@ZH1?|5MJUzZ$PKyYg~Bm)(&2`r6v+Z*L+eAAGgv@QL1@o{H69VpGCZl_#@) zdv{lx+qg%D;RriqI3Ki1?x*V<nFY!lbJyGxJR?)1q0Yb7e&^S^qO&XR{(TWRM`lvH z&3{#Wfoo+8zA{X-S@d#40qC59X%WgbhfnO3eH@$8t{Tg$Y;I;I_QRr#fgv{O`sC@G zTJOCEx4W;aoeT8myU^E|0X98m%H;WTu7*s{4}8HeH^wY%^X+x_ze@P=c_tSY2F`pq z>vxvNiSLu<9NHRx(&&(!*t&2P_iud4&;Rv3c*Li?JZ}EH8T0)Z6t<;&z7>A_e92|i z4Lc`Che}qxeKC`Dj?4nhATG%@$6m=EJmVPPS68#kWcF$i?W?OSwiv53967oASx}() z`z7;aCb{m6nRa}cjm`HrHy^90iks@(xwba?EzgCdii(I&2PO7h^4XMj@^qDyo8GB& zpBW}pK&KI+lJ`ulDlgiu^;mL_%mT^g+n~6wJXJWSW|>K@W#!taXrt!ry?S-|SI#&s z-S%I>kFV2-cZ=SCtIIDPdct|RpYLmo;pJBEEc`b&swns5Etf;lyvpjDliu+uAAfzB zaY6o(llK?S*>m}I&Mm8-H+B5@9;iz8UbSwTxm@h&ljF<0FIVmr>6)znbjz!M?)?v* zOpy3?gL&=g#YSgC*C?$^+Hf!N;gg0F6D6n2U#mKMvQ6whr`3s1%<}GN-1h*d;}>#I zF_vUyzB<V`tx$S(_sVy7b{g}h>YuS`-QibvFmt!u9$3SD$pW^h`x_FOCoP-MlYD<) z?d@&3!IkY+7S?5NB&4N_r%4E0F(|73_GY3?e38R;<-Ovb)AO|!oiiw6xFGTrRIug5 z>Ay4$%$Xyzp#ILWSJB(^d?S*-_9Z-9x#-?W)z1@T9E~O<Y>`oKZ&AG2n8NFH>r<;< z;Ne3%_wG=Ymz0#exx4)R1HN@?k96a`RBC>Idpk*S*M93AE3Pj;y**9Bl0jg~<mkg+ zp7but+qUx6fs>549_FsGE3p5}&XG1xsGz7pFVg3i!)r#RtX<3NA}j>I&b2OATaXv2 z$9z)YszK2w*1c=L$C~Be)7hNTSo{0i$wNHK>=Qt<LZ_!JE0zU!&LiLcY5I2Ka{AY- zvojeds0G~s$NMAAj9-8KeL5$nLz|byPhU;^-0kmk?CD=mhQEsE9V&&ovaBv&V4XC% zuebN@jg5z8#qu&TJoX0bdiMUmoA^ZK_>|X2{%+Fyv{p6tlmxi;mT==!SP7nG2aT+l zAG@972i|h#Fw3JD9A+n<U71r>bL%sBjOy9xt<S~QdR3^4CNNA)Utq&<+3Z5qhK`PR z_x9elUNGyAuBNAG$Vu(HiBGQZTiM-7e6oZ^iQ7Bu^%_nFX79a|w`+%)78XUWNt>m* z*J}Fp&EWPLU&fkysxvBsW^S5WW42uU%I}l8b1GLmZ&UTttDN-22Q>b6V8O=n_i<nE zEdCp!;E}hetu@%bm3z|vRf!KL)wVqC_P(acwyter_OD+hp5cd2be^Alo{2~16ppoJ z6U0=?mu#$BpYZJD<1aNoZ${>>OStj%$+9QXj8;3JxNW*AS^XtYT{L0AgynN=K1yWR zs_@BLsZ@4d_uHO#SL@oWc?T~YJAS-c%B^o%4MX9x4@Y+L*Zo?(YTllJX+fdu{q~it z3^En>I_Ao&-X7wR{Pk+XOwcO);Nqxl3#RjK-d3XNpg#TV6`x?^HGP4zKm$U}%`+B0 z5&5)6c{Yc%<(2C1?_?z<H`-ota)~vXCDOMdTyMH+_}%UK^E;|mCq7ZRXx$@YFTr?( zU9c#7hTQ7b1kj=#%b!6<4g7td-}~SBds8JS(YR!+krSCw$uz^p{{Oq%?`&=L{qm4@ zLGky_-v^mMXKt$KTeV+xd52JWgvEE>ht8)DAM#xGSZ9jevNzY4zXvrMVow%Gw@;kB zC*soG#3w=qM{Ex?6zK$8*{wbMq<7x$$=sXP#F?H?_nyD+{cKj>@*u`Zti4wcGZ@Qf z7~MQ{{1_j~mLTEDm&<Mb=&Fk*INZqEf680u#LTu6GiS{Bz{_oJW21BK<c_CYCku`r zJNBd@=k_+=Pw~$sDsOB^Y+mBs*q-==LFw_0l8-I6KK>^SZkKT8JbvQM?RsmSbJD_% zRVzIF_9q|b3*|U)hP@l3^&+9;_O|hwYw4WKh+r{s@$c{N@2~w`_I^Wwk!GjK?Qcqz z8=vfd_4VZ>adTNW(3(wUW#vr_hfgrJ90X1I-z?ge;qi01R^Q##ldb=rlzhx9#NK;V zIXNrKYpaWZ!Dq*ZCEILFm+Ojro$%@;s4pT8S~w>mamC^FB0ZDkU5b;IzrVBd^6k@A zt8H~;_HWyMNY*Xyc%SSf)7|^CcX)IyIUN(}W|Y^b;&2~x?OYH`@73!pXKFSaILWx@ zgtGUh9$sm)3m43v?KpgB<+<RdIi`ZAMfkX{Yu`(J@`RzPntcbT{m!SyeZp~CYi2*g z1>RS&89{5JbV^?cdE74b;5G@1k2d)1=(sf&G$pz1^+C^_Ij5^Gs^wl!ESSJPJw@hG z#g_;<og;_$9zJwZQsk=0%qhaJbQtGONLIDnYTYxZ+93AH3a?#NwZCrMkT`sT(ImBK z*_E>fwml!&PPQL=^^wuI-*RTo!^g?(=TqkP`6pWJykU{N=b%G?-gL=~+6yyh%($^R zy<cj+zv9!zxz^=M6aFe5KWp7H=eEkhqq1&(d+p}RJ2Lp4nX>Ge*S+gEO_t7`EN@@` z5wvqt<l>x=2FK=OuRgLE_v?b!9LR5*eE;*0Bis7#Jzc_dMD%M>4qKEz+q(?~@3IfK zy(wR1sB=ea;$rogKkhwEe6mOOckCT-<43c{ag~6&z3J_p-U+Y&J!z{1FED84?!B7K zmnP>tW%BjE3#3;}UR`+oecc-kKR(0s=jY~r%1B!9)y2rpPVf2k?0%)*-R19>wL1lP zEcE_VGVz06`^3j5oSQbjKDqY#%`N)iqVAf>TEly4=X4)DG3dAuQQL6fOmZt|I{oR- zJ#l7Pi!L10+?k>`Jqx_J{LvGE>~HVy>-(#)Mfuyz^htwMeZ{vERwq7O^5nouewmZ^ zpPm!q%s1`1bF5c-se}Ueio_=pp@NedU-{?t@4lBeW8O5sII}a0(^smuGd3T4#mto^ zCk)z(eC^pMH&1bO{tdJKOnRadTD)?_>~cHMz}}6b7Z(&yI_m9yV>Cq}RK}tpp`_%> zZ?^YqqqiIB#H=`>t9JA6JlpCe2h<|#9~%@kEivwq;n9OG7~lO;=*E$gzL!HnCC|@U zI8TO+Q))H8)r_CB7K4|ft1X{ivN<Z6>%ytCOTFFB>V&NNy;8k>hmybI#=^oPum3BT z7DiYImR>Bqw^EF^==I9$%e^ZdyqNNY*~E7`tHz$=IDEqKPvCo}*PG|vF_|u-Za@3z z$wY+(8>=QAICEX#>67C|OJDAZTXn^$;M3AMVSAgaiaJ!E7DcA2{{H^He3HV^6JHfn zxlZ;k$ym5a#Z(8>SITe}RLzpG{QB$5+UV_OvTlAtsnc{07!(O;gPMt##nx1Pn)UR_ zIT?G%P^z!3<q<il)#{>WYJ3ak)a)uz44)XIz@vVC`s#9-CG%t+bx38zZW2nDN|^ca z<Hx(Z%d4v$yIHyzjVx|PJp?x&-~G#bw5V<3<fay#;s*y9&xx$zJatk%-D`7Ytnr#< zFDxuo1f*80%bl@FdNp@XnDN?sK5Of*zU7@G^QdRV4x4nB({nQ$(o&|iw+0{OcgzX+ zwDRxo@4?y|o_Q!b@+zyVdz|8V#Zn1s#h=w<^@yDDjZeVr)JcDz>_<;r@2+}v;G|;U zg$Ucwgl7{QCp%jOGOzXC))eOW-6QRah0dH4a#LA89yITn^F3v!$1W*1zj@3e1_}|N z^(ohuy-f<8{jB{hXccSX`@Q#dGIkj=E3jRNu-%&QOc3{?!8NAs)7Yb?xA#nDxxiiY z^v&Jf;a_V5a&ByBOnjJh`p1tQ<r0?LPd0bk@T$a~TcD%d%3GJxxG&I8@93(Rd+zP? zPViRO56v>(d8%gPt0hcF7^GG+r^%VAr*BQZeAH)M(5e}bE$Zjub-F)*SEt(qE%|fS z;k5uqYIVd8S?jVL>%UI&_Ku0|nVWX0(9Lg-h<cTjTV7$|#Yo8orl(G-8@XQnbD`*y z7-SK9q~E&hX`ida)Y~f@l1o1{&1^q@WlmYrE|cV|pgD~kP(!3h@pWv*(^swCQy2A3 zK731=wa_$6oO!MD0~1-XyyxfU{`qCB;o<4*C0-;H&8xh<?r)Xn^h+HbzZ#j@EjC~1 zfXv^Oep)&!a~f~)z66~IPc~e;5Fs1YIJ5oWl|5#bi_bp&Iw^4VHJ_8_OeIApd%LQx zu4*}cQjrZ*|IL$|wAtb^gW`rAJ9gCnuY13t;8S}_+$4|K*9R0I*_xTD3Ej(**vTtx z=CR8rRKksq<@(8`Pl7ePSFUo04#9}@9u@NA%jWF8x=?vW<%T&Yr}>}Dy4e(HcIMWl zr3`ap%pRK^I&?De?9IK^+igrFGGrII^!VkRy=_wU`Ptbb&7eb)F`(A=_jjU!)15pn zCq8+ib9%9xSc1e(5hbT}Z7(zLt8SP&S^wqLrNy6*`rkh;k-x$0LWFD;lQDmb&$bU6 zHy&R8d~43d6(L7YuB}lHP&Yrl>*v|WGp*(RO`FWMLCj;D(s?dT+sog$uCbild}Twy z>+9>oEw8unN|(L4p%|`qJ%vd^UVeH}hsTaN!J3mz_(1&^z2a2K$Vu|4LT8S&Ui$d* zQi-4b*IV;rHq5;<XV%I6|AoJ&ex5a%OMufPtbO0XGvOzn{QOydzwG^$Iokr(gsrLi z)KGHA&1~76KMOyujJE&3VKSG1Wl+qtKdz^ad^%DviQyXG$Ab483Yw(E`d%A*dSr&3 zQpu9AwA_EMku9dJy?yBmCGHb9r?<YmHG#+FguhRAaphvfqI<|diVIio)x@s}&sIOg zwze?iWQviJ{i7!~k_veq8{NGeC*`jE<9%aC;o}!CG_Gd_O?=cf=g!^T<?pw|&wuwf z)=kl0%QJkvzr3_`vcyiuCr5l<K3QYx)4y!H^s?nkL8lyeU+w;)-o9eNMk^NXw0rX4 zrTV+yf;PiGdQ$0Z3|bC%>NNA(_jh++_hjmj&x)`(dFal@eeG>+E@!^Iy?uN}V&`%5 zo;kO7gDc>axKn0ZmUmb_da`^?Qs~y4E4O$qU%q#ecaDrw!?9Naax*H|YpBPgt&7R< z=)89Qo>$P5Km#kQS3b-~<{e9X_#}VgM$kE2oE}!)-Q7V|h3ykR$MNXBGbnoX_2rbM z$xYxjG|M*xUA?$?vh=kbueZduU%kA~o~QS!B9p=AcN^#Kd2-gK$;q<vromgWm@AW= zcX(V={=WN({=2{H*rKNIar0&35u54bR&v@}=MHF~EAsZgzrO`Hh$y9|Rqp6)DYxvA zv46CN^X8s!2YyIiRozg#an)Uk{LMR0U7u&UJbdNZhJO=lk`A}=`pUDIgtd3PJbC8n zET2Tp<qKZ&+m!wSkFJz2WYv7SN%wM$khHz!-0D}6v*Mk0$XFCO+<kNC-rnk`ebemC z^6s42;5mWe$tO8k*{}P`vLOQ^3-gqpdK^sq|L?ET!?kS_Cuh5zvftDo<<_@OK+wQ) z@yb<w-wuD-Qv6Byd~D5WcDvap#pZ-G+?#0QEXP>%-}<tdNm#q-5^3Y<*+EzBEiSK2 ztohVr^KGqsiT9%?TMg#Kg#4d(Tzy;Z7d>@R1(_umR^}BS{XGBwpZCAky<hZLRfWe? zXAZ~C;)VMB-0GL!>0IQVa(q&|$j+s6l*K()Cq7~EEN`Ef9UseBoA6bA{@XjM8<tL% z-n#Vh^TMJCQP2*FxBK$${`>noRH^r>BHtGC;+<Ys*VO+0X6gAd;poY`h1Z=6KJ6|n z;*j6D{%Y(SBO4nZRZA7oi<$Sqd01Xj@?~a(MdUvFne7K3U0CQ`w8-_))24~;sgDhc zibOqsy?CK<_{3T{$e_^EC)2e;Ki}BtI!ET0+a~t+8X`s2_TO$Kn}oGTT)c87RCTA< zlpd|n{W6;B_L=+V-&v_%{*0v|XLXw1)GxQ}ZQ3R~zc86*)XFPu_95CpW!}e+g@Ky+ zl0N_L?JQnCW5#9|W0m)lce@p62P)XENPP0`=6e78yGmDoe^fZpWu_{3i+RtS9J9*( zT)yX^i$k|-J$?Z?DCd`3@3P0v^S+vdweNUn{Q3L7?|Wb6A3fG9eYyCkmiqKR$!6=j zZMvP<Up$$#ImCDK3g|-7g^zNVK26TZ=#Xz!R9%tya9i%}XM7B0H$QDC=*@LI(t5?n z>DH|d$6&Q-?GvSCWv5=67#;giX=#<`bZxI`6JMu)J$zziSeJF#8xNnIuMa#FHosGq zZhrWSNnz1tlhDv(6E|O(>^#5Y$%)=o?;`Z4v?y$=ID4mki8Z&XEND8}dvoRD70?Y7 z-@A;spF&1&1hn$LPhMtlNqUJupxXTn1+&fbr&%A(wNz4ia%O|z>7bVkaYrs)1?S9j zPaiq*DsL}-?zeMS%ENhW6N~koZhHJqlWjh9YWIa-MW0j)i+s)dK~272N38F3h@WJb zqsowUvfchq;`5}n>Z()OPMz#e^}1}iH)JL2+b7d|Zh^L56bh)f7f4D<7UtcpQi(m) zan6ZhWlC07*86*V?-ktw-RspF_v_MhtIMZ5!Yp4iY&iyMo0Q9odrm*Te#V|3HM83{ z_<s`qaCicEEmg1|WG(AL{U>$BdCSr+C~zft-@H8e&hcMgUr+uxIk#FyeZF4oiBJ`B zj>9KErxq67TIamu$1yQEDJh|+0-}X!%nfs&_V)IkTzj!ZC(pHNR;S~Jp8o#o_KC&S z{yRJhy)U`DyQfNSEV&xDcq7lY%FoXl<yc%Sf1ZrY-ItKDD^mDu*|Q%9PbwxD&GgY; z9e5%}ir2{|^Zvb1FWt`lC9mh+S*Jc-M^Qod_(?^nBYWr0zP2y-={~i~j2Y+O|Nr;i z`nwOava&J{Gs|lCbxMWrYjfKtW}o`?^)>r;JAccaS5+^72A34IqQ0I8Jt4az^|aWk zQ;Ka{R;rXwT-3R_#Ob4D<=HK65(iHvZkV9s_AcyXwuGJ30&lbYduulBT-M>Z@TmY> zaB#5FtKH@A<z!`R|GtiYA5(C4LidK{>s}fr-aOfTIWN?`+bGmp-Tqt5yIT4Epmq3? z0=o6T9@<wP{{Q=z`JT)PNfnnv?|;8Eea|1!`}!Z5?SFL1*PflKRnvV`tM2Lbd>%K8 z1?6u4U-Yl9yKEZ1-%#wMvi+~e_dm|Pf7Q@z-!t_Z?PK<NzvkY5{Yh!Qjs5<|+p4Ed z7C&`$!kj<<)cxN6`g7PXOXbfS{XKWfeL7g$@0?!$vvd9zRiV}WYwiD=t&QPZXMLJ0 z{@105nomt4ZFhA0zHfP!I(`40?P7w5fBe?JBN#NZ?DqP-+HYomX^*?RM0wYA@qHg$ z53jFp&R=WFskyJLa?aGr-W#*5?k9qJMtZByKGFK@df2lyW8!7iT@`PArSE^dxVkgI zIj<;?bz`5wDai|LmiMOb{WJCdyYK&gpZ|05dFKbGz6~<Z-|2svym?lN+{_sG=}UPV zW7b@mb7jKB+Ub9%-@a2G!O`@>bl>OdxT;TArj+_yZVxv&ajop_t*@)hdw<yVb?DUP zyncV<)aFC`f3BNe^PWFWRsHE!<@yiD?%#SFJ+C8u&$IOU=f~o!!xJjM8BI)GEPe08 z=U1OTf7~O!=R>OW{er9ddwwr>|9@=zsaZ#gHhMjjSsDf&w+r9JvMplyR_Ge#>nxVx zK^1>jn(vM4Dg4rXU3g*JowuRCXT7gUb}U%Y9V3^eT>tTE{O{SyE)|OI5q-tq#eaeZ z_@ZW?lvezr9{%2GwXOKd$<gsKdByh=6*(4N|8ehhoZ-(mn!i1hL@zTtnkmozb;7+Y z_UpFqU|${C8(;SHs&xIcSo^Q9<prO9IIGI0davU0{QaN9>zy}MzYec>&d1$wV$((W z9lxIIu*N@gz5h?PD0SaYTlxFnRxYpcUYBcebX8RNQLXutx37Ga@#x97h32Q*ET>-= z?+R5HUF4KnTI3$vJK0^R=yrCM?gw{?EeH3WDE!3X)c4_Z+`m)r^gpeveA{9w(HRF` z*>+rKx%ZUG;$NfO%+|R-e6s2OC)Ow3r*q#~>##U}k$UvR-QOmA#iSL*lh=w>?m6LG zb-LZYX|nJUE$2CZWcPoPPAZu6dS%nKR~t76p4`3ogxmh#qG7j7!;jV$KNj}ec*@}E z29xXA{Gh?b4RiL?PCxL>Pw)KkO@YxGQr)U^Y_gu{c;+n+KfC&V$7FZGqW{lNZ}qy$ zvta_`+d}=K$`ucvB(_hjtog6Kd;bal^V#a@TXQZJd@8jLE_k+<?`F>%2T$|opWIUX z^yX{C%c!e&Ts{6hrtIit;q#{^J9bTFv=dtr^ILJw9EC91M^FAI-p&`%Hr0%04P6#` zb489pQ%=d_^Lw%tW@WBO3jKb(QYm=TE|zE3C7d}=pLkd0W<E>$nSFlF<<){)4Om)B zzv{<Ma(eQb{rJi4_d~v4J9s*O*RkymbDYa6Him4?5?m|(ll>D*Gv5yJp9d^{&VOIi zS(<tOgIN48g%+8I)9e0g@7{BQd)B`L!RaoikDk<R-~Re)^Dg}q<5hy!p0wTxo*dXS zPpeulK62lVIX3qb6_W&;Ytok*969;_>5I*(cUQ@BJz1$BJ&|d7&RhSygC`$L-C5Es zJZ<v*AJXUiKQM0nJ0&`HOR!Pira<#INmsS?vO<5eds#Zk_I)|h`e>t1q1ASqW6|IJ z^dkJ?O#N-jCzdaC?VqDs`jvmi<ap3B<3CT1oo4qs{Zw;vz#1<_XVb5Z90mHHrq}*Y zu=sg9UncJRGwHa!d3RU;KVYx@Z=q4Yo_^6+y)7#(eP#A3&GcRHy(Pz|Na^Mq+kStS z&w3^|tAC#QbX3#lh%wu*b6$xx=TEPzcy(fl=_MD3n@e+!#OzuUKK<VlXZd3%A4}d@ z!YuOW$^MeZ`D=D8DxSZVYv<MMXR34VNUw@eJ*x8CBD(#AWrVK9JhX*~F?K%ZR!?RL zR7}s@F!xXQ_5PUc=d2|^Pgw4=EraF9Vf&IJdrz<*Imw?>H8oVG^7QQMYpXy1&zT|p zJz%E$ck!PybAEo=qsAvcY4Y^a;4(L3A9Yiol=n}yA3rJVJ-BakkVN0)+y0Xrxc+S7 zJ$*9!(UU8aj~nmsWY?TBS$}tu!OiU{cgl*5H(i`sFgJ$J+dMbN-)H)~xmTZYwZ;1D zo!|3J>i(sZOHH-~m=t_^F>!OtWOvDJlf$3d9XzRgc<%}J!zb5Ht1jET*M7&r`*r8@ zu6&;)&A(>J5&da%_uTIO0~#0&KPA><Fz1e}Lr9Sk*k!uv>o1hqPBVN^9>(QtS$VK- z(t{@}Ir1(waut4>SpKi-!Ph4iJM}|0W-Y8%pRYN0*5ysCcdhi-?q=BrU#1`Z<V2)Y zj{5$mTs!mE?^>GIXu<9$XZz08PQWj3>z(SW=e9@J|M#!|z1PL+C+a%>M^7g9d~BP1 z+=A`zIj_VAPcpglE*<2WV>9c;$&*)iyq=d>wPxw;b(gN4?6&wRrI4PvV9uXe+3TnL zzH<7)*7;v_g<nswJ$6$0*xnQD2SGkReU$I@`^N13*Edg&{`%yWmu+Q%d25dM)ye0d zFV5ZFH~F|B+dr^9n%sGp7`Y+#Y_5FUSXlkyj^A1SXsewz1uy;gshwCUrJ=t4P_TcV z_OAyfG1Cv6Tzq`*3HAdg*RoX~p8fC6%q?2HHj|kJ_gd|I<)8O|!ETWqpuXSHliXWk z{cCyt&7FGaz{$&^ca}7ZSyY-_oIIIZJ<V&C_kwj@p?;g@mnH9!wLib(b#}v?RgPsv z>32$Rt#g*X({1z5FON6p@_~e{*ItADzx?^>M^D0*-LqW(lJVv=i=9sr1N%VUFcvCE zUusbBDTLMh<pEYdIo~f2pWH3s%nA4Jo4lU0XcgP-lcAwMOK0!lK4SSqvw5<6PxZv( z_fD>rE7_;i5$aR;>pHL7m#0q>uT6ga>~6pO(UX^DJ$GyllCY?p)ik^01Cx5c+OL97 zD|h~z`zL5=mfYc!*O@FsncqG6_GFi~n+^97%YsiY3iUtju&%5<y;rTXQ~I&5<xfxT z&m75jN?-4p{zc1g-ZzgU;6Ml#xwC{>0u%_VC;OkvSpGKrj8*RSXq|gUPNqh#u3VTX zXS=;&vU~rWm5$|~4rcA^o9y0SJ@NRRlhIc=E3){7UOky?y!0k$4P?N~T~0+}Hxo7n z?R_0M$L8w99&7E^#>vaocX+ZJ3cY^v?dY?5>HD`_{r&1H9^E-Rzw(36w&LlaN<n?o zlJLS$rjF;PT$;*Q^r?|=j!o5_?iz+;71DoRoQA9>-D)HaKBhz3)Hr_KyZSF2etrVX z;ue;UM=U43dUEYYQ~th(SNCoIxHk67lPCAe7k+*7WR;e)-Ln&tb82`e7`IM#m$az- zvP0a`PtNhnL(tx7@JiCjXVebND$=a!o-D5QOqRW{s7Yeafs>p{=OzZIZ@+g~-7IhG z-Hzk8fBY%{?FobKNr-2D67uj#AR9On^-XpcsI~ZMSojGP2#|%KAY+a|jPX(5F17CV z+G}ec^1Pb8etjT&mmPG|LCVir8QYAH`&+Bm&#L;g)xl5HPcHSrlZ%hzo>)|}T%12S zzTovqRd0?L#{!@m3Rny)8Yc_8%u$}`muDJN-e$I;&3HxjK06EWd^&hvfu-R&8GDP$ zHxq(Ue7xq^$?RoMI4mq31;QRYVG(@pv1oEM@Ac_xZ~wC9JA3_i(Wj*2dW~=A{JBxQ z^Ly=|eK~Q(X$~qUIuD&(%ma=L8TEdJsv^)KB-VMm#nsh0K-bMRbrh>yIQjbi$@Hr; z&G#+R|McSU$<XNzn!R5hKiPE42XY{%OY0nsIX0&tIkfN-$0BugarnwVS0m6_BH`=i zMS}+^6P2v{CJVa+Kzv#0m)HCH+JRa78`txL_BMlCZ~K-`K7ITQ=yXm8KM}uo-4kD5 zTe~|i`0@S5mOJ+>Dv#_C{~2Yuv;51sA3aYr1&^Kk^6JU*w5^Y4UMk7^$$qzC?wu)2 ze~Y`r&OKSu*7>GF!cT5>_OkaL$F?gh>TxVAdKaKHccO**_dWdemTP`5Iyw8Za_?0O z&=zMkKfTjeeS(d%K36(-75Ztpw9Z-jZtfkS5dP`+OM3Ggue#rLXVE%*m)&ok!JTd! z4fXA_jVoVX*m5%Z8s~;PkMH;1GnaN#TobN7f0q9I8K60alM~Lkah(ZU_TWsk>?CeY z_5B4KV=jSe2;)aWhfI|NzYCh#?rYk5Uau^+u6vog!m&ho-u7RDRlocHSsVWHdp9fm z{TidB7f*cGpVwReR_}1R5bL`Op)BPY9TQE|*XQrJr&3sOtirl#VZ8eE)~6+D+{c*w z<SdJ(RTY2IHqQ&6JpWEbrFm4{Y0=l$cw>K`Z2O|N@uk*I*1K<S%U|FB?fZwF{|=lK zZmXWi{_@G*KY6coUzbF_d#U!S{P3^Z?T6z`pO`bg>yh4T^%JzGE~Zj%eRh>@gnIb% z*s^4`<@`;Pf1h74M|SFW_Uc({)_(o9y8iA|;keHIPX%9C&JtVO#Q!^BhqaFUt=EmY za;vpJ?*6^O?dWl}i|=1{%$!`@Uevzo0bi+7qTjto*EZ`_KR4lRnw<Xm)?fd5FPC{I za6=CNG=>gLE!MDX?AF@$?eP=d$!8a5o8POud|_8<c#p}F?~)dlI*;R?be4V6+jO;! zmFbS8c~#M;re*a{Pp%9uR*l>TI{fq6Nv>DNCY)X27UA_{?iGWH{%>xdd>h7pc6DKs zt*>sEY_4(#Q_1oCi_bW|$T+?!c)sCuy6v^ZHtBtnZ=c`Er~J!Sc4JY|yMT8WuDTz3 zcY&qvquA*eCr`F^avx2e3CdNzb7Cf>YPVJX`Qv)8Rm`?%8dFix?rG5*=VWAm;|jm~ zDDvXLsRh|z&9*)&o&AYp^O{YYwm$u`Y<~3ig3GG2D|dX)PrsD-^m+5L=seL)9DZ_! z?_A{?C*NK=Ep^&y^Lv~6*5A2YQW<}7xu;&9{>%HktN$$A6uR5YdE*|3yX?B+!B>`r zrB#-#c@L_vcVF;3pMA4Qac4u6%?fE}GiA^|!D=~svEPN)ZTBBBZ+Sm!qnhlVr;pXt zV|8_AmxgULPx^cJ&8xN1K`VAkg-_5v9+g&^cQ<O@k<?fEkDpm5y#2ZQ|AM=M6IR^r zeagS-kY1VgmC(B-?Ww1=Uw&I|zWdE>S?Bw&v`<%;9}`~7*Yv$0vfji}<lC-!XSdzD zVw5{ybe|{t`>Db9-nIgFjGx}_^{c*m_GQ7eH%gD5JbAnB{JK7$+pAAU9<_Z_8t%GT zwe_igj?JNKMyHEkU;Ct@7hM0*<UV6*<Th(2q0-$O|2T#fwEq%%{r!&p%LjXlUZo#> z$#?YR;?B6ae=3%x?4KW_4>@bcW=l!Y-YmUotBT_0s&sH!de>U*3>AEv_09Bp+{-Yp z)A!{}b62eY7WM8F+uLa$)@}K{Xdl<zY4z3IUd^(Tzi(Zd|7+*hTle!e-?Pp6`u)?w zj5|fMC#V*F>L}Fzv|;X@bGPrD$zN*n;H>7}`t4EolCPhB`E{~(<jQjMIrDdcTBN%R zYK3>V-9HpM@2$w@H*0qJPFxL6Eyg!DA=WUi=?mOdS!DJ7%4SJ$6YzIQ(eDS_wRpDf zs#~*vF86|`p6jiT{@eO$QJ&}hqXG3#e|%q9_}ll}g~{)B^Q}E8eecpYjxBqFZMHXm z-Tr&8RQZkAqyH4{FWKA5cl^Td&UZT1$6L}^Gv2?t*L>mE0ju^!Uteu%h}wSl+iSi< zrxbH{`kL<iBl>3lT-Cj+f2jSfw~l`Os-#5T5S+#X(kEG$s1|(6SQM^qZx~xu7B*X3 zB1kIpGW6_F-Z?f^PjtRMd!oH1NAlg*(EZZU&+g=GnmajqTa0;j<?J}mX)9*uyn6C3 zF7o2lwD5m<Tc7)GyQBByz{4kkkK>*s_I|vkvVC*1<^1f4!P{cuL@mNj#jW4<@ap=g zxJz0KEGn08mCl>D>XhNUH<7LC#(9(8SCy|R+_eA2-ILm@=EW2>9+-P)mAbjl?zg*M zg39;W9e(dDfBULUKU{t3wH|}{(bJzKzt8=<>*O!(<JPD5|GifIBJ%XEPj`dXPrmn# zW6QqasI^zC+O7T8sZ{kZEN9GqJWpxgUVgLFop1S_?!H{{JL?_$+M1-x`Zwx+Yn#L` zOWgFX#KYuf@2@Y@qBsA0QDe2M|6uW_F!!`dPtj|i?kv<T+wu5`ms0tP-O^uQ>TXZ_ zd+}#Ui9D#SwR!USDSl@?H+pS9=lxo*aqaDO;b&VX6>e;q?A|+P>Ag93Ci?F-+T&Ol zp7Hd_wI%%3dD80NPi~l;r2A%Sdgrc_%lzI&?l^sR-JiQz=cTvbF-tL>W0Q2J+vZMH zQM}%ZB@sX8n?KH(nO!yQyIxxDwB>7OeP6tGziq{*9BuCSgLkjC)of4g+t>Bt>Pi3f z)63Jgwl0!$v)%bSsDH<I_59F~P03I9M5JG6uXdU}|I4xBtfeM#d*AA}U1QDo|1J9c z!t#?-Pv7|aD7Vkyxb@M`ntogEJ=`|=uI%Bq-zT`Lr_XV!FK2gbeSf)jd;RD0S^I0# zx4-Rj`R=kkZt2GpyXU{Vef!tmPY-W0o?jyDyWdsZu)^=&GmGN(D)EfHhjZ0;I<GCT zzq@_=*XpN-H#5)kRG(GXtp{rERuz4M?ryzX!g=Ima{HX6`{vv!ypr0zt>sScp1T`n zxYtUDR9e2;79eg|^l4f3y$w&dDYEmb_e*?Nl2=gQ{@G*o7lqT&n&*}*|F`FA-i@bi zyR`at#q574yx01g#m)FH51#}VD_ZTG^PREa)343Xx~G1=wCTx}PfN__1;3A}uUg%` z@L%!X&3|s^?`;3-tr!32+k3B7pH_Vp%&1>}BQZB7qj2T#vQ0-*t{>lUwY=o}s?*I2 z4n<Ym6qd5z_;T5;{Qd6~D(0)74bQAIc<cZDZEpMCPc2(hUSGag%M(}sY1;iM)?4nX zKD>QWZ1SCjemg+H#8>^4GyCMV<%@qGIJvlU-kci9O5HchycKe<C%4a8WjFWE?fgCW z!e5JhUip60cdN<sR@~pAE)~Af?%XT(catCPI?49*o9>;bplr7P`90n3yp^XOfV0^{ z>&n<;na_*E;@+LL2>+M2caLr6RQorHr6GPR{}rgO&DbaXb>`}?h3|~6sb71#`<`s} zoHzParA1fEVvYEhzpVmy+V*A??^E!Td%x}VKI2gNx9cQD*ZNmIw#@zNxKH)9+UxZ) z?{)rvi+;PX-t($#$@1^!YT1p;+!q|4yGiEW(Wv(Yr%$fyUwAy|)#1C1dHhXWuLDjT zGFtsEV8zi{d8__@3-4QKbz<%I$1PP?)+~Vq2lsoUYxhh2=jkc?`MtB=R(kR0iGp^o z3i0f{hjrC=I!_P20}a{Ma>>{4>)r)G`j4$ACD+c@YkYgGBKgi&Q%Aqh{eJHxmCwFj zJ?-YNId@iX+UNFu_PS5Ko1Wd=S2Jgo<#xO6mlJaSon&kMru$||$*ncd-%qQ)x8tdq zqI?s$qt<SFZ1z;;Yu=^F$6o&5ee=`1JJa|4Y@1%uC97W<diQzRzsv(#M=HD+cz<pw zPnS~v-92wkOz-YG(8(dZ+QIMVT>sJlKJINp`?2MDe?jBAGftfQ{`Sc^)(4gguSst2 zZkYEuY5K#kX%j==yk7p*Gv8);nAhXf%NtVeru?1yc<$8=f5obAY*-STC$@+6;5PRK zFXt-7U%R_(`-yv1?a_YQ?AzX{|FYX#mp{FH)9vO3hpa@V{V@rh^2^uq{`R-uY<EAI zIC<J?i|oqn8~(7qy*hXAr)AskM3paJ{JUf7Wb5VkiYuPZC}=Ngzm|LI=f2$S?{6-3 z-0xfnF7dY`cF2Re;ID3<ocdiW_uHP3H(l9J-&bu7(~;h!yPa>}wFmbiOBcP)b6JtC z@;-XmO|4hOwZ)+&cXIwlo&CP&<+SM5HJy;4eEUSmZ(qjcC+1&&?Vo!x_0H3|8@gq+ zJNKQuwmb3p<t}NntNM@Y=A5dX{iY{<)BYESPp*|O>2_0{Q&n{G@Vm+yrEl+@f)mA; z#LS8}zLy$ys$;ER)nm)j^^DV}29>_<J{ar0PUgMN{iHIJ`-j_9-!9txpDC}7MdgmH zz@G9(^SjZ@N-o!0zd4g-cJrUaF6l4pUPm7N9=pqiqwEH2(*N3Bn`V>;=Naz(`fcy- z#Qe&i1*Y*w&Ar9G)$RHo9UZ^zXWZ5I2aMMGwa>m`nDp$4(7pWF`YBejlJ5c<t*=B~ z+%3&q*Uq<Nvbk;H+Cy<WKHln3Q7Zf7J#|$jk9s`!laSK)Pma8D&Z~u#+#2fYw_N1? z>Mp(V-)AJ@8E|6T6^Z<E`>GO$IX0n*Q-ADD{eGiuJIkE5j`QDp=TBa)wZl1C>f_IS z&2OG;OWwV||Bqwr<gPSB4?jEb22ZOp&YVY2HmwPrnmEJ#yzYZ17nRew)ccLV;{ru< zY?@vihAyosYFuDc+WJIiljF_a-ExOdJ{G?>ZSqGxuRqzM7C)od$}?h^)%g{E<*wVW zc5(9L)rR+=2W=)zjyrntI*VnnS9rmv3?}t{x$jEHPbzopn-e3fuKy}jdvoD4mIjN; zt1*+9{?5HJ`MBPz*BXyxr~J6CRq$ym_qz)}*!<*NZp0eTl6AA(qrdax0k8G#Pj?@v zzH!wktV`+1<%^Ri%Ujeug6|ToIWy51Jjev{$CGDA!NW?R{v^M;y<O~_bD>>RXQh}i zUYp|m@b-$CtzA3+EBN^dG((06*ml|f+*JCzdXn|Bw;A8McKx0cQ&3fQg_ldf>&q+1 zJs6hff1ixjxp(Pg_taO$>4l$69nOjP$)%pi?Exp%$4>-7@sqR5WbSoUagKv0rx!sd z3t0>c!2Q+a1IH_(<@TOWI(laByWG~Rorh<=E-yN7^e?oj57g)HF#{bow^nV|+cO_8 zpF25!*}NKENH@Lc^<!|k4DI%Bcy-db@KepsD)z5WSPUB=hCi4a)0+IOZ<={=QFcP> z!J<#XmmfU=ty9b2Y2qhmjW!^$x}fN!jf(pO9+er=%<AeLjeK+FC_IwkEG*(YKOz5Q z!KcT@OJ~lB+cZ7DG_By%4MlZOpu!W!fs=(rO&lr(MNJ*WOAelVoA<o=dRc5K=afqx z_I{w5p|3v|JzU}xasn|vV58<I_wDiS-yF&QRYgS)pUhF4>8=*98LAS@fA3`R(^o%_ zZsOQKSxRlwV~d{(ZW88BHF=*8^3Iu4&^+6u&G3NVKlW06mF??T@^6<O+-VTi|MA(* zqC@*8{3`g=>9a9;I_OkSdE?24PhMxR49tG_<aWMP)b@8>6L%fSUbnaC?o;#F$DW)@ zb~`^7?cBZY_7nepgD0OMjdF)MHBWgZyY9&!NwnX$yWim3l5ll<)77%)rz|TzZU2Jp z&6Bi!G1Yk&SGAM}9d;?RVe`w|f8<1B>YZ6vTlb!=h}n|p0(EWg6Dv#e%<~6*r4CEH zsQR>P)133?@Bgu1TQ7P#yyJV;$5_k6c#qWupUTei&$ig96K3ptcE#D}yqd=>R|<$0 zO$&PT<lFKa51wcq-g|<%_|w$m+y6>u9iP5K@4I`@<V5>@w_Sf!U)ntRd?xhd0hP@g zi~1Ji@qot_JtrBTJZG^oQOSDWHNUw3VGn<;Y6xXH`gfl4qT74^_4!4pTsgVZ^EYSS zB?-5pTkEQo7Oh@1{l(#v{c#)SfEQcm`|VTVKK=5{v#+dkY>J-fEIo8Gf2UL4`_*|n z>z-K6u_@glUdiEiFSaat|CuPekB9G1j+^`E%bv2LbvDzlo9<1s+&NbhbWrINr%BQ$ z^Ugf^I%yuC`uCD9<z4(;zd!b*fPy9-6f}s&%G>XDD|fMc3-s6PzvVr3m8N_dw0Rq0 zy)!HKUD4BHZ%ezs%2-r#73zNqm~%%fVdu@YvAOFa;*MRv7TcBds&oIOd+#sDZ~F`y zB+psCZj<UI+mCMYesx*vR8B|hUy9k}7ZzaNmUAqxCH34hmmj|Bran)EuirRnJNLfS zVXM1*+GkU*hCVqH#QRN3Pvv`1q+ia?m8rY3`m|54uh|l?{kE@OLb>RD)B9hT-esn* zX|;WQ?XKom_RTlbqTj8`zq{;WiGB3DhPB09mYSvAy4mw`Htcr3a#%1fPW6>XhV9P- zcb04_@Oc-&nO%AQmG*6sSNv(4b&Dsr34t2;lP7Zvi+4?%9IeapbkCPJPrP9p>D>G0 zERC@K>2+$^>T9N}Ex&v2UbMCJ@e|D>drvs8Q@7vnGIZUX>*mTiYv#tKKV5lk$=rJD z`rQvtUJ1`Qp)#kbY4SVW=d9b+_qzN0tvePgu6tgL=OpWuM~-(THc1wK+LU+i^N)>R zdUo%N3HU5ty!R>3>-SHycf6CD@FDbN#N=zsqSoqhuPBYyyI}RoZr8g{*_Di|L+5yY zH~Z+b%k`d`_2pmNKI!GlANaMX=J7I>Ir{g?!l(bw6FqBoBaMB{{;T3!{)K7(Iye2+ zvfW;%ov+*#T=)OiMfafJllf2iMt$G;?daw`{C8vRb@lgOtA4cZ(b2d|ySdC?p8Aws zHCgS_$z+MWRzElTeEd<8d2E&X_G1;n7N2cQ3X2@iEsiryFP^&Iw%BjI+r>iyF;8@k z9zHqyfoVbZ%+T;j-VeZ`(_CIOb+*}QzFNth_gidN|4`e_|G(?B>gK5;)=D>o^S?ZK z!s=W9VC7}RffT`hbx57)>vvABjnKTV7tbHowLIX(%r(1h)_j<z8LrnkH9L9fi5H#M zZs!Zf#?{@k&Dq~&eDn9YifzH)zpgFFpSdi4kKL^|S(7vN9h56y@UL%LMx9TT&pMTD zx892RPt8!;nY_m`-T0aL%J)eh;-&9>neaY<^Zc?Mp0C9tcFz`3?^mlTEfV~6QZiR> z{q&x)Sf<++KQB35obdUTiet!$$gcLu+t;dZ*FL;{*U{Y$^BX5G7x=Ekf99mE&UNV( z8#cWXy%Q8tJME4y+Z|t%(=+b+cb53?0Zmw>ZxRjl*W2l!;g>h#GpjRnwkY}G6RkIw z76ylHKDV3yxlxAA%Xw3#E_&{j^jGzX%j>t>JGV`b|IEGPt=8$ud*7cqRVMZIfNqNU z-$!93TUYxoddYVCO~b8at?7+zy(ac*zG}N~znym9s>@^3<kcPDeP8{)^XsI?`+&}= zzJ-&2mF<4IozE6B7BGK~=G-}3yF#y3X5IxYj=KH#B=0ZKtijSB)|J*1m%X(rIkfkL zbLQ@SLSf%tYVDeuy{r3b`pmbVleOnGMcM94y_I_A;9Jl47gtZ7e{P!p*(`2X+a*;+ zUxWB{Rg?GpTvQym^`_@`vAAh1$AS_r`)<8gH#?*D=hi(9(d!@0%-L$ZHh=Zhw_7xG z&F|-I-+fDER^EoQd^*b`qQ$PTo8}z(zEf9i_r16K&gBG5tWlr-qM$MIp}nTiwL=T< zFWGngt4~{TyVni(!~J_(r}}Q)={_re=4_KSh=L5hKXR*9m}xAldcSPZv`6orT$}LH z`Fh<Y>+Sy!oDA-$p4k5S$=9EY%-O%DKGZczNZ<7P!`dB}4(ombmsxhE?UUPu^E@{$ zJn_P9^W?m*u~S-8!(uxFbgz{JuibuMEh?^Vt^R{)t1Hy2@6Vk2)?{7w+n(BJ)4Ms> zci&RkWi#m=U&Z0rGry8k*;QuA3*S$<zI*SdkjQS2>66X(%Dwq8SHybJ4$s>8yNx7& z%4%)gwDQ>1ou1cUsDXyS=FR!@;Rs?ACaAG+^!CYUp10TXAzABiX;Hpi?$c%3mMiqR z^XJQ#%U|ni+Pv=T>|LMBpHx5Ujhh>@HFo-$!<oC~?)WO+4${Bn6L`DS^6tFu%ln){ zBG1YxWu#7v(e;yD_tJB_-Y4_-UwRCl#IC6e{?r*(b^7i0&S}%*Uvuwxs#QAK_I*#e z^|kxjr>pZ;FN@#vIyP6#w?E~zY((6FpV3pVzkZ*=dH=cD{G9!_->F}#{cGBhVzpD| z!_@A})w`nOw(py~LaAx?mG3*XCr`Y;Q0Sg-WWD)b_gQs?d6zCgMhS`%i<X6iuPK`J zcZ>An+$^>K|NQSvKb!5R<<c}~RfP4<zj1~9`;PA7`(M^lXTEjU1b)c$q;uZxb#?2) z?rd0DXQ(c`b@PpHKMTJv3@h3G=B~$)>PNkh?l;mVQpbBDn{*3{P9Bzn9j}?FWWE2G zUtIaCy-VXbcNe_8utnxQ=WdG^`*Xs?KIfg%ondyrZgxiT&#k)}Zm$Wlzj^zd$<1>{ zd8$ifefL#N-+fDImfXo{)(?EkyMN>@^7>etxBBF_-EZ?Ycdr*nQrSAMCLk~9{_`qz z<$cbovvRT|^McCnb})krmrugROIKR%ep|Kw>ytg)xw#X9w?6Zmw`#(29>{2M$K>Pc zHIkJ+i`3QQE5)N`fDdGTSt%~%xJE7MYlx@o?b4<fhL4ITKYDV}Mc(fo=)BEeljW`V zcYt!R7RuxezdHX``<-*X@0Pdjnk?*M4r-j9VOIB#29KXC%~|-pswnctx>GBB=PaIA z!wYHOB2T=jr<-1V8ZBaVpxVhU>fG*}Z|mF(KbdmwUYu<F>h>%(YqmEE51xRge-BzS zSybLyq^^Gc+1B-a^Fagu#p>JJj$O@mKd%Gt(7<L-)z6%KELm&u^W)1)IqQPfgsd)_ zH^-7up();Ude^SX=ZoD7ikc*LfT!ddC%X&VTK;T2te&^yt6z4{_MrEEdPmhPCw?+K z|KLe><D8WTOF!Me^*b%z>kl)$UsDI&Na|}eyJ1r)w`PsB>E?iy@0QP-qrheWZYe)_ za?xeI-#@;mPv*v@U%qzod|KhB7ZZ(_mONc+zdbaMfn)aR^*{dQT-11}<|ill&b98V z^!h?S=9ZKFe{T4fR8G`Zw>OKOb?)_|P0-_)1q*F==G7f9ubW=1!>}O!-`nz<>nA^N zcKz)sv}W@EqxJvg&!saQ(E4%M{@;ZpO&<02v2{na=bmpUeQlPz&#iB>%rw2Zf1bod z&e@Z5<<^u#u#=iWQ;kzEP3?{<wOT$udWFx~ss3lD`k%`(?6*F)Pigwg`rkj6*S`G7 zW4S~q{n_c6-MiLmZ(U`xpQ*CJQN2d|=gpkT0KHEKyX^FeuAkHgT@zCd>Z=?-_~O;c zr`o5*r?1y%cjRleQrpMuD&X>a!tQ5ZYJTo?t=*Rpp_{>UN-tG;+T`%*TvKo5+?&AE zU&B?d;rK<W=(>lc*E<ExVAeSQIAeWX@f$sxZ=PCd`TB8<^@K?i^!4K7`I=<9o<7cz zReGLa>TLP*Nsrm=>q|{8J=^o($wp_t(6i?jeR_H;=3qtMMy2mFL{!hGJeDi}dztys zllreG&;PiTEcH2c=gM>XA!(nEeai2WeW%UQb*wvPOO1lwC&uon-7!Wlqs+xC_fGbH zrfBKpu=M@b!lLa4fs>mR+MW0~!lfL)h<(#7t_z(0XkW_opfyvZEhj8*%5j;ezsa=n zR!aBPGp?)U4(;-+wRRA2`8{KMON>`=(6ULBrrveCrIo!_&RTk_R$x(7=$cPEyQ@}h z4%{7~3JN6|f!z_R?knz241?ZyP!|0?EUa(xaX!nyRZp~T-g8~6RX+VmlhCB_qc;00 z?l(Vrvc2|Ie$C5|Jul}NPBwnB?3CEr_`gqos<zuscrIR&QlS6oAXn+c(+^`cLf>}Z zc{9UP{p`uP@%27G^@;?Z1e{=;c=(ZZ0E^=m&Yh`Ge(JD#ozz>pBYxtey5&h3-%q5i zI<5Mza;Nj>Yw17B8WcLdE#wNEblh{M*WWC$keSy`xt&$L`|n}SMwKYNn;BKyIiHR` zeSO+-f^(wi>a1^vFIa}04fLzi37%AXyBu_6<EC3bS>JA4e*V?fS;ovtj_0Pdlro3- z?p&|(f3mdCxxIg+Kks<2&EGk>{?+CB*WUf<E1b33x37rS_t`c-9uz@b=UwwMe=@{A zX%^KMuROX+WqMQo@$NkfUVgVXRP~z&I(u$)oNa;n`Khbj&*|G4&MXW%?D8%8Tinzi zPZbK53cAQA-ZwHWe0J#6WR)3@_9@&BWR*K>kow!wH!tY5ohrwo-vyhiHG?Df@4x-C zOd)dnt-d>7MNfPAoIH59-#c-Iz8)lsEOli2Hy1%WqTthkzkvI{EhlzP5>`uhJhfg) zcM>a~i_M1z%8#DR|M}*5&C5c*or|A5d^*M8*8NZcjeFgDE)~ReFf4wjRL)m#?RPfw z_;Oot=X05e)V$~|S`X)5nXqxa$!Z%#kd^Nr2(VmCjqsl|>+6wi-M<@Cr*Bf_e66;X z%jT0NbMQ08jvcKU&AXhLPjAbelXGRK^I!Q{hYGqv@0z-y-#M`+Z7*nDpzFD*r<P`w zl|FJfa=1Uj@89<Mzvt-NUQ3jZv%K=E!FdYLBUif#4|kr}op`G3)6F??0q@nfgAN0S z^*uX3Sg(Azc%8}j00EYZ?h)s+La*_^nfM^#{=#e1?)ocoESkUJbjaQG?{^n(3gpW1 z`%*M#>SX!74=gHYKWq1$8^cq#a?R|Ui>`8C^lUv5s9xRhXks(_(UbPu^XKc=GC2Kf z-kR`0?-L{6&-K=R=cmt~3tdh1vu`T6&l&q{pUUjH8{OqggOnS!dli~Ef9lJ;vTIf7 z*ysF@n{iWM{fYY6f{I6X*zNy@hWf{8c&}U)4w)n7R?S|)pf0*Vm_1kh{`UO&#=H#7 z9e?$dbfYhvZZlSk3GmaKy>e#Q`inQ`tb4g^G8Y2_!-N2r6KfNz)`&H|ZF`yd^hp^1 z`QXbtL6=j37DX^@VO3|BC{a6qe*f=n)&A$ZCreM_ULh{W`ua)g-I|O)U)F+;*=1m0 z@X$DJwDj@iTR!)y&IadWxwazr;7LZdxsZK7$eosdN1l9<<*z^O$qF%LS-1L|#44}0 zo6Ectq}Ai2G%l6NRxzlvdoZAO0h+hH206dN@5~gxbJI4vI-jz?_WE*FY0+|f%j7+d z*B?A#;CujDVurH!w!fsuoPmL%q2uJUt?b9nM}^9|IzQQU*1*=nl7-EWZvsO>5lH&# z;(M)XM^_yUYS(Mr65D>@z)41-hAfPmCzu%+9IR%{(JVFg;ZNS<nDF2UL$e>|4HF=D zvf<vfx(%f59QbPC_P0;I!%xR%U|`^M1#PoKxh$fD-;dAWg@*e2-;U-1>fw*q-T!+d zaE=V<vikm5|Gd5Dmep=t)j9d}re&GEAI%Cu2i?6pc#@G#_URM#^wXa!_vT!2S=bz0 zbTUTo>YJ)hyXB6aWMp7a__^ZWlW#j-gA&2ZC#i>Rs-{&Hy<nUplW-vrbe`Gl)6%N3 zSZ;S<U|^VZ7Sgsjm$!?>47v}&IDLhByW9bYwKy+sU|?WSk^QQ-#qRY<-{O;npEgI% zk=ex#N^nyq%b%XI>~q!1Aa2mmW7Jo^S72AZ#C09R3s#U*3$g6P1O-fA(WjF$FXhBt z=UJ_3<;S<Mc``GP)mOi`)icBLmtEWc>Ko{!X$FRuj+Q?=GkxdmSrHv7Yhl^K2MXy2 zPZ$^&7#bJM`SW9oS+4l%TPF57&z~$$<F0=HH_h?#TuBC4%HHtYyZz`%<DVPm*o3dE zt9^7xT<%vm==M|wg-#9i=}A{h;_~l<x{K4bw$6-6-3PiJ$EtBMvr5Bc9G4(~lA_8Y z&|%XdXZdy2^8?ppJ$kZf#?vQNxn}Fr3yWSz&5==H^f{ZUzRcS=%y#G9k0+1K1YL}~ z>0WEty0{$?ny)M@L7^-OSwQ{jiMQ!x9qDH^2O|!gT$o)@)WBk3y59F(Mseldlq;)D zgFp2$%#A5pyeMv~*26+jPVg{UH`)8-a?k+={eF5&H+Wr*0WW8k*~JRUl20dZj@p(m z1%7<Nj@}L6EaYLM^dxJ>yl=5g(Uw0a#l>2g$N%|K+w+m_ZWAc*XXZRiPHy)<pM7&t z;L5Ja(Ldc5_~lJ2{XF})aXI)900ssIg@ryb8nW~Ce4l>_TL1SX>+O?gSI+$N8*<Ce zN@%d3M7jlFZN%3nj4yZef-V?^pLhc{sAB?j5fb8TfX9p6ZkN6g0|g*x=i~WkKgj3; zf7l{;(FiVEq7Hw_r~)0OV72q={5>IiJ?e`xe0Ro(@t5D+oZfHo^Q`&(H$Jyhj3m=D z86;RR&-e%B{(>VX{UeXA%DTB?tK_ofdnZd<SZ+zLsEDxHBl`OKdeBuM+)tlyyV|O# zU+=jUbMDvH8<65qDeF#Y_KbOlyh7dk{qiCnue)3(d&}6&?AecUV>fsAxlb7q95$fu zgaegIlOW~W3cbd+-Jx%fRm?scy6@W=%e`K?Y+DwGhFVU2!ochfK1}M%%pA+;koQj9 zL8nrqm+e$BgN!2CfJzjFhd$@9pYFdva_y>9D^=JfERLz`pGdy{%W=DkUmW-0ldfOi zSJoumc7I<K#0biIU03JVfYv=u^UJ$3t#AJElMA(_R)clAgw44lTW-suzF%6Moq?f2 zL;>6vTRR85$kTdz$7E-7ld!45o_q!!8aOt0fxP-@=A4VWz`FzTLXUxul`iSrzG{wF zQ3Io^<<2Man=50VM2c8Bs864>G;5aY-m2$|-63h)tX=)w-9IzgcS|l?-Z^>pvX!fh z`sOU1C$sBlbf}-I<$;Dp;LYl0`68u|&FXLC0@Gk8@`Fo0^gT~i4xwNN@6b>O-`4#l zXsOti$?-;6-j-{tjypn%=|0p=O5!2l=xFYK{N(ad?wwsvm=Y~2_v!fg-7W>yh!&?# z`k%}C%<6pkEO-GWzu!EQC4cs`ZLIwKj9c7j-;oYxhF{C>oqStWbW(_E*Lq0q<3DwB ztzM&FD7)Xhj3o#D6zBhr+^uaM0p6?=Zd1p1K^t_$@-+@+aQWb{UdOt!@YdQ_8G*~P zo<BK0@ATgHk3m~yjhT}==R|56{=YIi?tfo@ob9ipuQ@p{ewww)tej7Xq2ws!Y~|H+ z_5`eJd-CMFePP!1=kjIXsGrnPRHPZ^``nu6^5sjQQ<h^=_hneD6bN6kL+3fS`u8@A zopGD_y8kw}7B65}AnkW9Yf@!O5#)Hp;-{~69xd7!R17oeQ>RbiQtyQGe(Pp$u4Gp4 zw=9Z!dd17|d)Ayg!jGOT_3~XGmH*ZGBx6-lmY=m9==c$VUz1mtFT6SrbjB!y!pk3X z_V|Xn3#)H`9eZ|D;<=|^Ta&JOwniu|57`ndu3oR~w@>KN6U(((d)Y4Rdb6>pL2kyZ z>wXc<6JMwv4r!jq^7@JE-f0tiUxR~7Me^wrcl`)I(601i&}QnJD|Eq|spYbtOgVLO zRmj=vkDtsFP@nD{F1+}_Nye%tps9th(_+1wb~QH@7v1d1YB2>J!w-sI8{wIg;HU3z zUlo_GH*G&Sr=HZ@cS3Wj(K?a2g+=)tll7;p3i`5r?j6f8h6@v$mf3%}B6+c>@RQfo zEyuigZk$}}7BN}8$lo_@P6(*hXfY~WSfLX<=bUc;$7_2hb5ENbepdK=?336GLw5Ci zsYg$4CWY$NE^eF5{H38v{MMB@+agwl@f3bi$XB>I<B7|ro7HmjAH-&W%C3sObgyr} zPkwExvftTjeBRkweY(+2*WPWfH?o0Fjkk2T4=z8mxsPs`vj^1hT__1_TKXY23*0LL z@3UIEv2{`7<l{1PKsNy})D~NTk3!~llkj`Tr?BcJBzWft8!rt8or>fAbGh&I1K0fG zOhL!y9INOy2cPK7`0E+k0sN1i^n@@mFfe$!_3qB&z5ICPs~2}qc3V{5IS9H~g71QP zne9&X&m8agCgrZI`t;KVbbAGZ!ow8MZDiLj?34wcgE>+1*W}~!P?s&nIC3A{N&=OK z^PmSF?>4;GH$VN(*B!#j>i?e{JMG#k8lHFO-E8UH6M7GxFw`zMhIaTq0|UdQhO6`U zbn7*~eRZ<%(+^>Jb@`onFK+p-+HW4a^;%TlWacl&H%)Gj^j|l-+`di(TrM8j?4`ax zWaX^m1)pvR%d4;Nj$RkB{aol5Q;s<@3+zFsQ%pXi+*5dc?ekF2^^ZWUl?iM|PA-4u z#eH<u<+8o5JHf5Nu+L7AV~_hS4NHqw%Ub*K8B`#heEd=90k4W>cg}{0mG{1C`0;@n zpU)xVs0*^{ZtU|;C{_;-m9(h*)46hTus@%{3?1v8YJPE7R)_9v28})W<y|>bvvb$~ zi;yBkW%ktag{7~AZX5xhy#_w>xKMqXAL!<QOY>zC6avAkxaY1G(Kapo#E=a-2;|X| z)~-tAQu6oY-DkPyTXs)AK6i%YPTO6x5A1l&(A-&se#$*KnSw&%>ND=PWwT8$=A`${ zFZ26n^7Y9^^*X<O(|oVpJ#doo*WuDn+<CS;Q#cv#x}G}udD`U5^Fh^|P+!rf$CsBz zu8s&@+qKQI_|JnU&Agzqx{DhAeXy)NJ4J>O6cY?DW~Qp^m%S0{n9OfxSo~=Riyz+w zd2o_-P|#2hk7aW8`BhjHnX9(`yg0AAXp-liId`g9Z|yprzw6k1xk^x)C@%7wd`5Zl z`YBpz5`Ocv!_VtZbNw+FoMj;my_lCmH(<xdKjwotVxJ}I4DQ09>b#4mW<qkh%A?{> zW}&j6ixpPST$Xm_+2^*7-pO1WRpR{QW`jJPmbI@2ay=WkBzykk+V7J`PwL0$OfLb~ zN0WMrJ}nmiRaz7oVWJ;xAXf0HqIt48?;M#0`KU*^SH+#|wVZqzT6dzJ-yXW^na{dU z;8QET{64x)Ei5dGfAECiZ{US5>uoGcv(~AU2i#n7b=sPCp9H^sD(AIV3r-WNgEWpo z%{+|r+l}5;oq=Xv`K&u%FMp2Omf)ecAa6m!+&yb%f48aYDZCEKksoEwPkHlw@@v+w zbw$$Y^V+BRtqVVUH0bLhx7%MMVE#ClavIU)+-&9c^4ZCkcY@Eu%F3doU0>d;F$*_% zQ}t;YY{Kfm$z*u&PhPvCs^}yuQ+d(qd3OxnZhH+c;LbqSHBSHJKO1FT<8diyIZ|vD zZD+b#SLCa~tCM%9S6u)nxJhRpb{3o0KRcMWi{%kKt?d(3pFfNH;>o9#t&>3wn@2Nk z?Dv1)r@s58kjL$>2i2-Tg~i=nugxm|a~L$;QuE`xV7}_@t`s@Y6{YVKZbC1wo&)I^ z7pSFg0UhWr{kXUA`s4Gj=GOf7bxztK2fE*(UNYaLwCHs{crm}%d((oVhOMr!MO&2{ zS{^=0dd%PJfA`nVc1YT6N&2e(ev!9=pWO|X$4|oZ?%bPjPb<o5=kAHo>jYHyy_z;P zbQk{|nS|U(_=x)+ZeCFP?|jzWJwc}ZbK{SkO!kujZD5P3PMx3CJDGWn?x~Z`ul@DT zYiIXt-z{(31@-iti_4yQ$?gXAB_ppvht_T0wY+>Xd!5kM&<e2^mrmNAy*@kN{ZQ2D zhh2i^M|Yon`X$c!+L4otzZ^h&uzgE^ina26V4Ku?^0Qao8PGBxP)d2Y0=}9Da&0b? zpIot1anZ-D?a7s~d$+GXTUTFZp0qXg`?}jz*7HKA9KN2rCth(nC=WSXB8J*O)f7UP z`e=n@l?VBQib~Jt(7pKc{no8AGPzsBrrvLR&|>FwwYs?H=Sy$B5zWy*Yo@eu(_H_& zJ$oYO7jN~gp8iX`i1Q}stVn(t_4%5<(SC8OuT4AiAW!jQ_2M)!t!Mw5!DWkzOyQ^U zJ5|rG%z6Iz$zKc5X^e8kO@*JHalOqf)+;IbG`07}*N56ccXO;uOJ8ay<{n>k_{Mu# zXS2r1%wHN|hqjjoaQMLwZ3i{CQx?zp^8~s`#}~BX1hi*<**u$XEzh1z^VnT`Xz!`J zt&^))AB@gf-a9#d`^jI^tBM-79w<e+64%id+`9w~Ei5~FvUif6-@Q!%t&{o95-ltD z8dpz^&fNT+|2|XL4!?U@*15OWS)0D?t-cC6KKyUsd-$!m<$~bq2GslhIP;Q^pZ?3V z*{k^G)NJ59eRA))oXS#vzjubOrrln-J#XgI+spPYO8@Zf9+Nuz3(&<{3=9eaQzn;R z2KB2?XBk)4g4>whhl+}(zAHGobzW+e)lTvAY|**tJ8$nil)3WV-DO2Tj_vxA=M)A? zFpuF&cg`4qy6tk7`+posIR@>0fldVi-#F6y(QNYJlaJ56nrkx=6s%`gM!v0BW->SW zpQCw#y7}j)w~D*NRQEte)LdT8-4pxyFz71W$oJ~zpe-~<j(N65G{H($P=9?Z__~eP zf1jA0+jCX%wvhUC8_y!Oowkttrm|?xpBJpqt2UlJ@!qr{BhGBS{(~nU;cc#Y*Zs~- zeg0|Jvg<nP+l^V%@4cE3<58r%(=h#0l_%)l9R`JyKJ(`9|9ek8bov3iS0|@05eZv4 zi+ky-qe6ai*#)2*;+VhmTKrtObJ88hYuzT(*R=ZtlutxjUm^<bJNv|FMET_*-*x-( zv$$lr?Xw4<>*?5E@SDEdl~IYSbVfhmSXf>B$jPs(EN8E-c{{VXYN}Y<M^;EPvR=gG zZ{u>m?#cQhtJh6tZw2+@!Ns)EJ1fu_h79JSf*mU^mf2o|x??uR$$sGG^<?9vlQ)NL z^g3mqy9;#M`EL82j`g2rz^Vp6*pl!d+nrS_+mA`)gBlYVYTz3&JXfz;oY4`pIw|zM zU)+^Kgf39~3f$3Z2rY!{?%M!bb9-x@{<KwFV*4$j%~Ut|JhH6H?I8VIOWuNfvZV3k z%%E7<eN9M18UpsvSULXW=g;qV%HD&!=Cbpf%8NFBge{-dVqjo!aI!QEo;7Rp?RDRy z{m<>bz{UWnZT>F2*D3}+^^WDe6Eg!t!x3e0pZYCmesg;RyxskG;T)SQ|DJr>v+MW9 z#gIZqZa4G>c0KOfp^{rWi?2*RE(<diw1scku9|Kq_E%4?efBb|z7EwjCnxUrs~<D- zX33kC7iDL}>@EAk^YuyL@z+nT-`f(nrH1#h_`ixDpS0WSUdgWiwX{Fy)7dVIf})0h z$Y<i(#Dm(8$a9yVh%<wpBnQ2ETx51g=rLo9$~T2`|MdS$dA{uI?6~i2+HK1H;rr7b zm)F1l-od%M=J|#4xR1^2|7?7?y2iUr_7%sUOTFeP-EN-dg+&eX3ZRpk;L~w;w;p-l zJ1cTU$oF7K5$-<ckL;<F)_cz_TMNE1*3jLua_O!q+Sk)Q9oyM@>PpPdkPySdx{v#7 z9~px#idbm#CwG6z;rQB5o45a&{{P>u>;I>C3D&*18vgIv`~B~`+2ua3m5!TpHcT(( zinv$kS%cM&ggq=Bu4_OiK9>f}snJ{>`hLMYP#bhoU(u(@#i@m#HU(w}hu^paT9<kG z%H-p6PoGp>Ju`jvXV%AulAiu?diuucsgK#6ilj$ps@?2=)auvHjQCz&cYVU2zh6H- zzQ;Px&h&5R{-3+I|8Flp6{Gt6Q@fAXqBEcLBr~R**A1B$z2?lb-tJj3zn00!%#m48 z9izVg!IoJ5dncbJmL7M646;51bqg-0f$lPoOnP+YWAkKwv!b}CPozwP{WeFusM)Ax zWi{D+S#g!e$EWRb@;{%JYn}b~P=4p9<oUm58yj2RH`+HLwC=s_`{}J$qYf=wegDJ7 zyY*kU=GUFx{zS`p-;SEUJDWB}tP;~U-J2GBQo_>V`xWb*DRPsPBlhQ5ZVqRM)do9F zef;lfyn<8)4<<g^G)I5$t|gLb3xiHickaA-^wGWZf8P54Ig&j!1a#fO{yzr}?@P5h zW_*0!-OnFy*FRf(ZO4nQ@P7x|?*F@c|NkZXx|`ddWGxC<H??GQQpEMWG2c8a9lj%m zcR@ELzP<pdN1lssIX=&Bb$IqUo(|Qbq^D1=y*ae5MK92lxo7k9dA}dX-~Y4ew4QLQ zoRrk0{r)!9m$v(?pQt_M-M;7E@2jrouR6>1`uh6%-}?U^fo?T;^0<ckyNKxT_??fQ zO7WdhVF+?|y!^gC$!m@cq9@QlC%z`h=<yOzH&#XP=@Vh_ZaVPL-AnMvBofN%;aq1w zt)G*o`PJ)$WK3<%-`D?Z9{1j!Vw`_x$H#p8?>mz`KkIJ(Rq^TMa=T9xW7o^dg~_X& zxIanh<vvyGwqNgr&M_A9o&SIT-tOb43h#1Ou^f9XxS_eB-a=U4pgUB?LXt&bQE&NX zxuk2!zG994I}<sSZ`|}Xi&JpU5R+V=bEd*%qp?`p!yo-D0;bI_-)>~zJaJ=MQorTy zNgk&cxp*z{h<oLDQ=~FpML&Mm`hB(U--ef7U!7m~e9kKnxc+uk_3yG;`MO=J>`LpF z`_GMjv+n)8Dux3bcXT2?ubycCV%eJ~bvxhf-M>`rVRH~@6eDxV<&(c<!&EJHhJ3Es zpSHVoQ|y{uj+!zoTe|zCr-lB1S3bXTgX+oozwbPctNmKC#!qbHo;^zMf6qK$^K9Sm zcgFdDAM)4#0G)j0UtbloOJwyOdxnJTI+^P6`Zq;C*A)3~$g^3ZTUhkdZ&JRR;J*bT z3=9kjQigtYxt0Z=?3T-`S?!dl*_`+L=&H?;hffwCId$sP<9>TRH66Q}A0HAU<D#Ot zuD#V&_n%ku<)Zuh{r~HfpC4Lo_jTp+`E^zMe=$#x&&$2CetmRn*W%|VYk%JJxOnpE zZI4;8m&@gOy+EU*%O=jexx4<)+WE69KY7LWt#T{<^vv(@SM%&wjX{o@KBnS&F+c7+ zzqNd&{pT~rU#n~*wy!^P?wsAvCzIv>|2Xb@pXKGf<bGQ<S-va=hgBVu@9RVy?OHoe z?S@JD8js^Amr9=huInBvk$ST(05sKSu(V^s>f2vd7_<DoyKMRN$>!31^~GDiwAcT1 z+L*(to$yNFquAfRdCTg4eR-L1w`JqjtzQ?*|MjS<_)+lTKyl=cKhN#;TQ_N~U}1Q? zu_FI5f1hoAw)31j6Z0AWzG<2=cTe8$<$Cw49#yYrSqhpm2|jhlE4S`yl(w~UyuY4D z?Cr1bMYHc$Jv`f$%D&XV)#qI1tKAO{wQ~2{e!G$X?^(W-rMTVCll~yzZQi`uk(c3y zsP@rQ!N=2&oHSpZ_u@&WVy~oneRkp3_Vs^^G(fY3GlHIlt>*q^W^4L&&a-*bS-us1 zdX_e|`1<k*owmNU;ySvzwtv4|p8xC0@-xpkzTdCk|Kiul$?DBg3<gTuyLpZM_3ksx zwAlGLKSbtSET~DmGCgr^S@PbvHC9D`9(N`8zj|`;>ytZ=bE7OAmalxzbaU6^<Nfvj zKF>Ed{(q?U`(5?h8ngFoI+Q$t(d|Ll#(g0h%vP7VeSR|Saqg6(CwCr~W?*3OF+RHK z>!qjGS*sSm>WKNi)0f}R?yt;?%U8+|K0Q5s|F^B{TkC5DQhrL`|Is#u-IQU0Ik+}H z@MA{$!jp+t!*UO(HqO~?clL;1aQ&~B%lY4BzS^CTn)-BR`Xhdu`Y#vV`{nKDtuADc z;4FUkEA1-pxmbVyQ%iNfF7So;sAj{CFzIJzws#)qa&^vKrWbVT>(#sbHq#RyHa=%C z4C|V@-@>kVw?xd3DXo*cdyD%)bE7AixwE$}b<+K1G27*r<<CER-?s1jA#3Tv?Uneb zbMCT#H<J4w&M_2{uh45g#(bW!<#hMyPaEfNo&5jF*PG}6{w#LXWME)8Fh$9)uDJGt zYUAGZ>g9iS?vA$j>8SV|6pV5ed>48PKlRzaSoZ44vwg4a>)uL%i~QjJdFtW)n_t#P zOnvYq==%4ow)fKB=RJBN%(r~yawdKob^{6Z{Tt)%Yuqk9F5K$pfAZ<+)Z>>wKRG}5 zAZT(h;g{j{$*+H}`@Y-P-(P*b^}nswXD0jW%~>{&)#igtQD5Pw*3i`fWm(%SD!VQ} zvHo=S(XX?s-r83`(*oOm`RvJ=t?u(G%4T>o3D3Fnz1Dc@$9uWYPO1y~1>a{*@u+-Y z`9$FHlh3QSZk-gnx%PVYvW%y7#m7JX@jCoh@H1%G&EV~f^o4JW=H2-|yK(Y;%|}lr zGcRBHUfkw`%%|qUPdlgH%DTDEbPvy*J&~L4$Qywh9hdtGKS{G@2cMl>ed=VhX<?OB z<<^IBiSufV9+-UPY-FEz_=>Q_&#c^?S0>~)>de^_Q(j*&s}eLZH>0R$vi`cO*G_MH zx+3^u;U{L!<tzPlY(B^=o8+hd-6lTv?3Lf^cP(xNcdF|Q{Pu0g>YN;&YkIYDvb>6g z?_Y+4%;ytlfo@u5U<f*B@$=8Bt*iJ~|C&>G<NV3|b>Z{s{(<tTwnDXq@81W9n9nD2 zMQDc2`}4BL;-{CTwz~e+yXI-r>kD3qL!#RxX-*8^>af#g|Gk;2tt!_(Tsu`tI@DaF zwdbM9*UTpNd4~@^J+{kqdsM8ZX%??Nv-<bbrSI>R#kSZ(a<W^`<n!x7&c19vb+TFp zT;K=$<yF5<-Q6)cooD$<e{-7;GJG=Ltl5cMw=H{i@@uRAtc1H2C$>+h5{tSUdoM2} z7d)1=Z03x~-)Fw^DEYMP`R~%>_g7fVwx~=im{qlI#peUX779AK5#8Bg3v;f^oc~$_ zEs$4a?amUC0}b#stW+y0vi!92%F`8DF6z@4Z)kg+A2xTbl;1qNIm_l1S3I!vG1}h! zRr+<<#z$9V?`OYT^5V%Qp9&!{Z~_YM=h(T^*B=xBmX(*wW|y0<x?j~;y=N)g@|Dg# z@7U+vumAto=7Y?)iBprFu6%5~-E2+L)yy4_p1i774psmDdfWeJe@^ko|4fAz)@Sst zKMT)Zt-9On)z>FYWkvOwYyUvY>ZKc^EqrC!gsLCxjIiRjY2Tav@!m0cnd-Wg3Atf+ z+h(czdmcBvG^6lS@bu~Pe%#ZB#L*Nbr+pi;L{Ish{rEdZ=*IDrvuB5<-+pxG>&6Er zr4m!$vCp&r@t_&x!k*hlf34+x`s9=DgwDyYXHSjTCO-w#F7eUi&fY5h`jwgOw7c)k zY;EVp#QMh-Z{InuCcI#lRgeF7=JWP{9`b)aP<&!m^wD2Ij`MfVyJ)l1qVncO8A$xd z6n>ihYQw3u)^YQ1fB8~g#ID}2q*U_f$Hxb*{1(2ln-=_Td=4tGD;`*;G!}k3yK3&l z$<ck`8Y}mUv4d-s%N;x4@7m?-ztr}s;iAdbulBv3vs=zp$76{`#YNWTD-X+E_<NxE z=FPH?2Z~po|Hs*xp}yXAzs;pX7L|8DewB<l1IiBvOoDZy^<($t>T$lQkGT3?F8}q? zV>`dUyQQ~Tvddk*_KHS8&Z;?=uO!A#kk$Wo;Pc^je*XUlKKEx^u*)Td==@$<o_AO8 zT6gGYoh>FyV{U!=yX?k~-m90auUG2Wg9?4i?(AtZU%jZGJ+IDh--mzSoa6tT^V%ph z<=G7N`8Ag^`W3F_a#{Mys<pghpVyuLz4F1%H@lY2TC(7&z|&8UHr2dYZU5rhk&}CM z=EQ{jS6_d=?%nzM+>rKyNU815Uk^Z8Z0BRs=kFgr>6)zWFV)Cd`R!&p$V7pOZxiJz z^h(b}Icj~_uELRNU0HGeE6<!i$HDc=6NbW1iFubVpFUYGwa&i0oLhbV+_}8(t7Mxm zUrC%aaqi~p%;!@NibyTt``*ReT=+@)*Uu*hZ7MgYu`ba)pMNdq{r_rSa7KBVUU*h2 zZI$xDlZRLKWS5&4zk8yst-bJ)%g+Psb_V9=;vq~ka(2mA{L|k5N&8?>_u+Q_?^YLO zi&_hde*TNlzpZqB(FIMboi&?x?2F%eH~oAJc$O|<*UXuFf2-Gj{baEHrDs9W{qJW( zj$O6hIZu84_1A&Dor;r$uP|FE%wV7Q|K0n4c^ibwm7+k6l?7T)M8PHV*G<7&Atm## zRT}$)%IiyDg}d+X$c)`ZpO#tdO#L06|Ga9R&7LHiiFW+1%rjEts^4r(P=EJm-|u&i zi+biH&#B2<x-Du`Hm`oJ`u)N^X(x;7E2O~Q);w<UQ}6x9v^jfj6|7(K@X6Pzzh7Qn zUcayEz@zW=|GzW)zC1hs|Ihussc)0#*w-sc6nZqTUAwk<$9+EGhnp`8{d~Y~|Kq9t ze@`9NaKkf`pDdek;AD9A>7{Ko+$j&AJl$ns`FtHSsP0Uj^XJ&Et$~F)x4*k=ZZ<94 zR9a*??YI5DkG;R&?|(mezD>=BM+e#KeVwZ0j;;Uyi=AKoUqfg7Z_`rCckOmx%9A30 zOSJR<UzJgrb^P2<w{N%WzwVd$+h70K{<pvUj~`Qx=Kp#Ae`?|TJi8AE<M+OQ|IfX> z{;zr6-}m(<)27b<Q7!*dzy5jo|K0c0#eD7O`mK9@@~O7s(vRTELcv}_J$yO~Td?f! zhfj(`)ZL5fzop0jzIFXcY)6jsmOoR&{ZGHQJZ?6TFKz$dH}?Oh@Bg}f-#`6*wWX&X z9c<s9!Sg5l-?{bw)c+r~|97_joBsdV|39ApcT>LheewVE)*EO2<dN*E{}cT`<iGW; zlh5s!%$QugZ`WZCa0zRmrK`SvU0blMZQn|l=Z{+a?7r8%tpD3B-j%8yVW{+}?b5mb zeUsmN{yFzvrtam_@UQt+%k?ITrR|>^rvCr!;{VGto*({yJ$qx(p%$KV_P^HFXH~y4 z4)|ZHc0>Eq;YWLW-TQ6x=j;h8H!k`loPYPvt?zN1kZdRT_(@U3)+o7x*>V?mS{ys6 zn!EPOjTKgoFJGLn-c|Qm+v}9|n~5isj+~6Ic^PupRIhRBd%4Z`?LM9VzkFp$(W3f} z$@Om@@7JAQx2SLD-_O^2OTG8mgn9Kw9X@~Pq<87}cVT;PeQ1L8c#c^7eB-sX*7Ly$ zzr5eCQ`2SCr*EHfc>Vvkt1W)U9Z|1){-OTIP0gQcPwGpn%Cm32|L@-a3HIv$e?68D zO5bY#DPWC_zoOs2`2Umd>s{U3wpxyJ=J|S0Z`N#ZLtHY(KW|>^v%US`QgDlK@h7`r z*+s>LOXh)UOZ_Qt&#sc5($}$P`u#f__dc6n$Etq6TR{E)clEe+ET5}0e(G_4zkUCA z%)2>%F3+$1a6w(}=Zl5T@_(IbLhGF7{E`1R`To6aF<*I3?)m2&b!&szm9rjiW<8!g zd*TvPzGEj>Z`-cadmCI1`4}HNxn5UW{e8XXf)_C|E7jc-OOM}PV->yiuJult)21>1 z3+L4MJI(p?qgy}x)x5W_;!XYbX&?G)R_|B$DOo<y?B4}-KG|PK%y(aVrrI<4^z(VC zt2H0h{Bz#5HSuo5_O8(7dVYHI)m~ce{P{g}^IxZ%2f+=*S2JT*uJmR)&8){MGPhg# z>ymYEO|Nfz{rukU?A^O9i;RxPJ!(HQ`Mqz)<o|2usUJUiT=7nR@$)CIj+EA3`z0>d zIe*`}^O^rIr2B94US{4iIbTcNe0t-Pck)3;H^o;y-<Gk{Vy9JOe0<3KYZfo+<6o() zIr{XHb@$FXJ{txGh9`|TpT4@|Rl4=cuH&~q_~~h=m;Y`3zP<df&Xx<g1)uhE&an|a z^w%ukZ=GMv{}Yerhn>FPGk;&-<ma59b+#;R+8SCc-Dgob%UPlK<nhTSzb9W$uN0F4 z)i$=DwN3xl6zxu$=f95gnybKE?*kS)WhUoFC(qs8H~D?!gC{Em-fg!mE-HOgb$Zv; zqCEfj<0o6eHGKBwSyLxp&)pwUs&kwllGLZPUcL3Tbag=C7n{oSx4(3pQ&k93cTb)j z%C2s&(Kvaz(~kSkPM^H`^A&&Ho7V@uP1EHnXRbbQvK3U_FAQ5_5ou9b!5k?0Z~?e4 z?G+iZ`YyOv`cD4N?@109cd|^Gy!&6;*_(3j<?=0l&SUkP$Mvvowzhis_tMu&>gubH zGpUQ`<wlraUkk7MJ10XrCNt8`)Ly@uTcs2%+j%@}Q86crU)<4?{5}v5Ru&bNGFF~B zFm);W^y$yF3yK`iPj=sDb4i*x^Yod?`BN;*Wf>S4md#1JS@m+$uF`i0yqR2|3kj?& z-lKMXviyPrCxbz;{p879^>ykZMg807B(77x{yjE-*}EsNs)`CfaY4%FFPnFy&8#fC zEfdCiw9o})fUxe&{nOX~UN_%DYR=Zx7E<xn524|7{A9IHr@Pwu!cR7d?{?Q^FV36i zKd*K2=^I7&K}&m1Fu$t$qzFoj-UrT1etzoY)P8x(EjOw(>*}6FRKI<~4hfs})q4cj z9yl58H}9#<&bR-6e9eaBA=_lDpMHnGJ}-Lwr2F`lD?d8dePR}|sMKott?M`M{DG6b zlkaPsnC>q2JvRLRzN~HCpgiv&7ZJ008rRmdtEA`bzV~>CSBYNVmC)tlR{yr{o^4t9 zX>ohi`7V7qt4rx`kFbEP@1FeJxBz5D_SUbPbni2LI<I(Cal(1E%ni2+=36&|3_UQ# z*tq(;|G!sHZy!B4ou%vC(TTg#w3PMz)~)^hqH|r5utnuOj_=WPZ00vk-ahA!kox*t z>!ex|e7R1fPk#LK>8{_4jl;o{$}{r(&gs~EI<k3pNs;kX#r7rP`H!Els}+0-foYdk zpC7+=?KG*YZR*Vv9{KFNe@9S#y~!W>dB?yR{FLE&b@^w4n->)q9=gnZe|Pg_`5BOi zE&No&=9f38#&6D^oYUJK*!=G4T#bb^N#!0tF~7E^cT;S+jlYg=gs^*wp5Kcn;YCLN z_x@LXVivNf)Ozs5l7Eg($)~3U^J3~3v8+CR*rGDh((*dQ_sMf=5<}<QS$Xr(6Wjh3 zF3%r5xp4C8<de$$PSzcel<?@uPo6n8&z{WFzs~`VyaOjB)aS>qUOV;8EW2%QQlBm= zE-ZTSM96l&|2f-xpImm_fAqxpnDcy#k{81Fdqm~#fVQZE2E;-P{POfT*L>aU+y5d) z=JAtB+rqY)uks79Qd)RhMnrwOh1w_CqAj6)lb?4M?7!POS=*Y|QeoDwm*?#yN^Tfb zZLhZYX>KpIMdI<q_D81HNq_$JNLuVHSe$Tj`f;zFf!RMIEh<;OyLWe0_Xl=pYrF8% z&8e&Ay?Rj&t@@r$C|Ns2U)}x!#Akgko<up?fBLaJS~Y2v{I54BJzDqn>f02(xX>*B zyDGdgT!THY+<Kqr$%{9C9H{&>QSDOs<@q7Z>f(9pqCabIy&CkIf0w59PJQ{{_xUS5 ze?UqNsh1_6>Xyrc5>nN?_tAaZ1IxNX%{62vA{CTnD(cra?`BSG_-<16^2uS<cXKEA zZ&1u+_0!YIy&@jA*6HR-OCyd)7hicRMwrWex|lMjrgC@OW=J|q>zN!MeQ)h#@29&S zi))`#^Q&`UQul8y*e`qZ<kgbA`H_XWZ*-N)vYuVKoxQbtTl}^xwJ`4Rqf%3*%jTEA zxZu8DAX56mzt4@UWJ({bxBs_r8?*a4`~0gf^KAYti~S}0dP!$rnNs%eZ_C}Mtr8Z< zTjTQR8z0Y{m>pXa?`mA(PQATpZ^_)4sEOaMv<ANNQwOIAALFB&N*}$weK<x)!%E!! z)ycq!!(Xp^^%lRsyY=o}8OzqZ=E?7UAw`|C#m=%rD|p?Uvr}HQ+$xGTlJr<yDcP0! zWNGH+#Zl$lYoGQ_kG*{Q;;byoS2qIL^VH}4x#50DEXDGZ+uhGk9?n-O*`8cKucI_* z(fJu)-ubWB*?K|hPk!B&skgJM+1dQ!Holp^cW=q&0PV2YuL@_E3BBBM%<=#4AoWDa zhp<`#QkOkYZCq5$>2bI1@%j6=&z-Nm&R+#_p{8Z!6^T+86=Sv4d*hCsD&=mR^(|*% z@a$6l$?;_t8}3c$`<~UBWx3|s+b5m1FCs7H`&4~j?tV>t65IaoprE>Qr~L1=w$L>e zpL7=-Q^-|cfBT<*-2BJ;Kui7&zMffs<ym<4Yt`M0-hEuAtNU_;SBW0uO1-E}p~c&E z&&AqHK+@*2$4~B>NvyncKke}J!sWdZIp@Wa{MN-C<GA+f<a4vR!FQ_ktW<Q>-&?EM z{=RJOy>-1r7RdX0cl53ug%3HNJU-dtC%AJL4r!rjrY3GJtG%lgB4g`+?=!ec+cMeQ zd^Mk6T>vBz`981uwC~?dh_!c@PFDBMJie#Iy(DK!R^|CQHXH40H>+IP&7rm(?A4eZ zu{kp;i++lE+&y{KX6NJA#n=BrvH_^_)D?ZQ;ncLp^X)+8s;WZJ^@6`=XKju>e3IV{ z64Hw;Dwl6^TYOnMR3lcV<XPqO(-Ax8dCFaJI+L(__r<Pxe0Oy3C2l=;toqx+aL@aO zFJC{g-Q2|S`pdn0jg6DJw|9M={rXzk)pJSnY-(1pLkhGKXmOrue05>|<;8rfh5FaJ zJQtc_q;6mM<-)?n9}o2;{rP??mK$8zy!G&toAXR|qNiY>@yRtkTh{jNit-NleLLqz z&~|}!uQD8eS1vd%d-YM!s{BjW-pw;H>SEUZ-D_F7`{Tdpi<_4mpYi35|9YL5(Kjl7 zzvr;sUY_vaNt4CTAVp{O_11RaW`FScM|*ph$5&L(fL7VJ{}*2u=a-#$_#KCOl4x7s zil?ida=7<xUA<Ju;%B4UoqYF_BF?vsih|r%jU)wZkJ^G#;jGp&<%w1YqnaxfBC~TN z?oE20@%`53JGC+q-1{F+>@N-LHp|;3o^~`&Z5m6f?xN&N%k70aBQGBMF<+7C)@^Hp zf}(?ScI(B<9o+f)WpCq_rR&ti)z^1SE(T9d`&f2oUo!y5(So@(_V0J+o%wkqX?M!U z860009`%^}Q2E`HMC+*Em#-Gh`Qsq`Zu?^E%CLzqwz#-8PM-aH-F?t#f_warDbFN4 zqCb69Nv?kN>5}mMYE{VKSdiGYEO5Cn{lGt~otNJGDaspHSyf&?{gGMS{sOGNzkS~6 z^re&apML3_2haVkOpj5|-|_Fx-nF%bpOW3#JXTKp)^Kjtqs@$lALY)Syn0&fV(?Sp z*;8Mv%fGk!?%{LqzGm%@tux6`j4@4tq%Dg|J7#rrzj-&mKKb<C`|jhn$J5t61dnun z)mazm-Fge$hI-@?YdiJf*?V{UD~oFFeqI!geY)0Qmo(SfNjIk*>^jrF`E}sN{-||P ze0zVjY<qC6`s=D|>u-7lKa;5l)j0aB=Eu3>$JJZ&gKl~0Z&}4F4@px`EG#!pZ=5Wx zzJFuhOz(ZJ3xj2tGJXElUX{96ydL6&r!%Ve@D@Y*5383M<-EW3_H1qWrvrh!w?d}g zaO;h&F8$v5uJC2=se+cWMRoV*=|^A8+jjgu-=g<dKW-}jz3Su%)3+PN+IZ&Jh!%XB z!wza4)NS1smlYztPW!)Hlc}b{eBX8Vr}VE(p9${#XFh*&=8&?#&2DdX^I*v$k6-s# zEGi`$SC*|VO0Qjcb=maE+fQ9xQl5QtM{UoCUZGiUKW}evQGb86?)tZ5Q4&T4pF$3t zES9sVeDEZDYv|J_^LUzS=CQm!=Jw|vXbk!P#Y{+ZM5gf5{pv?Imp1KsUsd4wAaBke zze4#rdp?(ZF<=UQ`}#@H(#I|z9sTlbEI&My>(iZh=gqn~HVbR#)J#HZBt@@XJMC?h z8mN_XSAOnJ@Y1RSC7@x2Sz80Qz3#jI98_>w96Pz1_xq`RXC{B&@xCfyRV-U}On7Y1 zUCq6@mG8FP$=K=g``3qe(|o^VZFB$oqPld?o2&cE>gLoqK|J!}$!Sn#u&&(s?%xE+ zpmbT!Wc@W=ldVmo=j?gzIQ2!$oZ9jt&ZVd3M#;@u73Hz#cyvhBRuA@1cQSWoSw4Dl z(fU~FoKx$f!=CP)-8=u6T$z5-m5b9)zAew27}>YY0GbSg-#-y9vi|P5d$o<<y_Ziu zJypEV@k&@V!d4Dkb3S2z{N!^sXjK04@o9V4#FXfrQ?b~|rF=k9a5nFeP~pASQC}o8 zkEiUMDkPe`RVMS4M){47pV1A9f4UvkrzL;A9d!5bNmZfS{nNbtuiSq4<hRR?`+h4X z*Z=*<&syE}aAJFsXdB-g8^eMka0Drc_Dtr7q&w91*PDAMI|Cs#z+4CQ@LyFg4))jX zjs5iUyj{f$<^FoBp!6RHP6~tCJ|a3lKSgMoXYtx|gGSO<f8Ta5Dh4suuvz<RBd9Dn zYUroez9d_9&YuI2#<+E+-?}fmgHIgi0lVknvt6e9gQ9h}{#!76)8yYzcYXgiZB`4k zik|4F{=WRz!WS_zYgP9>t&mP#9#PtSNs#j{oBI9PkVdiknUnr?Z<LwugnCzZ_szQh zCnKOr!)m47JRbL3S885tRzJIH?_0NDjgz^}xvw2s6{=xv>dxj^KWB*v-=%35J8RTW znos7ahYVNuN~rJOwr0+rpy`WOU7WK=bL#89c%9p`Eq*dWI<{q-=ETIi{ky1NGIhJt z?1GBio!jm^l(;@SeDf>cM*nFKe|&v4tHShZo%f-|r(c#P|A%%1xxPBx+?L~Sx$|ET z$F<(}8k3XTC+;*@mG&5144u`vcl*cw`SrJBgm!dSep)8eY8n&I=d(TA;^#pQaDTdN z(%hKJoDQL=)cvx@{<XRb`Im%uuC;u1_w<HWKD$49SXbZf&0$g(KXNi(EbHj1)pAR2 z-toM6^6P&6`$d1gPU6@P8~EOQI`rw2S3C#nw!ahvj~(P4{`mZT?)&Gp*I}`4EAaVA z<ApM>O<jGzs`go_uuArw>vf;@eV6o17QeiAyY-^tkQ+2BPj5#Wn>X4XG&g?j+Le_> zrTym48}yo9#4st9E>eY#Oux%JXK>|soW;+3kRG#j;`Pbd3*Q!9SDa(>>in*{ddX{@ zg^#X&Ir&`i;VqHf8|xb<hl2;IJ16Id-Mw(~vXj*0e)Ymn+r`4`zns#COs{LYw$v1! z)td5l*5&u0@_+^0kU6*Q=+4*d%HUqtZO-CPPkyg+pR=b}EOxHRy7jN$*;L!eN`~c6 z{}S`X_MMv<s1X63OI>NbbEdj}*xaw1_U_5Oe{02korr#$k8hmg|M;!nu`e$+e)AQ7 z*`QC4W_v&M?sT7DV;5yFwyH=aR?GgUx$#AzN=fg|W0URQuK9CWGE*^1>Fx2LMIW!G z`?+h^|G!ebY2(F7-Q2AaUM3-_E3d7pFANNwCi3~xnpgH!lZ0xmH50#_@!p)Z<l^L0 z_v?S|{jk(!ox4B3hl#2fv%7zlgm>q$e|`5BAGgvnu6o=vZ>5ax%nuhQ$CsPbUUKuF zw)ktZVdi4>sm0b+<|R+}*L{68^}BY_ir_UjN=>g`gtYNoUVZucgzx%f`6<x6bM|EP z=F75Ca$IYpJofC2x-xmH#PX+4WJ`P+-bb2m;+zw+BXrIEnC)h(%fvoEIdxL@DX5oO zo;Uq`?0q}i?O*>Ici*=({r@(&_<orEVng+(_WO4gzKRNbG&S<;=lgSK)jzy@HRB}z zxqB}r+UY+%Ump7J<e9q}oqOI))oZ;wb!lrxXNlXTQtrEk-{1U<Ubd-oe{FT7nOW4Q z&DyM+XL`!c_<e8Y(SpyusW)qWN>1~zDXv-=zH7?-A5V9!OskrG@x@EAUCFoH{O`s7 z63{*Q^TpTy)2$1>%(Jdv?f&au|GoI_TC)?r9J*+1c<F^_>dikHCtLdOeOy=nEVFl> z=0rxrzdmpNAGkRA#bmpCFIM(i-3+aqb8+&ipE9;D-)dj)`v3m*_4r+zzMbAZ^|q_` zmR<kBy#yA&xUGesnnB&^mfvrmSnlLg-lC|xd1{5n&jJUHlR^{QC)<89jP!GCbKRy~ zFZE)M-2KCODMA)I75w&voH%vz>dx1F>i2y<{VjR=_f@pF>cvl+xuescbuWM3mHy29 z{F&250?VIYIeq=v_PF>Pld@JlTNHI|W2RTi!_t#c6K1L1dYK;e^3pz)ZLipMXG~vp zP+_C?-cSwEkX?R(`O7c+Hh=p3=Fql1t*h4G*PFF&n@8#TzhxUsVi(1E)$aXy@ymiE zAstKI&EkLQPyL?zB_((LS#v|n#p;pIR2N^@3e;cvFJkfb1@~7Me^yWWQu14N@6|-9 zD=&NEcGsztG=IF9eE)Su!JLbiRULP|%r&X4ch}$aQ){EU)nfBEFZOQSQTy-Mx7*vj zi&t;0p4~g?>8*MC(=NV-^l9>UpItla^v>7ps?h9M`iYYx_4>s9tVh;~+P`R=%>C@n z*R!C(oO$;oJfeS{KB{ki=jx=|%?Yu!`#*JCKi!@`_1>P)S&_H)RV4p@bT;hHjd?pG zCr#M;{*LDU>gAu_y*;(N{M7XKAy1w@wN};KS+iS-`%~-kOQl}cf0udfUvhbAlUK;g zp#5tuH?x&i{q&7Bo~Eb2G$72Ab>+3Gao7F^&Yie@!mLkaAOGp+dLJ*@RcAdlZqh&R z6(zAsFY`TrO?s7U6I-=)%iVi_Ja*}9@zR>KPk-@p?^Bz$?fp5iBs2Gt+xeV*d~W(4 z^7&tu{C|2<#x^rJe_u|~$(~S^xfg?Z`7Eo}mRy~A;#v7J<Elg+8QWMTebu`qruY8; zmD~H`S^LXf|9j?T7M!?vIk|NApVPaiW}h~-yrmg3r)%HA+0(W>SfJ7NB8KVNhD@ZX z)5QY2c>VU7L%N8Mp6pdBORav?`i|Ya;M37+>HoiOeBR#uHR<X_al56KY?r3h*ql6Y zO*Vh`vo%xS?2gXzt1Db<wm)ii?7G<Kb*Hw6Yp>d@y>;i*TZd-t((vAQY1$R%TTL9^ zDGz_my6P1kUzd1hod@?-(2(lZSs}(RgDn3@F4JEVRjmE#n(WI@L3@9%TD9Pk^84&V zCK{@rFZsVbuxd%kxBAH3=_LwLH=nFxi=M44z2evYOH=nPx?CE5cuj%gq;>B4nzjCJ z{(E=dsxfW2$metI#msxNo@SU!?2Vhf{!(@SJk5#UqG#JjE>1VIm)Lvmtoh4jEf=Lr zzbsPixwp>U->FLDug{G?e`RdH-k#Ds>HeB4o%>>S=3WebX{9>po?+FpO@H=;Zg`gy zRkUSusPXX-FOw?Su+DR;33KM8FO-FjlNNrm6SQ@#oz)V<q@Hijt;?(~zQiyyID2RO zy4}&!7Qg!*wkh1J_i66$dts07l|8-}7TX>badTVvcIlvn0UNnfKVP1B<AT2VmqS%I zmw5m6*cCV7(A7!0FPGI_=*Uux2z$BonAgd?<?XsTE6qZyb}C*q)6(+3eqDEq)RgH# z>5<>fCau17|NgXT(w|auihOsytasnFE-h%$dp-N<+h1Qi%YXT66IZ0_+vS#3%UJ(z z{{O;r*Pkg{*Iv9FndVrYaLLX8e@^~B&-5>4mQ|}9zou`^ao2xQwp#FNQ<PlV7b~;) zUd6@NrMUKrUiz_N@$%b&b31eG7K^9NWWC#%=<dIYH8OEs)V=c;FLQsgp6dI0>bV!Z z_ElADLKew9$%*but?s-2rN-3q;%m_0D&xdmZLiPYy?y8;zZYts>f+ZYO(yETr}i6N z|NK-w>h8x?yz7I?y-Q11UMV|!ca^1DN~F^%?`hiebAogYRl=`LdmWdwt48pY)=Gt| zNu7x&Zhg3WSS;%0s;3!MXTKeG5nlCqQZ}omtn3Dx$k2Cxuc<9*3ek>?vx&|BH{s={ zxXzc=rd6`D?|Y?xSyun0D)(PqZ`=i^?9Y;WBa$SPd*jMil(^+zUo4)pyKXn9wCzoe z%$XNo3oG}{i{89<*J{3sEfc=)dAUo$O5A-_*VWDo=kNKZ&-*iZzKu$hUy9WK2l98? zC-?jBxZgGT|KIu__w7F1|DUZC{&Ax6{DUW-CjSS|Wu^$&{IuY_wxn4y_@}?!GMCe` z>opbsKavvaYpJTLl=u|Hb@cYtsIOD6ZL$6OJ!z{>q*mbmFC}yBUdGwjW*l5H+rw}A zgp$~^ocFF=k)LrdOVKh`>5}~V^8d}b;a`<^zIqz)^0H->+TO24J1%zbo12+f@T;V6 zp34&Z-LiWX&G%20+qe7W$qg^7zNA?C@JC71emV4u`Es<b&&e0Amz%}h<o9l9ZG5>_ zOu{zy?SsC!>(6G-dt+srp;*5-eS2TAi{6&GFOwI@saWrnY44mIzk9FcvdP}_&z;@# z*S-GNRsFi3tN%ai-~WlV(_Sfv*LKzaXQ$&U|D6B#cCXXUpyMZxH~lr+ulT?3-w*Bn z+Mn9@{~qk$K4o(CGm*s!=TGn+JNZ03`}I<{(7XLAsp{e>0b8f7ey^T+ujRFAZ2Z3M zPi}kfJNcy8r&Y&$A=ls9YuY~V)?HR*+w*&YSdb5Yw881a%iDETN*XS{KE-u-2?fjr z#<6{izWDdr{ov$l+vQPE6lmqSE$9E<k8@(I5_g~VIvlNU{e7F%cC%OJ+%CU1hOD@+ zckTZDP2Hi}vrhj@towLSpUJK1ui5#HTLSm*Ub)WY);60`%~HMpimZP7!lFa{-kl8Z z=5gMjXM5(vs`*uiV%mRQdL_DPTd1z#75m!}UM6fyy?K1(FEmDYnY4MnzkF!MOQGgV zsuFuEk|glZ%gVl}82L?4`0^++v1Iw_g?;}P*0HradVVSWWPLQ&dZ)tN0-OD5zh{Sj zy)paycB!I0-YJ4gPqI_fS1;3x5>S8tTe_Wb!~JK*?_NgS3p4+qasBE^?@udd9j^C0 zcJg^x_UhE#(`HWQe)apL&kXj{Y?1H!9(JnEl9(5<sB>b+Q?DKuo$w@;q@8MQ>eDik zDv~<Y+?1wi8wzcV0ZBvDfi-kStUKayq)63GX<9Z|9aw`((oP{|!P8SEIwRI~g4I!E z@FL;j35)xRudI5&u!7xoE@+WLkD<TbiRkKoefxH<+a6i`)T4aw8xbv+S&401B1&CP ztmZAPZ2t3(?ccS9{BO4Z<oO&u?S92cu7BI67OTheor^tx>Ll;0%UTC&l3yCcC;XC6 zR{3=yviM1fVvw<A>>~cTrs|5e_nhRdvis)fxn!v=_x`eQ^D~tt$D?03r=Oj8xz*$B zlafxml52BXzEp76zF0GJj^4#~kFAE6Rn?#xL3$K}a?g}>dV2J4ztDbe*2$MbwH+bS z#<594mmceWS-3f^XqSt;($!-=(`SH;DQs$<w=d=8ldMyP?tCv@^0R)~Rf`tu+bP{$ zQ5||)ygOsZD=)UCPY&iYlrjI#^>h9w`?C7;srProwjY=IW?XXWMM+U<;9mWB&YBgV zWvVG|ZGL(uCeC@$yG5<-@e1i{E1P4LzE0RUbwc5@8<wIs@;^&{+HLmz`30wS|EwlE zLw0@GE?YkNy41bBzOT1xm*-sP4tv98Ic4%=OUp%*4_hhi4&Yi?=U@d&R$uljf4<HC ztz}Q(#y7(Gx}B5PPm$i*Ry9WrJhC}K^Y6Ql+u}BXr*O;;9@LxY=umc~ZPtu;3=h)| z&H_z!MSZUTuZ>~Yq;l}&(-)^d|DE+#?9{7|QJ^(lPa0I;K6$MQo%#i>D0aA|VpVzh z`|Q%&`e9dNJ3#%s6O7x<UR}Sw*6HZQ&rkNfuz=VsYddGp&dcD@<Xq5znx)g6KWPWG z!rtt9Tz&SzJ+6bGohl3-v*Y~k<yibXd-an1zo*<sH;JxcU}#vG23c<Q?^>J1PUZVd z^R5*_hDNM~=EMl7Z;$;SxAEIr@q23`%0Pny!DqcTe!B8e611F4+6uH|j3LEcUOhiA z%(7gTK_UK*p4l0joi*H$rTCGTFQ06F4PHO%FmFfb8hz0<XIGuI0ckrR*D#rx!9f~q zS%Ut<JEaT^8Oi5j@2}Z)aOZ0ekP?S!1)xQ&91)sf{~rA~^EPR3MCq5!7a*~g^YZzV z&)>Jn|9VvZL_k-Am7!tfGw^~d@Mr=<wcGpGCuQs3y#uZ1n;_paSzk2k?eobH$;e3$ zo)mFB`~6BTe{;EcVG%>apM*Joj#bqz&bcmoezJaZ0xvi<Il-5nGBZ5kc>IKWb=bl; zS8@uAmVss{88)dNJXw2x`eOr2soksQ+DQ5TD|z;7R%xv*N9E5Klh3#7tH#w7Yfcja ztwoXdHJ`dzRa~6w;;)SrPdd{>w}$=g?q0QN$&Bf0OZ-e!#Xue3m4E(Dzt0`-Rr7V` z<&9G^JlYq(-1OG}pYQXAKWBY(RHaTX7T1(4{*q!DWiR&IuIj%1*Eo~87p2p`EZO9; zrR8GxQkUchFFdn1PRUqeP!+T`wEoJ)$p)o9Pxngh{dx6P)y<W+_PsXU2wHL4;Nw~H z3A}*nd)Kwk)2Gd|uKxRbx%j@{r~Z`to&BHk?A^-jqXti&@}IlcF>TL>cdJ4s|0r`h z^S3noX?=N?9k^?{a@pnQyDsl9Py6^h+<ehg)!4c=RiXR#n{Q~xp7Q@wbT_0r)ojI| z?fLq%g@n(~-G5a%HuuWs_v_rWPj4&d?+Cf9TXH<++G6!YGvk&2ll$hqx_WZmDdpaK zAJ3iA?3?#9_f&(&Ryo-j3ogFC_uc2D$71!Vs*6;6;^u#8T&%v<)AX)W`4WSwi)ZCa zzbvuYebG44&HvHv<<IulSN+>reEsOjaPQu%!_eFY%HTQWi{He=Z@#xP*si?x_12$j zjfJ>puRou^Z{LQ>yu#mizUD?&)FyiG-Lvnm)=j>wbGfVLzrA5&8-C?wP`&rn{N?#` zV|l!<c&}WqRlbB>by?F&oycdY7Z@ko?bm$2NV~k`!IpRZU)HAoTJ)~p@A}TUfAg2l zH{Hu?W|nbqiTBPmZ@2!`n&hs(>!+|))x@*mroxxhlfE>SeBRx+%>TrTlkcyG@VzQu zVqA6Ey6W@Mld`sVd2iNC)-b)lW8>d%Z!bNX6{=ww3O-qd;l!LLuTR?E-=0&yIqSaO zwe`B;_jktD6|XFLndVt{>fx=Y)=N)s*Pi}9<lf%keQO@ywHDQ!IA7^Q{{0}+^t@?$ z_ipT~*eq(kEq&Uy`+HPhs<|#*U3SIaGh9{eudZkOq*Hfau8O(lCHuAPZ8`t#Kwr=A zPh!(byxe!aoAgE3BYbb@%TGog;n7R9PM96LoWH8%rbeXp+tn_6H?I9s)(q(h-fet) z<HboQ?bzJbKU1a)TUVuhF5OjWJ$2o0d&b4frKe2SiY-l;<gUN%J*#TZJ(vD@e)9ES zzC^Ds*?h9fx#>%-r0rDcoVuU7mC7sEe4o7feR#h3+N7h?@)@rOf3J9a4>W7YaP#70 zx%{)Tx4)h)E#IpXm8ZKdvRHfT&rs3p*VjnDzILgtYc^}?)Wv(Iuzn6oO5AF;J!*FB z+Riia(bMLut=fEAEB4x~lHf?CdHd2lx89t(uH-IbWcI3=ztqfiCQiQ;I(1!e(#uVp zoi7vFQyk6QmwV@_UUCXGb2sw}i;Z913hMdY)Cw$}WVT-^_f^SPz0UV~_Nr<nUrN@W z*?s)dVWG$y|1Vy)&N}qWxT@z~U2oimpRevNzBqT?FZ*{dJoD0j9k_V8_rx{bHBo5` zp6p#xur_77j(LR`WZnD(RZc&>A9a_%&MG}V`S7ORF5Tnl+N#x+yZ7z6E8wjk@}_r_ zvLZL@=S_>^PM!ZcX|I;)_E+Ckwn@Lek)@OGt<0P0CH2OGUwVzjraimvPRM$n@9DLK z^>5Ir)Lh5wJ|5RqFEOrEdp~u;zO|Q@Hm$s`9lI@X(dz$Mw^IcUm2BN;6<gQ#m($E% zF?Oq_thdD8Fi-2)BH>Hl^S^{}e|@^P?ThZ6KXEUAn^skQmc8ka>6l-qQ`-a@0O`3W z(m(Ht|Ghu8GJ7`#ui0T0d-dY{4_Pu?PmhJ2-T0;R^|O7D(^eeHK+W#@pJ!zkKfT&E zW2bUa+@?K2ch{PPcy4|8>O<Bx{fk;3wMth$%ex-(_w6ig_A<4U%G*V!OZ_h`{+j%9 zlaA<;sPbJ^<yV_lT~odr`tnlat}6YN_vh*<idHQ>?X<q+ZoPYMU3k@!*05c-YV@zw zUw!5%XS?<1WZNpCO>aAA+izUFJUZZI(4iN;Z(htin;)9DU0|8_7fIWzm2-uz^)EgB z$)#sr&OW(yUU!8Rx5wTWRm@+to|%E+gmkal;t;Led|?-xl=~dtggpA?{MLQ^vrK04 z&2=(!Or_V|=cxO&O}%v=m%sk%jQu$lad$sTJDR-Srmx8TDTrtP+;v*7pROzUs%Lw7 zuY&5gcaGeS{KA(*cWmUFQF7PG+V;)<l-9&c%CqzDZBdTh`{v%CGVa}8@9)&iy<{G{ z*ZcgJBWJIl-gW1Tfnlucp8smLZw|Qh%)8~S{BrK>^}%dQX5Tqd;-(+J`1;NIxtCVW znQ^cDOO$-fs-hcCyB1&H_%m@=m*Zmf#9!;9CJ0?GzB1RYe99#4ruVE23@120oveR) zYwPxPF_qqRLM|%z_7u5(<L%=MQonhURWd^|*HTT`IK1fHO7^R>f+gA8LW*td#TI=R z+BmCo;taioQ4))oSIw{M=i|Bgzvt5KEH$@B&-!QTEsU}dSUmk8h-sMee`(*9o~K?s zGxZGftQMR5{c@DE<y<Lwda8tCtkr{6=PN%O2^9Tx6{yi>U~u5OF#nJB{yk-HgI0cd zc8<@{#ra!TeB9n==2!g=eRS;lQugWE#TkG6`OcNB5WW?C`mgg<9{#U~B&=eU7Jo_n zEq~h7u%;@ByLzhL#D8Ghp}d1H-de>rUA$eo>xf-{Ttsl~#Z~gJ(mzaPU|{&^VE6Os zYv(=O>gu~dmc{H%d%gd`>&2}J+ZzpEzI@VTrFOZV=_0q_k|q8n3+h6xl#aYAcV}O@ zr2mo=JG*Y|qUMXyFBH;W3d#1|b7Hsjp8g`?i<s4k$Xzb%i??4mIOFB6O@93Qco-NI z<WI2gUoq{qd41tmEkD1K_BW#M_mywG_Cdz~ujzc|)-5ldKVd6w5bI3rxc0uU@yM&= zNfJq#7bV(2ohZd=LcNI{OOGTeZ2YwmMaU&tB1v<jgvXjXoi?Z{un<_I4x7+w`R>Gy zr3fJtkg9GZ<NJOc6lY*yc*6Pf%l9j1m(+aJn=|JH-%V}3{pDLj!pnCB20uO6$Nbpn z2Ds6~knl?I=%?A%yxTh`3wJ73AGHo&mlvIP_o83l)a5MT_9z3xL7SZ~#QgkJ+6q6d zot1ra-s^`?R)Tl0FfcIq`SEZ(elq*i$*Y^A3O;QCFGOZwU{F_QWAU3O2%ZIGV0iH4 zNW+1X#!R5eS_TG&IddcgEGpd~jY@`w$->M`>gPGYO-BZXf}$jc2TvrC&7WhV3~nVd zFdR79$=EnK9p*3#OGAZ%PdzlZRNYYT&W!5Er)E1JYu%|m{m7izAKfl-Av;T5+hwi3 z>FnqC_kC#I{{PF&@_hzAF?%Wk)8BT?JRaq(itNhyYXlVMf1LgN{;m&ePyhcMzvuVN zM5j4_7A@b@GxNBVj6I6l1s9etFxRg*YwlL^sd$@sMrHWy$LxrZl`&ASfAwOav%CKh zuHc?Ex8KVrU3qj>Jm!Dz_H+GDo~)02C*5cNSbJ&zR?9j>s2<qhw=Tsr<^LMfi!=M> ztuI|&eN^A`=8L~~($%l4uj`KOfAwT}_B+el`yZ^ld_6h0PaY9l20fGKS48xDKe6%g zS|P#f?0vd!T0KJQN2>a3GB>WS+417}lXgDa8YLZ@9e(?Y>q^w?x4xQ_TOs~c_31{l z<NSy)lX&ywRz<(v)zE#XPn<Z}FH;+_>*l}12OUd4b;o_?tu9etZ;_rGUu0SSmjRj< z4mhZXPkvIHcJ#1img|wUvoX7ZVw&Tw2JSRndpB_NRj2uByXQt)|J?Yv`?y?&|J37i z_k=eKUG#Iioj-l~5B1J{hSMgSU&*~!@QE3gewyd(aV~kh(AE4)Xl+;Z@(XN6>!mrT z?S6LBI_s6hg`DMq-YkB3*Vuxe%KF)@n14{~vhZfDUv3lAHuKK035O<MgTBeyJKsi# zetf&)a@iiAl23e(Wfw*YFP!XNC0+W-j(1h)MSFIZx2wyP=JxD8qf_uH2Id_Jzk9i> zCZ1YsSsAj~J@cB&?UTN&rtf77KiToRMVSe1S#KrDtbY7tFdHP>G#IW^mv^0aTi>{> zDEMb%vih;IPkSePh<Na1Cp2R<H2SSGHT{_NN^jv+E$N+R)=KB!PLFMqx&9__mg&WZ zPYzyv>@N4B;8Ps$G5>7-TkrjDPCjt5m=&7Ko9Eu?$PTG;jX8T}r_qgRy6jh@4#`Y@ z{_V8h-QKG_UTxXeT+W<qo)Qr@pKb9W`8Ai8@7sQR$`k|J!$@Wvw%FNHc4b0`D7)Nh z&mECbmrffTol&`FS*PM`(~D1^q^+u1QRimvdnz<(g6Q2RwpRUn-#&T2Pj#8Cin!ic z4fW?gpRn^n%Yn9%q9lE%o~mQ_E#Lo0&w6+I_P5TY$E{9(TfhGL{5mXYPs9rEJzK6; zY+d#IWNqQ63Y2W|;EAxvt&_9!E&gSfz7IJmcGE6$&Hf#M_7|<|w%x4QnKFOf&gVJ* zn`Wu^Z%57-41RWwg_-H@bN=jkJwLl5J?q`dO`kt)o3Zonq(5)^bbmj;y^Z7NYSHIk zcd4t{Kh|E2nyWy%75(&rY7YhnKTUt_b=p5%R(8_`*}jko6>Hyl{q3GND|xzDQZ90K zYMAUFHe+Sc#ZTOMpZ7eTzj<%*wpnKWe7EZle>=bX)wzP{vmSlcO5#P=lCeH)yZ>}n z!?)eX&R4grnHq5UvD)g@TSJh`(NCT{r9!(ueg5{Q{QU){`&XU1kW0>=D#y;;`gP{+ z?!(7Ub)BeO(<;J@D1$$}e&R1{Tk_&XXT(F5BTMJb-8}u?ziZvo=l}Zto<~?*KQ2W0 zSyr6wy$~%VBb}{(KHA96$LT)5Ybt-=QGHp@vvvLQleZ<UeY@%J$&#YtQ@bpF%Gdlq zwg1PrtBFo?_LPQJ{^EC<jHnnI66eO8{BUtGzr59#51l_&wOA<btA66${VbKu@7~4U zmxV>eoj+XjQ`GI(&u>jjJB?N{Et#zSUX)kvTC(*Vo3jCabx&R#R(j~(C(F;Z{KUz# z%@^)WocrhNuJU_lvsTF<{MrUueZR{tJN9JRpD(4V+ZnS$EvDwaF#FlZHL+;rw*woG zmSuY$S~K_0jlx=`+U!*}@1E?vHNC@3?saJO)x2}({ndLW?|=AX{rR3}PtvpAS>E2g zVEHLDmra?>uC`{H{}I3Va4l)S$oUppLAhd!K0gWkef5xx*ZM5onA9~E8IIBA8)P~+ zs89U<w&0WFTlUpws!P{&>9t31*<QGE<+EMq``<lTA2z3WTYaGY3Y%-sejo+@VT+xU z?oE>`_wy=06Yjof`Q+nM?V^mej@{Mw-SXe+Lfz|(>A$wD4|7%Be|KM&R?)KBH&5l- zEPlGK|JnBT?V*$ByC$!$EIJo!ZvZRRS|*osZJXDTxA#rV)xJ2tduw+Ku9iOwFQMML z-#g*5yY}jB2~X*%wOi)Yn16nfE-mL*w*guiCv2FU{k3;;MPHTmw<9Ng-!UKeTk`P9 zZ{>#@k%|lExi)pDwzq7$`GfPx+>0-d&Gow%8UM53iPZavbM}~K{f{5{LQE~<Ke z+}mKJa?a6jo<;i|y(`aq+b8Kf^_(WXHGAuw=W;n~pT3)}mgFb5MId{L|L?&6`RiZZ z;hHMCZNu`$$<Mi<1q++S&Z6sl>}CsNwm)8%&zL)vcS-o{ol$)!%etS;UZ=X(1X@si zTO2#JXzGn~U3o|M%{|_SFraP6ap{fWNG2A1;^ab92o00{16us*zMb73Z}a=x=k@zP z%eQgN`P0w@T9OWGG1)mPy4gN{Kd1c9bu;btI^yyBqJR9Hd+2=L`tKcwyti}P?~k_F zx~q2At1R{Jg^0?^;wMXM*{5gHkDg5XUUc%`&9uiydw+4a&ik0Oux`<fA3wt$`<%5+ zpIwQiD4bqamNqME-k-0#zGod3)UD6ltf*LYPy4;Z>J1DG?ERiDjv;mXa`y*qi{Bh` za@UK;PuMx3fd%qfVbR2_z--&lck@>6Tpuzg{8ZnM%5smLYo@ZUEZg=l_QR}4pD#JB zIr|Z*04ex%vdi1o^m^^Z?0MyXinrCTdpLJ(^`bkRf#0v(YWv>yc7FL^$@rf(pP#V9 z+I`<{o}6!0_2R-s;f;ryg(6GtRebGPpLam7@L*`sJ?)gYuKE_Kv996SE0NljJg=Xe zvUk2De6i!2UfoNN_0xW@x#cTkuXgsR)Sa`@DPP!ICF`G`&7Q8ucXsJ%@idjytLJV( zDk9qoKMC`9AC$8!+Y_p!_v^sMqaLky-Tl?=6}9_nGB1XlK6a8{w(5sVgoUPGUfQ1f zdup~_{84@D7F+wJqGu=h6+WG21`RAW>@mJ@a_d34+EuG<roLFYRn~7_(F$FwqA!Uz z*L;(gQagU~>)y-mB}MDh?K@8B^MkZ7d^)E9Z_K2-x&)k!*|jOm`T44b#p;Wqr1i?T ztW4j$`069kw(83n8S3_BH6L#<zg_u>PyPMXeJ)!*My$WJy6m@l&xd`lr@NJW+I*+{ zFN4y4&|W46h7;DzbM`pLJYIO$^oxIOSM}+@-UXnBjp6BCHXfWRX0wE}@}ApNmR!}l zXCl@(dG@b^A(gjJvTwED@p)pJJGWuh$5)^G>R-;iIA_lD$?`5wrn7@xT$#?J9=`9^ zMlGdFf$qI~LNo*Y`&Q@7xODks`Nw5zXRYO!YqP0z;pFd``^%q)TED$_ES^tx`mD2( ze+xbZ&iw;Qn$_aAbN(nO!kxLh{8QfNo)EulkJnvWbk!=T%JQe)J(D#zyS7c9ZI$(E z_tPh}x87f_yn0(=ciE@AXC}{Iw<}%x(UW~!1hR|&95`w0R96Xh*@SX7i^}Uy3arZ( z9<SYEHf>Y5U*08oi?XB~_4~ao$DMk9ExKNFSnlS@__Y?dPJ-6GA?dW-X?Fg|>czWd zLRV)#DSFLf+c#fQZtb;+mtG!w8@jvla@g6h5{t?L#-9_}Z~5I@{rBG7_vdbfK6tVd z$qcKVg%?*G>FS;}vsiVht~}qWtui~N%ee=CDe9l%ce;07*EWMEvyUk~d*Z0Pwv27d z{5zGkuc~+Zp5%&_P%QWqg9s64Q1j{Bgc;wry(s;>?cDUY%a-iB^mxTbwXHg7_p+xN z+?ieGGJW#wm7mI<#=ZUivgWzK+fO!Sb8Ny9$*RE5?~N;p^9nwl<V04&=VxaLD!hI^ z1<gt@INUpUQe7Rz85TdExST$@cjouBBU{>^zWsdaWUjoreFU^>0F`eYf#-jm{oMC| z*3*44oBYM3^+nc*bAJ`Tw)Tm}75|(o@wYY|J$b%!^6y7aKB6@G51drj(0lu)WAgrm zb7M@RQ=+&0dE)jr#Zc4im3o)g3IC~cj7`7Kc^ez>8H>iA$?*lV)1~KSeA7;S9&)lS zGRa!gt8dLDtL3ZDy)J#fXZ5oiNWBG6YpihP%14W?+r0nvJSX1gx9Mq7%jxs)E<7E| zD){4b-_98^k+m4b7T3hA+R&Y5#mDQD13LD`f0!lyca7Rf)c)I!3sLKm+?-CA%@4Tx z#ecGBw$@ZcBZgs4jgWG|n}^EM(&k7NG`+g21JXZ6u{2kGzmavlph9PS%<S7ie(xSW z(S%lg4!2Kk*Dc?ga$ob>bgr+nTYvSIcAuy`kyo%e;jX4xn0MbBxlNNR{_*+E6N3&M zWT@xAyOFm!<~x_@^S^7`GJd}8{gwOE^NEewE2Ssz^KZXS-7R8a`58VO(NI*hf9K<h zv$NjjMz72GnRRkn#7(tNa+{>rOm#UickQg`+=^}2L;U34SQzL*t$5Rs?AeihbKRv+ zMX@t?TFm&PQY4pVu5tD5theSd_d_Q?$;xjGfi`L!7A`+^Rb<6uQ|Z2V^$w4Y-rGt~ z;x3CT@|Q_^FhXlgrXyQt`IZXpUjF<H=OWpv;{nD`4xVFr37Q@Q9S<k19Lq9M=9Byq pE@-!lVS_z1V=*xNK6vijfBqKEZzmYn&aDF#Zl11wF6*2UngI2Q4=?}# diff --git a/nav2_bt_navigator/doc/simple_parallel.png b/nav2_bt_navigator/doc/simple_parallel.png index fb51da284584090fb9d860afdc4acf75e243c882..eb5f569acf52d21104275f286eff79421e672cad 100644 GIT binary patch literal 26255 zcmeAS@N?(olHy`uVBq!ia0y~yU@T@}VBE~X#=yXEH|V<>0|NtFlDE4H!+#K5uy^@n z1_lKNPZ!6KiaBrYme+)oe*5wNdWz9Y#i=bUP6}HtRErB9T^A9sK|y=l)-~(ay;x^| zxBuzxb$Ywj?b`M3)w^9<9St`EbTqu)?^RjYKEbc*yw9_L|0>d>j6BsQoKczlxyI&` z$Fp;DtIzK>w*0*B`M&qHuT6X}3pjCHoVoVH#}XDN4#jixRf-i`J}^x>(<*R?`$v@( z!^Ohfo10pDdU*WXFQ)p=G-{38TUBYrbJ5eoNZhyT?bho*zFhXVm35oGHRq<$vokXv zzcg@BS3DVG@_O0qyriRDqVxC`pT79AWFDVmiBXWTxD$uI!pRs8#XSwkHhCCPMZ$IV z&p)5f&ooZwvzp5{*YEhQ($}-*lz)D9_S(<9T`$$@em<QZwl@3H5>K0-PbTY~|Nr^C z{o>0nIk>r#pPZQJGs}c?uAh5Cg2H4q-=rTO9<s2pExP>j#M!gCp*l__ER)W-&ffX3 zP5Q@!X8tw(@zrm)sy(lLy>>eX7Z=lmx7+VOThy(Wb#>RTZ*RRF92!o44i61AOg_f5 zY4hfr+w<k4x971g@Sks&b9dKNW_G>_GiRP`U}RpgW=#&*aHC5TGJ+c$8yS4&T1{QQ z|KF_S<9!$R*VngK78Mm~=;$mde}8YuvSmWj(zjoI)rsA;B@|@-$0w8hqxL(@>Fnuw z(#S5iVAZNsS3hz*%)DeI{`S#Dclo0^W}lBq=bKc$yIX$$X(PK_LAFhJY^mt<xT?(V z&$d4vH1kLp9N-n?ytqweW_MZPVP5kIGiIFl{eHiHVd2KoT^BQ+{C>ax`K|2rxu3SW z_sczfHaq_rfBg^U&(F_4Kg6y7<Uk`c!;G_OVQV4|&Mm)p^2^K1j6YtjUjO6k`g&g{ zC#IuEkKU<#KG((F-MHpQLD}0|tSgk+_Qu^$y2IAocy_k==NrlW7q{ofZ`!nJ$BRYX z9zH%xcI=q(>Q$DQZqyOm?{^OW`1p9|mrLH36(1IS{i<uL@3Q-1OU5Bz^Sev#mR$B- zTQ~P<^4C|Z*Jm|s%ebiYx_Exgr_OI6{;Xx0Cr_T7wYmR610(a6y1&0NXD!QgTO7#E z&wss*S30fs-<Ow{r532Ft7p$zmYIHT&P69DCliP2k4MF~e)&?8`|;6HsRh1sEH>V> z&^^6j#mbcz&GPT9VP$2_Z1{G`TR+qO-;c#*=WV}dJbn7~*52>;Rxe$)Eb96GH=9mx zxp5<6?UpSemrd3leICo2aeA6=_SI~c>Dyu^?aa9JQ|<GkM@hOWDlXn09v6Dt7B9=x z+9@g~mNn~IiBbLAt=G3K^`4$JYguO6=E&FA*UwKgkdRt?*iMjN%4EgGO-aegruFsz z(;nx{I3ulhUTF2Q%v;-XZ<`!=dH#BQ{oO~O*D9Wj*>b7Kl2PlHZ$yLyx0ud@_x1m+ zwZqq`SX$0pvP4BmNoiK?-Q<2-H&<8I|38k~gOb*=Wo(Nt-guK;VimhMQ&3Rw`JJ;D zHrf1+D1UR~;D*G*YgFgA-K+ckHf_H6B3sY1F<Vx<%T=<-%gg`!wtfG{Yti{1KOE-Y z{$rM`b(ulUkAg{)CRIF}na;t<S?Ih(S6f5l!I4g3zukJX&OQ?Zn_wiKduq}ao&CSR zzdvt!J?8MX+}kJ4oJlz`LGfCpsc-SFo}ZteC!0v^eAJ~aGwmrT9z(*yK26{M=V)S; zmls$5-mhWZ=eaM=TXII}R!Cf&9K+6?JC7Va%D5`$)79|!j}Mypt<FRT1~RUYQ}`y% zkeZ$z92IqHmTC5h^XIpJYrDCx*81bek1g%(%mGnRS+%~UrKO7_PMtc%U@+6?$1kh8 zE4r`qUNI@2{-mX)#lgqN_F&iRb;_EWo#Js7jmGKc3Qnp{pD=0Cp>J<*|NL^<|KsP+ z+21M^Z%tjk`rD$%S#LQn=<oj%wENqwY*UBb&t_$BnP2zo<gYt#Zf@SXYnPSpWs|ob z9v;4R+220b*3u&VoXp$j^Xs>r`~B^9es*GF;;j}=;Vo;Uw`b+=`Pe2VD7Y}T{BCKK zn_JtrE5ZJe@xO0nug}!q|7X+JkMsY1QD3`ciA(k0uh-XJ{`aBXJ|i?V^xD(<|9`*V zYGUPHbN+t)|G&5N_y1XxIcr&HNJxhMo)1l5cm962+yD0F^!~3~m;24Vly-L3Qdc*( zEZeFt7vAlDZ>MW-fB)(8*w#4=qH8zDEYI|ndEKS={@Lt&wuGZyqH=vpUSE7!q7%KX z$FlfYg_X!f%QX{b?G$jTVDx<E#PN_-WhS>`i}-{Ty%vEuhe_0ykYo-qd3|Q4u}=KH zJC_qV6r&VQ#+YQkzP9$vT<hx)f#e3R^;>Fw7Ck#Rx4UMKtGHrv1D9fpIjvko4_`y< zsIir85O}Vwt=-+y!g409c=7WRtGS0CXI@^mvF>kGd8=B>ZI9D2B~>3ke)O4ZwKecj z*|TfW`K8V-PCMqS6h9Pwx8rf2*yNpY>(jrzxtZ7H!SQ`kiryYjLD~|xKL1nY-njE; zW*T>Pb`~awIPK^MX;D&A+VN)7=~+H6W-T+!zh`6auG;e3!$>?X`QDyNKmR5s2_Cj} z`~Ov$yQ@IOudRvv@%y*=taq<ppI#HWnS+z_qeF<(j&_yeho((UO*<a8NgGJ;@LhiW z>eY_F-)`HAOci*icrvD9>g~MUyo)csFwnKIn4!IH$027y&WCc7&a{T_{PXGb%WG?A zf8BU6A>rMfoqnhFohpPqpB-8)!NZof_iNanKYthuq<Zg^-OiQk^XmAfeln(FZgl?M zskd%LF)UiVc&1(Lu6AXiMSnew#N*O$ZOJ@x>=@IlQx~4;sR<p5KGC~vR>8J6Jnfsz zs;zhm`}B5Y*_^)je^%q<MUm6D-MRd*qu8YOf{cIrg-j2l{6h=ZoZYh{Yu)n00?$`$ zk!Eo_nEulLaHhYz^0}!h#n(M&x>hXB+q>ZYQis##K_Z8=L1Cqxw`RGrz@b`vIb-_@ zy|&FOCn&~#Z_N<Dbbb%F#`!j3d&hTnA9x#XOiWnCCLixHi_`Jqwo2|khf`iNK1hGy z&fP8Hb>88XxPTBhXYj4^*itu(Z@LoN2Xk5uCBJ&#c->)9%uW40Q?{Jh-7vx8g<;U& zyV*uOJ2~CXH2)~v@ZA1f{9;S_4bSHs<q1CB^XC4)*H)Xjm<}c0&^36(H{%nFMAO1( zr`zk?JNjHERf-4BSyy+wZ-ejaYusAroqSj3MqP2(@j&wffA;OK;m@3NC0%Z)e*P8} z{;rP0e~axm?#3GrFRV>RXs-}qQVwC-uHnh<tng!dV&`H_SM>we@7r=-y)Iw$&C>6+ zspOZpHQvQ%c}lmw-OZ;sOUd-J-hypBr#6MIjWTXt>7{yo%J~KNpEmeiy>LFKaq;S_ zTb9gxwKZ+BRpHD}k}C21R`Q{*zi~I#O}AXPd=<mFWh-043RsTa>;78wYtdwZiA&<% z=fqA;zq)18<y9)eb9vaOH!VAO#NA<ed2MX1UeHIjmYZ2m7Jlsg?p=JEVa3`2!=J4y z{!Z8&zV*lNc+N`ptCkHv3Rj8oXU$DbPk6Lgcm48B3rcTC&*ZOcKd@g~Li<Whr}(aY zx`%#yp5DW)VZoI#VIybVAKRQdQNR2a$Lr3ALQMPf8NNuY{nsa#Q@yr-y;s*Vuc-k^ zZ7WskKB-TgqRZ8Pc;fnn*Il;GS@gK?y!iYrQzPcA)z*+wVt4qc$>H6yX6~wcvC~+$ zKJB}G`O>Z`-?n>~uh^t-v%0UYtGjp=!?$`4TXl!^p0D;epUf0p+`qo-V#LCI3mjB` z-}(EhGW^=*S#QtYT<n*i9>-Cbyx@1h*8j10#V(q9fL*(&&c8Zpu0)R4OUbLNmqa&* zy}4=fb@z3ZuhGkcb!#>Yas-@w{@}R5ySfAHeQU!$|6*J9bG7$^RTn-!S-!b+YWiwx z*=gy{`?VMB;`mbcAYGbu-O<uWo>@zieE!C4U6b6lb05!Ho@)C5-Ms(5O0SEoUd-kF zN$+$?&7ArO*^e%~CAGHea`G$r=0q?H%Z0sW=ICkh?BAMK&+%UU<el4@S~J<p^X(=! zXH~lKFS_`!@}VHd+oe@43?WaN<2S6eet0qeO6S#8N*3Q_TfR5m6TcA`U&F-XxT^H_ zon2g)LiSo0G5mNDs%>f#S6dmeWs6?*$?GeHE>B!9Gr7|Hv`0Mu!ot4Jn?Xqzf8Tuc ze%gXQqYGCA8~WErO<VoCFtxgWO^~}J@8r!-_vW1aCveaAluq0_ooLl9CmMCnN6%WA zwf&oq=_>V}+V>NhOgf}es%y+#Rm+?Oc=pGt%Kui$T|51@Z}yILyQD&kINoQ!{vKC# z>|;x=_iL-Y8xOL*40*k4mB(A=@W*FwJ)H69^rkCj)-sVPH{|B~2CsekVc&z~f?V5m zIqTEHo@)Nq?`Vs<C3dmY!{~d_G@<Uz|L*cmO<j2{Beyj->Z0M)5FJieW9M)0ehDvk z@a>#spV;N)GA*d#W=gc%N6y_}v(H@*t&llWI>F-Xw_TTv1#Vpq`=6T`+v+Zx%wDQ= z@wz;Z;yT^KA#3|=lz!b@mi|6SUFPlUhfi<5DlFYNYxy#l++^RCx7>A)y*l-6+Dh&P zOp9f<dtQ#Y|9#Qx2`TTMe&SnoUpLkuIC|Z>NozElyJBvaoSyC&QG5E&jq(X4E3-PA zye92qoUk)iRWg}%&aX&a?gJ65Pb*(NNq<;)^-}q^bxkH5FCWg>acXmD_CA%nTT4Tq zIG$Smb!$yXknKO)FFS9Pg<QB~w8hFHIJ`GZe6_Y`bMh5&r-=8za#w|TUNLu&<vqd^ zy0PuZ%D-zrXI6rOtls?V<oX+C{;un+B43@_*0Iht>sj2X5LWfNEvjw7*$dyRZWFHJ zefc-U{>vZd3+ZjSyPiHte`Z!{A%AhZW4^d8&)mhkUOs)-`a#9?Q2$c@?fr3I+g56Z zeNDK}aJ6>b!(Hc=-CP&6^#gaHIs<#m-A}vDsD*Cg=xI4Tf7O$)@WoO8r`=}XA+%mG zqBPfLi_g|c?Pptq_pg|?Yw6S1$pNOX7q3pZk=x*Rbk<JZw)@X+RmI$lo6F~Ru6>Js zX#cc^g01}3ekHlGi?T0f&U(7Q_eS*eZF^4lGe%X4nf-OWn#g|kQ;EsE%^y==*lyh? zr+epBd+VfmF<YEY=`8YO{kry(hPdCns@1QOu0FprRrrKc#Uz#Di%Z_vz6!X1Y5Fd0 zEsI5`ycIXj>vQRN=4mAEmzon)d-?IPRngDOTqS2;tz=*8clB`VixW>+Rur5nnpqz{ z&EV+ACo2VHXKn$H1web~sng0P?3LzQzah3${7UTIYgfz<nE5{|^Z4%?n=2v2ebW5K zI;))Sukx{LcU`{uT{7Q$Yw9}wuhYr{c=^+JN-v1l;Mw7I*Ul_me$Efa*bmIF=IPg_ z-^#l_dmmrl{{_Fo`)4fI+mxC2`^{skZ@P10va8=+3ZK>SzF}4G^wgWnSj*cV$YoWg zDZB6omaFExZZzqueO|$SWLZ)PdwETs%kPQPDy=)DnGfe}wOx0ny?K7Z-YK$I)`q&@ zU;9t4*8jF@QNx<IuY%sYeb>rV4rP61wrgFN<g#^ATRC1X6tY~wojxgli|zC4zIQde zo-fXex%yqG^!=oX`!~hv-n{b7v}g7Isk--LcofnseEzJJT5&k(()%l{){o^v!q3l( zV2+Ltf1euts^0Z>z2ltK-~Qd{_@;Vt&)kUi^ws-&Z2nJ3))vf}eq{Hgf~dvcOQtrw z5zdG<3_U#WdvyKDivEkQx?BUy`!~r?R98BAZI<5o!abT{xjS#!fBSvn<~LK(=}-0A zbvMQ|<v$FrKeOuc&8U@IpZ4BAyzRkl$8|Sy&Y$nis1HiZO#iDF{GFZg>+a~LyRH^* zOUie@Yrg6qy;?Jr+2Qv6-A6;)97>lT{d0KLpO6X5qK+^;i(0XnXW0VBI;}4<>*b!w zZ#$cQvEcVPb-n6cYWMhmCw@Iud@f&BHnO@lucg|<C_mlPc%hQ})izUJKAphBU94^v z=a$cW_=PQWI}b<mEw8IpZw-Zn^n=#kdKCQX>(!&LO#kXN?-O7B@JNt-@b_mN{vnIc zMOdspC^k3X<kf%w9<5vR|3-NqXYuLytJ5!Euxwy^DSbttxba~?@Vax%H}cc_1Gmj~ zdn&t0_2nJr2l9E^iBIH<e4aU{-JVuhwRl%}=ihIp($nY85-Pnv?NP9R47c<1Rktd< zwYYQY*^l3_y?Dk<{*TMu+>1$<7Ek!J)5=_6+5)%AtgO51_K0iFUzzw^XW4&wnYfkr zZa<K?y=|w}{LOz~y~>s@`u0=kt^X;VJcE*TZ|$xg^Sbfh@$u~`a<OYC6+}*3#ozyT z>#yVX-{xA)<a%Yc<=fx=yH!_2?>W{N@b$^V?W+v+=T6N%qZa!8?x$6|BB$Nt$)302 z?~YCX78c9A|78BNF#3?sZ!g{@0@h4zX979Xk4L`}TPJq6y=mXSy8G$;tCz59W%kZU z*EScC3sjeVofUfLn|f4r{Dq3&v${{;JGu2jZHLy$DN9yQ-lS_d`-&Yy>G==)jC0SM zZa;fCudv5DeSTH_BKB3Qy|(|4z5DcnWca=AgXUKEOmvesOT9T9vUHnnY3l1|#oOXz zYuBdQn|=rRbka`g9})>y=5DL+xpd}O=aEa34+$(0+Hx;p^~&e(wx7LTyl5@ooUP7( z^-czqrk_5*aqiWT_Gzo*6pv*&q)Q7pE)Q4#6%)JPcxw7pd#f8!>l`nx`jgmsQ7HWT z!dLmpQ>9jK+7&U?-0896vVS(ta|3&$qb4kyl<&Om+Cgclie4%CE0a=m%cqp2{ZG2_ zRX^hU9;=`ihFog@&s`HLO`ZMLf5o@mA+--9-c@9*3R+v09#gCTrrQ1M-W!FtyZpD; z*`@!!diDCYFA#ss{?WcNY}(T!QP=#AJKs2HzT#cg;`eMOraCiICopY}eSJ+JLz>6( z|Aef&sd>SBlV=s1h5lW)y7151t1A;Pf&6fEdCuA#@5rM@M`Au|9<QwK+4OgAxyRO1 zx}4`O9cB%wRDD0;afki$)1Ok)JvW`@ePr+<%Jkgw(ghts$HTI+x81C}J8cP1mH}7# zxu<(Gw&XsyjL(k0ed)RP7W<VmcLzq~OB5N)#H^CLeO;q@*Xku@Rn1j)SrgWNcXzfu zzM3U(U2~7F)<u@B0l#~t*G5fRmNnJoP4=0@&b86?&R1Qx?Kl5(^W)A{oBR3~PYN|M z2y^`Bcs1&+ajdO)V7>jPRZdgS9Ii60{r~lwm;hUI`f4$&6;=h$_-;>6%ieZ#Uah%H z^3Knd=brEVFlCxu{Gz{}M&+A#7_M?ZvT}Z?(Ke0qjj{hjlyCIx^8Tu&Ve_g+GO_d3 zg?&o?S2f#r72N*%L^?#tb`#gOy$g3eVr^M{t>Ds9kgL9NX8mzK+aLLIak#pj@pk7@ z&My*+`HnJPSSejSHzL?R?`6ZX>5us~Dl6(8EmQjZ;(FHpAFbQ+X1~3;J&jpu?)hT7 z_pQsfKw_`5`f|n<){XzCu6mkeFLPsKe(vLNw=Zk!GmXDLeQ)VFSLO59?XNH2>v^SQ zD&^~I=u^Gx<H>c`*2#y=JQ%U?)!i2izOs3@)wiA6yzSRY*Zx4QnTvzNLvMAj_kVU_ zhxek@I)yKpqvl=z*xIYEdVj&Mqv4{f7I$u0f91f*hn-upW}EuXm0q!7_lp%P3nR}z z-TPq+B#_STnHzFVJ}X?*w9apN@ZsK@_myvlB>(<>V|&4u*=)+EmOq-1^XS-$YySO) z+pPAq{$;hCw(G;a|0{o)SY5rkPRW06%@!5T@ayl>%M;Ibnyza1$e6QM`{By1t7@j~ z^qnhG946lPVtv&1KxQfaFd2!ZZS~x*@0K_fY^y!@=+nnSyY;pF(yu?y^13EAEt>zw zuhpw7b)AnreG~dy$zogS?V3N;r7A_Q(!W}0+zQ*Y@ycP{k2`+FZP}7LO?m(4S?7;J z^Tq!=#pi9Gzf`bV^rgu;$KumV%e`jV%U`WcTGR4JWa=K>X2$3rKb%T7{bGM%>>T?j zt|n-!*4MgKeRtN1i!5Kgt1!Z;mV3v%d+}epUK-!s$bIJ}FK^ZSEB#vY_r)DueAV%r zU+8_Cy^g92CRmtiY}9_u-xsR><5kv`O>AeG?mLve7n<9@>b|&K=>H3Qms{n>zAjmH zzWhzW);(?}q1NSLyE3wV&pBF}B|FEraL)E^cQ&^BmUepGV4r3cw`%_Ocw2GPfZCNA zX`$xqS5K?0+5SrH)*Z9-oNcA{KD$`>>elp~*u@`aYg5A<Qto{Eq_ek;r*U+he$n^s zdvcF)T}?hd_2;T{X7|>&9*?cg{eDoleqWPRP3G=beVXUz-savt@30YDhVY(To(rdH zN-uV8zLlLI67zxm`|&4l&GsklZk(Z>zu+m~+pj+-89KynbIN)a>+*~3>e1X!k6&pp zTzOb@t*rF8!^LxR=2(AJ`}FgZ&B~eOf<N0GjaQ0=_^w=aI_$|R?vO{vs;sQur^H8Z z+ppSSKI#1Q=boqcbW8lyF1`QZu=Z6>bLR=GypQ*{&YNr_JNLWg#$y}xe_hPKvbSW< z*E&^@p`OoTT_T#^{(HITuWIbAt-r!gKR^9>$r&ZGN7&Xbn0a+B<J<SO?>IwSw=phl zW!O1qzqi);u<}i(@2=N7EcbmvZqLb8PNo~2pP8991zuXZZTEw@+{vnM>iE_EZOct6 zKe}@M)!IX)RT5>~F8pm@O0ya`_U_+xz4A{*Y5dnoB_4leF03@P-~BbqF75QD<u;kp zH*UmLZj%a7vUk0E{f@u_w>A7dA-^wO|Nm$E`dtxs?QN2UReUV}Kizsn`2E5R+sv8e zj*5i_N%MZ~{?a3L`;wA@5L?{Ze{wdz{|H&GV3g2Nel=(P9_DR=b7oymZ}Yk~%aeEa zGV>LT@>M-yi=Q6h3GS4+Qn5<0(4eHx>&dyKZSnc{yJyFjd&sE7F8e2EDc^P`aKEXs zOw6TSZ*#pIEL42*W~c64q<i1_Vx7v&^3bm**ZiMaP__86hVj0yx_-_9(rb>fS8a8C zq-n>=ZdX<-vB^$+W##6wTgz1AR=6G7I6qBN|H{9-wr_^!QR}(Ct6aCvto<&r*6m%U zao(TvxvReiY|+=;yk(+s^wskX+E?E%dOX2G_E%ieZ1wbhE0=G)4T~nflDDyn?EP0) z#muvZ?GxWh=lWn%mH73O&d$sYn6+@;d&4N*)i%++?vc^U-c7ar5EXrTlj*NB0pI7? z?Q!DezFwg4XxXE8b`e`6_-l9^?<Rg>;^=6&Q=4_+vEg^ef*!5wb8a$CmRlV^gUx+k z;OSF$xu5RL`m`YOLUq*T*IK88*1qcTeIUNZOYH31<^>t1(_YM6tF>`)@aeA~ThFZ3 z+Sn{5rkgb(H`?^9VOsiY)~iAGo4CCEOzY;))jS>Y`}n-eKdM)Kx6W>ly8iN)qx_-Y z2PVuuV1MT4r`fmib!+vatM)zoSMap>-lb}tTkTuU-1g|7_)318jk|0Z|9tl2^&5E4 zWv^*+J{|JujcMdntN!}seBYDXRxb$*n!iE)pIDV&ORfAWLk0J{oXqRC^+x5d2|E3* zeyLSY|C{w}S4^+3jC%DfeAd50vo+TzSgzW$>A&*r1$)JOkMe50Ygw6Kc8e{Zk7ND% z&Bs^ea`y$^PMcWm(0g^Ji7;F2@=32%>%;y(IlERnan;-MOH0qbXYT${_)5mX@vqtQ zH-W#mE8V~5b?z3Yt=rAG%LdQdUT@Vn-xSE5@Z)VkP4D9a$FEfug>16^COhYkAlv;1 zJL2aa%MW9Yojxb*{nZb*ufDJ~U7EEaBYoCwcpzkC{+o6$`C{FY)O&6^OFLgEHu(K5 z&PrRM%X<IatCX2fSti|F5|#SY^6UDw_B#EN>+F6oTx`D5z$W<j%Hs<bD|ABYpTBF~ z)4bss=W&Tsn?t)VUwTzC_1=Pg2HW;7bekz}bNgFNabdGmjz#ifuNi^Np*xq|7v1*! zE&FV?sXw&OGfB043pu&{9E)AswCkzsch)9k&OP4OvPD0H+sGp9?eia;T07J78Xsgh zu(u@~Pc`YeIdg`f)<xGZ;Y(-Fx^&Fl)Kxvld6{o*(AJP>;rjEQtFEMS1jRqweLt8v z%v|TO$?uz44~uVJ`po;iUHh~7ce(Cw$|v{CeetTl@{RW%#)+$}XDSNpQe9Esq!$1F z_K%HW_g}3!5$s&ZyL;)|N4y;kf}azw?+>Xw^l)d|qi@`;Hv(V%+;H!eeAxXn_PK97 zG;EfgvfAfpkg_d#y+HW)iQ2ypT#r}1JID5cI8)){kQ`e#=VxUGEe>~PO#ALzth2Xa z&ec!C%T@@V*!_>yeP3AWq-#g=^>rNou3KFiH@UoYzvb_kZO<yhpXI-_6?^MEY3J;W zv>P9%S()(nZ0WsKr^n;CDsJt}xBq6Em_AE7C>Z)U$LrHq0m}nFiv>MjZLmm9ef{WN zEn`l-u;0HWQTxt*{1~b(ExhcOP-6DA)RR(Y-!lJ}v-tS<s%2-B@-`#)^_{EO=4^Jq zx-zz?ulb0(%E5-!Ax8Zkn`$d}NbR4>_h+}IeOAWl^I_2$?`*~1x=*T<&b*=hOiKZ_ z7C>mzmPNXr3%2>l{tBBH`hNne`<0U5t!uYDT2NQ{Y}c=Pj@?g>^Mrr>-0U4X_e#ui zp^8gB*H7zA`>46PJNIi|z}l0WbZ(0~6&JqdU8P^XJ#JNZe54pldHx1@pKX5^US9o~ z>1Vrwfz#G$&5Lq5S1m35Ssr{|l4<sR_HRm)uk3nsJn?O((5=mO&+eU@?0a~|+v~5T zpIG!im1#~ZU$=1Gu7Blgt)5S`knOsBb$ZJ7xK(U#gZ`AoE2zHYZChx3`&s7M^wkfa zZ(4dj_we6~8_fGR|D0Xj@A~_q{r5Y?=PRu``ZV@F5RmSxdG+Z}y4m5ISAHG76ZdMu z_75wxtX;kYU+$gyN`8k)?A!-BR($D~7c7hT`}Q%nV_??49^X~$-S@(`Ub%FA_2i_+ ziL3l1g;qyRTW-GMS`4TYvqkf%Wme_V^bjMi-r_aS-FTZ8C9lfgnBVYu2Y3I~>pxyk zUa07in;tMF*D_6bNq#`*33G?H;+q3wD<*FZ{(8eBo}X3o)gih68=hTHT@xVwpT%v} z<d%bmdT*HLdS!ilEW2G$K}(WJ>I+|?SaI&o+`X;tul$v=SMgW>ViR3_&RzCn$dkh> zx2|GuU->Udalb$*pGx}tTkjscTUG8={BeH7;(Z)WkFUPJWwe#w;qTmiakX|ljjMFh zR+a6$pLIH9k8iD>@piNSJFlMU`@Q(dmS3APvg+pcuX=6%Rc`yYMJuhB*<9ZxUJ~10 zI_p{1`Mc{<V{aA3#h6~doLDjUO{|t?iTo<L*{c@lM1QsFlz)EnhSelf{}ro!V*fV1 z^SJfN_Fv+{CF<g9C#>r{l<RY~Afxq_S9tI$x#`bWg{6F1FfIOmXvFOBxd#0wtKV1# z8H?vVmS*^?AKw0K<^0uAwO<lSJ8Pn2a$oVDDP85myvpWc@uIcr-suYOH$L|;63@Gu z-u6rI+|L(RJN?=x&z;+|=lDFuR59p+lG_oxH&!aI{n>q>B_ls5Ez{}y1(s#JdsaS` zZ1v7s?Yrmulk-0FC!g8CZ51eZ!}WChO}FhU9M<i~ZdvXu7(1oJS0vA{{$I_$pU<Sr z-rw_0N?Nr1aAvXhbiJqFZs(^T?GimR&vy4yagK}I!aPpLY}vj2URAfM_p}XFU$fTx zJYm>=uS$FWpHJM}Vmb*gE-X}0SFg5Gxp)+$bTw$^I`@{zysB54^J>3E`nO+Rmz9+@ z!>Uwk>(;HH1se+#UUsYBNo!RpzL?k5)g@tFrc?X-+tYUWI*0Y&|LxXWx_r5D+8K$w zJs;ifRlm3OZ&%*Mx05Mk3%~E>hz$vhZi^@S+x=YPty0u*<cN#ij|a^EKF|OEVgLWX z=Py6(&~urzGecZ|?-!x_HJ^FCr|T`P{_a=NJn?hES<~wuemw5~e1MsML;86+kg*(^ zn>)<5=iRkRJ2&U#BG>MUHye*f)isJ6&Gd<>`FQlnlP4RJkMkWmG)rPnaK|=9)8dQU zii(RRjnjA@AM1VGt-sG<d2ymewf@w}lMl}@Oy2RJi92H7o=!%a)(q(&WAWVO>(=#E zetsq>B66f%zV60SVM~X8IopU$DV+0bze(or`?+lSVZk`RNjo!){q6snNSo)S+}xBJ z6t==V`4|r<@Wk|DPAv1CZ6n+FAt@+LF!#~y{Cy8^Wv_p__xrua?{>fcR$?LBbu;JL ztn76U9~^9cb8qkL7cVmW+g0}TUpaI1r*-WwljLJP54*J2C478zbROSwXDuC_ls7jv zetCVp|NZ{|`%af!70FXJEiSAB#gT2bSz%$}p5O0w&*NKuxT~iJ<eZ!v8ycs_Rh_*2 zkV9YPWXzoD$K|Sfu3QP3rXR02ef{=?LoJ*-QCm9F=hse?ulsQjq)a(gtnl14-RNVw z+wUBDbhLXXXo6DKZ#ih@^V*uo!|(3yetC2A^5usG?>S~Ydvr&}vZ&?b<KvqX4l>2n z|1I@zzr1qF^y$Wlhgc3BJ{-9{PnNCu;AO?mbN-WdX6)_i;!^XO;o#xHA#Ij(;QaaX zmlaE`*!ksB9v$hl`EtQoCu+-y%MUxw`M*ooi+X>MU0y|9y*+k!nWvJy`{6d;$9uou z15LX6%rfbe&fjzKvSOznC<dmM->Ymt+AaS1>-G4{%l+j+j<{QPJ9ka&?rFQ<@0&eQ z+5OV`czgeL6)Qu{%^cI;-rnASa<cm7f`?9V6%Sec+aHUrTD^LvRjHQR<j%Fx+l3?~ zUc8*(@?6EV_~EQakCKk{$$BRxDP><<GqF4F)`gA9$0f}3WVYWa;{N~VxxKAy--|g< z7Aamd^1Zy{^}5|F)~rc6IZ1WWiQ5tX|NZ^>;V^&Y_q*jkA2jpZ$o9QhqB65vOgCyv zN9gLXjWs`u9zA+wBik1~%QRc8-|m+Nzs(1R-{0PTF0oi7Jjtj#<JvUc=oxmkR`vfr z&yU<uuyFa|k6CJyJ0*?NCQP4xyieBp#kIAwmpcp1ZNGBH_421rpCoLn!0Bf7`hBlH zeOE7UH%>oikak8Q?aYjWn^I4MoM5vgO>d6z?6YTPoAWmxJisnrqtJQBx9aPwqw4c( z4xO5+UHSX%c95@JRAzE7|M%m#{ieFVRblI5JX2DZEI<4*NN?Ydq<NLkB;~5#7@FnZ zd-JluMO`sf?Ba=6S6A=+b}PH``P}jy@Av(-k@cINVm5o{t5vHlYJP0s$xw_@G%bFp zp{(3&n0&0@<<jY&J|35^wwj~2cEg4VhRMeaN?rtnt&M8!@0aoDR`Wa?b3>xnEpO*j zv83eW%J+M}gA7cUyzuC_eEk#s`k&p)4-3l9Q7KORy8Hg$zQ4b}Z?5@S)YRN;E8EAQ z<~QerxBlKE#^-Gg&oa#h`TM|<GfE5*`)VwUpPzfWxZf`6-k!>NeC{_cn)F&0KiiOa zm<?2(*3|4-?kptRKP8ey#<pro_4~ck@BevbKIw$D!d$=O_5XjzD=8`Mc)RVk!Au{% z^VhFk^OAJ)IK5}}>Q$?fPEFC2;9)b%xzVtH|NiC9LcSIS4;Ut^`97NHF1L}7tM=EI z%(V0K&YqiVeRFrYzOsAYmx3vWoKp(A*1c<Fms7B{oeNIv?;o`B%b%N_zwhMU@Apn0 z=@kC>{rmH4(fLa^Z4zoecwqVbI<1p?xF=7m6#w>a_xqy%f4_hJ`Fwuy-O}roRx%G4 zv2u%TsQX*xH_xWiZ~5UIGv*81^W**ISUi0AqNUyA?4H%P_Sf5k5}Uv6*C{HW{8a4i z=LawMD|~fD)5LePT2aGfb^oFt9}@Z9)NMQ`Rf>ni#GL6hzjxwDr*P%JpU-V&`wA|$ z@k&dW<w(pn%PsPFBsMLm`^7AkndOGFmKA=#TOJ%2cW#oZ_lK`jFRRJUU6#4$(<$vU zGYp%XnwWar7GM6^<EHFAU9YsbWYOXYDff>4`MSRT>1qA_pj>k)e&=L^*=JvrSbeFg z?VkQ+`Lbn2PfiG$yQ*0Uc|MChacymM<*%2^D?c6;-}z*cw~cIH!Nj=r=?@RJE?Kg~ zAoJ3aG~rzb6B3@Dnwr<+S0Zw0_R{VXr%xxJnPJ!?W!e?GI_%`%lh&HPmn+`y{a*3q zqPyWtA3txs!|nX(|Ns4!>+q|X@Fne|TH5BB@Av&a_wtMNyB*AX<Mf$*ONy-K_Wgdh zyZ>-Izj5iSkP@rd#os?4Xk?bLue;+c$mKsV<(;cp?yV!C;ju@B{cRo=ocvyV-WIg* zGGb?uYG7cXTu;E3sdlx$Hk7@M`uBbRe?cj!u7e31?9vS+e*F1--d1An2Nus~aVbwv zP5trX$A|6v|Mq5HUN&*&%#;51e~--n|0f+(z8>q9e*RLxRr=D)k~8z|=U=%JqPPD~ z(QA{*Cy%JluX*(FMayo_vv<5RX1UeW*jQRxHe}6ZWo3Q%`t|9j)8j#rVk5IKBVWGe z10%ovAA{7?)E6aImo8uS^zisl5^>1($vvHWNw2T1z2?HV>U?2jq-5IWnKy1koJlL5 zF17O6{QJ|ZtysRlHk`fuzv<Ne`!y|pqxV1kXs`eD(QElHB_WGs@6=a%EY6&CX77<x zQ?);S{=9hGwrf^ri>5x1&fjxzUF>d9?%TL=<2<g5Ys+NU=T@q%7dhEtEq1x~#q>8f zen}=Ce*dw=;gIhxzu>c{Yd@V-=j*&P?`BTg>1n#4=+lkfw!_lsA!qIJnB!Y+|9ke* zpheo#=sVNyvbRdc#+z?eo=G#_xpQaD$D`tTU0xNl>I;@EcNWM~Nfp!o@N)TlGp&s` zF2DZz<;~5>{Puq)yu7@8x22V0i?zq;JKQ?a+s<SvegFFP=<(z2?Q&HeQ>KV`K5?or z%$!+X^!wY}$4^d9?p^l!Yt^r>uaCRS*B<%t@v*JIOo2mlm!#f1xi)6!rH8NVy|Zf` z9%_Aad%M5TPJ!5#EoZEE`rG|HQnguiZ`}C?M&^h;6^6;jdOjAUEK**racYTycI&35 zlD3$N^2wL2lzokZ!zTCzrg1TJDzE=k;POuK<Q`#fPtS)hE-t=S9c%yp&u7qTU84sr z;;VE{K0I-4>6@6ZN*Pjx%*%vi<orW_My~Suta;MfYyCm-;+N~icW>GA=W_MUO@F?( z99NAN-o82W?Lvdk0@eGgdxdxJKOi9BwSS{|Ky+x=y$9!4Xp0GnO)iN$Z5}p#a(NQ_ z{+bUAkJr^kO{$Exp0l-es&#zv^;f%EN>7KLR$doxu~}Z)KX$$Co-Mz^_}!n*Qv5i1 zrtQ1(d3=j6b8x*rc*0vg@%*ds58OOYSKY5`^h;koDQ)Rm_3uykrcb|~{^V*-)Gv#V z%=#H+QPmx9ET`;CUjO{aJAH|whp|2T-~DGe;dT4K_y02v&v{-p?{bmv)~P>!u|5>P z(Yqq<Fk^@RJ1h0Scc-2CeA?(nfy*)V9B*s$LkF@KerI)E686s_OI<o4ZQF9@7b#qu z`GV6|ExbPAwXBe(Lq&h%j~BeYdp2#HwC8ci)ThGs9}cB0-#UHIWUa*SvbLwK)>c2# z@cQf@6gkN|Ama795W8Kul6H1gzk2s`HoQrm{gInzarOJaT=5cib#(`8&CQ%`cbPiH zoBZw_)q8m6;Z}w(Qc2RPt2U{KZ@%dg5W!#dW&WE_n~M5!j|m7kmAs#L)-PK>a^-7| z-dDa`VmF<&-O2oaK|#~5qg%2fm-E-1Kh`f_oY9)Tbe(eD1(OoHUuNAq7f*harT+9W zx8ucmeNH<r&pd3u@bb?K#y^!9&Xl@+tNR|l>`d&HjC+snES_`gw`t?TyOza2)Y<%Y zO>Ie>9y$NK<+j!x|AJ*F&E1@NR#*G^kFc`3uS%k>Gtbl}ZZG|JNBFkp8JiOiGRqk^ zyqw%R<=OlPr`qkA7p&5m-*l##XXl5!GikzGr>Z`YxqWDvzg+qoQ-8<igJwp2{~SF3 zdGh=_cqK$6Xv*BK_3;M5`IW7@+W!tLjK9a6a8iEK%(~;Zzs$F2f3tYDg!ya9Gs~jN zYCntj<wW|te;97?_M7>+$FeVOsLbTP$SIMnb;5QhbNqjWZEGsHf^%6})A=Tvd~0+2 zyzG7S*@s{Mr#;&%pTxnTXqL&eI&OE@?RdYV$KC&)elBzS)P$FP<`0X^*6vLG`og^P z;dGlLv+D2q`MN6pJ2-Jh4>*Z&9?p%Ian|3}Z~FdTV(pxnpNuo4+OPkeefaf1--Ha4 z#Er}|Yd)XmyS;ek>l-^?o&UjFmi#1jKkEXO_bj*fSIm<v|Hs{M(tN*<=et5Cr^P#8 zguiE)Fn?eBtW!x<eET}y#_w}TIlnNb<oWJ3@qa%2+`}q6Po-GVs&UO0-Wk4Idv-ig zJa)E<E!mg#w%u>#TKCx32Jw*xGq2Tt5xD-pPPdJrbau%92Oe2kT`RQCs$1Cfbv@EK z#dWDu-sJ2rtMtn;kzpPw{;yyEZC1A2`dnM-(WI4HXE*CD*RY<t@bdeuc6O6L88dAE zmuY`c(02BnXR-J9^lV%<=i~Li7p>Or`C!6O_*Fggb&u&2ncHtJJUZtU?Vb^$6uI)X zr&KkwVePR^&v);iWbw!=ysUJ&>eVnstHv`T$E$W8w4bpe?(mCw7Pk`j<<9>*ao^(g zi=)5qyO!CS&i6oG#<QS8X2B`Ve+LC!zR6_GJ$}<9e440GqUW=lPh@U8Wt1p6KD1qP za?iO4=VJ@yJ@-8b&tjbAmi9`&<><G3vx(2=-a5MR?P*E-*OKio-M8y1>uj@kOtfV< zVYjW*Dp=Q+{rrZvtFM&)c=45`{kY)ebR7ouvf6tuy3gPCFnXV~s{3J%R!UA@-K-Z8 zMtuKU6cwh-P`NF-w|V*9rxEejOg3FIn_%+H>iBiJC};iMDa*4S2g_6)F`4!3(WXDm z${$Tx0wz`W^c=Pqnr$-iK%Qa9HTBPTSBo3|I@Nk@o>^;T`wFeIo3H(yJ!#WF`!Dki z*qt3#l-|18^H=8n&PhKSw=HfrZm(NZ{V0RU>B^05rN^X-{BssZ`_#X-Y<e_DIb`ay zt*=-L)2}={t)nVg@TXeCgZVzg3qz?bR#%%B|DT$`QIv1<Q***r=B%!R0z9Fv0TWlx zldd&)QQvJo@0yk^^U8P!4;>Ys%&J*0EI@@&**B3|x47K3mDa(5lYDbSIVbLIi(DQ$ zb?(z6@AP-RJ1M{Ra#3Gy;)gA)uNs#%`d!bMwfZy@2Umaceg1rd*PZeV96Y@XSD8#t zwhj}p|G?z5xGMVj)+rHHd|CVcm!I3H8&h#S`r7fUPg&pm{+IuQ-BrN+1JjvhQ8hJx zEsB4rPdawDW8*HFy$9#t5x%{`_?p3|OYUpd+iv{L{i|n}*xdekv$~Z2G%L@FEl<Dt zF#1^{r$BhU%1i@Mw)-5;d2I(gEcQIQGd=qHsm6>f?S$*QCw#M1@oD4iU-85?Rgq`a zdo5|H`gb2qmT%o?rk*B|k=F6%{vVTzg>&wFR(0ssJ$>N9yC1A=fx&?+4L5U=Zl~9$ zyt)&<CUxShQ%PM#mpY^?7;n0pC9Tmcw>mpDH4>C*PqdatPc94CF0sn%^U9SPMH=-C zpdyjsV&~cK|IMz2Oe!uhp0%@YPw?&=d)|1e-TT30D%#4z;$Bp9{rME}c?&JRYh2`1 z_OSn;YgffQGxIeEPp{gx`!26H8S$-EEd23QChos{mR9%d*!=Ws52K$ksJ@!Rez7^{ zvJ(4&lk?BzR^Hqla(dtK7t@}zPCc>xf2``B&i$<W6OKQx_HVw!{NVoEJC8C?M??qB z<lmYqaB=_7%tgr-KR)lj@&EDdhOERk7qtuNS4{n$f4wL@W8;I^vf9r^ADNd2Mu#5i zn7O}jMf2<0zZ{(}JY56T0y&ipSXz=+t<5pv%_xi%^GsfsenWNJMmOihzYS7;+48B| zX0P_T@%ioQYu&Bi{(i7ptoMKJ)^B$&JeeJr@;bf#$piiOLiPz-!O!%Zo-bBcP?=<` zX>a`SSGwkj8~zR+Cd>J2^54#zIdxaxy~FEEG!$oMt-kU9akS5lhn4NW_HVzKIcwR@ zWY^c1rhR_2YUlGWw|wgZIlnG?o+EzZ$-DN)_YY1{kKVrKkI0Sxiax*pAJE_O^rz$2 z6WslWezYs>>Hl2mbxBcYW9h~%PhygCJ)fCbY~s?ZI=D@Lu5Wh!Wwv`q<kROKUl_{$ z?yq~|Zrx}O|LXS#-4=VSeepr}^D3qlHryMPb2^u;;^?bo_ndAr?|)9$toZl*$GkMo zGwz+Qb$&@5qvY%>HLv3u78Wbk&B?V*zZ~MZ_yI@HUhxZ#{}QL3SUh>Q-;)a#6T_c4 z-ea8F!hPvV)gt!QH_qh*x=R}#zEZ@m7rOLxXMe-Ge^tEc8{NJ&f8m|5S6I!Kk9B3i zn`nuWxoe-^yHcgw<>%xwDfv>F+1j18L9thgWSls@zxr_UPtL4gu@kv}+c(V$n)-n) zj`!}{z8@x=y*{)#ya<k8w%Uf<eShP_?JJL;yuLcKPVrSxMfah{6E+IEooSv`G<Am0 z)d$im{K}ZVWE|C%`^2|uo}zL+>%M=lyc3S!HuxJ^dNu6{gGW3+^SZV*a}6Hx-S}a2 zWm<E6#OIB_el;tyoZ75Vr0`{JYu?_dxb>=m;`2kE%e}FjeeI4NXGew|pJL1J(jUSL zSTh^=j{S?8yFlBH)mGg?t*GI#{R*)Z`Q4v&L%+J;68w85e=}#7pT)I%*{2^qIBxJj z3$)U;EpBqiC8p@T`=Xn&KZc1OT$uXG<G}TJUt^Y)i(76PecfRr&9wN+`?~NIVLR{f z|9O-3?pzY9#@Uty8V1)L6IxbXXD=<!-FsCvYyOS-FG|eTF0H*3Bjdzz{>6opcVd=D zbu27gm2)9^%Pw`#cXr2rdikvuZvDHyV9va~(oMT>`}v5;vY%xMWX}C8^Ve-^!K$tY z2a>Mt^4WLq+n$wPf4^}T>ONCmtx&e)ac%IaO(98Jx9sA+6mqCnhQY4tYfZ+U<mrj& z8?(|h>=p`@_%!PqhhK}XakAyx_`2soPL%iWB|9xz1m;~_IJxqp=8DyUp8O&9pJzPO zlAN_F_j77a+m4N|D!VWFoVfY;hV$c`Sy_qFZ>kp0@ePa@X;YA>+ntq|G(DvG_4^}{ z!OxryNQuY=cV4)6Go)ixe&Y43E8cRw&-UK4G+k=C#+;*3MN&Sd7qT}c_pDnZ{wC}3 zu4l`)Zt<Vh<IM5UP}XXu_?7FY7qi`1cC<fO_uC)mZJ9^aWuiA6<FeQqcJ;jS@0CAw zPj~x;b$YCBo+WhETP?B6YuU72n{K8=hxz<96|Q8Tb39_!!hI$TtGq+K?XIkw8Xdi^ zPlYXRt(>@A_(v7L&C$msIo`hf!FtsoEI?hcw&tq%EZgvF**E>K6?HwUnWg=E$x2W_ zTuz+4bJ<Oy6}A2oPcRAytn-tJx^nf}bk#GfuFm*m$+O38DkG2Mgx%q>o8l%epOp4b zu~g`)z@n(nGjCu0)gxN)D*dZfx1Di__OB~Zq1!f=JXxdH7QBCj-lS=h7ynaSwJv9k z{@IK)i%+I1_a8(galTxb^-S#P%~h!}lk%d=4o5hCUDYX-vAQ#Q$ELVs(J9YYDo;K1 z_?7pen<nAkJcA246m6C}e@k1b+q@-ol{x#3U5dY2S1l1Y4~sRJ@@?v_Uqu&6v;JL{ zzIyW9LGu-2OBExwDzV4#rp|noH2=@xSCs)@Uo9*SF+Xr;ufRN(zj~o}rF2W|4Bpjk zebaMR%TuaJK_h6Yywck~sgkOz#m|0xU$r%RRh!*q+1D4-FE4O!uKxeKb%ov(=2y`d zk98f}IBV5a@v9SNOTX6-zxH}@dxJr#bkl{3sT*ErN&7cH`|eo`c5ZNtiOQb-7!#Ev zJB!OM2DIyL=1^=Yn2WaAb5ZZivuZ}c*Gs!@uPs{^;rbcWGCub0{|B}E|NgqII(=^2 z$xq*Eervt9tC`UCXpLFqJlpVO-BVtPXZPnlzwzy9u3U45^rSPb8O-Y6*DW&nufnic zuYS$hY0=T4r`D~HPdamTzq-YqTsM2m=@H70*eBN<ocrd-r&hC0$1S#=&z$BgpYu5S z=hOQAZkuDW)@1LlmWg0<<Lk|uJ^Sf=|1}FQ)~?Vvmp9qM<@W0d;=G&>!)Cd?TE=g& z>1ncC{8twC>;ESI`EvJ&n(u?A+i~0ZCYRM5Up_^A?m_(x(w4`!UCRHHQ^mh~PE!x_ z70GOiE$?iZoEAwGPn9xUs`B3=+Wxn4rTRAGKa<)eN{_y`DqUl>Q_#O%?PLtc+`f4y z#Wxnde4Mgu-Q!2Q|MjliHtGHSoxNY>|F&t%$9eju8om~@KNFk3Vp?X(`NW)GPdGvL zEEK<cdYWi`!iz7}oZVaR-dy|PjH2G|dd``e_MZ>i=cnH|`u*{1@gt4%|2f`T#y^`U z{nQ=TBmBDr7<kVna+s7Kf3;)&6Ni1ulT-9qR<$q~{AjZN$lrIs-lD0~+~)Z9{JSk1 zmofccP_S;j{M3EtBAgSSDRylNo)w#R|KjEgFKasFEqIIPPV9Olb0}$&MBT||p6$}c zn=Mn*{RIW>ZzRsLPA-kf&#&QSoFckpd*n^`EwVpXi7w*2`@4tnK*;KMMq*M^Pdxnk z|KXK;p(Xw@xvQ<WA2@#9|L?+?(Ods*YAWIT^Mya{&d>FHf~))c^{3zaZ#a9J-jZ#r zt{hz}@J>m$SaH@8WeuHa2QIwJcxJWl*K5(3vj0L(i-k1L+1|>?<Gr3&{3L6ps)^Rb zdx!PY&u?E}^zrWhj~;7ybEALq2<O)@?mv*HdtT>`*QA{SWp5_O+*>*KnsCe1rIjM7 zO9N)rPdacx!YH_oE#$gm{C<a~LrI!vt^4W|B>p)*WVkXjOQ!z%Ri-Vg&Is8TNbTNN zcQSe7t<@UmmKnS@C}h?z&@6ixC%f&;qM27~H|u_XA$CZ%FDK3^^e?N)zB)&h_yTo? zgAWUN_P&U#tNU+v?cejfN9=yeHf0R<`|I_eSt)xa=cj!Bbbs>9ZGFty{}~TF{Q7_C zwpA^Ev;XlqygJ5jFk4Ff<g*vGe+|Q?mv=<?nu;>~c)`2&7TZHP*>7Sy)a!%38_xf< zMC$lv+Zn4A()Cl`H6(7|wrAd?k`p(Vvl*?^3v3Q**><*6Cf3h=59_=A@?DRf{lER} z!s)}8y^8ubK5Ff}^SP|?aEbqsTOm4!{#sqtE%+UG=iloOye%^XvtDeUHe=P*>8BgC z6%$uUZBTq_Y<gzai$7a_3D-qw`v+|^kFPi7ShMk#8OPe?No!YX9ef~v=TpxiWvd*c z^6OtY>-6f({MUs#Fa3E%KJk~tg5L=idsqHV5`LFxc6HPD+xwXc3f@{jnSbl;!;YM$ z!;d>&na)YJwqvysU%hOm<;Ks(LTz!crhV<a_WFamgZBAD6GH=vxP+EF-}k=qWfjwn z|AHm*%i3H{-(7#~?3_<6Qp#J_PMy=V&scVOsdvNT)rki}bNAalw6oh+*R$^xr(68j zmgUZcuWlU=pFDHdyskw)P0CeOD%T#(QC8uZtEp~py@7B3nbVsSt}toXFje0Rf1LN~ z_3lG_`#gIU;%D+7uWx9)zRG3ZJ~^Z9rhCskc`bYVU5RF2jOnr!w$272r(dKjn)~w? z>qLu3T>Zxc1gHDB#B6d;7C8I*!%3U8mR;fjF7+2)Em$VfwCL)KZ;dMipYX43*l=%x zLF8Vwk4|4NPb-Nk=(+`43$W|hca=+y?s_4din}KGP424s@~ZssK6A<03v_~eHSW(V z{kA~DAk50oILyf-=l9xR4#gNySLN(Vt(N5bt7erZOqrEt=5%b@HvP>mDvpt2F1Nn2 zXrB%$1#S7?!Z-Vj?)FI+e7^Sk_Vr(U@PRAT*nh?%wX0X1&ds|vHFC|~-E+Qd^N(L& zwfjhK=;_<P_r03-VsZG#C$cSx+vlFX#;NFX`_+cjX_sGLecyBT)uVaA`&S%K-?q|a z{!U@8e#e0FuXj34H+<i}>iv$@tGGg^JD;vPC4HxS{|gq8<*WDeIvRYCDpi@V@#MP> zg-12pf;g^E6<tzX@wa|f%^SbcWl~0be?5F%C*Hn(cj7na>@D9bR?BWny_eqhYoo`k zm32B*ec|?eQ8!u53^si%dfU6}^2fr6MZW|O-PP(cvfS}amhbN;IcL2+yDvWe77!eG zVtfAGGhg@rKbg2|<+d){`+HCAdmsP&+5g*Z^&7HvXHDL{KjnD%|NcvVCWAV~&GiP) ztb|ipms?a<$zRT^p1Uu3U3Qt|yF2`@H&?#-^U8n8`~TDaJ<dPo{@yz`RMVEtC-H^r zcguU}_gH_|S4^I}Ixgh5&Wg9c{mXAm+bMAGNZp;Y#ey;yCm$5o$@o-QZNO5Nd|}FM zY2WW(xl`_J_1|7q2^#2a{d|w*!J_!Rhp$A(rQUkGzWAzge8J7X-gEBVS*=+9uDxSN zid+23U!UVkp4;#I(6@cZlX>4QtE=Q^Pq%$}$>>&gPDDDWPCX~pySuWlWSU;AuT5UI zo!vg3d1cc-N1Q9XvhctKiRG88zs&Y|pE!Nz7M}8V?QPrjFZ_HVS@bY=&W*2?-RpDD zZ%mx~azm<^;+?lo-sx+evux^L-?%4uw?y^V_nmJnc><QU{>{FpqM*{%WX#Ul`QqdX z?Yj1J?*6Zi@q66-VSns=Roj(b`3bcp!iUrU9lIs8S-$+Ty~dmgCs;0->8HK9x<CE* zbbSG-nFr4Nw#zA#U8ixz>deQv+AForE;sqFGCA$P{h}(~=O?Z$^}Bvu#@BfAwwKC5 zW_!-_`u}A*@Ur=S@RX@dH&c#8)UzM`oVsf5qbKk54Ov=19m{K(&o|4@s{Z@3`Tpm_ z*4r=EACg&i_n%efY_ZLiKPU6dGV1r-{J-Vi_4)C3H5>MY?z`~v)9O>_gam|AYwsu? zYjd5nQ-C2w=GVkIkE3VSY~EG=qyPQiuD$pFp0(0Aa&4;r<@772U!-abXQicmmA=0C zJ9om7Gwq&I)wa^p|Me|;6OwlCH{;Be`#=1(&r5vqrP`3C#iDPw<mLWLO~E-4pQ4NW zbDlri{m-|sEUNo;2B>1+y}$0}tR>&q)U}%apLKlB^KwD+f>oElnz}Flthnbm1J^kj z1_kY0W=Zz?lvldz83N{1Px)*A@2*vS_Ayh|((CTk)9?JYe|`V?X8EY9+V_dmCmWQg zS<U6!yWZY;+5NMfvGX5_-{5t2&|qLx4D7wObmnV=t6`I>i`b*>YiB*-e#X4ze#PqN zpe@@6?!EtaszrL<cDs2SAH?dEx0_v;wA}PGS?%tZbO+U4Pq^!jzRQnGJ94J|BR3E8 zg6|tnJ1$qQyU;r0teTd0F()@iVa!B7_w6tCF{t$JoVQ^{UCYrg*@d#YmOFoY`@Q|W zEO3&}DKFJs-%q%`E^e*$O!@xGwP)`${%gk{ZtN4!+LCsF_du2O-CL`I_}0}PxB6T2 zy;*y`yiG1+_Wx@B$@z7Wsvi&J$=v>^`FMT3SaPZ5zsAHDy#M%4|2==$@P`x=N8g*H z6JCCg*uHh|v1nWINoVe^`JmDAg<*eyzq`^K(KOkziZ$Q2{xuGt`YdssaZq@4=Xynk zh7B|Rg@`=2h@G}><>{%jXT6uXb}^vPPl{RXT<Whs^*grgyQXDP%+Or#aoTv>r1%8$ zw%9)mQ<v^M@bf);c-(x0FF}8rl`Qss4o>>jv)Fxq=N#Yr&c_bQYo4`t{NLGoJT~K< z+`DNX!~QZKzGGyT6MSddnf7D;4_{_a-<e%1d(HJ^apkxCext{yPR`>yx_DQ6*&6S3 z=BC9bEVi`WSi*TN)Ai;`mm{je5@Ox`>*ZS`HIMMl;A+^pZrX=1KAwwrcFcahoA3Vw z4ZpX)+0MqK``((Bw#>r1x8ujbwOyAb_csJ^oqMx=+b8L)+?hucZ#LdtliW4$eO<xR zuU7K5Cxf3)-t|(M%Q$#O#pBOc!lq8z^^&>i@MDhd!oM7gZI4Ii>TXy4{Nh5KkG#q8 z*wwEOJTp?M+w`WJFYUmQop1g=EdA50^kSyX+&z=6Kk|2~DCtSc%g0Yzeoj62b5eHG z37_cm8@lBgGOh?2UzfaEvRiEW-yO3V7hdH1%&5EWaH8!jHqaJ!JLUCh-_7eEPXB-R z{E5@`-g7rj+j3Uk@Kx9GwS_m<pBJ6Bt|@E9PU#!J?`B_XTy~oKYKPu5;f3p_MP|Kb zziDta%xbOhe6WWYnwQ->I4?hb>H8OvKYp<qW}K4Msjst{e&_SP!!@R%Szjb4Z@hKu z()R0dkJrxQ{#$(B_Iu219nT$4em<Z7{MqdMv=<i^&f`0}dhM-?yACENPgYA<qp6;H z__xgcpPGT3${zEI+Q0t%(I`Htx`sP4^R>oV>&|!w17`Krb~iL%|Mxz&Q2rx7kMgeX z9(?P6o6lVN`hql5hrEI4-2Qo8k8=3_d@(!tun<(Fyiu0Ea7OLWW44F#A{QT7t@8S8 zvEiHiljZM^>1*^HxRAlOw)*_99nTlMbonN8=;K^%%N^h5i#%Tf8nbP2`<ixtmigRu z>n%%{N%5`wt6r(T?Xmcc-i5|>zOIF4x9$JiU;4iGnEQM8%0#wA!@nJGELrAq-+jkr z%)hbz>}-+L<w4Q0ZV^89%f)5pp05K<L&Y`g=Y9Gr*47}9m3>OG@TBt#-hV&X-4oX6 zC7<|Gz2>f7_om>Ro2vv>cOGA{R!en7w2ot9U-`Aq+#E}nZR)tYT6|)8k^0Ht_X@vH zux;vFv;6&w?3G&9ryJ+rQ!}xeXsnri(kr@uS>~4)_MOey_Z5Gia4WH^s^Xh<Z<W!F zH6MHRO6}ilGjwQOboph(wj9agXC9~b*v>sIvB0TB?A$Sislp4KN*sBs_ulA!Y26pe zy}vx!WRb3ik@zC+taasWFXlWcs)H^s6F9^T-J=LOUT6-3Xxz)|)3^Rz`rN4`1$3H# z)b;!4FDr693=2vVr0Fq4t>|t+>-|!0Ip`!2fA)uK=T$u7yma}p?6S3SduLr->@F-W z{@mbiulc<U6JHL+m@S8{Ulyz|wzszrTN80H<JYlXX<0dSH8n3Kai=-rnwz&QuKfIL zt4068ga_xW-{<^KXc36>om6QpWm92r^5n_0=aNmNW*VpW%~ld}s?hd)_BQ9=pPv#u zY|GETEU^MD)|jB^d`D)gz@giq-GSThmPxBkKKZhE-@bik=G)&tE6Az1XQImIvS~AB zoY+zL_`=JQ-g(9|eeTqJJ}cMZ#qls#W#;aKe|~<x`1&i~<(itB88($hot>R>U0xgy zeL-?}b{1#em>a+RvS+6&$Hg?2nY$gozq>oruJ+ge`}b<y-9w+(%G94%nS4e?GRV_| ziN%Rm*6F<xhtj1G9UX14urT@S>1*Gtd$;Iaa%61mT~Tq-@UR0-tZzD4gt8g}E_<r( z{odla%%+~jt<C39i;s~-P5ko$i#s!a@19@%{^9J|_wVeyFBblM`<<fhW+6_+IlUsE z^)@9P<@$VeXLmRE=JfMw3JM1fu51xF=hRgx9=WSTbKSbL@jFas`mBlAc<5kfi@-UT zu1fKj*Vam#-z^co@MrCL*KRROi-`h<W_lRDcRD>?pFQE?BG-z_N=u7gfkQL5R9v`r zaf{ov{}Hb{bo|a=Fp-=Z<=y(;DQvBFd5O$&k(=jxuNFULU%KPliK&(1MS(kwGcFZX z@y&etLc@teUHRyq?%voRCVK1M_4O&X6c`1a**#<R>|+-NTLk<(x^@aUSukpX4r*ap zGJ{*OMR<bTg8c?+lPAvFl%w@&5(9^{<$aKw!<+rIpQS%8FL?IA{Yu!gh2Op`U-n05 zDyt^Lnc5G@RlIXAN6s!=@o5i>-=7aslE=3#49b2fzO&_6TUJcSyPjF!E$%fwl$F~5 zGDi2Pr2CD{AGi1H{plapUFmnouWZe3X8-vDHO@*IR^i@(ZaViG|9;?>bjm#EnRV)% z(Z^}~jdHH#%kJ}c>gd~CZD=1J?RDk%>J^%2lWu)7=a4kH`zPwpyRS08-t_<YE|d5E zY?)SVvhBJ&IkUaj^-DBrmBl9)=14m)yMKCzYdxESeX73oHQnT!w-(Euda&$enq8e@ zb9zK=eq51B@Vkns9hu)53bLNh7D+u~l=W^g&x{IohQRmt@4xyLyVc)`<M+nbbAIl; z6|}D^Rqm?lOr5Ht<*thC5@mOpzq~LP<bN;s?M}{eE8*XqH`VuNU$;6s^X$>J?_ab& zOTBy8EiiVHXKiR;yRpa;*#o|heZSvZyk_71)8<!VPB0ctE@KvuDx6yx+5d0y2kyQN zmd$&=dvYYkm+3wWe7}CtE|bZx-$nM{I{oW$>~a0b?DM|2dM~bUzaNpm@lDPjzHhld z_nr;kApS(%eeu`#z6V^7ZqxY8@lMXJqJ%r=dc-xOC+hCPMj29EOS`X@>dmvdXg+tb zhOOBC3kxeM*k?}XpIIj#k(qj3s`}kzfkXe^n4K;9_J#k+@*@|rU*t3$Qs44x-+_IP zb^gUhmb9%AzQ5pNnYwwQIJ5da&-IDs3=;}-q|^Q1FHrd{(LL|S#7S?2Wqv#<+{4UX za5#T^z&vsPGt1mRe0h0r4!aq1LdK<ulYa>Rwy&FW@^qZr$`V!cO!KU@_7lz59=xzb z`Sq3UGJi^VnbqzbY*~7qvEadDbq(9<rlZ-j)+h1j#X29FSI&52Pnv;o*q+pRi&p5J zRWVoOstvZ?*%^4I{s(t)V$KT9g*y846feI&oN?uHM7(R_Eyr*5e<UVy|GTiL;n|V@ z9-*FUTIK#FrB6ddR35*2c5;e!+{Rf8|F@)y%(;2~Myr4F6?38QZ%;3gyW{fy;pZ9K z{`86+-)-=gfo*T!Ji)d0P7Br+7pVR&+4=EOf1RJ-A^(gmcRg?HoyXc=>z***<MZoW z*?7g4(lYI5E7`X*2*~Zc@~m`|f1P{Mnd&ofU*kiv^qUSH|NJ%kbL77uBd?{}50k|v zZ~E_S62}-aJtc6$uIZiI_j#OI*1l59PyOoy_nvv*C92KVnf1S1RCN5ZI!kP=YN%^w z&#dnnjSnB+{B&HgXU9LqkSyKC+G9oQw)H$<oXlwOqBKS3_PGZu%V!^-S#sMuM0Dxm zYitIe-)%p8nmg$G#0}47)9!9>Y?~$2ms3CQSn<^znR^&dc;Dhx6YjkDexk%*IjLNR zdydQ?y)Eu~hW*J#QWn3ya_`98W%#MhoneL6xd$J%rSHsp`YX(MN{YODc)VxE5g)$% zdcOS^7M_Xu$!9oQZd+B)=X3rWw|ujiae8j^w>Oj5K9;@n%l(<nhxn#L>H)En`pOgR zXZNocIApb3^z)-N&n&OLt37t(%fDHhHoMgS5a^!Y<+L=f?$q4f%jI|N;*whB{oxDe zu@s}ANwsqh2G{u}{!%=qS2OF!itU_lggv9)sQ1MG(m7de9`)xH|Ag5htO<JOxLTPe zUu@X7k#TC2cV(Up*HZ3-%*z-GzFpxrF$)p2s#sRZ<2<?V&=zK~@ZG$oOW*u^z?k>z z{`vroSc^?>EtQt7+oEA2{%raCKd&`yYMrC+{@;-wzsNKE^bXhaGp1jiHlJ0Y;=z?L z<0s2q7Jubewzq8ia6*;kTj!G>{PpTNM|#7yPoBL+I^3Ms@o&_>Z7HWMGtS%Hw3@fu z-5iu~0)DV4iT`0N=a+{D!r7VTW+BWAK7QK%^6$oY8|V8MyI)+}yS_5A@?GW~+rMZ2 zzw|yoZ^_1mUB6x_wVm4`->_$jgjV-CgN##LQ@p~tg1!q$<XM(Zp1x&vL!5Hp{PRJf zbNX&+Go1ao^X{WH7Q5Pe-IiW!I_dK1U+<0`yP`$*G;R4S@ugQxUP|ufwrTqoiw8xQ zO<VE(y}Ck<$>iyK|9o!qRr@sQ`vci4`_C>4pCjsi>!H8o_79oePt%j^4_dF-|C2c> zTk_MS#eutaJa{RbGjG<3j^C5^EzZl^IQQ2oC9O}BIpi$PzB;@&$C7>9yUAxCGb%r` zaSA$9uW_#Huztym%AcwI>jf5tmT5n;vt?rnh>xxLX+GQM$?`X<H9e`@=gw)F`(@9H zf~U)mFc_p9`>QcUPolSq>--z_k`F$6{!}%dbaA}J*mUUl?CU!V<jXF&vf7y!PCshm z>{&MFr{C;3N9JGn)h>7?pJ|=e*YmGc-YlxVk@1<IrD5|&>yIzQT6Qm&-~6s}dg684 z1jFgk^X5A^mu@^Ny3f?pQ2K>^UF2u}$)CN7{U+9ZDRyG>%QkIZ=;<ElrgN9+_w45j zw7G*bSLiKs|L>{0ZSwRz><50;?CgDh;9BjbQkw?H$<u^yl*_Q&RbEQ^`Lu7nz#>pd zQ0u10pz!+1_ON*UlXiZ;CZ1<lv07`v#)Vw_=h??kHN7%rQelqu<LNfpant4t`6k@o z_)Po4q%{_^N=kX=UAkkxd6B}*;;pGH-z2-&?b}p2_e!lqZxz#d@ruQP{<j{kb<vAR zmfLQl-+95&c*W`yhZp28S+}VH#96O(DB}wA^LhrJxxSZoM)kC*z0%^g2#@wU@}-*d zh3%yp^-jn2#{Jp*SPKGfm+u!@Cc8zW?|If~i=B^4@7UIG%2|jm-ghypZBb7IkFS;6 zxu0_@@Af3$eqsD7O~gyQq*PSww&D5d@j*Vfi}`Zysz)C?-T8mxPa91UpNL;NOVj-? z1O(sOvyb<9ILAd$E*CWa(<k>=t*Geu>m{-`yH2LCELf-1A8dVJ<@1m5FVfZA3{tt} zcTDa*dz5VQs`Kw7$z^x`b^W|vSbN!$>oVWP@-OGZt13@k%-F^HNZd%IVNuWFieGI( zktJ=ry7oN#K4-o@zg7KppF7v}jjH|$XZ$_PaN+9I;&t0ZrY@8IxcmC$^dmK=J_~)| z?NxYv#9U+Qx+~M3gETk9DW9<WYwIO0Dy3f^lBK(n-8|VyayIve{`>{2SDQRPZS|3t zfidyg`~UkEc!v8woXI?+hplV#Ba06wC;LSFlG(MZ=*qmhCC6(sO`YSsOr&xfj+O-Y z9r8QWc3#ymt@$Url!<@!Q<Zmz?p_vuzu=#)(TyU$Tbup2^@LBVy<;<PdA@&0mhQV* zd1qhWE~sf0SX&&qyX@_)Zt*A6r8~UybG|!pwNCmcoOk@{*=FN*JEeE8#XW4dv_9%l z{vx?`!Oz1dKJPcuo}%}ol~1+q`|TI6PHB4FJ$<0Fe3t!$mS?L!8E=#~e!H&zLD@h1 znmgwDLK0?e8z!FZop`$FvF2Gjzl<Y3pF>VJuFcL^v)*OtwV==`ZSf}(4jtFoc4Ai9 zlVGn+{l<weKd-nFw?zJ?SE;93a{fPMFL6=RrI9Ife~7g@o$RpWUmUP&LBOsDvRC?d ztdCdt{G;rZ)@Mn>=ZRP5?K3e8Dg5&Kzw+lBWeh!SZhxxz%<DNSH2vo%^u4d>oos!7 z$-+$yCr`&6J9>4lar?FfLD`aqzZF+Y_T|;jll!|oqUOfT4bNpy75N(%Jc|9%YEsYn z;>^N+%RRZep{^@u^st4zo3~?E=9&4DpfKI-zirOtDb2GzZFg|CI(c5}%$F#B{J4Uh z*I@nqTOV`#1?<I-eJjttZslar=+b&J#VB^qlj(Pux2&>gUVFYT`9|sLnH8`9TUzxM zFuY{cS{E2S_m$ud@nsQCYtIOBE4COHuS%L%_QY6(Yw6F^4o)0}YYS#2&D-!iwx;Qq zal)auDMxaPOJo#VUIh7Fo|E+AOlV)9LW=<3W0UY_P8@~0lausX1pFMZw6`%O>I9GO zS*A1l$PC`TzQoD#L1Bt5pLe|Ku8eh+`xuzN{e@TZ>c{u@dwr>wU$V~V{<)J;S-RP- zbwbwH_0`{gSUz{2BS&HGu2<bVm*;B;2EX6As8m{dRp;+#uE*|t5t(PFSmt*vC_A#& zSxLgCRMmZ({q>iUEdtk<t=>0-`I%VK+p7ip<X^VxIma&Cy5?4c-IY+Wl1M(qBU_Kw z@!v9<*>QK9nEBReJv;PQYIv|EJX))7@MahL1#>e{qj|;NKbog|kDoT568KrpRDAyz z<@tfp6T4?GlWxsye_{Sktcrhj_V$XtbE_Prgt-;1`tNpCKKr;{!>d2_;bVIN5xaS^ zuiqscT`l>n?|Zx5f8km;-394KbbQp5@9*6xA#QG}oMzv%Zr`LAzWl}SrO$@1t6O;Z z#{ZAPVcbt%#=iEr`Tu@cvCqE0`7J!N_!>Bcxm-`j+wIa?&8ltLB5)|~P1qUUD%q>5 zk_ko+?-xt3IV-m<E8el{iUhCk61h8vjzq^Z%=+ERH?PY4_`cds!Oil=?jCMG>i_SG zjo;+HPkUIjxF)U1OaJke-{{XT_S{n;!LwT5|J*mD??jbhu0wuIXjay#O}k5OxpNfe zZiqH~Z(Su=sd@28P900RfBdq$U#;HB**Sc^v-RSImW3Pd)qH&|dt?5tQ%;|MMg2Dr zN;Z42?&GrR8yP-s&h4MBOi3-Sx^A^Ddgs4YCsu{*GD`m{_O1Sl#pZXn6Y_#|TLiu( zY)^W(sOY$TiG=gA`|X#mZnEBW%$j5AYU!sxJ)h;hb#qp>bNtI_Ajw<v^?T)=4OPZb z{|&Ud&u!Ty8@)Vo%fG}ga(2@n-`{^~&2OFezu&D|GrjBYpG-BKT0gFx0*Btc2|MGx zsc&NKt7@CSRf{f`9k<>fFO^%q;ODB64^!eN7bQ&I>F{jn5rdp-`HU;p>n&5V?|e1M z$K;m7r%7eZXSa*(+Lc+i@001wTc&4)j0&U*@9%lBVU0%JzYCk!ZEE=R$EAtgZ|lz) zT#7Ag-+Ws+$7}IY8~cf|@7Fz<eLXMfv%J!cf2U+#t)8`9T}`Kwube+WX@5oAkr%uf zd;Yw%uajh$XLpci?#`~e|9|oZO21Q1d0<l0#J1tL{puBKPpB5Y|IKjZePsW>jR&9k z=&gHaGI#Y}txc~=OBpm`L*CkMapEY9<eGdkWmm;PaG(0dCWg3kGjI48T&@r{OOj*g z<qe(kTs0uLY8s>P`wjlL%2sK4CBH5f-tm8}QTNln6Stzo65}WSy%S-3{q#k{mKRyk zZ;Mjzm8@&qJ6ql{Jl?T3RI!)$YKVwR@Pu9S=Q*d{OcoA5a`o=zIq#X=Q?HtaEVP>M z&Y}3`tX}amt*z5eux5L7-8|6fKkvxt_3C@u&Lv*C^Z)4G%je~0?@*d&ckst|8NXW- z&v(oy>p#3{mXDiJU!CLng~e8>HHs}8ZkwFG>UBTDKdy*}ac|q>m(s5$@QAXWyb>-Z zU{kQ_%*=A5nQ4O8SFHW^+v<PlsjFuX+nB%8*mtn`Bd^?>3p`F7&(-c5iaT+rD;$mC zP@K~sQmoigz!U^J*NZcz^yr<8E0d?o^sd`?>0+SX>*-TMIUe3ww=1dc)p7Hm|K@vJ zh6iU&|7f+DeZ|_yrR*yN7Hy6dJ!<p$$n}uvDNF`g@7}*P%S->luy@j$OUxl07jMeM zo#DRBzwvo9dtKeF1&8Y1UVU?yd5bbcuW{)gZ)Y{(lfTU;RTXeAes1qrb7jBgNjtZI z9~H~)edV{QZEC#sJ8jz2Ima$6QC9pFdnN8)&&>ZS456woWqv)9>@wyv{`0F{!u0(` zKKIg;u$PQlEiZgz^`CLEE^JQU^nUU26W)Dk*Y>_&n7=0d`0aAR&kz3>JU%>s`%UxW z7iU6c?(Aw?XdL#ib{`{)LuDS5`I>t^ahLMy{(LWLI~&!zdba!Vs)n+{u+xv9e28yq z5%4>s7ytY^+ZRTKq*q>dY-<a@e@Q(wX=}~@_0gG^uEqx5KeKPK_@V#}PDu;i#S1%k zopRd4eAxO9^A_#RQF-B24P1&={>x+a%HA8ZWz<~|{d33M`1O(NZ(n`P%zK??v@QF0 z?pKCVmuubC4Q6H`w|9s;aU{<6tGO_ZiT}NV$*p&0U(cE(ZZdN7{`P|LR%oQYs;xt- zz}%zjj{bS16h5c)${)suPk*IVRj>!f>8IOuC$3o`I)o?$i5iZVbD>FuYy0Mtri| z0;i61Dc3WnU16S`Y4M*`D%_l(%|DiN%U$!!85v48MVjn(wOxCrWcazSWmYhJRx2gF z%3|y1`3x%WZ+8UV-{i4v=~lS~eJ8ZQcAv~Ut9h^b#QfX;WU>pVw=dp$t^BfJ<WlyG z>l2=dJd#SCFSlUXXZas9Z~atEP2YTt`AQ%x-gnH9{@Od|$G`UsN8I=NdS2Ve*S=|b zcXdP4<4s=t0g5i^ljRn~I#e~3$%4|d#!JRqqD#Q3?PNJPp?YAZ;MlM;*{3#n_Uyc4 z98_1yQzdK3X}@sw>VguH&8rQCWA^TBDPW5&GWUkmrjs{3k8ShWzh2ucGkn*sqJ96b z=jzmDO+Q*xo6LN?zGCWR>wgDx>-&!0y}bQy@^h6xF263G58Sn*>14~r1@23~EmE@Y zWbLoZp6=6WDD83MGhe7{CeNHLGD|PDw#^a>$<m$3eXZoAa^>5?H7x>bUr*95_P-yX zwCvtx(b=y=w0zCkeB<sV?OZ*(ZKL`BmtDv2?*1uQBwTLz_1u2rzv2H=es$FwK7LpF z<GYk&;j_TqsZvIN?Lbut!{z#~YQgWT=34USyc9@2$H2g*0J<YUX~B1mx*ykb!{_X` zwW?avB9QxfQ>Iw!rKPLQQp>%TY71U|xAoVoM_kq%OJ#1j<W}-c&a1w-NPD8w!junF z;*B4*-M?u%*-iRJ(#->%<w2oy{AxoJtuM#V)V2+C>Nx#+liY&oS!>UyecIQn^7eN_ zA@_W>%KL6y=ia3Mc=JE;%ANbnG2co-1w5#W>s-otRduG%o~M<6s`=EvUT|L`bHn9{ zuYY01@8XQVRffOK*V;?(t^D4z<jwyHOZNUxJSqQ;p}?$;UG%4?#8+RFx%E;>)pKwC zRGU0~@10k#lk@)xt1Uj5_3U+cZNhY)qchzDs(&v2_QhB~`|Tcw&-@E^ovL}I^(k=W z-We6A;~8Hcw_fmlh4wksmW=&+FBz*=Zu^zf=B}4^-@QL5aKf24q0%S4?;Y+dEjK7R zrWKO4{`9_etJgodVXi;3`^(4oaf#1=#czCb)1rypFY)~|ca2jPXVz5TU%W}-XxrW3 zN0*ZsQg<$AJmG)S+wYIR&(6o93|igi3SKR*pLIXq`*Y8`TBVg*ClBbCWOQHe-u!5V zmQAwVHphpLqf_$omvzhD{AZ)KxbfB}87;2h8UIh16}K<hc8>eNL;e4Ua_cR7b}!do zUbZhY?)a^b`~Kcc7Fl-u)*Nq+i-xh6n7>?F&bsYt`eon8ycc2|M7W&Te2-^b3676# z*?#NwruFG^xBaf2%&&Z}Sl^u+_C#IyLbVFR!(_3?vN!nOAE+~Xd;e&#$nkx@r6+P< zoALjxu*rc(d$*aK&sd?!IC<qy=kwky-#VA9Gnx;oi?5~gJ-VE{;Od#TCrdVVWNNQm zueWUBu9in<lwJ0g>l?qXY;TBD*1P?GOZ4}BE_>_kjo;VJUT9p;eBsqcz4QKA;d+WL z$4hSA)e--Gb<4LG*STxW?wa1q{dUvj{MOlPwrB1B^7Ygq5jLM4b0zo3UC-Lqcjo@| zr}NyN-rLA-nYra|;rA~~ZR|TAFa}5Mse5RtC(dQLW$sSfnS1_JJ$!ndyJ3Ui=MP^v z6W=epKXZBZEh~NF@OA0OcisN^=I6<n`v1RM_~zYw_Ho<sjY3X0mU&k-#GRUEH#_{) z-P7~eOunCFBz1=MLW)sP<b<Yt5101i<-ysSr)^XBo!UQTt*w{xvb%>n<>NL-oe|Y| zGi#-8-9qOTn%3Mm%HpQ2xp{b>?*4R8+IW=zGFR?>-xDFHE&Z|i`Wb82t9|$^I`3r4 z#q{9&Hxe$UU%s$pv&7|$46FUKE*8xRi+gYU3Do_*@%doZsn3rzPg))O*DvS1^xCZZ z#fh@fu`gcUyknNfsa{vnJ8M%8L)PhHhBNZ-c=!Kv%=`O!Vc36AllH(1X?gdTuiU=0 z^B1nWw&{0(bFQX_h}iGa%xB+Hm@=}~Y?t7lHUIs*4b`@_Zs*uDKJSs>^__EXE8o;x z-JYl84qaH{eE-UYXCJqzP8T?27jtc0?Cx)mSbsicdvxjc^=#o;&vRo#rT$d$IX`{p zSX(Ms>!!=FVBxMAmjhpGoV073-EMCC%Xf)q_~DK3|G5=D3uN<;baZ?b_bE7e#d<v@ zdsV6OUUSC1?vo_`%2l4cxMRhY7M>YSpZ4`WQTcP_)oZzXjz7LgIQ+VJzO(<A`P5d; zo_!w+xBS~{x%0CxSJ3w)qgNj}<yv+hf4YB1(uLO@{lCnQO12kXE=hh-${!FO3CbNl z-%h>{*tH`tdR}vRg8d(-_5}eq%0kzM?7CEcXRXB7-Z}Taip@N}UrD`Cyz*rA3cZsF zzhd(jT*_FRmY2V5QBQ>5`>O6!O(I^K`-5kcP581y-=nK?e#1Rw$?Y#Br|4<jxe`_K zRW$6p_x+3Jo6{d>P0?HTMCIM0|2v{N<qRZy%?`Z!_>EJ_q5t3H6}snNe%P4R59v~F z{=LH~=Bd!!UF<7%eDf&gD(v0lU);5NEBgvvy}jIzlNxJ}Z~E|2Hg<*^hvGV)_U@g5 z_fMRZzt1r1cNX8QJ%?)4PwOB2n?E)7pRW@~;ndd!hT*$*8CLxh?wR+$#r6}2V#^Mu zPaAj;jWgsr&!PMGnN|U(KaX;zY9qDZAW9x^<&>6iD7Fa57QOh-Xmm6sXx&Mt2nGfQ N22WQ%mvv4FO#mxE*)9M8 literal 20032 zcmeAS@N?(olHy`uVBq!ia0y~yU^>FUz{JeK#K6GNb8G$$1_lPk;vjb?hIQv;UNSH+ zu%tWsIx;Y9?C1WI$jZRLz**oCS<Jv7R06_`_tNAm7#Mu7db&7<RK&gA%ezPRY3=<= z`}u0yUitRi5)#;&BNEg!E6QwR&KeEYna6bAEGz8Dmb{kN?U8+ScW$Ryr{QnMw!c?O z_wIh_wuza|xuI^`{8?%`Vb=_WoECID=zHwpU}n0_l)`yXv}*VJ?|bI&{-2(9Zch5W zbGOgfls`N3{rAs8OXJUTo}ZDOTm0|-XPe^ZJ!hC17#NN)%w+IrtNs10x2GrP_O`Q; zYz!JaCs-VeY(5-dRucYn87`n8%n%SUfwLjSL5*R-1_fb;lMOx$4vCIx43ijVGBg}& z@?lV6HezIGWu3|3!Ir|rz{PFEIDzK`3xkMQ3X_851WpDG9gxYiHz;9-q^#`SotFdh z_WfK9^2Bz#y>IUBKL68}@ssn;n0a&N%$cF^a@oZU3->!5Cs=rN?^k~~sOmkf=9Gy1 z?;FQm)a*V@?6)}mQhEQ~@B8;Jefeh>gQdf(+yDOlE_XU*^Yuz_JO6$?_uDf96@(4u zn9M%=`+a@F-Cd>UJ{c(OzgzqLZhZcU_g#Swd>gWF8=to+wqA0^_WPaBr&g~I%gU-a z)Z?!pY|!G7nQQWV=>@*MJ~iL<->o;D_33ny@PxuQtJI$I&NOH^am0K59;@JW;jes+ zKg*tA;ZgkL8Ed!xe)avo<~&<{PUM$gxBWhKRd3YXjhrW}f-bE3x@?Mh${_|NVf{ZZ zF3g<yDrTu-ej8f})651%7p>J-uD`!${l=*9@Gk3p)%SCj2Cg-iy1|knUD*|u)q7IN zD3NJmXL@|i)4L~6l|<f?pT*XuHi1*ZY{{xqx2Nr?d$;eqo#ys)w-R0IcH8g&t-tJa zsj2a;ko^`8X_+QcPqUJ1wzc_4IHWu}a4@{DfBJH-YrmU6_fJqd!NMcG&F94H=kKc9 zV$}XU<$b-c_ImsZbMBu{8hsqL2|m;fl}=Avb)tpQMeW=E51*pbPYV~DzW%HDwVXYL zsjYXL56|xtEhmm_-&d?}#JKao#Lmo=Lo9thJ=!xhuKVn<R}ePHQ4nU3T%s!MQ#|9q zw9e#fCtPlx_|0s@c$m$Iae||Z+B2;aEs8NSCFZZSGJ5#OdI>8`Y69ov45N!uGYkI7 zUSgWrkjOlf;e^787S9Qs4Ld+)vdlE#G-4E(o|2mM`j_C`tF!s7rHvSj7%dMi@u^9C zdg8<>eGBft0#(NwtEGEf<oISXba;O<dMI_|;n~%Xf43|@9-$ySL0M=zXK0D(w79?T z=kT6jF=7;$FOsSxDD0rNV8Rk5;dPEHTFW@)cF48gGo1M9o^_{<j1i-N_++C*-q0-( z`>#f33+_6(`BHuVK1VeL_a)lG+yC!gJ$+lYfl;Fm!x2^2nE~9n%p1-ei2aoFdc(>0 z%7zYV3hojUIL}+S?v`7v%3iB?Wb?tywf8UHS|#>o>a?{H71o*S#chNH{_WTlHf>Js zyyKf9ezN|4_~t8fGswWonHh_{8*V+4YFd=bDQi}lf1G({gUrN#ChohFvcE=T?cHr> zP_^*x-F+|b1>Vgt-I`ZDJ!)=6)t8)CKX$|^cGj&q=%~i<Xwt0{Ev9!KWHm&6vTC%J zxtKV)!N)<-^EZpnUc1%4iC-huZl7JLd*JB4#rcc(Z~s>Gpzs#|1IKvTj7RZ;FG>VJ z5wJu}_?y#d&Iz0ibq0m!Tvl^bzup*?m3;qb{6X0$U*@ZE>)*Yry_#HQ%_-TOaWU(~ zd))=5|JazJp>koV!*^!st5>2fCQcRz>2(ALo{sRmRco#$`>+1i^#2^+H`%NHYv<k8 zp38c0Z@&7>4>k?^9=zwB$#6m~^OQ?M$HKQf^Oo|>b_z)jn80~LkXu>!p4;1{4xHOF z?_Rtm6Zr3TId9n`v)-yZ4*3T~8`+v0K%o~pb3^EX*u>1H=KL)Sr~4XCWt!O_lbAG1 zIby@ts`b})<=VWxs<wLK`@U~wzw743&AEM#wN~>};ab)2a$;5LWzq4?j1HjSTjP@= znZi_b#A$9r=G4;JQ^QZcEi=yTjyrwV>7Lf7PxU*4e?Qzab>H55o4F_UzpmtHFN@Ax zD)xu>7u!sR4p5ovC^Vh(1p_E0r7$TpD+sHBVx`H4Aw?kNkje=bhnNYR4LnUgGgx5i zCvZ+y5N0TJRAVsWFiI3kVN%dL!Q#N?sOHn;!*GNZEoU5=*17re*5u=Ty-ufW{{Q)$ z|L2W`5u<?xNXy35q?&E-bevC3(H2z|E<V9>zyXw*Tv8T=WX_qn%IIt&L-nl3D^!J- zMs2?5^Y<+yH0MdZ3e7xy#Kb6(DO~N`xv+_x4UQL5AH7<=zHphq<@Dd*-p2p`b^Yn` z&2#KN-BuKyz-=<~0gI2Yg;C+MlCo`KZfXo{2c~w;-Tm#)<I~swJbRiQ_W!YVo$}w9 znv?c2l9ChW@B6ChTBmt(oBBLAHHF^_!fhAb)Mh+mkl=_`TlMu>$<Df}UBA9n{7hf& zoj)(A^6`_Hs-OG!{f(W-`SWG;{E92@i;CWzczNmL$5Sg`uKF`8$?pV9ip(-gpF@_y z44ew<XGiU|j9%A0b^eSsGV=QJ*1>kOivC@e{odts!vFp+6Q%v<qSH?&PZs^jnttkQ zR_whMft)8yKFK__5<a#e_0Yd;zKNV)6A%9^_ux)pY7^M_VOI^$Dzjx?UpE_Xog93% ze7RPV=*nl&_XCX-?Q36OKCwIaYVhT&#>Q7q2Ia21B~W}wRpGIMuv+G6mg_SaBqS<t zp6GV>TJz&b&QinJb>0_6H+q<s-z}bhqUFz*wf@SJUoDrK9H4eF;8}~e!!bx4t2Eby zOuz2G*D!vqxz^USooe=%&+h$xS07?w$FI^?ul5KWR}nd<&o{vrl3F?y_2o1-24y{M zO;PxM|9=C-bmLQsZ{mf)&T&*@5OSLutz4LTXuI82h9|6$#1~ijfKe6FuHc1=II1yN zHGq@j3GEXs4(t#MDp_YTykLMN$Mp)r46+X3<oHB1g=qmZq@do@<ik+H04}H}giqjX z;1h9FldCG-_w$wWxkF7&J`51WH>Y-5m(SgzKjU>ufvkfX12}cFZ_*TA_2>NjTcyi4 zYuwrSI^^=^Mf?*u!8zzcBhRUpPi*TwkFd;S09OaHC+7Kdc$cjFJ1uvG(V9n@KQAbj z?@d!a!2-@6FC3nw9I^_16j1VVyU(Fe=F@U>RBt|#YB}x!H?Ze)OX(*UZ7+@~wiO|d z7lu1Ocex@Py?P=i!;9G)H*R$87VC6yQH);Nds%A1jVGxohXk3nUR}*M@7pbtc9xl- za$!T_VK#S}Llf5eSvMS-yti2G%gk;w+Y>Fj9-q8s=BAc2fwSS@O9P988(13rzNI*Q zQFyZ6(qtxwUvb2;2Xo&$fE7fz@cJ3(FfN$vICDdZ)2cPc)ngO`%$@uXT(NcTWHnmo zpvI6SXazQ--{(|It1e5P$<_@uhdQm-D@Hg=eft$&elj<OX(mI5e?dW0A}53V&8eM< zEHfES$nQJI*`~_S1SxHbI_*G)I6w;=y+U?%iD?WRtk9@>16Jz<NqbMGZrr%>Xt%hr z4x<1UIJy%A*8O|Cdd+1~2Ss<~x8{5ebr6+b+%H#6jM?zz&;9+cyLkEIeV<sIxESzW zmg~6&qmBh6N&K4--m%AT0;l;lpDVA<Rx!_R;7L4v<Veomiy0QH6?{)k?V8kSnZmR{ zIxAw4Wqh{DL{9S}nQ1z<`$KX=u3B@LF-9Jo*10+ODoXLTLsxjIlo8_v!OF@L&)<8k zReUNubHn14N6gR9PkCJwapgfv@d^epiHV()W<6U0E#qF?{B-l?suM1@f6t4aV0j{; zDtz|mrV~flCvd74$(;Lt;HU7X!X;TJS*#duE>IPoW1Pt3tCp3T!nDBHOYMp5sxF@` z$)}I}SfeZa%Eae+0;7%w#D8`UYE6ZyN$W1HSh-ywg~^EVvW!~dEanCL6FL)eW=`l= zKEaa0^_%64aqx*2&Rg|Tr#NRY#5$@qIjSklwlF$q(k@ss^MSuJ<E{oDmS!IZGe<R_ zOVc>@qF678rYK3IFm2)lM*-Np37jX?5VnF$fW+=E1#hE`MMqU%Nn7jh`1t97+G12W z#ho?2Y&A?X8*(6(%!}rplPxI^Ymr6XoNP&HL=o{h)smu!BEmYQGkbl|t_z}{?HVCY zZSrCG!e}JOW5jq9(muPu&aELVd)S1%K^{_=$fpFUSuhGKv@D#`*&a7Hf8VbOn<uDF z;B2rvG0*42@`Vf!Qv%f9-6{2olY9GRJ?n`UZX-rZw>Y`TNu90coSa6CH&qrJ6=q$Z zd+w5R`xD)zdnFD!uQz+X^|yks?gY*ghLMvv^_KHq=sa_}C0^u^qneU~n!@oEPqj@# zDNLI@`BEO8i&ek9D1kTRM&{bjzTGlaCnk1&`*o&+)rj!|`=?J1YBiv+dXkmmv~7p< zlWl372Pby^{5kpCrlN`0-nO#MWO%_0i3iVXsfU6ZFDztD<;mOJcUk7<%&!h=48Is= za<I*8$e9#4bHhEiHx=xnTQd1LjV|)0FctOev6;Xb4~jI)8P75n`y49ec2lcjoY^4L z42kQLlYLlv55|6)v!v5!i=&#taRuRn3c?e7KdA^``zhR>qaBd+aB}B0wG=02Bu!UM z+P9vpYR^2kf7j{TK9bE_PyW3ekj`wxI3f7S(?*{kO+F50Cl~ne7@lBpkmpemKIgh# zcUs)*`?G$7%!ZWZwHNmLM5q;>{8akw(Xpj(ZyyGQ7A&Rxn$~GOE#AOrQ&MumUjbI6 zWV0{z(Zi|QZf<Vtq9h~M7rhPrcBlQp%zqi{_h&ubB`v<YJpA?6bzhG1#l{vqep=Q3 zYnj;F-7a4*E1qCU5r!s*FZ#ma+R_}W&#uaOt#x76zYV8$UcRCE_HK$({QA6XW6d)D zbLQPqhgH7i`fu*_zOAkN>!kovE?}F$DZ08Vddn22wUK+C@$GHgyTZ-rOTOrL@gEC( zT*{Vi<=p9=@M&qXy(}mgpvBa|2BXB|S`YjDb7Hb~w)TbYWKP|;+sCE!>Qg<&z!x|C z+mQlBz*|jaop#H#;=PX9zWGLikzapL>74iGpg58vgeG@3m~2_J%<|Xd&J*iGe(mr+ zUT4LE5>8Hb?|%EYZ}Fe~A+FxZvZd})>JQEt*LKc1_n>i`<|ggskpXH=;rm})L$Uk9 zcAqW(XB~DD=3ZW5{o*tC+pp*1OMm4YIQBVwabT?L$(B3U-aqnkPC@k?gOQ-Io%D$W zP(s66IzW@?qSHtEj?b^~+0?vb^6~i<Mc3E;W#?BEX0T0+Q`;n;!nCRLgv-urHrBzl zf9HN|UcdkMng07XKfk&W+<vd}*VOHvO%t7W{k~xRyWZy8rH!4*>0XaFUoG<Ovo&HA z;Dr<cM<#V1n|brrMdPQ=`RDDbQ?ky#p1ix>YUA$@DxL=Z|4VA_O9!8qpIi5J?##!J zr=HviD#BTzxoh#wHP>bfZ{E87_-T7f!|#tazI<M9rt0N5>1?C&WPO>rbw7Wcd077Z z*s@hh!dG|6)TA&eNI|rAPU<}N$7g9>)vl^HJ}<vcUMfF-M)lXZk&`NpTs@+4&nkMF zvu$+fd*<F_HMicgfQo*ozOPxiA+OG^4ElSf<m=s)uWmnn`Z)dc@u%vZ2I;5s{iocY zyXJ)BJiY6um4qJ^zT7XYAUq*?LMJ$wKlw~qq;}r3^5D6!S3%F!yuW_DdFw~cRF#=C zUmc0b-4!x_t;s3VO5uzXvzIiMGo~;V@qhzprt7@!-eY@e0@hs%S#srM_jVO~&rK_@ zX>Uz)^;wkoH*m#7RK-1?N~X*YdiZ3j_IZEp&nhoXo__FJ^ON`ajODyWjFxQRl1JzA zs@zwdnoG}h6>(3>h>}`ZH^YDvQN|n#bUjz~aaFqdlJ?>Wa}Uom1NpylW{SJozqj?f zv(EOO-d}Qm>b|dS%{~r#0bY(leV(9Fb)C<jYo_zd_N|n5bNhGl>VDI8DU14i7#buY zl0Ijy`uT+2vx>GWTJ`1G%1hGf&wEm@e_kK^(SO|}p@091&;2~KtA6j7X7O9w^M9RM z%g*2bQ);=?&!hKkOv~ToMDn%D2w3VA6-?k{FaUMok4@|J@{MJCer3xpw!R-nE?!=` zINj&T^7lRYJAPjKzOQ`Zjl=f)KYHu$uRIj@fBw52=`Y)5mQG-M_v=dWu97!CKi_tC z$#i*!tIcs{WdMzGJds#ArT1CQ)_Zf-UU|BChe+VhfV!kjR%U^o*7twc|9{pz&2Y`1 zBkJ`#9&6qYJNfMWoow@p|CZhVe@yGOxBRtkz2l>a@qg}~JauyAs~<VJ%hvq6ATyJJ z!5EYRmV|h%ImlV+yLaWJATG_NpN#kJ`Eu*^{C%&oHntR>i~N&*f8XWpSEs+P`M!@o zcEuDYsryB*ulM!M{bcH4@J-(?a@E##HOrS-Y=HRu=P{`{0rCe|mzv%WTorZwinsdX z;LY3X-fna4zOv`o^lSeQc1}*O;aya8KK@Sq!`9PNf^_0^Y`@eUXAD|r_9Wnn^s5aD zLJSFPDNIHEQ+zaM_dct+E49=^vp?tVuAG@dP5$emwx*wtyMHaN=>FgDw{3Oe_Wam( zJI}uM*_!o^MjQEBr6w2f@iREQQV=#!(OBxCo-b!vbk_9x4WSQncfb3T`_}xs{fCCt zBHQoR{l59JFuplO=|3aG3{Zn}Nr;x`-tEs#_x*XQ-{0SFEuHkaAzV}FjU>YXn-eS! z7Pq(MZhrlDRp{z(Z*M<e<0~?SiJ^@-h3UX~!Q8mV>vq2@y0(nXi;<y{eI`T3<a>ME z!UMP%PUxRtX=rY&>|M7&gkggF1Wty_pQU0QH5nA*6@&va#0ugTYiqEAx-Lvz-eS*8 zcQpkuIDB(dThNh`3y}i#)Vo}#J%>n{IjSvic#;H_;!R=Va(oBXRpy|UaN^`wsJ%=l zSa^&N8?L`7I)#ZrOe}?|ZSup}*I#gXF*0z2MyQSzoX;*{UCO}lSwYw!L?i`b;tZCV z4T=jJAWl5MbAsi`ye5dc22gc=-(dYkWerw_CG19wm93S%j1HO%3cM3IPspFiKEkq; zp&`XlO(ET2{X`KBRt6PTBgUPLmAxh)MRq4xo-jN!y~MVZp}|5yctYun>jt2}YHsv# zC`*h>c688WSO98SD4ogHvCv>;_`+wzIJ3F3_f10(gM+?;@C3yf*H5Tvuride&1~>F zu*dBiC=j_)n8f6snHI5lF)}z#;EeE?as7m*1}no01>p?_2I~!37Kkt;H2WN2I<V)M zL1PdDgAt=!Vq9{Bqb5Taj}c>ALfm4G1tJVbS!OZ_8>|o12;gd1)ac`|%V2$AL;zRA zqXr*`D1-HkOkRuuEE70ASf80XurFnh$eY0FA@R&qfolp=LWHB5g5iwo4RH>d3~l@= zOp_Wbd0%i(VM>_cpr)XACi}pF1tJWG8I2g55AR`9Ve(>}P(FcELg1OHLSz6}!=EM} zhx-QW8DBOAF+34WVfr)0OZ9me!!y$ZJQ}PH`yA8`9G<A`{>0bjiu#P}42Qq06ZzD0 zcT;NjW(J01j%o**ZR-n9>u$F=Ep{gR0Mn)JpqyJ<GA}N2UBCC+tj#<OX^v_O&NlPg zY2@E*`n~VW9=4PgJ}<@dmsGu{omlqt^z?SVRg4a|6oelbn3<*RSH2xneAe_#w!<}! z&@SKEW|8M3kM1gc{bm|Nf=~*R%#+v~mG;*X;+Ty()`@JtSM|E``P_8-*xZ!Wm-!fc z8hsj)N=mL&s$Z+P|NCC~qa&QlSsjiQOg+S|?$0oTeI|qHQ<-1Obbg#W!g507(-qt2 zbBgDvuVz#CXOLi<*-&Z7_T1KjLH?7%=@;qVKX!b(l|9#uVS?QWmy4Da9~S&QE)@uJ zn_qB)&clC#?jnn%{DK)gBvTf>h^czH^jvhl#QaSH4-2B0Q`-0r3z;RI{39yVAUUD) z$dAAJcYmC`|L2E#_;bzae{LQ1*0cD}EdS^Cr0#zQH`V{>*PFQJ$BXqpXQgVD-}(96 z_xXh8z<V{HPprDX=aKOK!b-PK<>&t{jj#D{Ik)(o{@nMw!@nuB|2(VgKFj8`Vz`1Z zr-J_Pw9S<VFMa;s{{O4;{NLZ_E4+Lvy#M>@>;FH$mMYpYH<`a}0`tD&=Py{r|K3{u z|B3zN5M}nCopY_P?(Qmn!&t;%G?5|b)+=6B;r;d3MWyBT%~~@3|G)cnKX&QIg=d>c z@3|^<<kHj1l?D6vBwZDMZ|f4&EAvFQ|NWHhA~j4!EJlLjm0M4*-WQdx=csn6|HP47 z`ZfDPay$HQi1P6$wC}t(=l;hd=Tc9&{F>PO=SAP#sZq|7#{PvTI8V65T=|`|SaW?% z${`0AHM{TjwROv4rZcaz+hzHmV}f4Mf}{7gy?0RaNx9h`{`bSh<Ih*|{_HpuEc1!U zNKm}G&)H5}|EEJ<O48ll?zx}u>gw(ISQOuU#x3R1{Mi3LR|f6XF*>NQL2$`D&sATK zZ96`1g4OfYHIiq|^DM({w_cBX89l!}=EuWO`y1bWl<d?qTFCaGVw$s@gW98{lSgX) zr97JS^!1yg*3;rA$j=v;`Qy#k`SWM2KFOG#a)_sB%G=I8GAECuuiIVnq-(2qe@{%! z<oe)m%0?frN0<9d&6+x^G*94s(Fx`gE-@}@Szn*UsBSm<_~GjHIMYS?X_ni3dd@2e zKiiPHC@4GU?mY3CH@1CJS}GVGXJ}M(^lszY$o>;Yrn$SQy%IGwYV>iib5MKK<TIn^ z#F6*0+ow(BoV+DfNncqwtMBlv2Rky?)-O9e>z~E<UAb>fZ*m(kR<g|O@P3z?^!U=m zi4#SoZF!BPQx4heoXlx@yzrv#{J`z+znw2p5N3GU;B!PZ->C5CEbl8bGo`w(-+7ol z`L2TSvy-!ZR#^5;(_3+S=j@jbY6|@d!i6V)o@jY0W;yfm1dxK6J}XxCdWY8?jtp5W zaw|!%$;Uy?QSH&B-<f=`*IUkb)}Zl8RruAC(+raHuYX{j*<jP;b42yOdO}pQaQNCQ z(kW&qS}KcFg<q*~&bQLoTj00wg!=@}6UrxCVm|2$Uwd@oQubE1nY>1c^K4GGl=ms8 zsH!J0EnzkioUS;bQ|4?5$O#jDTzH%^4vU^(aj*ipZ?Vr4bC9Vj!iNP@m_BhB35us2 zN}0g<SwR@o4g)!_$!7+SQKDSRp#rF76F4V3s-0=}k>G=b8n;oR(TSGI37m%=A-;B0 z^I@B5z;Bdjaf0QEV2YC7iI$TJ!p|Jlc-SGHVx7t1R=d3N^`u$9-u`e@JG1$L(ZY3d z7k_Qi`}?g)ed%1NIWN7{LQ=2pcyR1=E$^e_p9Q!}Cg!9h&G3j(Tcdyf(#ub-F`6e^ z>dk+>7n{jY;HdWK(srMU{fVo0`{%^m`n<hmeT?G!&Ra`$pFU*!KGja{x;#j)tJ<%h zn|ef27wwgPr8P75n^wWvycDJbtTQ`KKQI!E;PF52YWr~g4F|OYizJK$Kkk*Qn!wqR zF`;vZin{Q%9ZkO3OP{jm-dTS>puD8ut>fLjhb>x`Yp=a@I`-Dyt=HP^)-B(7)o6?V z?xp_({`vCdzUTZVBbsu^MlIDTw}?}iBmOU6ZvNVs>eSV}ySl#><njNz8xVgxad(rc zSK{TY2bBvZPVCOlD!+Pf$=irI3c?fICv@)M(Gz~Pc>inm>FakMk!AZ(r(TiJ;-G*2 zEuVE=<n;0jhc=0=X5U?B&Gl$@8E0+GTE~$2ey8K|w)3^Ff6nKqb|%?JZI4hwXvu0D z_meIm)xO+OulIIu<N8s4Sh50?f3|PDb4^6CBt@xpy?`?${yGbp(w?X^#bx|;jh*^u z!%;t@g<5;lgID|S-Q{i5z0m04yU>#Pey0~WxV+uD|GA%|+L_5+J})dp_r^Y(yQQnV z#m8macGU&3kM*OfKf11+HY>d%<xo)LHuEiu<j&<@&Yg95y9F#QvB}Qd&?avqdgWKa zdm&Zftc&eiw>JCyShZubo9VUH`;Kgu&=P)k?S<XbZTB|ST4$ZFwJql{N}LyxqGVz8 zP|~m9x&|l5^v)OGs*JxzeDi79eWNO)G}>7@WCOc#l!7pWEhw`t%;ZZIdS_9;U}o4h zX48G5{`~V&Jk*@N-`OuM+vGDtz27KNw9b@S>Frgi^g!v29k+N-tK2br^>6}b1E^RN zdd%YU_6|q>!mlQur{=Cr`~B!`jQ0n<R}Zhe<lCq9E|TYkQ$lvd{G#amoBQrop5J=+ zg+R(78@AL%OPR_{6gwt#e)x86ku9f^{o7CZ_Y1^B50xLz=8>Dp@q*ik@c}4@xA|l| zH+a<=7MeQW=Y{DFbNfw2t?zX_*49^ARIhQe&AV}O64;(A|0WzuthJi$l;{3#Cp2<B z)ZQe?lsPSpTk?1N;aj_-&+kooyK^mjP`7xc-1gm<H8y@Y+2S7mWiF>4p9~~_Pq#2i z6wldxFS|Z%XG!m!Z&r=ItG7gl-aKetxFDbFS{?iOny&S}H)7u$|C)PMn&THw_q|Ki z>p$4?LsIgw6sM%0jm_!n6n)g@92L9e$seX8nz8<iuG{;zsP`MnmTvF;U9c^v<qeM! zqbuvo4)1s)$0W9y2L6wX9IfEl-#{|ukj;sfhtMRhAgtExGlPAm0o0AOD}zqX@=+<x zUEwn6*g2@(DUNElra#SdkIgpvQ@x+9uXOJ@IsMR?K@&JXt7r?~`l_n?YyA<>{FS5H zqacBq8S!tWXKF~CJnizE>FPD{ESH$5-E$vI&(~exvt++9w7hGb!1;Rj@i3Nso9@(1 z;QYKqQ~2L48MzcDh0mZecbCtNVqv{s*L%Lorz~n%qAfh{{nu@5S~*d<HJ6pd??1Wn z{@X8!tuec-Ky}kPn`D(`<;Qp-MXh(8o7$D_Ex(Uz)vQVsUdw&Lh0!xy?UwwP?Q8d( z*vhqYt?07{2@Svh&cAlO>Gyv9EnDyTFSv9&cI&m*@k#SuockgPO#^36xNz*UT4DCF zO;rVCMxff8N%AW`3WYAYn<kqsR?}U3v_Af;L-zU-@o2-%#(B_^|C6CnVz0xR8!OBu zz}n)}O!mxwymcmPVq(gnT7}EjkJ%svysEg7peCbFv4i=f>73gQsuy)_e=W93>-ft1 zd;N=FXy4|ag5(&P6D_}@dyZzmyRe;4B4ts7#H7xIiDk1jjXjpu{eG9-J1gR{4EIL3 zBaHNg6Q9TONr6>zX6rnBG<(hMRnvaID$fpH^fmhKcH5+da~pOFARP1BC^1&a>G1V6 z+kaRKvb|C-o51;5ViIS1!hy86Uirq$UuD<#zPzXH_jlX-*JbOzC)cIlK_reY;gmx* zCr`O7o8<A<-{u6a3Jq(DPVY!nnhmYYPHy#y`F_^_*R>QIl*%&mq|4t;SEpO5S31wi z+41w)$H<gJGV6S7{y)-wU-`azZatev@BI4n)!%Kt8yPYFWSZI0eWE4AbY<?R!k<S{ zp5D0mY4-AG_iRF|9zTgWR(v@;Z)*9v_qml<w%g5~=v?(A<mKAUsg@^td}bV()|s`} zGIrhkS?lENqo>t#+~3dVsq#tX|IN&=D)yG4Qy0gsR1}^dJ)v{Q3GKVnI#2GLwdd+S z+d#{*Wi?+)UcQ*QCjIbPFSUQ4*l*XqHkNwr`|a(=O)@E87p`3<)3-g+_(bEntFt#x z{dIHZts5?`{}lV4J@K5keah1t`-}rEje}=vUUz*^(dQfoYAK#>xnfrNvH$$FC(1{6 zPo63~IkfWp*@}NZru8Zb^Zzes&#yI8ZvS#5#nmS%X`Nc=*{b=W?D9Mb=bvgO>s|Ht zzkR;ozr8@GyydF*exXNIo=onPc{^(b3$%6o<Z51hp7wRA&7zgt*LrRhUOi#H<ayog zb-pQ&+WYO^MbAHbqrGHRi1_3cSJqhaxi$DEN^j<v6JjwjO|w+Exb$y)yNZbAwy!UX zYS-N=nD^w|eg=nYj%q><aUVXdT5taB>D_HHxhJIa^om|z&l8?`V_)*}{Mu>3D_2fZ z%imO!X59HS_tl2e2iHg3d-J<o(Q|1`aC^AjoEz!hA9ULHH2A1A?|JexRe$~eT}u|; zE89H(cHZvTlt-O&t!rN!%f41vZ65jjK(k`b{0&PYuUekB=knD1wlQ?wngTvMhi{H* zLWkECSe|;jU3=yYORHDW^Zy=jnz&oNGEVtF;}fowMLTX78CqGr(qU#`;9)TejG4g6 zz~I4>vIw+ng<%562^Y{rK7)ebgw97zJ`4;FN(#b9S!XgZG`KjZb#WUpGB9*D_=t$7 zFflL)G0xP`JHf)hpu#j54N~Bfv(aFBxGC+d)WlBdyd4K4w@FA#7e_HOFnnP%3RLh~ zdTElXw~NA}9bYba&t1mAz+l_#Bhu|V+syKjz_Dq%(R0dRVtmcQJl+fp2ND#7Ta~lG zbC(PfJSmF`TKGUSq6`eo%|0R%A3R_=EX2TIU~s}k@FRGtl!2kpL5-^mJe|qFaD;KD zhQ>RHA^~AgR6vY%@R`ur`tZa=<;9B^TbJvl$kmqoPMse6EPAJcq`Z82A2$QT6M>W@ z#tgIP^&kK4FZj5=zTn_ze!E>)wjZmR7FToc>i*i$%T_uJ;8Cc{H$sb3Qc?~d4i`T8 z{NG=7z39ImtAb_4N|+cx9S*m^ubV96^FdRWO2YFa{(kgYdoh5WeJ%sT3HcK(flETX zPOiB&v9ruY&F-JH{QT8sS-ok_IZPmVX^?!tHR-cOYa4xb2+oYynf0_}XWUBDCl4M7 zF)-|8o@vlk^KM#I<SHfMw>OLoBUeq&_BFlyP)3V^;RNrAmO!1EGv=?pG7&Vr>T~Am z(Tx%_85m9|pJ)k$^yFG0)-Fp~)aJv$@I)l#kj4oYgA*(a4)+|@dYVAfPz(%DWQh`< zq&Ra&@=w-H!e-NT;-BBnf*UhQcIJ+6tBz*B+mOFLX5#|8Mvzq?GbQIfyRoAr<wz;_ zWk)pzhEIG(iBoz`waohDpvJ(E;4p!6u>p8ooB=e*vp6M4O)tKf^SKWL!+{41!fq#L z_(Uv^<N9OD4qg>$;Povf>0p}q9R*<q(5RsS7qZ?jEN57GjToUOd8@7IPKYab{Pf?~ zv}TxVkUW0K#2xN>(gJ}9)z4BN-C7NrB3pUi!=Up^C(Qnjsi4mP(|uC0`&Md)s9nkJ zZPaf9$u>0jNT^EA+>!Eg*MVOvTu!yzK6z~ECSz^0ZSOBtg9;OY37m^l0@dX9)tpsj zwqgX87)(ZqQ%q8mo^rjs;+B13u}_Av?8CnvSN6(Gi+jE9;_sZb@3mpEJZY9shrkYX z{|Yy$J5}%X|KzD>&2rwKUt)hNHs|Mu61xeWpj8nKdzyVDRDTK^I3GC_{KNKZoH_H{ z4Sp(b>(=ON^Un)U{GR#tQiGZzEFMLiFUvTE&&()K>UG$XtFT7?{0mp>Rr0RW_iMbA zNnv78c&{Mr=IN_8g>lDo+ZXFDH2b_@<`?{1GNE&I*sA$GJ`4;Z5-Eo?GEcT_zwvrq z!u9IEZR;Dmw1orzmdtrpaLlZ!`fBt9P6mjpbZ1`Z-Ye9!FU2Xi@kHI8T?(^nYNN_! z-aHD2`|+NoaMs?#mrSE(d(6CW(W>Xw^3tr<UgMPuzh|CyFZi-38*bP>AD(y^hZQu1 z!oYCC`b0}0cxne?;Q$Ml%#8T@Gd}V_%(wG;zb?4{yLVpySM=$+zjxyQzvZrt_I-AJ z-5&-}TF;)qxwymUiuC8=slV#~*#CcTzc2N1+wA<mhu7b!n*7B7%+vV)=j(rb^j}wZ zzy3S7l8IjZ^Y{PudWXk-`>DU~v#FnXeBl0nZL`hoKE%t<nz340n1R8Pb*4d=s<7|M zSwYtK=dRgPx~=9($;-3BZJ$1Di{1aZIy<-e$JB29pTFkU{XS~$SMz$_|L4Wm|98h* zy|1bM`}@45`>hkF#N+KB?yi=yELx?)?#OraNzB@qY?E1^L9zADL9It=YS62tA)uMJ zFC|~+cAomUIki*d%9l^SZXB6^xA47v)W^VR@pb>+p8qqwz3xG_a%IW&fAyOmYUde0 zOqSpO=3D-smoNUw|BO--{ar3Ud&P-`GxV-L-CzI;688z5i*FbOt~F2BF8!%fm$s}b zYgbi~*Iysy_Bi`*?e!&}E1&BN8e2S{bF}_LeqPnX3yJZw6Q0D?@A}#I|Kt3+XM4NF zZian4$RE4oUHsbrr{DkYU7vd9#{M5SXU<x2HD+ntYV)J28#oyn?lk($I5zL)iYrn} zvy!)6nxT39sq@b*e|$`==imCg^L%{z>I3WJHr0Hdf4?#->DcvU(`|l)^Z#G1|My_K zUQAl~){Kjb>VM6=zxVgO-*NU;cdi#rh}gfQ;%dxR#ir2wRn3oO)EF2}@SkYOToUDV zRAl~&$cai?NfSfVmZ!hp`~F{l-It)<-|C;0*MHBi+i~@J+J-$}PA&ZZq4)oflm6>A zRf|0dG^=~NjrqLo`|O+HPp+?z3>22(dal99;LzuwCdQySb6b$dk~XzT+wWICU%ma# zrj*WE7bEsme3Z|-@!{C){9m_JCK;!nzgPeN@AcUFy*6FBqMsI+uZjNt_kDeRS>Czp zJEq?_e$Y+<Tt9ZQ9@AWExT*a8zSryb-&^<k^mP6I=gQyBnyvlw){-f6t=-LYZYc0) z+3zYiYkK_z-=3e(1mjQhF@p2jlc_-~zZ_uZkEvQ|ytwe~*6Vq<x1GJ2Hb>dLFXz@4 zPoG2gBprF2ZIbWrtM%h%V33HL(D}#E%&e^2Y_Xzgbk@$zxeEo4R(?3hetm6p`ull% z+povh?_DD!FJCUj$Z(*b(dP;0&jstxXWS{h9vif0ZthLzZ(&Q0%UTPDt&Q56d3o9O zxazZ+j0_CUj7AfgjZ7CCGPw822)>_qH}1-=f}@*KPlKknp1<DCz|f#Eq0?vbQ^{UN z0qt9xQoA!+PPF8TE)rLgT;%m>wpA~Kg7=SeGt^l9MNYW5oxI+2j6uex;=}Cwf1a%h zeajsV8hKCh+jK9Jk%7DAO3(E8+OLug2KOqT&s`9rAbeBly|EOtfti`w{!KF`*FEei zeSOXL$Af0)XZ{R35By@dRrBt_!SvHl)1N=*ytw)Q+U<R^)!wz5i%X{}h^HuN^W5w? zme66zsvom4^YSt#Ij)9QCoh-1jXo1Tboj_vR;{_VK`;7^O{&O=BZrK?7)vpKxRt%W zHEu^zNy(K=Mg~oVuZ~$RTl>Ju_Y^+45wlg%E|E9M^1Mt+(m{;}J;xY&`up4Cb~y3L zimzkvkkRCQHJig#EzUvB!^1_b?$@)6GrN8jshZw=Xj3?$v$a98_aMjKf}`g9fBNdh zFisE&l3wC8CA&9$BBzkp#LoG9K5kwa6r18S|D}Uk&!HYSC70M8NvEgj`f)Qza8#!( z3UO8QsBlrM`}6C(+ViZWIVV~&XI%8)wA`>ze4W762Zux%m>Ya1oGVOO6cP?vLS;DP zq5+%uI))B@@NkC#udx(2tN1zw35k@Z5<a6ujx-Y^5dQ@?m_O0#Oh$^NUJT;}?h`C8 zWm1$}XIwlX7_$Skj1kPQoN@7lb<7T?1MFb)JcQCr+IaM07!#U(CY*Cro75=T`_S#5 z>COUH5lOI#g4}5)TpZ%-8km~ED%e^ic^@1S4Un0@dCBsG%YB2zjE*}BSb5CB_ALsZ zaj_xp!68wDDGI_%iYIiwGg!>Xe4teuGzsSMTtRqlf*Z3?BX>Bck>>GSBv9?i+}JG# zA~~8Rc|ADwVi+x1XP$_W>fLK!TY3KU`EN7!s^7DE@LKVrh@aY%yEUDyo8Pob@)|UA zWGjiUo3LDCacTlXic+xUg*o;CT5l~sd|}qVbH)4LtDpHD{xTV6YkyRGs~nxw`SD|6 z`JRK{BPU4mMrg3@D>(Y%#R`*s&t_#;taG}hAbhjah_kRMsPg;f-TVGN+Pc@JCh5HQ z`FE?$znjm}?DZG%R{K)?=IORIiEhlBocD{b6L`2`cI~U+`Hz<Pd5EScSqn-Fs8^(I zyE5J9&A*F{wpZJJv<OXfnEx?YVdjkuiOqk{y)Js(Yi_id@#d20+~F^xT{}K<dhkOu z&b(o4e0{o)&ELh$yH9`JyVcFBS=e<VXQg=Ay^_5Kiy0-=UmX(VxBIbR^PQxdn^HLp zm$>w$Jc@qp?shHz>slX!%<uP2*=K$J{p#%9%f<fRRfYBCZiKFSzcR|`V$QE$J@cJT zwA7p^zL&Rm&vV=Nj>-!9Ec!8mE;UW|=B*|#0@XqmmPRh<k`8^dJtt1~#_GfMDzAUt zIj?i#h_RAz@aEc+M}qa`DvGvk3qRQ+b^F6tN&Cb4!k_NFI_JPX@qCS+b;F+x`S<sA z>+L#GDO5c%-8$Zqt@CoTPtM;pHvhx&?_G*gb}c{p>~K_b-KJ2jZ?EjFWFqc6?>ceh z#EJCnyR<)R3-{K!tL4nR5uDl4p&(pqY-aZC-^*By)6@0KXE8l#4_f&oZlzMk50>YG z&YMc6a;^?p|356@Z-b|&TG;ykYu=>YuK1)Q{I}nyC(Tjq$>wu!D<5Br&X3(yvhwpk zsk5cmW1rtqWd3t=nXm76dB&v8si(!BpWqY!w4`+2KEXeC&i}n5zW;~o@=`_1>S>n) zCoh@pvm&vR@3FwU6%9_Sk9>R4s&(G%nwtOPYYt7zQ&+cN$XndCS5<iScA0y77TH=n zoZiXz`{jnZ)$9L%TgDQ*D!E8UcvD#1ocX`5oOrwaxl#PzS0{MQEhd^jG|ir~CdzbE z&dn3~f2ZyL%j707a{_Z;&=GgOhm-hgGJY=q|FrA=&-gZ-`sdAW_dhPEJpa4yqxkvX z7b^Gv>g2C`v#R@g&AsyJPN^R&z02R-xfx>N&(_f?bHdN);mQmDB1CWLZn>7z5%(jO zd!toh9=n^GjqX~P(%0JG@?>UikhW+RmYezFN@Dijz0&jkUeC|oZ1Ylez0ty~=;D9d zZo8<bsCt?^t-Ux!T=#vG;l#u0?tv+fZvB6}QU6|b#)(hc&s&Di(|R8Nsk8ff%=S;a z*4O>=|M&Up{mO&am!0_eRCKjmeNy`2s`rnkPT??2aSBa6ujVWACFxBh&s0wTm3?on zU0*I8uC`_G)l{Wb&RgTA&nWx9N<LS;wtJ=Ob|b~}3!nWtwq8+KP3gqxtzr4AzB@jT zXZUqYPw~?|^C?D(_dZz1|6iD|dU12k(N*r{Z`PccJxgNg=OqmhJbJ<hg;txs^H(cz z?Rd9sx6h5eD-W{ysx7j*bLU>P^}V@Y8huJ+X0Et4dwbp<-kAmhiC%w`4J-t?Een#8 zKkc!t_i$J9c&_vN!zy>V+L+3nRkD`nxjLN1XKt{&_FDe_?ap<-if)Jh*jsAlI&*{c z`Wt&pxB1N2z#d<uDg4Q5iumF^n*Z}pv`pl9ym{+Ques(2EpFu3OpQ`ZeI&hoh315b zTf=`{6W3G{w!iW1htE#E_pv>`Do*AzH+bc|kYrvfbw6%#)`l{!rm!EkyBjaP3vYRm z_g6Ri<B68ywj-}Z<z{lcy<q?M;a$)7u{|pLjSS-jXYLT4X(0IUOG)XrMQK(Q{4x^X zd*A=rA8#@9$C=XUeK8xqJp#@2e9G7I)BE#bm2Ur=8G6@UHQpMlE2zb$9<odhTzxI5 z<n2bT(Awy44@|N}tK%QO4_IESJJ&SvE?e}ik0)D-r(fHvGS@0+?e@Ig<r~vHZ`GcP zy|a6{guB|Z=ilDm|9+&n|H~xx`L%Ce%G++AaDC>6RHto<!f8q!K4(ItLMtDB;<M0T zoz|JFtsf*+_*7I`IsA_7ji@O%j0{6pon}`|Q4*}0z}XoZ6T7AB-Iavy50fRCyWhp; zEd8)`i}0=73~x^dwKoSl<GyYFTYb{2bp5y3FYz}oOlhCg>Gt_$(chDkh5h%`{@R$l zT%}*mR&v%`cmG`bvaI7DFZ<7#7k5HC;g(ULqneMaz|0B$Atzj9y0qc*vgykX&-x9X zm!0M;o1#=$HJLL>NlEzCZcDA+i!)#KojkQT{dBbd^hKXeyu7r{c<I~6Q;#p#+Wjnx z``cX^@SH+tK*Y>|Vj1zfpCn6v=biUqH)8zgpteaku<>ti<wd56&2uk5625v|O=}VN z?WgGmkEhBCix%=3_TPQ_YhUZHYXP9C&Q2GNRp9wt!xgt%=e~4M6Jnov!q0`(g~Nrr zEL>{0*H`uQY@x!|i;_PjeZHQYxhmuM<)^>yWhKuqJ;Y*U_{ULAXyF2*h0DzJVt?|c z2lfVKbhmODO|&@SQdYEJrIOu8pS?Sm-<r@7`bO{iVddFcycaw6nwGvw^(vMTN>Pdi zX`f-V&~Fz{z?_x5wkKR3DG1Lz#ptbhgl9@n#Le*jo~#EMEwhv+&fj-Wh|_4|T8<Mg zHC&oVbHf^86FQGLs%;WWWqY;UG&iv~w4`U&Esx}~!@Ncl*D45i2Dr@paIWx2coCD@ z5$2gE629%P4)Ut#w=}TU4tw}o@!$z(p4mPtR!`fx=6n9x3YHWlJJu<k9gZE>3RsO8 zKWeP;af#iUl(?8p`qb0A=Vg9e`~TfZzcS(WXMfq6$h+DXLW3mDW(Fv2ta?(A9e5<^ z>$7jy-muT~Xkj|Va<SP*#c#b)V(iYKQ~CeJo389D)-G!bUo5rb|C&=S#s6boo~%9p zbKcLuoj<Gf-&+0HRJ(K4l$xX!DUUv+ef@J&Dq{X(kas6^HnGq2m?M{ZXqVNKU+2I5 z=oQV9xVbkgh0EyS&EAI-IbVl#{!CBvUR-;s<uAMJHBFI!c8}9nq&V3cE<UEn*MCA- z^Y>yACL=-lltm95)r6Lt&kSIVepSAn^@g&rr`yRRufERTdhbj0_49H{GXuoeX1$v` zSNiVvHScH2i%#rRkFR){sTXxMSSL1Ozv+g1d`5vPP#4WhaXMQVAuMz5dv4XXRjb}C zFx%P8Zsy4P(d5E4@6DpK`L|bdul_R4C+FUypW6)f`?!47zi55^`>MV7PKZ~zy7GFP z%&JcNHM#TR^Y~k);kTnV|8q0Bkp4%+O|3|Xab^d<QQ!v!;m*t5J{GDmcf;a$t~_6| z!srd3P)_Xon)YesDNg#g!<LqFm;L6pnVa@*dqL!`1+~i4h0Fc79RGU4W&6LmzTc8> z&i-=u@~+qhjhQRV%l-LPglo**zbgn|V4A5>F`@IwOGmYkt$9~V-y1kQ_<dxq%c++8 zu3x5A1@i0N%FOotz3^-7s|)*YExFx!dH*Z-*%LqN&gxYaex-fl_f*c;+9zIL%M?E0 za(u;d=XL+elqFJ>1fe1G&gh{j^XtX+*%x=OoU1XDV_KH4`>)BIyBno4FQhDT{(p=4 zX5p{!-LI72m>UVXt1V0WJ+(7XRrs6bj1w-$BhH`scE9zRAySO3_K7gP?f;_0&Dt&H z(7yLwXQPu(A8ESTtbd}V^Mw75cfy}o3XW-6FmCox5dP~H`#Gy)Uy{g7k2!fp59iBH zSYh;Le)flB(O32wJ<MI7wX;mlIo{}^lv?D&iJdF{{WVtb`yaUfkQ2*H1Cg&=3Jcda zboz*NS{Ob2xogdwE8(xXolJk-f6Fm5K>Pwv^4qEZrp-HYfBp<mLhANusVm4|zh#-k zomYCV4|nZa$NH+QU05Z0dvkYLjnTs|4_+^E{=aL7#q2%%n|5_qmtS^N^Y{)*(`-{Y zSC?gpFP$c|d&2Yue1CWKZdmc??!Daq`GRu!&tu)yeo5_;NU0a%HJWHKH`Pfr*8k(S z#a&yTPw{CllPp`cb*ad!ZRdreTIL8!Zp=_u5dQYS#sBZ?-CD1&%FeBRx&M%pU!{WZ zl4?+HZa&%awQ|?#^t{EA0cusd7hBGJ@mSnb>x9drl4+btMkiQa%B3g?vQ6r|R-W|p zy7k78#jRmsZ!dO#3tQc>O*~rHdG^lPHL|A`J%8xtrnk@Y_Nxou<gP~O-+Pt4_s*lW zzM)%gu~>h%&p04mW1V^Ya{soihyS_UJ^D|}Nc#KqsV)EZ#Wwq>@EJ{<3wO_nme4a_ zjFuhOYRog-e5!c0fYsG=aV6S|wq<;OnJM;WVd?G75<eW)Zx7jCYI&i%{CD5&u(&7R z6t-_==j!v>p_lr0+xgWs)|xL1d=`CE|E2e;?Dd2DwS}+u1@6zkt{~jm?31Ft&gaY5 zwF^(UY*bPZ{^%K{_9ZCYb@h>bTGCrzMCX5fFy-nAxjkR+-8%fi)&JwRI>GbFTNhQ8 z&1OwiDv?*ZUSg#t_*=Mk`h{lszrV{sF>u1AY*EUhi#1j2etns^eV)yq%@^m(-TXOO z+25m1X4?D}YcHjJ`QiC{QRuhw_Funx<RJySV&Y7WX@+YHpBuf=`_;WMtV+51!^xJY zFAsCJ+I`&qkxwgvnL*F<q|5PSp?&tT{EHVYzrQ^jQkV-*?5zFz?44KalLs3=e!6D- z)ZK4toy1&szv*(e(RDSOHf66n_jF6Q5aY~_^9n|ZqOtdH?3=tU)L<9S?(Tm{HVb@O z!h_FyG^o#u_xhUSqt^8M@<+Y0D~mb4)h@2Tzs?a>$<147?#k`LH*dx&8?!*c@Qzbu z+LzLvmwa6rRGYt6QSXp=EpPpVP8SIewLM$I{1-fnEM0e7rM3Lx_ItnH+*`{Y|CRTh zoAyK_K@+y^Gq-;}QQHx9`Qr?i(=Jb9ZxzmV{SS}&4z4%(=eosgV%NQ&wYpQ)Msen< zQ@sf(dvj#xuJk&6_ndgKNSxZ5>?uFPmreQ6ZyLdW!bOQkP54|-Lm2DQrd#r_Lp5`! z+pdmWy{Sy^@ViA<n|GhQ+^j0*7yI4hb9nG;o>Sl6d8*5HZ+Cg`7@9ZVXN&dwKhZAh zIxW-!e+yTN-!$L;c^iW(A|+}_XPkSVf9Cya({CYDgWl*}pRafIshfva*6Vj($@yCq z-v-ZmJYk8x@U^AtrQ3c<eUaH~v--AFXZ$UpnI}w}PqiG;O3;h?xrJ+Cvz_##)tdsl zzx9@>M@grz?*03H=GwLIeuZ7VUcTOToq(or-^v?nVqfMiE6;mBuUh|p(hI5dRPMhs zN^Z<wvHQjAzyF?G_*c7|ZKlVZ)~THrw1c0jX1@8;I4#KLa)w=Sc>My!MFOHXSIsh= zHO+I0k&dEgxZ0aZ`+pWxpM7{X=qLLhJ-z)tJN_;ySecWebp6PL&MiVwJ)T~mlF5DM z1%2(A39MINZ7h{M^<kcM&MWJK+G%`u>b=yq><_E|cKp2U_gDAiiXW^!{9Bjx<JZX{ zK~p%N^2SZ>nCUT-L+2R3(Zp<MVJ??)=vN!}TcvA3F17K0O$(G#4^_R+kG*NdI`c!# z&hWMrr(T~ar_S5$FE09&yf-E1P1RFjU(@3gC;2bY5Po%kQL^dQ+`|WN2l4G|J}*%< znRDw6r}?3rZ^MLg^6kT_`S<P?zgl1Yw`w_id2qkrgw7ud!mRv86D?v>53SmlS^GUS z#Ww8y=9M+RZNExEy~{s-xwfaed~OKK{C@6rUiQwz)e3=v^DDkxxK~?Ry-Yd&xlcqe z|Lg5+*S05J&)hDwTI-J1-cS86`qE#xEt;PGTJwrf)7n+q-#0FrRr)II^{IJ!f!bF$ zpNM)n*RAu_{e9lIU0cF7-&0l){&;eMkHBO{HKFCReO}yuDJt~6d7snjHK6Y2cC&lF ze6P2^`g&vU+n2^~Rv%)k2r!4#^Krq@dj9*{(CW(z-Yxw%Yw^XJv~BS-Z){$EOJIIL zvv8x`<Kq*2ERJ41rnT|f!(7v85l#Yggg=I7@9oOo@;<{h?@5yO+dSnZ?)5t7lS=-t z@_xIAH=f_t%|Y!^vyX@ksNkN+`F?um?<CRK?FCVr71ut>3J*K(w8rnv?Q2!f_58kG zegEiM+UvD<WM^J5=l!st3e?@S26s2F)qkIRz3QEQ60?$Ub=tFElRBB#zquK^?)~Qf z3zRRU|Cu2-v%o87!?Ehyw~yaf^iqp@eRY54>utKKc6ZphUT$kX(sIfr<bUJ+>(`x; z<H|6_Ni^!b+UvKs%^3FX$m;%A$XCx>_I^?6)4L`Inzuzo6{b4<zFIQ##fADW=T@(~ zRsA~tjV1dV?F7H`w%?uPjW+&&YP<VcR`sU}Rv*iTgITYp+~_k}_|Nx?Wow>MqIkvf z3GOEvRrcI&Oi@}=pQ7XqO(M;wT{fg-^&Wm*wZMGu%;$R7qIce|Ou1Qht)wPk`_ie~ zd~Wbw@n}{Pmi_g9!{@C0S{@DI^Bq1uXTNC+`=7hE=5*%jjlA*mKTclc)AG->JvfPZ z>2<wJuUeS%w{DxKbvMPyo?Yq2=D92KlyAN6e;V2I>i#6r6eVS-<*_MB9}4%(WqeiD zUiD^o_t&s_+k9?(kKI_AEo5ZaVf!QLq)T$cM9$aU`#$|#yKvR9>e@rP8(+D-;G9vl zbsNutmA~$N%K5u^ORAIo++f=k+dQRKeZ6?M>egws^6w_17sL<${{GMHTkhU=IZ#^E z?DI)^((khA+jcEb{7>dwozgasQ9xr|nD13TO^%hX|9P^2Lg3z_d-qIEfI=MBYYh_( z%(nU}zxVUOYF-g{wO{fxPy7s@aC_=)SM9@oN4H+^kG=9grDXG+yt_w#9WT1I;&xQ{ zHtijASJZzOTX)K(^mX?AZH*i=C$xN9zka%HAb-1$jzHve&euWLr1r+CT1liRnSdNL zm2-E;E7pjv6}DjuS7olAV0|{~sP(FKugf>)x!*Y&J@2b;6~C?B3c2|{7PddEUS6pG zaV}a|^=;nMxIF&aB`b^^e|0wa98o`QwD8rs@24)v>e<~jJ>il8X`!lwZ7lgH`bI1; zJ*-OncC2T0=&i3ove!0ixL#3PxSc&0*8VBKQTbj`s^Ap!Ooh9kKs&j{C*uB;i^t1- zN_dR~rC@zbXp3i)mhiRfVWm2|ZhbHM85MPZW9H-Eo7Np%z2n;Q*57BN)5?{9LR%9c z4U988{M}Ly{h#{iUxcd77w^4Co$h?(>7UpVUijZqQtV&as{hk$Uu>UzySJ4a(*0}l zneYx&oIP<;3t=n^oEkATw?FI77PAsRm%AHHwG1jm!>upBi+O$gP2LjW6s5umoo`rR z4sZ3@QK+?X`>xd$x1yC<^f*HbYfYSX=T?~qaY77#bmB-(<^RUL_Eul^mc@0RSonVL zk4w|i`QD!YSgPi+A7pPzh}s)38I4`GCtBiuto=53^^Q_^`+sTIY+Ac_n;yIyu><P6 zX+9?N^{&sivHf}E_HudaGOtfBE>2!}v+m24Z^_HcWbFU`czJVA9OGmj0Z<r(r7Haa zZ7ToJ7ro*q>+3tL?_HdYLSt-WZhY0{dGBTgYg?#YDK8F@TD*Cy?BuEL=cjF-r|0@~ z;^n2e>0Y;wYxnzye)@G+CZ$0^xN}0}%#2?4ikd@fkGyhwF|)s_F<jJEbLNK!l0^pF zq+hbk^pF9K$chHsmx{`@30?Jm&blstP;({rhMs-1<oY)=R(Q<5I5W#`zv&bn5s(wx zQV(^-cE(1jMka|Cv2Wkyy=DK^nB75n>H$ZO3Yjeb$mbz(r#GYt(kkuX>JYFA4!7I5 zI;6TN%rz#l#I24^`St4E&$9fdzrIul?dF36G*-<>U@7aYBR|fypQwg3)Fw0gnpz~z zx7@h>+MVFcH`AuPez<YlyS1x2JeQapS9Da{Bns{nt@}84uV9stdmW@LymE)#!ZwXH z9U3mKrUA@C-(s)u#^-mk%sde`q0_}dt*X;*x}gtf<{LB^k-!)6-2X=11>LMH<=&gT z<|kaXfm*eWYFu)lRKt16a_^}l|Nni>kJ*uPQ8Zg@b&TVrzS@NAI(6?C%@?0JW2MQ2 zPKzD+HRAtHt=HT8<oePr6P%vr|3CD5yX{94qlpS9SYFP#m$K-djisIPvj5@s6>qBR z_x`Pp-uC~xZvUhdW%h3e_ut$1`ar+m`H=KeU!(S(w0>}4M}Cd|-fz2X^8ZhIo|~xj z|I{a|Uk8)@=gwN^H#KXjl+i>Ukg;(oiy~K=F7qz^dF0PGm!~&oewuiB>HLWzpRV2f zbR*^I8K2UyULOVF=Ee7Z%=-Lk&b0H(f<pS{>&n~4KB|mvk+BT5s#^BtTgA^aK4)j? ziOhVkbP5B=SUn@f6R!j8RJ|*u=dYbRXH}nX$UV9B9ibCcjN>ZP7ZoLKQaWa489q6D z&7QnUZW)Q+z5Xf{%VO-UqpQnT9s0aYLo(b=kIm9BeD-Rkr=5*H6VAPKRhxC~cTw=Y z=}*6E=AZp^F>=j(m07D~A}*T#oIYdiivD0PwK?^SFQhHYyqea2w|iX~y?x#moBVdW zSEVX5=S;pH=$vzD*5e0LAr6#FNs2pLa^=-ouf3Yf^e2YD%-QKD<hRr?JabC6?{Sqi zMI6k@w)s>2JzOW2I|Q1{+uqu-r*GA(_!ztY7VDLtOEPYpaJa)~0^dtL;iffHuP?Eg ztn%rd&ec8@Im-<~mWRImOxnYI%)M`6h;U`pb?H-DHSBYEvfo^v*m6Cv>BPh-&Rsqe zR(w$rZu+}vO8D|!j+eS>8?NShu#_59-V-zY<b1bb$%N!ikolo%3=9i4fTx5w85mwL zfhV6B7#j3Q6l&5I*5C8xQseY^%YqjZPHDG9Se9h`=Vq_}^lalvOVBbirGnH)U#{G_ zxY4-1fBwIZ8-wlbs$OkftnPVG*`K-6NXD-2)e)D<qIF^0_OG~9`3SV)=7Q5nmiX8H zhl-wryu2~<)9uHpl}SERv$9f{Kr7i4zMTNcIvK@HQ$GyeHF@^mwd}7)Ep%st*7_W9 z%xYeecDCfh)_+H&zh3<>T)g$=rqV+#UuCPotKGItWIA~L*W?LX_I;1{ahfL=Hyy02 z`>AlvTKkXg^LRc@38+7^@ULt;XpIj;-I9<M5tARaWK5KQ1=>W$z`&3MT6DzV!1L_+ b|N2j>r2~t+3RM^w7#KWV{an^LB{Ts5eTDYH diff --git a/tools/bt2img.py b/tools/bt2img.py new file mode 100755 index 00000000..b6f828ea --- /dev/null +++ b/tools/bt2img.py @@ -0,0 +1,157 @@ +#!/usr/bin/python3 +# Copyright (c) 2019 Intel Corporation +# +# 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. + +# This tool converts a behavior tree XML file to a PNG image. Run bt2img.py -h +# for instructions + +import argparse +import xml.etree.ElementTree +import graphviz # pip3 install graphviz + +control_nodes = [ + "Fallback", + "Parallel", + "ReactiveFallback", + "ReactiveSequence", + "Sequence", + "SequenceStar", + "BlackboardCheckInt", + "BlackboardCheckDouble", + "BlackboardCheckString", + "ForceFailure", + "ForceSuccess", + "Inverter", + "Repeat", + "Subtree", + "Timeout", + "RateController", + "RecoveryNode", + "PipelineSequence", + ] +action_nodes = [ + "AlwaysFailure", + "AlwaysSuccess", + "SetBlackboard", + "ComputePathToPose", + "FollowPath", + "BackUp", + "Spin", + "Wait", + "ClearEntireCostmap", + "ReinitializeGlobalLocalization", + ] +condition_nodes = [ + "IsStuck", + "GoalReached", + "initialPoseReceived", + ] + +def main(): + args = parse_command_line() + xml_tree = xml.etree.ElementTree.parse(args.behavior_tree) + behavior_tree = find_behavior_tree(xml_tree) + dot = convert2dot(behavior_tree) + if args.legend: + legend = make_legend() + legend.format = 'png' + legend.render(args.legend) + dot.format = 'png' + if args.save_dot: + print("Saving dot to " + str(args.save_dot)) + args.save_dot.write(dot.source) + dot.render(args.image_out, view=args.display) + +def parse_command_line(): + parser = argparse.ArgumentParser(description='Convert a behavior tree XML file to an image') + parser.add_argument('--behavior_tree', required=True, + help='the behavior tree XML file to convert to an image') + parser.add_argument('--image_out', required=True, + help='The name of the output image file. Leave off the .png extension') + parser.add_argument('--display', action="store_true", + help='If specified, opens the image in the default viewer') + parser.add_argument('--save_dot', type=argparse.FileType('w'), + help='Saves the intermediate dot source to the specified file') + parser.add_argument('--legend', + help='Generate a legend image as well') + return parser.parse_args() + +# An XML file can have multiple behavior trees defined in it in theory. We don't +# currently support that. +def find_behavior_tree(xml_tree): + trees = xml_tree.findall('BehaviorTree') + if (len(trees) == 0): + raise RuntimeError("No behavior trees were found in the XML file") + if (len(trees) > 1): + raise RuntimeError("This program only supports one behavior tree per file") + return trees[0] + +# Generate a dot description of the root of the behavior tree. +def convert2dot(behavior_tree): + dot = graphviz.Digraph() + root = behavior_tree + parent_dot_name = str(hash(root)) + dot.node(parent_dot_name, root.get('ID'), shape='box') + convert_subtree(dot, root, parent_dot_name) + return dot + +# Recursive function. We add the children to the dot file, and then recursively +# call this function on the children. Nodes are given an ID that is the hash +# of the node to ensure each is unique. +def convert_subtree(dot, parent_node, parent_dot_name): + for node in list(parent_node): + label = make_label(node) + dot.node(str(hash(node)), label, color=node_color(node.tag), style='filled', shape='box') + dot_name = str(hash(node)) + dot.edge(parent_dot_name, dot_name) + convert_subtree(dot, node, dot_name) + +# The node label contains the: +# type, the name if provided, and the parameters. +def make_label(node): + label = '< <table border="0" cellspacing="0" cellpadding="0">' + label += '<tr><td align="text"><i>' + node.tag + '</i></td></tr>' + name = node.get('name') + if name: + label += '<tr><td align="text"><b>' + name + '</b></td></tr>' + + for (param_name, value) in node.items(): + label += '<tr><td align="left"><sub>' + param_name + '=' + value + '</sub></td></tr>' + label += '</table> >' + return label + +def node_color(type): + if type in control_nodes: + return "chartreuse4" + if type in action_nodes: + return "cornflowerblue" + if type in condition_nodes: + return "yellow2" + #else it's unknown + return "grey" + +# creates a legend which can be provided with the other images. +def make_legend(): + legend = graphviz.Digraph(graph_attr={'rankdir': 'LR'}) + legend.attr(label='Legend') + legend.node('Unknown', shape='box', style='filled', color="grey") + legend.node('Action', 'Action Node', shape='box', style='filled', color="cornflowerblue") + legend.node('Condition', 'Condition Node', shape='box', style='filled', color="yellow2") + legend.node('Control', 'Control Node', shape='box', style='filled', color="chartreuse4") + + return legend + + +if __name__ == '__main__': + main() diff --git a/tools/update_bt_diagrams.bash b/tools/update_bt_diagrams.bash new file mode 100755 index 00000000..15cfe088 --- /dev/null +++ b/tools/update_bt_diagrams.bash @@ -0,0 +1,11 @@ +#!/bin/bash + +# Run this from the root of the workspace to update these behavior_tree images +# in the doc directory of the nav2_bt_navigator package +navigation2/tools/bt2img.py \ + --behavior_tree navigation2/nav2_bt_navigator/behavior_trees/navigate_w_replanning.xml \ + --image_out navigation2/nav2_bt_navigator/doc/simple_parallel \ + --legend navigation2/nav2_bt_navigator/doc/legend +navigation2/tools/bt2img.py \ + --behavior_tree navigation2/nav2_bt_navigator/behavior_trees/navigate_w_replanning_and_recovery.xml \ + --image_out navigation2/nav2_bt_navigator/doc/parallel_w_recovery -- GitLab