From 4d0923643f589c9824aa7febbf6e85a0da724410 Mon Sep 17 00:00:00 2001 From: xfiderek Date: Fri, 6 Sep 2024 09:59:45 +0200 Subject: [PATCH] NASA_Challenge_[@xfiderek]_[Improving fidelity of SSRMS demo with Trick] (#42). --- ros_trick/.gitignore | 2 + ros_trick/LICENSE | 202 ++++++++ ros_trick/README.md | 152 ++++++ ros_trick/build.sh | 15 + ros_trick/canadarm_ros_trick_demo.Dockerfile | 50 ++ ros_trick/docker-compose.yml | 44 ++ ros_trick/docs/moveit_rviz.png | Bin 0 -> 199135 bytes .../docs/ros_trick_bridge_architecture.png | Bin 0 -> 339544 bytes ros_trick/docs/rviz_joints.png | Bin 0 -> 31139 bytes ros_trick/docs/rviz_motion.png | Bin 0 -> 129433 bytes ros_trick/docs/trick_main.png | Bin 0 -> 38677 bytes ros_trick/docs/trick_velocity_plot.png | Bin 0 -> 9579 bytes ros_trick/docs/trick_view_variables.png | Bin 0 -> 41929 bytes .../canadarm_wrench_publisher/__init__.py | 13 + .../canadarm_wrench_publisher_node.py | 117 +++++ .../canadarm_wrench_publisher/package.xml | 18 + .../resource/canadarm_wrench_publisher | 14 + .../canadarm_wrench_publisher/setup.cfg | 4 + .../canadarm_wrench_publisher/setup.py | 25 + .../launch/ros_trick_bridge.launch.py | 150 ++++++ .../ros_src/ros_trick_bridge/package.xml | 18 + .../ros_trick_bridge_example_params.yaml | 8 + .../resource/ros_trick_bridge | 14 + .../ros_trick_bridge/__init__.py | 13 + .../ros_trick_bridge/ros_trick_bridge_node.py | 198 ++++++++ .../trick_variable_server_client.py | 85 ++++ ros_trick/ros_src/ros_trick_bridge/setup.cfg | 4 + ros_trick/ros_src/ros_trick_bridge/setup.py | 30 ++ .../.setup_assistant | 27 ++ .../CMakeLists.txt | 11 + .../config/SSRMS_Canadarm2.ros2_control.xacro | 90 ++++ .../config/SSRMS_Canadarm2.srdf | 56 +++ .../config/SSRMS_Canadarm2.urdf.xacro | 295 ++++++++++++ .../config/initial_positions.yaml | 8 + .../config/joint_limits.yaml | 45 ++ .../config/kinematics.yaml | 8 + .../config/moveit.rviz | 448 ++++++++++++++++++ .../config/moveit_controllers.yaml | 18 + .../config/pilz_cartesian_limits.yaml | 6 + .../config/ros2_controllers.yaml | 77 +++ .../moveit_rviz.launch.cpython-310.pyc | Bin 0 -> 499 bytes .../launch/demo.launch.py | 67 +++ .../launch/move_group.launch.py | 73 +++ .../launch/moveit_rviz.launch.py | 14 + .../launch/rsp.launch.py | 32 ++ .../launch/setup_assistant.launch.py | 9 + .../launch/spawn_controllers.launch.py | 9 + .../launch/static_virtual_joint_tfs.launch.py | 9 + .../launch/warehouse_db.launch.py | 9 + .../trick_canadarm_moveit_config/package.xml | 46 ++ .../ros_src/trick_ros2_control/CMakeLists.txt | 81 ++++ .../include/trick_ros2_control/socket.hpp | 51 ++ .../trick_ros2_control/trick_system.hpp | 142 ++++++ .../include/trick_ros2_control/utils.hpp | 52 ++ .../trick_ros2_control/visibility_control.h | 56 +++ .../ros_src/trick_ros2_control/package.xml | 29 ++ .../ros_src/trick_ros2_control/src/socket.cpp | 109 +++++ .../trick_ros2_control/src/trick_system.cpp | 268 +++++++++++ .../trick_ros2_control/trick_ros2_control.xml | 9 + ros_trick/ros_trick_bridge.Dockerfile | 112 +++++ ros_trick/run.sh | 18 + .../SIM_trick_canadarm/RUN_2DPlanar/input.py | 31 ++ .../trick_src/SIM_trick_canadarm/S_define | 49 ++ .../SIM_trick_canadarm/S_overrides.mk | 18 + .../models/manipulator/manipulator.cc | 112 +++++ .../models/manipulator/manipulator.hh | 97 ++++ 66 files changed, 3767 insertions(+) create mode 100644 ros_trick/.gitignore create mode 100644 ros_trick/LICENSE create mode 100644 ros_trick/README.md create mode 100755 ros_trick/build.sh create mode 100644 ros_trick/canadarm_ros_trick_demo.Dockerfile create mode 100644 ros_trick/docker-compose.yml create mode 100644 ros_trick/docs/moveit_rviz.png create mode 100644 ros_trick/docs/ros_trick_bridge_architecture.png create mode 100644 ros_trick/docs/rviz_joints.png create mode 100644 ros_trick/docs/rviz_motion.png create mode 100644 ros_trick/docs/trick_main.png create mode 100644 ros_trick/docs/trick_velocity_plot.png create mode 100644 ros_trick/docs/trick_view_variables.png create mode 100644 ros_trick/ros_src/canadarm_wrench_publisher/canadarm_wrench_publisher/__init__.py create mode 100644 ros_trick/ros_src/canadarm_wrench_publisher/canadarm_wrench_publisher/canadarm_wrench_publisher_node.py create mode 100644 ros_trick/ros_src/canadarm_wrench_publisher/package.xml create mode 100644 ros_trick/ros_src/canadarm_wrench_publisher/resource/canadarm_wrench_publisher create mode 100644 ros_trick/ros_src/canadarm_wrench_publisher/setup.cfg create mode 100644 ros_trick/ros_src/canadarm_wrench_publisher/setup.py create mode 100644 ros_trick/ros_src/ros_trick_bridge/launch/ros_trick_bridge.launch.py create mode 100644 ros_trick/ros_src/ros_trick_bridge/package.xml create mode 100644 ros_trick/ros_src/ros_trick_bridge/params/ros_trick_bridge_example_params.yaml create mode 100644 ros_trick/ros_src/ros_trick_bridge/resource/ros_trick_bridge create mode 100644 ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/__init__.py create mode 100644 ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/ros_trick_bridge_node.py create mode 100644 ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/trick_variable_server_client.py create mode 100644 ros_trick/ros_src/ros_trick_bridge/setup.cfg create mode 100644 ros_trick/ros_src/ros_trick_bridge/setup.py create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/.setup_assistant create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/CMakeLists.txt create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.ros2_control.xacro create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.srdf create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.urdf.xacro create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/config/initial_positions.yaml create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/config/joint_limits.yaml create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/config/kinematics.yaml create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/config/moveit.rviz create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/config/moveit_controllers.yaml create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/config/pilz_cartesian_limits.yaml create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/config/ros2_controllers.yaml create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/launch/__pycache__/moveit_rviz.launch.cpython-310.pyc create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/launch/demo.launch.py create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/launch/move_group.launch.py create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/launch/moveit_rviz.launch.py create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/launch/rsp.launch.py create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/launch/setup_assistant.launch.py create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/launch/spawn_controllers.launch.py create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/launch/static_virtual_joint_tfs.launch.py create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/launch/warehouse_db.launch.py create mode 100644 ros_trick/ros_src/trick_canadarm_moveit_config/package.xml create mode 100644 ros_trick/ros_src/trick_ros2_control/CMakeLists.txt create mode 100644 ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/socket.hpp create mode 100644 ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/trick_system.hpp create mode 100644 ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/utils.hpp create mode 100644 ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/visibility_control.h create mode 100644 ros_trick/ros_src/trick_ros2_control/package.xml create mode 100644 ros_trick/ros_src/trick_ros2_control/src/socket.cpp create mode 100644 ros_trick/ros_src/trick_ros2_control/src/trick_system.cpp create mode 100644 ros_trick/ros_src/trick_ros2_control/trick_ros2_control.xml create mode 100644 ros_trick/ros_trick_bridge.Dockerfile create mode 100755 ros_trick/run.sh create mode 100644 ros_trick/trick_src/SIM_trick_canadarm/RUN_2DPlanar/input.py create mode 100644 ros_trick/trick_src/SIM_trick_canadarm/S_define create mode 100644 ros_trick/trick_src/SIM_trick_canadarm/S_overrides.mk create mode 100644 ros_trick/trick_src/SIM_trick_canadarm/models/manipulator/manipulator.cc create mode 100644 ros_trick/trick_src/SIM_trick_canadarm/models/manipulator/manipulator.hh diff --git a/ros_trick/.gitignore b/ros_trick/.gitignore new file mode 100644 index 00000000..57d0c1c2 --- /dev/null +++ b/ros_trick/.gitignore @@ -0,0 +1,2 @@ +.vscode +docker_repo/ diff --git a/ros_trick/LICENSE b/ros_trick/LICENSE new file mode 100644 index 00000000..7a4a3ea2 --- /dev/null +++ b/ros_trick/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + 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. \ No newline at end of file diff --git a/ros_trick/README.md b/ros_trick/README.md new file mode 100644 index 00000000..ed6b34df --- /dev/null +++ b/ros_trick/README.md @@ -0,0 +1,152 @@ +# NASA Space ROS Sim Summer Sprint Challenge + + Team lead freelance username: xfiderek + Submission title: Improving fidelity of SSRMS demo with Trick + +# Improving fidelity of SSRMS demo with Trick (Moveit2 - canadarm2 - Trick demo) + +This folder features an end-to-end demo of canadarm2 (SSRMS) modelled using [Trick](https://nasa.github.io/trick/) and connected to moveit2 via authored ROS2<>Trick bridge. + +The demo includes the following: + +1. [ros_trick_bridge](./ros_src/ros_trick_bridge/) - A ROS2 package that allowing spawning & controlling trick simulations from ROS2 launch. It also sends /clock messages from trick to ROS2. +1. [trick_ros2_control](./ros_src/trick_ros2_control) - A ROS2 Control plugin that enables communication between ros2_control-enabled robots and trick simulations. +1. [SIM_trick_canadarm](./trick_src/SIM_trick_canadarm) - A trick simulation of canadarm demo running at 100Hz. The simulation calculates forward dynamics with Articulated Body Algorithm, with friction model that takes into account Stribeck effect. +1. Demo-related packages with moveit configurations, visualization, launch files and additional utils. +1. Dockerfiles and compose file launching an end to end canadarm demo + +Both `ros_trick_bridge` and `trick_ros2_control` can be easily imported into any project that wants to leverage connection between trick and ROS2. Any type of data can be exchanged between two systems in the provided framework. Further sections in the readme describe how to adjust the provided code to other types of robots and simulations. + +## Starting the demo + +The demo environment runs Trick simulation of canadarm2 (SSRMS), connected to moveit2 via authored `ros_trick_bridge` node and `trick_ros2_control` plugin. Trick is used for modelling dynamics of SSRMS using Articulated Body Algorithm, taking Stribeck effect into account for friction forces. Joint Trajectory Controller from ROS2 control package is used to convert trajectory points into torque commands using PID controller. Additionally, the demo features Wrench visualizer, that subscribes to trick data to visualize joint torques in RVIZ. + +Prerequisites - docker, docker compose + +1. Build docker images in this folder: + + ```bash + ./build.sh + ``` + + If building for the first time, this will clone the [space-ros/docker](https://github.com/space-ros/docker.git) repo from the `humble-2024.07.0` branch, due to dependency on canadarm assets and rviz2 + +1. Start containers: + + ```bash + xhost +local:docker + ./run.sh + ``` + + This should start two docker containers - one for Trick and another for ROS part. + You should now be able to see the Trick GUI: + trick_main + +1. Login to the container with ROS part to open RVIZ + + ```bash + docker exec -it canadarm_ros_trick_demo bash + ``` + + In the container: + + ```bash + source install/setup.bash && ros2 launch trick_canadarm_moveit_config moveit_rviz.launch.py + ``` + + (Optional) If rviz does not render with the previous command, try overriding mesa loader driver: + + ```bash + export MESA_LOADER_DRIVER_OVERRIDE=softpipe + source install/setup.bash && ros2 launch trick_canadarm_moveit_config moveit_rviz.launch.py + ``` + + moveit_rviz +1. From Rviz, Set target pose for canadarm with `Motion Planning` GUI. You can set target in joint space in `Motion Planning->Joints` tab. Set similar values to those below for reproducibility: + + rviz_joints +1. In `MotionPlanning` RVIZ Moveit GUI, go to `Planning` and hit `Plan & Execute` +1. You should be able to see magnitudes of torques applied to joints (pink arrows) + rviz_motion + +*Note that the displayed torque values are `total_torque = input_torque - friction_torque`, thus they may dissapear shortly after starting execution, because arm operates in no-gravity environment and input and friction torques are close to each other after start. Friction torques can be visualized by changing topics in RVIZ to `/wrench_topic/{joint_name}/friction_torque` (e.g. `/wrench_topic/B1/friction_torque`) and bumping torque arrow scale to 1.0.* + +*PID coefficients were manually tuned to ensure smooth movement, however as robot dynamics is quite sensitive, additional tuning may be required to achieve optimal / energy efficient trajectory execution* + +### Plotting sim data with Trick + +You can plot simulation data using `Trick View` application. Trick View is automatically started together with docker containers. To plot the data, simply open the GUI and navigate to `CanadarmManip.manip` in Trick Variables tree. + +trick_view_variables + +trick_velocity_plot + +## Architecture of ROS2 Trick bridge + +The main design goal was to make it easy to integrate existing trick simulations with ROS2 with no code changes on Trick side. That is the communication happens over [Trick Variable Server](https://nasa.github.io/trick/tutorial/TutVariableServer). + +ros_trick_bridge_architecture + +There are two ROS2 packages provided in the solution that interact directly with Trick: + +1. `ros_trick_bridge` - this package contains a lifecycle (managed) node that spawns the trick simulation with proper parameters as a subprocess. Managed node transitions (active/inactive) can be used to start and pause the simulation. Additionally, the node subscribes to clock data from trick using Trick Variable Server and publishes it on ROS2 /clock topic. +1. `trick_ros2_control` - this is an optional package that can be used to quickly integrate ros2_control-enabled robots with trick. It uses a separate Trick Variable Server Client to exchange command and state data with the simulation. + +Additionally, any other ROS2 node can be easily adjusted in provided framework to exchange any data with trick, using the provided primitives. + +## Bridging ROS2 and Trick in your own project + +The bridge and related components can be easily reused either natively or in docker-based environment. First, the native part will be described as it highlights how to configure the provided components to run with other simulations. + +### Integrating Trick simulation with ROS2 using ros_trick_bridge + +To run and control your simulation as ros node and publish /clock messages: + +1. install trick on your target machine +1. Compile your simulation with [trick-CP](https://nasa.github.io/trick/tutorial/ATutAnalyticSim#trick-cp) +1. copy/include [ros_src/ros_trick_bridge](./ros_src/ros_trick_bridge/) into your ROS2 workspace. +1. Create simulation-specific param file from [ros_trick_bridge_example_params.yaml](ros_src/ros_trick_bridge/params/ros_trick_bridge_example_params.yaml) template. +1. Include the provided [ros_trick_bridge.launch.py](ros_src/ros_trick_bridge/launch/ros_trick_bridge.launch.py) in your project's bringup launch file. +1. Now the trick simulation should start together with your launch file and `/clock` messages should be published + +The first 3 steps are handled in the provided docker images + +### Using ros2_control with trick_ros2_control + +Additionally, to use trick_ros2_control to control your robot with ROS2 control: + +1. copy/include [ros_src/trick_ros2_control](ros_src/trick_ros2_control) into your ROS2 workspace +1. Define trick-related variables in your robot's URDF file as in canadarm [SSRMS_Canadarm2.ros2_control.xacro](ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.ros2_control.xacro). For every joint interface, define corresponding trick variable. For example, assuming that your Base_Joint's position in trick is defined as `CanadarmManip.manip.q[0]` then add the following: + +```xml + + + CanadarmManip.manip.q[0] + +``` + +See [SSRMS_Canadarm2.ros2_control.xacro](./ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.ros2_control.xacro) for reference. +Note that currently, initial positions are set via trick simulation. Initial commands are set to 0 + +### Exchange any other type of data (pub/sub) between trick and ros2 + +* (Python) There is a TrickVariableServerClient class provided as part of ros_trick_bridge. Check [canadarm_wrench_publisher_node.py](ros_src/canadarm_wrench_publisher/canadarm_wrench_publisher/canadarm_wrench_publisher_node.py) for example usage. +* (C++) - Take a look at Socket class and utils.hpp in ros2_trick to create your own node to exchange data + +### Using provided docker images as starting point + +The project was split into two docker images, so that the standalone ros trick bridge could be easily carved out and used in different projects. + +1. [Dockerfile.ros_trick_bridge](./Dockerfile.ros_trick_bridge) featuring: + +* Trick simulation enviroment +* `ros_trick_bridge` ros package with default parameters +* Example trick simulation code (canadarm simulation) from `trick_src` folder + +1. [Dockerfile.canadarm_trick_demo](./Dockerfile.canadarm_ros_trick_demo) featuring: + +* `trick_ros2_control`, containing ROS2 control plugin. +* `canadarm_moveit_config` package, starting moveit2 and ROS2 control. +* `canadarm_wrench_publisher` package, containing sample node that publishes Wrench data from trick + +The files can be adjusted easily to facilitate docker-based development. diff --git a/ros_trick/build.sh b/ros_trick/build.sh new file mode 100755 index 00000000..47416b2c --- /dev/null +++ b/ros_trick/build.sh @@ -0,0 +1,15 @@ +#!/bin/bash + +set -e + +CURRENT_PATH=$(pwd) +SPACEROS_DOCKER_REPO_PATH="${CURRENT_PATH}/docker_repo" + +if [ ! -d ${SPACEROS_DOCKER_REPO_PATH} ]; then + mkdir -p ${SPACEROS_DOCKER_REPO_PATH} + git clone -b humble-2024.07.0 https://github.com/space-ros/docker.git ${SPACEROS_DOCKER_REPO_PATH} + cd ${CURRENT_PATH} +fi +cd ${SPACEROS_DOCKER_REPO_PATH}/moveit2 && ./build.sh +cd ${SPACEROS_DOCKER_REPO_PATH}/space_robots && ./build.sh +cd ${CURRENT_PATH} && docker compose build diff --git a/ros_trick/canadarm_ros_trick_demo.Dockerfile b/ros_trick/canadarm_ros_trick_demo.Dockerfile new file mode 100644 index 00000000..a3a982d7 --- /dev/null +++ b/ros_trick/canadarm_ros_trick_demo.Dockerfile @@ -0,0 +1,50 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. + +# The base image is built from https://github.com/space-ros/docker/blob/humble-2024.07.0/space_robots/ +# Git tag: humble-2024.07.0 +FROM openrobotics/space_robots_demo:latest + + +# Rviz does not work inside the newest space_robots_demo, so we have to upgrade the following packages. +# These packages are already present in the base image and here we are upgrading them to latest versions +RUN --mount=type=cache,target=/var/cache/apt,sharing=locked \ + --mount=type=cache,target=/var/lib/apt,sharing=locked \ + sudo apt-get update && sudo apt-get install -y \ + mesa-libgallium \ + libdrm-amdgpu1 \ + libdrm-common \ + libdrm-intel1 \ + libdrm-radeon1 \ + libdrm2 \ + libegl-mesa0 \ + libgbm1 \ + libgl1-mesa-dev \ + libglapi-mesa \ + libglx-mesa0 \ + liborc-0.4-0 \ + libpq5 \ + linux-libc-dev \ + mesa-va-drivers \ + mesa-vdpau-drivers \ + mesa-vulkan-drivers + +ENV TRICK_DEMO_WS=/opt/ros_trick_demo_ws + +WORKDIR ${TRICK_DEMO_WS} +COPY --chown=spaceros-user:space-ros-user ros_src ${TRICK_DEMO_WS}/src + +RUN /bin/bash -c 'source ${DEMO_DIR}/install/setup.bash \ + && colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release -DCMAKE_EXPORT_COMPILE_COMMANDS=ON --event-handlers desktop_notification- status-' +RUN rm -rf build log src diff --git a/ros_trick/docker-compose.yml b/ros_trick/docker-compose.yml new file mode 100644 index 00000000..64261a2a --- /dev/null +++ b/ros_trick/docker-compose.yml @@ -0,0 +1,44 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. + +services: + ros_trick_bridge: + container_name: ros_trick_bridge + command: [ "bash", "-c", ". ~/.bashrc && . install/setup.bash && ros2 launch ros_trick_bridge ros_trick_bridge.launch.py" ] + build: + context: . + dockerfile: ros_trick_bridge.Dockerfile + image: ros_trick_bridge:latest + environment: + - DISPLAY=${DISPLAY} + - TERM=${TERM} + - QT_X11_NO_MITSHM=1 + network_mode: host + volumes: + - /tmp/.X11-unix:/tmp/.X11-unix + + canadarm_ros_trick_demo: + container_name: canadarm_ros_trick_demo + build: + context: . + dockerfile: canadarm_ros_trick_demo.Dockerfile + image: canadarm_ros_trick_demo:latest + network_mode: host + environment: + - DISPLAY=${DISPLAY} + - TERM=${TERM} + - QT_X11_NO_MITSHM=1 + volumes: + - /tmp/.X11-unix:/tmp/.X11-unix + command: [ "bash", "-c", ". ~/.bashrc && . install/setup.bash && ros2 launch trick_canadarm_moveit_config demo.launch.py" ] diff --git a/ros_trick/docs/moveit_rviz.png b/ros_trick/docs/moveit_rviz.png new file mode 100644 index 0000000000000000000000000000000000000000..bf26d2bd28d8411d316b140b41a590064f0855ae GIT binary patch literal 199135 zcmbrm1yq!6v^I=|s3;f+l7a|GDJhK(NK2Qb(hbrL%3y#9NJ)1KymW^kA|Txj(nH74 z@$Et0bH4MRbJqIT|37QJ;mr8NeebyTwXgkrl$92}dYSk#78cf3aWP?eEUXKuSXk$f zIA`G#o(%u|D2(WTxY|=x{D<){8Z5~YH`FtRiW?r;%X3*@ln7( zwbE91KTy$K_{N2Gz24jBt!LIvb%H{>KfS$WX^Q5_g(Zb_%!G z1KFfM8ESEeXPF!p+ zlW@Um8(nH#tX1RYrY3p%5R|`ueZ50nZJu=0U3vnv;GtF}PfKL#_i1ImXVf=1MDk9~ z9?R)W@Z6Rss8KIh73CpMUs%!bGEvmueSNBtH~I!Sd6i*X%r?;#thfgX>5B9r5^{>0 zR(050b?>ju%#hjI@y?+JBO|O=#yoZwa(oh~=u>jpE?`c)gH#&r^NQ$w+A{MpPgQE> zxDEZ1HJqMCVN$yX&Gq`vkEtm=V!xl$)-5e9E?bM-R^v~wy`JLS;kHhar8Dclau&;I zy?go-Z>F-bfKx)V4#6EFI?GXNdV=O&Wfl66XnvR37LtZ%zQnu=n9F&}s89d75Y(us z!mrABJ1AWq^WRXPdik(tCUcwRD^&|UnJN|*76?Rb%JWEaKF5EoCJ=}Z<>fBtv@T=S z&>}R^zXWW4{{E4aRuIghhf~)ZDxUb7lx#yKXQs;t?;3?NlSY4k_=z#N4$>1ogsUiZ zzkEc*NW)P%>0yVD*6>%$B)8>>{{C`qVZmXcx8?V5v(6;(OP4Nja&p3o#_+oo6&Bi= zn4lh3A5euz7_&$C`ZjOQcflcqKw#sMyH5V}`}0S~($bQGBG$((G%W0)deLG>qUiMW zwE0j`G^@UkEFGWKc+KJdHsM1psrrMp1`2(B{UDm>gN3Gjm>*hm$F{|?=)UvwdtN!p zj^&BBek`dH+_YYcP*M&>)tp)W@zIQP-%eO~Er|B_ZKe;1wZO3AlG0MQ-xHWs#1eSh zwC}7qT<^7h%p|2;pT&>j@=Q)nPEVh&dymJ!X)%yj-`HrpGFmAoCkJVc~q;P!)kw`c$^@Bf9-uw6~FKImtFHrq@=-&%Ero} zd2!={uTE}sbvYx=S+UgXfp5J|-jM=+`aY4fv$N%BMS6ej%SWuNtXh@M$?@?WMds>u z`{UoeE>R8+4w93T&$dQqI{JX?q^8n_HS6c9K7IOB@s4-f?9kAVc8S#+eCz!!^XJc> zo0^(pdr^ip2L%OzHz5)6Z{B<_AGv|$iJfu~Cc#WwU(c?osT|3mP+D8~n%MSxrnbf`Yn`mu{Xv`@MXW5N`Kb%lP;Vv7;_ux5v)LA3Oxb6D)`=+2O9`G#R7 zrIoiY53m!9-W{Ktdjz(Hjcv)tPv&uShd~2#e^>&tJ($(3PSn};az1086)d6ejS5GWhY$Tl64!QJiTy%s{$A zDyr%-9_E;}E}fZ~Ifso)#BL;;?D-y#!lM75_=1Aqwpowk!)>rpFyW5w?pwa~+HPoq zXlV)-9b{#tTfIU>MTNy!6~A#O^_wT-fBwj?G04cYL0FNF<_XzTm6y+ZRrhXl)0QS^ zAYSObr>7^6)^)6!2D#i&xMR}W4{468d^2>UlFyyoprcB`O8F*Y_QywuE3Yl=?YHJS5|6=sZ!@WNyXatHp%->HW{-}J*om{4hk`rjZ9^mq zUA8SGB_$Cb^7C!#?!SB7hY65RHWZdn{tf;V4L^U<(9p_@<>rP9 zdQ=q^6_xQne!M+e>C*6-%*MfC){2XQrP1WUEgx6|2sw=EMc;C5&S0h8ymv1#?4h=Z zsA#iZo|+dLjfUOyMofr`;bKl5x0{}TijR+fy)n}QD=ANreoUOMrD|bfGFWUm=G<2I z&SImvmLbCN5$+c06y z4#$%X&y0)gGCA7S7K^w3eiRpIjE{i5B<8*9=}Z$S_Cx2juHhM3UX&X%eTdJXfVdJt z2ETwnRc_GVEc)YR_C>5G3Ud05Ldo(ELYjU`U&WkgJV>$LA_bkiU6J4YJzd}8>SGL^ z!W>URP^GBXG)JQuy4=Ws7o%m!fB~VQZ^Oq@BOlgJPze0Ul^tDCtKX9w1z(lewQJik zit7CesiMDq$6AG~`Sn7apoh?P2YG_OpjWK69@#G64Q{G}3}R+X^2q zSnq+^X=rMy7Z`n?-H48kerz$Us;s<4Zd?&NH)nM5;>Bz4b&ZU;;M$9eixHFcI%{B? z>AG*8tTsQaW_SGzaEa`Q@G`~8H7T+~GaAZo3m7;p#JJtPhvaKx zBfN=d6$p@P)-w6WxGN>_p6F*HmOqdx;W-444>rQt3|ZOO#vZ)iE`qPe$H(D=D%aih zTJI|m1eTYV@87>~$EPVNxe#etW!#Q?CeA4lMb^CrCz9Pcx&F?R!f#eiskNdjPKN2; zOvr%!Hk-xg!INbh&IMF>)Z9pXlXS_ez8X{3yWd{qE9Yood^k|7JK@$uIT-=LGY;$v7rc>3M`vdUMUaT(qwx`;%$g=T zI<>PKS>L{8Ym~}2lwZYa`3+lmjf_Vz_kuSbW*I#36!$Gs6np9#8d8}@TF3`Q_AF)b8JC%r|Ts9v;So(|ki22swI&VZ~ zXZYMYVdd)TDjh4p|N4(G;@3pod&`kBeLcMbXEX{nEQZ&?;&2ZQ_Bv4MQtaz{g_4?y z$&W`aU2$(`2bYxV5hv%?Pd^ejKmc7Seu;_qD5>ESR8J-%-fHG|xbJPI!3w91N|$Y_ zd-nhWnHm|<1&R^jifAsgVX+H(VP7TYvU(X}nQgw0@=H?RA*)I(e+_<5m ztDBgfe&_b>+ax5BVPT>;fD4*KnRN39mWGNc_?_7~>T1DIT3Y-X^@vGGWTJV{f9icX z{I!fF6?JuW(Hb{AJUs5*yNCD{{6OK)S$ z)X>tF_1+Kz0$<#cqT2@^TA?CZbYe{@o>n~bjOpGzp%Gf8th-3r`s*3T^vS8Ikzc<)3YS79sxqdqCS?cm zj9ZsNVx>g(4-UTb_HKz49IL6hd-v{mqPfoL)3h)4$fMI-8odyeNy>W}{qku&$5#|` zq-&ot&kROLA#l(*~Dr zb`ExJP3ObzI6*Q*?quqB8f`4BrG~VAY^O-$V*5_fH1hV(C4ofib(AuWK@+^Q`-YH zz@%QZv%7m8vA%%`2J9RhzP`Q?MB5@nwIOIic!R$Q-^B{Jp%xYx@Ns^ACX>7%EGjxy zW+xdh`#YMq815d76^Sn-1lje6gyz7&KzL;2@oF6&lo=}78XtXpF5}>&SqvkQ$eo>? zygXKN|Axu6ZZ=`8aW>&hk&p|2vu~Qx^YZX2(ZIUd~IYH{Y3@DB{OsHSYQOvoyq9e+ogZjX6GY%ju>N_@cA7 zm;BMon%*q+QVnMG5-d~d^GFPcYK`X2+@Al+X4ndzM3G5p8L(az`AozXzD8>x%;*|4g0@2l6T zpViFHPb%?e-`A#C6CE$5oh@Zt79}|aM_2;t6zQnfJIjHdf?jGQMQR*o-kk5Z$@xE# zJhrI!A?R@fzy3A5vCyxirbhg}&dHxN;_a_rVo)ysY&|{y_)S@bo_jPjGj$hb(-q5e zR(1^OBNG}3zd)=-&nmVIO;ICd@=ib+`u(Ojsw$Ol@<8bRF_hDh31dpB7+J+dCjS zjhEwia4V;YTJKMvaG`?!^5x6Vrc($vuAta_ISh}{)vT&O z-+5EYG_gq1^>z<2V_36cOGF_gJnlwG;axd@HeQzNRV|YE@UDCXqsb_zz@A}2_{e1#Z|A5Nf5u<8mx3r@zdS5%M?ylf@aGSL?4f2^ z_m3aQwpsNTFEmT7z46!KFC|NcRk=|Zw8d1K^kjH?VhO}rnwwX89J_~06*+Cp_`Cw{ zL$~2GdTWcBnK>Ihdb-Q5?@Y$}CM&N{7{*4a+qrTCeaGF_*8QfdVR{hF>tJnd{SJ>p z%SP4K*4EK+2hg5^ynMeIrk+XPdi(Y*lqQnYU%>wkb|(FS5x9p;Q_Q$8849f42&DI| zr6I-W1PSm)sMU0Te&Pl+AuWBar$0j}^PhkI0W*QRcz=84Cc=?#6qajaV*@IjVxx`( zSj|c@g=ClQnri}9T%=&OU8ype>R<+k zhlf`#Uj{(+V_L^S^{)$g(svJ8qyUd6uT!yvD32$3cO9WMQ>|fdySwn^?S;cxJNDvC zNj%o@Pb~(pV<_Ef_rp&o2S5gfcYq%msHuPa{3)WKz{beP2)hgwF@}B#V^Rme0o;P1 z^X6Py8Xe+;pPyf3BuP*sJ11uhj~xm!a3)D~y-s~Y!xit^2MQ@T-nHNdV#%GwbzoUN z*_ymO(aUplT()!Vl3~m}Yez;#Mz;tF$I2aY3JMe%Z%0N(-bA>%xqo24-cMtE%=N>~37e#XWoWtV#bjVQp<~<}ih1(n4@fbk9hs z&1`3~1UYM0=s@B7n`D8OBKV3w`h=!IX~`!a{@`tm?FA?1|+21)Tx%f6mYO^$Da z4lPw#3aQd(-@Jrtb&CQc0bmW=OYXt%A3ucouiRr}Q-JG`cmxLrrgrCeO*SYrE72?61_vO=#}5b&rVf!fJUB?Z#!zo$Y}`0) zjVk$5uJT`iL}g|4`-uM$lk@|v2xN|vqhnG^O7FDw>2?Xoa47MkwASN{+Bs;-+?w@Y zOEybP>#twp{~5W?U@5G2jx(|nm=pjJM@RcBPBgV@peNhY>-Y$S0z;AkLbMUh^=KC!qcg#%$ZSR(nd_uI=ZhkJHVoInN#4CY)OB*C(^wUsIz zO@+KgKwv&x5@;eNCicPK{~-gzI_{iI!-m0xl z0KWi20?JNg07S;+!NTUAo}RwGVj$r;a9bwVb5Tl?-kEMh#wB~ozIj=i2ZI;P{_1AHN6WI z{M9~g%!!^Pwx?~AS1wglF72`2aV*9;Jv)2KUXJslJLoam(+_IOYcpj|{VC1~(ep3z zh@e&EKmAFZQ!P1Z`|ptoCpJOB>fT3CP>PB+_y?S(XIJ(#=O=7ov9a1=)<2=}6-2ON zaU^ya^%Q0*X81>)kU>w_+C7#0lai8FSFJcB`R!1OSFZRvuN-Shyz%&P?xp~*h5f9A z_JyOP@uGrpLl1_P&wFSAW>;%SF&SnuVl5n9mft7;Fg3S-)nk33p+V~PJ&jT%Sw0?h za_6h$CK=8EcmdK@h^7M6ef8?qY+LL$8r{;|Od{xxsj#34pvtJ6H9PwJ!3VzMKNb?- z7yhtnGNlxLRQB|h+b()re6O${m)9od44&YN3AbPdB}$Tq1dYwD$Lt@{-(0nb>nJel zs0Ad^Jl%`0prw_qNPqLj4FR>&-jooN5+33g5G6W5dM2%Y zG=Qesm29!++Wo(a?KzVXO2E9LxU(}G>oL<3xxI&8Xm4+?K0b0eI@qnMs)Be0$p9)r zX=!P2@*&`5fozG6iW(KDOe=5|m$ELEpYD)$DAXol_I--;fbM}y=nEe-_x5U@ymLc%agp?9RvhHA=aXqnBq zBGH6H8Gp!>{^cSivY}&+`cJwp>-uzgc7?5Z9pQoveN1G47MI})TZoTiL04r&aBRR) zO0U^O{yKfNq!w=+4eHKg-?EdP**5V&vScUM&Ni!vrXh*q7;k` z5Q*`4TF9r-`;4r}yu#cxo`!M?Y_@Fe*N6%|!CFC&I$?K_aQtHK!OX&+Jm(7boo?ei z4h!1KvNcB2xcrg}?>~M#1?{n3gPG(40s?j#6M!IW=Gx;&Afc<~zQxZ2aQ2yu_XYyM z0XyJAz{Ssjk*e`L(-WPYSx=1wV|=(V{nNF`>%-%k(Q&wTh)&uU(fi>!l9wp6yfqLw z@5Kq{Uy~=jD!X_f$aKx7Os1iIsn6Zd&B&CpM)=fp+MY7)bM;nE#m}s)R0Glk(`b$0 zSOC!c>Ep*cg6^TJJo{-HwI(470Eh4O=Unk_$r5azcj zr}W()PztB-jh%V&tV&aT;OiC6Sn(bAE`6!Zzbn5(+RffK$uB{Ei`*Xqb=g8+&O-== z_^jagmX<4OZJl~7Gk68KBm0XxZUgA415QNCFya}R=%S_NKhrvU9WJc*$do1Q8#B); z^2f1aM{{~O&ep`X;Ui$TUnTrS=}+=iBzq=>%IvMJd7RdhB$5;4a$3^7-dw|`aoviY z)gFHSpoEF((Nr#& zVUj}JONAecIPA&Y55B&clKrA$C#4@0aWwD{;R^s&|KqoQiJ=Z9r+*L2H9;1A`v0CY z=}(nQ^lk^^eyXT3VAWK=bJX2eMEUODpQgR=Qsl?BEGuzB=4S=A=2ahu6Kz;|$?U%) zx)8@~F~!bg>z(pB7buew9~^I!_&4Lx9vZz<>K-$q6tns{H>EBQ6bNvr)k z?Nt`ptINr^`jJ{&s!o}sE=L=~S0dY+<6Ukp6c4?VB(lv2JW>-kG?s7hi@x{weBIU9 z;R~<6wUq8;nHCG?FwEm3QZsQTMY4I=g4?XeC%U-WS+QzGQoeQqAmLG6#InNEp@WDda`vD{fT zgSjf_m@zpyxBIwuw_JoG4%X36XjvpqUB5-Chm8;t103`mz=p!nU1_RdzBQ)JyE(iY zAYvGNbI?=ypto#TYyXSPeo<17V*;njy{+ZU7o$|qN>NjFX6D&HAz`759g;3oM@fi_ zJ=9|}j(#@CR#~5NcFR+Hna1Gubp*|dBLXM5eJJW$E# zC3C9LH~zF;`}uEI3adrA=Qw14>1;!JC?8$uS!oSf7i_Ori8+Pw#d9vALg$|Qy_MH* zF}yl&rkWs2UV%0l^ZVV&IxQ5La_iauYu>-rMT&|E)xV7!nWa74-L7ABf!*}!fg^oyaezzA%*ZQ6AC;G{DN!3&_ zF{!%HC(8@?Sod^&qQb;l!}eo^+{RyF3sxLwtJ$yZb#m?d>7ZE}8{ZEcADhP<9CQuC zMJlMC^}qh8s4U-b-IUAi`OaYK*ei|y*T*Akn>ye z-nR;P`H9(8j7$nX=u+k^+ae9A)GD8!u}Xg=c}`l*;!@!mldD=&O_wOC_?bBr z5)0!~$^tt@(!_BlUK1e$sGOYYZ8X*9jq-@F2Y*{ApUsGo@9-*k%-}B(qj!tG>9~0P z{;VJ3Fw6Z)$`jug`fVJaRO{wnWZ2w^hv=Urq9l|C_hPj{=c0@)_Ydb#}}u7{swa@Vi%R%{1_ z(X^rG7f2Ce>zO);5Ax5b^KKw;3a?)DlE$Hw2th54N?kBRd|)q6(n!~7Hx_?Uj}nnc zwqqcWgFgQDQpMp%`4^2lF)1Ti=S7!KOyczpaaqESYl9g-zMkF)P6_b z9PBbiHtfp0tE+l+upsd>cR$ZMSz=2hFhW6x{^fSTZG6Nh+kWINGrsLVGaG$%(MN2u zeVnd=0;2Q`yC#!D@z?f$oV(*Coq21+y{S3fBcpR;iZEuz-SIs~mmZ6AVHfWq9j~M0 zTdxn>4hU%>|Nf{)a|OF~ycdsL-{HR{`wttry58EVd+A{tZ8NjSq)t*jb(3`hee6iR z9*QvJaedm0i}|;UQkdvDidegcSzC+pRe6tIjBcpZR}L+h-!W{~XThPIbop9z+k_^G z(89k>tYxdBzF^%bHBvoEtcm{UXUix2TAgkI^Ye6?-@M&N)O>NBzRvvx&a2#U(Oj=< zo0~J;c?-4N7uTYyY>Agvk`{BeMvfaZmsGZB(7ZnkGvkt?24}qR*VQ#pIfn9;gA0c@ z`ioxYo4h?Cp=ppm>g$0-=qA=~c;x9!NJwaip(1(Ic{~zM-LNc+h8)D zr%1~~-Pyep=gtL?seE6GiYk&*p>r?RmM zO=>b4-b1N0{Nc#G?bDI{VeO%NHg{e@K{sfmy1Lkyn3%Y^oxZ=lKummfU4FEz|NjMB zz0vK-pds+jYVK}l=zIrTmfs-r+6zTfD20eJAq-8tYS0gMCBZSec+>!SlF z=r|f0isEoPuEqh&?B8(Hw|=2F>mIU#42aWMV0z_8pqo@yQi6}TeB}y|sK9L7+1Ww) z4{U1MmEl5Dm1HSsye|&qt7NGW;N#ao7dtBpnsE<<8aXXTHCUu*g1C8jn6)Z)DpyX~ z0<7+DueQ;SE42*+w6n@&+AVsI>JIye7Kr+YEun0;un>T|1M+xkYD(5GORW&DywH*O zUYM%X<5&P{#L1=6N?t)h4``r5%eV}>xI-*TKA%1@GBZm{N`lbR<6sRs@KnesZW~Nj zGlXhoxHKp_n%{ND%I?bhy0x`6ZeYgBrh$g#cizOo#TEXS^N5>Z|2QJ0MBkJA!*R&l zUg$9{ti^AS(#5&;zWW!h?6oZzS*V1O1C8M7S|Ljpb)pzt>`L`lq<7=}1~LF3g%i8x zVX>imUuiopPsRpXgBLGe$i(nL=K&VfAb$WEpzU#Jx4k?PLZ#1oC$eQ`W0!yg7-IN? zT@>gAKq|8W%HnU*SI`Ewose;P` zMGgHHx+sCr($ZaE1&()TV}pZl@k9$4ND<6xRlAQgH%l_!hL$gI@EHu(3yFE{&2qFV zfk%EWC4~?YYKAc6+kMjY18qRlhbpu-9Z7QL0m}7%KtO0fj+oXlDETacK>x1umXHPksNsc(Ocn zVM8R)_MbvSLp7LFKliL?y#k@n!K#ps&L3!cz}mQs*StZAI9OS=_w@LE{;XUK^epf@ zj*gD96wrXt*VSdy`xVgH*|}Z*B!#0O*n=36+#+nYWN>&T3S(IVJ=?Yn+V*iSCi$_5%F=gm^F$Qx`^!+_~lE&s8y2u zr^?Dhplxs{pFMj9EwUtH=uYlKxtyj*4_&3(zV&*n;vD7S&`z9g4r`0xV4$a`7Zf}O z1so7Dz&J1V=PF`(eebVwD-R9r1rDhD-!|QoN>c~}IVjjN5=BdV)CUc4A6AEoSNyI> zQ34@zgtEZDmOpRO|5x^g`GEcQ|HVoEFI46K^05iM5}u2T3$Y)_%abhT2l8qCM9Q5u z3@ZJVw6v<6(I)EZ>Y$4%*ZqJCEk_g7VN?M9VE;$#e{ZeE zFfCn?ABR#|SsApqNuQJD=b=3T3OEv-IJrcTLl6%$sANk?O1kW%056d^3|uWeJ*quk2z11KaCCK% z@HwtRJFSNsdjH@^1tvWxkPKpkf5pXp9UZ&S4u?o7RBy!yLqPJ4DeCI!O?jR<2ehJfRKh*p8d3$#$+5ArORy>&(_oTvhSwYOUhm%Ii6A~JwhCI)(`m(QQ&=dXmG zVqd^0NU4?<7ajRxR2j93Euwj1!3k|wMm6u^gJSTTc6C+Rn^QB1$fHq28-c6{WVGOm zmnflkwS&sc>DC7Q5=K`EI&p~4{MJ*yKph({H3JKin2?a>33me-q^G}Ml_m%caR(&j ztl^AQR60LCT%VtxClG}s@(FSpbg1l%N%U>ZOi z56>UecyG>KyhhAU$HKA(_Y6;aFcWDB{mV;~lA(+r{r#)$mm-9z9?;Rn(R@L^d$+YR z267hKd-o=x-IGPh4_q7cMh^}SASA#g=ipY50l$Asfs_?2Qs2Np!2O^E(^0$%^B0(- zJ(wdt<09o$W=_>$u5JU!0HL2^Zf4fK@FiRCIw>6Fed$VOd#O35h1S%My)cFgK9KOGsRX_MhO9YL#ngU|?WM$_!|= z(z)+S(Xc^hkAowmUWc2TyC*;k@*XUXXlfT=8R%s>&v)KOh}qh10%6Z$@S6xi`|JjM zl}U2iHi>)CWwdzysIINe667kEy%YWj``6aiLia3COxO+N#1FM9?jpf9D=R7v)~B1P z0_TA22mLV(656`JenND~Yy)|dLOmt;Z<_ZbBtB=P8)P~#1`z3_(`u)gQh~vto-%w^ zCj)s_R@QSek~??ORmK!SBNWE?g4J@A&%wdLZZcc5yf<4jGBEJ_i4q^9W~4wpQBY8T zYk*kza1B~8kg!<87hzj<9uXn&LnJ`Zk)cQra>dz}$i7k=L(m67s0ZAO>MVx_?b{1i zVg%eWkoeHQo}C2|)%_bE_qLWY6BC7SSROxiu(5G*nZ)G)TZc|0 zH8r)Yjd-{I1rD?U6?9z*XdT3oWqJtQL3Z{s#5M>X^hKb|00LSmS-u{M zBo~)$5FD0mLi@H#uklM<++A$1>!hSoex?={(jfsRWdE_>rq;(7hqWf`yf8WQT+hP)_ZvO#)2G z++W&**ip5=T;AQSh!Asj=0U3sLtKD?mJTC!At522=vF<}Ovx4WLLV8AEsWZLhk&*i z<>Ckh4lFO|y&>H}n^oyC{@-ZvM4@*ogB)}lpcM%r2E#Q6DK|_-(9))Yd_fA7@+Oc# z@}Jxd5TnMloYjzsiN+uZPxrhL@eoF21P?d2t{6dn6@YMZhs}V9ghX9UZMi>p60|rl zUlLL)Ow|GV26u10hH0&pL*!GtaKz^^lt!FJ1qHiN@N5l z2ya2G17a8hRA+|NLulPSdemN5caNPNGnYZIG68-JWzSHdsRKweP}rxHrcsj-t#s7t z`nt&?yMWWjj~@Z_18Vk*7VC*{biVqOD)2-7A5cxj*}s1M`UK||zx%qrZk;S29uP3T zxHxPT4s$^q8nY)$>zB~j@^1$KD~<5~Ds+(V7H)&?Av^IB1Q7Jl z67Kak9>JbI+U4o2I4{#nclO*l z$Xl91HED8*^r6pgKh!caHXc}Y`b(0qGd)j6J;fO)Fb+b*V;XiK^n%(>p!Ne*pjf=D zo}nSgbb}ivA+l>$yH}F$gYWfIvOA<5~rG9>So4Lup;=3P1vE2s8}fd5|rT_-t(XFgIWepM$!XK&9mT zg$r)`OT|zST)TFy(ituB{P}$(E;*kna~Mo;<*FV)RDhmtMumNbjiI3-0|TUnJ&AbP z?#bA=(u^HKN+o{UU;r+laE=TQ&(bVc9@(+CN){X#s!LbQfJ*s_Hv%>kD%gyn{Jgw_ z!$Vl0XH;^kszg0IQ;j!4G5+RBTx#lL2yhu|;4ug|Fe^foRJJU_@j~iu;pn?dnnR8-ThuKI;Ac z%EE!Sw6Nf^_U9SmgA~oeNclGCP5}Q23j=Z+I(b%>l`UEvta17aFS zxC&SdXzdPR-Un)M6l%EC21aMxp%tA>d5uD#0t!8_G-#9ik#c{*w_Y88${EQ7+4ROG zbYzr#U7>cV^)y%pOtwl$NqzG1*=y%La*{oMmf;FyEXaRAG#e^L4Iya<>JAtH6wPo- z%h(S}2eQNkAS*1aB#3hS{FI9K_x50yC6hY=2%3*p>;e)-1^^g$S1aI*Aag-me`*RR(AlLE>HM=34krlf{(J4Qw+>Kh&Nws0wOe^EOQ{ia)-kc6t+!fb48n}e-wk~0ntPMnE(NDRZpi|>Jx#7Dq@9^hIBaCc(seJJEZ znbe^w#8i(hk;S?V*D@+$*MaN2PniUvUp{?P^LXTMlr@R~&(Q_Nh(z)_ut%VWPHH*> z0S;m;+1=Z|fMuSNDLlJ~_#j3tAtRG>%S=!2he3YNce~)2nC$fQMuU7PfB{Qn9oqpo zT3j?!S04g3C#H-cB7%Ar2D?EIH9a+jsXLdlL2i*ril{6;dqRLI&h*?@7%5zspO?F+ z!CXA5eXUa?{g|qUpO*BRsJ3>j$#Knlpjt1EQqy{os5M+YW0w(~hY0#H185IHa?;Vd0xa|UB zV`GDYbaiy(HJv#$cq=ZVwUf$bK^`Ss*&y12r<5fV{PCkW47%?zqH2bRqZ%gp-4DJx zr-6(ak3s;{cpMx63QU!idttj9KHb?^pO&<-+1PeT!=VJEtT>}YlMXT{C|j$jJ_^5m z|Ceu%C<@Pu_fMOelZ~^&P13pKip4A_KY$r!++V4W)zgmFG zrj{1XA~O&dP*CbYv;$535OBo4K0Yw-Fp#4yh#B()i6E@fH;ZooWuZ8N>PI?;Zx<+7 zusO&^{}VU{HVzyqEF|PaDA=IKnyv`+UI_4Siu5pC1d{`@8_Cc9`-B6;n9JT&OiWqw zdRP0dQ6!YjBBfJ7VG>tRunCW&USyU&5udRvlQJ_q3qz49F!zo4uvb~%&FBxf^VY3f zbQoR=2~qbt0`$mm1J4pWfC-$(jOvpLxbA>b>+eJ>R79BaVS|9*WeYR=1wkC}y|}n| zw?#=0{}yP^RZFa1X=#nZun(jW@>{nyW45oKgtKvl_FI|c8q5wrDge9bB}P41?co7q z4?t4DMIn|C!ju}l0n`SN#m!+uAyR{0S`z2KX&C*OfQkv{bzqKd^Z)Q6jXgk-UY|Am zuV5T-4}|wbPG$Vd-oT-NL>Y!2AbbMaRscu})(?>%UYL-cZVY4tx+n~!j}SKD09pr3 zzHd(?1lCL@lJmK?wjd?t8@1NB^mJ~AWsQp$FABsSkAFXB_aCd=F!=(?OjXs*6-456KQ^W+H*?AmYm{e`nnU%q@< zKMqU<)OD~!y^W3O5Xm6f9=4PGweogkhjbLz#PoDezp?9W;M7RT$UxfF+yBw^_P;|L z#2S$3%*@QdUV(gEf#L7g|5Wx#KfiAM-}_~^X8%qf!`8ZT0S!4i1|amuF?z&djKdyY zvw=BQ1yv``wsaZh)n14=^UdlcvKn#yFB2T6+C}(l|7Ea)V?IL^GAf3lV0YO^x)u?R zJ^`Ws0ASE}3mzb0gOzYhRamwB`?OC&{vT)@#?b(cuLv<}RrGgut_wK>a3X~H3{teZ0$;Z(R1K=oGTD`bUGg8XyjQTVyt%^YW!ET%iW6qXcv8 z00=<_R8;Vx62+)9bnz(MCu9Tv0`t+y9}q2^Wl|`|-<&L$r$Hhxp>wunkeM@;vp~!I z^srXN1c>^WehJC{oKexJp0@RpRtCheFe70n@Q|wzd_Ol`!^Ni%bcv^muh`~)c%EM#f0yd=TU;L8b3UF;p5yBu68t|mbA3+q|D5>f z6Hk@JT!|+geYT)JsXFQPj=*P6?VZQE<~P4o(kr2l;ME8@m0N0+tLQ#$3Rb-jbrWB?Uh9CMS?g;^2zm}K z2N}OT?rEQfjUQukwBlzxUns|j{SxSIV3;9dzmSlSAX*uFo@fXHklZ>PO50%*oDzPxY!1yYourHs~YUEQ(`YmP?`9Z8$K9R)u|u0aZ0@n{R!d?R;lb zQ`4oJG^$y>+J`6=_iF8&jpFLVEC6Rf9AISKG8`t`hdw!0yDgUPH~mB)Ey4kc>k*54 zYvs26|Ge6(>{xcGgimbR`1>r1VU!ZI+wqBndDhcSKnAviv(5fyYa@lt^EldwRVMh1 z3hL~*I1%O{|0kLo=HQ~GQ=6yvMpoQY3Ej6x9Gvkm9jXEOJjUY*Jdakk)jfzkphy2~22|xALx32p-PM2q$Hr zK4GHM*NKhYW#C&t&|m1*+n=k8>Eb;ebIpgDVEr-pJ}@}g7TQ`M3}47DmtLtMa~NJ5 zG|d71IfPzwU^pUD=Fu1tUXO}4aO?|Eb~x801T`(mE7<|3Zy4)lZ*IQi`>@IpxLM1A zyk~;w?-wb)!J9b1sbQz9_E4GX{A(}~Fb1tAfHWQb{X7012SRv>QB#K=Qs& z*r&C>Wa&{369j{UYSm+y3B#KmfFo4CsjeL#jU7YCW+TE~%bDvQ-6z;yE?*(WeFtR} z9KgGNCWg0Y0KEm(ibkP{Qu#`u`wB#cmf4LF_x&ZPDotn~CdI{#L!kp>i3@CPd~7h| z1HHgdL;tOy&MmL@rd&69+wEZ+|D%MA%uLIQH4&6)Nr0pHh0-+^Ekq!VIY`ypqKXU8rfbwp*DU8=FgM((eKYjHoe)Jbp@h}z6+q*dMN}0}wBjVHchcKB5 zj2s@{swbTf3}QvI8A=~S&O!tL24gc52E)=JPfy>3>5fuhJz*RpRKJa9fibeh9$7p^ zy}mzoTm|W`w6qk0S@mk|70lZLa#aD8mAdWQQ>g(J0I%(UB{AcSgt?@x4pEBwmGGh! z6;U4JsqN}x{_8BbUCSs=ONJeO0ua?rXu^2OA&_<*@8; z-xe#Z%i&y51fGA|P5~oo82BgnIaT)&5$?73LLPF?;&ivxcU|EvBXem3L6PLRR8;u` z!|Pl}%MBYzK(5`veb>|^aTsH~?{1eg0?iAr5sP9~MrWt;6+4(12hO66V(-yU%N6^= z-z9;Nla-Wu))!ek=@rM@EK3s6PLy9E=Brho{H-$HDzW z^RHhYa@4@N{oqY8luN>y4~LdG|Dc`ky!+T^yj?k3WFFZt`B4xig3Wh-7T)mi{g?&= zOHkM|wb69b-e+UmfKkz2_ACg*sP1&og#2!8JsS7IQ|s-pY<3uR!o1%=v|>~4G$6zw z)h0SW0{ahhKyV*cTnDvR9@;kC7x_#&Z(Rzda0*=$Kuy3uV@0je4x^<&`c{tt7&`uS z&%ZFWYAGsViZ{MM zS`E7%B@8QG<+hKAZ--mj&D1{3=$VSMhspI{c^XhZqD2PXa=@#hGQp5I!qC|PF6$L7 zAwL+b*5`iP@0kZzkfwkJk*l+?Jkar#_M_q@a!groL_mv z{rzcea%B_mNG!^iIQf-Kl$4Y*Ie4>3mGn=rp6AVbs5MyOY^};YNDHyh{q!c(>L&{u z=URr_gCyb*B|Ur3pU=9UK&2q6Jf1DG1qvS!-taCJbOB?31oRV$pUAscKpM}Yo%hiT zVKFgBP!`ggO^83DBU`(|AXiYgcBjKx_w&V#Hz_l0dBco-x1i+3SbP z4%O;qw#LxqgJF`vlyJz*7eRjkcP2PCVKwZ!(XvLSHx5r$u{#q9wNDhtm@a#3LA1{1 zlhj^g2N?LiE*IcoHhbr?OH1A&B<&3ddv2i2z&s6bQ#_?}Fh0&{G5j?u>Y!Z+FH60+ zb>6m!FY+#UB5>B+IzMn=C>a1$n3gll_a&#K94%-cJ0I=N!lWEb$Q{SuTwyMG z3A77mf!+8^)!L7bm=-vM$X=ibT*~iV ziic$h;*g+C1J>7lvqKbumzJf&6fNx^+WQ?)vTg!G(_^)h7nQrEqy#UDVuSJ0<%LFg z8&z4($pE>h)@z;L=(#(9Ccx+JCtxhA3;xxUgiQ%4Vpp$x3on5J$(UEzWb!#W3|wOna9<4SoOp#(W%KrvBCB(7|<|^qWo(s z*BCU$r)=f3t=6Hxx2j;M5GtSxB+2b{TkIh|I zetR^KOoDrJiTw5_lW%Zo1<}VM{AJ`j0o2A2I3U|*z#J|;{oW+S@vjZn$9CUBKx6@^ zjfR(ZADD1}Aua$i^j|R3(anWtI>3M(+Me+5-eF0bjg-_TFTC-GmnG!%l>-olmrA5| zIn5`BeI|JbNFMy33fen-4kjaLYS{oZ*0B53Q4lgnQdbhl|PH}usMMoWT9$6Tq1CmpQx#?&KxLvJ>d)vGDolIgz!T&i>NB%=yr;FWzf!} zRZzOk*lYXDq&5J+Z$(NAy2IZnSj38ri;u4WbIFM|-V>{$j`GQ&b_h_U{Kze?HSZ)mHcNB$Rg8QemIZ2htXueMaur$UO)SR?Ef`ZES5XRQvjX zU8HTsQi5^=01U1up1_z-e(OG!PRN-78t;Y&4*d%V)JcCCD6c3xi6;VXUk_+ly=|DT>WuNn?%yy?!aF6BruJOM~)=de17U ze}v`|NrGtCBIDwu{WJRE-oZ0dmMf47(C$&5-85%vPPn%ff# zSAivjUn9?}Ff5n9id|vBoEcf(`(C<8McO{WxFa z!|?`eWE-!yczrr8v;DYYkCE3j+8;aI8O%}t8NEm^)hFsRPWBvU6GHfmuzv9=HKz#J z{NWj&vvqZS)@;#_Fn}gDkLb6w0*5FM!9rL1$#d#R^{*YYdO6zJU6&8Weo;%pW}GfXS*< zON&*`+a0&*IJGR7ayvH5o~L?P1P^mx)Q3q8yH*g|fVLvat+fm~7epaR0OkffK2Lz@ zKXJ4nQ521OEsCJa!|>fTo`Y^z0)Th6LPy?HnE#fd-D}0bt0o0nZ_9=G5sRcrk z1WhsoYhe9Y#ryBS#S$c*5%ecm=m>~QgQ^>OVr1;zcZ2q;#1$io1(gU>+vwOB#^4po zS_c+ll7vC6ciOcz2_nh#Bst6s<#W5GC*NUUz=-|DSqkW9|IAL{9(|w%O+6_7DMc^a zOuKEpflJNV8VpyO8RhexCS97?O0gd9hG>~8Zyh%%|`q$Sz ziQmh@46ine3s)^C4}Pyk=au{XO9*zL#Sc$5ke+H!fnpL<=@1JIDqb8PMKduu{ZIPK zL*uaZ3*p2><-3PyPI%P#1O(&^qAPB{|uRJXS zBcqX1Be!b$Az@*A^w+a*85kI#P`N6>f~xKagM-nBXLAts4B{cFUR%h+ER2qHjeB?- zDLu^fI9ps=W>#On;otT{VlV4@Mgvjt)RI1VC<~zDX>MsT$~UgT{q~W&_~H*>qB1nl z1P%tw0?$u+diu^bY$%A4B_>8-EX1e8yxb$eL{ATp)g3}8kWvQE9UdEfP#=Bv$9Eku zdJm(cElTvYv=X3<>9tHUG%#2}6KsUK0&b!$yYkOmlbXz|BA{_>^0`1wI4_sZp})cN z>;Vu9am6xda~lqZ{kuwjG&!F!3Xe7k+ZP}cbc((XxClDYPfkrj&GDDxhuzOb&R$?qFbC|y;LLZ|41u(Ohb9DmZ^8`)1iTgT6 zSZa2qSR?V+-4EA_5Rz;?y4}~pL1?hBr#v^V!DfF06S!WHMaffbeSQ9>Ind7wfstHw z;f4odd|x^~6fiDb=ANz{>U>f`_9VSSFd^#AsOmyX&%AmZcu zQAs5Vv9174I~QACVW|~C&1xU3ak)qQ&BfurpR1B{@7Mpv4ibyo|8E2tZUN=#pvfFC zk-@U^H*J-~vMDhLWyNp7^$01f2zU^R#)7LbseEK`ea+3@?Qd)FdE~X*)PK(^iB!48 zL-zBnQu8K8b^7qdzi)saps;(tjUpGR)}kNxJ~m%etdLruDe zO~(EGcR~!lWNNRv|3HiYA77^5`r35jg1Zb*HWbc4FPFl?{^=7b1ppPN6YH$lFEURj zcK)*ZTRo4CK`ybCQ_B4ZN3963!O7{hhngrZ^&;;evC_W}Ox?9t$`u4JT7AcoO^@fz)_@T zA8(XidjK9+nne2sHlz&PliGdd?+;5PANP>W&wmnMES>LLT|MUI#Bb$hjBnbEZxYG> z`#lX`(_gSHdpzSYDfXf}QGx&Ydy_aEe+aREo_af5Cvuj@Qnasu>F>XJogYj2oBB#h zSnjnSuDa4sdCHe5oHck5 z@RyyP9UNq?hp2gHDM+i_6Xn0`>~|Gjv&7i7V{5JY!XkoYFkJ`;Oj+git9X8nMz|W} za!+daCEdU8^43ngZ&M0ub*p3;uo%cLi}Z5_JeB^rRtns9otL02QB9x6e6>f`)49JW zLGcLPw108-iWEU90`uYx0f`4N5S^|lJW^r9Vb8o~<=CGI`$Fci{QP!>hNJ7=n_HcrO2b$`FAr3HKoy7X|v(!baIk>N>Mibs|}YL0+8 z$7TG85vts__h3rfDMd^PM+TfbFpwc8&SmtzPQ8F13O#zE($=vGY_(o_P1|k}Ey1*_ z7bte{!RJ7X#S)gPUBQZoc|M9M?hgPRRs?l66=EX$>>gC;tgETX)r1ENh(Mb`Hu%TfTy6R~yHY~aH1-QU|9)<6Og2*t(8Wf? z#saOpQDY316fgZjW=asVcson=kH*GRrd=y+E?=fs!dn=SMqm-_S`;^ED7P-Osh&Q~ znf$CY*Qj@FJ~(-N!4sG~AURC^pmTyV5Pj;o`A272(%-wHx^bIS4>58hDQONk26tz3guwoHUE#&pT@Z9r8SnP66jXzP*^@=^( zoR#V%hGMAon>1$S7d9oeBI-s&fd;!KRR7Ss3}&%bS^)os+zP$FU5P%oayv!niD5JV z9*KF`*&TjPZebBbY}#e{koI;RsL@MeyU`dr`b{TLpK%+co2Bg- z^Tg7n_E=tB!)#h8XrQU7X=Idm?_P>^Tr#3#&7crO)I9K(;{ItsD_L2P4|a??=?O+d zK7#i}B=siiBCiI05?IcdCM_(k=;#xQLk<#j!4fP~deH=ZiF|25+DAF^F`fbNE!}Ro zkebMH1=p7?oP%7j$<-+xvl0fKe%oj084-K#V|uFJKqrX~wi4K`UZUqk<`uRL$pqEa zEBu0jphg6n7Jsk)O-3Ra#ssN{pW>Rsekp^!k)@#-4LHR20KPbqi8&UXfoOa)e%=sm z0`~Px>pq~-(!PI|QB-N#2z+Pcp4$EviV4LfmqM+k*`((NiI;zYA&66|;30<(rUk{`p7`8bZ({JLtR=s37x|qF zo?h+;kF|PJBkq0BdwvHPqkHl3HV0$HRI+n&SjDXFChBtw2-rY$joUGaZ(a3)B5>7-R6v4LKmuF0j@lr44H}L6xUg#3--Fv|!x+ zR@Y@r6PImmztuhEl%3!36a_Lndmm@w7}<{9sn+@@-Qv=$iJ89Sa-2nJKM;vJQllF7<>us+=n8`9UQc)!1Zh<8sgB~w$w~LU4UW*@ z2G1XpYCCjQHs}<{kmR;S%@^nLjt0h1DyFC_&}67MC`P7Y)o2goBIGP5=RQ}k3A0|b zxt<+^2?D(0(xyKY?DJIzZ&Yi4u2oSMQ#&N2KhN$&Nwh09P>+JW1=`v{4^4a^t>7R~ zh@LlmKh6mS)tUabx}D7IcT+bSPYPs*Lk=hckRrNQeu8;mHQSwo1~ruZOU(E$TDwfk z6VfOxsAcFkWZc0Y>E(2X&0xIyQhO%wPG&Ay%ft zyHtmlIy$vQTuvi4+i#ggMkTd`d{iSld|Py%(0$4Wt>h%07m9a00WnI^1&@r4O;Ix_ zc>p$!7SuB>>iwxnt2i?29)ydAFC^Q(_R3xV6VD->x^qCPZ#EjFm)~NKSg5(4mezts zBv;9|n`;z@Y578uc~Ac_xR^~7%t8K}smc8@moge|tVfHY*dUb0wmFvxvSi*uL1{F| z%SZesXOCnw%v@3FU=C<(X+iF_C2Gw1^K`BA&>wX+q??ORa%^OfXWYDZt?EtT)2ytu zDwscYG&Mii9@f$V#B9`oIt<6;G`FXcTG%rVa@1RFuP#yv2_LO<%2NYFq{>|k{K*Yu zMQLX&0WP=r*P5twjGQ`mZ=>h7?6)q>v;oW!9YI05LdgeZ8u}zTIj^T!ojvq}QuJxP zLrB)a5P(5kEF%&EO%#<&5DJCeOfo;Da?7uxr@I>&!31>y71{eUiHJ#rZDAGDS0d6s zK_IUX^_YdK`e*wY#Z>D)kYQ`+zZsaA#=d^dH7Lz3FPCzBbwsF|siccFq4OeWOV7Tb ztSo-c_7t}L_mtIszbUl6a^=d4!Zd5SBw=oD_*J1l)y>gP92+)?h;E)#mRhLW_*?js zr;X>v+i3Hx#Ikh0ddRV{i^BJqQt;x%g^TY2i7+S?=n6KhmMs0TD!nZ4J1j~GxCz?| zc4efH{=*|GsYh|~u}~rB(S>dyXg%}f5x}pC>Vm?;YNt=P^RRxHcGZi<&mb^6E=@9_ z1@-s$Z_o6OOzXHrrILzyPp%fL__O=7yRy>1U0G7KaVuV!V7p>J@C?J6npo^v*{kxU ze;d)4%4*xmf}kwJZK%A(&F!@OAZR1q6Rud@=*-#Wjn_%7R*dQ$Vk+9a1Jeh0@9@~P zlH}2?S08oZX3a~dhY=m#H4j*}`2vF38t1*|ux&m${oOY&GZinNy%d^UlVE#~KA_>E z0?FaandfC}gg60x2bilb+yE7PzXbDO3C@Bn^@Flw9#{tinee0i23Thk7oCu>+Nq&t z2vScq{VD`6=#x(0WjdDNyEIj$3X~dOMS=n$rr>7*QvI}VLK&NIh9={TuzfEX_8)C+ zMyf!R%POm6t@VXCNWdZVhbZ)-cLda;CHjU3dZ2_>QWuMF_S{dQ(sAK{4yH(SI15xi zVJRpqbOL~um4$fQGjfh!Z*MGjM3-17a{#SwsAcEZqqmF?Nu2z_q0xC)IgIJOv5y+t7I%%Hlm z=WgwuzPA;Vfs0sQLqa0sZW4*E1|7>xc6M9pHH2k%M+r=-MNlOlCz}majFL3A@@O-v z$f(zB7Zc(=#F@Q~rT0qrx%cc*%mI>`z5JK6>hmeLJUJdL!*!olPi176+vT|A%aXB~ zJDO_-$W9-l?d7DSZQM>9@shP%jFqYa#fgkTUARCxQtMgIv%8x}%4UL+L{U=Huf7eQJn`nQj>K32G_t`N5ox zCtWuwnTk35ARjZ2L7VAS`Kd7SSmN-VjTM*1TDbP@ysM|T_j=cjgO?b^BKE0ta7G>k z=_%AF!@(oKXiepxvOlG!=RG~S()K3)CjPACNLyO!X7092?7x*oZmcDKB>Q{b^dp>ne+1ZahM{g0#UJz zOZ%z6E!P_t^xt~0k2{C&t)!rJWDgVnqS;bw(|)1~-+ia6NT=J(-X(FKv+!VQo&evx zv(MKzF;hKC;&NGcGfxJRkv{WsOtyup2H6Lo?mM6N&XL-CVkPx@+l(@^8i+(a?|v_z zLvni2{a*zMJ(GZNW&Zq1&Tme7j{&L2N-aAgQeF&M{)&&k;_4;w9+b|8>-z$Ze3)L` z#-u7CP<_!{>-A{MZgI0>qiS=IKN4Xbc?Xowi|yWV#PgVoQkf;o+nV&l^i1AGMe#<` zq?c&xA_9=zn&0z=6+itz5wAV=P4CNZtqrr+@ zI4g@Fdv?_s)L5~*5$Hf8(1DkkM>~q)Aq-X&WISVT&fVY$G(kuJq6)t1@)rfU=SQr- z`CKu8EU|3URpE*scj~`hYqR3d%=qNz4kFEwoK%MI| z(p?ANw^NRN*69nT@~Yxk+?50V8sz^W4`ITxTP7e9lQ4dH4M%OHBxunFIVz@ZW29q< zzQUEfeCuqq`7X&v+a?5EtRwf=id+y(jnk-AaY;*cweTj9xHuNyX#Jh%AH|Hvio+41 zsv5?n+|W&4TS!@ZP*JccUobmQdq|?&u1G1a^2(vqXM^Om88`exw+svD1yb&EvR&Ok z8W;T+^Wu8A%oziLYqYsX;+V%8b21y6D@87)V}eZ%EIc6_o7lGNW0Kl-gQMwS-U%st zMYYMt!H4B8WPiW8C!I%3$%vYCO839tbwEqYBhgatFbz44x{i}Wu^DY97Rt`2wt}fK z4uQ3dEDdoicAVS&Um045+}^@)RlliD#CO}^eiBF9(7MLo4;6eyonC?FXD?%$)laL^ zK*w z2-Xj#R;QL2x&kq!T8)e5U#2ElFtKMJJjl4tDe5X6f{aa~in4K)T3q^i0p>xQjXwW6 z-g}lo$%I+9H!wqK)zCKdeu2C!>ES7wg=;%MVRQ={B0ksWTQ3U*YellMaNrWq1Hkd@ zT^&VaU#CLHd(Z9)a8K+}>+0^#dQq0k7a3)?M7A-Zw3ekl(E*VY>x=#NUKOCt-gCpKH8Tws z?5J=MkEl2^WyGn}F1-MgFVZ>1U>KJ^_1i1HQjp$hu`6KMUH$W}fW7TOr#RaLdv;oy z22Eu6Yxi(+-aj%$9nnlrqGNwmOngRC@R<%VpG`4oY5R+Mk%r@}sYdNZgYwHNP0#AZo%KiuuvM0%8tD|>>I7CztC zadxHsW(Ug#X4u9Va0#Q_ji|M>pg*fK^{tl2UEUqacHD-t_Q&Z5V-f*-qgVM}?RBt? z(;DV7isZWLrFN&4Gx+<3Gx8UI(B0MJydOlbWa58md^hRn5+P`LbP_MLpNEG~GT&Z+ z3iMKV!_Ajuq?df-Xb5>YF@B4jy?V8%W8#lmP4z>niZ0VO0kfq&r_jy!mTi)<57BvL zmQN$T6Dysi3B`s>Inv4{R?BF5uBAlr^|M&!SB@;g#@%Eju4Jkdw$RAMA1zjq&Cxb@ zzm7Uv$Krq{7IiMVGK>e(de;WtK8Z2<4U);#CI(QQ=tPGsxI8FiwxqHlt=KUf+H<y8Q-V*qNEiTn9y*hQgYw_WNn6BnUQ0d-QAbkH2ZrO)uC=F>Sc_ zdsea2P{6nDU&$4X&>Mil$$c^R_Ts0go~cy`%n2>z+FV-DID}@xyu9uhsKd|LV7mq8 z^!nA1VXMp~_$<|Xdkc~}45a0b@y zRX*?e`&4*Cii=RfiFf1e%gmxX6y^K#o;)w?rnzht^@r^8kso)m3XTmvWZ|4!Sp_so z%N(43WsVxzahYCzT%4O4snYi~TMu-c8)z6f$!KU- zT2WXSsdGHkSGnVqmR7X6L|E-Z2hu4stiFewvNDRRwJp0thl9<$ONG`j2O1n2S*G=wNCUpH=9;OQD{Z&KOx4QI~ZGW^haaH!q)CGMZ z_qH>aZEUtEpwF2;akPacu}4>@>!J0%jkpNnD(0v5$ay~(kPQsp63p9Wt$bBKm{+`P zHHl4V>$6ybC?S^ZT%C~;t8M2P~&#pFA}Mfb5bEIYxB*xhLjuw%kqi+ zH*4Pid3R{2(rZiheY3KuT~IfC=1POOW8h{Gm+}`0)%7uRnMI%!gw_^I7A}9pR{?X4 zi_?c&1_Gbx==#EM{)g&7V3^l&>KK_Y@1xG zaG^n>$}WGt3E@i|2RUfn@T5LCmk=aF2ocbG6Iu-|GH7Jzf)(|fn?PCFOT6Xx4|Ozt#^lmaPi9*(Igsd)|VBU7`SbZ&;uiZ$AOz zK0AjG@D3-6T`oyWO(g`=aJwgn%^}?mc8}_r{?fb}V_g8_rGvhE$XQMcLg(*{#x_xY z_|73JHkk~j?yfEZl7Upp8@fk(=(({(qH~bk@M*%iP|&N9I|gSNL)}?P=ukiuC^~oR zSz>2*^$m{h(_RKsPEh5g{Z~Yo;r{6OMYG{0-x=Anw@>h~SVZ2d>rl1voKtR136I-K z#Z@Hvbsh$c7y9-~5RiJtaw&Vh*+&=bUTGBGpn*atuY^?v_qUbUWr6|W7ZBJ3#W}bt zZsj?58T2GCxs*6*ua7Zs@87<$_HJoz^dXkL_Y><4#6G=xQ==Mc1i=0#E`);$}*czH~F!k1@xM0gg@l!9R$g5?I9BQ_}mlsxND#YWd z$QfZQ0>EY=5cs@NUg^CP-jKZ%c1+N3eq2@c>2e8OM6;`vmxDU}a44oXs5eeSv!^OR z6ceo9vH4%R(F?!40aJUHRb37U(v2SVkfRHBb|NlSMqb``q#+tHLrY+FCaDIFwSuAQ zb@BD(OU)%cC;0j4lgriQOm^>n9z{Q&q3+50Z3x=5tSl!MCaSl zY3BNz?>s}uTfqj};2tx*#g$c5Q@HhD5(lUl+B&vVDFR5rJ@Z&|z3i^O z&dw1B2}SkJ^y@JG->y5BY^Zf;Hw=q0E_Xf+$#t0*I1t#)KHtAQHE;!TxTN|HsPi`BBRiS*Cj^scW6nID?MfAJh z8jqOkH@Rpb(cMjV>gf`fkYn+!YK2mjhZyS~-G*d#rX6QFk#EK_1!aIU-w-`25vD;8 zEPETle4;%9kw}f%Uxc}{mUF-A;oWzv55#l)5Y=lJJ8v2}_`PQ{#ZHQY1&{XYYIZzU z?%r+R)^ieu*{>i3(di*q_AF*T{`{eHS5+FVQPKIoJ# zEEB501&*LbGtfDM9p^4mr1Zp?>(Okk7%&16t!sFi>+SC8%NeRPis~c%EhXKT*zd4( zZl>6?$dd7+!1j`hQl@e71^2Dn3I&yM0<*=M=Zt_< z^%EQpdK~#(mj|4lR%>h|Ig?r7GfXFb=srs3v6RHKBeCS`O5CHfEJp@}R2-GOp8N6S zA~poO+F0n3Pvg^Jq@$+D=YS##dNV_1jkkqQ)2s>D9RPWd6(LyeDTt<^+d$%Y{Cr>r zj4kN+X`dybRWH5h%#1nR*rOU8#}rFGZRK=IH>Xoi`YFhH+C_4! zS-SqAd095K5S6EkTaMSoXJ3}N-{r!sl~}*Zy-Dom8xc!7TJ`(9pt7?S3t~=CkUm>V zJ)D|#QnziD-KQ7e;offD^P+Nil5*nJNVmYbM+{2ph@|mEhY)z|G2|{DFd$YA>?56$ z09n)O(Rp7CdoXqCXurT+T4?Mf|vvNgoW7;+deQl*&&wQ z#otueW<{?g3WjWVD57xEP)Be)klaiCTSrqke#kU9?mmuEjW6>jT^mo@7PpN%{cJwV zlYF}&NlmfyOCH||s@;5@JdKJYhzG!7-iH${nd{9C$A+GeuN_xj|D$*~nNs=fk6$7a zfLas-)x*~;T_Dkd>I#qpr zeVi->GmP}$>(eojk*0^^VQlt#bcsZ|oBwJ^gcdWMQ}s~qBQZ&~>{p)sh-MK05T3%A@)F`TrE{9*7GVbWca)E!U3#+^n3hVEbes9V@M zC||8-mIsXe!bntD>V@XyfRIpV&`%`+JX0rATNmDBXYMl8)~**3ayz@t{}|?Tx&}v? z)-#c2V!J_48RZ=z2vx8+Z)r5N`^VpN1?;`4K(ADzGuS!Fe~0DIgal*f<|Z}ive!2X zZOH>}6gvDZnodw*;oRc6#?kTr-@?|HA6`wuiWzF}9S zGpzPu_4QK8+7w(1ub*J0$Qv{7hvb==vfi{{IadI3Sam*Avk~K{y)|zSZn!=+G1gnS zz-sV?+JJ2;{YK5BD)E#?v&-allv^V@-YLE=6l|SWS02^N9caOY`LOZ2P-CO7*>AwC z4!06){>nohF(ojNUznWb5*MSPtreNgIC+4UcEWK7C!LZg4LOAD1km=W+ON85;Az$7 z`bSEk%072a+@#OYq4zi66>Yxi>-UHMw_VBXdXQD%)Re^)`8|uT&%An^&!sHb1SHJh zsdgfhqWWi#Fl*Kj>t;3Q@>a`xsl##-xa$8;N9XWPb?MhZE@g9OPE%^3{lE0CDO~*X z3OF(E@2w^%_w?KOLL%YlkBCs$(Ac@%zp$`qdsC%_23@U)V0P)Fy3~w;#EGR9^cA(% z)-Dqn3Lkn)Xa0OS%V}z=V9M7yPMgrXmce|x?v65F^FqlD4iQDce*et_is>ufTG}=Y z+7+aut*O!i+4TpycY|J?HHC+@q!tsC1QyfFZ`gG?XXZ7nni#A_S z(fv|fJG51{G^57&E>|O7xY=UjN5`%J^Sttkr((O8WO!&x4(ie<2zH`Xn-F4%;CVJ}h zy8?6rX1hHgLJB^$Uc_+n_1;~ZIi+Z%j|O(6O`g4Q=a3}uREe-L$!PO~Tc3p7=&m!~ zx{;mq{$Bo>ztaDs$?uP|U1?g7WWB+`Oc^j~oPWCGk9^)s#|wX6B6urDTY)AB4F@(n zjMq=Dn?HDz7ci<@8ArdZZf9J*CS6q0^o28u&%V;oW)7VzdLgg;Zlp86YqEPOXd66z zVHylTgTu^O_4E?Y+xJ|wIKg4OuP=}VZ(vmfI3m6{_Bzwgy`P}n4qkdptgDuRr2*c~ zXeza>LmoyQVu@p06d)lZa63W?ly#%)+bJz^Ee$Po`h_bOzJ$)puj@aWjm}W`(ckP_ z(Q7aEoqiJPZNbU(>=X3y^3;522~sQ0au>AvUB@=U#H z9%LT-^=q2@N|v!**;S#P6ltf*0$cPlm2CuX&*Uz2YHMoVI<~jE^dSAPnI3dBlo4r} zhJCM}jNazvOm33$g-4-*;$Qvg&%%yP8w}Dj4`^zQO0<}X(WwtsMfatqYVyf+_TvC! z%rgu0Y~WtBx{h+t1ml{#ee(v^NzXNPz38%Y3CUTW8j7#4dS{>7vX5PVC|TIvq?XOc zpTa+gvp78O-DNBC&6E~Jda1m%BGA=En}_1+GH~8|6!}qAzr%IR^8*$8g|G8I4<35c zLlx{0MYBNMAkw%w)7FiOBl0hXm9^rxha`)^C;4t`Q5ovj_^>i0h{~ zIr+`}n4_FMdFj9GItbHX7XhyopraoXNZ(fiV5S z?-2cbpAKX3`@bUF$^qJI_mbdtK9MrLzcRe&Kas8BuR$s~h||-bE+3=rA5x~72;9f9 zR(q9OQwv=%6pWm$H zXma1>K4-@5pxh7VmI6bP4-{sP_f@QP4Xn=OX4uqh9(vjJ`OG~WD}HKj!|ijf%{*slBO49Jg#OMe zm$^d4PS0OZRUji(3>*kizdlB{v04@iNrmRYBbS~OC9};$P1A;aiQ%f|V*Mg=kh0c! zoQY`xjsp-62sV&!XO+AF<@ZHsF@SRH8=wu4jK+ZO#Bu})jhmi9WHN}XfZ8GEBX%D* z?6Lolf8A#lzvWN+oo}fb=?ohh$w-??${nP0r*nSsG1iK>CkhJ+zH4sWq0{{!Epw`z z7pkNEblZS+&pz*%xKn5Pg4WS Z;2LzHgUQ7&~3R;}UuLKzZ`EGM@Z=@d!Iw%lU7 zcV>>WnM3NN(A`m8bUGP&8#sbZuWD{Ox4+5GSn>4dlv-u!Dp#-lWH;B}HckD0B#MtU zupyZZg040zP09V;9q0g}M;#=*DFbClcbG-LKW9EQgqs*DS`^tY5Nwd?OEqWs+8J3+! zf0T>({J17DdegO#gXw|pi9DnR zN0#fk`!_dkJ-V&i?9qm66K^&g{Tamb)!GC75#5dPk>?ov<G2$~h!xdNbjpgJPo(698cZzK%igl+RQ!y{U z`EDlmF>ANQ`~}zn>{f1jLfSW_v)(CFo+KPLj9UcZQ-$x!>^xG+9HK5tOgY*1KbzM5 z%_7bD_r9?<-u$gPcV_untq5f;%hQ|srClO-++{#WHBnHMnpxJ0JY8*+O4~2)kr-ZQ z8g(AtF9(Tlu3pfu2{K--7(kvv|0U5#Z7VC$Ffoda!sOnQZ%ar)j0M{E%I0xtX_Kd3 zs<`lPkIaqsJX3Vol7XK7xtZSWz-d?MlR+J$c6J{O-a970M`*jG5Cart>}&Ci6D5t7yi%FBVLXS37i%LRoRrPbb{TmaBqdk1~vBU(?0rKHpm* z-`h{I-FLhVDF=yT_hzX`Dv#5grR|vm(yU3F74rG7>DqK#n3?g0d~qsk4|?TzYnU8_ z*2}AAD~pAlr6R17-H0PN5FFyz1#Lr-)3;AgzrK=d_V>ATt4BQu zu5-nMs*-ss_N$SdLwD}CB(wRx%*mPwJN=Njh9R3e7bNOmZEpB5@vWit%h?>&HNo=# zyKE{VYa(R&6vQpCv4&kS6dY@-r&dy8*s{f{`TMC*PphpA+fV?+RZ^m)5>!cz?QBr( zhN|!DrwXG98zz5Av2m~2)K?XQ)76zDA=!q>yF#57ys}c76%sFdP3~Uo^fS_+qisnp zR(H&vd8&9*rN>>tt*@ZrS(<~+!(j=x6IA48HRc<8w^X{>=P6I;UyOWZWWVmCp)YkI z`SAPlns!;NB3H7~e9XC&mmV9s=7+-C_u!I&pVBPf=|?VFeJ$OtS1wfw=FuvVWLgc% z*t)B`i(WKu*-oMgtQBiE7Rkus-+Svke@JpNuQpW>Z%E@Stw^pL?XOA?mYP%ceTw$r9=EQ-&MWV~ z1x-xyt5-&=fnie9X9GJXw$FrYOExUFIV@~1rWh4u!u%+TW|@E9W+h<5sd9@B@z)U! zLEGYWwLdt2nW4+}y6{wcp33gx&evaJM$H6MR^v)Y8&{~v|1M^)Rl2LP<#S`*z}58x zVi9AC$vOoAawq>ZyRIV)M-q6|jFf(s-L5A`Io^Y}wv+4>wT4y>gY)!KHL?$wjNFIR z29r`$a3(=h(``kmwdt`B?|YdZ-Pif}^-N)NA|&IrzZaT_Wmw`J@}>X#$7qMQf$Tpv zO_`P14mt;qvuS=zbLJz-cZz7{i5xh2;^L28$bbDfd$LXHy{geggO_DYAs$k@$71 zFJ5G2P4ZCOMwqK3vJ{}+BH$M&A`w_M-|<5D8ZHd%$|hhGahlEpAcNpj7YBVIe~dA7 z?Nz9(qh)U-_#U3yoh&tHdZ(o*2vIYu$lsh1SH@+D_Vha9sv41b$$yU-9iaq3{XoB| z*3{e^y=myx4X3U;97{H$(DKj15uLVn9~KN>RB`J5@>%G1@#Gq5oSqQc%_SkbOVU3p z3lBCz(w)jSD~!k}J!BgV)fJ;FpgJS*igx3p@jy;e7DvEz%PmX$A78vymNI37cdt|w z<+mi)ire&CR(+EffxPGHxpI?$CIqWE!*flrHn>`_wgNymDl}_EKsD9so0E)0_|Q*i z*%3zpaPIV^MtSZ zvZHt)#78GpC9kqXrR^4)nmcvl$E7M4+#nB$V(RnbupS7iY?OWbriU=z2E;ez7rbB;+Pw>LB7g#P^L zoZg|QuTQ9n+jvPe_xJK{4?Rp_A-Lf*xqISHC1ra5kdOqPrEf85Pt-H`g}H4xuc1{T zMOIhMHJg*bj!?UEnka)p>hnLekyZRzyKH$P+ba>uBKE+zsmEE92wx=P!HD<=5I11C z5fW5v*Rn6-O*2TxkB$u>kANr7bhxm-L=1%`&b`7T0g!nOLfw+J_7&tJRU-?`Z>4__ zF+m=X9&Q4QLD+oZ8<9a)m>+_8k#XnJ3bA z4qwst@mWOx4wJBvw?xZb!W)u2Co{2Oq@|~?Bekajj&mY{V?=ltK|JD96M>&#liv2-ld64! z!_Fo@VZDQ^JYUpcygw%MKjKQ$+ZlL(KI{JjD_H(==ODkAJ zFz`AXQU}&XoVrEx%9=K2S9_4*y@TQ^WG}D2;0k7G==#3xMZr(41!)%*y&FWAaCaCJS{=a6@F73&4kIs`w;z|IV_djFdLz&HY+U?YT&r94;u$IDHbYQf3w zAVR@)IY=O}{5euqMl|3?s3bYTc01B*L;ny_*GJgs` zniPT+ZM+jca=2l7HK$4?9udDK41O?%RGqy8Ss`dRQHmH3urUC^&52%D^Ji zu!%;0lR$v=@{wPcx(f8UFPnQ5lOLaD{ivKXc*NyNEzSv-Gu|vPT_bY#h-7ER$xD|~ zxRlw#(^oYJY7mhOFwKK&AsFlk58@yPU=9?Az7EZz%cUhnb#FXSNJhvJCGrzt zHQOL~vFgvQovP3AN60PJ)Yzq*d9NW!XpP8!g!Z;}==o^0!P8b2^yz49x=1jG!JGCI zMQl3V@jQSfRaMo=L}+XkXr4MVcZeZ6i9@*^9%-x$A_l25nuyAQ@e$UMxAT9-+fwjZ zSCGxPK^F=dym_3f@W$~YzQMd~I(b2U_0+SrUY!|KQNPK|^o=-ZNWvMB6BQ7SAQ=jQ zY$`_vIv1!|I-h*|vFB7^DD~he{XRtjcs3(<`cW}2fQjqHFp0*~iR;c$n?S(ka~FYjCqI*|hU z2~Tf#EwpG56L|-h)Xcx&AcyP}dHD+^$Z?5FL!xYTA=~A+!^SU3HbhcJB9v#yoiHxy z^>t3FaJs0#2LoZzjJrm^K`FN|=xH=GKXAnmC=dT9l5iiS#o9){XjFJ>wzf#7@HX_^ z%2w>SNQ>-onHqz~Obda^R2{5@BXsUGe(F@D=3lpGbl-lDE==8l6jwhYxQK{nK%yEh zT`t5=cy_Dzc#R|2wc@)R2_sP%xbPf<*?|f-gHg>$9IPS2{9>kjD$;M}9Pm0762OPp zLfA(U?_e3Kv95`Z33=J^zZtOsmFF6$^T#(wQ|e#^`apD+DU_X+RR#N(hN@(pCv)ft zXvCL+WpDTIbFK(Y^5xRl^KDGv$dMyGedD&{aH>QWC3~V|{k_w+>pNgEq}s#Y9bv0R zvpK1CY-y!JqOopj;Sdj|LTi?Af;Cd^0xtH!4TKU4`p`I*m9~~h$L$N!n!jVpl z+@<}7hK5(T$NpG$d|*EFHtMkkF@6wP5z?mLDR$^sREb*DSTC9Elz+$de4ofJ}m=*EaGPAYi&$=d#kubrR_PU3u zttE5#b2D6-7p718A|xI3;nw|`A&oAoowDA1Q!nx_5Eww+;{Zx7W&P(4LonXm`-RNR&3>u9eQ5fmL26VqT?P=Uwq&Y>2odp;d|^LnzUJP*=- z#wHBOGtVvjAnmd9HYO~|cwmW?PRu;0ZOFv&g#O?ugJ1gD*h2Ka$Y0ZqjYZG4Q3Mkl zBFyv`v|%af8@X8Q__99cf>Us_MZBz+D+-E+Mu!bldM`Io6AF%Q#jRn($ct7`=>Upp zpVEO5-M~*c-o5+hpo1M?RIe7%yiFJt4~$&ZT^7U)txN?(G{gE}!|tDGd1l_ZQKr z$`Oat5?^UTLUUtATj*r_{=`OYk;4S&JaCs+6lteCiSA$EOqH8Ry>}v<4TqzBLDRJ9 z-$N1j(6B>H2d$ki3fGF{8wgOBF;^oYVjXvM{UkZ@z}%?$4BrIe92_v5K^sAgMtC4g zwFAqB!=#~^C`Xd=VPTn{SC#wnO^&a)7$8U04`DOx*ZQZ85JrIXCL+8#Q2viXk4wb> zl`*CUZRL$591XLMbch|FiB1I88#NI%J zPc>ST2dYMo;ua%Wvk0LJ@R7Gbtcij~f-)I{fE-;O;7<%wuU~KiyC{YkFo> zsltaZ#1y2$wO*=OQGLpYQ8$(nlfYTwOZI&@-odFzr=a)FW68l_coW0LY7*ZVR+AyS z3LYQqm5B~?urKfKdLH=pzLY+ zVrx-n^i!wB6}sx@Hrzv973J(P$wPjF8rt6leV@+ShoS!d&9=4)Fw{!W>cYD)a7llp zpnm>fZTfECiY0r#wkqIjU32`*)|haEN&A5_XO@u~3TG$69tz`nifL1w*A=bBOwb&-iN?eExVsx%UZ^))3Oh0EC>DVG3|LU4UyI4_nP*njP4yR>-&6fS{PvTdWBmL*2agsp z^0usD!RUDy%HITa1OKmS88lAT~PfxsuS=<}v~-Dg~F<-b7!u6vp@n z?j{R;D(Y(CO+yep=TCofIduX(@+PPhv=#_r1EF?`;79p2l#vXan4CQ2`!QHrp(G}p zJY5va`pE<256c(WYpNrxL^zdLIaSe&V?pb9Kj~su(R#FfBok19gu&f{6f@S$7BrEdkSFL&w*|)cm=%n6I0|<5Qd7km4g0 zK?$z#m$azlvxmKSXY6SG>*`p_JB5@kj9R|#TGVDCUv<1xvh8mskU}0a9_&^mmHf

iQ$qs{peyvX%8)tCC~vMkS70 z85hDxhG2h1VJV|0Xi`&bVyRZ0x)>f-K7=!rAMV!MD_wdaykk*Y z?|E(5a*}pxS6rBBH@k0N)`0T`?6WavIgwd3tLoXhfHKl;jk~- zK*bT?=?$>NhCJS1rT)|7R9UB=zowrH5j%O1;g=*IizwOekUD-PF_i%=V$!zUlAZtU43U7+;siEQ|-O(nw(B#&Q;XIiOv9(=73!r4h{gsJLN1$jp*3q@`;IWxRWNA< zB7yqHcHa|lw^`rA!wT8j;)DtPDBS3g;a9Dif+88m{73`6XDAP>6*LI}LQ00ll1#k9 zhEsFY@%jrwRNmN~Z?O))=)4L&*e)zO0W5 z4yZ&W=3I4fTCf(Quuq{F_z-A*R;B4&xNK2qk|?xL&;<@gTy-X_re3H}sZ^%J@Ao-j2;k>eB3s8?LzpCPt!a#Y z7%$EqQ%5Yl+!rx&bTcx zq1sv~5$13Wjb*89oFai9BYy(s6tZlxF8=f`OL(Hmpjm5Q8I{U+dNIPQX_{uw(;32= zsVGD#Oecz;sZMpta#{Ta-p$Nwq+OMBEs_()enrPl@dBmgbaqD~3U@zhtNgjE-SJ)X z*!3*F8}FP9TP@n1U?L(-oUsZU<(h)GiG$#v5y_Ev<+`k!Str8+e7rhnDlIJmDlxWx z^2`4KyimZbY?wdAZ7q6U_n*^UFL~{wC)A=DjrRe;N0{W_B0>DeJJP*>^_^}ak3CjX zuF*Z;`h&{lyPlVe^VKAgZFrvC=H+}dpaIko95LXILQkSL3`_Kbo5O+tby+{>&Re&i zoRsC~+SSq%i5~tmb%~L7l<55!pE>>i*F`VZAfj4`XvnQ#X z{f2^GVEGz$Zfm?we^39Kx744T?jOYNXHNV=nu_qEMG=1IYxI(t|7MyssTspu7jzCb zP7SaS_WSS)y1q4tx%%S`9lW=j|Jz70`_S~~=|v$&9d17y_D_Vqf;0-uUBh;wG6SWY z#br{}vOpQPRAp2-md)=yh*hF)#H*>H(g zy*nJzt^5J!!(TWO3JU2ITu_K6c=KgyLtco0IeZ=`byF zA304lTTYd~fG%%+remtx82oQn=mS@WIcJM8V+KLgj-$6=5%x<(%EPBz$eR+vst1-r zj?sZ%$2LhmhTs%NEsT=7+%$#v^nVUK|GlS5?iNNDrk+;}<7Cg`ScU=lUH?n^eq zke4E&Mwg4C{gI!#K35hQ`EdU%6KQ)Yc>Vb}D^>g_-L5bqOIk)QlFWQefVu0AX z+@*vWrRj?he$~b+lo24*(ZBh6w^+SYW!*_S_zWNMWuvBiT4#xeTC-|l`xUz?n3i^V z-WREvvV1+|H7%$nH!Ny8E~c)hXO`@f!CP!!H?6Kl84hgaP5?_1cnUJcqIzdbyS9`G zuxcj-DajP#V|T;nMM*|*5ZPJJ_p1%pT6VZx53LJ^>~Sc0R~fUexTG$6eR5X#-C4mA zLn>XgKrtG1)#b(3LS-6Nc}3^qko9SW8C!kQw!uu@{hzN>Nj{*kbJ2vHeX@*1T^k?s z;qRE&Nc3oeCV~#F=Jk*0zDLM2E;IGZ?2R9MKKNvG@qaraLuYH-i(e%y<3eB4^TNjQ z55vZhrcTW37a%|lcDdk7b1wR3YxmLNEsEOuwc6Lyq@+j4a2BCCAcKfH{c@b5mnjq! zpvflM@PnHT!5rQ*GRLINamnMI|DRuK zIO{tbytn&$fe~~2?BfFVdIQgqQ|$xgpe4fmn)JNC8Rj-PPrJ2W~b6yXy(2X z#;?2ksNYg{b$!d8VVHe-Zp~QhqR*ERJ-#F+VLC)KOJBq12|oHn5+ZU~?fzUKL9gi- zxs4M>Q7E@u@-H?18|EM%V}XT~5(b0XTG+7gjj;ifEH#G3V|ztC6XdDa#W zXKL;6Cz8|=_ObtWGmu~}V9fd;q5Xhm&ictkl|TJ;=E)~WQ|X#Y=i4VdJf9|dT%xb# z(g^VpJ`P=0n`UaoYoiM#n?J%+`K3llucVMf@ty{cS$^DWm>=BPyrc%ElTBHo^2^pU zEmvAy(u;WrZw?i$&p%->WuDua_!?Qyx1vr480G1Y%mk8 znD_s#k}k#NE_wr4vtj885o7mvo63Ev*@W(D8>SsZ)8Me%XYf$w=HwS{mFREC3Fb@w zyjQQMB5(oKGZao(E!Dj{N`j9NV6mx?;m8sY$-(5A*Hx?6uZ4HE_rNCCt03gPRwk4kA#ILe8+Oejjm(n6ft(lw+#FaqX)BVMLd3aXrf1KCM=tF5rn5rr-LcFrMW2_Ff1LbQkZ>4h`a z{&M*DiREva=B1&@klB_%+bL0ceVO63k&9~rp@f8_E`Q-}WxT>M#5{Fi7rl{2do_ZP z6~%^=rRq?hR_u-yg2SSW5Pif(My0XL@Gts;EM8`=KQgZoeEjUyItDpO+9G5I}J zPK&N{#p3#JN$e5+SiwO>bu^!N`8cOx^i3URWo`85^vdhU$i z3+*vaSEtZr8T)=(zOh?K(Fh@2*UGxBBnM+dEo}UhLoL#a*=kvINWsN=^S3?yP5i9tyd7ndmj45uWo)ClAdQMvp3@4;GjH5Oh_c z?3S!#5FA=1Q3OZ+7u)sBn|u!m6dm`U(j|sypfGc32@yA>`e%VL;s*%A0dQeZC7>_| zbxQx09_!>ZK2vdz1!bc&sL%+Fn@|$rk)F^l%@)P)>KT}he*Ic=z7ID*5F1k)vyzg2 zg9{+T*=-=4VS{LxxW0hmc$?bFc$<4+NY(k20Gn7Edlr9f zCm|}97a~x@I6WwS!qUF=aqhwI4l<5M0cI@%}|6d1_U ze&bkVqbC_=X8(h0MfhRif`&A~2Aa4RN40Q;%mPOfD+M{y{_+r+!TaBnArTs%2aEhH zh|K`SkKg^5yiwX6h?v1t@jyAA{wB5r|M@LQt{D8F{);%qY7|mV`dx!|GlU$+CXz$; z!{j-I)NYA=dRE(Tbs1byD^1(RTwXt3T;zMcUS9D^{705G=EShXF+}mF7rXK&63BJxSOIAyE?mKt*F_1+p3I!-^Yt~8IIJL%&^SxLrm zPN4DUMH>{Qh`N}oCwy z^ZrHYOCxyq?VbldwjbSExD}oV9_xTJJ=Jc7g7}|59$j{HKbgZ978agfz4I=ZrPFn0 z!@NF%f>Qe4UdY5Z{{`QF2i}X;QG622@4z~f#S9X%%#l{gcnF!##v?4OkK#vT)mM--m!yfD{6a zt>uHu{zr??fsG3UoPk`HG5F*+Xr@;?0FDT_4N~gApO_pYkoSWCgmP`$Yyzp}@5Ur1 z*NsusjR_6V%Rfwvke%JiaLFL#iU~jn#`+V04k{}@Zyx|2iAgJk%rgY^6%0QC^;|%J zI6+Saj{3XrsGdO}a7y$&P$OT(M2a+6O7c|B1ww8P^f1dJj0v_7$phIKzKElYBFl%o)j`0|!0agc|x3_NHf_woG0R@4&10Mx= zDnB3AV?rn~1!Rwie$Y7hA?yJ_5vZ$Rv?M@Tq?dCtfzcUk2YCZLEWl0@Tnw{4zo{sB zbNqMU6=PzT)B1C1q49PaibhkfbnpAhIS{puktACT7ewe>~^0&LS4t1R3wo?YU?|1g8dqKY97_T-if<9Gr{nK zSXyHk6GIC*qN=O#crdAMuLt$h*j8b;8b4L%<31aE!*igh{PxV!rj(_8yUO)N z67I{U-VQIsh48KHzHK;7DyeM?HrD%0XYV%4c+z;%x6Z09tg~Z9u?#1mu zzcqDP0yLD18-YTAz)*_ld+CClAR~jmhyys!RlwQKF+2;vPd*?Hs=pMl0o3(s;NKxk zoQ_Q&l}a-527n7FIO~IjH2_$^em;VJZcG~1{}Pirf#tlATUclf3>T19AP)V4;1Gz% z1bbsNWLCkXxCR0Rz?~Rdc(CZOPG15Wi(riK0N7g&c!!LXLF{tm9prE~=Nyyh1?g?N z!wm)d5kG0oxT&pcr#3-aG=d;10GA~EN1>~nKj3f&bZ;oNV-iP!9R&+x1cPk@TLghH z+NxI}oDKx?UCAQG#x_P)2l)|`r*?jn zb8b{?^$~<6r36Oe+}76betGukP;1|Ut?MWJ3>dvI@ybBw!e~iKIhn9@V6u=Z50w=Z zaPM~fcf&5o`K5NjR~bztBqtP=gtkv7Bvcr_guk_1}R4> zlI)&1{?q?$fR32jOXj-RDO?M^VXn8z2~A+Q<`zUX1kmY34sMx zt$hFRO{CDQ;>K{(WzmZlpLl+GSWtC$P*pg?GF`IgW$^`7XNZNg;79GCm7|utGh7Z- zs^6v==`}J$*%qIUpY69()Gk`uWOilQQ|IuS@0(7hot#}4&3tuRO5l3jzX7i+=IchA zzAIIc6vnc9Wqe)yf&(LaI`Mac+PZ3QQ9Gp-@_!vMPSZb@_~45ybWRY#6(N2MJQ%Ku=20$3ud$mMQ=x z$NQTXEx@M)NKRZgc(E8CpHKUsLpG5FL6of_9b`4P!mT`$gX z!P)^KYzz!8AX<+KXAUI69Dd8tJy|U(7{&0tfnRoqIl|b-M1LD%qQTu@{&(Tl=fOc} zzj`!slN78k{>K8?-Z%n!8IvRfnKXoVk((qjY3%BP+zlu}Y;sC^dyApIi#v8&`Vtyyk#P1FDTP)G(GhF=nV+vp7F9zm0FC-qnUoAN}+L9RFKEJ>x+Qr`!B^Tod5oy;jyvxM39r9>- z5Dj4ds zXCt8z;Hb)O2=1t<(IhiguZM=Pv2NJ+>)htv4;3gunkvZpKhv*!G<<>(T{en5O^&?? zNiqTu&mZq6L#!&05+9!;rRCz*y=0COdy1z(r@VncZRjxu`g0Gy$Niy1^U5#XVvuF~ zy(#|^QaRfj1bsy9ckaM97RSkj(+UP=ZJG-9fas1DSo=)??*aJ}mf%xJf@S*&%_vYA zEEt$cjKt~Xt@vupOu93>7|vWIBkO356&^~6mzet|kAMJs7Qxcdma8*1FQxDgI1JWM z2W-P5ncCUY8Pks~YJa4g z)r!0<6sl$;BhWQ4uoV=!^2+$qWUJo57secwhP?{PXdEwJiuNNl@Lu}2*R{V1V@15_ z!T4hd@6jtFY%FT&+Bs%hSJQqv`s9TC91kEr{B!z!&2%;UX>2p&;?)2~cTqPif}YWU z^S7@bZztb;&;;MVysQ>wAM;B;#Z7+<;6qfh6=yZc zi z)Fv1=G_L6u)jec1g59t?o}mqdD8RdZf4h4_>c@4D6j)J~2XkDdAY-efacE?OiU_Yt zBX8vQJxDGFN^n?^d&j+F@B|Vz7a;uF-p;Oht-Jyb0@;`$Og9+&-;mhK_qk+~i}i1Y zD&ex^EF!uipO?pG+NC6}GWmItMFKPPEOy2J{q8rSpk%8huHa*3)Zv#p5txPSF>qZh1# zb+M`Vp@rH&woU(SINp2Yto|C%D6&TXwMN9w?2 zI9tj^l@dXjxKACr>o_`+8`fvEq477+5<~^+mz3B!gzR(XuwPfs&|bW6O9BP0KYpg9 z0mq!<@A%{HMcTeeHD$#l*1sf_L80}nh8Dio~zmjCVvsg+{#n9LHId4SLsQl&o?hz zT~6SFpE3i8INYVpfw+Pv1nmx{fWnYO&cmxi@k1~G>^fLLo>lX)*xH%Jj1LSw03R3dU~$8WlAv)LIUJNAs^VWgq?eGNNFXlk}kozs_TL);vHyvIpIXwm$*9bw`!)4A%J(%2hS5J@O*fmlkT z%F$f8w1+opXbg!1aNZEVL5_Hh&You;+%x-K_v@F<$LmgFmYRD^llM2M#Zn?aOAt#j zo(pUKmNU&t*>AD=d7b73PJ$hgu z<^QnC+}wFeM@E!{ADh5cPP9Q$ zezc`tGIT5D9ybFHA6jBDY}gy$U4WjUVFVK8unvwOW)xNQI9+16~2YZjj1L8j|puRgWubMg@G%1ay38SHfhZ0o=Z~0oMc2iw%s8 z;aIiygc#Wk@M|3$ zotmxQewO? z;Gj=4(noH*Bf!BD&H&F7({bXi-o8Fskcq?1vo@N@WylmsS4-Ag^EvW49-0L1ZLPn8 zeU>d(gp70q7t71u7t%Dk&u<2VjG?*o2;#g2ad?O4MAB>6b%;H5S8b*oxqRCzak zj|N0`#0H&xxl1`fExk@o%0xt+@@x0G+1-Bcv!(LY2RAbL9r`$D6OVT{jprp)sNk0Na5O;56G}0Du$5s_lwHKW*E&Eq zBwT@-;eeaqsr14;26{Yp0ZSESadoc3`T_?~He7t%(QJpimq;1OP|P;MgdxndH#K-B z%|idqx!$HSQ?>jTrp9zPogSI(ISk!23iKDl7=>>M*63|uejU#*J5I>$Mn^5^yRTIY1dG3 zG(6G%o}9*LAOA_{)8~`37sBCYCeEmXU2s>t`SRYw+qcvb-Yo6<27g|H!aUeEMmkqzt_VeW5hHdub zQ6#Sa+36>C*Y?bti+zLFf2KWuoEs|OyZ4>+qCS0<_tTh(tpPrA6xCjXxGJ!bSZ zdm4pMD}JR5wGX_d1PQ;16|Yp+Fg@*BR9$m!zP?9FR|6Yh1z+KC4P}bbac>HgisCEy zYy%xaV(JR;?2MMgWWE@ly_!uUIlvlaNe z``c0SR;p-u1hJG!4)vp~@G7f%DtX?GJ3ajG-O*-bMv!RV)`rnLO75=+dj9MxlE!N_ z`68Lg*`mddIgv<3R+?f}Q$88X<+WBp$Rttf8l2O>auY1SPBn;mz?BoR_Lqc=E4bA| zSPd^X_Y}1JK!-_p!quE-)24&U^gS;rXdRzj2+h?lvo_LKk=dH@e=Ye}^Qv@Q_r(V| z6v*YTaunF)?K#8RJiPsY$LI?5$9x`&n{uA__-FR$Nx^Kc##hqTfc(x6&L(YRG~e2+ ziKVqt(k-7>wuV~1L98!a`nRvQF?DeC{z!pW*xQXSOR-~~Whhf-SOyEJmrfdaRrXIoH(Y@i z{Ma8Bn1<9EC|LdNhgk9Aa+&a+q7g0}G~Q^taAi^#SE`@(wQ!$nv;czizTl<(tYeNtPn5Bww`8slZGfu6n7moUqp;Y94x|W}No@Br7?- z2~LmChv;Vj$%L_QG%(QChNcea2J#BguHw9TyS`l@O}Y`aI`!lcd0jnyC?p?G`!r(U?4Qe4(DbDrzig(prX>^$+7dS*MG8t-(_759LybxaSUQ z1A{4bTotLaE6^RcWg;>cO3u3=Lxv+m_Td~$=K4;7Z(gL^oA0Hb?@QC>OS@;~bYpwQ z?;>QE?V3?EM2k;w6z4A~Tt;&^{6Yy6&?KIs1vKYhWV;*Q7c4BVl?v4&v$~bU)6rW; zl2(Pqv=gfN{#JQG5?8zNpq&_Ne>f}OmE>e3Dhb>Mum*=Ew_m|Mv$u4d1~d5j-ZiLw zgG?B0?a$)H@ANAy{i8{Qa&LQtC)>3A(q!5gmX10Q55uxcsmT6OsT-2zizbriIArg!T;4bL`_d}*$nLSd$eoS4PTc#Cci0_AxI&86 zmBpzW(??eemE{TW#8j}zq#h;oU~;tgx2F9eK?F8Z+nrQ)f?vUxRiyqmpa}BGb3R;D z!TNrKp8Pgra19n+4Gt|fdF#zR0{5E?(xC|MH72HTQ6qjF8Wk%xBV0vd&hP6@zPO3| z7eYIb!N@4R!<3+T1hK04);RmP1e=NYPy%{~q@ z4k3Ls`p}l2W@l`a0XO&QOmr+Ik0|}u{ZWUv9YGx=Ow_uop-KVD5Aw9Su%*>$R(b6a zGTXcN>WYezU&4 z-?1CFZBQrzW$g{$qPBegoe1R**RMsf$VZoOP!3jb z_tQ%9sh!q_O`kk?gLJVCH9&*1K~cHo+%EH{@N@zJgo8LSRH( zeMJ&QFZL^h<|~b?j5x^P6x@P)%D0$u>6sf`#$U@%D8BCW3kMs$+{}-?XJix-5n)Ov z%tjzflN(3l?2Lo=(E4e*xL(ol>4t~i*-lrQTl4Q$?G!VN8LbAi;z8RHqzHd%PlQ>c z_C$4}k6xXDp#(70H?AWmtTdn&>VbIkp0R-WY2ESKmR z*J5aEX*Sje@{{FaKk(H+0f7{oqxJ$nSnZh0d=h-9vWlSmUNzAP6vw5qCl zIO0$tkD`_m{8Y%BQfQ1MDF?7w;Wo^>m61@W2cbb)sxIS(!)_JKaA70hZ>BNtzSkMgsT2o-qbWx z!A|}eypiErm+d2)lWo>)^`y4-JLMz7hZfXKs4rFb6QFpXvpTGF`^+c6yQ!c-mzN-! zZPl|CEY+c1W^!{MaQmg@<($>=G^VI?1=|cidI|5()&i@0e(A-WYk!ZI$az0u+(Vhj zph;+T=B-4_8;1NzJ?9ow%NKcDiPelmSoK9o-6eZAmwn=wNq=iDebxDuV5g-;oQtBf z#{Lx2O)rm!#^>{8l9W{b6elG+BA|dhWJW9jRizH4t3w|1Z=nu!{TQ%0){jhemsD13}ZMP3p$%ev2 z{LGgqv3Qa{;K+-y=+yD_B_h$G1pEl@NZ_egg4iQL;i*oI+tF7PXrl1_h6E9>;Um1P zFOZT>$f&V4QTw(;t$$<{dLcMsz!rf@A+igThY56c)2ml+si8kL|7E?J)QCf4r-g-4 zlbo>}2S?1Gf2T~(U&|>}JKV*L&w{M~jnA21KJnN++e^Ojk+_S(ma=bRI&^JlFx&edr~S~wl3f#bs#RaK-nS@(^V!r6^>0wSI2(I&6Iu!yhF^Qo=V z2e6RlikHz&cMeOoVqZhhBUKdW?kQ?t{+rJ>gn13Q{E5UT7?A$Dva&ci<>S4+#H^ls zoDUzw7}!@2Uia-Y(T435t%Qs4DAjf!2eMmE`^-{6l ztXzL?E*ZZ@z=S0@E9JAZli^xkHMUdTPIBdAm$Z~-@PhK$ua81UM;7)y^+2g5`j&&A$3>pnoaT{0O9n(&<= zDQu{fGoliCbN){IZ9%WYUQ^(K!Y9!~`RwgZ>{i{INswwxUyRl~=chaC@ho zG79}CnDdB5~T+fwY3>I|J@ANgw%j(5;zQQAw^%PtBUN^Z*k~tBK#llb`Y)nE#WkBfu4E{(b@eG%#QW+ly}_MPxOYaf^B^fKv2%`%CKj9-5@ zSaa6(&1n+%p7ZyW4c33V#1W$EgL($~9^kJ2`Qlx7&XjA$eDa8Ntzu0kg*Spc#|n9j z=u2OOA99gjIya*F(h+~rqmq}}Czh}>8hhY{l4~Ne($qV*o<6gAhMPxSirt64>8wPj z$F>Jkaz1e+?7w3_j3W8@n&%$b%RWdA7V)eP2|CP%fydFc;GTVbCmp+7R)9c42wEVl zkH&_+GW8>><|R+YXRMkQ=gP243|0zZT>|`b@jq^+Ha12)eVT0i*h*E^%Z7b$S90(X zy{&KtD+P6MYK7w9%4Y|!2VPo6JKAU-AG$EoH0(sr;ZgjwU}xvP+bKibHxUZU>e zm`uUL7W$Hgc*ht?!-!9oljX%vyQZwpNs|4@aE9{!?=#QJUu1f&fBl+DnY9kr zB$uM}M->4Q0_U^SFMdXyLGNo*MzE#9Isv|*zfCm$u7(Ew4k-Wc;2r>F5saAwn7Z6( zS)f4RfVb@U1G~TOa#5*LLj%6QEQx^om?@?0bmLjqqW|r~O1i`!RKD`)+;7|1E1z}+ z2e*GU7tq^Mgv)mH^1t`u8?-Gm#?7uD5{_`Aas8EHSkz5oI zGRN(Nq7r=P(KHr`yYbuVD$<4|L$W0uAB-Ls-TQL#yP#UtfT01~L3(^-TkfJy2w7t1 z?mwfZR?a_m=RBB4CLg)}VWgm@=If^S_-G^L(%H7EvT}_f4=C!(t;{fj;g7tny>M^Q zKrOGdK6?hPHvxBLlkwn&Vde8DwMTt+j}y`;C@8)SM>;lcL8BxH+iOr4RvCSS*9%#* zaT3;()@cRJDR$-wD<_QtNasbgRh$z`#?A-LuB(3A0S^*>@Ae5wmqpN?zOcmMBmek7 zoS}z*GY9Lx=SGy3>PL0?vTAanXBw+9oP%BgU2*`On*Wg1ArLDj_ z?`h)5fAr%!ZYLjs^CcWH&ar+%&g(=TbDM7(O9!YwZVy5kS%Q6Wxv-G*HUv5LY_&b1 zEO+|-gIq}p4d(h@`XUvY-~K$Ia>U6c3gQ%z=zNbqKV+7D9Q?iVe9^yZ4j)@CLpUCP zW_VSdeUPaPUxq9zuU?z<^^}zNhM`fKg#CFt3M_Iap+4H;f-B=$2CvX44Wt8~S9Bh< z;M*b!t=!LCnxJ+F>3WH?m_^P`k!IoB*u-UIpYkfnyl>A-?}OPGQQNT#VJ0{QU)3Lz z#_ys^%Uh*5Ig{qcg5MsES5&_rfQ z$A;b%bKZISI_RhVQ|+s!Ycp^C!T$m5auY%xFut=>1%hL3v;q}yycn$X6ikjZ&0o5% zRpnD1BG#Sj)>)n3Vz`u?O|$-mhmkbCyJqvW;?;hZ$Gi$=cwS%q(8^d?pj1LD=3y-( zgF+u39`^IKZS0MkCnO|nPsl+@@K&GvmhA(`Faa>+2T0@KRPy=r2_{$yqz~i4za)6> zd2Q0WUv*CG_3z)Gn&f4MsmLe)k;l=Ab+6`ilSlJ#%O{7uY^|NnO((Nq-I|M`rWOnX z2N$nYG;q1)Wa?k%QXS7!VyS7x^ zY^yl!ubcaSe9x-X<(PP|&@mBI_2;)GHRi)rS$VIQ#jzw|22RPNWjE$dB?*og@qQ^D zXo`gcHn`2VgU$lVSvxF~B=&|QP{khfAca0Wnma)!7@rlm5d8i77eqIx%)3E5?m+iN zc^35!&gTC=3qYP4bMLx*W_xdf0IWB^oT%JQuFBX69V*+m5bj`kXWtMnXp`q1Cgzxy zqVGAl94(I{qpXVgN@lwxT{c?&UKS@z2FcTmio0MEbkOz_^+MdMoJ}Q9lR!EUb`@7W zF^$;Hi5GI0k_v1^iw%1hr#5E3eLkR9(#Gr=q|?4_X@iX*CKn9(yt+S>UH|4iB$w-! zgJ;MO&tWzAO`-$KOH1v*a0v2t!4?Y?EX|-u1~7dQ69c%-{L8=qn5Aw1JlhwsnJ>Eg zTs>Rz2oM;W+X08r#|>_*_%?yCZU-GLUO|AZ@LNby`adn(U|MCMug^ud@v|KhbP74V z7!?#C#~nbNgdOL=QV0IezfceZd7F+X0{pYi7HqC-+2U+{sfyQFrk1<(gRTXf52nmO{fEVCd~7J-ggEt*aJKd zUpl!EZX2p^UxPqcHAfQ!Z^)V9;@Xwtc=dm}9Q5-vm`tXwJj9 z0|bKXHFaklNK%ZV2Nn^48TQ)_q!(2Nz+(qMVfyT%guWoPIO)M4q)=2#DQP^arh=ueF8ues)gIV$E?Z#*F zj5so$bw8EY@&XnnUb~vh$#sDg3)$>{fbja%zBe)t_8a}Zy^w$dt|vqJ3bh(Gwzdg$ zBI;H8Q%+3~6z2k|m_~#ApXErUa5^5=gD}RCDuX+2e4>BF9BPjsOgUhO;wll3L&bzmzZ@#^Iv*s0xi{w@ev z)ob-2zkzo&^uS1be5;lvp6c+v@%Q7w_fIZ9OHRIbZ5S;4-p}pOH2vd|Z?}Em@B6>~ zQIvO})xTkMXg=K8=Zq+nw5YhOj>iu7UC84!@d};t-I4_m31>US@GG_}mRx6#xP6{t z`(d4;ahOmaFMPyxlG%90rsB|YUZ->>zqn|#HQ5!|cv~P?;(Su8AhJ=hS;oB}$TsVJ ziep0g1YUiM;Am65#z9tK{X4o_*Q$fhV`^C^T{u_e{PuD@UIy;pYc#{Dc{cy&zoXOj ze`=R>peNC065QZo`C7r#!UEh6hDt!Z09xujgj`jO9)E>53Z8EWKoYfQBVlSuuSAlRxiQ{*3j3sHrBRg7tMAtOMRtH1U!C(SD?H~Pgz z`O>Xm5@YjTYi`^Ps5q53{x~f8t5Zkv#_pS>9%<C@gLw@o0F7T%d#qSsqBD^k` z20(u0z&mt&)$;HI1RN?pMQQ+O0Lae;rYb0r7>iKCix=DKI&D8W2`k+>5xEt777*46 z$$ll{>loO6h2S}fb^Rm=OY&N}p$TxEvvbPJ<#2$}1CYc=aK^$%&jZHpDQ>!fhe=xI ze|Zm%W?Je1YV!yQ=^0g1L3@y-yPcz_Q~cDXi=AD~l*VGvr^y)J!aA@4oG1Z$R;gd239a3 zfJ6evdH6o?Dd8V5?mFSB{|>fuz?ug#&s|(xjE&QW>;izN&3BGkG7?m~MN}~AkQxa* z_v&Q*G8}?o$hZ3KIb;kp1sr*_O`ie$g)wpg3b%w~ZPdVAubTxr9Wc&xK>lhmk-d=g z{R69)6+gArpeNwtK(BFggKZPoBf{tfGr$$kR!l}34Wp3Dk7m2k7chj50^aRoGo-3s za(2E8eDDmQx^UnoumJ8?17P76RVj>hBQQ-(RkoP;kY9!QWj*$%a{>@Y*KnDPeo&Oc z*AqXdSFYtkkv07gS`M3|y)5O0+^S&N2l_p=emOqn8!98YarkdT!c8= zS4kMe<%d1rjvC*#3P0YNlMXO(mX$RPpl2sUHZ1R!Q+5nD#U%!1o_Ny9S#}4U$Zh>K%NNV690s>Cpm%SE)d13Fs zo-%C;V?+t_-xmb**x1;>+vc#;zzeK6*u~^vVbF&~4>9_9*l1Ob5+%XP7_=`g2JN%6 zgZ3VmcB_vuu=>Mmf^}+PX^D$LsT_l0OB^;ePEZ_y^&KlOV?M7kpp9jSJAA+ByMeywoRb8gqexbT2A@{P8QI_Sk{2=M;-E)X7+ej1RL0Smq4XHW6Oa^fDHF{r`n zaq_U?&aJz8bnB77Pu#MXDSdAz-I+L_?fitVLH)|ZoV!b}14Yz=}%j+fLe|H2tEvUN?d#9gKY-zcA+$j8)u|J5p!W<7cfRGV9HL z_quw6%2@08u1?xoxqRUrkAExqxT9G<7PRly>+PJ!u0h<((jkQZa{nG8gafVmO>pH{ z!D&x=$JiHw@lb=s7cx#fJDxo__FGt7XrjV?+dY@2paG3+6BMcYK#SJ|sfnlBe;1El4$LJ%_(EGs53~hRYb8Ws2bLz&16QatT z3PGFTzywLpPjplI7<-+#Y}v~{07Yv6^KQgG0-Sci5OrWL|2-KQ8SwaoH7UO&cYK{D0z68h zqoXn4+CMc6YYm>Juu#K|6SM2U3TW4z2TjGtruM=asY1?r$SND#5ax6)9`oELjwj>W zcb=vJU3=UQ1*+U9FIYRme~qj?^IX*A3U8WD#kP@Vn8kuRS7hc>dYuXD*m}@oKC8U+ zjx}BNEBni+7xDV5VAb#{7@FgzswyZ16g+ChR#q3COGxARS+RXnIv8=>Z8yxw5kC5s z^sI+--l()j!zk)StCoWlnk9?mY`D!6Ha^=WkyJl6Ha3nuPODv##dCQ0fv|$X<_g_x zm}OJAt6$81*T|t!N6s_+3!n#pgIzW~hsT4x0*ftxWBJ?$)h;~4QZUt51Uc;1vdP+B z!~IDy2W*P1Jp<3rPQk(Hx{WXRxK@q10~9(7yYZMuV0{>ET(^Gzf2}|8(DUo)>7D~1 z4hwAUWH;2G99kktJhQK8i(ML8yYBaP##%r@shUIS_rFtM(%}a1+=I#}4Ob=+?j7Wp zphmgAr+D?1VXYM$axrGaiOh2FY@Pu0huZlE&aJ`{1x>&ijrPfUd+!5v+5ij8!!k%7 z88YVY%czfKCH-IVcSTcy{`qKkWy4TDW1He`o8q4p>=)_Zh!-zQ*Uxc@=5gVl+@y)T z=!WvLu)nO-`LL!kV{Br_cjs0E2lmfyF#K*)(Vb9I2&ntsf#ZNub~v3hl?6a$ z_-o7Py*AN3I~q&*^8+7AC_|Olx8~-_sV03^Y5`WicX z6(CMfSi#ubwzz05iw|Bb%anqgyhdZpAs{m|v#E)O-$EL0s()%8rN-3fX&)?97a;i0teY zD%oTc!gF5tb3DiK`}24IaUb9N_;%kuuFv~A-{<){Ujts#_V)H+2UrEc(=(WC_C1H7 zWuR2jp`AY{p9Zv7%i%}HJv(gg>|9!0baQ?Vhx_%#qyS4@gOc$Ye9=#RbedwMk>6x= ziEhk`Y4#4rI7>A=op9kBkzBrmFM}~imnGhEv6W@3&2vUH^&aEo<4PRNm+*pBEYL^v z_gPj4t79232+F^9LaTVi6$WPw#ubAqwxl2+}u@2xvAw$;5K%xY4Fs+A{$r3+l^ z7fEJpr4}loW56 z{yW3l91o&6pX}n4fUpOY3qVM}abp3vtU&C4FwP-p1tTErn8(R9z>Zq>1ynMqQZ;w; zR!|nlQeW~Rlr89gp&5pN4&G}D(b3VsoQ4MsGw|t)b98h95gV(syh}v_45YFqqc83a zi!pqFLkOsn64<8S&9R@Vx&Q$20zBfDO{QL zL*6s+V_T)`9LH|yeNrjH${1b&yWeNeoI_sphx$p87e9ZefPui4G@ zQeST-!TqakKn~=ue8slyX|(^@YMZVwKt%mJYlS(syWYW|XfpV;rHR`y}CJzY`tjj}wNgJg5m(o4Glrs1I2n~LAC2EQIx(V#e6iSmuO0yWtran z{p%5A_B-rODc&kG>)G<)-|p_k$xf)G+f*9)D%4)Psa`Uxkv(#-2GY<1Z(@T1v80 z+~^nEE3ENemH5;T^a{`ieTD|N;p`ijy#o7ds=`vSDA)JC{lpeDU5~(7v82fj^l+$t z^49$i0Y318=o&gp@0o$qJpji9Kj2GyJ7$F;HoOP#!tkoQiaX??tC`ii z+%Nw9efHE43dp%-o2MwX_qyC6k-WD8t6i~VT<<}tC5DAOJ90;jrZP9)vXOnw z`VsbfQ?iu%_gxR)+ZNKAzY-V}&U`8nK_>zR$85K6kChr-3z2dWoPo1Zrk(Cfx#LO7 zQxWT24dK!<+2xL9E*&Np8T5OyRYL84v>_g8U;+;aq#30;+3AZ1h^w*jQ{y!9ZD{nE$Z4TvL!!U1*(ocoL)uM?2G>-+EP(VWCD?`LUb8o+%VWNhLtfwqZsugz*$jr= zyI*L6^Ng9*i{mY6i%qX042x7Bzr5}4uuRGW_g=`qwdMtDG^-ZBPa6i;-^s1Nkh(y~ zP;?1-|9XIYP)Cb4+G298@M@qR$34lCMUS+r*y7oP`2Ihx@qftiJ5P14rgDr8$Y5>*W|@pXE-v7xA?9*WJDVt9S8#9W1fR z1)2#x2RSiMuD5x-SPI$3`xyOfO7;C8#`*-LEKHO)Q7MW!P=ZmN4186YE_cuqe!(bj z#T(|$O)lmm6A}(4BIg~U4akYnmEIrRf!hW9`Tc-aQbJseEn&Eve6nSZWZs6ZPngY? z&s%FmvG*8wJ;ue%6q{hXC@M~13+xsjDB}f!Z2KSdOHfAV=)C|#PJUix#VE4W)EEYp zFLk$bhF-#2sNeNUf4lsZOAA7RZY>x8tCIDpG**s}IHxsraVV4HvbSZqf0*j=t6TaH z&9r^FE7P(x{CJ)CZ+k~MMBUsFRBxQ#;G-mb`VAW4*gE?wq@=**DCYTU+sxw_HWot? zPZl+bn?HPkRY~3qsopQ0nxchXFz+u}_F&fd+CA#GknfD$nwV^G*IeoyGY%$3+7iZV zjE{W=11Ff5o_y@JmOFrHe`%$7q|Lk>kmCnJLdjZx?P8hbVbuNjkR4ru4d${_^Z(cye7PZzvf)03@SBn`<@0Ex3+_ z=o=ZJe@~*?hHB&4f%x?%InPl&dHO9^QT#YfK zILoqeA=4H=dYwjkeC!chSNl45`4U|mTf?*0?DWm_Bz>YIBpUq8Hy$z@nLqWU9YWRb6i0-oaxgNsnwJBhpS~7EvcWirpl7Tq*K%vnwq=mQ(QZ1QH<#{B zycunA#^o4} z^9hXg*A3+~T}jnJbs5EM1hNGR^eNw_?imb@$WE6R4#;xuS+zM&l&x0&3Jd zquo&^ZTN&Z*)n_gM?6wSaVtloBE>3Td(%(qv!ncaH)48&PT1pvQWY17{^EOFOPfVu zLP3X=+^@E-PWeW|*`wl|{M>)P3AnuZ#{VI=Fpt_#V=5a2|9~v$m++AhV93=>Dy6(! z@=RNbO*H&uT$VEyRxgz<23=*GtQjvZqBVi{L(Jv|(rA1KUjj<$+WtE^5alu7xB+YV zkSuGyk&#@`zE;IQ28e4sB3+lFBX2NWne@V;?jbBA8O(N zlaC0eoQ0{P(AO_@KmOqc*}WUohL0>2{LCrkatmwB(Q8|_eK~<`R-;r-`*1m1F{i)X zyYCV&{D8Su)ai#9bX;Cuf_^C&Se)s6Yi$t^ASPQyNeNpl(5EW&9d&-CL*sd1j$#(p zy?fR7Ky?RER+NMU{=m)Am};};y`2l8JkxQT4;#FmeKnxjwI#?v1jsTmxOk;5cvVyG z)ZR9_gj@L~DnaTPN~bffAou?J;$lK!GGG%JkF30q zf}$cD8yh$+_j?dC|FsV3jqz@EZkU13vr_lui+oD=;S`{hfKYzNd5cz|v+>`~hQ`+> zI}7Z_W+ch;v_`kz5$0cgkNLr_v8QN8|6x*MA}Ed^B(QiUI3`vXsRbAfGI<`uw0~9O zvI*wK(=e@`k+!w{q$tw1ep4f(RA9A9t7i{BEYU%_-%}xA!NYrc7Mv`ZmX+rhfbqMg zB0}wzXveV3+Z^36WTCX^**NX>NqFG-xv=eTo|`K(d9YLdi59?l2(}cSk7u)F7yKY{ z>mIO2P`?>a2^e{*{kp&DPdV{4bj}Xwuc6E+d=7MsG?ooa#tav1>iiG@?v$nZU-2bJ#folzk9cGL7mdq zLHQxpmI4Pcux?MOzzie)72@&(+&}eA3h~F2H3R}mTC0V#sprl`|fJ3f)BAn^e zk~y{_kA5Kq%f%y-tY=D9oA#v|<*QVL0*9rqio!6D6!!69d4DYjw7%+&Xtp8S5Ig0 zFoIOsl?z!K1u-^;F(Z<33zFo2hE5w8f|HB~c}_AA?nPDtvYyrGXSi1TYpwE8WIJOx z!u$J|K9RgT6`j3C@z(kAe@#X>RDE<P}sqNX1fqiN^|I8GWPk=f9;>YIxxXL>>u^ zU;6Km$Sye3@b~xcBI~z0=x6y9o+EM?G|D}M*~}N2G%t5*wI2oN#PZ5jQOvkdl&)54O7X)|C%YS^o5UE>WL`{o%9b$Px z6%MxdgGgDmhO=zSC-KZfeYmOwe|D_IPhY9dV!2(}(vpyI_tuKiy%+AZn~$UtcX0eU z^KbPhIZcgkTPWSU>sM9fg4~Smn%@TRBhZu*Js<%ZK;g3oNl`ztX=x2!X4Thw0YnCh zJ4t?;ro|+?S@0?3`2AKlOu;W8WW_BU!L>TUG zKnlU1rQ>lWhe^}-Cm-*Cn>PfXfQ34yv^vV`0n&x9zLluBr%1hSxsSe~`_v#`FLu^3d_#zuJ|2|ShxE+Pf2K#UW2;kL9j!0V*KVLUE7jjz(i ziY@p+hxO%#&|6m?vDj-aj*f(3_ngI!cNRMK%7q@kft#(w>R&aYu~Crb_nYW--@)~Q z{me+o0@P!9$Vw{Yfs{J7nx6jmk=X1T1d++OHC#x^M+=d&E$wc~L?FZw1j25dB^1=? z#UB&)C^$@(+{ZO5-Vc8`%jmpHDiFQETWWfd;}H>}(ED?{HZ~tD^)>bM#Njfm_4}6k z(JqlcF}(g0xT&X$&RFnlOjg4FWxZc$Q%eWs4=pS#!2bFio(d$07288-u%+HC@bZ8h z0(K)Vf46?t@QDIe3h>1dY^)(c!JuRe`T*8W*i^x;!We>lP!$wlw2)bFqu#1{t{K#X z?z5hFEwFHRU&)Qv(a}LIL+;Od%)`VAKK{+1@_}t}kVNKiy&9mzaSPhFLQ6MWil)LL z-w6hs5}jl)41jNYbbQ?XFJl@w{)5UY_4Gv=1f!McoPhU>>^QjIhyc4sW6ul*c7Ugz z9^l!I!onI|l~hi)0VXT}TVj|5z^T5y)CA(!fX@T-8-1svP-fvZHp7&I&n_;^!gOVal& z>0@S-PS-WZWrf~Q!ZxOrq30({ZVU{3E<*Q_)Duw~!&2iD-N(9& z?M&qQ2R}ainDU2^*Q8MV=oBm+YnrdseXbfCN{E4uulClfrA`@@>JF2~4~cL3da3aaPdx z>>pS|xvZZ7!D5o}G$%SNfM45#}%y^X+uA71(V^8*7u^;=x!;Z_K- ztejjwJfRBOE*f2I=dEn$n77@kzeZW6O6WzY!!}$(c4A$9AIiIqOj*j*y&%%C$QSh3 z&Y87b8pH_o+sCk*7!2lBc3-_UyL(>au)a|8{=J;MJme>p_mvhDBtGyxg8>O7j4Wip zb8FZshKsIfw7Wv5Xu;DsZb9ch*iv`*_G;BwP~H>~F%qygHl78F17t#2=(*Jyf>EJ88hqP;gkw-{9@w*x1kf4CXbDY08Vx2$A13W#3jFEx z7Yw%`ubakPrnWcf9vdfT>HGKZ!9bgn6No343WOhh&(9_+t*(-jFDx#Cxd_$U4hU(@ z)Vq#adBGkGj*BoP`zhQNJ^MQk6+@#$2c@b3r2}9PXe=8+Iem}1kN*5`CyFb=Md1TG zAlQOyYHFU(ouBw#xv7MpS+H=`{DVIw3jiw$A}(h~pmslKt{R?o?f7ufJBMU;8A92nW&TpLUKs@@`9>s(h zVqVaP=Y4IX<-)-fRR4|Onqp`VFJal z%HU&V?J`%>9UE!?@}->p+9gpb^}TJ;uNuQO4p#IrtGUvZ2+O`W)4SI?Mb!`4p&`5- zdz*}aiVzq2w`5QCEXwqjFLwLdf(~y7=zsgXxF8-hN0ssfQ=XY}LD=wJ)Kw>pCGz8Qx=4$=SlOQvDzT}xF zo5xoiwe45mB_*vo@%y)CkiKMtJB6yz_#AGMwf*CTp7?XH&wA6ud?1-rQ8D_~fzQC$ z*x2QfrH+bT911GK>V6=B8=USTL`*G;+45F*S$Z6Y{aS{V(-dE&VOUudz`ub=A zkG>IaxC1~tr%99HO01@u+6R}FAzC3f=9@R^1fEJAHROZU7?kjh9J-PzpqKF;LgXK8 zHQ)kT`}MzC2~HRPmL1_+`0R+fg^IU^sHlU&G_w&Y`9YU07P$?brx@$M%kMYFg|dIk zkt+`qwy{WR0k4FC zZID=H4QW7t<#8MqR0)WR&e~Q_Z5%*+3d<=iY~}UhfHGs%v7_6=Cy*oVdhCLzW>~&FR&Gy%?StBKf}EX4iP}deouA=i%Mw-j@}`S z=p1hL^-an{;p$?&;j^@96H%;2$mLy{to)R-@f@ld4-XGS*YVRBS6QpCYXUkr`P zK#EMMMgf|?1*a}$F9+7@mCyyw0$Yr*4c?8#iXP6B#bn2gUozl>5?di67B*c?pFaJ|xnvi# z`C$Pig#1TgUeZ(11!xYz~`wvjNPHrG0r92gBx8zUS9o) zIbvPC*9*hn4f!Nq8&W^0WGV?lbqRQ=u{gv>_(8>#hufkrWtyXU=M6K&bV!31kvSla#g9UgoFeD znLxRUA>=0`*cPTg-GjS}nJMlNG5LT&A~gho5huThysZ$`+_Q`Z~6sz_`RfMP%B30Ad@__|(BwO;|TP zXnZE*n9#RaBU**pvYB!LGiYW17-(!3z}KdI;gZ~^1B>mAMrdB(#htWIhCYb_+}ePS zMl7xV4@lTxp7Zl@cAGgpv~Z}$isk*cnwJT2vkST*z%168yD!{z4F&+<*Qn(0LOPxS zurh&a|M4zAi66K&l^HeY=t0|{2*WOG@GD!_X`)HgwdnU5GH?N8Kn zE1P>T=JYg$>bTdhe)f*>rvqSwHIC0d>o!h56;2P%^O-vohGZ|7q5)?b`KTZ>v?BVK zuI1TiWWC=NXEhI!6q!sJN>x%%X@45|ED-BKm&?w| zYGY>yApj^{5-@)7;WGHHJMP+3VK~l_7Qr}^!zD3Y6K0Zy6K5$Ol_KoPBmPfldW%b4 z#7XKjgQn0fs%IfjDUm5Ot90$X(`Mu|Xk|Lg%VmN74FVERn95LJKD40MitFl*1IZRT zpE`eoK8U&ckK+v$=?(|S3=q3BErsdkY8?Z))3j2GMO=JRGowOx1FBQC(q5Pci zFh?=RgFXd_o8ShFmcO3(JF-HMTPkx%57L3vjg3_9M?vg873|p&TgEd=w4Kf{D;w=` z1w(3A9-s_E4Gh(P z{~q9TC@H#j9p^gYcl*=csHYiokXh75S9mzl@6VjhWNd+b-Une`cw~j6nBqnvj!-5L zKZTYp;Rrg(EQLU%1x?At7N-n)`G*49+|3hg@!z|izbDJq1m&Yx5SoQ?1fP%VM%K$e zWA$Ddymv7A26@Lsxf04m+m_cbBpo(>QoN+$g@8F}bs7;b7iLl$TiYF<2c#jtcaOAg zLo&o#eVrjuVB-bl) zUA4R|l5- zQkM(ESxt@3_&zX7Xx-`(|CoIQZcZ5kKDzve@$dnGzaLYC%vr$fPVhI3h zFbZ&@6+(tm`W?A6=4&KF&i3gzCgO27yjM!1;k%&WMa0j%!E0jt?92q&M{c)tRQ#Rm z=jV`CD|TcRD>r3*MY7L9JsHo(=U(-1D^HH=~gy1@rtB>_Xx2l}oEHm)}76 z!?V}wOV|8tyMJq#+9l=f=M14Wg4pCc-t8m<-TQoWcchu{!{JhpiMrFtdxwUI{#h?K z*7#L+N_9E{eG2T%A9iYfW(oE6^)J|<^KHFbfeh?^!DWI@-<#poI7B8pZ7I{-DAYT)f67swN8p-?&9t97IoB%+dLtY&TOa9 zD#xKptuM9Hqv)yNRZh+eA>b$Q2eFw=Qji%uQ$318XT@P&{l|*k_mm%nXx$sQ7BrZu zWFyLmn=P5;gB`#Kv4FI29mMx6Je`DPLsmTE^xgSZ23bPD0}9-LNj4KqlL)9{MD-{- zfY-b$`L)$BMUHuBV&ZjZ58=kL{P(3D z;!)S7npN2}#{OMqReS|Mi?Y{=p{L8G9#ae_5h1VWR__ zuw%7|tOz)E0jiD|en6cLnCo(?99Lxvy?a~51AQ!ni%vn7UDjkXauskXUldcJT+)iU zWvydvi$yO_#}Y2NBE=-9=iO6!#dH)&WHdANOwJ z8}J%>_~^HnVN}tg0Q$UgR4V*wz6Ttr324+*yn!2AW@X~qU-g&SXspmPl2As+Zr24wTwXC|YMwQjBKBC$ zko1STLbm<9)#W{LVw1DqRTRtnu7Nr1c*M1(35tc)>FKB=dq+oA+2Mnd3g-5nqQn#p ziioM24I9r9esxk#ju2+^cOJ@(s*10&No!Uw=xVd4eu?*(rJ6Q4P zaiB}cILmF}h<2iwdjF~j_&wPFMQ-C2{>BHZf&_-w64h68d>DKqp;AXhky;$II@2hS z9tz(%yvFhNKRSP`kBI=3ZUASIE8&^WhWzJ3>? z7@$N4VOwme8_A4l8&E|jaIGxM@&9Hs%H)2eN=F_N>3R0=;?YpKRB7Pgl*sqSo2&%d3yHv|bB(`AOv+yML77w*Z3QhY&fVJpA4T zOJAk|E;<0{x!&0GDMne`jJ}MW=@_lXRGF8{TAZnYT`QWSA#$Z%sz=hlDUSg#dwf z1aUj!chBqfj&lpnztT%Nsd)9O?jE}VK@r!IKROLbVuF6G#-WluOa~J|;Xb&Z3JWdu5V0ucP#WL|+epIU!0ZAH*i;EE6#ynhB?mfYlX)uJ{9{sHrYVVDocbdaz=7WrTO5Y*PG_FPH+eSO9)={? z+S>ASV{#flq`SV2DDjk8=U$c{B-GZ#5s-@tXip>jZ#D}GFx%S)yDX}v)JN#=gZ^3x z0k^a?I-*_(MjL&6(Wqx2dJ?0DeeDM(JMxWe!OG2_Ec)THLSBbziXpApl^Z|r?9Gu^ zsK1_(b9H|hH>wqrhLNs+gvxPfg=3Y#9>O-(TvQ&Kq7( zLV$zCa>|_CN8nFF5NJQ$|F{xZeZ0zAU*k~h!f?FLf~USTo8dCpQs30tz!`NbXAjF_ z8F$6-W58D@^O=+NN%#VICV!@L;|q z1JD0)0eUam(Np$*<9SnvhZ}I@HT3OUWZz?AtMqWjeBkv!Kt}@CPxK{6A4B7CS#M#| z3gum!&lm27fB&A;f8ciJ8_}$0M3?Tg7xLqe@cAn*dZf3vBTkqHR>+Czm2+XsCT<)*UF9rGGendJpY zo*Js+j_z6q;eXBA`k6m{cHGhM>~Sjp;hQURzxNpTZZxmI^pGcEcyB|Ez?hi^Fj5|i z!Z0tqVKu2ekYFVF^V)|V$5CgRk(=oQnq*&`X?A#}DTBm^tJdn@=Ug1vWeMmw^qH=~ z09YZ%$2uwKsTr?w&*MrBU@iVKtdWh2@|3>r(|7k7bKA*pr$iry$XWENTl8y1zke!) zipg~#k`wQ<1SR+s+!X<(7|;%^u>X4vD0_`rwREMw=)CKF*JG((KKgRQM-~qs^Lo?A zW06khZUx0~k(F!NMcvnGc<f`euyhAlLi+bTyn(^HiE<&hohJHUAq#5(y*Jl;bQIdtBzy6jbrFKM_SOy?71~nvW~{3$T01yQK7Xq{fQgtgn{2H7`2!kBq3P$hWg?dJaFLpt zeT_76uB@-5rIuNAuS&cmSi3d4mS2cQ?=V=ict-rT)_;tZleqBu)z4BRUme=0V)n0NIUH8K-Dl%y+2tb&2V^dW%C|vB0k~ z%p0>M0rZpM_l6g{!^CUyLbJX#AV>@mR)cMm6OF7onT8}d7%`L9m%?1K`ZXcXh7$Ki ztXj(}?D&Cvmo_!m(H+8YdYO$!vB?kVs3%gth(0Pqu~=aJ@a1mo?vt9lb*#rY3@ zBG&7rYe{)4^_-o~73}Wr?v)ZCUk}g46tkJkDP0TAn@(#bH2U7zGQv#uVffpJ%O#!8 zP$!$X3=3uXl2h;5QKa2oe~E%;roVoI3UnTlPs&W1)ACk;vjI^5Og;o;fg{sd@7;k< zfR3LurHi--{E%FSp+Na+2oPMPL( z4QuFX(ac5Dq{pJ^ct~iLd3nNGeNrC42yvDo1De`t%<`ec*tACddoT^I_8pTwGo9*8 zqkVXMuS4JtWv?iYVPU5(Pq)ukfgeQ{dSei!Xd}ph0yh^=LCSd<6j!R8o;Ab6DmOeX~x3W59B;&1jo zp!fK$HeTPs;5p()x4+40b0fZI@#!R10@k(qKSF{YrDX?Xe-6E~H%ao6aAa~=ND=SQ zJAV?^t)FZz>y-GOE8NceST2C>uSqG$+bs3Q7WhM>?L}0hEE0BH@#LZiUwLq(=Q7G^ z@cuQnGZ5;+&vdewQ>Cg)1cz;O(1qCEIuFVq#!x1~Fc(3%+J=MxuMU)88O33x4$Xpu zTe5GL@v(Ul2?=oJZ$<;xnWYOS zj=PE2&o!OOJ~)1tX9FUvR?{swr^a6sUIq-Ua)YzI))k#fDexm@IW$0CR@Qto!)DivC7cIi7`0!a(4E1DkoXh3?o)wdLmXljgzXoCNfp0y~!Vm*dFc?$9R^$ODz>G z{#IB>s{%F_ZyToH(n)>k6+^X;K5e`ghOrq}qj3EeJj9}Xe3W~_+k3Lq@5YV}36y*o z2oDc89E#3fh_PC{q^r&=9!b@jj~{>CA>7hvIz#Fv^E2^xU2N1bUn)HV8EK3OK!&(^ z!kTT+?JcTGf*m?&O4+e1JY54~Sxdcf*O>ZW^-ly-WuDMN48-yd58)#{il@h0KJ+-? zm3kS0Fv!401Q`+qb`yKgk+*32Kr}OycX5*U)SOYKG@ask`H4y$I}Jr_dc(X8C?l{TLpV=dPLQxWK?qTB6Pz(k_Uf(INzB>D~TT54gf{q~x>sn20Apw)mk1K?cc zxx0wQQv%!iH1v~PluO&C`^?c@Ca0^qC!@~oVkVYfqVO;;(xU}dK#s_Gk&>(mkGG7@ z1(W@veHJs*1$Jbjri7Xk`D^R`Q>U|neXdtqOKVjNTS?P&??bz*LEK|6@t0DUw30DD zv~oWpC6C5r9p$j5FH|lxGHUIP+6&0-j%)>?^kv(mJ%@o^kMN%YGQTH3 z6}o=h_B_fhTuvrWzFF#2`@!By{j`!4=%@9-c2N24X4gvss*QcePi%9E$mx(`hrut%~|eb z%Tu1{%W6k>Fc!h`gzN|Cc?k*X4sYUxHs5~&IYL0YaVqO;`b@J`ZK-zvv-@oh4isZo zR_+7bfBgG*;SZAqutaFTEE~z}2`?Zp6%S3$kFV-K0Ouaw=idW%o<;_X;pp1{Z@$B{afL+}e0|W2 zH|?fwlI_S{`~*2=fakJvaEL6#XpWVE7C0&IC_4S0#lOGX+aBIPzX0=NK%?v4%{}em zfX4;}$r%KU>1TWS@TH&b#5c3AZ$K(5DsK!sL^akBLYe}&GO)Me<4wSoD>gPZfDRKu zb37oc4^S=CYyjwDr$P0wb$|s1F-HUtC{R8Q_?+BSP5W2k=yP$j^w8(LwBZkYSTrF6 z{0-oJCBXIpdw5;Alo}M5>i+;HUI*rE9>OoccHbCsMZoNW{-hdxTTnMISZg%X$`bCq z6akBz7x(?(M{WLiFo+()qhk`nAox$;Qb`eZ{`DK4U?zhSfG(fT&l)aWx~9(8*{T{e zNQ9B$6oUzhRPNCW@^Ke*Zaz%>74T!ymhTcmGp?I9#;c5cus7)1U#)-lXGLj&cj)-= zJz4Ue+8^A$OyBZI%1fakuU$Ica9j0KJ{zUd3{Tc-iw<{~jHw*t-ld}cd72akdou00HrZ|6`syrQf{_W&Ect+^?-{D7GCaN-W z`w85SaM4vFyp)CzJk(|J^!=*<^kK`=x@s|#3cxLat`Ehhiw*0dPME+2s#Wb$20aLQ zT1}nkuhI7|lt6?YtVe<9Q|r2>6UFQZb?K#pDEx~+fBp!>GN5U}PR#puti)PRcX!YU z2@XgYb2a9U$3Et%qyqnT1a6XviejvAS$-`i8Yp$2fQ5+Jh|+rP?ChW^Tn6V2;=pqI z*-v`vF;Md;4sC60&`c|^{u&w^b3+~NAS+3Zq7MEbYHI=elI)@)JK$V?!MG08U^(DH znw;&#!*av~h~B!!o|fWj;OaI3s~~};6ix5fz`eDH4+?Zn_!VE8Q3mb@&}B6>odK(S zWp%Y4UMBDhjPUMp?}Qiq16bt%Tn_uI4e)})@I!Zl=-L(7<`Ay51!N%#{j6`9GaLDJ zbpq)F^sXc7%M0qVwEMvJ-S}CHH|NYx`BIhlzYewVO#+~S&^BJWl%C0*aSytcr&VuA zvJix9t%0Ie$HY!1ia8{U<=p{oCu6Ot%Af+1_>E~hJ+}uB`0*xu=i2yh9$$@qKOfGb zD3v26C1Fr(cy(#FHP>%UoG9W zGh6x)DgXJ}+1Xk6j)W7Hn2aQctKigGESc$142iS%KnqgA-o^!>coqvlLR%zrhl7oOjnPa~3zTG3z!tZdV8F#fwlF7Wm-lHLrU@raghCmX2Fy<=~CV@II zdfC~qn65FbA9gNoOz9O5fJrg01;2m}*-D=K2lF?O7^lHV548fgc=wf0>=m~*pwoKH zxQ@HJyQ3^@g5b7>8;{U-V1Af*oESJX2D*o^461z#K_AOGnQC%%ue6M>J5!HR>r zgT?9^UuYnHB>r!|%vWS3C%Ru?i6+Plt*=0TW~LB6n0N$hThO#!3VnA08?!-Z8NS{| za2?EOa?PC_#S_ zdGXj-;752{tK5q$ZnQnOyhTZf6Od`1c%72)EgY~&L(VXQR66(X7l0hh8G+MM?JaVt zbb&4PhdvqG!%||zv`7<@lmVb9f3!wG+!dazF+CWqa;u@ryG+&j$AO5Yv&enNTI7}L zcAyh+hCuo|g5cS)sWv>O8;tKgO*^dmwuEg?M0non0JPZLzJYM zE+<7RD4H{EB-`E`Zt$IwWgvk?de71>TtN*D4f**nV-NGfM)m~rAv;@gU)CG)93Qam zGUNwf z*D?fqva;Y@=T0msWRGZ9kQf}AQol!@%Po}t8Tz%m=5N0Lj%Jom$^&W5GuWA;^iz*v zG@5(LCLiv!(UFnw;4c;^I|gJnG_xHpFJOc0z-@aiaPqLNW&_P7CA$X%axgpj^Jf`b zd`lX1f+HhZ>gwf>`>2uS)z!k%(lfB-3wJ}knBjJWu`2mVeL-X;>VokoTp+KiYVYgy z2q{k*NC$#z*um(N$2O3ZFdE(ncSg{I5$WHK4jBZE56o9i28D_n#OZEMl+S0}VMfFh z6?>o)Y_u7^*~SHY#O>+1Gm5%L?ep7!B!3R>S@Q;0I zexZ&K@m7@2*Vt@6>5n72VW{r|>AkZ~ZI@69hvVYS@te10;X&-*5a@f#L5qAhau;kY zRIUwDbr$_XZZ6WoEmFC;DByT3NS;-Th?9u+?WO_6APvhP+EUNrf?ixvVWEe>x@L+Q zWef=}pV*N7!<<4ztZW(WaV_1>tjlRnMW!kL6}u5D$Z;!cs>c{|#w+AT9=xPLT3ly< zf`2;{PyyxPq&!O=Ds63na7m5V|B+VuaK4p&n&;26VPcDfWKj=_FI-AM(5QYCX@sv3 z3Q{afJstcHnNK6)pn}D>W44MhkQ5iQuthxDzzU#Z4Eh)p_JAQnQhRjV_&F+M{la}Y zZD|IGZ)l#|?bsx^SI_?qoU`j!;k%-`lEL|HAPCGu`J>}s6M`NQQle{NzYWRh!S7lS zyHTLkp6=y8Fal33a3@49>wuJy3w)FVpK~C!!BYGX)y}~<3I7*((Cq5)Md%jvOwhI1;iG(Z~g&Mj}9zH*nqnWt?+oOZf%TZ zU2g7z|3%K_^>s)#L~quC7YBEd1n|TA&$8t$_$1WWAAy+(>T3gw=J?pyOeS`$m2sG( z8AE?Xyx7ZzHdHWt7p~!1`1PSix7g&T#wpzd(lG`5LqGi&A>WlQ!%6jpGm3INz;jmX z7EWNf669llJAk41OCm#GUmp}|mcM9VcEj_|gNv`~pwWgN-~s&Uq&!vrpRYs+H{WN6 z3j(-uA3Ud*839adf^oS_zuFd!n&*P@aGIJ6ACGZ`03o>eJU1`zCJDa%#0Lz$E|5yx zioU5#JqD+{UI%@WVg)P|VYDzC2Aiw>H%wU&7Pq!K8*)*uudIka>uDp=Gwsy6h5a%j zj`?=?ujtkNehWtftHXn)e64Q_2I=;`N4hhrO6i8rGku@P%e_xiGuESiGW7`q>ClD> zH+DI+U28ZDLHw5Os2a*RLk4gze7qwnQ60i{{c_Ffw3k>oe~UkdZRwQ@u~&4GH&57C zaBae3{K<0jDyX|fwpqh1^g;)(muna(+bQTk@g$SiiCGXc9-W@j#}AbpbvUGDHp>~d z(b~vGy!<+MKb5W_5Us_4A7{C+>#0>Ftxh)X`pyHR!Cw?+YH0(tn_)|y{hZ%aNMHw} zUlYa5O&D;y2j3rzJ{_i0@KY#xs_jLS85OfiiD$aV#CKCz$j3dYh>kr|iR$8S<35|< zkpNWcJM?-eq7E1$_oEI#N;D@{PeeoCAbxO)LGT9~`2!&Ai8nT#%xq@a*F%)GE0{2# zW-Z%{XW-7p%g2Yxx2#fK$6!fM9nlG~m!lAC{tw!X)%#H}0{_Y%2L2r+#S|8mdO@S9 zDzHE{up4*BB)nr6>igLp-y=mE8&>2WI6WLfwCV{6($LlbT(X5hqJtnJjhp#id(USL z__yJYAHrQe3}mAV2>b!><;-AENa*P5x<`)lk%s*HA+Xn4L#x*2-@{lSjhiefZO7wxml)+{dYdS~Bbd9#2z0RucD zE87XpPUvVZw7ckw3Z0DrC@WEWy1jz~c*P13^e3RQBEVQZpjkfNUpvuO3F({%Rw~@N5=*9Lw z*Fn+&wc`ZLQDFdU+Ax~Qyjqk?WkX9c-m5u;#DZvzg{ve%VvCVXN=HTgjx^DF# z+h%H4xTiu5yTFWcx%KNGK{^SLgaG;0%;HiQB%wa|+e%FIGZMWU?((cZDo_Vvh&N{} zo)XjTTMA4yYvVC-7chzA^zS{kFB=hAmS9`9~No+Bb53&!<-S`}HC1bI#BM84wA)Z;$D-J|#=t5Kq$vX_c zwLjX>ykJm9MN^qndnetCMN}JtivGST$YUqr=!uf#4qDQSdmG0*;vLkR*T!i4j7o4) zQoOFf&ZvvXfALWF1fp=D@27sdBYX!R^Y-8`SWtO>T^<2lVTD>sLFpQM&+SnEKMiU% z7l-bty){6%2m_Xm{Aa~UUcnyA<|)ms9v)In`)MFdEvzQxh5T`{PI60$%w=YcoKOo) z*chr{4Sg+0x0fTMf0DrOOzK5EuW=`#O!#`f*LQ#<;HzQFX(SKBfe{q-h=k((A9V=O z;J|ROi(y2q zt^=<@wC{zlkg@D>Or;aF@0mY%=ML394B*80{_FH5^yU-g8p}>!eObXsz?p!28y&5V zn7owG_7=u=NQ?tv)i@O>7YbdGc4FF=IW>9M1R7wE0+MNuO;q-sMZ=q({V5|x& zw#%|KgN{7DK(XY|uUc+CTWbbmH@e>pLLk6|kNNDIAZu=JZZn`Io1kU4N0n1Az*g*R z$@gq2BN&|5SG9GGTtRvQwv4u*_hb3>sJRwUGtu*Zy8z~JW zmaRJ!A5;pCYLlQz#35WP#pL(1&XI%YAs`_jA}vTRok~iVbcdiT2nf;=f=aj22uewat0Gb&0-_?4 z3P^~A;QhYmfA7qlxtBR-=FB;B1a{y3{l4)$pJ(eemt8~CI@gIpW^Qs{1%%R&vJ2yj zC?U$%_@2nM?A;d)V0$MKp~Fm03?iEHD@{$(4V@QYpe(Ie08#t76$d`Z4PwlOfc3*^zf?)d&ouQY-uEYx_sD<}5TM zaO1J*3G6EL^NsGY$NdwQS!Kt3|LE*18=y5iC>}wt;cTI?D+FsJsGk)E+iIppN27HW zam15UJkV5HnIMAS+wYadw_g})BKK0K73qiO*Ry$TrMp37L~ZC&-a^{LDsC!kJl@r{ zJg1+!@D`&s)kH~-fh5+x?fR+gvyoS|niy!TSt_QzU^*BSOd%An%2$_j)h<&gdBjf~^~SqxnSwAEUSd$blw&Z+w5g46l>$&0v)LzC| zvjMHL%hx*iF|I5I!2@4Np3a9p)FA$*MbM%vR3X_k1wMR7aLN)5A`BUxsm0=!8n2!A zKdz@5vT_>BU0=Ur3lT!!F*^ZC@S@rJ)9cQ&YS~N1KUR!&t=mtyc$$$k#!$}VzWg(( z_atOrZdwv{#F9vZ<5`smly;DcIKLe!VQXwWzPP%{yP}) z4J@yV$wQ+l7q;m6UfkSpM3?xjE7L9QP1RcjM_)vGWz*j1tA(DKjr@;i(s+sJhkv}G zoU5ANpz@1N(B?hAEysm4c!pvTMHhQnq431DN{Wx>$3x~i>cz*JEH`Z>BFHn zp3>KPs0FB^AZr_S;_ehl8sij)eHdUsa4-QiEgT2^4H0PRY}?shQgUly_hvmOs85>| z$xscD*p>EBcxZ8+G~M)GJ?;I{VCL^2^%D%cRet#M>FMtMZ68{0|i(x zgKK?wa`NibHca+lytW7b8a1hbDdI1>)B(RINd6KP0C@$E^YCZ1Fnaeub`u=Jm#}jK z=f5bxp_k@IdR;Pcf+f)A-+<5c064-qmQe|i56rn?;FUAD0A2J;zR}pS$}#BF5Rm@UAq0_l;9)4C8E*k2+~YR*~Vhrj?vm?(~drMwwSak=D2` z#~tx-_h(T>f>Y&!C;1wVnp{?#{Ed%&k4-32ozc2tWHmYYM|h@mCnZn69Hif7W=}+f zneP;`H{pn|1Rro|oDfkrg6WqNbKZj2RGDCcvqgVHpp7O4S49FmTp-4EHo_k1RZbIm z^^5$8S`jt4%9GxFPvd*-XU%tPX=Me9Fd8!VtYUt>OV>6NG@@=cF$g^^Z#-^JgA`$E z>Z}XA1A};&y+1!&ndLaW6}Cz-{4ct5D$O)53&b_M2@)gTWzo`Y=#2s}X&BVQkS8y2 z1dqNUtMkVWwtdkx;f;R>(4Ec8=wtiPd~aZuJck)6xG)S4x40f$3gTD9!`~Fl$f)fwkH|X>lzTlbRoolRuov`R7w%C)1iN(zQvYb!F6U02%{bsM@WGY6c;;d?!9s$oDtnGvOF~}y0 z8-2KFCvspL)sSh#&oa0P>LHw>p^$Z;VFneDToTrl-`rl?2Vt%sS=fz&BJs|(J4J3& zi3SZMI*+hIvBxaMDg|k%TV3Z&dqqDe1(ydFD3l4!dSJMXj%f(b+N&IYZzt|{;;JOT z+DCJ~iI?`|s#t+cLhd%yb<vE-x9L3?6ukZG zln7d|JqVt3r<5FuF8f-8YJY5xXqeA`jB|>Ml%yP^{#|g3se+t}ge-)=+LzRc z{@<4{VWf>jE*DAXUdt#~(-f82d|Wp0?uEqh?hmYQ?u#FsxUoB1Tcw%AW^?|evS5P< zS&=i{fOy{a&kO7UHd6v-aWv8HOHZsuq%BWXi^#YbG7EgjDm!qSZDw{dSZx*SZ@87# z9GP1lnevTV1BNjsZ5+hHr-&$-ksW!jc!NlzK0V?o`Xjv4J~wyHRd+<3Zd8h`r?k5; zY+?vI7{Js!objOSgtqib=q>MOpicPuMKQa7weSjF?jb!HNfb8>h_SgCq;=xU9YYl~!9*WnQpMIA`L+r-_jtGTP^npC=be zx%z}GL9Y-&&MIr0(wpQPnpztRR3rydnFnX+DFV8noPkUj9GD`&*r59Q%H}X+?YOz! zR@)vl=0sJAs{I9$@XWUJBDqpUMjXG$zz8b$`pg^LFZFB5-`bh3wMY_QbXB}3zDyj} zd>_75-EyJ9VfU_y2X9V$q*~^8=Ul2wS3iw}zi#mklgg~Axlf05X_E<)5`0{4I(NNo z-T$RK>dMEHEj>Dr`=cT4YCJD>l!;Dv-jZDKpn?FwlRjQ8W1ejwy2ex$6zq7^~ zd4YpEiWfupC8?oQ?R?IXN~74w2n#6#)+WW&>Sn#|Y9qMb(?x=ho;8i%uhGi5<>*{@ zVS|}w=I8SARS%Cxj~{37!CK7J4|J|7jE2_}+;gG5$?OTjQD#=FQu+$1VG8=N_YuFX6y56XQysq47st4S@rR(PFgyZ~a z*D)OAt?6vY$GYnN@_RK+lPw<_@dP#e_on0Jn65aF57pCYQ=8|y{kZPcvfA2?ISz4W zr{R9hMEHr{BXt3CYEn`XRHBz8a}?e?f@<>rEBNM4eLH;S#!PBIj#TLFNrsP0jz1n$ zbF13=O{lEMCTw2XvcU^msa$gYNaiP`(028W1(8em#Z^w5ePV=TCvTUaG<9d&lS)y> z+CsLp)Nf>rj>M!db@P!3qDgv*PWBSk`Z0oTqc|L^*8afT~eLi5$r*3`h9X)7tPhLWYKNXt&Hnpw~Rz*;z$ANok9FdzndLmx#&~#ligXRYr{SjF;QTk3)6qhAG}> zaGpbPB!(acZdxF8Z(jQTSj5#iC(CF&fgsfyA!Yd?Nb&CL3?pwahGqz9Uf-%c-)H>c zbyJ(J+Y05{1K)4dCzQ-VJx6o#E$Al=D2p@^fxRl@U$Y{oUYLm5vD6OxciiIGU~~Vw z_{Ko`ylRbRLdIOs)H$a3V(j=WDZZqwNqXbbnyOp+J{RZ`9njOzWc2Z&?0e+_>m^K?GA` z4UTsAT)~8NzS2?mgd(I%oNlU_Emq}a>8oepxWmrb=a!+A$&*IC&0c0Jv`>{6XpvVD zb*aC2s4jvrsw^O`@cPL^9;0LU7d@r?X`w+K!Y`JrkIz&niB5D6BSX^@S)c1`&N>E# zG-FoUpZ11l?pc4T%d`u`D8gVwsP%`Mr%mevDl2{Z&MMy{#2Gjfzd6d@qShuBYz$`NeZPEEXC%mU`f+LK8O0jG|K9{ z*F9v%8rSFI(LQ_Bl0-~XIHoER}1tFt)y zb);$D$mr$v`x5Q28h55o${2({);uedJnN*h@tEhYb6mP6XSGgI#bWqomhC*6UE>`X z*`nBE(*mX$7ie`~H3p^ePZ!+lUkIq;pKnNTv9!F@_=$8#$&iFLJiduRg%O@%RWxR~ zLXHpA$uoVM?O+JYJ$3s1?GIqGjZjSGc3`ELJTamItvCMI!;4UTk`IZth`i8ev;A?F zhh}xLtpq`aGMD*1S4IcNcef^2K{dK~T>jQhr!a?-=+WfXwrXg5)kzStEN$US7xo#z z@YMO9E_?ZCyc+w769T&T2tOL>!PpCj7UfTpp`oF#VV|LTRA?&Rqp5=wGgw>UJP2@? zu)fXCxGo9)iNMT`4|yV(YW2W7x-v>4$5j-W0%Y)T%#0I81{b;TSjc> z>$b0Z_~2sFry6|B z?Im~9H>LZ)Z*DuPmi0YyfETR6X_e(QKbpPz8+7mR4EQzYZA$8i@TTWg?j0R8RU9Ne zWoXH>A6z>}MnG<2s3?wP%{|8117ym{^v;ahg!F;3IJaz=-uM_N@tgalPhTz^*Bez- zRQwOJy>$%w7VwQ!8G5kB^5LO0*bNEI6Tlxky+nf4`~V6}-U5@lN;gM^F5Oj7)cRi} zCus5cgGHQ@1k+=Lw+gr=GgBcLRBAshPoC3TZjJ~WU0O1Eiz%u3sj`6(?&`}`o}b9n z3AvWVo;gv06L#YQ9aNSxN&CBp`SMESHK-pWqLNi?%n=ymFc+VI8Sm)QmN>^Z9lihT zYCxG%s9T-z3c6fnREK*C=?IQJW!{9vm^Nt(-$VZ&lAAC#dDTEoo_Zubma5P_iYAVc&~c)5cY=* zRp)7&YE3v10t0LzmGAHj#)dis@_Za0zEq_X?I9gjQEVSYZ;Y$;}v5 z8BRm6wp_}LJ+n6-Z_xRxOr-y4H+HT7kLhoy!k;WQ95>0xa}l#nUM{4HBB)`Aen>?V zZ)1%Kd%RPC1#kYldt3L`&9Fogfl;J6EhJIlOxC7CtzZ*{!s5fD`Yl>%WlO2$KVsF- z21;>%mwHtF=&r*@(zE+orN%ZkHZbFatglT4i>z};%nrznuwGLX|M`v$rSGd>q!^LW z9fhoTXau*IGh|d(dZY%d#Q=pbW z)3^&b?IxPsk25R5q|wEe^;nK0_qF6gnFzs}b0%hH1Aefkv}y4c{kgu?FP(+K?F_V~ z>)dcTVa)XJ>Ta+{>#o>6@p?9doBsE+(_xAxMn+4Zs`UBTY-4O`!g=>%y;@1rq^nI7 ztx9L+ZG-fWKc6PhTV~ucPds+9X(D9woc^VkNvFSzq?J9SE(|ECDVNyzEvwd-nX^j7w_LuX4rROKq zhu(tLMNnW`3i1&`UOGrvWI0=idD~fJK|k*fs!-U+S^#RJ2zYq*tXe!O=d6chi?mWN zYH7izZ^_!ks%44nDi61xh{>@d+2pr*C{2z$IP7f{<$ZWo=^%mA>vIwQQ6~w!h&An^VA8*T^rO`bhAZyP4T-{4$f$L9)f!RsJc3 zGJ%;lacM*f^El%3d4m<>N>Q#Gd}gM%i*7$S!y1c;t+&qR!}DR_P)jIM-skM&UEyW_ zp62RhF~E9~(J_%Zzo_Gto2^cGP5&|ap$zKB>aSI@68f)vws$*SanERQjs#Hs*eYaN^R~cXzw9AH-2`6*_qCD{QD=nFXtio z+R2fYjOvaj&z;*k9(S&JFtuE&ZZR|R=HQ5W#VIzc94&cV+gYbgSWswAv1Qyl!ka8Fit;q6(2Q)f5Z2NyQ4M;8gw^@8~= z<7L#Oz2}q|y{pQYaPlmSv-hl#t_G3upy+PyDrOZK>m1cnvhT!%@0*`5i|xW7k9lCewj#N5Uod|LjOGqoU!UbAk+EiTc@v#_0TcojZ<>brVN!&o zzMG>>PI6=Yx*Hk#fG@O)h))!V*dlJG$>#n2kugU1%cr`n?OKKAx0#t4zXsn=PRWPg z{U=_&6j=_Iz1b~xup&#(RB6TfOTt1*`zc?hwy|3JRenKC1qDK&Vn2>3*Qz=jF(&da zNOZn9H!xsR%b?*@{f+gr={``EjFAtnOpw^VYl!v1CnDh@F-_ z#k&gOq!0Q}q+}=7EBhNd_D4HG_n9@K1#^3DDjX3)&bSO{4}la3k*8(x;a9B3$rBiM zBA!-1tMS034Fty*nVX#DL_CA7*Qj@m-==ycp2ACZRoQ=7U~jO`eQ;``RqZ(UaU8PK zmEK?}R=dlJOucYRq|SboULu5_vb(L46NxBy=bEPTl|%*x1xe7E_^u*^s3(-@$j$y< zk)YOUz1MwiDs0#t{oC9b-u)M@KDQD5+GMzMs8TUa-#1(K%`ieK`^LY!tARYR6BII( zWH8g7962`Vz5A;^jj6k_GZasK?N!~(AiwD)8#AV0!J~+qR&#JLMrCD3rcCfn_Ml>8 z-Tm^&P`Utxv00}+T8iyoGTxy#JUHPiU*|>+>2__5{_TDWcsKHB>ki2|H2JpZkpo@BQNu>%$|vN7-r`mPR!JA z+FVgiXwG=^oex=Ll0mF1k7tHPZ1jJLZ1?h^RG!Yf!+fQl3Nckr!%hcXppEcL`dg+~ ziy-PovG!2U4=$`|z3^{LD5?{=<6vUQ_}HEm#O!@;QFTXpx$zA{Mo|$4)KOjHZ%Hte zzBo#)cd&arDKb8$d%1tkb85r}_9!Qc1z&O@mm3K@em#EQBeEP5-NJHQRQ?oanQ@y6pdk%~fpQP^U!;aoj@Cp+tj8I|& z3BaPSfPo`j*OhxF77W+E-f4U{S3$^G11%tpUnisC1Fsz9>t;N~OOlr({KY{+)Jva9 zD8=~-BDD@*Ro@`}(i}pkOjTh2TZ2*fVi1#w1ReeUIVS$Rz>pB(gm0U>hF_p}YxaUr zi`+7cEHf;a@3I1c(3M{<(hr+s-=Kjey-~Fu4CGf}kP1zWENA4?Jj#7wi(LqXStEZX zqk?Od!jXp6W70_hCsj?bz1{2DChzztOCz~EcsWz1nr$pBz*k^B?rgzKJ__R|{4oS9 zk4+4{;xvvL&fFsXMa|iRW&Gm~yPC3mDJ4R2as^oOMyG77rxK6z{o$-=H?Cyr{b}8! zX2k+pi14N7(kHd)FQNt1v}Mx^mLNgDZV*NM8Sy=x`O_`pY|gvpz^$KG^+*}}ZctG< z8PERN?`UO6vF|ag-Rv#HRG@F(5FwhJADASqYT+mHce6EF}id~`spU`k0sS< zj#s}57HPr^3=Cv&8a`W`6H+xxR!9A{{qob71^@?9OutzEHaZD!@>k(r$Ijt|+ekzpdvR?^N^lq3% z3^zs_(Vp?>jv3t=6?pq+<*=#a@ynL;IlsttOyR80oRy*4;O^_bwDs;GVrTa_Ccr!t z$7*crWn) z&W*;##=>+hc{W0cYjAVXz35oxMR~fx%~xMhiGq!=F+SW@T>YxLQa(|ST!=?Z2qCcL z-Lmip(5krzq3pFR;w$p7m@VlP9W9OpDesc-GtrpiB)?i!B-xcPRy)9Hn|n9orUH?q zj1(cp7}An!(_x#{Du-urKq;?(jW7Lm zY5ONY2SH!FxDCCa&A2GD(tqck1ie{5WT5b*HC)_(`OB4?92-~kF^?3X=M<)e0x{VZ zi~^vn3Wm;yoT?(G+wTFq2%xlnY}3}<*cd?Qp=1wmxE_-H>iVUjVcU5^G*ck9A7@0E zMzTpVNF&x89a77u$4O4a7#i4EgqiX+B_z1HTHP`D-aTTfQwrA^1Cr%zQpi5EDXn+o zRM=3_{XMecNIR`IM2(=0kaRJ0k<=m8kIsL77CxIO%wlt6g$Y4or9cM@pHfnyUxxq4 zr%!)Tj5fT#y5*zEvrdf`I3h3{VVu}prX@;(MuJ0rftj-BJh zAImhlU8H4%)f;`KLdxHFjI6MVRi!oXbwz=oMV4bfp6I8RXCh_e`j?JBU5!CKO(kD& z&X{9e?5%|LU!(N9<@~xq*9ePG@AEE07{A_*;6%FSd7L`?=6NdKkRq+&l8|KZVHo1DPA`ZP z$&k0k-9gscf@i2*%rwVLKV@LL`2S=laIY~usN$5JpWQasXb2Qiuj9dUe$Ux1=Vwl# z(2&W{y4O&=tz@ghc$$Qt^r+$;;d=@zy|Zc(rd5=C)>|?PnrC$mJQS_RBSE(X_u?+> z=RoQB4|40C!UAX58y3!akQxl>Ocq(wkcKw%QR!dN30OK$0yoty7l4I8S4b!-P`v_= z1`47>x6~l+JOmIKO4f(rcGizpbc#C-77XI-IwU!x6i*PNcft;7{INy!hq#&_pM$5o zU_EXF?nw*Rhvy(u39R|-Oictss zv|s285buFy?kxD`bfIkr$q{OeQ^~(N(-TAVwTp8APY9?~L`9)_`MVC}GoY=#7x=Eu zcnkfJVOWDY9#a;(j?;$cz(SkKVCUDbUow5HcKsS+*(j~TLG?A zkrH`)rGwpO;-VN6@W5>Ueq(`{0+D`{>J{&=OWE_`YgT9wZhkHM^jB_;5`>aD(3AWg zQpaLl!` z^(D7zI@zg~XO_$e%_QX>MR50-8+F$PUM8D)^dLVEi&7Z7s0guRCu~V&_Fww68ZW3a zblg65YxXIK)Wtv;1xkQGoGZv5%iO=oTnF8IjYXqIdWo-$2o(uZz;4eMWu66=q93gZ zRmQl|A95P46>p5wOF)BfZ!U;Ejhkz&0klb%9~hcsRs~qoD7yaI+q|w^($8~_Aj`^b zyZJIScW^@b1YU97H#WYd*g;Kr&L_HaSP;e6H zg;;g!C_=bZpbd+9eL=WgS)x(94mAR!hWFmSg^vV)+|oL`60cSiGVe!o-ubUG*Cj>Itm-JzI`*br+jNHKJ|;d$KiIm`75_n{c^S|thcvkj7hw;*S8~??2mRZ zo5_yj*2KlP15(sOC*z3m&Qy_#?H5x{mZmJPqsK7(9mLJ}6rLw^C9cJ1{IR;Q5I8)j zDe{%RJ7k7LIwdQGfb!wuXrTQ*`1EW7X9r=Oj*>pXIDqK_WqoXwIzr&S4SKcdplLw* zL)PyqgfD-8l@_CUCeasCVL?jy9JFF!m)Zeu9Y`x|SZo4^fkSNAIlkZzunZF5D(3_34?_fuXheNeyL_|x{~qzX`0 zP}(Wz0=3P|#?U-^h*Vhi-~_iASP2L66!!x(J*Kw7>IXU1t-#`mSE~VgEZm|cDWMV& zQVlZ?)DWx1pip0Mc@jM5a5%7VEtjJ$l>l#aaM`Q5hNPq;0uO)r4H-^3dJn=goeY%c z{7gabjg*RL#&I8z=q6X=5cSQixgYdt&qsMr4N1S;HwXV&ke^s=0(qm=DCVjR7cj3cU2c{66>gDtNOx z!QKfT<VJh+S)VLooFmp zxo%EW2?WD87bKxHQFs!vbx)z@Zd6zf-+sSPzYQ)x^j?D<#tEY$$|*Km-HMb@8{skoYdEY}`T zM~MSB8)`s+btUk<2Jj#hP3<5#k70QDIe2m!35rb8+TX73I%(p*fB)Vk$I@~($Hevd zroDOvol$Je+jGzVaD^OfX@-!i+Se6^tr2;7M!QoRavs=QHf>YunebRDv1}zDxId{m z`7orfXtTz=X}|v5{w1I9$Z2S5{0WTyvXLPtxRQeJ0NWS=RuU*1^R)OtSqWch%NT@A z1?tc*f9KDGi}Mwb=fR+lil0v>fRi59!PUagtdpH5{tMxw-~(ont&mA2w!c9pnI*2L z$c>4vHqI|aoWbwF-(lFe zV@Sc{$0A@GH!ChadGzdDXo!J*oSnrJol*%f)yW>KK7HqsI%$&*b;qg7vSV~RiS2iu zRe5+c@bsR1wXkXIVCx=6?lmWw9{W11zx&<2bEMBG4`*(0u{~YB`KyT`Wp;4rLwKl8 zOkwfh7I?ESbfB(q(CniHJ`^lao1rmQ&|WYg&``oc1%zrTQe+J#7hM;Djvmkx<#N;B z+@AL|<|%ly@5Bv%`b0-*Vvt&9(hiGiDB8EziCjKlsD(!t)ysmpt@~(=z!^Z?00tnWU_m zzjxt=5(3ODG+h>9OwvGuE>Qi7#&4O~#Iy5np@Kqfd*Bj2b(fkV+GD&X66%^Ev)iCH z3xhw`Z2{Qbb_A1Kox0dhsw6j&R>`x0l$__=TO=76QtoCK>RY;d{#`T=i=h{aj0(aO zbYAxt`LO*?o>GEdeqOD37(%PzqPeJBDVTt^Ymj`A|Jn%xQ0~m`z@5b+Vvhc3pqyts zve8OgYxTM&g7=W3J%Vsl$odGfzkew~PnW@xu7OES`&I{IX7Tm2j4qM0r(YPE%^`ME z9pp#dv`otNTn z?zdO!e#|@%mij5`9f~1LhPG1|2(gj&1(%^C?3l~4(jB$#jCdx} zzc|AFCP2kO1svGq*s3ZJyQK4J*9YNQ{}A&F@3NQS}J#xOjFlGkFy$S-+=+WDF1rOeHmzGpHqvzpD#nx6v_ie5O>zj>pb zKPZsEGomy^uQ15FmVPl(%;ilNhvDk*=qSXf3|RwI{`-*86?T-jjhNoPH^-$uZ<(5< za!-=+=iy5MgkUK6eKYAEqcgQemk8Tj`&Z;1e>Cl(ujwffBU2{z?rGI5?uVCbt*-B} zzRfrr&zcFt;UZ^#1o?0>CjI7DcP>uiT@$t6@X&*XB)9A+*~tV4FE3HOQD8Vz6aAv; z@oa}%IiC#$10h=J6ZGe3+%=R{&}uh<{RJHt!DGrLV0~kzrx4J`K2#7B8lpl5?PPpkDZ`%Ck?iiBNpe2Yelxa|3Vv2K+~rs%Bu zH3xfa;g7w=;bMk>$tZFW6-KQ3>xM*!1&^!YyhMsWm!lIcVW}j8qab)n|JdA(-Rhc+ zEe{WcnV1^xpRz?$U?p59A9scgAKdVbSXJ0LxVg87S1lYb_-cl5Q}JMFpru1e)w>ag zpa50r?GpEddKaAAv*=0i$o7C{;u?y90DsgCv}L?dd$@VU!zUu}?^L~yDs`7RA(=E$ zi_*ctaz1ND-Y*S%;G)dex4g`b=82?)Gy%1hU70o356418B7XvdYx}`cyxQQ2sXwvN z-OV+Ddbf)(eE2N70-=#ty|;aRs$u$uAaqNOgIcQWiehqm*%w0B>d)0yf0iLHI7Yw- zQi>zmh*%2o{EOMEkq5VgOp1ox9336IACc(koX(tt_Z(g11>=}nimnteZprE^XFi~kKQ(SyDZJl8y2N4Cr>82We)$f)^L@i`?$ zP8b3iCC=unMgE0*`oCoqbj(Z_TiMr^dW2TB?kFKJLT_l0)EfnV{osP?q~=U{%!s9$ zUo7o65dQn)%A1>m;l(U86vWY|aIp31^%aJGGVRKc(0M5`QA+m7R9uI`D*8HOBH>ZT zX5#i*WT36!8^Yrpv7DJOrHKhkV~L`FGaz?2uj%8DF~nD@Zgbch7MScE)z?0nw>{$* zA;VvM4&M43_i?E)% zY6>c1!35Y;LnQ-n3RnAj#lYtoC*>Mze!#@8$)1&0BN0JHr9htm{x}%^LiYNQ>jKon zrX(iq>exQGQ5fXfvbk^fi?w;e<$!*Y;o+MATPUtlD&|M8((VekTo;TVagnGszw$5a4#}mW)C{_J+RaAVXO!IZt3C*yO?LH-jNLizHE?%#G(OVgos`b7Ga&d|?&7s9`40#$nZ z>gtojO~SKar;C~HfagT%qEf27p9y-PMbG}J154kNbFAvf4d(X@%L+V#bPlHH-aGJq!r0$_mkxT zv5FE2LKUtk1m%`Ncz_PLC>P%5oP{b>ZxmjCrTp4Qj~>AbK=g~XS2N0RhIP4}7SU zfImMYEF6IEK1Ghy;V~0)|o&~np zFEa5Gf6L;|GsOu9fNSZlxlyF%WlIX=5|!G(0|yh?KA91BA@rtD9T?gR$8inGvxm1$xd9x57Nrm>D=~k>y#Ow*^cq}1Z0Chh*d7tk04+z)Ndr4qb^_P)Du-k{)2_oov| z&gA%{fYYm3Dg4+T7NDs~*{Ww`>hA6i$)0eLqfZK4y!{D9GRd0&8$hpaIPyTw<#$z?9*yyyM{IgGqkO3cH@`tQXP#9m*ic;DapQN=ougGQ zADg{cW1TJT-H9hLFy=$-SjA%BkY_!ZO99K)&$!FafBk*5W*d5V@n{KS^^Nv3Gt1A^ z=;j|vH}id`M8;ngZ!;J4wLA~d(%(&_f{34Nh1b9mVKUAjCwVcRvu=VN_REQc_|kOWce= znSp#)OGcNJxs@4VDF`1QGft4M@x>oALy)mV2-hfzF=_-%Z`jzIM=tJNL|P+FynRNm zBUa18CIllumR1;3P&!X`B@;Vf*pOgP89l=rXW`N#{GcLTVErM^{xP4N2L% z%R3Wm8CV2qbh@ANbzTW88_`AY-=agKRVSDw%9_>fg<}zMUSVvHJDcbAMun|N)&k58Fk6eGQDj8-I53(E29KQ=gq^_v7#f$kutPA- z<$`M*Y%({{i60O@Dv~x0ZtR)BvJgU@V9cfzw&A2V3gnLK07Uu|cKgEL83y=VtQCht zQwo8>1@-mA4Ub`e10laukzcC;YybeES1l;N09uzrgXP4O9`lmcaxeAjdG)tuOceM{tNOlemAy$TR%p1TS@a?{`Jl`S5 zr`H0-4Yohg!SgcS&;o(iLh=30UdpXj;N!q=CQ8M%=-sUly4d;%-R98q2fT3b5-^-! zWT3&bjo4+Y_Pya8P{0LrxByfvhK>a(5JXL{=y(LI9-!lc!tKa-Q18qy_;!6TQ_F-K zTwBF9be?<>VfCwvN`@6TtC7;hFm>vglle2Y8w333Klygpvx0j!iyCp0U6IkhcC8Ji z>8%#@0#mk`W2#wnv`J6XY{^=T0g=I{-2Y9EBjTnobl2rpXt_N9)p`B-Ky$(9@>0v# z&nfv0r0#Ic%fxj6N`d%}-yE^nf87iuN3L-YVq-hbJl{$ex5sf&6$=D?PC9S=+QY*`7uM2^A7*MPga67%AN!^qMWOkP}Jl;ij91(c|R4`dr5G^MF2gAZ>rzPbAs zN`N79ovCKXijg`JS*j^*U%^Q>K$^=4768)9s)SjYs^copS)6_Wz%$iakk7wpadZEs z6xPfUPn95o2v&)CuzzhT*}WH0^Ijq#-GQ(5h#3#ts@8zgP$&#IPiHQl2{zaN@=$_K zICvtO)R`8fKy%Za9~?+sLq)O$Z}Y~ifI_p|I&g^vxs|>w!9VtF)!cw5%l*r7kw@FR zrvTtDk3r;>lKVzGh?fAjdYMX0U!7GnzaO_mhvPKZ|HVq9Pd*myJONxbxTVlIq2$?& ztgK{K2@>M^w|QE1Bf4JDhV_W+V*5a)v%2cd$3z?Tb#r& z{jPhS&%pI8*7j2pk%7w(MIk6%=zwhwYA^jJnx<89gPLOFr*g}Fi$2nYdiVR7E^mF| zOwvGiDc?k4j0ZfB7TS;-Tg6<3CqN&(_!4d(fxuZzm%S z=JiE(D-yovO%O))df#-CMwfxpt9RuV*A@#X>A663piP8PffXW{rSSE=SJ@_PVot&) zG3M}&yf#G`nn?-T(?le$E()#nxocbHg^^tm4i8(HisK?Bf}VeC#6@gWocO zpC8cW0%}Fw2-@}rC}`1B8&>Co`dhbSkM`9*@|F1uyAX!y#aXui5{-F~&{g>^mSuX1 zEog=l<2h%Qg-Uwq^;KkUO7jb*P&l{YrilJF=d=4E)+b3rg05I_89pR;`Ica62BD}X zCyC!CRht%Fnr?WtwYCOADmFxlA@yx=pluPoKT1 z%vkA2n&V6KOT*damU*!^dz}>-9c|Y$F&mWvlbnG8X#Ja4+*%8lT4$fyc0|5N8rM6V zPa0WTux@X3{vllZa6mHWPYc`ioonTXTUdf5Lh(O)@y^h{E9H56(=Xyjw^>5jhZi}9 z1(64uqamYP1M3buD5+ zesduoo~n@MrY7#n9zUGv>hRcDOfHbe@4kjLIV0J!tBULyx?V=InO1K|N-d;QOXrjN zS7CQ+A?+c2G>XjN-B$6ZICZ`6Xtp(&2?(rAXv&0Fj3JeEU3(YZtHM$x2<-R5N>@0r& z4d^r#40x$mDVmnFvhVcm7HRDfhV_tqrAbOUi=#P2p+TXda4fiYSm{nDj4Y6VhquhV zNZAJ&3WAiOEndA*8u=5kMi0K8^Q4aJU3`WmMuu^huMVyxZOI5i{XFSWyRx*jzJGvX zv(OjsxMGpLTK*rhE%qOceml>7pf#jBpP(p&6bwDaP>QX^wYoap78Il+r4E)2zn1Js z-r%e_zse_*eEA_^p!5G|0nE%`;i)YT*TR`IUm#`{n7uP?pWrsCc@Q+m!SZ>12o|>! z&%)kU7%2<}!@0gQLyvsyj68vW-%=j++JbTipAL-@Xhy&y9>tBlYNnA?bo%rg0Ehh> z(K*BM=KiNX`~z;0(UCw!+!hAuZ(w~YrFSCM8%+wTs)|+RZ`=M^<{rykIeLnQp|&b4 zl!=y+v<}0kmyh}C#(4co6P=%9qyi@e)k;cLwdztUG!Cnsk&&DS;1K@=Nx(p-J;;CQr&8yq!5CSTI*4zm#;3c`>+cH&w}s#fJ38upTY$c8lmQ(Z z0@4|7A{X`3TwlD(llb7AxiCYldY1G1oq(Z(sXGYb`!=M-`% MaS?CLnY=|>#fDo zf=JWLjuhIyR)BWQK0WtVrPL7XA@NOaAAjDBI%P!ZuA%z zb9(;WuSEC0G_0FvZqv&Og?A@Y=kMncuq{0?>b;qV_5FC7;{92FNgA$w zrd!ceTyYHxgxP!Y0fMRWuO&Q33f;pYAr}TLcC7O-0e%8$78P*it1!a+#H3ORfp6gj zV>-8gzA~Raf4*cTzlS1?W@1<%pbVs$!zmicIBKZ>A<+y>J@4O3!Egsc!>X;HjWj%- zZaV?my=yS-Y!E>ktT=Xt*cq~9`5K*LWO(ClyDsrWYw3PTDSUcGX;DW9N3U;xgSHOu zlJ19~Rt5#4>l{ToUyv^Q>%rW);J^wPm{U}c2}a-?AVYm2-!=ju@zC$)0^Sv#EZ6}- zbZ0Hm!K>mtWv}>FIu%(|GO3i_AVjL?=yqv zodHMe_EUJM4@KbSE{+I@4^SFlLCtX0M@5>856^tjDQ!MVK}DSIxcS8=oQkER^2>osJoE89PAsrNj~SPZN{&9S1VlHg$qgTpW`+){?)C1 ztJgkx7G|<{?i+Ule=nw+_C#(zfMe_#l>K>OXmYslCdIC4M9WJ z;x)xgMF!F~8!M|epD&#?HDU=x8i}kobwRfCd;efJqO-a>si*>)k*Jfe3@S@DWa789#PZ2D5LM_SX}-Tq>x+o zzLJ_Z^n+(e&B}R&F#6W*t6eI3a-_9pOTFma9QL7wQ!%w=I3hqaO<*O{JS!v8-w8X+ zaqEBqG}#+QA8CBD{@-6cl)r$|SV1`_4P?Ri;{wuBQcW!_C^G;RkeQg=wPyuj48(=3 zEH7I=zuqw`0~;;$hy!f0-uY>G1g)K>E;zoVODK{C1h)1G`h*`($yAD%8K#;?mlEGe zU;*O@ICr8S1e!43vKCwT7%Y~J_8eY_$3JRAzXa-`wr1NWSIzj2*;~LX5iuJ*_UJ$z zir!rq8=#|k823d2jfaB+!WoOIswjGWaYSe)C#D~|d3wTrIM8PLBRbSUdvuT!sSKjy zeppWfJrw0_0G_sDZ~?xfAMU@P96tQ3rQQY+n{j*{!6{8CiamlV3gnjDRI&DkF|>P; z!%|+8&1HC4Tk_$1Px|6o@D~OwES2z2laEM|Q+Nx<^6k1a?h*=}e9tROwu{VN8;O?M zN51P!4$frGK82gQ_!LX_F296ze$#eBvh75$DYZH7M{5^rPoJBgVE?hgs5sU;RP_Z+h4r@>6%NO8VDnXD({?5D zx0z{Z7|kYn?Ocz8^UhFE3JTuYvz%~p+4t9{%kBk?P;*hrWs;Q{oavuym}-thdX490 z1pCqljt+#aXG;39D6<{VIu7T6=CT1cDkvEp6+8ma z0-#Y))`QQj5l}gA-c+e3eQM&E7T1j(I-)urRDefbE*w8@V^dnnuaycCz#<;lJvwqc z-0wZYk2Iy95%Ck+;_4Mgdm7-XHLp#%CUM-skDUM3p~SJ8be`mDvS3tM4w}bVS?LbK zvxg7YA<*$zN5??3=u~t5HE)}sAic=oT==HQYM79x?3=i4 znJ3+bBfnM9s7gcaKKsSRML{7Uq16|vp3|*Bg03WX2YoZd90#~4>#G?U0Ns6!GnHby z>WljViXV8t_8?mEv6CcZGlx|y{bnVLu~_-X>yxLL%n%oLl-V4Vx-6Z)VrHdF9B2xA zKs-cR{`@UQ)uQL?AIjusb1x*m7ZfqlIlzn7^7uAaSgL?PO8lj) zxLyp`;K-bFX#-!Ty0%~xpB9eI3P1px5M`Oa>QU-GU-N~PYjuxZ`G_(@*Bu1g#e+C) zuK#RuAKVUGr2V#DpWYnFQ}gRjzPQ_`45=im0)0=hjo~0uBswa*%5y|;uOX0i(AucAvZj7 zIh|=dM)%aiY^JF`r-9|#$SsShO$7);jZm^B@H)izsu#h=9Aj~po9f9_;m$Y96sODk zoRw?619?|cByA;6-LL^+lk5;`PgrIHYl>=C8kb-vH*d4A^~Dx7>i_vgN^>wUdPr<`Mj z`oP1r1pCt5uY^AWSUh>sAIfG#$(HNxe9dmZ_f^KX@=77bsG!~F^~V9kW3-xKa7z^M zdDwE(yRptdX^Riti)ORU_YTY7?xInUmnR*8CUs>bFTVOC08nUtesKrlIJ^FVp4&WG zI3V+UzmO2eZuEXI(cCQln}N$k{>s)eABCr zp)HkQ8WG&8p7QwAs{dwi{ncr>R2OR3vybtjsYsB80=iLC4e16t%$inQ-E(vCYLiWaHnaJ{PLzJFLD;=6rK)j;Pn*&1C|vRVM$A zaM3pC$rr*a+-ImSBJ?{z?Gj}iW&HB2*hvM4EU6~?(T2x6{%hn7ds`m|429VHg9AA^ zh!#rC70?(c-uUnBv|s+iKY+zL&Pae;`Z)z+nv_Te{c4y|ox2pyw(Kb-eJ=pY#P@R> zMu6{ky?GP&?RID%r5rW(!I^Ugfet9t56jyk+Q7zlqCvbT&N!*?EKV*JK$p8xkRj%R z#HsubPeLmz-ET_AEw*|YBcbKeX|n(8qZ}-xb;uIF7a78~>>lLP3O-db1BVNVaE(eb4d@7~Duu`i{q~e!R8+3Xpw~Nz zRk-*e%Jd?t*o{Sx5G(Ggs%}{7_7MWUE+xK8!7JjVQ+wjXC0FRFM$Q?Ip{lw)<%Xiw zX_EvpE>-p#sEf{yP3@e~Y`iZi_xESTvK0bxJ_Pw19W$YI`^}%``(h9RA};=0WUibiVYY01 z+PkM~EE0K1D;H&R(sguj9s_8xdxy-ON|`YS1metE94W@xaJ9j8ZFLp8zAd=sfV@I; z8^e{q8jT;mW>A%4m+@v+Kt)fPO9f$;Z5)0adx1fbdU+_6s_rd^&{$BgQS}LErKYFQ zYE=~uCp*e`^8csqh_D4wHM+^ihB$*j(=*4x7?-o)Xp!6V$&=66*7iH$Q?3--No?&!0DNniuI?rQgdD%w>Rt;JC_4fpsRt zx9wm7y`3>gw*H8lrQT6QOH-SAO|1~ zyvGE~oz?pS2{BxIDE333z%z3_nOoQaT|ii6eEdMss+d2FK+-SS5~C}&eE$SKQI*$u z5|`%Cx4wZx z&|9&bYP^oDhDiasvKiUl`LM2Aw1T#~pkP{z;|YPcu19P19_&VSbCkGzxp< zW{!e?n>5vZ=Z+|4$Y(Q#@a4E~hc|UZA&|??Fm2TNN(*aF#8;VZ*%Bq%{O`SMHG}oD zor)*SWWmVhKD#M;G|(`zk<7IVKM7kH5r7esg->kuf{ zL2BruSt`BQzu{+S%A6Tge>`03j?=dh_?fb%__o*-kn*52LPoNksg*ZbsAV$>vUYNd zZ}H-`V(>g!+PL@Aj;|lmsonL%xBrpOifwNf;Q>(czQ4W2d>a0%@*Xs9K1L{xhboku z*rF~Hg-=@mITdRb{#_QrI&by+NEucK?8TRBVqSAW?|$( zbhc)Z<~%E<_hA<^;)24c_j6@BHwa&YP7nG~yrN#yvQ=A)RwK>X(lQhJSa=adLtqKa zP)XnRUPKv9NHqu#dgNR$p4cJ5T{be``8*_=|1BX=k&w;zVa6BRo!{YS$Q}h>L%bB`yYBM?5`49;<5nX1X1jl9!;i9d`k|X(ps{lhq>91YFNU&vw68Lde{Rp6=}c zu}^FfDu&Xi_WKig{@r z^7KDl#M8l#C1O0q7Zbc&?%s}nzDg9Tri}LdZWx#7mYZ{(^dRqXdo9j4pBMG~HPK@~ zuBIDK2St@aa;dziSMxV$AHb91onA_f5MYnv9a83cx-K`Kl)4rzZ!Cg?Ltr1rEOUdj zYS8-K=)+uE-i{>9s1wFl&zL|J3Vp(!1&jyKeH5n}Z3NFF#Bn`8i|Ytvmgxg5EoV#J znl9_23n%;`9^^go&6Ibr`WOSudw3D5j_}jLO(M{LfpkO6_QjLqx zmYNI<&-|s5IEIGJC;!aJh`KL@Pi3`~RNx=i_;0`u7Dt%-3epw4Eeb~XprUCq-5#Yl zyt)o!Bi~#np~uI7O8mX|587-B2g*iaA`uF<`+1G)0#VT;j~$KpvoR@jZswBW<)d2( zu{1FJM}Mo2d2)-yW+Xiu>A-AidU>F=CEtDKKW^8SNlJP)o*9T21wy~8jj67xdI4et z$N>v=QVz_3o@*awdmpnfLJ>xA0`V{~+bZ#BFgZV>U5D?3YXi!=()0p9Pi<56hnP z?psr_4^`72?6TpKSWO?l(}@>6c6Gba+{}-#Upq3~&bV&)LDs+AkIiGQRUjdu@~wgb za8!{BcQs3ISb1^!8&3z)e(98SfeT$SM@i3+hb>ENI~MOJLYB;4APX zmWv#{m|7PPPt8Ljgy)|A;#lxn^N6H*S5I-+m8!SOBURdM~z=|EFcjT5dalK`fU z2k)gu8a+j`N-pyktOhp)-uYbmLxuB3;=(AqlDp~|vTzk0k(vsu9tnai;jSLZ5LVjXsI0a2)XYtDaMO(luDr;B)K$qkS%+bS%tQZ;`d6DLSDA0+r*{>Z7* zTMB&p7lR`=98H{m^snTf9*&$9VUMp?kYyp=XfQG|dJD{^o4`x=VPqRPi#0&Tmb;mn zQaaNKya8hu8?Ccq0`X(58%`1^T4I+9>32te?@b5lP4JQvZlqAFwD2M|9GJ^1D@Rv| zz;kE(2c+{-Z}9Xk^?HA4Q81FM4f?cF#qn@w{OPFOefeuX#wu6I%UBVfimKU-#X@r5 zo7*-EWm?}z>HViUd&d{Mz~F<&Nlb)V!VZ7oNrkESIpO;c(8(?6Osi-b5RYG@NERWX znrQCjBUeRgV8u;LNhF5Ja3U9zosHNADk_BpD~pzxGXu95odPJHyyRc{bMMu&h(DLU z*0|iz0pHwSntMLLDmk5d^_TS{zDZNM6}5;H>+A zqz$l4j^hf@P+$4|iJD35W&a}btAWHos^|~LhSuZb9v=@2f%0G!4I(0e39@3Rrf+~u ziN9ctK%;UZ?KB}?O^n9s3VWMb0XFrm;BylKLl)||`=_TGoEKF%(TmUYszt=kGD?qA z5uNOM=uIqz6g4;V7QFka?l7dxKC?iGh;ooou_t+1(j`TVFn*Il8ucxmhMnlH>_*AM zWk1MVpZFn#?|DiX8NlA7W@ZPlF%$-nC?-NY5s|d42NC6LDgEXg0t_V6Q6EN)v>Tu( z0paYGuA^{8DJ-~<73lM%(@l?`*Jb+6bMxSw&Q*KmYzdd4cmGDepX05#1oIRXa z-y3$-Tz6$hwGy`y1tm3Lmu>Hl7@6cGoM9mBce(ynL-jhj2KgTWHI;j%n04;Q2FeZ? zd&YQfUfx5}hhkr4W-{w9CVS3e%5nTT=W0*%Tnru8xp`Oe@#3a-6@!; zIaOSVc%miH-;9);SmwCQqnCNfxMcKO?n@)#CWDGebr44Swt|_7{U{~JP1V=hCgNJ$ z{FI_m;$gCG<_O9gu8;OaWT#iuA;lT-w9*}{4_AxQJ?L5mHOXk8f&N%b8@? zt0PuB`g;Mhz7I9iUz8o&{zQXhZNS!IvOX0gyL-J^Z`mlMry*zXyi;LJ2$3G~r(* zpZp%q>fXDEIGSqfhBC1-w6s(>FILhz)#ONf*3a|d@a4R;w23^2U%BG*864k*Y%Tg_ z=FVQ|xD%;ydv;%J)q-lKvWaTJ#WcIav8&t=*fH zF;V+0=*87e(S%!k>AjeU;bE#=L9uQWRghaA$aKHhifqI+x*&lpNxis zII6q58z1}=1`@~cN-|vIzkR!Z`&p5{vp7#?2JoKc>osk7bAu-Thxpwnd}|G6!Cvq# zcp@WkGrK(s{#!ec7#JEBM)1}6$?=E0FME6@3R|wmMn;(tG;P-6xBiRbyZDe;FiUT!CXgih&xe^FoL&F3vZ^!=(iTAbtux+5?V4e2I(vU z;myg?V&p2!q_qR@3l`bDHve_37^7KTkelDvlhwlRQtdHLt+FxQFxvA4DM)8+;$O<( z3hV8~VezERlNKvIWWPXyHpa7UE(Yx2!HjRf*Mc~?wfwpF)8`Iztz6_%dMDj=mF^{D zV?iF0>uIpJT~^<(If|hFzq3@40+F$Iu7INMdT|RAnqTOw=WfTHbvGKyJDvZhg3_zAGMxXm{_%6^Vomw?Z8mdCGG)t%>Sqi>zQ zZQ8S$OYm4)j}ADi+hPSm4pT|pV{%7x-Kt4I_*=b_TzkKf>rHqU-G#0oEJmclN~dw2vU z(4fM=k06KcV9m&5_ zd-vt~1e_6@r@uChkby86wU@PCkt-Gebt;}Rqy;nTnsYZ$D3x)clnfDdZvP%`7Aa|( zA)5KLv@5cMzvG-+-Z&*va2EKRPY1@w9V|TZ{I2V)A7I0Je#~s_34?8IfbiBCRXdu5 zV!6)>;qzKoM`G{3elLaK733vWp(m#67neLIji`U$&a4Hi)cn)eT)%#Y^K75GlZsiT zx_XAh5l^>3`X!w=DRtK0>poY#FlD+o0T{LAmX`?V^jW{h5v>cFm}*25A;iyKb>r`a zn_FB-h_`bF$iBwPXk26^D z4(r-UcL#SW+x+Z>m;yzl2Avcq9xdVJ(JoVnt~sY3d;9zVW$uVvwb5rS^SX(?e`iI$ z2=h7XrdD#?q(?8FPX9Z$i#&c7$)Yi~(KcT= zvt9|5)I(WbaEsS{>r(Eos3g<=(yGR!>hXw}|FBCSkBymv`(c9TnT5p!tc1T(&?Ot$ zGr?y>?o2g%F49LA{_;XSpuzCo=h7};rTqH)g5DSv6t2;;YEo4N_(!Tm(6y|DsL+CCAx^>yRO`H`83v;opq%URVt(=L={*%h za7A1~hTXCvTvb_ceD~NL$vf+nlA~I4^Qu+=uH|ac*j;puIv6gbn zDetyEI=y;u$4Z?OC0Dr8VpStf1+l2fkgVFU>d&`&XI$+{mA|MyM z^>sz@umjkj=McaSk5)QeR8kDx6VRK0uHX#VZT8`<2nUjaSk1g#| z5|V-f@jx=9VYh!E$oFqcy#5Ut|88EKpWlpj(`?egPn3JdBN86ZM?KBj3@+|Tpj+R> zSk*vomxf{gExLH!2`NwNMz3pvI;tH5fi{`W5q4*=seGu*tg@l^%TP*5&njEU$qh%u zsw0Fy^)yl$Z7d2!S@h%`D*fA4nm=f56Zv!c=+Pt9qNt5X!74~1-4Bg`d+=kcmV4;= zyL*D{D;fI^(TU;<@j!)T{jwDoc&$|58>r1^XYaf&sIn81^Qk~cF9Xw7ior@wRYlG8xKA}eRjQ_jNEM9~NJ^I2Oxz2M4 z%=s(e)@m~^JM*HZIrZiP;YTMyoA#D2a<&nYWiS2kBJLv%X zhWif8=n66w>nHex1vmojpbwQa~=7tr7`a|g0FvOpGCwFMM1Gz z=$5~|8!z}m=cxSq1D-6FMEOH&(Yt@IkUh%TvZ~(i;mZQIqL=nA1dw#77S@*Dt#MSY zx&QQE73lW#7JoPzQo)83aKD8EZpf`$F?djXY@L{lOlur^0x9-^?TGm?kD|>`G(>wc zpG%))p2=qGmMq(8L3ogi)v!M zFOiZ95FkR2No(2HE)wp}pPqaI3eL65mwmtXM1w-|Cy05Pg&g%b%OeyzadJYp|GnB3 zaXHrilJtX=4jLrFq`MC4K733{uDTR;lia-rp7`xrE6jYDsB(H85q0@0vC7jSkpEY} zLrjs81WCrK;sd_L0#obzRyB;0^h4TIDt?z~eVc3e?^v|fPDXKs9k=>-wf`i|bWWX$ z@H8}<H{Q*xMToxlr8o+3JTc4cl_Tf$_&k>0oZ#7?qp3w_@cn2TQ|kfx ztf-a_ml$#Y9Z=(k5&0<5@-`A*>$)-52MYnhRbJPmMr3Ni@8-%0NtCp*5(4q_t#i;} zmS=9Ut?-Q-MK5?$j4l`tJIl}CVLfQ_nWdTy=9C0|*MxiM=|aM4`} z*$BFpHxgQSJC_fIiQ)RN9vJ7qi|QjJ3;3F_$c$ryF@wzB{%cWY69r-iyDDzB7r)xH zpUviFsRmwkGbf+t9byWff0Cacz(#h?t8FFcT?sc~6VDJyc$4ps{-ExeIk)>d$7TZ8 zZ{ADoj&*3$FKDBns3gIf9*JbqDn?3tStppVjP66YIANPE1WGxb1@nC9iWb+8TCo02!a(;4tIlW^8J zHxcxLJ+6q0{IL$n+|BxQavoiQ1a5Mm)M0oV*g?FQp$aPtVUHp|c-3=#U;zCR8*!dg zqKr9eYvk>+-|*n0#}&?&Emmg{x2!%EUM1i{ud6#E?fN@YveT4(qr$u4Ijg z-%mmdr#+?9Q<J6ke1HtrQE0&l*U{Bt1$5@Mq$i3*nOVI*)bA!he73xXnR^;FC=K$z)Ec zkj{6Z{2~{Eesi4pVGl21dT|BVb-8%ycw9NRai4s+wA)ehD0^-sK#^OMo8V#3!}I6m z`aDLC&zIMeUA;N!2^n}iR9N0Jk~U}zuB3lX3r851T6d}6% zIVV1g23_k>mF@iEg0R|=#YzmiKdQ3Vg?21cL1y`f_0ko$8DHxgUzt6Hwj-VtKbIAm zV=|MIGxN|lWkpkho}+o}`&h)adR2ldRs;Y|Sn=x<85bWptQu96wu$7H7mF9Wxj(Nn z2%LIRzL-!Aw+HcY1Jn^fv$>MI5`y7vne)PmgINhwyf1A>U7C1N-+r=VEkVbkL5HA! zb_1`2SfxWfCy)86Ww6R#dTX={?5A0iNqGx&W^EeqtH?@5&-3}Ml?7}Dn36z1z_ zpV|>eWoHrwG9glvFCK*=l$&OUm;Evn9xqMv4SN3hHdDrG0GlCgTi#yI%>c%39T;~1p+=u=Xte3@!}sd-ge2O zg>TkO4O{mYeh5Ml)A1^@FyFiuv8a%MP`+Air}XzzpN^KQn#T<@7GJjc0GsWc+yBVE zTDSNH2hS@tZ#)|PJAdPI_~$fp&M!m=JOBvBL=p4P+~P_FK&vyS8DPmL;IOgPutuuN8R6D$6D_@fNEfs&Nc3A)&khg{_O<2;uk$>^hG zFd#ip*?@n->l(dRpE|Wu{S(;>mi#)@)aE1!NrKA!o7C;&RB3wX^_ylrZw2UH$9=uA zd6m2`J1vMa)Kuxh;{?mTTKZ@=%L|2kW{n2G&|-Xh9u}}7Koymhd>ou8d%f}0*uGRQ z^1>B|P-^@vY*&6$hPt*y03s7JojYoA+OgFpTO)iL`jDlR*y=D#D_icZ>-*h;dq znPz71WpEwa|6Ow-hus@yzW3TMw9up8{d()c$oMc|R%n<}QQARefT7p#(RA1MH!ajb zIe&+&G;n#~!s|J?oF|?n_gM{vp^D*3;C|^v*z?-tr6g;hqKO9gx93x?1W`h|D$LZI zCxQq>xRT`x(~ZK@{`6;&>$!jHUMvWx(8^pP;Sz{@L=ZlocsukeN7ylmt%=z>u{pcV zw5DeBV`PL>o*oD?R6xLa`zX%AN#eW;Er_{q_t2ip_I=@F)3z(dAW6TF*Ta~8@#L6c z?hAIe%YoT~lWu}ueOHGA4Y<~jv7hD+0?~K%j3#ju$k}=hvdb3f^4CKVI<)a$qd!Wf z?u)>c?yi`lW2{j(1W7sYhp>POhH#v+YS7^tRcN0|#IUOC5p!xvmM*&-pDHKs3x$$?O+zVy1#TW*2WofGwHZtCyox5^8q z3jb5^wF>3gea{{Vozmfz46)d-m<9N|E@ULRzCRL|iE|uCdBsxqM8tP{xLiKn^~Ku7 z<#j=#i#sFk1+mUAR_!Syhg!0gFh^Q@`%8Di_ZM^*jR^WQEo6N&)@ z(*`xjNOdUJkW*mrk@omvtG3Src7O|;+S-8UG$G|%INIom)ac&4-2@?t09tjzH#M9m z4ooHPi$r~xF|@ynB-L6kvr9=Tjvqv@_ThGY%5%+HtO~|o>eMhu8tFfl_+7YUYGPFQ z!a%Y4E*YIHv5Lun9a1-pG147OTQ>;kP~8l)1O&ud$BYYkmw62J*^9|3Z-9T%XWFyY z4WG~G0*URcjtI_=4SWv7sSJtwE)mD3h*Lqxn_DgyIUbm2TjP=+)y0_9n4K#sH9mPN zAoL>ydU)jo_kZ0z?nWaN?wqu<4OKV2DglUJLK1y@#HQxYPt!TwwQ7riK&WjP*Np-glok)4Dw?ymLot_+!*cbfZ{ z^kl1vu`;Z@i59?@$2|| zawthPaZ%w&g*MKRIS#_i;(&^S@R7eUmb4s<&yE`$S@QnC!h%?8TKjeCsX}h>WA)1l z6&2Q`%2XrMvXF^bjEX1IStibM=zNW2VnF%z+9#qpNxVa5Rg>Or&X#YAY4WiplO*Li z7MUannJ$~kc%iPnES)vQAmj`?$w9HElAUh=|Bk#)l^%04ija%%JogSk6yo8JANE!? z(!Ryg(J6@?*EQ3cTYu;A-(#@a-#J=d_g=FZkFuwrTF86!COYkM<|66ka})}eAL%su z0@op?hLfz&ggGvF;W8E0*BbD!4IV*tRTbiOMa*)x871O*yTe(4!uLbjJ#LGSk|5qw zF(B$!%AP%g2a1av%HNS)!Zw`uRVR90l!V9}>A>BOmuacQ#D46V>sLm2%6OE8X5f|u z65`_Hr(I9X37AB!1+s7e7UF_82M4v08h9ki?CJLG$J;UmZ$9o-~9ApV+n*}YS%Fv^47d@{Mt>WsLhwOK)mHcD2r7lTbI#WW+pN!Nf zPzaNz!eZlT7Wc;MZ5b`!iVy!%2(yTLQ)F*xc83*zNGx|0a`}9ymPqd4r2*2`y9Rg8JP-y4Rtn7y1 zlRJAcWOzj0>M0{1y>3AnXPn!rJ~09k+jF`$LxQvkl#`Ch`w0>1r$0BurEG?sEx0=a zwvDuFr9SbFDe`%IEWJcSrJj?oe%uoDBKeqlbT_v=q;OzY-i(z1!W%#W1CG^K|8q2v z7dzA5-*+}?KlXeBn5)a6$F@u-n!^=0Lki2?z-}jjkiCx#(Oz36K=J*1ToI^=F_#QY zUO7rJcUBBy9A?oQ!Dy8x&#rI27DA62Wu=;#B7E9@ng7aktTCa%HNqWY(k8hv`!ehh zW`sLms@y(;#xtLK(-Y09bed@Q=T=DyH+09&UY0egkCL6YBSbxJk2d(do%mhCDi~fZ zZ@RQbt7w0!KBre35YXV)L_cxHhviYzNZNldFm!=iGT>XS)8~w#DuFQu7x{%aGhIh! zmL`onkz`)CXlJZAITqB!37vkC6dGv>#m!bC0eemswNtK|hRj-q$XH$tiQ!DoDzU5q z#2e@U!Me?MI&k}2bia*~K+sHU@|XOXmdlqfk4;agM)&AhglU zPI)Lx^(~=rSjPC9OcHG}{)-ovE6FG?np|m;UGYrh{h^aBGVdvpHMPHYThC(O?T;x> z_*1^%KSx!gPa+*mcbu<2*r8}NDZ;j7IM0@%5qDbIXJ1tT1xA_n!RE>1gm)5uec5Eu z6Z7-8t>6I4^_Ho1n+u{nvT5PSWgqF#$}NZSpGF$^b4%$B><8#Qvw(IF!{xJ6x0UyK zq&ZRlNtS!dS|_^F0mZ+ zDP0df(x)jEu~{rbiS_%9KH{P6t~{q4VgRhLU7toUBCq`ldzlf z(kZrPYIvxwd^SO}gTvyD!f^M*LdpQA3eggbKoWP?W&M%hG;R_Mc5&OF}xA;=B6!XcUC*!?QoCo^1|cWkZnaX?S9gnHuM}g^ce4F#iLd9IrH{Lhg_;hS~SD9o@+lLPbAdY}p|$O#1CAm;tTTz6e>qMn49{P^vddiNA_q{rh*%@tT6EgI#dGc;g7dE;G!ZC_iRsyxo)4@U&k@RO zBt@Gj!`BCy)}wV(>s{^cAGORa2m1b{UA)JMsLJ`4A(7W2BCUJ-JLP)@qZX?1g@Tc{ zT37IUkM7fTmYxFiZuA8mE1TBW zkA}5EEQ?xw+2&e#P~5mi8>QrTuY!Nn3*Z{r;x6EPh4ls-uhSFbB=C94tNPa=nOBoe zZGsKABd>)ptZ1ukH_nGl#>>)X?;zZCF~os(z>uv!dUFCvk{1X&4}-{-MzeO-glzBY zOwAJDYcNKArFz1Ps=lB7moecnv#rpE%-3r!YLbxt`+ZB#PxDmZu@1s#9*az0?wE`-eE_Q^ zd0!wWjFh@{{mpe;6u83+`0=8~kU;5w;YCY4#@pUr*~8>a8wuj_P{uJSnwpb~@LWH2-_>+Wf=o{-4{IZFPazxhOgRh7`qq(1n_rrPe_vdZAC7R))vIYar_G`>c#%;h_Oa+fy7eKT*Ts6Lr&rwraPkz zXVMKadw1wVt`?1bcR8o%VyB(RR_x6G(OWveCJeYC-=*C3Ry!xzH1&Q`u2$}o-}X@$ z_06vqs;Hztx`)(|(j!p;>oJ@-dVK=9{M!~f7F3Y8`d#kFPt?c&1+f-|-p|x@ExD8H zZBWav6GaUp!U03%tVGh|4?5NP8gJ@^;}{Cb8Lz-euVMIc;{X(|j20bMHEW$;yxZ^| zp{-!!W%e8(}9sY=})MrsdwZzPZURYiv>QmCX1GKZ?eWkpOynUmJgP&yeJ*aQb-}* z*Kka#;K2uOi{4&5HqZ_MR(P0o@9Wp6!Zs_E9Bg+6cyUi%=J=}f~R zKe*eq5(17NDET9u?_1d}&0SafGB?gy4nH&%Vn9Y^5xgDURj?UeP#Kt+a&HM&e5EXE z4h{f1ZzXz!9*yj#3p}#4Tw}YZMx`p-605i7Mazgv^5Ob2Kwu%tR)k;6S$(d7Ift3_Z|1mZ@OvKk>N3VmiObp)>c}XH)EnAOEM{G3*Q)Tfe9b( z=&;c%?AEPf6Cw6bk~3Ao1rlV^g%8%et6Nt`-v{14$h75l;jLdm8}}5ZS=9u=(5L^2 z_TjGtVIDSTk$Z_r>{2hno+gIon#=Q(XWUuX=YJs}0+1tOLx`Rlua3*a0|CHtVl_ zVL%=isPjAg9{kyYHgKVj1g;C_b!>a=v%=8Iy1F{sx_Aeu!nWUSG+WgGb~GJGq5^D4 znohEl?tfq=rlyCu`p4dRSOk2u4olhz%=D z;JQNakX5qt?0<<)ii(QV2=KiVMN%N%yGntNcKv$wEBuQS!8RZpxMmU=8QC;Tg{^OE zW6G){>a30YcQPLd{10u+pC30ODG=%D>3Bm(yrKX6A>Kqia>K*!1S}rI!LSui$OByt zL~h<_nq3OH=jytO1xs-}j|(e)?+D9@x0%F$`@bJgPJaxh@!)>|-sM#6-gY8973n*LL@}^un+I78CVL0lZfj$(`d$jN?LvVg}Uh>AU;Ilhk)smlCEp zW@hM#qup`~SB4sg8>=@@z|RWVuYc9l(3h=*N6@xs^^OiLv4-Jle9XE5vIUfDD9rmG zaNtZxLC;bDUXVOS2CZ9WMDLUMB@-;SpkJTP z4{Z1JAgng=DN(@l(SO?`rFSj-NF3~k<^pUEAprpx^nl4d)^T=nS^_Igqy|2M12*Qc zjTT-MOI)w-Cm{WLw0wjHe+vP5Bug^yK*`@HE)TSK9p>OA`2Nq}0Ni1H4q2$kT90ms(kXu9PCi-f{}i9bo_y2Yi#BG{bxWg6LsGHAFVlJB!3IWyv3}me7D3 z>8sQASO2ZrzpGmK)w<}8C#1ozE^YruEf!`7Dl?x0RPN3XuMr?*D z9gn5>;5dH|YT2HAoK^%=R6Mvr%^`n;KY`gdgUPJeMB*SQZNS(3)i8K0KEjzh%HZpz zRv{jqXLh@}tkcHA*>{2{E}e+9cO9gTpgQD(pt+MpFUoL8`vSaf=>g;;54U8|@BJAI zp875+<0UDl;jXSQ)3>yzKx$k@z(&|gH?(=Nt3ZE3>a{N|Y3(|T7uGjl2JMzhjny`N zJfxFcJBn_Fam zMeDlm%BM)Ji0%IZE)K81T(^-d1^0^F6fG`c;X!TZss& z@D|LtLVu3^i+>uTpD`t{7(`&S;b>~1G|59w80YXkujJcXIBic3HwW|+fUgQvb;#o( z^16dSI6s8B9#U^_e}5#?aBaV{SO8{F2%WO=Wn9)3J+;MrwRq}<0bq74*%a6?TO`0^ z(bLoO`n9^99gyTPybfVEiwv@}vjMo}CFjl?xiuvE z?)^E!dtf~Iv&8>zi{{_fBUsmvf9I!G+Cu*RKXjtnTAkBQ4aeK!=`jOobp|vk{+ zc1II|_{JQ=CBT@NtT|B+8#EU>VxAI?f4BOs**mDcnB|BqChA<9+h%3{{5M&WTtP2i ztq0YC>7-6s%%Sm0xGtuaUXs2?H?D+7Ea}^Qu9$arbLXQ!T7DIsw5$BFy16+I=kOOq z;bsqGy@VchiN{E7oBi_|{N$@BD_$T03OY#1*3*OYyb(0{!BjGwPL|RM+ySgAbfvo& z6N<(A7~zP(Ui}shg0cXFTZz47CLLpDHlpzGgz{pcK6L!H6;YzJKs z@c#oLZrzYMVl?z0QHG#D#`JoFO{>DdTg!jrk000j7?U3S^xV2oOL~b(v9r9q{tY`B zWmML7C6cLH&i}x<=MQIREak<%^LNl-Q6lu1kB={WK4r1J$%$(#V)Rfp&d7=6P6t^u z4Wg?jOhp}$io_2-MBgfoy0=-V^kx$4O$+Asv;V%Q41b+U>3JI!OP{CnWA)ZW4Ne5D zIzlYA{`!?m%QAy!si<6YTT?m4#^_Kg)lFkn^%0Qs(^RWV=N z-A&u(1#M_qc~CoB3s|HEQ0FTuD&9#X&l=n1md|YjHGT@T0ZXZVa%{c-W`U%?i4;cN zbvp1IiBpiC`m}7JQsg}tqsOX7bCK^+^e!7BLkiRn`373d`{JE33T3d0tB5r-!dzQeXd ziI?vfGhbAIyIC`Zmj&T1#G%yvhL1|YzX2?#xQ>i8l6F`=2b=S+BLAJ5?BEN$A5P25 z97F8EGplGSs?Rgc5u%A=rZYZj?@gU5RvHUyF6owa<v0cx27HNCw*GRF+B5T!|AhlD;hQXV)14~woqc;tQm!|m zcQi6(Rk~!X4*o>(J`$iJ$B0w$jE)#zl<*hbCHXZ>o%@+LYa;(^2QZ615CVXMusV`4 z{|T%IthlgxJy>#M#U*ks9aX+gT8i~2=X`L7@DPI-qd3~mJg-5=;$%Mts$(J|B8WR? zdiR3TsxKG)kj~NS?f!;Tm6wJg;RVT?i`g_8fv|3bl4Q_&6R#0W`E^An6(A0wg`r$R zF(m5>P)rxOg}zCHIQE+BmkB{&oX^91b*$kD$xXNSV)XmSPvj^}?fN(5nM4(fOrS_0 zqKYI7S8~cxXJ)H2XsQ`!r+86s1%l?9tyrH$^d#)Jm~(loyL^xgDy%W3k3z$FXz3GjfX)Sv*y0tdm(i_sDqg&# z#HGRFy36UZU&sKOy>=b?SklZ~hR(OPO6=)(>)xd4-6t<)Ykg$RY^$5Ol zqhXhml9vw$kGjZT{!bh&4~F=k;2nfhI24YrM($oMcLR+Ac+2B%g7d=mMYHLL{On|cux5a5AHxV3myBRiRn?H{N!!bgmd7zYfr5V%k@{eZJqb>Q3z zSxCW_yVg`=WTa)EG(qq?#e7rT(})$(%LJvDEa6g75>u{w3(4_Cy1PH#JUEmr=S$|m zcPsM`;0khRk{@E~mJjKI4;M+1d3jOn*E#%g#- zJHpUOi*;Ri!WyWh*(1))MwL3wZ)I}<^Pfa!8Wj!F?ocF>zK6ahNZ=U^%Z@*i=MYyI zcYn4}57b*=$-%gpBNmv%rZB#38}9IRjIdTyg9IZK{4L`+{nmAw8({5Kv$MrnCcBj^ zII<|JzKNjuq5+!_BOSh)0CO^=2K4CY2msirz2pG;VN5iD?fm>)Nl_8mZve?PyB;%% zx(4`ubKMaSkUI($5HkAKe9N%uY=Haw$cS>I{+US3)+J~Ya*9Pk_?wW>6^LSkB*4lb zhb4N=_vF(O5Cno`UQqjiyBDl5X2Mu>8Gta zf9|dj!U-uqnXt~+EwiV~Hx(%1XBpf&sb&v_fBxdCTu>KNq-#^WSo$M19-kQUe|@+l zYgeqp^46LrPd^;RL^tQ=!M^{hJ12N4@RCot;&%a2>}H4Rd2kHOJn#KomJ-kI_Kj^2 zteojRL{LHNx5wul2Y%h*?Kufqa_o28L zSbYp|Rq%i62hOmiD_PJOR%x@7MqDJXHGr5f1}+9Hzz211Y^*p|EmCJq*c2Y(4+bEB z@@4{>^V3t11hBNDyMhdz2F<63_sxeGZ*-b8u(#HMgCq`9Q?BdjmRsa4Hn+6cm}ip? zVm8oeD%r1rZHr5%4IG{cX|Mhb1A*Quri7OJzNA_tf+mx`-kU>vJUa4NU#DI#$=PEs zQO_Q%NPwo&`R#JE_PF$1ou*LJi&DM=pRHXV1iF9b-*dTIabvOqb=E3m3h}{pHTxP# zbj}O^WVp70!$9@AU^Mf~=(TSW%OB%%UPNz<4AxFIbbe^oY~~Z>6BAps6|hR()E01V zr9G63Ga+M)&M}cC+ty%JSd%{USi?laaonRo7?-am0nm+cwsc|U?xdN9zM={hHhr>n z>TnvH62AiUUJlbAh4WPd$D>MXLY-%!dzWBh<#D#F`S~NY+aG5wGiSzj^vzITpXkGP+3LJxA+^w#(O?JATIv z8WTLQ0zo(dn8Mjz85I&VnbD^5cT2I0E(`y+h& zU<{56Cke}Wp+@3AJVGK9MAa<8MlT_LoeSQh&^webP6Ua|a!jPdgZ0 zuIY|+qvd1Sc7RQg520Z6vm#WZ1lXMgA!Eio)L=q(3Q2=!8WSc}WaucvCvmWpf-w8Y z?Rx-@xa9#7<*-pp$t53X$i;E904?QgHM`o%M$%}$t zyATn=DR;C1y#5LX@fhhDim~oqN>n9c&CW3K2CIHK8_o97cv#lo7%@>4_OcZNYBS}d zP*|w6(p0Xw+(>`;oh;p?)S^gTmBh^3yQQ#@DRUU8VQ_%4IgA1uRNEjDy}lz$@{T=@ z4d15eZG_4sBu?;JdUWx*p*{3ofp}9hd#p6O> zi$C?26>{3_{9SD4FC>AxPJC>FS=M4KdoYK&c z?mbrBme-O1G9q?Txi}zOUMTs12Q^5_qgtNg5b;5;Ju$s&hMZMhohc#3%;un%&zV}g z^?B$gT}xDL1WJg}yDYS_d`9@9_#Y&^4Boo*Y|Z%Qv}y+2N-`?irFYRKjf`llDJ>^Z zpwB+b8lt94xbDHZZ&~VF0m7@GQDpc5POz;&L|+59+O{MzpKDqSyr$|qj2D0@|K(rB zf$I4y5{01BUKLyMyU!yv2bi7bYB|P#+oo?^B+vWDKG+@+t7JL?7hGVSTi_1RYZ)VG zfwksCzDt19cr`oM!TzPU7}es;^5>ivX~^GB|GG5}et=o}kol1Og6+$%dsVt|u-X|# zi{OtBJ&EUU!p(HZ;B&SDJZ)b_E&nNvxjVYK@j~GDOn>|w zO;!<7ZjtcGdptUM?h^-NOTbYWPd+9`M=1xJt8&J0AooZ#Tag7b0uo@*>*7}S1BZ{w zN6iwDxGs^((>ER)7W>QO(SNi6FQQ>Km!-uNnseN!!x2_)w`le%Y2E5-kbCfyPievq zo!l6hM1uWKDolt;g~XuEn|!xA5y)VKftC)S8pc=lVc|Jo+Bvkv{!i6{ldVtfHE5HV zXwsb0Xp%W#&bFj&w5x(**PYvo>2qY} zo>v{=;cK45QJ)f(T5kV}MB>WD0dgO9V9tv`{~@E|=Vu2(KEED8l-CC-j{Xda(&ec+ zJ}tG502MUPEAC_0s%+du%6O+P$U)K2dk9uDGe*1e$&GveS6D_?-<5k!<;Ewu_*YU$ znF~O}=yw*yw_&(Ecj4^&78%4aDZTz|8wHXUV={AlNnW%FOsR<*808$yDGBlyRZsKP zckK9fGPVFJrI$+6CIT9HRNq_1`iDp3O8V7*C;W^rgW;^&VhvH#! z_dd+nze0U3MbhKwQH&Fa&i7?<_Ic71M~l|Q%M&hrDw@oVD$QcV+5Q~J5J2?wa1*lR z<9;7pX!A+w`2i|UFpC43P`)*h;SD9pAOLw_!yIuA#H+^ABx^vk|6>? zAzR89hqwL(+xkktK35Bdq>@AggoK~!cSAqW1QJX0DX2ZRFQ6R2`+fiMZEK@c-^uMj zLWt;<2x3q)TVkzmLbOPus%M%xPU(>+JV;lleLM#dWzzdw*_lW>3dbBAXTO(G}mTO>*R zcNcq3dEpL{db3bMDoPp}zm@J$^VUwsRnHBWY2ANsfJX)&W2pBU5!EL~z2~l_agb>$ziIb9YpYLt8n>YQQ z4A(xT*%hFBdy~|WUy1|fU5ne#{@JW%@{GgxHPn8gK)|*+GGbVYwiN#I`GXSsAG6&; zUoLH3S90Gp#De-5`0gDk+wJ>*=n|pRNyf5w6_Y1yc`Thk%ZF|0aIy@M6Yntw4iLv) zD--Z)5oE4Nf}rIvp4V|`y8RX+;A+4b;%4%~Wg`5LVlgj!N-hviD$qhq-1Mtnp;<@owMV1+qU`l{oTc#F1It%OA`Wmk z-IN%TVL9kJ1ta_Izr0~m^_dxLRsZ?&=g$M^3bwC_&`}r&TeyH(ml_oUt8GDS(hxev zb`yxTN3ar5Lm53~x%cRe45i+SdEQ$Sm(HgRk2@g4%ag-lLddR?Xzt+4jbg4|PiIe$ zc6Sx|?B(uAg2Yx5oQ+CB%%9W-%@{XxF820k%)d&W@IF2nHEyK>RH%EMsfS z;|=?O3l3>sSM|}+pfCs{B%i`{Q7|KyP3Ru>JM)%17_#5~C`>t}Wp)P>U(BdsgQDI} zZ&+(;vf|M^*sKl~6+P!unCVlZ3&bJf{j`;=DJ#pf@iB~2vHaqk6jXLyj=4K36;o^p zFXLcWz0y5>l3qNP9H^x_;=GE6@#5&BrXC?1+4MtbP|tI=VG)lIxvnABlt`^GRX6&G z;8J~MKAB?v)NGr|!1=nl1Ksj62HlJ;CPqe);VxEEV2r5*`NW^Z$imt(8B*Y-^vC4frekV$% zY_^}df%@;gKW$C(nMwz|8nd-(tlvsW5~n8$O#ZQqf?6H7 z_H~fRlrT^a;C0=76pl(~gXAA!DA<#0rkXSLux^;ZYiOcE;bg|=96{x80A+S~bWzOx z;I%LE^XGVDK=}J60-NyWZOvR>zjjYi3PtW6)LR0Bc`&^KMm8~!nm`{T0tN?Js#RL+ zZgxBbqL8skOqeLtTkW#nD8Ck1P^9nu=S@XaOde$&V&#B?9F#D7X!)_+cvZ6k2j0lW zw~H3rdkOIl1Zg*{7h~Z(VlK@xUcYWTxOQ)4A4oKV+hgnI9P%zE!O8NKqt~XeILj;*W|KDTKe}w*I!lCW*3N9X7 zHa*csHEc;%{{#(A$otj)+Ke!njzr9}t;6llwA-AeusYC@Vu!8eP1p}Ss$eA)#P+?; z-(paK{F?^`!54Ely3^6wD$eUz^O~Aka%wSMVq?Q8L1S=~s$JZ-2Fw!n>Nub5H2LoV`DhYsR zow!^?Qng2KW-l7g#%!+_Z=2K@s}aSy7KOu~?}=+tVT9xz7sO#f%#Q|6yo)va*J6U) zgq=SHOG%E4%sJ_m^}J}ryEVgum$9?bGW)HgacMt^VBpeLeb-1~`3|mE^g`f= zMk*xnFclJvgby$|*KZ;LC*d-6GY*T9^yj z3o{+gt2X#-NMkDMxZ3sf1?pUkmX^hHRo}r5zy1{|4MH5`ogU4!O-x;%gYae5B4~xo zmY2!xI27&V)5$g^;^9PMSL#Ad(@mppf|nPYWAWqhpmHNehZ9}oeJ)z~nu7=C_$lSW zZNG0)(|2h8ZtOSCz1mPkF~hYtSi5ll^~<5{_YC*T`e+t|C!X9`;{ww<=w8sHWok@q zx9+{YJ+M4~3zF4ggyXLcYNf{CpezS7wc@OCe^`@_%wcw-bokDP0ph4YA~N8THhNDM z@p*72urkn{eR|7jC>m)0il z>q&M;6RRZ2!t}_G#TZ;b zEs+6W^i=i%k6}i}?A2`?%)sT-pjhT`?iMtSIO{s=IX5yeLU5)8&U@x?!7$vlUCg{(xRWN0?;>I?pNL(0LNcx|> z`1_ay4etMr>^dFI^RU!U^;RN(Ksl;>FY(!3u_jI1O48(V*|`A96G-r>O4L$gPqnnp z+lvDL$kGYHfD&6Xckd#qtWvFdT>pA5LfOIYnQpodo2q0&J)a=$Se4q(aYDuEj!Pa030!K(-*GT%ZSyd-Z3vWqRqakBo>&q>sO;f$_SL z6t=7v)Umz}`vUM5`);3zK)6nEaUd-S3b+=VTwU!qy~Z<2CL1kjv#XRhNZbf4NUk>} zi+VmJVn|N)v~=kbp>e&fbqXFDdqyn9M6=H<;0n`T7OOIo01iJqgC^f`#Sl*;D*ECio4;+I-cWE0`nWH!?sHkH&@{$q}q}ZIr3JM2y1pnYfEX0Yjx%`t^3bL=rYDAkL`p9}rvvTcAgw7mDB*oqNZp(u*R&pX& zx9nKN?_g2%hcY%DI9HpEJGo&&fLDf)ALsk+{U}McHfN!fC-!Aro{e>Lz2nwoAv;$@ zxX@wr9F_A;ZH%u*%#B88^`}WS6*q9jtx^FQ&q1-N1ufe~g9Vf`*(UInUkPkjcWpe4 z&w@-JZ;j>S|GZ+kd3N%imC9f*{;*2rr{IfQHkw>P)~NdF#m+t7r0XAz&ks?5#qyw_ zgV~WOIiupej3sm8ucd$YQ~zRktsFgu#25DIXV5+??Kh^Fv}0+zNr|lo&K+>$@hc3} z#l)L-$3r26MXFK>@LdVD*X!SMw}#oYDh#Q>hk|1FW)cJk00rec+UbeHGR0V5mjmBf znVzC_LemMHNbN*ehvyV?IEjqpMCpP(n##vVGzhE2e53>Yz_V?}+A&a{Iq~fuGJ(Lc zcL&!VeXp4QjaFcClnAf{)6gh&>dTK}4nH1X)-%q>g_a}n66@7j@AJh0>GD7P;%w1j z8&F~+8G3een;z7}K-&@}0Qn!$1Q89a0-@*ad**~dft^(R&U%1T7agv&tubH)*c6gFpmu9xQL`Yk)Vo$8>Va<%F*#dT4T~hs&0J{ba~c zW_#A|)seEOu|y}LCuwGd;Ch*?JN9FUZO^G*gp#5XszjntWt2usQxl@ad*(se1(zSkij}05uJbg6~gppe5W-E7C0?B*oV8ND$<%Wbfwy$(LXt9%* zO=*K*a)Ek{AZR2ZynL6;B^*wZ!yFwI1%{7tFSA9ct?n<`R?CA0PC;+ternmnyZ1qj zUhYHm;@-4xjE4yFW+$Z7e%Sjg+ct=k3wdl_S@?6*cf~*90VR3@8y9uh)1>kR65Btc zM@JNkGoKE5Y(f9#Vb!aAhbEl>gYD&?%Q7W}am(bP6lS?GY8Jvd-nSM-LaMK|LtNH9 z=NnqTA=kn6trKTtYVw5agSAWrR^Pvq>3tF-_!3|S7;lUO;D7H7>JAWA-q+U$R9wKz zQ@)3%E@5nN-79#%V|KL{vjD(!PVxd7lYA_*Dxwg zQ?&e01f(I{&4y@^V_Cc|<6Lk_;$W9;Gyr45a<4=>fNMhAw5?*c#g{@5^b@TaF52?wa!=4KU#;|2<`8ZgM?)t!!mPWi9C21%xD&&Os=)X*2gAE&#Ycy_#;tte#cCH$Ax}Z z76&aS1gum_;y!kzs!2{+=-oERR<>&;%wz?-H z_mV8RRMU3qaTMmWAh9m75!y8mL#+{(o+Me7pcs@%8y}VQ0M`{XNLuBao1R=;WnLl? z@6)G^O-(pZdg6^>^a-x}tA7d_prd>X)UX59*mU)FfNT*OVyuZRhKsbHPT7CSWk%IB z$;*)@OSA(yY>gRf4LW<%zNJ6CtXe;qHI|mdv7-%aX<2uNb5_;cO_jNawh{U_Uxdt_ z5Y1#u{HOdBZ?5*ji^(>%nY1wqee^neOB2Vf-4elAmlqET@LZrO{E$gPS-M2=fCG1;M`ahmHe4jcmoGQh~9fzjSRSdXiLl)bJee-KJZrGODcVZr!Z z?9as-(8g=JI$7`JC1V8W>|Ux3WqN&c772kj;Ah@Ec^G9Y+HP#4{Q76L7iHdh!1~?7 z_EWtFJEy74;m^!=rz6Y%=q{Z#>`ATn&qjb&be3R%-wr9K40ZJgng zdb=$w`Ein0j;;m>wG)vTIGMLmmUN&qX1}O5v09lX3iP*Ik(>k+5q-oO=#t7B{CFU* zPR9_q>|$RtzCzhaE!K`k1X5g?6EPOI2Xe|m&jXR$Oy!Jq=1HOw79!!m~6!v$Py2Ujq?_u@rr4LhEaSPy0O@&}4I!h8Aa z(j8-?>J8qg0uul{cU17rCSKbMpqB+r>+u2xoIBi7mB%iTbEAts4=?IsRe^;*&V$+@ z|4@Fm)=c5Z&)Zu(HHKhionfRdR4IZD>JCJ}gMsQ!Zgmnf7Z;LG3f@cS_d2UZxLdM{ z;=MN+Wagai_i+Bi7;wTLu$o8$2EK%|Rj1y*cZzm%ldhtfbN#Oj4<+61&_K&goI8@2 z{A8%B*J8yo9*%cPaRb{9w!{b`F`NwE!r>?o?6813y`HQJU_Rrp>7?WG*ay%hC1S$L zcY)N@3HT37n4u1AYtpAsR3NKf^j4Lg6-~7S1Uyr3p9;qwh2ucOiZN@!+T!?|H`J3S zmR2Jy2FdyO+cM{j<*$mXlZm0T$_;h%V6zw)8 zyQX5LgDRGg<%y59N>D)Vv>Aw**zy2|km|^)0yr5s#5g$I@z0pD+}8ya<6ua>!-~gw zuDZPcY@Jfi%l;olYVaP@W_+UkA5w!q+@5kNpHZls@|*Ox8lm%Av;&@I>&yOF?tQqT3f+M1`r{8 zNI_Cq*c}ax1K_|o-I+jodFbis%QSa?{~Xsz9Q^*hlHCg=^X*PmfEVEn_Ov5P-1G@t z#P#gMdBrdfUL_uYqaw<5ATV7S))(>nwSz^|etKk*__h5q-A~W=_v%f|;?=L1B~0kz zs9@{#XfXc|sX0Zx^82PFNbjI_3UP)8VIc5;-dUumpEisd+B9ym$ZD9A`ED{9*P zhSGq(sUWqUqT9QXnYX`p)@S@Z{wzyH&VXr4PIS^lSoI`>+v}FpUX7u&=Y8KJuB$Kc z+Rr5a{|QG;DnFk5=~I~|B7_^ImIhO7ix(!FoRSg~op?Ck-BGM3o zb~m}#ieK~a7mKdL*yl+%n|=NzEc#OX*<~)Jw6Ea4thb}|`Wiqxe6qgUplg0RX>u=k z;=`k%5BZJy_nyYe5}Tc_nyOXWA4wdaWk#x{^unLs=b9pQIID?!+Ex0$hwXif$1g!U z!R&*lN!bblgVRpBl?Q#HgEe6y;?PoUa0NzaPcXM=kd8t`aS6NAf zI0AY@plSZ`;|Itye)fCav|r*63V$c}r-KZXP5UKNosihNIU*^}y6?~D3Q&|kB@;0+ zLK5QyLa8qP`0RqIe70USipPIuO{y+-N-8+HxEv_>o8~QthbDpQaLQxj_K1{#3$JH) zv?v42f=O$0nESgVk3TEwB&u9@tVD<$5JSo=z14VF&w!3%oWw#2U6MIQJST=xw&qv8 z*2NAisA)m>gN&h?to&RRWd+!LU^Idv1N;IUdGOHe7}IA%&2$>Ifo?OgB})bHThap# zKuEHqGy^ao*DPb>{rTwJh^IW{UN@r+rw^6OjZ~wJqK)$3P`OS{O?}8#5}B1l@(Gi&TBVYS(iU z>!@Zswq2lyUjYvf1U)LQ%-1n>Lw?S{J2ib4Yj;A`1Mh7kT4B}$?JxB^75fwMFgO`w zg%j|mg4Yc?BtgBf_=0{0Xn zqXoz$fG*k`Qq5Bfru8ELRR@^ltn0Xo-8d}xq7FNeAJp~PP`kNCTucb;qN{jmE(yg> z*<<3_*Y2Or{5;y}dwls;fN_%dL)SOOo+9$Xf|gE`8;(MPGmX(xyD0?uXtpv34WgfLWB*%(l8+Vn}`x2C3*9Vr|S`jlM44<0zmFHL8%w9%qplm z7p5uJUePH+_)@9?-0(EreW8E77m}(nI$8{q`{FQc+Rp-kf!uTF*E$4UM6Mw7157}W z9IKoz3|Aug#~Z+6K4VgqtTndzds1w&uPz4g1O|tPDMH|>1-nhLvbH019+lqxC2P6) zL#&BGyKZ*eRb8^2J5*3?ziBdVR~Z|XyHA8-T&FGJVS8r z<(#A8b&i~3xvd$@xo#hzojqHrY_dK7iFTH@#_A1qfU=NH%P=ifsIFr5p{!R6C?e`~ zk-xEu7VrzB`Fliztlh;y`j?a5eZ&zG`3|t~egHHMnp}{mtV*)cpTMT3#zZmYRYI+l z?u8ENe(z2CbL)2vWC?E+*@|LB&n}`U;-QDoFLvCz*{SEx3;)~8l8RC1b<_S%8MQ^6 zKNOz%rXJDuVr|LW_aUVHg|r7yB*86sCW#GlTrx|5tT%eCMF0bX;KwpHoghVEIzJm5 zn;?Z0c32KJmPK6Tp)=i)kJNj^hj6wDzDl%a45)ZNwcb=}PmRrco+z#E&9EY^3) zR$x`mLZ4oF13>xRh=QguxtZSmY$tJRbzD!d8JbOSt8#IF z2otFMcO^+kg_!t-vMb6D6ym>(qwa(bbr9=$IUlNtBjhf&?}aUTpPT~s1^U-NqGknF zzXxQw}ax;etI7tO6Z{TQfeSlep00aq`bzz4g|2t8U6L-t4KuctS$L z-&=?FbEF-oq3r71=(hjh@1KMAqj4HgCNx8b>nX&6y1&P-g{ufP_*-4>EP6TMNnns+ zxl?B0Kp@!V$=@!&?Gx!UJ)^lhm*sn4dD_JoX-}z}Vq`n7TfC%O`lQU#dgr5RTC(7T z*Id|nxAVr=Kd3AZ>LOj9YbB%!zUom;kMv|9E`UTuEpwgx(N17LE=GYFfPO` zAkdR?awQ?J=v-R$L<-5{Mc4PHIN`TBEUp+ZLFpm~9<1iY%YmXDV=u25c$ z`C6J10lwwM(w4b5=(T_wdWv9=&h;4i)>QW8+^Fn89W_2-Kcss*DbsQ`# z=e-7PgGU!(EeaS&D2#&@`=Ww0s02t(aPEY_e+Y`b-Jg97S)j;5tD`FAqYXOjf4D4$ zIyisM3gXA`rIes`nO{NvFY|K-_HInjjNF@DzpWQC%B>Olbb3xi2+Fd`&@A-07rIVFH$tQz&Hsi=TWsZJLF zg`|Lad&8L=JWCxX_vOr+0EKZnY**KA%JQ|`x`!cAx83+Ax}5rH1{&9;7wL@K&&o2l z*RR3P@WYbZl0MUV)D>)Mf$o`|K4{&k>_T?#`|fCWUp&)EJ7LN+oxP7eJb$y4!z)|a z{kV^*IjKFjBJ}YVkQ*-S4vg-5m0X@itGu-ZTRZow6pQxbV>QpCfYNc$PTelGPq+1$ z4VyeyBDjc>{o;X~gk+0EE>oMfx1wFY93H(7%uYzXKvOx*g4$f9q(+kqE7j$Pl|$*A z+>MKAZM~ZA$74#l`-&iAWETdo$Gex=jP<52;SbYYFnKls?o9CfttLPm1qrMhhNG$-eCxZyYQM9~(D6KDMBIfM7l z3{SpFD=zvrtza@1+lmZhNrEB7ODiP3@|zPl=a85qDnwO*RS-CR#`rb_IpywA-jj<1 zVOMY)+kDlpckmZE(j;D_oW@a=XV}PqUN*~J0)-5gWE;jvfXAVF{vRL0b zEL>z(_#CDbQs0i1aFNI=qN2&KHymlYD!#if>`X9y{@-Rx)e+YxC@&!6wp#Q_T9?s9 z(~~O|tTTSi8ovQ4nv*x5A9;mzc4cTVjdcCalN83YCmc*_gTp=;!v_91Dokr zoLW>@HT6&Q5a#Uc^B4`t-ng%i*h^T7(}O$A0exMO&HHNf!#zS~jf=LJ^g8C(#sha4 z<4^&{IC?FMe4B)<rhW5a5F4jUS}$1GW(vLR79~Tmz;ifnqjKSjX)b0`){3q^J_k2|KvO8S-lob++zH# z@vY9>sLNO^8xm+7o5X*Cv8pV@8RE@OgydxHyW2&4209R5Xjc9s0Y|%4kpN-niK>J*B3lK zFlB-{C!AZCXc8e*Ef}#C?d@gDHYV+2^RCI+MC)RnD`tv%T_tGRjk@{_IK`1j>lidV z7We#FBk%1;^2_*JG$()6`s7X8;{m@1sO4|AvMYa4ZF6Xy>bGWl`hHm+ z368m?__}RfyZ_g}s{>yFiEBrm*dkaiyMoEeJPb_9_9flAj!Zt%F%dEX=O=Tp$cMSWij#vQTS=M-9U?-{)@CoTVhsmM+kH2^aXxvxpJ{u_FLUDz zon~F7c7Rmsjp(@B;2G;mzEsuxR+AH@7H5*^aFE(T}s|DE_DV zgy0oRAH6nomd}|y{S{p;X+k*RL&hxP;zH09uI%oN92h~&>OBdopEcS`G!@fmVXvg1 z_h=N5x()=rkb(j}U?lWPphHl4s5BNxBc~LvZXNmUwk|tEfj0HuH)PjPz>Fv+vfq^- z=T^9#{@&=qu{=L-TPFlI^wEeJ*J`CsMC>|6xe*X}j27L!`Wt(%)vkx0?=s&m4{h0I#PL zYxqPiPB1!`8Hb?7cmdcT^2c<8t&w0WU~`|S9~b~*TDI`G0+xb+tZN|h2!UhMxg&rM z2ds>Ne$N1;*2_y_K#?S0bE^`LBID^?P#&f}+D)~7YVYNmLT6I-qv9;U`56)V6Z`qk z>VP&wU%qP+@S8ds{7CO;LF)DWw5Zo<;dcstS>wNXCS(B@sw0$90WvzXr{RzEv3>y5 zSIB~XwCFoXVl_ZH02cIGR3xFa`Dq;YNveDH35qd%aQibPZCM-Hb3FEkTmtj+|6T@E z<9yH=!-8q1td<+budgn*pNASLHe>OBOHTbuFU2rxrN2LSxy;^gpt z?nt}2WLMoH^-7!v2suY)%wR&KM68ybO+n3IYFr&n@~Esp7Cpr5DJCA`w3Ly{#)qI~ zSxzT$1Gy*wsNZmt)XgyBX10DEL&Ki+(IMi4umycL(>q{51~PJT&jRAGT;!XPP{zR? zXRk|6qJR%md=>1qf< zDlkN_#m0@*#ec|~*tw}^uR@a2@VrA>>!TF`u`qezpG`KdO2hqhLUEmHyC1?}J2plP zn%ykE0p2ugz~11;o&T~{PeTJO-kVgwA*+7~aFvLlSa8G2eZI&&Ss|F;0v54x9zhHs zkz=gyKkns3l5oQD97l%QC2U`#n$BhO(g6`7R){Gbu^P)%5p%T%Zq}oiazr=!| z*K*0OEc8%hf90Nwuo<-H&In-LjIk_5gkW?FcD&mF{Bm=FyG z58UXz!F3B+e|E|-J(c`jlzX}|EV#?YR}?xH)!wQYEPt?~eEV=OXMC4#z`5{nG>kbs zeMeSoW$eD$>>XlZ`Sq5wS(^jz3%Lv>uo_|xuLoeFpcE>=xeI^L;DDH80{tqFt`s(% z3JG`t0>uMQI8`G%Dm0z=&({PT2%gwDD4*#;Yk}-wh;hvnM;F}Cj5T64Byseoc%m3r zzWwPEQ@(zmV`*>y3*cFnCVZT*Umyt!+{?LJgYx6wyVQgwhk>!x<98S>cKYn|{l!kS zx7(DqUvbl|U-&ZIo%|S0K!yIkBNj_K=Wb&sHXGZ(z;&woY`#xNwBH-m|Jy#1;B++6 znQVQE=M+b!bfaCGWXCi5un(Q+$Ji@=Q=FE%m~PLRK|?d;CFH?2HDdBV-ke&yTK$GU z%~s)kH(oGiGJ-qiEIBQ$1w>^7=Gzndyp(CQv#(qz%U_w*7@ZHLdP>e6$e%*~3AItO zfKdicWX(xe1G%{4hu}v!4w^eg78HhNzIaRB%P#SR_eguzBW6sLHJ-mBN6kxSrF z7dl*0#6W*0ivo2CS2AvbH9$3R7LX#GN+wiEFwn$S1wlPR|CB`LtGu$pI5yq(0qFKa z%?_6--f_5R02V3mx>g8+r_;v%NFY3Cc|$5YmigtLfM^Z5>>ap&@DCS};eO0}XI0OR zQAk08&J?CVFF7``Fo*C?OTnvaWsN$EF$5CKr{C^-`)1hwm#Cy4R+G5ExS#+E0zPu3 zLQeI?uG#G1h2hV5ga0m_gR6V~O%JKx^Y35k2;r4jc-aux+*|LMJS2N-vHTEI^01%H zNME~w0{!c#50!ln3g0ZXiQZ1-;PGAx$E2e_$0w|=|C0qDIag`lbUtWvT$UgvpvTk8&?xv9^y@1-kE=35$ zDgAPRBcc<5>v0I#T!cA{4tjlQ`TeRzK3myRuP$=NsQLL2LEV3a0;QF}qC}FuCRh#c`5C15bfC@Pa?_rnc-y^78<+yOiY$v|Qh| ziSW?x%7D>|OSX*EF`V|ei3-GwNawz`JtFmXke@KPL=ljr5&f#d0&-!n6$3DTQaIZYuGZ&BF zB$1BOL1r_mMM3*D^>z_C$pu!4W?&cx`RhMy(S+{5@CEP;U0o-t*&{C{MgbtKiyK|?eXy$W7g)dp4@I@th?7rsGMcfk zt}A?)!vkZ)!*ep6Wr;A;johqhrZt;^l?I^7Kol@56d4nPCIQ7>n4f3ACA}Q=So>~+ z>LQ&MBA|$fBuNNiZ4q-FfGh$+Ti6Q%y|`RHJ9nJUlKJ(`T@3ABz5D2wsNa(pyTP%Z^Mk>Pu0y zmnM>=ztUve(6Bh|2+?oaF8W{5gk~IJ_y3ss?s%@>@BOF!vS-K+Nj6#8WRnn*6+-q( zR+N=JvWtYs-ZPX4A!KDIgzU0c#_zoPeml}!5@V7I`jgt?cWC*MW;msvFbp<91HbT&A= z+uCmS`GH#ku7$1S*-(+bOUWql%)Uaw0hxN50Sd|dQN2V%UlDvSn$w<#k1s_XEVHV4 z+VtYVQzq1+c!V_s80%(4R6N-7EtZpC4aQi&#MaQ%RD_7_)^!}DWPZ<|`LSzdn@Eq4 zN78KnPw}r{o#y7=1b8t~4yQtHva-S$@v9UGHw6*mDbEs5>HA$IZ8BdLGpJjakBwBn z++NZe`El0%2rL+ZG9dbc;)cSOVq;C5$)241#{BW#T7lQ>N8n{30)m2DM{qhn*A_GT zd3*@lkH1x3^1$=^IW;-0Pv6d`u4JiBVal2}9I{)>;^|5$l(vz*H>iF;Ozat*ZTWVz zL-XsGGqU%8Jwb(uuFXF$|6+TYG&T=A?SJMye*VXbI<%_CGoZ(N{aG9@ol}@kfc2dP zjIyvj=P!vI`*s(1eBNI2sNKz-+HFmEw)pu&W92*h^puTfYGW}voDJgAxa2#7C#xrx z_v?GYE@eDmEVM28n*m%ZZ^BLDjp3~cYsDhbQjJ|UR(o>cr2w9#hywAuP_Vd zQUeFbvDPQ5B~1u8JU>T9I!#r)Rt;Lv$wQudAJEj@{wr6B>n~_}HD9X#PVvb1wW%&Y-oJddPw(>lDCvh|ogdrEp?)_X zEHxg!_S=dDy{4pwV>p{?Qe0R(O+RNJ1@f&peVi7|u=&fjwI)0!1g>hQ!}oliP`&-& z^3p;1{Lif!Voc^G)&tL2ss4OBqw+DgPtZw;W|4OLsR$%$3ToszJN^j4`zRjZa>LXN ze4yQTaGehaxdkO8A}Iyc5+DK^kVK!iBv2*k_|4E@U&^fN#u7nY;^gjPr+zeIIaFuS z&B~A8$b}b6Q&Ps``o@UI$$I&n&khFyVmBFwGUHu+-g|{0j=WY{uc))`lO9e!wXyhh zo6hg~(T12kvmxHF-R`m?RR=VPkrwXq({xal+xgu2Jf!~5_oLn8G?Umwo}-PiDyf9c zt^C)qxA#Z5X^<=)4l^<(oi3q(xLjSXn3$wH8OoS=D*53JTVtT;@sGZky^AOXvTZ#$ z{;_-=w+f~Z-ekUE3)5ezdJ3>pr`cgkGU&~If2)z1k)AG%UQ^6YALu)7tP$2eRKdn8 zySR9YHGCro^%8`&I3wr+_52C5+K#j>2AR62Y@WhRsX8@loN<1@xbkJJZb(>9I zp6t4RlRhRCsOT(IQA+P|uULN)umU}t`#=U&wM?@~U@uz>wHUV*E*dFXYg9{6O{mH9 zAMdk7lWT^BAM)JTW{^jT<1);M7zCH%nK}P}7T&MEm6a8zo6MRE?Z+!indMSf4txL0 z1^ChUh%hkrPxxu? zQMmCF0|a-aAgS(4cfpjiD)*Id-wEO&h-EH{d|{)lefcIek;}}ZxYCYThX3GA3M&|A zixQ4(6v5Uo^YK>WK6qMCD&fZ(34J1&`1m!APn5cksaKszcJBT>()0Mw2ROcE8(ZR? zd_awQDd^fS)pAc9D}sZO3XkpgI;G_9#q5XqnY4F^icoFO$)F2SJd$92@wV1rIcWX= zup~s(62|LF?V!|rtJ{rM)CYv}b}t_e(1*1D0_Qq*eqa>bdFREI?}uC8UFP$FPLGa! zi#;tcgkz|pQml_+Tgh2DjhdX=@7|;c|AqJZPr5Q2R^6?Q;D`)E*%+GUV_^F9o$oyc z9qRVaQ`i$m&s9=41G_mu=Eo4<0|nCqK+}nfiCL7tB>p4esaI6~JQQR7sdRU+MmN|U zNY!|3ewixEcGNvhF7szr_ic5<(xGY-2=R~Fhr!?Y8~@>kaelaK`0nxI7r|(ejqjQB zHrt^6b$#e{Z0Uro&TK_eEZ^vb#vEQh#}Ae5Ju0UR^|%MUr}V6$o>ZJPUa^rY_er^5 z!bteT*aCm^YDb37`}glZQ)qo;YB~mz`+clp{^GIK@86qnC4)ApIEb8R?`i8NlL5}Y z{QBz& zGwbVa)fI7mQO)nX`wymh{g~TJuT}1RZ-|KfyLz;!Q|Dhg*rj0xj9GtK(z7l`R;WMI z@`{SkoF)dBZfQm&tBA|2%R1Jn)mZ5Gs##``I3a-g0T3xVuL?E`_tAI6A_D z&ySJn@ozsyF5}M8^&$OdH#-dJXja_Fu++GQ&m- z>Sr7awtAxk3+Z?4V=#8+xT(PBw=l~SSGGpqX)Lj#C*Anj*w^eO4ldShU5j>+J3db~ z!i0#1>t3Z%Rbz{u&O>M+&3lnx0PCz@UYqjRL+2{f|vd zkeILJS@U7KgndeGL0dQFlme4#VFRPOShTMNE)o{5c-vfi=e@Gs9#Po$M86IM*o$!x z)4aGTjbiYeIQIoX;*}LUr(lPWh*x?{!+VR$If0)kHAUyd%O)JZRJ}?a^CWri2d5Z( zM5xSM(m48e#3`{E=Xo=d1)G9yb5|CC2832n1DJwxf-8}y|JV+m?(EPJ)1M`4wf~+q zW4D@hCh3R57EPx|fzR$Suo5=?shTzvmR!&f?)}u6wZCKx_2?CM9rO9yJ|T{b#@C4Q z;$ob00=*7?-k!K6E7-piJ3lM>L-;1d>%~A3J|tkHR4u^}jOH;q-Nv1bxsnlx|1c^; zjXQGycD1peOG-+@*RnW*d zB7_Vx&H#pYmCe5!`{Do4fET&)n|=L8%HqMy({n%p(x)k;S-j`q);#|E@%%Bmh>L=h zoRwi?3$%vczn)YX8$`1vx#NzOS^1w%Tzx}=_{tZTQ-cMIw^@#L`_(M-ng{z*-BlO= zL$iBUbz$66vez^21Gty<_MWVwA|xN*zfzV0d^??^6NZaibNA2HbtUPY{>o0e4v7p_ z4?1})_q&`EDN>DN;jPEtU2e*x_1ZQZ4C3VliDT58HRykIR3-ZzVkSybDUoBh9-P8~ z3zfeFu)KSNl#md_^HKvzpKYt0LAeodTAw*k()lJFLk8k|;L(1FSy30mpR5kpGXXAc z-p^d3L3N(~8!3peo>Gcqr@K^V6^h@9dOt90zp{h)MHhx4;cPfz{uM&kqlTS3Gnw)| zAcq<|zpx(@Gl}P6<>_HLwg2S{f$|4WU+KEOz2#S~bG7l_i@3|TSyuDxj$;{>x2O-M zQv#zHum5jJh;P^)EKlB2n0fjxJ2{~vCjmvtP@bOHd7xJRY{&n1=c-JG67jEw(&@(4}dNR*^zHmjh6_bW%5&CjZXBSV@ zmn$BdBlfpk&6KG+PGV`jz_ELDB5OR*RP>N-lMX@5o(;6(s9kFzm~+zFXze8#@4v(G zzo1L%oJ{&;%&i5B#yhQZd&g>d{2VL>R)!wXQ2+kg*Y|0#S8+TAi%e$UCBS-#A>T6f zYyaap`Nb~bn82h-lIvK};*8!BD_OMRD(7UQ4DURN0(@wC|46CG7`_?82Q#ebL)(CY50k;ZM<8@ldn4JYYO^I`m5uA@pLNKy{+|- zr4jd#RLF=`wlAA*X(g;L(s6ZfQs6-?QOGHoOsFf}vMNo}`u7Oe+*=QqX6>|YW=t9z zZRlLBUD>T$zia&qJ)B`vZAXhc`tD7Re2TT{SepR&pQTubT2%N_BNZ(;h{>4JUF>HR zy@HG4&i3|PY6;NNVnJ!Wmb%La+WQW*MrCWB)IZ-uv!aLj#~Fj?1v)IDK>6pGnZs#$ zU5zj1#=>@4hV@H2<+?TcVi7aFI+DKydQ69W^bHsDZC(+?Px+jpiCO2{9}oMUo}8WU zou95V>gx+Gg4=6_)8lI9!Rk8Cekjs6ji@D7QYO1FG^-qOVMiow9BsCdZt1@ zzt?`2cAt6P9=;M?$t|Y1WV4NWn_2Q;cz03nr;kh|D+qu!gwKoL1Vi-7`U}I#g2z-Y znO;@z%F@}@Al9Z^RBDi6FS;KsbSHwL&64=0aS)4n^VPg33l_{r7HGR&%33g2gB4o= ztE_1b^+4;WAgd594d^^k>D}FK>v9(R8O@vQMYSKlP0;jYF7Tnt83EF~yOw!6RQ`0I z=1>0zw+(|c-fuE6&8UOFdeJu0k;g|~lyI*_cp}Cso)~#SNQjt`VU#e=k^QGEn7W_# zYo}lK<3`_)Cx17vyak}A;T}#jfH$}zPa7JzqZPaSs;3Szl@|nV@5P=Eglz&B9k?Th z^iFse1S%_h3OC#=uaMJ*z0i{2#7%dPoXY_*bgpC=uMRTq-IjZR=PNAL9|aagoL~wH z?HDR0&Tw$nf!TTxy?;$29PG+)MNKy?kEjhyAK65aSsyc|jri1gOyqNTQjhgi-Azzy zsmhHD^-Qn0N%XbCwBJMO{v)5MKpIn<2;+Y5_R0MCYEC-M8ShWjqGiJ__V=a)dl3^s#eg2+ zaa4alzle>@sfV8*15zhibnwbm{qCXY;c+>}6yQ`7gCp-QByo6v(up&|NN3;K5I9{QZYcrBh zw`iWa0Vm5;c7UWAeAUiD1e_SLP1|3u?ni4lgSfA5zwy~1^XVYkM<~X{FDH{(C0lzx zd3sVhHgagN&+pG}=uW;KWcevwz zYt&r967)w)UdWR{Q?91wn|-aavNGzDT7vogD7&=gKlgVCNg6^dZ11KN6(y_VOfy^1 z{>&m6&4F#s5vz3%>k>OUrTz)A-Vi-G1AegCw9)DvR~$S%YIF`@-d{ zDL1Xu$gn#JOALZ3t!lHXc`yQi!@sj0e&^N#*MqNKM>4-s>0}@OrP7dvP+VXoeTVQ@afvU z^PZ0m;V0x=P5E;-)x=sEAwYHUYuj!De(`3!W!NNi3FcXOyj5h3p za$OX+^!1*HOzOQm(g&xfmI68$-56&*(!TBk(dFeUsw6DkFP0zTI}j_p^4#6Mz(2>< zOlNo;!lfQj*DP%?*DO)wbd{4f*_#UqO4EhOGdf{lnNeZZkuXjV`H6sqT}se%Ss6e ziD=~%V zNA-1%;t3W^b3rKv(c#}7>3bVm=IZ{@TGAoUtp{0dlcp$PMSnFaZTk}K;DtV3Ip47KdaAId-Si?umNOO3tQC>VlU6))^6 zesy3|Q&-j1)fTY-l4PeB^Fdwzo|&0}nOWZ0+Rv?Yi3F@SkM^ANYjPKeMBZjMk}W=q zs7c0FE+1RlJAQfXLEo$E8il>AYWN~=-Hy2@DNWy!vH71DhEkW$=<4|>-n291kCF3L z!Tv3rFp!^g%))#1dd^@C`*_B2(358fGW}#=N&YOSw6v6%nE277N6W_C_EPfM)dhxF zM*-p)TGbOJx`nT_mS$Un!9@rM6C)Ai_zRaqU^~rk4REtPw?nCiVIc9UNuZFLkiZ(R z+HNVRDG38l5w33xo##NN zMXOuR-_JI+7y-qP`-ckx9i#UJ+4PtBZpet+i%{&fxx z4o%Pu-`Uxr;WbiZbl>`^RBF)VcjSKTGtl|6bKd88B|raW`snCro#R9m3~lcXsxadq z8Cnl24Zmi}{@LBV7)_g&AUn7NQrI79O{1$_>uP{s)b5ijc)hw6R{{R5gxX#fByy|4mPj>W+4KC2o zJbv`f4<;P$Jv|kXC##?KoC23F57=X2=KF%Qn&(-Kvf6`zcQ7#7zhFIFK0agYwh6RN z?q)Z$;%6+U3)$WlYA}f}7{Q>ji1FPkO^WzwwSR3xL>bjy5zKT*_tA?Eb;-`#qS8=J zO^7LOYI1Vbvq_0HUYpaS!NkeQNs5X8@@1SO|E!Goi(K|>bi%gJRoPdUm*vhFA*Sd* z&61*7CHmY?Qx6a`pd+gqx7BKkEWs~2fhN05TWp`T1#r^d~jKn#}1i0!sYxN1k? z)7WVvR3oOr{+r~(przowCS6ghc1}djRJ7pb+vaTo#P8|vvBt(m^AW7z2oh}hnwlCtJw2)m7h>qeNRTf*Jz!bjx;`$LMBQvRoCmYO(Ph3h zwY6>y-<_v+LP?or{0?0aRSk{DAlD)b^Q5^dNJ|Q@ah3){_6|5qIZoE#A2~Pz%nY_` zK+$Q=Az0wzpiF46h2cUBcn)tQX&pzxvO={>9&^TOl)LU^lZfP1-z^lRgR}(72}R|XPpzD zWs>+^3KkGwTU7hdM}Mvjk>5`Og9qXiem*6q!QOCRO?IC5Y^nttMO(!NF3ZYsAOqGK zz0?c^vQtDT7I3!NR1e7_Kg~m+u-H=fs-8B zWhE5cnl-i-Ux`vr99;2WAbGGk+e+~4laBd^2y*K6EwF8UySGN(wo3=zwnO3l3HLx{=W&w5c zG<*_;VcwS}0$Y8gNS`Bd1r*JEe!YAE2L*oRw<6;k`|)fpT*X>iS};Pnd~I@#iFTNcUeS2^$B z{0V3Kdy^Nx?gU25B6|LD4H9uNS|YH1wiTXqtaHX{i(kM%Fauk}o)SW2CH!C(mO>qI znn6#_F%{K}+ov3WQkAl}?0S%xHSai2!j8Awxpxh7G&eg)NI1g(dR8WGV}#BR3Y0(B z@g{}j@@-JajC2#EC4z&>m5eF(@Zq&%`!7p7@sWW>rX>arDk@=`95-r7d8m7AsxQ%y z<_||i>tG;9!P-u2NfUVbE3@tmstHt49S~RjWM<%Z-0+miEZ627kU>wvQ_;cY-P$r6 z*d^U`YZlTyx)3m(C3eMua9mgc!onyUEYFM@GQsu^%bI zWAbiU<1))Js&l-!XK?EdKDORhl~XVZZJqCoJBM^Dp=S}iLmL_zmUn9MA9tDy2%@+S zRJ{o`QFaF^L|lw!?e}vvT&pEqLrAk4p5U6{k>@vvT5PPX$eQ)IFL%m5EqZ^MPw(}U zpZ6BG*gOa1`xzNY!dlH;#Tk+cEJV}c$`KM%x~Hf^j+fr2++F)^`-e?+<%DAmDVmik z$v~3i9JMb$iASNWox&T{@pA`s#Lcp`T^me_qCzNCASwwNKa$8`h>z}DOrNBC<>+Zt z^xaC7o`@r(yJV~g$BKWYZu;kzHyq=EM7^Ys^d!$00w;|fMT;*eJP)8Z`nTItLDcWh zRJ{vGN5F(M?B98qK=VG_v_L@7#tIT=(6@AV7Yb{;gtA=dif;=go`T%|_ATklR0QQ_ zAM6EaIkaA>W<>TZqJ#YuK=GA^Ufu1C~7+Vf+ew zx)6^&XnE@C>+db~(h_kbuvbuq(41Zk+9XbkaVso%|K1TY4YI^2<;dsk6-1nKY|lyZ z#JScsgU!mhuU@B={6%AtF_QII?kCB;Qu26ddUw&c1YISv*N#S4*CDj1No!1ySibivkhK**v;l3Ni3cjc< z1x}PU)jlx03BTq*mOOf#8l+dSklNZ>dNJp3w!*CO%fFkzY0Q>9xb<*3Ck{OWual#E zw{#RzLYcj9x6K|HSKHjw)g6MYvCerK0svUpzVrXF%;lgdzw&)-yYm}zs)o6Jkki?O?)Ic98P zA_c-oFlrA+bf_L}&}3(4M@Y@%4R?RAj4W<&1d%G?W~ODj01GdRTNo5(T7Xgsb(Dnu%DC*avjr3dVYs2dC%9>Zl%9< znqQtwEB|)!2m~a!z%3nOl<&K{SLtynX)za^VNS%qX(WXTzyqUc`nPA(bq10la`4e1 zAd_=uS*GZkY%6dW6B!dP;gFUyvhnn_5e??fOPg7l#DmCV!j~GwrP$tm(d3eyW1(Og z4}zU)PL6F+HBPiq>PT{rljCLYZ|i4TmBEkizsyYLC@w2>YXX;&R0?LVU2{L zZQ*9)8=g7c?zLK!4ja5k3uKXhR-|{=#S(H_&EF^hBmloH^Vm;tGGZ(IBn!A1d`7x5 zAb|gDc*W7dp{J{Bv$`K`SMxQ4zVg!GOA!YHy|SnXuL0ky&FfgfpU?Y3@84un`j>K7 zvFOn}-{e-tZoC_lr<60;{`js+`M~WOwuc>@>ZME*Zu_8d>0CAPaL26B8bl$%R`C3h@%z+bx8=9(`g zc+W2sx8*uD>@y?pHhV^{Ej_VYuQ+VK78WgVojMRIEm}>@KwU>X)rK&$ z^5Hc#-wD5aZ!i(#Cups93UoODIrfHj0LhP$1L7k~vyc;nLBr06VaIt2z+6vs=HA-g{G3C2} zDOc~SV&7P0`}64{DWe-`#Vnm2T(7+g>vNRQd;ViJhn!cCOo#5 zE-Z0PuJ?j3g1%(sXhrPxYQh3wy()WJ+(6$ax#-FI_|`xzPrj%EtIU-+*Ayp@%emOp zGVeL4OS?5R`e~@5S=B(^x6YXJ+Sv1Rh($zC<33rGDPJiELV4p zk<;VHO?Uxw0zj#?!-e`7>`@ln8-%=Qi6(g zRDVl>fa!z&8o8=tsabjXdv|=4{QXA_IxfEl=%1+-N>R312w{Xwdn!*ptTIC0XB19p(bAE2iyC6Hbb3XeG6dpq`H|5!+mZ114 ztlJ9Kj3g}hhX{XSH&R=SAOT@yy4!d|GJf=CzTadJZ_S(@JDmFTR;z8FjEHKcvTtqd z2y*!wH8nLC6+zzHwXTX`g$lnAWG({v*i%o_J3JfJ7^^o^HTWq%N~bzEw_?e;;|6WX=X!WJ5BHULmk7)cwjM@kZO`MBcEk)tn z<&)jW)@G^1LcXkiF}uF2oYdG!Ur*HnNwS@E(oLD=E-fKA1aUEvD_}`ZJsLeYncs4CThIv&w zTn@$>6Kb^@;2e>H@GGO!!o;^PBL|bTl7&h7Zu24N&W4 zVIY0JDjHMP4Q~K1VRv@+cAMZO7P;f}%h^|1N|RMTUc&vmm68#M2e+r(12;Um{Beu| ziFT~n&_AJmVS1#A-BjMugd(D&BgN5ivMHt?z93|n!YTUAhxh6?Ic{R|iM8BTqAl@7 z?|a-}d<-sq|Jl~E%21a9$8s?Wic2hJ18a{sdqh!}SUl+rF|U|~#A)+(71mlt&$twz z+HtPo5=#c%C?88sU9&7&W?QhtWAu%6IXBg+HR4V0`?YhVm46L3TqJ+IDmx7JLo6}zZ+cPhTlZmF&Cr%@!8Gf`u3jF z{Y05*mtN5dY^`1bW{WiA)hG9@EEt>zq*?n4@>TN=A?LhRe?YIsDpjA|crS9%^V;Rfq z9ilZisj({hJ8tD_ycdRN)5K>cU#?!x-%$E4fA`6+MK`F?nWx6uS@gcr__IbT=%S)z z5CpXIpnQkqd1_-6op`G9rD6qiSjtBtsXf*Lw0iX6%-U^H!z&DF@_AoEm=ur~)5=|$qg?>H*T=w_w%e6wcFKXhd;?lZRkISFpNk=kjW8n~2 z{G_E4_8{RXe50TTMQL#JAtn;drm~H^)8s&w2?)D2Qjr!6bB`va#l>=rF60n7DRa=> z5L7dLYEv-cgXklbw|4^p)%f?^m)LN7m_Ier@$>UX%{0Gek^6*ax*P$f*ewxdo8(6c z7p)$X$4xNH%bl)%StLkEN=i*7Ces*0Elhsa8XgDYmztbE;dX;d znj;akRp0<~;i{>tD@dpYEG#VKZcVmYSc+?EK8zaabH3(^j0AUC898mg6MQB-6+3qF zIOzwOqPyg^0d!7H|;PO_xmb0=Mu z6sx`L#|?9$_bhKN<8yQApQ2%A$W(g>zvEth67ha>j+7R>TTqhu?LAIxMeK82WhLE&$L{qLO#YEkt_ztQyq7--j5NGCO%%53fB z`}db1E~$0Dw2kAYP?S5|Oar4MH4CE)Dp6*|HkMLr>v>c87Ijs+@YzVD^p<`e}|1Hf^jJuZhlnADhlJzsAa1A%AAT+BxL=-P3`+&%bc+t zW;9)3VEiWk-$UV}A`~eCiy0(5mH~S{2M2B>D=TXj0QU@GyP?yAnatGGdZ#JTnNxZ? zIsyWM=g%nM!P`*<-`Om=I$;du6m4P)Ix5BL|C=xlOVmX`tGEG{VM>h7Lsd<0ljC(u;z5w2wWvy&qL z7CL`VH|0nx6X8;_+o~~)=4};lGn!=?Yei3n$*qzcCtB0zhiD&WiQSbWnri-R_r~ez zt9v&LG06F|Li1W&t}}IzNMv&z&+Z%{=4b(vQUKZPYcT`mSmU7uv}+LX4kvPZsQMTC zw(DYQa$mAQo@6DK^KYvyh`m|(2ur=7m+s$O9vgrpDWI6kAMRd^df~{2c>4}mwof~) z>#)fg6xKAK<1273w$7ga*uOD$;K`qJn>v7y1wVj!=0f%v$$*4t)fm4P<`yH!AVti@1qP=8Fz^?vY>u{$_UM7|5{tKq=J<-A_bFy)kRA=nEy-46Ea74}pXa@{X+X(KFNvt4-pB~H1E5M6i(SXNJXLZR{fVZYOO1%}gIXl^B3 z)_|f|SZ06x{=Fwhm(%;s0GK`i{oVt1N^M3yXnUb~b)Z1@Lh~1h{>*sK6Z?i~)L-!f z6dSGc3wSyq4Ids#ht&u zJN&Zmh#cQ^Zs)u*#dlm;B^;TZ*T;xAx5UeM?R*^tzy7rIokBf;du@dw zc|ZT_HR)Ng3NOSPN!Vw`Ue!q}{~AW}B2}0_EOFl4W6~MouxL6j6+z*yNub>97J@9N zr%QfY&H6LgGu9^eSVLEUAOHigOXM(Ja4)~tlu~T)SMYBDU(T><=zDaK#b=}8H-j!Y z=z`_DSP9S~6;KhUrKN$Zaa!Lm5KHW_ssd1O{CwiI?`oms?|1V}f0`ePGr)K4`qt-D zz7}_T^X{GZm!zv`hi`y*4%W&)`Z6wWdB1*gyaMnLU{busb?a!k;N3wLmxjd@QrQz% zcmc8}n>S!)qwsb<6F4#7&eyt`E*jHe`RFl9VhaArCLD@~;;$&LXgSU_pLWHwDJd!a zJ@|9)gYO<-O#>giH1zdHKq^bj<%ebl0fb1&)(e;+BDSL6vt&|Va4BqEuKE13`EDKl zt@2MQ3zQGqZkAl0RJOUQwI|i`0j8d9yRaH!Gazwrh-!`e4yI~0K)m| zOQV7c%E}B1VGG`crzYAA0Z{a{kTn6)n=V#fR#ujibAu~+h?D_3L7Q`J7%aTJ8?AWE z=$;%iEG+=yQYV{je5q)qSP*XRg75;(J+!nK{MD`ptST0%6!aJ{W@E&Dj018vUU?tG z9L5MhZ5w|2*PfoWmEW+V#~t^ptb0ywVFEtKroC~4B{bEo)MFrGF)wcO0^@EcnV{B+ z!J%qE70J1x^q}bWH3k)8nM;A}mwi7lJriDBB)-bePtRg)lI?z7X(lj6nazLxW+0EW zPm)4^9i!^{a)8cP`TB>c54fua?WCFFpx}LVTPKP*wMVI22qbv7pzfig$S|AM{L4j# zQpJz!PwZK|ou}E|+w16z{%Cez{PG9^EgWQ$Z=(&rC06%8K_%hUE63`I=RM^9P2E;Q zD<0RcUtjK&55^S{7T)!(gUMzzaSnbGxKDzt-FT6HG3Ip(clV_*dVp$C&_!ar?rsIA z9uWYA3U~t$QKSG8hwn<9cCMdrEFirsDJgmNDvWMCmGM8`h3*?DnFm8q27~ccAjV)J z9*PdnowyI0Wo)vZ*LA!Z3llY!Yiq&=pd<40`*KiMyMkxWu>%YlQ$ z8PMkLl$liKztzuu>-KH+d)Zey{+waw8)keLV-(^!7bfxkMRg(HUE7zM=vb)T%!B|` z9-;um8wdaeTjh`+Ub|L3R&8x%_5SErI#b+Idjusc%1bcG-ZRM5dglqfFNZN*+27-p zH#n(YOL}RskfFCa1P-OC2fZ)0I%w|E#(Z91cl@>q=t#7^n6CtO2XAY0=QjwN%R*30NRR1>%CANsnl##w&S9>@wCfhqJct?cdW1nFX6>Fm=2 zQA09i#Us)p@8#}v5wdKw**Xf--Ej8!*PV@qz8GxBC(wHVlr2{BHyH{Wko-fCZ9n)k z^U<;+(zMBwQQWn~Q55_r9s^4F;q^v!zf8K|{ZMq;zX*UE3o3tD?E`%~KDqCQ=86h! z7BV0kK=USj@(IBIj*zN=#OE@6YjM6-M&!4(*Cg51Pfm}a&!+iW$_G{%H+b%FYhELj zZ)4=!aq=Cri3$rW3Yi6WpMZM67A-F(7s>GRGe4r~?84;0OiDecn3G8@sK3MRm*RBG zox+!0Ms9&g5p~1wL%8)HO|DL{A5EqwQH*9pEu1rCjju*4*PKtx5pzVF^z!4njV@8E zTUYWPR9C4))5>qZu%#irv_9aK;sQV-f4)?=fyXn7RS zMV}!wIW_gzmsC1^V+lv##dv;Yr6AZ@F@GYUaK(lzp*Sfko zAlb+bAtIz6eCr)CmZbQ<7dq?8~v<6knao8EK&qSGT5CQ~&va z{q+ws3=AG}osP}`3Yo06OwWN&D&Gi`f;eJ{_!Y#vlTw{bzIzv-Hp^BrX{DIL2+E~7 zrMz!M-A>g*`9bXbH3>!TZD%r^p_0lIk@dL^(<2%>qtS#TgEKLEOPiS zQ#l{q1YBV()H5qc)& z$svkwP&AK7GKfvDE_IHLA(Ph4bd^H*%v9^clb3_+OG`_)i#k1~c7xZ0Ylf#QHeNWV znLTIY*6fo$jhb8+pv1PQHHsI*Vt@@jPc7?4mPQ2Udf;CxHBHuA7hzlp4oXN&O zwZ%f_&G@yZCIBaGmkFd4CX$9gD}8Zp&7A;IiDi(Vi%?}Hf14ZKu%p#%SkicRZ)Uhq)W;Vink^qK6R^tzmZLGUm_XUVoCYoXDs-Z`Uet3UO$)yuF1l#-%Tch0Nd^yrLUy@G z8=pdJP=gzuJ`S~jM&p`)j+&98--v(f#}^l6D#PKn0vux!@K?vZ8uW_MO1 zh`I?qIqIlIx5-xPTM7AerTd;a)BTs1ckMkQ<%U1wb!ivxAjfpuXk_Uh{t}Orp08Z3 z!wQibJ$L)oLcvmbafKq#hiUwi%7Zt&118rlU3!vv8lY~f z-)f+*zt8o{;NJ%rSHMROuj=7u=@ZupO%~?lypLbq?@IJ)RUU@ca#krSH8W{OkvAsT z>WFJB&GFGd?(&HFTOjA$+o~#Ec!g3-)KPm!OPSnM1o5g?)f2Bg*B;57b6CH1d5DpP z7hJk?B}Q|UD`i{#+;p#}|IuF2>M9-H?XFqz>K)}5d}p0ca!hi(Foh+aK`GSyf2GjB zmli_%Vv))A^v~n@Q@8kVLQD3c%iA9=U>O_^tnGo5$B*|obT>6vqS`_NkLlwyhgH_Y zbBh$!b~YkfB=7namXu&4(B#xNKKx`8)MK$t_UY=gV417U=E8JMrF#P}cnyllkGvqO z`nK^2I;GV4!%$O01sBy}@8aV10w7+#R496Y0ua>!Oui0_w$SWWz-+ENe*mdk%ueI- zE^aQIKx!+*6~l3M4#7fHZBxILkw78vzHDK&Ar5LxCaLgVh81=U0+7IQH19}POMDNCR>io7fZuZmSe++ z>X}$;z44nSAqMDB`db?s9mD90?Jvr+&nt>7KSVs+NhI_JRix->4-}um=co>S0(g_m`P?Ck>_dWr0O zTa~xpo7vtekMQ-l+WKGoyNjHV^qh^9ON^6~_U&K|@Y-namMP-0`zhKeQQa=%jNtV< z6kN{|N`Ld)liXt0*VLz>%=l^I8Ckkz7)>R!JtZoeLh}8llec_$hh=D6dk8hV(|6H_ zMTsjJpMz$-*AdO)kw^uzf;Xf=pc#=xXZA`fzh@CMHoW!crio{fBm4F17eA<~D@e1l z#H%9a-;<0LAO0aDcm_1S)bcx3w9bD&YB9YEjGt32Z^qV=zLX3N?F=#*<>J@R=eUgDjOHPvymg3j#fcp~uQcDe z=)?Im@k!bFyux}GWuSekfPCiaX5Tga1Nj+1_Gz^!5pPs>RPP1yx8IDr=CSZuuU-tc z=R1w0Fe@?OMk<>A;T17Gi>w>-P`n3M2`M_VRfsbL;ngUR77gO6F`=@xQAjWzDIX^% zP|aM&)U))HPL9{g3q(Exe`1v)f7nidR)X|bc&oFy5Hx;s$F1t{4^6IBv{>V%PH&L3 z=I+^haOH1EwcGAKb-t8x zq@4`o+C{wrN?MKyErDp$ZRuH8aZTKJ7$FLQgO*F~4UU){IPd<;1)x?{wJUDMf58yM zBFx*@va)lb3Fl%)9cJ$L5`U}j@6$8)snLBLN>nPJslrUb$&Can9UUF)&*&@2jaVOH zo}Y=py0ZC9{a&ymWyEuFw1FZPT0ndU96$6pS;FQifp65#O#wf{0wT{9(9^kgP}< za81nYU)nhuxa(>+*XfTQTzm*Kv5+xV%d72w*YP-ORfiW<_`jQeF0O< z@Hmt&A;agWpr9bYD!qns)dJW3fXELA;tcXj)Ik9x7SWV(b$Mol3Ml&{MmC=^o$Ol& zOh@e#6%_NIRO&^Avn6~&f=%y7I{%T@=^)`BD9x6P`8o4=J)F_ZTaBqXYacdmtLuxZ z1eDCwTRR8J2t^?Kh`fi(0B%yWegz@daY0E56$%@gB=cLGLqe^WoE!=~eP(?-7S}GM z5`I1(`*xnDmXXPXK`D+c?=kA@T~hERxPR$ep$Kly%UOJkmK7UYVLIHL^tAZra(2u) zBlcXcez{2heZh)u3n&Hw5%BcnXa@}qpm?`EJUnvWzSY;$gH{=oo3%MP^L=77*hsRv z$kVeEz#Q)br+N3ZKSQ$K|L;DaycHAca5JI-1E9T0ziRRdC1E^1`}>FOuGOaye0H_{ z9Zy&$%m82MpR66C3mr>X@B2HRrZ}-CA3r7!{-n}wBe~zi^a*cB5(oTR3Tj@jCfg=XUMY(oyAdefg-Ti-Ty?HoQ{rW$?%!&{~W>RKlE;7qhL<2HL8KP(~51|Z|L?qE* zp2-lAxm2P7nUhjd2uY|YzOSX{bFS-mUBCUudCob{w)fg=z2EoyzF)(AZ)>jo1Z<`L z)^(pKt9A7U{RLOK6Fv<4p8aH)e_#>FN0H5ga*bSQ(>T_~@*!zFk0S)7oLwzm=v`o71fTXm}cZemSq5p@l^ zcbu)LsF_(-IB4#D=_Y#9=>0pLgXY+btm2=;JYt-AY@=xvvvS2N1NJ39|7%b4-vMWG z0e^deJx=4q(nzDpvfskwp^DorBO7D%M9!IR;X{UamOnyUh=tL}u$`jnuhH)f%uTVP zD>MW_=UID1oOn@x(fxX=*+Fx2cqBrw(l8k_tIv9VejYgPO=V9#fi&Fz+;Gg@yGV;WY#BU;re`KM*k7M3KGkm|XI7h0I zQGTIghu82{P+m6f6n*UCDvzrDl{^jX?CgZ*!#r7}9X96<&5p$K*M7He zX`oH|Yi}<=!{IV^!3=&Pr<1zS>mHH!*nZlN;F2=2v%Ay$VHD_oW5Sr;pKF zu^H}XWqoQ`nqGoy?yLQ5UO_<$*yGPHZvrDXd+&R%y!@KcC};{_4CXMou`R6Jyr87S zzRd9nI^BRusH=Jx;NBX)d31DCY;2HuYvZ3;5Er|=t3lY(pYW|60#EX@em(IE83{DX z=oNp*@8d;aZ1ot2gYl$So;c>;z5Ds(c1{_anIC0W@W7%i#eQBe-yN|E(}eYY(Y6mv zILZ;QoO<|cg5AZene`0FBE>qD%+A~X>FZ?tWFn9@P#ak~wh6%-zM-A6^KW$MZI8+X z1P{K*|FK*+2CQv!k~^|gyAqgYr8xR}dx0++1*a8g#C;QYoa`@Sy?AsYWGG`FtXmsW zryA^Rhb;G>nl~Egk#rg^e}A;D<>R*P!o&@%)pHTiX5Sd)<_Ti>!Vo_}{51Y>f4DrE zPexg}o9*@9)j*U4AP2>pw0(n3x+x=%(j!?F<+xq(YG$7BX)*>xu&@RJ2#;tMokJ`_-KY;NL0Uh(G zTEZS(*2k`U>U=Lr+PZhDmY3|4#itw zRwCz^gSTSxaE1n=dn$%#!Y0H3XF|%d^e_-o%=gjVy?Zx^Br~(l>Qf`-#UpN(XpZtTy5tVDoRH6bb<=!qDtULd#m%w6g`+P%M3B!RQC$3* zfLM25Usvqtxt@=o!7y?WO*y_D%=dYkoKJG84p~n5s1g?p*ANv|RgepT7zyi`8;M%G z${Evmr=%(VLAWBVBu4X^JQRY8ik12KKd7RSZN>ya$OuMGx1_6PvDdVcezfLRLc)GH zccBf9AGB>~ejmao`7M?>|qS7iDk=35_t-C6zj~=0h+dyIp+y%w@aoko zz1C`a5j(Ht!(CKraSxqm`qwojbnX4ox>MISLI*bp*$-j%<1yfJlD(_cR2x^5l+%DgO;N^Vx$_XbGR4)fI?afm2z(paq%^kNSCY z05S-{GWHF;Q&5D#tMj|Bad{p|8jjQLelux(JAj!d8jX@JapZBhTNwU322(3#DA^0O zv~=cM$jXuqvl{6t00Ugw_kkRX$)j`}N0-f6os!~`64J9~USuij+JVQH1E`hn&}k{# znz>|`J7ASOJ!+@!leUxk`rw7hfjKsg4IB70&IZBD1qa9G5n<$I2M=ygF)UGjEe&$@ z#j|J6+S{?n5wIW9Tn2rAgQiC{d|QWz9>k0yvgeMEf7Kj|uDRy-k||i&^}{Ao%_!Iq zB%^&-#w`6l)x&o^oNXVw_jc0R-oMgiKbxjC5gGl$Y5N|7`81^f`VaFQ&wq+GmK<~4 zHJH4|SzjM^w=CYDHI?sv6wp--PI1S4MjHqiM+7fiy0rGTNz@&4xK19}G`MyO2c-Lo z+Q<^yD=NoCC$5STUKM#zenvHa_Y+`qS`EurNj-#b;}YNBW=F7=%sXeAqPI5C6C@uA zZ-BM+AdW_Xz)9JP^OjQlJ5GN>B4{bq3wx(09#+Yja?2v}{=*;$(s!R2JI>{sujwivT;o4 zQDJA2{4~s0)3AV`$OZXvZPrj5{={Q=3@}$&h_S;w@(2Eujs>)qIWbT^N)qA=11|ZK zi5{L=x#{q#LSDeUT$(?@rP?t-!VCfa~$&drV9g_A~q7G}>|I^IX84j~_pdcjeOgbs}FS zk0}^t=VHVj+<)+3M^nP#j|{n81HHYUbFb17SNPQ~$+Zfj^Sc1!7E0=$*%}TUVgD$M zjCVqN&e)l5TRU$5SL5K$bJ`eiBFf?=Zp^#hy^&Zy&6Bau_J|9u@a28Uo0BAo(C4E} zd&-W0BI^FydPHANS{k|f<(+QaR*g%0{lWWa7n}3MJVibK=#e%dCLy6ch-4^_D+!{P z0!mv!mg=EtWY6_zicXwFo5$rZ8Y{9lUv{s-j(r-#1M07BTb`6|?zep8j$>9t(_5Q? zcfFK^cL6*d*LNKCa$6|1-cTI1NUDGAMv?9)(y3&1hQHusf?s&bnVT<>d?YtDep>#G zOG-{9Uwh+4nvX$H$rzPi^JFr&x|snbi?7K1ldrb5Ls$N&vUvQAxx|Dj9bVFjr=zEJ zENCv?tACYQOmnw?YJ85juC=e(gO<2!>UjUL`GZyV`rXF=nISGR8Bjmwj zNtyM}SSDLJ8GBUxB@yctCiCIQKW^U3%yak!tws|3+vWHEKzCd+<7|TUn6nxDe()zl63OX{aO?NXC_~-iOtU~Y+FSNMoZZarW zI})XXCptD*yWe~BIE$S)PypYVu?I(}{LEE-g3JXv(`#zp_#UydN-%Kd1)10{>QZX~er;kdBU>x1A?VM!9y|8EU>*$i?TL%V%x_J24lwJ# zIJuo5($1fiI44R?aNJBxNwG5Tp>JCAk>e40FaI%8YxCY_?*43$M|+(B!W5vkF;Sh< zK1^KV%)6d3S;0HrI=(#$d7V1>FD~U5q#Ce>=?-!!Kfhe!db8=`_hWmB?Yt(#t(ElG znjSgd<71-Ru$O_r-D?>U>S-RWNsruqn<;jP0QR!xM7nSF1;69D&BtP8TdBy*`FZLV%%2IE~$sl=Ru1M8c+C=-@3hQ}zX4xXQNiU7K_QYhI z5R2||WzMyK+*#40%1GOMTxoyU#bqJ-M;=wyFc_o2L1tn1H7v!+v~iCzC#%bL9=EjJ z3a7l+2sqz+aL8q9A#Ut{Oo=S@#3^Xwsea!)Rb9K&@jVlVp~f2LuVaHMpIly*&8&Z< zJNV1iJ2R(o`?|`Q_s3%0;nXCM)b;$7hB%_~3A$Po(AmPCOnY9-kYD+C02lX0UfF)e zx!XJ`DewK3>g($27&s+Yjhw4MewQTG&gWDf{np{t&o?!^-iv;xP;1aKIDGM!cO$uC|VIT5hv!%U2P zmd~@U;5=JgNtIhrP_S~IneBhvfpwZ;0um7*eWjaIcO9hUIs51Or&5U_bnP>@ge(gW`YZ=0xz zlPaDf_o~$nZ%cVDc~HYXKSpa4^Va`8+0S^gxqHTCpZJ7!q$-ApK-;Ci(|I6rCmS_` zfM&Gfclk9JMSc9j+Uzn|zkW>(PyM|;8$R9#50YOxyEu6-H-_$$70cRpEFho;UQfe) znVo5T=m*j=vYwv0wYAk%nRYLwg7M=c%C0dB_L5(@Zz@_8PIOyY>w4tblWEZSZAcx` z9S^U>i5!B1KkPeh{|ik)4mq35-S+NwA8U#-ML%ZGh!#=gS^f&WBkG_j{UG1+z2%tC zMpJo##y`+BlEYJr4&6H{HvkN??i~_ooZA04fBM8Ipw5djflgh3 zmJ*6`g%BnVF^NV2*K3xgOljczU$Z$^Zh4YV#Y@%x!7+~#H zae2i{mU4RDys+7mdb22ImwN-K!LzSukMfUI>UHfaao1uFMR&+2FRKD4Bh3>Zx)$_t z9ciqhArt{)_E57N_x?G}M z!t(??kus8f=Z2>JhnvEX5#{CjHtQpMl5gKhCPKi#Z{51JLDC$Ox=mAyXb{h9nlMZ=>do5g!8vJ` zvJKOE5{(j*l5!77py?>#N_vH#kHA)J7aXicK!pgC>O$@T=C+6IzwcnCQ$gXVh5OAx zuN<+rdZnvbxavO{q+$TN4QqQ_L5A%7^Ji*lr|T_w7n6X1MbXqCx#Rt%m}S}s69@(h zkw(&1K{#u2QU&$fG#;B1QcVuI_< zZE1n}@w(5xQ23UMh@f=93oRk#<v|v$*1lO?DQHljTZr~`{m^J^`?wf3y9%q^?`{**^A^E;%YuHgW#{yw)~KKFPCxtZu4zYG+A|JvU0$U8HV zdf#7VE&PLxA&o}aR+x;78n3tL&>3j1A)e&jeo|A4BXhm_61rBYFBJ_=y}RcUyDuMb zD_xJ51& zLFW_#SGk3q|7H!15YXBvKzf^*H5hTWrI(k_;)8+Qpt^p5zmFBr@KCym>#0Gz8i2o1 z-X3TY^KpH0gvVt~`_oM?=RZLdxu&jTU0kX2z|*T+k87_L&?>5;GOXaEPisqBenG{d zN-KpzH?wm)mnL-_QyleST36a%jxTO(%}}c_UA=XaY<{WzOC#Fo z08J7xJPkhrwBZf<k$Bg# zjIzEOfQVht_a}gTz0sg&=!$V+Pfl*`l7|MmCgDi{7o;c1%5C}YQgk$Kqa7oGpyO&p zzS=Htl#gWGNa`qwUzotGv#Z~4=NL?$WgqkdK`XSb&O^w$Y(w~-7@_4t; zu?}ii2z)I z1Ey^SG*v@oeVIquL?)@Prw10YbArU-zl-yTe}RzOVRFg-{arY-KDVa|JR6-0P>XHh zkvmFHpg}`XdHL)1SLnpB(zvqJ==A)$8bXy$B%{_w88qqhL_43w7xL|-Xpd~aM7H60 z_f8$Z_-wnbC>puoZ&sENMjxzfL?;X9VU|Ae`$CiHO~EqkVfrs+S!u$hGU$olK0fyiL~5Y=O~5^Py?g6RuzQu2ikmha0oy`Rzz>v`JidU^kWi+jZ*4sU=pH~e`oJJX@kLbzT%Som{m)ou<^fNW6|=$~vUy&r z|L2Wl?Q}zZy?x=|ghA-Vq3S~lykD$o4ECqTmO3MGVvhY>~dPsH^Qb>&*6*v zbebmV`4dOF9P7(^Y@xz$GA~eHURYST^G@|&kCIJ0xEZ%dC@3jy5fxoJ6qc$U8~_n# z{hi$EYCk{$LVVm?(od?~24S=u7=c1x1(4Wq3N*qu7wf|7ih)v*n^iHd85eas*y;qh%RJE2~`<`kY2H=gt4Cyg&V~@@705SGbFG$uU3XSv0anFUlt0 zP0qQ(kJ7HEmK|wHyuQ41+Y_csW9C7R&-H7`Zeu%9rZ2ulEWUQI{|Kx0Ei!KA_+q|agD~5IFultLLe>m-rGYJh>=I7!d@O8ocilR$zzbwYvhmzhz0rx_(eupe01Aike{GlwTm6pn<3*<~ ze3Xl9XbR0!H{~m(6=;a$yLMBjuD>BX_8Gl^tRy5FtS5xD&fAvuhmC9e{_WD^CZn0% zxt%+dISt*icnbO7T^7(-MzTl5#mAG|9N1%aR+d+-%h|KbbOJ%!(4(YjFTjOVD5RJ0 zKJE0AV3EnQ5NmmH$M8>_ZaA$b6T)SWy%vFe@68#<)f#urmAvll;q56Esf>Ao)+;A; zsm!TnHwQh^x4FRQWtvgEFFDcRp$zs&`1Oj4{RAQaI5|$SS5;bN_ZJjLU+Udg>0KdE*jtmh*2+4oH>|^L=&9K$O=?cctNBfT z|DI~7Z&U~?E&maqzBseqW4iv!r*{mocYNP{31-TBAkdZ-Y7;v(Sf#J02c9IBM|pZA zR^wemFve0F(huNK18(CI5YX_OIn2NijqLE-o65p*v)DJ=828)Sz8pR6^nP|>AtySN z61@htuv|QS?)<^BOU0kJQf4qS4D>dt9Q)f>-s691U68A7sZPA5jR-r(c+>eX?rb8) zIW2TQ7Z(>dcR)Y@K)?met-)Bibqow=PM$n@<_vV_dj9@9gpQ(7nebKD?mRO)J3DYi zR6nxIEC}>^drXyCE1_-J~KlSfXK}f;^XOs5N^ZcP?k!< z4J{~m7zd`bRmBbXTCiNsoj(ucK6R)6$MNw8K2uit17c*p3+o&Bpyq94>nM0+N=m-L zokz>a)q$Q{s6uxyXx-m1aK=cnAWxDJw@gaqwpQ3Ue@bevP}HjzXO1n}rpa@6S6;c8 zbIj&xl(~z~Gc8V^&J4+y{MZy;U0n^E z6tO_JpCr>rS+zj>+P-uer+;0>3(X z4o8U;TXu3hWFjK=Yjz(2^S^%mdL<<#)MnvvSXa_^b=x;>8o^$LzY#XMqVHlB78Z+- zz)SS^<9AxhX&!cQu`o0HKG7pN(4_C-aW^W8E_ezq7)QtWn>XDZ9UUDUv{W_eW##4J zEZP#z3%D8NDiTW%*yeEls(OtH4zh7_axTn+90jQgqFpW00o4=+1Pi77V7-2Sk?r5NPeMYX;m_>zv9U2EGtYf=PCo}vi}Xds;Sse= zl4|gxSER#4mv#P`HYKangwQRuXaB0$-Z53@kLBdz$~%X_AjH9ylDX_ipK{62F`}ko zU2JY=>Taha$GLxX+}##8`;1n-pXcFpT5D{Kr{PN{XRqu&8 zwEtq$78Vvps+Fd7-mdX1A2+vzOS(;@14tniJQ=2_k*{BO|72uf_%S!Hux6))P_ z;#H2KhKHTbYqgUf|F*-LY8vIAc9g*7GAK4iNJ>^7JRdUq>7u4!TB6rY4;;dXCi~G0 zOZycqk>=xdYpbHi)fXE?7ZoznHcKnGI7hv4f9xo2ed$V>|IR|FX42A_Ebjg({=yl) z@A*hrvJ_F!A}%JDH&qX`YMp?(O=3NTY4qE-HZbq$G+Uhy#Se9n9BR9I{d#YGpl^N* z>Z_c4w@@}edi02ujSZWNyIbvvo*J1F0Eg&&azpEhgrp=?CIba}iYU`22CGWiYDC1P zr1nTpQ7Z7+=3ldIIyksHLFu;U@ZM&DiHXqJwLS`WUXzg%aa_?yi&xF&x%t^k#v|A7^*9(62S*>K3*EBK)R&I%N(~DOgUSfu zEs9y-?9>~@n(xpJpyxC?Do#VXVP(ZVG=@M98ztHN&GY?Ph;k5q_T^eZClwnT3-T24 zd*#;%a}5TF1pos9I}CgQAp=^$$pKbYRxhGACG~SheA~Q$6~OMcV+10@Qo( zwv&lH{_*&+ZU9Cpp@!a=+WvEP_D$K5sQmn6G42~E2-j;xMN9Zz?GMI`5*Hr7E|zeO zZn^jIdl5BdNLboB>C*UQ|FC!TFCTCg)Cs!HeT$jNO+6sewtlT=@2}ljNn6*`zbU0r zpW}_en6D_YiE{?;7_N%xi`7Lmnh?Hg15g&a(xDCyTK?m&t$nWBFeoSp$Jb8`lS60Yy%2>}R9y4WKtn^)xQy63 zJUra4v2tr@1^@X640wsngZRWmZ^*Xt?{yxMN41E^Y6qWkrhY8F5NK7vN+EiBPf@!M zoMa?IBQx#okI=U`epwP5{}X>+CI4_#yw!1Gm7)#we|m=2KPe0;)nTO+*w@eS`r3PL zC3-RctqKy9^l7Oq^Mol{F6ShplXE~oga406S~(_|G{L`LxIizH#KX$^y4Kh8{`5EC z2$%y`Z9`7PgAZ`4cLClYDk>_Iw1i|92IHXzXQDh1iRv;lHwhhW3Z<|pv2*&F3eg*m z(yLd^-Zuo}X9;^NA?Tv{hW3Sf_s(c)62%&)Aw~uKP+ePl^XAPi)<*upb-q)+{3!X`E$-_*;}c7;0Ma^xIeJj<^*?F2bj!IJbABd49mI=|6` zs%zRZ6WN2vOphM@1WZKD`NfU8x}BVyN!X15*=cBLU-MzZ;TY4m?;55NdfeK2(U@?U zf|(cV+uz?GLOLAJlPNC|Ugsk4EI);_`_$&=k0W);dgbik;Bfr-3x3Oe`?Tp>pFbb@ z@!MdO1rz32$EqkpLlUtC%v9U|{#Re(THl%RR zi;0W-fB%SD5Hn8Jj=0!~y25;0iv3b&#gU@KtABs1;pJr6|T z?a+|g&Yko^7cX8+PfxdzQC3$!3(h(|3OYe3fodq9mozR1tSkpRd7VbeUT9v-tsYc; z`?hURP@NpSa;B^))1B2?4R={Dp2qIwFKPJtK+Mytc*j`0jD+1t&Zz@uRPp$CiC!?2 zo)q?1txy?XqxoJzal+x~(e9!{@=AvMnnzA;=e@s>TXQ2h*%+lXE)ly33dM^tF@GU2 zV`O9mAlW37E{8ROln^{NGBPxsHkh4hYH9*;;WPd^8yF-71;r%w#wXl3Ke0+`eWrl- z)VOwL02}_u$xBqw7w-?vixLSimXqK5Y(QV&9G{erwDs>k-IxO*ncg6K8~$^ zbTaEheLg@I*}d=%P$-%(%dGsuL4vFj6RLOlGHO0VRkeiF3`yHS725vd>|k8yzK-&a zMo7cnRCRBqe}~M^95290KY&RfS3S{Y$UX)}9YM9N_2ICV?7y?cJ&67g+5w*t!1K;qQLtT3S=ad-fa~wXoqJ zq_acaa&GifTBVCK7a;!#?mby~|GtM8TS{hmxg5k|fE;n=+Mx?L`sQ{IZ9*VgPnLFO zy>lA68N6XlmtOtt>_M*gD?$t#1%lGf? zhipyxA|22jej^{BabK-%nPWsvAT`l(Sj=5wx0DPk{U1JFUR>MUj(#CSIj*e5UPV#- zw^S+tGT|z`#x)Or3u+EjZU^kxi1^8=sT0SKv#a##-h4>xWv$JM zmec$7X2WEhZeU?Ty3UKE6dlTKmjVtuGUPGbQ3GQ>Co+_o-eVZ?$a?YQA#PnMnSGO8 z8TGh;l>IXYg~$zUZB+C%OqUsHtm&qd>GVQ26>eLG{kWmg{wng<4zfpFp7HkFe3*|u zNU)!RXtQmm31c>uEy_fJ74O$K|lbmIEy zGio?Q@KSVik#P+i*7-2v#?ActgH>Y8Cf3pJ5JS!(CLe>>8BKJtE>A|jk5z1i&b3gP zhM3svZ5E4D5tzX+{(c;=c~90gYQ5yWuZ@yibBa( z?fsP_wVjj_BU8w1izVEyrly9V=l;NykdP2EsDknHiHV7B+^;o(n|SsV^q`mhf%d6c z97#WOQ_mWin3&tpQ4kYp8=RyLa7@M>7@6T0=_}vtElpcwp&&XFc9@RnPMtWd#ubU~ z1SFNxS9B=h#*JrxBt=Ex441`mJK0zAeg$J9;BgqL^S=kbb9fvQXn3Qac6Q3j$arAB z0|dCO?d>4UW+K<|=z(fM7XUq7U7I>TGl@vbnwH+)>keG`r)DAg8uNku@eU-h>^wZ^ z0B{hUm+kG}BYCOAp)WD5{` zKpD?FOgF4C$I~ibw zMUf$$d>U2mwLfe`44Dd$1x*eQA9i#sSkr!4&n$SDO3{cSO`P$XuiNLwF+D&M;E#&! z>Qjb9w{C53ZazO$j6(=w1Fw)pV}K)Dwrl~n#n^n*#l^nHD}Sg_4)pbp9~(QEKdipO zSr#+y4_*6dpsbBL8i*vGGA0q?zAYkgE4Ef%?8OlSL<%G{EfX((oX-C@%{Fog>{LV1 z#KXby8ClcBgvyCG3N^CQ(#1ecu3Wi-JhUcYUV=>dljGt#&|?Fsd8Xt>ChEsMW@Kd7m>BA}tJp^-X$A8pbx_G9~w9lw{BRFVX z!jJFY(+`@A`2<{>%y(Pbj%tZd?&yVEe5lGWi{#tn39t`;WIfk#)MlSWb7WzMlLoD@*_+$Qdqt$9a813=bWlz{JM>;^xn2By`=EYW>(hwpdfpGqbQSv^g zPB|>Uq;^`Qg@sL4Ru&dIq;%+jnmveP zoDcg3=@9k@7$#?|or;r&W@hV!L;&63j^Iq^Q#x)5T#@WUg@!YKVMT%!q~2$WTSx?1 zx3I7y26X^pe1#RLalC(9x~ajJh}&v`3t%9(DJk78-mTz80^eY%Nir5@hMz#^fO`VR zgUjJGNFXx9L^Fkl4?h6(gZW;q0|^D9X56h0j|#pYs0`+9rE-7kfX9LbPgXkE=zf0H zfHS&0(d6{E@{rCv?!9<_r)fo#zO(bXgB4zu!8x3YuF}@^8Qqteaas{H`yB7m{r0S( zTgtq5?+3P8!}6kgjT2IS641l$L$7!gd_d3u@Je{oF9iUOM7=}D%pdgQvoZ2<)FlX# zU99w)&;0@epZi#ly1#^Z<)d;OwvTsHheMrSg0C)(GL_FkJ+5idmAL--a{* zNjt7wlSJpRcsGY{S5>8>rtY}RxM@=+zT<+f@R1`UaEGkd2A%Q-B`t7So{bxkFAlY} zVFp9Y{p|qy*w_-d-F?Et!)Jc~!84U_wNX&Vp38H3JOw^ zlH{2IPfv=nr^#;mzWk^AdlpWK^i-2`bCRSEIeK`QQ0c|gLW-rhNrz#{QC#fnW% z)lJuBUEXkEps}F0d;jH|Z#-g5{Sw-J^`AybMYsfY`?#}vpCvl>N)$V{EiXahiq1CY zr<=a~0Jz*W_8s+LZZ@_bSY?26WS;t8BFb7``#a1j7F$_mriLs(0RD*r3SekBOKSo)eDaMOD4y3+pCkMC z0ks5#k0vsQQ66Vz9=V-b_H;kq(f#X`Nb9tzjm@9Md3S6bG(#CsAvFJ%JyA`ZtFJ%) zkSRm$;5P4uCjI@d=}-w+PU>CPmQ#-#pdgI0YZBctWNn}inFN;2WGwPtJff2BWjrSr zd*6xfi^Vo9TwE6vw`%e1P*p|I?vKY8&Z3^G0c|jjM8oO0#KeOmVQ5_i-vVFrHtcqO zY(s=XTN|7HPfXedpco4aC4;41oH*#{=mG-+7xaOHrub>o`=c(}wTnj0@F@BE1aKKZ zD#FH->w|*f9VagqaqoS?vGy1XU~ddsx^;_Jg$L6~6hES`^63k@J03n1y2RJuwpuf` zMjYQDmvJ3%Op?qMZ3UGXp+lJmYPG|OG}{9fFWEH}|BLOf$TmILMzgcCz-2su)nkdn zDc_Y7j9y^C`5d|Qq&QHMWuYa_{RHg#Prz%@bo}ANhgikWp1C6S+hk`P9ji&tAO(0C^(Vq^D!K z6qy4#4deCeeOC=CkSOb=(h+G&mr}mWdfwg@qViXZj&*jxhRfSmmx5j0LK{Evk)l@t zL%k|6Ei^=W#fUOu%f4fZ`w6G63jJ4)9tk6h=`VFa)I{|Gv59X`&`zN&{7-v`A^_WC zjtvy01GwWr)4P4*0Xw#*YBbi>z3uEgg)|Mz5HBnSWNy)yF3tY<0h3sHX{oF0dp(T! zV7>ULxtUDr<|iuAB~#nL(6AMDJ}8+l$HX8=ujk|x^*3;Jb;bQaNsFIN@*ux+-73hH z44~`IojV|(fx?4&wB8SdQ83zM)OAkce*6O}$5U6YIO(}A?c~gUm1z3+Qn6K*Iwzg{ zAwpAnI}Hs@Wj&TSU<% zO>}veaRJ`minS_5l!vUXclUP2-MjhdX0HwqALzhP8Y8D5$sw22;GAiGicqGE!v5am z>2!G{JmI~i!#{>1w2fCv-8PyqL@1YCKXF1tezkB|myY5pCgvr!=-)qoK6RT@n-(F- z!d@Nh?-%>?VtF~BEIu{T4+j+ljdl$|n4$&m9?0Ts@@qUY6uI4a`@1?*KHXVVI-F@H z6m$Da#=?gRlk33;*~={779=7SbwHQKj;SIsqJslf6Fv1gWG3LR&~Vhk$c<9-5{7wU zacc^i`s$|{0uu85+AHn-lM;yMWD`G10fo%4maeq0dK9iwQsctW#+QY|JN)SGG7_%z zo6Y4Cl~2UI^G%nwdT}-}<61?VX3K2_QGrZ=c(#_9?xr(*j$ySq~K( zK`3nGtEQ!?Y&<6ol!80K6-7Im5oMu$D7r_dLUZ zTc2eLt-8W};*y+e-#SV{@ZVeRH1DMOePI8C{edm775MbNBzave3OIl9FapKDnyg;0 zYvY8?6LU}T%Fu`fT2+zp8LRv8ibfaTCHw7jGYw!Ql0_4#(Z!^|d6I$LHV)~uy z{Munzst!wopK*IX{IK!bgaYelZ+TBWO7eihe6v^#)B6*$)0HOD0SaEXAck1kyvSQo zEJSzoUB_rI<{jaWZX%``^Y(n5(X?{GUw-(%zl1jg!6DKC_zRj-YA;f!Su!>su&_wF zejRz~{il30T<6PsezQ=9z7ZPAG|~Q0{M1%hZKHwvyw&}H)3Jo6hN9xchq19=Fr(mu zWReQwm?*?_RuQyB2s>iFeUzo$5Vt~pK&KaTz18K+^i}-JVr6$$6xFd}>*pNExHScU z7Ii{70so(PmLxH8u7!&ro;7A~WSNgUf7jyCNRLW;g!I{b3oHbyvg^`r*C<2n9&*c& z&oKOtz07&b=9WS?{UbWb$($m}!ni>R;INyic?m*y^+7MkYPE5E5oQ97E)! z^hKqYiltg#T!E_x$%v$d%!ovfUX1%dhMqVPD)Qg=QH}G*yWM>H=u7R0L~HKH%Hw94 z>_nR0>S7`O(AhpQZ|_o@C>qd8a5VjMP`#(fDH_}car(b6GWP6J<35na{>1*Pj{gTC zYE=LeRAwY{KpayT(g|VR$X(AJZR)pMqgiL2Fmmi+E0VM$6b$&xVzaVDdgjRAq?w81 z49WD+l>mj{@k3?R22!8L_xj~^j*WC*tK;exqaj>*O|-PMPJ9C-cF+f2ZhE1e{ClOR zBLBrI<1H+|y3Sn#4|PtwZZcbQI5z9N3ZSVN%hxn`ZbXWK-QB2~<#rzO%h<*&ht`h9 zq#hGKKau3xBcpI`3rhudplRw~*#sIwQ^>TByr?vD71Q1WG_8~pb{Pi)JL`mg@2(-? zjx@_zXEeqLU2bCJ41MD|KDVx?{c=ao8m+bZo|n2KwDA};4dcG9K8IKzCs~8uI*|ft zs?ND{w;>&Bb4c>iirGgHPX8XKCV$N(=~$QS)@CzBT2;#%U-pFvo0$}v+c7a+0WCpI zUj4N-t9LY1#dY$q9UDOGRiJDw!$2F!GZ7Mzd7x;}kH)no>NDeKMQJRn7LEopcJgU- z)BO9}n$C<36EOj{v>f@2-iuPpxW6{*M<4jp~IS zI^?y!4Ey&D^?82Nk-apC2`*vGJtZ8#d%U$*S7lnm0o<%YfOT_jLe^v!-(g8RF^yst zBO_bEBByV~C30(tv_aH1CmH?i{7}Pl_}{SN4&YH47m8+sN$ zJDMHtS=wYxG5p&o=JFtKGEbS3-5V(>CaLPSWhX%DiGQ}Y=)J3m zQuS4Tb$3stjg$;$^!xj6PVUZ6cLXoCaoU&G=GQh7g3Q+4IzxP&+zQ%{O{C3~P|XX@ zFf%cwKg^khUKfDA8k^Sn-)dI6i+wlC~E$+SBLh`87Z~dX6 zSUiHEtKfICwE4s1kPHDVMwf}UJ2Kn1R~HpcB0-sJ0lI~>8|5V_-9aY~uOm)Qqhxbq zuy8S;(ICpk+6a#WI|JO0MH~7-`NK`2C=gyV!Pa_>1s(Neo!YLEym>9mX9aqZ@S0H#X_-37nVv)>q>9zM)*zSHfs_>tNNhd8APWKV7NQXRgb=R&ym$ z?=L@w#*cF!C3nM)@r^P_QSpIzAvN5wW7avZ_t#xee{g@`vd3akYn(ZC>ig_${97O< zY7oU6?b$=NABR2yXuujFq?4<_5oFHIPo6{s^Ko$*&>w0%`xouGfwRH#p%fCb@-)PT zAlA*Ko}_JN*}wltNXQYHK0uAaVtH@+f4#)=F0tPYPwkr*p6o&hq@)t? z+7hkV5!rGt;~`U)ANF>B@m)IOMf7usKXdfNw}r2L-;h)zPKU>V<_ER9*DVU>Qj*+- zxaRR=5jnY8ke}gkp`oFeiN>Oh#vePJUvMohq5#H~hqHhSMePlrHWmqBE`>QAN^sH> zA+j4bWEEXL;_f~Kl?Gs9z}{xVBn85!5Ze?lN22sDWzKqd(%0k<$q}FFh4$r z1Iu);qP`mVZEUD|413!#&Tk`Ab-!wHVJZ-%4IVSFI@C2Lv(kXeQTd{qOa;`$@q-8; zQqs~;icwNh?lCq-0)%Y|J@<)h6pav!2ccpE)JNLi0f$8f8xe%@qgU2zEbD$Pb7S~I3wWm*D;eRTz zu^u$U&B0wlna9b>D!k+Yd;ys<2~B2X2&<~r0*~?nyurfC#dYKQb-he}tVXc0xe>cJ zM(#NK$IsDGSm^Q4P%v~C#(z5q!fo@$=ff!}w9@t_*S97O=}#afqp49?^IDBt_thss z5sVGfWIF{kDSsN{SjMg*cz`^)-u$6EcTav;7)A3o-0RGHl(k;t8Fg2%w#2_-TI(*5 zV880pe+BvSw_m#bx<_x84WaEkFmDxx@afV&bR<=IdkR=z|Rd{j0F2GDH-9%w_EN# zN~^!qkGyzo0<<619!T{x$$U32g(M(!-NYq{j?FQ4aR*Cg{LGJkx2U8)M-)yH>QE!T)VEQRY$&?{$D!ngojT} zDH&|=GtGgC%!mo&^Q&1|DC>Ao&1wP?y5+x|@*-*%ZLiWAk^>>qHgs>CuLkc5EgLZZ zo_;!_7=m0EoB`wG`O{bOqSXJa>-=HOm?l3aaUX?A_t1J8lFcG27;@9nG^N+QZwyIo z{yuzhYm#CJ@Ddorzr ztR;ww3vW)VL8vtZ8B3%?cMk+c?tjbLysu9ojzb5ey@%z>GDQDX=!vjH6)Z|rc=&b|mA13IzX93x z-nAX9wv%1=z}(nVSy6EwlQmB0TAPNr{gF1`>TU1WWA-zVmWW9AR&y<5G;SI>vqsN| zQXqM~r4eGc?4fukfrPEYsOT^Rm8UaXFDMT>Q>8gKIDnC;}n0eH0~+xWcU4Gmg*IRGv? z%hMabVf>)@{v2I>{k|`MKt@DHy4{hcC#;ZP3+tZfQQL+}kC=P8^75qYUrwRNAb-)A ze0g~pdG6d0sS})flgLu;-gg%OAzB5Ydw&JKaD05+D+(&DJ;`!U1_xCkQHEd1>j-iY zu&#^ngD%b?zB;1S4XI9%cfJf8GZe}AX#0jBun8vG23}rs5Wa6eIjk9`c@lJmHu_gg zbmhi^>Ok1qCA?k;GCWaOn8M?LM)RTJG{{Pb(SbR{ACGXj0l8--lDs+n)-JFVaqVBw z8vk__*fM^0c3t`bK(SEQtr3E5>BRC@Xx01s`?)oq0RqJ_j?p&T(G~+HB%dWXzW|(p z9NUR5CWzLo+Bthu&!QC#PTJp#i=?CkWGI>>oj!STW_}(Nu)LZZE(H^h(@KDSqM;JT zg%6xj_nQ$^Qd&U&LtG@@UQnjd+1UwHnS|<5Fww5#)-6dC!Ii*7)6rK}R+btxyC#?% z5Se4l1CbR_|M|&*AE;!)azF*S1iW)6mwE9oMRmI41yz#kJw~qa?9;aQX=-Aqj~BP{+z1Z_(z3 zlsjQ<;I167vLa=4@O8Amd)M&PT%<7fiQra_HgF& zW$3Gh900K+UxvvEs-)YH(ccVD z^DXsY6+CNrS&=Q^-XeJ#0e=Dzdk_&6s~pY95?P=Kufei=07W=sd09wKptsIL-;T zVrLa_M5wq~v>!Wuhso&aD?bRxCVPu{gh&AcwhQh{4R#9BU9^@v1C5)qa@CC+H-L+2 zUx2PnODn9Z%J+n^!Bch=(8nAdwcYhfZ{5C)Q+)g@LNfGTKErBI!J^>g=H^Dvqn&DM zYFoGNb=xE3eYPMitqFsio0>w0g#F*(qA`gf)!_!5#|Up7c~J)}7}l-@7eRuVX=#E3 zKkRFLq_=MMMDG@8@1&%PaErZ`Q1dB6T26ig7uSmvMM-64Wl7211ql!}g2v=!5)~68 zIUzVo9f+Ej&#MPAq@DZbMcGY;h*W@NAZ%leFjgHLk_r|gElP|l$*!YxL zQO!c}k#d~RgKyp}0;6%MB84oFjU;DgW+o>Opcf@*>qmAAcxa&w{Wy3KH=t^;v9;xt zwnF~{4e|RH6AiD4G(RKbpPD4lMVJ?#>D(kN{BdLi1w9#~^7o74HrLqBeht7yLKey& zi_&u=E339LDSgd}=rf#M`HTY@HX%rpi;I>+4*tN~z=zf#rr-OtvUtx>01N(JSy}7L zm)>4pB9&jZn!>Pv=z(+T_!{QcF6=Zf91@r>jv)jXKm^mv;l0``#dq%lyam7U4RnSZ zZxqN-m_cNccE3N-nL(qbgztcigXCO)27zB6zw1NWM$8CP@V%-0)xi^o?v0vYRd+=~a6q!ZchBA~fNh!H2 z8A>HX6q%(#Bub<_A|hoTl2TEG6pB(IWL63diX+yCr8_G{m- z*Lqf^;kvKu^EuDsJkH}hJ|F0PEjH{|@paz{OAn((gb~uDnYnpXoTX$60f%CUdswdA zamQi?oUCTgHWtP4KF5t)+4D?fB!}`QCnskcPM9zO-QwEIG6wpPzXAs(;5>gFH33G; z+&?EJ?|XLX;!3(_J{CFj*21Q`?@Mb1bu;ptcOO2WvfYP>dQs-3^=k&1s3SjT!bPY; z_U=7nL#AS^g8^xk@!Bf`yX`Wn&X7)6wE_q0bXwf5BJzy24^m=!xroP?wQZklLy!h~ zP|#q=@YjY`yWgkL%%erd2u7^)gp$vn@qFx1TZoJwmDfnQk`EuWDC`p?ezTIR1sg|h z+Bk+MP%dL)G5^Yo*ROAchyU}{U|8gozjYmcMegsX=V|1wu={TOt7-AO7!*3*?cMwL zcT|IEYjCbtmt#I1&JIz^1~d?wX3d(l8A%4IKqxI`#msQ7Wi}x(F+=-OXKGU~s_D&} z*VHT;p*RtJkqT#)n6rsI-;| zg7%Z`G{dycz%0(3zdlV?Ahzt>)h2^@+&oWQBe`N zXBA^NNO*yiKun{Gxla!EO$WzPg8gQ!R!~skbjZK7>5w^6WWs!&5w;9#E2PpjMhBo*8-Vvnb_}uI1p>RdpB>YP!$du zv^}+(g2EaS=KlR%b}Y8vWp#ETdjx==wz29=!tktm83!5KOdd>*hzi=U%a?c>u=e4nZk`VjpyxAH8pY z$---E!~+NVK5f76HMx5MBmi7?HQB7HDxy^GbmsK$&`{N%Ub%pu2Ta}*mcirYP$dUU z^yroYA(m|Gu-}Wme)_>7R;+r)$nM<}G30?JJCn)8j=eQ^KKpo}dCT=DBTWS;g8?pO z>Q)1b0*@i1M+-+85Ltyv>hsn4U@iDVREQ<--XU@`ALl8Z&0LP*1|x8fA3du2`E#6> z)?uBX`$h(^oN2$l>Jkg(2}K|xemN!PBS@9MB!QX7BSFV;Hl_KO!+`6Xmf{tK^>)auv0vhNygGdEs2J|yJW zOmCr8Ad{nPGGo?13eUkofEkYZ%2Y-uSMw=0O^_CscMR28@4(2!=Xcl6X#(nr3)xpa z))&!NN2j;q>506uF^mXo+_b5g2ME{*(Ed$*2b?NQbg_%jmHE-DXU`L?Bla0Bmvd*o zyX^Eo`?CUVl~hqO&+- zy}Xpju=k%I(T|PGp8J4rVnJr_(=|~q1{@}~KH5^_`MYkdyZiDBlDSdezI|in@PP&^ z%*AcTZ>|JJ60=CWQW}|!zO=p1r0lXPudIqRaZQwbXlH|GSrz>xr`*&9xg=AP7x(rW z{%{?|CVQvcaD$G|OzuJCnKKn1<$CDV_X&@;+0$#djKe@WNLQU?1@c6u{UDbeyJzM> z8qS@|!C78CugC}`2Kt7p$N=avwe|cl&M4Gnl+Qwep!r8@!pUyZAM`(+5bZ~a-Xd0@ zYn{{pvB5&(emgIJap_%i(j@by9c5KK_hFFD79P93E)+fGPnLDL`ecpRS7=hsStZr%P314d>9ri$F!|EJvf8! z9Lf}!VdXwTW?M-G?HCoAsYa7#bv+OKuJ}s6=67g~8t7YHi9)|n#^Mr-f+!&=Op%GU zky3g+(?`msD@cwW&-_9~UGWu8n4dX(OOE*yGs~s-w=F)3m}I?sN8#%R!^9Qen=xI+ z33Z^z=j_=be(4*l%l75e*424*@*A`2d1S+h_i*oIdW58o7TIRrBFf;W#cRMTYTk*I zW5A}?ty@o=m^S&!^RVe+lkABu&f{Wc5dA=ALd&Lip{DS+WbF0-Hqk@x?-2^vRX;Ysi$8$rnViOzOz9vr6ZhV|FwgQE*E) zJ6)8Q;2a#T`(l>x2?BPOm+*3%^u#g{eU{pTpymL3T0zJ!kdGkhsS&ErD07HRG-gj9 zKUOE5rx#zcv%`R6UwScqED90^!EY9?q2}RiS7@o~x3^j!k4;4^O)f+w+C>7s>(Z-N zIrwqu(lKk^-V{bHt1_2za-Tx??)OT*C%IPwG)p)-n8%mZ7dDHnyex6N(o?=FE9Toz z+jPQz=EIXd6ui{AQwJ5WY?wtXAjv*?qM@papiWVu<&?{XK(Wja)iceos+~wobqpNi zt+_lllUYtoC0}(GF9RiD@P)$_Rl08w`8q2(DCCHjHfs|>!E;UmZtxx3x-Wg zCyTE0W=P80{`n_&{j$jU$2h9fFMS@RoR>Q;DAZ^A`U`)EBh$3^<0CMuWaaCWO^H+r zDD$BCR+UbNyi8`-tiFw@r7wBYo_;kMU;(u>t?uUY)~EiiFXX+6Ib-C$}R7pvRxi6HRX6~CBs)y89${p$5tST*;8IR;&S>|<{n<#+ncQgAy z7YqCtlw@DA{Kwq$l1&ZwDg#skUJjiandrxbvkVB)cv9XashhryC zHgTvV%N#TvoH`bEp+#dqHDT=9cSe#aG-63ivSMW2iefr{GtW(LF`bxhZXU{9H9Q(+ zwEeY#0!Qk~G)JwSj_a9NM1+GrcG)@~ZuX?A60`V6S8t?_h58hUVOIJi_xW`{&IX4b zMV+BV&@vdS_22kZNBOcqPD#7i+`MT}F`hFgPY6!(8>@0H zlVW0GKDWE!S~_jktQ_)e`t95FRv7`vOQeg;)NKt^H?BX{^XKyE-zOB7xVV^avMD&}8-!2S zMd$-q$BD4U3{N-|m?c~XN2A+6c<4|KH=QWvdR%3+x1val_sR?CMz&}?;f_{$GpWzb z9LsNWbHPHPw^CLc&7w(mAoc-x^YO|w8tXmE(Zxj&bjQxStjeH(0`dAMpJK=HXnYpC zN>K$&pbHH7OPC6}lS|^XY0Kgc0%HsffOehGPL^~X-Z}d3jxN1= z_l8}J>jN|Xl{pmZ%ncn_1HyniKo5C3PS$Gx(C{TI-<+!&#R}>s_BE>xa)uwKiENv? zxgIi)H$;MCnHE>o_usd(aGr|7=9(9CX}I$>v9EBR@4b4#ie_=o74Pp09Xn<&Q(-2Wch%tq?;iJ*SJc_4zS-j6NK$YqX+Rs{Oajqa&S+`B9YPcd0dcq=%r-^W z@I2oWc10|Ap$R@{5R)ibmmiFxY%P6sOFDon! zgMt@IH7Z@U%1fq%hyg~zXfduXL+N?4U0rJr4lSA_DraRn+t|Nr;EIVcx$b#Whx;mc zdwc(=%sh?Z#TK=*6fy*8`lpFhafqRb^wb3h^ZgQjapgkQxBm+ZpP)8?(G;kAjARHl z@T6!cgtB?jB9ik0FCCe4M#>BZJOs^VN1>$%4t|ts{6ODV(<*|Z);EaMGKYPcX4$(k zNW&pLfg{<-rq?($6{dqpHy?#A-MS6hbdtEt(8WqluH|3@!O^=A5Z1-2f z9hbRs=!U}?&2N^WLG8qmEaU1vm5};zCF#_h%;3N;c9xXQ?7_lw+oSd%C+A9nMs){k zW#!OWvioa#lt=b_aL@x*%PuEjN(NcAqnsQ;JdtA@epH_5G2}`i802yQPH88$q?<;? zowrLX%FGnZk$}nVRQTM5L<>A40Q(_(~u~a z;3*RyxR!%LKD(;H1A$LEb?j(1eflp-b6K(5QD+B-X?;$o-5}(ik852$GiRmQ38~-% z=!eawiHJS8zw+U#ygoD()A4ck$JZ%%w*#NRFM6f zO{tdNVVUL8V_$7MXMSTFBJ|vAYnQTMC@djQ3upn-Sb3f79?Q%T+#wl~jn6V`_;tVfV0X#i} zGt$1mKp+8aAfyxi5Su9}jof7+w0+JS^TTCTAj_U*aSCxPc^ZahapJZ!aq;oee-DlVQ_)!6f z;4mxkdq88vsa{hBg~HbHWQE*ZYsr1`%D`cP7N8$;cO&l*N5469x_2CG0Ze5N{2_YGm%!aN^qG++3*}dL-Bx>=-h&O z$IEPC!qjEr7ocA=QqmmXNa$c2kb`3{h=xfYt-Y@CMO(&)HuCggZ8(3*_S%}Qi;t3z z8SH<|JOV97Ryx0ForQ%3>E)C63P9Ij62C0S|D`l^7opz zo;sXeTW_tkC5~-|a~3b+>BFzWAR*mlZCzcLy!gB9%J>h)^hA-P;W3oBIDH2wVWM}_ ziI<}e31|R7!=REfz^anLocA_#oi5^@`vAO#WYB%WK$m>YbJ)9Y(-jKBE? z(ekGuN^9_0mGmk3yex(*nK}BIvcWjmzbPr%-DwCFmzU@9b|5CBKN9QXf1eXj2JQ3-NbDxJ!8gm*#L4KJ5ugU5*^cZU#<9T z)v{%7$TRY4+-Jp}KfhC5e;Z^6Kj%0EnfzhmjpJD~B?b4 z**FaiGuP<|8x@~1H$mr!?2YaQk;rv`-r40l`rN`u#nAs~er_(^@vA4V!}|ZJ+$ZI< zHgKecv7jogHa4#8?5yiSJ6zq|a<07HyFaJrkFaHr!dk8&r0cvVf?<{LGFVr(DaUYN z7mP%nzk=I*N%;9Y`z(r zy=v__tB`3?UvlD1yUg!uwky&;YnjH>uASqX)f3~pE$#CpV9hvF(}3`S)0f(3F54}c z`qkfNat967RR>;H)i-{>{&DlO!h1nFr8U1lt-Dy&Wc%tD|MzW8(Sp!V6sO}+ak5>t zg7vUX-MMpT_rHjrG^c(AU8G!-8q5bBJouS~iCfL)&A z9W$q~t|XAQszyGoUZVAr;x#}3)y+Nc5JRx-`>jb6TNS!zQ?43{Qo zCSV{q>MXpG%4iF6XF?jXk>-Y1X>>CZKox?ZseZGeVfxr>KkA&PoRW6t6XuUx(z-b_vKc&b@ol<{fIEqyAxEW8Jz|{ew1FTf zXsfcLAaC}gbIGtv@x(jn6X*@zrrQRIWey1W>({Tt^Vem_8|_4t;O|d|Wh*Ha#Pudv z;Av^G(fuBruT2_<_9P=Be}V6p>p4<|R!M%o4xxYpzPH6p!QY~$1~~@iEVWER_W^^P zICxOlqWlzrjE0@`%|l4Rsug#%YJmtEOXB0>jaoC?#u`h~oZj*_>*Vf4S4*dnYa4#Wi2_-SAp&$oSLkxELVY!K{nK3m4gERQjoB`FlWQPtK35?xUk5tb$D6Bc7_5PXIfgufzQ|PvG@5V4M#AjS$AS8 zPQ}E~dOJaDd+~I-kRbk=W>={DhNpX>133SkwXMyz}la*cYYmLD{n!!Q=;=e^GFjri*$=KOe^sHsG`}8xraSq)!h#F}{175ZAjr%i7 zV4Ej2O^1+~*z}zWhQ1`z%H(Sv72XV!EW7r7^TBHvM?-Kt9rV%_OOI*6c)iR}h5$Hx zX>v@fVGRQ^UvjJ+9@GDwqM93Jq+OIu}{ ziHYBn71@bhJ4;x4+Q?73kHWpTbH~gVFN|NbMCGs^3d!gE&Yb!1&)*$DZ<`uU2L~5G zunJ?ugcv(JZ!8cf*(Fn;cPO-vny#2M=@tmQsNf5EarnX;*Ql3alb*{jEU%M|M*+d| zbaZl(6N!3q^hxmaDaV6@KXG7!)D$e0kmo|wB;D7oc6R>4row=nC;^Fpd#XrGx}wIt z-7cc(Ld;QM185l9r%fvyXy>z5HYs=7xn%S)ws}igp2ng?T}5v~R?M8A_2m^E8_zTR z{eeMOX5^zHBbQN1xXFkk>GRPzB(Cz}gS*?dw(Jjs$GaB1*rxEVveJB_+;)ZArLNwX zUXrbuDZ6kX1tt?JQ8LBez6`#=$=SKw@A8dAb7B+$khi^;2IhhVUifzb8a}IRK@E&< znLf=EJf$FA$E-k0#403EAu~e+SV#Caesg;8P)*HQD291nR7gbOLB4o2UqsbuI~;w& z&&q{&0lT#Ic^y1>5U)bAbS}F@qfNVZF=x->?2punUPK_GTm@9qKR}|{+vRYMpi~Q> zSH@vujM3BY3p4*sQ8Q2dCCLfRGapd@Cx0K>^8VjeE*Us*AVi?Md+&FI@$AQsop?8e zA)?J>nF*Lq70#2nVMlYC`R^Kixwcftd9Pppu3Eli>C&ot9br;QrmXwBYcKzm=HF(Y z`gcbn<-js`HI=>j1@~Kfh6DDqh=p--Stfc4X=clW!eP#7T_peG3 zhsbeP^LB-VgoKB`BQ)srLku=gQPs4}H&V(rF?4re*Yp=9V~A%Cl^Wbg_x_Y#k5*iU zCeGBMBpb=-EccW;r?31)h>|>waz5P246pOPyj=<6b z$WI#)_T_?=4q9{|RA8XFkx`q%=efC@PXK$pP_olNr6)=pnzXWF;@6w2jy=Th3GQrv zj-oR*Ud|#6E!ox*l4N}L?kY*`hX)sWHDd5@jCFuE7~lp1oLA>xIU61>A;+pH0O(Oy zDhjf})ea7Vede4wE1=|{h0Km??ox2&U9q-}jEpS0GG38JD;QmB?GDO;LL?y{p9CXw zc)8*xEY9bTA6Gg%H$L-jx*Q!ng%~<*+R)LX3A?U{K?O+7Qz<*=7nGKkhD?$I0Tz19 z=+QbgC4Ziek9_|Pj(Q?-_wL>4y!$H9sK&*KoPv&P-MT9Fnu6paR*yr5jE4qfk3f&Y zZ(QO?vOuB5Lg-3rM^Qx~&{@J6W1IYJ=v8wt>MQ#zhf#_I2kVl05$$u(Ky>urBrkvl zP!NDpz$glG*U0zHIm|Ogf=uRETMyRI5D=qz-N-*n;O&52OJ5io8*kU=2qShM2j}`K z&`O5O>ms4|KWg0v)3)0%`FWF@s|_~|e&H{1g+zudH3xh9&2Oz)HKvr_yLK%eeayKn zw-pe8NLHs^vDt9nAfh-T9S)CO3{ui~nveOZSC7Y#cZe>U@7?{gcMQ}zXXx7IYm($R zO9XIq=kDDFEGvcECEr0Vj5PTgJ<1O#>k{~~vi%?o#ee-$Q&kl_5uW&cg4YLZ0-ExiT*i*b?ww8f1>hQw+{Q1>J7{5Tt`G@0V$1|`ejGt+Lpi$^P4Hf$eJizV9{53y`&p~OaS1*+cz#i9LSlm zbI)7f>cV7H*Q}$+@%VcPnrqU8lK|<-k(Ypbjqn5Ax^|_UqGNS+$=&u@iY~9O;W)>2 zysxP6S+)K^OSJuQdp7S ztwkg(pn-R)DNQMTyN}Y}P#B)^`O{zDaIu?#Gqa!X`bnduUzf=|WKrX@aBq<(<08T< z)j)5Roper@PkiM4&Pf9^A6L(a_LRBt20|0X)O=0VfdlDyte?(Mhw%C)PD-oD%E`H7 zKi$K_Lv8On5I;r5%P-78g>Ms7L5l4VRtqnm)j5sH#{liAn||)q|4>yAw^br-ny~@; zo_N927?QW@0U9K02Due(FB+-;W^krr@t>QKxo&;)d`R5TGzAIw3U*{&`SU>x1Zf37 z`B-Hrk(7ZEM>62SZD+4!W@gf1Bo)%H;@BB@-S(AZr%d z#*Eb@Jj6{`;^I)ghib1~A|Q=p2Csx^An0bV^RclL*H_GHIQs0PFgl@t$7wfcHEJk^ znb^jel@5-MxSc;@MbfOfl1M)j<#Xn`p>lsx+4q5Gyzg+F5bagA9X)b5E`*o7)O>B} z>SCpefVZo$hV`W|vIWSR0Gp7Q2(>=Q7i?s9bYwBq2f&5$;n;+Yu5@z2BeXHXNhdIZ z^1V_(83_rsaI0O7g*SX$vmDLfiqXfQTJWDv_W0hvZ+Eadc#aB=!V9_HZ+v)ZiX6hj z1v$^0*oB2FRQZ?CO2chh^E!>!1tYa+0c>nW%!?N=6qtZNLebjQxErzg$dTZqM+rOV z=Sv}J;4~l#QL;UJ@`N$`0lv1dQ0#Ide|X9Tv|$7uU|JnaKWd}c=;&OtBY##`rCN7K zz4;WdRIR9N=$B$ho(~c&+wdQ89PJEFgZ+mM<7^`mLYdFeqdiG4*u-#_Dtp|~ahUo{ zH^FC|N5G53f64|RWfBObMnhu|Zdyy?_!X`w^^51h?|qKO zK{ComWZiW7_U(&UnB)RQn46aedL1!r*eCE4xz<#545n$QjXByf0A(qKBg*3KF|MeL zhYuK#{q9T@DUxyp*_VFkh~F<;a+{Awm+Y(kSha;Hd&n1q{m(^5D>U86$;=Fs2aljA z**KwJ<4lhrEaHBCUBJq2C`FA0uh3Lf4B+PMSThj|l`FBbun23;Hy5p1%^c#!Dsl#$ z!9fED@@pzSeIk~M#8hf-dq|LFYt77_n5=9Sx{XdT>?my4VrOR*sVtrv*08mWjiQA5 zvP@%v{bv1UR$z79w@0e8xVs>KtVkM`gUyl$dbI?Dx+zQM*WkR5{P;M>kKwQ)J1_Wpf9opdCT-kg!CWh@_4UPr&sQH42{8wM!9~v5a z`n0ifqIKyc;kMwvPr63-sp@<1@Zk+Fy0u*J%?yQXU0ap}T*tj-qq%Mt@v9YkVqzR& zVQIrto~1R_j7Z9Y4`9W>!E?>*d_+tu@LUlanVD&f8~1a-Xc}ZZD+?>D0luQ2vl|t@ zEN`{o8GS$+%jkbM>wCjP0Ji{hRN1~kELn!78tK2$Q)u6@qZb@5eWZ2^C`1^k@KKm) zW3!2N-SDKA3zexG%&ir5>==S=F7iq+(zm~qGz8tRsj3wL=fQ(jke}5H)NrXqT}4-+ z#PvG$IkVIDt5>TEeZWd8S@eLQUhiQC=#p_<4S|-CbY`~YC&s0ihJC83e8UWw^}KnV zCB(zDhKgbQqK2&dRNkmR8JvL-6MAyAGKP*A@n+Io41>Iz>Z6EGY;?SklFI%7%(oFE z@ot7HO4bc9@7ARY)-_6sirIy`e6HP>X1v0Xzi<8meArl9TU4em8p)7SdDJ{FRT%8h z*mc6Y_E{}H{C**4U z046)FeaF4r{?~<2`(zGGYP$`qB8`Spl)A>c0zGQK#@1G8+pRjvw~6UBEmvevaOX69 z&Ug-Uf|Q#x=Ov^+$>I`U`% zr%WtZ&{sTg+_>%UV4t*ZD_6%+K~v@D+Sw^9C}a|F{{DNrFecPwCRpJT;Yn)H zJJ@8e{-qvfMM8hUczAm8PAwowZT%yf6nHKcOqknK6wlZB;Ro@d7 z1CuAK0#HaJ%wdE_)1srsBhb>fVT3SKjl9rBLb^juag}Z`>=II;|K{(cRo2B*rvw{N zLD7=2Hw16rm{_Hx*8-q=q9Om=NxZ%S9QjRs_X{4 zU53+yG>psp{L)1OQ2~`Rr#7sGIt2{ezpvtZ1Gh+RZ4XoqU)J~R+*xcpUSfHW`UqMW z;z!@Sp(Xld4u9}5oy4eH_<%G-eq=8;~lzbJsaFpmG`5nQ{bjSC=& z@#4aiq$g$u_w9z6Fj!K41U{Kr97?Is0St8tud<^@=jhSLswS8Kw{~ketXj3*&(Ess zp`%C3-oK}KQ4@ck=s3ISd!RR!4@yVg%Sr9E5)Z%Wj_fu*;|^NQo!dj}hsOl1V2Fys zaGSEbP!KU;VT+(uikP$zBy5r?fPUCM`jpc|?7I+-mqa0pLGn~T{vy*^v#+@hL>3RJ zRQ>8abO+D`&Hxs!!B%Q|!{zqBQ}!{%K!v5?NtUJPKVy0f0p0T@Z+ubPrFqu)-&z!X z_AH~IjDDOwcaE@(cJZH1l+`)e*#{0C^5P-TL(l!bhWKTN=8!oi0~IIlL=8DF(UBUM|aXw<&mRDbBUeZ zcfXiqx^CT=6qzSduI`68(Nh{2s@0cV`8QJ+ruZLBo#MHFRrHy<|M6w3*bAOUlPBwF zYj0k3DJtqC?NNP4{V!P88w=X_<@PNXDspW0GRt{wQS$a(GY>2R-EE2q$<3kAmU_eS&eVuh?5I zT{@spo7vD}_nF*?4puEu+h>N#aDXHOj3z~mrDOC$MiHKv{(xT^K4OG7Js1G7fl8fH z>#Hv_GvB^{uSq6?h!tAU)ED~?9vtY)7G;Vc+R?RciBO_|d?^{J1PK2`E62_Xii+#d zLD1}G%ANiC zUCdY|y2*0p*JxDJm1H;D+<~~NYiQtYJh#)zl7UHV&>cecb7)lyMRhYuG2)y_2O_L+ zY5?H@0p5tT-z2Ur!aP|y1On_mn}E^}M@f;GETf~7#QB{>SN@v78^xN#`3d{;^|kMy zc7jQ`3)8sFjzyr~e)bXJ!S>ZkoS*{|01h%zgPXr4PKAjX85t0wdLG|y78PwlKj2ov zZ)NtI&Wj7P&-?~L+V0xeh=}x(?s3xp<_MmZ$Alv2Cb+X?^_4A) zrK~H9#TpT+v`ihk;E^_)gj+pcX)pCP4}byi8KUv)D{^*r9>9gELBKIyH)7|d|E`ep z`z&FGhC7c!Gi3B~inxa~^tNA>CqVH?d-Xa-zXo|nc0fz#&Qx`s)U?E(!ZiHLfAsNC zUZ0MNszfAqcgc5;8>ouz-n-}D3Cap*JZ_& zr$yJ-MUh<@!Ckay(Qf@>!_1lvtg437@b)~jPd&3_isx~-)&w{VmZ6f=K#J&|G~DH1 zJ7|Al$j#=wr1k9DVPYdd3xokh6~DFGrll(N4T5>c?Bt5}ceH%$Vb34$WsNNf=D@wa zdzMfmeFkF$X>Dc&sf222?&&erk*N!^yKz;adB$5#Y*KLP; z!5c+HM$-CYj+`@EZTkrRX#PYAOMqg3I+BzgZFd$GH&W*vaSwj+vf`jU8cZsXY1w@NoC; z=|Hqif6>kq*q*f|pt#OrBbGpJ6>GeF8)@yw4_A^hzfFoc8pVTTJ9Z2}m&E=}uuo%N zfjWnqYEoG(9yToI{CTAwJyzP=*NNx0aekhawfJ%#(1Nr$$ali#x;2blYb;?@b3d{Q z$T1y*xpNb16m8JIKw>5jT>fXBE4@p0SVX-FxqLA?+5-f_4rcsJR!p%+I@rB)r#*Ex zZG!332l#S>1oHU7vhH2Gp3rr_xJ@5HlN;4BZyDkYevOd1;oGI72td2W5V z72Eu;zT?3iJMJOTKy3h0z)iJu`Sh z`Ok1N)ev~)Sh@$FmGEJm?)VVr{M z4#&xFW6Ptx^;MwOHH|{+av!qcyo? zNjURc8KX#0)&1i;9ggzS>C-3p*{kuweKtr`cysk%z(yuivS-7Xzh&xLk=r=n#}ouBTy#R_7lh@7 zAyRRIf&8{}?W$eb)XFoT@`GD?3~Zelr!~EwX4`F9g_u(Fs-BRt!7lLr{VBAuWt4_yz%v1PGj+@rSTc zuvy~f_lU1@u7R2Iqx<(a?-kSdVdB51q9P7uzX);yAJFEXXQM1O&9^OqyDBU4gPDQb8nkChJn`1CWied*c4`~Tja zx;FjQtGTpRY;15`f$!eciM>)JJ5F1>&hVn8huU^7AHO81Sy{o>dpCj zV&Cv+m=&}E5fRxRQqPgz*gZnWf7UFHUS?tqUA=05_iJcACpC^hx=?+xhx6XQWfm~i zHuZq2Sr=!Fd+_`J5d8I_v_pdc-^6Oyd(KxO^z8d=@gy{p- z)jt!u1q&b}BO1R({|$#^#e`7$7?kV88P=11;i0{II|XJC{1+l&16O~N`9C46;H7^V z^uQL7*Qr3uAJTPS=l1^!A;nt#e~yq+fA-#v)hb~ZwFP#Q1_~vj>%%MY1j*anqu&j$@us58cKU`2!-Sue61I(RVXI=f~&X#jL85d~)K4h(cz8y*~NV_^{#6{U9I0UEl-o1yK| zBLeaOE?@qh;N8S2EtTMQs%c*ZGT&msB|b_X?Fmf_up)IQ z8cJU{Nt1F>YA3OG_wF&8nq50mr=oy79k{*Sm#oZ8>r0Ea#>Tqrt|it8Gc)j7kfdVY zE93r<#s-0^soswTZ4%)Xa}gY1faNm)Xo4cFK(JHj-yh1Ae}bbEiTT4spQWRZ5o4gb zK7~D_``i~Je>lg~RDEp8&=w*q`ttYO*|X!U)f=v>p)~fy5B}Q)2rk~rSS_u#ZQAVV zJ$9O*;ZiDC02KW&WKi8jZFtmuokl#L&#(fNkh{N(~l9w&@15m<397Ss^k3g@)}|2Gts`@vfJ&}3xvj@Ql6qxOp6im;|4 z??5J;w~qVgUt%lxNDMgPL^9Y$RW z8bp~i!)Re49%18lmawIP>n37d$-e zU|#rE>{EFDKlh>c0I~QMqVeSHvZ-ZW=J2C=g}V$)*z3YkQP6l$`b;A{xN=GOrgo2i z^awB6C8cA0_KufYk~;1-_ABewbLr>%#+ zrI-h=^WXJ#`N&6hqQ^sog?2NeKFv$-+mYfCZB!ek`^;jUV>L^?3Z7ND2=YUH{n%OD7-K1mh zGMVL`Q(w@USc)44-S5P>xU^jOQ)X+0-}I>W3+Uh!Iz> zToH*mn+6AtGN>E=mC$V@TIJ+KIfWH!q&Z_H9sSa&GQ_@6vB;3%a)XZ@BPMSsDfI#9 zou9p>#2AnEwSq6e`SX5$CUAdEjg{Vt5+W9YtMI6(jFRu&A=YZY*hucPxpH2-2vi!6 zekbC>1+O3P9{>UPR@Makd^HDq9XRlt|?(++h6QZN<7ZokU`36%Ka&zB3EwDJ{S@UeY=#x%}CZT)j z<8eO_tt%$baD{B5Ai~mR37jOs;t-!8!Z0#IPGOq-vDe0my75Kc2NtO+lo!`n5I5 z^!V`xIBkY#WOXM(+#svUM$Hi(&XhM6D#`RYsa{AA8%FwTe>(5|U0U&^YNkY1EMBx| z4O78Lr4YlQw?Sfa;-VKa*0N8Z#`Kiq3z9Uk^N@&j>Isb5M0yS}!B3%tXlFWfjbc+^0qi;uUJC)Y9x;;xTkDHRMmN1UH z`PjRq>6*K}m@uh)_;I>0Q@wwuVeGAq4Bs;S!7oR2<>jT9qPkOmdbQ)tQrGPnz>(8xNhy}n7#Mb>TyM6# zn7%m3#Jl;|o36${P&E~mn}vlT50(wLN!YXS&8Rl<}06+@XJ|7b!RL=0}OIECy zYzccNjCYfK*a#zRuc_RaJa_IZg7IV%ljNkN=NeXLOa;sdj^G|qfV;YmZnV1YSK;w8 zSvOgJ5C?vJ{Ft~jqmzF)RO8E7J39($%USg1Xo{5g%zCtH?W*cWh%=P+H`h&Ut~W=) z4^@rygT*!2KmO`fOcZ6?w?7UE&1n6L*6bJ0!^UF-g&S*@_4EZx3KlGeahNy}f-wy) zPCq(76xGIf98_uF+Sv5z*KdYVd!;WOjg%9|`R6tq_0E^Z6d#4>jLVfqC5yJMF0IJKPTf-siUl?qDHh*>CdkglX4va01Rbta z^}KFBoNNBOQ}y0?)J2%)@>Xtgfsj0@RC_S@c+URDB*bW0w;kV%8njhZR8&=0F!0Qy zNnj`SHMnZ^*D9B;Yirjwr?#Lr;Y1QU(CdST4o%q7L9x(r(cv_OzNRe}JU3o>hZb`@U3{`s|0ACeCWIIHOWN@v!iv Osm3#mE=m^t^M3)2tMJwU literal 0 HcmV?d00001 diff --git a/ros_trick/docs/ros_trick_bridge_architecture.png b/ros_trick/docs/ros_trick_bridge_architecture.png new file mode 100644 index 0000000000000000000000000000000000000000..4823dda9cc5f4392ff059c5ba206c8d8ac66f53e GIT binary patch literal 339544 zcmeFZWmwc}`z|b{D5UMsFd^wQj!K;A|N>+4Fdy=D5yv%(%s$NC?MV4AkEM) z#1Qk|8-WL3WWBFKI_*i-i_1v*z^v5J0+<$6^voL%jv`hD(cGd5)3~c>D z@Yy&CcM;JVw_%Es=xeiKsFtr^PQq+huE91(NNXy}z9iMD9D9`IqKwe+$=?_WSlg{| zifNSb*SGNvlAe}at4G#&T=lJ=v=^#)-S6njY;P}3NbhnC_kaHSpELL$JNO?r_@7Yl z|9m8T7UMEGHMM#I&&Y);@^~W7|L#B0N_bo^x}pY{Y~If+Am>{>dLA zN;TN%e>@C-K5FP(p8-BOaWV{kjNzr!7=>#7ODxY|7u#0YXpQ{C%Z&c3Qaiv zYb^4C;^122qD*=(AjJ=_;%y>iXKjiiCKo!G&l=4dt8(PQ=9KjE%<|s5f{@+Qhd0o1 zmR??t!mEJca2$9o<^loEXuGi@AV{#|t-Qjn-xNu{iWo>q@s^iE>{pU-FG(Pr< zbRN%hQ2Z~i9=qrjCP<`gb*smabGHYj{EvzFH3%96ZRfvJYUV5Qs9Ey@S~ zI4MKa7vrP%6MHsMvkZ1wUaQ0g+Ms8Lb9gPs5VwiQ6Dbnii=6sx4(|^^eTqDBhCISs z?69#BKKNnzKEe|sM>Y`6EFUB02`t~ZC-t4?gu&^<=6wwJ^1D$7sn_!d%uRRHV(|QK zh#dap!;bgYhZ811-rd&7c@|F$jk^+;_p_;4sYwo z{;@CVL&1f(J>aiW!Ji)=qU{YmMxY*&{7=+*wQH`e<_`JXNcM zh~V>9|DFd#V4Ck-^Wkv#{W2tyHXuAc?9e(Pj^K#drCUkNKqOo~c+hyr3K7aDyHb?c zR{2)4^%|ddn^GN(PISL_xV<2hd-l+R-{wK~(I|=vJT{GDjvi7D+Cx8u&=-RnxEMd< zRzQ&`ZtEPScW7b9a3#TyB`@r~J?vxTlD{7*v2^38pGC$(T#u8S0nb#)j-8a+yL9-O z#}E>PRhA3YLb zknT+ZqzDy_q;1eZcpeERD>ncdQ1~!)$kcG~zk)3B)4yPSo4EOuhp&#F6;ZY|!Ut?| zZ)d#|CS)djB#>0v{B0T5gDK&QM*_`?Xr%eXw|Aq6ndXq0Mzr$DqxX`3@^8y9RrAXc zIAV?}Ab+%;x_MLd@MAM2{=U88Xk7g#NA4?|xh+=Gw|cqKa;Bwu#69!H(X+C+_IuZ) zM8QV`?;pbB9)J?uSH53txh%hx!mC1dbRS37O-Sz}f`f}9?zF5LJlSQb+~)Y-G1XYW zF+?%L>DHI$5ye{F^{^wG`p=g?^2SfM3a@%K9dqPv|MML<6(D#2^sD`3*&f#;e)pd* zC*}VR@hIx^9CV(Ce}z00;&Gl8c>c`H%!#ci$1_LI1qY+>`4QWxi#<(BXLM0*O67xkE#59*4C|hb(j8de@7O&`};Z~DQEq#(I}Wa0GSdVe8>qOaQ*4__92 zHtz0nh4XjYvANC!@qAAX;v+vF`JK3H9U`Jphc*Q<0c+Oj?B+NE2GV}}fr%|MmDi!I zR!c>SxRU}ms@PpBvEvNwIbx92pz`_&?@)aUf=534h;?IMMg!~mm4c=O-13h=r6XQU z@A6~Szi?3Vl8DGrKR)^l`i9@u_-I7O;L_onKeW3aPy7FS3l!mQiUJ1tD~Ab;Xf-?~ zZ*|&mwgeNySo~s}#b98Z$czfFrzHl&N4HS(dy6&QHKRR*v-Rtx=>&UU{>g|S-u8f- z<dgFoLch>(Q{V;=uzOAy7LqhBYoWQI#@<@QMV z^%_3gaRe$JHK;$V%69>u^*2#NzDPwcUx4AWe_G%J5l9x0DmfAa-~R@N9w{CbX&_L0 zZ=STmJ%bMTy*0wFw4HgH5|X+07;)fGY!!QVZJ-HX4tdNm+|}Q>Ux0R3Hc?eFvPIJ7 z)%o9?(_0%7@I|Utvz~lj|7GHOLg?kee5gk*o~MU9#6kmeki&5Kg+C=uErO9&@4-zd zptb&Fh)|3e?eHR_ytnCS$K8MIM;e#UX2GXFM_+2DC5*;Ckm2R$_vdalBt$qFsgkUd z6Z*MCm6z$(vKW)Uq=pD9keHb00?X&Amu(aNeWmT`AS2Z|`4yCFm%&h=HsCk^{s39v zNAgeB3ekkGn5KGlYt*>{l$EU?-(39qEi5C#x<@73X&>Dr7--Arqk|*jdFk@=7xt(7 z?0w|bnea`3Z~SpP+dVX`(0kist{~CL1>R-|KbHFsdI=FoXmD+$z)UMiy(pXU1UtT` zS8s|^#w{(!RZ;2B1}~lx5L+)@<$Iyx>M{X2-TgI6V;s2A%oV=-M8B!p2PMY=0fE}* zf2bxENgFp3`%n0_a6|s-(<>9-Jbm3rF7d9hiBtxzp?u{8Rq{=Ti;)dMt`G@)VwCCI zw?R{)mFAU%k~En?r~l<{7!Tfze4nPVsAB**(Ee6*O;~mOKT?)YeC2d=$dub9)0gMs zZI?$hHV4gw#Kjb;g_rUNP1nGygrak$B#0rRv%MA_qng<|{+xvONY587KhHmgbNY|o z5@xo4Bnmm50=D)rL$mBb)k-Y6c|gR?r-}3;Zp4y9h=Va#vWGSA&)KSojaFa|b{m5^ zjrWEg^t^#Q!*zpKlAmU8^uV5@vfSEz!p~TyVUc1M|H=m2@3SON3|P|(3^)=*)rl7R zvKa4FmyDR35}u}62XKj*t$aIrHgkoyIYLNlAlGn0Io^(@J6XZ^QHudrzZ6ko4Jmws~@bmTOp%`<}sn>-!6KUrrHUhw>-H=F7Sv`orNMM z(fj-QZ2fl{sqm>!yfp|QOXDcA3j3u6Ao2jTCv*Qv)!!`{`TCJ6mIgA) z(Km*tR|N4>Pq(!>bR|BD7AXu++`^h(BU^>~`}gnpp}Vh7Qp7%vd-%=TcDC*QsZ*!; z)4boDu8VWgrn~c?x@qn5*u8s`*_Jyd_*i%l1IG<>d3_M~cPa%z^1E629!)MtsBPaJ zu~nOo27=@gm&9l}{MQOKTtlx)`Rf*prw$w8q#@LMwby2_PQRhjDNXoVW2{Hb%#VuG z=yS2NLYk@qt@EC_N{LO{%(Urfxxnda=4GK8A*AKNa?uQJD-zUIlMf>cZF~r!y|!U^ya?{a2P0CE=<<0{na^9ITI-4 zTyBNzX*PFapQ|>Po#r;|c;L^b6&`m!M|F^Z!{??_y1J|po5JGOe7BSp#|b9pfQF5NAX z_fzZrA61S)1caGB$~ozG{|!=>YgSe2FN28j;=KXZSZF?xy>ln^2h&GSk7yO#m9`m$ z+t%*LRGplJXjN=~_YfdsrzWSQqi}H{y%>h1V%gcjJ5Ed(Ipv6t+kZNcUEgbOPR{v; zWyO4dPJ(nezse9lTUjn^_tq$UYxp|GY^PD{;48t6IGnX$PTZ>)wv{u~IjJg@=JeU| z3H?6G|8kO92gMPc-zXAiK1YyYgMlNZ9q>Zx87>lLZ#=k0M1<2!m@RrlR`CKY!i$FQ zxT>Y8kyFFx>*F}OQl}-(1oGLYFMwF9=Y@{+K3K8T^&ucSFA>58{jh5>Tx|UYej~|u zyImC=8`<>dz@l^l>JtRU4&fvoe!#YJPWj8C!~+`En70AjJr6kKv`{ zdwBjR3?<~AP1b$%vJ7$atwoe;W<3|R-yV1GG$vkt{~7|aIc^#cH)kt(_s45#%ACT> zXCgQZKXI6ily>bW0V3MsU}vTg(8G>f?K7E3w9IawUVz3oi7VwEIl>hL#Cb^GdoS+i zxJ&o(x+|qNHx7_6aZ5M-ZYue!nHGrxl;P*+kId;J6WV(@!Npa%T3ZRi>H-aPE0l*F@W@$dditYhEFZ*urq2|@_CpaYZlG7RsT zQ*R?-+NEiP* z9kYn-;h8(9|K(^H*J{FEfbwA$Ki{PPlUHYc_J>{5(^26rc~5nyOL4WpC~zR!N2UzRxsg*8AlSQ7{2Dre3YH(?lZmUl6IX z^Kil{mH|cVtk3+ww==Ik$!1UKI)SK;CvYcR#7S^K9H-1T>q&wvPf~x!W)LVodTJH3 zlW(7#UGHqYH$j|Ylnv}@4HU_4?><63qbk37UYbH9GXelg_AkbC0W;NfT&)Qu&T(oN zrM$TOxED&rXJbO_;K}5Ezj6g$^V8Po&$(TGb}5GK&)`TL!zaKBz%m~J$AWQ3?7Ind zpK)Ea$PD9a4X<64aA@2LfQch|j8t|X#y#{ayjN{3E@rR;swBxOHUW>r&F*9oy53p*LtE=W3Xb*h@71162K|SM&Yz-U2 z3*`lcq+Tj*EMxZw``VjLM6o@OKLPwg=ZRL0U2ma-ZNOOSeEU#8EVfclI4KWtmjoYO z`fJS*_R~Q;XUAizZrnB-;YZ#g?YC?dsA{OU*`<#ZNl{9aXK0(ySE*eFFzazXbZ}Y( zsZ4--Ky=o7KC<;PTbe&GrJHn)D+tV`F>_CE{7F&G>&jiUEAA## zH(9fe-BZ@9AlkvlZvaf+pNfRW1KFlC{lJ71$lcvk{foViD)d$0ZcEE0AGeXzSs zMn)Z+RcB+QY9%jAM>%WDp?8gu%Qu}+Zb)AIPsngp#qxbbK zA2zA?;(FmhrZuXm$m>9J@sC({kB{A0LJksPp2$o=DA2J!p)pQrFj`*rYr#nJ{s{P{ z%C@%Q{YYHi*Qm(*uDEI4*_-F!PUz})6nNHSRSRb_q1E^_OllFkO|M;Ka6zxcuZm2l zv}wW?3zIiy+j|JQsFG~~@+jOtL1X2^qLN+BWSW0<8rN<4*3ZMWISA~fY%ahys{c@F z7fgEC5_7vk1l+=8eQi&HXrc(HfWK{lYK2X+)NY1r4G-58AH?}9HQpB7~DS>MRX-S5!ZyxUF|Q2 zm-xwadn6cjC+A7=-2jDDEC2cjzriN4nkSVj&L4TMzDPI5sr903&5rKIcAoyklH|kj zyjwRztvVz@%D#xpDF~O9!Z6={(R87fhrUWOzfwzRA+svAWOu>&`JQfy%ZRmF*7KT5 zWL_?OI#9>!Bd2js-@|VwJh*Y9rmf(}H( zdaIBb$`-FIF~u2k@GT!mYAJowo(&qHH$70eb9scjOsagVgq-fHb_4p-=hLP-67leJOPtLq?@^^2D}8E8rXR_agD!N>8A zKKp41{aswDR8X5#nUmJN{KVSUi?Uw=yoT3@J0vG%A?`}8*8Bc@j_?t-C;S8)lM5Yj z9txaEwMuFcLNu*6cC=DZxZEV30k<@6P%ugRfFQ;9NN7O+s`t&S7>yzey}7}H4F0Vl z%exMnCMp0S32v=;ccd9t2eEiEc!{x-Dben|=;H;!y9@;fxI19O#uM zoP1mFHcG90K?r!^=9{KI;bf4y3^PM?jFz7rN@Ph z*VvB2nL!*(2(@hC=}3GO^T9|gf^#H6j;;vRqlWci#Ww|((@h_x*vg&`sb7h#?Tzsk zRGn^(ppy{V-e-W_fAHqiIh#4DGAVfdr>joR)JTy^UzhP+kCLvyxW}jN+1SXHefdhL zEBWUL)7n94sE8$JW6ABlzhnNu>`1~qKt1y=dk3AA5FY&8ILH%XghQf{tr9SoS_0%b zN!)=-m)TaD*jtrt9pRH7#V;?@#vh*-g_b#N`J+)t4^n7&i#b!b14nL;PFp>5L};P0 zK<_P3N&7Ahmz0op0^06cV*pz#>P5o-4)0@#J1NZvIBd0sGNDX!Mb^^gc;{t_{NHxL=HTgS8h@wrM+KHVZ0vS}+%6GYJlgNmUvF{y=2u)E?JN z(OYCYL2DP;`y$ivH9jqT;}KF!#tzl3#CV0eC4M$WQPW|OlV{8Y4>yI3q-VKsf>b5* z+5IuwROIbV0ITx5($so8@2I+GlI^z5GKzhW=%2p+B>r`dOaHtC03j8HQl2U|;#_p} zy&w3sy>0uKx+)6OKs#_e)S}@!h>BXy`>3{j1c`WMiVLZzhWf4>g|XMV@clAC%$76) zrg1s%It!g8IQQeE)PcUitkBU5024PkFqJp=22=A|B?9+o?T=@&RPw#VZTi_6vpZ@r z8|D6fQ`E55%cL~kJ8~8jg{3>wAqW92jR?4)K^uLNMoIq6=KK}{B>U;~D#z_f00txg zYVm|tjJ+b#1vx{|@l*<=vczTlg74jH(*(A-UNplF0V|~Vd;h`!?qf)ssfJIUb$^dP zzf`Jxg9;Z-EGJN8dN0X8#~!`6ktxW=Nu_YQMG>GPU+|G6CjTs zJ^I%Am8)BUX&tsP%kbvSo7Dv$>U>pk*Y=VQZ-Gtan_iEoQbE<{8r^Ez+7nCpxha@a zYO`NI;=_Pr%{e7qV+uUA3{s>SRg0GU4rV?j19y;AkPx8@(96}O$2$HGuaDj9yQ;I! zj$8CEG^r&@CZx4np9}epfaaC&Nkk#xY?zkye3yAB=1%A{q77@fze!+35LLiHR$3U9 zB5J<-W}7Oju~z%IC+DpG`vjLwI3O6)k|jy3is~5qU|kG7W<^uylK@K~mKVuTIMSVt z(dRbllRsE-7pen&f*?CF82A)V1XQIqv0`tEE&JuT@aTQT3{BRp5r+&8=m19y7jkns zuUGS(_B?#F?wC?yEpFLMrQJ;3hz(>f+eX#E35j~~oon*h=byw^myUr%;=0?XlzIx0 z`!D28ZpDrDZ^Q($e2cjNqw%Y8h)9eqg;ajH$o@cFy3K<>8#NOjVrmh(dnZ(#XwRDF zlq~=+D#n(E{(wpVjBD-tE2q!Q=2$9$0<};=nC)|$5IPa3V);Xte!Eent_TUGnX6lX zQ$c4>afi(%cFX2Hm+a-r2~ z3MZ&$OV4@>-?9Y2b+$=(&{5_H$4@zn-(4qeKI_A%pQvRqIRA2CY?YN&)ztUTJfCT2 z!Ll8c2mvca4{r9%uVey-+B`JiPU!Y`R4M-`F}B0QDDIV8#*sQ8ND|G#(%RY@01|d1 zpr5W)xswGP?C(nDyl8G9ra+lCQpn!Bzwwo{?Cp2(V~HWwq}Gc)el}HbhI-N6(_=EB_a24YPhTuT&!@!c)OwW<8n@Y2;+(kBli@{mRyLSJl0&|$ z4Zb*#r$QpUKl|Y{qu92M;~H{1V^=?&sm$dvWh;rCUc&u&&7mmFC|V#*t3q%UBbjH^ zt={WGTVd3d$Uwtu<%7UG(EzF)_5qf%O3|$_EYD>gU~3q2mD+LT%f;cO^jhO#wg@Nm z+=EMxgA(|(#6NamD8KU0Y0TGBTYku*#kO?|+gO?wbq1@LpY_o-U%z9iL3Gb%WyKF) zjan3tkbhv+1m2H+uWFA6Mk4@7HBg$J@gjL~laV!&dBWOGzN-G#^v;E7=3S${$S4zD zU$>J~Tmu`-YPK3i+fU`?eF&ehm97Z$pl4$!TI*1ZO+6*|O01Fog;i@a5zd=k=Rgb! zRM>UP7p;oRlvC{-pu{pW(OT$@IY!S*+?xUrxe-dK-6EUC0Si!xFx{#y1cCIyvK?k2 zr&SlE<8ZdGbvC23!!>bvS1B`^gV>n|o4L}p*eVU$A`uF-F#UYN8()_VmxhX>N3U~c z+IH5$7P_>XF$Y@}je&P`&QPXp7s(WpAuWqhL37S~6Lg|%v^R@1c;(z_dx>I8Wzo)_ zUQ1SO_fITlk9>;oU8+C{y8`ut!!QTZzxOo1v&ww8uzX7q@e%k741UzR=eyYY@8rE^ZH%vT=oX~+S! z^WN$l$JHqZ4vrnrZh5dAdsD02Q4z0ub8)b7p+Dz|smI(KaXL81DzP=(tC+-@RA_Id zn!Gt4N>asNMzIfqxy%O+pT&cg$-a2)SU1oIr+S984B_P11F$|uq6`vsbn=iW%tIcsOPiN7}K%Vanu6HCHy`gT{;&-$i? z<`eHTcE(%(!g=fw2{Z%kiV`mDQ!$9;Uh8+=D6~qKbRx?Ei(5EP^;Q+Zu6E_Isd91DZJdF{`MZ?1no7{c1rF0jEVzQH&U7# zz=JKiM|3e(&OKD&5feh_E?|J3gv+-41h3Lis65&+6+<{q=oy}25spxfNM!*q~-e0MW1e(^|@ zz8c*=sA3HB#7AS953IL$LD%X8RV?MDZ~%r4&G^hVm?FpfK3{+GU^x+xwncYluP+7M zK1gE-C4Dp+BkujcrSRDoTr-H_E%<~dx2mml8$*R_xGZ2HG;jyidp-&dOaPp`hANta zl~N19azW=dqe(F1Y0{^?omOXm5QdVv+ISP4Ku6GD-Kt&GYhQCPitNSKMbP>D$;>mPQkVRAM5aTxh zobg9W2QAiw1f|>wL`r&bgSqUtmmMCxaMCVuPbxn}!#Q?4)RIjI+5iL`i4;~|>Rdr@ z)d-#N#?5VWTe#}6JNCZEUBC|fC4HId0qq&qS>7TV76#w!e^)8L+|eC*^HOIe0x!+7 zdGhk53^7qr(Ytml&r*mvnw$WrFXf8snzGjFa4CP$92}RguqDS&*WNN_bF{5_>|y` zj7a~76sJxRC`1yrFE^RslfU(Yw1x}N%;*v`mw{LV(TJ!>ZOxR?59YN_o|SLlLOn{5 z4ddq&#iK2g+5tY{2imSPrK}Oo2So{s`r2E#u&o%uO9Ec^VQYfP<2`^nVgZ;|iWrmj zB|ytpFhNyhcd|8Se5S^Oa<{wsZtpq(j1R+jtyAx`>H8U1F3-er#@NOOa4rNXQ$O02L&+NY%;Tobg*9^rtM4XVQm1Tp&D_c>LH>qt=PBG8Vqmtn&As;~Yp{m+zt-!Sxs4*Vmsjj7X)!;l{?>($=1OhY6U6>xK=%r(PzlwSgHaO>uOk zL5=8fb%XnVi4(@2fMY4yQEa*kY(@{KOsa5_U513YjC#hzPJoS(488;{?gV+B88#Cm z1AhsMnG#d42$ z8&{Uzj{*WIxm%gj860j$g)^o)Y#tV+0%D2HNSX z?}h?DopJa6YAqdG(L>O;T?UTR_mi6;U3T!!62|WUf(hm(5|I8M)1NCoC(%utqZbh~ z-EdIb>KpIg{Bht!lfT7KlB~hx6N9tL0y$+}ETBvOIuS@6I=4SHsX3m$Hxp_J^e9Mn z(jfA>xJuCSq@K|sW-bM$RMOeKRXE`#mD0%hp?u0;Ep?uZB)0a$#V0Qu-Y-8~2K0f# zU`Ffei#0ijJM>_C!h7l~5nFC@1e8DB@E*F=`QV9_!G^TkRQNsf=-HfNs8NiY1Fw~B zegd8IURIM2k3j&f0IUu$>yA(~fC%#QF@hVyo&X8g0ZG^ta^`r}T{!h?&ChXPOxxg7 zo9hRw-p;zY-Y*&-RZutrI`rN0*&y``MWar;S7{qRrY-805hl85JG1{~K9IPkzj`bX z0iR=QTYQ~cvpj0S)I8$ph1T!(kU@TTU)Eiob81jeimj@!jb_80^B^aH*k#K7P#TTN z0aF@WN#hG21o^DhsUWKxy(e8I36K$WH1j2Fv(V7*l^}Cpe&pk2VpiiiD}lKTk#nF) zT3uYs3mCbMd7_crlu8gO&)8}Xa%|YFIq4%?L7|%QgCe@sX%#OgxKmwR0s~}JPpVLW z%CfZ3_qU9xyz#lly|UOAmMnL?V{20oyJ*CehU)(2T&FmQM1I!mpDzWC6Y&Or5!f1H zgt@~F7n{0`(U_r)xlVSIxC*o0M})MnS%!9xuX``sJ&psXig$^U{fS`~_WBq2K`%-T zNDQ21pIUycAQmTS9Hf*ep_plKiSn47$}*k`S>~=!(dlit+ROTpYL`+%bI@_g=E_3+ zuhw?9Jkao&R$R;p9mNG5E~!1zJ#h2eWkx;jF2*<{ywDPzzL#H{&C9PXWFW(0%}Q6@ zkb)02<=w*sCVfOw*V-7$u)>nbW~;r_*7v3Sd z_@59P{L%sx8Dy@HVh)rx`kV7NEidHX9IiA4UaMGy49mu#dn+E^4Emte8C(H$6=_CW zv`&qv_S zggcmiw|ypXy5%(_9p5UkJ6ynlx25)itles{w{1#qhL)Dq+i9zK&sXzHIJqjV>cI$6%#J-{0SS zO!_8WBzDxQQzn{GNX|GJIsE`jTQ+^Dv(KDovAVw~0$yTJwe}fmxPE($*-=w)5;$c%) zp~Waq7E4B$noXJv)$a%8I>6hPPs#}DJLDKmC2 zBo>&BYI3}m)(-}qYHPSTwk;QuZ8i7UaHud#Axf!!z!X#s*fwh6etZzx@#Ub~PzLDn zwJhEE(M(oIQS9l~t#=}=s^~WV@`@ln`=+HP=(?rOR2 z1jucLt%R-q(ijbKnrR$)bVYkRF1KNtRZ=gT`DoNqOd-1_hq&m6lmsMTH!=lh#z0SO?5NI}5R!Bb36)QH2@ z5>%mtqf~ke*YoKji*Y%r$bKarnKC@;lUcmUk+UJr=9fS#f!YKqQ&@^pVbG(?Nea2N(0GwU-Y z#boia5GWuk%ienz@!q(fKbYZ7-bSS>Txo_QvRM4HK}o+oter}RumUc3vJ3B|&B?Bl zR)naZS|AHW;7N0iQqy2~hx{BuKivLX@$GNF!j6{H&Xi$*T&)*PS`HuqLt_MZS<0Xy z@(Ia7pxo`~tRdOi*?F92q>zG!u(fpX&A0|{EQ!*56Y{&h-dO?>Ulx;Pu7-iONgC3_ zM4(g6xHbRuY1IPL#a#kc*tl%6PT5G%!A7T?_*%=xq>eIZ34qDtp5lR?i9x{6+(6&+ zjbwtyHtftq(DhAdT2&L#D2AWJ0UC)>vZlW(bka{wwil2h^fVw6WB(Y@`%uwKG^+TB zVY0oS0EsgK#yk4S9*q1v5QX50R-FW?=U%mg0$@LZj%QVB}&5|77Oz z`wokF0oH?t79BG+BfvVs(ZV9fJBuwi<@QgI(JmyB%-u@W&JZ*k$sez=)LWjJF%lxZ z#Kn@9KGzoI3V6|5SjtBgdVNub>IRS*tt#dzM4Vf;%}kCti|ucIvsnTx>zRZ{o~GqH zFWM(^BX)!7kR3W>08S~X7NOUIX)P&lsb2$J577`r{JErlHL(^|%frk6;CiU3FRSrz zusr=yKa*WC7$>#<`V?&Zhr%2Y+6{J`SRS5}MMyuEQwdPi+&xO2d;Opaa!1YyMr?o< zXI?rR$M*GbtGbCNvOHHg7-E*#w`JHgxf;s;}A@?BF8L3e zP)ZNoymL#T#QKUKeK^fxoEO;C;x2nrtv4MT0Ht>~XHdObbSbwrjPH93P-<9xY_F2i z($i6)Q4n5^Z2cCy=rsO@GWNdfaUSR{aC$$_>8zFuL>D&yu4LX_=shn}00!njhZcd) zIus=v_%KrTFP!d^gO%IQHgbo6p=!h_Ku+<^S7`USSnj+aJQXqC9N=vkWRSv!QM`^ zNL`3g8W2sDyKl{z>bETq0@Y$S<+>v%6v{u%V%ULgL;$5ljWSU@x~_-6%-|WQ2+Q-m z{c6-IBrmoMBofc-$V3TjqF3e%ziR1ufFLJ(g`$8;bahgibw}ABa@jcXYk`OV{`L-yL z?-+Y6s=9~I+2l({uk0`W)OZPb^(kFArU*uCEk6nPMAp1?M|;s+R?A=Vd6bdnhlak8 z(rk3Z6&Ke3rIw`!V(UoLn%*U4(`rz510^@uUT2nxkY`I- z68i7k|>FbN3TxRXqsx?L*n~GCAMZM`HgAKCz(UXlGv~%p5C5wC(Saelc5a z1E`RPMHW*Jp-2!N?(PK2S15@KCuvnUB?%TKQ^3!D0c;NYW;d*tp~te@t3yzUZs*Hu zY|D-JXQ^?|V7py16%Qc|ItgIx@?4_vqUk8ZTE``1EDnMf=ka;mScp-`V!RE&H1zo3 z6n^yJBGN&?E4Cj4_<>nc#|K1|tVk_%_yWyzH}euDa?i#lvB zP7&%$83EY;q9r04*uXa;d8dON{a)zHl1MM!+t_v$_-+b=-5x2LzRZQ5G__%y)|M%( zoDOjB*$VJjMg{2zLHG<;{H`l4vs8%=A0@meAF6hpg+;nR^7?3k?M6uvV-bJ?D)3T~ z29n${0+JA@v!)SH*w;_Wf2+Y{kza z!|~)bw`ntc3o!2nCa)!C`vkStf?Gf3q+k2&U7^hOM(SXzu?tg{Crgz(MT&x;8StaX zNU42)B=(gGP@7urK>0=@;2^{>Ih}BtPfGYsavy1V`L^}^(|%BS0iXFK`|^$uk!>Q9 zX8NXLszgc!N~Jy@`o_`beZTA6FP`u^tUTo zM}skmwFw=OB2swnTft7gI@so#3cAnD>edI9QoAgJXV7&_9H`nqfric1&(>99gIAyR zCHzYF?`^EP)hLue#K*{~Qs7^Z=9D+%l0xr8KT03ixUy*apG~YN11A!}YM*v-Eo|UU z7bzvq%dNju^%t>IIqDU2Gv&iD?)Tx!c5C&_mKAqQ?l0hPOeUt;id>W}F&-9X{s8(WGZEEpe37Q0y%Cws6QE(VdG;C;x3su;8&xV8GT~h8AUf|xeDPDeC~iGe`T($_2RSny z0~>cP%?WZ{*~zIwuLB*M}ON!b1un3IVY-`VcnVdR>fLnBxWnTzXk=?c`5xz0U`N3KtjP|p zMH0rIz1`*ii#(TnXs-#OhXD7H?b)@?F7HCk4$m~NPrbk7-|&5EPWruWsUR1ckv8LdL7luR9V$ zec{I4$ycAmOG~C;I1L_ZQVPxJO-9*@2*plLk2kReo1K45G76S!hkl_MHcTUYaw z;O71Qyw>w?1uyZ2Ng7vjB>=z?*LfC*ArRP#AbE3^ycgSlQC*ZoF_qnW$i`cz>x>+& za86x5(?j%b1DA8qNXXv7>H!6f`4^5kK_GQVcs<{;@jZWzfTm!`LMoMx@7es5=_1N& z>2a|YKihkxZc8PvuAZ(72ktWtB_D?tc@aF0f+C2Eb&67lGd14lA1r(H#%6FgxG;Fc zF0NW$m2nN<;;s*8f~YX;~lUpSD8F53pG;SS^6MuvyofC*9F$<7}ExA zrA(a-F@Tg$igg%ox<%jgHq0d||7TyBnpj8a5l7!cU@y3@QcvKA5$SHF6Fg3sF)3P& zI+tx7Qn!hjn!CH0&}^~3-#8hWGcBbVvNyW)m|6bnQ!Ft5fm$3>!254jxaB+oeLYbG z=)v=MFR0%~YA6y_25%8l&1 zspz$-My%end}EM+Qr$;!_;Wu4gUT3iw%p_w(zP^c$Vs>Z7!R-j0C~3q6W>Z?F#^-5Bgcs(2wpk`3pWmm;IY~%}{kA1VJk%|McQetwf-m!}=J}Lp9kqMMvtBg! zUv4eUekfaL5H*?CfLXj{Eqr!V_;cze+x`QgAKy<#{vM$A87U!L!fKfxLj>z=ZWQXJ zOY0i*n7tXH&Ko&0AzbxX5bM0%M+Zl5oGyFPwixRzkqM=1pCQ!e#Uk$>_s97~yJZ5r z8?>uv}FiRUlG%H{?n{vDHz(*&ufkgnzwB046=Ir z4BnDGe&xz~2XTLypsTX0@ZcUWpFOJv!x;ylLyPF6G%;4n&&P^J*W88n?gOHj=?BQY zn5Ml6WGpwqjJzMHGV6zJN5kv{SHPeJlQ^~cYiu#z5iLq&2z2AK1UzZ|ag;DY%D^4R?U$ofRwPe=CRO@6DErKy-PS-{sgYGKwGC=K zN)nsSv|jp=1WLhK%s5s2pdvCTUu!vEZss(Zrk5qlB>^0f;h?|91V95^>2B_|4?l`o z6%sd;{Va4XZaB+QZ}x56+Um?Dn|>L^jD9AemLZk^je-Yj!A+k^ZSdz+7AffPsPcU$ zPW%`V90z4DN~7HAHugJ@>LeiU`Q0l6FTb|HH5pqXAp6-n{NObhGAZ365oz6Ftas@Z9t^U1aeVM1e}vK&2BYHwNmw4~GwOmf}@U=phq6lH5_Ywei1+MA}veY(&Ao?hey z8MhwD)OMwI+8$R#MQEBt+LDxn0SN|kO1NtpPTpqR0GcNasEX6e(etSr-H*g+uJV4c zQ%?W`g%W^q%6T4ApLK1g48}h@RFpHTga2tpe0&CUN7dq`gU#S9ysx?nW=(>T9e zZFU-m5^jSp%Axh57>^=h;XNk-N~byV4u1QE8o#^yGaAl81KE1+sp@4i>1FVsg&sTq z$-JxbWKd^{9!qi7ABU=loy^bBickqUfm22#E5|a+ZW2WP_LEDvZZ{t<33H1DR|W{l zQCG@=hRCrjr#)Wq4%FlLBur@(D>u9V+X2#6f6#(|vLQPH6o9-3v!wtlh>zG!kX!_< z;13t>2*b9PSi$_7H2!it3R$Wj0q?P9HP|*8G$5inh@+@J&kgH{mFy9q5LD3eCmBgqnU=BlPfpeHr#YvU6w1PIYJn9; zaB2Z@6;PDC!&D3un3)UlFf_%zU*iY;|pf$8%_5g-47H$iL21pxBM^2T1W7x-7e zjgfQEQ53oehV;us>fXzmzQ;B>gXHBm>|-LaWCNXs)S&ITkfmadvmGT{953yFUK36u zY||bsY5|Vh!%a`sn|CtZEf5s+mKvvkk}rJOMXvYj;x5MnSzFbd7cz-RNj4_%{cgop z*qOkhu6$Xl&&X@Iye6eyvCoPvHQasW^kHDqEVZOgEaJ`5i;i~Ojqgkad9>9QFq0Jv z>6e`?U?lSDt(E%CO{5O-cm9P1D`SE?E|Am%lRD35s?K+j!)9c9}F*D{kF7 zCjdy~G7jyTY#2gp6~lLbBP${zDh7YnX9yj-4uL9$!je{{0mbdQ=9N2K{zxKxf-xRuM43e4?w zz6w!V$yte=TLh1Dc1?J;mOb=Z_Ad7qL&Y03rou4kzUv2?*I2#Lr~>WLA}N81V^@vg zQiY)YhKs>KmS0mS4||MuBmD9$OHT0ZY1u8#U_eCAw7?LDhPD{=7kly&QiA~k zSGl~=MI`-|KTSDHxE!?d!*+AMoP1h7r|DY+bdx1%_VSsdO!u;x;8w0nn4}(GkDY=M zSW1Si9Wv&^Mzr4~5p(wNt+Gm{me$9;;i_5-j?MHvXKPnV$w7qYZP+#LV?^$)O9^%KennEE4h0|FTg?*Worer5<7}0gc~Pl zwyjGiGK$X*f9YS)spw4;86344goY0q?OxjGZ^a7VW)n}&NmD)Bfriziu>)8%0;EViQJuR)TGgG z^ck0$s_^Y?M0*ZOu`c-;=QnZ-nfeQnuzW6!&$*I;2lve@X9#S#78tG7$BpHrOu!*& z&MT2?Hbq0s3s*tgM|bs!GAHhrQ!H31l(b2eBzrAS1ijYsa7n>(YaNL&3UoGFgMzg7 zV;Ee~?yIC+WsK-*3c1{5vUxDjMKxp}w$WnHX<52IuP@XaGnjOgBG zIk;=4A6a)LiHT-Slg(%?N9?XfFQAbX=D8A#q>^`l*v%EIf8;TaSz>e2r1nV;3u@|} zX#kog6(Eubyl`0^(^I^vQ(}!z1rK+OxBgha%V#}*MGKBnNLs{ZvRHr-c!pb~2Lk8I zcu&a}GbZRhep1Tq2;$nWAxy|gEy>K9|BtG#49YU<+7$$(yQF#OM!KcDL8VbrO1h=H zyQI4Wq@|Sx>F)0CjCGwXRw!ApW(U5sb!x&h*jEkLOesx?`EB zw{3&T!7>%(jL}UoS&Z?gC`N8Sx>H72xtn#gLtmkcGF|r>YdH@ zYd1Mt{;3D8PBr~bal#ovO0?W9T|49fihQTVkvv||i`SZ`0)+T@ANC{AxM8-8^TlTXvJ)-WZB}&=!PzIdObuzAXd->=2}{OP=>u0MW9Y!{bZ)e%8mk z`})yK@%{Xvb9m~vMmn1Ll*2|~fT^|cTlhqy9nAnGM*QPH4WhE$WaW2e=sr;LaAEg! z5%YAmp^GOPgi9Qmqkp8E&^%4-aA=n}&_{=Yfs7j^(F%UjkudamhikXakv`fk9WhU~ z3A%W^QCN}Ww=#*#w*c$`23h6?Rj;K+VM>0=|7rmogC006ss&CT=yzRL1d3<#gz23b zqY>R=e4cI}tDQW#R%Pc_WoM4cjog{|K2|PQE~~uG2D99yYMbW?1ek+XWL91RHqz$b zr3oNCTmp@KhZ>=!hQ{$$DKLkweDu6bLiM-@-QuLet_-Cf@d-FNi#BM^C#vRChBm$b?MRX+?TSeXjk%whR|A*PryPm&vQ#4!LemlLpz$F9;gW z?x^fWQqGMkGODR6G+Q@ndy|@{ZV^hGuVC8*O0BaZ5;od|A;B>6UR53c zI_?C-$VA6US(=sjE1zHR8+J3=9U+aKt_3gfDdTtkdbP~B^b*0kVQV1sSWCJ5CK{cN zQg;#rF3)U<&`5Uci)~U#6}aSM!T;fKiBt04C$SnJsu)t6U;AxS9#qS9nZA3w>n1XC zvf9yAu(}IuvJl{8JYaX2OD4bbH_gS){dc&m6Y2la$of!r*Gh~t0X0KC*~DnmFh7oT?(1#oFn*e zCkMvpGjPph>t|KBy=TX6MtH~ePW1C1RqXREGF|O@i;*@q{vmE&^?dBz*0+xClB+M! z-PI0t>RmI|HhwVO-`u)S>YGhsip}U5N@DIAh`aLGlKn^FnIIW75TgauW3r2$*Rqc6R3A^smp%g8RW0JYRs7#cj=f zcPu~h5V_-hcO-Etd$q&8QW=mRP=o9U_ghAPOsG; zI~)fSX%8}reu^yKFWU*kGN$qK@fXomC;GC;L{#eV$Y*`2_a}Ufe#KH32895N)@)D$ z?4NCw+ok!q$vvME@%BIp#S4^qOzvj(=n8y()XYF4*v=JqA+TN1gIWe z|FKzAn7J*vK}FcH<9<=syZjGlkHe|Pqhn=N=7V*enK-3&eZCUfo8v6py@zNlNfblc zC-b^<1lYhsL4de_-ZQ@eSTfDn`eDXCi=$PgYR%Z`jqCRcrc^@J=G)L_PBTQjHOm5T zT@E1)t4sN3Gerq!-R}Dv;P3Tcywx_+Tm7h6{Vnw?ZN^cabIJbwjC1XiWqSRy(0a}KX*un%B&*w|B)I+j*)sy6 z|GZY@CE!FI+G0RF3OG?ZR@XD59#`Uykm^7B)7#g9wvBrwrO@^LHEkU7^@qHzyH_ns zy4LfHf52=Q-`*~&q_7A2(MiWVs7YPt#m!;`TU{4Gl;${}nKowL-97PX*|?w;HABUO?P#4RS4bR2vtNmy+TcQX63&n%-oR6AYR zrfIg4{Z`iF1re5uKb}yGJZGv<-C>b0P5w}1y8!#K+YBNB+mZNC-U?RZ z?mbKNI7iDG$_vtFapo4YVjbsWJJ*xj zgtI$$3*+{reXRLro4${lO<$TUxvky0o76|Ah(j(}G@3tnCRb_--F|O*SZ=Z~+8Adr z?(N;QTSbw}e_qD>$NPyfmYrFTvQS5zmIhUab`F=@idk>##2!~VN^M)lPtV@7DK(RS z5@A3TJJ}XP8Z~Nr0-*=--%Fa>dIjX?OW>O{ya1q3BhUE)u}pp1$~$y}tj6L-U)bW6 zk0}>PLhK$uzWOCsv7v>4z<4bt;u;V>t#tL%7rv-nmiLRhK!roS8diLceE#kCD%}2E z^#{ZpD19##Ar=wKL}&x{5M3dLTllLJO|p2 z8uy9t@^%7{@==Z}az$9lKVz~^3!*h;L3IOkV3X~&_n0111YpLmgxu`dTY;LAD_pLdX_wu>p1$7u>M~xD8*OJOlKY83TK-&5oe>@`^F2Mm*sOh zmh5{GlOZav+%D2-T<^D@xoTQB$q~rSQLn$4`=P(AeGpXzDyZ3q!1hKttPxYuy^w$y z3aP|8{0ee(M5vbBPsar8X^j7Nn*od*(9YsYahcM2$EZ5bsAi=E=uRxLL+X0+gZD}) zY+Za_ExqlBdH3ss+{>1_gs~RVehmm%)W5A%50VJkjDj5>Z@cjH4-W8%1NpU`-_T4) zBxPQHo0XRw9O2rvpT4|Z(G%jH{s%-w1Jg(!rYiJVUf7F|L263VKVLF6#^hM~UevI) zMHCo2T~fQ{O3Q_K5TJNbQsmuyo^3+ip)Fx1`r&|%t}L77J1q}v2`$&o{axCf3{<Qzjfz;qo<# zwo~p$6EmHaF`*Y6o%qLJD`JJAM``bQw%JP4FGnS&b&qdt9!1n=_pejv9tKOY2ybr~ z>52-C><_#nns={WHa-lk!HW`td7lpx$yBICDaLpW(q!NrOWq4S4#LHIj}e(^S9CZB zAo5ZK=9}#tK*0-n9>Dx2Hj6&)l2;_l%Xcx&E{{;6vrQ;K2NCMxK9xBst;im;rVj2bwKU~)*9O1aeE=c|S0~Q4 zHZ^#uAItWI8^h~xt43mg0$d}VN?wmLmbsd;aNo&qr&dRzt*g&-B#h3kGP*NR(UVJUfZG<40jz=WUHS{ zFv(w{lCeQKfE1f_6m&|9)17O{Pm(ZSs*>wRP}{zv+xoZJ4L`~b{Kd1*nJ>pS?m`Cs zeD@SR`tZU2gP<|mX2H;CLWYVWx4FNvQs&4ShomeI)5$WSTet$bWl|_Li#V~G)*@g) zT?Yc=&ma(}xjL(T=X)I60*aWVqY3YVqB;5xCA1}ILyy^fy_RuN!Y(d6MS2bFflorm zBiXOzspF#I+<{RrG&aIAb1V+eBzFu4==-g*;WfSXI~yJWF^JnY8j_Y5%)w+{Q(rB= zBvheUU4X8l&~^{Hh8W|x4Qxr3qj)p$MKF;l>@)W~0rg8((Xu=JTj4qi)7&3tuDkIE zf$KcH6<>zq$zUiCBz{ntd@`n3VS|^8W~wZw$A^+Ea`&N(YZ_7VcauYXU5H<4`-$Ue zeG_AkW{Ar02oXy(XrCx1LHvoQUZzt93AOCa&adYnnB=luQKJUmLFIQjDtxy$dGd_2 zMiSLMwM7e>hn_G+)y$!G%$Ua50kSGJ8IdzMx%PBwqI!09jx)5pUtvZY*v+JzlB_yJ z(Cp#O(})w~MyrnwE_CO1`6q^zhicQCjsAJ0OH0I#$MJ;Vt1NFuCpH-OAG5DY&A2nj zCRcshnDpdopx=qVlfL1$RkL>8)d(NLg%njIxSKZhF{$zE^}?L?j=RZgq5DiPg|x>y znq(eW|9ofo#BU<+L4he&NI066IrU{c53A~Mp=#@CAylmEqk!lei+5M~HqDomQ*d2cag@te)G=!`kF@1$D zN?Pb4aIb5A2eEkt+g0Wc|N89TXz(;aYwJ4z5+83!T>yhdRet=lqYKRkXuiCq*+RP5 z+H`Y+`-H=zAvA$lAW&SfV^D&HmA$+-(Mwqt5Y_X%M6}CidBrcNp6?7q6RsS|m>~V=8 zp4x-=Uwqjol^`SSzkWn_`|rlQrFt5(`RN3sIDMDKU5iM{-t3+Tv!KYTd7ax!!mrv` zn{t9L`cEWF&gp!ycv@5ZLEPg+0Of-%7sB!bc9fNV=Sl;W%8t$3XAxs#5DmFnDi1>fQ`B+-%Z5mp;mKVGpgCrf`NZl{Zf8Za8X^M}pI< zLRX(QF0`3sr6WN!F_<&aw6UKi#Nf6OtT7kx-OX5Oha9UViB13;7sna0u zpVp6xBM_tTOS(2B!E#F7KBX5|{|j9qasSiG5O^55CHjsRq(Wq*w+g)SsehPNSU0yQ>=q6V9nLzZhbcHEqzJ#SCei#NVU zg!NubTrgTL5e5-NeN}GFg~6b&!|7hnxDwcN9M9@d7L*)7?)lA&;c}PYdwp6V2_KWg z!Wh|kuu09RY2Dq3RyI@n9yiES;ZGk@-%XT~guD)%s+xzsRHV(XLesyPaX#96>S>M9 z;nrTEJyPz5zf6K~QxI>sGoa@Gu>U$D=hupbq5-gjmZ0_1e|<&|uH>-Wci@`)Xp2N2r z2x-`*m8c25ks+2*gnUi4r~RNGP|(7G&)VhvHcUa|F5~U7TUEvk~xopB~Phv^cK+O*c;HnI|s1!b|?o544~7 zTOdo zD%yP5i8{0oeeUTX)uo3gu|!4Duz@Zp(W6G=ru^+2FIjKdZJWp(-n6@8tF*4`=NnTt zzHs&|QJUHg-24NP&SYZUp7J-~I=Qua8C0g~iGv+Cu+2{a ziIX@)f<1Go@UG#7p|<8bUi~O4D*8P%p{X$k-cU9|TcQUx#p~|2jZT@_r-p++cgLZ3>}%F)E;&?JDu6%~Pk4ym(_`b~h{?&$kp__(t2I z&qI&&d$)k5HBJ&DmyaY7B#3rgKX2bn_@pPIt{%T;8Ulhs?u;2ne**v?`NGX3n-vli z0l4o?I{rbdqj(0oc=Q7~C_nE`o&*J=>NoiqHgCT}86wD!7({@2LDh?i#;CJQPJQl< z7lR;fQ@gIxR4*ybt{Ag{?US4lW9X!*DXis&>wvL)^K?xq??%xta<(C%9AY)rV*O(0{j9eNd&fIhPf8P}i1r*#+@G@; zer1_GtJPu%JZ=yKyz<$ssd)^-W6JM}+=z~noft8?^by3{6*DL6rD3UNiy9$!30B+*N)rkjh98|Hk9QK#=5D3@9(;qi zrQ8+-C)o3r_2>iEmi4c-To2ouCk;qsrd;=KSRaqqEc<=tcHGH$2xYkIyRn$^#S|V& zbWx92*Tkt9l;<*#iu z8aN4t+e}0&Y$er?3;IGD6AdXgR>pj!BEFeJH6gJ4_+^xiL;A>q8|0ZWSh91?FnM%y?7ZNI)4A*UA+?cJZ zY$EH^<*FHv*JPklYh*{bv5A9Mckq3qg|Z%{YWgMqz-nux`G9**`0_9%0*rMwH4>Uf zA7;9bz7qA9zfC3_#}yKe?a|!@!G^R^TDlYPyQN+3{5iH^O0XE`Pjg=%7FJX%UHou# zyLVIqh{`$-P~&BC1f%Nw9Fm_J5#B$>z>h_=)xCeJ${rt|^=}L=u4ejm{;=H$S?hpz z^wJcvNFx7(POAv7te({=nzCH3vNs00d!`jKMR|F3fd;Wg)XrWn-frQ?oW>K`Dq~rt z2Y~=kETXE|(!Mau%E}*)x_DuNa zO>G4V9oE#5TCyT+vK^My#hQ3lg=hIJxwJ(VukRnhE9aXw`8`B10hX+AX=Y|d^g6Tu zb@agnGu`a#OY2I}*X^yzEYO%-kU`Aq(kgI$Ty8;>5*y5Se{g@0$o4~jd#AHt(6;i& zV@XG$QaD0~oLBTSqsQhT7@0ta)G&o)Fs|*AluA+tXPx}(4C1SNv)s2qWUvb?SQs*6p#$zv^vSk#WDZw zW-$r3#Op9S8R9z=jB54K$_MpF zUN8O5G|K^kq>yW;E;5HARL-Ji;crr80T_D|XtB>paWbO17ba0=#2AmWLrNPLm~84n zv;X9Mr3NwlA}j7MOv zK*@I6vZP^ZaK{=+472fT5N<@rYL~fJHvYhT`6%2fc}~Oomd@iIEa(~iZEKjhst;28 zzF&+=k=RD&UfcqaXusMO2vzGHip_Eme0Lif=-sIUN#!v?lLh1KNoWDdl~tg(DLQBu zz3_g+j!}f;f%uH0Y{`2SH~D0|fUfN=?qkd zAnr~MCBnE^bd=6Cn9QlcSP&9A-<05~70cLaoFKOB$hk?%Pt&7r0`I7ZSQx|G&kjd< zY)7fZ8P!4!oViQJJujlff6n4Y^s%I#+~nCfc&bKGzpfFDx7LJgN=GKno+-9V|ytX8a=k8yRhIY#6|x4x%e=d@4YP9 z8SG-{BPPP7F0Wo1eHpR#`>4OB%gXB2C^1_X{DUfP77$acSayt5GOt3~?FD~IW2&r+ z`8QG2pZiNO;5~Jc+Fm29PXFjwF~eB7TncNYI^(AndYx2WXz*`|2RRidq$>VLhH6pR z?@b}l)-?)7^{2ZyxX+QH|D$1L5%#*e`zYsq@xJCX*bmIXN$Nq+DsD9Kz>-)Ka_%sDX|NysBU?F)iypfGE|^92ei7q zmO;!w#WbJuQFsl<@#7;yg!pI$vv%D;#qZ5RsZd#u7g3ty-Bf%$wgX7KSK<2#rgI;o z?60ozt7H|@e;*w7OWlDI1xLbIDg|Dn?4!hNZiS`9H-7PC5mEm1QQaBcgTo;!+eKF_eXDV7Y8&;c^W` zd>#4Zm!Fzzd#Ybjo3SfewaKkci3%lecyoZEapH zdDBg)*h!$jc4NfxHwmdHiC>#_!Gce4uZp&8LA2yNQ960Fi8vRYG0j@URVlaX>E$R4 zvO77nh=O`~=P#ISMU2U$ib7#S2gbSCLru}nQXw{C?pqEpfQQ#jI%Z)9uNg10Tcflgvwy-rNBwp1? zjXIFlV)TMxFX7@8&9o;~+dw&k)nYK$0Y1vy$^|(S(?{;P0C5Oyf;85rUq(3vA^jbQ z8K1R1)he-kMD?Q63y zeCYMSHhV|J&~R6xoDCi9LN}!C;7~I>euV4)41(H`!kKX#?Erk)HRMiAWzq{q6n_g+HW^3sZmk^nElxo@KA z*N-;@k%X_;>ch6A>~t7p^^xwF6C`h547gQ(IeKJox*raLrN0;3YE3xJUcW|yLb#9r zPd}c*3jL2Lxuy#T47m*c%7tBakd$C}giV#~T!QP%5qSQ5nbx3Qn$Tt^>KuVze~vIP zy^Sauq+7X&Xx*9(Xll_l101#@6Oe6C%JStXI-6?*7=SCse-5AB0wUn#%CPk4C`yL`vRG81ZXBa1+Cl>+uj2O>TVs;YnSwHp!^v-nubFrptq$OmvW~n9bTG6994DVGUPlyQ3&x+YVSNU%epVy$(>X0I|E{n zml8Ilt;<$;bVb}KvoSdw49Asb&d5`EAKLhHPq(NUx=zoQ>BtPip_T&UBcr$xv?{R=LT7s z3zo_X?@96RxIM*4UIoRWdzg=wdaY3K4P5ar39R?q|3(5y5{u_R7OEV_lKD_Yc(5PBrT{$~DYhcuaAu2dR1WOo< zGw01k*1L$eqXFMeJ47ygKq@g*J?Qa&Lt49L^NQ5GNP&&}I5xyz`T|7n;{iKoK&%|; z4N^VObtA$weht8GX>&O>0B+ZUnfV!z3k~f%LPhM_Atc=cYOsWnQC^W}6e(S;C&g8-iZZ+|Pf>du1_OBfwEozE$+uMVDayB4%M0l@>pRd4F%td{- zNOJfTuDP0mfLbo_70Rds_NM#pF}CHx+XyoxiqlRcN#tZp;b(-qoI@;>mnn1QuU34) z#k^|FGNylH5j*6q!j=Qk4HrqZ9(Q)7vf&&?1EKgV3}U4-aZXRWu}PXhDsm|DkPSW7 zue)4)ftgQ!vgv1Zj_BR%tr-Lkq}t+^;+8Z7tTv%gN`sMq9uiC*j+&d%tk14 zvrt*}L=~z15HR*dnHZ;kN;TUR4W)ZH;t%(G8c{20F-a%;4aW2RKFR_2`Ea;JPEkHP zA9cq#<>B4|%$((rynNn{^mNOlE%JVU@+3t4N(wmj$lUL5Nb*Hp$s0Yl<`bJ#x5Cyt zZfV6$=Gnf440$sPC`dOcI#HMwVjl(ubC9RPT&fIRU3(QL%PEqGInqx0cTnVBYBc^0 z_p;9Kzio^z^JawQU(nI3E$kYcbq{e7#rsSS&|`yav*YH+PqF zpiwaTt7x#JnMVP0q*V8tGew*4E3ZAa@3dSHAb#!fy-h(~R8<7|pe2$2~SZ^KjCydBVoqjUCmEm#&NO7|o#^SgnJu*R3y6$?{IDThW z*O%UCa@YPP;3`iZG*ROIw}dAQkowyHBK6)#WZIu|a18-cU#={g4i5*3?GhY;e-qop z8Kjjy>0++vuN=lR6cQd!po)F^{U*r;IpwQ(z*bsxLF0_nySgovrfM)@aIE%PBLojC zk}LQx10X`9r7QHC-{o%>@rXTQSM|frTzcZLs&Rh4(;{Im3IEdg4pAZhMj-)|o+tUv zPCAUDN3tk)T0dbY6IgONC|;l64WGWX=W5EKEG-lG0hp3}u;nYoy_fW#^?D=H1Nzj?g433Ca)m`|9Mb&tqM{=6UA6P2f?HWoFlF}(Aog_-=so3qnp zE6Y~54vSfL2rn2(q+}=KqlhsNx@w8cQ#g*@Y>`1$lF6dSoV|LiC|P3Hc&p*u_+T|T zRIqxv(#@UY2@Ith@kDl4Czav@8U~o=rJufbh)G*8oA}wN1!3DNF0(8LO2sW{$!nsA zfax_Rb}y^EFJ*<=v?p<~(&cy3R7`iKkwcualFT5s>Z#flbnV}xsdCP_fLP2chiR?j zoH7~W<$FrF!8c!(YpW?fc;pY6H&;#3i{Ijj_p8D1^Wvm6M~Am8cdb@e7*=k7{(En_ z+-YzPTC}npooV*gZ)6U^0yKsWOGe^^pj}MR7;G2P9|vd>i`t}{Q=m#@mT{F7AN>Gke|~{sC~*| zPvbuPy4D%uJR3g7tc>^sf==*?#GGw@2)fq|H@boiV*;Cn3%ZfveziSbU`uMs=r6?nAkF%}wHCINOJe=p4g|_SAa=zHbFygJQ6c79*6c)0Jbsb zzsnS`R1vp1;aYE)Nj#``L@4uw!*LVxP+)#)+qnD+gG+rM5g=>PrWTjd+mlktgxVg{ zt2yT}n+ZNul+144oUr)~$hRhog&aF+$RlLWAK|{Lww&I!-(N zZD1zVc=sysV4Hkf=i|lv&{3`qqNH?01LgQ0d95|kC!{xRrf7Erj}~a`T3Zq0Oj6MC zj>#qh`1Wkyf^Ht7C0Jsg*T({r?RgZ6@{e0;K=;NIu|J@ZQq^Jt~k}WEY?^c@OLoe@Ag{X4Md@?6LBDM#~etfyU zs5-e{J7H<=h@%E-cB>v-Hi@x9Psq6pv@5Cl9+z*)zdvfITNm;as3J^#eO*2F$^2JZ zq8Y~ijT1#*roa2Vnk>r;fNj|Q?m>=a;YYs0{IU-4wFI#YW9;qW93cD_4g;4nqoSgE zK!VI;pr+@YJFq*){GhLpk6iX)^nF$TZBdoz2@GI~ixi8 z2!94U!9r8@B|PrdH5whv9>D&d+o|?e*K_I;_2Qfv+ZD70yLzyB4Ilr3lN5ZLa1l#AnY4W2k;OJNf~X*qAd+oJii^7(vM)iAo%v^X=z4Ti zoDP@ly8FhcoG-!Z_}NQoVr5h2KkvyTN8*yZ(>#Ti7H}iX7Xbmz6YK;klogKyesRab zCbdpWhS<`Qaz5g2^Sz)Ic6T89+am$)D>BVo&V-VHOjys2 zItOEjh;OOkLbp?OMzqk;@E{K)lLox#3e>M}`($g!ki?3ldQ4Wv-g7nc@FP0I1K)X; z?GkG$wsku%+dK3?CZjb4KJxh-p)kW-)~n9e^_bH>_{#@Lw5DwZn4(B3CPu(-jinC$ za%P8V4)k99)&nFOx>I(Pxc|PpWx^+cl!Sj49#>OgbhTh9P`XEGf{w0=?rH2V4-nN6 z+VKo*o=GT=AUHA%xK!xM(Tq$t9IBm<^=3W3pz)!DF{T=FN#}fYvSH6r|FT*J_J^dT zBpeW=^$=m4g{XP~3Alg!F(_6{wpWv2iJi9%dTvA8uk|3vIM_X=xuS78^*Y|x6htPv zCjNTaktD46+LFN)G=w$(Z3x9x&g4TcHC|rPbc{U`sxdn(QgKG1f$W|*xbK%9&FBH? z?nLOLlEvZ63+RWzT2y0n*Y2VFrjQAK^Ixvhix_(qtyUtn06>aWgI?W{Q`PlVuFp3i zUr3A0x5y=qX%#PVm1W6JQzpr}hI#$bx?YqtX8lV^F#IJhk$K%}rCl}7^Mb5MEK?!s zZ3&uza(xmU4y{$AG(l{umi>-^Y!ECEksL}Y*8EE#q?@@g<8TXS=Yb@&5H~P@5#AJ< z%N^H*iGyF-OqTzcPIt_`3gPmUU4d1TJvw8RSM+ggna<_-H3P}pvSH?cXoV@vE7(K- zOFyD^w|(0U4NM?fjM0CK_@gvbylA;9_gI?3m%uLa-2rnq2P$C+t5r6Fmu~gnA5mhM zeOel#>0@X1TKr3zSP_YTwK(>(B;vklDHr?QEpq&BONG03{D5S3%;2=4QXm+mYP9ZO zc&<1tPJCn6YKJ$Cc_%b;%=)sYZ-5{NMuPTwEQe$iUzDBuJ zwYYiGxS|DYpezjyFUgaZ^b-H=in1f1ClB)nxZ=N?m%>KiK(gt^l#ZNM+hMz6gT(_q zL7JCcQ+vj1f7%03Y#92fk*YMUmso%`-m)+pnP7C@XynjX>%lk#7-6-#~WQ`YHuZs=w#CT z{}dR%fxw z!olb{9ZDuEp)gvQ(LONm&$mjA=@G!owXV#b+|#c>LOGGi#sl$?smN$o*%RzaP$n&K z7FSkdateJ)td7HyR=}Bao?PEvj*E#-+g*frghk)8GcQt;3(n#vn(qqhD z_STG39-q6`98Cta%-hE+#6PcKzt%z?DyLC$QG*f8cd$>EKoe2Z^}gy@vc=- zQ&;ZnB;8ZxQ^HP?7EWBr{!QN~`dCIF&D<~#Hdy0OwXrA0o4bN_uP?{>k9s1+#jd+D zFB1f~>DF0Y>`jJ!Nn!vX*Zpx&mqCLc`D9Z8_RfngP(@>OK^E0Vb{T~1t|saof#s=R zIevVXgWQx18)*X-+JKtpoi-D?!wN&QtSmof+n1^k!>cR~XlB2kdH9(7g;f}UQc3D# zd>ghPtK)K=EHAECw>9$cj>)9OxP5dTl|^M+g2^H<`ao$ztg* za|;{d`{xvYe@dwhc8Nif_eqT6;%IK&!QCx2MPr%~RU28tqn$NaiUx>g5aX^LWk^(* zY_lBtp7`(LOQ&X$+Qnk7Dog~&J?>Rux`JXff2{Pd8SFs$!efqYu4GWc;XzfB(PdD-K0IAp;*); zoKY$PcAKtmQ-F+OB4}T^q*B(VSF^RxcfTYJ8G$+d-=#<|Zfs(}&Tr(e5l#;t6tFbI zG^@RpFyB2{QGx#T^OF`5b<4N*qLdhXHY%dmnW$2k?<5^ajfH!@xYfAo1a&`h6x{~T zafYUM$8aB}wKNHTf1920Z)H{rAOzmzWLQ4HAIiWCaccKRke2DAqob^5@bo$;t6#Fy z#ER2!xVZHw5tGLVr}{!cgPfngU_F`xYgyNnesn(80~Yjr|3+bV7!S`6q(k|5WD6Dq^|qVj*YmS<*wN&2*wsC(Ubf8pTwu;yI<`*{|QB@69qGju?>1e${>8}Ay8Y7?_jy@{o2~m6X^%D8COvf*%�H9d`+b-u~0 ze76xh?vj*!G~UgcK6u9ltpV4g7mdJAq0OBI?cs0|LB2P6&_g@ip`LinRB~i3NuGp< zPEC{s@fl5d62)lvtiq=lW7vNe3zagV50l24fs|A&1{E4aliOyTO&6(9kjY(0qe7fi zaG^2n3-}k_xqpO)N`j)6LpmT2^iBd5zzsvX2eSrU|Eocw^njB9z4OQQ>?eYsw>(?S zVXdD0ILBU=5^XZGForS^y>^#)>)~8YQl^3yaMiq20f|_hC2WM7@B0E7{+!1NqXHD) zUMjA<7ZW1Zwz$DWIJ^K?SMbsL#aDLqAUF@sqJS|#1a79}=W?71pnthk7>cuh5de!EUzJYM{}U+JZ3+YysG`nwX;f`ktC!_BA$CGp zyjLI>687)f^*vY)Ff{I2j3!>t6xY`|O&l5?E)JG1oE>z$h>&L~XFjr_N8b>~Wd+Yt zy%Y)^s*Z3CmV`*4Cc$a^twfo9eq;sR-oV6nZR9SVh2A%n*keJMa~z5&2y{HW{}kW} zi|r?ts8omI4jCSG{T0MebxEez!>reB<*cM6C8up5AiZfl;vc5Ea81yXql)lJ&5tl;{=(0zz>r!Co+`mq%D z(TXC#3{1Fx&YNSq@Va+FX03?g2UU+EumtMqZl6Ws+6Q5q7sy`!5FaHAGWdA^`*W67 zGLwoA9UujIL_`YfkgxEAk+cQs4cNOfj#=|2(^^*?7$O^RF@+PT`J4HM`5LZPWtp>9dKcU=3avN;omI^0I zX&zsF&YRm4FHtLVED==NJ+rne7Ogo7Iq%~+lfrC$c!xpiK^(=D*}ay|H0p9l421p> zow@5MMe~{wSwRiH#CXsF%4q8RR$0yx%uB#Op~B#MXd ze%56fSdbV4Rg)Dd8O9zYd&&2uZ5q(S4aoJPyz9~guT^B}bHV4H?MfFnCrWetU7_dy z)dDEFIoCyA3NM1n1IxzMe_HNWOV70H=g$R3N% z{$y#;#)c79$Ck=02y|StcOO)$cif-q0!yS9_i|&^TGjMlqOt4m)M7~$Wn@(11-DE~ zpMG$mc zn4b(go=DfgWD46s9h57Pm2zCMZ|*?ca-aZ%uq6zm{n zzQ+i~4RNBAaQxzYClvE@V__fJiwtvbZH8hy99ZHi4$a>3O2caT^F=fO(rIP(mYRGl zHBApjw8i38-gi8NOD-aM=Z#V0c%XDP>~3J73+5>7NEA&Wv~!@C^Q(_khlm*dGMsMZ z@kg1+X5-b^Pc^M?-D$~7kt^*l!3?*m{r*i;v;9sO09R_pc zr_siNGHrdYf*lX%9IcliVgU*x52mJyxm-pHBdH@x1O$Z8e*)`P&5eM@+KJ!Id!Ha1 z05DZVduWUi;9Y{^4TTxI0%>pL6+izEQ*RlR1=qEKsvsdHEuGTc-Q7qx64Ko*g3{gH za??mRigY*9-Q5jm^M2k2&8Zhz9#S@j3h=no@D_B{t$@X)$X znp95|ot_`yUNC%;K%N)`diz@8U6<)r+CEyrr6LW8dH_B(m3~2xycqxWr4b zO~5BZ3CM3EGrv3+mPG?TO=6+8id#grrO87C z1xEs(Z&W+Gfj;>8Zd;7)sHBVkV}@bhv~0w%Wz9ieSKfL=^1}~!o%Y~AjFfSK7+Vr5 zJZP~5owmN`VN&Gi4p>RiA;A!52%BqqYx+06`*r56O*l3`xv=qkZ0bjtcR5R;qK~$? zrSmvpeyXnIg$+OZDaV;ONYG(anv~XW1(zZ_j#SBbXm~`;|8g6v6Ql2$P-5^Om1Qh3 z+WJdC44PxUUGkQRe1T0(qaKj>jk-sI-ya>PF3Bzuv~#l1A$7p>9#+8$Ag#mrbbGxz zl2weUVG0H{tG6>`W1f{*1)Zg|;*U0;my;gv2jN`ow79(NgyBko(-9CP0nN@^{{ACY zXpEp&Q?2ouAI|q{fsqsya^W}V(5NU$d;3ZQhq&=|uzf*5YyG!S7~lBm!_B$&=X6mj zw5co>?8&P*MFA~q>+X4i6kt4+>!KB1?&IJGg6*oNgvJiym*%k@sdJEIDjq?OcyD*l z?H?dp;#XW#f%iGDL1ed_{0)o(4*=_MxTxE`-S-jt-e#&8lZxMu*fszbW!MSvYG+JT zo#MOD0cRXH?CX$IT4B^`*(2f=7Kmf^7c<1y&j2iUL5c1X*BeFIRBj`P!g{Rzz)p{E zB@o>GCu_}N*DkFxtMP?DvG&Wn?5$5X&WRzT{2%J(^Vkrnc~?G5=b7wnF|sYNR``<# z&*egb19DVI^KqY_>cvW*h_#9Ji1rSH!x@IZHj?=R$s?r6F2>E8CUsir^o~}hnksmVyjm=^m zo-E(l7Jtean@2@WfC(*?uQMeL(4;Gj5KtDY>Q4T#xZL@9{F{`L>o=JU@?7x*1xVbv zI8{_r6omN%hs>8dB^;wUK+cT|{S_w{ukQ^ReAZD^&(A31)1$f%rAxSa4UdoJ*8k7~ z*3GQpI12+vZM*2B;ay0%`x?LRC92@OwmTAAi9I}g+5EJ+e2YMsWyDYy&FDt1s9ulr zad2PLBE!8N%Cr-OidMqjPpIEgE`W;q5>V68(&p-g2uOQTL<;2V8*lL#3=~oE_zh#OI!ol2{KjR#m6swcCX&G1lx>F=C+t zunQYi=*p#?M95<5B{t)~q6LmY(=rpa^7ZbSMKp$P$QuOed;^5wB zNLv+wW+5Ykf`UP$Lgfm%a|bD(7zVOFfZ8fDchT7?rmXhb?EyF~C;_35^nC6w50EGF zbsru5A3t;_^R}~d5bu`}8F2Wr7gS)qQb|?_Ubf}0L|VZtn!~5BYt-S^PX7CSiZ5kr zJrFogPSTN6n5`}A6y4a{(f!~jI+7Az=$2<8O_MA1Jg|}2IlaAxUqQ0yXjb`D4IRrg zmH9FH7siy=$+lQ{s)ZQP8%QF#kuoo8wzzpDn)pb4FEj}43~7%={XATR@-*cZ0zofz zeQ*8U$Is!8aF=>8CbE^TU=#Ez^nsEQhJ>|q5as3!T$C$7c9P=%(PG#+Fd+A@g%wMR70AX|lV3LK&OUQrL(a)6OEeB2SC7C0y6;Cym4D#(?*P5e zBrL>ui;ss#i-%nV>vyvX+x5ucflIl44Lqh1JX`hOz3bAw2MKcamwRemy(%As&22$Q zy=JDdJxJMooz&mP#1+4B%oWvq;PhY9^ja-8A`EbXL49n6BX>~79;ptQz|{kmQ*uEW z23^8s^|EL=Cd?SC(qcWam+CKrsLW&=uf;fESoebhZSoCMpNGQ;g46}PE^!Kq@?0Z`oY&azusK?De(32Jg5~F`@dEk0& zc$KmS>QG2N@)j&n5-9EMCgS(ktt;1-fI~MyY#oRUMTy63DZxe2hUSlhkjG@#_|~pG zqWccT=%nw7E4{@Wom8>UL1f|Si4h@uyB?4t^T!G|=bB^OlJbB&$0|`ikFiQBF1MhC@p@-()EjZoG{zGhFtE9`yY9 zu6mitcsOlo(TtJZcuoYJFbg*_Rgay!0A>Mn>s4m(IPkG5EZ@1qtI$Uk&b2=81xRX5 zIP7L&fQlOBajePY?Fp@oG@euA)E6d1F=>H}v5oHd-h4Pm{*MeSU(+7gcrFDVNJ5`;8LA067)Z>`t@TEHS9W_OOJl)% zpYIy$GJSkbQcO(BZ7HIJjWLwEJB&sp+dIozw@61@8y7Nt54PzEG`ZG|!X}Ia`ee*MLaXZj}uG`~53Wss+*Z#C`;wm_IdOp>K(=44Qfr zrML0Kel0h?fXEgt7d^3~essjznYV{vbbx_gj_bne&7gwCOaTm(c(-KFPvc>oFYy)~ z+?GrI7Lt27q(XQlOs?wCfQA`37Edv0qaZ)fky(MRl!m%@=1gTITPM1kPW>qjjzuO* z4jDc|RmAc!+mi-*v7*Dr#-oO)yesw+EB$T&CT@1MSLiNMaq#^o9YrttcLjLGO8wmH z{^RhM*0=hetnbV!{t1a?G(39Jz^fQU36=EJAg`q}p*heV#8gSuZ2rINDpVG!;KR4T zNkIH`{y;1FvI^&AhrJ_!`EBps&<^5gl1n^~>9R_ZqoBoRgvRnYSPH7J4gnd%(wN75 z+r>h}$G(~!sxF=``fp@<1PlJb98p;2IwIA?H&JTG24XyP(|qG>^u1x9zN086ztIJ` zNT`icGUgyv^X?o46r{PR@z0%zWcuC{ftYD@FKpNQsLu796q6I}W~k$E{2&7Ag+A(o z{!5HO9aF3=eD$rr7Wf;}QP={kB6|Hav+M>hW*7$9gL5Y^Z-Dv_M<$8k@c*WUiF?qf zwQx4=O}TxtTm-7w8;rtl7pmpD+z-H7RsXO)R=<2=R|xgO- zTdDsR7vR#@hu`WDgxBNi?heb;AG~;RhO7e-w(aTgib!}LR;-9VnpinezZ z=~;v^6W zEjv5v0WYx!dMBJag*5-<=Q4hO_^%ZLP(PhUm<4XY06|@10vHj$K|mG#14;`Jj2f`@ z%o)PDBfcipAjj%@@H_-A)t8#j-j}4IJTG241`Y#dlKp&2v80_;o4#NNfmsj$$ha8& z&_iEXLFZNgY1^o)0FE2=N*`&~N--LLKpL{V-)q6Cf_ z`CQ>nQJ8K5oL19_*o^w|V_w&UID)?3zdDMD<;+Ghk?!==`z2gkffq0@k2_dxze{Kp zqkcr)%&rm!B;uBdiUm(@`<1UZRJ>TM(2o0a1i%@E7C55_(R{h;XhP2hC3P_h+~B18 z6{d~v_TCMgF!2H!!xFo$NiAj)J<6W2x10EfDa*Ou2*^{~Cz_4SxSWluNmTO>b9&XR zFcJ3_N{wN2F-8LI9A`~Ea4sWgdmgLl_dGFQHX4+pM9Vz+IIP3`DF7EWihl25F@xD$ z>h7@ARjhTw?LiuHT-lUwF9_z40S@iaM0}}WDay4h(la8Z)mk;IKZ)q+>7sQHj0%-g zj)89@kj&0FI0YO9>sOSj*`w5Sa=)jp_toK>VYrb^Qky<(EspKn#{U^ZQ4|~9o{9R2 zj~i%SY3A3W#PJQ^l*%!!O0=bBlx~G8dgr$FZ`w5|iz5cLpMegq>0*ooBIBy+gYNiF ziDZWa=*TWtVRR8uL&;W`z-$PrEm$S!n? zmB*@?aH>(se|V%BbmxDURMGs!=zUMc`RQGmYRjoDMpNW8H;Y2xmndvc?8haHFWBh_ z__ash9V83TsbVwInJi1*tKM-mUC*qRT@Q)ix|?}8W}$a)a9!P5N_ z-$)^Uru z^d)3gZ5Gtc{53O{Qc3?{fSo@|LD2igVnv_(U`m%QFoT7;ImF1v4ooQm5uF4@S}kb_ zWtXZ~&Mq-Xc(fF}!s;dRjIi1J-#3zT;x1XB8W1A`IvkNm#)XilRrl%=7N5Rf574v6 zuBK-g?qmNl7yJ~Iy7;IFxlS?v-AsfLp|pG>j^AIit}H`NpCLWA;7Wac{uj_PHhz7v zVzVuwZgp9OzqI0133Q%q4OXJ;h~IkM=!mh!4KI?BK3{}&dmx_pm28snDdQXaeAy0% zNK|(BEb66#m_tz=A5HxxDvMH3eZ8i`RxXliTW&TzKvBU;|A0IFD+9piYO8Szq&U~o zHNbHKB29cK)UkXgZeD)b6>NNgu?E<6*t^vCe)>7V;8Ad);1*(*<>r>HvXLK+7zwxJI!ndm|N8Yy#E;4d3D#4Q#_KbMOZ zQs8%36F!l^B8)SOrz@s&p#sm_gvFpTo%$xIn3>Fib`)SgM_t@LC$%nZh*$y_~Lw-|~S5R>*%uUEFPd z!JC!m!^OmV086E>1qEiGmr>w%ILE$%#T;BNoLFPvXDh%TJV`#&CU3i?eyu$HU{$At zVH?Ozz*x?b)U9sb>+MARBby=xAQ*x_&*#9P)!RGjc>-8O2PyD(MEq>W<{f!p-n;K&6?t-(mU`)JQAW;K?r@h{t)W>iuMc ze;38c1NWIUpsTLM!8=*>Q3*-lkwzcFuGsmjVaUKj`1=-Le>9?aS5akEGfs{#5M#7l z`(s9h4@I6(67bf`Kf-M(vC2jCbmN{bC7MHAEZ%LV}HStfHbLs|>sF0mp$Wnx-CBzXL$i*4tlNHSS@t_SX*RG9Lz>Da4jn(BxvMFfw zU+Z4&SvTtom<2Y)t5sS3pXdPhbtrD`4pWFYbGsfeyu&jxGRl9eexfF$QbCR{ofxb7 z?Hda;AIOIb9e<5#^1W(jGEBsvUfa! zA+Cu0(UFsM55yMbH25|IkPTseANoRqP3igKhX`ewXfMg3$S3=FzY(Vxh(>;TditG0 z!$QBs=bi&dfWseN0ueBm10+0!Kr26NIR4D6NSbA+HW=6(7yvQI; zi28h+oOjn)j&HODrZe3DZxQc5-eN%S|NpqwH_%739lFOK{?6M)=kY$*K|9#h>MdbI zi`hMuPH}fLqdT$~Ku~UA5c?z?cAA5K1iv|ElTIkhsrh^NOp%$0Fde4l6zGnz>GvxzDaV@aM}RA|=9Z=zHfHnkOUlp$kL1BSH7;4$pbGs*VbP#}FPO z^|6Bkuwu$_4{jM=b9g1bU!)(di3NQId(a6SPWj(3yHxwzWqc7m?93lo3gkvRo%T7% zEh{ZbnztL?6*xhjhio?|VO(Mo1!O~gIEH;c%_on_g*`l@DAQ3kdgJbK6w&uCp04<0 zV9%)x!q6?fpD!dy5o6Bw0t@m1>n{F>n_zffc|m4eZbmv=v9sFxl#9BS#fHiu#${$C z5V&*Q81r2bL^@dsJ~+L3;>tjbAQ@VRxZ$NG{!c@=NQvs;YGzxw|#pU9kaS#q??RI%|xa|j`OR%{S?u1Z> zWe$Sy(_bvw-!Hzs98G~oq4}$ZcNe6)Ba;hzWP*olw$r7 z?uEXW0*WC+yyOreZc9T)xM=&wcVmsisFh-sD*bC|Ed)eF!96EQq^OfTX&Vk^r~-q+ z9W(nm-PwH-2M;vr!B}!6-$p~=NJK(<3m*k349Be~YI1v542Ojq8YeQ(tHYH>(v+~J zb^1A0b~Ee?&Ce6@EnTJ!*N-%F1h``i;!nSlIwskLNn{XOs_tyWFY&a)U2bAQs}-<~ z5=LvpN0Ej$TUJ_1)+iazHcH(36QQ3>ro-_~YJ_ET%#L-KL?NjrKPKW}Kh=>?Fa&)S ze9%GrF@h+$E}#uvOC=)XG9IQ>k|CPr%fr{+8yJUe^TuN5;3AeXhp<0S-vB8y88uQR z$#E|O^;U71j*&5<1Bzf0@;-eLnY%R5{guktkIvr1MEpHhCF8?L^99v{ru>p+KepE+ zgAqc1BXObmd$}zq;}kmG+%J+PF*aUI(7K@7jbZ1!Q(B`Qo+Ga(_hF+CeK@FEm@F!6N^ZGK3)4KHXp4+%&(_A#X&BJGFAUrb=#DCxX-bBOE(P zA_rrLh;4-HS)tOYV(kx{3%7cI=I8%4oXF6Lj0Q(lu4I6SaegnGNC(e#`R~xRs{sFJ zuV(cuzP%=v`U*%>=-IB*9(B*bxDdO;aLqd{s(~{r5(xVK9kVX1>&}ZzB3vn59<4FO zE3f9?C(q06T4v*JVtV<^yoP^7q0t{HUPjE%`SYzKKQ961UV;fm9nM}TSPSWEhHNK>C&AIz?w);(T! z07tiN?x)^e;WG7mS+?nNZ1Bz=|M$*9^&;>XSD3&xyx8Y}rZa3qm@4Y*GoLon^xAC~ z#e*vkj<#s35E_~?RV=d?N{{hMwZ!DUe9=-yui`1cW26{b-HN>*C3|-(ek96O_gW$c zQcNOZ4!@N(3>Sg;D8=WkH06dMI61}qd{>G|Man4CbYKwuvzhRdY&^9I!ISXJk9b zG37Y#2vv9A9QYmu%Eoxch6}}aOZQZ`KHVRbe&GbM*f^1ff2XqEGxPPLVw@aiAn4BX zW+j}ma&ULmCXakbB*xjKlZKe_O2;4fl9|L43TDb-1?xI229tW!`=EvitRtEK(+Vj5 z!v}0mMCQDrcG{q#ygD7mQ+s?eCN)nYae7858pY0^dkWUheSYn5{{HH7j&?15lrXBzi*o z(WM55zuR1x`Lv-Jw9;wgRrK#s+rSe|TC{R=x=y82SGr~`+kXWjkse7eYq@+I0oNdO zB15$sn&wd%c&CZ?$xwGN>bLA9YUwsQzEvgD?-xjLkLdq6Y8NC}2atC!q(Tr4=AS<3 z-5LW0Q!w=6e<{1%>+yR=d2d6C$#RkkoBOOv*s&#d=SXO&*CAXcJ~}{1|1p0bxNIYA z*s{zzkr3xt{nzupjz_S&iXmCSep%amefwygTja^fp3498@9&UR_a_(hM4P&`p$IHG z_nB~bC(<#ebkxgE)oC#d=@=D9sSqVtk9kN1mR=7o(^`R4OT$8VJ%<+awH_-)yKRRt zddHa2SB2nS3@K{vgUM>h20hoL^;N$aV2v?p_*b8Kb% zzWs@hM7i$Fy=LOS6V!9&mK;XJ9&b@G;fdMZI{}0PD=JDR>PBXi5h|;QJj9B_Z@jMlC@u_x)t+KEryE}iL#>ob&6HJ zPu2La%4$}2XHh@!lZ3k`dcr?-eh%=U%s1>S9qx}?7jo6!-<7O!2SL8e2_Q3OuWX{Hoc^=|IOfIDp z$q0UQtJ4v#6JlTDUn~7MtaXsg>bLFxmTZ!rx&I&UyMW(7H~anBADd27DY>Hhm> zk-GDNuy)5elA`V<;)u8lkMSu)p>+gOg-+IW$NDeZ0nnGSCjG!USDj2N?^Pk^`%osrk$C)%T~-^`^XWwAJKxELHuqY1hviicEh^WCJxiu?>UoMR zpXOPXuA_Ue2am`5l7i{X-FAjW(k5-;o#TIMAJxt-{Wu0vn!5aP7jvq$F7 z``*q}#8(-UK&{fgmSN>DeEL&1aAq zEAM4Snj|*?ZAQfwT^bZYY`;apivw+sjoVts?n~N&r(vHBm$!kDd5)V8c!wOh-I=}7NAS3HiP^P!*3S?F*pCw7wFX-Fsb~-5> zn`J0JkDzeKB$1tym#F-{YdZUch0r&a~t#I zdgDL?2jQC!d#9u8bE>H3laQFQ4Cha(9w)gtm%wmc zTFpaoeQV#eox)H|M_Rr?0HJ$Ea z%g;Jjo9=KNcs&@tM8};^i(|tJdevVd4nTlmW}DedBKgOUAE{gA&(6=qBNjCG3bxpr zQhyJouzpNfUS$7lIbSrg`I0`=4>>fif!eg}wm9=6ejg2_J9E9d$c~f#3{6cUO$1F< zT}00}lI!>KulH5ar=%3B0Rf{G; zjtQe<%&_`>Sf_hO+BJfQuckgGJfHp3p4GVy)PNG4KFi;C(SvgQy`t-3C{grqWA&YV zG~3)Xq2aPnmJYk3s0xN*hh_baSAVEpev@~D=-4{?sAoggiCu3>PJ*)Hh#E?gebS|y71t^A*$x?J>J?+2K87Ul0kfG^(Xy1jg&54O_bW!C&GWE z&+a91KlTj2Mh?*BHI3YOH(KA(+#31r@zjZ)m)h*kEZZgO5YffB{&gy;AK4*{W>#ro z7S+26wY160hk=&LQCBV-+jKEtq{lnou^IRMCSkV1PR<@%%LILjvI;|@5 zJsz3vw>%A!*A5`DtWj+kFm~8-z8qDwKhXeiGb*GAxnDL(RHIR|&ATz#7H<@|yWQ>^ zJog)xI2Wx@o#9x|i|A+Q840k1Yao;hLHH&@{2AN>QMo3jjL~Mf7L!bkJYo656@%P} zpzP0CRB@u~hv?A?#^)v-lccxj=vJGv^)mw(J=486MYQ=bxJ|9Bqe{p4(E%{q{Z180 zA*lnFa};}{v&(oKHc89Xw3|~Xoc*($rBBOkqwM>Of0Pte+rFI^|I$&`;@9yU{x&p? z1?|(bEnR{-^|LbXcAB5K>~6cak+VED>ACffcC7C};v&u-@wYR2UK1zrjdpq+7Ye`2 zl>oz~$%Ch@AV-gzE|;@^wEJ`u-0tP-qI$4}h!Da`mYr~s#%H2^lcVd++<|cot_{`? zg?JT;?bX7#M{JX2uhAFZjN59Kr}MZp@?Gf`J)AAmSAEetyUN#AtCCk}Hd4F%ox+89 zN#t7;4f~}u2DK3L$aZ*UTH<;r@vgPH;JU%P@#IeJY*!<#^fh!&2`QJujA{SWSE8Rk zJPS?Ld22^b@Nt*~6bap%R1-}!=Ds}ecE$9LIBR(lY=AV#vV^g?u>9K<{J!zcNq!@U z)swSQ$Fc!^oFL%KXd?|4>EjgCHLdB2Iq@ZKqaj|3EroRI;rRo%zU4cl!Kbga%4_LK za1j3kc2T|Sc=@gzifoXSc&|^3p5bBY2}$7vK#vZQrqs5PjDQ^=k}p)}$qyWVx97p* zni{nFSs}a9*Y=XlUS?Gl?Vg z1%~C#Fkw4#p7kgM;b#j@BhvGAHpbKGslx!5cj2`v?#q)iw0q!VM$I{yVy;=d@U zvv<{(cn1r+0g?WGb|W|)%3zjR`j=hwaps-JPD(Ay+65J;_+d}8Rgyhlory9j-T2!i z+U|?^)`+pva+bK2_}AMtKv+=aAa43eN7_Dl1yj>7B4-NYKv}%TvJNAeB7MB49@O-s zAyW29a88@*`Sp`0_gale(Xz4G6B@rz=@;HV&xyiOIY(O=lDcE>e=9}(!1~-OB*ZJx z`UTQ#DkAY$R%%YLOCC!z__mM!Qgz-v?(cJ}T!J`YZur~VK*0aFZh(9vR=xv=e5iI8MDv_SK2}bm6s;kt9WUW3z!uj*?J&73MCz==S|Aqfe`A1 zS~+KP0kYPals>mbmn5_PT%D4gwk3TwOcdUOO31#BMsCAPR9)4XpO1LV9(lsH8Vc}k zEvqpf69M4h_MRbYgjat&b-DFW4lS+w?Woy10zPvdIAahA{1VE=h#k_>CH;G~xnuU@ zmWuJ4IvDQZyH!WH29Z~y1fu*!KQBmTKNTw0u}yy50v#>?H`Wu@sgoU?=ttzC7`!9u zM8BaqVguji*|~eKBe%4!i1v~8C2}I4MrD0(v(^RPJk|1aeY&2^dfh8tQjNVswhshm zzPumyn(W*?x?HsqH7tgXrdqnwBqP?VD>(Ynh-{-N4YVjZ7i%RH+G{*h+%i&Zah`Ij zQ>^yHBDf#-v*-_dwzOCck9{1=yxGk19v<$otSA~&FZMZY>#t~M_y@=y%XHf1)iE{t zsut+aW@pkiLNuoP#5pSxMHLyMr~f(@9CyA+IrU8O{#9Mh(Be{iz)vc9g|9n+Hf_1F zhj#hW=7+p>Tv999cs?>9Q*70yIQDK4{xUL8?zGi2!m3Hss_jH>ssgBICMB{e!!Giy~ zKk-lD&iDl_{a-!yRaJ$0!TYr|c^0c936I;>OUIds0>|01F2{%X&GD;~jN1vGU{$a$ zgCj$9(I89)KcO~r|UGt&a6B1@x7FQKj1RB4=c?KADIyF?4N>|pE;YK2@C;v zL#M}n&+|^QyvyF_Lz!%LxvQ4A>if#DMqJJZKMz>h({TS=z^@LhjgUk?|3%gCd&*NOu`&mTeMRSc+AEo;1ou1L?NQqg|JM^Y_l--w+n5{yy}<5*Vn}1o z&!{KUrp9qb;-R3eUU-$TjVM2Tn?rxT#~ifAOMfGcC))WD#{iwdfaEeL5F~`P zCl=}mr6LX{k`2>DBiL$^OdM$)h90F~cpYYG$c~)e#!hh>wjbY{%I5jcvOLthNpU=U z7gjRC|DJB9tG+bWVH;Ds`jI~KR}D#VQs(PjFOjwd`y{87LP1TVsbkan@~Wc|SIMoT z%xl8ev(-96$O1GP-3F@UZv2fB`cE1ugQ?YhxZ$Up4?}BL%RL6R@fy!+6mERFbcF`m zaby`qgA-Xd$6A4?{b_vEHQbQB()Hv(MW|% zBNyw_v`^oYCA;Zc*-5Ug1mqlT7kc!=yoPI#7D9rp7*ZnQcFa!`FJ))Yt5fCm73GD- zV>2hNJ!Cz=$T_Mf#FZ>wF5zY|?nW#uy*p!NhnK&0lviH_5sL!lRUjy0pTB?^J<_sx zKX!DCVdjvg0Ym&}$-Buiof#DuR}gTCgQLq6wrI7C(1a;PH}JV+)gpIFEO3lt1>6tJ zjLYLq(RoF^gswp0X4k{gW663Lgo1Aaz)^_0e$iD&S9+hH1&E`@UZYbi$o<84>?Mg! zO2XDyT4>X}1R=euV+o{k{bL2P*kffM$F<08SudQtkyGtmLvAONzaC1QSG!Z`+<_X1 zV$9VwW)Wdw_*+%JQZt;XeQMw<7yzks<_I!q7bAz_mU^~jkJlIO_Z{TgoC(q>Z6vp3 zCP=tH86YiYr|9GP!HVjc6=IkFqd^hSrdhn-k{OBdaM)Hed%WV}FhIslpe#cfNPyv~ zRyQNqx3ak{DS|>OnYnsZ1`J zp-%o+k-Fw=+R;7opkR0R?8fp5xi2O_a$9<2{j30-xvA<$STorS;U7&i?w&CDtG}%+ z_(?T*!u#XE=%~e-y;$ruq|uyro^RX0SF~DuyOTzLiQJdygE9~kX?&Ky{p-l0;)_-j zQ5@q?(55O%K73jG>#6E%ov2>$TQ=3VNd|qgH~08B6zA|$Xd}K=AB(QD__V7q(*M{D zULs>Z$9*uE*k|EToRqVJ1fa+3nBxYS$S(TMj=S4O)_}j{E`l-oGbLt!Od&?!SX`*d zq{Y!Qfrn)dVwNVcPvlS%RMfZ)t1B{v@+0i|&rMJc<$rATK1puK%s3p?(+f+m8>opc zc5iC&Ij2D_j+2$R8M?XtX*s)V_mpKqK)k&0;Gisg|5eBmey6HapH;ybMwJxhaAT_A z2xMxS>tv}_s#F4yV0yfAY-2SyjKMLS_JdiKL2cZ#!SkI4o4C||CD2gC?L2k%ZRzTG zg49-rgk5lc_lwS^)UQ&vCsk*>7&4GEw7Bh-_(EJ}pD=0F-OJmC1@5i$XkNyuZ5RmT zr*q$tW+d3Qf2?J2=00#5;penrt5^8n0 ze#b4k(?=2+YJS?iojXH6O7BKz!wYa|R6E9vn)Ya@3CMzlCEY1KHB4C;6gAh??pB)M zOosJ|*diQ#jm^GK&Q@-|WW|?SG3q_-U7`I+AO{yto~&2N!wp3$@u+%<#NV%2US4!! zPX$3`$XLl(`$y`g%;a;w%7hA`?UV|Y-I8Qm#b2flCB@@y7e|!WaO6osaTM~_KAgxI z#?t&1)!OJ5Z2%|oVgdfqm0N#;QOR;;42FVL8EJK^hmpBfUcJOhJARMvm;~9!Q-L`6 z?6av)&;N|08f8qL9&X2h*iTb-cuv;?&0Fwd>6*p{_g?r;o94L8!|Lsl%uUgJ z^EjJ(+SQgEE7f)Yd`K?^t2vGm9NfdxKFTbqmka=XLV|Qx;5Ib?#Ff@HXhJocQYJSb z3s%QD>)QUhYFN&1J%ZDlb>AJt+)uY{$6VEDp!WHMYjnM!3cwAIrgF-|AYrNR=1}QEt_0%_WY=0N_`U57;%oⅇG4Y&PMl zRL|9sS~bCcnLZ1>-Vk?ncqXxZ)G6n*p^N21luDcE1ajMqeaN6BlVFUdcpS<^)!Ts& zM^iNmG2;kBUM)?mV^$Cj`7I+IOw+x;^$h(_dw~Ff9Yo!%QLXS=r zmu!jBR7G3DCjP&GsKBqLKzTTImBQfv;;qsg(lyl}BP%N|ud_&|J&;4o4>`peP)_64 z!pjrOq@|{2X6Qd|e$OYq#!Q zuM5KxZ1h3^`u~y_dD|^F6RP}IQ=@3?7&*g*kk8rcogVyWfMTk9mFOV7Ad=Dql?4I# zoYw!|4}KaqNceMDzs&G6fL`q$uoE*>)zvBZE69^Q-yqx6rC7;9Dxs~B9QI0*@r8t- zMfu;wjTI=^7^}ox#M*Kxaq=Dq%^_Yk%aE50Rqf$anPWuczGnLhGcE%4VUO=p^wpd9 zOqBM0ACvyw+2Zr`#QN%AQ@B{oDjg!aEDYVGXrp)}6=t7w;IWamoBT(-DU_e(-NP{bjhO9qMy@07?KKnkVfVeO1I>$oWQ z&Z{3)RaKB`Nc93)Eql%``Myt$*R0#&+?11N8q?=*VyS8es-JnFbdvI2<7#muU)%{^ zf?G33t5h2EZmrKY`kGJ2Hus;;lG<71v zf5~Hop;Sn3NK?it4{vHIO8q>Buc7N8K7JcG;CJFwHX+Bu{qnvtW);WDOYrQ zlhd?#yEMp7p{n_&E{$pEQuxZ}Wte5fR6#~M_z9i_xkjd+3%1%M_}aoy7CGP>S$qwJ zpP31LE|m8mV@mT9;rbotrf=H#oJYZ!$nyyXnE5t_PU)g(v+&-Xi02(lR^9 zbeYzw0t;(Mdz?|9RdM<5WYI+V-E>O7CC~k>J1|kp2OibU{rIKVs_lE(9g2dFY}7lo zdJiBpTU>*TiMoDxZ$=FVZBd`H;Dj8F^EK>HAbTkHXNljgWZinAVy|9fzaT_|a#KEL zE>ZKNKJKE|11=K{a7PY!sfkC+X}uSgv}s#CLuaTO2Yk$v#%4iBhCwi+Ut!t5<{Wj1 zvMP6qy%Oc8u-1(?dV`6H*-cP{Okh^$OH@Bnl9Iz(OX$Ax+6qNOPv1OA!0taTz#}ka zulw>`uHUNd{OqX5a|aBC(AfVTH>@LDJ+F^yx&HK+14CXxb~bVG+~}+pxC90wILTXr z9~7>=hVmnA^~!lQT`O8LJ+@Mmcd1f;1Ft%(e>hY6)P8igqh9LQjL-ASPZXY6`;P?2 zIZ*mFtx6LInO;Yzdj1{G)W-CGL5vNd3Kj^u#Tc=u0^r-vD!z+R(af}h^6F4yi*@I) z*NcQ5Vo*Hj`t0YcK}4Zd1M!bJ6)k5nvdzG46U5zxOFK)qNM(`SUG8r;-m7K#l!HGZ z(C%Zlj{btjc1CkzThyfMKH}92L+hsvcC2O@d4kv*b(^ z#^jKaFRoEvOao3 zWsA;FA*R;M*L{06)w-$b=CccOBW2!ZmV6)fjw}RK*u@&h-s7Ic!!S+$6?o@F`Ul#1 zMD$Rz0h|i-bhI(i-+FHVSFGxCnaer4;G)Hq;YEst%V|s3r0RTqv`FtHCy%1nuW6RN zD>vhQR#tuLY%k2#1I$_u8*$PB-67&9oCT39Sg$%vdGV#fyOpJOgz&t~-r=mnC%P$r ze+6GTwa(yyRQJVYo(Y2?3j(@4uM|lZxnbezf{A^kGfoC&03}ARa$M*J1dQ(|aR>#^H*dI4Abhi| zTz`3oYxclS3kIsXV5nCY$6dr9pW~NOBu}H1gaTc>@H#^N`VQZ$muBSTZu5kD6gxk? z27pHenRHUYIIWO(Zt|~F1jpl348Dh>%PcatfWaI=46Xc+4XMQ8=oyyoRKl6Yzr%e> zjLQs--xC}s7C**LeMvEKL1~D?a)FTq#cx!oMSXUPZWm_C} zf4?EHem{_N{SR#A`PB$FbD$_lkt*Rd^!1wf(Nx$E4ZIF(?Uiq?oCxfh%!cuo6Gw^+ zi-Gg7IvBh_7TjvCbqb zeTM&MJBT=e-gQX@UhAmjdP~x4IH|(C^NoI9^#Lcl#J-mAm@H<#jovr65@3`3iTivH zv+8=--T`O$@lDk>$?W)DB|i7l+UD6L?f%B2B4_`?+f5d$VG56{EK`=ttpu1}0?*eP~m zEz7l@|ND>qQCik*(>qJDOGrD`56FoeUKqo{Uk!$deJMIo0>NfNbxf12*|9#_os?PL z<4yy2JkH~@cgYKUe!pMC_Vy>x<`pjjEl{7!j9yYDU)LuAc7JEaNjYw3MU#p{zmjSX zbe|pT^){b-PZ_UYJ5vKQh4HXqg{51D;Gxo&@6bkep081JNx zGc>I#Y|Bn|xYXd3eYndPKc+Hguhy$Mt1=txar))ct?OB{tjmQJuBk%XfSe!gX+7Xo zwoTc!{3qE23#z@DO+EVl3MS{dyzUbDN_NhFEw-GUI&Wh?8(4i4GTGgm$gYc4nQo+r zJO1Uj+6Wlo>_7IGpw%JW$1E zKivd43>ebev@`w8S|6%R!Z6B;W5+M&P1U3m==AHvzxdWE+qSif{m9ZKwm}{#<7mvw z;1(d(*+UvkRR8O^5nPS1Iow_rFeO4Vyqt6elppusL7_k*}J}ydZ zOP`B66({A*%pNAw7k$p2M{w4rsOPUzf2VF;`;@q09b@-gtyO;0J{9Y-!UEPy_eDe> zvj4wkGvzAqIO7Z^DWc_KT(&ii+VRb6s5k$^+ASu!r-RlOem>_q*SXGlpLu;tP_tOc z6Xdjr(u^ZAD&Edvx^OR7sxphWOZs~53rfF>d={LJJ9h0!gK#I|P1OMvv~Vbn`Nnji zJlh-ZwKm4>Zmh>?H{X@weqg#6k!sBlBnbgaX`{}zae`OO?n4!>j6zyEhOsjG9X}Jk z0Q+e*wv&{+V#T_&T5VJLH8hv%&#O!n4tu~!@;k@i*myoMrSno<;tRXtgu8~0F$&K` zuO;+;Re7V~OIgU95!)C=G|s^(9@nFG`I}zuogkXEpSF?uuQJmV=)(C%u_~_QrUr?R7-a19?wY$6EXgH?nGBz-oB&hDDLH{OlFjIjW!G?wKp+aN znX5Qq!CeIOCzp_tx}2{T&s+X>ma7YJq=sUZIqCb?TJN+~E@kY?gss34C>!Xq|DcsJi=$Ua<=MPPO#x6o65YjK~Lc&RJ;zL$qqi-EqmlH0(*z^A66ff};@sO9~$)Kv2dCw7Sy>Gbm1 z5EtDGt7j^l$<2n{%)B&5rd~?rJo>EPHKK1~l-Pagn_lwJJbs&?ucURxYD3t>_IFWj zQ%J0yu+P+*I)2}DH#62x<&&(g5;ebevg0;yUYK=l(vKkZS;*KtAF2Abn=8~CUMR_| zpJe|a;#>8#;b*zknnODG{bGe{`Stp#8azC7$(%_S-gQpBxn3w<@dg8*Hh0H|%_z^C z^Rqy{cWp9rGnU}b!a=m}0Z5By&qO&>=z{T_6dxMGLdKpWK$;d=iGDQDAgMj6Z92FG z1@NTO7DGcr0^1wQD)r**TCCGq%`pW9>~RY*UH5gdmF?!gMGT}1+wX$T5+x8~+F-CC z6JcK!jM1}@dy)cSx)t@AmPCI|ZSC^Z$}7S_R))66iD^F=|15o571w7?i6XTWQ8eho zrmXgqElz}LEEY+|%OB zz-_!xE7G1b3tedX!|TKiolNpg<+`$Ir!I13N6sepGgc7?a*d@pm#?FN1Ru4=G-C2(g^s~5On`m2F)~?mV zMwh(P{9s%K*{_xD*{TR`EtU9Oe8GjZC&$iwiUD!yZ$6QZ?Q{&a24ifYLp5}I@)zSh zR|`T!KhnKU6J{$9E$V9Do%eOTl|FY1E0OX`jG#ZeEL#3OLk9;3sY=e>t;GoS{+u{z zoIaCsVk&41^iCuxY@1KGyV^moC zolq#6W}K#I{^gmI_J&KBUfH>dKYomOk$NAYJ)WD=>5vo6ljD^Ye*(W z?Q$RNSdHqATdEgnE}xXCmtq+=h7UdN$sDfZZ>yMfzMhd-uyS#b?WqTo>vmea&~OyF zY3%%~aK-`ArluR=C{0@TA_`V!PEbEkI`?$MUSeFgcQif4uQ^>&wy?}D>qL=G5xTaa zgbwji>z6ZZXtyEuNc+vG4lDJ`$um(%zE3~|*0R3PppqSP9z*vgW@~Hn9c+*sNnUJM zwKb?=#4;*ce=Pp7LCjJGnM2wK;+_@#UtBq4(O`m$zy?EJe(`eb8`TMF%<*2sZqw@P zH>U{;bebvaTfau}xT;_Cl4gTT3F>~VNNp!cetKL>5I;p=zXHx1VW41_EfKiAHPIn*EM>&%4S_hz%KU-Bn<+GL7(=Gt1Ven5!dq@)bA4yLA#m z3F@KDBSk4^Ygm$LHn(B~{ke^VndNq&4Cd|2@&w=16G(%o(u;F>goMZmCs>d8qHEu z>e6a8d6&YN&qlNAMOBMd*=XTLs?COuukn!%`SD9{>kKL&hD0KLZi3{SDvf1|mI-oH zrb>3tlHx_g;70_v;!vbu9`yN-BKd{xeUB6A6+Uodvd@)#(3*wY?waJgZzN@*qUA%H zX}d1ZS`cuBki*l23Yvj^t(OkFxq&;&~GtKg^mNVA1S?(H4?Kpui`i|v^qJiWEe~4 zrSvImo?d?V*wF6D%a++U*Dck3=C6s4#N z^#fvs1!7*7XRDNtBPJh{*znau9*F>wFPyD&Cy~&($ykwfZ%m3@amQp(vu}g3sMf1J zmhWBhaPzaWTFlr9nDwEg{q6R5OlqOdqV2UoUl2rHD}+l*J-7~C?=K7=^{?8pG!8d+ zNDHb-C$FMTf!D_5VYK)l^P(_kjcO#QSUkFICV zP@H3mX+?D$$!54{tRFGO$j+Z(9<+JvE5i~-g{pnVaGBSeYX9^!|I$ENvC63p{n~tk zg~i!(rZZ=fDU$i4SW};Pe~&=YVWX8#+ZO&<6Ok*(Y>?Jdq821iZM0=uNMz6VI$OCw zHs?tbIW6T?0&W!0u2D$*5Imc;DflVshcQOt-uV%`UO$mSJ9vofA$e4_eG%Nq(YBL_ z8LpYb8DY-p*lRudt@Q;vWIgIXHVl7f9Jd;K=MIV%uA=iVC$Xi~l8stTBjBO5y&Jz+ z7&=yvtJBOUBqXGsR1Qhydg%}uIYX?B#s{6ON^FhG*rHpk+%V9>cex>W6}oOb6yiXH z`I&@ow{1~uu&R8w2V~Ee+-N@aLlQi>urXTeYYr;&yl;ej`CKc}lU?mOp*BeIL2U?= zFof^0Z_cu!-~T#s@(dBShr5&O%2$GKVK>Mhes&&ABuabcqy#YVOzqgcrw!m$g>-y+|P(@DbCPbHPV!NQplPzvX0QuvPRG zsLH;6v()yr)6*Qw@uqKWk%JA7f^tSJ~60HXtWp*hA-`_(-H%nycGdCEab&>UocdGE>c8Wi(&Jl6{j4 zE)?u~lCIO!b}7OfSCX``Eb+ty1gLan+8z=YEmYAoQvCG#5N8APTG}Q-Gf&C@M_b%P%>G(*|Y z#xB)vQ9AEz`gY%xiJsB?Ii=x3@SVx83&0=OT)=hhQzAem5 zz09zaZB5&5NzU;K2r%?V6i63}rv{RX(F8mtH@lK-l%sk7^N{VXeuvq^oGds2P_(T~ zvdy1pw-{;K@kz%v`*pEO$`=%8m(+zX+JwVNUGl=S9}&GEs@<#6Yt>YM!S=y* zBf1FCH#dr4`?2S&;@gQ3caFFQCA!ScFl)-Dj>vQ@D|7iya9E#)FUL@@cEpQQZwPS9 zi7k~|bV7&dBW`eQ&G9M^3&nd`eAi@8!8I{}(5ZBWqfM=iw8k*-bzyir)WatEVtie< z_psH*c>I0sS8d+(fxD10==pf|$^cUmy@9awgPahZNm>h)@9YtSP~`bifl}qg0C=oE zRKWqNn@}qE0&^#^GCgM(>&_5%qk$O1c*9dTCm$tEl3u=38U^o*3PN)X+~j>$z-i{HJU^=5FEbD`HR@>mY*-l!^#ghmWQiRM-olpx(u3L_1M;BR>B{8iUkm(%H&b9SLdRVqsaRjdI36bkE{CSOrMr)!a5eLn0d}<5AwH&EI z4(+LA=4`GC7KuupVPZZA}Ri4}#*M?NM z;Tin&OYcmUPRY;{_feBQ=y_Uqul?e9xTQmy^$V8p{$<^&)t(2>ec042u&hLdn_E^D za~@i$K5{o}b>T)MRk%~#k1kN_`u1#?Fo1$9ozF$7dPx^8 zrw)A;*S*r8ib{nrQAnb;8qv`J@_WkgbejOGw2I`E@D6|5+vyE&<>s6yc6x|q>@-XVwE=G3|gLJMm_?JW8#34ApNb@q&vq?sZ)cc zWzkTupXBr*y?6IwQ{=Jd`Q;+YO!=*LZCv)GTc>trrxCHI*xB;H*#>8u)T z(moJH6^!Jx2lxR9V3B$lNDUhfe3hb4ByNvZV6ajcz5EHp?x&t z_^Fd8hZ5r>{2*`5&*y#Nk-he57~=24v7&&OvT6rYTbvI)KVGD;4?K6G2CXZiETWHycq2^D zlafAw0W9_mltc(OtO7MFa~*DpxYeoD_D-X=jXq#%F`U)HkG^<|!SvF5^!akGotv>* zNtF`X(nZjtAQ?bb=!%HE85$Y)NZ%p$85mH{>vuV2_i^H0?Pkf#U4)-pCi4=O>ZP}m zPH3Heu^fCh-C(bq=PKr+S^Dgn&4zmc4-aweuKPa12y-2e3WsDjn>t%xu8~>?j2$+k zAX$@{U7a5+=cnZtoo-nvCTLV;ZDDT@G&gsg1J}5>(~E_ZDr7HNl?*g z33AA&n}+ci3@|2J!P76O{a10jlBt?DavVhW7hsSneLj_G#;p*#@tOz@wm97_7@q;r zY3=l0*U@q9 zE9pIL1KXc#;E|+W9Lv<LUUBa>kK?UhRP7^L~u3VZ3D73 z2HPB%#JbdXiXn7S2^F=m2?$_*J(YMGNST{Hy{}>{v%GfF6U#aM+EblFW@|ig&@%AcY zw#zLxpD4W-_TaDj+*U}3KNDD(l-*m;zF6aixy1^xr$KeX$!{=<^xfEMIOc^HGW3Sw zMolp<#!~E5K1RVDDnVhEkgZ9ltHeK|mChM+lXU=;-m^nWy#7-suW+E>hG0g#Kk@tH z2;2KhQOxB++#x)|W&JcVwv&@B>a}avhC=kxZYtuozssy`lOJlcR#{mF?_YcjO4}h& ze|Lcd3#F%-LmIP(eiej!MTR(G#++F%pR@{wkBcD2_leUD64!I6n@&Tdki?%li7!cT ztMc^w6P6jLdy|r`>Ge%$2GvtsSBZwJwI*!rp{JX?%_vzeRrBlfGZ9aa%|C?FsTr1D zZM%_wtsLrZBC-}Ha2FBiSnB0ci2e%T)=zH&(=Wy=?H12}CybtEK|__|Dd8#K57_r7 zCdf3oaf?E_WoL%Foa~)L<1dYf5cbo{A>t)lk+jGV32|8_TnjU+6O{9dL2(YiX&9~t z_^i^%@y&uShBscZluLS$Tl=Mo^>APY%vpEKoExawl2@~5`Z>HJgv`2`0YwBD?XtHN zIY-`V_%RdSey|*M0^!+fK@UOO3I=7I`mLIRvpJx`7;KiF=#lZz+VxqF5{r*Zc0`zb zzX&*eL{H?gDb?pX$l6k?+0Eat(K@M`z}O?2v;GNIhR6Dr=53^LI*nY)D~yH*PGbAD z0C%hci&dW3b*)PxLF#~;m{;VWj(V=-nMxc`VybgLlvU* zZNa%asD5`#c)sr04JIqW#QV6;+^E1M^9+rweSzRc*=d6igBzN<7?n5tQrdv~(H&#V zA+>Wne9GR$fHJeOnniM-+n3delgEpmG)7zbd9Ev}+#DHu?<+Pz(wBd-RLQ9DoLL09 zNk6`R3>8b zfeLQg$SfEc;fs^T%W0WrjN=I@DOo2zZcQ6GWwg*A4!mg5*d znVFdl_q$?=Vc7OiUc$+2X-|1TUL~ddsJ$hpc^8n5KMZS9ptON0$EoPTLPE-p%qCUR z(VWfBr=b8kRBu{7^}}rp$k|~kV(FbVEA@6t{mGbs;=)b#6F4-kS^k6v;W_;hnypkg zRc>5T{@fRk=?j$(8| z7fbsza54`9;wgnmtqsE8=3(flts$1IR;ZvmT`jSf53V&7`^{pzD_$U&Z`2lkfwy&sy5rpAC0X)rwV5 zV3ABwi%wJ#S9Wr7$eae1!^jYhXHC!gEj8bJ_3HKOft>am_fkdywN*i44ByD~d;4V0 z=}Og$lmRAC_M!Yhjw`DK>YQFdA7slDQY#g$yScV7b4xrrKbO8}ZNS6gqM}%OK|2o* zl)Qk`V2g=v^~~w(_M?Ad8A>R_fu5A4!JOIPif`*d=L>?O8|Es-*}e15C-T%5O{&lLwjb3PH2Rev@_;S{!XK zdD~Qvn>S=Ay|Flf(~y26DCDF5g9e!jbs%eP&Fnv1+z%;Much6*4<5 z=A6?QqT(7rG-;&c#j?F;LFL^qRL-tbHE51|83t8Da-Zh`q*Q|j)C%70>>ZOs5An5n zv$dmE`P6Y0np2btm>Jd1e3v28Wt}8Dk)HiJKj{VGY69kkhU?6i181S4Q23<7c0|h; zyw?l=bY~hR$6l2E&U%2L8>tj^R$CtoEE6m&kGl)3B$Mh z;PMs^t)_EA=0Q1x?rBe6KcSod4p)VlSuZv6r?xV8Uu87mCc}YZNs_%{$-w{*A#ySF zd&0+f!^NI@pFaT0zg!C66^!7yUli>V$9)?)|5*tbd&5Omq8f_E!f!BSxWl-yY-!!^ zim)aGxpA7GR*5rkeugND`n7iO?-BXo>>#*fX2lONAF)-I+MLN@vd`B_#4?uM38o3Z?gm>g0Lxb~{6W@Ym;D zr2y=IHt-*IRZ>JTLI)p#)*>6x=_`ry=@AIO&qT`rPP^&PXZS);EO$9>G{9Zck=eMP zo0^`U8IuZXuY2UjW_4TQYyTjKlw+(>~7Na5DKNwPGdqdy;Bs{}WYX0koqmz7jE29Y2# zH!_X4D%^Mg+38_K4p<3my^FI2F!^;v?F|Qv>KctrN=j<8>c0Iz zLV}E#?dj>zH=4$?O|f1~R@`U=0F`^tZ+DaL3z)z-CHlgo_>oMraO5nH=S|#MuXj`| zb{1!w&N8o{vvz~yxpx>m{7Mi`AXFx0uajVY_e=N^78yx;^C^?G1>e(rg7J4+#lt~L zr9qa6Rskr2_|OfpCvrru{*OsKlL4@QSfP;(rg__{)i!{W%CkIqF5kwcLRG)iZ>+Xg zh1y2;O^R9>1t}N8J67nO_*)PKJzF1Bty$asAc{-FsI>~9Xe6(;K^M#fxq-B)q1Et5jRG#P*% zN6RRUR}#hhxS;{iB_-E%e9jaiVY^Id1&Nx(TJ%IjnL0w@0Y@pkxpj0B8&xL|v5>K% zNhV*YwX1>~>8>-fgjG&GlBPJ8aLZom{Cb;D?4;1Km7)I4vq9Kz zWd|x#PKBl$ufJS2Q|ai33cw&wPtTY@UpKN>SAkF-h4*jq9;52Nl#IUSV|5Ap%#jC~ zBP3p|bX$cSz)l6U&cLP4F>rPCqs7q^ zw&8&e5YecDdKf7=G2G`)U2wF|>>usRxisEuWZ0*U<}0mur80zsPg}5D#YH<1&N)tJ z*<`s&Xn;4^ad-Vf0Y!&z*dhD%t7!kb0qh^S>fl*%R{J>HSjUA*s%Xab@|T48IR*JG zg@(ZaRlM@2J`H%%l#bj~oq?_rKX+0Gg|;-6&?jUWeq*D33B}G+)wqZ5d;#jD zkC4!t>=b4%Xi$4?Ca+Jj%u&aO4G7uYL;l0msUYVEw=2wk3PD zDc_sE<|hCJ^EP)K>m+UCmB9yXJzh*g5fFy_NrJKO9tdg< zdO;XKJKX`io!SmV<|`t1mZgjmKPX=q0HSRvU@^I5{F8^4C z+GFU!T(v}FJ%O?8b)Y04CTM>*sU|3BO!&p7Usme`S_R5;H+{cu5=hd+QWp+ z&nU#MZX5Rxe6AZUg>x<8!PX5vGTYN^k4oKYP`MK??Z1foIc@_-mW7Tnn*WRXjEo_W z)en!YwG-H{GNan@m%K|o_0OhFSC?9PzT?(`VAv5rPrSO^TuqaJw+Fvf;L^T*bK(|3 zh4ztHh+r~{mwhp>`m~5fWbCvB@vECRhcBaZmxQ7cbu#a1sUo6+2h&5>nvY%r<1|Je z+ps+VJpkxbVa6_&4EMzjUUUq?72K=cMd0Ga8202dtCfARs(QO^*TRx`32M~B9j`JY_=^PC(*jV7C`VXXHEsltr&pXF*ch4|;7 zWW(jFsAR7UVGTL^YanV8#U5&pJW}@|K$P^g1IGrWHs%!KPIV!0Tnu(RT#<%9FG7J~ zAoR*A!Rd>jlfBP*=@=N3+gaLsAkF?#nFJNwc+(E*=7__g;^;u}$pu$Y+G*%)*Pd&iI?xv$Xf^*PYHnV&swy+V2<4(M^Lp9_F&!EZ}3 z&KFfspsbi{Xs{?iByzPctPdjkS~J~w<8q=y_{hKbt#rU|p8rRFtCP(ECKLv1tIzqu z6(?|IR4MDpCCJ*Co_70$3Rw$&5KD#q1Asby_2j}7*U^Hr8}XAG1bJUcfTXM zZ^OMO0uK=#sYd!%wY z0+oIa490?WJA#4ux^EzG=W^|?s^lMSAmXe2^L7{3q3J@Q*ty*M;$U&9BpZR}DgnExKQ4U+E#n)w#!rg(V8AA_fSS%LGp?govc0qv zp{fej}k*#>g-Y&##u=h#mA9X+fG9Lz@pI(1``(c9z=y zfk3j#?5vcHgSQ-I@H+8|EUUcU&4lNZQ60!`i5_Z;lVMv*a4njHD*Msm9l;b~KNoI#s$RJTS7G!=jIe+$43qR{GU|Cuo^E=A9VZZ))9ZwGl2}7@kl|lsqw8+ zM*qzukN}ETB?vzTz(eLbCFb`4s(R=&l`Yzspy?>Gw?)RlVFCq(32#W<_u6;Q zp@*l=8Ta9^;wYbY|0c2#IyCv^xPwqjiMsYmiSE7-4M;;0L z9d7aYKMpt9s}a3C@K7Rl$_@^i)<78y8kPy5rHDZRt%?I$_1b>- z7}v`zZaI4Z;734>)%maN_ka7UAPrdPV+-Sua!dV(cGDu5vkKY7TrWCNfY|^uUO4gE zYV8GAU1w3l>&af}A5FX_*CT(`S0xZfPU$Nl=l417P==^XK9CjHjK?uJXka)TZ z2DU6B+#*CtNrwIA({lF3ONb9&>2HvG_D?4D#JOOel2b=pHhOjo?Z+h0xs=&U4I;Pq z5|6+Vs3X1pOFFM&^2wIgBibdRUGI+8hT`i5&e)&Oc@b^%_GqL0 z6>E^Qz7z6HfSSMq`&2J1^ykKRlYM~f>_uk%x3&BxH|h`I zX5gV*oXca%x2 zK8ls1IC#sehsZFgvnf@H<)3%hsJ^j^WVJ{_%;?R~DEC2q^J)x4xfsXz$@_h`YiOJD zLY05SksGwUWGA-Dn^p{p0X$Eb?XV?5RP|dF$X-z(M>_80)e4*3NLFS`&ukj42_}bm za>7#M0&oE42$9^GtM>aHdW~G(v5)^pCOM*he2C!BBNHsr|5n52<2p6wb6Mq4sN|-f z3XG^c`F;x9*cU+m*}WY>nN^j=!9!K2a(X95#m0B)AUoY}geaBTNvR1uP~ZrA#I1{N z2j~uBNz$S50}mDN|FYt6rO{c4QSE$9S!$8Fo_M#!5_BKszIL_jqkfJYd*x{5s>m7V zuXC^gz#Gk5&YqqpgKwKe*Gik*NcFB~(QOehr-_D9kgV_Xq^#gD+Johm-jAbv-jwC@ z#`cIf(jg+*W@L~*Fr>fEU?SBG+ZFu|D23E7@^m$kom_{~^eV^<4nw!UKLEklB8eeb z>KrjZk;*;hKkwQ1T#icP2lpbsW@?)V(53}h(Z^&O`=k6TCG~5&O-~ZtA>Tka*f&z5Wg6D?AHRg%9~OmljGzh zu370@r_?X?Pb?&@>H+s0Q3$}XI2LYl@ry+Lr)%*g2VzEc33a4Cvbc-Zg6RjMSOXNj zKTEF_Z;RC^0tUZ233~TCXPyc7>1CO#!MF5|jy$9Tds6Zb z2TT*$xti{CjZKa|AQB>nwVw?38|Lc+Ui3Gb7~d^WlcTbWLGb1W6$_@vyBU*4ZS|ES z6OkfzRjYi#_;kuo0Exf=Zx)7obo+W3sBH==0qGio&_f_xm>>+%Mg6`a4uk5u-$9Ky z0(xRuseFl|p0GJdGJjv^$YgMlmA-iOU6>Z3mHql(2L&P49xkA?KZ+X?VZ(3^B-~qf zj#fiM?DGCqGpI$oJGQ`#5@!@kuFBuQ3~{c11%^mroAwFn|30UL^AADAQ6o6}wE%}Q z)eg2U@$3gXckm!cMjp`BLo-21`WZy-h{)V$5_@Z~-2XnHh{q|zrW#K96QY$#SjtA< z8$rYt|BmP86N=ZCA@0ekq; z-gMCE!h|3;o!~wGhi2a}e`1|D2=yEzfHInB+q)FEP`fY9L9vWdu`^U`Pl~yf{SnpN zGc$7+fOQ&?-M7i0vhkkS)4yJK6JCe+HBbQr@(&JxmSy`*M{gs`9p^)&I-}w$K+tNL z@Dqe2F+`pv9Dcwt;Qv2MD&TtvMJC|5r>T6lxvn>a_Sc&GPyQBMnkEX|!~Asm_1_YojqW3T zcncu}>C9cSai$wCKHEL(>38`1$58M7mV92+?@EXH_K&JR^w)7{qun!h5owkv>qqFN zzl9eYX7}uUiRAK)-hXE_4%5B2J^}gPd@(O1toT>j_3-K6e~SU|uMGHJb?WJH)ICncpiEDGa@Oh%L^i$t5Ht9&Vp7gsIoh1H%Rm zecg#W?l1RdK8KDH=8%-_}&Q|=Ew&&XDC~rWHE+<>8Jk#>WD%={DdR-?Z8BK%l}WGw?kCD z?4dbVLf6ax-j@G(!~qB}Q#)*U4zuUiKF=ZjR#{kvr#+9P{4XKjr>oBX`2QfG+$Ctg zMU3;)&8x_VxAGq42i?|du-D)o5Z<}*JC|}mvyQ+4Ga{a|AU`;K+MUP1w(!?`(;TLi ztnjyPX`Un@`|E&UlS6Udg)b%-4-*xG$aDV#Lu@)LBEA0-;Qd~x!&?Diw1d4KkFs0% zcOVY7(F6iizJ!->4)3T_`ELWsL1&YJc9^*{aAYjq$v^(}Ma$n`EKIgEg(0$sKXSmy z18PeU(UX6Gc#nbu>c6uXhuOHN5+KL3uhuMPC&I)2CmFjzd4LsIf=H1Lo%5p!wfYT8 zdOq7wX&+GiFWq$Luin48@N$@+`+wlUG34IguzfYHxAHG3_#_aOl2QZ43+ln}HLmSB*y3qJg1$I&Rw{FobloLn#+&NoYc9oCAqnI&Ps3-YlkH;))i{k1)Gfw zDOlPoZF2Q2TUyG_&J2 z3=$HD!1i$D%C(&@e^O)|B}3G(8Lu?PL`lFIn;)KIf1HNoc74)IB_$fE;(r> zBFD!FH<0|XG~iCus(7-+!#fgfzn}BQBCy2zU(DWPymJ(2zJD3Sx(nF(U+Uf8)5R?*Okk!sQ(T{#c)u+VzURm*;c_ zIKX_>MD)^slc(sxd4pNl{g_LBwwR&)B^R6VHIXW^W5|bo?%(V0+uiOnn=RR#$`r?u zzCw*HA%vxXTSn<|X77mnqEJEz*e|^?75MD;6SZ1#Oi>O$kPO?Y#BrpfR*t-W@ER@lwRQa2W(U+Z~RAoL1);t5* zpzsjICj3)OqXH1}o|Z=Q`JB^l@{Y@#&iHG+WDoiJxpo)1V8PjX?aXR5=g3}>fv98z ze35RVw8Hvx&9EPMQyc2nj{lbZc&8tq{(dI>MIsN@DD3hB_2bW9dS!20g(^W(6!SRd z^+!%02ui5M3uV{8cl8+hSqzYj2UY#lI(P;DQVFoS`xEE=MP6fbOXRjyrqbV&pvScq zJb}u6?5`iP(Ep|+q*m2tc!Xe|l0wi{cm7sXAo&7F|IHKW2CeVUP;m|@5q}l+_K^17 zQwT`J|1IguJ2b`BgunH{LK>bG)?dN|oPA}AP)^jY@iC%v|5i@3k#PlVFKuytlj19I zmk#Z(lYCVTHLT?B`pB{RYMlQjsQRPt%la?qw`U8}QnQU~p6$S{qb z4U4kFfuSROGaPGg9xZ=Z>|b zmCMKfR-mare608wpGVEmdzRnvjEZQix|ee#TRdI=o04zi=lq2}!oKctMU{5N5A#T_ zP~!ZzL97(BIj#-LMeVGw*;$@K7n;)#{#Gt?mnG6w3%hOSigzZ9ZN%qJp`P^kZ^DjG zoz%!jg_BtRx^8>+z63qeYr((eJn9yF;?0TGl=!5B<2YRA%;DIbDwpP{(zCe6F)=}y zCN-*R?nB^MHx8Fe4YpL`iAiaPSw7EStMY0M>l#fcSGAK#?OS%f7QgkAW*O%n10(be zVd|H6Y+{E=4_4Nsi?RMUU_ieY1%;q_tNo7aZyYfSp5u|dx`oi9ubi9xslujSEU%$9 zd)gH3@@#ui8mDzG4>7Hk;m=rANHRWj8dJQ7wHzjLqRQIaQP|0h=!ZTo(s#>*?+Qqk7HC=b8246D&SmA zC6$Zer8^%cSJ_Y^)#@^*-I=${anfvZ!C8V-9zk~XvdGCb^692-7mLy& zu6_n>&e^1buTz&3@c9DHd<`=jFSFasjZC0^BQ6Q$i;|-%c803c@&r}qc{swia18-~ zB0qh0Qw15-ZbS0su%_Xv`8{EYI0}p-?ACqWD9BtQq+ui8@tR@?1?n$ZKr%$NKwZAO zkc^%4reMh}NxnFOiffx2}b=SE-mHCT5HUP<-#MMsTXQxD#eVO4@eWW%+D6|ZO68TVK*lmVB zfj(h!N2X>|O)*nBI4)}y1KoBYShCJ?s!7s*Yti@ei-`y4l{_ntQ(Z@0F2!)i{I1{Z z^)c(kHr9k%>Pub;dgWlPyqE2p@s%qMALVp`8~nexajPzt?qSp42KX107UJc`QaCSF z!!5xtK~GWam$h9$+4ZErj=xebP4~G$LDfO)ZP~};Sacu0 z(^jhsQ-5-aQVm!8I(B3Ff(py)SYH}QV}Jvi-Lx=ROW7nY@D|U=fzu7e(UyN z0b|Ou>L~UO65v@_|3jq{Iqe49BO0=~hAK3@Ogfzu; zcp;?>XM%;UpwZK8RL#ag?Dp!{`&=vI={cirt7JP9<)qd-k7(%hI~N~ajdwH487P=x zEKc^)%yG%L<3@34ok#Is_=?K2y_@jGokS{Q!#k=jV778~tND@S>}pwyU!DruE#hz9 z_(y0r1a7~BFddO4uPG&yaE~ubYVcn?zD$!=c$waLIO|0`fq}4yOdE}u^qs+K-)U4A z)@iM_31k;m7n{V}>8s*2@uQ+*s7NZi_i=oEozP^SoH#-g1bTBrzkuoN7svH#wQF}m zhpub=GUvy|T$@q@a3*-xX;udVuO{Rgc6H+Ux40IaAz+p$t+uP0@mDjHzOKlOl}$gM zJ=s7O`850E1x!C024;DJxqSu->{6cVor!S2o|2yvIc;%;$66~o8 z4T^u9rwNZ@{WiZfdDg{d=f{`N3uTxH?QeJJDH9A(~oHDPxBt6_Hkm*cu?9=x)dBegQq ztl4JoecXwd@2S{-l@)5s#;g*5=R3Ro$k%UqNK0q|hu>G?@(#0M=k3w=9(~spvn9gw zpGxuj+>ug&8zzL>CU&+yt5|O;>A2*lu*{sC*_dI`Z@F>)aeeW6Sh@;F4-0cz&1dD4 zwTvHkJ2z=eiC8s%TuK@)x-JW|R%8loEM!BU8nn#4{@Ti9mM%#;W!HBN>zCkWEjf3~ ztoGPi$h(-NDl*9qQofXVGo#Y-1Ft+uX{PW#LVc!8ox8RR2M6cbGphE!oBYI#GZ$J@ z8Qyzp?biZm=PKt3ueU?BRC^A|jX5VG7Q@2Xw&<+%Z-)G*zO_?KomY}@T<>|)BHLas zF(^hFzd`atKHH#=dG)kER`}3^t^^bE)+7s>*3lBqJnioL^2#wJc8@=9EXl*LWBFE%}0SHy!`ceCfDgP+(0skG~;%VFLGV5shH|rSt*wd72obenC9|mc+(l=9&WmR)|WKBVAYd=-OhN71JmKMQ@HgP z)GN|Gn}M&<-(2?dM4#=(%Q@FLF+f8v=khMH@GhxvW>nFr@8>|fZtUlgW`@N+!~t0s zbF5z8G4u}XnI8=^G>~pOPgm*A#iZAkl|jGb_2kaN+t(AZOx5JETK?@)+3!{IEih|~ z?G)4pi#J2`j0%}s;vQPBYFNr=>e-O65@mD9^h=dgepxlgixgo}9qqT9q(78~IZ0QF}#2KH-R(+Hj_52i2tnuI*0gyvEu` zMR!K&BJCeg?CLK>sWoSc`|1vl$IR;AKXz79g)eJz6@SqZSKTW$iq2)aMK6vImy5VS zQ_d~BtKH^9XMv?Z!PBxEB_ zbBQd!Pz!sCMi5r+-zv+AI|=7WM}`(S=1`z#mb6`#S9KT6cD`${&W~J-r@|6x4KDfK zF&yekI1vhg;x|4_Y*A}R3}A%e-<80R)Lb%tOS&HB-)Me0qBFozna6(kd0^gnxWQJz z!-?Z^oE>Y#Pix&4sT4FiKMM0Rjjr6$t(Fh<8VH?1@bG069eJq%KQ&rltheV=W5vzN z&q-f*h*L~fGO4RC4zbl{`n;c>%{n#V=erryt@kY1qa*IA^kcyfIAdCJKIbM?vy)IV zD4vV_oRN=PC-T37bZ;!{I`4M=t*rMC&b4S&;)Gu0S@`*kRww#RcArrw=X3N4hI96d z=eg)=1AMtmeQQchYhTJMtq-q-fav}3Gw7U%>|(K31C1{?8`{0rLVkAsExHv+ip1%o z0T(yf1Blzik~GjR8-+g1MI9C?l~CXmk?yX#HIY%2E+`lE^J4FCco`(|8!fg>_?2sjv*r*)JR6GfR(MIX0meZt{I)|_{`5{)i*2M$ zJga!qDn;3O|0udGaX-CO#ayA92=5FBz2;E92+C*Hd9dH6YH=O8)VVs0@#_ODmOqt~ zH}9LjVbv&AaNBftMN{m^npZ03V_e`?+jn$W~uY=b)8lV0rR`ti_0fl%aL8&4@EC2%iOQ z0jK542d<$Hm*k2nZf$~{wobq@boA?dljvc=KCl%uUPmPskq}g{bZ^Y#|FHMw;ZV12 z`1n&PRFW1XjHo0#WnW8V9kPXx?8{g~n4zdBYu4-}`@W5=lk9sj_GN67?2KkG4BvZt zo_BfP@B8*UzW@LJ>^M4#>vP}NbzbLnp4UB{bHI58`JMuw1_yx4kmc6Tw26c-p^425 zliRRzrx@w;#S=2>2_m^R`z06AlLy!8`C)Hppe6=;WqHQg$aih7J(n-*dpmSqSQ3HI zRf5N9ym|M6i|a;y1PADXK0;^xnD@dCoA67qHg%)%_}dhyTa_6G=h4`^9NGpF3z^0d zw1O66c;92hdnq2qieCZ;8OCK^&xQMNYk%&-9S1E|vEka@T$%dXmf0RVL3PZmp`-d& zRFOpM&Z;EPb^W8!SW;3Gj~|z&v9}G5L;qLKM=lLV?$$-*d!Lw?gTTH@GXb5$HU9?y zx=0K1pyl6FxU#yFL>!r4X58G0`>vX{uK}m(xok9a=XI$)0Ld6@80V~QG$kRuP@Gc!J8EjD| z!uO$f9Nyf_374|6sKl3LrkMCFSH6?|c{bz(&83ef&z8Mt=~MSz6KkA_7ThU88ws=? zyA#?P{x$RKfV3(5vhi7-Qm^Oem2&&`z;p8Z?hrrF*yxR@?s0ape_F?nGi?40yH};3 zzwPAYt4hXNbEJOy;)!XJ*yrM;fuS%fbtA#t7qT(Df1MEi8C?LX};^{ zx4maAi{w5o>?nh=CmGv3E-_I=blsNUmTa?(&QpV|#&L?%>uOeARNlj{=PT&Ys8lhw z9Y-}bQC=2wE$Or#-~Qa7(s>KB4{(qI9a=r3F+(Gr7ee3uvrm4vYE#|Hl&YN0LNav@ zdp##u%u(|4%kneCZZF|NF~7BY3ly=5VTC`ILi)C5fRz<(6xI#q8qf!k^byyHzv{bA#H}l8KZgqfuxnQLpWuE-4 z>U>+E-($1!wg~viZGT)QBrg2)muE{!K5ISJcVVrtxq*j=PYe8gmq`OED*@KxPz@Gm zm{zkn`?T%TGBrNjng0vhYwl8k?am_Gtou#0vO2z29cFgq%pw1x=K)IizWD6tB!i&sr1ko%6F(*`y+EUZSQT4rC${LDcv_}O8_6TSX$Kc%9gC}M z6@@p*2uN40w~WPU#SVAZD*^?+=ml=da(GqQnO$>!878iEmlpcQuZo%sGxk{Ga3MSj z9|jY6h{K)Z_DQaF7a1$Z^YU4DYH7wvsglaM&da{gMnRWeV9My_M@&4&-CHZN`w|>m zjw|0Cdu-qc9(f~4IwY*$LS`78Lr+S*8#SIEULSfQ(G(_s?~%0;8*k&gB;t90Dd=&Z0S!WUt)XV0jHa z2k?!8cb(dy^lT0X$L@`z@<3eS20Fy%l910)@8*T<9LM>)wTs32 zX@2tlL7-X6PjR~0-h`)Fx+XteOG&%~ar|D3)b^)m-}3su3r+L={P|b`qAcFz)4hCp zz49ADej>sYJf@@%m3}VIw2DAt_1dqV3tbJQfi6sn^Pd|kqephEQA%RME!Ugyh^oedOAH|H%pWXKWbs=!xQ>+RsdG zc3bvkJF@*EYNsv2v@96^uUpKfO;uq(%m>aHd5@{~?)CD_d!Y0$9qD;+i2QZVs#vs^ z0}amk6K&5!@y(rZ|94BVK8|ND((c2fa$`wDHTYURS*vqsqe{ojgxgM5KaGms2rcPu zXS_$r61{^X@mW6jWy|h3(@XJTw;j-5y@|`8o&--@apa^5xA@jO?Ed&1-IfssG4Ij7 zJe8QGuJIOv<;el1*SN-0FjoEHXvf%)R!MXw=gU4b5li}z8zNZ40UVu>kXU;bP3qgp zF!r2v8lK`b*J#=X$J#@Y!B4hxn!X(&m*hp}Kfxg8Ej9XgS9dZumumFyAfmjlXio%6 z`^{Bs+7|fviXA6syv$YJDDQr%9Vvzvc|`B3TfshEB7;V%!+fr7 zf_a2{Yp&))s?Lw}oa?JIQjO0V(HAHol&gHSes#` z{Uvd>iP)MSZO0bgt3&RlxYeQ#+0kLYnG8){mh~-oKI~dB24BI+>!lFwH~o`qhV=kGxjYf&x|*WGIc?#`b72sBAWG)$+!c9^9NHn7N_yusR&t%#U8g% zJTenh_`GOqHZ7fU7x#IlOdXP8oywXn!ffO_&RXxoSWWC4i#xX3W=l@>`vNB=vbLeY zqoUUfzi^}t5B`~*=o_e16OYQ5FUboF96A3t`3m^M%VP$+%V5I{-wy(K(8&5)*Szp? zGB26-*(x_|oTB#HYaJVT#OKDDj0v@!=8I_5&YGLKrin9EqQnp|U@SykKpRy!I959P z$oR(2ra=8Fjiqt>O?I>MZ&b1>hs=|+FdX5RF5M^-+kL}<6ccfvz~5M|fhLOgydSQG z)OWoXZIexO528cY`+p2b#^`0eV3nEGG{026d&yGqh-U(ObnWT|x5M5*2EDn5h9Exp zdOJ{Vu(ACSw^7T3#c_;IYUPNLpMq*46G_9{u%)r6VxHVq-8PLR5g8c1uOn)e-0P=x zg`A>hpWc#^yAb~7dG?H2Nx=i#w{llr-1*OdOh1>Ue6V{iP@7Hj3J8SixSVxqQTbne zJ~1dmiQ+^ZtR#p#r>os9bvk3=eb8BvhO1uckz}O0uiD4&%^KOv(H$G|p2cl~5gPw0 zCigM-2l)FQu_wXi!-|@Igiz}{Bxi>X4`RV$tCY-6_Y->`swKjc>RRS61X15o`Oy$G zy>I6VGrL0I=qU+K)#EQ+>LM2QW4Z3zOBzzilK@dB^285tN|(EIW%LANqAIS)GYhcz z!FSE=et<3ew(sFo60*;BrZq8u1LO#k5JD?HWDS>?n)r^XnxB%}0~e}d5G9bb-wQ~j zlZzfvp{Zv#a?Af5-h7Pdy>-<3;DxaB5r+Sa%}o*_V*iC47kT>YE8p{g^`CKhGuL(; z#AV|RcaGCkZO3`eEoy~4Z~Rg#?%Q<;@wW1*B_Vb1gzT=Nt<=7CC6i|gw{1o~KTLVh z+E>5pU=!a;XT*$wQQ$4}V_y+xMj{IV@nQeCcAa`$NfTc~ZNelHq3GjCoX+I+|z< zc^DV3oi&Wns-atoGjUhG?KdzM24LmxA8n0j51*DkKG9g0Tnap|DNJwD+e4VRumQy& zLGFH|$vZ&w964;mM*g%(Eo`eSGvtiAok}sPEGH{#08r{bdXCU`3xUFrDlaCeoZu#Q_ zYekv5)H?Zk%6TS0cFva)V}6Ph;;kw`t!=bg)qRs%aBmLhWU}hP8{XuUM!P1d7If3SK1%TsB*H z9nS37yu^L4h78msiuzgB%pA!G>xx_Qu=J%<~OE9N6tZ|$_?%PmRhuoboZ}D zQ2o2&><`LmIX&?-6eM$bmBvXft&EJp|9Rio$b4hac^7ApgH*?Q5=6KDgh!Rz`pr0D zJJt-UrR*dx6^)3fMHmV030X#0MiIdn78KS z!e86OU~s18)PUd~kedG_5-X1VnSDfJGz6s|M-P6!w0qs=^nU~eTsED>^?-R=3Y9lN zEK))3O25VQk80la11q+xafdw0G=&y)b28?B8G1s4JIuYP8WUoO09hB^CVP0}feb(~ zfHc!v-ECUCIezR6>*Ma=f}ep@k>VyooaORaq-v1e(5(&yJ_0XizCS{env z>Qkip<=NpPu{N*+@cd#%a?G-+sOzJ#6M?}kBV&&>S3J;Hb50$QMH}Zd{PVRP<;TIf zVUMQVonubD1&geFKIw}hq!SdGrP(itj?1*>h3mZ<+ng&xSC6^d1rj+Sst$YiHoArW z1U#}y{$U_LKOn>?OL|cx5!c2({F-l%Ts5^=EX$z`p<+L$@bX{M(O-f?wtVKVnDBl) zK~Ky{!gDRjhxVYy$yfW6Ldof)WIdG7jS_>rIb`G7ol{F?d{3EAN1jDPrI&R;#4f%p zkln z{ve6vK%y#(VJ*hF+gWs*?AIk9@wAGBuI8w570neKhKb$rO}*K*Q2zrn>MS?l%Dd^l zF5gk(jURWH>q>$sZsVV8=^eA4PfQd1&vZ`Qd$;*2?+)L;gl&JppcA#_Y&jU$zMj@; zco)Lxra|gBvJTKQ*>?RE$~lt&#OA^<4){vjb7;$-X&+}6!h5Jx;;&DwPu*cTFQ^o* zOeC4$`p=i{lLayPPgA@|i(j9DgLMY*?J@j0T`T9oJn5FJMi!DVSL?g7a;onPHnWL$ zbd0KYef^;|4C>J7aIUQGl@w&cc60?G>D6J3)Lu}C2(lyf5l8upc1mUM>P1u`1wN*a zadiYYLx!Vc37!j5%kZ_G9&1IPjBpkfyFO(2H!vzp_t@|JJ`vn2Nc6zXO5@U22ioEoK#xD|&$2Cj*es<9iBiv+`PYnGxYENATy^V|b>LQ&dO6DVz1k%^yc}ns@Nlz>kZ~@a z#(XO-F?9D47)iBeURW9|&Yl|kne{Dp$8(ieR``3id0bdJOmS@N8&JJjbVux7n>YuaKU%3 zXB@zmklp9p(3|EV4ISlHUHUWbHvk_4<_ks*-iH-;YG>kmVxdM6F5*(Y1nE$XOkq_} zRTZuV{r9S>OWaF~lBIB`q(-(VfKGbsgha4=GOR@M6bJgaTOya+wfoghi3r`1r!$G$ zjt>C0-F)6>i`wzKqQCD?e5{=Om#Z>~6nKD6)XBvEk3gz#EwdBHwfO~zbFF!p=e~fc zaMCK1DOt;);%5Kcexv!=3D&b6MLiWbz;A6bkZ~Jg`pPlaey^UHe`o=oq*D35A~K{b z!3X?;A1{5k``W-4#OghtuD2aOlQv9bQaGlRNnX}%s#{ai)?TUj z6X7IxojPPANKDdsLyp_%%W=?=hK6#762{zZ79_c!%Va>9%&L zuQF>U--*$PIV9qA_F4sifV@VPJYTcs4YFK3i)hDF#C#v6v9vAxNz!sUWfcMpV}*HN zaWeclbTX*;hV_Jh_6!%CE>`6DZwvNVRpo5v6xag`#GYUkuu+|YGS?RQ6l*^(A6b9} zOd8Ok@1?DdW(RUweLo*vAmP{ig9BZ-J(*`ggVi6d|G;WY2uc9u({7@|W$?DycJK(3 z-glSd?xoUTSe3y~u2QK7c0M`$X1??;{9p zCys4m36zf7fRp&ZbZF`AWJ{^$Vevf()VW8izMhvOkRDGvx>Q4UBf-ZGx9F@Z;MZD7s0 zJ>$jqaDpS7*{n|3sF9`q!t!F4wiGavXjDU1E~E9bQ{3|+v69TPmdMw;!Rzgnq&52{ z0*uJ33^=8HzcU2#2kLA`!>6WH_f+5^_=v^1TRqaI;hH!NjqK`zPbsg`lzmWLZijv$<_5E5@Y#TrqH zbjMw#z)Sm$6xQJPHv>MDz#qY}EqXgIckO+8Jt*woqjpoG@Pn2*IibbMLA)S&bLIp; zmLd=AU@wISYkR9MGfdgIqtu2S%bQ<@_*WI4$6a||fZ(-v>$)-3J1Jp=@!6UbH5g0= zvowIRn(XH515zvKaAq-T$M}U!-;bFs$RO-Fa#Z(tj+Xfr_c-mQsV>C8oh{so;Sslh z!VZsqo4NF=Dn;K@);mrDHk+%mW95c&3soB^+M7Orjkh_k?83kTc+{L(n?i)=9$iJM z!exFWsE+=)Wtk#i1XxS>Vb#3K+#`Hla+Vx2C*JFwXG)eEA{9FGf{|A2n z_3=3TV$&@u3$hq)@r+fL8AfCz`I@|OC$`LBK-xt(^|Qsw*0!uys^GNKIaf9921#b0 zl@_JY0~NzE)&e(ZdR5Ekk>Ux!1&!BTyMkoP(N9U^(@xoQQI*Yt;@7@UPC*Da;<@Be zZR?(>1H>Q$2Ep1n9%|~)?(>}zb&C|%p@YW>zL12N?X~30iLB=AJo|q9d_f7Js|q7{ zsmJMDF^s}}Q$0(4Teaz_nt~t8q5XH0s5oA2L$ih9bz)iqB+L|uD!js8jfQ&{k$hM4 z6_Jv@6tF0pxfTzmWmCez8AQPIeA=$7wh z8E1rvGC;Vi=Ua^kDfc_Lwr~ldQg+&^C-EYe-=9b7S`O-<(LN7sMpT?4s^g1>V?3)0 zOIhh0gaevY?PHCg*C3T9?yKK)VS85gABj=19y-pLja}mX40O}RJFSVb-YR7(%pU3KxNPqUU16Kt~d2f@x)>`~RCdBMZ&yd}_K2_~~aCfh7M zj>NMxDq||hVw3*+Kv%VYa%_n-&@9owsB--1n)l{_FZ`bP9KBSi&P|o-=NdnbWE7m} zZ5Nd{|2wq$gYxHg#?gkiW=s@9;h@(!ebOOz>63bi(NPyLMb4B`I4yD5za_mXocf35 z{Fca<_f3IUfo|Y?ogVL&4nfrv(Qg>yydP2?!}Sq19M#Kks2F-VR}x~vC~o>^oWL#d z8Lij%%$I=N8mu+ZFRERY;Pxpy{i${!^Y&lBJhtIzvCAMcBh(^Lv zgHuf|_=wZms#+vGEsc*(JD6DuReAY%9OrDxxm+u`>xLvtCF~|XYMBt2$8Q7Wmf_o$ z=svPcA%QlGA8-oWGRFB9yt_A4X~leNs&LE(I9#NhDRb(?IGAr&)dSE}2CB z4oxKp^98o`HDqfQ3N+|+g|P~-2i-sWmoooP|0ZC3Ulh2?`N`%Hj<)>MvF9yUjz+=! zC(i|SeMno24y7^&%IV?rN?X)AOnt$j_n^FQFRVZxXvXa)0dhf6_MX55iNx@3|7l65 zXRXKH*o1e>?lhA}c+eelD099-Nk>~1&{9y~JL%AU@vdQ|2UL)zEbn2j8`?RvOhWCQ zMQWDys|@2Ik75_I!$fuS9^l2g!kML0x8;h=_wa`c3R!Fsp*?A-zVUb5|hVgvLC0g5uXMH?lq` zzsPgXY@p3~%sT#v*}Ndf7Oq;gs@Dz-%@7FZy^M9vZ>`HBU)A(dMy*IRErXsa|n6Z}yP0aO) zPujgXI^*7?NHbUwKahuzD|KyB;aD%O@qNv&54h4Wa7v=!Kfe}Qi<&3QmOpj|q+H(a z%7_p-+XayC^8g9GmmR-eqR;q;OyA94;wPrelXI$-D?g5K_y|v|9<8~j}Pd2=uk0tCQ8OHmc$Anx*SYd_jmImX#4_yUH1#^v;5xMAl zXU_{Ny!^u;_z}g4_zwna$^q-x`GAlJKle#)yR|RXOVPqmEg%`!DSKTG|H`(^aB51Z zv%)L*d$p~9V7Qo0sH`VkEh#qY+Rl`wz+#2?GN$6@9D{b5C;H4?)b5Rs)4<`ZDSn=Ys)72H6h zlDhXvDeLU;tDkpVCjuWea_Z8WHs9Pc8lO?%6})9G*6Ok#W^ISBB&^kM$5c?)_s?3kGR<-uYl7y%ku9w zQ$Vq_=cP?$LsJ2w1+VMGtWi-->0Th~m@mj{_g{VZH}~kYGq4)#=`196KdZo`HsgQk z!Q={`hAsXs^Q-tlp5lh9oG{?O02`hbnV+0GdYnA74|cK*8sCOn7D`oXi5S8K}#v-bGSt|0R`G3WcX)GRVF$y*Tgr%_t zS9pKEk^e#%r~Z}kKYslqB+`wcE_zWQ>3hjeHh-(%69fG$O=!7#ye2k{mu0r?N9zP6~bK|Wq1GlWo>^)Wc}@zjb*n{ zNuXH%+o@qDANa4mJe*x;fPs+$|M27B??|3f6Xd5$z*BjFjAAK-M$e)DZtg$+Uw+x& zARF+@T0Y$Zd-P%`7{J3-x{4-qcGbU}mj5e|)!S8@m|$`sYvSnW{1$%~%AjI>OCNE6 z?@@YV1IZ#XxV&!UKlZnelQ~UxoiF!_^y>c#XFU_w2j<_xc&(|z&fPJvHyW#$vp!K> zo>cx~-SRc~SUmT>M&F_y`rFqMBcFB4q54+iW53S&iMKC*Pom8@X~(z`z)N(U)Ju{c zD>+GO@1oG;fc&qYT^$j~M9J~zL46}YZ28?$z3=CjhsJ<@%dl**H|{q-@#32LoH2QW z1syuWwbiZucSs9YC#Aa)4%XU>iQXZB)$jS!k0L88{>1YCJ>2R>hnM_j|GHc9zx#pz z|GV{XhxNw)``!9yBKe2j!Cn~KhC|7)q~h1V^78Em3gT(Mt3w~^jAFJbsg|&hys^u*zqvlx z@qt!1*laf)Wkiu$(;t}ypG#gm>Zl`>*s#49^Q2m9K7I1Hw{C&GL5FkHq#ZWPOvDg5 zqv(v{Q~D=tXQ~c-Exc1_rNB`=09;nr0}6HJsKh8tM!u{p;3yoYXVud~gdh^SodmprO zl&F@JK|g=$&wl=YR`_2$id=Y{mD(QPeGlozieJqITTV7dkg7nk>&Dz?%05h0ixH({v&c*{5=AA)e8+vE%wa*wk1%B2!hHj}* zj3b95C%d%1IeS{-l*qRddClv;AU({n0Uyk69t7v|GWrYV{37 ztZ_De%c_;W#{+oDy=Mv+2KQS$a~8|9^4~;p=4tmy=q7{y@K*~&c1U^df3J0V(ATgT zGDhraD;;>r`D%vxQ!H%}KWZ=1DcJ;=_U_~D4`z28Jjh+iD#;9b)o3FdzH`^0g_|3k zjNLOnuZ~RreD`Ra#};$EBY#0&`!5ztr=w92rj zZj6jD+f+NLnubYE*rQDMMr=P8k{(r?Wjdt*E4jkQI^TmyzKbtY;S^Cw_#9Lu)!dfb z^PhW)K6`n5LLR4!FSkH%eO9^0#qgCHu=g=?mv*n(B#4~hLHT8kp^UkqdvkUpz@J}X z#qICyJWhtgDM*j=e*VkcBMNON1j-FRcTQ7&=!}ljQsmBp?!%EEVAJ4f6tUjDI^H&w{POVKBvGs^(J%8nI!Z;t3_|S`?5<#>!5{=?;-xz*6$pmy(kF=a;(j&o7nx zLJ)T^;#Lpyr|Al<6pyySG<_E9m)W3|+EC~&$Mk>`S5SM>wTu)>y@Pw&te#6pGI%ID+BuF4RJcsHHzK50 z!=O#QRPKs7`46_}$-Y}O^HoF&=G8o?4EwG-nJ7q1n~^b`pAJ1|9`x!5IRmPkY>i}S zes#xf8q9)pf!70JPTds7NUwag7FWZKSlwy4KFb_cIc0fr>5h2-sWZGaH{_1hcWx;9q_4g5Ng`VJRt2>B%QN#?ma)+`{+#LF_lNqP_y9{FtH zCgo-DDnz%msEEUe=9#rw^H*%(^ilsDJMP^`o%HfplM?gN;(9HH(xRf87YcaI8aYYF zMCH}4pb@Y@p_I@k0(qogjsNiA_%9ihkWW+El>qc?HiPc@u3Ey6rQAdo!n$VR)P3Vf z_rXjP^?ED2$}NrhXT-{EDdYsc8VvZ*9kRNPBp0#ILk%H7HumaiZAUAV>eDzXmGEa; zTsWe=s0L!Ndm`miINMd`_S9q88#(%RUL0VVkl3=n_n7$lz?GjrtzFq5-K$*|1GDZSCwn`+GVLv`_E_`T#8 zUlI}}$r&zEt2oQ^&Bs1d;FQ)os78QEO;WLrJP9O49J)TtSRxP1jdIQn(LxZP7WN~W zUh52Ajz4$MdR#O|!&p++m~7J&RqrCug)v&ufi#$xI>RoEiKO60%^klY)&$ddM(nCefP&=A1Gn9 z`~9EO3-+F;X|T8~ktYED`W2B^-=vwG8xc;;VJ+!aNsEQED>h@FQ`rM2{}!Ljup#5J zpXQ;Qq&y)?tO2~In*-FvMtheS_}BQ?CG>OsYj}F5^;5keUyYZb05}bREyl5N25}W0gJuPBPQp*PUqDqiY8}(7kxNhEp+GeN8tH zKX8Rh0FyE{2 z)m}ENFDHAw?vAm9O97Lwrqf_LOm*;+83H_MsXmw^FI{OmuD29)mzcM>z?^MTx1Qh+ zT6M37hhJcJGb>wz@tn*>#O<{L2_#1Uwo||6V3DrsU~yHr-C$km5<0z7Vr6>D4!3BI zHXb%f^Qd<>HSvPFdBquO9uC(R&p&fPZyd?9EN{)zST(f6(5s`{(6 z<((rWI6qOz_(x4&OJdlkP-+}lzcl^p?$4fFLctH|DjyGdE$wV}STOuU3qVJyzk3~4 zSuq+w^w5n7M!80A+v=FQua4-k zAV&UhCsk}Nkro_z--Ns1vN7C@#U>J>!%#+vH0w13u2p1(X{4uD)+5hFTf60aPx=ZI zYFb%e%k-MX&T=%D60L51jYqq*Bq3MZsKYNfD-?Z1TJn1@wWo}+7gV0);ym_g#pAYp zCzm*11#FNfFnD?(%d-3tWZ|{#9AfVraJTr?&j`97(lF!=w6f+ApMt=`CfM}bGK)F; zChwkEDe9H9{OG+;u)T&LNIbN1&;M1qSWNuoyvR&i`Pq-x!l}->hzkHqj5GxxoPT|+; zp~K&;ZbcZ->>msx2qvSO_g^|?r(COM@#=2Z6g~)7&Myn{ zTS~n{-I+U|vwL`>dy_8JrckP$-H360M9XM-+ga}iJn>}?=Ypx;MGN1Z@2YMuY*IUo zThysFou17Q@_f_|{5JLr#px89!v$)I;?x@{x7UIc0;c`SN#eKH-wM0ksZL2*b)p-+ z_vmnWp{r0(z)Yum>$=RyEZZ;%wc4lGG`-5{NX2Wt>)hC}zAnP6#oqohlj}=+Hy3BV z-w6K6Ai`(L;DUGf$a$^L%A89Ce#tm&=R-KnR?m78`~n-~`iF|^w*^(@x z^jV0Gs(B181Iip%8Z*6&T=q=fd;fU8Vanrht7=`JGwhN>kM-`3eal_ht&i6r)SnRF zw(tFc#J3@mE0l3su|ZiiJtdgc@rrf?Guvv&xJl_Y);wK6_MU_L-qoW7?Nh~?lM+ap z`aam!^sySO%opeJH?{nI$wpRc-H7M~jV>$Gol={%dnpUbkNlGMOiga7;#XPg_|n!= z;R?vPP@jAOU=3~ns=?~;FLpx}K72vNz*It=aYhSLUsuwp#98bRAbX&4^fJJw52p6o zDakKe{i}F3+pTi0zYY_qhZ8LI{NER3GvBhT7_g3fS3qtZVx&bOmOpC>uqz|f<5OVH z+fJCYElut5)}+QBfTch4S&j^JMnsYszM1d{7=5D)YFS_RO}uiuJJ6Zk8<^Q9zGNd# zUN8DjWS3>7xWlKTC`}u?ADkt%hCZgKOp#uqCEae#O&FmP(a4OWGrL}Z^4^xe{p7wZ zZFcfrhQmF^=x>{T`#ZMg31%{HzH(>GW_)DvC>$Yfv`9YLz3|;By*Ga6Y^*iu5wpCp z6;A}6YmGVzBNWw$Stpuq=0^AvJC%yMdSa&+l%margzzseXDiGq0XLOT--N^djn_TVdV8L`dfyUl6WHA?d6&nte~e}LjpOXDr1R$+Q9!6 z*BHfdGSQhn#DNsKtWa0Kx>W8~F8|(PFIjf)BS*f%z#Xb3oK}2@)VAt4;eB@}ZfH(a z;mfs?ue0odCK-jWKC>twC%TidYWd|6*kbl6X&GtxLsZlf^u zZI97BOU1p&RhR8?hA(<@H>CEdKNKyd4Gy}qRm2L=Sm=r z)`F>PN&;%j6=Y-Jd>&zB3gp!>mVA{Q(yni0w(VU?o3-$tamB)n+%L8244{%|o zuyt$ELi$Atcqa4kFLVrZj^KqjI5e};Q939^1b-$4yNAC#p=bHAHbh|C_9{;1dIr(r z<{(_)*(_mkh=Vy}hbJRD4kIhfpNi{HI=B6P=j^q^-IGh~u^kotNZSs|i)(eic1~EC zK7CsWMK*MuqeLEsft3>riQCw$jY^>M$o4Q#ARsPJbt;Jpk*d@Wnu^42yCd#vZzsaf zr%O6sPOM1dQ$63_zAnJ*(A%N2A?tt`vr!T#!;YX<5C+LE6K0Bu*AFeK!%*X!cO04a zO6)VjG~*T$SGRu{9jcFyLh%an1Db-dBi-09@p} zHqm#1UuNsaeRtz+(=5$6t#w~y26HXw*6daXL@%wj3#)8j`BBv!$*%oLX_I5cF#dsQ zY(AAr_*@5m62G0H;D}Upb%EIT_?4~&5THxuor(5aJk7eA8Yf?H>gq}5;PH|mtqhhjLpj{V zwGU{d;W>7|?cpd*1S^%l6KF4a1VzT5j;$x%nH?c>Ao!8s@I2Mx8U+^jeXw}RT6C}m zww$*gL>rlnTpiClLP@JhmUR??;lDSSyz6CT4?JA+IrwD6>*e)E!n#wuTB@Uc11R(J z!Dd6H)p0A++dE(Hx@uRU$_QA6jadBbxVsI5p{Ir2Ha6e1Te2SLrq0{>O(k#Pkjbq= z&74F^E%Gwwzp}tiv+>Ela=^L2asb6Q6^@)LdluOIXhxL=&FQSp3-vNIcR#dQyhY!J z_MH0J*pq=Gt$1C$?YFywu{;zhRjjT?@cnF1-VcsEgj0Y$A@ydYnxUkKTs)p`ifppF zb4#URtD3MVSuEfxVk%E^Lds?n@jq;00yo=eieFo&i^shrUG=gz@)bHa+UgnQq&3cl z5)o0BH;!E?X<-A$0;q`8ujbxjk-RQHqNf=bUT&dKZ7#Y9Lv!uHK3(z%Rn~OUEG~-F z>QMe(?vw3Ny|~}B@0uE=HMCb{ACp7tyDLsCIig~v=$y@hsZPoXoQq1GovT*)7OKRe*M%6 z`bMygK?)uFGuy)O2Lr~y3Z~5;>?vcIsh~r<$55(^;_pFKA<74X#(OcVIh|46H`#V+ zFT+;WYCYD540yd3-{kGN^C&n-TTKY63{`nz7%KS7DVn+Na*}90opglE<-zu@f`0s# z(#!2GYtyXxxub1Gt4M6ajH(h6Q(XToYkGPi&P@&XonQ?V)ad<|E!{Rg4;R+b0Vg@x zYmod;s|us0DEs=cVr{(TB`nABHmEiCmj<56vn>s7tM==~IaYn8+~Wa(EJ<<3Z8AnF zJ=k6{5#1_tO9mVMytaPNR#y0nXS&dmSI)fYEv!p6n7gHYr^&hYDo}Z4Gq;_UwWcq4 znsYWe)kz3f5b-2noR-cKrl>qhrBo)fO~&l5g+b!{6F!yaHr*Nvw$Qn4r?mk;c|Is` zJo{C7-*!t2ZTc6LOlnv>!l2#U*NoiYPc6S#EE$%KZ@MbU4t};Va>`f%4;dM zCEyZ@oqS~|Doe@RL=aW*==nI0uY!&0Sy0(DYo%-NDU2CB9tjA|?BK@&*%1yLeV6HM zT10o#nvsP=qzXE;W#{I1btc0FV=Dw*FU^n1Q6}L=Lfm>FfA*6v0-at_X+?AM2fRrU zqjp3OjI7Waq~TfMyHk<025$8cUrHop%lMb;#%H%jU;_o!Y{<;sjv$vAyFR|vyTdeS zlItN73^lvYT}?V4_SRI(>SkH8dka0Z$Y^FJ1uzk;PVSra%#t1sMJDxoYqgu9W=AM^ z$R`rZ`n<(Y;pH6{xtF7gp#d#wmr8FAk7ONg_Q{qlsdiA|l;WhHz=lOguJwFx(+*l& zW2(RXSZnyWdT>#;wvOq$&==#*(V^FF$#6y&5{p~jXgP0y(OR{^pp&MoYmEkxsHa%m z6?qJ~*adzZH1?Q(iS0MM)FP^{VPmD811Gw=s|gBw4R3tUW3aIjA$WGvcrDmJ^AR`X z)JwCQNxML!^KMlUAF%9Yl@$Xd0_ZZME=x=Q=Tp7(Di*zw#(hosYR@975<$Iso*A?V7mrW*VY%H8TiftF5vD`t`g*>Q9t!h1~nPzDyzqglK zM203f+eB<3@XQZeW?TCNoX(I6;ry$~kweFU$Ry|KkC!WA9#@1Ix?vJqN${Ps(blpn zA9(_bXeIfy7uLr=DBn(>3D%|6X}ZM)bg!z-LjtHIH)BbpZuo?2E^)P$GjIRhK0lzI z%aZNjL(v;}r;L+Jvxk5IaKs+c1^(1MELm>3i5Y0`5lH=jLuv;O*^MIf^HIJH6HyDM z1wIPKE(g>@5Ur%!YgBzCUl~Qby4c0aP<0i}s^lf(*p5&8b#pP(*xqvIAJw(i3U=$) zQ2y`6!!QTpoS`MNW$38o>`;Bw-iF`uhmpNK<1W{RdvqsSM1duK_KniRU6GlcrsxXj z+CH@vu2e5Ew$WZgVpZ*{@DPkYmz3jQGcDuR*|DU*4B488rW|@2`@D!0ndnd&AtaoF z;wB)`sW%3eyV}k$sEZla*V)95;c!PQT}D@zc72K-JaE*KIa(SYc>qB@EE-!KpSW49 zepys=yEp#Ps`<_MNMoXumh4eM>ZLFBW0l>I?w~^<4*vtS2wF#r>fjPwl-s%avEA{o{)$Dq>v1G4f(Jo5RN&8;$Q;iuq(_ zjWr<(S#&6;j{0{Bdk@U@f_?&TT(%w$@VSdn@s_g{B+r3e0lGjgW~I3I9$h*!HRX*d z)Fn8S#(U#4OL5a0n0nJ}jpX|fyO(cJPeeQDmdML@Ds6`)JQ^&S{EU+B)vbN24RlHn zUg+r_efJILcsiNnOWMn0LG5-+@U~@Vw6Uz(_m$Req`!IxlR%E*x_Law!j!*E$9mf#ojx&ESsZ3=3}{>Nbu^l z2es}4<4C(K6Tclp)5}lvDelm*Iw&2=`0iE683}#(Iw+<)9!F>HS2g$Q^WNlc^s?HA z+#nj9%k#a4TWei8vhia>yA0{KPjiZM!kvpeok%zaU9k9MQ0U3G_#xxwczyalJ)tKW zL(zCu4la38%ifn^M^|UMbg04wS=0IVAw(qIG0Tdlj0+zCICm76c@3jo8rCK44lEoa z(RS)5gelp!g)zx|7Q41t3&mJmt5BA_0#jzB*MfIdg@VN@arlyZ?X+`mlg=M`utD8b zzM;I7(-G@7bu}mWv&}4O#O_yzX(j-zotSI_u@rI?=evg>XsGJ z%dDbB_Pp3FEYns2m6@fv4@gdYeU9hXzFeX+R2K_n^>}{k&6_3ALHFE%~<#|z1T;vCzMsn=2KR$&N*^RbW^RMZl)Dub! z$W^c1vR=51hz!5@bALlJ-nR~9Q()56I0%y_j4-c**X8H_sa}iq`GfwDj_zd33!nhy ztZ)(l@@|e`Q$W;;p|ea6?<;n6Nlbf6yJnB=W52iC(w|IyGFk}=Lp{tub%GXkqs_w5 zGd{sIOF7)t^lK$}pIO%)S%l;(2gLUMtCMVgFICBQIV`l4!rdUT;aZ9Svxh}NhKW5K5n6{*s`~K6bKsjyZ!c=wTfzQmvk&1vGnCRksh!y?O#Km%KSFG8C2@#d%+ZFOg5u<>f z+W4}XZaK4a1M<0DXGp}o`D%`-$J(Z%By!+Y@I$`76aiF`lwXoAYjWN9+Dfoou(@1W z%@h6}PJI8hPPyS;g+~$XSa0pDS_Vt0dsD@xqEX~)DeGRD#rxceLg$quOkLs45x$C& z{eHXn6YKX6*b@8wB9K=?&i7UefHo;nG*lxl{K8KIPXGNHXZSONw|y}i4%D4~T;U++ zU3+$qTRF0g#q&`SYk^69&DF&y8r1rP`49h?I~4DphX3w^x7xkqDN?DBtP>yJtJqi&hn*8&#OjWnzUtotqY-shZs&OP^c@8ut!heyBfn{$lu zj(5ZyGoc^J2XAlX09$PQqp0ckrhfABnVEZALHy4md1Z+DZp>KeFQ za~n-pi(;;ICF{nTpjhKhMst@dqPi-ohP3_F+k`Cx>wr~n(cHu2hyoofU~*TknCD5n z?Oe(yc>rSyAxc-oKgFf_zFyf4i+Rk1tEL{k4#Nr=K7~!ItCBsO{m^N(ajm71N~*0= zrQ;0&83WlhE<*j*rVOre1gj+J6}GSDT?Ej^ym zd9l^0>T#3}+=VU-+CtYg1IBDPaQ6m#U#)162Cpl*KBQaPI;orh;Oyqz!XC{o0Xbz*79`{Mc@$)q*R$bmDJ5STea zX2v>VHu3z%unJAUc~%3o zyJ;K!)T9gK!0jT@XrYoUFN)Xf?X8L`H~k)Et7|IMX`k)NBC_^FqCD$H;l7LV(&Puw zIbp1}kzn|H!eUzg2Byp z!{(`y>r#@&`LoONZ{(++pSw!uMF5PjI@!y3oJIKVzVm+mwSVZKCJ<+2-A4|E@dx6J zO;VA~4*@9=vy97W9@gemjl(Z^C1qO}_e~tjRbH+LIQNge^g`|Q(BM4NAv2Nb#MO+_ z=p*I?8n?Ev zb?zo@ED@OMF|m>=b?>lMcZYNvNFVU#ZFRpGg7fYr%T=EaWDbSnyx}mM5Qkil=0`ke zUBTJD$46s>Y5j`uwBzY+a*Afi&SfHEtkZCv}1-NY*RMbs{&}S z)w^7MQ5=3XJh!UU&)NTm>5Yow0FJEg@8ceUv*9?0hzr^Dc%r#s5s>!fQui;DSzauk zR03HOk@ND$l2@MBYw)P|mk*c#$^Ftu}G~QD3fb(=E z3Sq|^?Xu{W?-~~SW*vz%7Ptk=1QIvTKZ#3c1fQl#6-NjzRK=Civ@XPuV0Y|pcqmWT zw4D4m%|VW979nrC{6#f|_LeHm^!_POri{P%6`yUD31qRR zDinHDGx*QwfXU7qdbKoj$W|TsK>H0?*4|}OT0XCLMfTSc_cv~{X%~vVqWxqzA#lPNNpPQb5sbq-uC5!bP03Pct$uPoBx{*mKwP47D?{X1& zfb#7Qs3gIY`kB|X<7t;mCR{Jyc=KFa)EtXNU%-20<$To|!YLAYsK`!+c^F0k;3)BBF0A;vJB$eDNH( z!)y9F4<7+A@9>Gt?K7!B;e+^?k6Zo&j1h{{*Btp!UVpWR(gnym7UwWF2tXPJ|E;w$ zg!jpGVT@P&mSg(qQqED^qk;jg#=No0Sj>89sm6k>{7d&#=iU7srdPvNY!nagChMKS z4$5N=c#(i5Xi5wWQUz*R#C)M%W_KCbF%Sbue**A4oqap!8m28HM7=&sZeZobC?&B_H9gtiIwK; zw&+2{Hogq30kjP`H}a3xAx#cH^((3SPna-En@_=`qS7<8y2fF8+zq;Df-bF( z`@F(r`Y1<$PJlOTVqe1CRJDLvNxXYnMenp1?+sSXa$|qpw>JkD7a|XX_?<~%)u!0o ze9qLRHGg^Jb&9V+QO^ZTd(7tTjKpg8BEZxCA%1jT&?UG6M5U%bfUyO*$U|ix*NY8h z@OX^Y)*(O|1evf4Tx3-HS*C+<-+W<{Dgg(MlMrf6a|gT{ZKmE3c;AQYgAQ}@d=`&` zHa{}`kM;<|*uT2QzDQIVtO;WP-d1k z_3+`RZl!rqR{n6G1q#Vd({+sTicl8D-p{Y~x|DP7`!_UA-T{dyPX=5~Mh$?+EFK+?s-c3#~G=Jlvqonh!hMQh5w6@Z19hJR@LKK|*->5ZRYEP{4^Q=vn9e%5Wc= z9IbRRzWD7xKw&3jIi4cz0bG3}U65XnyYb@}V@OffDFjY8DR$!RLJ`KlI~)ML0nTB6 ztkzHj(t{dYVOz?yDq`^G#y2LPeKug#)+!lP-c_n9SqxE!1S8<5;yW@K^sRxSM+UY9P|;I(*)M*U*hpGmv%=h^Qpk3 z&z23IhQ&k12yLn{mbEDGL|4{$i3lg;_Xnby}G_nt4Z4%jD` zp9|Si;&XVT1GqA=IsiL-&CfEk$YtI1td&ZyPNeJ#X4v)&?ert(7wS8HcacqW*8XWa zFOBm8jQ{Ed;1af^<~MS@z|1q#<9bN+Q@L|lZCJRAAN89)RG`1YMx;?w={UXH9yqcZ zCHm`05jSw0lGs>ZrJM$sUz5<>NcX~L&=Z)PP;7;LliE68oZ)FIXY=_O7|Ku#qn?#v z_jZpty#}W8OeD7g`DJ5y6EHt(;Oh{tsqXIUMPA9+2&nx~3;WmiB@jLN{a133$;dv9i_63$tUe~44Mh== z=qe^?r*n&SalmUGiR+_dZ=FNYD+-8PO)xJ;@Pz&u3vw# z80_i+Qr-`=K+1?ipkwQOLPbQI$HitxiPdAjU%((Ss$&=6tYY}heKi2SG~0fzA0IeV z?1UA|9Oz_%N{Z1BJ`LJJvJ3+zVHvz^hs;+3>NXdE@5XZ);)!{edB*V%-!1qBNU})q zIsm1~aI4M?Yu5dKR(khtyAU^|@K&c8M|x~GXtC+xb53+565aKB(A#Ql0PJi2xijQT zrO$3mz@#moC{c3Dz6#ho2^ncztSk{~s3yg1xvb}2?O&!ac#flxn2D93QtCwp|wZ; zy%I+F>TrM}pRF24yXCo8CA3*hXr;Mz?zd|V+)>E8)ml0Q6Zub*l`@X&rN_?(2zrhV zCjRKl`)h{TfIV*AvaKol=!90r>2{D$ntR994laXx*sPEn?9pROzl{l*XA6uwmS5;o z)aS3SDj!UW-CWA3Um|ZncmM+JnEI3-d*w7|hY-{p4RIn~NA`W)=T!sibFUcXh;cj<50yM6lDXUdky0-HqXymhyXa+j0 zLsdhU_ed8Y%BlB*zs~%^@yRhPjVIq-E`oBc7X%;N_(r%>Bq%2qPNQXD*)4)4S8gv zz3-K3CLf)3)Aa*0-1U5i$V=Cy)~8Z`2T|ohW1unl9-e<5`8?)ZXs9gFmeOZglJ9&^ zKZnY4etwHy=zl*~zU=NBDMIx7xS{gz+FH(Pii<2=W}IA(#WswB6`6Qa>Rt9-4hEaf z-CCF(c=~`J_>hRe!K1!dO~|mAvUTNbtB!@2_<2Xi0Q>3c**mEIys&Oj98LEA`fQ+y z;fuu;^0&O=i$QL_!ea7eb5zxS=xAH8a902J7?+{itz&qA*J3qqW>|>_ldU{o}Y^m4(^K zA1=+TntIkQCwq()drR@*g-KOCQygtM#IPH(?G{CJ?9w&NU~ z<(+Z4TdgjZjvs56>HKDC#UP1R*p8mvNhMf>oNe87q(Ml*5;$94}1Pt&098Z zFpRh`Ol}1|(HrJS7dV@)b7b^#LTD%ly8pWCR?{%Im1ZtF_s-O|^=O`O+wraM%-Q@^ z-Yn6!l=RMS;wH{1-H6o~NJ6k+SHHsZsrAA!e8r>Q2C?0zHRl`%^ACgR@;W+4oVQHa zk?U0i00S&1g&a2t;dHJ?eas!A=+cPs-n;f~v6$R33QpI%crh#~Tf$o<$Yr5wfLnF{paGB~a$+SVI4Tj$p+XwIjUy)eGxnNa>uF~K=Vzzi#fY%0k4jx*{PPe3T`z|wyciIs z@O-!n-)aan5Y~Ic$83@>h3&+r{g#BZMT7{7c-3TF%6MbqIgSWU<;ig2q{@tLUfGMv zJe?QrX%PnTmU@fw%liZirdQd_(ETA%YbN;u=D6yc?Wr2@#&?oz@76E6vcad;mX14r62J+g~3BIGcH1sUVCYV;0D3D!$mrm{OcGYBgCh@#f_v5 z84Hn=c8sig!kJ#SKnRSyDqC+5+h`TcuhFPy?XORi=`69*zw~Gdgq;OID6B`k zts^XT_jn)ITAnWqaiCMYDyXf`t+CX0NE>&BoJMTqvu3w!6-H<+)QU7tRVme3M=zgq z6_7_?tIb5R<6yMky_#eD{(8A3Zd_v`N{(JN+Bep|4eKZG`A=R>kp0WE(Ufm`CP$S7 z5j$q>#lN|@jt+LmxH;yU@cA|>x*JP`OMvd*0X%85awkkB|1~x z@Yu*gs-q5D$?HWw8j^OYZ-IglFJt^+eP>|{$He0kJFXrNC*jUkln`R~m8KZ2!SVXm zKBkSPvnfkAzLAO~x=e~0SN!^#i0NQu?a0P4_C+(cTD5P1uw4(>M>zSxFcGuM$V9(0 z!(@^&&G!E@Y!Zl_0WF%~ zq8fLH)*|2pla)ihSl4P%B@nzA>qy1 zkk)X9$;Nr`tD-OAF<+fdkK-I4Pu9|n9yrz-j<}ET##jd)TtwheB8_o&k+(XDJ?mmY z9;c7`aW)gP1h4CC%K!=^+I$oG{5*I7e~#opy-%fN)b>F4di%%@(+=V0Ei@3P;1g`! zq+Q(4`^acDOyPP-FeA2yJ;@OI{zM8&{KCXq{_8MD0c1Zv9Akc`LLW$OnrZ5+KK*fNc|rXU8xp zR9%oWwYS?6WH+Z|IuJgnpds0;K82%|dZ5M4VUs#S?og!eUCWCfe`H}sHFf-MFo%Y0 znW9Iuc0Mb?8kp$neq?B^3tI@4;hdC=q?>H>gZQT7#Pe=ND z0f1X>a}*&UxxJA{BYY%g$7&|G}n>Eos=tQEb zSekb1$2i*mQ;{g#27!h?HUXnB)&k9Y*-J6$SaA7Rhrwl+VAuh_TsKCKJ%IK(`e zj}|!upHC#w@))Wgsv4wln;IR^zNglpKkr*xsX4O9Jv^`#BTDkrZEY26P7!JT$eoj* zYcn#gd$Y9kee>JIi$!=L{UkHNR$_F-75yaK>En+sb>T)y0gi3&>r~~gzc_2vJA{XkUW;)3teMQR{#4;OALB6qzoAzrKS*M# zZPYsj=Y}I}^iE?3nB@ydwpf=XoYGm%&gx_>!R!)`RR$dxCN1E$e4L!ty8PV}7vrUP zU7zodZm&xfsL+h5Y5Pocby`gx z-23z)CR+~S_g8ch%C0}#Vvae5U}USd!j-%&Jd-7&Osh(Re6>?UNJn<=W*L^p0bj2`9 z2W<^n>r3sKn(c$VxjOv(S)+Ur)xB!&iyvu1>o#=x;EVx2R(e{#t^eACx_rF?10Admpl0lKYC0jKpXE^w&8+a zjP+KRab~;doqKHYTSl-c^FSngqdJ3Z|aMq69cdn z6wp=&9u;23@O^!elrdb32GK{y-VMatHp9gEW~RcBmWj)C7SDb+I^o*40=#7hp0e6v z9-!ik%$Fg2A_WNwf?%TUKoUNo1W#Aj`bvFgexbU36ls~v*>pEs4T8(Cm=i!Hc8?_% zTY-^XT{i^I`}2KO(d~ETYJI88@wD0=!2BP{@?t1^y6WuY5L#@#ih?O^TZ{X9VPezU+F4Cql3@B2=Lhqu}@I zP9h(dWpkQnA{}AzEV}Zn#sd?nH4P^eu0`sR#m3RtPJ$egFPMxLf0AGd|Dgf3+_xI= zU8vKX{v|uT=*mq~B=LEAe9KpFMQ+FEYNN^2T#|PzZmVyYQJ^ zk2^z+(j8lE)X%lPSg#(QNM4}@sUkLm*1+CzG)-2FEjQUjS}Dq_>5-~sT7_xspwK(x zQ~9+uTe-20J>TWU_(q;la>6n-rZm>ZevCFuokG@jG9K7Cs?{7k=6o%g4z{oI5-3?b zmC_=xlhKNcNP`LawC{ltG?Y*{hLe4K2P6xM&R4W3mp6e}1!A6YTA^4WvwQ1nxr{NJ zoY9JM-p}6@Mn}&rkSu`na8H`|Vi&qlGlAQ#luxss1cR!d)2C#>4>kRd4!W z3Qq-&sRDQ9fCVa>T5JA`!de&aTwmWdM8Y% z=w`~v-d#{k)ok$~C3Px3fmJ6j{(L-DbFHrA zVn*WFFl#^wY&P&6WM;wdC++sVu4`6aai|C-;QMQi7!Y0QS}6T=Ur3gT$YJ?tu)w!wSKPsK9k+TU`z z_HkPTa#AU%I|ZA@;ix`2|v$d7D8OrY-Q{jDNRw0{apX;x$a&PMlq)_h&+Kd3OODH<4byy4(Ji@B90glXZ|NPn z*B+M6#maT;@8I4WLFuabQ(KyqAM83Y7xEeJ&d(;Q^L=S4-v;A*O901t1YQ`AIrbbr zeP57OWak`!9xpdc-d@^QQM8+xH?AQKxzQFs)V}|CU+AgVi|gbIF_W#wukVrPS{kr! zx|^cSISfQNDbBtVrZzfP(0dcQr^ma-l$I6OFqWJ-X!ZSIL~#lfEZJ@P{>i(9mO^5>&sFZEF?E9+(aIz=o_M2d zO`PYnO466J5o!bR;cF1sT3!c&OhJ*I`Qp;YjiVKKKM=O1I}TKN_3m3?QDH!gUtisL zhqDamm%e%<9Z0uVCoaX%99Z*d{LcEirkkiP@{vJmr1o-t zBN)LcKdr^&T1c{$xfibPjmaOk3bzgt71@fxpDNXUbA1FUDhI#~+B&|D(PH^WZ8@ywWJN}hTx4`OGm{`ds4ITzHh z-V<$N{RMiv2Tvz+mh=K&S%42IpC2jD7}vmq7PQ<}@)nB{FeOC`lqcU$1Lv( zztd2)B6{dK1&r|<-Kzj4xJ`^)@F>g1{lm&{Gb4XmxpcJ10rmUA%`2l{hD)wW+VkUQ zppnw%%(0a3)glK0IqnsfWh^`IRpOy}a!Nho9M;VoiM5SP@TLkEzZ^D(K99wDS=KVQ z<{y#v^O2g;iH*$)4%V&q>%F9qbtgFEd1vn_?H*-U@AIkYP6>v|uqP#ND#AesYN6_{ zK3yk2cP}F*jOrGujP6o7X?x6cE|<4h(;UV;$yTm=_$_(IGAWTwJ$X!hnj)-93Sxgu z9S4Ve^L`=CxiE@LFe!SP@_Q>$htX|9=6o957hw~21_hwOk$zkQ6u02AO;&Q2k8og^ z35)i*JWL56#ygk18|xXHTZIx4M@2lM40SyQ)NpIhSz%w9Z%S?7^Qd-ahKFxNYr7-f zaG?e?J~uve?Z`AK=Tm#ekourMGi0pa4i@n(iPb!b5*(AQ0q+i1H*Nfh(M%}AYiBIv z4yuchLon-V%|u-a>bHV8nBb`^JH{iAYm0O%gPOk?mYwO^I-lTz=f}Y$ zTTWM;WmReQC%8|J9`yF;iJr$Y&v7%Q&KE!}J`XR69?xwBf@2`SHKXMu+Y9imC=!T^ zW7$rH7D%%-_X4=>srpD9Ko8BC^I_4*kwhv8Xf#r(@@9sfPr&$IV*^ri{)7+Tp0|O| z<>y`AAcKcPpWbnWZvbIv8`5qYDrx5S-+icSo*Vm{OLqH33Hkb?lysUWs)|MA3!73B z2N*9{pMkfNLs`M#^iVm$vh&+WfZ#y-UNgNxzDmP7RIDkasHG65(it>gMo+Z;U5JR& zCX!9{6ska50vwy@W%<%91;3Oin3(R?(0{EZl((|)=t5dkpwCjaAl#GI-LdBe{uVB; z5${~{W)@HY@Gz%jy6oXm(u0}hm({4cJ;q|MgQ+Cbtya%oJ$Vh9c#-~k-!XF^VA@-` ztem`A3BxDLMClRALaB9+odyy()^QxdmczF5g|d}99SWD-jWqaLY!1Y@nnG5NHLEXE z^4A;Ba68YM4P=XZ%8<%4TcU)@zFsdZsFlBm|H7C*H;JH>O{3pwAy*Bv9+YG*q_gAY z1vq`ZDn4^m+`s`K79{r5bMe!geX8Y5$!n9GPL&4c$tm$ z9FC$%NhiMpRG9@-N|Fm`)INRz^(Xdl>bCA=7+2GX*4EHH1x6a}x%MV_IX1+IhJmL5 z>74L4ZAqxCmQ#6b?;a$oGG8|l`YSh#k&D)QHj$FqU^$Jm&W&J?pNnI(#3$?r3eKf@ zcO0*c*^2B3qVk>hy4VRW`#Q!T%+GQ7Di;#74`-V3)`C^@X&!IpzO3ErR*Q6A8KVh$ z2*HJxkXKfP35(&tJqfP^(BD`9gexqo^hE(~Y8%r)Et|s$E6xLs)sz#h!wY+vly5%v zrn#(h!yC?ZHUa9X0QYXIxx(h@ZcI$yMuY%X#17uXK79w#XrL_9fC_bEr7|SGonh>b z8tw1EIb9XT-15FDLo&6rKHWIWKS|t#f5ZIp2I6&TSsGlnGlhP7mZ%lk-(Rw`yafl<{QqZo4 z6^5`C*_?j%gGi=A_Tdw$BGxmUXX(Q}Yxb^`Qj+PR@!siQneZ8nG3SjcNNSUkVXq3} z6ty0(MkZ`GcpZaFPl%lqr)u^EK=$2)`k5lf-RCaWROvP*aH+j@=4|B#HaCN4QaYBw zf+L&y3S}#}`IJb;20-4|cGagF4xO;KWJWx}NAP?;+L?ZfH*iXgm6s!7r6mhxH)~!l zspH9yK9g{s28b7^`P?hX+=ji!uLY3~j49v!Q8MBLdL-;<3sL>TS;3xf2@}aZUP|w; zdpId)3l<616LpMza3BJ%4{#>n=~F$#(hHT&nR?CE`$M&D3mGyL-_y#^zZ-9Y!+7Ff_d{L~kdkuzH=DiuK5#U&`fuLJYrnxE=9 zVoqknms%h#YF!XW+BjQ{pZYv-zl=(GGWYgO*Q8|LO$@WO;-xUJznJk2;MHgg&_j?6A)Utz>xdEPI}8gCrp!52hB7 z=rR95nm|hs!6ojh8Bj&|V9Lok5V||Kd=x4=r;i6t95-a1w5Yw~7XB7$+t?^3gqRX| zyl&1HVEIGc`EiH|Nmv)6@|N*7=z8h z4V1V~yl1|3dNJpg<`VwC~lui6B`T=b&XM3h^;rKlewWM;DxSE?EkUZrt zwuJ<0__jJ2JhPnmo(B@C6&$bMK3NtQW`(>xlQ&%i62ixh&MdV=CBt#2_gJ!r;SxfW z7Zti3eXh%|cM>m}Xx?oDc6M~I>6}A)0EAGaSa<+XN^QQ$w4gF#=$mg+Y_l6w6SVah zxEdo>Eb5jYoY;~+>N+~qVFoZ(#F?F<2VkuEUD&lmDq-Q&0AZ3wc_f}g$k!wx@3*j6K{G~>l&Qc^VsrwOp6(G4 zc)b)N8|B^cE^f*rJHgVn+5OJ?lGAuWtVu?v=ZUI5?;wrg<}cu@-6zft!uHR^5e_HI zLv8zfl|U8hnd8(P`uU2F98dv5_io>)L=|yA2^HC)^SQE1dZCI(Dm#Dc?v}%`?{^IU ztU4ajP16_76g=>&>n)?b=G;|YUR`0{(Ys{ruZW{d4^=pLYskMF*br&*ph8@TdLA)) zA7nRzfh5CcZS!!=mGuaUA+;|1h8-%c#jLJ7SWbvcOAYJ%`89>BJ5GES$oIzF zThu5kjVP%;=0@3qR1|h$NC4V7-y%{GqeM0LC4o(SmPfi@Pb+-vV~49V`|ng$#Ln0h zn~&c0Wd|;kR_(qD-_>@8ahmFe`^4M;A8*0>$1C$7E+S33*7A0LGmep`Q(Mv__wr#j z`;Wh<=7Yq<8d%Pb(3>B1W;!T8O&9QXgs`b)#=a_WfDm3P$S^-I&~44p3}+6yza#D%A6jOUXX<>#L^?)z{jFKRO%F%QOv; zE;w#M?46!kt_qW8S) z>;ZW`vKUZZoGK)A#WY->lEwXw4 z&21>;IE11*i+Z+1o?K-D%7ISRYvco(!6z!#LHS&1F-D%nC;G^Ky}!@7wOoiJy0TmBXJbm+8`Cw8iRC+i4TzC;l$SOx)EjbD%zz?1Km?di_^`F*sUsCZ zcHwugv%;argFmC-tUww~`!-oTreA`WD2?HuLl)AIlg3!8eWY|B{S$Z0(OGjvF zeY7|Ao~X{Hs|$(M8fsZ}@ubUn1IdJEgT$itYlE~M15+CDk=8uQ7g{pAx6B0_p zQ?CS159QRG)t%yeN{^u=^(q^A6Q9@Vjf8LlVR4-MALc5%YA;@OqZ=j;>m(ho9bl^P zXHMZuE+94x_ArKJPWOZw_@WUx5}u{vW{AV|0wq(#b4D-Y>I6^R-c|`Y!(>J#pa`9L z^-$3o7bss!)O7}YDt~B&g?9(F?GD!+pn!hI8d3U5UCGTD!|{&A#fHLzHv9~lHu3Fe z^dnJkgtQ0hraex#A9(QEE;b3QP`*-#LFR@PpWpcm+ainaPQKt{diO))+2!cBD5cJ| z!`3ERJ{0HeIJM$)-^GmD9a5)H4oYUFwql#tP3Mk3U*E@asyr>0F`F|Q8sb+=5q3K+ z&!tK#*H{$zA#%^=XtytN7Cn0(>JZp{KA&W!x#;O;-BafobQHM~!-0qz?aV&oMT4VGu#SD4L{l zAbnf$Zoc|!;&8sQ6d5>J`&aSTBT{9`XjQ7P&5(u*eN+rz6bjU%t6pwDNes3-xECLg zwA*06%YefQMZ1@rT*M;2FC@`x_l1x;v!Z_to*+agF@4hoyqpe7z6Va(IwF?}QqA`k zt6P#t1SX}`m8<4B6E1|?H=+c!bhGRHv@Q{ptNgS- zo=Il38l!pSO=nd4Y^Sc^N>~`81gWfubx=PG%cD!ECSQBR@(?q8)t9)1vG*S$45UMK z#As+Q47Y|VL2@VNCQ%ze28~IJ8(~+@4rf;rMNA&C*uuedQRK$qb}UG-#_~T1Fn>>f zL>i5nh(({z>x&1^ue~P7bX&ATzohBd{~d&eBqpGbaCv9rMk>w3V$FC5w5cYE1R3qI zC~`4>8UaKlXG1P!&TEFrzUjscXx}ze75V~0UQa7_NKY8TJx%fDQ|41Yt> zBniRFxci5i-a#$=c_)3Q_!A4eTTPMP*4L|>(|KNJw-jPh3L_z)=+`bVHoL#@BJa1S z?9lPUkIq10IuZLmw*kugHojZ1j-O!73O|%>JuG3R92TB{bWbA{LW+SwW^A?u248pAHrM))hZm2sRW^`wx;{v;Fb{h^AdtfPV z*ssXYQ^S?u3ZN=dp}^Vr9Hi@-$d;nna`%$FgyUebj7qz~;;GPimnLC_em?Y~522>a zDHs1#AH$g3_gQ?;edzUdYuvROlv*E49v3(CS)W+hwHaWtW291pF6Dgc1uGSfx4k!oR@>A2z*9cr95-dHO&ilB!70*ZDG}4zQ0=;`%1U(D_@Hk zmQ%4RCWfzHbvw|*RjHU2je^^Dw?z|Z5n(7Vy0_cTQI6Zw26Sar-bKfqh0Vo%P(q`? z;C?`U2gB-Fx%m(SWJ4yBT41)qMZcnCAoHc{Vd{NnyxyBa+el8d+#vM(70L*T^-#Iz z*X7^;++H*zMv+kb@BpzDajB7^AH`bOE22F|7h$Y%Jf@jk9~j;_2J&bhJ;8Y zB1m9YOR7ZQE$nRj#S@}AZKatYDzrxD1;>(oM)(7%EI->)MwEMon`^(Ii`bbr<|?yf zI+;_o))ck_oosnI1o-L8wZ6*~o42^dl>huD8(UgQzyPiC(Y%S=WH(u$;BV^tg8{0T z>J#Wia1E6Y0+nVwmy$SUJip*H+S8`3t=CduB8x5Vd!wi$Xa@973l!JpEy>SPOvzP?&tp`WPWrU2A#oEYgVq69PuO->G=VrSv{ zjn3ADlR=RWD*!Kf!b*rEfb}DU26d#VA=9+)>#MC)ea$U-LSuS0z(U*n{oEsVo@P=! zKY)4@7EN^AH2U4tpGN=+@W_U*;V}PS6t*sq#scu)t1mrQQFjwFoKdqgGFJQ%WIJ`f zsZD1KYo>4m#M ztZTb6wk)TMe`(4Z`h7=sVKL0^0P`)if2!-k9cxaz_(W>PB=gWwc*>g3SuCf2Xlh-H zoLzht2XkYs-~*S42%Md;!r$j9ro@kgua~5vuDGJ0k`r>#!}H}_LdV2|wZw@a;pEqQ zJ}ydP92A0IpPDNIg&Q?4+y?r(uTL<<3s7H%89m9_M(P0%j-?*N&3onfbgi+Pda*1@ zoX_`9;tA(fANtzAPPPP>q&-6`8n2+F;8eSV>eq&B@cen79k}#CRV8eW5n4c9j#eLQ zw~Av$mhEt zh9HgEZPcH|563n6k?9;#Y;Z#dQ0`TlvuFzOU#u4+Tr!H^wlJAYTq_)9?vcCUSLX=J z(i_|XMDGhg>=k*|@i5eVod{%lW6o=B!s)CrqF!vdgHfy$_qF)d^~Yk`p7lepNNRILt5$AyhRQdwh3l4C}3N+BMaN8eOJIu6z=A*E2WY`Uls#P#e`9VyL~-V@ zmg0XmYg|FUZVz?fo8~Pa_ z#R8+i3t~f?$qDoW^gq=oMOaqY8+IX1^nrfz(1$7)0SVvS8I<|Jl8OJ~%K;cK6m^Ky?Zxi*lp>STP0C(CwBk8O5Kzt zAm5zor^nwvWKIk}FA2Y7kL`{mO<)5Jug=;4N=`X?=O`VT8-Q#7P@-ESX=4X8DW*v7 z0nX36<>ETGoYROg6#uUXUIY&5FhC-2Ig6MO%ED&N@sCSO$QRu>#0UX43PU$h?nur8tvfkTL^dqgZ&qi zQ}6Et3Sv3oOQqTVkDGmL#Ukv2NkB`@IGMzuOPQgZ&1_+djAQ6|{b&DfVTGMYpWXZt zA6-QA_5~`wF}OgBWUU`l{7Y5h|Ja!JU_b#MjbygNXae2e%kVbC9|NwKLiiN~Yw_=D z2*}gj1Gwa-=vJQRpDEPb05%KqC5HvjbNPAiaRWD(`5ZJ(m1GqK3Z~D?ZBw#684ct+Kg+ zppGADy?NZOpFu=T0Nwl-jRm@YWz0zVP|Z*Xx9KNI?w0&dIsz!6r0M%Rq@Qj>d_pP- ztG}tg-&-T`GZmV2&3U}EKlQr$|3a_-`AEh8qRWxPY&ICfe=HnL>wnr%_0IX=I&n+*V){sT0K7^S&zIM{URxWu(yPGuq4 z&wo*ei7Yr|6l!&=4nv{8F95FShRvJJ<{xL+4Oo1WqAwZC?b|}{0+gmB6Sqo?Oa%%6 zUeDG$gD(N91iPc?T6X{4^f174!AGRGn+{ZClJEdYs*GYg5r*P30?!MO{c<-ZSoH1& zQjaBRymiR0>!e_hMxvSqOZ;`5S9@bB9&F>1vSHctWqGu*AzAT%F~zod%YvdmFp4si zADW0N9fp>vN`^AWWeAwPEE8eGt*J<%pwdtNY7Of1InLn(pvsN+K}KVabi`+(?cSNQM3IXTPAPS?2Iz5NF~c}IY0 zjTqcFc_>b0g6FH+Gl1&qcNeLXeq2VtDzB>O;bs)sjei1->B;68uzdt#SD*ghfhL|v zf~DF|+=dV-7bz|Bu;(Y(br=Aa5N`kO@LvkaeIo;u&Hq)Qxf6b>RYxp|{0;g5@cnnQ zd(9G{VNQjz=-3YESF|!c?X3}DA=RM+D$nf0O5+p*blod~R4GV((W!4+EIOqLss3hr z^a;p=4F3*g@;zCkj*?4!K){@RkAXd0iV}vVgM?Kqr;B%mzl;1Q^ZtJgTlOc%=4ane z+|PjR_)ZckbBluQp~&sXjNK9ok^ueNlmDA9`j71(_cz!?z1!t&07x*jnv2+CljIYU zJOKK_eEEwxNHh4~o(zDI1tDY@(PkAaHv2C=J&lV{ijFx!5NIpU;rWv4R|PDaa2wlC z{T_Lc0Do}HL*HF=;HeUVey+FVk3Jl^O+LL}#O`-h0vt5EkCdh3Zn-a#b|HC@gcane zYorIg#-C^d{PO+puXy#$JXn;mycj7}LJPx3nD@pd!<%e=I6dE|ysg5&MgP7ckU6T=BOE0OFJ^dNT3L5VD> zRPmn|##euO87zP{|D_=oV4+FX(YQaT3mSQSInXntI*iDowxU!_^;gA=A(dvp_qtn( z{I7xTT-U@GaTI(u|6AY!c67~GAoM=r)4#~b9Uw@?{A*M5YWeW@nzU|3SC;%NAqf!O zw5d+{J&>}kHV_+cp)C{r1H#-**_h4R;y`u^*VE?k*y#wGvBM2!LoST1XBhu3#|&C;jH~7o8qEJhvp;w7 zzrAI0ETwCx?Uq!Y28y#{h7-;!K$mE{nT&fd0FT2=7B1nZj299$A znY0V=fUMtbDheRP7!}q62KR{3AL0BHID2m-2))wYZnMGj|D6W~X6gU-_a?7e4X5~b zJ7ey#^%WzfZS4R5dx_80se(}1sWK*`umX&baoT}`>IHe36}JOpx#GUp(-HY zz!ja4aT?PSaKYfx97U}6`GSkpVDdAHarH{7%atgx+4dmZIf!lRUVWjy_hpdjNQMaS zJ>+o~sONEn8AaGz`t*(A^wiK$@tJfkL;piDF2_yP98MMC!@w971f5OQ7ek$P# z<^N}}i1*$Cd;ldos85MyU@+_Hw?qNK_qk-v(2JS&fp=JfoZrjl$R!I*ui#^`%{_#J zl8yCMdnAKW-Bpp5$7js#UEu}f*Kav4RiPU zU*TGu3Lp}>A6%HJ)>X%;b${U3H=xquPVw8qVHYL6Og(=Kp*Lq)^BNKnUO!(&W?Tw2XIO~yGl!Da5&A2A~PR6@VvI0u|?xET$FK96&7RnoU2x|;-%>Tzo|aJ8AhsY-}Jyp^yJH3a{M5yKkk@N z-erUeIJ&1$fG<3~fb`$Q|07ju-XyQS@htVhyAu75|Bg=l@oNcV%r3xcTGi^NiQvAM z_M8vqx)tZ`mP;Ufo>sAPW>0zc1c2_-E$<7D9g|zdLOFU*tt+jk2~Hu}RRcylM#M;e zSxO_0J2G5o7}a>zlqQ8~PQMACZBkwn|0I_AwZD>52I2K8y{6$O;d24|cl~O*MhK_L z1hQ}c$)nJHHiCciUhq*!!*~K0`@+fmKj59W`a2`xBZO{Vjz~Czp_jOpx9I{s4XzWI z?%31Q%uNcCOJjmlc^&B+K5#!+k0l_DVt<*#agcm*=1e zvRHgMmq8ftzNAV04?@G8!1hsMwl$P7vi92=5sp(tK2;3_urbSA#K2a1i2n%fRIXBX`%+^U zPduN3unwP`SIfs6UC-;NDg1a0#X>2c8_i>u!x;>S?KOBQ)MBj6GA6bYAQ)Mp+&X zosJt0Z<&;}ALuKI?FUu7g7Vbbq(ZEYjQvFxJVAE|QE$nowcA8}@H0o(^7#GxiDoCl zZ+iV!4$}Zk!&6>jzL%z*lRrEL3o#x>BR2k-l!-jCQovHh9 zUm~w55*sSvCr@9y*cnFiNBs3ZMa(kqE(X~&o=5Ya?+;t<%(Ypz2i*;VG0c{mlXz@Y zj2SQ$E$%wcon3llK4G1 zwaQFxccdB*?eC@ZfE=_^AYI~*f#oP zd!0}!e8Ku>oC~=2O`faa3d|98%f#X|J1k)GY?z9v#x5`?Jfl`cCt?O_`P@niwZnc= zJu{Opm;z7e_JGr5VxF#AsA+k${VUqDgm4Z89vC-9Y%0m|8+Ybvlx10Q*OYi)cmY>c zj%aQNlk|}Bn>x$=$;nPzGl_|OZbPbf=(iVZc3rHod0+PP?FFe)-RpTQ6-^G|8t+Q; zERD#)4Ca7-I7xFilPfhW9KkZzCRt5`vz!T0X6=L$|Z zm>6Q3RB|PTHM|+|REkBvKaJnq^I?T~c0_Mc2d7Eh(_d#h_?^hr*_r|zlkAgmb8BO$ zU*>2{oy!}4a>)IwpZv@mpH%a9A~B|@Bg^#&+YN!Acv>I&RsWfCHv3GEPb!=WfVw5i z&DUVgxF#7Q#|m@Ud7Ax;c0mAelxx|ZD35v+e(3e&B>r*;?BnFadQZ{Z5W$ooqnwpJ|$ zukpTd9k4!K2!Jk(&7GNP@8KKqtj>JXf7ND*6uwhpO0k(3jEDFx4jx52k)bw zp7LrypICtG{w2wXWP}x87sqL`*;m(<=robW#hKIA8e6nkifsU2SchtV(bqodo$|ME zyl=Rcf7VY#&wpRpH17`<_1@slZb(1;y4dR0nLPG84HTK%lS!*rjcF2)`^vkJy;*GL z%=iT(`zKOaJ15h`ok=lyJe=S|r&+F8_h(B<-T#i0`iIiTEXHP}2SD)|=~pP7b7(g9 zX|X$Y`pe5}u4AJ&#-Za#I<*m5bw3h%~~HYa%-?@>B~M)r^6+rCQM! zh)&J3+MV|M8UO}sAYfJ#6=S*<1$E0jN|O0&g2xLaf!awAZy_C%JQur1*_L)!D6L%j zQBi6^ru|9NRbs}Uswz$+A$l|4rkRTC(wI5D&Ro+8#!^KBZk3Q;)VrfT2e+Zd^oq5c zWf0$bs5GnP+{2QzDKp`OGxU=FHz^p^f{90?7&Vd~?hn0A``~l_=}ElVZkfkEMJ$oK zxxJyf>edXiwNMh#<+6Oow2?`xcwL*J~aS!|ueSTW@ z4hz4O+hOTzYpch{6W*;l!}3?x_Px=2R1w-IyXe!ccwM3t`&#D>0{|Ej&)dySzL+X=EN&uwdz?%C$u`w;cfsgLDSrKrW@81-3~^#kR|Wd_ z(%7k+52jSG8ZV&$HEBV{Rm-dKe>O)&ZeUJ9e&%-j3nkUhVhQW4?)uXyC4`>2QT(B8 zpmR%o`B_HHwdqr~y%6p!>ZRKFlLXGIss8{5^|M1OCxQ9a0YB&-O?A!EC~8jWPKQ_m z3xQJ?>vk`11ln`|vS0nePMSm@+@=x_9b(NDx5Qo^HzVOvBW5++?PO<=o5!VZOQv*p z^6j+jK@us6v~jhiCKSC95DY`rR8)(LnDoSbI6ptSuA~tQW*wESw+u;S7DejKIxu+j z64!*xgS%r8(aU>juM=6V4`uzbKPT{e9(|M8Tp3KaGSML`3$VT8lxj7&A@InzkOp39 zIbjekh49aZEk`3B&1u2?C(BPioow^S#68m&L?5N+;)M;{>(=@4gjLnCjC}Tb>)IX3 zAbOWk%Cv|VD&7cc&#y=#hJq7UkZh$LiXfRHMpQhG;*Tf6n-2-?QUzjKW%&ZmemooG zDc_&O>`XcImlS9~8Wx26!?=E(@`8}+ zgq?-ykn8lnAxC!;l0)4X9n^ZIE*`3%ByX=EkZ{i(dn z@|5ybS)x|dlf>Vw;W!=FZ6@-%Om>sn48)F>J5`&->v^B6FdJwGp2)jRPND%F@_dt5 zr&TIvm~&p6Ytl;_wF=LTQ25w=%QycNc#Tggo34+SbTeLN<=7NZkJD94#jvV$M{)Eg z3)>wP1kK&&>r|9a=W-u-es_TmkaFT>2ZK(I)gr~l67h^QUconnI2%@n*_g19_7U9+#WlZ1(W=l=dWCASJ zMtH&8TKdh^QnOu(XnS@rGCVBd62-?YC$NWpzZ}iDw&SL-c#9182vkE1*&p_ndO244 zJPs_4xw#!c&9V;4p`cEM?9j`7Ln)+-w!zrx=OSPP7l67-5Q*RH%CFeizlBO=tCBl`v#5Wf?Ed}Uly zRF-A)+uNL1+yVT~I)R?-hXuA;QlpE9DyEU{)$H|W)JeE<5Rse^`kyE|nK+{r4%h8B zNmddYI8HntQ$UjcNH7$o`@$6vYd7xNHz^YAzLOur_PmUp3N!=*dS8tGqP%=af5*-h zy*%N3PU8Hx9O@P5 zs`^3(7B`lEj~CS8$#QgX{H31xw@y4ZYBSO2KWnff{hmVPm`0B)SkHl6b@)M!_Nqa5 z&2IE=`E)&VylPuu1RRVlmS#B>Ki}a<#>rb6sqg> zrDwn;j?8K;Cd#EV9S1W*D|ts=Ei#WUiDjpbQ(|08h+hrj;M0^g%K z6E&G}Cxolh??i@cdLbA0xb7J2|C6V8Z`-c24m!gm)=)P~c51-ghtX4?Ii{WdWUvjono&n;B5j$yHhsyCo@ON_>z`*G~ZMc&k#_1ZGF9<4(7|q8Xe56gjOpl6jZg_Fy(| zm0J{L`Q#daVMEEOTydP`Td^4=8qyEpn6Bg{)1ia=12;SKWQ3Hg1lf$Bq}+N^c7fDh z+8t6zQZoAIdqSSRqLm;^g(A;HU{W)hAweRFXddRC&;`(f0+K4L<*rmKvI$ZD=5vFB zC-S+~WF#qrVyo&_s32NBHw$ds-sx7OTC|ce*f~JcFMbT+v9Hmpv=-HHBUtf3pB>*# ziZLLhsf~FysL8^jV+I%5{-1E*2snR+9#Mq zn=(aghDzTxo1)>D-HNrT>9=AeK_1>fW-xd31m=drg>xPbcr` zmZwgGdQP{?ENXi>*}I6ON8~C3Khp&hY0I z0q6<2mJ@G<+@Tqh4UdwRuExek`Tj5(|MbmWnPT9WlC^w-2y3vvzyBKm03wzPX@A$5 z0X4nqXH)@cm{l;P~F6REGTrAT=$ zwE4P!7FN!bMiO(Z@>*#`L+{y|0L(@PnpV*XPGP<&%5`cAg1Lkr*%8$6N6S|U{x!3|a!)NKv;^{IPf=d+yB7WSqOJ0#@^VTM8!tw;LXM^Od!gqt1Y;SQ=Gj zDar9peoJj_&Uvf1=*Pm-2*ueGP_p)2GK>h_DeEtnOhDoY9-T)(&kgld# z?!8w}&!BYlSLNhXb3z;F-m%ttDJg1W?3wiPBWMj5*7XCU`eyos^OT{E;W3r-$ zwh;g{dt&GHakg}jC5@R67YP7h;AIjyWFWVj`_$PcLIaCo4toc0Xwp8hC_8nMbna1&Mcg4Qtb&i!!eo+<3Vpp)spe9Xa z`BsW9>C!uJ5NTb6nJMB)veV#(&LQuzseF76Mla)#+`#$ceqrnKhH}1g--=i~-Sc42 z($MixVAE+nm43;45Z7KT?CxZpEpy3ojF1=`T}$x%xG2`bwfN1ov-V$5MC_#cCDVA~s9XJ%!N?JInu=1AFrD=xMi3l(UG()D9B!@K**#{jPZ3&NpOocH zMIX-JSC9Td)+g5=xq2}^4=tON%b2U$1GHQe=mz%*7my6*pHw}D&$=yB81fxexpHg$ z+A?ALOABxcdQMy;7c1$Z%E+&(KjY1GjG@jG$0F?vpmB}7K&_>G%SUQJH^*k! z-uaqYt8uvdFxl%QpbJBat@Dy`-o9jJZ2*mNt|XbZUJGG7Tr zAvJqc*UHap)Ya(Vz;4E*1`@5JGgkCgSHr`--&5%vumZ75Z1bDzMm5FZU3)7J9PJF; z%mW^UIL(fG?08z_Ra*Diik_1igV2r_7zC4nBw6Vk4B?+cbkcGZifuZwqItB%BqL;U zY=9l+K&Il3bkLG`O+T5QXLAxD^2YJZbTqv5v@xVP)2$j*s6f&Py30XOFF{%O(dG0Q zw0z7bZkrSXkjc?~EO@ol%bI^Ns20oNe1!T$Mi1Fgzt^2mU{j8s2C>L@+zt`&j#kB5+G( zbl!?SUOro8&-2}Mt%->kC`KLwjGUr?F707;;J?f3bylSiI+?H6*idS{I+Ph~@3y<3 z5S{viceASHiP$cvWX!Zw8%kWZbd_}SE;}#XZ3eTT|7uf@QdQ!mmram|y^K}Uw)>!P zkQt*}$|A<4>-q~zbU}cs5}=9~(PTEaeEZfEc=W$t+i_lx(`6;yP(iq~cb~0O0SFg~o&SXgTT4HA8-e}Le3J~@S}iBE`-jq{z4%p2dxekFC@|002Jl8;nnqybe4-W;vd1hqa4ycPnd6kRRigml)LA!#Zo4XK)>cv3a^aW_GMeQy~YbNUE zDn3rXA#lg0;W$hC*#SSXaJ}~hI?H**(rsk9{&0q)oAimi&-qRVRi1(9%;BuJ&7`oP zUV~@Q?v&>O>0&7V!Pm@5`eaXol~)JVpgGHI?0S8bvEkaw#Z>|iE~-hG9v@c{a%f_H zR}6S_TTg4UW}VICD$y(HDK8fvu1^drIhY0*x|~i6o-?_YCSKz0l3l@+IVk`D%;dlCD2B5 zgBda=`_I(6*z|N;Xf%Pd(T7J`^QjGZfR@P#o-4Dqo8{YElS$?)=Nd53m~?(kNyNHI zCBS^AM4Lo{HPi_pyC|qUfInji+z!n4Z3G&{XUBVGTMehO%-_)SPkVS{Y*^q~6;5+Po_-{*@kAIVS2XI|TGN!tMN5C)u*Ix9({diBC2RKa72-BW%IeRpXy5|{vz*jnmMaR> zl2uA19mdw`)aMmW>?U0IqDglce@zw9Ff3_P13~8+De-rc^$eom#QYPDGw$DMW4h6< zCis_n7AD1~$(c7}cFxV0N9Gz6XHB>-&oF17y!?n3%@GP zB4tfTmUW=b?gtD)r)2cAEdrs|CswbDP6nb8ESlv{Cm(tY9xOR8a9LINcDx_DNx{?F zhescN*g`1yERMQb1Singrh4(t<7zoA&r6Am3TSUB>lV}kjmayRYZy+dfD=+#$pdJT z-q6b>8SRH(vC5Z)+#B#$^>NSvVur_@HXi4b7R4GTa`IsMr@YWlt#R&H@+?7iw_?YS$k#L7Avx>gaxFnm#hFewiVLmJqUF~K)5 z>!)P-u}QWad3r+})j&Fd1K2VRp{G4N$01)t!>=8d4Y$*V z2i-d$1e{YIp7ujIDp$ZcnO<^Ef4i(>r_2|8jfsP*Ti>rSIm_h3EC79UX^C^`Phy>; z^ntW92BBD_mz^bPpiT$hTkImGNp|C%C^gXsuAV=5D)Y!Jk|*a6UEN)_MkOZ}0&g|z zRKJV;n(pp6!?Wr*n<8szTdZ0D+(=kNTq`6O)gvaCMh1Y}awm*s^VHeGP}f{$V{r8F ztby_IT*9G$wxjhqS#g0~fmkWH*AW}l0*3LrHYm4bxp^ujq?Q`N)pkK>d&!_~Wu=LhlTh`mNMs#ua=Io1(f z%^ab-NnIOpZvMcGuT@}scO*}x?8~&l{V`pS!q=R|h%A}=C1&e!;x;3$BqczA(K7y` z+;SpZ$G+?Fo$6})MFS8L%3ss<1Doc1hDiD`dM%h`f!%z23Fp1%Z(D(5g7wtA@yDAK z-EFZ$3`$w##;fEQl~k97zhALZhiB01)VXrh>4r4H{v|OF{ojarAc)|_$1&j+pueRk zSiLCT%}y6~sq4E8-6{k4ZYNDlmbV4&`~E|wR>PaT2;SJx2s{~)-n***J@W^>;u`Qv zHEe}-b4B8!PR3LW$`k9VRBCkYE1OJq>S}&J1`UwX(wI9+$n5aM=Tdh#k+6exU=(M% z+wG}YQi$~bS_#_LQd;RYHe2eUu-F(UI}cT8DGtg;&eF&Te<)D3$9mO4zt)AzkEfR` zKt8gvB>MD;H$<<2&tox4?Ll_DV^Wo85$wq_XqIpyFV^%f3`B-LA3BYJW{a_iCP^$y zbOkTHHf?%hpCeb~EmmNG~Uvx@}e=BEYrn8nDUx4V$Wv!N1S zAPS8Kgz9DOT*{g_FMF*)UDX8&b?1chfXmCZfi+skMRZvZ^4bZmFpCVOqZ}%L{hrZwmGru14eOgkJ^DBTO=Tm~L02 zff@ez@vK;7uRU$JiXYE$Sg`<`|46=FROt=P3R$MPen3?zz*a)NfIcuiYJC?_@G}4f z>7Vm*87?R38g)Ve*FthvqsWm>G#~YPV)uE)Yo5=g$(n3~B{#cr%8m z19hq667N=vN*m}hZvt2`F>0C&y@Rl?ebfBzBQvX#^ra>%O9ni;8*C*gRqMJukou|s z=tCr9cSqODcVqgxvo>nlINK~9eGgd4w3BeM!B=W`#BJC7z>X7(e z?DY#Gx>G3#%rdLql3}vu+b?!oc7;C<(&ZU|Dub}gZ8vxA5@Np=eEZ(=fd%c+V9DQ*}2-nn)sx)pBm=;dRcNtg*^96b$1WQ&X|Br5zvMgzifoxhWj!$O!V3c? zGBD5MUG-@|YL*mgRkrtqszp`yl+nQ5+<3SyMZ1;<>k~nfw%>7!U#)_2^ag^6je*5~B`G^Yz-zECDiRWxsmVv5kZ|Qxcn9UWDv8F^XAf^U=eX7w^5! zi$7Tnpc=?#p9ND?pxXTfuNkZ_G>EK%K|c8LOCDkVw+*T_2Wo#>P*j=?rj2tzL9>?+ z-~67YkXTN3YIg`D;5M$gpZ(zvq;=v0MS7r6z2I2VbnXE_mRS-ajpPGdCjztH!L3+%a6iPSxFW9boA14$W ztp>O>>Q9s!b5*?J6#uX>Z%%S4gLbuzK=J@zg=HmQdAY=m`lB*1Z8N`**9Lqtz?@Ev z0M5NkA+~>wkip?L3u1b}+uVsK!u}UE{CxRL#`ioj)Ha+HOor>elX-GKD22M6p}`JZ zCt-fl3^g8NWT2|`^K;7Z7B<&~YkFOqr>25$%?-DHaWuffe%M{R{Jq#C$!JR=x&KH(<2t6Y+c2Qg;~YBiIy83`~ZZ(&zlrP zd%&z$vffXBK`dc@C)go7n0EPdQceKOqk+YW`ysS5LnBvGD>~bz>#?O0{lj^xd+A@5 zlGf*Vk+nZf-^m}kU5zlAYkhH;JoblI1m0%$gzIS$u)*2AWhp%I<{B28>`pKV4(bR8 zMJDUjd9(hcD8I3&-kOWwW>xHml@80D)en|h9_ov zj=J_}X6fG$;o#H00aG%$kKqgh+7};BnDx+gmfK&O8R$pp6*$K3(p7Kp9!iRve8H7% zbiz)xKA+u1w7-l7{_g^fO@!Wfe(p%iE#oubIU*dvqWlrd6LtlxI0^E$ko9;$YFB7) z1ecs7?A`Le@}2s0jS+)f;88KTH$&17ejo3bivPp9G7uqE?`PAb3Yec_RnUFAs+WU;6+0yd>-%$!P3Bd+<8}~ zU=I*UFB#P(u*R=({yB&D>E7?L6{9bG`q8+;{8J9hm)D3yxaz;1=>-x+YIq^1teEim z5wEx5Wst(U!RxdYLv%d7G0H2wYgWNis7c5!5i48sUcM4-lR12pp-J{TKx}8H8FKwK zO!_hh+w7ZgMjm+2MbQ?fP$o*}txC{0sJiVES|4AJZnj{Kh0gu!s&?(a{{BSkKkOA{duadJ?(OdWLg?f zbeUd+@D!y08pFeJ#FgBSmGam27(GtIWE* ziuGq$cySBC54c96f@jcY$(D$QbhcW7rygwg`Oz;qO};xiUlfRq4>{HHO=xn_-3>@Q zha?+Hjjq4ppww+{myNsILio$<*Jl<>5JrW9&O{!FTy0FFLi4D-d)j!v%OjUTGm0!H2JWSSH%r$8qqmaMI-%o zM999zi|x=iRKSYm;Fx-Aw$!-Cpnt!1vnJ5=;Rmen%Yogy87T$Rj7}say3|zn-TS{} z5U>4f{rgNDt-`ay_2#`YV2)OnYDiaBDR9A}YP~v{n8kjX-Q!w4_R^^g zubo7xX&{KbQy|6i0b#l#IJ^^2DTUABU?RpMU(W`KSutHUOFgR!EuN|yd*r=?qYaVlG|Bn|G zE2y>(m?^hqOO+9vMYkxtZl!i|uUWkSEq|$wLYCl0Lx92jA28LBFHD z^n3h`E((4#^YurZPdt*k(B{wT_qPu;_XjWP4wCglzKRU{J*gY09^e25*;nEnd~O^B zgh0Xc8m(UVYmvth;E~SgPj+pgM$E+`T|+^|?ZGkf-j>5k1?mBcFsq!&B1ah&=k2IU ztALlqekZYwp8a`a1%`vETNEvph)pohhje2^Cog`2>dXz zS2tEup$y*XGu11LI=@&?#4f-6dbC3ji&mV72t(nev=8+oad`sqK8fZ82T=tfWoevu zw68I6-{rg!CVCxki*}j7U7!1-Q@uA3=Fwlivs z{O8`tPVUlc-Tpf{dn$+7@Z6X%76ZiKNJ#o>*`3-+T3D*=`Q4i-l*#JX?JS%f3X4P2 z8Ym-oFmeLv<(G#s-M_P2N=!)?DaNROw79Md)C)1oV}LE1rArQ!QaFC-l^0MqX%dr*h)5!kk0hUT^2m@%N{e? zHH`c!$#o7_PQ@l2^U5%gmL99@#$|D125mRfiTmZ`EFvNjU1iSsu;oK_f4qAEpXDAI z6Z=rB*`v1wL}KEeoU^X;!N+U2`P;xdYTrx0k>pJ5dwbpA5{xwZw%MV&9sVSS$GYjt zJQnTy>nRw&S8)B_mntEoNdgAFm<#e*N~PT$mPfPd?n2*~#r zJTk*BoZX{=R-uQlo#ksarf#@4DC)ox$at&zZs*vX&n3gFVxfUu@mu%4Jcy~#5v1IU zLY-7i`{d6+E{K{Zuj}D%EMPZm)iu=fzF!!ns2R-JDJGhA@Ekd?Avv7!@@_k5weU=K z`PejiaJ-YLHk&X+&m&K$$XnZZ{N8oO=~SJ{Q}9Rwf0Wp!t51+ez3yPXm2^=}+ohJq zQ{Y#|Btu85z?g4Mh1~VExDO_0pAioHzb>+qj-rZwO%yTzN*sbwgYm zxEjvqe=pYvm4o7Y4t^n~wEfg$__6Vvs;HEl-5?tCnXnxBLxq@R5sEX*hGY!*22s1s zQ_|b=F%Z$~-#lkmKja_M!dy&UI}z%Kbw_Wp+TAdao{jb&n})E*Jljw|!yr$rG@)&X zOg*m+t8Q-3q^Y%OcS|}UC?e(}Evr{+e6luutA)Yp+d){5;rZvIrRB;4cs6?eDrIp5 zzYe5M`YzR}>r{CqMQBBm;9lY)%&OO|f!stZG@^q?KE~~aFmC~|x!&6br1zGKH_s#; zC+qCl0FRnhOe;&FEPL3~^(-@XnDKQ_Z<+(!?^SPt7qK&RpyFL>egc_D@9unHJ2FL!YE? z%s&>)S)qCZedrdEfJ64&o@l1{k^hfFuWgX2kJ5fe9t@{S|Lz12f zUoEyJaouj@Mq|tO6Z}}X`t99yBq1N?BbuK}SUIy^Td%rZu6g5zJ~%A35G0U6otkh= zfs*bzywV$m&(=EHcvk=J)xlp{fGvs_ZUTv7aq+WnAd|_s zXQ8c!EzdB)H7;3U$}m7F5gfzZ}B+oI%gCDM65US+52klY}W*Hs^ow^y$FfMANhfL(( zesEs}(Kpy@6KliL>S<0njCf(bHyLe&_?%d2*PkIb6EbtJ9L~Q%(6M(!IWao#y5=%- zmpVe=h7e~;#~xS~qRC^ko-xk&sm=FAp)r+il_6`R0+{%r-LKv11_3- zT`H}5y2PW#=uYOatuM3!dqnGs;(* z6gj&GbF$0Os$XTT{DY_a-pnQZ-kgUYAPQ+228MYXbH5jJV!vy4^*FcellPhJ#7HI4 z1<`x&lwZ%#%EhaKSwBxxvUyaokm@|Xn2%pUw>IqBg&A^xgy3_Fcyp83V0miSNVt`Ih1Hn@Q`{m7lm z>(a&xbM1JjzYKZ>Yioj9rcwu`#kBu=E<=j(TAcsyxqK)PdKZ1*UDbWHc`YMEGwe@Y0tG(~#%Jq&y$l<Rvns3c z`X}=(9mag3tFxgeiRB+QuC=_0Ic%hErI@K}FXCA1be`(kCl*ChJb1OYh1OZiE%O$s z>2f#x%tWnCFY0{fy8XLth8S>%P+}s}*9iZUlP67?Q;@=d6J3z_$ZUvh=kg zht`57iwt4A??-&gZ%~%Vz>6bU?+VHm(+Q&W5`0{(u50Y>xvgvL`)%3_W<5POsq4N;a74 zPnoxW_#~yX#Rx@bm);k@2LIC zLx1_S2ktl&aZmi|&|{w;xIcL;8TKl-(^s*)GgY}`Gk~7HS(qd zqdzHVY?78m-D(R|c*z|kc^mTNaUhlGW2u}><$$?J@DHV2%nu!^@{$9;GH*r?WlGAI zKG1z9Nu?X!y^`rD!5Gh+nPa*7PO-?5fl;kp^Jcca@y%?Ssz?>7<5GX6Dr&+7M? z!qr2O%wmzLc;M%=JA>ZG5b4NLMT={55hRg>ldGaA4d1jC(Cd!vlp~_NGG@&UX zxsKOVa+L)%z=H~M0rtvnd2vrjS60%QGwrc>YV5J{qM1o^H5WfC7fQb7X-|Eig%Y=C z>`>tk58iI_t0+i3eA3d-|e(^rl}a-}<{98w-=#fAvN*hiEl zN%P#aNqL%66V&VR64mST6lL>tqh#|QE}G@3ZW3iC*mpA+u~fVrc~lQC(uvH#dbqJy*`6B#jJqB25> zdpW^D9I~9`!MeIwx7SBgp8(tvGGgwqXnxUUt@?R&ND2s1B_Kct@+f-m4^HqxOdiwYY|) zz^hCFQX3}EZ${4N%9hRNs`#r04AmGiF+M5Gb?U&(RI+#*!EBWylZ~0_aR2Ra^^FRd zXc!#kp!F7!nNq$s6pbgz`*sZV#(cJdf;92~-hgNxO4agUd_s})>hOK0;o;55C;U8$ zVp6N{behMK{UMIJYkT3dnWN)l#T}k)Cpws$lJEW<7e1f{=ET?JD<8Is*Z(An=^*ev z71TDyxXn=Ug5bIkze5uqIR!)yBPag~9S$`qJbKGNhIJmd6l9BjGtX#{Eo}R38drpL z8YRb1GB3uzEkm~ihj*r?w-nmQ=o1y`Gg%M~XJk>VN~+vRl~?-9A!~M?-ur6H%$fTA zb>f~Q4wZqd+3wlkd9tx-B)wMxgFK-m?8x4e0A6H;@{!# z=}~*3xDzWt2N6oF92`4!@|elfAiPJhPB$2WY_!4h!kG7)PGy?60>uF^1scV<}i zSjnV8ZrWYvWfY^D%H-gA*rr>S5dV{n6|^xCbh_|xXoo%_yz1(U#EsmUy{m98uQRTW z>cNdtfn_Qt^;453YiKeRh_Fl)DzD9ZCaqaR^OgDAO(Lvmk`RJD7;p?v`{Txz>H)&v zh+)a>=fGz%#aIt)x>TP3j>)KXkS~O61v_w3Ha`*5?4`A6(wQ6~E`Bje%yvF`+$MAd z&VgOvGq|%$>Qh7U{pd#4yBgudhnZwr0QGdJ7Uy~j?yp{a&Guq1VIY-XW*Ry68ayFg zGfhMcx!h+ji3lC6+-cZ3IHj=SK78l=d3Lkrg1BRT-|Ox`^31mY`=VC^>2-R@?IC!H zmd%_;xmIZJ?Hue(io1vte!*KdF8v5ItqrNeugeKr6n!v_P_P;>{b-VAy~1QEbPo19atr(VRCUnosy2O!Zn=8NLi8fnlykBHCN{>03RJDvBDdaj z?;(3-hy|!TbHxYKB;t=}mOPzmQRLYjN_xq11RWIb5*94h$z~+${tszy9uM{U{*RN8 zvXw-((P>dhitKBveM=>KvSrWC7+Weyma>*LyX@JwA!~@SOx73?!wd#v7zXpZN1gZQ zocHIP^E;o%_m6q>UoWrwzFybzd_J%1@f+u&%v(4bB&Q zCJkg66e*ERb``2zKR)*%^UicA9-A9b({g}3v2$j}XNX&M(|m|K`m78pRpH2t`<6Kx zyH*>`TQq>9?{tze$wqn9-P5jUxYgj`ALe(rQ+>;QOns|0*FH&wJSyFMZ@1c#j`u=Q zzd~i5DtYpwzL0{G-?Jl@1A=R%ncHRa?5fdW!UJ0LohS*oy6VWKq}^HV-5Nh>_UO2| zA}mX6L%vT4QY6gJNCN!wVj+W?>EM?M8RWTuDtfEh@ez97w_&UG#-<}7H2OlGNe1p- zy)uc-^5CMWduo2-HPm@a5#L%D5nudk*O86BQ=^sFgiMR#Z-jh={pRbN3M+^GcDn0h z$l6!%oB7Cr{J2KDFbuOK@()GKKwbO9%r+b4%rdm+_N=M##OCXKQh!e9Lj5Gl) z7#dLha$EL!OF%RKxFf$cce0-{ZAMwRD^6IT{(@n}tF@1A^SArEK!>z4RR5y|gH%jw zC`XhD2!A)AK&^LT-VzKk%81*}R6*md^HiEI(j!Q0;j+Nd?4Z^i768LuiPSX2`O2d`Ll&OH(Fz7nPxt8)dq z8Yp6OG)y)2^%dKGWiGLj)K`g;Zw_`I;F5CQ9|n7$`pU~}KYMhxP0Jyzffo$4GxH2u zx>t{DYDFmAe;xtR>=1F}WU7n?i%@jZWXVUFN~5!r{a+?Sm(JB}#pXp5RU!y3z9!#4 zA4K9x{L1F@!de&{D5%KiN#^5|Cy57sX0rU4J(TK~n@c`&`qmUvu$SylH+LviIpu?s+FS|{3s!yIji*_#7T^#0Opdu|~ z4A}rwu#A+TaJ%B}M~iba+f8(s+J+s8Bxftp)-!x;LF8l(Q;qBG>RD2u;{AidyKi08 zVb7|>=78^ubJ`WLtkraFEJ{Ls2Jri%sjJ9W=;uk?dFmEjaq=FyrR>mH|-#4!` z;)C3sIm@-&LN&Tg$l9+QSE2$6gB+TDuUJ_BQy4rR3TUCdt@bSd8hk`4b2XSR;eMy|Qo5XTZRr+ar|ZNN&)cWU!|bUuibq=%F5a)j`sn$8mgE+5 zD14=|QO?s|&RlH$ML*VAp`RIrov?KxUv0K`usDe1zGC~K>}$agdqqWtDe{y5`o5fY z!Q`vk7+*Mnpffz^S*TykvAgeuJW0>!>6&P1EZhy>am9Pm5;_RFG_6@j}?sM zt#!dwXjeBoA7c~g+*t@#Xrt7%X1~#`O$FJoJk_t}(c%~Dw`QZ!SViC7UTa;xJW@o8 z=v?L2GYBHFwuzE@?Q~*s+N0AYk_7DfXj=q1c7;Xo+vrO?i3-#A%8)f;OQL9N>vOa_ z_d)=D+FamSYIlVq%_4(>^Kw_#PK?$#sf`Neg41$GQd76lAE5h*UQ#ht?VT2NzbMW8 zlz^Ok*h5A>^yT?YP4bG%w!xh@a2<{~0IZ4hG+6M!jysy}+xt=%ze=eAYuerChu`^{ z+{kaL;yu_k>Hr||FiG!Ws*^)rafP2kwTE#lGyF+%`xO9kbz&Ls7MQz3w|8GI zc1p>@?_Bye5A$;X^mm2$t#F@_5*&=0@KT8{b2ys$xlEW{M~zlAenhywsOpomItt4qz5La>SOinF_nqF9sq`fQ-=mOwXNBbJ8ZcBNyjZ^i`U0<^1i819#=N?oSD> z<9r^yK#TX6L*h25kj=a){BTCU-8F&^awv!sBC8!w!O`A)W;EPcKw8_Ego|k+)||`D z^ZHIU)Av<4Rb-#IolxCztZ>d8I=&5&dC-Md3xpmGExi=49_a%E7t& zPB>MQsFi$fhb_LuI#z~-;OdhxUc5Q3WEg7mPP?Hg+IZgwh<{qYDX0lNWhHb|d-P)Q zEb{rI=)CoUofD;9;J}U# z-f-%UvK^f|YWHn=ofwa4?=?RO>Eg@?P5E03`}sW<#N6;mcYe|3+t#&Wr>TFyQbOpv zlo|lXz4g30WQY?NP&7GXCtjf*oVPcGk70e*q6x+% zKzeMT=DI|tMui~CumQkVyzD~vF4(kF_^KGgjlL7XJa1rOxXk1bzr;fA2J6P@<4IkM zDA-VdMarO*>P!?ku$_bM!V0kXE7NjgESJ6PlWI&8`-K6oGwscsSST`tZe^H27!>!E z6sZSFZ#Z{rc#h3JcS=v)z^%b{CK@9Bv^?Qr0dYRPGUePuLsZD_mlCYxw-OM5{>Tc- z+&{?j6hWgyg)z^1RnjUsD0yXkdOBPooG!xqNriu{P`Y40;YQV|&P+Os$H9!thhh7F z@d@q}KB1gXVbU8~T-cudJ+#=&S(-(%Wp?G{qf zz(*blkpTwv`zD;PFN!`Ajy1MOMl-ZIP!)G3k^0h>OzM^`mWr zIO*XAVkb9yf=GR^1PSwEl|9CFQ_9JE=?Y|(%k*vmDtk;?scxr^$F2ZRi!?09ro9Sr z@bSZ3P)f*OFS+Ga>yEwu!@0)cTT*~@il<4}dW&ADAt|yQ5IM~{+4GI{9H~79U(vA+ zHRTA!DR?V$y-D>V_Xq!5<_RoIbELB}%$sYqt>4K5r&X zQi{;h2unB9^8nEi@ypa0|6^(+9LW}t+4IBI`+hQGoeUz@16uIZoZ&XZNW&s{tngH< zgN#6hnKiLX4|(x^c>?E)Ro|2u&Rksw&qel}QjH)b_2P2e%)v*;^)3>KaaMxj_jhyw zwL0Ykw;tUUli1K1eVDSsJ|Wvf@bOcxDBY-4u=$RWL*l+?zbJaifpRHuD)AfO-Fbu7 zU;G^B;YKbFgWXkd+S&cSrNusW4>zpUoSbAE^m!{@(`opI6hitUZw`l`$Nhc<7^ovz{f{?lE_Mg3n`!v=D6!ZdykKjhkmhU2&RqH3mg)Ii^z;7poe|^Lg(M|_ozsX^ zU8f@+kbm+M(0oxtcj{uKK?G!3R_@Nwv@XkgA!epPdY*@Czx?EjYpH>W>J&e@@3{iQ z3#m10=HL0Td#OEsUQ_cc;*YS)&+=g@pGmL?+?@a^?$n<3D}d8BG__AhxyF8wgEv+6 z>)f>$UyhgAsA`Gg)g1E)#Z?t*mmIlUXb|RQO@+m-65r%G{sxEYC%gJC(K_%teCE)$ zZYT$caY=_QM)8WV-y6g>2*=lCrvKhPfP4!HzxG(!tmlNeL^ z(mGy7=29qfh6#0Cl3!DYK=1NOvo9s){;f5G*pf{Tf)5DF+H+y=ShtcmXbCpo z72m}IT-*hBNr#los$f~de=CaVhE_`Xu=tt5 zSZ3rVJx>IaPjbHA2N{Auk=P?-bga{Ee~Ck$2O!B|yJ}8CX}0ZmHhvtcD9~tM>byvM z&v021kFck5cUqyE$|i2AnL=**%AK7~xNLrF%5`%pR5&(HyO}1CLf@$VCdx?2Q8{UB z{+3GsnR;0G)n{+JjXS%MH>!~Vj7yQ!@=qduk>zQH)FFp5G})CV-K`seHw~n3nd2|w zi~N?I84jV|@NVf$J6lw$e;|o+m`u}gS6UKf5FqZ&K0ad@$?lQbGd;1@s*tNiZtrh0 zg^LisWT7+a5jDh1hN(Sh)J8As3@MZ*2+*w_&(ium3kf8_im@%UP_wt)y8YIlLO zZ%mT|dv?-cQMI=jUZ9I}gHDzl4ylgx^H?OwIiIfOX(wC{QW{(METC;YHq24y?%T~~ zm&wC6*6CNfH0a}?ZP?J6L|yu7#6X6cqP>2G&9%WFJ6Cj1p?Wa)ip5&SEA$2M$5brG zE(Sf9Pl#`D(?j6zZ3r27W}Fj6dGh4BfBVUW)!;Yer%n)WUP&#AIA|7f@2oLs^A}wi zN7j1cuFXS|+V(UY>LKH9df9m2uii35UX%k1V^%4J!TIZ~vH7U!+Xs1o4--|5Sjs7= zo}!8P>1|b9l=P%&Pl6!zM)_J;#=~!7RH@0w*E|$ybhNF#XL5?W3VotTI)0TPy zacZr(h~8m3m|H#_)F{f|D(lFpW(+dlDm+>G&%m8z5d!4l$%()qHU;MIhR2rKiQCOD z`AOmCV^o+ID^q;a)nTT;Y>Y;mLo2l>8{G31kiah`gn0IUyb-9eXHDrF}+`f%R z-c*XbigE%svB07yUDO&s`S-0r0;DJJ-=E}MczW+Wz+OY?sF3MwdHhR^Ru}i2lu#lg z;PGtsqHg3Iue_hv>Tj>0OqjkZy<~)pGKT`FNNpAAJU>%GJ}LbQxjMgBq<|B2c)%AW z0Z>q+>zf)-Ej+v!-@>!aCEoz51#NHYJCeu#=hb1C8KypO_q>J6ciNOZi~3IO#a}?* z1SohM>Q?)pWUQvsos=_QI87h%8y}gX$X_r4RMRy3|093-ws-PJBvR?LwYcNke`tWL znvj@L2x_|GE~h5uUGX6l6(+#kEYQ4|&EOe`Lc&~B+7c4$ibjvxzRh9N6OS269_I_7 z?}zf+EBdbYSI$2>&UTPDL+zT;pTk$Zl0nq(S^x?+_bZf5(IKfYHZ=J7I)+r{)Z{26 z0kCo2R;N}ku{={?p~6tzF`;4)e`W$a5dQ`6XyI*68t3E@SMb@n7}$Te@S@^V#s(Hs zyAK@c``h=+Y8B2J1M(i5ApN@I(kzq&4}Ho2FrxcYMi}J3Xzk9@EAl?RaN#kd$F)2P zl6sSd3bPq{nzi!Tzz|44vs;g8KBu1yETdF6SpxSpO11v{a{u!}qh-WaH=i})6^Bcq z64%kxd*^wBQX>-&Sx>RxXUTN{p82n994E(9JKryZefZ-`fy%%J`sC{s(%(7^jZjnd zN|2om(3N_Ly75tI1D%FS8HG6i^yu{d%PAuWf&Xo(r4dZ5dacc#d#`oxg=R9qzMNg& z`)n+o_{f#@d>ja;`q%d7*{uJqktQ5#hPSdzEVnK z#V^Ps{`bXsMo_Z~w2mo(+Gl$8d|5Ei33*_yIaDPVUy=J{`;Ouk{@OTyzr6R%6=rqa z;9{sS;yPa5S3#K*$cfwk+bnrx~PM1n;7*sNLOdL)Hrf0z6~tXuwX>(PNJj)BF#>4C^+LzjkH_a1%mhzhwP z`I3w3`R`(`L@XUhU_I2^q~mCCF*L#zG${v0hh;HEV2+ATIZF9x3Q z1i|HRAJaPQCj!PDwXkCVp%}7!_VSehisRMLDt>2`0;;lbY5qnc)u&%+L@KrCUR7qZ z5<0&=w~}kKBD&D=^Jb;aDQj`kzD>L~rabvv1-$uxyB;OkV_9DLm+V1aEhSX(SVWeJ zC4&IOPyaEZzm6@x8_|DzfIFNjf@>iyg(1MT(5J5M%XxfZjUq)e>jMWob&+lQVw8RV z-#zM|?e)JOWpP{NPzC>Y!+6T0cn%%n2}UE-lOuGUKKUhCf!aUs9U<9u@R8r)x|x_f_xsy+-u`lVCV4^AHWwAl;Zf+~hX@tOI14&ZYSP(syV zrJ0lA2VE(J^3PrImnIc*Pm8nloc{BY-`*!`{*?)CM_t_ga@3Pp_qR`z5N{L2~ zP;lQD`OkCBC|bOKX^v(Qm1YeXiVtzWdzdeUk~a56T0EmW_?I6X^aY{cPSF(NZDjIn z{V^4xSJOC$Y3L6T>7Q>7`APg$<(`p@pE)QjJO>^&+%GUZnL;G~Mfh6@v1F~Zk^tfF zm-{5|l7RahE4SnLe|MkPri5x+xVMkVHT>^jC;0gV@5TMRi0m{ZFTWkKWDD*v_p9`a$g8Q*< z)9R>ozYT$Bv<9Dgw(ZVxr#O)@9Pi2>@G|*$oCmmR&eNs){s1$4ZIV+}OM@yu~ zUo6G(kakyqk8&sQ7k)u}o5!B?-8uRdO@+}((l2e#{DWuwYrN`r&p6U|B_IFOK8oJy zgb#tb9yueRL$8p4v!)_!QAa^t1iDh~jk92I2W#0RWMPVEJ9-xeCz7DR(BK$n;r$2Bn z-3edpEsvXaHrZ+~*(C8CiYlT;c1K)g6*#uU175~*#iB8)J3&Ga#Q{2{39TOh`6e*x zFpw1{yl6T0*>rc6!xF~CE&iqATq4IlmbpJfpmgQ~m*f>M{UjGa^8BX=#PuYS>kM=` z;QG?gPc15KU2ye*nfH{Grmjh2@)LQM2vL;tVioiGPWJ)GsaM}(mosBmcb;qXoS};~ z+oxYF=4G6Tzf7}IOOjJniY|)3tv7$=ezmO_)Uh++xE-^i9BGqJ?)%+$mwYwb;F=OR zFRdhcDtFh1Of9}vJSaJsc76lNIskJp%Vd|Riw(fdN zb(fvkzsi=xYFvLir>>BNZq*xDa@u{o$fh_>LVr#Z^I?;rFGkQu#7|<(8x#_zdink+ z%sij(Zt%g68ma3|R}|d$$7JrWIk5jEbC=tmcjwBbqP=$70hp|#QjzW9du5^zSRC=0 z;P>FogN|@2WPMPv`c)*r=mr2HoCX{0jMMLUlX*n1fFh2AuEEdi7d3p5Q zlvfYXzNwlEG*Bwtlvd9i2oi@uw53n+s35CI) z9JuETuB-dNLPzT#-}tXbah1^lF4OJ)=}OPTGgV{q&Zi7)>l@do>l?r~ zyQ0xn2j4w5x`a20_nQ$K-BjX$HoAGui!gY>-KNnt?xMbf52Z`zr7G~%^<72vLW|WV z0b5L!<4UL1c#|)T`xw8iSZrFe(e@nz#7iqkq(5yd?8`y(o#gL%S;0aeytct!rE(vz z+Q0r|>fe_Lt|9Kuh2DI<_-6Uinfv0|r(C-eT>ORl!S%AMo?UsRF_IAZIZ4Uin=%q52)Z`R0;0C{#Q@3cWti{0PS3L?B_Ycq>blm!ZyF-{WkEtN~VXz+L$Rm!O)j2_L4F|S675XQWSk@GC z4T}UH0ertlRlswc{GyR zB3gc3MAz>ZF=%mw?_@QnHOQMtEFOCd=w_$s1Hi_8IcP7U%(ea{v|{~vL{hA~&q&j` zM0CTw?d5p@>Wr-Q{m94PZo;W=St#Smc1Tg_XQVOA;5!iqAMBvtV$X{4 z8S|kbrQJgK3otE-+&5TY2u6O{tRZ!^`XWzUf3!_p0Ygnhw!o?n8FxX*H5*>1f(_4YC2krHQ+xz>;$pkqcL=TnNdX)7Lpanr2x`vcd8 zK$ICWkJS(kos#UEQxJlQ+c5eK=bBiB$xx^fn zhA#%xNH9_7_~7*_$XWojnx0~9pAos`3pVTQTLy~Fw01t9SK)H^#?9Kf+N00keOcJB z3mvU=GVOFMrNw~FgsEUP${W?#3pOOa($UA?oZI_QyX#;rPByf;XvLBSiK|BQjm6&z z=Xu+Cr_M3*PY3arK-2HpyVzN`=jY_T8f(_&mWO}Fz1AugR|_{bC|I%ZgRST06LD2g zG;BZ?>edE-o59C4luhhB4n6te%h99r8@F-81)ld73nofZ+BAF;lD(j?DU*?)=d#xk z>d>%bg%eSCedZTTE9MVzNn44G%RIg$NBDBopl;n9MN%GW7y~D=r2Z<&w{e5XI^~tW zjd;O0p&sYaV^S5!cU(Gl$>-4lIhlEPRK-HdCEsujyEr5FD5rHpchAo!f_p;*hTc

+saTSg$lNEX(4XKbW*L z2gZ81EuiLaDzu~7b2e}&)8ice!V$bOgB|L1R;hnF_P>O$|8wk@o<3KR@@h0=;``aY zLF>)z%Jx#1@KlFY-ms72GAHzfsM!*i4EaexS9LoeUG-9759x=3`JiV3 zFEK|7B05#j-kj=*+BfhXBSZ+TyGRQ&78oL=c06cL2D0a{Z$mUAR<*fVK5=YC{ zH@A`cZi_-2tV0x^_t98bafg!J*)R2$>veh*R4h-Y&PMp(F#FmFocJk+sk|KuxAcTY*BempMq4M+_~b%z#g*tBEsiX28nVHyWF^1cpyL zKOF({M6xxLr29_C8C?S_M^s=41BDGRj7ilM-Ba$4qs_suW5FgykL^S`0#cW4r_y08 zcKDbbYCGOM9c)e**%~rk_JM(jc%4NqW4K#fEB?||iNgq{^*`2B|6F&|1@~VPI>a)E zHTfyJI5wmIMI}cQWHOuT_udPia?=3d2~dLmIGDxxKriRM%H}H}y+T=``_+QDNc*KX z-4qV+r4X}ePA5r8PbNGIVUYN`KvOZv3|b>kR9%j;OZvd$x)LK{g-mgGq?4DwZ8IG| z9WL;EbI?3LLJ0_f&+~alyJ$+wY}SL0$(vmg{%=2O*q|74aJ#cC?W9OU(wCcTviErV zSHFd5Z06%Z+)Zq_qv$(asvA<-TiK&u)6UrB=}&TMm+D1#79_!XOz)8PX)A48x@=oM zaR9}1TaMIG*B-`c9&}{>4`uz0NF?+?dq5XRy4S8IX(wj3Q8r#s) z$*U7csj(Ig=?Eeq7bw~Yil|9ggU;@ z#7p)Am2+t^Yrny1>WhnQuY382q1b;e95Gb=G|C>FbUTq2cHIAIk&J#mD$VzZ5TX z-t@cjjO#u4XJ%pJ=U#b^@Hp{iO99qstQ`#Dku7Ma>nMdrk{Lfxh^L_iZV3v*# zNzU*o75g9Wz#5a!10xSs>C7o91-VaDbW4#u2dIs9)c6>D27N_VB+d1)4i--loo z>nG;JasZR6DzhbL4B?WMw)7dS(3P|DpZ8$q+OpSl$ij3j68Hn5^0T0Y2so^WQ;9W6i7qJ;G3kEj?|&`)72Bb&2QO-<-aR}!pP86+0fufOY-uVZEY z_g@cJcn;S+D-1Q(fYdl0|J{ikoOhvDH0eb#U$(%jrueld-O7yg@2No<5+EHUK<9Mt zEPDB7Y``EalkinyA|{}AKGh-Xk{yc|KJ5N*_ch!EJ+P9= zq=}CX;>E_9n9FNhK7zavaqF8H3tnQ1&(*PLH0Yt&ZX}GL%T?Ff{U&_^@E%)?c-JH> zkW+jhMvxwMcW|!i)6*jHV*b+Fl|7~aqtM-DStc9gts6VwDQ$EaNx=r$$yte_UM)|{ z+R?5T(~%qia?RqO$~s$~TNLrp7(MRX&I?A5`(=99cqE9~#Y%1zH#4V?mfH=0{bW(W z*87m45ypB3zPO#9Rn)L6J@R}kNWT;b$>#N0D5=nW!euI*x(hZ`os$>3m(N*G7&H_g zTfXM??~!R6uixzMzYC$yukNOa_@xWYuohu3lfR|KdGp-y=Oz4Ri4;sVhz7%$1)_Hd zn&g3(LwI))<0g!hVGzfn05z0mQqhD}Rg#KK=-@);$C+?#IOL~d2S|OI*VG@B_&pOd z)oB0{`0NF>1+-5vc4xJ|aK_h;(!SVvKm4reYmmiFd*u^k{l3T?nERyk!KVv!#=>s; zeekix?s)rB)Gzky0IU*CFY#XNS|p|hK;g5(?Aka`Ve9!j0?bN!wrV=2I>*C4tPD+^ zLr;>4?R(dS zMLWiTqMGlT1~n`AvH(r0Bh7}q;y(37>wwKZD}FcUeh4R*DrC?A7up_ot_}@3bVv5K z#zU6lavdcQyOiydw0RJ38Atf-VJM@*tk5@t&jWny(w6glGQcu)=kso2!^6=)Brw7L zU}n%aygeH$Ihk*iAxn*bcd-4v>f8>g#i~w7zA6RsAE~NpC zL9Hs_t>mcjxa-OFR@}j0HJZO2y&nlOst?4dhB0rf=k_zy{~=N+Otl@z=PRD=VUcCt zFVdc?b9(cEyT?%omLXkI0CCCVRD1!bD-bNhW>uvwV-hW6ZbJpA-q;K7#5cO~>BoB} zJP<);b|~Dr6TBOr^vbagLifvM7Nw-mT1pn6$UgnAHh9K*1ECZN3}Tlo$(Og$jM!9# z<<;j_I94Y6^koj6M=!f#NvrWYmJSJ(P;}nd%#J!HZo(j=?9;|o6i{?jh$jX>&l8hX z8s6?DRp%>K?r%=4y-mb!T)s+0fc2!XY2ya5FJJjenfHi{8Rd`eI&^}R36HNnlp5~U z&V`#SF=hcdQGyu1X_(_qp~G;onRvHkGB8@O>ZdDa7c5s;90tP(Au#PQj^~WW-^j{- zUYS=+@_*H6IB2-j5uqhVxU&VOPrecVepQk}+W&_$_-DJ7Ot-(E)Jd~dBceGelT&g& zlyE0Jq7w_iN)<7m+f4Ey*;-UcJdKB2z-C`;QAknStWc()UO^U&PX_k=G)iImi&dE) z&h+*Z>51fVs60x|7$*~jW~?Y!{N}Pj6TUd7n1tg(k z{ok#^0L~0s0%~&6!mF|gn{`+aG6#J@cZQxk8LZ}ft05YWw%CUpt8^+_YXIm$dqsb} zBv`eO83y+yonc{dfq?+vCxMBeXXK15V_<2TrGiF%2SEKA!`Yse!rR6S735(&%K1DYRn< zlhPN@xn_WfYwt!lCCP@5P5O9s`Iy-H%B_Mw<17@8rvo;k32NDrstEe|eP-jf=cemI+dg3*x= z#4d3=`M`ly-nY0tdMX>nVde6yX7~cAsEW;0xxw^x|9*BCd)8@i8K8?uQV5(^pMM0O z+|gRhV1XKCa(Gn5_p4QZI-?%{j8Mu5SSG${W{D zr_qyRk2jAg$|*b$V1MD};|l@^5;T6!;NLYI@aA3xGS)KcT2-aHCA@ZiCwAIIHXH9gcUEMP|)X523bluFD!{Vi~3kLc3S0yL-{5EHW9on61@p>ON+{!DG zu+xPcCRW%1h8(<|NE<%}G^%QBU29vLWJ}+-DEd`$n+~&?tRTP-R%9=MWY-Ox-FN?r zeL2CP$$C4Uya|}?k^Bu0+(ZG4L(CR=Ho=Mq(edLTLG5Dojd_JApPV9-dTD3Pfh-NS zoppe;*i3f_q^OUw{UExf_FVD>Wo8E)ATU}=JkC!aj)A?cQMl>&!@p})?tgWV7_ z9Dqxu`*5LW{0#pBj`CG6uBMa)A-dOqj^X?Dlsl2PO;Duql#qf+A=7{m1Wq8C&xyuw zYX?qn{pf1~z;~cuO<_hVh55IxNFG=F@D7*mP`;QYLmC_PCU#uzyj)lB`(b?|UavSQ zuUw;nuaW|u6tQWW0vYv~bM8X-EFla+4kIej4mwMH+O;38NN(1%#SyoL%FI{xEU|8% zbDlr3WC-v4?57EKzmj2Pc_%7Ni9Uo0kSeJM^SCIl*5-iq+iPGMjqr399PGS*C*yh1 z0R>M2E73S+>eK_E4SqXseDNFKLCh&E`@Uw;{Z1^z_1zVlH(s>>XjSDFwfdr*e2j9) zlu6ST4XY2PZn#UlOS>7`59XlGI3Q1~{(Cs&#K8hHTRM;ggn}gCrD%JW@oDGCPdrbz zSOGC*ku23A`{m|$kge1-JP5{_b?ezsbeJ{ku|7EzndTE^-Y=O@_(Qy2NM3(|>2o<@ z_~@VqfZ<{g9`FsRvDbFhK#vZNKF<_HD+xzl?#eEOQ^i|BI9?|?s~=TyF&hQ#J;opP zrD74a%Wv#l)@ew6^XIpls4%h<(gaPtHgAB`-`;A$q^LtE^N>QuX;h=ns(|*}Hxwdv zxN>XLkA?t4r0DS%Mxd~pRG3}AB@F%qf*N^90!5JHh-KGEV{s#25#hMCxbCP&%{5XLm%!O}N*_A+_S&dZ&GZgP z?@?Y8_a-nh@QAv#?lC7rlz9V4~#b$KYItQaD3jy3#oq14jUtFQg*we z(S9q^6AS})wLkgQZMD_fFOry$csYNQz^WysA~Xg~xbZ?#>t0mHA8aA4 z_{c#N$59AlU-=(W;Okl0H&ryZsSA?)S~#1c&>;et>@k2M?|Kf+QWglDH>vYl^?8n% z7HpfL*jxMh(zwhB-Pq%mRt_~b8!SK`l5D?z$V}`q{EYPnHVOKP))|kB+$f3izflYZ zVvpaEl^FhG?*Gs1CKr!tbJ+!1eypn+FZVJpQZeSH_c7NaA9Mk``Q}NV+QEmKr3t!J z?*5;8@@cWrhmEAFRjpwVxps>EKUU8o?qQO2qE^0^GDyN^@7$y^ufv-7}BJEmMm@XHjnR2pHgY zvZ7u3xji4k5I(-1{Z1OC)NTLS{Zz*-g|{uO^LEyQ0g+-iS&LRf_l%zX!9kfu1#xCKdad>Q{#Aamg+J zpj54aUT`uA-~>s`+5By2+MLpQCax>mFrx-P-x>M?;m@aUn*aNNpL;n_lyRk%=2+xK z?B~6R&#rXF*3_zF@)qShpRK4IdssMt5DTdBRE}b{mvS%$*Uey1F&~;3Fw*qZC+CHw zn(ppx7@$Qe#M{*qb72*DXHC7M+1xY@?TrzY8kRZZIX3tfx$j9mD{MKgB&LMKf?>p1 zoNEakHJArx$z2)c5NGTg>S6*Kj(TUc{5$82Y@7(;J1qc9Y<|gh-4`yf)1o&!I(k+; zRUX=u*C{!or_m#gI1KBm`er*=0w1HUlv!SRT~Xp{__MA84wZ!XlS3WwC!dsm;twQL z7uBleeAauv2SW;BkRNs9>kUN=Ekxl^Z9Rh`%zPDI=-T|z%df&3~b`bGhu!}|5_?A?~h!n?g_yD3*-hZ!U zZ^Tc)3xOswAyat7bmkK(0~^5jhnOKigel*e_MR`e+377CUc2OfD&4geGBge?DhR7q z6Cb0Te9tlo40ChvSg+ZJCM1bmtbFHrSCZBKG#0dB-mGJ<9jN}Fvv0(1ZhJo<;MlYx zJlFCjSdx86b#&TF`N8*v>jAy2Q+TKjtSU$X&G1<;_=@%Tx$MMiKwbGBtZ~w=hhmm4 zZ~JYo&e#BuxnilFia<$YGf)vpWAZ;Dug`(O?Af4kpUqUve=0;^bYXg0q*|aFHH|-r z9JvaXc-~#G_Ltf0nN_dTp8J!i`5z@@WxX_3oRfL>UZh^gIQX;nqcheZF%#}Lkq(gF`KRY*5t2wRw+bi~}l+JmfvwhZ>IHm>U(g zdfUGsd`z9Mce-wF@4=Sf3Wmfc3EQs1kMf9{iN_pXc&7D^wc@|YgHey^9Hsos1W!$% zgE8$Y2MhnsQCA4+73RYR^&3n9hkPSKcJ;sxK8374QlOW5k!cZ(tN`PgZUUK(>WF{L z`MWu$4Ss82Da>b^<3oO7!l3!>)UHWtibw&y+@pVBFBccDPlK@l}cO5d~_KOi1oXGNt8^ zVGDqe!VUGOGEqdnm96{Z$ymd-uHkpdzVdrKf3XY4O3Wr>;)v5Y)Yz<6>0FBIS0>M_ zg|YphAMo*Lnn_z1bXpMZEl3<&^1ehp;;jxd^}-fXxqyU9nvh{k^3#&?SduuK+T(yW z-vu?0v8xH9VXoiKfs2A*x$PAAhIqzPrbgK86l_GGds3#)P!sfSt-p8D(>&3l_B|{v zO%ik)e8#zRn_h;SHPb=oGvnsK+Vw23fv~qFgw1BW#=XU`jDBYWaF)GOt)Xliw;t;v zRqg^PZ(yBcKbREco>Ulp(euW$mKdZ7+6qXAG!=i??=+&TuUhH`NRytMFB1NN(;352G^8Ea4`e1H$^_Ed3HDWPk<{1-`T#sdfI;fj|@L6?6 zt|!t3%-0^ywq(nu^$rKh#0MR*9BkrX?KY9Ihdl?~df)BH@jnqw|E#Ti+sI9$;?;Np z$9dE`T%%T1L;@oXTFS1T$?g?Dl4aJvM~Z{-NLIq%6k%dz%^dn|MJx5iarvYcQHyDz zPWQQ_5MBpqk8A*6xGicq`5=jUMu?7<28vv&TO!Wb)lSoa1qM5{vNI`qyn&}#L3y%Z z70kQT8ii}@!z`GBeC(|TV&%%cdT{LAs=ys9N1l=8HG1#leQ|wP8 zHu%~hvXR1nI+A~6uHO|^aqj$Rrx}#R{i@uqy!~Mwd}~Kbi}M+SSJOSJEq+R?9akHX z=>rk|jqzDhA>4!bCLJguG>!D->^{}J`ji#bU1v#3eUG@E1kILlq!ISzICuN0LD`Zr zn30v@?0=P-kjbqeFp*|tKMe)bT#t{<{Gj&>`-BFXzc{M4!3sh<7*ZCsyaSpYt&!O_ zipFh-F*JS$p|7^ZNkB6?Bcv-Wr*>E08pT}neVoLS%J*a2n|5ljB-FS@fdi;}?#T#N z`d;tuspg-lv%u4EjTcra2s5VcZi${(wl*%4uZ27Fi+!%z=MXI52)ZV8Oj$aK6<~K2 zaiIV#%&B|I#dqM_AM1*LW}oT!Skr?*yh7;G(Y~EV7QSie#@ZjdW(|T*2YmSy>5|^3 z9)QE{2Gp=S7L4u+0Tr^OGmFziS}lMR=8~x+*qjb4fS9}XNlB)^Nz%^Hgs+IATxz(I zKo=3OxWUY$z9DzzsTawn!m`U+fxbVRgS6^>0VT8ZR;8%#v52gCno_2w@O zKe8@5Gn|dYY>`ie8TLD(r*V~Le<~lZ*M8O)|2YT{)Joe~QlGnPX+M0_HFd*#=bI>& zzvo(_Wf}PUbTj#urDZ1@{-pN$N0A*tVc)ILXYK9Lh_ZpR6gwt*B$KcdCmBTPeIW0ZRp=>idw7QVXTv@ZCgNmkB zZ56=#KmV<*o6AicBsMG31lcM&zPU3I5a zT-E=fi>|5_tph2#&fN7=<9O-;k~Tx&6_sreefhGpBnVMbSA$0N5UZz~4sCay0AT8-UQ4`^SArI7*FZqYxlnn0U2`gNvVv5VTCo ze-OSmFqU7MYZ*-7ez|JJq^a}JJh)Zq77qV)(V4!S(_hk0n^i9r4rFXCWEU{NYzJYG zdee*l*`NM^f7Bal9B!MMiG((u$evL!3)c@-y?rU8=JT*UxcD2Ul1F^wvnSCEivM-- zfLT-Ua%NrG>ES)brC;v>U7V&KSTS$yeFXY|EbEF7ZU$0ePNXzOzAO5JXZmOILb=&K zKBdcMklWd!FZS_0`mum|0`0U=gH&*ntKBw8@spp`rwJCP_ zNxgDET_&*lKbuSOK0>mm?DemA6TH#ju1cWe&3&{6>mP6_J;Fi1?;m2?Je!cM;7vIIbf`Gps{Q7mkKjsTAyJ^0jV>;`SlQq9K}$2XFw=6`Pv zRD5xTpTYGnd)X71i#1AF6y-*5AWzWG?wNdN)8)}sYS3ue14(6006j(N)DcwFmm~K6 zw;V37?=haas)PqiaZAOQbf#?UA_T912K&857t~}ieg^zsj&Vz%%h#x+-+Pdm(2<{7 z-WJoc8Jbi+@y~~R@EbH#lzARh%AX*654v%k#)XA&QGz+W^Q)bpb5V2CZ|Dt#bo#L* zRK~^fN1d4_X-2*Ie8#;CS8O|G@}Kl$^0$zfg)O9kDt;h0EZS8wy8?YhIobm)p6Y>4 zetmWkArn;PCRudCU9ut7O}62LyM5maX_e|pbqp-k&BptTyUmECPECcax=~HJ?X__O zj_9R=gxee9w3$i?S;%w;QOvnaW6_%8as3b%9a8CB+PbxXY7w(FTigWiJ6&8j?aY*B z_dJ+X-h0|enj=~btYV7ukczvg7LA|#ScvYMq3>iL?-4ks=b?~NxG?dXP9di6Ng>9W z+PFK@`f7ESwOY+=Q>BYs$=os%E-2m4t9L9~rfA`Yr^(llr8h3_)-@!> zc~=cgzkZ1Kf^QM-meJC*3r*aTn?f9St!@Li&(Y`vs5be=yvmN# zk_ruTG`(XLdra5wT7c@v48}UbZ&R!Mabs0$X~9+BCPMi%qbJsudFyR@16MyMaYRKc z;cA{%$+pcnUX1IXHrhHGo!289U1c<0mCDHb|FQSpQB8K+yC{lS5am;mDxji*(u?$> zBA_22K}3)a0YNDdkWPpVl&&I0=|$-vAVg|JN`O$M*CMith)3I+4Q_OWs>udwtXpJ zd?CAN>f_#WGtlN#Ep+SCiGCq)g}W&^JGFHI@_mpQP^smpw;mNy1mFZ$dJ+@pA62+XM9-~;_?uGvM?l`Q2$prKtQ1li~6`@Z(o zS?(Ks9z^SYFr0GS^rf)*ep~Xy%I9X2J^AHBy-rxw5b{LJ_qE|-{5Sd#Yw-RVAiti# zfSaYgF%PKrJ~sopRJmDGoI-WB^R!8SwrTZqQv$dn+Z*%gwQ`UdxGSsN45)_H+2G>S z{u!WooWy`Sg*OJY7d$tc$F-K5fnsEJw&R3Of3{6;f$0sDhm39KTVwfbtDg7I-h<(u zr*DYD`c(AD83d0m(&i)|XbMvfndn9y3T2gYJb|f?l=8-8=odaW1GA*d&A?^q)!E=~ z`~Deln1mAp?mWMsCkqzElrWyt@B{;{)sEtVpVGguc;}@agx*FQ9O<&wzT_)P|DqzC z{@II@;b6sSkvzvvD*QJAI^S6WCg2!ehdA=YAC?MXcoB&ijgRF18m~`f zHk1))F*Nxg`}X4BI=P84X?;09*YUhuma+z_SKBvk62#qm)~~?1G&0P(@PE78;NUvUN>VtiQaE(DgNcg!?(Cp=;E z&$Zs8nD18dxTNRWGedVa8IgT(O_E0-+auc8s>6h$g9X1d)yv}ZJoh48=E-y^B_Oka zc8P$~H3VJSQR&LpkqO$#c0JVQ&-Kb06-XQR$mSe!4~t%@1N)E2 zhXWKxhYyf<`E8n%pA*Vbz3bNm9xXv?Bd`{0Lb= z{pb0An5yvo`R_`3`e-7-K~3H7vypepC+-g1N$xr5%T_Kbg*DBx+$*3qqDc5myT19v z#cmUe;S=L2rCSLCzrHn3I z`qR|YaJGi9o6&61%Pge0+>ZhIaqp3?KMo_-rX3&MVFfq0r0l_JK1F)2z48 zE(leCnGW9$>w{L4P+$%K=w;G09c)7Dn%KdVH{Bdy2*~ecLRV?%E4ZsWbM_STaDnqb zKFMwFhq9}D@d)~2g5oE1_$&qq)xKBiT2{cxW&5t|g6EO}PA((dOMCBhUKaBcZirL0 z)MsnwqksMI@ZSq^|2+KCUw(>v>p*I9<~v^A_Y}=>!D*{8UcO3~`%Yj%SpxR9chb&S&y>>G%N2*A_PNkm4Ma;7oCt;7U!cO>ze+_YpO`{ zOugTe;yLF^5h9q|6LQ}5(XM^q+}Fe|2>P(_rI`yroXFVDNO5|Jay|R7usCWF!*^$H zVuYyiP_lken_oX=2k9-nRF6P$OCMb;mOtq7iOf)&WgT{q9xwq1a+*!{a+Xm}ozwZjzczL5SE6AR;jy#d zLOl+gHobJDQrPy13$j7#=Pw2`tq53#N{h3jvuI_%Q2ike|y;W zmXjIF-Cm=W+cdNGITV@5y@Y}Cqpi!~uCi?{@=^}5qIz52_8_~u1^R{os8KkCa}^bV z3jt3&dn6eJwtix%%g+-+*V-W9)Il=*yU%k^QdRDh>LhNy;uWq6N&&WW!~f3 zjlQ-y!h7))dFAu1PpEQwc4-;;(~z$pSDYe=!Nc#qc*D3vW4qF*mPV7yVj;dnnPQ$? z-!q3WdQbmg?oGqFW$7OCPS+XoiWhK}e%(dhW$|mrSLv%-{ z{cbIcPX971=a@QU;KgIZo$x4fLLWdu@vnrQ0`l*vUtri!+ggqj+qvdzntf|k{DhMu zTt_d}Ukc$l9`pQK+(oL3f9-kjd`ED?y`$&7<4&AR28Y6gcl+FPk#j=c)^b8RIv{VO zR&g|J;}U94*zRT-;Y9pOQrx6;Z?jW935%_Dn z9^RWaeo#t5^8x&v3)@z=_uYI{gR^hLaAI&ZkCap*g_oq4D~E-3>67jKrVM|*TthX; zdAXvtJv`>gCO|%;hVEMC!VZWVEHr$9@y zK!5d zOE%Y~hudfzX0rH(paV}@GXj};^Ca(1p;j;`)2n)6;8>Ux-Pu@2{cXB$=dMHM*#hZn zaw|-ChtpU*QY5b_1!b~ujLZGJzF8*Nbmz*uF@osyBKN)6fY?5@i*+cgQi~%B+_FI* zGn9VwX+;=l-_Yq(g|aF6MY!>9!4@eghsgas8=PU2uj?8$4gZ|TMShelm5(HgRcV!m zpszO9Qb5o)nt2b(o$}N&>xSP4o?M+-`O?tgOU}e{Qhiqn22W~7klOnW<7Vr`3_~BE zA7|Crq65~8x$?lyqqDoo1|$J{28}%%(-bypSMsOVJ>s{W3zB?qgYn+j z{3Rf(BCu||ZH&8raDAbdX67SwA0TK5Y)3jTqqr`N-5w~nqrTopZEc5IWW#iQ7OTOqG*RXQ6n10Q?> zR;{|qvdVB^q;oy8#Tls}F;_RnvTE;9Blj?)Z(b+x*Uily(m`)%C7=2(_ag-Dd`2j$ zVYtq8w%AOLPz(AiA1Nd>^V)P@UQ6+qx=VZ>#SqTI^VN?x&KJuNW-GWTL0( zqwCbTgKjuFUIDQ}Gq2d#_27U47+NbPqO2iIU+I>6heqv_V4>9nFvtO(A3}4XV=Vp^Qn^>qm6bKNRnHUu; zkxWpGkbCddvd`{Xcgb%KKtcJC9QSbF#7ApOV}@&8g%{v?oi~-8U(nQrZw$=vg7Y7i z1WLcfrP0ya4LG9#BM486e8-vd0B5GHr}|mCVp)H%*xm4L{{;x!_O_eq+;AY_yUTxf z{8Fa>0#o2B*=OJ`FZJ%nUv2Y8Slnb!`I$~_5)l7;^KY4}dd~jfs&$!K(DM@ssnXkX1pGb+^8Z&W}>^!w}dVTL!yB}A- z6YNBP{+QMqx(i`yRzUuLFC2BHR(QTstgw*g-bl)mS$6o*9-{ef>yI1L zi}?uUL%MLPyLI7~-A-YgY3RO}gfkYT)1z$%HjQLl8!qFJJ z%}Hg$0j+cGMfr{&$MFk~ePdT=Z5T?qOoV>iEC4P6Vz-K@G#onmz*~JIQQd@ANeX%s z9?^)HC#2H$fLnKsWm29Ni#h}VLjE-F5E_#9=o?=A^XH}e0FwTO%Tz5vj3PGTHt#9< z4%2fSA`jO8<)z4tY2QF?FkyTF04oeTfrgAw&+~Yi9EHXt?fU^$=K(W@p)Ae^azWl~ zl}qsinz@OsBR1?}2H;Y6Qnl{L^Ur;IiElLO-u=7(jU1AWvibB*q0risKOl4q^uH0< zpRZ?r_A>ZN^@BM^1^z@XH*uC8AZ zO9A_O-^%?ymcjMAXz^XTkfiCDS8vrhlMBzOm$bxFgA*V4wJX*Ze(2;aB5QK9$g8(I zudUOtb9eh>Yr&&7T@i=z&z(2J)6J9C<}(o!+Jld}HMgp*=-1_V7izDQBNL(HNWhU1 z4H2>1n7@&)fBm_eGH8z7YxzW7USL+&gY5g!KL7Lr{EH%Q7Rs{OH{&e6Q7}awb*==+ zdP203v{ulFfZb^P^R4DL^BIsej3Kx;rD_i{bt718M#2kUnICe>TIa?UrWb8q-?^?Q zF3)iH{yzxx&4r)nU7r>O($hA&4axCl3B;~Twi4yvey#sh!lg^k{@UP5>ptbfWbwOf zaf^D^NX$u)Xm0!E=YI9|jYzzSY85$dB~#o41xaHqdD^D2-8{raQ7)fbzv%TOKHSV!6Dzo~Q~6jZJV#w=*11ODHYwSI zzr5_xlOXgpUe($7Rcui~@=trk1zrFCKr_$9*k9f^=3MM{(Ac5|AOb-|BDi}R6zME< zH!js?a5u3Mx>}jKZV%@@gUui-{>i+OnIFI)v~J;+wUrS$Cl4N)7?zF3*ff})X&y35 zTMwqJv?trYi*IT8{+fU%`O<5?S3 zL;QV9+pprk=o`RW{M5Gks_rj^qNQopk^XV%Vfe4FO7^`EjTL2Y z`l%(zZ_Ei0fbrT^U$0R*bin-#S)G{-Qi=O*#Gku=aH|`@$y+?(QYq`=x>D0gtKYrc z{mYtL1)~;enO56%Fscz9`0cA*`r$h_1EaWGOXd6blEKL2i}~kYk!XVJZR3T#W><}t zfS@wsD4D=Ox0`Dt8Q(-9-}&i=qm#*M?!3c?QprSW${sK~ywK=u57FX=uC)*V^#^Yw-q#(i5U9cYOu1=#T?S5S& z25O${s^c>9B=)swcKveszecy3m2Ba?1zL1NU+kyc>dW508`8`AO{0KT9pw8NrDN`i zQPJz)Z331+tPHRhdn!tM|4`T1go3Gx?2GO&HYOXHXNBg-FGdC!7!$tL_w23B_AdD5 z0z#r40l(SmfLHKs)aEt|@&c8(J-3b4F=LmP(*B~s9PH3PlI-`40#K3r+jssppWh7V zHwwSJUXq-2{~~4I|8h={@;_3Oc|CLbKQa}>?EN7}`Ec$(sye;??{g(k`};DE%v=@x zm)89+!-ie_uC79N@#nT&eM!gYu~>+8;IaESk+P9sY$j)D&06*IU0;_o!u+bz^Nd8i z6@)8QvKW74eCNn%VU?NYL0B0?&4gL%?CuRR;bw4__}ucrzIE7Udz66N2Xg*n&n_JQ z(dHi#gh2YHX_?%zz*{``shAs_Lhi=C5f!N%_yIOI@t2lc%&OXy>(7xrDhXr1xmPhr zM;zKi=l??*MDcHf<>79um)(uv@@|2aps>m-`#x@9Pn*!%U$d=KxpykxpJp!mmS+9)=Rdg?hOf{H5GgPQ zr9F9{|FrlIJJu#b22RBPRNA(6md5^9B$76Vio@p#-GQHMbt?G3AgPKZdkR;oHvQyJ z{|zPJ$)yA9g|mNWxkgw2DAaCZ^q(u>n>fy|dgo^7_)|gp|0)xw2Y`tO)ZC_khYax} zI)BMpH`~~M$-bKs=<6B96reu{FZY1+`RH9gIW0;vf8tG+#={NC>tgU6w# z@u1D%GH-;SjZfvqv>yB&Tu)-QEqH1t&HN+I_R+>I_IzAvw)n^lStn@Qnp}tiK+gHI zmxCqni|xzWqkL3v0~l`tk|OtCgdZDRuckJ9fvmmeWmLWW#m`nl#Op`B06_gRciJS| z{n)%7 zNY^*3G;h1Ax8L^LujY`pF15J2*W52WPVmQV zWurvDiP!wPE&mZ+!1}gkJ#5#8`bWjCf^$8;vcCUXsQ%Vkn?>uDlkGcL)`eV|-IrTI z6VV@?>6^8NUs)~yYk?;DU#+!CbI5Nv-~Uz7@N1{cCa&{yG2{OS93Y{5Z%g_!rUSqM zgV)J`Q!Cu?e=^{#E{~A`2i&0XYY1)PHUDG45$iB|2mlA%$@G6R;C%67Ap_1#HRrF^ z`kw+$H}7%TsWK%uh2#hPIH_)@ZnMBN<$|@P5Ms6h!;N<{YYpzWoJeMk&^gYwg_3xu z9%n7b8Qa90QWJ0O^Je}|oePVCca3+Z<F7N|_Giqw@v%Mq_T*6c|%=jK6~JcVNN!p1q-?ClnC8mLG3V@wy_@m-`o z(sD53E2*2SC*Ha!Z!h0l$Pm8lpfA676wo=81<|9Q7I%;aP|Xe_pn3MHA+3-s9b@7~ zMPswQ&33rP-H}M$;kx$71uM^FV|XB!bb7Wmo|mzeSKOaSGNF%vFS~SZpXCorpPAI` zJ^WsS$I&E-HuIj;Bwhm-jc7gDZsyCMcM%J7FO`ccCC#cv^A`?(8tWzXCCDQDGW%c+ zs_i{pL??Ad#87qnm)y$BM;URpX|KZu?v6U`Bn^nOnqHY$u4>2mTR@KTZk6M{%Z4dx ze5RtQFpWyMLacq!av+B){=CnX0mAy!nFy&}O@w=XT{o`rVN%!EMSlj5aQI}>p=^np(ebc=Ipurb-gQ;r z`@7O+5N<`UUHyXhT(x=E`_v zQT$)!q)8LYTwo5!fc$;it!hiG<{7o-$jo#183Zo(EkY{0%uC+MnU%P{ql#aDRj1^W zp_Ab(d*!}40io=>6Uc-OH%QN!h!Wp*awEjX@l{6={O>-0?6hns@=mS~#zBpZ0%<1> zn;!YIF-3bUM0@Wx_n}S)$}WGsBlo0F{WEN(f?1i7xZrD~4qVv^>_*u5AFdbc?(7mi1$$B63Ffhsz!uH6HReBWx?J!g-OHD{`Z? z<1>3RYX)y)4+Th^)`d;X#|MOZ$iX|Bpn@94Pyx}apRD8Ou`Gjh^2KbNAm&_+zgCWl zq+waUd4-4rRq!M|&HUYwwy~-$QhS40i+*O6``Zyl&x`P}ez}X!_ z`NNY$f3D?yH|)G$XR~AN3`d=&bg}OxQ=%&vbmQL94nM-z3V@bxSTsL~M^!-(kIZe0 zaurAHwRKu2+A{(RabJXU)*Y`M={}D(QA2Xx+O|^!IzxL z&9anlP)A z%2u{WYu9syzvUlY%fMp;lk2UqO7)<_n~16g_J3uPgdU|^7V{#l-hDR~f1myatBeKc z|HltW)5@*fQBpeBp}*Ch^{(8NSI()2xu$lXswT44XcPT{ZW9Vo?eu=q4D;0FRiK$~ zqB}uGkem^`34=+uTLYZv!S3TBhwFI*pY=!XUT~_cHe}0x+2xskwDQa9O`{}aCO-g= zH{ewzr&&5=B0)DYk-KE+fKd|KvO=o+hsLi>BtmP>vDXaz)O5}}zFV`o9CMMDd%v#0 zjNTmgHxF0Rcw0^m$S9Pr{*wtA?#!-5B4my@-Ru_SBl-a~=b5>Kmx)UuNdzg-cQx+7u+OV*AtE=0#}RK>%4Px#iiHVf_y)!4U%+zpCSP9MC^Y2CZe6tKqE`VUZAcD@e94E{YulJhWHXl<^q zi}INAyl=8x*RTo`?Y7F9C&_kTX_*jQlPjw%83nJiN=5zCL`sPfY$;elp?bssSh4vUcGp={XQl4k`=^3@ z0&Ckl-NZT)7V&lVfko0&OM?jv#*pD_SDxRnDD@P6X=!|CGJm8xME53vZLboW>orFb z(x$f0m9R*Oxb7jVA<*Kv79{8NcU~)fw<($7karBXwaTiVw8A!Ui!jtCe{w<5Rka|N zuR&mKp`v|mH8Qvd;=$mlYJ5!ufgRR0HxyreH=ev}ClSfhkbrKNLoB3^f3)YTmMxmK z>8#;S|Aa9-fv0O5#O^Z2CqPkQGPY|u{^Bg?jz8>%n-r@9gtdlqy0t#I?vS?yjib%7 z%?aOmoPWH9=G;q^`>Ggx7DC}Vw<;7*3fje{-ifv;9G||jZK`byKYn;7wg2hy+^~Cu zX_~?g9;#Wjar-->?RxfF0k64i1dk^)p1$cWJKQ)Xx^F&kqQvQ1&(#Q0>AX{mkFZF9 z@p#~ug)Fz|Nq>3jX}5`m>Ca2Z?%R)bD!ztiFhMU|wS2He9Dtf-;$^_CC=(5-B@0E7oa|qXX}= z9njZUew&4<-s{jmw`3r}^d;P|@VKsO zFB7>O9PEoy?M=ZVQ@w{c*5$fGC9`mhc_gCEv-r@(lzt5Uknk0nFYalp&`#DAr?`0i~1taOx?0kRKc{idJDqUyo-PaiVtbdz{^W) zxY5soo>}QF;0sF-2&}lgU=7ileF1-7?ZH9Cp^LNtG1evsYeGPNiDj2-Yga2# zgJu4nVsF-hcFPRwSJ}pMsut`ocZfdn$sC|gXh5waSZTU#1#X{63}?ofBvc=M*JY^5 zt@U{1tW|2qOT2~wCODAui2YUknV1x3lZ9%{QoH$dl3zATe)zfjo3Ir#^wSq^+Yp{x7BKDyjqG36~Wk3TGcpWVMiYVT~^Gk zH49}Poc9y1?*I~e8qKv47X5oR!7#*rh1ixZ$WY2 zD?j7q?m=T+9HPXqGFYz^CvNRlGUPZPYkRkXi|do(6``kS`A3!7=4+Cc>7m6-9hQ`J zp%F_*Y1#-yjcyf1&+&gZEv4ppdd#*!7(~0DxHJU1rwJ+2dKI`gAbYG*zY?BdAD!_Z z3SiB0;@MMY?}3WABv=*CQDBi2y+GhMv%7H3W5vM`6M1m(qIXJu4c?L)J?aBi1zBMb ztpBFCM@G>Drhv|1!W~3L3~Gz!bxhdp@{v|zGwhy!mf6bE6mw2zBa`1Ot81<)VNyLm zVe*{{LtaRlr?j; z8mwpM#p;VivRPYWaFm+_RqRxwrKm zv#*TCgd9u9EMQtqwe;?44vlno3=-PRNV!??m#;%uI}&oU+6cs6?u;WxLiN7rC#vz| z58KOUoPj|-tk~_kZ3qS}Ok+a~2Cd6`juYMwN@;LLHNv78aWh2(s$s*oXZH;S>^2j0 z6=iK;R`OMdePi_qnny;gP zYk$h@+3D=7nwNH1L#2nXcqvQ#F4dhXz2~bnH1h`MC1)h6Oggk>iq}}nto1We{Ep_o zw)I%`n%24E@uXO$K$^{1yVA&|EwapG|^?!+KL36(p5u)MTbE7}F@&I#fdp-Lp;#<-hi5dcUhT53jTs z_$ej*2)Zzq5BU*Bl#&Hp>%q?4Q1c{A$B>f^B+4fs$h?LDzF1_HGsa<{b$+_|9~+nX3+<7^e026hJ8`o{wFhSLuuw4JBDt5 zZFKWlFti_?Kc5bQpoj%0I6ZXs#Yo3q*i45n$QIm>l3vS!w93PZ(Ec%`r&z&bU~p2< zA;TyXp>)E$27#9@1|tGm+8+|8t#j%`Wp3iZfQ*%!2Jt^Ok8ak0{y1cJ^RzZyRr}f1 z1=sHZvc!x@3z(9(25TsostV1vme=>W2k2BEy86OizMjGdJ-GJkSvUONXhTBW9Ej^t8*$g$hG)zd|gKVcwy&AfaEbn*(KL!1(G=grWGU$T2|XrEulGwD=-jGr2CqX2-QacE*-V zDv!br?SEDIXE)ra#%7~&*zau@qsvbmCuls zEcj&=lfEM^U)5hmXwQ^|PgW0x^qYH3r*;mrzz$e1U~-;9Gjsw7b(pn)>P2l2^x%oO zm9QZ=1?gJ+=puMDs88-uK0s5yv#Wij>x{radd{~X!tmLpE29_{&j1ya> zPc!(4+2u&ZeInbDdAC@2#VYaOGV-boN9L^H`1SW~OHf@x9cpUaH)n(${@N*#GT)PE zjU}q*H5d>TEcrMeULy@--UF6kLSvaaVo?dRp8&eOCCIsQH%CoP!q zBpa)tI&mdl&R0l1HREcaVCalj0VB+A{_2e$!UTIa9AC5KTRC`3S6^Pg<5{Zdyi4v! z+#6ys6c#&S=2ATFM!UCP3(6K9 z7E>bz;UgGV%;43IE{=A!!4ctB?`{~&%}B+rm0adVwJ#IQ(pN$T1Do0vY-{$2nUUzM zLxbKA-gZ4}I8?q(BH5DUAo^ARweB2KwyFv?Zgo5__qt)BlaSI4xfvI`$GhG1ny@Cd za!X~=^te}eRH|3O;I^4U&H1H061Pr^$hJ;)GZ< zQ8gQ@QO=08>(|qaX4~gL==+;58G7dS(2lee+fiAG>Wr_>wB4ZbZhqd#!@b+4&>FTn zS-jZyzXUyvz-3s!3!3*Ug;F_IAVBPal%MfEw#x;3WON~$y9u+L3QfXjdYX}*80%fv zvx@In=@N!1GDV@;NrX>~vsq+Op_Kc?Yp%5=cmv%61C%d0mQR61YqeJTk?_f-*>Qx` z366eRjqZNk?m**^zntmE!j!`pr2s`tjEZH0a~+&X$$IBc+v~SH?meZ&SJPS`$zYb= zQ*hl++^uMZ7kP(Y>Pj9axJ&^ZY>io@o!7%hoHJHh^pnhIE~*hYGnP~DDB*Ih zWS1uNIo!Tp(0o*{l~AOP(z3~7XAYN+`|=u%U^@$A@0}PZT^+o>W;Q^lAxamhN8r^; z2%Ue1<>>->ut{T!FkrJ^eC1Pd(qPCMhf~ z+N72d76o09c;ISHztn5Pfqv!;P|7Y_u@;5YwaPY|LtQ2dK@caBjk9pe(1{OW*n<*T zMuefh!$%TV_J_cu(Z#(Pfr{@%Scpp2$X>_d{6a7;wUTY`HWja}3TV|;HJs)zbnL5h zg9hQWW@&J$m=^VHs(4$5w<)r6-&Wn231{cf6Em#OQgJiiIyE3GO@CUSJD53A;nk$3 zv4{8R6AgZR!WkyDC(pJ(GsnAJeXSpRuTKDf_bE<;sy(!l zT4oa^?7gULY#3I0)D0WR2I*9jy^?R{azna6->+yz&@2;emgIX(*WoJUMp3rDcB5@b zuHA9f)uxl0q|uVF!u%@yKr?L#B-xr_-+TclZ?*RWv#v2mi7yE_vG@K*l!oh5V?FfC zBZUXAu$yrnJrkPOYm+LlCbX*$cy@dMt8ypSj`P4!QrcnGngI4i$Mu?17(3{{GuUSk zcwwvOKKt)f7`UoVs3JA zL@qux6AI|Jon@n7MoydSc{WqoU84w0T^{v9@p=-(>gMp3IW^;@_a5tLewj-}W#Wn% zDw#rFv)Bqrt&{sX+RhVSNHGke)#qIMT!!oV+_U<4=d}zS{QES!>>dQ_QSms{y$6-W zhr>f(b|EAg8&Xo!L>s+T$pzE5FqcWE*7R3UkJ*dz1d?Cmp(fG0yLNmLc!RQK!kIj% zEH}q;ICVZP+(%~{iaphE35oVv4N2`B8uWLUQ^=I({CKws5{mYGG*^vh*qPWMC6g4~ zlXVoKx9Y$m5imE>3XvOr(m*wTnkXii83gB5bU6^}7|toLzpBbrDDTf2y#fd7Ax(h# zOhX)02Jr9r>9kLkv&r2s6dX1=Swftg-ti&vO2k&9%Uike5c}KoVwLC9GHF@hHspgN z=y~B5>+|Up3nlr?ULaRwtLAOD=E*`J)vZEwA3m;JZ46{jJsi)7Qj>weJqEwXLRH?=&$j!#eP6%MjDohkg_JN(TFJXA0y1$Do|&A2xq-HoqTP<+`Nuu*-Bx%`H75hMDtQ(wBE zLD(0Kdn6PjtMHyUowg|ZNu13xKs6_DqZ6%JhNM?>(GQDY z0e6W4AYgmlg2JHGK7|w6N~7jaI*$mwF^?7{p3}0~FPQ-%W#mK)+uOzSuc7QBCAMq~ zmPx+0GM6IO>C5X`g(76(o#JZZ!wJv)@IcyPTJb+5Y7*70`-VUi z#Y&1JHIYGqggP?&zCCt$*6&N$A-YQABuqrr>}!ljW|v1}$>SX(@_ibuO06Yf-J=b{ zi$%d}HjZ_WwJN?s+JsPPulRAXb4U!wjhZ=|R|6I(gMAJXwtqWtS+cKuQB$68nm(M{ zZADnHPr)n)PejqolZy)Jwz9-2 zU6my`d{sR{p?mN~o?QOyGeu@GR<&?68f=xAiSx3HIZA8{gT|m2fHeu`uVhndD56EM zHfv}L5UiOYT`P{d_2#9JAoWnnGy}U^dQ;e4D>Lg_Ui8`P`CWuzOBl;-X*1irTsV5d zk-C0*h@lPDyKr>cJ0!*W1~Fskx<$ew$WK^S{K#tgsCoIyuxExd-zP;j1Vr>^FCXf( z0(uzfUj|`_7i5=@Y-fSJzjdbvE57*YJ~1@N&BW&PTCF^Ph=*c3je|@1-;olHi+%QE zl%@IFK<@sVNM3~_dGeRq$A=LcxuO*mu=GBSynIue)pg%2)Y0JwDr!>cP zl+STDt0SZBK92g&`3Z{FP>F_g#YRMN@2fxPf7rNi+QN>dnu%Ab?TCWz~Ou_^YKU|5b;y7>tEB7)pyCi&A zybD%~l2UL|Y#Q*@aY0yE&EzYfYx0l=%lcE!`OW7$r(-8LS&0=!Yrx;hDrlSbP)M#f)`lsyI{AT8ln$Fn6m1D2 z^eF8}q(kWklCqv4=c{Wnl&g=$dV|O^NU6BI3f)9#>NeUweB=G7X6v(|snm;0jRsA& zHATJ7^R&#jETN3;Si2eZXC(w{yY6xIawkyBVD?kE^2XvI=4>cjY>85m}avhe_@+**TP{>RL;*C#Jw{YXWmuCO; z0<`QRiOqr3pS|VQeF6hdr0*Mvfcj1WntAqKci0^(O|RwIz*Qb+_aLdW?nCeFAClaJ zTE=9#4Oabmm-~j0#z}$DA+&kiJ-ID*4QU{lL=K!)KWZ4d)IDZQs6EsSGu)O`J$Uzv zHqHEPdD3`u12^vp%VY0TtaYqPmWnXT&OA#W&2??^G~*dl`}w;-PI9>7My@r`TI&XH zzlm!Y`;^BhUwnDnDrGl9psMV(;o5Z$RmD-fz61&0P5{gaduVq*|*h-;Z$-1Aob&o z%mFgDmY&EG2lHSPHvua})S0YRuXJoaqC{i`6vFA~TWA(SiwUPDw{&63+4u$;f+T%n zC^z{g$JY|VgS6j_xi)$oq9I2d|J|IkNV?#`CpL*q0;I7 zl8FQ2e8bf9>b*0hl^i~rdW8Y*7XD&c;JBGN=SPpA8F9PD;gHd3Gy5Jhd3bd3LaK~G zt1)O9+F!5K%-zxs%8{SV-GPQ391sii?ii$dU_S5SoJ(RTu0;f`e#!*w`b6&%xi`h+ zauv-rCS0b>?9HhqvX1C;nthSnInaUPlqb#X%}A4JYeeNR;s&${o^tkyk&d`5@=Xw4 z*jgz_4AmBWx0(K`LBXAbbLZ1do?M?bz1yqx*-oTgeh-y=aTkPKes1AAI=uIdsxKh$ zT@UzOuz8wVH`3Mp2+mLgbeJ+B%p7zMjSELFTb)9V)x(gPLm^$Dtl57FeNebh67Mb8 zqUF|rqYPA6kxC6G6^;UK71eAoqQ2Ws*;qo*6l`-fgMTZrz=BYj`E$!%I+MgE$~dUD z&C8)2^d!7s!Mw%z<`H}__lkT0t?S;=f`J1;r|6WM&6Cj5iN!ejVL_BjbjQf&u86yx zkWeN5mPkwZ+8OR*PVo`{=vcPth=nr`^MIj8Il*4%UKL4k0gGC1{lNoF5IO)&(vq1q zAXX#W4OWXkccjobjB>v~K5@*HCb%Zc5}d~^^Jf(=xoLSVd(Pt@{KX7nL$(W5n1|vxMhURw9eahbhJ$eT^?nrPhzT16F2O4}xs%AO6 zTg%{9@HpV>8LfyXwERRYYGT&|N%!fcW+kD8u#qDu%lyO46*Hq{0s8}xxV#x)>7biQ z2wV)uuBafg!XeK7jaVQCJh3;08>E$|gi~y|v1jGsPnGsp;hTDqt0$6z^d<}!x?4ri zO&(C1d2-=iWd8&wwuZN60$)IqGEGAF7{9jBV~!u(F3Ls}^IB%NtjoXMtq9nKKZ71C z?(;)-cjEK~ryg6S$8o1x_`9;mY@ zBpJ`EQ@COEs;<+!x3)Jbo!|73DNkm%IEf8vCwe1@y_%RC3wU+LwXPm9yz%oVa%f(YC2y}SFQ}Jz5*r6(=9{tSoT?M?}rOArk_`#QIW-s5B6#;fR)mp zl#E?&yTva}?EmZ}KgoBs&76$l{(>!Iea}t|GYuUBoC+y#)0;8y#CixDdc!>OY?2Il z5Q_NqNH7o8KCq6QiXLHaFu$_p9;rPlO+jpS=Oa$cD#=3K8p{*M>yE>kv#uii^tZ(+_mS6q}ITe$%8*q~- zrZZY))%F<^S^7&-m5|VGXXppSo6<&rVwGyz`wjqyfTQ6vOj{`}%9Se5&+_Dxt4O9KO5{8wsJc(_CWW zMC1pu=ev=UKWrgKDHCUOaCLA*rVOc)&Uy%$=x5%W;Z%^6nyKe04LY5uh^UdaU2n=? zM<1RI7rW(E&@*v2vdW zYqHf{rPuIqMp?Ma##6Ty=M0e^t5XoFBYC5B-jG4SFTa-{P%p(&Ca8p z9_bGf&wH?3{?;7?5i&FBh2*uvFd_`@_g}8Cc_>O$cF4-QmX=!N5 zqB{=4Lm-ix?B6!DYU#&A8W`G@Q;Gw<3VFdHs9@J1@)ig_I*|@ZnsPBs#xs5GqSZ&cFLbB6NqGuFndYgrpPF zgcr+P@mxTlOPzf5nA{*2;vv`&ez+~8u;1%6>F=hs4vxSE*}2j{Q@g^s{NYz_HAkWe z6`5Bg_(W(6$CqMHlREJ5CvN!%TiG<`kkSF?{DvVa$>WAMlg%C$yohAfNGKgxlxZfi zp80egSKjq-*E)^dXW)G%LA(#4tyoI1c8X3Gligjgb|ntISJUcT0=66bJvIxnL!mL8vPS9o zgI(Wqhgfb~4@n1%lOWVCM$LuQ^;8OPwnGIZRQCj0y8ZuQ?XBagz`C|!6#;1lrAx^H zNhLg#bf=^UNH<6~NC?v1B_$}`eL$sCy1V31(hc7}Ogzrq_xSlf@B5#>aXe?Ay;olA zT5CPGh$ht)xcs*4Qu?(WCB2keeaeK|qf(o(Iqo-BKH=0YrwLkgI~Ek(g3YL0i=}!N z=PCCup`}jCDGnVD9quz77Urkb88Wv>=__x0tYyszH)pVPmJXStA8gU-K3v8<7*Bm6 z?6GBz#eQ=60eN0pl4POkxf4=FNd3opkh-KVKU{8llV3SnQN&cOV82Qgi_${TOAI|p zocV423yfC9vjFsSc)RrgwyB!Y^!QPC>2~{!IRT7CWj==Ia|UezC>~nBalGeHBiq%Q z9?2Xq&$|{?nsG9Dm~o0s0839}OfYZQ$Bd6_6h2w3MA>Cg5tsBhURYnNK;O54?v>9@ zwkIR&SQGopr<@j`E0y0D)Hn&KW`Mf-a;K~ScC^;VSo}?vnPb;F_ze0Fg@OcRsBeD} zAAMGGPzLJV8lc|&hi|$Si_7>-RJX9Ps98bQ!_Q)Yt~UgF8RD0H_tA{wT;;Qh_Np44 z9LYR*p^_{XQR{5_!fxa_-{~rk?7a|`lRJ-imJddB9AmrPh?XO`2WrgFYc#q_MUh-_ z9o5#qO!J}w<9AzEGa$rz=tUnxg%Yxpay>o)i^{fyhkoTt+y%{*{Es|FGlCM;{c&aI zW08f(7^$q@S|_(7?U$mJ{R498mLaD)mVSl0#D=F$vMGTzUe7k|zh^PIX6@OpSw}Qo zknu4~7*=D~n{{QoT}aBiy}juUT3Xj2^BS3;3zbjWLbXRbq}^R zbAZ6Vp@(UXZV5fA{p>{YCXF$b#HQ9Np2DfedMKH85fv7<@?KKQ+WPsoo2Y#sK=m+4 z{=zM6MwV;lq;k?<7m$F_SSj4v#l@Xp$WO$iG0vy~8rEf6*T=DY<}y+1KhQWtp#dcO zu~Pt*isw${UUpF1i(SZtCh8Ow92G>TFNCWPcPbsg+XO<5SyC2J!OpT_zoc(zOoTc#Xjo2&aecTsRJ&V*86@q9eYGh`WYIBxWFamWf&*EQuH5BV$?+gmf6 ziznJ0*_DMKt#daOF#5*2N2Z5eGMg)zpwy9El1+rW{k`I??p7U+c9X{yoj?F=!r$O+ zxbZFZ+_Y9mOR^=W8Ep4QF0S@DJ0+*lSh6cFoM0XF*q$s*-^FRyU!PK0yh%4_4}gca z1`@UbEQ9)8EXV14BL|oNORc5NnUab)kHsUTGq|Ice8nR&125JnywAk zQx`2WO~*jK;n>{#USd`+JVKf~(y@E%HgmFOCZ{H3+4&-%9+vwpe#$ABr=Aor=X7yx z9@)zzLS@l&;UtUiE}18RpYH5-J@*$zPu{2)Pdl94FHEwxpsw_Yp^xG#?)@Y$QnSb6 zHoY1@Ijqh%Qvm?WzP3GiHvk4UoHa3-#D_zAYVz?XS!Q&rZQkH#+ntgvo&!eD=*(e- z`|iUGxS{M#WgHMAJ$$)92u_fC3hk~WZFlWF;+Sv@?C_Y_f!I#TF(qz6CYCbe>!^hb zC%UZI-L{td9=08-YzhFECugiT-rz$v|;Wz&v-nj|AOpfR@Cd{Lx^{UHJ4-cgC`=bAUN## zy3l9UmJjRHiBKn8I~5rNWd^+S#R9}H?8QqGMr+mFqdUo0>2 zWiS9{gED@UO?9FqFSQeo1c3ad86Cn29$$I1JkA_kCG*55G7}E> z?hLqr!q-PV`e8Xdj78K-ev1jsrktc(w|C>bGSSE3>{)I`Jz|fs>eGSCSJGY`oxqN)e?v<)sm=`D9J)eq6qj&4vSQ12Xq&+xu zZzozTpgA@_up<%F&^hb5$00PsI^!O5Q4bn!4Xm48USOVhcQ_e=m>H~BI777pWP>#~ zOAF}n^8b!!aw7E?&t&F`XY!Si0H)AIJSYVZY~mH7g6Iw0Jvyv}g_lZz@!;A$5BvZH z73xE)gwyNzMyK$`;r3ml-PC6XHRd+rDJw()T0v8I?k6USuKHG?I;S}pb_9`ew?)a^ z&8Srt-q_}qUTSpahrwY*1Y^eDVbU1>TEN>vw4A70dcS3=6sS5?W0Hd=3Wx>mjqlCk zd3CzlOT&?mH`}+uUAH<yDWis$tbwd2i}l!_5xIa?M>4%UunZZek4GAFN1TINM9f zE;(LFY`BAL-QVTknlwoyI03lYRx8pDhM-ra=_yMG%Bzo-Qkc#FI9BNqRzHCcTwI9- zR9`1HM;_E4z4Xs|05aPAkAwO^zaqt-jIfAc3%b@_aScE$aVms2Hq8*51&~+I*et4Hb(^#@_B|L;2RA1{jZNKGfd6Hy=x?uhsqi#Z*N#rLG#F zgCMrbA4;$WJ49`8qT7+oOz~AU96lWTSRFD((^40A8=lcT#vv4hMyvZ*It_i8Y@h8f z^q{AE4-jwWwr4@Ob~6L|f*Q**n~TLQA5GbZWn{h{Ps-Cgc31oYuO3V+2)dM8TerXy zJJ%%Pl$o=&3Xk2gEp`k$r@Z!^PDU-4P5ZHJ!DrBC3(SK`IMs;ffRwM~LVQq5*E`6& z8>oem;+m0aI>AT?WA){-sH0cc*`_jGqoFRFJf=A4upKhRf6^nn>8dxo65UzX?vF?~ z14_cH>KATNk@Ab-v@!MR4R4H}7>h4Nuu~&PCvkWLxlO^14?gTz>Dy-Q*7U;3`$UV5 z|I8kLGMvcP$e)=cRM^w2rdv*GSsYeY$jKg~Ml$CI%xSDnI=)|SVU5TP_dVA;(_>7% z$h@a}yYKH(=?27uq9Mb_j-eMI4&Hi7L-017QKj5JE&sf^>ryq{n zE;~-KB7{Lg02avRa#=x^<94d`L|#7>%j2=jcRxOJXQQs{{vw~WW2 zaF)&KnPEeiKbXLnXR_p`?}p*xGJ;{(w?9&NCTRajg{fz{bmwEaU6RYD6Kl2iYwj;l zlMvV@yjc|9FGh2O;MDJt=v%XQIIml%4+n$Fp{Afd zxDr(zaLjW7THLsns_G1+H3L7m%#Gn0uH}_$<{#s-!^y|fBwRWkOda#_0Hajmx`{=z!QrrGy= zN3wdy6%eSRyPvGQsIP4nqo;{#KU@R-w{+aqwA9E9&M(5) zMu9tKrHv7^F2@5@1GGszX??(8i=|}FnP@-m zj{P2c*_Zx#|5WagM3jV;Qk^yhOD2-l zS?5JM=`$aw1vDd1w;VaSR!5l*WWG8c2GAd(o5#~TDVKI7C#{oLzP%Xa7c~IA3`32T z4!s@*Lu-|q7jD!vPe=f9cT8E`Y(Q5`%Kmr*FJ!Uj<_@~S+)8eCvifQDm{RIgmYemP zt>RSPv_nfz*DYb9_|nx~nOXJlop%ggpC=Xz`QUA~FZz)zKa^ zOEXT@k-lds3;@=R=boP%@FSVh6_mL}AVR#b{;Z&kN$lXXqP^XUy#;`iX%4LYfG`{m zA2-2+w0KHCGqpc5_Rir=*;&i@0{1xsjR?FpSxQnl@!`;gLdB{!Oa-k59x7g{v%lp9L(e{Ejg9i53c9U7W45~f!z!WwUld~2 z>!kA!#czz}ii+10cuwwngg~ZR1wL}VNUgt{5cP^krm7b(4<~uK}Fv3 zP~9r{O+~|6gWBQ9cp-#w!n|B?#`z25x5Wa67{m)w611xuAs~Bm11I|zXF&bVSgzQQ zP2=ps88+7P1c*$P!1++$y%k!YbhbZ7o;@W28`xSq11G5)UKS74+CjN}pQfZT_F8&u z#B*d|e1}hkm^MEOJQ*^F+YVa~JIDEYD{k$aZ0HRG*OXsvqHyj=_Rp%m@!SDGdIlbq ze3Q`6YP-MfOnHNwF$$zFOT&TuwFdw_5v<1AX013%4?N6Avqmd`Zj8J*m@+~*16AlX zu8N#qxHYV4(0;_}e-3(+wuXrN(wvkHP-|M#0C$0SkBbEdpS2WaXF2_-VSeu<;OXLcPDrA z9CCl+ZE)LW`veuq`b6m-qCu8baiPmiJ1hQ+i06mw$#~TSdO5j~c;?gE^SOh2pRQki z`I8G!ogf>&MGEF1UAUcw07F zFO<_|eLA}o-hWM9X@5lo2KJ_^63)x%fDcP>nARE|0rdT_`u+YbAOuIMVB6nLeF6pK z?zf5`;ijJr#HcJaPpw_R0Q z&os(GBgn8v5Hce7Z$Hkc{>gy5{U|ORNgKfLg#00J>8gJSoD*C2Thls3eWnvF+a8Wn zXeuJ#Yl@l6Ml7x(&EAe=Dtz2D0-9&nHh7PqqA>w*H<9y?Z3D?()vz4meB+inV zT|mjBa{(%HTo7_xYce7VRk7I+sXUx^Idp8;tXUi1h?|ysC-md{|0HH9qYT!!5e3E7 z)XFVpS=CTC;nEQ6J0ukh_)8e~HA5TTb`tOPg5e+yq~GUMu+Z%qY`z@&R0DS* zvS@(9d&cvzP;p-dANKN^AFNkwo!@%o)@4w0#tTNg?tP~7^7_SHX1c3v zb4Yh-b5^9{&ZjP3oucYoKj&(gzzwQV)T18W#)}u_LB@wga;#(+P)$#5 zH$V}bYCXH$Ii5iuQcUID+FNhQZ3vCuY?O+fc~Q#?JM$`RxppwNvca|f!eyhJEo45Q zmbvN|g>7{A2KY9L(womemecy3yBF2;#A1sQ!`M`N}*l@T9y0p?+#*z^knc{+b} znyYdVM&hxz0;UusT2D|Q$4V)826I@_=crrDVuysj}a_EjccVww_Q?2w^Q9f z&23su94ho!A{t8%eE9tMl4?aOgn;WaeIgvlAHxgbV^BBD-!F+bNcdnmC0E2uKiL2u zl5pyA*0>IxAk*0t;dCf&aIkla>gizO#zx;S5~<73_%V|D*<3yQQY~kqN|321qLemF zkXdNWnNH$xulH6WW{e8pZ0%~iHgu08`=5cE_>2gkL@2VQyrFgSS*7F)CO7wl+XzqT zM&oVZWs{Y@M z3T>|GySMh0F#m7UwHxvN96&tt37KrNR^WW6lS%gfc3;v@9|YW*AF;JquUx}=N#}oV znfjRq|HqVgp<)Z$W=NTc>3^!QFk^0nBayE&_Q2=|{$I=h{&T+SPc-6cP&|qAw=^&) zo(as0AM|Z;O#0OsTXqQ|IK!{6=C@RHwFV9%JR*3nGE@~l+@!cUov?22sJGPnkT1`Q_|I*!vx=UVN1>PBPB9B> zH*0kL2Y(oX|C3(|iJ^?gB1yRMT(-UZch5ZY+1lvQN~W$lbHCSJhBxYe7rHNC9M$%V zvt`3ej#HTNiotF#hX;G>y3NZRE;U1JUrVr_!Xw6sei{?|-xh6qFXBhKqWjit*+~t2 zvlgj2X}pR(U)(DhVNWLCYSqob!&{~$&G>Ow#A_N5ssuVs?$swYl)8VBJA|H4@-kfs zR<;E-GcWq1t5br3*H43O&1uGn$@JFoVVcShzxX3uxk5FNqP%$`+x$$2pqIG*c!y6< zH0hH3GUNJHiubf1o!ITum*B#0R4N401zu^IdAlIy2uPbY59d{@kQ{^ z?PREDeNf>Cjk^hcPHp6F-N7Ew7@#a3_guzmy;>TT@vWLq&n>aJ8-aB{FFH_Zzy`b6Y@{j3!^3Q_agUt_cn*tK=>x5=slLTeS*z>!cDe) zuJX|7hT3dH2LpQphtHKOXW52^wYj+;8$2p&psSnhHVYovSRN@X8c%b$;t^pJujNKg zse&B%bG+rSxZ;nhNlD3+ptU)VE>egQZ_*XHk8e zUq$4Q9}jRTlMnJ|3VVuq2RA+e|LC=xtfi}`V~?AMx10kr%41{JSF??ysQXU4%khJa z8%2)Sd?2^>b0W}-h;9;r|Nk07;(R zKj{}4>PFt%23No48iIWDHJW}W0)6XA{|)j%Z|+X<0f>yy^9c*fwS%4a;IWJ2=ZEapZTRd5 z7k;CY#%QB9L=Hu=A@0!!3=^_sCqd?_`*#yrj4_E=93Llg+M}vNU$Sx4oJKKdu=3|z zo*&Mve@zoy2WX$}K(?&mvuqiC$(V=QmUY`mr%SO~*j-R;56X^YHdEY0c5_1YYHKQ& zrD&B=_@?rvU~|`#)2)V56)m^uK8Zc?Nb2ITQo~Zvi5arLHo|m2?V_7wrYJkrJ)t|9 zi^Jd$Hk3Q&k3(a&XQsK|O6H;0%e{-9_{7FQD*Fu@UJ1vHYvlRyO6qbje&GIP6OL@t z-hD21i^(=9n0D)99^rO0Aj?-AtK}Y_uU6{Y9skHrI*Bv9JC22deR`|@kd)%GdVjpZ zgHOHEg2d%$&QEvYX@x78ko%ke<(9`~=d|-0g9vXDw-c*+og>Rcu`Y7P=~*-?m~zxb zaIhFD+w$t^&IdAQkDWzv#%b#h)DM#>c`_z_X*!$;l;*G5dp|}%dVT%nHT-KxCCrTr zH#9|_C|m2)5~e=KG?Qn!O?oX2Q-Fu+otIpw3^v;xr=Z>-&TDBQe#qaiAzn$CcGI<6 zb_h4V(uM;7~yXF;G z3@T24g7*|c+YPd`Zcdxcy0;jZNs+#q3)R6zy zlgy>|#TTR89JGoN4`)f@9RMi{kjB=$JeaUFyEr?}b3Z=`I`v$87lVj~t5?PYjb_1Z zodbUvy80AL=AmlQ>u4q|&0M~Hm0ElA3b)e(A4o1)zxOrWmLP56K-{4Y28GO9L>v|` zf>bLdb1t`A$yny=B%-BVm-RyRd1mQmzs#v2)A!NQR-P>D_R>uJwnW z0h7bcIIAC}OGQ(WyZwRCX2Gq9r*VZrV3qd^F^hlyO_tH`Vg>aH%nCRXj%1UW^ev3# z#RzGb4;X@k2+eL3cmgT$aW>iJr(U41^*L!3g}(GY!O{ns5xdOsxvB3JpU1@wv-Zg) zadD$;pA)o1hmt@EEwgVb+0R1OpN!TK1eVq4dC7TP9IvRgM^G`W${gIKm3wVIRzkJv zv;HAFMduCbDjDO~<2Nlfd*Awk#Kwe}!rQ1mCn(2qSWJ#aTx^V&2Nu4~R$34uU$ecl zb?5%YdTDRM$4rVrhpp*uiCD&DMfQC``qkq=u{ksFspg`3-1+Zi4$}RuGgdD~WbO#L ztU^34&eogpw4`V?iIE=+uBHVocPFZE=6YOSpe*fT9d1sUj``9T)>v%jzfS4$0Y#EVyqC6e&fi*7B%1T}6nXa_I`rD}A^P{K*Rk>; z(Mh8PE!pk!YObUYv5b}(?_@Mgai}EFBB5a(lq05*PG*`=u746-16=>)ju z?fEXuo?@yGQZ1p!2Fit+JP7TQ^vRXx69y3R45bd&7flgj%ch0(G3AysDN6azmDK%| zU($?YYEW9&I&Ag8hV$v$pKR6bjshvSkoep`yjIw7QBy{jyq=~sM0pBG648s{7ke)o zFTws)lMN*ly9dof(K~x7>qGfP)Gx4&rJ8EK(f47Jw98=Kp>*CDEA{IuxREYZv#k4+ zes`k6oM=GO@4CrpJ56eweOicMsX=!p)M({xz&-kwi!S@{cMJzO^+pqp&aVXx1=oi2 z3C=ZKi_gf>g6mahg5)m2Y09v4!g@#`wl8^{_g(@;*11Qg7`7O0cEZQ)`2FRBq4;-*6G$$ zOHu*;_Y<5y+ff`ynXl}oF4mASu|&U1)fUPz>{xf=C$7(9<)B0 zOJ>sI6)~*2+)cd<>bx9jxM(JI{m%czQ97QLN>j8>4#iGB8x+jKNuF3!Y9`xeM9r&vtu#^A}dNuYHc?Y?;hn z6qILgV5b;V$y2>QM6*uD`RZx5#QLPYT^3*XvA?Ft=YH}2M;+#l=}EEjRG2S0#2#I_ zGVqS%Xg``e<8)QrRK#8c*9(fMKQxgU2@Ct+F%n!8KgNkQm7gx$5+KRMc`JJL37_AB z2i$B$Uk&(@hYjOOac7f(?1;~QKNX>-%;JL_5tuqj(;Jft877grY$2F)f%h9(nudCp zvsROl5wgkmd%r#UvX%1Ke1R>^eSb(r^5n7kc+?$#dO*%WNOh~M(ek8SY z*-4HM#PX5*nWMQ|&GBb6Cb1GHq6c;!M{~<n|EqlxE8aH4mRRxYtvrDr?XXsxu0b zAVWAN*RzQHVi?p*wA_!I^H3%#EmP-+9ZEO$hVGpT8F?Ix8NM%Box`-VgB%Y9$z^XZ zx@Q9w2=Uhx4JFktGreXhh(E+5_gO#Z2OH=m)%E~q7VYQ;h$7%u{}F%I>N-;fG5wQb zjbK@)$pBVj(%Id+X|}1_A#qJdi=jz`2Y9#kXQ`E(`tM|M=z@zEdXDe^c=YBA1P~P7 zva_7`wQbT>M%h;$sR&P?O||UQk8;Gl6>f^W3r>As(Y4 z=lDRTXfv_0=hKn`=NFqelsraR%=rqy`YUaGzL~7yIQK>&5(LWPsRJLi>4g|k(ikd) z$MT<-N9gTx(1lAjafUDZYl0>jKgz_DH1kzpU509^`crz;N9t{TAm)*&>vpSIthjIA z@wgtn`fMP?8^{YAEzYRmHCJLB&bYUwtXcN_#njGp5V=aLCo^Ti9>-cC(1Hky!x@i; zG#CghJ_X=0F%H4QO!WOhqD4Nda_-~CAi0&=yK>1Q!Gs^u%eE}R8iy(wpJ1U@(jV{l z=RRiqH691T+I6c7hXaVtUgha>3ysI(*P@1}ImjFz=%`7pHZC~5vv;g6LJ+}}VphB~wkkmFHVVukK zV9#c`>$h?~x0AB8YKcWm!pCiLqV>f_eGkMfQn;NS-Z_UIPYUgQWFkqs0IMr+=Ij@TES z;6VUOy=J9FG9^6R;uy>_-xeljGaLOX*Sg*U2B}b&vr!Bh*LqANlW4tM`V^|$8d99E zUdc)qxl!}(hmaVB^?sn#Yo=MW->ryej?U{=#JV8syu~JaHeR;CY%9Jv(pej#KPA~G z{C_0*^Uoyt*8UQjvZPIXE)g3WRk|G{mG|rky+TzErJ%!R4URyvGH#;z{X!V4+3YQG zKY!iqgz-75GPZvV@Bw1(O6KcJN#yT*|Nk4FzQb)r=%fW~GS61p}Y?X@vPw8d3y3OmHQW#-+~* zX0Iuv8R!O2CB~OwoRrV=8BpKlp9vpp)Y{+U3(>$LVwd{($mPIHkffA|%YHpokXa@_<-P&W3~!5ogx7&XQ_S#8 z|Bc+%KyJh1*!w!;1tBABvAqhZJo+j8zBmH)gKx4hth;PoUS-w|L6UPVlt<`6s(Pwi zYICuYRK;i9X$wi^8X7s+m{?#nz9CDWxdC17il=D*HddO=?<2980s+GiMeEZnJY^<2 z)t&l=H*|EoND1Y%=+fLjA>!pIm2LT9lF+pShZkRw;uzUejJJPZVKjflkIcOdmr1ir zB8v9@{x%3yjB4dt=ept_jXT4n_eZZ0673I_89x*E0}0@>e4UdEkTB}(g`pir5~T6k z!3G^kG-K_>$aRu$xpHB}e~XgGiIIs&k+=AQvs8C8K1`Up5%2r&IacFSMV22^GnkI* zBw7LTQIZJllwlkNwR{3I5+333W8^DerlxS`aEjm=xXJ#{Vws<)X9>ZBJk6=aq0xIV zT_TX2e`_}yE6IA^TqK|&YMmRbC{VA} z;BInn!-dADMkzv_YB1GxM?4>MzFQH+&ctKyo4iQw$?6>9bE=sv1b#9A7w+4>i*S5I>OhS=2CU)I46B zs^yp{(MLNyY`9D=(<=7*Wm%+aDX7APA`ezeHC0*4c12SMe)1F3LAx@TCNZy@+#Fi& z{xd9}^2cGlW2tt3Fi~^pMM9^U>$>r?2jgA7$Ra_pdXrP7saMjdybnQoVgNbvlq0iV z;B3c|QI1$M&;bZU>|zKRpQZ}KT>bg!p(LxxNP&4yA$E0pPYLyPAZfikhxm&y3-APM zBZY-H`c>K3FyQ`K2jwlnfAepA&oH=Zwzoc3DtR$PsezsfuGQo6+(AiW!-d|*dAiPt zil@zji^(e2{gFWOqTBaR$a&UF9ST|oyzKy@s0B#F80at6H5Ntw^$aojh|unQ>pHPV zs{Nl_fNt&)64r)2Nyh4o z$-Ru!H{RY<2Fh5FvQ#jfeYi?Fn4i+S$(ANVUj)3Rvhk@+UnR`0;6=46xG$aDlIC6z zuPL{9wtPlSOJPv2;KVdKwXZFtmQHAzpm{JT&d3wSqTg|sy1)c)V?<*>5T`YiOg1Ox zmt`k`Ij-5ybN98uG&a@d1djSbq=dD_sMgg@EQ!lTO$Xh-WfvwxP72SL@o!N8)pNn& z$fO`G70BT*pOi}I}Lc%r5)NqEqTV6xQ zhvQRIBXB;V<-s;f-WQC7LD=LL1!4^Ai;GjsgC4G}A^>cqf`pE3db-PxN-{2E2m?=@VG8ynZV>zaQT1##_necJp^ zw_%^8Kfb51B3j}F0HYWhML1I8Yg4!%1y*Ua7Zt2{l%_FeTv$Zkzi_~e(wpQnQlv!L zx8gCBaQ|waYoT4EpHpJHsvuqv`Djqfbz4}x#co8y@LMZN8q|D(UA!Px9eS$$#<|jB ziqhq`>i#M#-3q;SZ2P0{+A&5h2MKJZ66TNib8>T=8_sql5iqf*aul*8CXsS|YUs8S zEuq>VOVkA{XCnINWkxSj;&Nc)<+z&=)flo-yR09ZuCF5*BmMrnuc7N{ z|LFdMkqfGBy+Lkr>KI$2wVFv8rIWrP=oxWSJc&4-;o{FS-7}M=vBo&RBu)g^}t2@s%5Ik4QV>E-yy>@30XF zH+K+ov#O;ceN~9sz6-G@@$M1O+q&NuZ|O0dVQzbSBTZ&EGvbY;IF!>47F8~et7~?= zv!pPwI*{EuesQ!A+V34Y(x&lLK#^d;%+-2UMW)vt)KCrrn zQw}r5yS;o`{lOu>eXSq-K`AmMh#M`!{=~Z*pW-4pzG&>EZIzHQQ(1VXfgb4cX&+=R zhacRH=kfmMLj1vnJlwYe7xH(x7}WKVYE}cH;k`v{_@rdzZLgt`{{o9p{(BFLM^h(hhvEOt}5-5;A#jHp4_+25XzYW11|dUZ$B~L&pPohN+Uvu zSkWWSNtSSQSRd_sN1Ck9NbS=R%Vg<<_ogpHRMOne2QtT_USYQFOs|~B{OzTEhIAtP zwtZ&C7~re_GT5kA7kK(JdQctR6_yf&@0igdGrYx*FU2c zu22kC5*6Te#apl7uy{=Kg37xK9z~Zp%A5T=3hLtmnue9BxAyz97z5Ul=v5f=p%9|3 zP5<4DQx~bA&iC#1{@7HbV2ewbZHe%TaVp?eZdVM-aEH2V&o^)Pidg_07j8Wx6d9GO zfZ$|Rfa@Emun}1NC}b4}ip*;TwUm6AAQoN|-KWkU1&*d}IqC6G`rV0fBPq<;7vc z`vHarJ&A0l)a3*m7D zWewA52vv6I!&l+xlQy~$F~H25HJGAhT0C#6QVkl@+usodI{j$q&BWJqVYCkzSvb)~4)#iSr5rSa|Zm;D%#j==C;2y)&O+NZ;kEsQ27( zb}IBVo37XvR?c-M5j-crF(iUnYki{9*d@% z0~HuB_K1_}0w?-|7PQ(?&&tr^O8a$o^X!B6ncQ89@s88F-JVFmK`OdG(csab-7idO zlp#{WD>MjGP94A!aGDRn;qtjY#Y>+BcCw}K#JZe9Hv!IA5k*5!S9zPuE#r$B>Mut z>>QOARO+xQkdMwpX(>cJYAp*Me?n*Hjxa5x4sv{eqW>x~AD_zs4w3#H?EXEf26#6g z?+&7=o4LBNrXWs>P0tfQ4b5s))3J0m)4n~3^76bShF#8dy&EzOW%@a=VtpBv!$>9G zJ&Ko$-&9b{D@Wa!kHL$bDY^kv~-64QjKPRH@on(i0mU zU4fFO21%y+sB#cjP{+QNA>`P$seuC8Bz`_QyNjn>@6KwpislEq0pJbHzng;Mjan?D z#wdVMM}gX_jTC680VE>R8Kl9%JYD1=?RjdYWp11V$k=+(a@jRAZighf3RwY}6syXa zVt0l=D$z6WiWkD6>xsBKFu428$e$KgUrh*6A-9Iwtn>ttHoemzK*fD%lrvIlD4VZ! zB>l^_^|w%UdEYMxu(}pE=O@nCS>i7_U+P%A`K2-rmk(rBT*&&83z<-P&V)K_`&jnk z3~@B?w@^x|ci@^ED$Yq(>#T=(cM_AWo~?+wQttzLPwOoSCFqz71W%(fAh~maDtsRi z_3qnH&vESv|2Eku@4d$)E`?RIc@!k%JLznXde+bTcuILpi4 z6dr|I07F`jNM=P^kzWTW`NzwR${E5CLgvzJ+tvOcU49BkwwqD+F{OW)U+!`}P|<0}ShZS#(je(lmuZ+%^B zR{U80PXS%0OqAoOLQxCS*ntqM>8;c($+DL4m-%ZIJ}(=Nke<|norxvMpM%iF3=}kdcYB?* z6mjX5gFsD5kOf=8Eb&`{GX8*x(SDtYyamYP)Iv#lMgd%o;~(I$?9-;yi;TsUCes6q zZo?=@{|Lgn(i@uBYh0H(A~Cbd2K{srr}b-TZvQ%)D0w*0=ja>0w= z^0`$usx~Sn<|oQQ%2>@}I#Qqy9NeRQoc(BkD2*0ifO5`qH+IaANIE%AN!!h%8_+8- z_Zt3Nx*tQG0iRC~dC`-Qn~wX&Ok-D3bHx;ZkGZ&xA+fJ|8k>#QQ;d02&=l$KsuY88sZu`?!q+cd_*QDF(vnQQ)Bpn% z+o=;Fc61<4Q8OE2H4op|qw2_FXac{m3zy+}lcviC+X1*i$UW2QDFiI;+lgqham=5r z6N?lxtujaumGe|Ty_ZcTC3*%qO|+*L^V^y_ph%9DIgyQLeZ#ZUMqvgj%j*E}d6kt2 zY8DCRGf*C1>CYE{Dn9yADOU%20?J@!`)NNQi9au{kE2@1j~#;I`X=ujmcY5{E1Y0= z2^fFu%Y|G2w2{Uw+1CE`1Cpr&GWS^5&N<@VN7-GOx{yg(3` z@<#R?I+mA+WO(e0JnQL0D)$3$6+~xst(HIG50=X{1hv0a0&tK@kC9p?st8+fa6Vi1gANboh{v0YZfM|+bZaQBPW1?;& z3h-2k57|<`${5A_XD|TDt~}h@F+w?q8*W%|>dJ53h<*5^ZDq*6oCOR>wRV1+(ZG5w zhn$vzoqh!;5ei3eC9`|~1AcdYrPJ_iD^(kig-9v7525a1N+0Fa9t^JZs-g>!_&7`0 z@Po@`-MIdPb^Cce-}wE4{@zvrGMwBaiy{x;h)6|gn)o0n)BsK*dJ`_@E#1flEF(x( zW!4WH-)=v2*qqD*=&2g0~m)&u5}ZYSMN~8kNL8GL&K0YkU>9N*ccU_yBg+w!BC8b%;hL z3IEIFXt6GWIdT+M$p3*L%nA*E9Si`EQQLbU=}%AZeR~mN^0|!(Md;g|Bt1*jR@DDc za~xgssqfs0yzbO+MiUXw-t~%?%h+(T3^-N9DqQ}Noh-gUlH1;rF4NF{yqM?qpJ^T*>Sl9UNV9E%~|(i zd!(+<$+x}?L5ttIb_4&o@|p=VS7QoEhg5^}?SI9m46JT$k`1-knz+JZs|cK{7OrS& z&jcb8n0H*f&`$27BryW%|GQTrDORk}`S9)_qbF1$!3;5v<<|ad4Aonp-8hC{Y#oz? zBTA|8Su%r*bv!#tq72c$*O?)@k<5EpE!p>PRcm|AUVSwp=V*f>jtIZBE59YB-&6}g z2mX!=QW#is8K5R|+qvs`_}-huefD0;KVOcF%|!84@atvIo!1FP=mOXW=d#m=Z&2|9 z&I|PtR967yDwBi;J@HVko}C(2xAx4s5*A4CBJ44Nk9HxBg@nHMLnHY*z4sY>dvIb<|(anic*If2&7Abl&N)$PMzT ztcY6lHjrbHzD6$L1~TUzF_@(UJ4RcMwHA$vlH@4v`Pb?Q5*2hOFvY|*;a>GT9Xjdl zx3;96zZaS|+f)gV!YE6?O$hUNBAtfoEdx~Y@5CmE4hiYnyFp$4WHPD*$+<_4*GR>> z;qH{lUySI_bvcM;V! z<>HLR)$sLL;X+LMtCMuz?!RgSe?Z~cyIjIl1L1-yRBz-#M;@KYN}6Q}oOI^bl;IdA zpKqaXxS((x(brwv_{UW^JL=*!Wo-uK|5GT)B693)s~i^V!PiH=3v`odI_bz(u7dtV zEXMuKw_^#hqt zgghe@!hDiha1@pHDs*>Xeu%fPMP{;|2if{|;G)a6Y_crAloV#G1wn7eRo={3h^n8Dkuc`&LQtO}}cKSCaN>=0%b%*)j z(c^3P*%Zs>u1kZ3Snb4AY5jVwEvh$5J|-}C=&TEsrjJ-t;GECx_*|Q=?Dw7BeMrsNY1aqf?Cc`gPMCa zMg30?nv`$DRMUFS;wHUiR;6EqaOH2YJ5T-g&H2jNW3CRL6HwsPwV6v3^gCfazMl1Y z1%xQ^?Tf~AZdmy4p;4m!lrU`f&8RCo_1|d=ADTGj&2n3^=K>ou%)_Z=4u40H({bz_ zKLBYs_ln*766f>?9=7~VEjFbmUpqeJc2`;v)lS6Wz~D@NHp^Owc(Xy zNRRi^?bod=MO%v}=xOx#u077_R<=~rcWQ>m+05|@cRwEufBLNT)U@gNd)PqNK z&zu1z($JInrePC80zQuf(3J{_$fTek6GAQ}91$@jUoeuPSjzk%U`qe3wvqDO_4N_m z*#*dsjgu1e>*#O82*|wJegiM_D4NqQW5!+ZRJ@u}x};}kMfplf|GUvx6-mOOA~10! ztiHyxh-9i`D=W54ixN%!*X$5noI?U@wCJVPbT@oF-K^XM9e17F$19O#tvc~ljA@g`f1?7tjw#( zRd({hr5TqdzVChk*X`V+T0Riecp*Qy5?uex4~cFEB$J{6rfeu&qNyXss-lutR`tKa z{gNEI$+T?>3j=M4-|lm$;-tC=u!@T3JpP38#Jx!196#c%3HF_>OER3_kGZ#llXlTo zg3-TqACdSRDcC-G-Tl?Ls~}j`$1`g}rWpb(-ffuXd?)=F`QV+?`@@n!z(H%LUjM?& z=LD<_5|8*=Ggx-DnvK2o?}Xm33%Ryyg)Q0c0m*5SFmQoue_h~aHm}e{%sc9!u$Pia zFTFj|7sx;WFj)Vf6uTW%6=Ws~1`gJA-dXig>1$Bc=8k-%X>XYCcwW#UyJ*V63!o5z zDGcH)bzeYOnB6?hycFH`ARDF3|V@~LS! z?ouotXxdE)>ypQ&qv}#1A#bPzoCOjud@O`fB2z$^ytO}akZi!z;L_i(HL_Wsxut%> zUpgKGtF}|#?JrkXOQ~CFzMP~E-U!oo2esTSbr&q=puYDj4%GtA4P|RS{0B#?Xd2<> ztt%e}_i^lnxL*0zlx{Kg`DsIuz^@T|}4;#Y?g)W(^M#XL!$FmwNf6Tk-K= zR|fa}_zX%#3DqoCPJSaa0UpRr7E+`lj$!Z(G?`Cxh}_mW1d_$RbQV-8oM=2$uA}7I zUh;VM04nQtj!f^iofR>OnOvJq`Kaw?_C$@h9LI%a^~M5uCy)Vbkw>0U(9rEC%s0^W zw2rm@^GW}^^e`f&MdT~vifG(FCxvMWk zySZt8x2`BuD}p#dG30|A;d$g)84FCeVbeGY0F~!Gph)Aj?nl=nkEzlbEW9Lu!P5RQEfLy zQLX=CFn!g9*MAqS5IQop@#(^ufcF;X3=BnBzApXZ5AWSX{nD{0zW~@MF9s_wj0^t| z4^Z%z74wwiI2jG~IZ45}eEGy?Il>(*64^e8YTL4?1dN%CAy}CSPa9=cs_oS;*%>&} zdyaP-*5|K(yAncV3Niv0uY0pdq2~4>N(2@9@v=_P?(sR@`its%44kqM#R8eyB&9K2yU=muhBFOG>EW+*# zT5=p0Zyq!*R-0{R$THVhMnB!9NRz3lG#ODlG4IlPM{WZXHBostdmK^6Ptl^j)3@F0 zp)1RKXx~+cC9U4*8c!S@s0Cj^Abq?#yVOs*pM)mm>-FV6PPo&YjN%3G_*ch-S&sRwPSt1gLR0{y$y zBbX&S_n2aNGswEVR`3iEe0du~+%8P>rhyO7f(Qpj7fH>NoE&Mf+^83z(&d}SvK`xr zCRi2rdG&w{aQK?GYO->_~g)s6XflH3_#?f zdr9z2?Xk?`78SPIkfnB)ltJY^mImlz|Bl(Wxb~R0Q&KvH`z<7S8rg}e;pxqh~!YmYcxU|@xV(5?d%;kmSSA(!R z2*6$V-b!RBQ0N^4Dq~SE!4oVcw>~u%vVmx9{AcZU8ED+SMJE~CSHsovV?z@JjMpj) z_bEVwN{dThMxyLsaq#nS5e|R&=Z#W#^2PpM|;mhl8Ta7-)Bob4f zL+pdIb|O{m#ujd_*6QPm>(-KH?Tvc~K_yYmrmK;=&(@Hs@l9m<5#^@QUM8&sykew4 zr!w_>&os{em02+EVf6<8Yri3?h*~W4_`9ajCN2KM;?H=sNJ-8SXG|aE%DCggM`Vz9 znS)|2**avuToZ!MW*Vw*?vbxmV)p9$5v1rRqB~WvOVbGaaZXG1<2g>H5X5kCfeAB&^z>9|$z0dxmQ!aq~R1cA-6H2*|x}l>& z&+uLJgi`K+W+^~6npNU#(>o>&Acc^7o+zxp&>w(uGYpxXYrP`T!6{L%gv(9ew8y;d zN)oGe3a{{8793|8TFtYal@{_g$TdtGL(WnmARYTj$FcPl2Wiwtt}QX;pzlLOH@m0u z^RkDEWsC~cX^Bm{kLZH$4tZma-lar;WOr zdJ(er(TeJ%Zk>{_{`mRYFfSSrPwe~3u;z{aN1IaTf_GMHu(U8m*cWo7q49Dv75>G8 zjT~=35@8bWPI*si8_=IaTemY!P)xB{xlfnElH93L)iuPrQ!SSj3?naAnyeYr*>eKp z6P-?WLi4_BbQ9M^K$AUY4F((5$&q_L(j>+Km_7ki$z#sV7Cf!+%Na~TC3S1`N!+N| zZbG&a$I{mHp#kVI#PMF7t9pK<52t^WV46xMdWJ-M=P~tVw7O=dki}ex%rc?<|GJ^& zNRhGU_C9Km7F6PJv^kmTFyw+WGWHF4L@$w^M;iy(w- zKxH!sW6ZC%E@w72g56D>Gt(-XPsV51nE0z?`akZ7Exb1_zTo`@Pdi}O8Fp~BjkxdG zmA$^89O$$jcKT9kQiJw6d%gQGVhOQz{^w)MY$Sfbmio{*eb=vST{-?;9RuGV%kMLyeU8wJ`#NxNBQwWnYSK5(Du(>QT--(9*{Qs6 z%4HedzwSdVbkIiZS0iA|N^!2!N&>d$rxSZwNW>5GCY3~{k!+7i)N^}Y7JFwvT}&wP zr{b_r`(-p!@<~@fv!>6ne^|Wr$FChO^YwB>gRfrbvfDlpB&*Juc8aZ-hz(Gkn9$3! zT7L0%dyq=bM)n$6<16Uibco8qIT7TK3uQkZ^YOvg6gYPR7pP!gJQ;jPfv4n25T&_P z&#v%GmT~TV$!CJf+)h4x}v0Ztoi|8phAKNQ;aznOeVWa7hq4#Ci8 z^XLG(LhBgviku%m_6-%O@7$p-@MCBlJaT)dLL!)IxVn=Q8z9U$1dJ$bjTkt%mdf^S z*&9qM#bU?zj=8hBaBr?Zt%N}FVRS;2l3U_LALtCKje>D-g4!H4Y=$X z_c=T%Pnd9VdRn0!Ug4byKbyBF?rgz!u2{?fTCvJv<4K#kanWTOau_e3X}X+}yFVbf z`NaT75Z*r_g*t6=Su5xOa3QksDGH-%guZE*Z({`v4F)&mVj83(vo~&}4nCF_c z#Wp<&;`R6@mFH_^g_s1CMBAl++%K~t&fYgFj_B9l5*#mpE6Fl;Y;O&ReLBU~!e*Su zYB*}6KB~b8$NGYbiqKeG`QA64ttmNt|Za&_rI?Hm|8QOiG?`tr18W{c*WF8ix zZz&O-{Z>({5s;RFO%}{Vyglu0G=D6#P6{Lwz1J9D|H~K^L>2HW9K7{*LM1IK=ouP0 z$?CYE1@d)z8+?f;?Gnk5Ws5GmYZJ1#K_Y}yZnPRrqLht@bFJclZ%?BV$cti%)MQb& z^t3mq1u!%W9td$;@EhAdR_b}*3l|9oo;R0maH(HeU&n6|R9K)XpOQfLs?zAw2zXb{ z62oyX4~G2NS8h9%)^Ma6X6Qc|tP!R`N)r2_r`j3>e-_DQ6}ltMEJbCe!EHvpu zVA1L3tRDw0o{GK7&52~W40Ne8bLkdX894n{E5i@oGjH#DF#H6qflAQEk9EF1#tIqt>u{i}_RCuG(B&r~aP+Xl-i5e2H!}Dri5d^w-teiV-m1bCS z3z>#ik2fhnH!AFUJjA}$xKnWFWa=)x4@N_l3X|{U-0M&1tWk=S-wFM z-^dI^=~F-AN9zzqKnjERQdvq-rXf*p5=S?%`9q_-z!Bc12Kv%a!u%LDpY>ez{88yEP8&YJ%dgRYi08VGPG@95~(+3Y*?xG2K;;bK`WLi)a@7s z%zCWhfsDgVgQ=z=0%H;VPQ)_cjz*t=(Y_|7!qA=3^=>^I;H#m;Ce`ouh}5Gl56r$T zJw3uiBUTS~PPL>{HD!)G$k}SN@RS=}90zZW=fAF_>{b#t5(%-6C^B9sY+v|hUZuaL zT-28$U$BJ6Wd&2Y$xB|GN?Y-7w%>i+dDVHayR%sNq(p~h$ZEvqE)GIkyE*OS1V-4?ZJOh0 zZc^c<$CX^&`ifb7*M4Oun;4Y?B9Sk|Nc8tXys4hy#E&Hi=E5!Emwan3o$!#Jdpzn@ zSquEbtiai1lUBH&xDE@}q)k7m{q<{*;Rk3Uh}_NLQbK6etrPhwwXZiV`|yz>0}xHO z8>?RcQwb5)OQj4jRV&2$nLo~pvkdu%(B5m2Ek}+T=L!}o+=}SAKKoyn*D2n9 z6zD!-pQvH!z2_5dr~9irK9G{Xp0-D9_R>T3`cqrxREG0`6ZcPh>0c8%3+GN=vjis> z+kp0Q|8V|T`Cwr|0Vu6-*`rb?!gu7HaTE0ittb2+G-d#4n1aTBW?5ryjA=Mj)ze!n z{IzwiwqY_qPdo4m^P?Ond3~i^mgjrg;YKN`gAHi3fo=hL8VY-T)pkFgRsx43X&4O) z&51iqqSGYBvc5Ao{#=kxj%*2vi#82(P^;#47q|3P$_aC`JLV=x4SUFS)jlCkFl#rh zt80L7aBXL?(*!YE?|IM@a&ASy;h#%tIZ`u|isKkq$ofY%IFofFT)+YE|Gy!##{%oE zo4x|>KP`%;>2%pyU;+@5VJ?9e3uX>PB@y3<$-&OMB}-iy$X=+KbzRm{S}WHN^CT`h z#+&|9_~+-j^qj)+;4D{#_XKNdcfW+!=q)tPw?FNI};Hd0w^yAWXM0RKC~x)e1%P@|k7{IY z1z8h}`%{QqtwLsjZC=rtFoJh7StLM69?sJ9%^xchHIWil4)`tH{SR27bb;QQJwf!J z%ZG5``46V*eITG-m*w0GY%ZYZ1%|4dyir7NDIQ4F1GoqdY{n|JVxv(_>8$0S@%#;D zM+OI17x;IiX{%s@KM|7XE39?#^KotY3EdT9}r zAESD1yz~36uQgalnWmIZ;!Q$Prz)?60n0C>pamli@(bKNYo9ZbO|L;(>j@^# zu@U%Ysie6#UwNQrK(Kf+*pA)jlRtF~hn}6Xn)nhrgy5>*;61GojPx@;Gh2c4@siF< zkC_H6q6M7qMrM2sL=p&KOd)Zsa9S+_yhR(}x-c2!elu0L8?_h2sRSUQZdG)`yDh(v<5qU#OP6KhA{$aALySKr+$WNVydum< z_W2qRA6=81p9L1DT>z&XClSqz8O#^j-=* zUcm-8Js;*B$<5L32`bQmWk-5g({qwac$`7)LFB|o80=Emb1(FxLUT>>ekIP?mNV>w zewdJp;j);IwtKI?d$u*oB1vq`QJ7E`nw&y+F%FG$*uZ={?G69V)Y6S7^kH6GFMO}& z`gw#-pjmWAU2BIKf)9cRu$zY9^iCTflfGC@;_RKSki10+j05_6zl{@-!^*-tKp#(& zqWq@$(d3_$^tU&3r?~)Mla1pTR=%`ma(`$bT|7?`P~B5HN|sVrFYrtbgLxhzrUA?X z7atv6oQhy@xei=%^=!`X03NHDn+vxsCZ`%>y|{Y(I#QgocU8d}{mcG5Xm3ia2rm%x zkgxgJ706F%wdNtKVmrQ_lrG(G%rXYJ)$rBriRtk4UW?(Q{$6j{ET()9tx69&7n?~x z8+EM9280DI-@wbXV`*0PFvAd@Iz5xKqzYZgl%&UZ#u~8j+~sONtr7Ls3%u-(nrJ4lbSPzfx>_YU|_|3;^jpH|w#|rL_y6R_*Tp$jt(i^rvoN5O{H; zHJ#d8Vs4D^R6bYHBCJH~8O3?iuMiw&Q%#pYxjG={u(Jc!ibIAhLy1PCJ!J(2jm1$*GPwTp3^o3D0FwGmf->P& z@v@_?Up!-S)lEQ9jX9OR8(A6!7I4U~^qw*vJv+MUCp^c(WtK^JbkuHg565&0M*!WbAXASG^{fDMG0Ef<{T`U{<#Nn2~ltg6a#7v7P z`m@u-r6kO=-m5xz(BdzeD3&M z?EhGAe1_@F`K$6Ln|!HgUgdlb}<;v#X%`k@<3`o#^T@^p6WZJH_Tm zX@8e%vV|T&p)6__IAk@|5WI(V0E#5B`6*zR1p^-RdD@xl2kOz-4HKi%+m9Su(N%yM zU5861mjcq6%{#nDwelVP6cPGP8msOr`5o-E5XW@p!>2DHvQ()B1uB)hGe36NDsIs= zGfYl6*R&7ufcK5Iyy}$OHEiD>aRBPbG*l<}8*Fc#|L1){r;v9OjT^XWHGJm~|J16* z84>fowS}i>I z)X}%|#tnz-&JVQhNb;k}8z9ss${H%*)fBNP6@7>HZ~r!*3YXaQ2Kw9=#_Jw$cSo`D z=+(I7vh%vlb>jJ^ewQb-d zH!V9Ir`)zY%W`zZGWBjVO?W4bQgk|zA-Qy&KUyxrD}c;2`IJ=HnNhZe!*I&XzyMEBPruNh)f>ph&+vv|mOQc+Mf@9|YmMYtZGHdt zVqRe~i*L*D1On7txb`Lc+|pvrW$7fPR)*Vj0abt7P5&A9W7u5?-*E%?!}e=2r={Jx z92E~40cpvy=rUqj;~Tzzm#Yj|pVu*@J296=c@I1Za+tEX;$V*!z@Kf%FvE@su1lQ^ z1Wm-bz@JM63{>~lUE}GlsI8FCic*R)=Mwl?S$ZyEGDfc2w3|Qj+83W5F(IKeenfu9 z=D2GSbFkM_&bs!VdbY;U&PQl8{raM-atYad2EQ&vFHHVxO^ZkJTc$abl-K|$vZ3ir z`N+(CgwZ56B7O2yb|UFDvSEnONX!93diiyfDj^!Qo3!90m%|ZI+nZ@zhpT7Fc4imG z!%O7iv_eN`8}2zjqftATgejHGQo}8-B@do#Mzia^?Uy7;zn(9gX+R=q?HP=&c4h7~ zN=Xqfd?kP^I;~4zHLhIIztz|&p5@Q;Qv5b@;}dX5nPF}qD}lW~6t+C=(8-lralQ4Z z4H($?F3V~{SAYIj3BWtZ;9W}a&14Ll!v|Jdw>Qh8@A>`#@&fgQF17da{fnR#;b))t zi3n^K?@tdL1K*ZWcn5q%kf9;)ZJVd}MNT&?5Ik;Tm}#fz`1#$-nyR$7BQMeZ+}{`a zWi3xKwLkrZA+yxq zc{lK3>XI8g!TDCnQKyg`3M}f?%6Z7#8LwV*A#~n3A8{~8b~ezd z52o2Lx44e-O}1A+n`%EglBdyxP;0aycO`yhPYV|%2zn24CCVTbqzVg zJ2m7P$EgauI7X=8Ry^KGY@6=ueQkKYl?WvX+!h=D*;pD?={Er z$W*RPxJ0_JlRAGdM{imK%_Ll$lzWOxVE5!9GWt{;|GE^H+vNhfS;o`}1eS+Ae@>eKCgwBsq%g@-2H=M{&?a}U9(RUEGn=BA*9LhAf z_>#w4bpQStvFL3;{qi37!3v$dY!H@$2mNfu%dz2JTeF|&+ACZSRM~`ul3Jta1gV8z zI;_u<3YWamoEh|`Fx;no0t`-r^lA)YS7LjIk0LzzdGPY*QaA9tM2R2%^AYtp<9^Zh zkMQxb%w)5JZg)Sl*Yn$JkYjHb?5E;9e3}2au$bvH6?W)*SEp+s*a!8aY|Onz zXhlGK+lk)RL?TW9*F~<%n@%+4USHR0x?rmml2EZWu@w)fOY3)~sr`BYo$P)!NVYoD zAOG}{WfQ_{sUsd(3~C~C=ci!&wv9O^9GgP$6F=h50{$9SLu0RRByM0sy{58_d@5E# zDZTj4!kM+fq-%5Z|e{fn0F>M>8AZ0 zn*^-20;QT1P2L|mQSJ(7W;9%Yx5taYQtr_iIhk>3=r8AU(tu(dd$+Sn3L!RWZ z*7U@RiC9gS-|{^Ex&7_=crKpory|Prdl>#yM*ZW_nMfn0JEXc@U7AcDQh+C4 zw{pHzVf5>6$&>XyK}7rrp?Q`Fn^DuK8Dx^#&D;N_6lH8uG$t*Y-z; zg4zurE8|}eC<0D8@#9Y?+p5db?1~lVM%)H76pQ`rKv(v;j7LMnKxO?aU{{v_2Ytku z9j4TVqb~Ej=lx&Ed9^`yZ*<`ISD`oM`ErMHlS{f%PI#*Fg+O>QK9+(W0Zw*5SzUMo z=G&dNs=AEH&`426N6mG2M6oERU`kkNF-b7uug8_|O>;@R`ro}(zq7Q#4@ft_M7eBL zLt)qceWPIcHy(?wB-?|tiZW9pHS3au*o`05cbWeF+>EEseYg!Ab%#hdE&4!eQ83Sy z8cv0};VH#IuEWk+Y1vYv=5E1eLg-hsPLg|A<-T&CFbbScGK5hzyJOO#HKHu>nl|EM z=G2#K{`S1*DfA`B(}6oUtaS9Bi`{~i_U#+3Q|P&L#1`*g{BvC!@Dz_IZ#Z1_IF}3f zvgZWg^YGs?VrbZH#DgvVEz`4N$OoC7Y3w))@{T88`FCu+QTu!4mv!NB4G6p2M46QB z?2SaE(L_{~<(E=HCJ$%ZtdX(i+W1v|W7rhL!+PDLV=0pc_VTN8BRO){&|R@3UX?N7 z*s_Jyfc6z9YsKzDXIs+oOc@IZRM;>#(GsJ))tNL;XFBDN=-r^kK3?}iS}H@Wbi$N) z(9<8(=!<8A<4PusEt>Y+kb727S9N4KGJU zImD*A(P`9H4+k6_=3;o`E^|}8L7uT6y^yvKT}D4WLOt*9H_9S5uM1k6-hv9x=OnFS z@UDZiGB;=V#D`*_P%pr1t0(tJ# zeM@=+a8Am~x8J&PRe1v}{<~wsX1eYXsBb`SRP$uj2LjREzwx9~3ay!Hv59^j#RFgG zAJre9Mkd5$La~v~H1|IOmlppCjdF%&HsVe9ScRBULv;1AL$(sAeCCo_b_wAzUK;*k z_gtszBCk$U#XNFcG*+}*=~_a038d<0`U#U|A%iy0JqaqR=BbY?YBa3~OxCI@sWC;c z#PB%Y!+s&60KBgAW`xSfyV2?AHlF*&R3Oc${5q_w&=Ky*or}m3U~(`RLaf)gkJ?5m zK%Pq3Qr*?p#)M$1wg%+KXWXyMl}sKqsO1b+!Tb-+U&01(nUIqQ`zg|)xrwaJ*DBZE zf$T^U-afn{WA&a6qXhh?bjjOJ3i&2doL%4fEA5z>Z_Y#QrrV}6Oc zYuCr-Qy+;&+}kcy$K#*qcvmg`uF229*oAiwXcmc*vOC;C%i_J!}yP5y)7yLhzfw>d7DMe5SoRNb9 z?SqG6x@SAlE)rSSkB0K(N2}_jVB5VV%Rk#aenAdlrE!FuTYg*gD^Ue8yuRS zyM55kgWhgFE^;0}-%Ng&SAtANNSadF^>(i6Ra!cKrO3>;t)JQ|I%5}?mtFyiE`83# zwLGSw)_jAwqF&Zf*Pu=(i7e&mvPX9UKmROXq|*QB^tBG;lNgY{s;nBB@hok~;+~Db zw&wxFH+cTa#bCV(tfhOJ$ zKKZoYRXPyli3w@&$pi6nWUE{qHq+>*YBYPK5~FVqEa^kY%>qW9n4bhE+P*B4JhM5N zr+~&I6l^m#c0rK$A7JY#_hXXk?{f#u<7=1IW;Z@@!{YsKLluCHf}Oe{ouPGT9L%mJ z5I6HrkuaD!6<^-H1HBv|0lHaj zgL;2Hjr)fi$iYt2(3j$r;KH&8QT0b4>~ri_wIj{yX58p$Ld%D1v`8xF6#w6L_CE>g z`0Qp_4$eb1YjC_pD#s!+v)HrDSfBX{iX54{Pj5=4m1E6;$TRY8#KB!H1L;6GgiQpO zExY1QaP+-)3(pnxHfbB>ntr66?fIC!zIVDj$rkl1Eh z4{e6c;%btdRFrMmIgO#W1t?NvT5O?d*_=UHRKOsM-6r2p4Xi!pBqwZC9!J3gi^y-V zpvaTcJn(w{S@Y@IjKm!BF~a;U4RNJ)HR=!EO@y`r-b^-?th zf~x@7Ggn-!*KK?qNKQz9R|WTCSq$D{^K^f3;|%RaO`@WggPL`xw}?ajh@!ubx&%DT z@n?)kFY;Uwzc1J!b^5zmoFt$0?< z8^FfWLzP=j3Rl0AdwhG>Aibh};hCU;mYqX+wil9r81Dn0j<5S0GI*HKk}1CX27@Dg zLHA2w@GH+$%GsuZ2GFa*ayH^YXc)*={#P`LUTNm@4$%YUu(=h&8_QL@)pTXvv5$ca z39`C_))WH?fr8GZTNbc(L1HREsBsG9y^8+-3afc5WZ~TAPL#Z4 zv*C5eL}|mbb3`U3-@(dg&L1N%7}Olforb2cyqAHXbIIG^2gTk0=m5-9!t=T;gYx=L z_8}n(W(twzw2ddSzNo?Ee!J0vC;=Dr&1|vp#|y=}uKkId)D^{rBUQXiU0Kd82W4Mk zdOS4SG7o&`6(_U(ZraH&I278GwCttDv`a~lTT18pw?M#h0~h+e)u;R6hSj=}Y#mFZ zYL(UkAE%sR%VgGfYt&g8hia#U#++^)$6&ABpCUp@O?m+RX1RVR;cXR5-|$U=mqNre9RYrsv=r<6X(P&Ur=NRL$_$;G(A?_V zz_aQZ6=3Bt_I5L%=%_0*?{Nepc^Fn9$#{HUuKbm(O)bf-0vnO%OV-(Rt4}$5uETl< zC^tbF!BXPmp}qOsYX>x zc?F^JNRfN@&)DejbbN`4??gQGmnFH&1>@B`U^eh+;BWvR9aEu%>l|)>vj}~^*YX&7{K}1)iUU8gDFX?2z(wVX!eiN~D zAe*_13NGeC;)8Z_$Quiy$t36)G95@qnlf36SXAlXQm z8i@0F^PxdtsnQ`Co6_0308UPd(}TS?)`21!cw5Ya7m zCWmBvzJ3{Nfj>a)9#07*rVL2H6s6H*LwU7---xI2vV-|Z^B9#)DCz~ftBl`A`0i&* zjr>o2HbVvV=_Y&R-P6_6OV{rH${ z2(}LN&#j}Xy!kq#QAprLbdMAzMnYn=_djxtCp(VEiv&|ZR2b!d0Pa^0YQLJ=lRe#p z)3l2}$=1l9mAU?LK&qBWA0EwBbtb}6?34V>*B z@>76Hrp;Fk3CvtjjIp_GFkf9mhT}I4;YxJ61&%DC3m z^5l+|XsnCc!xc(BE5qqH(NAhGe;OVpdsUj`(_hxW(Z-S5us$VL%-?S*vTao}^)oMz zQVXlvhOn-61F7nM4IDhcf8qCJC$$@efnNsO3+YQO<(2@4+hkC|4Y-j~%U*0Em%b^) z!m(v@pIsDHv^IikJ{cq%m1$f5ibBUJot8JXBy3sI=Res@aZltY*%xf|eP0_G+4urY z)JL>ay2$o~`hJk%;~2@xj)_3xp`+tGEWq3Qr=UE#eSaZy^!(fbh@{QhnJF0Og7s&( zJ{&|Og3uF5@+-m&{c8lL?t_2ZDy7Gy=0`fG^dtHzFzwgUT}s_3fY!%mfJA{m)NJ`i z<{cCg1ko!kpPB4$BT7|Tu-gC`h7SI&$_duF$)*>+fX?8fY_5AMM%(l%(j zHnu>dVSh?$`jrUPK;)o#8Er+D&$8zwW}7I5jPd0%gUYc{0Q>k+@+?C?dtaJItzk;# zveqUh>ZSD%!7lNrrW9~gy%)=$C?BK`4IiV*e?3|boQ=7kES=YEblqzphhoB`iPmK3 zo8XF@bf^+#Tdac@mYk9U<%O0n9-fE~$=7EPkdx!^nS%fh;9{}T6Fc(;*V*LfRdV#J z{ZOlyFZQ$T^+j#`a-X6m(JNz4wVryYG=5w*M4#_4O4|+Ibz{M%!t`I6HncF^hvPku z$H&(|i0RGZ+Zy5nR5l*|{J46+wn5n{Q*M!eTm8>mue$I&dnH!51baiT+=44n)K>VG zH$q0xdyl!|^@!^Je%QgBUPb1_DN1`Fi3MX1#w%`2D)|G<5aw}|^<8JL{g9#WH5}1=O4z~v`)S|~zs&~_Gb3~W~_6TJRk0W#TpV&3b z=WJTYyEAIlPKg9$bH1=-X^cm4q&_tlNE{xXI*3$ZJLmG<%C6*X=~B^Clt__diCNUK zH(+SWYjXT*#*zAPvE%8jC-PuokU*7f2*_vMyB~ykd|7Po8@5EvP(QmQJ@VPjs#bWW^Uax%l}a^hkAHP@;9@<&rA{bWc@mv~a#_F=^QCC}@q^*&66$ecF= zy@98rYd(+q92_b9D9Rf(YohAIY(6pAdlLhIqtRXf!iT-~p_b)gTT$YGb1^iA;Pj0b;!=;HwAjbHKb+`O(!AGSteu?V%8f?6x8@fq!gki_aBV~Hqs4VFB6+Zb?VMp= z;>v0C;7CVGqSOo+4;8!E8OM`a2Yd}BAa=Y2B$a>acr{*PCPAa$28NNvcchS5)Sae| zgS5++9GhQ)xq~83UY_u-&43ka-VHKi17^=%Bq}-`Cxn`;>{U=$*~tA%nKVEm>%}JQ z2CyuVs)#Vi{SC}pL~zzI540*l+mXo2&WwESKE^sbk$e*rN$r@|^NzYYa?CYZ;WX9q zxPHN9V}pr-@j$vV59gEI!ctyNdXswkgl`jQWcMq9#t#&n1{06Rf^neAS<|=L)VBrn zuP{Aab7&xb4$$-+2`(E=9Qr!&{zq$HXp!ady})_zK6=Xr>)8{`a|>g5G7a&)&FNRO zaqK!wnYoGj?7Dfu(Pg3!-;%Y+N%KMm_Qr4WpbtZQi9TcUl!gFI(NzzY()wq$`{Yk2 z5bklBtxNpLC4gF!b#`75L}x;Ne#b36&7SNBUUSq5o^AJ84RrZ0#1FB-89IC42MDGD zvd(7|%&=mAS|j78fCB#b=aLASEezo)fBvtWPqSWpNaZ>?(jRzWxb(_mm&_9gi}u{d z`OL;a%C^kILfQ8!MwPY(s^p*6wCmjLUBFBRR5TwPT()`KIwk1~Yz1jLI$+X*3z!+` zy8)2A5e!XHi$UhvtV#&0N_c>5uuHI&54Zd<8H$P2VwYbmH4!v&{ow^5L7%Y1=^I+v)*Ury>Q40nT{&~N2I@nC0ENN)~~V4T*3{&`u4uyoJo$lK3e zez5{3B{FN5)*klMlfD|Z)7n5Mb*`P>jlZ-TOqY1-#9HEbs#16>}G3uM3xFU9TOY~ODly^qW-FXI^K=~g0kdINR#NvAw55F$_^-Jm<(>i-TK#)9J z{BBUHhiSSd@(l>D*$M6GImuWMPVuhen)v&gZ>RlG7cPR&N`^J#J1LO_c)<_^T@U;U zVQqZmuwW{XGi=ILXxV}swfsp$c|S7cXqW2wEqc$1XmwY)EFQzUPi9)0m&uC4n* zi;!vs!-1fk)9EOjQHa|DucA|FUwoiDw=!KX0kHK*|-HKrZBGHX}&I?2z;akDLuXM|vTg)po&fjW;Z!Ddj zo~@7y{z&=J?jrx5f!GGa$O-TDp(B4zO<2pEJF6K1^GRxeZg@}xrI_cfodCXkj|1Mr zP7c;{i$2x($C9-cyxCuM8606p^QD zJoNp=sQbNV%;YXF1PYsH(=A^l4fVF8L(>Wy{-B+=+e@!5GevO=JL9CEZy+|PJDWoq z={p~*NUtxO9#a&gcrP|9au{X2d%!cF-zZYHCY5A%#e|Bucl9X8cJj;tRp5_FG=8j1vc&N4W`;PFK6ZY+*|1V#Oupv`jcV2 zd9t4XTk7%QG}E1UvIq(?VV%ISDal_qdFBcpv%N^K>UFdj_o43i(!3=8{MD1$Zy*?U z<#hVt)g$05QBsB+rKfIyVH^D)N9FCZ{J!3j8F4FlM!LutO2vrCp|!m} zZI9AO+UA@Y}ht6c*NI^5Nu?;teU5>vW}ckUH?fZgI{4~O760n$Nl7ZXGnOGPjD zMmBIYd`R*BFvs3tKS3z~L94EZHhkQ(uErWHXwm+v@RnCX3;$%u@>Qp3W>lrQLONu^ zmeOrl6PWbsQ1q*S&I?vn9meiY>{kR{O$1REOk9h&&S?IH_w~-i!2{E-2RZurFMp!W zxwpt3$;Ak~g}1nJo?HK5&}y`sT!k?j6xMB=coqaj3Rt{K=#|6%yj8pWDbb5q+~A}^ z`uMt@j~{0i$p*iI2kUg=j-jsT+Icm5{g6As%XL$=0W=Tuk7YCl`2s11s+B1Bp_rAl zH-l2sbBS6H)=+l=G5qbg|HcqV0XMh&DpV+Ejy;FleuVI-J*ojyYTuUVkq_BT*Rcn7 z);WCkc|(faocZqiVR(MM^s$fT1vI_);rG`WUSQJfDk#yesMqiRIBzIhcyK+A7rO@H zG@|XMYMft=lTVv$*ST%asnV2E91&g=eVs}kt8_if*2?JeDx=25bCq>2i761LBe_+_ zj$Ypif1=uHZ3WMLzIK}hH?uY5t z8g``h@)X>vpEl(90b3|t&@natZquAoE)GM~C>v#aiC#wDW6XHweXkYQ5sUR!yl*-i zQ+aZ2pDFZ42RHXD5mF$bo^)Wj>40&Ot5f4Mm#FiIit@vE!uUS%e5>Xhfe$rOlS=6% zu~DwXMQis^6k3JXgMVU9ayiRPQ1l`f(b=`o2u!Pp%9hTK@zvpFjrg`)mS5N1_blTA zH)YY=BnoboL@+v$!aG@#Dx+<0KsUli3p==g8xGhD)*P(|% z+Ec6xdxq&hFze|k;w2Cl+nyJD(Mq0B{Mu%$;hNw^6GOQN z;o4wkcs${UgB_5LsuK2o)2W!075fEs);I(s9L`ggGiHT@ zSyLt1kKdlV(G#=<20gxiSU6p|+ymzy+XFLm<=g?3bd{t-hmMyn#uS1TqgLvMESJ+p zwkzoSvsS+U$gL{U@?LvnQBWK>mrnH86(|Hv85vbvP4gKhCl{KpLqDk)86VT>TabE@i^-R=e6Dl8v>qJA_PUr{-JQPfi@Rt;;{<- z1?OgOrB)B{s~j`9KPC;=A&)WfBA1?tsz422Z3n5JjGHG=cd%-zEDx_Dyml3})uhmQ zTfGo$SDF5Ui|ErqX$@IwnPJ()$V4!nF9poH>I35=$|%N>u)FT_Z!l8GAN4tn2HA#i)bVQjopUB$DYG!im&ekie ziVyy%*9VMtGix?E0OQpCJ2o&_ju)$JB_m-CM0X6*zc;^gYgiT(hxcC5tX%UpX}&8j zK@yy4jGe!#Q}W8(a_yp{qc|))m6&odDpP@7%6x_NTo3>1vrajLxQ#0qg7Q|>?HD3lAqDTCSH2&& z)q1aV79qNhDe|s0wB=6x7#C+A==HfPVhl3^MN>J`(v})6I9xDqZqa@eP4T&gsIO4d z+cz^9_+hkDL16S)g&_N8K*$~zOFEQ)<;5(~vq7pn-V3dBo$J${YL>YpYob%1l3)$x z`$naPk{tT!pUM=oe)h5_n+Ut_6J53=9X@Y7Q?Jt*=;M{z7Fx9=tNT{s$!dIS_v+Wt zS`~j=TzQ!-j@8L1>{o_am38?|^vbV%qjMGQ$pn{?BS}p41oiUls>hO-B~&Vx8eb=W zCk3G55zYL2rmV&Rq`>O)0dcnf!J2AZxV*aUK#uw3`x$wOhlX~wDi06Ku z<+ueA@?KAlDRXkv2^dr#KVghko+=OzoJQtVeF$jjH|z=I*hH-lV|L$V!FLUx8=oPFb+ zVW;H@%Ajfl3w`cA*#9H#JENN1x~-1_q5^^&0RFNhvH0ix}5Rh&_L`r~wpfqVJ z0s=yi-g_s2G*NnQk)X8DLQjA|;M?eV@AcgAjeFla?vLYe_=CaO&)RFxHP>8oHFWCv zUC(}yPIz6#J}U9jQ&tEO!Mz#Ck?rd1R_9hY8d@*~6Uc2)M_!M?&d?1LxO!mA^Ly>; zx3+b+4ONF@nwwgmR&X}jln6LF!60#beupoxa_rgQe|{_K_BLdCS<AoEty}o$X>&E^+x=n!?*#V-AO8`UDNN% zi6}0s5I@PZc8#Ri0!pGD@pI7{kB$L*d#`DkPZN4sU~4VO&y#|Hlzr{cF8iV2dDQk6 zYu72Z)zE6mbobUPzPU0H>clH~-X&`UO#h^#`RgC!4@?eBxmEIez5m^aaV<2`@>D;XhCMIu&?-|@uz{e zXTy4`MHltasY!m%Kb=y^8B8B;-7=LgB5Uhz)hO;H++yiPe>N}OCo z>*UZLG6_KG%AMHYmkTPxE^^%6yAo6kU0<-dg?8x&D|fc> z4A>lf^=AVMg>}dKYiM7;HFW(pU`0vur>KQ=ng`S$7cj%=9@Z!%UBzPU1|tFpc``wY z2xt0MScPZxVfOHWY>rR=S-SL6JyJLN{H^0fzU{r~2F}Eu=J>;p&(X0TtKh8FkK-R3 zw@tXEH=NpxC!~=L%lmhP?&$g>5G~_ty|l$x1+t2#q;4#<#GMo7)JB_9l8Fz^A9mzH z4ZrIy|A3CmvcMf~XG@?L3h>~}~JcbB7{ zVfFl_UXNAw7_0Bbu)>WfhqE!-2Kdw#qT1$!QF7cnr*U2#p!zUr>1kJd8H^}RWJsL9N;Y~SPdSvt4|ZJ!Q~T+MV2*BP@PeHjFVoV;ic5e_z=Ho4=+_*`S7?Tg2+KURUbx)KHZkWk zbecT%bin{jpvoc3Qyfs*!|z{>g7bcPit62x^HBEr4FiL{A{|8t_4BC)_!;*Qio>4) z#VAhIIBsSa6!MnuO$jF&Yz>$0ABoH@;j{XaeW!~<B=W&6e#!Z87I~_O#Z@G1)biHhpS&)xEVJuxnUItNZ zj+KuTEND^Dz#RO1V$oyVna4<7DGsj=5ZNh^485Qw;W-*`K5yg$UJBRtfhv)*og89N zX<}eKTzj&frN%4iG2*jx4!bTVVn*C*>V%A64Ft_1uCZUTsm@R8h9f@_vosXru3TC= zNV@j$jaVRZ@X?4#ja^gd;0buvjy=l%CDqK>Zg-VRryOB#w2Fy(^g1_94l{sSOByrU zRc)iiLe=E0e5P>(UGl1eseu;3>itPS1^~E*pDHLy%=?4bvS70<6dT~H)EN)v3SE@G zDCWK=@%{#esAY=G*!i?&e(Iu-tYLcpC6wnD$C1KI4@e)G!h~B(CfDKtrt#KUwj?h~ z{-GVoL+KN}+QBJKRF2>k-s31i2%laGA$|;BZazPxz0?yh$1Hcj%DH=KGk2v%n?VV8 z98(4DEyOSesU)mvl@qh|*Edb;%$dIOo6DSrrN=Z`IUiC6Cr}a~QY6O8XG19tO1x`r zzI;qr8qhr->z*hfpo6HGD7j~#vtXSoYwQ|qj&=Vr=+RU{JDu;{=|TVF;Um8w!7Es; zse$or7)#6gS!VjlM%C!qYCz7T7VFzilWOs0aOLTn)N{v_uxGnYMxgDSi-Tp+ zt>KE6o$Krt#IiEWf{Ay<-2s9KDONQil>DoN&$Jf;hO2mEEni@$Zuo5e{R)lXMrE)6 zM5K-eg}er)A*=g?W@&_ZB2=oND!Mmu9(o`vF|?g=NTRY&r=X!8FCws^H%1WL9ua_>o7uuc(9`IOX$<)3t@CJ6cOATpy%=Bnx%J~QPq0g6UttKr##b3q&P ztQ4vfl{f6f4_=btf|ZeE;%oF*fyUrCj7I7H5k`X#C=eEEuUPsdqF2pOw>kGKt}jY4 z|J-ebyPRISs!J=QMfgNX>b4)4loVW~(5rtqknq6OF!hxx{X04J1jlUWuGziNLY|W8 ziyh-pbfP{YfEOTvutNx*k{hBQ1r5`MP>1l{-T2JvmmqqWenrofu7o-Nl*qB(Zx6WN zr}$#Gp^M{5BDxNWr>RHr1UDuHoC@NeaxNQ)4d+4TRdca3OHcTUd;yU<8mj*=@y+SX zwFbs?*4~1J$g~4^3`W4qo zig0<3d%}fPm~p)GWy0m`q?&d$yX$!kV&+>NZg{SJ^Y_-2IP+?Qx^_6d^;qMyQ97qu z*fRpZmXs>pqi(%yS8pmasBLkmtR?+l3`vlgJ-VU2 z?=G6uQB+|+hzy*m@#N?14VX(D3T~e)v*X+h-Hwrxx$tCgU)2PZC^eK;QbPsm%3=gY zw<|*ayPU4{61J?6%<-?+D<_<}846e~_Nt(DKP`J}s~|c}AY)Mq*NF#t?xIAaKXL!tVy4OJye&p51DTdmZMFjPVE|y6fE!uj1;pNBxF+5=Z>bS3cR-OI_ApZg<@0 zrQtx7uEYJ%emw%#;pqx*-&Har8F?XkPbQo{y8w<#bvY0Oq0HYYjO}*{Ta*UjWqfvW zBr??WlUe;z^gx-{;dWaC!%!O%A7}3SNx*SL162tPl{JQ6v3Bpa4Fj)VQEK&jBf6pC z0|NfTSZ_32l>5A>vqYn1+gSow?pA^K!oSz|pSYIYxDm8*pj$5=M5}VhleCvXmc8c{<>ha-dIa z0{qKf&8WqSr?$&o-T)C4A0VDuI;H@6Doo}nS`!UR*L!MNXC%)mWMIS!zR|xPf~aJWcu}jf8!{36!7CsVeMMcn6f&b80cKj>~2=)_=E6PgA!#_NXwt-6;Q=2I0z?)X4;46HWg61p_Krm(cTY+lq!V>fP^8@!z(|92W*%k18j71dOBlKEI95@dl2I==`}# z=(vQ{Pa~2MGrP$i!F^oy%s0cPX6pV8j;Tva9?}|7bGy8;)l+4$PU#IY?b>l>FGF4U ztb3HEdv)&Q=j>d|Mjd_E1uFb&**Ea6_Ycp?YxKqn)NNC$cU@Ytet$zkkH?H!O8oQo zdUGHJzx}{X?DuEHs7udDNmS$Sx0RQ(zhQ;=jPbKJenWj&UY=b(*xMQ`wrC0IWjO*e z2a;GUSi-C`a!xAAgQ*Y22iu%|ft6qWqAo#v2)22r0>rQVNjmVR_baH+?Sr+(BNi^& zD@FRZIEfEOCi?ZI-iPsLfrTmm0 z{E*M5nx_tT1ASq`x)#f>(&kevkgB}?|69Ne-wfZpS;hS5F^m4_^0 z{i#my%Q-3Zg(*GI((K&T+bLE3D+#jhCC#x_q@$Rh*nv1xq~$^!dv;j_(n|W%fOYyN zp>})pAT3azoLXQgZzr)DWcaXW2Wg>?IBIeD5Jxkqsd6h@`?!;u=KNX^SM-wS8DrtO zq!YWQ?ArucC@#J;m;CrwJhaIB}?-c4@U z&>pLt??@8*RCMXS%}9so!8EnQXbHnDWt*D}EWYWvw+r(Q4NKki$Dn5$i{IoV(^c5v zB2#e1cP2g=`*mzd`jgh_8hge(irS=h(RG?BqH{wQRn1a-}sRgBvEFwqNpS=JADKN+0*=sO+nR#M) z7}Y%5e_7)2d>{+CZtkd3aj5?Os2`q8Tg>&+7mA|qh$f%sMz-x++E?|S4(GotpNb;IlGD4>m^SV}!YZr1oj zBm~j*PnUJwrC3D9@P#F$el)xsn$lyvm;Vf2SAr%aRauW#^^W@M%_QQ?;ZgeN#52zc zf&=O5>YV9~bsIOnRV}f5;Hiql^iUx>8fDkBT~Xotx0yw>YE|MX8!iy1S)I4&r+t#e zj-JYlb>)>B-nqEA1yzX#twPs7TyKUMKGLm>zeb&W|&3 z9X-_6&@XB4g_QLs4Z9=)0~@?Brne3~y5tu7QMe-M%69u5Qb!KJvlZ7SRkKZ>d^>U8 zbvNf6AZQ(~td9ET^iqfhS~rf|5`R;Fj`JAk$-I5%TTd-Dd8hdyyGqH6q`R(qiDE!m}|CXZ_sbyVB4d#Xmh3bvd7UKq-D`-G4Nf@3D*O!&myu!n*hQdsxcv1 zrqG%1g342K-M6vrYGW5W`RN0^_}h8jq(BJuunBqsftSL)TY49;seH^NZu!!~w4EDU z4#vL;64bxgIMEz=4Ek66sd7{)&GFfGSl(GLa6;}&-k5?`P5 z!=@^`jl*UzUDdX@WtL+2O|ZU3R8sA|^dtZ_Fzty+*KSRyB#V)4e{ z{40JN!d{ravOETt{Jc3yI7jUO=ASsblW#B-pnN$WO+JZ^PeIpUuI5BJOd_pbG)U+b z8HVdGKlz@o`q0g<WauGKB@Z!3Wy>9|9g3=)rl+gq*i(7a1irqI$~o9`$hs{>o`% z+*hRF^WLr*7|%l=GRgqYVn{ixq(J8|-iwNAZbng~@!8z#$7|Z^;?}5-WguF#CiRQV zsEl@iq^ta3I8UFAzP^p`qjnjz-MHND+T5A)x&2hxuymg&alC^iiLv{%r0?l#P!WhI5t%?;p1ev?t2#@2V#7>*O2oPP^2(V$`HJl0-d} z+^aw(^V2Mwg1!&e;D<@_kfw9N!v82`w1nOq6!+JLP$HUa|MqRuyLa`ERNw|pp=wbT zPeIsD)>o<;;2mWLW`~ECS-fbE;rF9g>4-Hcji|`4uInod?|HT97lk<*zG`JDDkF7; z5ED!z?R#r2rAKItWUuttorWe znG#8sF8cbEp1gGm1}^U5Cfveu0Z!*e0R&x`)H^y*)sA{i?x^gymR6sYQOfDFD)wx+ zT&yT$wCcu_+?_7hiA!UgL1jD!DJgN3x1U`vmrt%~{Q<8TZT{x}9?17}^KCs1>hoZi=rT`k+;V`NU-jA(O~u`ke=+CH9RsW*8kl zPP(%Oh*(On&D1?5#pPu=X`Y)CzVGwd?&Te)ktk*+ywdgC63X+v29|f2)B}L7XEejs z20%4vB6L%5ep%Hbr&Z6+OSK6nz(X4)U@+IJDWs%Zi9~;s2-fZP9f*Y`Pg2Zqz zXTz5F&x4#9{Nesuuy$7r>`#Wa;0^XGh0Cem_J)5kuHQcO=fy6hEVXzpNxgt+_b4Lf zzC?{U+go1g+hVCXajaswbSZSF;p#CvK4j==`BRmrBi`q&eX2lFxzm;ro9cI}+Y>4qI8R%_V3x-)>9SluBI-jrZ`Ye%BJjyaV0m1&YLM z{So^Q9KQvpR(9*xKd-k_XVE0Crd<% z7}6c&K{Q1lUDDNH@cpq}((Y)7En(fIe2P{>v>hn4*UBHg9WZb)4j1kZHpm2ZiIo8O z_=T*ES(hQK>wKRP6_?$Z7{B~%6LcnJ4!+)|q+}fg+Kc>tob3b3(BI_g$7AvokJEPN zQ*?7?Hxl&7kYXI&3G7wmFTY@bhWqt27 z9Rgj=dtR$Aq={qtLQdZ`^6*`be05A-xjYuuqr9-Pf;YC?li@z6*T?exFN!frOtSZA)hz%{2X1HvLXk z-de$wwG6xO8} zH4RQawGYHmOnOuKm2~WW<)k=+2=l8_M9|NZA#80&Antf1`wSS&)*kt%%w5fv->KnP zKPv?mvqqPgRR<6%2CH(k0_8Jo6@UyNXW4jiaV0D6rvJw+HN?HJXY3NbR_A@UmYB87 z`gc4p4DEfyrYlA(!I}B(XyAu?nC&(Ob36N+t^;1UB}KO~15w+aD+I7^opRWBA6u1P z7-@s*K}a}%?Q||qB78`B)D-Z1_Un1o*7<^!Ho*zHrR@*T!tn|-b4Myh>%mO3I6 zlkBb5QRJLuT;-HGx2uXSG(%KLy*xD`Jb%zaR>rl4>4}MA{85V3JuIXV|x6@Rt+OL4Lw*+epJ- z?X&_XI@hvn*tG%_;5WzL0}N@|uTlO zB1oq@uPV4#N67eE&&hfSqT0qKu~*KPRTl)TXJBJBn--*uINzOkO0<>9=dk80hgM|E zYkIES&}Fd0F|F2ZS*s9uwE&WfU6ym&dr$q3`u<{bh*049aE>p><}1Lm>GRotr2F3= zo|kPfqw-9rZ-GL>S1)EAaH`7J1Ipc^8n0!y%Z*vM*iPl3T2ap#cyxQNZZ9=_Pq!`e zM6`_y)!{Q-t9;Mg8E|1j=9<1gzZgrzyo}Wh)S}NC-fFbvnzS!4+@!2=+igp44OwgYotn*b{ik5gx!ZN>Cd4Ap zrjrtXv&*7Z_jA^MWJ%zgAn?dmWmPk*+j=N-%)P{)S)xj;q(sFjkFE-aw;c{5$TPP=Kw=}AqI3f`ZOZppeH`JfIb9_hZ6#$t77|oLN?m8#7qG^Rf^{uvI2gY3) z^_M>QEZX<3l+v+$YGG(RcV}n=zd|VWiLIS*e^6vNHZr;;hw)HZ)+BR-@Q8gR$g=2$ z%x&?F3r#m9Y%1-QFAgYIav4{(^ZT{Qv&L<1aG!91e=^&u!651C(F|L$&VoZ$x3fL4 z;;nCZbiDOe8;1(Z9y6e-x4sT%S6=!Gal0~3U&hMv6oz(@TI=xQJj-q5|8oH5VN<)3^Vo2;g(2 zqI$fMfiy2u+ex>;vvicb-i4h{9Pw04f;7%=3oALyT>bVA0q>9j9RkUiD<)pt+g%dz zWU@A9wQdb^w=o-mqTX(w_T0x~@4DK|6q2WkWq~4)?Xcu83gXYh4Qdk4IuExxPk8;6 zHF2P9Ew}4WeVXS6hy435a4qDA9QjS~0-OK+0>9v3;*2eW~8r4@xt^jW-x)X!aMX_YQ&Kvow5VWu>s@MZ5h{Z4-RlKZs(t7p0z z7}xrO@)j7Zt)Zc@{#5umgZ9?=&UB=YS)HLb5-09FUQkpuReUBB*4?o@#Q}sgI#KZ& zPPemr&1&yzVi!^8+zSpp1NLhzFrmjEmZgpiXAp&mPic5Mj4y_N6D3(F`7(++XGUqj z65#bDxsGONZq2(@q68;zN#@3@#BJKD23V)1vMm&~=eO)rVBjK}qkIST5V~Z*d!EgUg5Au<2vFY;e&tO(N z;1j+Lp!6VEt6t$UzYHW7{f$S&wMVkzus?I{(An`wB#rIgO9Wq>aJH2Ev)l3Q>i6~} zEtpax(463nulvd*`D|_#!?-ND&U6imNNN5qovUh-qt{^^X9BO4D3vNDi1(}JUp zx1Y)_k!UtpqpB$JAW7y`u?Wu6!YgkuLwqx5DJq@kr*WE4zBiNZ6iX#65`0o{Y-O6o z{y_f02noY~-bIWhMXQ^6--k~#8MeNieKpPA$4%~2> zaW9k%fYDt=T2a6qhP$uMJD)$}P|}s+U!$OqXs*UhN|^p*KI@Gpec>!#9m{e=^}Zp+OxMs~CMt`D;5Wa8=lM z@=et8By#PEGz4DnZX#s2nfghUPbz7O79K8F3qRu9VPKs!MlvnIs@IbE~D_6CJQOZCkHkpxq?-lvKkG!rm8-90> zCs%p!^tTl0I?N=9ymMX}NRgIq=3MTD%4m3)ZJ)WR^?HZLcO$rx4oQ%GusykWs!3gZ z&6q2CY}9@rldrrDpA$gXT?|v*3T+@&+Pea+hhjzW_lE}kb|2oQc6MgXZlFuVE5mSZ z@?ONpSVE9{Hz^LD<;1i}Rw~51##+D4wGnl8o5)MMPpe(kKv^^daoxhCz<~rN3b$)W z*NQv*>6kZHBK`YiJ#POudM3IPx8kduJO)_GDuF5G+?m)g3P}x*jUP2b&;J*hkH0Hu z{DfEv<_2g&=Wy+pa)-{I`Qg!vEVv+NlYRkBvauvjDXCGVKlYO^9~R@j<9lOaPN-H3 zbXs1XeVcoaVF8Dp5h~YRB=EF+>7HO*QbRz}wx3|iddDLbj!+(pR(4^~3S|w<))yRn z#%nK_)XQ&ue1jl1lgagNb$P3B%EhFkb1nh7uGQ-MNFt%28FY0phY+3A@}b_3HJhZ{ zp=gPpW(ZK!LU&%gzq^(pp9fKN-nk^VVqAfo4DiZt@6Ekhh@WzRonFF2Jcc)Dj+;G& zuJ;Qabs9^yeUiZ&Mv8loU& zz*z2Fom>3w`bO%Ye8Q>t01OcLIEguP6zwo0ZtzUZW29@VZ;SkV>G5vgk@Ub z_}wlEZ|q^N{do05kr^^sD@%z>Tq0@(68}^p)}72zIf)ephh(n--EO_mQ)UWkFvEfP zY9vZv4|(=hnsFoZUVuwm^~vAoV9@m9kH!o?JumM>ND{e@*>^RI@gg_Ho9Zh;1M#ss z&371UUU^@AM0^F31^%okkmkiE7aYu0xa{10`PW@iRu20~f@*p#tgYCnL1j-#D>+Ej z`0{49^>r9DE~Q5hiO#8d?A=-Ed~57*1Vv2u?l!8AecIb~2wKeiPl6$q&G{+TT}x+n z#KDQUp`sLhEs)|nmc}T;9>}y*xUF$)t~n6DT8aDWk-1bH>2=CzRPEH{MFx9PNilDj zaL&{u3_EHA#ok@-%6-b-?txn!tw|qx8i0*mPuD;nyVwuvf1HESHPl;%Y0BR@^RIh9 zRR57RiRWYXv*KumuyMp&rR~caT4&M>E2$&=k>8~*B2*3peeJ}!BI$Db2u%0gxP)pR zkp!~9m^U3C_Bb>QiTj}LyYwvXL>8%Ar8b={NTX^`q8g|}YtZGG@}Kf&z{<(%XjRFA zULet228bLai{V3KuA<2C;u1beh%V~0<8rS9=(jgoUh=c(=@!y0F5C*XOg1{WAXHz z+8w6zdVcgi)vE06#DyWNM+Vk`5)+kvD2;Xkb32vW12Ax~Yg%pR@-j))7-?Coz0IN1 zQOEwBs`A1BAP&wuw>jwvUJmf${FQ78pB-SnEDJY|z)9eW)?h&5T#y)*?= zBC%a&YBGe#l+`3J&7XUUi*eCIRx2GyFeK8?|#E1>d*sVHdaB z3tK)!?%Ds$#m2tkGt-=0ub~gBO}76o_DGzkV)@C}se-lj7kfCkh|h*&M-m%C2LeQ% ztpT3^3s7mSA>o2+eD0h(bOy`7dGMz4x+&=iq=WC&H{;C8(}~+T>?XHWW5Z($Czah?9z90h=b&0(+lhzUmrQgwN9ZS79?`$0rvCPR>|+KL34k34w>#jJF5%oV8|GRq}jJG zBtcWJr7`$lSaIK$A$M+XKqk*r5S9-8A8LDPWBAhuIpStDxrIN#|~8gQB8LMPrK z@^p%1k+gwEJZAEEpP-aT0}eCG0?!JWBv#pb!_u0bf3ckYdE(#4MnR`-T~O96eOt92 zMOgh0aJ{sL^R<-JvE907(mZcfK4SPfWdJh2*W&=ydrf(+y;1|Ndc^B9P!#Y2`@pWB zr&xjTjWyupHp~pjdBf4MdDgLv52-6^!!`bh=3UJ>2sv`+GjF-mJ}-1`v#HFyuN3E< zW7=+(u+Bbl{w~V(m*yP~0)(LeeZJ4xM-DkL3Pk!`GqO|c;(8HsstGd2_@obxTIT*3RCezrzaTm6egr_DbrksP{GX4ti!zX8@?Bw`Sj_bWi+F15^IfjrERwt zm|!^w{QlNk^4})|-^wGiuO*8;Y8IU+y0@P%7upq()f5@T#cn~m*;_x$`lSb50z`Qi zEmr6=N1ljFBQH~gL!2Xhv6Y@G9h-)(;y)UV=j;>Q5UG=Z(XautN6li;NO3&fk))a?Mu4PV9YVXJS z+M^TG*pZe?z>iE-%5;pTd!vj!gd*{wLxq@giFt}f|BIRE>#`khKF~sMP#sW41*Sl@ z>T7h$*Ja*w8r~N{E`z2;8UD+ikiFDpb+Gm_Lf8N~0^41;z+N(G@Y(YeIPVVYBKh~> zcvRq2!&+oArrsONw}(1hReD%BdOq`l99V><+}G5&y1_$=`)nCLDNTpy>`pBnUviA* z5$<>=P*+*%H5@BrL6K-9xD|^fk!z5rj=2M^r9#??D!#j^Q$MfGZ#yn;QN_R|1t0Bq zY&CvQfqGzCu{T(Zy}w1$*xroEb9NskwSrGBxh?VA3rzWy?>skveo0K>CiJ2(TYH%B zTNP1Dj`S|91%!0>2A>Cc1F}pXzkrHk{#W$|XK>Fs{O+DIrqOlD zq5ln3%O-2i9y?E+EtWytEIo2ixq4!}#_UM@%#G6xtLJ@q_4=7PK$%ZFgqt1#-0dKk zld0fC!opU$>rZKqqGdv=LJ(r!WblJ;@hO%c8@M?}$$P$kTBI211K@H2c=TrjnO-YO zy^M>k@KA^yYE;4#3)@@SRxE?0_}^f2Jj9gE?Wy2~jj0EL)WoZY!8;Ocy9&W<%s05N z3WsgRc0`AB{uR{u+sU-;*CzIDDA645eWR0bhYphTL@-3WOumZk~0 z96)G}@5}~*CoRfum+enU?WSy**Bf3t`OKX<0$XH?ddYFbmnnrirwXn9ndvzmi*8DP z{CfrZU#F0vC(bj33`KruQFjCTR5>jz%g>8agF4rIJ?`u0F{%tcuAEnInH0FkPN(wG zgA}wHp29-4aoWw26Koy$i*c8n1mIKFE@RobPMtTFw!Fgj8$KK%iv~%nN|XR5+S=In zlzSaJlWZL~9Be5i^BT7P%!~g6Ljz|>@kX`;lnwj~Vv~tSvK|*4r(^6$0;-wr{Ut?Y z-5`^`=yT#2qrdRD_b51}!RFg3uY4`KyEY@La(C?Cr9Xd!IxfbrJ&Dd0J zY4Yoc|2mcb=pPJT!2(k~@6Y0u-!Jh6FJ?=S8kYt46#@GmihK)3|LC`}bJ{{_8Ag?9(^~nt!FC|8f>5I06Wj zZgn|k1zC&cM})YGtcfa;7gmLw)<5R8>9jhmh7P9+=>4BgrR>+KSe?A~wFgH)C^5>0 zeUPrd$~GAUD)XZd9-7o26u(-}$d~>=GBL@D%{qmsI?QcPMx-!Rm91duTuL!1>vA`=7xCuE5|oszF+<# z{V!+Y|0saKmMD>Nn<_!;-A%=G&#}kN7G8}_+P%^$?e1%Z$G^&Juv#MDpBy>&k7)fL zdg&YlIcJq!u6;Ti#PFT-ugro!C^7CCO3F@cken0;Mb^=c2FZ{Bo?kTa`ngkGq&N~( zq(<3o9<70!iWv{a9;cpPhd5J24KIddY?r(@E&|-zDCQ;MFiFHsX+J#fj;8dHVBt^y zY}lV~`+rY9U#^g3q!XP!L7V*d0fk7*%LxQU_X{}!OZqX(Kpf?v&1ZiQ4eCr<2tJ|Lztdjog~(_rw;R;+B8GV ztS6@~{aKU#_f@?16xjmHTJf1F>)+K>bKlJFwU~P+H!y0`)H60m)lwQq@;?4FWahu1 z+Ye^S;uN&|x&ymz1uqx_GkNW;dYj&25)5~vMz8>CW6|RNV7K*eW*YR@M<82mVGN^< z5ssc$9azA?kWh3**4oEZZ3H4cx=Ot-G_iegEF$gscG->RvlA8~J~$e<*PgbB=i*K#S~`&$ni(ZQ41tIg zhYDh+6qxYP6rA^Hf33KqJ+@Hb{d`2vdqRZTdjc-jNGin*{w-DQLv7mZw7r03^XJDYzO>V0oDBP`NDrm-0DwV;Q%WvK(!L|!a_ zCZvS)xTX8Unes}*I$iz27u0)x*x9>ifp`srTJt(NQ}xq1A>-dKm5qx#fx8`~&DWkN z;yNFWALr4_|1eWoe8P{2V>s@YZSSu&4gyyMxyFM{3L-FRPDA(-LVXW5-gr)zBUsGgw`jJ--Hn;&D`UJO&t^|ELwr6!h}+=o*RNuy8WG^9 z$pgVm25?8~13$_R7%!B=_uVHdp-jNvJ5bOWt-=c5J`bHJ4;6I!t^h{FvW|N)2?CCG zz|U_Rv}^`|OOibp1=?;RXYB)mV|#$xL09g&QT5Yn-3SQ;Xr{}%&UbwRJ1qx6<8Kj& z?XtkA>|nY5pk2rNyZpeQFM;3w!m-camnc^CnJ*D(K!h>yf!E4zd!e8I*{s54UQ1HY zKnw?#;z}>csWX9cqyNPTl5D@D!=Wl?^QFNoYTW8%B9M#7ihFIRtWMSqqMRF5P3zn< zj#c@i|I3Cr6Pjz#^ztWXJxs>}crDDj}bB?ClYnP4Tk zRv0~3Ht17tH&gKR0r9jt5RGNrR!z_Vzg`ZQD;X-bknx(2x6Sq?61Io5)ir-^!m>4L z_H!PMf7eM-aq>!Ex}lS!BUM4DYzcs=ViQmFsxJOOnz1CV3!3T^{r; zJ`LGxY3B~*EF9~kF5cDF*u40yBFXgKZB?b6n>E3^^44#Cqb774z>EsbkTXo3(SIzE zm+Uy^fwy?TiEHU$LuWK6x}gB(hUGjO3cnXx_q$5wzw~qwm0CJL zFkJgA^@8M=2!ez0!Ltn}uX=4~r5KTji##YBDQ ztSHELxkNpuj0g_FLBbsCV68Q4|3n6pJ?YL6!zTfU7W48OxRSu@BB%;9PMMM3h|KUL zspzRBwdgM@8KG&JeXrg|+aH7|^1JUo^zv9Bz0CLcO2lQcSh;gvadMQ5sx5@5)K5gY zfj12;_I;u)3pGmxS zb?Uv`a`g%>>lPTr$p7hko(YlojmVE1GYxo-|U@+3)!sUQ})B(fB)5A*# zzWu4PISOyD>r_9rVAsi}p}V8;ViVJ=4z6<=7-QE;7K7aZO1SqN`rI9FZ;(#{W6t+n z#)2IQ0vy&oALH*^cK~;p$0^&3ga6XczGojceS2T_tWvU=aEWC6O~rTB7w%xa)KZg= z;M+re}f zKn;71N4Mzl$QZbPGg)~7cI}%x>#c9eFW-HSd--nmtD=Cp-8m`d0FnRbDY;Uf2JSOX z^i@g4%mH3kLgO^=wLON+|7J8=EiZoIEX;kCa!yKoqPg67IT-w{8yj$Wg*?drgrDUP ztVfU>)X^h4H29*>OoK<@^>D5)BWEa!CBGSeE(3owXDPVoe^iN4LfucUio|fu!Z=`P zt>mg$4A(p?4~Bl0T$POBT7YqQq2DD}Wn#FNV0nZ9G71OdQHk9jFDLZy)Z*K3Dl6cj z7jBgotSZNGs{+f3Pe978M(2_Ic=!3;FrJ3&Bq?;RE(ca+ zGtSIQQ8eu!M&GQzhZ7k7C%Fd+BdmLD6Sl_ZnMK`)dPLR+GQ!;Puqvm?^0Gc}{7Ozz z#9@!6Q0h~o$+HhibX72{yr04#+hMM-=&rrRds*E?gm275xx zODqH3Z4Q7XUOC_FXrXCd(%nXjmQxPADd#G#7{nP-<;oY3kER)R+V+2pDYIVR>C9Wt=hUf?!@;BoeaQtY4HqtNe{DR)zJ5Cd2w$$*=Z*1kx zQxK7-KmKAC^L%rTS>$0bHEU*?eAEB{#|y2Yw9kS6j0l{-pCs%W1W>L#kXB}aaRvau z;}!rSe~w$yt#!v*l&h??As0Y}LAsKMM$NEF%7k=Q=wif|f_8dI}%-zAtYuAKGthfvtJ}D!5 zzjrW)gkhnpDeM>K_SijZ`rug%Hw!VGo4HX9K=YJ5Hs}5d?W)BxK18&!RjC200H_Fs z_+*sVUmP8C)K0g|l1hz%HCEugX;ll-|9@u5-N-q*{@i(o5o8iv2uan4 zbnAxpG#~yy_TD?JsjO=sR#9wNkuFUXRJs(Uqll;=pooa{F483Q5)hCkO+*MCu>eYw zmJq7+5}MKp5TykIB=i6w@H;`Aff<&=_St)_d)@0^YwsP#eaZ)@ z(7*W)4AF}`Cx1-zSmaZ^4Sb{2@;wkhp87mgwfx}H)p+Oi1SZKzRzXJUnGpbSx)h&3 z_ZOoM)W1F#b80+Vft?HGz7WMu;v+8PBH0q zfx4Rf8S5lu7unBkVWL#Y`FUDGl6l8_&ZHg&+`(hR9sEc4P+T{Bdz;ot^|Wj$%ZdhR zQVu8|XI&Rar_PWEYc0iJy!=?{<2U11`r2W)WV?QfocBn)LE^2ty6dTtoUcpj$|=f; zi+l$jIQEn3Ee{6TFBAetZruC5@VgHAz`~%(KnZp&&k5N&dJF17C!I#^#IGv*wwS9v zUXUj_=C`8r?-P~22m#b4wvZ@REM&=1%=DV?|qTQ_6(CJV33EAi$ahp!i zVM&p(^_)7eE{W6dvjB%(wJ((pc3F`6mg}8#6fckqM;SgZDmAFk_QO2gD&_v|hzTALLD=jRpf>KkMf{!y?YOjA3bmU@5k#_?bx z$7zFx#+uWl+=Ta#=_uvXBf!9b-ch3g?B3nBi_gBk<}|UqKrI|)zPCsxv!nH(9cu|+ z2=8~uB0gYUh*d_F0y~u+C*XiH=SNZ1LgL4TNIer8{%Xk+)WC6HzZcAZ4eSrqG5FVn z{ZbuI+$>q-SmL{pMaKrLV;qb4df(S~S&F@sZL)#<&QlNT!^ARAQN}2UD&P#loy`YM z@jtjZiH8B2?2opF=_HmEG0D9p0)PVAce_Z`2nL*-@%t8-U#2~;^$a_GH0G(shJWn` z${A_OHPG0Hx2SiK#DVutcW=rhJTn7)>wugx&6&xrACwmyG6)~Kx(sJn`!ZE>nDhg7 zWqD6=-Xj2~1As9mSBaSR)E=~m`|65z0{J_4>j6L}w&k40yzcww4%lCjXYj1K51p{n zm*=e;I^VsPBQNVA(tfH}7r}A@-LZ z6PlT8AD^GN-tqkm=gJ`SnzXX-%Mn@DBj7z5fbV|+HqwQF`xyj+4vp}ht*U1aJMl@q z7;08^AM9>DnUJp})$y}>ICqTc>9;Kd`Mr7`_d=z&Cxbpg6u1rAf*_$=uD5|ew;r#( ztWpcQsP~>D?CGS^$rFRC_-$$y) zz19sE9k>are*KrK#ve%d`_4-h>lYeG)j<_2S=4Ayy;e6bFCp`W|LHl=N?>8qD`_Uk zP0cO?BEHPc*|#r!BzKdNx#J(-WUQ6MN$OEc+p8fZzVWUcPIg5Byrem-w_2K<%;B9yzo4O8lm z)rZ^%Hdd=*GAjO3-uVOI{$ZO^^1vw=G_^WevAX^-((Pw;ROycr@>RbxLWk0({7YT; zTxEPq`CM*&_(gsmKqJMO2ag18=v2=WK2xh?YC-GlJU@-@zvo`%reE}{oYGh1q(bQJ zcV8ne!>o@SyWY6POt+0prfqxl?oasb2kbyO;rM&W~LS6axaJsrIRF zEgawJ0Rz=%O$l(+ubUWd8*a2b-j;Q{Pn8z9w(`UssOAG&&jJK_1KG%@9V6<-In29A zX%FM+G##LR!y+BJ%9d76vpTnLuia)F(7%wv<}+hLF}z@{hL-Cvd5Gn<1~hsLZ(x%X zybpQsA@<@HEdTw+;9pCSaVSI2{3fsjz&4$eXUi^;`eP3AbsZb%-~lQ}o3Q~Hoc_5& z{d2%gTTLOJjUS5aae$y7{U#m|>@w|+5dDE0k9YjR^vQaH4Y%K~&$QB6+f^Q*-9r0Z zbqnvyng{&5wk$hPX!P?>tG@1r$ZQHZ6KxJp+!py#vddH*P>!+0~{ARV<&d48dc;BEkPcc~}n!C{r?1ow<|<>n}XWEZjB z2rW|8aHruwi%PSi>m}1O5^Fkp)6+=#Alq?M7IhDg(%*dL{PFR9r1In;VMw_I&{O8O z-o&yqQe|rRmFIR%%!cWP0c9mm?ki>FYl}5fTb&r_I7oO%Zf!PD{Rrq@6YRdGN9ta~ z{0HB(!D-h`=EP&w@&lC`1Adnm8(rMI-W>gUu$*mOlG3gum1e8B{A4B>RedRVal7Y9e?Mc54lvx6l^p6dmBv^a= zWufM~YEJnL_72;uFBHPayA(**^*ve5I?{M@PLC9{?;JxvY7ClpSzy=S+8BCbq!2L0 z@@B2)%+;LEgTS2`*P>~>1?LXtlLHkS;KYFd#^VsD3K$U08%)DFvac%REBOjOQEpBq zwr3Uv7xR6xSS0|=@N~ZUaxdZy&^)rI`08H$(`?LgTS+Kz9EkW0>DXZl=1;TlbZstV z_7Q+%-}0z1>e+_Vk2+ftu8{UR{SmyjXXn2|FqQ+wcaH13Rxs=Q6;zH%QA_s@0e1kb zFC`D>O5&{eufcE|t5goePvcy&QI>GM}La z(1WjY90>WTM4td0CkVCV=k=XZ0-!5*BU>*j8G60J`s>-Ma%@f>w{=1lwSAp@!atGv z*uhu2boa||DzX2dA9|ZWg0QX2>4#f6jq+}F0L;joXE@IVxbQU{dQAe@E~`CGzf76D zC3F6LV>ae~>_CTo`=X#?#pB5EpOGp4=IDx+!nwe5)~J{Juct8sO-h@I0boadgDb~t zWWUM%kAUXIbJuI?$8)vINonz>sLztZragPFh&rg`f8~?1Uazmku~_!`?N(KGH|td_ zmvY@j$}$0ELWsgPDnF)oQQ}C<37s2!=S^03GhiTSD#j5&o)|darHVMqtRj zsCSB6|IobWoGk;1?h4LEKlWMO)e5{%m(@D3gnF6V3Lq~cSdjLL?s{`nD|KC7qRrKd;E-cm?{bYY^4b^4Q<^z<7 zb(S(k5;qn2-rtGoFp8+qggNg#sr`+M4|vylGP0=t{e>MQ+Nr0QDjs^ovw*|rt7_b4 znRI&}Yf~)~3Oq8lj@2@rXCIOS+eU=+yceWjZS2=tH^g;&lrGYhj$_^zBkwfX4`{O~ z>B>rB>_MFcKC6`e)IQ#b(I+l^hm(8PLfAiyQ z68wP~nCCkV2bfRa>8pL_NO*x^y?T<%3)nt#ICP(w^ryd1Wg0(VBR?55KrK5Sq$J-C zuQ$_@aUW>g5@)v$eATA3M{-X7Ts+EyaiswtpWjV8$eFwU)u~^H0R1tU1N;7G=)rrP zdSchdjSXBIP(}KYRZVKFdz|fEKDA5y_wmg3Ra<#u9 z`TzH8aYCDyb#a&EABOad)T2ZCQ}wfiRnl!a07(SclN&~O8S`f6IH0m$#z>HH-_Nx3 zM4I#|&-3eA*w1JGAy=Fx`yb`go>v4on!eL4?)#f(q&0u;)ffN}t>r-q$DQc5;<#tS z8KjLSJEVbs^?S0L*Iqtf=U;zfCus+8qybBpX1y7Hb!ArRjJ;qrBU9lXBE(mwIs|9v-* z6$0B4H~p9@+7C3c@mhEMci#NytuONP z-?<^RM((Y8eAf6Uco^%-$oytPHfE{oKN;<$pVM8r6-Ux&=NGTCad~W+ip}F?q4*ar zwkqX<-Ys$K?)>E7N#K4%uA5CPB3>+aK@X{wr9tGOEH|4(&}Xk6KVD}I{8P58KzA3} zRb}a_sbWtY5(Q_YNiuUO_>^Q)Q1B^1!bFLfoLmTWLL{4DSKJtLd0K?;$DK4QH3nmp zzh&RPPWMH*22ifluAL(@d`9td_a$la+Ff)kfBr!_BFfV!t=udnU-f(^wZYjt2G5<0 zwDoq8>+T|VrEMvYMk?FgP9sLoUl4M6wEi@ufX6pv{_>QKN1jdCt@1fg)$s@w?9gz} zvfpG{fCw2G-!9TG(@SscJfMk~*AEFoXo|;LZ!A(o&vm#pF1KYC7)>Ub>>`bKEbt`r<_X;R^y@EoQ_LS= zzmRzRPT8dgKZNf0UVLp9!2c?Vzr5&D=FcgR-26x%o#MHRi-5+kn; z8U1$XJuf{DvPZs|by<{JTT){1LC}(!>~Q3QPvHu9vZiNxNeC;QRn>-FKFiNojU0aS znwAv`g)2Xv$Dt~KyBDozz0Q@73g{k+$U2mnIPf4*QzI}`FzCccxRdv8+Go3Ir}U)9 z_gKiZU&vZ8>q!1e(@Vhu0Vd!D)~RfS79&#Wc=b0HVo|%x$C<$xE@B|K5Ao2uQ`tII zIU_x!tEnJT;O7kSy<{hQMDv*8lcIl~PL8C7;;_P5FVg?z!KQ6}!e^PK){yx(V?VA+ z&K~{vZ4>SXaGCS@Px%Lhn|5qEv8uv%@%6wfWbsA1HWc&PxmmHla}?4#lhr=E@UZ$~ zko_Pq;ZE}{eUAMLEzrLZ+O`*9mKt-dMa{0j1Ypj2I-G`m28P;_vExZC{4_f!7m%p^Rf4zcw2TCC z(C5Ufzhe(+7ItqjGUlu}JAM<=mjl08?vQW7Gy2c>lg3#McgYlgIgy!vKn8r^O}6~+ zzy2A;V{(O^dEx!>2R(w9p8YY>AOo+vzd^}oa^&oBw%-5)Bb^`2q>*)zZj_fSNtZ5l zivFS{Rej$438XrW4f*=GcaeWH-0U4hRk(S3+a_BGw;wq3cU$mCG}X5Z$; zH%U2-y<=E)~CZ(f%yr<6OCaZ(`WrCtBK_F48=^PPEi_ zZ92q#4n_t&L&miECEGdS{CNv?A9-VN+gFB6X8n}un z2hVTphV~J8Ql$P1V2Ob={pn-yXM;;`Hc!!Z>!6aZVcJT9sSOMf3_fz>cK`@Lm!RNI z&E^RAyMw9Cf6hDpAX`l6-`92>O1_-i{M0JiTdlNu+EHpGq<*%Wd9xc~?g2*zhy#H< zb2OgDy#I*|F^EQ~xjLxZb8YCS+im)tf?U!S-R;=6=gc{>Bh8y(Y8&h`tw5NT&jOKV z1GEcR>GeL_cm;)w*2Te4CDyY=|czjW2l##5>hPtQn`atm`&D8hx#?kyeuA z+CSsGsE_Etg@Fryu^69alO8hnP!EqS)6-h^GQX2vNKI- zzxJ-2iZ{QEJs6mZV8<7ZKmW@=rXDbs``9z`{!>6ZT1n{--x1CTrq4bmLZ-m@kz~53Hze9V? zX3K1BXWxzK@BPyf0GLvr;ihUkjC;w87KEam*LX)$Q>pKDmB>= z?Pu!#%_5x7mLJfoj@tZC{lNF8fqa<_oa@%}?AT^L8I)7cj?w=6EN_|FXNmpt{<VovpbfBrwY$Updr z!Tno)BGEgY?Hei&DN|Jb#rYnYq%@0;rvW(_uuae>jHT?h;hWo=t#G@9GWT{m0@_Fd z(VvmVj>4`|rBY=B3N~EPqk|697$)v_et4$?Ptpv4S)2b68Gk$9v>1!~>a;c%JLOBQ zJ%`Kj9xRSUDYcuYS3zrdS{>OERDwk?rqJ9rB^AAL|?_g^7H zl5fnDG1Oyvi;-;;L`2>8AznoSip3v6`uCA3=h3x^pe@X6I~FZm@`hbH^Ix#|aa^J# zI@ZSC?N})w-)Wcc9jJroE2qE0~C!79nztW{ft81pG z=a6qV`^k3tm}$W6*#{IR)KcAS2Dd&)oc<3}RQP7Y}mBX1s8JWRmv6zwl&dF))*eTqU7l9fbX zwi&7PIK})v8qLqME{?tV)-td7y13~Uxi-IIJ3CHL%~%P)_AhqK*QTO;hgQa53x;ls z&D`$~rtJXkN?NWRwgYsD0h-cL`8T?3m%i_GzEu)>BJ5%k0DIdbS2S>j;vZw`VcsI( zY^$keKpq-NWxY-d-l;_kE_=r89{LyP+a)8xAvNVmK_R@;3HM5O>(&_kQ#|-5_NZeR zDhtR$I&MqDEsypSVLOKG9?w@rsxp;7WrTmotbiP)SoO&vuOsoB!Du^_{=QFOH-+H8 zusd1|SvYSO9bN5?^T645&P@I0?U@m<#$8mD16H=1S8hAj&!DA18SC(`HeGz~kT44w zb~B0DR!YLxM+h1GsU`i^;()Qz-anxqxMOqpO5L+po1~j;W5&SWUZeB$Hq_VOj;m$KF$oURO>w?KF&(e{kgV_4yZ;)PFn5`)cQoBVKwc zPf~*OzqlNUZM>4_AtfmT0lXdW9=FJ+ZULt4ND@Y0qO8ndTZI6~+;pCN{6O+O#~pegM)r?Z_(U0c|b4*wsp=*#$@r(jdE_rx9wt9 zk6I|=M$jf%&9ZD1*2&s&L^;i6Fr2>|DD{B?sZLjRU#GkiSv(sMRCQt;e*Yz$;}rc{xO^8QugPyBuf!VVDNN9`AT2 z(`mUEEeYXX7+%V*IM#E)W!O8$hlyau+ZPYU6;Fa1 z^|f`c%r?cRXMcOu?SbkSE}Zqr$u2Ef8f`Hcm`z+p%k+tyF0P}ODAk!OL<5_cPE9Dw z9eM5nrNacNN*>^<+iZ8+@+9@=Fh}KmqIMp#4QCQ4hMtc?v*xPzhKbZP`*XkURGNi}s4cLq#cbaZLD_Wr;EudMlEk>4~0kKHk$~BZfid?%wo13Uz z?OVc;R2Z2GBTfZQtgSArC`X-`os32VBRVu(KA4vukMiU9e z$%J6Si^CyvCHsoGtL-`;@rP;5;G5D_^~VsnPQ7lKRTm&7bH53P&+-)LFl-P_ zEmN#ss^-t0zEdAfQUwb{?>Un9<&1Ht5;c{R`jOyL{EKBOAY2rdtGF%G*UdJ8+NRI1C@)*9!+yc(^aau|}Do^AV~xk^B( z2SrftcNV{IIt(42iM3BCa>yj~zEd-qDONt`;|2}aNO!2wBM_>xIw>TYB<@6EWIEumMdE!dG)I`Og6KuZB?zNp2!lP1dlyhZ8c)XeVzd7V16j+ckAO)Q)UfA53tNIYiayMeDMx6d?X{kg4H@s_)Oo+NQ!x?2M-fx=~jXBw}i%hFMd6{MTOpu8w8obsmq68p7< z3zqEo+elbQiW%ce?p4FojYDfQ2v?Ey&{IVd$E%@RA|l#+17`iWgf}6zZyLS=#-*c; zC>8kLqS5Kya$n8hVHHDRcOIECgTj}*92Wal!3~XQQM^d!=^R5}=3Eu~W^S~xJFSDm z0$xfoo`~jcHgb0w44nw4v8;ESBZi5FI4qXau-o^eg*7tJuW=d~5{*s?<5Dq=BOU(#3rk4v{ACH>e_2A2^wNrf8andgmB;Bg z0zGfmVMwKv<52|YiNQ&k;{K)cF{v+ca9RulaKjgh9Bt)huVFv6igb}+8cbHwM)#s( zGK1@qV(c%Dqb=~$EIv7bV=idMe)u&4GcJ&rTk2j+FkI-7hnb*C7e~!!?{rQq)jr1( z?bf)P@8g}``_6qW27g8A&*^}g61&${=iy3&Tm~ca5Zq|&cja7Oo9;?VrPsyyLf=pium`m6dX3B^&J+=OSpMvW|5X zl~_WllH`(Mj$6vfJFhl_+ID>IPWAz-={E|+IbWEKLrnlIutav1D>D~K!;!)7Knhf+ zb35=b+B|BX-7qjSJ((~&VBKr*miw)5xH9w@Fg>u|YC?dDq9sxDl;tqSxUZ?hGPnPt zBH=Z$ezFqQuiw|y-UlUO2)LDzRr5~98zMSd+(h$&A5Rpg5f*L9%LAuAOo!0&pK+Op zmycUW=9lMG%XD}8;dC3Ho^V1<+xGt0YSmK*IN38zRurSmR}^q-ID3qJH1DH9Q6T1} z6E5~hAqG}8E0lq7rZ2YIW1Nzi`|WmIb3aGC<68?UZ#t`In^AFF#{BGL6pwG@?)EE% zkCX_J?Tr*el}OemEjEXsM9GI9GYL4!P!gLGNh&zn(FCHIy_!L>(mH-jmtObNG4I`B zw`PTWmUX3Q^aV}|_7_mtjp2YO#6|4Ae?!h9x1g2Zx--Z`Y*J}~6J`rRrjF->HTd%^ zMqt&vlNAnH=9A-UQt&GJQcXH6Lu$rao0r-{Ja3jIA!uHnkiS|_nNFC7-y!(RO&awj zXu>lG-&i!8Q298!j1(NK0U|YP9wqTQZa70>)zs)qo9U!TS zY8(iGF0Jb9O8r?4DFbgOC-NdqR$O*-ww<=yh+MaVfZ})?8YIuFKWQ}qhN$E7YMS1q z6D|Zeb$_6SF0eXrA!|xpERFhnW4Z1^L$LUv4qRV?tgJhMcCL>wg3FiccWkI;m;7GQmEVNzylC^2-IqEl>Ue?(> z<%oUi89bdgck-~2{%EgLg?dz^9_wIW7S6pCZ)=aggErjn=7O9sGfR6}cZ(W`07mGA zx>smAlSpK<}0As>rp6bGAq`a>^*NR?mUpG9NF*2y%FvvV{-w3AHSrdDPwfS4TTfs*$o6mg@ z7z`nC?$_C2i%e~&^RaUA0;}nL(1wu&hXq9ikkGvAY(s=a>AX)j7#1g$TXfUajvn(3 zC2F>cr_1Q$igs`2N8TJiE$&$3-O;SphqI6puPBh}guiOGhuall3)8?OKX8x*PQpc` zcE5(p{IEP;FMyC=f&aX~3Inc8XnvH+ZPMo}4l6ci?!(pPe76vJZII{^lSCwT@Z!c? zlgx`&KXv!oG)33hV21@{vD!IPo;F4(T4G)kBi-skhk*>ETrDnA+h&HuNQMXsOlE8e zuve6IK|_x{mPTr!J+5&Rqy%7f9ve0|oOD!%2rvr68YZXQ zb#DJeP4xArA3IYfQ6bRmbDdJ-LPr=Df|)eA6@ z7uB2HGx4r-d>=YNpm4sRl`v8s3!`CLy9zB6)ftOCSG+6;37BRxmn77xf@@gSIAREs zZhgcC43LHihJ_t2KwVyoFwsM_H;gQjPZwCqXa(M|aUB^4(v&LE4l6gX#JHPbshAba z-%h8*sn-ObDK^i|asBnA2CYDiWeGJ?g4<~QH{$F0X#_LsmH$WW1s%&WZRjx(5p!Z@ zdMt@N#c|G6xlRPzy!B_dUDh7O8jzAOq#S;A$ZCmeRNMWbJHlVl7}b~AXaYyni6G74 z+UWN=*m-9n_uxvCB&vbjBCV6iIQVK!YIV7!>7XODS)ei8)i=R@1(p-i?>^EBXG%(R z8*EQDoFOI=3v)pyzr+`s$JZ4V4n4CYSF`F2m8Y1863-YH+3mQ1J)RacX0}LozQs{| z(%`{mftQpmJ{y_9(>*8$Jd&s8URhZ*<5aqZB$f6s2Km;m0Ac~}?n%hdk(IU;YLhLZ zmZ`P()^!N%b4RpmKut=eK=^YV*78N};MuPw)jVpG_BHqC@b#Qr{hcML4IYu~g_Bo4 z*$8RhRggqHc;uEf@gX_WfnKJS!cHXdI@X!R_)T-9U0*uv;blUCl+>``!rP@+uC-J? zNz=&$2MdRlksDw-y$qj%*f#_80h)K!1v@?=Fv4wWI(Bs9k;55Bj0RtEYE+G84=V;1 zJLoX1Fz)Xs^vT4D9qd}BshE;-cgjFN9J;NIlpF%XJvFhmcO$|?QDOXbR6Wg7_IBtY zW_V9m@|t@I;kjM!%o1?nnp@{Qe;aTu2Z$;M5gRpL8{Q1^R4TQ`*e8}4Txfj?B7cDPGeI6Yr?YX~h;=J3(dH+7A&4 z=Zv(-60TFGVRLP}k*a~NiP#Untr_Tq>}tdhM@;J1_AKC*OM2fvY-GyG)XvnRu!9e1 zGNpe%=^MLpDXowjh^Gj&Cv5)$9_mzHJ zc(5!M^F5ncT@HI5RH4eDCffb}F_#^$O_UTIaf{I!P7hG7;=Eb$`Di70g|GPPTa>l; zO7Mk%B_Pws681_ow%fKUhD+c_+ZE^iT~Xmxt;G0Ve>o=Zx5WDvm%G2GM#Ucg*0~-*m3qH%@HsA}C0=X#bXrz|oNZE%$Vf2lR8xb0^F@%rHkC+^$0GcjVqc70b zEJl1|zQEf!aXPt|s{Hi$8|_Zh6qMayx1xdMa2NP?&G?Mw)2LZrTtU9AlqzTuh`w>v zARq^hsD3)?U~k)_bh%?_Ty*4c)1swmKRH!QK%(RU z0WGwWB*ReUNz|f@d(GSnHB0|YgVdgSDy&U|@V5dfH5n~M>8J28Z>wGq@C*n%oIQ212vJ{G-&+Cx=e(a)w$bUYjF&Cu??Lyt!do?ddazej4kZ-VStLqcW~NQ**L-<&sWQ zgtk5_&g4x`M#&0BEh0OZ_(?u^njVH|4|-*j&^up+!B`i~{ zrYVaU&R>uit8BQ_JuV6W&pp>4`_Q21gmcs}sAvQD5%;?p1rYAMMb8f6>*1gFby{Yzy5W011UhsCZB1rgorPu4bJ2Ti;gH70L)xgB*JKh z%WkRZb(rJOQR?Cj&POF3PY@zG-LG-9jS%QeoB%#H$2rKQnl7nsDCh2s@T8#5Tn|(% zL|8@(yX(8nWhVaq;lf+`v;05Y0R1mgTn6U%ORrlQI~RUcw269+GvX)QVe%6=M0(M@Lk2_2`ece_jb z!IvNv*3Bpq?>}ND4iXxXSJFv9Lj69tQP|Z%B1J~HUtC7n-Z68R<Gjsx4NrG0P*Gw|8egf^Qhhwg{Ng;nQ_QDJHI%elp9vlPUw zQw}Sm4HJXM;u{-NT_G6-Gp`f}!%5Q!+_SB?V0=zx&i2I?Kb}}DlyE3KtBU(>&Md>eXeE_6z@+crxDzwv4ojrdePo4`DW22#yS?cOLZ^#NM zArUZhQic{aX}=7;LICT;n@obvJa;|XVR!9yU{#GWMC^X#4QB_*p%Y{ogs|ontVO`8 zWsgH(^?8oGT7UZDhvV8j9BdeS+4KoBlmraa1Hr-?lxggZW9-<+SBJzZgdsd3<0ocI z9&2)?YCCj>Rsi^snz@RSQz!cTnW8GMdyOfnzjCvTydZ9h z`6uP^nzHS7eAKJlYOE1j*6eDT-3zQZM0gzWg&)9$HPuJH`D$8VPUiH!f||R7!m}-; zNaEc$@aQTYiQp-UQ7a#VdReMz7@3ae8!8UHu!WSMz>}*A3YHofm9#GNRWa#=+)24* zkbkNRqnZq{xAmxP4<6CHQagrO$u<~|L-kq}i-PMfup=rzPcX@6mOAuXhJ6!xNqN?s z{9|e&55ajkk<+F69LKKLQIf^g-*bup`l4ym@Jj6Cn@(D7m$8L!OLwtabQA3%2$0C# z8w5@>cR+o1X|i^Z%8tibjhoZ}Y5O~9 zzM*&q`C>}YgXYSWykTiclc9W`dNBUdl3U(n>PHkmk5Fi!DwB~e!@H8ws+7Dmk=B)P zI?QDqgVMw0uL8Kg+kW$zn;rH>UkH-NK73>FCjEh#Z>qb3RTKDfEA@Zyk-yQp1pRsD}j}( znH;Nj-TJ_Ez<8( z3ts?aTNB2xz@@Y>yaPR?`iya+69V_PcM^^m=^#>DbQYUG^eLeA?1QzmXU#v+iucvB z-&59|d|Edy04QCzNAm_LWju?ZG%T<&TGg_@e5gAlHPP)m3}zQBKgeK<+$*D{Z~@sz zX4?xo=_A4{n`z-qv0~i_w2sI*)LPHPEn{3{M-(178+g5*raCxVDN)id;=WfpmmICcitc6ub6gU*0B1mt@h$*)>tZ8#Fp*^Y5;Wd3i(K7mK-i_@bhb$IH7D#MHe5ixUMuJw+Vb1Jx7 zCo|u6=`+RrJBbD}f0g*q4F35i2uqboeZM+3iUJ#Rf`;PDF{%JA7@a$h&oWT6&%Ug~ zU0UeH-E_5x`I~aW)AECt#!%=drjX{{QEX1yc$OIz=&{a1$Jf(Hv$bYPkScq1n&w^Y zYW;BhP!>}uvqNXg%v|}P)KlSBxh8QiJ4eo3ea+{HLRUBQ{0!pVy+AEQ{LuGE83#^A zv#?Twq3%Ip>=5=ypNRF6OJTb3XDo2mv{4FTvfm=9sO=0-)~M(VqvRk(>+5ROnm#^3 zrk>UDrMJBR%hR!GThU2fK%(GC^jx{9j)zd@VLlZS0&r>8g4baFnX|U+1-Y zfL;S6J&p{f^SCcrygA<`P}Uu3NpNc^K}KL@0+Ugzy_3*>9s^#Dnqf;ah|bgZLcFrz zqBVkVoZ`UezMhivHGK#lqZBDO9KNW!xE0C(X-ci+g3S;LAS8Q{d`bI&jMj*Gjg{qV;sBhX$YyFVt23f0=#ty8teg`L zc{!6Nc3La>q1!^+F+%V#M5^Rm7^kNRorsr;j;LFweO(oG?JBXq61=@mN6go_5IZMI;ASz2{k6;=_lBEqt~hSj*A>QH zsUiA#4`bU#mUXjJID@Z^K!c8W;C|9rBBX1)^DvR-2Fc6%J7W=41VYx zR+2zORw+Z!Ai~6&uUhP5MnW0E3T2aUXEit!83V~Wi)$1d%$2Bl5K-gcW>ad1%3jm< zS;jYs^%fL24@wC>a1xa3jzk06bV+q8A$hX&MrO3we=j;%{7T9yekEm6SxxhFN&2At z7tS-9C{HriA|sRdA^e2J7z&`Cszw>s7-yd5+r{Vzo45rtu_)<`dlN?25H^k$PL%vw zgG|PpYPv}MP_(C-|5eKv%W(ssloh_9hjgR$ah3{%_x9v>-eSP_*_Q|@T~dTU>PD}f zK=pMOptA5<9Rh1SJ_VB^6RL~T-O!^lS`S|%M~ztiVvE)wj6bzBhd!byeH;?N@-(d(dS8rvL*CfPv(J_Kx&$hTCKVFiJDB`uv5hu zZ5scNP?K*jLOGiYd3)?z5E+F7d&gHSvdh#ss|G;cgQ8{`4|{xrvh-*%AdM#|S7x^s z#SYg6eFev?Ae)Cc9h+`zi5iT43SRWqm&@*|oq!)))^=}Ks<{Z;zxMsuF%zJU#9#R1 zQ<#`>*d&%xbiaN?-}E~HsXjHSEK)5iN^?4cFwwqXV`hSKG`|s3$!;7Y9{t4uRWeTM zCK3?Q8)tY|8gXa7>O$HQ|EztrKS4G4Zm|DBj@U17Tv%{_At<55=@RL^I^b#J%qv=o za~A~KVpbU0IIJTlA~S(%YJ^%z0eT2=xY?l3omZxBo^Hap$jgxkbc!r9+29wK3QL`f zQAK(wut^&J!E}MmdG2=oZjVeX6m%+@r9Gg7rp!47B=P6+$_4WW$7nIDd-~Q^mOh$e zJ|;C-t31^`IuAyf+yy9{6FR<8V+v3MV32OpL$Pbl_&Rfdt#UT1XCg}wR4Ah*8Uw_H z)x%7!_>e+k2g8FGa-c`T+D^?26qd+^3cfb55?`puD~+ih{mH5>kz}`;f^-WMu>`mx zPQRf_+5N{f^IUI9r<-q9Z>KWvi>vWwl0dVYNTYWoj)N&r?L$_fxKa^D>&%O4Q=S+D zXlMsN-bNvkxL6Vq#zbl&$R^1X^a(Ro1o5mY76;8K_!00ZXRDn!5NLoFnwo%4Uu;or zH2#uIaUF`kQ`@b`&Roo*FiWk(mgl{eUbk#I0cVtA1r(e+EW+_uVNxy_UvLQAWo2bj zCsVDC?!Ob2MME}3<_NAzGCh5%G3;vv#z0)Y1YrKH?|Dkmo;6X?i$ zFDM5>I>49nT#yM;E;3`nuh5^=itX_x1Om_mVHPBZwbVr_brV2h)(lee+$FlE%+N_+ zy%hW`SNFxhIOkr;4)N}p797C{c8Y}U>Xk+mZS(ys6n6fqmS{bR zhd3$Gk#8k6y%KJ#3z?m%L;rnW)g04C+5I|nqh|w8Gx|WsF6y+vzWu{3CxB97ZpxxB65lKbE6csQ_Vr_lK%VSAcjXQLwhehSX#L_F4s`jsZ+w{f+^$7j>!}e5?h<| zx};|YP#(dTCQb4v)XK86;*v8Umjrmq>MIXz~cgqXw)*Dt*#K7TZ#pF(gwhPd*H z9s`6*Yp2t7Ko?mb{xl-)WPudhi&d;qN=VORyK$&2fuS;czh&uX9KWxAf}2h)snMYj zTM%bp*bvG8-(<@dTkI9wBRk`PD!93Y!C{%cW@Q?iiuosno?b#VkJ|CglEb@9LOYC8 z@CI*=_9)ZrR_RzS^G?PO`d$hC}Yn8diN^2jW2d=6?@CU_qT zPHK&avznCz*ofhb`Se@O=bFHzt^sLR(LlzNl*>zE)x%u^r4`^2hfwbkD3cmM1w{^i zs5fyAw}`2QD)l1^czm3ZZYKo#MYptWZbyUv@tpJS#qQ4pm%r_c3u_h^qc8`7g z^u9AtmS?k)I?>yNA2yp~!mVOoV45 z4{RA0l!K+@dCp5CLj;;|@2B@J47jxb_GsXeD}#@%n{6S{ES6`& zf0}QcOJKa=qJ3rCoT9ZZ%&@=g&!H zYYxNNrHz4{H1A|m-l`v&gh`cF6j+VDgCz2VylkO$&ZCKUdTOA~g*bwPcTP*fpTs1V z02?nIf~98Qe@Qa3LWRB+zftQ)lH1AOmyNg z8{Qj^odk5x=47C!eJrsbEqLM0U0U$6STlu#AdQ8dSv-2)9prqg5r={qUi9eVNrS<--4k{r?K00$%*S(=n! zgFlQ~IXy^+2Tj_w#wYSj^OQC~(wCNr`GrN*%Tro34jG>&je5Igo+qxNntO3rSe%{Z z>pSpQOF&(_#VLO1lMPMl-36&1&nXQ%HSJ?(OI#W=#gRP=BB_Jwfc`H}AdogF+~QdB z6p{iJ&H)LU`&fx{RVw20Lo{cH8?fWxZNmcXo+WV`xQow_bTxaz4|*9DWYR{=(kzoK zbnkP)k~#@Elgl4uHXFgSQT8XBf#x0z6@TSNF}{$h8=GzqknTf3BhVCJ>Qkl@yn(yf7$dw3tWkPX{&%9zRxDr!~fHM zSF@PYF`r8D+A{mAr?)`aQdQ)20XAP z$;T**xSESe4TfQg-=e%uu-&j#(0~^&>g~ryYB^LLjMA(!6JX+RTO&kq!ssECm**Tm z=aJartoXsgP93MWvn9iOV_TKFI)QAk##daw%wEAR1lPpSl)aGGJ~Do#s&u{A?2ALq z;4)sFqfqN^=>RC;5#AkZx?i-4)9EGLI*5PB`Hm0?#|J@Xc1slCaR~m3z*KD?72#4vql4=xAjVL5j&GJ?Ex5<#`>aAMDAJS{dxYb;^*UiGqsr z$yxYlUqq9XzV57U496@OE^414Vw_dYYjXycBn;zq=59{Pi@VMOf0>F$x!MKVC4fx4 zwBcdHz$Tn@J7(ipQZeo9UVeE*^+h$rDj+X4S=Lg*q%z=_i+2Bbj(aSiBrx<{|%V6M7q`6;n~ z2uHiL8X6Ylob?IeP3FY)|44feuqLyneOyIB1VurmNl^q8r8g-FO%wzHMVeIUQl)ng zK~O>Iy@~W9NQcl=5QG4s1Q0?|S|IciN`T~l;;!$y@3)^nzy14MmtL!`$#c$`nS1WJ zXHKxK?^M_6wS;`s(6E4*}rH0bn;C9allwEtK=d;kD6a%df;8 z{r`REN%)^c;*&2cIq!5JM!B`*&Je8~bVu54GY1WPJm${~zz{kX3Fj^F zF`qDwpVAgo?Z&-;9MU}JT&*g{%-x~UlZjTjQm%+Bm32N4K}{X&&ZLa6R%tT>RpY?E zvLH5kh|KSjC<{MwJ*|caFDr>cU#Eg(cuc>UP117P+ihF7%iTU(R?`=mcE;y@;--y} zaHoOJ?REnxAT3nU+C7Vv!roJNU5Y->8PajBNyxzM(Ck)Q^)uVXiZr;U;J4whUs^p9wfbV z3_X1=Fa?cn0BjH$PbwZL#8k9CwR6|i7H0~{x6vKP0ul(7xb>!{dcLKM3`%7V)i;1^ zY(lHbco;(F1!}}Kl-=X1O;h@{^s|dc+82Agus!$W^e6UlvlS_=68*F}pG83A9pXXR z195CEI>|x=ZObc$?oQq50i;kEAz_z@HR3{c;?&I+x3lw z2Zun5W!GL!^S81tV$)xnTR6S?);y8F-Q4Cw61*sdL0*Iw)JlksQqi-cEuN>X01Aw; zG^fpou8uB#)MuLw4r^1OIOIavO!f)(%g8V_HjqN-v>c2v!aJG#{A^$atG0MeDc z6#lkVf6_r;RV6iohN;~+291QLT-DnW%f*7&ArX{_V_MG{WTCsp$W!H41)7G|1Kjjx z^>w#Py%rwS#xYBnwVqk_X>t3k2L^ooO9C(Z2Z2W?`6q!l{V|0u<_OuSJJ6$lY@)^k zRXPv9H)xdbY&n^c&a<;29NAFcD(X37q`hu}S_T3St)2W@gLPhW{h{Zl>y5pD{3JP^ z3sW`N|KYX>lAX%&T-*BVkd}KcLr>NbI-bGLmOQ|eCw#{~!Y~yct8euHtP?uk4c$Mz z3|dfpEh$g)3r(MnG7~lMdEu5kqmAELq8S3E9!zr58*T5{Hix^;wbp_~EMfJPmGQ92 zRy72R-0i(rr!-Uj7BGcCqT+_Az;lPmN3^ET&KrQ@Ay0|^qZYTfyO{o9+a1lMV)dPP z(J)~HbV4y3i>)A1bkw=8i{AmxT_yCdI;UEH6f^U`O931sx<2hu_e~itL&feLbot&w zb$>;s+k-F{Ty!;*O;c_kcSY5ip=xIGX{(>wHN1H9U@3HIyC)%G-BdXkrZZ*qEDAbV)qx<67E*|q%60QbB#I~ zZft?hM2w`X?m}_hqp0<=_NN3y&F3vWjRRK1i*ty#i}F<|ojD6y;au^hgwM^VHE*Yq^KwZ z%$=)>()GD~^T-8$0kDpMw}>vIl z$GKsL;+jlu(BS6rFex2sh0N{Z_gwE375x{du^pMH>=ZwU2V9#sk!!23x>hxApgaBL z(zR{z<=PR3s{AjUh_{sq6Vz$(7l;b*)$97G$~Bw2<8)!-rdrm%OEuGa%lnBA3k`kd z1HPsUMDBdLp`#&q6*nkVFN^}pdkfHElGRroEy4e2`t0`F-k{7UY#(Pa98@G_(ATD{ z8UUt#^NyfR>C%}p<*?Wvw*~$10I2ReL`EM~C_Cotu07;Odil-VVxAtFy~5oXFBnDa zwr-e_!9`j;4y)N2v4M9E6ggX4)yTu*;ibGoIaE~pg;#teAMHLJGG{C{*g1xhKbt5K zg&u4KRje@wcqMMq{v-CvjsZwxDwQ6=|RH;%2=lLeH?hsAi%1TokAwus4KB zxr;Kzm zVduEog}&*Ng57T?z1ON513J#uP);5G_GeeunDTkv=*M50eLqF>ZhwVyM_D{4EYZ5n zG;eXd%97wXwaQYn8@cd~#I1vf4ihBVG@Cv6-!`s1eO^YNoyHM`dTw9UPs&t62y1Mx zx15ZMlAStCU2}XdR8YC^`GZJBXd1EXIYjKcL;*Ej8K5MbIkco*!_Gf#oUZ()rRQ$S z;g+ZksuX3!>bcW&L-Kpp8*`v%r8|MFhG8Fc{dN#l_-)gyPdy67NoyE`&XF18d`vb5 z#YYeVjzP*rk})QC@$mK6L?r`SXW958Tv3v0+{IzWDQPYr$e+RO*kNwan<`?iX~dZB ztQ~`@grkF#6|x-Q4%|WCg64}N7i-a)36iP}7=4}&PysCTe4{wd-ySs5BliVm4#x`A zBn5c4sPKJwrmXTgaybpO?52#mp>|Seteum@QE{maP>J=-eF@IbR~u%%hk&lUe+L>% zH(kOFq|E}lwlP^{%M0tB3j^~ih$*LxuI<@^1`|*vh>+4H|3A-PQu}&ky5oVtwgsz2 z$9I(qu30Rw8}H}?WI3Ho8An*241q?j=ehe2{C1uyt$~peKW2EQ@pp^J`E1Pgq}<odHh?CSwaUq1g>6)%HO-ER~YbG~)ov50? zw8Y>)27iD5Ik!U^9ON5#1@>Ii-=<1!&X4u_pV_`8<`hp0{0F_0?c_1JdJhhP7Q6)@ z%;$LkKH`o-F%TJVu8^Fm{j$0!3de&#Ub|Zp%$`AQhQzN9{H^u)S0?keOeDMbo5kz* zx<6i3>_-{#S=Q|{N<;yiO=4b72UFS+md8UtSJtYGwi5bjhM>Pc9~h8XI9_l)O7nLW z6@B>)^tb)fq6LFJzNPsmKlmi- zDcH<|s0CHUJ(ovHv{t@p;_!7&h*+NuydW6s`|>9XVE*#M_v7>E17$UaM|L-`bQ}eF_L0in+ITu zYp}qoq2JD{@9Qlxw(Dqy0~EQ`qi;g@PRzzlQvLM>5do#UC=vvcq*EoGPB9_Db+ zcb{(qGJMQl8tDEu2Rz745zi>$QuSA(oL-Ars9=u7pmS0_PJ17Ij8}dyT}EdK$|#*8 zC}&?P!dEgW%YQ{Qg8_u&d{wso=}_|!n-NZe)ZU^CU7X(Pe~lFHzC}FyRCj8P22G9X ze(pK{)wG;fTJK9)F<|LX3l4-WelTuX_wrds;d^C8LB`N{s=s{dQQ~AWq$l|YQOVzx zgAA`YCay?=@u5rh@u*7T9WSkF=wpQo<1BUIi#{`Kdz@r{1V=@|cZ8a-yIX2o@1@DX zT(#6=M+%}2hW+k4ct%$iGRS~9W4l>R*rmgOK~pc--x%u_MSoO7n;ufhC61N#7XcxG z8GmfH5~*48ibf7{NF(rM#@}YI|4PMwL)VhV{Q>xl{o_ukv&7FJK6>e0XYv#cBZf(% z!ugGZnjSNPZ%>CQVHkD!^fKKbSMFUnCFRAR*Xvj09LZ(RAw?4~^2@HQb$^_=T7Nyn zIPR|rUg1@`K^#AmwG=2G^+1na{P6Q4{c^a#6L$B4;J}~vqE(Frp*FrX(pqX*zs`b> zBKf}C{<-vYTQfInXpRtvZ<`3i=3ms>2H`eQ_TxJc@97w=%KMfNR2c`NwnPe&mh&#aA?Sy81i#x|zWl;YZF3yiuRa0n7GEV(AN5 zww>uXDuq%bQPbCMKfC5%&XjRuhfDCA|Ht~jk1r$+hX>CIBD_)rCk0$3^rA<9@ERY| zBpM8Q{_U~aEqAqOa&&(-nLiFR-9tr&hk8#(QVYTptY=`~w*~WkTl&D#<)pY`z|t+0 z!beV%4_qKQ^S8D8m0;n_EqxJNqyILaKR%P_1HvzUH=I1WQJ0q)wn3gG!c?-iuKljz zkjG8DJ;(4rP8b`vBHP=+GX+=CR_1h;RNp`0&m%T=D+LVWi~c!K{1TDoUCmBP1nd2i zC;MTW-!1bZz&ovKs-I?ytk2P5gfBBX_qG3QnZI(um8A-*?%i}45w8(~&tGRZwEW^r zp(0s3gvRF%VW-iM@240RI(rZIK}}Wr_5;fgf5Y&1`*%}3t=XqhXZ=h4;BIikbe^$Z&YBCMBz)q)j z4s2}I&?J7DINScuCzJhQro$OWuOeCVqJ((^5IjwC2hFbM^ilT8EhD>)EXpxEWu&x=R_=l2`&5fpg6?*ty5{2MI#)h#-8F(MJPU?}sb zdDw1a*q_k}oZ^Vs%!n3^&xqw_5{&?+oVE=YLr8uB+2Pntg40$up|1Ab)+ zbMNLKY#Q4Cp7RBv4+qq2D1aCSbS(M{Y`S%?{PtODzX16rWAYb}CxUtK^hOHxRv)W@ zXq^`v>~P@)U*u1C0$lF{;iu_GetU2~DQ`Tv5%Hp$Ezu5JU82|f>uCa6k96esb;>bz z9u$5Bx+!-Ts|>-o=>&^ZF|}_`QX>5SHm3epyK=Vw-PI6LaAyA@CjR5L5E1 z`(UVG*E22l^J|vBeZYE74;;o2ft_E|Nac|qu=Y*frVA)!)7CQ>fus(lhw~Ep)`SovOP@ zn*X(5ST;EeE^2%Q#cXO>`W8J;WQCSQWo}6Lo&rJi|?3fdN#|YG8qxQ7Tr6 zn=+E*zui9lfx50=?&JRnXcb`3l1feewigbEKX5g4`h72aKKNWO@WO!b8MtcOtIz&~OfJ0isd4cHWHXX^HUP2!mf)$X_YxZ+R}3aK{gJpQUAf z&Om?FV@PpJ`>cHOKLdLPt@BlAF4LLBnx#*Fp%Z|&r54^bfqCKJYU=H0X4JA_zkTN) zgOdL3WV;`p>;D~H>;w*5NBDpEn=$@EJnPJ-!Rz(#*8k#%>x;C_#IyvPq`d%F-l|p% zf2NYfLW#{*U}=sp{&~HAm9YzbVyNph`S?5G@dPDS1kN4m^W|s1{;On!$raLppZ`Ch zUgFT5M^`J5cWcIn{0O__WMz}bymq!H!^+AKPzgp+JH4m%?;ghdt_eMixgTen1n$rM z9wz0Nf_>Msy{k{vuTIPjUHdC-rF8jk(ghHg@#AT?1(7UX3nexY@@MDvHvRBBXfi>C z&54wsQ}ADeQT63RamN`_{`oNeBl|)o=fmfz5Jicd43mOxC9#12bQ(bz{N|ObvRXMi>+Zd}40KD~4IBE->R)*S_9mNmMEbC!I5FZShm0_$zAA;1l;1QRtt5 zXn!PZzJ-SG>j7}*mkx>}a+84D@ob-eitY^6QPiT}3f zekjS1y_D9TT@@T!qdkCf4`D3{-EUhi16MY)(!vi>@QO!k59ql~>Pe~JhS+X~h~kB# z8*m9xrM8L9DsIVTo&0V*IRWCDu-)*+WzP+Z8s8~*!ko3=OXH=El5#MrTfD-ccsO|a zlMNWtIYS0ULmREd5C86J3svB17bh>TaP2XfR(>{P%A9^gEO%bH80;(Bdl@&fm45o1*Mirqbmvlr3e>(1y5zmhNwR1Xzy1tl zKv3m|pbC3Rth3b_Oqb_ODM0%mp-1i5K_{NEk>b?p0QWMdZ2t41_?7!lRQ}c}Ee<>; z%d_BAl%mRrJ);F327A=$=<7~|AOL*0cO8YL`(PYg9I6PuI9N;ZlD88&2)^5=xcfX+ z1o^YNR3_>xBzBEwWaz@)pE8H?P0R-6IO+1nz`$JG@mSuB-F2*hOIX; zC+}sRI(2f6Cn7w23H%_PyK(E`Ng0?fEVEWd`nuXX-NLlp#?3u3gqX$5n5fhIsKk1G zh52HQAm`=~+DmYE!M;n3!jgao$XiuPK8JLPCW7HzDDu6v@*MY}Y1v`&N;dA#^hO8h z4v;=RX!JgT?xe4OIRA9cb*uV(zhgP0I%m6EYtmAcruclnR6RaD;&xW=js5YX*zUtC zCodiMlL%1TdZ{MmzR9x)ap>#4)2PTe=K<&CFYpl4f4ymy+UQNe?#bbRJZ0JY<%G^z zl|b?N(K=gEIhMC54@uU{t<*_TO0%%U4Fl=+N)so)-XI#+jm7uOmiVR5?`up? z#?8B8U^g0E32}zL>0|X?>T6SLtqs*51N8Jlx~1vL$F+(_!KQ{J&?O5kJ9E)2!9-3?Yp;K zqWOw95Vy0A&eJH+j23sX>J#6#S6nAF-807(y_Xqfl$Vfi&p6oUBYqH&u z$(8VmHx@Wij$maAHa+;zXu)QiPM1s;;(k!_@J%*&B`Y#ORiR>TJtB-JLk`tU>i-O8g_3R<3SFe=#i61=bhY=Bi+@=G?sH*7aw zDVSy6PSRv6?d(m|M>Y7=MyHYErT2XHv4i)rmFe?r$|_fd@vpybuTGio zJg2W{UR83Lou3Ii4KC3Xl@r`&M>g)QDRJq;%58nBkDIi<5}pm9AlM%iHkzw^{I+rN zjKAag#lxtGvs09O2mV;1uga818>JQe_K#OhYwfFVFLsqa_FdTC(7O=4+SG6)Q>L`+ zE47ccbS@c>W$*z@QxtWe=L-4dlb9Qf!Hnr$nGZJgJhHZoUqt84wb1(E)f^Jxh{Z_M58 z)irx@cQnx~&*~F(w1mak7c`ue=k-4xcCZ}pwPMI)9;L+I$+&SRQAofc?W&GIdx9XR z+2?ToiDv$;P_(rLB2}2F(5x$2r#Cn*tO_@ndx!1v@~05mx8~URrC=7{*CRDfO4Fs> zQ5?5#nZaZG%|{Ei0QKh)aNC`Gv#+vn)0#SQlLKK7Zglo)Iok**}qPG>b+9k%(m+oAU z6R)J=)e4i!ID&kfg*sG;uhcr+{`4^agtGDB{TIGRh`!v>^ET^LZU<`woScAXOM}65I;GU$fU2NM#}0fv1nUWV~#OP-78s zg>4v^wodK~v+T(G7LPc7R+}k3zPraI7)jnGJ%2)Wbi474CF4y;4_0Ify6im_b}Wam zyDBsdXX8~e$TU(hjvVc94O?DF$3t}K6b4)ROSLZ`Jz8q$GPQEm{Gs@5lZTpOQ5E~U zfZ}N=x|bI@xBZgb^A0n-(iWANt!!ZBFq9>!9Pg!DIl9D*0lyR1j?P*i zEH<=D(z8hH&1Bz?6pKLYp?AeJW4Hbn7sE8FR*dqIo9N3edc_A z^v1JYl)*_%7jyP(YoaQG-H}deL06h#TbvQvGT^Va#T+h30sEFHX#2M%l=7Lp@`9GP zVZ*Ml?_HMRlv{xLBKYc+;)wfUrjY{4&SdF!d*jD)@XsIWOXo`T+51ajY7Dh_=sD}1 zO3mA(8=+9ETiNrA*B&}kT{g_0dVcj3#`rPRd;8I(k&>I)Oh>}q9p!U=z?s2L6Z|}v z#~{zWE#7Q`bciogop;4xNtQNN*>iUnOb_SJQ%)VKw;zXweZm7HN4|R?cR8%PjV8Tl zsjb22!=bS05JsCS=eb@*>{Y#LwGj~oi9j5PsyuJG-V1)=HEgiCq+b7MZAvk3yn3|C zeq1xE24BVSZbS3{rgHCs8c${nt3>bP(1U-Ry#u7lFTbBY5yI#3&3t^`Jd#eJ zmtJT<=()%vnf}#HE7Z15(z#wITINV>uDLa&07sA(e(XrP?>fBEvJImzcj%FVXT`eg-5(>=EJm+r6kMriOuL;J z>RrKxR!US(t?0M@dPzwHhW|?bb_ic$J{UnWo&^nPRU1EVGPg)xX4%#IveJf0KP`}2 zLLy8reJi#w$DwaVz45`M@E+eQ^A1Br)Cs+J_07J{fw&>vajQ)ReqRnO3)G(jVURx* zgF2U@zp+)t0=oz}$DR;3zj6)IIJXH*oX}RlZ6Q}oT`oSk!tyvV{JQFR?mx1_pCe0O z@@66R%^zv4D1dwU*l#~_EH@QLt!x#)y7T1l8kredv_ES$)*Ef{pvH0f4U-$_${}Q2 z)hSg#^rT3*CC+#OG?V2FQYxX_IgOvipRpd~y}WGOQVC6~axxg!i*6Hug^^ZY9Yc)R zNO=g#?)S3q)PGcJ)!jGI-+--h9Z1D5oWx*)sU&qrF)X}f#e)x9UomNx!8lTW+Ruwe zsV!(O&Khp;{^8CapZV_0t9EVzZ-Z6UpNy}~OvkMb^*KF1*Fv>>Hk`Dc=fj6VMNt`KUe$3@*xHs)Sg4`R)gAxly!c`H zK1^&Gt`yP`e<8+fvErK{5S&PvdJrv$h+Bv@{>bY-TCaeV3w^FS#|y2DysZ z4e=Y5HP9A)F~39@{WM=!`AJ>Ef=7=#<`cY>8R~~H(HT)4X=R7sdwm^oF?J1Od$r5Z zmz@I3B;G|`!Wi{M2j(iOQ84-}vN2v@SOl`=?PxU&qhONs8q7%9*xbCH%ToU+Eq}mD zVRe#|@2#MGI}!;q;hoSR-$>i1!Ryh>#~yX5)G9i+hM&HviF|iG*M1Zx zY~?+@nCY{-*}EQZ5tFo^SJvqf=3wtf#R83vEiBfnDXp4{T_OU-Vd&%peG1%y0w3@g{8E~#?{6;>MUvD`@m zcqeq1$5pNRp0~Q9ia7xE7jJXcbr4?fn6<+S11CV zll-Ray)+0&?1|bY%GWG{P)OCEfTw$&ukJeP+)2#QQkd|U{7S|^oZpnvyJxvZ)EMP% z0e-u+NMuo#N>pmIjh-Pn7Kr(>qVxJZ3!4g;Y{b^PQ%wdT)B&#KSPD1a*WO1$7@RG8 zifUWMz2^{&hIJhh5!P>%NMool*HrobNDxnSk`a@W1-CMP7e(nTyoq)D z`rf~HaS>IeWHyj{M-H~U7<{W`y=*j8O$+{2XHSy=f)(4`Ak4)&OlR>V1}E!|aFy_r z3!;p0#(fQ-S}=8!zYlwO0C zcbb!V1I2mKT?d`YN;7I(${xG1)SlI797_df$l!jhbi@QH)3EED_5I2QX2UKCSC&it zpQe^}P~)ilc_g;=w5Wk(-nrBgyKE|6e`ZcQz00=Fl^V=(hFo-~(-u>=~S@sqS0@k49YxNOj3Q-vZ6I*QohEkwE|T=U6-0*L_WA6eW1xqAN}c9B9Mz`){Ti&KF#*e-@#Y17O&5?Or?qbD*7M?%zi^_0hoBMqbL z+;Z_x+u$EUM26Ur9>sP(Iumt9J)-49O)Ng%FHPG9vtH*3JrLq7yL2Z64`l zN(F(qEH5ebh(RU#_C=)AqkFX*)1(v076T!b$LN{9cLT-z~nye;o{-O z5jmcJHzXUOD^rKwUcF*y>1Dqx?kQi}vRfxeUdWqA>dGb=BQxNnm=G#23a zq3%-KFTGS~c-y*Im=>h4&qXroJWzJoQ%*BlWnMNkC_Q#0)mXm-`AULDU>&XbMaJAx?iSnz4IDi=hq z&vedvyvrI%fOu7IC?`XGV38AzX=EqPh4;qt8sZz1U}f+)UZpvA9S;dVfarVIsOb2l z+Xw1AobvQILKpY)SPp*yYfiPDaWjk>vBu1Ad|24#OSt1q$HSG?W{GT&0WkMd98T{l zLobijD@h9aj@5ZIZ{};hWmqLUBTJ^?xqI|uM(K&hbkeK)#~;JE8;R-VljfnrO+@Q5QCH z8cSm??Le42zraEGuF5jRL0xw&rA^MD1!k9_NlkANtcKoiPdI$m<=qth;N+MNYfN6% z8Q!?D!rNMxsn9fD_49rA&m(#LHYv_rxznO%u;t4piFsYzl;-4e!~41Dc&SDX&f#Fy zpmJIwHu2V?2_s_PDC*&TAAG-V7+tI|8gDG1o2HUn5D1$cG%^b2ztBz_X|WGdwyHck z*;Y1MXvRX#8pE31kXx4tR5eiC(4zN#^xIn;oBd(brRE6vK^95=P80Ag!=wew+Bhl# z+I;K@5{2U}qdAnQ<13mJdp$4mrF?b0>;lw+i)rVeiBdR2v6>(p*0N~vB{S!%Rko|E z-kTTSp2UFEtV%MlTrPLraniFiR*KI!QfGgDys>ek(2RPxD@~gx72ZS8$h#}g$9^3 zAdOn=eOFfBf=oWLb&u@on9_vL8rYfo^8PyI=(XN4T)8XsES>Ni zi1z8tx>|Sra@@PrU6rvnnQf_2Yp4%_Ih8Q1_)(W_PnEU7!piB^;NV=346Y!HJX{@3 zBk+$mHMr_z=K8XtQz4p1v7%${O>2A|C(^r~o?zkGJ&y@>O%+ao`rt052%5E<>d;1X z)1(_z7S=_!rOO3hKdTgJ5ks+Cx^W}deyH@Rfazz}tUHN6z@{FV>>2g$}qXtJie3w5EjG2$L# zp7ni^S5y!7dDq>ngfj8&cU>XT&I{;Uxpf$~=Z*gWgJkb?9>p3Np(jJq7@c3(u{c-M z*LBo3=<9n@3ER@31=)}uI&KxpW#h_gXx@9u`307%z1bdbsWEl8n2{PmZiBjbyHQw{MyKEmcJ7d3 zZh=zs{QLv`guPitw3^h*-`8Y?J-PfF{~eA_&SSJwJ+L41@_Ax3C<# z5-*4(tA`8;^nkrIteuSC@ckNBG+LkR(Ka7v&~-fvu8}>E;>j304s2#U5@mMfUK9p> zpr}fx9l!Cis;+{uJbdHpesO&k+Do}NKah);*DiMX>rm}*>MTf72V&7%W`^5=K*j=o${D+w%|7*@ft4s!!kYhs=$~={=HG^<> zNKE#pDsBb|6jEd01IsadP1B2FzD;VW2|N=Fy!6GJ^KUdHY+}y0JJudfKVgWlZO{)8 zZ;8>rRhJqz(@7^Ar&^fZ*dUP?fi`!&9IiE%e<7RPg?XGmVbA$%aT}`2{^s%B;qr$x zE@AtJ$0jAz{4mV3S2PRXX*drSt!;{$2jYM`z3l7l5tEpy7)8xXiwLY?&F|zI18DUg zY6$9o0g3KNV2gp9t#=R{CR=(+Oj_%@%9s0c!lG#dVI^q5Q8gY^tD2?-453W;wIo&< z!W%z-B13h6w9rU;`-m*8Q);aW5ZZroRIgc-q#$JcOF4hrG^?}9&Xd9?F%h?Oi^p7% z-?wX7%KHh}F8WfpXkGhNzYQ3iu?~b0k$RcP~G%fN1M{-_j#96xcX-XJL zj=fjE*-p#;-PFV6)V&~|_w1YuD*`@j>pr%;yqZ3pnQ~#f?`%YzmRz@lPbbQC-BKz> zt*Ta1JZi8mxv>F?XO*74kf|Y?GCvsii6!=#z`|!^_I8D7=Oy9h9LELZTr&XI-{x!D zifbKQ>o-QeTJ$vE8HG^K=GzLGDRWMbmt}J8?`=m5bxinlU=h_uJUd-ycmd&(Z;wId zB|_^)yxOA)+; zF92|^vZGyhyEVzNL|m{O9BIaNIJrZe9DA!DL(PJLLoJr}4i=-h96qxg$qlqk`(RRs zX@Yyrqtr6&Xo~0FVlMQSsMOuu4Wtjrz4a1zTEf*PuR$kdAb!B&yRFEo)<(v?K!+Vn zEXQ1Li-ho2vv_x^sqwM;H7hpzhMnx`iG&5!hzn0mm15M;LgX|Y(Y*^}^(aTCrl8|dYa-SI z9VP|^f#L}1!Cl_xG@RLhVjMH6!5nuH_LmPi``;<{|04_)xqV?WKd`^OG$%&qAjQpk zJdr6V&N7KamPtla^oUM<#hE~u^83R9;l~Cdm!C&TT8EgH-O8oCbXU()im!&&vNksm zCa$DS=w*R;sJx%A8csDJxv5y`j;%Py>{7Eg#2Y;|lzG?F;LwPbKF+yL3fImZY`Ipr z_1pq7m_Hush`wU_Wl-Oq6IyjEmyALJCz6Y%UB)XgZY5{aQ)u29PoK<{DRXW1ij^XK z42kSSiVU4cdeHk+jLrJS72lJ~Z#0-3`0lZ|#EL6F4UX%Sp#^47>(@RaupA;fsU*T= zx!2(ndp%F5-nEzs5LJ8>-Y9>HY}YiX{ZrGb4SIu;ihKCT{@Ps4fSKqE8Vq^o`kBXk zb=i>tPnr4~l&@DU_Qn|y=_We&zR^AiplLzLNN|x+gLmH^uPtLJO0$65^|p&qQ;iU) zxEI@?=hvm4qiEl)*njFrw&aa{d4b<>S98ske&1853dFUA4I3RnhE)Bev4WFl17Ww+ z*2hKw`}m@FkTJo=%{y0hJWo9*SA2VCwA#UB-?ncZkj`=LXX|lwTI5*XhV2W(LfL0d zo~knBZggE7PK{JA&|GU5<5WrJyA9uMo`;+Dj$v4qzZD_iXhDmv^2AZ$x!;cq7>3pn z_Tw6@mam)ks~!ujxRAeklSmG1VL*X0mQ>CHfCFld?&f>%%yR`5AKuggX|58lMdTP2 zh`*H@VP{e#Phli?L$^XSEedIQHF&;?YxhL;<-*ivQ>B3WyG1Chz1IJJ+;-HvlWYS=2X#Sh4r(L3;E+DvB5#jx^aH8x-ISn>!DI zyQ^+UHA23{+_MmsIc%?=+5nCE4!7lOqQ3nWSJU7LlpRx-(q&R^qFywLB;y zu=9gS*$^LGd8UN@WvBI-+kNG@5CEXV*Pe@n0py%UiN2os+i~H0>G`CIV9G|?9aj(X z-mil?kDfOO6LXp4gO4q9v4_&_UdFEmzkeYlyASBKtSu6n5q$ah)nX80MGfk5+2JU+ zMc%phyoC7sIQ7dN~;Tq!Iu1x#nh>VwB=slfRmj^OAadyjVeI+%S}5c<9yMsY8?2_%&{4 z{N~pEBqaM6kifj56x8*CX_gtND{7U23!ten82obGmKcGs>*YKL5xRfX!zwMQ_Lsj&gBmjd>bAxuXMdGi`gviuAabV>qEtfGVbl z3-gOD&Zn^kcx^5`yx-jXoCdu3;3(i(o5m)>Csq2VogwH!sf~0{Sf?*n&6Ya zRb`TVTsSNBrJ!D(OOE0rgc&6gBhDu+x=G)urzjc3qkP6dkk!RJy0YeZd2YYE&bI1t zln1Z`Dc?hhRW?rdAayJ|@M6=5jjvhb356QiquN0fd zIx5kM~T8UK#YOwS8>yh5kXnW6041 z7(hucsAPs^xYn)~%L#b|SwR>R)0~fO@UNXX_0EObGgsgW6-Ye1*yBtQJ-eoG1bH?mgf|Q@{gw8ZzanpfIyfaj4mbE6v zw0tFvOCvwG4v>y)scrU~RY1g$>-^?K{Zzu-g#C1TOi+29r}EC)be?J&RLHWMby4o| zp(Do>=C0ia97UFOe}NY5Cs}C46Ku8hNKTQ|s{!UWDNkR-gtx2Na`%?pBVW+aJ)v84GrGxZbl&#b>|)z@ z|G7hPCaOKZ|8-6J)jPbVD{1va2P*%B<*Wh|VSDD9#-%G#!5awCvi1BkO5IIK5_22r zX1(hL*FPX10RHE5kv6|cEss9z^!{sv(y=jgl5KCsO{%awJbu@H0t}+BR4-;%jt`H2 zZ~n&64-pDFhCOb;=<|vY1yV%S;6t!YiA5UupIM~chZ*-lVf8gY8%nrY_!MLa>&JE@ zbR}LhO*MJ_>LwsLtOM~t?8q1s7gtUcQefq4@p`{cJ^X?B_|5wia8mnnKy1wQ|J_>nIbs@B7YTU z*JiwC1q%TzpFJ(quzoQ&ow6X%GsJa`5@HvkQ{SU6vDM}lD^>Wc=&I;A8NhzLk^6#% zE`;&0oVgTopG!Wl=pb~G`xv{z$uzD;4L#jWePk2-eU9q7-o4Z>CB{9UXc#lkPXMm< z&61Ojqy!4U2q_+ng_sY{xj?7F8AQdHH8ea9q3K)JTxQD1#2^fld88?nMkvYDxi3QaGWUMz~sdo7d()5B}TDHgf%$+S{l-JhM zoo^qXW^G(39_n2H88W9!v1ddodsW;r$kf8O14vc}OU;z>UV+3oL^u44T*}_@?HB(m z&EJR*Laha;xoz^vO9lPM2oDyQeKWCPBJQsIfu2R`Km4q2&2%`Ce^|olbK0B=kc`qJ zOw2%fuvl$&Bw`Gw$+m$t`-JRW26#GhxLI(v<~EU&D-z7hw=WplDaz2wlpKMonpW%h zHi$fExgbZs+_B$XzNB^v(`Fb=e$F2JN$rW`23t$@rkTatsOB9F*?Le`WA01r7qwY% z&V%9)G%uJO1pun!X+hRnwc!q-tXz6qsB!JeFL6n(<+a!H2fhHHlW@`;>!-I?xXLngt6g04!>M^<$D<3p^N?VZ)j zldN1pMSSURw~j1OubEq+&LidVyIadNyf2{-doLymm>qkoUGfApq^LWfEOxMihJ7I1 zJ-6r#W0KH}0>zg%s?eQgv_OAoott>nS73UB&S=+>dM~ZpXR%3fS!kiY?Av|LiGmg< zY{%*n8g^!qa)qvy*!@kd^v_%bZr;9{yAhLif6FF9fcold7AYx+n;6rQ-+I>T>lYuh zhKoN@yBXf!DWmCwlF1EF(`pkoa7?zynl~geLGP4jSE1;-v}`D$x1u&{Pm|nbU=dWO zGfS&SKt3ARu8ukxI*x(P)lo_gW-QS+xDa+MT?BV6Whx@7L{=8Ii5&TYfXBdYwoC8} zHLcxxr{eS3ICm@E^~zC7+ll%?NR}44OHtZZ%2u?2Uy2sF`%cW&yFL{dQNd1YkeDV+ z?|len-j%dAG_-d{Q$RT(6v2;$x-s8O8F)PsrT3hEB_TgG+_R7=!5H>`K1sV?R zcKEa#M(o-xsykJpNr7OwEOJphD-U||nS!YJt8e#PiLP1Ff<@UFAu})Q==bGkTNYgs zv%McjqxWk`u>TzZi3}{{e8KrzcL<5h_F>UiD5-{ey;2jZMZN-xKCKS9X(5**ytT{ z(|85w;39`wNkCa!XsSdhSI{9vXvoj2w$y;XWTW=hf~ZxGOld?vq;5zP0ZG$qhc|k( zIhEm04!Ubrz*MUm!rXT}A~bpBH8{pP@Lxf^4hEM6!Utn z+1IK)Nh%8vpC*C`r-$%SG`qZd92;FCM&C>cJmF**XMaC|+^sXF!9yb<&to0fBov|$) zA04mzOT#?rUE(j3M8?$`Qs}$i=;J?oz(thAXBVSbWn?EH<8NcfVe0mIS1XwiD>JUC zH9Ic%#HyJ0Z+oeZWcssloI<=9L}}|A*PCql-`Uyl3_K>0@1w1i+K*6bWRY~b*}K@> z&--v~A&Zn+$5y@JiF}qf&NVO4v(9}rW1(p`jEasw!kyd~FCA!mZ7Jo*#{E|#cOC|E z_ti)DupLBT0kI;s|0V`?o8Ts3?isV4K{oK*B4s_Fte}c1>lK8w2joBW8|_hzeEJ{( zZQY!=^>>;qlN>pU_45;#OVU)y^7bh04Gw8}tVW=3$mR9bl^+xA(ng^yDR`QVJ+Sj7bGq=@rca)I=ls{5i5O#Hd+FgrY zv&HMow+h1^f()>#UUH$!X81y$D(7-69k_a_EHe*nHK|mF$3_dLUNn zZl#qHT~t-wZg$!6U{(pl&1m#p@*5izva#@GhwLx6_OT*ma)X&jjT3K?1dUI5H>uI*3cq4y>aGfUc_8IyGB3%ziQ{`FXJ_;XY+75 z5wj+87KpRmyUVJGeT!&)gD0nxS8O~j#tx>RkcC7lEF1lQqO}U6;;v zuFiF4d_T+c+|Tpe_x(kZ|Hcqd5J+p^9Ir2wjQ(_i&k{AFRie*qzgffKjR7qJo+-dD zR#_@O2fvWngjfoG=3&>DnW6)G^Nw_Wv%fdM5)Io?J=wK-tvb)_Ij;Wve0hzBu{RC} z_)}SGDZ6Ih*kgh)({M-{p<&`R=PD$QkV0K~K)0f`MZdUnkL@+oaoEx7xT)It?rq|T zju(h1NLI}q-%0&lxev3Sg5lR&drkZ3<&xI;hTcSWX8H}pUAkRKu4}87PdDrOu6o1L z?J6zOps!B;@T$cNe*b~FW!b>FzHM!{>&KB}5NzQ(>}+z6+)OJp5+HL{OKSBFt`-9s zs@oxIY&}m|w#gBKxG~D}CA?rf^oY$#SoYDb0-lJ#)jmLZ`yGM7R5sbi*5)VJ12{}8 z)YYww7e980&HX5R1J6Pyo`AA9eomvYL&Z}z$AH7q=lt8VNty^Z;~KQ!28+-j_japb zAO$`5oNJ2feR*Rt*Y+{LtwVFT4-v9pKK?Y0?u09r+nu@IBqs$*iO3xA<-|^ou;yyR z->vUZ@G*Wlp-wX-thDGOWVS9;$ahT=OuWw|f9CBhIW6T7A{(iB3|YW5^axr6k5RaA zY{P3+bg0lC+CZXZkTl(XsMM;|2vD4S{JKU3bqcOAM3(lHTC}Phx8Qj@Yzb&g1r&S( zyPM4e`gqSoNx0ew)H9#!(w+L&vOFfG%FRq`Zr?W>Js^0Gw*wZOm?n^ zn^}q?a8!fI-`;fjxxKZeFzS8vB7cFZ)%^=g7A3pzJ1v952L-H4oxbEnBtuXB_@bNJbPbDzD6nxY+j z>u))}7JA}c!BDt)%b~Oe-w{f#80paOrWEf3rk{Q=ZE|?Iq=`A5!(E44dcfB0{GERn zPsgbhRAf}oxIBTZ^IR*#_e3y@lhoPK9ihk}tj+}OweocNfY*m58ity^i>#i!mNg(Z z`p3qLbxWn}V15QBI}iVKEZY9yMEZP2>)Zo;A|KV`vrH_T<)mpWqX#7q-Iec?X6yFl zkQq_dOlxbT04MkwIf4)j1V z6eqc@=6pFu10_s-2jXZxL2J4tKydsAB5IFc;}U*TO{6p!5Z=0PxZ9NmYZU!RJ`F;r z9`Zbt5TX?9KH5!*PPNEcCr+b&^o3eBxa{|}1k5+TGHc-z+^-B)GhGAenp_u>s9}OS zkR<7is&Gx?H}?WIVS^36-ZborcS8;nSpv9ceG+_{ty(XiaNSs4J+`@C=Id?3P_yvR zKs1TjpRxx#0#o+W19ay58`3?}RIdfzdQab{f@d&?LfNQ7-lx5g&m{)6pD>Q> zsu(BV5!WcwXt@Ykje94+P;}uQ+bJ+eQm&NG2n%Taa(?Q~v14)GG~Sf{nl#f^bgtEH zL^h2A!$f(vHa;8h7t<*nTN35&WHmAT=X2MSB3pw`sV>4~JFLNzMvac+ho@bt@NG~M zId#&gK`8>{OuF_I+jSEBTh0Qljxt3Zpnu9_++&Lh!i-*W&hhAwc)nyOaP@M1BnZr+ zxRoxsmwom@nD@aH<@f>6;L4R(*Z~VgsIeGw1MZ4@=X!f-VB~%R?J_WWmoqDoDI~)O z6$38Y96WA3yjMUd%fe2fMo#6N2Aqq;G)m17XG4%+BNWI*NhAYw_mm9*GPFo+MSI$@ zV#Es{ix;v_`mpgy)G30ma5D7{4(#2g_l`W}GPEQ7F4_TIGTrlV9#@=rH}y}F17%Rk zRF;4azWYN_4SQk{x;7=b_7yc6wym`ckIq@?ya_1F9XS!+ZQk2ez zA)r3yFWxDa5l;NB#kuWxw(fdL7AK06%Uy&mdmdOG*1L;GQa9Amx2@hjvxls>W!*9k zG7$fueI1~@%0wW32|UN;$A2^2(7?I4M@xR?xi{(l8|Xc9$^ysi;tEn#BZJDpc0%fB z{(d_n%Jkdu+k_^s_^IV!P3bCAsaUUc|L^RHlyW>{EekGNiSO1Yhzx~~Y^2i2-V6x4 zluE*5de(~ZlNj+8HA8&FhT`5vu_?d05tZuK0sB+^utRi)cy7Kbji*Q2wIqM>Q`S6g zAsexW@*3zUUC!Cm36Teh5xokamQ%C=N)TDifipQ#Cp~}?AVB$@KeHTec2NPshbp4J z#Sh|uMaFi>{#EG=ETiZ<A>VhE)YKZ-}#@AOM0>{kV&p0Rf1&4g7;oM zUs=B77gBuki18&Ib8xpxk36Pw-37uh%ou)Gi7-XS0hf>UK4U-Y79i(Q@!MG;mGoQ< zg5YuPs4Xx+oCW_W6HrZqA-mg_7$6obn`&Y8%V33U1vKDyy)mG(R5mr_2+IWX;}GzI zD_aau^vteIwG6JzcCcesTlwaI1Ths1YiwEqNoi(5&oCQwLArosQ4utIyCO8CaWRX4 zLr9nafIgIM3rC8NT&2Uv>qHU9&TuA?Sp}dB#!|3@s zgDL1|0Ug|Baaa^}6^s&+M4dy_Q>1QWt0#3v01-_m7*o#z#gPk8hhTtGyL@W4Bi-fu zr=wy%Tl~yoF3RH6EE39q8JP+cI$fX%ZUy*^gC&-5mce>&5#RL=r83(-UQ~azGY6Pr z1XehLH@H;TrxzMj+O))7GOz+n%QEY(3xico>27xYZvuLYjWy!cP@%Fsra<*WGYjyX<)=JYMKkh{kF4rVG^R_m78kep`{Z{#12F$ZYr?ql6nR z6{Fx|l5iGfVkMf?gXtvS{G)NX_#s>lD=RxjYiz zlT_9`G*wQ2{4mG`XAcvP9&x?U*&4^ov;DqCHe{?1aGKSOeO8Z3*5Ho%Zhux<|4?YS zzC5Gu^}w0K7h+243-J{nfmI|))mDTr8jdKY7!9bp^Esx~LMy%{sU^;Bez>vzIrxUl z{ElLcD};DNqB6kYm7zu-ydd2+yRW0C%XSW#d&On?J7bNH$rVGflBc{Z#tQV2g&7pA z#i?sbdf%$kSvv>VTj#z`OuNi{6A<&AB^GmCCKmI&$C=cRmrCkKOEHgC21TF@Q zT(^6{?&DJyMZKgi6Y9pxW<-Q`d%N$7@&5RUo z&oX4P>}aPdwQ9kO%QGnxxw5QmKA|g z(EhlY@!8btTSkYZ)nv}1(0v_|1pc>7;eNH;fRYmYk$OqaG{imYa+6rcY+904cT|MX zLuFDg?+2uemvbb;PxU8<&{!!ok(6bo;f6Y+Aof4`yUpn}s&owQ=P+_7qY!T8T4Pa$HLpyYsAFZ3Z$J%g585 zbZtg+$gkMm4o(m*xPF6C=e7O`=bN#e3}xvLbD=rvZL2ykh%YKfub8E$&;SaEP4eK* z_eSWK+Yscvxr*V8I`v+zfDxVGrcsCVC==h9Y8TsK{xo#DlI&n!q z<|!TLYi1Atvj{{`Fci;~2_PDb1{1k2P(Ie_wnXUa_s{ax&WPR!@bNd>Ux{)mMVyY2 z^mapiio3*Azd2|N#M%FK$WSUl%SQVn#s(mos|J9h;JauD}R2$kqxZ$WW|$#GSq9a z8gcQ?TeBD;Yb}(==71%q%JXwESDj3}W?oue1T>_o0`;t_)SJ(2#OT=A zf_v$WN9Es~w<9AU7JtW6%9=$cbh*_3&0l|{OfS$KVyhK3=`r#!bkN@67VxZ$m>YXWO^!xF4@I}&{I@YasCx9cWPyo`#H zp@oR)c~1s!DUUneMx)8lYQ*&7hfZ`Ir4(N%ymfMIb<1b@;dY&!6p&Q3&W4@e@bvUG zvPgjrALudM;-7m zI55iMUr9C|SV=XGBKBZ9II1pVcd2oRa@mcz4t2m$x{=gTsd4Do^5&ts8v*@q{VVy# z?I}IPiA%~4IyyHFF)vq;*5LyB$pb1C#!*K-5)YM_%LS59UDW&hHKvx1_0C0&IUb!t zb=|yMm5jQ@dPz3RH(?|_cA772u6$2F+2f#-h!iTi;hNB$R&xWXRiEXWYgFo`1M~E? zX;ca$>3(A_Z_}N3=88klW5!B{>o)*zD9b)kv#a7p?w#7K?mAyVo6$7U^4V{X^xf=a zFNv3D+)6UIX)9GzmL+UBq&ei^QKZf#t>;aKKmp0pFk%IG46*L~z zB4NsetJ1WDRXN7-x;yu|c7hI{Rzf$Q)}RpQMZ>|E7%6*IFHS?QFHurg%sn`-)W14I zwE~$hu6q>+7@|rqjZ`#V8mnmB5vadbY|$=rr_?MJyw>cF_*?Tfw;D=`5k45V> z(NfE-yP^Wxi?6_z6zOp~fVXk;S@e^NClE_bdk`1Pq$vAu1 zS*t^?I_LJp@VeJgsa4ID*Pe6XCZ4&?^V>OQD?5WXk>Nx-HP;S$m72+NX}_h7y`-x= z${=N{6{*Lj|&$E$E9 zFXnZEu9|jRo}*TwjiVL{X`Z7V{#K{b;!d7k>FJ()-DCpef(luuKs8^d5RSZ+s<^?W zHHA4*?pvQIoO8X6@mB99)?u_NuL3QyMBI)IsC4+KL}k-emsO#6b&07R8|pru?#gU$ z>@;dz=RD-qojHPE5*;mOF`=E$$U~_DY|6bj*Um7I<60O zy+Vtye#;N87~4)AEi9{td(ya!()e28g@p?I3>bw|nWrtCjV|V)-nDy|tTimWP;~Fxv`&%8%C4{!Um9!2R>7KDf}{Wt zFiyCfTU;@QE%=PH-i+B5@u*fcl*|! zByJ7FFM}%`N~|4=BemA>WXUoha6|Q1ItF)J*ioKC+I?;VDNKo(0{rOmziX zgZ)jAx}(TRL$8@-0eiRd&oc6>FMO-vr7;SUQOlRv4-$i(4A}i5T#5)FN>?5^{O}!- zFwgioIp67s6A&2t#!}B@rZER^m%*|D=whv3S&r~wv;TvXj@Xk4c&(j(09SsSzne?d zcT$DDk;uyrJ6D~|^s$--$j@bu`Um*uJqCr8oub@5K{_y}Clx)(`Tf-Tp<4htG*Xik z&>|-#y?1BH?QT!u+=}4(RFgbg&&oTC=6j9yL0&SX(2JBOAAkJOu&F7A zdW|65(|0AmOkY#_ZHw9DU&)80@^wIe>yk8>5IFPXu!Eh-$%zBkHZ;ua}+>UT%95w=v$)?4BFI1Dhp>g_nemSmz zFtptMe1Z6=8rsv?{-*FbANYfo14mq8q45_FoLsj0(Tsc+WE&8lWK>{wxfN{a6R@Fk zw&Tp(GJ}5#xA(>#bP(cmM_eP-tHT`Pn@iS*`P+Tp_|qM6IT}}%1;`AVg2RCce{<%> zDbjdH>-*G;GsUiac@Aq9v&d~4qlxpsPCdTEOIggg z*WDruXw#fM@}IzPOFkzIz0~H+lp~u|c@fClpO4uI@UM9IDZ_;0Gb7B$*olY%w6m=v zw|`|$=>I(l7%8vq^YH2O^yWKx>1Irv{dObAS;Kyne>`V|jeI4ehkA|4ZeMNaU_6e$ z3#XbICI!meGnKNG1g6eW9(RJ;<{^*Pr^~Zs1z^hL&rEsfktV$q(ee54dEFQv%NOsS z%=v!R3Wak%pj$i^R5PU5Y~^^7(0A+cw>Y=Md#55}&bz$}`$ndNND8j3hdM);TTwbu zGdyazX8haSYU?S1ubGRX*+M1V{_Bc${JvuRbic1y6~m%zo8}zpf3Db}=bH3O-whBV zTKQQ$=UE5MqD-o!b2RcF$EWcOlFg}0GX!~ggzKe+m+r;2OO3UVC9$U3wk~Y3W{KST zZpe8^8~F9u!LNs5^iYzD68`PjH~KsCvw`-YF8&~l5HPOYFTQf2q2~7sd2O?XeN`I} zpDa^p51N?50ySwQMcoMA9`n0vLe3L5i~?SaV6K*cp=MTM{|L_zRTJr4H0_)1O^0!6 zDRa*?(d&tTs-CX!m?h2yYlqw))XAkSILNH4eOcsk$8?% zK{ddy6@P^v-J=2ClALc(+4~NBa&lgkDWi!uAj#o`%NsU_j@q+;^++a z)xirbFxyzdECh=U;L@_$)1_X^BzZ!Ex zcB5LAD%efi-hz(NXdsF@61Kt_^PuAJ*_WDVA#q8K00|+#p1Rbp%6h~TggMeDT13>D zS+(`^KT@-Qe%`js?_7Z5J^5fB-hXWLi7RMySBNY&^uBEN{q2@L_DO8rC~2k5q`J()(~ZKcBKD9nVe0kL&s5XFgloFUC%yf+#?4BG>{zo1j&)(A zoXjHEbO8P4ga6Qx4bVif!Dj;|zx$BpDOC7Dz|v|}CR=t8d(*KjWqQ{4UEcPYGeGBd z4Om1N6EA%t?flbnfcp2;UVj|ybDkd~F|R-#r`IGs zfhpLHC0--aNvez*CCaZxWw)?fa^u(e7{Xo}x2Xfqt~8*d)CRh8p*w*0rJ8i1o>N^E zpE#ZWZG%)pqW3eN1}u)G5=mr&D%r7f&)$k2arNFT#ZX3&$r*0ZT`xe-c3;ek{D40T z*YfkR)aXB!C+DZ^j`mR%+n@6PV@xtSf0KV((vSQkQF2U7tAp`GNC7U?X)U~ zuW58N_ZOm@#O%U(L%T9LwStxxTeiC(_XX=`+@SHdH)Hr7h6W_;cI`d}>73K7Zc67k$E`ReCVMo-A> zaJG?Csm~OI>uy2D8EGhiwqEQBqzS0n&1^ulh!6uYVWNB?zRda!vOP{P(hR6u-fjCm zQvqwhWb9W1#kkn2!p~urh@U1WF$HS2@NB$kCL9hRn6-va0qD8|YHvI=X2NwCvo>EVof z4zyTap0FQLZJGW@R6Bh(+cxEXr(m412~}cccB1jF`AZ22?|FksTvrc08($MM&uf}# z5>lFX72L-MftbdmQT4OHiP`>4(zum}^BrT|?w@YUi#~e?0>2ke3w0WcoxwG^ZBS^h z`JJQ&!8|wq_R?7C;q#CS(G_q^`cQ4tbIlVNxtdmbIvh$^PLhW-SMy8B4?fvAO0bTm z&G0gZ;uDwq9KRB~yGtUf)R?kX$)rj@eL7`+kn`T6@ZA7Hy3#yEc?Li42NwQ}TW3}) zo22R5$%`go*Xc9HfzgR}LK&Zm`3eM??dUTdJxu3$Ca|k=!a{FXIZ#hZlQ~nLDxoW! zZ+D%HLz48FPz>~PS3V0`8#sN@*n;yt(AtNuesH!scx+_^M=X@1!HuHrW5chh+zX2@ zKYYZsGW>DJs3u`5{#52dM!7$Mfcf{ZF38xtt@xOm)*m=ZbE^4f0l&IWg+Cn+4TL^K zj|#Ligzts=TW|HV26>G?NeZ-FREFz80^06Y4RV;gc#`qCbW|ipWO{_ghZnB*kbIjc zGFGPF9kh|}J39v|bYf2H!?0Eqjn$37cCrc6iLr?je{ z!Q?)u#>Y{}jj)7($0&ss<25F(=QJUnFr<*Wp&i_5kq%5p)9cd+94)$l>&mtP#src? zU!(YHK-s}RY|Zve^~hjf5{%C;03t`)diYJfB^=I>@m#Luud_Lj zwkVkz;-BulKn(O1&F#QCF9X31E306wvr@gLfBtEAeRqDZ&8)U3M-fEDS-St4X?A

*oBnb|e$7I$s9PRS_53^yRP`zQ>lu>Uvm5>PK3NtnDqCmK!GQ zUI5Z!SMGcyaS>vs-qQMevwJRnnM}yLW6=N7fVAKCN#b6{%7s(>xQ(i?6Wk}wKPLq8 z4sXBHgj}aZrY%T+JXYxqc(X!)1df!n61wa#YVbCB%a2Q}AQufH;BIyPU_21}x<~R6 z!>;iAQpriyea!#%@ebkgosA;1zO>B!kMQ-+)!Kv8w8&oNhvK;zY;{9yz%7qIK;#fV z`&a~9H?hV7e@Avh8OgJFt3;Qsf)U&xfpecA(&Uv$1IPN9uqIIYJH0lU(%6nFyrgd zs(JE29%@u8OHpk8GB(ooqb0Cd{e-?bZW&TR1N_A7uRYrg>D+(2{x+7M+u^c>#J+if zObO`}Q8av4>Cb3eCV!f}u=;RDqr-2qMZE-5*v(7&M1bCI^Mp)3QrORWYl(XMBC=LcFovTTdfR_)4BAXVF# z!&=P7yJrY=T6zS>f9=ceNP*ve^Az~2X?>Zxq0yk1s_Z28a6&NB{OKyNv|ysa^N)ny zHO`ifAFs$ecL|;JjWb4oF35`?3kNPto|{^e=hruUXHc)6EE8P721#v<74+0EV&S>2 zAV3(85ku~KY=(o(cOy~Q8jc3TrQkjp5Pkk*eg0SUiB_))V=_PHE@b({spswCi~}V@ zZw|{zN)USvq$$b-RETQ0L5o1Do`oh=a>f+Lb)FVEnY|@cBh7Z zrs#VqmDt ze!yw49y#51A-6Lly$}oc=1FuFVDI*(I(>dFyZ0S8$?T9R`qgKT@~<`F`rEo$hRoM6 z_l_gqElLZ@B~@}RhnV+lPPzj<&UNg8Ag>3>nv*rz77IMx6Z9Oin;X2;?9?e#?wn#&K%3dsp+{s$kj^-a;*4&j2)OD`O7+aAN&}73@HY9)_d!oG9`+|=9)?CH zPLxRa4kWh^7-3eoc2G}Baa>*6h8>197t&as?gHNeg6YT3O6VItJY3jrG&!rG@|o1_ zN+s+Vs?+;orgH2Bu5jg64-o^m6s#?#?!;gk9yZ}~x1y@$AxJcrJ0m+boHIrMk?*SU zK?qdbZcbRv7ce0P1?w!@5+<%_1`9{*Pci>cWNzv9?r`1b0L4hg@x@8SCs#Ao6H1$_ zYzBz5X#4H^iP9D$8rg^%JJ5nhHpXd@*Cj5mWN}Qp@V&`F@VzLI=&I2TO=hf~4=*cM zwJ-z>R`V~Z9|1W09lanf}#xldy4 z6&b`~3h>U;zi=7nhUn-`BR5_zdgf`|)q}?J-Fp4ZdXzbokLfY0+q$!Bkh$f0SJ+>@r#i zc=wV)g%x}f_~};thIfIU{D_&HKE)0}iuLzh*gw`Z{2)DpE=dOwrhlf(xwZN7u>=Dd z@)?qnrT1^G0MCosdp4v@@!Z8$Y%h9daydw9)i}q5`&LgJRDLL z{oMy?lx74Qz8v58Ow&?eg#1oH`3%x8;q`r*KFa0#t3i=h{l{9QDdl|0eYKZL{TI64@uUNkG1%bjW?$&#7pDm-y<#VF~TqDIsuAGIv)RJEKm+8wiwprj2W6%@-g}6oP?C zbUxAP+Vw`E`bx3FQQO|E{0yd{??6>7n-5PkdI!pe0Y8f%uh-Y$w@07fU(U%5X{f?% zJF;MjfUR^&?K8bSyQA64!=*PsHyW_0@+50PD`>GIjen4dct4Q&`$pFvkX4A}u9*(Q zHHukNga#b-phel%uZ9+5aU;WvvaWkBndTBzYuTXl|E;bC9XI6h~#zO z_wyW*=`UZQ1}#q+`YkuJtF*W-7r2!d5F8QP(vM|cSI@`#@#&X0l~Do*hgCbR8elJ# zW!>YoB?52mo1eFybMqa=+!$2$+^XDdxN7M=*E*9q>giTn<*2|r^hSd#5IPIUr`vI5D%w+(QwOv@ z_;xVJ%jz+6Y~#+>B%-;r#8YKX$GTGmZu)}Ws2fKVY@97v*|4JAy|TK1*{Orp=vT&$ zUALQWog21&Y%K~T8`xk2PUDQ5Px`?W>iCf2u- ztv#ji^1hWj(5QpZ+)QCeld|db&hmOWFy1&fq?K6KaMiiR6arAQ=i(!R6CE|=*15R@ zfAqxn0pkC4j$#@vBgq>Mub1>?BiyP?Gp-Ppit4x8?WkFJ#sN!y*TZQnj3zD5g1U^S zrVCrHzf_CO?_)Qb8Tp<`?|R8G;B51?Vky{FzLgn+n{!o^qfG|GrR+V^&5}o_2}|WQ zlpET$`pnnYo8WR~${5L0N390RDklWy3JAQI5~L(pn6QyJDc8ds^`I@H0*0 zI-6{bjk)tVsiafvpwaV-K$1o?7$eaP<6215P{K zkZ{Ky%}I-v*a1q(6{BF`Jwef*_0<1Nc5&$N-W(^@br0bs#{?PiZ>)FcJVhd<8>TEqs06>VW@2RReG%TVYgp%%v ze<%kkG2NmcoLiiPD74^-XEjX%S34(?yLtt zzjPZG%w2J~TwTM9G(nTb6%TxufCWLRom%M*(0#4PgL>L3xt5@(+@7Sb7Nz;G!hP?e z{9@rw>tvTyrozfzZF7*5mi703{wL&&e{KT`#5MT^kF#gfYat7r#DrwLUN=L3hEE=6Q7Ze zm=Vh^(Be?eRSkpcQ6aMn%Jg^*I5#mOfivrNf|V)%ci;s?X@6SS%?s>!cZAGwWEuf% z`oLG1;_R*Cz>|NKHjvF}>g&RaUyWn|O}js*Euf(s)k_5XyLRi37VC0;!M5&ubs&V~ zSz;=@{3IZMhaWOj=1=$7oe7Belvs7-$2*vXiPBisG9o#iYu$x`g3g}PV?*Jp8&ZOJ zB6|^CIJ2_h4ti~jNE4inoG*Z2S##G6BveL~42lg}SOO`hpPiD{R&8n>^5$|R)c*Ru z1G~x4{M#d%zmb&O;fSW+9nNJwa7fzP<7z1ojMZYX!x zkyWZPkyQ{hq=pZtEmBL9?AnZD82&oTQD8gXsXtDz-~aoW<@@5dKqoJryK8;X*R=bD z55?@%2MxG=XNz(XINk3_VH8dIB(%r?iiR^$3=pS8M*}$+*{o7Eoj=3 zG-$-vx}iEp(_*=F$%_NH%A7I?FDLjDkp2BE@Q>xmWlwrQFQUpS@8?yt+O%cg1yJrN z0p+q_*qDjZC#*pw6L8+m!=ijQc*CyKjKt)2l%$(^!24n~^Tf7q?NOIYW3u`hZ<4Hb zInzTHNX%;`?&2XOp7p=<1{-Q|4Qb&k>zBeX8j= zRt`%`VscLba^YH35|G-a?c8GaV*ElQl*WSGEmeD*?^c!w4*tEAS{uK|W8lPhE%{5I zYQPcwpTd53Rn?8fQ=f0}upRy!I2JsiOAKD9LN#;d8{=RDfLXUqEI}J5(~=uj=XScm zj*ac`gsIZ4A|nm1L`%y2?KOI?3z@mV8RJZNLQBdR@Zq}?sxC>YRwLp#bV(KM;2Wxj zW-Onjb%kHYgGrgmZED~5&lHT-;$uxW^sj?>hE9Ply!Xf-E3ik)N@0|}TXYL(fht7Vy4^HXudCOP@=ykw&%!5A#;KSmqM#$M4c$4Z;Ft>S zP~}#vv$5auxxu=CbKO06X01CL=yd%)UN2TfO-fb-7bSnU6@94Y`E_BMvv?OX$7HNf z`$Yykc|o>n`^PZ)l-sPnOg^Gxp5LENqz3^6a$$-hygFogmYDYf>m7Uxo2*G`+>eyM8 znSN_}-fI-yn=$3cr)S67=e+|o?W zmq|{vt%Bh%VwK{guY6|;ln)`lbja+>^R{mef+L{D;+a-USP-oNcBE>a3VTh+>zXZ* zDgN=@2+6rUV|{iY8e~}0Q$?8>oB-|Mn5~njr|JR`Jw4P_!)d0Ym&=k`$w|^!zU*C* z&C-2Wq#lN!V0|aWMd%7ozd4~Q+PuGS^}qTuXBKI*H{JPnj^1!v0#F)84s8!QfY1r-qB@d4 zIM#2(4TZe7a-`f}vHdR;aq2^2ysgdHqk-v$Vz3|Cj1~#BRFQJvl?orlN)7n*te2B6f8x>lopr z>J6$)`0~>j{L5yQ$7J%pVooepayT%C=IjuBl8%Hwze2k5%w^)xa>2GKlqDW{)}>P| zwhEvPmcqe@{aU+JtV!J#*oX;gi32fXv) zCP-_q7YZG*wPAfPE0WeofbH@_Q1QBvIo;5_yQ7wlc2Sf z!JDC}eZ!z%??*?tHX9D|`wp+nRg)<^Q*#4>*m)#`8*~8Pl89eq;G7QBtkmedeWn6* z!;QQ?B8^QXOkY9gq`-_T@*E@l(IRM-XDYuO)Kq_K2KP3UOD02rF0{j^zD%@c&B`)O zq$^A9PSh$G9(`&NT$C&q{T3wFrw!V>fzwzvyx2!&`tp5g+YZL! z>17s_1iL{u_c?fia6ShR==NHVKUN{}y|ZNb;zBwLZY(REelZc*?pX}kWm-WV*y#wh z$~OYNs!>y;cGkVFiY1g*@A5qnzudPc&Wl5Nv;#cOlb7G!*<9MDBvf}9TP72)IsQ+W z^;?T;O7hS|M09U6kruzmmfr zo@-miz^;qybj$(C9A$f5g~9|y)jXlh8^>dGg3sy+bjE|a#c7zvfpha)$O05sTe%!KDy*>F}mdImOPO35>d^i8`!s0C+>`L{9KQY z#5H8{@F5zggT3zDcg}i0pADHA$;P4WFn*sZ{Oqvi(hs(0ibr<>6Ge8H#|G_MC-aS* zXShz*{>}wJ-HT>IIKb{puDg3=_pRi^wqf21tDEk2c$Q`NhIx8nR_q9$>)73fsYsR~ zpV><3%I%Vroq-~caKw|TO|RYA4o6mlbyT`0ehIem(sZQ4Pszutm;>jGQTo_YKeDXn zFuH@K*&Up5hu|C9HWRmp-h0k(ij3~k)WD>rAiNRMtLf673(kCLnqy*=xT70RxS=|G z*h)PvecW%7S$ZsXVaR)Mw|+T$H}}BGnv+i#4Ib6z8!6?zQ16)HZXAr+bZ4F17%HdL z5UiZv_CqY;(v3a>Kbqo^ohep4G!d1;ztZjw!#^9HTf-tI@GN>ci5oM?CB2(FZmfu2u(nuA?-k$L z#Qyo@ho^HMOO}N-TDK1Op3Ty%G&3A}?rhwbugS`5lEsx%;fLO$F!tEA#`}7I!JiqL zTUqj3@k}({4v(~;w_n0F`VH7oY?Z((aZ|m1OUcD4E8Ckla~xs0;_El&*7&wcM?`Yn zeeDt3i%XVM`J673np*IQtb)p!_|UAkfblVsKam&4H(j}--bAWP=A zhhT!Z>%}dxek*y$+q!I*;W#`m;fXh|i1%Q;Paq3@&$_`v>6Gc?Nj+-0s=!h+ z$KY*m4duv21051~%mQhGWKY?BZ-KR+4ZzFC;rch1-tT@j#9Jbs+hdhtvNPS=UF#-7 zcV}j3Shi-Kz@fW~`1Mx&RI~F#AN&B!OAkJ?gl}Ty!;DCylWFWK{8)Y3aV>B=JSo|b zG#5U=(FgGiUY{Z7J70^#juqEWxQdV14zF!)A&emd7TA_TMBS~SlmW{$mcBReKF2;e zi6YL3+GH4xeba9|wpeU)Llp7KS>x+niOQ)JJadtz$UI8yc=_(y|L-Z#M%RsD;lw9O zLfwvDwT~XsZ>B@W6%_K_nA$yoY=K_Zrq>;ULA?#gX@H^LIR2CU?ywpkvf&PHVyv3G zw*Pd^42pGN*KrgbmIzx$+LGW;ZFwxx*Nq=e?8A@K*h5hADW4z>z9*2CkQLiR6zffv zz6wdmmbSZvabHx^W{LgEcDnRRm*IUM5KJ(U^YqH{1s zm~dafkERBR3Gd_dYA(kj@@y9=$?tXx)th`#i=6J95x9jnjn-II1kr$_;7vr^6l?SxCw^V zDs8_$Ui|i^^v=f_D1JyucnKE?d%I09jUH{&0Ca}Rf!&p^A=_#MUaB057@o#ZZb z6~Wy-pK||eZdb#{La>L!4*|P%YbMdrsFze%Pdihl=FKyOEYs0Rk(1L-Iw9TKAs(0N z<9@85sUWSh?CCaLPiNh$nQPXu@*YhhnIN)!P-D@}@!LTqVjIx-6wg@^k+_Flywe^< zP1f?=oleOVg7t4-%eURRZVIP%vh-cl0g zj^MO6lOZAeq$X1~-=$S@)*ZcjLVeDsCjQ+(@b$BQdAuKAH>ETkcJ^s7Aq;lEI2c?b z=UZgrRS3`5OfhqufYP4YA2q*3d3~WR&g|3L`-*#Z`wl(xX%opR{e!`n2b@N$IdX<+ zMVfkG8BZXY4x30Ge!Z7olo&L@U-jwR!Cgnd5lO)2Nep|hoy>EpQwuwtH6?{Eh_j>W(HaW-9LP8pKi00l4oO~JK88&u1 zrsXDsmIlLQ`H!Xcr+n5X^YyTkklu8g?nF#`wsu=R1TJuh4%w9H@i`rA&5sY)%h0`( zu^qSAQR#B$jnx%m!k+1ep{k1v(i)z92+hyge*hv3>%=vz+4q738}Wu2+svb@3Hhrt zc@I<(U1HhGZcD0ZMp{WUDfz!G){ieDtZ&{|fABa`dY9{a5xO~*wRTPjEd9Rq`RR6y z;IAz(P;;jKeu)S>LHO{qgTG(=efI-wLi8>3=oy0=rLj))cdvW){r>A}l(1--U%wTM&iSUyMC2RKkv>~@ zf8XG}GrJem%|S#V->7~%S1#oUZXYlN7zMX)B7_OqA72%wK=Iex_j3%z>lN?jBu;U$ zJ5+7uxzdk~Agq^i{##|+4W{bFp~?>P@r(OT(^|xPvO{lwJ%Y8d*x|;xz=1svMvc{f z9$4@^=7fOoWpAmRPjuP(j`osoh%Z*9VXWUAJ6Ima*^ie;&5xc91E3m;UzFw^h1CHe|LwQpo>H6eizr<-2|t z_b<+w;ieD@>2~6m9^nMCw&>!HM1aq}n36-8n@zc*?{$fAE@enQTI`F8JD+3CP|C>#i=8?Xu;=6C3e|nC3MFJ{)m3}pHjku4EfXFqIU^_Tk zR)r1R7a@Nhxme6DZk{7O{u5P_* z4yO+8{Rrr%8Q$>oZIpl@IK_X1Q2r@&?N0OgRbwS~ka{pN=kpUSN1p8ul|QSCU3N0& zzn&+**sYegHsSooqYz+TE1`;x-3u!SuB<*x9RPP~cfG2zy!NeDxAil*@Fb6Z8vzqF^qP1V&ELwYthRFM3*EnBKYM_6 ze(e%V(U@P%B+}hBO>1Qr_vNXd0+zwaXGUw1-2WoS8?A|bsBhb!d4HM;hu7XBQf|ro z8f4U{ZCoBY@`~%%pTG;bfRrva{@d7_;5f(Ps|GzBc54q=7ng$^-!GRA| zig(|{Hq-tb_Oq)}77$&RYoPNh)zt~)4V2#SLcqVc=`<27-Zhf{VrOd0<#74NI2-UV zvBf^q$$AVB$$+*Ce=W6tR%vMqdK>;K%=a>!KjvQQ@-F~OCcLZ2QRKf1-+vBVOBJch zU5DI$J#x7~2YTVW;9~w#t;pxcIZ594FV0rYsLD_*4cWgbPo&C1mQMv(ANu8xr1_iA9JkH#;TB!!xeo+Fc^=zkG=8xZ$l_&2|L zj4<*vlHCAvExc`|t{qsmyYVlcMOZXL&!_8epG6<1ScKiQcVW2t<*%7gukMDEZRx&( z^rul+4BNOsbm7-9JZN$O!@CI(g)^Z>Vsn%4`Pli-{foFI)Z}GX|F1CD?kDz05GMJm zzdzq_P`SHp^XsR~u@th+-8C@QOvSPu{V`wANdeWPV*#tz zNByC-@>@B6xOw9xDH_<$G@tRpvF6|&_I<1QGXP*M`Jz&M;CBe7A#Z=lA`-HKOT>ak z1t^CdbGSS5_&RK`afR5GHYbKt(7n3V{xCYNxUyWXz8nr)bT|4Jq0KYf91dPZBj;O1 z$LFc@U!}KDG~x4c-wtmKCTpZgZICxDu|L>I zX$lqp5`_QuWA#cIoziUoMdQ?P>KQ5_@~@4qxa_#>AARvZ{z<+u<$iRRD!^pl?)|ho z7e;CXyLa<10c&KndsXMR670uCFiWkL!uf1yz zhcbQt3FWJ7O4v=U(?$v7TS?_K9b{WE+GwUstZ2Nq%I zptNEtYB~rh$vH7jWBA=K<9+9u_1gVizw7$`@w>LG%jLSvdq4Mc-=F()AD(AsUgymr zN_MY6&p-q5uv4shk|WcfUsF0s>u-a+US`ElG#{!AF;^Tx>|@t+{qT{N{y-DAKAx9N zGqqTE^?%U`rk2)cRAv&m&a}v|I5~v4;h)>m9K&i3>EGhrg-><+G1Yu(SBBQ#H@^D( z#W^SbB}qiJS8A^y2n6C`?Y+3)eM$8~MDFP0k#`@Qqd03u$M$@uj8+R`MOZ$h`jJq>QIo1&oJnD&u-<>CXjti8_IG>DQcgJK3qyFub z233TOM=e$>SLT+OuOW)n5#wh;mtjjU6)-aEjVpKfF2LVC4H!Qy!m@-dc^WX1J4Mt8 zC0f}fgsDcIeC%+j7gPc<4^K8nGzUM&&S&cc$=bc5jioV8oXa*b7RnBvT>HuB-n5H# z93339%Jp5{y4T5lkAsd=!^m1#eaA*j4Uuyh!vp@Zo@dsa4Wlz2fX%w+ee|2Uw-b!B z7;oaHIOQu6qHk0u8!~P$6^lMF4;St9@3lEa|BdsX0S zZ(^L8_-lLpA=y+-=aYXG;v7%QnxFW3kQ0pdUS2P^^ZhI$YrLC#wDj`!I1at_wB(3( z#DIGwR2Vo#Jq8h%-aR9;yY{|4k>4&oq%KZWQ_690JNsAaP`u=8_IhIVpW5v*!@Y}q zhXz!G1&GgA-`16#*~09)u_#q2a?5smI@8=tao3-b2IRS26D|!b zfn-YJ#Ezu9*Y#iLP+tvr-Yb@O5W3H95~;erP?=Sp&+zf|kxHYFH&;I~59{w3xZU>7 z-?&NTY_aw=tdb)E8ol+`=0C!LuWIFkdNrmtTnQhqV$vO ztp=3xL{{fZsPePx63o-Xpt)N~uDjpUw|q(*oq8_e`P*8!Dgg(*rBW!~lmx|RZXn} z7##8CAJpdky*qi9eAd@iaIMAARiTLvsmG-+azmf*J3RtFWt+6(XfH00Zh(*>&8(Q0 zEX{`n3`%;W^(nqJzXt9`t&BP z<~u83^dMe;^=iKkKt8rU$Fi+Wj2&R7Z}3 z^!86e(tldxUr`gIVMY*gtez~~i}*wPwTTn z7(O53Go6pa01(3j$I<=!JM;;N{?nIN=TwQj0AVRNOBWZl2Oj^OJg(B4J@U9YPRU&p z+Me1@Z4l(qDkdY+&O*0jEmM@Au$J5;`ZGdBH(mmDUK9ilgg^{l-z_r)Pca}&!l{N| zeF*U4y*x!uoWGmK^TRUR)_0xQn6KSg%U40MANY{nFPa=7ETNPO;!O)m&W$~9z}ty9DfbQCXxnfCQrE@InhD!{%OMyZVcgM z&5;fPZ7c+I0?yc&*hWee6UJBw9KHT>^Qv#43m;+-eZ|Y}%aFAJJYNpx#*z8#+*i*x zHo`1P4BAGPb(XL6`tqZ!zxUXynJw59U}$}Rg(S_HlAC7-$(6zv!MDt7gYQpp=h=A z)7`JD`a91s?`CkQ4kGx_%C zd|eoqYdV~RD&KE-Xs;p_zu}_<(6W-kggO&|WvI4W@4=-ala~TRDeF-$kO$DKkFjpe zJLU|thi8?s*I~qVrQdj02G;FLJd_yPTR%?}8)lm{xS5eFCwy!)qz!BJWdDC7+IY`` z!tUI!mNZg#oO#hm1kbKK+X^KFTbmTm!gnvf*;)g=m_hqQ>lKW%+#9^;pIC|{7uoY64blJsPQhKGt{JTUtyJWttj7XxWUTTnw&!$m@wjcRd!&m%6{DSpHVaIGX@YM7xOUpAH!{Id8K?_O2+eX|4o84nazjWQ>QR^o;} z(IM=mbG}(;uoWX1kd568BWc3ZpD)UNCj5T5c1h*NRhS_FP}cHRCg&5&BFCncU+CfZ zouuYYTP}s)!7C&r@ncl_(X{I3aACmdnenbtTKSil@+0?Nex2->@~f~r>*C7oNV5A1 zsnwMij?yI465T{)ub@*HDqMSCRjH;W5{4TzgmXGM9`I|e;=(n4<3~9p{F9edAGb5E zhw%Aaq-$Cc8SH$GJba7;PVDy31y_o-IjFUGKcdWYAPV<^?OCVH$t(JdN6*sc(O_cf zlGw#_O0L_?qalPy-8?qNEyx4vnz!MaX-%aSrBBJ{YTu=F@%)5Ok!h zt-eug+z9*Yc)V;*o@`8>8aY_##jeeZ+i|D{xpnqUMWn3-AaR=H>7Sa(YstN~9x)4+ z;)PO_!ud4_Vi=;aoPfeP5I*k0SN!K;^I8~BM&aL&KfWq#HpCI+A9+p%5r?6v2YcRn zAX-Uw9ML*lJ3H|`?e|b$C4&5w9{L|as0z5>Q{FHl=B8n%OMnqEC`?LZKl|d9aR>~m z#crCkqGX@cqhsK5f#D9J-3Gl?#FLCgU&RjJBM^7&F~`05(jEKS*^KqMXE$Hx-`TEB z%!Nb~*Dm_mEM$$M;AwAe7@sdIXyA*yC$>9$|JX z)jpRjKp)>IsEu*21k(O=d;Eqi-mS=H9gpD|jPp^c<_AOvE$EgLn6>(n;;0Pl*80#c zSTkPwpG3r&TrW^{a(x1eRkO$I^_PUsKv1R}Ym38&7rmMH9l{v%Cb$OHo`l*Az6>Gk z!<@DbL^PE#4KEg~>=%gCkZ5;44RhAbl-Oc4$EXklbLe`zEF#eHLcvux!Eew=vAW(k zy=%_aMaEmoIVkOVNln<}@X1TiKIS)>(t`j5LsS+XK6%`(L*_b?lB88iT7uiYvRdPz z5t@0o?0mM)32J<}uj)1(wNsKJ0pr3AckK}s3erFYdSRahvYa8zcEzztu@t05Av^BW z@rLis@`trxR-D%tntuZMv%++u{nlJun1DX4rtMu~%7^l}l`CwqagBr~S&b{~hJhS>zB)XDj6E-d1 zP*n1#(Wm6A9kDkd4E69F!J8Vc%V?5vZroSF$!QH!+sqEpQrr8@ELTR;q81Bk zZk^U;i#PzW5Ooh#1vg;cq0GoQq}7ndMAB}22X4Zg`yylu(keYBIwEFG>N`EenbImH z15=2nHvIlHpD-ycQQ7mg@lqo$pfPJDV*799y>i>`Ln?r`IiBjDGa$vB*hPAAj5ziD z;Qa(y$Puf8RsF1xeH+^2AxJT*O$$eK`9jCL%-&3yr#F7gn2CBTmoHfh*v8(?xz8d| zUmFc)p&DKS3LR3bXow9Wre?vn7J~ob4X?#I9G(qoTNr!cW3jZ^9qp*v*i`VBm?u({ zJR3YKo&}xQ(-Va}@;I`f(S4v7%(T_2{q%0HSMdmEQJ)d0XvjPqr;F|c5k*Z>#ZgiD zN6rHlA_=h;gsvlmhWL~NLj2taB$^S6z#`jha8zV|Zt+P(*OhwpTDa9LZegy57H2I& zP$A8JE^v2TT#l#a23P1K9!JATX6!obKETjW{kN*QUg$_MQYGN7MkVk>fB9vrT@_IQ zXVERE0E3H>&1o>I{s{>Kh5_{QYmbLcLe@8gZ4al-nQzkeAp*ZJ_;lZldtJDy?;$Pp za}uxdA!@<`F46mNpEh(M-Y7UPU)gcV3@~clc8F%!yO=&5Sy{P=V72V}_MM2q9pOAa z@3)w;62v|QTXwp13G;mOs+5B_>9flmFQQ{Zg>;=yAI$QzLE*Nju-udIfw-vD>^;on z*7B2EMc0<*eKtGtdUUKQ0oH!7<(5sFUH&?tHOp>PFB`yhxc_IO**~%~b8C&Dw2opm zZM-}+mukYvP?+`#$?-|Qv zHEsZA(iDBPoz$I@@C$-Rg(m2e6P_Jw?O3KL5Y;|o>Pd11TYf@r^A0BTwqfseHP?Sy zcWXYX?@{Q+2iJZJSCwTL1N}m7l#DEKzAC=JiJ#y}{=zohqIGqC=duSAQrc|%OZtny zBaU^6Zg1$F?C4L2(ttWF|wKnO8AD*oHUs~@^2V&B+gjimR-;k(7UGUGJP*6!C w5aqXj436-@KZg1z;{FMc|6UZNxK$6xswbza-bt}%je&nFZ5)=TEoJQeAN~F#EdT%j literal 0 HcmV?d00001 diff --git a/ros_trick/docs/rviz_joints.png b/ros_trick/docs/rviz_joints.png new file mode 100644 index 0000000000000000000000000000000000000000..316e1c0577f8b7e83dd44562a5e5e805bab537b6 GIT binary patch literal 31139 zcmagFWmFwukS*F+I0W|q!98dK!QBb&?!nz14iel#aCdiix8NGw-QDey%$vFM)}43X z4;F_$Yc>5|!8N{b@C$9)d~0HU~@lb*)BU%^Y6S{0-`IDuktyd$s9Q44tifi zcb#uFgOSXC5og~oDzko=Bh1uB7{!s84@B&bA`sNCDq##p5qSGUQ;*7*?ClbW_*xK^?C+PLLc$Ot zxWAvoo(JesAtoWe#{gjX+FYg$)BrRhs;9vLy0>rbzGi?fib%6_rXK2p57r3R0>N~t zsS+qev^!N-zDz8E!i@p~+Hd#GnGtlZz8|21Aj1B}WL$v57z1OYbf&B+5+D*xwLRk0pp)uZ zZgQW1(3=r|%tRU7)J%P-kQ;;U63p5=@YFXOgG8s3GXy5AYRq^TLtiheoc*Yng;z)+@$Jb7Tl;1zSzRa*DQ2VPCZemC}4tBh5~Oc zlQ)7IvMi?l7UxD{k-j!;DUR|-$NtU$62P~m%j1S-jSgRhj)2qf3Trx+xbqDU0BVBu z=SEuGSy7K*kw}eB`Ym~@X{X5lpiyu&qF)SOOP4Jgm>qGLPR$1x)_Hj>UQSF2#Ulyy zcccUw|EZeM_{nNb@TvAL;-+b+$W6;w1Zz_pJ%3d<|1gcWx4SnfVTcqO{Vr_LX5w{R zd$);z{!h)Ix93C0xy<&qdyyCYySA*AIXI*j4QG5OQQ4= zCYwXY=gx-R?r&EUTSG6#KYm?;J$d>D^TX0bxLRf-`$XBz0iz8}zB^xce<61|Qb^;x z>pY6qIF$Q?8h}9gNp=+fez`?Ldc(QB<5^)oZcNP!?oKG!oZ{SF$H&mRk|}l~b7%+| z{-w6%=ERPO8lZxczdo zaCniRpU#)`_(Ebts-x9(_VbyvfOwc|VCXhNz$K5?kG_!n*~*#X3Q3^v42Pk!t#RD& z)9DA;Q30+yznXm_5O_3_ij_SVxm|eX`2av+_m^o&?T6w24Oi!i7nXp)+dgQQyq6{4 z-_Nya;V%Dj{?+JDkoHvUeq={I;WzTHB*YYDtrE-4vP{kdcaAF7jXF4X-RBNRfb;b|xkY;hhRjceyBU(^C+1m`M)2;!)e5@#`K-UKzGlWQZ z*nEgvPjX8hIN3*_db)NNAj*IxWDR!?g3Sex>5VmRRCp&*9waw^njRHLs*2ykI8zvX z6nu$u+k}47$I)&8MXqh?U~zMT7WHlbzNkctXmZqyFnqwfk$4UC|i+-5fex9=&J~7ya|8 zfnruqkUPzRE4M~7?#M@g$m~P94SXd0yG`-BuQS2}$4;V9(AwSoOY|HR?`!n?KGiwU z*~MS0?MB3D8cIf>8=P!%bHM3AjMw-8?xj&TlX1gV%<;+y69~&}kWo z9P|;o#sxlhXkD^VHM|f`mI(wA_F8`+*4Ov%^VwysT2;;{H81UbubIv!rJhb78I_Pc z{b+@)p7*lpzUFGN0#8dhEj*=VUx}^OqcB+Uale`zTYBB;mS*ZH_thid6U#b|O4$}r zbtqhKb633aTYCv5le6Q?qvFz(Ahvra$ z{qkx6&_kaVeb|h*{>%*vM7=8*TMZ6<9i1#T8daLCMFtCMP3Kc?JjJV(y$46JDdT%) z2O&b3BN3=~))DZ{XzB7X95pU|rSQGNUUuhOSPEU=6b3CD7a5Sw72T@l;h^sPH zdViz*1_5lPd6cA%x*kD8Ilv-BDP3qZ-C{ZuIP;|(G4^i|!OBpu{;R2~*GqkdY zxM?{*q8VNKH82qZ9Q<;7#tlC=yPBbceEkRZe*D)YVLkvbMn$$JmOd)0Ye1fF-qTf2 zml)^%sykS8tZrILTs_aAQl<6u0z5c_D{n7l70{hbu8&J^u428^Xbl%3fO>BRM;C?T zS?L9bvYqI><;ggx0f?~XTvCG>r(nn_GwpsR96p$27+MN0jjios4|@vrY@yp5S=r}z zVsj?fWy$Lu&XcD&YuHc`7WJ?RFiXnKF$4KL#1~j%>3JEeU!QJ78!o&j{}dsb0jEoF zlRU*B!lC)IHTt7j9ieCc?PIf>HRrSdaM+h0=Er?H6nfFgE8QcuceZlh0bkM4 z*^Gc9`od?tolo&p>qfvw*~gP#$JrUzN|soYb-R3^71_=Ds<%Chhnjsir@8b5K|?Lv zT>jy)1h-yB{p{-k>0Lwqbn;M+FrM7WX#NO_8hlPVa;6L{k5ychggF7_iBnBVPyX2Y zPV8h?IiJ68J8EO|gF_Q9w`Xs`0?wkp=ZV7N&bLb*;pFn5eT0?PJJY%YOdtJ?DK3xl ztK&cuWK==pf^)Pyw)QwhKce^Gko&tZ~LA`q`niUsLm371Wgd(Jzxp zK`@zoaB%hCDviOqFTU-qy5%i!;W{qbFKhhZ+iaCpVve3>yIt`iGHtyTHpH`74gf1( z5r7JHvR`X4B|s|f>lonVbangdkNN;1ckuH|Va+6hxWZjezS5M$Bph<{RD)#GABc=Y zJKOLIxr0>J&a(1cOdOOsg{3R1*%pRp+pejl=pji`NMtPfF0x@~M`zq_*H{-OJ4{^jcwzZ;xUB^aR1QBTx=XE0co zLosd!oT~1XdYn=5?BFh)amTUDq6YAwu=*n(!{y)1G?_7U8!R%`qm+nnRly4*_$w=x zm|`!s5Qe`SSpFTc6_mh&ts|a#gU9LiPO8^MpWNtyFRWM&gI>kjnH!lSz?>zs6Wr)N z-*+taSVK-GUGZ_ayg?eJH^CV7XC-~yv~e|jj(&eL<(Xl(;WO9p z?2wvcUPZc!V7WI{WYj_w1*@YiPE4xmG-wjO^(5V;z$ zdBP&Vm;0#vawEwn>j18&i}*uj!5_zJ9#|p)f5jv6Zl^jX7%7qA6%tEMiZUFMBK()= zJtmQ@vKXWkh+?=YFGFKL*D>ib2|1{5M8s6e6-k+U7*#pO&t0O zpg&F8gY^uj+e0k$-_>Arhr28<6WfZ#q?^u4)58vVjSKS`S&=;+&v?)l@0hS+efMb> z>oCz_Lv{U~1RK5Izf@v|i%_w3)E(K`s_nUnLe=2??v|;FrTI(=YahA3PkVc36j(T5E{M3sB%X*aklxd@RdKZ;KEZJV*V z?h0YR3hi2Vxja<~sWHOk+SdbVl&~Gb(RI8ABX zTZ~0~EGSgS8>M&g?{|y@+I!&7ix_p~gb9(XM1_49`r$%Eou%QTXo}qxj z4!49-?gGhXnVgZ>NDNkzR|0sP;x;zi1ZXpA0u7Qj?$w$@s z_n5|d*BRe53)mulG-ATfPe2Gb)iP+7M4%8rkr$d^#ts3e$E8(G;5B`nW(z7MWP3Lr{q}F^R;XG5L0hmh>uxufuXAd!{-S&<_hvpp zi%`QzYfTHEzYsWxAEbm7#d+{k7i^N*3`M!yZvL3x`$hJI!XV;@8x#`Y&iu&q5jD-bw3q> zP4G6Kb}s-e=ig{VfCFoT1$6ujNW|3nK>=p*UA_Ozz<@ePgflLKrYARpbebi(#%*TU zyB)z2e5Ohz-g-v%0O@=U2UtnV%;E^LwZznVOL}G@6D)V!SoCe+${^sDvKPhs(7z+P z-N5?DZn8!nK`rwI3S=pANh~P*y@C&dhd4@$^GU$Qb0dhNOeS7btd!@$k$E}I8neW_9> zjdMntXG86iJ=L@Ny`77SO2+Um8%6FMn6GUURQW8rEtl=a@?Nqt-1-|OO@9|$1&w7T&t9X3w30TSWgMe8D^sbwabsgCj4E$Has;SnPgz z$P;-QjjIhe(z*wgq3{>QCM9p9DUud}F6b@MFhn0%B;ZwahUw~6IHO%Z$AC~#6)wX- zp-@y^Ny{P-9otGDAR$u{7%bUr&n5D4_%1T!RL<`p_pj6^%$W&ad?&q2Yixeh?;_gp z^&!Po{&H-PNp<4oedeGkiGAf5^{gHAr1;)3R^3ZjJ=hNtfC>GCHZj%Ryc3}fO|Kn& zSjIC{zh<^+_2u0Yv&IE7mNOk8BfsaJh~_iHzSu|?tNJe$h8`kCc>9J>EB2Ew3Y+Zq z17g>s)D_o)`~6HA86R!}7W#UXm(tkGre=*tNWbe{Hx*a!mq8VC;UuqzL4m(;*~v~mTo)ca5(65Qd3P&hSwpzNF6%3algXd5ZvEnRfm%SXTd zvpOjU+V=xoa3lzjY9m}9zVL@*e&)e`2}UJh0pPW?tUpxohhy>Ig!VGy_`owO^0o-- z)6aZUIx+Ei@Bo==oXeJ^ykU_s$G*XK1tMeC$8AK@V!10qm*9DMyt4fw>Qk*0xf2KoBD16L8V{ z9xmL;7T3)IP~7(S^$04Q4C<}H=7L3Jo*0WQ`Yaa@793L5)9@Nwb#3P%q2TXvMCC5S z&P4D}J6=KbJl)Yk?_^MPX!X0DT3=aqTrop4nHCgcK*fWE@F5DBTY<_Ndp3JLAz{NH z;RrDggy)40+d#KM&&R4lr?wao`M~VgZ)R4uI4ne+q==dfjlh@OAsTL4Dg_@B_NTkUSH%Z^|^`SZxx$Mb=rE~<| zqGzI#;fAXYMP^-Q?HcUJqnUdApt_3 z7xvo7t`}9mSWGPD1mt6CNME88H%Ajz$$9NojnWXo{6i7Pxzakihu;EF?r_0wtsg8znIw`aGVC~t_jX&q>$ahn$~GccqnU6NJhuK z{RpW1J}48vkO?=k5XzjHI~sWtD`C^ww1tF2&Tg_aRQQ~)_tOr;h{+Jq#VvodBSE4G zIWQ(%t+Y6=Sj=cR1?7rA1#k*|2SHPWp#EyKF6~~?GHM`@>P$89!&kMGd8bN0QDJ4RQ zP&LZ8{g`jf=76*A!O5!|{#yc4n5o6H_grPPgazF(w$p>{O9yO=Me^0}dKZr}vemwF zcSU?W=x=aoi#_rQd$&L&7s<072p~FSbz)RYbwD50@cH`3@=vgZRKvMDi)+)x(XuX$ z?jm+&hkFtW|E_J_kvorV5yvhuW7_w{m!6whS58FeKCsF(>1=grx{0|AaokP#80@xp zp+z@54|Y3B!>v|&E2ek4R@wb`*IpG~6Y1x*<0WNT!#x&pd{h{9K!PXjN&LZ{2?Xx? zIvFY1x~}bLL&XMf`)E9=20@Qh(ZuQ%L3a;`tPY;G$=!j*)Abh3r7n)R`mx%>1+CXf z(>FRfY;Zpt@IJm6$0^N^$@P}ntF3*1aS?@h$MrzB=uosHf`FIX+adY}V!6=A16-*a zjG%mn=eVX?d;AGTE4?n_%pG#pxDBO_oD1EZ@gy0K~dLnD8%2_de}_QCVgv3+Co zEU($4ta%SUa8+%CVtp31Tj|bkrE&OZk6b~B#WXvMr~I_J8g0pue)a`<+Ls(Vk{%YY z$*IVNzxQ99p(KQU<3LQQ;oA#$irz*yrf|A@guay`9v9e(FIN4g0A$~Qd+{{hF4gak687gEpRkxZr*h0c0)fRP`b+e5arX(2(|V}7 zW8K|4)gz9q&0AFg1@MK>)KFq49E_Ya^*1V|f*t}#FX-;-;y8}o)A{|IEh=g&xp?Il zzPG0=Y?O=3iW&&t0Vz($1N)*E_~XHDD=c$m+w;%fxhEFnk3+d;m;5Zn%8vA!UIlKg z#hBB(hKl|dM!S3PlPfz`PA$1DU-qe8Br@wUb?!;f0Ey0x++QGr860b>34{>mA)5Vz ziussZz5IN3|EL{DwHEh4&7V}hEs%OG4Q<7b|y!nXSf4Z*)QE9lSGq568OkN&2|(D{%I(EP-AXuT`_B@AX@Lv(Q}t#Pt{ z=Ew}?5D)`bk_C^8H+{^-rhHQp=%Fz9wS9z8%REKZ7boY5 zR`hxdBPU(OK&DnCkt3-ylZiwsjJNHYj;nc1lffacmc51!`yuqFN)7Evol5TX%*aLB zr)DtM^Y24!?lU+n^fwM8LhI6e^`{38?#N#nhcfbhBb(~smiB#b>Js>@P?)RbK&eBR zF2V5auVQ9B_p7Ni!uk*wD(U#9mfWA2FtB^whHcnLLc;j3z|yGR)89Yc3UHTF{L@?h zCoN4DTKu2*b`VG+_V(}nQRI0s_|g7;ih9TdMgI?i&Hw+ccHc)5eO7OM$40rHcUg?GB62jB4wmeZ?5H8~WT2u*hX*&Is6PE~iimh6|^Ug z=pgxK#TB*krf7H9H1}m2I4r=RXvSCY)uS`*Eb+sLT;DAk0t8U9xQ*P_>koI3@RREk zGzO{B6ZLaT$b2!@l%YERQy;roI~g%47;KPkrgBtX^&VZzN<|cLvlF5ER;*cK`dn|4 z@-p!~(3UlZf3Wt#r5YN*T(=3kZ-N8>B4 zIJR-O*E~aj|AT?=w`-kcnr75d%dPVI5CFKOF`pVzvzGjMXKxnkNw453bjmqR4CTt$ z-2!E?j7HtR@ghd_7GN=RbV9;vN=Lkm#YYLmR#<9BWq1FL8yzkG$Zba1u%z5P>$oa$|xgbAsT zG;-n%D|yRyaS0t^a^FZ-$wWr=%VRUHGhVgF=;}kB5no3tKvl(YP<8H+cVr#%EE4lG z8izlnX{DoecIBW`QOL*qC9V(k-ev63$P<1uaKHR(id*u8ZgB<^Z0Zi$lW5_|B9tk3 zXi}^PD8KQ?=&ca%-^tV3^3^xT;^m)D5i(W}ZDj9x)=#piq`ksa--ql)bY%rT%_IqX zjXvt3+Yg@RuK#jTJNsot(=+vZDbxqeDO^}Qjc)j z@~tjjPOdc%*Rsvn#)$Y8+3cbE-~Oh_ElxB;?2)-4d)(33<-h6(`LiLa>xS@d_|x$k zPvpnqe5#iv)RZCOjH;xD$jq^8%^RA1U6P=Us;|w}G9eI6Cr>;-Oh`{hWXYkS`RWT7 zT!Zw2>&G|l&aJkFp_ru9W~CkZ;}ickDNzMf z0v&q7ic5Y!Xh=RBg2hog_zANfQg>OQP?Xz8iD-arj#ihtr@C3SZHPXBzyhUv8sc}w zEi82_N{MiT`&R+N746+NlfM6*c!v5Vrm`VVD>^B5ojIQnckMa zV^G$NqUo`=Vb|d(5A6I3uj-)MmQuS@dfd!%I7ev^=qo0BWFmAl z6w!(Og2;pR@CX$%qaO3OhN=_>h(yIfIs^n200Unj0X76x6Tn?O*4+^@cobTK7oQDe;&tWxJcu0MVJyTjD$19*Csr7M|f+MUAAO!@?2u`q)6oU*>ihnOf+ii6s9D&0r#sP_A4m~i<;TofsG`Gdu+m?9ENR}Wb`w>x@j&n?uJ7_?b_N(FxEYbg5c;n1Q<1!&C}6YGk@kBD#}+Os3faax8q)F~G2z3Xz}UKNe$Iqs%%DAn z2N_wvA}fInsMEDKGJ(-2GHI~3a1yRH`Kdvsixg7g8fE2Ie*hmJQH4<2l8TVO?;o9> zI_xS`DJ8*zcR9KGgY;poa#ANm4iF@I4ICK;!h>$6v)X%{TE|I5PXfZTi!okpN9C;p z5)(NB7SX!Ef(wrwbNOKzWr&lYi#*4 zHXZwoKWc9;Sdp+P3OQ{3?)KLqJ#F~gmUEO$dpx4Zo3~s=9Oqnk9>l+n!zyy(+J830 zZu&@Tu|)hzL}PGbiv$nr&cpddWyJ#l07@*Txc2i3N86=@stLv{q9SS=Ka`x)?w4!w zoMRH~2MUYkY_C?!-^wK|l5zd2ljnI3vU_cxsXD&cO&0D?o{_T^=+4~wxOf*Eqw!3k z2{k#WLHD{-zH%03PusoJI@$TW(R9H8okJJn-L8axp28#v+c#y=4SP|E2IwYZUH*1v zOHYibgIqfI!*Eg2TD&#Qj!2^yc;frKF<*Mo#0>y>+>?J+2KQ!D4eWAzt;J4QRBMmY z>2>>ee_xayWCW%f`0;&SyC0dX?Bl8V+mpr2C)e(YlGCgTz8G`SyVM$8DJ#|96TOZ7 zM(h+ETaoR>Ecv8=H}-(xTJ$Bq_WEh>y8?Tc5yQ~n0o95RKbx@s#&YZZbi=KFJsBJ% zjYaKXppVye9q( ztp4jk@?A;9etQpQnHz=wtW=XXH+-UWesXa2&?wBk{Oj34vE%O+oeYBS7J%$dSI1Ui z><5q4O293tE#A&AW z(pS^C2u|m@i8T^tJO}{NAJ9G4*M1;=+I#Nz=60<7)Rph-`bcmXSZ|c#po9eh5D6Ln z_=}hQYbyF8d$DF-_oELa6Vp8lNA$MV*4PTid!3*Go0ZQ_4|D;@ar3U>)8#=OMf$WX zGOR~Z;dm_S^%vjgfA}({Z&kjK<5iE%EtkWqNQ?i?^5nyti0l9%SRR`ABJ@2nqKc}H z;Q6!pZ%74d*eIyHvb~Sj_n9((Y+iq-uC#XE-D|&UoWPr+zYD;49W&dXTlR!9L9jQEB#e&JrDGaV(K}(nu zIW(wFRZU|*4V{$Nu64@oB)my;IN2&DR9AfKK@a+4l)himy(Th%0k}+sv`D<9qwKGX z@^MD=Y1Uut;@SU#HjpV<`Hf#pb1%>RDM-`tur*DTj}O6rYE!hf~3QZd@X~Q z^9ch6NzUqDfh)I~E{q{zu9PdUqeiQCC&6ux1Wk=@cOYQEV)08n;YIs(;W&7qm0C$S zUB2aMe%d=s>VD7o^ImSl$_uu#MAFakYnL7O`n;Cg!rJ3s_&T1fHQ!J6RVWExothoG zB`TL|0KhIkf$~MCz?6Ssh?U^^ly$Vt+VR6`E}Xl?0qg#lP{7TpTpF}UB$C9y_$fCv zpN&ME>(Hx&yTQ}?tTxNLl^G`i>&WVLY?nn*OU~3mx6?e*axR4+XNLsGWaMj(zb-bh zsWT(!U@fcAFrKJpn_y~&)t|R2FI@~$mChoL*M+r2tmUuP>xB-1>mK_HU5U^TNkZE^*!4Tf))@xH@ zGGjd&u_@SPn!)||{3i)*icTsbUF#+#kQKVL_ma_j7;@-QUm!<>Vu)V)H!#KsfdDy^ z5$e{8F!ekR!D3P7aTEQMh>#}0z%I4;7ModoOJX}U}C-R9f|Xp1TT`AjY$U>%`}nq}7L zzqyt)Stt|W^i*;6U4F0Da>%KqzK{rP${`h=%tlQ`pOOiz+Hf)O$1W78uV;NDR3rvS zI36DQ-tpG*v^?2Qi`n^n1ZRz#3;)})g2r^|edN->l|3TIPpV9)^gdMuCA)5w*1>^G*er6~`r)aP0+bL&XOu@64tP!%>3 z^62E0)23y`6tL|nP zSS>zTX}^}EiRNg~L%T+o*<0^l#k=;~Hv+n-3u|uNt=pq5mu4pJgmNa#%(LU@a%M}_ z*(2PnB5{thY1&3qI{?@+8tU$Z2``c@708(I517>sr+GiH5W<`P*t#K3hA*qEp6i8Q(-S8>{PnZ=k5Mo?ecG#(Yt9>6*I76&5dpYWhJ| zKMO51;D`VvH@3~7Ic(*@+|%xXb3!#5xJU5vf}k4on$S<8f1pB@_F%woHFl>K8CWMV z9zb#DnEoMksjW~nv!MSE?)pPQrfnX#cU&YatYC!T)CzAWA>SW|bjYT_VhyHXX zHZGAi(7Nm0nZzvDlPJ54Tv!3oPUr zlWRH;;#9iT>%uB?Nsrr6{uJRzZ2_SA+>UFm^iu60bu*YLu7G`;7MFJ0sikIY#w}K+ zs`{Pb+v=C5#qTvlfZb!=>vzXH=@@!`r;)g@{2%`8GR^P=xsMpa z=@U6q6m_^+8@&JSsGNZ+Q`veq8mBBXeP4zD?;6dwZqfnYDoKW&Y)2Y4VMpP==w#?y zHU*5e3v}VYLLZrj<0SMCpGZR1$;To%;*oE)F*OcYAmVs9A#p6pIK10;#@21v$xu3tjQIZa$kf!F?@t)ThjP(l5r~+jK0*)liP8iI>Q6mGQv(`I9qTwUg zHzullpA41@@YLx6^A@fWDd)#c=DLYP2&KO2T!I7963 zlBz-?7JgGlPW%iB0c|53gGq(MS&E0Xa8bH4*T4zUcKfnc?p^8P81iV?kW|^5C(|x; z_!Y=CAvmK(@DX>_}%A)4*#|>O}TZ;?S%Ab;Ryr_}qOPLMXP} zZ3O2w!paFvhkdB6D&0!GJZT8N3053*{-u1`52K%V{M8GP4ed1|W1Q>7v8@o-{F;69NSAyB+^tN3Ura9FKq_8{jSL<+oDB9|Q_G&PR+#U+#8 zgp1O&2{T6JIl1U>{3PN<{ARGdPl2Ba9j{l2vm{!7WKhD-S_5e_ClImrEc7#xCz_|5 z6M8;22PS~hm2`M_I8_yfK<|8!d^6Uu{uru4Xz)ycEICN~e1M-X)vxa^mL~v!$Im-& zSGs1~OL^m9gBASp+6Z)0EIAH4NB9e~Ut3?Vz78{a)@k{;tX7V_TkS^BdCiyx!EA4V z;aD!M84|9EbT}zZ1`P)1RZ7?;5H2CRj49M#R?SDwFf>5)(BZul{?p>KI&L|^3rkYl%w25jbQb8G>xApASg3#PsKTf1V zeWSAfYWdT4J^&uOwby$-WC)wxL}KJmZMd-uLLx%O`{G26FfKY72q0=}i#q9uy!TPs z4#LLn=k-+&c!hh|_*ScGzx(Ew!@B73rMIIhG@smj`KozZV&P#$mqU>Vh&qL{ts;#9 z0_d;P!51_d`iYj1bUU)b936nNk$I7qWtJ`XkpIP-(tQmN0TN}+cgY$*6s(qn#1Q$P-wt0|kqIsRQ+v{AyQj|5+0W@t8IT--j@w+C zY_=fioa3}t)~QuJg%rqOQ&2q#o!WJvUj%`BR>qv39>JEJitxjQM86 z9e0fBrv1iWxr+zrg6FQV4}9TA3*YA09&}%LKyKcoN3vg~Us;h)JQqN1za8dTXSkPBGWD=Hf`BCXH=-*@ca!ZGXoL3}GM}8*Z3k1!&T9Zjd8h5(`AP8x{=(gpWHH~IrzImBEOL3oDhRH&fwAQ|= z9ppk*0Jw7)5BFwcWJXDK+a6w+RMKbw#>+ox0WSvmu)Hs<0m@&Uz2^sG335yG;_2KF zDMsJBJrM`w9_+7%!+Xne5fU3bOkM1DWZ0(vh#aHUIP)jZrtbd(a!U~colCkJi>_B4 zh63~%Pb|5V_5aZ=@UljGO)&pUZcrX#%BQglZ9_%%^E}nqOMmq^Uzm;?7V%^ZH|lW~ zjoeFizG5ZbDw?H{Txr#FoS&6}`lZgn@YYEEraom;P-K)gpKfj%+~in6IV_rJ?wt0< zZK0k9BA6>&<7(uLG0|#|2$tUltHfqE(#6$2pkHAmqfDaxJ8#Q|1pGyVJM6;A#okzK z)LS#Fwb2UP_u=Oz;-TM*^%xmjJieX(r5v^n1m1c^PFx>SMe{JJn2Mx%_$lG{u8g?2 zS_kC=*wni2)z-zsm0i5{MG$e1Ac&;YpJNO~phy;<>i2jD@##bN(oq z9H>I1kJEC{^I;wi&qi$?(_*J@@R7Ox|3L(561zW8CMUlWuGc`Yd;;Zws_qN=1UgMc zYz4&NQBu-8-&SB|!93}YO6KHA|Ab|{?@q|k!gwV7C+v}e?5R0RIN2;Nf&7m9DRJy) zAOhzlUbf(GX!~Qcs>2#T$kDqS+MN(>)`~^VsSmn#cXTYr9Hr z{@b?#x3U!ulAq#SYcsB4zm&Q}DnKC>$@4VKz*{9zqQu54)QtnEb}HiUUjAcB1Y&+aKKNP~d3Sy$zKjvTJt^hdUegpx`C^I33=)9o09{ zobomq)8_d)38i$Lu-@{e%Z^P8;CqXP3{tK4(;Eek1P~#^d)@1`=?3h3Tw^#cKUpOm z&(gu+&qplN#DoeeprBL2N;fQ1vIu=pI8NsMN+^lF9hn@M7i%&8Ad^^x$YJqttHF{y z6wT%;9-%&*$)@l*zS4q}sy8$t{kJwNJL)2>dCT$3MNfrutFxaMt5gHoca!5lFw?E7*GM*ry+}%;+x&! z@f#Lb5t;aK1nwsyf0uYx60u!~p(;cE`gXh(&vwhx(?5cbO76lMKa5Mwy`3=ZfmX*| zr}jrqaWpEDLFaLz%2QW~!MFWGZ9j4jB@hr1Bd_AZyd}aaJBxWN(O$c&0TE(h?md3v zAqV;Y2}dA+2Z_<#Q}xltwp-O-)_Cc7R+As<)a;bT5ht%_=HorBhH42zuzfhj*H<61O*NzhZKd2L{fgOw*FBeCL7xG(s&Rb`N=-++wxOqIYV-5ja@Xs zY&b$K*IUcI7!Wi#sh2NvD~6ykgdXPnvtHe&CKs&+n?vTN|^|3ik;FnQZjZ*9{~N1iN7 zkwF(EA&0|o4n331<-6;x@6Yas0l>8V&fqSkPq4D70B(uLuChsrzihRrj5rIn!4?(W zhvPTOMfp9ox0`{=`-@6@t|XR1#3M5oJ+km7qq4Eh$ago3Dpd@GA!CIHY*HoVGpaoA zsJ=zOZ|#1;WuDWt>16*G8vz>#qNT66T|^gGDENnZzq(9W2nB*vTuFVy+B(~z6zr;% z>~Wx-X2RPDrgk|}PvWtE+#G8>S$X&HZgy8Wpqsl(@Okt0TPG_)=yGHypnE#CoLJt=s&cgV> zH~QLqx`~1i{i%nNyqz0`ZRhnz;A3#~=1na_a^wL7FpV)ZCILm+hV_|mn|waPbEw3& zepY=^_wiba#nox;==a`$-O)pz-O*{=w$8pvEIsgAIps(AiYHi{)ZA{dJ@^h&yx@_S z;qckEqvvM?AqxjQ?9#JiM*5(=Q>^D}Y;8m4Eh-GR1c|?k2&mu&1CL+feX$Ny zD}fMDgNIa|jxmAocLnQjE5OX6&$-F}Qnf|zS52Z?ARRs~b-DK-W0ldU|*ar%hXetu(@l8Q%ARmRr+dYf9B^l;&?*^e*S~ zq}9e1EZ!RVf9y&X9cb#1lGWw)<5?|tXsGU?d<^U09ynr^uYU*cnXgU`%QM*gbsrrT zki2iL%H7l3(N=M!L5+6AK{aRxyn>*@3=Y|7b15fhT7_k1r#l|C`$ge5=8E_W#9g zAU0F@H;^e(3ixS<%ftLPYU4^8S3nH?02RR$03$@zI%vN!Cgk&?Y?k2g_mI@S7Cc3j zvNnHT$DXW#&hP*DrU?BXFa~!q(n*nV zoOW1w67xj%~EhU$_R(S!Yhr??{K+@b~or#s^=8H@fQ_{3*iI=vBY$!{sk4yTA}+%*t26$Ex&c z0nR>cN}0#}Iu&N{pi1jbn7b$|XK;Cnq0YPv*HSY%(_3yhTu6PVuaFu}aV$qYrdpsr zL5u%PB}=ZXd}d0HAJDX7|H`3zN3?i>uLgX#ImQZ(}!*XduB@Eqo@PU|h|4)8GEE%v25MlKbG zE?E9n`Fvy4j$}N%6GIf?2Whk#)r? zZ*1=c49?b$MwYg-;_S3KhMZ9MdcrtOAd4VG{Y?6kUIC6+Y77rGXFo+AE59{QLXF=n zJOKV#^v*HOI*C_7F3W@BiAi@5V>ey`BjPB@SfEdI-ph3&Mz4#76?WyRoNsqCw_i(2 zR~hf!qomgeubsv|wl&+a-om;)B>H#qw|*qh54-9Puk%{>qDnv}jrhOXd+(s8zISgl z3W}(}Hz3l~AV`ra9YH{(DOEsvliopk4=PIUAieh%dXZ2tlQ)Koh3 z_{!!rueep$=e?+xbHKHgifQ}1x2#qgn>gfPpB|FB4Eivn!-|DT213p`Barx$nkkP6inntPO1Zb{T%Q% zDP8WG^(F;$HSv1?`O8nYPlzo8*O$r(@(QX+3Dy@h%y&_9k;dlTcZ&_k2K86U*2aYX z8u6Y*&Bgd|_z|NgOh~9z|D1u9aIpLPgTuW63+@(S-#}U#yigdGFTyL$SfxG*27B8+4JNRJK;U|!weX|TIr!WP1eH5c-UMmT*xPP{P(n0- z3lRiQ-o7)tbC2EFoP~vDi+1VYAnG4UC3>n5;+W}^c2Js|!II0y(fJ$17M2Sr*0pc> zUB( zr#5uVHz%I6GBCJt3$*$eF1d`{f2^Ns!^^<1KYG5!HAF1|51nUlVo$KCmsadBf(@s* z{;;=q?FoM{y_k64(kwi~szq;|6!fT!YgR!>V2%Ek>nGbPE2U^z#erOSp`OFXeQ$8o zh?^tdttV+v2Z7A2Ic~2GZm)VTxTDKRlQ24{={ArUS0AbqbT(dGc6s7s+qq~eC zll&=B!!!pg0$05>%3Ih=Xh;;B3VK8p*sG)jVWk4bcp__!*2BFku2*c;e-S%H4qS|B zFff>OM0Bqp85fa5RX`2Ip5D6}X@3W3>P};TyXON;eNpsSAR2#>?-expL60Mz^i}7z z!nd;-7;=;h(#<+b)#_^cN>$Y|T2MZ5J zOPO!gWIrbM18VvG25K#}*T+UhZ5MM+Z+^0TtGKJizyPNgZOA`krbNz^_dHZ3srYdz zasPc-?R8ee{e=~;_Ub~lU&O$eK`=bXQNm8X z-WJD8R`(sUVQd;_7NwBs_I=J1cF=GGuHi%X?9mvVTWl6c2-@3K24-doh;{mG){O@9 zmpz~j>Sl?s^>+H{6qKLt2{rBOjhZ}FK1ms+hqs&UovL{jA7nOm*~XMHx`FE{kLoX1{ypsRvR-)HQK} zqYTw>y+Y>#P@&*rU4vwF87pbln!ATdgL}=Ou#sW25llp03CYs!k>bWUc_+xfI`5+y zz%`)!eRQ@d$VnAjc6&gBS#`hSN)8ovB2|-!rjIamlSA3m2fezcRa>5rQf*-Am$4yz&_AD}MDK?_OnV>NUQ z`X+jCmI~d7nNN@p)LU}Ip25y;e3GG)-$hNS^kZ&vOBJgb(AdQgWT~EGl;EX#KKzI3 zP^lIj5V&Nd{(?{Wbov)E*O^Wv3E-+Y0FbNc9Zg(tS>F>~?*k?I3(8-cH6jx&qM0%| zUQSX2GR5=9T_i5ba?6TMEfW$QZ4XT6X@%~R`q;>sHtvVGBvNU49Ibr?4nrN*l0{zU!~C~X+_>?k>cE4G?#`^kf|O~v z|D2`ZsR_aPsp{WZ4B(bb>0e)X5GUqj@hg3)I?q!j?MYkvcS7PU0uj-T{bhw{F}aH& z85hUYFFQ&tHX~mEEg|IUx&t3+06vu7{qEvbGfMm~{_Io0rzcyETvu`~3aX%m^S764 z24B#5Lx};T+VZoJs`ajRjER_N`lcAQ1k`(ua(gb(uUwCrZ9F8lm&-{2q_Xm#g3jEn zL8=9pzh8S1SQ_x7j`g;??vB>=ldEAnI+f1!d#`K(muBybLUz`ZM99sALJL(IuQoT_ zkRJ%L!k&)F$;(LV3^ zR4RTcf%0e{lMlBV;kP@|x+*=&zav=#bj;N{1sPPxNIMVrx4c3ePP24ABX*XJ`@30c zuj3BM{paQUv7{{`ILqn&8VL;14I3^c2D_w{cP-Yf|GFwD<=!&=l=&I`P{~cHm+@@* zmplq+L_2sfHf`6isOcvAEpM45AD{A#rh{w_Hsl?u!Vz3-K0sq0AwE}?=q9HyXQGXy zdfTgGns)HU{1U(K1s=wf23&=hFm*s)?$vgN3-1PhI3Ap9i^gA4Y588aL-|7w2ZXIK zEw#j@M{-<`jvD17vC&sI`E8EY9n0r0wJeo0tO~uLSCE2>vlj!9T7^vu%^Q`e6DEe7 z9CG8;6BJ!C4I8(oeZ$mE--d!X*1;E$ae z3h-YzOQT6}bG;scHSWn;7nMm354}MxoJU{xmp*)aQ;wO^1@i1r@N!?g!)_b*FYUrS zRB&No^Zi{wnz1>n9{kNJ`h6)D&`wci%EpIU7n7r-F;=vEB-s9 zEl@}12wE5AId)hnPCfZFIoWFk?Weq`iSrGK37?^X4bo^V9FA%jN)0CaY7A?ESv?S| z5F^_~-Qpv+2l6L7(ZVE!oDePzf7}%Cm9+pjwGc?*)!}aV$tIOb0jL zPh@nh-NPrqE%2C&xb8jfK}5yVR0*GirphiC%K{Z;6)~{Z$!1=#XT>6df0LVLLXJft zv{Oe8y2GaUj8^oMPZ%Qnsn}2*mCx|Gw&X9^=Xr5m(|nzP8}^eQ))pJ~VAj?8Gx7O! z??^qgG&-yzNLO0$4ui=?Fm=stOwWdGL~t4SO{29kc3HC88Fy`zzNqyrnIC{rz;ztj zFJU*Wn|eCT6zj{q?9NVU?mzgtKjpSYueD@QQ|abwY-35+UFPkww@#VsVK-`RihRhV z6Ep)aSch-IbCLJhXv@9@6={WDZSt9Rnhd#3m|8Q1oGm4qR)mvO`<=0}XlE?IugfbM zw>A*o_0>Rv8I_Aq|V2dVCzPQe2yp8DxSJM~TDEs=FK+rC~QjOs7Ni4gW zsY6dT{`x#^Pb6>{g1kxC!eNx0FHC1zEBSM#j7CUoy-h{T7w)YYe_1+s0O3D6C#hKU zeYa~b279s}*_D88i^bnLp0JgACXq)#bCM_40*)l9;hyHko={O%PMyR@KvjaY_F1T1 zTudI!0U}_m`-U1x#m!gHXH?UlaoqU(*^@Gk*?EIEi~ndk5T8{ebH_|{s@Vs}2 zIwhHNk~EqA6Eh}j8_0euSax9ErOq!fWxS!~b`A-9D8aU-K_dMGb`}?eG8`&|V%K;o zM*5O7_2$m^btfz>Hn*5}S3%fs?<o?jHx+;0No0(d} zz3(D5U?c8d;#1WX9L#^oy{J#6ALrKBGE0+P?%A~S%_mkvS30j`M!_J#P-4XP6$1l_ zLUT!}$?VVTNKz#Ggm?`$yK5I@0bXk#?CO9@T#d~inJr4W!;z(z8PVL=?l*Ntf)xkf zUr*zUpoW92LXu<$P{3n9i31DjIy(ui^|S2q^G1Pen-m6>(nz={jP6B0z}vqC&BAg zIW7cmrMO>kx|$Gd=T-lRZ$11nAvVo(LHqU-^Xac7<;Y@2 zN%ve&Z2W+up?jn*VPc-jKQb6rc={1I^(5pkA6QXtbl zyMN#1{?Z_viuMMbmzjrOPMYZ|(K^;fV0v~py{Wh`z57YDHvv~+Ecu(@{A_+E1_lS@ zLZhGamgZ3UO;wX)fsKw!4Cy>-(#^zj@tKi}L1zlaB#W+Td2He3tV#F}B`B01y}!^k z&ot+I`scOfh9R}%`Ci=0w~wDAnDGcBT!YSEPHvR!BNEBhxCUZ&mZH*qC^UpevLQ3lG-r zTwKvfc-A{1h^pBA6UMleT918G z2(Pc$Z4gCPmsf_6@>vTrz2CWm4^!qW7hdcw-myTQ9gm#t`JWVi=~ubT;Onf89KN{_ z%D0w8*~89Up?nv%I=z|8o8~D!5yk#DMaK9?XFg;`d-YL`%aN&HYu>c@>>BBpHTm|0 z0U;3ug9O{GTFO^W3dw>D&d5ZhCDpDyiML|r`SR};;~+IBpGoc6i^pzv-U{u7Iz?*? zGzW5b%dYcl!27dy9Ogp1a=LBin5w>C;*LK)%C7EkxHw9_&hsDAIrG9C@~Uq<&m8rp2|@7ie6|rx;xw|ZcZ)igcla`M8Gf*}=$cvVnQe^d&v1D1H9%SG z#h)+f4bOiGIyZYe#)x^RwCucuIV8`y`t>9kha5Y5Os-h0rGx2LLyKCE+lSDO_Er}Q z&-jS#t9}s@$CU~7k*SI1Hnb19$r?p_eH!#PP8LLQf62Q)9+_;7z=78;*~5d892CGR z>8>P=D1I&@TWK@&TAz~3I1yRwuf5y`Q=_C01oS2OLOy3)k46%2vCL`RO!lkyQ1_)F zGo9TQE4ab7FQzNCx7T+pT6v`XVOVvyRz=Q^ohuXe{RYo zbga0M4xacol()m9{5;C)LC)tVFTVaEy{UKEql{g!2n9{~V@n!0L73khyZ63kOfeCU zZ<7psA5=H#6l}U=<4Z4BS$rQ2{yYmsImefNycwl?@Z%Exd@rYbiTHOEj!*DKcQ0+e%V|+quAm_58`#p=m6WIKeL2OOYs;>5vvbtWEj0bJpy~~JI5zzC zw3)_LqqR$Vzu2ISckg_ZapGkdW%n)VETMs`pS;cm51-JN7$)3wKI-1sQ!jo2@YdHt zeV`!RQy3ilfJmu>jQnWdJwqSW;M__@KW=gO4Cc=kf=n89r^}RE4)+Q|KMwY+cX;hL z3T-H1a6gyI{ajA2>julftX0^c6O`#1uNN)Q+%g^X@TGQh^~X<5 zlm&@-Z_m!t=wK8}HB|-77o)!-%v)YY(0Etfas{#x<0DOh{NEAXvKV=lz|`#neGc#z z!z23e4$`jKFqU3|B7RAq|E!)k5ixloLH9Kv8LzqLQ@uX}o@l>QnT>RHu&4evZEL%W z@PvLD^PSLMoUp$&x|eJwr6P3etz%w1irPHP)$=l;{y&Ot<$>L%t=w0t^9Z_IpULFo zWBtk-TDYZ?_t!SpNz&ZLY6l#%Dd^r#vnjmac|az#=<-y(<`y!J*pI0o&UE*E^df79 z_{MQ+;&c@Y$yY9SY0yhbpm~Um?~yQA{Vm)>-QBwu0lU)L?7OYO!Hb}S@V1f=R|#R|lALgWC8B`3tZ?5F`U zvwVkAZ)Yb3UbQvwl zlUXOcq@`BSro*;~D9HTysVh6+lpIdIC8{!e9VC;2a>X8PIp9BQ8sBnm*6h9#CNZiYZDA9WaE@qRtCRo~wn*>;eO2o7J;yKju}V)Og7 zGF0N)GW}(S=qN!FM{utY%0lx@PsQU9q1yExm9*Rh97ChJ!sdGT>%=?~khP_##igjy z$W@iKOPt>V=$M(Sr1f&_W0+am+?LOhTOzJ#*GM5eSmYFY6*f)>_R;I#JMEt7%_oOM zh(}X!eI-!P$AX}jW5YxpZc<3@XSTI}+L8>bWI=-CWvqgCSlGcSx3>)qcu1>llBW;z zXM)oT`gLje7nSs4v}?7MnqFvrff+q3kzy8Bk_ka&|7O6yln*9nzm5GaWT@S&L3>MB;yr%I-aKhMzX4K5{Yf{4S$d3b=j zmEma1gpr|m?hCFtFj4F0kj{Q_!)BUay~kN@d*JF9xN6mDZ!B@H?9i7u(V?Q^$d)cL zd!H`PI`fPJkM>_PET*+QgWY#4L2B4;xzp`|^ymH5s+J3OI9$Ty8Lj#Go#E+7@_&=P zl*GLHTlVksBc4>^(+Jh|7Iwu@crU~)1%WB zZ|I$r)U#uf?0B)KbQ~}_OqvPx2AlNF`YDSH2p10IfCTW3C1bKU(1tn#1I6YFr!he@ z354^B7eki6J5BmDRwKpKxYMZ=U%!Np9DAI)$vq;pP4JjVm$VoM%t)XgbT;_yr52)S zAH?y@LN}`xCoKQvFbsBMzPqtcmJvs)Z$>^_rQ)0_7}hgL5%UT(_&xbF1K6xnU0R=< zj=*x-KcVNa@y4LjTn+{^vF^txufA0cXf7Qp@2Vr{%F&N|z)1UYq}pI)LwQ8_;(IMn zDxTBCavoy>jQLy#n;m|_BM`>)mg7>PcrNDzti~! zwa?7_sV+CxhB$hL)Qua@(S*{!i(SwzYzWXV?KIG|Z(O#^bl%2`=W5 zE%rN@FX~QOgthVYHsVUvZosdt?n_H=tm~C9h0^|;`VOw;!A(JlaBWF-2X|@;@*|!V z2}+EO)z0bsO%#+9($jJ}j!a=_Y~+_P_k#uh8ti&*s^2G5o2#+m)^X_7-tP(60--{A zTi(dzyhQP->(D4jnd*`C9jKks$IR-xQFV)K6_R1I#e3u9q?yK!Ts+LhaZgiUE;g$d zI;Usfu~Bbaf0~LmQvbz)K&zR@WWM3Ek41^W7J}aoT^cUl*@>G7n3jj4dPVV4FPKBy z!SH1a1(;R22_4XJJ1f;~DuZ9LvbAe4Z5^UBk5!~D0~>)P=8YPl1V4wWd-YTNu+I}p z-G+82AHW<+?seNKa;0r$_^2bymW<9(b3#HMMbEEeyZ9bB51*^UDEthx()2z3cfT|0 z>D9vLpQwNu-l!%#0*<9NyA37xPM(`jjlm9lbcgXRTxodzz9Zn8*H!RVaMzz$A||J_ z!6)?%yOIXCMqA?LM{w&kk<|r}={or50$ZZ&Z5OD8k;P9VHlQrS28Q~6qsWzeSxt(6 zTpqWa>QA%?1)HD!Rk(M-i?oBkP*bKkTTZ)?7%3H_`(MiRp8Om0^2K#K(M+ z|Ao{?;CoVJ1^vvZe!8scZ+h%;tEW&;4cr-`!2|_uWyN z|61!~dVzj6=uv8z!tY9}!h%h8Nu2eyjDLIf3Ds z5`*i)#KFK&rryOUd(ZzW`sbBLyzyjqUM^G)dmipmAy1cP&9*6Yz4t-l1Kulwh-A{& zjJICB)!eNwVWDbx^h)5G=z>Z`eh4QoWi2l)y)e`0a=AVXNfEs<^;lAzs@`N+ye^+r zMwZR5*_PXCPZ+kjno_+<5oOZrdOuTU3-?lZX2qdjLbh&blKUYVkaKVF(qB>R+Uz%9 zo!K9rDkt?+X=%H&^SxD3yq7v-ap?lqRj4A8M-x56RE%aOOj!eGqadr zzG~&050M^jsCmlt3-L_0&JGxWq4-?x#3(~O^Tu>89?YnTv))+nFWA!SOW|+wAM|$# z;E}9!|Cz?WpjJvvPmm?*CN4>9P|xvZjk=*?L(8VBw@dC$u}5N04+u3Q17?kNG2?J- zY5+IojSROqS)3T0plT|HsGr$_m#byZ<}bD`(XfkLDmL5o#Oe`YQO#%;u+s09*&Z)Y zSNWBWER6r6|HPX7{G_7DD>q#~sf4tYE&ToO+%l)bL2=W_>c<*ZjIn$IF2mE~vQd?a zN|l?lT`nq~5n_HWKLfqkeW2+8QW1j~`c5}Q;HSAi zN4qUDm~CrJLE#nD+-3qzV;acRKd`78lp5iI{T9rggY730nugV7Z@BmjvekBLlD|-_ zM!b-Cj|xZJrL4i{XPthmwN!qhQ_UTgAK`Ymx`Z|V02bR}rwR5wxKt!u4LegZqN4E$ zzHL_ZLJHk#EV6`7R#7+53{w}sZT4ZJbDAIRN^t8*E!2#wo~leQ+d}C}8n4IcKQOCe zK{v$iII@oq*^$407`{9dYmnWCJcT=2uK|ozCu;E7T_4Nq$%Z(`5rxMU<4={nZ90Z< zJ+@UQY}$#w*K!d9Y%=jvj!7k)q~d95N&0k?W<7V;2U4D<-_)nK3%>^dsTpN;!QP?4 z))$LI2tEKQz#x`B0#V8F=M9sfU5(zyO)(u#6W1NlcIye#0GzgiPDz;?9oJfN*3i|X zKqimL_~9@m5tg-eBg?@wt;^{~a4)ueXt&8`lUty%#)a!O;#1;5sHMH;3;{iq#$KC@ z{B6+2`vfL*oh%t8FgL=+Ay%4GgYa$CUJjamFRZ1c0?Jn)I&~lfw*tn@oi&$)naByv z*U1B`&^7o+Nva6w%@QoP3KHb1{tQ!TxBlq0=oV=EVdfJWl8tG)jj zfWPMbp8_z#kSyld=*HzZ*vKsNRCee)r9~$!r5^YE1nJUo=Z4t){Z*}ksm923yq8!j z5!qkpeb*O$veA8sF3p|n0!M`HhoZJK^{b(UdUpT@2}R#O`-LRG?$fKOM<>71#tPOVMC5ViQH}hUr&1hRdnr@JRN%!=z|h$wec=(Yvx4TnR@mWuoudPym!~rZ&EJoV1<=feM2K~C_z@AkGI^ZM&BL+|n(1l{{+fXKlAGYM`pp`e!K<2xL&6ml@D ztsdvQ-QQDbYynJHTt=;>>_bbJZV3)Cld1ifY^{pE_ z0I8t7qP4x_uG_6I%lF01MaLWKjPcr-#jXhAvzOfA@i-;$nUU7Lw-siwXa)wcmZryF z5sEM8c@h|*>JsvJ-@Xz?r+kR|5et&{aVoy)R=hm(&@)aAQnNTuUMXhTyVXcOS*%nsry^$SMbKH{x5RPL zByyGWMOwmo&a4HUb>g6-P&4!+tb;}_`RWaYrrtnirID|SHBgoJG=4c=$NOW(xxjAA z<>K^oaMw`RgU+=`xF1KIeMsH1Y7@iJ(TQaQnM%_~kjM<7D8&2(Ih|NEXc{m8d%=Cv z^|BmTHF!#gOBPMPymshwYHuhgX3RaXE|vp^!)>|y_^_L&K$Gtvd{2h?~mm#8gyk;=5KUL-T^iK0i&5uu9v1} zxVNQIm?E5f46l5T!Tv~J&Goftlf1|32nhgCsj%gprrwPi2qI+hm#knUp?Tx6TwRxx8O8dfe7V zE@IuE>uS|}C6L_Gt!6#_iN0^S&hgjFtH&QeR#*3dOlw>Zl>4hQu-0}#JnF5FeUH@K z4vfmWo(5iD3%_wR^5AZ#*6XOH5?TYkmDR)5()DWz?K)X$ z#p@64NC@1vp~(%+W}fF&Shp@&XI|B7N`})p-@ZN1azv5|% zO80R7a`Z&!RO_sGDArHf6E1Z7Ol7}gih+SmFVnle?(ksvK^^b<>2h;LkY4LSnQ{ma zxNmeD@Re&K+0c%uK41P>Rl`%73{THO-E2EkcH&sJ*&;RtNUTPQz+sWV$Q-+1Nua#O zRZ+{_7)2yG5ST02Y;8Z2lR|EDLIKmb~8q8C7Mf-03@|YaHUuRuhSEu^PP}sDj z`6Rf-sqh8+RL)ks;&|@3gfm7;8Q$29Q8*~-`7w7Ci9^V`tUolRsk?gKWMU`07k^lL zGL#aOHr@j#v$7pCg(o~M0oS1W*W8`$gt=}Qi4;?dqU37~!82@2*}MG^p-tT>)6SQS z?ky?CdfW)p3N{VBhOppIRC??R8dABFWtEzaLKk;@TGSGfJ*&%gKf_eZc5NmTgwhfb zaUTkIPT?_x`6D6&)1`qnb-S;9ToxXkQt?z{#m~-Q8+Tvew+^=S475oJtcf{m=Lt%7v{kMq2+Z~X6>Z6Wwu5&SZk@ls(1m8EwHF_OI4))9M2l(z??y$ocy_Z zjiKLc&L)?MoDX+ARZn6wqNyFAC^7vIIxFfvZ5lGq#;2ZFjDFgG3Njg&Bb-*6LH|f+ zZdcBg-m%&H>A&mfD|Wi%y3dYSW1lW5fky?UPASJUUo-feuAM!#E4y#oG>yGxtK&4j z`|$Bg3g8jEgtK_j66Egex!_db4^ov~^~>uJWI#o6xGBNFHuF7;OHMw?)fTC(^7Wy? znxY;?Tt_l?76SOT8RgTI#JLy=_m$J-+KIA8Q0=^qjgC)<41+GjchsQaBgidOe1+K` zd;6@tP(uNr4ni<#al%mwjaLt`%tkUlQ&ZE<=uhq`|hb5+q-zKj)qRFf;Z~Lvgq6|MU8qcpO;`eFj$3zaEqNz(Vo%X(!NpLlL z8#Qr&n8VkX6CQ1?2P)p8WoIC#{mZalF7m?7<}vgGrW%qUY@UwKtQbc;^u8`7HE_Ue%Xfy2rvxGqS?G>@MIeW~j=Yl_jwrFA-o$fWs0tOQ8iXBr!JVAE zwM!;Py+4!38+D%y#mF#jsV3~Fh%ZpA3fw7?r5-uQReR5=k|&gD9^anvx2->X#TZ3G2I5#vGUa-(IGx@>zBd&F zY26A^zgrJ(gUcBe5pAU+v$65qyEF1W8fZDvndU*m@hlanHrcR{&K>M;1vi)*yjscL z_Xx|j@lcRpT-uKB_=%sV`yRSXlf;S7BB$?<;Ld&ql`f~j=Z#^~DA94VjimP8yDTbk zv5Am%L-M@XDx)*UbBCnf@9TK#VC%Xl-1ziC8q>rTh3=(?NAq^`8{woA1r>pk6kgl0 zcWyS|OHlow@z&46hl1q^bG&;SK1hgeeDDvrXhnZl>D9^I_Y=%}-Sg=J#6VRAP*sqx zKr;q2>iCI0qnc{#0E%vO`F8SyGQ&5-->&@p7o5&RZ!bdkNT~P1SNKHU-#wC0z^2m{ zLj*z*kqXU3Epip6Q5iaygwScU7`8MT-XFdf`Jo2nBYVMc?QFTidxIS4K*Jj17`(%9 z`N)G4`AwEP*fJ<|-@b%ouXMv6 z)D_lW_kxd2=tD=f-U{xG@>;cA@qD=cA2J>uE9sp}mN#~++2`F~eU_d6Vr z5P?US8;0@Ul5!A%{}Ru(Z$JMMps!Y>%anyff|nIqb@MocdaR>xL(AAi1pdhF4+{bR zCu)u85btJ=M$op#ZhU)++B||rgolq^>Sf)Q zLQj&ksrqcaK!l-^W|^Z(-9G?QR=hSO5;b*YvwFsN%Gz7S*5BZFOmcD2$awczy~V(> zq85AiG6?Xu@F5_BXKuQ9uq?c!gcf+x=dYn5kgP+~s!WsX1FZslc{_9C6RqU%@ql_! zd*UbL*4JmBYl9#2^dz;k^!*T}73!0_{Cz8Hy2`#mrP*jud2dh>BOxjHoA+isvJ_{S%qZaNlrP}PX?*n) zN?W`4>l<4s_4p6LNg_bXRwWhe|1hS;hc$e`t7~x5QfnA&F z=GG2(@qAtvPwn4UoA}YGO_@`c`c3q-&XoUp>@hw&{trN08Xr%<7^G)Lmk$&O7*!Z$ zB={Rxc=G}P2*w-z|DAz_BYP+rjoPR^{$XOkTgU8wStT=6GEfM3H-hUs#bf&J}GyQidSP)0smFK@3 zrK6O${CCM@6j9UQfA`-0|Lt}cjXt2^AUO>F4v^L}5sc9yr#s4FbK$?$neo#gIrkqf z1BFIAXq~K6bW5pIP{I7^0#M~-=67q$E7uB-{V7x*Oi9N6E#fv#8RwRa)leIYtdtE> z6j22J>voMCA|&zHH6tF#Iz&pfpa7dO?SeiWc|gL{^jiipu_63p!!rLKLuYj(ofuaa z%>V-@1#{A|B#D>fT9dIbgBWT3vRg!QB$(OnkVSI5jK>YbxK{*eDJ+|T{fYPEfnoW- zStpmAkQ3m0=Q(3C(<{P%{>pYx5}gz(*efAOgndu%LM~4)@83w8j0;F>dx{*o(NL&8Im?F8`;-W-N5&!Gq2eNp=DCn2Y9BtFWwHJXmNpT1G>jRS>WC3r&{Z&Q z4%n!H;-jx4nEQRDEp>t(~<^!O>ns8Q1a`F;cUIdtxsew#_Mnm)} zY9A;NDvkyd2}Fvu={Nirgy(xbr4fSC7)5LT!$Jk$O9SnD#fX5OhzknD`tTmLCz!;Cq(p zfTwBTz!%1y+N5LYVC+uamy=jqF_avPZ?=YP#Z&pxW_*4SJxM~D+wH)e2zxfbYH5KH zIk2;Bup(5+Q|d(lvUupPEE1pDf6;zk(OJ45^%B4GNKw>mn_lDX?{O7`Sug0Tc(6Et zf{gBc6WeXdT92?A(kcAR)gmcca6u#kzK2wZ&@X{R?9Taqgz7n8nx@R3&szA4yHf8?Vo#oo z8HDNI&ZSqhNMAbtb=_o)75kH5@&BeO*h>|M;U}My^LdQ{7Tle$;-QU#If0|r6t;4f z5M37RUxSN~K?*gtJvJ;i4ecGtFfuT>dluTgc_jAQa2*jjFQ^?&R?57}Os{i8Q-3|e zQ}Q?1>mM{|glLfPzLe)wR_P}%{NSdd10{Zw)YsJGt}3D`COwXh5@2L)wTr4`ShMBk z{^czy`#3aoRao zLnBLPF_mbM*nh>2Y+66W4(^|IUOic4%K#Fd2;BUn%S$WD9}EGs-_Z}dL-;+fr+esG zn{qP$-R06`=CY92`QXB-b-#)F6GMz54^Z<0R&<{tF=sV-Q(!)&hQMxjT=nsI%x#MO zSK(EG=)_SPdJHK_!K;7MLH5&_`xf16634T;FFRKfbBUxJ8pMbYZBxItVB@y(yEQm@1UAj9tA0+a-6=gUEM>3~P+X3Ac z;U0hq8Y8hoFt6?>Y=pCvi2#T3$N>WEv)T+L{x4C=B$W_xbonq7!A!pqIDmYzuGe*< zbg;84uc%;DI8%PUP*xL`R+X04wJlI@Ts(9UQiw+~&{#f6U}=yHJ>gx7g(h3D6kz7Q zXL(JD{hi%;RB*fP+CoQH*w9s4T9q)#qNJX42+C4lU7cNj)i1a4s_G4V=!yCGPUd9m zcwZU8#SM|C#YpF|m2aeWeyvylx((@7G;#<^Xh0l*_w(lwIbL$zL6w8q(VYa7Duele zPEwJqX5g7AcZ-0Cze%bQwR9qbLgS*SfPl84;mYsdXtgCXHlWb;rWu=&u`#xS@_K1$ zX($BfORcZ3XAZBMy*^r2gMg}MUnm|VD2x4GS$VOVKBXICHaarG!O6MhDMlVeE$T%W zO-xAol3MS^x?*`@0X-%yD@!>(aC7co>f=SsB`YJ|r(kHyg?1}C2_SkqU%%qUsSEf( zCuHiv64otQN{T9JjZKP|mRX6{@uf-aX;4E-@=g61`gZR@w3MIJCdmQ(WThIhj(qsO zcxd?Jivf%4?qtE`KsUtPwI=Uea1BCo$dE{4a({xmypKVJWV17XIuZ;DfVgp_i5 z6OIB)%ggPq`?Cp5%2!ucVox{g>_efbFy~R-vU;Vdi`GAnM_pZA@c)+A=OnPJWaJ91 zA3uy9Fa7YP>CAfC&B|Oa>uv*=x1``+D1kw<2Lo7 zJF^vfEB6A?=OQUk>=yy6>0!T6iW6TkS4>zTfp07&LsxSJxBZ8`u9w|uM7=Ihd{0oe zZ|S)I;KG?6pbgb+nvBtF#ZKXg4x#qKQr-}sGBKo{B%sVad>qQ$N&?0w&GI1lRKyHP zsY(b0JCH%~%%51RBq(_^A@|Cyr;Z!y3$gKoPn}7l{CbBrJ{G&il;!=|<&fOk#)$l{ z9S13aCZsQb&;e34!d@%ByR#v#FnLtfWQ$~rmHXyqK{|5m5TNZ^!te6_5$Ej#H=kWl znsMuLrSwcs2u?s?Jk+K_uOc}WT%Zma85u#NZD?$ivWBu;9Hg{?5YT1p z?R`IyCnqt?LxKv2D!Wi%4Ot?G0RgW~g?jLPGOVTWO zdxo=4^5Mb3g;#raLLyXm-@cKe|8#P4QqQ4%#_o-9Ms(tgMyA1!(15fU2*JwB@2p; zCB^~_I|&}peqAo!r<4^$fEX>TiuvC_@n>Zvjm_8Eqg@594-p(Il0Jhv)hJxhOf9{u z7vyo$Q=spNpJLhC#W)*So0=owR7u_{p_CYB%hOOfloa#D+R8W;4ww+dyL~0b_hB7J z>;^n`j)FtI)a+a|WAmCkN;VHqMwL*8f`US#SVNHngd2CgA}A-##>UnqPk|j0(3Sn? z*!S^r&iC5gx3Rey&Dhp<|LO7mxcz!%xz*j$@I?5y&6$%6=X?@gbO223W)~WbcO^rl zs$>ShID)YqA3MHU;jA1SKxtLPJMjSRMn3pNVzDuJ|15;Nps^!J;lJUEP)amAuv5St zwB)chhi7z?t*x!W+KZJ&-HKXv8nMqFlbIT6Qm9_2bO#PkTMp&*zNaL<6ZVZDDGmG%6vEy3$~oF(RSw-!Qkbo}2$`cmQR&z{H< z&~U#2$F|#zgtzzK-_qy)`IkV3l#c0N7a+S-VZ-9(hxE zG%+JsUsO{KhPCRX$m&mPBMkPvd7zTaFg2c9YFyZP(GTS$ zX?T_lHZe?GRjgk;oSD%8=BkW*A8t;M{(V)}zp1m-2t+W_)=k~Mt$Nz4g0SQ~L^&aJ#4YkBE8J8OG=y46l z_oj#D=_Ka)CgzXN^>Q^2>4)tLavm-;_%TWCP_B4wYn>Gc#YZf&LcZbA-8pcx@5hCCwoVR_5t0f4wx3=kNtYAqc5Sc;245h287JF zUZladeSF_WPR{$HD4ZxsWNNCbtDBnSrT+!SptXG(C+xTsCr_ZKk!7?6~xR^5Qu~%f+UhD zZ3AG^)nnMndLho+Gq&II(fT`o*)Sdx`0VXZxU|^IJv_t^o~v1=LD=iwah|ccxjE%7 z7Gb=wyo`+7?-b9V5Z`t=3&&Z-6i!i}J3fVYI2y4JVPj(l;=a9`i0PJ+WSf7yzg`#k z0>{}NFIkq&C<^{Fk$zRC$Yy4E#T`A~=%lu-1}bvZoqQR$Nctu`t(5^8J>vFi>?H;D z(d7>ecEoYk2`DSb4~nWRjWvVv0!cdyaf5~EBmhbtGWjb<#-ymf7URsNbPjp!UupHj zCD0?h?}SWlu=T5aSyY}s}cfxrM89k!uC2DoXw?j8p{{y zluoMf<4@TY|A|^!;K(gVXl3A6w3rjM+tdP~{0{hBZ3rEUM}VesB|s@5*qVoDd7>mJXlMJjKYOi-SPO|u$BWt~Ay zWb14kKuj|iJj)GD=si?D7r$7T8o(8DU+?qcEk7)&g7FBTk)C$A3@%?Pp zblL{7-2>0+9{Y&O`#0nMdny`{EY5&UplLEBsjBI9QJ5f1dTk%59_B_;+M#W=J`dUJcOIi5-)srfhT*$YndkP)+Yh+DkN z545F#hm06Fv+ZT^JL3{>hiP-Y)|@EG!BvpX*?sbi`K1qrSL;)xP%#gK?@j!JbMJh` zcQ%+hJiP!Qp1vlQT&`voJ)4`J!V1ByyqSB}*y{4Ui!~d`OR&RRWyP6Uy>osXXJo{dF9{VtJed2!%3V<`WC`O`#$`bVTc99~j1Tg>IS=K#$%?~wU7HFaCkGK;)>G( z*{WD~3XZmmjNW1sfAegwrjC<#nclZMA5;vj;lU}^D^I^n_v1%08X`C0^-&FS8FQwxVXk0i zx3@n5HQsiwdN>HK)bR#Pmi5+pIB>Te9Gnhj5b(LEYllaL`cZ*1<*63yYSj=@6}^C9 z7>IndmlXjpqGF4Nz2q*BnmpQ;4~fNZmSc?#6pp7aQt~6zer(aFy1J6F%xal2_}|f# zA)0bc#`UC?*4R(a%JSXn>H&EYP5if~0YN4mJG{)XBDIkd{(lSE!sw!MPJ$9XiX%L$ z0^+~xk|C4;>~f%_$fv(ld!ba91uV{IzXl<~oP+{Mk{CTE%&h3fC{5^m`J}J=Xf$T$ zT81IUp@J7$cZEfI!q({6F~+1@p9Ldg(Ge>wzi?_$U5vR7!>(6!DX^&<9{!U25SWtT z{R1y+Qmv0Jy_^%(2$a##tq?1I8HCABf)Uh_l5*4Sj9zr;H!w!=A8dJ~cM(9eq)Wd$ z_z#+cH=g|L5wqgkRnC(k%`6k z(2R5|8roPoR#1Ct;x)q8ayOCyO0ToZ58@cz1t1@Nk6^1m_Ej(o=t1C z<6to??!gIt>1bP0&Igr36z4r6Ljf|m1G5f9J%?CO!Q}jIAgfE>(4H=dd9?lt6H$IAaVS)-Mw8&{7R9MO z2ns#a<{2nZi}Bw5@JU&in6@893wTejpddO4WQalWYl4!Od0NNA0`?gilIr@L&f^ut;ULv{Gxk0~?S`Zwv%h`Xk&>@6~*QIeb z>0@DS`@J-e{5yX=T)r#!{u^e|pLraQkMup<-{Y<6T$_80e0D1_sYovgnF3 z#eC3L;gvmHM@xk65z1&#tsxHvdrxDHQQtaq?6o*i6#g&0Nb#JT5h~li;r617~({^U&1d z&N?J)=jL~xRnT&w;_SONo;<3gAUM|^`$_8T=vdv>_W5#eMzgFS5faZJohh{K{{@}4 zV0J-d?E3n;5w1+^NR8{MP0Ml0s;YC`Rl-kDYex5WmM`{d)$?6d83%haC!A-j2q@WX z3n`fs#Wfb#)lt5b&{ypIq2HCaU&9nCR_qsi9{Pbj%3fyPTO?T@l-slNz|zWQ?h;i$ zXa2&i5u_}@Z0r|9!2)bFwg2HtQG9nsU-$vAj_T_C797UojfacD6>OqZgs*Vv=1Pa| zMuKNu(SGfjsb`x6wa^(I8w>eRzS!u1=y9>5>RKlkLmd==)T>Dt1T7`kKZMt5T?oi^t)+Rs>CZ7F!>0aMt2t3}adHMH=-Ni{zypO{(JZpQ z!O)j|D4vAdQ03o{19>8RC=0`aKTm%}e;3>=o?wJ_({F#hKU9D_KuZoL#6<|pdgS-L z%o|NC+hXc3p|{cd`SSujjs0zlSdFQV&uQK<)zXMu;}6dM3Ij%NB#2dL2NO`ahMl#+ zqYcLbXY`~8^sQuEx}D5wMi+Ml7OAmWXR6!1nKD3AQX+?UE6KEK}rFJ`;~w1;X(Yg{8JE~x-O%SJCfgaa8*mgCg7Oold=izcvj&rqXB zH77b%Yj;$29Rn~{v;~$0?kWjz<$~s$x|vn9*&Dg%zn$t&DyPx-jD2x=U-iXC>j(2b znL*C(pWe~e>8wf*>ZWV(s`s6L5mBI)fpt)=aWQXZqLY_wAnwXNWCmH4v0z$P>*eh9 za7;BFK8&Z2v?qSwznj1>Rq724YqhAesMBnf2b_Kp$fbV9RY458oouR1ncB$Uechjn z2J9-OiM)jWXi)D)>YJdpEN`grH)t;^}_H#z*R zaxMD=91uF7@I10S1KgH*TMO6KWpfg9(YmHe^_guys>pQRq5JRlj^Y#Qk&+R1xA=P! zV^h0mGalzBnhd_iL!Jq8$i9U`!d1%(p->+sjgt?)2HF{#L{W*&K=K)IcJ2Hb3lRJ% zIbRQu%Rk^%vB_5oNsGyn`L!&tOLyep{c>_7L23&*XBMSPRDR!sh9-_0$-cnEH9jFM zB$LLq{Y_Cwanq*C4o4KWcJThv?EiWJ%tI^}42=8Xm7>|S@D7^=fqro;65czmZGD|& z2~1J0LpR}}S{p1g`9fUDK>85uN3XX!2F64(c&zcmGJ)-t{6XvWz26ZB5z?-a8P)u?sFl583Z+U%;~NI{O9jp z+D|FOU>)f;Y1tYi2?UImed##y{OUmRZ~aE?U1n~3A0E&*X-{cAne-w>@v{L`tXL9o zCthHGlmrWVfnJSJ?D+Z{Hl{e{{6U;w-j=j<2<7K0lT)g{xWGvH;tZ78WkTx%xkM%^ z)IaKYmP3{U_SZGPk1%2xyA~}m*+>A6r(ZkpR$jl*>7x%I4VK^#%-t(5#jH?)V!pq~ zIna(e^)&QPFHM%!lw|!0oz`nD6)nR+9gL};lL>?qlCB7a$|$$R__M$z2(a87*JvM4 z7gL!X8VZR;qztX*m0n1Y6aoo^P7Z1EVQ)d|hUI&q!Eq5?;iVlrGLzm+0Y3^h=VjCo zEP0MDRpg`$-t^xG+pG^(R^08!$jMU{A&LytMhUEhX4NqDa94>YrIj$KTJ52mmZ1w^ zO&008-n31htM;%+e&nfh)Ue@l`8^krDdFLyHisPaZ*&;N@X>kaEx+J)bjrm7HS9CM zIIFP$<@Sp}(hbUS0CwQimeA{rMwuUCXRVA>B26wQv%76RFlYq?9`WIG8ocmawoV=i*qbY7dH(cTfhK7#N@|^3@^3z680)L`Yp-@V z_a1WSiG^6(Oj)5QK6KH3#$-&ImcX|RHK@w3<95oF^mVx;NG&0{Y zi{ofZo6pM13XL%vDV~%8%)p+XNZ6GSf-k8kjb3sVcae#!us|h)6^44!Ef9Y%D~kZL z%UoCpGIp0pnPcZRlxA7;J$ak|yy!brbu7@hv7}aX$0R2|ZU1(l7VD_oGL=6b(vP&P z#-Cf*fWlK(U#~$J#IyBJ6LoWQ-rhvj zoOoTWGnJE_gZMpohADmJhDYZi09OHK3u`*#Kr3_jUjb~rcZZ5#{{M!+BbWMnGEvkcdG2!8 zsnu6k4BB?8nmghAc!vEs_E< z%Y*0!SC<*T_gk9aoMFV1bL>OmgoV&ccBf(W!{u5RkMCkTEo6uZn^CU)7~*VUve=_N z0@}wVTc3h(V&tI=K5EVO>YRIR72$>Kgd#|~Jb|5S=pS?Bi}Katb$CrQ zJ`6R_{tmVlNqxOllh5Ae;7GFOT`76%kJ|GZ;*sjj9k01fX*f?1J(KUn2CG zNym13lPjAg2D*uasS|~(Q>IsZ{h9T%&~{wxQy0g!X5{V2?A2i56anpP6`Sm7_eApI z-*VoV2RgA@Fxw-_!Z|>2Yth>km4Ax-+DN6)68SS9%b3 zQanhC2=5b*z=Uj6voB2dGhd9+V}aI%gt>|51zR9-~CBd{&6bNhh7+C2X;&w;oG`-C2M@(KEgODkYyEU9f>sG zl#}l`ir(mlDm8N7HfW-QcV6=y^8RXO&b_Z< zJ&HZ#4EA)k;v;vW)I$E*GFt+Pnq3&z)QCA2%3vQ_sE2f4UA?iHswxZisc>a%?(QlZ zDh`kA!fExsKGHJsxrAm3IV(Bxi}HS0&)2*Q@AsgbAyh`^ixbO;6Z2|{#1nu2x zo;**9Nl%xWor6YShr-a1Okani(ttNbYxto}8NVujVo=tr@%QjLa~6YyB1rX{v>W8It%LkY@IXkNo%V_mMs_>3yD)- zZ>SQGrOcZlrZ(l8;!)v~4V>&L9S|Dmj%Fa=`d!L))Sv1yu0_$#v~OUj!bXD644ifB zQnE1GZ2fkRyd{H~RrTp6kEj>GMeaB7Y%HT%*VuTy;(d%B|#%F zNlJ6%AuLy(#Uc`o7Ej{Kj3Rt{vU`q}n!mTTQ3hl1kib2CRlJrsVgk0v6~5*ljSG>= z5xA@6O20sw?q2l;Bn@>ezQ{H^L`Mbf=d8=4JVPQ~wZwta#aZOUROj(e$KnT6s9|yA zK>?S&VF^AqKOdWBNUIo7y&~FDI@cGQmZsL&3!sjp!c2ZFYnNP*_cJ^?t~|rGV@pfv z*H3qs`zf3TUS}IjDpVBR++YmYD<=Nq$iqgNK}Kos3g>Q~Bwn2j|DB zvqi`2rtX3CKD;W7srtr*vl>eEVs3J(!=*MIw*`&kfMjMWbxH|zp*Ld8E>56Wgm`(} zoJG84&X<0dJ+kXHJim<{?<^Ym7dW=tn9M5b3(gGRuk6n-F@m1SWvIDFf9tM&0vNte zv(Ax`ZN1N?PSGH`XFb%YU=}g^c$)ZK{dbWQ+*-8qr^(3-9t(MNod0Z2 ztAT}_lv)Ol^cY}e1x5}9EaBxRJ%^m%`OLCqK|w(~XM@Gx#fOG0S|b<=7_c&oB+#OK zgReYQHil07l;revWhoUwEHK5CT6iloNGs38>bJHYlh;~J`k^4qdH0HopbO7p4g#*Sm z|A@MHaW+~s@~A*y5WfH!92y9_Do`l_qk{OzO*iA`5A)msVB~|_y6n}ARz#F6rOf4d zCFwbv&g?v2)+3j>CaizQA&@ubw?V$9a?`J5u0-9F6~rKCg987QIb_{YDrMzOLNqvp zpe`_9jA{*G?w=E!V#y+E;9ypmtyx-B;Hjz-!VzVT=F0c}u(5UdNYTS|xDg$W!O3co zUmFSxJdCY<;?t4+M^v26k`? zs1(GNS^Z6y9+4*w7B7yX0fWJ?*Y{p&guJyJp$E5gUA zo13-2D`a^lr9b1X#=nG3b`byrtXih!-EH#ZreBl_6*d%A6Xa0W@RqUdm&7duIJmA8 z(P#R=&7}bqBX{UO?juoCB_#((ZYbSF2NDMVB%a)gB*bzqg*HJ9Cf)H#<(F zP`x-L>fVV_mVXGgEa_(9E>YLyG0+f@K^{&1*3))ZJ$IRA9QaH6MQ3MS3Dx>|4BFn_ z;8*m3e$+iX*5MAEVVk|d{2 zjc=a?RO^Lm2P>F|&Mtc6xfGFKZNGrWh~GPNiBB3o5UfI*oZr-3-dx20PST+dyqhXz z)6*NOG_3f-k@pkFuf#f1cQKCEMjM53HBJDg-=iQ8sx?t~lg?G{yrRQJ5;007Oxp5! zMO_Z0|@Z8~R1ydFV`}}^wdD(=L`*TF@mmur`nB9+7tq!%14B)u^ z7^~|aH(5Tk>Qh)yL5Q>g4Ai-h|FZSNFgXbvVe0dy1kV(7tTVV7@ap5{iAI~h_fIL~ zQI?O38DTx6EwF{tO(Pi*q9Y9vmrXm92EW?c#{-Hi@{uGI0+Be@3`jvpe1WKHFnn71H{U8J zq~8!e=F~Alq%3IZvX{lj03LEIzWC)c+iZM8_k;jtZ&SUQkQ5LC=?IlQ3xI+77)5RW z@Z%)xxh31m-SpF@U?M9p%;qdZh2Dgs)6gY)iFw}Q>^1aRgYL86YGtXt_AzzY5qbn! z8GD$Dw)wBi1-LyI!K|h5+70K~>kOM49g<<;^>;YL=xb;*+Z4PNva?{+o>F1xT6n0B z$m+HOSdspG6+={qR4187+ZMp(gCt2SvxX+ED-KHg?89^AabCpypcjvn#3tU?|k)*zxbo=d^(yMb-$)g33 ze*XY9AqEP@tyTx4s`c>35`5%K8Ia|}v=JDQ)P4WxI55&-p)&oHN0mPg3?y8@1COiF zb4@gO7sj!~Xk#jdSXGy4g72k%(!+hD;uJfV#+VCD%g+chHQ?u`1}|a#PC2axcTRUb zd-k^4c1FOvHDg&Y{0f=7(p$F^aa>r+=Jlfs<~(__aKcMLv)S&koe777Q6JRo<);nC zwgxzxctz>3CUoSAysf}O^mCl|t4$9M+!cU34YAWesUkmQbJDzSF*H?s>-BN(j!Z*D~S>RfdN=c z2g}DyN-0>$K(J|5yuf21X0!=AFE!_CVv-uT8Lql|d}(QEhWujF9}3LA8QHm-x>bC0 zMcs)mhUf^(TKY_B;&I;jhr2V@p4`_=LR3e^CPH)N%qWt}5H-6dxPa~Z6UIZ~t?!rE zWu#aOnz}`b!#Ax)nCC*cgPuPg;SdvH^kC}l&Tm&v2&F1WbRPA7ONt3FDBw@WLs?A5RKouIrU|b!cOx;bJ4ooz5UWz?%Iu(ark-}o2S$s9AW~~s=r(p zQx{(VvYq&pl(IKx0RJ6lzdX$|jsZfanK6COT=!*u7>oUs2~rAAhFxsa^BWol5+D>j z{st(fd+}0@<*x-_N`E885KLtdaANn0dlZ_ql9nQ}E=a;u#pT#_rm)40I;U^DhO(fF zvn56|1Uf;p*RXyHxJpLKnlQ%#<2JPK1F#Wcy)qYGdKse?%LatK%J+}Y^~*1fO_WU# zdwhugh)v?FBIuSg*@%KxpwAv`(IiQCOKlqM?7#~f>K)1i{TDlky{;kq_PaSYhy%6t z?0UA1{4i`iBe;&hGW3a$+_iPt=)T@40c!v8hNLp z05c)+KcBt$zOhyo$^R6m{Ni-oiY{9s$r3PKe3i2tWXf!z-N#&(oGQ=BqDqXMoZ?pl3Ko!U6&Xx*1CV(6YHF7Jgy+W+H zu9|o_e8s-S*NG|*lPR$8cdB2kxKRZCwC2pX*EiHaNQp6*i@emlymv_J$C(laBzNqR zMN#2y_3eRMOSmD3VW50wX6CNXE06^y5Y5le4;N>;yCqwfu@Nv5bWJw36j-MCJ~l44 zwzg_j85-#7-aVX;H8wOv@0Z#jn7InQORr$ls(jdfe#rV~LR2zfvaP~EDXWa|+f6&r z{Xjgd?SSmYbp2H7C#J5>J08M+*SQW6zFb>QcW3=`%QdP$21}e&xPByB)uyvT;THE3 z__APs{PR>6ZnQ6~rzP5ro0$tzqDVx9CC*q%CBFIOpL`-t8h_ZHvOW_*%4NoYTEQS8 z8+L-eDKXEvUr|OYEQVU;Mv*r`a(Gqo;rs5=w#;dEGP^_m{M{@2il*hEQN&*#PmP5$ zaOlUPU(_rJa7K|8-ouqo>!sd$k%GpTKS?bIqO)rC=6^@OS6)er=tyU~$%{2H^raU2 ztc^S}#};t;;-M5Kz|YTAaNr_z=(ec)&EjkQoA*=PD|iY1W&*W|ucFNWxFN62>vHc@ zN8HZc0N#)?0BUV@+<1j^8xa!lvu-cVWK)n~Rhqp~pw+ciK5HPxx(yh^*?!2|A6PS( zOGQqJPNB5{@lu$t0>cOeyJtBHUmC<>F7{yufiZub$tk+wSNQQ zpM-iK-~}=< z{F9P6TA~I|oq+MorQw-LYS_(a${O62OLgiq+}&+GM^j+_3IEKIoF0TQn{z>zVF!L! zr+lcO0Aj(_K~zN-w?Zxnbm|u5+4ML(&U;h59bxa@d%xn?q)lP;s9jPapoy~g{f+uT z!(R^z{7=N#4MhFV?aM3S>-Fs3DnoD8O68}zQ=@r?#8E>1YK#Pqy}WJEcD^kdeO-Ku zj0s&OAD41a-q_vx`(!%oS&DhCDx-19{Z5T8VqSIolh=0sxbB{R^TIc-crF2{&+VHjz7g zeck%WY02H5L%{ISDLDA6I}HNT#fZZrrq8Nz?KPb~d8949iVJ@gI?j{k z$9R?TL72Yc@c^iu(~5pPxM^KEe?tzhLYyZm!=k#WsmCU@>(?TSybX{%N-u|$#RB4k zDwkL2@DaexUu2~=(OL|c&qU~xL9G?PV9qVv&@RpcnA5d@AoSNR@fE_ zo!^-%<-RJsBnFJ>qu(0v2%oPT-W5Pi0ASR|+KsC*{6g&lG{ySY6D8YW#TOI!m`#v} zL&*mtwT|o+yNa-5LhOWhSPXp(%hgzKw3B)@7)P}V`fLKbK!K{%R4h#eV4eYP$9G*7Aqz_Jm~uRz2Nj&4)4zxIgpZN7)T6AoEcj z4?hRvfWaAqTes)_G}YD?M@D%-ExD$VnkSBF0PfcUz}rFe+Bh8CZruQCHajwiIvh+@ z7sC1qMd!FMg>ECw#wsedgdQo;|2p;O9;t0qy|%CvjQ?~(SF9kU*j zkC%aQMR(%!>e-sw&*2No@~(~?E8YTJvZo9-5~=iQ2QF(efnRAf5~5_8&~!YMfiS0a zFG9Iy=gGuU_9O}giOI!Phadw65Yl0+_V6aki-iFX2D*LK!DQT%-u&iwgEa?b>RLDQ z=yz3EF40(VB1s1l$z(G;a-ZnAyZxqoP$Ij_raMJ|%}Sws9;nBD>?SvCaCuT`+Q1JH z8zy6nS7`Z$#-4Mbw`t=ISFmSAF~5U`Yfmf>9-+ogo)(0qKvHdP8ZisQt(jA(yoK|{ zA=AeLdcCg~ktnyX-yR)7agy|004v`KpUbzmj}+oBM1uEv?6Q}LaEmS3Fu?xm^kl~d zYI$s(4p%ch1vQD^c(}dI=!`OHeASamY5`mvoQ20j0sqL=#80e)F1#*NG17#ZVtpMh z2nYq8^1#B^X^MSSR>It%>PViz*CFq?k8@t}Y5pCdO0uCC6yj5T@$FZ`Ik#ILML*W$4ByUu5~!&a~xJ$Z)r19)B}pqq&@<#PT2 zJdXFtE{JAz&4wKXE>>_tdKeVoZyOnN!(SI!e17ZgK+MqZlzG_kRVQgi(RD1k3zHix zj{EavCyRawxB&esuG0^AWgrkaimXdBK~y`_-_twXBwvcTC1@?!vAU$X76lRpt(c(~p^% zk*`~e$Jd+p@0C`*+#l}7EjE1Qr8r0EVdtmUbY14V$%$b@#jO)+A^$G1_kiTE@+Wco z&EPqOU$vPjof2WhHAR&o0(ZMU<%#y3XJHj4e-%_DeTdm{yFM^QJ72-5i7ZOoS_Q23 z)g^vF`YrdIjFw>&XFea^<@sPHo>NlrCw&?G$&LV^#V};MHd0vxCn4cbc!5Y(GFyG< z5%M;37?(d^-0}Z<0e)GaR;|KKO&lijuWkGR<}&}>wv5o1aoHbAJ~h{Am~ALABORfx4vJ9$*!=1@x6j7^C; zIR%CArw#d@&(?M20_A%xUr(fH2&lSkiH!SRL|-#GG*9e`LRqL474j{CY3!}D)Tr+F+zL^u6kx;44qX-SdB9ZB)gWNC}P32>V25IMQ53Fy2I6eu3^79*gp zQHdpjt=aN9?zsu4K^Q7@Vq;8^f3jH=c@(0g313%|5!BHHsZCQnBVWA9l zf~~Kp-+OExzMGpQp}G|>RtMtfaYRnUZQx3YtkTy}FEz{j#6sB=7J)QSbm0MNr&Bs} zxX^wuq~zU80vU{L6KzcdcszeT39PCt&r~Xu$r7g?8G2>{@B=jR)$uc)Y20lANI4H~ zawigy%%Y}A70qK_nn2aP@0TX8*P5K)5PH%gRP(Jlb_^7;jwpmy_?3RL@rs?c3mW9A{y!x)#QFEW%Kjgkt~x5KFWBCX?v_RY zkp}4ok?xXi>5}e{4+WI&PAR3OB_stz8U&=fQ&RdJe(yb&f4N+8?zwX(_Uzd+5%J#N zkV#k?hPpBPI=ru-rBTHF&8p?v+$Hwz?x)k%Im#C#7$I?SlUvdIvkizN z`hMA)0z;rX&Yh-Ik~79$F?3K`yJYhtdD=F;UFma*&o{jRn;Q;ptZOR&?PM>a(k4f3 z-`(#)SVa?l|E_+S=@7&SrzV)rQ;dUP-~RTk zd<_>UDsswhFN`Hpr#B%vG9=L#9u)s32FZnS1Se8k{7p*g-zrO~rv9NuAZ+YfRcBw! zE6Ev4E!p`|8y%l5Nm^(?Xnw(bE72rC9M*9K-6P-UJu)Wlf6iE^KUiS#i7ExT{o+=M zzQ$>>6`O(&3kN69h+m0~o%^PDE>S~6VO8LOvL-c|BudOYvQS@{DQO6~x=iHZi%;`K zTlN*;rISIO7{Q^nL@E{~jEllShj9?UaliRgpTJfpMMxbRtHcd?$@n`6KC7(4StjUZ zOfn6Rbo;=8z^KhoO`;-~-FLQ`?=V`aV@qHZ3AHQxRV0S)s_^Cp>AzxBl1`JTZys5v z87*%V$8ct%MNj!6_l}`TVM+XDw|ZF#zK5Z>0v$Rzwhgv~sg)yZrhdR?yk`nt*PvBf zA~M9zOr_QBo?mkzVYS00xf}fQ9}fLYvoJBT9NTo6{N&&9L=C}q{5|X+_@mcNZ%(Rp z9qIEJe_7SYFcdz;AD607xwOP$>q)Kprcsy_TAcm?lVl`j{Wl%06`wnhJ{Yj zFT=_rSw@;ULnDwKXOIA{NKs_aPrFK~k6U4%FooU`Sk8D-ra%Jw&Ut=pp;>omWE8J)%2+ItF5 z3nB~ro&8(ZuB}vt@E3ct+Sm0ASV(@h_UDz-8^NdODv`%qO^$_2%%f0#SvntRTf0uM zybLz{Ghn5gj7MG?sl?+Zt`8$Dz8OgzON%$daS=5M@d;IsoTNSS{Z6)~HF_xF(6ow9 zZP9;ApurH1b^?1=h$CqhicpxN7yR$?M!+rtmv@KAfOfF!OBD-pV+ji6V(@5i|LbQ> zD?LqzpUDimsF{t#sU0HqyiV2Ts+%%snsAhxSFKNGY4f{X$4!Zn;__&j3M&s!tW2Ije zR^z{s?c42`Y6dspcu+lRM?}8HqqUCL3-={Qh3C0(Uz*??(A2eEa!%wyU8uLOy9B9WcaWc15%J$h zq)6l~X+ZR|m~nJaEL~*Pw3sinKc|_^zWF#KzsbT@D)Wzk==Wkt2alG*`-v%5N+j=8 z>Ca1fnjG5Cq)uNCxgx*HL!Qa66i(+P{X>iW8Vo2Q1h*6Y!@AfNGjX6S=r+5Q?)i-u z<-L>H{*!c<62qcCYDYrYDvw*gvo_EJgZIzc$4CEnB?1>AHntcQf~YC6Z>l_)&x+YO z?h#lbf08eukK!u1h;3jj*SjezZ+u523jSDKo)jr88^Z8Ih)2~g(u35Z;HgFg^q!D# zU8|HH6%}^+WhPdVn=F{~+j}i?Bb;NN?axtguk}bg*H1w*SlB;kncOX#zvz9@$cFwk9+Gf^j!foiYAGV9?J4bhNGM{@GCWh_vGYc+^8nLxa)W*c9yn7j7Vz4; zUCite>qU9o?-%ws$C!J`@QnRxCQu*<_a6^)7b+?yzxtKfu@bij!t+ zp^$u+6~pt0V3B7`#3_@UCe(KP#F<#hTO9g5hU3H}%0$>s*!hBHseiv+O*@D2Ydl@S z{+%276l=nW~4YKQ#rG;d-_AugopU{CM!49yU7EX8#EXjFsi1KGiFBH3dBz7yLj&e z#5V^0Ba;RqE3Niy;5z8(qk`owNN*EM*xi&Udn@>`WA^(BECp;j@}}u8BXg$oFGZ!|N2Uc>zgj)Dvs)7(bDf5lu}I;+ z61HG{W?NrPYbS1UwHEP({gubrE$5JZhbDCaqjmu<{l_&MHV-CyLY4s&z7DR&>ui!+puFKE>f`p(HFnS0v%2hQ7%(Oy!KB<^&0@{)rR2~%e`Eh(}br6}cJQJfVzJoy<(rxHOKGkwRGHBH5o z-=fl(N?Jy=5V87xL#=XNRV&?RS({?<6>=hR(Y`!w{BpSj4y<@L!qJU0b-e0#h!Uhh ztBsCmF)!7VU1||HT@`+6bE;>Eu}SQpFKb#;o?3k3QP{_~K#q3(DEFT49S6}C0$t)S zd}@_yg^fJdrxjy)=SJq6NoFaP_2GS(Om*j5zGFy#}^nSr`{>xW`jE_6IG2%Slsb z<~oT^-p*2w=d)Feo|1}3?+#-w?{p3P2JsD;NK#$=g5yb)P_*XGdr@k) z)bZP43IqZrxv3RZU&j(>Z0X>hgxHZveO36V{?X+#o5d7DLlJY3*+ie7^;baMNdO959PCl4X8V_)@$f;!9Nh0@v^Mrwg<8HQ!j1 zlO&sbN97o65uXZKCMR;S(HHSb+orNl#Bb{Z*F|X>yp4~ zSl7Y+c0;h)HtOj-HhC13yk=&5sHM_d6;1JD5P`@wZ*}dva@{97lYS4y=c|(_m@Q<| zlLj^MZ+_Yt$1HMI?wnwgp)+YQ0NPcGqi zOQ~zt<^WGDAP7Ms zw@pvg)d%4d{Q#eMvOd>63&stY0@Ym!`^j~A!2dH72n+}GYkPT zfoKWdcLY^T0z-7VNvKP2wmLEhjq`Fn3V3;xSLkSwzVMIQd{be4#3iCqlA?t&z{cHv z5wIAzkZF8Cn)AZruf8N{B?)(;hU%3eO5P~39m1C&dwUl>R+iWy{|}nB9(*33%A3Xn z(DN%+1o%XaZQoR#)b{*Uh!08YPkt1lWz>L_8B-`am!fNVZBbs4_Bj=ih+tydH4Pj2 zn-F`+1{NhG4Ygb5hE2Nu$krWjR#7WQl#!H=!a{~V>mlLgBQT(bQoEes*u+~Tq{D0}5x_C3yqnJ?=+& zf@3a}HD5WYI&B`u(}m&Ddi0NB_dmEDgJ^gao~aZUJr#WW2Tjol946OJs-J+|Tw4~K zski%Q3y+Na&xnJeyN{@WHMO`3v&~p~bb@LK31)2n1Sg$V*Xz!gDSLSla=J$1G_*6PS<;z7e$FLOE|dHB>?DsKu5d268itn3{VUcewIS&*k9C1 z8Q32g(*he1B*v9Qg#OK3)W!JA4g`0b>3tgLS5Q9L8c#QG>h*^`4JO@BTCk+ujzUGD zi1Y0?)tV~*Nw--V;tc!zR92CY35J}8@>P)*BhRJy34}oz;yE1uF$;@&GSsK{3?Zq# zoFTTo>25$g1%*BJL+`r@H)upw6Cl44j9?o4(U(deR#vJzuo01EouOqU=_KzlG1FJ#WN$fUR#k>1#1dw!FD0a} zuCU!yu__=R?`~CCgv%Lal4V}=YIERMWl}h>A6nia9r>{6Q00loG&Xed2vXt*9L3-1 zX=SKKdexWlpt)e^)<#<=%&JQs?-gohZmbvO=fv!B*ql)L@q$pHC=Wf{ys4+auxtno zntMt2iI;99QvDR}8}L>A`2>`^#wzf+*HyzcYZd_a!9hZO2{8OZh-Csk(Sdh=bCB~nAdIt*97e=z#?(6@i| znG}kR>%xQsL2hSispd?38pLV!wEiP)x190@8pMQ$Nk<9oP&!I#`KbpZQs=lF8rJ;e z0QJ~HaWPqpRZZNkAm^|}E!v|GiKY(Af01#yU$cnwmi_Ls6J5>S`h<@NKYVG&Lz|Sa zp398z(xzyZjdh`lJyeLiMrg0X($}b?dWu7T!m_Hx0Lc+*k69djjeBCq*z01G!NblQ z^_}y>jEco7BrA+;OtO6vdpBQ$WL!`r zqK~KmCy0d;e00SNw(#4I-4u={r2ol!HcM2D;>~U+<1*jxreLJS_-<@k$eh`Qb~!1Z z1GXYXm^YhK7)d>hPp{@e!24e4le&c4r5SyS!P@o!6DC!4u_PY5tOqt~2X9Q3F6$xt z>Jzdj_doyb?GwV)P4oA$yXgFvGq79c3E1B3?359ZqxPSO)Wp@h6}~5ls!eD3Eo87= zK2`Uw>fXpn(6Aj9O>Mp9j{|)>sd<3HCv)RymzK!w!e?<3wz8_+1YQHi?xg+1)weSj z8Cc>cB^__qfA(#B+mzrl*O^+?&lSOqq)B_CI4(VcMZ;Sw^J=6_5#ljh6O^iprh6UT zPswkK&ViH_106t-Sqcpg692Qn*l@@;9B?#CGb%(_ zzcHW5ug`h*eN4`G{LB(ZjwJ?#Mv6Y6YL`rh89-yM-f&F0+#%ifCuMllQryWYV?SKj zA|vA947I-q#}3Tmj0kMT=6lkV;wFu92#(6WW)KCkB&KbGye)4k4pvK3>kS$tsJ~ z`Zk-jMkZB2}>6Yl5=G1CuT`(e#rt9Aeq|i0~ zuw~sP*>>&PJ&%8kqcG2^HRrM$7OEXLmNgTBpT|r3G8vCS-BBrmT{c>nfPENm!=^`2 zuYis987a<&ut7+7bu)4P*S%==i0)%{f-(#aKK?J3uWc~jcqxuFqRxGlqWIu9seDu5 zUHvhKCP~?5iY%&DfdRoM+gd|o(8z_7yC)d$B)wtd5#y^*R{w#q{Vvfb{J}q=G|#N6 z%4sBOvIzJd!t%4ACVB?SZ;xF>H8y_yCQufz%avD7cnpb$7ONSrCgf2HLcRiKav1K7 z8UzfLwsfzLsVPHk;p*!IX@#|qo5@pc#0jU)1iUxW>#rSTb>38rkt0N#oa{G>O=x{J zP63BsezA}G9dMS zr&Tn6mT^{yGzF>4F7VuJz0!*x4pmWM*a!$jq^}}D zV4@E{z!8;Df|mRPYV_VLu5(%W)>5`3+rdA(k2&U>7=;hx{MB@YrS|=bV4v(kd$wQO zJn*4kgT%B}C$u;+AF@b88cE#K5NFu6p(AQXA%RM0Ad8y*N1h!=1V(!Or5p<^KdNK8 zElZnNlfA+~s|9kdH=mM*&{m-9AY={Jtv3N&Esw%vh&qsBKg=EuQCQBWbz27O*txU0 zf88U>H6R8hrx8~xE;UTyWxJqPuv~e;(Amdl;)-TGDVX2dcQm+~+@fvWn`BQTEl;9( z;#snMT?XyZp7G)`H3U8y*3$RFz8c|@FAy=Y3X#ZWOFs0#wsQ-QyepmJYw|?y;5tiQ z-n()Y|q&Q|a%zHr{k%K9^FjJ;K`f$!kBkH&YkENi02j(R%TH2$MS4-NU0? zug1#MlsacP!(&B09#Dmfi;LYhhqOwyW)JVRzn1K3Gpt^dE#_b#D5>INE<-f2u*~!4 zABr2gBkg2)VNj!Sy}5pi3&r7{?u%Fbj*L7f(Pc76^Oo`zA(2zLwM>F$%3|>vMrG|D z-2Ewr9TgNYGc%8nE@lb<9zX*1{BgSJaS}Nlk#qr+CI3f~Tc2OtZu7VP#m;Z4cbGo5 z4m`J3DCWSbJdUlZs;UgU-TkbZgR<0I{#>Oz>i0?IP{06q&mP|j>(_4&{q9AD4;lly z_V1owFJ5glluX!Jd!=0VkzW6Dy7xRu(&1YOyicERKD=FhVZ4Fq#6!-_%^i5t8#p&L zMH2dY)1H5rwyAg@;j2l zHxpAx!C%6-&8Ni{TE^BSTMd&MLdGIGRwS6Yep@$G(4#g*uU|&+sN|h$l9me zpEOLT_)d@;5%&jjgK+>MpJSjtr$}{Va(`yBew%-Rjzr9b|4qLAiHNf5UvQtt}Q5iKjX6-ihq$?OSzrBjN*9}-tVmDoB4{}4rDf3+l ziYrZbrYGdZ>gwz31Hx_;(J4?Y3m z7lXbkxRK#?&n_#Q4fwpBokoNw4G8ploD2IXe=ZE1)rCCH2p)sfPGem@@eFB;9#HFh z`fbz7=v=?QNMG-!;AnDS`QClJILK1javbv9|FysW&CG}TVohcsM0f8Er0yDYh}TXo z9|SF%J@@VSGEi|Sy-x=DpBuOQnVQn61b>Xn>u|a_!t(^81JCO!rH4hvCyeo?k+OY` z`|htz?w*Ni(I;@OznJn6+$=(#^q80UG_tt3Xu}h^Gt=O-_#oqE=MlZ%BiMF(J{!2( z@OD@7$<>JUi|gs9veAkC>zYaQ@&rghlUG5gkN^GBX{{cK%S()ojC5FNX*6Wd2%2LG zj+K4vV*!LF&wOtmWI@MOUx@PZCM`@XF5U~boe0N>9RDt|F=<|JVEgBcG*woB0FJn{XC5z-loP2s=zgoF_ePUAZ`pD7am?`Z>lR$M9F;pBWw2E`2OU@ z{RszF2wr`Qch{d&gMR5aU|@iU9J}!Ma@Pl7Na!@#n`z50=5ANDum$tNvLl=uip zu}|**K6wzIYzD%VwLMczEwz)^=ljaMPKE4h0X zz|4=AOb8jD!=JA{CmUg5Vf+i;<_kL0KnAjMsxUEw@6Ak;$8Me~a9w3y45Z-47&9o>vTh^smAXJT3h(yzuqFcmbufkOx3)L6c` z83hG}&vEWcqLAmFE*{bel3qOB2OO%VlOf>;xlBX$3t(GM1e}+^|B*HLnvZ*>+*~Wg z(#81fw)6C~B`boM4150B<;cam8n5G>uZueeW4|WwM^C!7F<_^AZQ^LPj<-CI%OoGY zC;qKPP=)8eEyk>l=XTYwQSbS8RZ-0O!yUffJX9Nx5-Vn#`gu_2EpMkAAIGFJs^^R0a_513CtZfhq7YCuD&E5 zmzvz#iRBD$o^+eJn3^sz1RgVF)k$;TqoziEP0^s2H?xAF)5OzV0wH4_LBYniw^x!M zaHQ3FxVWm#d!q>%R8m(r`!JitL&Ym>;-5DupqAoqnN;EkVS? zSW7SU+-Rmq{K`^+kfA7&bM50;^@`2&Ph`-i?EJiU%cheDV+e)q688+k41DVr$X>H zW)d}C;+5q{olo}Ozw_T zfH?8AkN6dN;N3~i)b1JTWA7zJlPe88B&)Qwjlm3A85!fZm+Qb+J#eltO}5w8*0_g7 z+|Ku=n-5$4K#trn?>S55HCOd!wqBu7gFS_To*suv=rrg4GAHG^Nqx~2_Jh63M_=DL z%ff~@KL4~KQpElUukYZYL=O1-FY#dTA39^9kY_Cd)Cn<;eVRqfwT|LYpym~4;vsTN z%2RkMpUXrLA}6f*<-kFa&I6-TS_bm)Hc}ikro?%-Oz}&qF23K)r`H=8>G}R_3cYI< zW2QL1I7@fp@4k?65(NIE)#nm2W+Yr78rX!4Z=$_Y{ij?5A*WaWQGcZkBNu zJ*JFalk$;AfdCHDIW~j(f33Kt_x!CcHx!GyvlVQ7uyL+BV5euhQ!z0y6y2V~q8F4x z?lxewT&Kd2bCZ8^sxN^dVDUK-hI~A5q6N>-L9kmK8ByC|YpgI}B{rIRh;J#ar-dNx zpcL_T9<9Hildmvrbp3ap?%OD9kfBWsS?wga#q6{+!M8X6 zFrT+@2nc)wlyPwK3Q%?cn=t??z%4!}MamhixBE^&*!y>MWD956PPHL+K8Mf*I*6Og z^iqnpY~h>886|Nlb07WUH_(tr!|@r}Yz-_z(0OusCHgQPqkU3?^7Y^2tt05OATweV z=AsehN2SUTJeCaoh%~^n_gu`QN|J=Fq=^sp<+9APl>bb-2PlUbdoPFZRPG+NJw}1^ zJgUPI5or!^K3=;2cXRLUeDYvcv+YcW;3~J_GwB6r=#GyjF zH1mXi(VrWu%U>+#T$-#eiQLGNdWUqV%J<9;WG13H!;5aiqNO^OZ?CpLgIA{%SEa^? zCqW*C0;iKtA1q27EBlz4o({x!-zFw21S~$xl)gCqgbU>NAAG~<_P7pbCZNwfXk3FT z#2KV@U2l+Dagg#3kFMRv&wRwP1 zi?_?=VZpQR683)HRE8Gas44|Mn$~=)IC#E)2Rw0 za7}H$bh8=5A6yS}(m~U1#YCx2O8+_tY@k?ayV@zW9?ERI^2?+xWCefidin3~YT_99 zauEMCdmUC7H3JV}p*0otS}SFJW`NMRrDv3XwwO6gdj#SdAGf=Lg7&ur9(C_;W|K|ILL%~bAtZ7}Sypw>c+PwN;T?p-m^RAkr|07L;a|T zoMVyhy-`P*8ODa^IHGQDQ)tLHel(#eE1bH(N%)e!E&k+IweEuSyJp1T{g$WZ-0IYe zt+RX22e75|6>{bQCONPb)qOgR;)N)nvU+XKm2|`}U>6b`h3K=Bgr`92_GyJUeGif|k}^Eldh`zbbDOh@?T)o0mxb7kGd| zty1keV~oO_n>7a2Oo7qM<1P*n&%Hkn70}|%;Ns2i&te{1BcEPRwAhu?Ob;9K z7TJ59$@GDGw4A-dm=WOz2I6$VZ+9q>RvSkhXW5NNgb`aN){BOT2ag_)Ad))H^{VPp zk#$oI9_Zh?=IhW=G7#ORZWHmf5R2o#oFYNU)FJ(5?)DOyg6Y)vl+5bcOz0I#O_i6w zQ=NWcVz#hXG+uoFy5SVCFnb*x5^%}KYY90JM2TdK^sC)viT|L@#6D}#%B?X|o>Eyc zXx&v%KK|gq5dtf)?m>;4&&YM+UsP0NWo1=ie4UY=?t4CM4eDjTUMesDPLfs* zUf#Ojk_CytZO^^O74x1l@_H1}4c<3mv z5V6`*lK{7&Sq1$cCzQ+G%bb-y-sr|e<>?WC0*8nw)=<2mqqtwP;8_JWdt;sej>maG z8?Z$1RhEAcIs3hFp6`V~bENfPi7sBfxx0q!)|1Q#a`8U|nSG2%ugkm&cN0N zRb}Nj;NMP^Xmy+Y1>ZGD`3z1?A+I@?URkkY{Dk@!pdRJs9@pz|r~C{OwrszH?Slg` zuYLPIv44&XaIVlgUxJaxj6jw!=1`_x}CG8&$*QAz%aU_^W!ANj+sfGq2@g~jSS zKP-e+)4q^YT_gW_f;&^9gmp<@5jjw#a9a~dRnq`lNYLxbr(3>n^B9ehA#22V zWz6#z^t}zU{q9{EYweTL-6$gLs#;DgxYDw-A14%yd}zH3JanSNhDhPD5@_m&r4hP6 zTqx;aD6_b;lMCO9#JXrT91y4BSda+Ui5&W~p+-Fq07US!G(vlei$3Wv)4_xJ``#zF zqb(^**R6t*`q-JNsUVGm4%+VT9*Rm)KVtFx(WBWXT*0v*j}SQ-;Kp2xrAB*uv-;%4 z)mHvP5e%ku|ANx_;TxaPuB@w=+I`-3bDSR|Cd9+z4qya;b*0wdN>2m)!f)|<0r>Ts zoyt2q00uqi_*YeNx>+e~gQEH=fF2%l=!8B>P$R7MB`9X~x_Uf>|0gou^TMK8Ge%W( z730Tw0XT6%n|1otD@bH{9x+9*(eW~JMDem%TPZTBM+fVMnxfB#VZYFbM$=1z@lU6S zDoA|DDRX=_$P~6e)cbEe==Fmv|NQ=9pH2m$6!51`GP_o-lhW863b}HSbVSsKwKJf+ z;N;|77KrZq;c9dNCM?^26;1}lu*Djp4EY2Gw&{hD^;Y4Txw?)a1q3W1J`n(g+TT*( z6wO*HKq8ARK4Y>NHrb?I8URw*`|CCU30)PM_#Snje*XNqaz*6!6d0kHrw{dvK?TEPk8{A;p4gh-~@lzg=@QE_D?G->A%RZR9%k!bgY&c8sCY8V1dZ zuB$HvPgiJl#3t_q{Y7VX0eDnZX#STCppZ{OBs$u5ydIaIwG4q7&bPPbZI1OXZu?Z9 zUwr{)_X4E&(7W66p7+0*DRjAGr(q6!{5IJXuSXg2vovNzieTYV8P6THrqktW;Q_O9l@vu zkWFo9(6OJl;fbaaJ_jhki|f4_29?Zj;jgV4>DRy>m$wa-9j-O5UWU^L%1zM+2QOOHDs2FzvZZ9si%Ai#J%K`d%Sr(-(=NN?w^$$&d%g@ zALB@(ZSU{%7Gq2mXcVXR6g%)W|K98L`Qg%%Xix(X3bU#&b$9cNxAS0-wPjQE@bYH! z1@02=-4ZUb;8igY0qmJ?t_mKV=$o#w9_;L)Mg!Qp+35oi?>NQD;PM>ZB$YHZf<#GHltwjs)6L(8OP8YH1xux2|PmV%QA(OJ8~QYu}Mb zqG2SF=DkB+oVdz|m>%+Hk-um5ExVxh-hU&cZ7q>R6;<|^#{YG;F!XmRwx%5UGNx+X zD&#+@ag^j~6tA85KkJcx~TT_Ebn6onNjB7vyPvC}s>NW^>eEAO_!D%d?$I+?y`*y-}<6 zJ2wRQ7`eVZG9C{t9*P7UZvqVw?Cqq>juh>an0!>tBi`%p5kHoe9I3@=DAnO2$uRf( z)v#ASpQKe0bt0y?crQVel;VVg(89<&TvTp9KeVHuex1QZu7Vj%xAl~V;9HJPV*wJ8 z2|JI$bY76^22wne6U(uVOyjHL;oprGKERVGur&q=*gzV0y-`4+8AxKwSK4+=nm+sI zeJIOGq=b(t>^2qXm7voIWk$8jzp*WkBYLJSUr1f5WV;nh8$_#ML-j5z!EDgf@F!i8 z+#^ETB`k4OF0?*UX;$Q?vAM4#Cd3c-KFY3Bg-F*RxCj=J5ZBHc^jTJwdEXsBzjs|8 zYHbyhK-;_lC%E)qC}5cLS`5&6F>!f&Z4$6k?9uGC*etSJI_=;|FIEN$L|_vYUoniFgR2ycDC- z`MN$h(gtkv+WHpq`5lQkDbHH={yd3TpIicx3M-viptv4fcZC23Sx~p|_4WI{Xp`_m zv9sTSU?b2>^e1tXn?38mYXA%E{G*ePTuYY)<1NGXdeZ>5_EEHuW5Hv&uxdRwohbbF zyFXY_$4H}8qA-_NUxC@^G*2`)e?}J~r&^>#SN~OrFZYF0uh%Z;B^@LZ3T?T;a&bD* zppr9(@L|oUYu>j>ykS#3-|aFpI%KCVh;><$GZIKl4Czd*ydQo@;k!-XtjMNHm4zIj zr}|bD*^pbCCVCYtZt8Vm1~XOFp!*0nzQ&8Nv~4n6790sC7RAaQur}l|qoy7g^z?*J z9Y>C8i%B6#$+!xN`;F2K%1L{-mo;774qKVsrELm`V8>7-n#>tDD52WGd7f_y*vs@z1KyeUH3yd`lYG8VPdI z2cRy+&z=v956>i9tLq55vn-WAx5W>9Y_S zHu&!Ap{g1)Im2V>VP+Q*00B-6YEjTh`+beO5571+!vgZ~ItNIE+_y%4{P;0J#oHg= z;cJvk@i}|oFn@(aMCd?W1%`%)t$D)3I-(J$OrmEQ6j#8D*SX8nWQc9E8Z6!3Ed;F@ z28W61yn?yw^z{2JkWacc+Q_}?v-|?f@Bij)?n@TY&j(lo$wY(}9tU%R+%ztryAu&D zm8oNZ1z&CN&Guf|VR#XE=ig|^cUfvR9EA8EFyR<=Zh#0{_fBD&-XZa@FVahZHBhb9 z32E{w6S?Y7guD9&8ty@{VdQ!t z;0c;)8n z4GzzP%kdYt+1m1<uKlmLMM z`7`9bQ~X(AvtpOsEje!8s`tU6m~mx3VpoutfZDw*>k|i+EX@@v@Q5vKR_rPl(gC@4 z2%0j~oicGc zO9p&G95CPYo6H0NrzFPSFmb*NUJWdMeFLN;07yB5BGt-jSh9q?-^YOMwH+4RV$ECGFYN9{%Yd z`u7Z(Ah!XVrY0ecJD#8@nI`;~|cImG%;F?>*KS*|rixMqoqCEV~2>B+>RT=p;^pu%i^4ipOu|!qN76}S- z4pc{P1etLTYQEgr(P(cVM$eBVNEh#VIr?-@BF=~rDlcGXn!r;t80pqp6}jD{^5bXa z?>RTU#=rmB9PlXF#IWZDzhjXh5}J~M1RSzDb@Ms+!~kzl%}hh71T`1yzkk6}2+F)~{+H>E z{K-l1hbM!D(#7WzA>|@P(#mR?(5E>Fsr0>mrDC*PH#n$OK^grF`OEL_Y85nm2xf*? zREH$b6^k=Lj@sNbJf6+Fdi0Go7(u+8Y=ivc@V~NnROg^aaMGU$S~-GZ`7+*V6Cbs0 z=M8PPB-FlK@>TwyAU6H_ywb30l99(VX8^A*mTnM;^|8$;e10 zx7+=CfL1ndsfUI95m`72;VFcC?B+EzZe1+UWf;IWEW(0XevA2oEN9979dGL?cdto? z*CRjpT%BFSLsLhm?P|jJ`(3eWKuKF$n?^C@eRsJDBt--7^Pk*q0n{Bp8< z%EE#U4dH1cmj3QTYZ=r+&s+bk^+-kd~4OUZ_i%K*Q!Wm7-Uo^jB_3+(J&gx>GZ&dyL|Nql$e$lfKehPDt~tUQU~ z^y085pF^)rzFhzU&i&qZy;#aApTo-+n`;^dI)@Xw`QjJ_XEv|mcg%F>oHvy?WeomJjnWZhrP*k8%y+#Wy7z>DPs zo=xcFfQA5Ix_nlBam!T>|kj-;3M^{2`9m2w3FxAc=tjelbC3&2jen+)EV%aa#5A^G(4Q+E{L7 zXvqPng$-Rqa1Gub8yN=}8eGDFA%JL|#N!XSP}YaPM_xx+^J18iAC7=9PFtL?s1-U!-c~Peu-1 z?dN!*-0gGBs`hiQ%-Pu!U2K%DgICpxClp$c&D~@qq!`YfyU<``{p4$9-6uW9p(grf zoao0Eh-JH0B+;u6B3hu71)B~rX)p}VzhYfr$as+Ph4j-xZ#$c*rVo4E)N6jq9VN@; z-IaG3W-^{`nmu2hP=n+i9n&JW6Y$r@Yd=$Gl9{hjia{BB)KhIgWne-b5*xjW_VO?V z;|Lz7(KkQ&!Ql@M&IIoMITPstb26T_?w4V?% zbu7j^8Wj!XKY3}}g(NbYA?_!G7S9WF;b?vSEG)W1uU)vXc`Wo3$86=p4-7os(#vmg# zc%1R+DQ8LlR~J`ST0x?sJPUa!KqX#|F5Ei7`g9cG1Gb>GePc>?di2J~4^bBg;Odkwaw+#?w!g^}l|)zJJZ|^$if~q7YYARSgUb ztkMPjv-GSis>hEXQ&O@LM_l@6W0mkIo80WSy*&d3=eM)l!@|J(LtL@j(`D&s9rl!n z)qfx~0@Z9#Rf422L}D3;;feuO3LTv(zr*kR!uCz-hv<0|+&QV`zPY!Py$gQA z9Fl--@XU}C$wlL5V?k9d&iG8}W4Gd5&6>8yhC@XzBhC)ZZI8#Bx;K7z`&z)NpS6A2 zBSn0>8$0N+P#BLcJKx2#gH1Z<@CVxgFf#ffaJdoPd2eQ04-vO^cULnFlGm^AzzSOM zqgY7bq+YIFm`K-ns??*m^lLcqZiL|lQ{h@B;?Kc-X90h*1Jmlc~U}2`_ z8xhck1>C~Oqb3p#aPKc`N2OzvS14cqa+A13@3F)BsXUogw4)J=VcbbLUHdK1{cRil za?A3k!iK#8Ma>;1@iZdz+J#-{M`3)Q|4gaU>m8-rNWC7LKaZN4n!sUU{yVR7z+EG7 z2nm%u$L@-CA1hQmdD#jG6bT6l9e@6eyi%QB`yLa?14nVrIsq$#?!Yxax%?>$g#Ge_ z8w{tAWBb>k(~ApSEUb}tvJk-9Wjy9FNhd7-py}mf!gG!^X|%oy(o^t3D4LSUEIG9z z>=09}I*yTuwm-diimDxDWk4~pp}Kv>KAOnUCbB{_3b`MtklZt(qvNHW3U$_R z6sE5LH>lfZN>a#=e*aW9z28sl<~61O((m0fz|>id;$L{k_&jd@xj-O4LR#{93^xO# z2*mQ9^8RM#%Lj2=2wLFtJiTAt`5y$d|qFFTZWyAbTo8TAes=NVfT!t z9i>xx{_k{1l#R3-S-!m!w@!Nh)a?5<>`)ar58*96sCv*Let^U5v=h#x)jM^gP>*pdcl??-QHl;#0sU|cGW8_( zIo+YHv55Byg&g4rQloFh5vm`_bQtWvWu8du`DzNZ{-?ebgF(;zqtI*=r z%v6Q{zC9v@s1mTw5)-)2(jQjC*LppFcn1K$KtNLj7&Gi!1qIT}{83$hdG@-2aA`<`{aatWOv=K+?g`Z<4t&79w)?pb@&K$#ugRN)<73B5tb=ns z(gXELt?lc{sn+xS%7F5btK-X=sa8JMyBl&RzoVrNup^skJ&oI1B}Z(2anWh^JXB@+ zE5n0#5F@5AdNX5N^+$oki8awg$^Zig-rCxjd^8qt+TxM(TY(eR+!50f zPHGWMs)5cCU=>`Bf?tuS*FXw6wI2Wa#Xmgsx|Vepz)HX%)rm$Ed)U08P|D!GG0RBwF~nab-J?{`E{ou%$=fkMi3TEyI=;Z;vz8wLmDvI(ab-TZS_}^>PFw*c0cbFM zn%q_@(eOMmU+Z1^jpMqtA{1DO4T_*`uD`$&ev~3rTq^k3_tGD-fsPriU+|DilF_=Pj2ZVN@V4pT>h46B4`RZ22*sfdIBItRTL#$eypQ=&Yc|jJk z89~zNHmr?^R5!XL1lx5U>xGeH(sHvDH{y5CM@Ij4?R3NHy~JbT)tDpm5EDLD6rX3j zzp>buM0@K}2(cmq#PK9q`-Q%Yab8mno>bO$?ZTbwbvJSlU%vc=k=&5rKDbTflKWlg z!K+7lNJWD0Z-E#_K*3zd)-~}L)wkRFrw+YVNgah#%@;iwRn-YWyzwdNPzy<^+GUO5 zuYN~T%I_o0n1{DdW9tRuNpwi%<>eLKLF*UcwQU@1gdk4Qc6!#=XQ@|W2Q^m`(RHH; z{zJYt^pzH)6m`9i5xT?CrPbkso)FMNIjAiwF>`3SnTq(f3kNdU|@=+mAGG47$0uuOzYS+;5+pJYfFgJJv02X*=3c7sDZ!%qndn z=8MnP414V7ar+#B_?!K>N(l}NpGoR|nQ9Idzh-1j+bx;S)fhIqtBC3hH~Gt{3xV%i z`-0!+M{_^4WO{Dyz5*!2n>j|kj3(Om;K8>rlYla>sUk`4V}ZJ(6(LBD2W^Cvp43Nv z6(Bo=#;nH_?tr;rV7QI$A%(*GOsqd*kyjSv+RUx97&KKZEyRt!MM|1%KUvc%_BzuF zQp$^{=(!62L8ulEJa|_KKqA!r%mLRn}ziAjLlFaeFySOdq5O0cRK{J*D_jmAYvoD%Qr zcJ|8xDn~*Ad-L`5@;~&0%2J^-sUxu1dVUoowWK6oZy=LkRPAZtSZ+zv$lG>$=zHaf zHL%B5)tlT{)5y_MJ6rhoH`?ljweK~3Eqcq6cV3p9_zK+F=b>Sa_ycx3=(MR*O56lT%bfs_kR z5?YRsl2b>eQGBjp1lnNwRh2*w2ecXD`PBdWTAPx0SP)Z=oT__X84uAPyEq3w2@T5f z)I70p_i0qFnWd$rySoO)$+Qx8=g9zhYV@ukZu2xsom2K~8a{HhlpOw8^ub+D0F9mgh=jMnB{bZ_(sP51(=9s??6+Q1UoRz~chJ z-N7w~{I&C=i2`J9IUavoDFzD;-!HA_*nF^@@lIwSOoAR5+P*M~1I#zz8U1||w0sA8 z{f~3pK_kTEtM{}k0syD?|km*x-;W+FX@?r_1AvJyo{!*VC&n4E3j?vAl zUn_I=M3T+It^PKa3xxXaprxXO@lEIf^bVJnm$OGVjb5V<7!FP~%Q|^ZRX6kn3vO$S z@T&~(6nb-k&Lhu<K~(C@5+m_PprZ4^=>j0kWNu)!J>};sKmX z8W1DXt=|8~Gm7ft9DLpoUeJO(ppyQa*759&j}+b?5ogKi9pzqgj1o6<;pX zOTfd!Bi)MiI3wuzPe1{?vZaMUYzj~MN<)A`+UPd65PN>(wLezi&l;zbnlP2txpu=1 zclFm|2efmt^k52{H8}5cJ2ekJyf}RG_z1?I#Bz;Sgg%pVf017F(OiDK$5_t2xrp27 zO=bb(gh1&SG382~Uf5@KHZQcK>u;mn%p;vInZpGwMK@Qh!z$&zw{Ob+nl&6E?H1p~ zJKMO1|13g>-u_#N3KEHz%7V@=;JLm+~an15H7n}}Jj6dWuz%Pznny^}D zXUn2SeeHcClU1eeUQH=HA(yszo5zFG$HPD3`0{<;wr{BUg-_Sb?}VVg9um*Xlhgko zoA!oj zoj+Lm_~#REDJ)9g9qCx~$Rqz|cMj_MVMD;71#eiuD z65)QP2fH1bO75NQu&H)d^vE-R#Rx_#`$H04|D55%3 z%7I^4Y#pRj^~?;2imJ}6=vYAm7+)Wi32GvPT{4@iI3J(4|Fq4@6Tv^kkO|IfeZ^*3 zo^)O~|9ESA7NSj@j#>~*UZaH!ke0}zzQG^lePJYWS%%|}3Vs~6t6r)Fb~?X9kx~Lg zpZ0|pZ|PUt1xN?!;@ohu!~1_fRDTJef-E=0$dO#;C}>G7o^ zRh|2z$dM>hcbdU=q}R~@nQkAo_Aw$r2IzfXqw~&MRqT9hW8?eA27|U?-Xd+D9wDfj_j}(8DStn#0v#FHJT9U}Bm&{Evh?o^gOIj2hjQNBtd`Jj2 zV`917+tW3TfL3?)7KL};2yE4{K0b->^H1bRao7`c-~as3MVS|>Lj91-+Ws~#pzI|h z0xV#AFD~-MZe)jO{^epm1J7gcX+pyV4L3}6E}z8~pc#fn8v5vjVzZ}}<9pLbkuU^F zPs|gPXt6b)X`ISssJ-;yg_QBD%nto?JTx_~)A}MCup>>aKk8xLh7N89Jd;atHH=l< zGx9DAs6pjIw7Qan>MOrqEHJC)>38@oC@Q$e#jflt4>yC>XK9~xwm*wr(ShKfR%Qwv z-Sk(lb$-5HIM{-Iz&qPI<+1?o71ojn{1zt^d?^fCrc&~Zwe0L1I~m^2j#q0-e$c|L z{&Fp1)f6qolC6p$(G9lr&uPRbJ4Ff3KO4>4D#6+G!_tU8WQplPQsijV#t(Gobki`B z!ngJ;2Ycy-wcU|uhUY@JOJR8(?nmt0lMF%%s#)`9<*C2{aFrwS>Lqgo=?;5ZOk}{S z>|V7ZG;{P7`x5`2UmfDkcI}5F=l!pK%*lk`T1ccjEmm26Z_KgFEwhR>N}q*9m+Py( z$!fyrs{nbLZNmlFUR6^i#JI-%foD`S8KO17ZC z%`ZSEkP>X!L?7-d_$EawPX_X}LAO+m4R<7bshwwt*!nK#%h&hg$NjB`U(fFibD%8m zPRmJb3Mw zL;?^-uj4*u?ac72XqISUNivzyS&q?7p56mJ(}$a*%h1;RptA?R-Kn#l0(#d`bUbPV z^C?h_odI)+|HIv-&!Hl(=X0=6LSB&?>B~5A@bsGM(rdjdZkKdHtgUug#Zq!P2w$y0 zJono<7wwr)TO*Fc>k@rVuP7{HW4ZperfOU}(9RKq!85Gc2WNvHI#5+7y8lB7fzD_R z^V1cvtMpxFiSQ@=S{+CfKcqYZV@)7{a-vV_h~76;)7MuTyVQi>$q^zn9JzuJR4 zi|3O_fk8Q=n`JF55ucs?j0}pGp@2$Xa=@U-*4ZAO*1L0{Pr=Sgq{x*S0kI^*O`nWU z2(0&Fn)}s*jExvji>S6Bl32OtOx0>IVs7gB-$qo|JTo2@dF_RnM~e%CdJ_ zEuIKeW8w6EbXe0~ z!6WcBppaNz_{ZIkIj3O000WZiwTw@*em2%NqfS-?pVRm9;H~1@w1j&X`qp?nYB;7d z3d9Gbo~B?*(ncI^ zPA|a(QZ;68N>Y>gD0fFyC&v-QNHlR1qOP_k!6c;QtCw8nJ;|<6U8u|E>DB#x(Bvr- zGjqQGVY_334zoKfGZT6B*>V{$7dbgn7K8ppaf&t8_LSM@5!WAs7q6%RBIr^{uyRTY{8+T z$;!BB1P{+M1fSH_%z`uuQdp+$ImeO6RG>^|H~s$X7rJK0%Fmw%zN;sH#y4Z2IH$(&PRAeG!W@I|QVqk8Y+gtJ+no2HSG@ z6_8oAM3T;VsW#?JH5Xs#Q;-%AAMo-TMLqqK5ilF7ZGs^7GZK-|vYDIw>X>WmTE{1- zo0*fNtC4x&cZ2(M)p%NQ7d2fog7C?+VSdXiV+3On%#drjr99eL#GuK<--w|Xlw1dS z=ZK3~3h7^y#R0tG)&folzg@B0pCoxIVyOr-TfKQ;v1b-P!Gt`PCWm-VMe#zc^c0iZ zYOrZCM$a!V(ckb02`R?wfKtwUMNP9>^#s_OqZw<4HS6)4-4dqq_J=-<;NskoIMvJm zN=kK6Js6-D=3s-R`D)hhN4T~cTgdoi&*7L*)M5&)O5?w?d52F{KF)LD2gkU6RfYzH z$l6>-8%78(qYO_XtHNnAIk3GZggCW|(_+CYvKkbOPhp^aCRYK=sR+Z)1Un3T{F6pz z)=gLh+4e0k@zz-BtpOLJ#NVWZM}@AZc&eg0a4#`4`}_L?>!o-;H!)1)LWXm=!q4yJ z1XnDd0Tx*0MngOLE_}PURF7+j3Ki8!Gz5KhU^!ce@QOc|shyuaLC-M5tn`v&@uvG1 zmO8V~k0PSAwU!jWx(IxA!boQw@eGUDDgS4RT&#?~Zy|!)grsjGWtTp~cCwmOut}#h z0DJ>Q;m?3YLQcSKed8kg583aar+Ga2a61WXfyg}k{J_;q8U-YQcw)1+dx=v-sNZV9 zgg3p+pAZKf>!GjOh{CZtrTfDcb1j6}2t2mtO0H%Th2Hdf=cxhKqER+x!UB7;LtlQt z^3NL+t_+c{;X%V3degeaC4a9(=ZJ?l={jJ-J5yO#Me=7md43I5zXh4*h@#Bqcm4)S zU?9W#?Z80l?kflQ!Oo8Da@6YmdN|&hi*OKl)xebmQA!h#hxKoFsd49yDf_BSD*k&C9RfP5GvI1KeA9 zfvt{Ij?d|~)#SdgYdIVpuf>VO8i0pE<+DA-_;t;hk} zPSaZHKJX|^;U##*vWCQ%={2Ir3XSzW7^JnMb?QxHyV7d|)}}sP8@pw`GO)D8W1f-C zzuotHN@tVJ86Uj&J)G-p>vZjh6FmgOUYW14T_mQ+yc0!um5afW>4#26p2#Kc7Czy& zKPY_qQ%1E!dhHS^LY+b&?BTxq#%11X0@ToRva<=KR)QbyK=XwcT@6*k0JJEifG`xqDK2TEyX}e0Dk5!YhU=K31dLFXzKF>=l=@Anbr5% z9;#vwx2LHDZx-?Q{4lzXKz|6-VyCb6c}9gJbH7JDJU9zaJNoxo$L+$mUG+9<1dwev zEoYn0rm$%Rf?}fl(}Z`Q6(VCT=I-eaEd0_d+SwnT|2`nR)7pF~(ZO6v>drAzpH7m- zW`;T8%Yvo|0*~E(f^#7P$>{7!3HkQ$A~ZSTBIR7RzRVNNy*P{pvhJIAP7tA1&jps-27 zPHIGs9jhB~x0U4-ZYBn*r!EF{F)TH&8yr*>xIA4~SXvsF9hGoiLYi)mcS3_io`xVp zCNF;rMw8WBVM;vl@!-Gsz)!qcq#;Q{8OlfBU}n@5k~B?ycAL+GQ(mE9&W?f12N#{Z zDY<#O^Cxiw*%cTl0KMVyLxOmzcfR<8wdxK2&Uu1}+y`)x0 zljoR$eLDD9pXB5*Kk)*Yh9eP?*8Kmjdpg_swBGLsYwRU(@ThmWbmNBit_; z*+L&)ehUZe`f#q-dI8j;f$9DJ8c1G}@#>6gXQGT{qSO7Bd4=l|y5c5Uf7k68d|wiK z+!LH<7@q}-ut!nlFcjeNTCOxm-$P9C6*MC&ngDa5e6)^n$I&nB8V;}uaRzNJY0HP0 zZ)UD+7OsegKwb-z@b?YovX!9Dc_Ybv|rtl*q})3h<&FJsA% zUm~mKh-wrUlK^749AZ%1JLYds!w75k-&XTma;rF{=YR!>#Ms;$T>3rx)a<9q*o_nB?NWMaC{8_lC z;q(mBFK6ih+XzZ(l#SB%-ZiHf6#l~>L-)7UQ;tNj2IL$`#VC@*S@Q;{vH@{%ae)uO zJ5arLUA;*aum9CBKz=7cWn5YB|Fr-`*plsrhYKY<->vT(N#~lk>vd0`4oNMwd~xcI z`)%(9Mn~bmg_MU`ykY(RTnO7OMoY@I7>gii{%f=(5Q9vfzReZ3S{9&GQ>v+&k|kG6 z2CF6y$PkB_^T)(vG|FeaRp3s~<elUg8Dc|XIIJNS zbwZ>lC=}Qb4NSiontC*vr13aiDdaHP^pBc?;1B38tTy7=-a5=r;(mR^1s{;l3tS?P zKjJ2s_82SR_PyO~c7AfN9@p9pl^{|G)-Gk02zdoV(f z;h;6{i1bX7Vz3wv#&h>2denS);GdzhwvML~gANu*axc*!$;;CtWiVj+T1x=)@8!X= z&%a|c4m_{l)TCseJ{i;H*@L-x;xd0~T5sYHokung85_UPe+0e$Y-bVo7c1!#Zp8Ou zKV$FB*oJv^zy7C%H2$>Qv^6F|Q7OoZ(&K{?gw@nzLAgXSUYhO6F@M^8Z`BL1;FiB7 z|9S>4-(*zcTGi?0n#~^OGq2!|t$Q{N$Q`S1x{3b@;bIYNuD{!mTaUoUX|2x5CYZQ# z|L-7Xxr2sa&dUgEr-1_`$UmoKcPzESpfP^ZtgZ{9ZSTsYojctPu%rCt^`RKA@Vq_0u3JFbRcg)CuWUX0MuuAg8#ZF`*dOwQGHD zeHqC87y^9FzvJM5zQk{<*bVok|J<1FO$lJo={!iuj?Jw}|?i6O*N-GTpCjBRi98bX~thL;e4^S(bZzJ~LB^uGhO5$$U zUG07-|Dgxbvk_v4hob-!j>d&H`Ouxo*KK2bevv+=3|+Fh<`4h<@>0-cYg$G;Yf1To ziGsRa|D5#?g(()Kuu0Dem4?Wj7;bo-0YMFq&`@TCkB=r45E^2~>0*)hAlHt9fRatS z{8hGy6vk3Gw^YKtB*~2+vzTdBOV1Vct>|MU(Wmaqb?ir4c&*j$cJQ|+mGn2d5Q+^x zPWYjtm|IbpQDP0z#fG1URyBQwlFQDmM(*FwY3VJcki=L0Ld>}lu~Q|fbVYl>ce%7v zc+c}QyjJH;@>Ck9`Lx@kp}aO=liewyQkO$ceO7ZsETGum@i%VUoP^-Uu|RKgm= zoJ0cc>d8dj7D!?~V`%a0`g&N(oRm5~FICy{7@i<9>N4>|V+O@B~FF~))cPA)4%4a~nW7H^=8gw=33LGjx-@a;BKkc2z!-o%e z0N4Y#W!_towt?c=|7onf5XjGV(LxwonecMzLwFM9on@OX>KU}WIohe|p^0pQ$dJ^H zm{9Fk?o2`sTSfCy5v-*sXPZ;mAIy=Zcrw{Cb#Wkts6yE4U)PNvGm+=r8wjdQdKAkXLe%#JLZvxH$e zwni}-7Q|kX%uvv$5gu?Ms0Xb3fI4ClaM`hz+kPU)Mz1RrY8Q_RB_0WcB=funHLRXi zcQ%1Qq|f~lycat|5`s>>4{wn!Ri$6v$c{l^&h z?)yilg`w{=c;>DT!{NDxjYX<3_x6B;rMY=UXP3u^;f^l$A7^%n)Ot_Xw{npbfqaBP zSSauJWD$W{X1ZTjH34~9J9g29d0y4zbq#-&*g2seA)qpz=dR*kmOFZRM}wi@PATFY zi__?+t|4NhcL`%lQzx{WleHjjuA{fMu>ra*%E32X`IW4LidyBhRIyLuFzWHRtR2q# z|C`A+iwk|G^uk*A&nT(E3H0!mtB>nd_0i}iAEi&}#F zRr*HZ5?!^%SQn+018jCZZ5&z>!UfkNLG_X&fvjBu8q1^OFjq!(TIIu1(Og>o!OnES zg{@ZupVvy8d3pCSM9LA-Sy`L9zS@V^ixsu( zd$~diRsB5d8KX6OhiJ79jWaQT1D1mGS5IMMTFv!X>-uS0NjJ|BB# zUd5GWFtY8=Ka-VJ!*UZt`1~D2k--WvLVQu zM9ErmtautCR`aO|WsEH!`=xtsNzcm`C(_t(2tR+a>PUx584QVtld7?Xx*;hjg+%B~ z{c23&2QBAFnU7d3JL<6;Ud@s6o`fPVt=&!=a3CdYJCTkZH;MyVY+4LFwXJ2r4rP4r zwd@UcQGX2AKzxhN+YWtI(#l=$;>d_nRt=R`Qy3bB9kBJ1Y5o? zYk3di!*1>m^)fvej4gV0O7@Z{iZ-&SaBk|=%a@P%z_${XWS*2!X6+p!IA4=tg+=gD zBQ}-YX1{7}B@Hn=UY{yHgBSmM6kGotXqlCUav30T%vG?z zD>pZeU0kRc(B^dXscc+Q;z~C02`I*bJi&tWaAYuI+MHAiYee1|t<-Z$DB7Y~eUp2& zI6{otC-(N~t7JVH%o5>UNCT*6$Zj_&R&$I#wxw~k%UTxFx$Ep}&(ecq$M-n9Bwdio zwAfy1ro7Z7c>D{su{ivk)4D;hC%}c+h!&F`+|K``Y)n5Z-BAC}3kGEcOCtda%`|dR zsMss`KsCJ^H}%P?f8R?@yMpnj>~wC_ZtfhL7@q?bjy za=%*%!|rKuGBVJDPVq@ki|Mmjp`Y(K`&Dpiyh+62f$mPzlZZ`%nP(qCh5FEo{ge0C zv%V>!F@BZC`ZCK;pxGAytluWL3=|SUE0=dkCn6S&Qzx|OD^e8vB4_Pr0|m3`J2klc z@N`R*?e@&ohy6US7uMO_+@LD_wr|98#2|D1viKY`^%WeVCG9E17efH!{kHDvid};y zqVdN=xncqN^JmC_nv#*yaaEhXqbHI|5$w}3#Iy|6OpimwiB`Un1+TZ+cOu!C=JIlj zsaHk9G2HA03k#8CyYa=;DqUm8el#ykR~7xPqF$9e-3nswF~h#Yxw}@O^~5FMxN9Ao z0o^8Xy~PTXmM(p7e4BEx0IYq6_OfVWbkC`$&D&!bRc;oqYnn>)`r33mvdfcfLO@mAd(X9Ds59J? zp#D_dUG`hLCXyp8!{|G(i z(ESu#(7J5gP`mI#c=?eN#)>rR1;t)1Vu*6Kv#0V267p z8O9abmFIqeI3*VArj`?-nAlCtc8|Rt%zg70o<=3g2(QYyU8X+1$4BGNq5sa#&JbHc z6Lu2TcZw{1bp^X6op~D6#Eh26Hc*hPCB-_CSc>(WPX*ORtzth$>(||4o388mxQ?1W zL|@2Ifyj9dVj4`su`EZCpnbAVgHA(A0Yg!U1N!J!i>b43D|rs1L7@y+ezawnuXOrE z_Fh}39OJVtM{@Totrw_25X%N^#5OiIY~kTuM@Sd}`A9*Zv^s%?Hf4^b*<;fXR}yq} zc#9oidco|=qq62oBi#_j4;VoGu{DEp8D}Y+!N$VnuDbJawI=FZOn>NxIyz5bHIt)Cgt8vlFlZIe2>JI+gGtJY*IIKS zFPWtSJN~O&k&;JcR5FZfu%VhT@pCa|wtO^4$I9va^+%kj%^m;G)H=&P8le7<#YVD6 zBJzE&a5DPseHo3nwcBQL)sODYn>^ExWK@s=9x=2hsY?B@?)QV2qEAv|WS}m5W*@IJIW56^Nj6bJw+AT#u zm3(|?XQBZ#)YBC8*UkO+?=s&1nWyg|YJq#ukV}Vy7)Wsf*1B)+zi0kIQ6~*?Yxlw? zy@XQV8Jk6FUxRQ0GEM%)rQaiM#1-!-P&wjRk_?Ca%zZ@0A5!XNhQC!!BDL3k?~RzF zlhZS_c%>{*mAd#gMpufJf+ZYD)}TTb*}_T}i0HNU8_q&yU(>`dvmDv-gn1$Uu^#@1zCpYj$6WS?O&i5=>{o}!ir%Gr9b z9WF^ocN#|2KeLT|uP#p#xg@XNl=G--`g?o~9Apx=tNvi(sK`$E)Jfn^0iqW|+olu& zjV0l@uM->giM-k}wXdtpthMtGSblnM=(}>J{=CW${e3(6?eFcRB$5?L(L2`(%5=Ht zeYdQ&$>*4m99rn2Em6#gJ!<*7z5)Xw!B5`_A$I}6@bx+&4qO2VKF9mi^i&gl&yq~0 zI{T0IrEXo!E|^h*Nw%Fnq&Vaj^^DThMp~8}1+zj#1D$m3-i+aS<+I75MaUn%w1o7V zdHhhI9x$Eiz_%Lr_!zsvMvSfL!_)wniHXqSb*Yc`LxFbN`pvSS;Rs5lNlHqU`ysNN z36LEozonvnVm-q=#O=HSJ&9MN&hn1|$NJ~hIDRp4>p3&LitzD?2`+>@-a7Cd?c0c- zW&#%%P%h83N1DC2@zZv-GC+TGhp|kgupOS%-Z4?q@-XA?;t@i+wi4ar$UzJ=4AVV%Zh-Wp<*ZLMs`Ul;~8eBXOd+K7pn${rO)s- z)YS>Z##`s7v8r(cIXKjI17;odBd9)g=1iq+T2SA7veJ8lulCNs~shN%B`X$e$#iUk#v-mPHMn7Qaq#*4g4*%#{{G@b?{3OO{0Fx(%Ag zqg~gMDN&WKCt7ZK;C^%Uf_91kJj|>yT*jD$cuC*Mze#Y$Sci1HLsB zgHB7cgZx{2J8i1Q1@--6VaHugnVQJ+UCyl5_crd+r(%|8#34LLpVpr_~rk^h4*DnA^#oNy5|{)bD^grVX}T| z`ZRXJpM-BmlX78M4f-jqM$le|y6;GY`=ziaKnpQH8BK7h{w-cO5fmdGp=`ul7O22F z@Ux*~=jB=2vHKAQW~(?j9vRR=v9Ad7Mz90T=lEABIO}btpm{dIDFB|IHtoZ zPjUx7?qq>;ReHO7NMa0jR1SS%Dyu7xx~ot~jvAKeJJHaOX^HDWu?%Sr`$ZWQdd7~G zQuD-Ytqm}iB=k{Gc$psr=M4`|qfwJ3)0~<^2NPO}hJ%i`(?xtej2#J~#Lgb5py!CtO5&`ht8moU;n7)767*#)05OsayU&Rw`gk98Fp5flK zIsrFAAu+N7kU&`>1Hl?K(IzbQcf22fUkB{`NCwYR$-ohUaHgTP+Z*ysT$-npQ3 zmFG;>lhasG5U478BKY&aux*uc!FZ5q0Y)jvJ52okGdYvZIbFLySUUvfZ|EaI6UgM# z+@qZXX}>=nK)|cPGq4H}=D_bOzgP(bDWK~@DePI++M1EIyK^`&Ft7@M()!h<>5c|^ zah<=ZEtGC1K^ABCzcP^Hdel!LaYUjD?;&o&eYL{StF}2JWcoU-L9uEB1}xmIUAOjiGSD2B6KKRy`|9I~QJ4*ScOIk$|=E{JWwD-uPacV=MNHTwboU zTUhtMwWC?7>)0R)8lK!MB=NHN9_3Ye~;B~matp>3y^ z6jS#3H05s`$p52R{7d)3$mF_nO!5^Ap{dwr24K&J!Rz)3zVs2=e&o3S1B^YHo5(ci=A#e$ zPl5!XmAbJV6*781!UKR4CGci>jS3*ad*pkl>`T_9Vt02vans$bo;N1tN@LKxwQ`}d zBH@A|F|ckqw%2~bD$~nWEO~-mHlT(tL@q?0-fts?wC){Z-|ImPiNG{hpd}VG)+4^0 za`4Mx*z+PX_!B*5NYkgk5VBF|eBJ-+nS(Nup|ANmmiD4?rlX3Z3HlxJE~jZ%%fE|d zm#I91*K5HC%n!g%0byuMVZXrBzF!Oe_fXbShO*=3r2e6(1Dy_ZB9eX9d@$&iQ>||;_Hy!cV)oGRKKT9!{r-St<#$i=eVbU6?1IWc%P?t0Uh;n zE8AtYtv-TZ!tM8WusJdqqJyYDuCA_{+|8MQ{6r$V^grNhbYA_cIH6sxCG5U2l%gu` zyEO)&czNB|mEBpHnR*$2nm-WhBQNx}A{W8Ev*KRO>PVjv_8UqgCn`F2(tT#A(zWX_3hi#Q7ia_cPe*l zj1yb9^M_R_c7k_D)K}}*tq;E*a!ARY7!)$Cmc2hx2uUxEyHm*HJrtnD`iau%3rBnJ zdci7Qtzu!N+3LOE%Na1G4U#lfMrqCWjBX z!5zJt6@jH-X2<>gJ+LrV&gJ=SNVhmCvUZ>59=Vz!0kR)J9Nqweq$_|PgI-KGKyx=X zHeS;d6%{?A2PD8qA+ZMh-}Qr351S_Un}Ff@u>0Sa{Oj!Qt4V+cW=(@r48EP=f9x9g z0jT867iw$eAHvW;@pLP(lkWsTy;iGTS)wuAvfX%(2MjXc`?6b{9?eYut`XhhuU?gK z?;alBkAW=n1F(5@pOAN-0Djp0Z<20Xayj1&GqzZNQtoH64%OCG&SeNC5*Pn~VDX`4 z1r4+UDrzVLha@gBZ4YH0u?$)9Y49RcJP%_Z#fobi(gXWU=(|NcPfS|yf{g*q{~Ogc z^EevWX<>l)S`c|SQcsj2S7%gxga+lg_?cM5hZg%M7g*YQ4h`qoz^zK&GU6S3z!L79 zvWmdd1Hj&_U%@I)w zu=$L5UY)gnbo3>+S-)Dl@?ekMy7oWcRTy^{;LuJ0$;Hiulh|J{L6o1U_xjPGdbrXE zg3=TK(||5v#hlP?1j;dBsfq)|*QPt7+JIhPbjl|I1^t3r$h`>+fl*bJIPO6KWXnG4 zpsdopJVCcxV88`$TH@hq^7N|r*!4~K1h|Ml90If<*xaej^(zhIn+wv-H`Q_OuPPky zK9lc;l0tOcQl)s(SSo3qT-9BQRGNs3tmu;)6*r}7C?+RP z|IX2TrB*8p>L&<|I9%ceddL1r1!Qw`4~x3;#3 z$)&cbM0{^1_(QayVpuHke*o6zSN7ViHN~Jq`3mq}Xh4lRyuIAr8#KxRUft3v5&w5@ zBsQM-zjY91t^n)C)Xy&~UXgo2tn z9M>kK2`&2=(nDm+pg=^Ct~}_>_6$lE9QQTy-q5cITGW+T{M_NNh43@lh9BO}ja5U#4U38V}=yqzp9H^A~13;1^o_{v@Z zQG4*qwcubAlQrNXo1I4x4W0}Qje`LTAkYJJ=x}uOGSCjTI&k}#;i#i zBD{VYE(d2mdO|KB@Pa(r4d}(@Y;I!Qtdp4@Ya4X|S;5*SZU#hCHl4)``-v%6OF5S! zrZ74@sddK3<~t>I4n35?;SOCXgPR+dD7hd2=QBbD9b1XNgouJatZ6?Bkz7E@HdihC zz3GhyDUxnovbG>*q&({RXOd2XfI`leA1TYqIxps})0`C1@60=`+&-q;F0pl@f#m78 z@BPL`L}AdAxs|n<<%gdC1}~}eGApl1Y7LLr30XeF$l6&-*@5j&_G@Ikh3zV<#Vk*J zdV_kkUG%Jps@Rcm!s_YQM?4gy3?e`1nCFDOByADdH1Q{A?+qeOuJ80~iqE0wg6$aO zWzUbr8Ev=4%mOe(0K|B8!k<8p*R=hJvJ}4`qo46;)*87($ITP;GPSmD(XM>=NK1mt zWx(=2{25d=1hfPIyj*T|F=^KCe1Bqo(b9DI7hto1U`Ibsj|B<)J8ZQ)jD z#C@3I?bD6#(Ki64eGT}AP0k(PD=9nFYfX}?RoZy+Q#*R1$anEbBLB!SlEhRh@L6L@ z$g!!{PwlzWMj%gito%xT$-;>JRv$*PLPAo=o$xI{cm~p%T>j%5pPbG&{dJd34xzRt zhxo#{{~$c0q))LI>o)Xp&`O>!zb3I|9{rr%Ix@1!=k;Somb`AnTiFGik}-gpp220J zQ6YwX96FOg_3%R)T3#D;UU?NTvoqa244Wp0>`=;8(#?@UtMSUVAHb9mzMiG5o%5l7 zL#{96r*>(eoY8ztmjOGYcnW92RPfpGT?KIB8v{ASm##DaFI0j2h)$Pw=G&!a2d%>Z zfOxi3E%_c|t$AQ-wWE5U@!(}{{u}W5T{_R_0m~FH^xXi_*{^f8v=iJd-sXuaPMLha zze5KF!n~mCzWnRiFCe%9Kl%~)1_PK!`$WFPgG2X)LxR}F!Xw!VK+lun0{}=CFq9tW zmY8(fEL%25e>F_1L^jtYb;&Lp z(f~i#g2wRN06d+yCiiW&V`sxV@4p+sr3%&*b!~mv;stASiXV)Wl;W!xZ)Tv5I;V8t z--`uZrBSFbJH*KtKEV=>GjlcscM0IDec*^#N$HHa37<<8jhX@b#DA3hD;pazM5M zD#b_iEMSd|G8U-;=Jy>a%z_O~EdiwR;8lxGj&7fV|4kCmN5EJLrRXas1y+}z@N+Qf zX!{X@1)wmCAE<-g+uD}tay%aXkMQ+Bg7@D5#SF|>0k?R&gYzH#bk>_XBJP8*m-CuV{8m}@%kjEc{@Ft zrmk%(8F+iq?-I};29n361&sRfe#TAwDULOkjwy!HSGvJdhPbR&i<^7<(mX4o;k&(o2gJYjn^nV*yM!@oETH^+Codi3Fn`{DM0T=VYk?tiZ9=LTmY?KobmO3wL&=ili_CZyi@~kc>Yd;YSr5;?Z}2 z0y#K2Oxiu<$&KEGg+AnW`ryU?fls1!d%X3T#3mI*N5xD;l@%+OXAw&N?|V9th+EBT zpVJ1-`b(g^BRcXLS^Qd&Gb_ycMWA_@`ilO@xgUOwX$^CA3KDc0kg7u?X7+~>_z?g!^>kuU= z=|51>QmrP(gu!4S&p>V;c_gYN0KsNloKaW6)#IExlfd)2xQRCocaH>UFni~5#22_h zJ&x-Dcy5rg0_jZ`7<9lHO-75;r}W4@_KcR&1b%w)!YELYxS0YhDs(XP?(vcgi2P`k z$Ss2c^TCd3>1NwGsUoW_Wux#5^e(~@?He(L(Wb0t3K7X@$eU_5qRm==qHG8Sla1q^ zu5(=2oeMsf6naj9k0Wzwh*XS`&da+A?J)E=e6_CVwBB;Ckm*wpvWk;_zQvx?@!oouxv+MK zPZ8`Ka6(*3W5nG4yBJbXblo^5IAfpUUQ6gkyilwDhjYxnhn*(!%V2;;N7tm4^t3w4 zP;!7cJ&@1cZG!b_TCX}Q*{tzjJqwZN1Y*7|j?KI{((rdsMQGZ2tWM>-N8_m|h!~*y z`ar!bMb28lPATz*{5#yX36wS9h@xfyDD2@}KY2Lo+W%26a5O~H{SQzQ{(>Sya?n#9 z7uR=`Vs2kL+S=N_%5iUvjEsOc0XQ1R0MmZ~<|N%7gUA7buqZ%aKYBVI4%Y6+alNko zZc1FGNYwip9lakENuXf88vwHs|NVQfI?2R$3>Y0QU_cWn_X4?%qr3ZGKpqD^{a`?e zH1hYO1@g*&jfHE_h#c$@KY8PvRasq^}r8}Ix&@2qKIZ^&4uMs`Atxb~)3 zX(VK?irvd~eoDyfuatX~LSKmdSR5f_Rx4nVf3m|9cBA3h2Zz`B9xms-%YPBL^+NQe zHr36YPVfUpJWn0|FOT)pVjd#?Er5UOK%S;%pn8VNLMBvo?fHK+on=^*UE76+ zMjE6`LTQlh?v#`mLh0_3?rtgRM!Iv9kPhhv1*986LO|f#Jm2xoZ`8w^x%a+et#w{D zt6i4owq^Soe(X$rjSs;;N2+v;i%o%Ke^-UPk8I{p8fA$8=EAw5?`)@1-c(mN+1(l| z!NbYz=Xb;W*Z@uHH%Xdj#e+K+PC(VpbfG?L`Ku*Zu=!jUC5_($sI69AaVtVABoG{=1qlCom9q4D5}}p&+iYLFKn%i0hkpKxxj* z(T5&d=6dZs*}I<-5J6B?`rdizVr~4wN~!s0)in~tZ{VNFVKVX1TM!MDntO@ZgpBA` zwz!gEHDz+ zJGUUk!7rkME6Gbmg7kwvY0@M*@uTVStz4;^S4HaZb`9-sV8*X}HXw}A{Tf|~gzwSY zWA5Cx%wlp#UZ3IUzPDEKR}{g9U~TnH5cbuAZzlxwd3}e^pTCjy9aZJm1Ht$lYOs&P z1Xj8SLB<&PG5g~>dAHsm&5JjyL|MyJnJ)QP_GgtsvyQ^zzc6|$jB0!79#~Zrr2-E- zhLmj~2*_yzaY-`;R~`%+U#nu!A(xN!csf!=hg^J)@MZ98D61J`Vs`=esVKtdhh3|` z359_(1YiIIHen}E)-TTF_TXzX9Ig43d5wzbciM`K_B2a-0($!TmD-iLyGx|DN}wLL z_wu@N1OTh2OIQpX0Z%XF4bbbon3ZevW)%cSk=iAxl;8R{|Txd;aXXhZLj~y`W zfLhuIRC)T8jcsjZ&Eva&Fsnm(dxDNXbl|cw6UK1M9BJV;j>0^MkhIMq#Q6l4?lq`g zgaihLadmifg)pP8PpHtjLC3kj`Ia=jXz|gB1W?y;DI`cGTrs{t4N2XG(|8;6I=hzH zzd!+^8u7Bfih%+zQWzwnb-qn4i*wXru^9&<2iwaqGoUADjWxYpX)FFk37svKK z>F=mbeK&e-SNGB5kl(RFs#Q=8~yl(mO zV$6m?dU+*iTf13k*6_|#mN#eKgeEu9eesT%){B=iBN{c_ZyV^mrz`F7E8dz1Q`J$j z2r8^y=Ya?;6ASIV23vy7&w6WTq?ZruE>)UEhjO+&c(4=1&bxh8Yy|SeZd1mMOPzpA zou{C0DL{BkO7IQ6l2%F{l0vLe=Jn<0zf;R;G@h#hTcgsJ1g!lYzoDdZf67m7JpRXvGc|BEZuAt-JP6E@B z(}2f2aP@UM`fieemlv(1U|HY#co)zqHee@PTg83_%bUMFzOI(jSX{5T5ha-yjD8$V zFC7h}nwAI+LnEh?V*SDEUxVl$T1c;5F+^a~Y4$zrHLfCry*v8XMQRi2)X2f*K>@E5 zf)lb%-v&vb8=35#dW8Z$7pm6RWnA%jTh9y`28&5U*k6l*c+DE9sy!~NBBc=0h{I3k z__oSD_Hm!q8$#aSjwPPAowb+)391G;*#^3wT5ky@Y}ono#&&Wat{p`mdrC~|_xQ2Y z*$#8)`(s|!8P?d7GHF=jf-o!>8AysrMe`dSgc*ekkJ7?rbJ$la6;t^XE>nzG{yf~U zhsm+51jsw2PHbg}S0EhE`eEKflYl2ycfieSqKUjmZQ|Sy+dhwEoHCHo7CcrJWZScM zpr5o#&V~pHdidISIJ2JbTVGvXihz6U#ouleIy$!Jfj$N;w}m-|!~ziW31L+cxRBE9Hzo~MF1!99SaeFRjYOF(s5 z0JHtlEMn6Vjs0E!lU;vMWiLBtKc#)x+Gf={3m7C_ESkK|$FkN-cR!|Su#-AD<#^U@ zT%jW$?S3t7>tfm~ClyvuC1^BDOTv@Fu{~$ineCiISjZ-@mI}u=Iou^rORI*3%fS6( z7+eUkj(Fu!Eqc3(yK!$n9={O`b3Y50*0@?WMs5t}$x4Mawo!CF`WGbk{R`=CtqO>N z8ca+~e7;HJRU=LM#S%@GeVW|`V5F)9+|lDeK$@|4{ApkQ)*??x!$m6uE`}q`!|i@3 z;UB8kAJ(9li6vq(1=SU8O4^Yytpyo8*n?{|^7=}5PPbJL48nr&c!QwY_5Ab}c@_C9 z_TOlutp1Uv^6I_C1&gNnaLOFGSf;GM?;fvJ<&62cgub-2%+Jh#OnLw&DtmDS$Pa5v z(lf}#&8nu~&(F`F@OF>;c@O&u_lpUB`v94@!`Ic0dnO1{uAbH(V9pEnEH_}oz?uN3 z#+Kd%z_kE3^u&02q8YBKic3)}Au{si_-UkUZG}({$A%I5 zPBU!Ph(`Y+d78Y;!DzPU$uqu&ix?VZ@OsE6y)?ymW(ejUP3;ES^9>}|El4=d zqNFphb24(n7cj46O2LrDXeCJ^udmv_4qYpLFY7#V2v7Gbue_2#=$`BkwhA9B5@i&wHcRY0V1<=m+M>@HO5e;+DF!D=WUmLF5g|71nKHbM*HIxXwpFG|AuO=gy}{ z)1^4*RUami<@IG^S%taB$QH5Reoh_={~Yv3oN`?p^8>{PysqZp1h_R6d?$>*Bipq( zh0&kqWfk?%CGC}Qr01wmd#udI-u#Hl5@rC*M>1iSg3tF?8%?M+8{Fz`vuIa-xBW0$N z*ut_nSFt#$^yrA3L)T1Mox^1U{>7J`oiyzl{2Mg8&$?(_B|q2VHw9IAn!lw{`&2NP z3SX93?!cRoBa#|-*yIKtlb!Oh{%kwIf>@$<|Fut zy-}r7U0y}3DAMoOHC}#`AVcYxQv9SQE`So{XdUvc0JqSJTJ9ezQX_?Js0&{)73 zzI5}-m1`Cobe?|I9}cN@tEGJTO6K-?jPkj?>x)Q%Il52+RnBpe2Kj{%8_7i@zKBuswS3)}}Nj*jhqa z(8)l+T7P5ix)Y*sP^M&AyA~;g3r+mfZz^+~eONiGT4YMi?8}f&7bSUqFKh%7o=;JU znItoM{Dk|?TIatUmp;^IxVt|+qoCUbK(WEOUOp=&fmnEN^h5;ai^jGt1v$T7VL8Ev z!V==N4c>}qjya_|Q}L6>$3`-yuRHY%4i-9yUFoE;*M)0kykRleSCW8?RCzW+-eb^& zeJe=PD0egU7uAT=@|`1M3Pt0Il1D!=E3pWZ3@Rl;yJ>`jzI0245As& z>FTXYs@QG;)|L8OZJ&b57&fSh@4pY_+<>WD31Qg=%JnY`n8&=%lglg~!4~EYhHD#N zN*oIa)@(k#aJ%PDH7exiHUJ$z-vM_nzq;jBu`&XJ5V%B}dnL0^aBNAb$ajGCI zZu3309`9UjzrtCERvJ0h`5XJxa|0#C=pR-Pv>#0ysuB#}Hio(HryRWMWONP>3Q1l% z0K}%~QhiuoCaZG;xSrBDEE3^>%n46%<*@q$G3F~w?xeqIqbc%kRernr?W=GkVGcFv zoJ;qq{mL!uLPQIMPw!?XqNgz5AzDQ(3D`bbRnzG0R7d5)AbQjzHQY_%-nK4<25df% z{tTK_X;oGtxNJdpG)VKk#0Y~dW0m~PUX=S30&W~_!Dx6Dh~9Yo`@-Mte8e2WTx-<% z<)JyVU$w88>{XlIj5VpMYsq*uen{L|@-?7rtmbU;}-&9G5_G4;+g7XQTR z87gLqy_!#}ATCg9hgl&{rSlrqTt)HdZH8D6bXf@xBa1U6Oq!wD% zqKk-N|MZzhle`L<^fha^se2wm2A&<1;%6weu{t!2;sxk)o zN9SuBrR<}FgSn=88LG6j*cPwj^F$4{Td4iIehO9Zb(SMZNbWO(<3VK!_RE+8Z{ zyEBOTu8{;VJDjr_qKAZ3?+NWirku%5wD#$^q*W3l^_wIJ9mm^Krb+7(7wgKl3t1VL z(_+$Y6E|cKBm1~WxpD|4Bp3G2rgH}699Rc3a1)zftCIVj)Za~{F!!%YI_Uiyu{ zKqS~d&t09Ag1ewO`0>0@EA#O8<#2j*zvw{SSMB51SFGukRwH~UiNj_sw-Sr*jx+`j zf6BJ@e6V`Y``e;qD*c-cQf0yO3VEk3LwN)z`4WmL22V!J@+437D9C#Yg3ot|pYUX{ zEiV=KSWsxBO^0ltdkr)849&@A#U6eahHmj9b%lIR4R!+al6IQ;5*XvDj*F$@S@Ucl zrj{;Q#2^J7aLUeXXOa!xUgtRSu&6gZR4dc1tgY2z`X7M_+v3?XSgJ`LFrm$KIiw)T zNb0y++TNzlkLVeWtlBKFLTBE>*1>`7HFbRt)D&P))BQ)7$@Zgv+M7s7eoCQnb*Fjy zzIy#fRK0eCs}7jXVW*I)whf%A-9sP8+&h*kA^9J(q_S(Uhg1!Wt#UplJvqj<$m4$l zllQ9eSd$@FyJ&&rBU8c#hHN^OF-pv~&0tQBvU=W&`J(sgCj=Xweg%wjP@WskH~(Q! znrhSw!|gU1V>LH_B^?kiK#rv>Q%G8|YCwA^I9L1nHO(&7Y5pfT%WOFR&}@YAsZIHE z4x%09%4lPpkqgQ%U57=dg|0`V2VFa*;z;LL(zY~Y5PH@Z_mGWS24Hu zA`fG2VCYm@YXJS~EaF3TqkYa?Bp=z-24E@{0q`F#rsQU@>tDSo)of6UNmk9)P-I-Y z7MTD;lD;%6I1m@~(yc^?k#}!G3jKdtfIii3MYX6&^TX6xF)%DW%t^@g+QlA_DCOdF zfd7>7g#?j0$^yn%Cm1GE5)A~JGm1*parF~1>g*jNTIH8v@ZvvJ?nMM{^)7q}2??#J zmC%mArmh@Ler@Ehqo`eZe|_}$-y@PUnNcg~WPyZcMvQEQ?oW`GE6YlUM@b?>ggYM; zYWT~p-gisA?Q!NxC#olo6h@EZWv|EJ9ojOnzyDdasevKSdB|FzX`epo)?CBJf+e#q z8S;i#)L$4ixHjOPak(*s^6_WLl#N?kR|9wBSANwgY?MUD_N8FXvQRXd-cN0!T)m;T z8QNraQOO0Ytc}He&e?##2r%xwyb4W*M1b`yzbC1ouZ(V(7NmFfU3Mi|F!hAC>Fd`Y z3$CX{Vor{}JHyuh_5<#PrG(F~jf{}cSo8Rm#7|L*2*tBAv<+CtnxH1$SF);)bVMU6 z?*ES6tXB2PkJzF6o~PO1)LB!D=MM~H>T(swGE?T6CWvxDB;JXFO&F~rK_ZGixiaA` zzvmIJA9UvD?xxkTF&dGDw-Io&tr%Bx9F57Au=(I%=py}x^wm@0$awU68@i_#IfC1= zh+o#;c!}lxPyeJ{g}vw#Rze&Gfe+V=X0lnDn3b;*8T+p&WeG@s0j;n;qSHf9rwojc!3j}E_=sw~&FjKI*w5nHTqDQYut zapYUi&+g~*VgO5s`!rw6gILGlgb7?$Ym@0R0vogfp(Ci{|4>Ih31XRHAiW9A6oRi2 ze=n^b$Q3G>D_xd>Z5hekAepceJU3)mHsDy9GX17|x!c;N?kA@};V29y-eY*Bv#qE@ zY)!IRx+t5~@3&?4z3)c9-{jY#)&6$6k=u>LmcEuMIVmY#{GpC*2rX-5%3KL=1sShe z<+#Aoy1Wz3HOkAT!dQxFV1+MPECM4rp7 zWM@qshK&-o(w(PjXL1NWr+TaWlA$E_o0WB4$2^aSPp=bEl{4v@-cg%Y+OQdxY1#eB zTN&`n-&Kznw8uYII$KusD4e)}F-^)^Yh&r*40nD-pklAFI8#%C^TuPF&H5IcU=)FF zRbG%`3?Jo(F2gqxVXkE}>Czn7+M;M0-}$0H8wAlaN_%^Y&ZbUReSIjR7co{$=<_x_cqL_b#$3xj?Ja}D zX4B7EJKWB`p}bI*dy}}4s{QH0I~_}fc5yW(#o00I!1n^-v6mM6$J}{=%z0XqvEc>u zGd>FfaY>588>(0B_8)WkMTFKKN*2lNq?m;KZpXvIylxH16K(wI_q2(zNk*o2!f!iS zO4DkOMVj`B|pT;35Hc0J$OZV>$b25Q#KexCECRm$3%6jHW~vkpTJ3 zepJ?=j=bRuKcZu2Cx(TO_LU#Gk!;qYoljR-972*gXgfCL@`LktTmh3SHa;aKmS3ts zZ5^Yz!ZAUN%6C-uyAqPMiNm4+p|YuxcD0J5{f8>a0;iqtBtDe{z;g6iS8HWBNs?jX zb2jw1RinZ_-MK%Bsog)sXNE8SMR_&}=Y0^@Wv%vV=|X_qY$soMp_#l@_<)$m@*O`o zq~26+*-%S)Vm0!#IqK3jZ)&TquRmt@SkC30f%!^z4c)${-a===YXk^Szm62-H=?E@ z$AIKB`}_<9I>=vRa$@7%!K7@XvfmB(B~`o_Xo=o_HZ`vbb;{;@>6(Ie?b+N4D&0Hw z!T*~m&_cV+ae{H*50KQK6u5}THuF3?*)g%{}S4+u{O zuE=W%GDOH)%%TYYMg-|sxH@HU|Fq6mgoH@-?3eY-tyZ{aWh*O!i5t%pKwkj#uNpG3 z_)V2_0Cm=-c?RJtwK}aLTc*&Z#5wH8qlA`#c$%pRX~Q2A-Wo)Wl0*nx%B1BfG;^4d zhdEHP5*5|XpJ-L(8Dz&3TXpYG4b4}2YnC6u7hY%5_ygjv+sr=*a!tFxdCJ3GEy@R) zcz*;TGf~@c8f(oT8{>Z*7Ylz@lJwH)+b8}vl5?sZ6ljKqBbRi8L4^jPJNdI|{DCRV zapB%H)vB>J{sGo6qkBNPa6$48iiqdO{0@jgx6rlMNJ$vs_%re#YShR(wGo$hoeAD= zS~Pu`wbXFpcLm~CYBF00+)VP;B9m2AR4y;7vi>oYqX(YeNl8iZ>cA`9*HF){?)Wd= zr#QSolz{FrrH{UN$nbQ$mHsF}it0o%MD34`0U2-O&6GEq4#^_1pC3t0ZEiT#!EOm` z_Os)W4d5euzY+MB{Y%xM_|%d{~U-hv_mX3*e?mVi-%5lhj=O~u%@7oK^H&|u#*33 zt#HD$K#f>L!~3R$=y;IJP_^p+*ERkxUb8@kEk*KPPolad!znVp*}3a<*f3kpKl;qC z*I}Mp_(^@DwKzO@Z~yT0__!oublW9&7sREk75KQHM6TiSHcUJRSlNee2Tc@NyeHYp z4JgFTI7#rDB9{|qQ#{ID$A`yd3e)WiR9c}0hXFQ?4!Dp>%^`&M+4Cnj!kcAQ!{wolpnpKThw+k2xX zt0;IcIu3Y^j!Y2Lh%ymm+5ukPS+n}E+oQ!oa7)mQKl6qV^38dd;yHR>amxuXy!zf+ ziw$z)?d!Ko(@PaPVgglJHopK|{?Q$@DBFp%ydHXmgp+oU+}Tf2TieQ)H-Ye!kNCQ= z{lCx7t`IM8OGCr?FYJI1UtTX>Nm%2a`d@#EWi%qE>np+U*E9f=r#j4xH{O3zH(|Nq zAEVaLt5Zv}bxwS)N#yl7(b$@V&KPbix^0^%P-z?AGe5p>(KFc99}mAd2TN1*r_Udu z?Q}UN|Jseai^le_LeBa(X%j@n@s_E-3O>#fQ)EpdSK5kZD;Hx-0ocO3%C~S}5PLP@ z4e)_CyLt5U+jpW0YI8Q1J7ZZ8LLwrH!C{L=>DZ@`Bf+KPB8~D;V|i=bmYKp`ue3GY z>X@FrnUqnF@fIm{i@s9Hbfis;?u;*Jk86)(k9h%^z7N~_L`J_M2caS=NJi9%{KUJ) z_(@q0)7!(BxPtPs$G^?6NU@-Uhv5)0i2lcsIw^}sFbN=Vqojn(FKv5K-;aja3mtm- z*Cp;*MA(2a#xj)}c_8OH#%R*YsVpf6wo(@Rhl+8lsZDCLr#pmfgG!Ta1%If;g#6o( z=cu!0K7xF^;4giMVhQeAEz4@Qrv}{-#V>urzSge>68yOzjp-H+ccPJh>kz_KtwIf; zQ3Uwq3+W7`bl!K!*>gk>N1^D}SYFCa;Oyr3L_-s6$FaT0z#kI=(tIlwxV15PA}(wQFs2*DF9j|DVDy zlfwdxsv*!%@*;$A|E4EY#U5N2f*x`A5ZrE+F*aP)6d6k>{q}M_J1U>>KS3m^5w)tM$1Die0t+)*REN z-(j2P#{md52m4or=E5s6sO_s%-f)d0J>r$e!FY_7Jo!sf8k}c$wRv}zUpUvDZeUpM zgNJE60bQP8p|0 zq>`lJ>l)1(x(iH4jwQWMcwS0;wf=E1Gbm_JagHX7m;IFm)#q6f0(>S&Ucy(pIJf0#P-}% zW4WT(iZbV$ELiFSa-rvbB&b%{&Eg!8++IT@F|}ogY_qRt>^C!kh`*f7tL2BS3mMuo z$S~1cHpolpR2rfCDLQE;Jf_KS1~Cuup^db^gcMGLzV75VdHz4+PQl`>1O9f z+#O{~>tC`XIKD2P1Z|%iv|-4vN-Yg!D~g+fTIV!*9pb06soMYA3kfx;|KL=-$7)<@ zO_UQ-S|z3VQq+xMG``9Zo)ikNiymuHGm42oj#cheY<5{BtfZ$ ztT>o5N-U3=#Mrh3ANcUgbm`wt|F>~to@#EEZTNMV16?vWV*5G_7Mh!7R%n)aOWuT3 zod7gO!1*w}kXRn@!X+i)`ut=FwbK4rHS(&Y$&4AJH~gjd+BLZ5fpMo4Tae3h2Crdz z?!2FfO?B*t?$GR9PP5WsbBv^7u^($vEOc)d_|9XF;V#Dd_QH*QM0X8kt4@E zF(m0>PH<0V=Gr3SR(qGVGJ%|826>R~gp?u9KILi^55SoM{tX8F1CEmMv9apvYMvi_ z)z&4Rr2(%*C2R?R{jqg%nTA4KxQbd~l*tIFq65yr%&$Jdud3Iz6s6E!2-;gG?Rn(y z;zo@NLrql-d-E`F<0lr1#m?hO8Ly*Ev30->=Xj zcYe3+V>5a*6X6tquQyid0~&#N+Hk!nOAWQwp7VB~KG}hkN`+d{vTuLd@~YOJWaYU@ zx{JGW8v_w&v#oTdavh&(>j>E7zbl!RSEUB$U;92@zx{7kZkg}b_$U~Fvvl2c8IhNt z)53E(t?}I?OXzo1RTa=UfZXN3oogUGTzLUVxrV7;m%MyFcYf~D%OQzMqdSX`gqmgu zl^06F-<*CK<+5TOfG_jzZx50Gm1RK7e!mr1ui2&Bl1@G-r~hk;FZwkTSCeGJpv9IR z5fK6RH`N9wyyRQZoQs@moS+ zCHO&ir%dM)$v|YRL_TWFG%ATwVId5;_~Y@u$wUxeZDms*;*AzIl{7uOW#+xhcE+lh z%n>;MDKp#m5POi%yiqUOTg*?8&~)1R6atvUqQK$;UiKAgXZz|CbAYK61nSzUB00EF z<2^4U;&34F2D13;pPp+#ati^^5d5%-VUs~pF`Wstg{Zm2z=QT!Dgmq?01@yHP_o|v zOO&nmTT)|d16YeyRJtN@!tn=t>^hOgl9bL%ktE3h)fV^>;vul*AVr|I!^LA|V$f>Tz!K+>b%r1!3 z%r?tM;6{5z=xAy05pcu!pgokdC0e@gg#K&P1JBMjOQul+!A2ET z2>-ejCBIahH`l+YR2CBYFONTWyY1L zt@s7_dNo6N20r8t3M6!F4STID(`ZN%3BatfwEwA}odM4nutO0p)y7s`|Er|ZA2JSR3lqBUFZ#dI)HuSq;A(UTw zTPG{R3a8abZDL|d81ijDeE17Q5>IOT?9P3P(+?pA`+xpBFUwj97s~WgGO5?O zZBbIf#>-1j5qRE?j_h`?X+U2XyT`POh8W#+%X+Iuv`ez#`3inaQP;tCh@il;EP>NdpRp6|S5BOX@PT)KFdwOKJY z-~@IRtp|vS4&f;Sb!vY|0QUA=yn?=uBG3QC zjMm`rIaWIj)K0KMh{;$p7{RL*UxxZbdU;lFID*OA_Cv-iLv9GPH^Uv zj27r~nFwga*1Iq?&m-vJ%BLo1D}j5ueHBhbQ94#xu1QYu9R_o=?{ z(U5pO61|?~K_cy2x7}Wd?jSi_vndCJ`z>;EwQM*8_(&bn_g$fT99R? ze2b=Mj3K!bK486Hl&)ce*`z4jVjh{6x5Ren-D^sgVyk(SA#ahc-$@~svMLswL}_$v zeDbVzL$zoY~Gy<=ZhF$w~fwGZc*kJ6v`VbKF-n z7SF>AaDvf-w`Lp>NCycKlRqJc%}&b~Pty$P%Eq&;U4yoRY`PJV=)%L5I(BM|T;0hb zc1lothm=8wtJK2rhqG|08k7;OYB&4A=F_3z05Rj+`!8T*1u$hCw@Y?cYQ-HdvP*GM z2*FeO^4nZ4{I+ZWq1;uR;Zl56ud-kwm9HromsIz&18W$Y{k+lx)YhC7^K!X~LCJ%0 zfsFEtMEkNSiVW~9nx*UW@*%nKH#igpZ%bIJP-UQt^N!h7@25}6%6Mr}pajzfkHYn5 zuYmSc*JQUsYrY7@BgAn^wyc|CLSILPbW9^B6sY-KUKA|D0W_iEN%xbH05nS&X*IiJyrIFOMIP+wZt!~;Wx zJiP(;j5$rD+jp?WyJx!ajO<-J6O0q7n+D2s53*D&-Si05z}|W-b7k9aiO!#W%%R9io!IZnAw5?fna(1}CP!X#ZE2m?VgmBxF1^RM1?5HS4! z&!Y_WFSr1}W!nUPPn=*s^mH$d!V)W(GPQHEX5b9><7emn2oT{Q4Rfsm0a*@?`{{G7 zM-k5)Qo!HU@E2RQv)K`#74~24y)^W9jn({-HaFcpR z-+zBaHP|8;$Ua<|0GjLP~q1+i1?nFvU#7iNfjNziEpnOO(((Es)&|E_TyoCrLd^E-7{d=ms31E8F zVBEg*Z$!zEq_LB;DK?>vBnDI1;#3PL-ToXxzDD`if9IpX%cXi}X)F+34Tavv!qeKZ zFnu(e<&`8d87Z@WsNfjD4R$Uqo*rQD?5wE2nJ~6vcMQPWlh;8V$e5CK`X(>~WeyAX zOmvk!6y9H8K$|+K{?Sqs`*X`Iq7WH&3aXHw{iXA4@$ydijdu01u?VJWac<-0lGeSt z-_+SOYa__e3?+z3#9vAh*?KpzZF_4L=pG5V?mPhL>oNLv!?Th_MGdK2qyF5ZsDd9` zqidK8BjSf$)6^J-K7PX;O^8584;k7;*F(`m=?!^hL9^30Pz2&aFq!5^A(%$hG6TbZ zJFy2;B%|ph;$dw8oq-6G){mP zYizca(u>Q8(0y%6`=(@L_d~HQvjEZCXX7}!w@7V~#EItWL!8saK+&4_M)Vy+sv>5J zt>sNx@Opf@^=NA%K4$Ad`RnviKF3wSiUzS11+`niZPhGb#5mXe4@eIJc0K)f`=Xv} zwbL?xnyZ)Ju-SX_(*=_@qaKo2GThn4n)K$eVdbS8Ze?RUn_y?bqbk>jLVKuezd+H9 zMeMV2#%CC%Q>F6{FX7n7i$B&Jx(v9n6!WYaDw=P@(v5Ono;i|{!!SLfk}0m_Z$h+GR^G8OqwpjdjtJ|JdJ9d~h)_ z5lxjyxK%d&A~zR7>=@ z+%x*fgoVwD)Pgsfy@R`1{JI`VZGhNv5^7tb7ha;rs6ojCndoraZr<0si(T$Q6^gWX zZ7`{SjcT(`vk7tcARG+MK8CE8XUMsgeem? zszPB{wy6urch6R=P5G#yVO7DwQ90VCo>j1izxjuIJ(g=6Zs4!Cr;`tr-hT7EV1I9- zchWV5J^vCAnMh~gqKs{>QD0fW(SmmO1+{XYSCx`^_Jr*?Ns)G*bjg*0LT{NbKE+;S3hBjnjJmo`P}5AC?EnIBs%jN(9KT z!81#Nk$gO}HY{5nL8|FMI8)T7(MCUc7Bz?>?JJ0-;&pF#?cXp-BeE1$`k1i?|GPBN zq~%0M=Y>t*yW9DT3%4xM@G-!u{`1w2_fAvnQqyA>Fs~f%=N&OIFtnIb!N{05CpV5` z+r`V<8&+GJP?m5A!&JvjvjpR)Kz0oKqTGvfse{Eoz=_-k->kRFM~kio*R8RtF$B+bIQ2u?bwiN4{L<%)mM zNDRshc*rn<0X{4!=|M)4gJiqa1FOZ2&0EVbu=q-aqcXr2FNW)@ia{d}$=H);yPd!M zz9r0e;H6nP%@H_&1s9k z_6VJu>>w-(QLZcr7nJ}}>Rs9m92#5f5IZ3}au34B>Z0}hwhLs)=l5{c_io+Kk~;J{ z7KY@6u?a6ezufav-!DHc=$EDVz=GH`NCSu2hwBCjkC4k`)R7V{Ke!~C0uw@uSHws9 z^u~&ZS#KS<7XN!#>XNAU!RGH%6gDqJ92Ig!p6AIcP@(KH6J4^W*5!=}$t56=Q| zw-rwg*^&77v9+n6E-4*)`u!rg(x&KBzJ=$F?ZLc5^r3d|%Zj;W2k9X4adQo|JlZ1! z<-aUkjTxND-Z6oq7N2~L+U^757`9?LwAzAe?-}q23%c%Lyqdzs#GD!jK@bqJKU`u6 zAW359Pu`>O@#*0q0tlItLBW|et0|z8|IwdWZ)fkUsYwJ$yD)y)U~bwytwh91b|}9G zkEptbuV4F~6nR`=Q`yG8jxwTt-%38yl9o}Asly@TGXZk&pCS1^M>qr%gxBRED0%Kb z{Ra>4x6OQ(hMtVaaN2u#c7~Zu7WG>57Ydc~)QG!LlSn}2!?;YyfG?aP#g1%G`iHEZ zWBZ_?h7aQ^-Nhd9W2ZNH2O*8xnNHZYzI1VHP{fd_y6Pj9o4tecJzk>#R_7~OcFtrw z=IZt+qiZfKx$&^|_Yg~`5C6*51=BiNDn@=`cu7MTT!Il&QH3uj3wAnPe56BDe5Q9) zbhCjUk)uoP3iRn?xPNT7+m;u9NaBjq={q$b@ns#3?ZCyxUM#)-bnI7TSHvk}2B=Hb zmjF06o+D)G=nc}cy7qs9ZXq%m1jYy7z6Iba&|n=F4n(@WeC3bJ2iRbHsQdcz!n%E} zqJM$y|Dx!H{bQRXs%?g<5X`E#R0b?dq3I>D$B7qM!BOuNs+)1LUD;@@o9GgtgJukL z!P38)G-A0M`$XRj$|a}5r9v?k+Qdw&YUx)N`1l1{XP0PC7_Y<`1cwBdw5QAseS(ms zI@ob_zr(Ct2+8%*E!#KZNBOZ+hS3)<@|z}QJl$D5b|M~TCd_Mz`sWJ zLaY-dy9#_uNx#dJ#SYfhd~hy8(~ICZK%v))mgGSA}-|c1(mp4G^>gVSNwl4GQbCYKSbW_PMVqV30S7lK$7E~s4sYXm8P{|RAuuTam z#w-R;zRd#>-K^&ez2fxnZ?nRX#t`81Va3OfD)g$*9EIE9nQmk?g))}0m6C#o!L?h2 z-VndX-8J8vx&3ym7oLtz-9kp5J;MWo2{UcoFV2A42~suoQ%G} zydNC?sE|O8#4=hV^L+?IWMuTmGZgyEvu8ZmJaRo0NHh4KbpG?3DWx0zpj>OfH85$6 zyiuu#!89HzoG`_KNeO6veOIqXdwYAWcM$VmxpEF zE8KY)e~8gfBS49BDUqNd46H(+Dt&kFARf;2Og+RYgOrkV{pLackEWnT>={R790-Pk-6sAECdlUG#?x8DRe)E#G-m^~9w>eIvF0@)AG z2n%*7YwvV(gatVGy6T{B1oo~I9iLGzbC)3}PVB~U(Ej&1j-Xj~+a4jfz5KFv@4%Ms zvtN?_ltc&iWHVqrmpp6+47k*{JgC7pH#e!N1l5-t8{YAma~;H{AU~+-XWmH%LrD`g z?yO7F$0i2l(dAXYwJxv&0gcxlHN)mAnxR`RuYGD=$ust5v~LgUeFU=A+@=Qn@Dg9% z{5oVm)a2d$LB*y*YRYe_p-3IN>!mRwzh8_)60tyQY-lPM{&sNgyT|}p(dOkotb-;@$) zwT6XviAF(7NIwvfjm+WA*|^)-8~||z83k}flr=V|G<0=!dBqj0G|?9)mrcjvMv>{U zjxZT%>HCiAuTKAZhK+$SIW1Fhy@Z3NsNXD^zRACJc8aJ_to^;!B--rDt*XYfi@hPliyZ$=SZfppG~^=BqETbt4V8LppqZNFMNrP``RXj?Ns1uZ!m+m9__hvp_5vL&~Tv zWo`f&5-5H)mqd%;6kdg(+C6HPKuKY!Z}j_~YP5r8?WNk>Icr2O!KB~Avag{U6Ax>% z-S_$D$2yu*QE7$By?k@9;3+jrEeCZ(#X%tf&4DViZr}YYLAXGZ`mVyluzvkT!8KUU zkS0141w6mY7HXg}oz$?dbz(w=0o&`>ub%>wKy5{;E zGv&nGPhKo|&_~vStJYwKE$?33B1t5u6a!)B;{#l#{nXUd|D)+F!=n1awLgS(gD`}& zbT`r+((nhQl$4b2?gml1TLBrQyOES`P#Wp(ei!Gw=L6S#;ey#~uf6sY_jCVhUW1f& zM|QUDh@FMSHqsS$`(1w_t+lDZb3v-8rju|m8qu^v(Agl|(PF(V1gH0NZL~>C%mkfc zqnF&<;NXW}z(LbHl3&~t*Sn1*7rfa~hzXZU1G$OBm46vTb84CSlq3?iPSnbzEx@?# zi;(OopyNdb;UwVU=H-DEi%;o=l>Uw}dmTVdZ=qEqkm6EABPTlxbhbLlfd+RcQlU;Y zK=0%bmQ-9UZqb+nd!>I@uXkW8u6K;ai!CUJhbNK3pX^2~ZiNAielD)w`yaTPUN3?2 zD1fc*Dj&GAC}JM$?7TBDxZl-jzs$_Cn%P~ z{Onlkm8~a^Znu{^D49Dzl=Ci+44=EsKaMMzs6RTc*>BHiM(lQs%oig!l0z7 znJSOw8q6j9WmS}HA8D3l>a3ZYd?9Tm9cKk0pCzBo`xJ*0H%{q(GckM$QU2rwK@!dw zzPz|vZs3%2v3|(RpjO?1lytrtb#&hk>hszV;gn~24;t1cp0g7 z6W@S4pdQ0np2SI+xd6_JV-KHm?uu;99E zud=xzBk_>u7lYZm2)efEQ#~u1;{V+Hw7Ya?<(`nb)3~t4R?ed$-I6O&SM-x>En$llH9ymw{Y4 zG+V*$$B$SfwLsGu(;nQ-PleS+9q+_^_s#=)`gj7x}x1Ami=0PPh?9f&c{ zZiE8>bHQ$kFtT}$Wi0Gad~Z-$lSY!7*##b0Yam;x?;LB8zLYqTPdpN5(jkz^%GgfW zP#bfT(oJ!VwA0_NQvJ-yhKL;$;A|}-J<{%4c1I`QxPytYWe{=wntDREvc%1frl^Rk zH;4oA_)?C7cClZ?-8L`!W@#l>-RRF<#O!k(ZKm6gqk0VbTtbd^v@Ur@lh$r7ycDY2 z8ZfCS(7+i2(@JoeQ+x;Y@<C z47QS18n1e3mj9dn@15ZT?2`t;Ja&|c=8TOj4%H&MZdX_I1?)93Qb-`HHHIaTP;=@# zZz5fUI~y}oxJ76xl11(DZgop2krLf)IkwJIa zo>q5%AL9B?GNMd-S^o_N%hGUhaZz(KbFXdOjJS(N2_7tLq)Ht+3O^d{)ON4KM*sV+ zKIuO!Rn40rskN!jOoB|x2VOUBIcp1=cx<7!ZH1&g<@IJ-d`f; z8h@sYb%DdLLV|$^1cJb0ya-tCB6tAnMT1#GBcsdb8Wb?+d=uvkPCFp>+fCg66VKQS zOvNMm(}-gjig-j~!f4axB049jApk=>rqZuZhzK`ewXqEj1QbJ6kqcw5{-$?|>o?~m zX{eAZ!lOlYITV#VY}g)TOtCo*U-k>rT-Hb(+o+rEkJch29)`W>d%HNA2q*RZ(wPYA zc`Q*lh|jI5>M$#dj0U4fjNU9tMn{C}0TLg*%Z1+Ze^!SV9SJ2iVr%>JXKhECNFq&} zZMNHeY2Aeg^Hcf{v~$MiJoX9OIzirz@QlcMrna^%OP0w)uOSJxM3}y?!3nr&eAD)p z4{A(&{lWD$Wl&WfLAO_E(hm&3Z;uz9QW&}NzuMAh2m`GOrY1;Zmd+G7JDA3BQuQRz z$l;96)j5KB5KW^gy^NCRL_!I8U6Zj3u(J4qjtn{KdLQpMR<{RmG7`Op8{G=Rym~vJ znvQ3tO6^m-Kd1s6W!YfwZ|O%V$&m#^1R$F-kkGC#sonrTI9)$`4p^&zGSHRYZJ zF2cirh;BLk*mNM>uJy62}2 zXL%>$)&+o^2>7PAA_Z_>0;&5oP*}>vkx`ZJ0j4z7NiW~{A`Ouhy_=qNrS3*1kjFH_ zgv7*-1hDFzR%>U#Z{|H|mP`Rkfx>o>%)ZhgQRui%*)-VPdqGVq$rENH#-+WyKBMah z47vysU`$CRy$fdg|oIR*xa;#XqZ2x<-YWvp5$=zmab z%3E~9R=@6ZC-)K~*4Tp6wLozlcAXrSHlvW30qxDl%x<%C!jI0gHs7alCMym$jj+PI z)&GNZ1XNZ!j;gY<)KuWmTEZnhFz@AkJ?ljJr(a`2JiynRBa+$Sk+jCN|4CXemp!EK zzokf~1XFFgHpT?Ktf+G6`@gbfE_Cl%2!W?OT!3Pnq7);s{6`|{f2aU(@pXWq2>5q` zfe~of6vEtFlSa=oixRCtGcNGb0wSUb%JA)d{d3{bE8pAUe@$#Mtv2NYz0$^cZr@)9 z=)CuR2{GLV1|rYnnz)*;P4Bs!2za5^Hq^WU^Yin-ZLR_KHk{IKU_Ylc9Oxc0&zjwj zzLfp_?acGvTf8PqK`Iy5{4*if+wHtbIr@@3HRgwrJ7;64Rr%RGn_+$MpsJoqOu5Pc z4~1s8v?gQw13Yh{M#K$a(ah6?m~XKb3^J#N@_6`Rl-|f5efz#~2wDlt`n4iS1%?)0DjW7mslF=r#04!?= z9sM`*!Q|GDMTy$!bnpqJ;~1or%px*BgH}_X7?X$=XDW@)TrqEY_TbbR2;7#1giH*D zqB}!ja0oQA;E;%vG~VBz2e-Sv-U&^f)@s^@_e>08T1u!E?vy>Yn&(nFNER{_9yek( zf~8fpkKO5L>C~i4_TJ|Sv%2bKiC%>KStfEg&6gF7biwpI*egYU%C^nwF=M6xW{;Hn za%9u`?_Iz@hE*6NJ_pIfNQTsX$hRY8wrTnFfHyK>y3Bp&@@YLhYE!Ybt_mff#F7_J z68&FsJ(N?75@0Um9nw=%1zdLtl)ofsOgv4ILVHnyR)DFRifE2K56Mx>*~p@OyGTFP z8%CWxHTfb9*+0~I(OL{m_oR8~oXk~O`WCGTxrrL(+R@~aam@G%s=#hfj-n`~WF6(Y zq1yf>Ef%g&p3d-Ei#H^3d~}WD)-@C+(IId*C6}Fj7EA^MK#*DtBRZ7#F||jJR&#=dzEt` zgk0#29LNEW%Ti>JavN0+a04RjaGSjB+7EkaG-v%fXBc&&Ui5(3F!3AV^VF#Haumzj z^q2DyJbe??$26saUN_WU-u+yqzcUW7*e3|~ABdtS!|9^y?Vn;4xs=|P7bJCj!-!Bs ze~0ai;yUgtlgIJYZ0O5e*4N1Qm8$=SA)a`j@I#Y*sId0c;ni>R$YApGC zv}=?vH+i$?3<G+&k`UnZ-Ct_`B_0_>W2Q!gVZP%KCNII!Ko%R3B2~}4%(WjC z#^H9#DxzKXM+K>9e4jIe5OBAjVV#8&q(1yT8vITNJ23tK9;Dr*ZyIDM0y4e zCq$ha-r09V0J20w>qh@!beeNhSZMIi(kW2Zxv=_!crEIeNrkVhx^%`xDQoeh)th9; z$;p9`U--7RjzcV|i0WPuk>mLZ(RGp8<-nr2MAdf}1Q*5ZRrp%^HQbVRFWWUrQbjVp zY|ezj+O{9LueftOnutUGsjk0Ksa=w{?G_B4k#wLE_!tA{|Il?6%mJU9*yeroxFNk- zIZ2=Wa2>9LUF-r?C_m}sriXk$5+GWhg%7Z0Sbo=;E_k4ntR0cmU&>}YB}+udHPQG18+`kg&jFMLW5yrN*{HKLP}X@ zMwPsvO{dLw-aoAdMyS@O^3skB*Z-#lD1|FCLhV?$wso>_bGv-dch_c0s*K_OSIAWo zq~S27+cu4%uZ*JO)UIdmMHcIYDV|)92NaNRn_JJzkzakfwIZmML8EV-aayqvf0sC< zg~9vTT@tc6rVyjXv!Vve8QkdG`bXp>I+pDdBgytRV&*2RT8c8t8F1yBJwCE04sBLe za+dSHwgsTGt2_g~rWrzoO_La4d2~PENLI?a>v3-)jNvuSs9Gzw?$1w!0@-hqS;!_} zynO<2()?G^ihqVUe)bHjpin)tXaMiLht7AhNuXcoCmhDiMC$1ur=ow}u&pBA?IkI(Bb`VqjW8$g<_;;92kM;g5{HST(DY z=hIY`wK(sxT)WVIK1@Pkk|`1tc|&bBe>)-);{Be27-oS_KHs@1b7wtKKCOQ=GZsk=aO*KpH(zPT{MaL zMS4T%p>e+n;LNzHl|oe-@M_Y_weKXyZTX0C_{=_Lm%dAYqVc>(`#39#A6}Nc;bjL2 zd3ZSx#i5~#y09fO5hL>>i}Sm!Usa7pRFDPRW*v{f7GuTTeZHZ1m+&X;g+;UKcT5L> zi);<M=`jO6KI zD(Bu|&Co2c`DB6R!`h-pOW5an?aNiOqFoZnOEFW~a@7_r4NphaE_T@;HgYSPmBs6~ zm8=8bX(%4xI_Ma5*xSszrBFJ|)e-4gCC~rqBZe#7(SGg^a!<@t&Y9*IFq`_$)j)6ZihJ&y&j0#pkY|C@d&BeA}aiQ7l8Ef zjb8FF=Z*E>xMiew4RozD56SIh*Fahu=}?osME?5SUe{=;-bh5k2^3#+O_3NW>#v3Q%$0$NSa-fssY9@+FE95bAF^@$qU zTWJ$U`{H`FA?Q>w-G4n6hx=s~)$F~X;1lxf82@Hn^)C18SAd6k7S&J@2vNJhLA4Ix zS%!4@3y3^M8*?9i&V66YX#93F>7H^FMuC#@U`~bvQG$nH{qh<5$#zGF4DI0jEPr_x z(u&p&;=ET9Q7`CdypM6k=i)k0Vw4P}u+g$8GMzBHKt+oofOjQy!7-IdW``ht!Y4}( z*K2r5A(!!2_gIF*qK;;9K211%S<#(D!LEa4Y{5K(#+csQ2##~;mYcuHlGJ}qfoqAS zGMCnGo>BtEo6DOI_-Qi+(#bA&cIqVSd^}wVXkHRi@b#>s*3a9fAE_^)rs(-GIw(4z zeJbR2Qc1n;6;vaJ^{>6`-Rdyl)4}ZeZuBN|Z>g^8Zu{K+qVw*kz5S3cRFW!ZlwQ^V zoyt;VoY6F&NK%cqRU?Y)ZQ6@7-Cn38BNgI&qdXFgoUrMSY3np3DeHQk%J0kf|M-U| zl^j5>EF3~a1>R}Y8r|Iulja0x(*e4ZrA?(y>lPD^}na^djcc{b%OFA zKU%Jqyur#R8jmo9Rny-23}&_AM8z zza(h~8OStW{IDypa>j$hF;NZqZfiK*Fk`m8?4ar}s=hFWS)`j}3TtHXC^_X#h$T}v z_qFg;)3fd%mcyjviKg4i;Pje~5YgAMStn-g{ zCh*XW{3Gr-BNbkdbm3KQ^nSP{SM?SuYK;9Nz4ts=%i5Mj%(sCxm6v4LqB>2-M`qLJ zLJv`^tQMK|+ls6w|CCp4pt_Bj%y*vRma&(@IinxBN4oAs(pLXonASzJ-9jyr*C;7} z?Oh%$0)oVLt+Hs&kwMyk+3)YReUAO(GD^`XgyZZ|b+&AlM8pc)Tz^9)aBv1FsRjj_ zfMTO2qGxh@eQlT4>{6L~z;P=ChIm^RUmWw@o8A`l(e>_d@93!$5Wxn%(z6>jffWBi z-sWMuApUWU{n3OiB?I*6FBfXlPBD~{_K_efVhG~Ar6wfP-xvOwg)(8)KOr|onxT8_ z6by{S$y#?;I=Hm_+pbQv=4&F0}S>1lF4YNUHeN(N8k_SR6(C}H_Xn#(;b%n zJ83DuR9E!@A!F7M#!~qgBP-7DOv`Z3rTY^lbF*Mw$4tG}x^O@8!~t7L4%6{sOtr{I zY?F)kaLPHn7onjqZge7f+FH3@J46-@K)Ol-e$JmGRFBciau4vWV@t#|oDkO*@&`7#YGv^E)GB6!DX$;E z5KyP#Sr+MrQzLL}ed`jDhu0*2OR=R+U>9w2yARweFXv33ZLTRES1Ck20J!G*`uf?? z_1Q~Qaifm*v$K;&0GZRa1KVp<;z+aT|MCsCg)r7Z0jM`R60TU^BtmfhdzXj!N_EFa z3AxWk@gVJ6fFd7{U)?Ik*T8@-20c2)c~*Id0X{cBu5(o6T05$O3d?icN%u>gbDYHf zYc~C9cZ_8x0mQ!59V-ZS3egMaL*z#)b~Evr$QqeOVHmZ8PR#&ezfo5QFO;(Lg~`BM zDXMoqJNE(ZST9OH=FPX_*MX&PQ^I_jFYw4;``3lL_9BKD_R6X9cMa{Qo5 zmF8POiI}&peKyTa07f0aQ1D`RderA1cR1Fog+G&flKr1BZs#QPjwjx_U9G*DWW{x^ zGNv)}7Lar5X{w_@Kr`IVkZ5o6qY=Hu-6YWiIPrWn=%QsGHDpzQgVj_$V#z0301HYk$zquvNN*=`>L+ei$e4}U z2kztWU5 z71wf@>L-|APwSpEZTt-y_c-2Ng~cU45Vf!QCDOeK#L_`K z;u89`4kc6pZVtjXWoxDi4(DJFBjE0pR3Jo6!1}dI74=|aUSw?Uk-T<@22~asMU8=j zJSJxLiO0f=fT^BwJgy=1BlvznsxV6NJkpmi zBr6Y|+yJ&&S7phN$iG}`$pg7NK6HFToN3>6-!>{0OXbu=bQ+_~15%HY6y!fBciL~Z z6r$SQM-^|_5V7fpV6AYXWbz;0xhE$l+GR4vKatc44(RUq=g>5Fr22nWNLQ7cf_+Au z@m99Ba;GB#>@gMFI43wuML7OOu08JZB#KZ7iT3ok@u2C1v7)%D*D$9JOWl2Pp%v4^ zwKjV>C{0oyI9pvOcXM)!WDQ#Y#7)BS%4FXXSrK_;OoR_iPqBe45OM5sfrd|1Rxd(; z`Mr&cC~}7Vg=EQ}K{7kJY#77G=k?Mc@uV+IdV{q&C}>RCNjAG-|1$cyUU_?A<3jR7 zT4gEHpv*DvU4{Jc&MDo+Zu2YaJTC6Jo9Lb}CB38eCsEV=%L9qOodjbtjRqFI`5J>8 za?rdX>Adtl4bFsQD@5A0`RLwp^9?DfMhJ+uC`z=L#DMBbU<*_x1-;I}+Nwwe9QK~fSq*kr9BhvJq05Yqa9 za`z&m*q{~1iYiwF3v!L6huigixE@cRt7G+pPdBPWf+Tkka64v0hJ;J~d?_Co+A`HK@i87v$Vm^+`V8kN~o*2Vy{ecHC5c>l1PU z!ivPuKm^0c&C%pec_L@C{c2OGmN68S_2+G6GtGj^|+hC>|1zUBqQxLoD|Z_5Ej*J&}g7A zon00Y2cN%d*>mu#p5Y{KD%-GXq1*CO>XB8FGLHv-2XVqNRngnzO~!p2@VG82DuS7( zyA5zTL5YF_qgtr_Lh}fD=Z~W6Vncox#(yG$ngRz(YaS9UeV&4sa4zMn>8oONm~gLZ zWfY?WWE#he^N~SO5u81C4>40!v+w=09-pZkqW7!QH^B(hC_!GWZLE?yB@-S`ho?IQ zU$fjjVbw-UKU-fX&Ww5aInK8+pQP~k&!0%PmqdU$0%73E4g8*+Zcfe5IsnfGj1yp< z`qbfe6Dzb^CH&CM6!pHm&n94#`(d;AQ!o!51SfMDF@w=}@QW~~@<46!ufm7b&MzP+ zOLP>XDaxz{Y;fP&HJ3V$S(o3H)031Y3|YjJu`RW@7T|ug#9dbOSrCd({8#m2WX%I5 zBWqraT5n-zv|dB_)bo3zX&AgZc7YD#)MoyTtTY+{KLsNqUOMVQ;me*o-WYE<$e=qb z;WwMw+ldL2t-B9fP9hk>gSiw}L8$zcZM8{Sx3NZ4LGU4h%}@ z85nG2E`tQIcGifLf}&pe9KsMu{)(m^Ke4PVa>-~$F9ST0(yApVz^#DZHyVp73xM^MiJg9xOV-{60=An9{~goJY7P{GSrIM~&#NV- zlLZ6iOD4-|%{s#&oA?HB}S>d+TI;!`=6pf#`^M2OhnhOyhZ4*d!u1 zgr@ylRo^~-1gMqWT9T#{R-}-qyOy_+lhHa~Qr`Bq46ZYMIfz!vHT-+hsd8L?nSM{A z${9#LH&9PDS}kXq1fY8UYa3>KL*Ger#grta8IQMDg~DMv5ho|`0i(W$&c5WS@^RbJ zwR(oSxn!IIsV(;@M!x;^V1Xi(+IoRL&_z)tY1TY|MD@hXmQYIra;tUp{Yl_?Gc(ZjxgG_Acg? z$jRRnws>!HlbxZkmAPP?+cwI>D#72t%YSsV8FqI%#NG}D$AEc&-kuhdOiVc57A~?& z8t$xYT#$@Sgj3puIzgzhd?fHYj7~P5Z`r1sc2EWIrq!+&qqogCmDPfojW>YWX1;kLNBm84 zc0OSsn!8YdWU5Az*}1OKowqfsaZs(M)Ass;1g71YUN*~9{Jx@Qf>=!BGtQrj%%y^5 z^ia;p5c5LzQu0f$e!osq`Q}7+H4*xonZQTJ55@4GJ+w#3lWX@9QCV8YODhy!b ze(JN(s}c9<-^fiT{3Xp|T{fM6YC_HWOzU*(XvGO~dN(X_@NF3CeKD<5z;L@QC$_M6 zVbt!|s#pH$M0qd%>PYl@`RSbWpT+86ZTsygd(q?$(6w!Dnp5j4mH@tw*zK9vlQZLH zR~LLMb>mM5l>VOO(2M{E-WPKwKYu{eG<99T7zzW993ZI&Fs*02 zj1+GlE?*RoxP5B<`y7?S)s5Bem`zE*(|8#dx?-Zb>1}dF@Em1jVM$$!z$`~<;7(Xa zR)q#lHN+j`cqH>&HSZ#YBS6#6tM&1Nr@Ai19?XYXEx)=;-l1Vou!gRf`d=^aq@WR#Fe}khucT0mt7_Cn=7<&Pk+CuebCr$DruaQSc_z}>rlBNkJs zS5Ao72>@ic(fStkS)-XAN*N9EH{dUD^!lw5`5DVC6~`6;74e1o-!|Vxl|2S_7N5C% zgEL4@nkP7n7O!T=MM$M7$oD?x(BJQ0wi2;DMI;w6GfA=~b z(-|Fw$k~Y}*n*Xd0{t3g+Jeij?=1qq=THZyd8^)XNIPCy>B#>gqcSI}5GP&q8T$C8 zstTIhp}&B=LVHT7GCIOXa)EqBG~DER!Ak1pZ88(77Zn<1BVPVjbV3r=S6^fFUkmvM z<@Zns%IJl+o&!c4h1mF3g=t|$5I#>K6sgVJkJG-tiAQkWEeLsr0C=`Ic)IxjC1RFjWJl;Z*; zp3pFL0;}@(o|{QPu?kcgZoWkXftt1*N3-0z6 z0Tag?W6|1wc((mBqo0-+Tj^WL!MCi`>2`L5_vS_Kcc=o7E)yTC%lx*EHQCMf6@r`c zCiQ2KUjC7B@pY_AZjCaEVC*gu<8M&x3gmBSKz^)G5>n4PXudAy zyY*5pm2AjwhZwU8?SHvN*LpSyKq<` z>8K`58X}gbH3-WGBlQBv$Oir5LJ@cP-=ZfW47$eRzRYSqZD}Kdf6ruiSM*$E)u65L z(9zSGCZD%fA!r&@YCdev=%nXoV`C@2dKB;YvzL;4{s&DD0*$nsoUKfMfKSWF$N*6a zecn*W2>xWgXLJ@`qR7PfTqA~ph9Ysh4>W9JEq}pes~?!%OG%~>?^{l?XDktGe}wOd znE3m=r^@wPH(@n=bQn7GIuQ=S9Ei85 zi#73rI8m@VISeyLEV$pkjb_PSot)2^D=XBE%v9X?%|AKa|KdXm0kPCb>?zDvk?m!w zcK9C)l^O$>cs6U@+XEY)HrT#qSlg%2f?us zTgqXc>jBOFe;J#vR9V$<7oDg%h(Zms-98xJWG;d%@=8!v+{2lu)VgEUQz;WBc>#$#y_B5 zcGY$zvV6szhM}OWWmdQR$|(aYvEhvN*Z8s!Yx3y>E6qcn-5bl2A2#bmX>vhK^1VlM)Xh3bfyH8gBKG zT?`hf=(7{Lynh+1JNqvo|CBlaE`;rFaH{W@d4`L2g{+7qgKVM=wmR5c*WIcB?Q>up zGn{^mQl5dU_k|N|tlpZp(^ABvnHC>n=&xt27m{Tw1w;&4fM%k0M8PrmjMYx&H-F*h zOkVg^XJUC-qnaR6K1nU=Jfs!<&9U;(KXJl_aevQ8AX~6UtlI~aHR`O1*=Gh$ON%f+ z|CYcA078M~Xaxg1n#@V@7LP->dsm@DgT?jNW<|Qdt6Y& zP_l|`(t9ar8x%_J^A-UtKuDZ4mkGJJ34F>Qrxp__@H#Bg0JKdT9+Dd$ zBO70Ud<2qv#iB$FTK8vZ`I17B)|)K8O-WPxqx5}oUg;6R=|>a`9GptFe9fNcl6XS2 z*_LVzGag2FbbkL&wq1Q%D4iVV)ibZI{dT(I((B;-g>-$);NL_Zzs#YBzO=M>k;k5r zr*lk*mGSM_T& znC5!9(Kflr%7~UrWe*isEa@8dZeHOU49Ddw>%5iB6t=l*mIP_lp+xZ06ZO+=gBlVgqudiPZx-kFX%wZ( zCZ#a^wN{N0hyUhC%%G^Ifm@Km{W>>=XR{GHxi3LSd^p#fNdXio&gmF*Rx<)e;lmZq zvt0ka{X@c0WwTL0q2f|xApdXu;w>}Z&}E5#fo+Tw=SxLaL7tB!dfqHiH-yoY9nf{* zAxTt;A`yD5?W)cI7bafcwI0l9C%Y_r^^2dV+3qtx;1=-17ZSdmbQf8lu};+A%KcuH z3iMjt`oKLGn(M`_%-L=>~np-zh%SC(n~bc(5_VF{yLix zPRGPXgwA@DyH9HuP0%nM9&oK8s4==a+lpg9j1Hnm(PBE}f#UXa(1b$c?S~F#2?|e^ z?;_GaZ}s2X{BqqEKXEG#cFL6;7L2|jguW0LP*NDq7&QLvn09(?U4yr#-J`|C%gtT= z(*W3T82Sv6QCA{4?rVFqnEr6$eeDmuPDjPS;k2K{FX_KFx@c8mGu1wPkL;`Sr^!_` zn)S{9X#w`0zy6cm;ZiFpVjxbCb+mLNu+XkXeC-OCTZ7^iF_Z2>XY!#g3qAQX1Pi}) zIN3I}CIaZ#<^s#I=x#@()CRujrbM>O{obnMiu^JLuG`BWvrQ&CnVVh(Y0Hy)0DN%d8lNLCgiWx>yT2S&>o!MDzFF6J+qlplFhLkc=$ z(qCGQG~g(q1ib4euH?Hlwy-GHVqz7sv}0d}&*inotq9u*BE6BkHArZCA?_fLT153S z{fiC_f5?zw{8=F0YDS}lu3_z0RnvvGs{p}mVpD>LF=U{^0<&4jV%LG-21c9Z0I6y3 z_=^Ca6N`=f%6d~fJdqt^iw)|T^ecr3fC8GxSF#NO@!eYT0jcRpgblu1{M`79GPikK zzTsRd2oR;tC-YY`*F}F`?NEoQdpd?c?`a90JRADwL<4lHh!<5FZ*w)ty;o+rS{QS= zcECYGZF4_RqQosJTZm}(+G#>5L;@o2{B0(&T$^K622U^KyYxYYC$)7ngHDN-$=`gk z`mTE0b{|0(trZl8_uo1BwMg=$DaW~dhE94u_(YF=i*;-l+Q$E`#S|)OY+X9%Uky?z zP{T0-C}GazVGEH_ZaS~Y9C_&|9uBX>9R}&}q@~~bg>q>K^9tw1&0|0v1URZ~4y*7o zLF27%c&!iZ1CY1SUEI4XV^qW5mYfdYWrgg^%pZ!0%Y~MZw<@^!Ulp0Lcjeaq#(*3k z28=~wKh)f(+f)>1W^|#{n#3JkMG3Yb;A8x&B~UI-{UKrH%|@C$=V}pkLjX5l!kbLR zqIYi_{K{W%m1QDW)k^9p-uic*{t9tZ(@NSYp)*0_e40#Bl+PMS6p4}@Sj&eEd!zf zs@h3$`8XYO*A0lHQ9k9`WwSQH$K?d^B!fUnDg6_V|Gz)^(2}}Po61$`!GSw@A%>D+ zHJDJN5a|BYT4OdM=;EZMrz?Kr9vZsxwi72dEYaEpK|OeF&s1(Rm@@^HCM?Ecuuo%o_B7zd=m37u;E@@dYf`c1>y*8V?+1S z(*&z(YUb$qjs5(V&RPJb4`_7X&fCt+HAYP0cmm~BzK>Q9omY3xn@KYHwY5xS2^<;R zSPYOP){V(@C1nxfB6b3U;sIzivJi=sNMI`2LErYr2&wj;$-Trc4~E`9I<5V8XC5scp)l~Q2c2~cg*pE5i!Cy55 zZ$5Y>**hY2b`X;c7STzEOCgk_V0kcj%1Xy{6D?RD*q^Z$eXW&3iiwT?rcvUJj$Ttd zZ(CQh*wlVoz?U%qFK=Fb4wubF2xq1;Yz=S-R*;K3Q^h5F2gtOwonhOHnvaYmZ89qu zdJ1*8ayoZ{Tj`OyTH(#e0}`qNe)l~OcUN~cN387Z$P%B2Ex^RW>*cFRC!n+H#NoL| zc06xMv$fl@n5Xl~Ko~E;5TTwiSB$C=HO_xpK^Bw0|1B)CIBrfSHleiF1EFSOpD2i! znD;pZW}JJsrw3izOD22NHcu)a_g_#6d2GtWFvUnk5TKLMy`pvQKt1E-{AxJ7t*5hH zHExeM29_jo&U~;o%pSF4O+Q55xpUTMcUOY}vq(2E97~f&ar|;9JRNu7q!EoEMNdhE zz;(=6mQ)lbXUJt+1lCy(sp$A zmX$j{P*jMM@jTbF;Tp*ZVCyadiZtAMw)AEtEylGr8Pg`}Qmu+vV$%&lU=Z~i>=p%) zFE#wl=~i))OP<}mT^zK0GuE}+B@0X>2lqgtX2PxsCUo4Q=8TNLA<$fge8!C2^YP{s zX1DHX(w3O+hB4H4m`8UKt8I4`!_&+RX8`5M-_B1OY{l>}_>r+_drq)rpwz>L#UDmh z%}`!qzm${nrw-H)n!V058Pt((+{e}-u+MGw-38{NN{q)|<=Pd~8p4VvYGMr2Mfxdm z6UUS9iWaHg6{@8&kP8aO=8_*PRlhT}JS%T-Yuv@$vdw)@lEtA%)VMRWdAe{NVTbU3 z1v2$}Mlp{R+0}l-Y2JtwR9%rJjzP&)Q=F*iZJ`F^8V}&EONO9sbB(`?TmbS&jLm#% zO65W%$|9akF`AZnH@4egI(VJf8VkkD2vhYP!BlctP$*P;qrZI%Na_bhM*$kvP+g)+ zHV%_5l=;t=l8e!+p6WC+)3OwUFLM8MnW1enyUfe~ZY8JX=pt_sI2}Kta*K5;KV?n$ zL0`uYbnbanhNE`#H>YHuAqc`SJ%dndWf@M5ObM(1Q8N|`2>R_E@HhEY-JX@lpulMr zsoGH}5BnlPtjJ~2lKN50cp-)Ms0<``U!DIOLG5!Yap7B*MiO@{MOm3DdDkOb8Cp7{ zf<&4*CMgwYTh6RM?DpzcgG}MFvL?qITQys$Zqg8QPm}H5%RuXB$%toM0Eh#=4mgY$ z&K4obLg-k#$gfRpjf!C(Nl+Q7x<1o#JB>qk;ncDc%CnvjR?c@OLDxi;tlw;T(N(-E zn(9y&c%rTGatbQK7i9ULM8E$NS?})6nVHnUidO|pv0XkL^4ST}Ds57NNMd1|-9=C- zbV1?jWfKxHTnHV@Lks_*zHgEls)3JFifs;$ zs{i!(!zS7!_e-orn0=Awwo~X_;q)VI^|UmM2RkWPaa$UVED8a0fSV2LW5U_B)8ELT z-fnHRr2imqXQ-;?Ss)2%`9t0&W=l;;2@+xOcDUb`ME4NMxlM? z7F1IJskJae3*d-$Ccs%!J^$nAPS57l6^@dK2!ggvR|NH&VUp_zhtn}BrzlU7b7q1cBxJ|PsUvxjH1 zGd#^FH)Hu9=g>;Ft|m#H&aD^z+>%5x@lw9!{KnX@4{55dw79>*)k#Free0(a zsW-WXr5A!}1Qyoo;W~^BL#V$fSThed(Ro^!27h4^Q^I5_K*y>GbpoQ2bcJha+Y#n5rL^1yK};(pCug;MxwVy-x8jM+WS143)IWh(&>wj z<(JV~Qo8R1B1>J85urCQo}0tj1b#=pD? zhcqSB|IiFZT=+KUS6^bRh!=X&?>VJL@nF}YjBnD2$h)_?PhlUyh|$jZ{JsBeBGeeMf5ha0dZ{bu9^#~ekqj{VANpDRrDOk?cL#f5U<=y68&5_S!#71 zH(E*`EAnS4y$A8#ThQ`S&r7-6kNLO1@{pyyF zzBA^VB4x%-J9|7?r+*U;KVCx7s(Oo%eG;!7Pu__O2f9hw)daZ5xOLwFlG#Ro-im~Ui##&<5`-D=b`JN25<@}$)Lq_2GYuOnwGNoj@&pP zj@|nhZ!r*^u!c(s*u~XawE-nt-oFwL5nnxOhpOS{c0X~>%=NWLqXw%EQ-p80Vg+$< zd0>;v?HQ}4u}dmwSSNhLrtUL7)LOt*;-{@LNL&7eZQVYK~x%wKaKwi;q!vWr#xV| z9d0;m=*xS>R2Ljlt`AGkc~0_x`iT63b%LF9^eo~-BW%wz8@I`J&|I~V&zpudO5pPj z4^MRf#wJ%F);6EhxNaX#Uw-<-*M`tq=kSOvbv?vNHWHWNnchDY%q|Cl3{4L!m9T@N zFWpjrWZVKmz=fKzB$OB&%Z#|zhU_&CV#NRnamO%u^&aaxPQ7wR_!KF%r^o)O+MzkB z!CHKuXdJ6g)U+so{Wg*dDQuvf0h#=yEuYQi%jH!Phg3A46dbeOS@G{4nvJ6RIrfa0 zujsSVBRq$tlj7wPgm-6Oh4jGCR0RIjNdBtPaAow+kJ5aH%duVTlwn;)Pd1qQUgPQ! z{oW~Jn%cB3{eY*XLS*MkXnoP>adF)_^r=Gp#~$soDmVs6_blK?&*(s;U2}e z80EBhvWjzO+@tpAt{3eKpplf(|26Tn^=b*k>1j$~3~`*}_?!7oL@+$9?Ok0OzQ~b-!2(~T{#p#s*F|Pi0ehgdpZUolExYgK&pOsoh(Sp9Rsks}iiZEh zPqf*(PJXwn1!Im`{&}GP4V`(w@av>p1|W-Q;gPw?woVyT^DV=F-YoaLa$xEd?=gY=ROuqE@6az7blpxl zG`h0&Jw8dDm+9D5YLwtGgU6MWl=SVl$>$n5CUFrFXa+T_~q3F;NQc1Ze&VHvJyI3LOhY*ec+M zhRxREhuC_MKu?@UnlxB&Du-n_UWn_)l;%w}bSRY?8r6i9{zsd9w_!Wa#+FiF(Zfg- z7!nt`EWf?LOMqtj53h|?XiCwkKkFZe#?LsCo0ZHIgfh?tgtN=}GO!h2LljSV2q5pj zC$DMb<@-QH3k2?X8680g)`)?*j7Crq@=4QaIOJHEN*YC}VH%a+1L~#rMT+lrd?H(Y z!-ViULp*cI=QVZA7N!S!ZPAnEKaWI^$7VTEiby5pPyfzr<(OQ6`cr4ms?b~51;Nt$ z=3_@`jD_uT)Tbq{onqgn_Vni4OYS2Av`~sQxhML^3a7^VU-j*fm1-UTU;BMy>`W4u zC1MkDm9s@7(8b9e7XlgZidFbFnb-{K)lk#8_0$DwUJepEv&F507?0-g1csFP7)zYa zW7@?nBaqq~G<;SYx11-Oj&LH577^_IO|{)X8=PSHL%VEx?*iL*Tgv~+-QOMfodeax z#SQm?=ib_}L03I)x7dl7RLF0Zl%Y)!qSY7};PR z93(r~IsjRG1mO+Y`ENFMH#H9aIHGUf23RRHS|~3K;B-1Rb*6~InQ`n=yyHF?u4uBP&_sfLpGtJ)rON`EJJB>;AMCupiwc& zzW`VReHZot!=$lt**J@!=Ilw_c%D_HSQL#s@{@XPCr|!0CPl%fqQ5NmB6X(&%S|Wj zkW5zp%sR2^)BQcu3hd)zx`bT1zo4pOZ?9&(GydgFs&Av7;*0yOYJM@RP*a@{!8mVm^UR(-gPmEuq2~b(EBEw6r1~4bgDWfN0SsXq!Zm zpWIWN*5U6_Yxh8D23>E@t=2U7TDg@*l4l}NCaM(lc}uQp{MWa?Wi2;4Z|%K*YI-;w z1$Jyu=y0pbx#6K`m;}xO)qb;emPC%dzk{cfaGN;7k)%;a6ZeyL zT_yYE((k+6tCMIK@*v*Dy=8IAhq2y*#sT~NJ@*o*mE-#2`CdOpk49%3IUZ7KgIEiv z+bt*t=M^oDU}N6n5+LV%3(M^{wqcT&tcFo035wZgq%b%%wrxNk`|PnMO* z9oO?$j^c~ROkjy0ABFmiyjOqh+8WDvo6!yt*F*%3{YFy;K{k2y*#>dO^vUhO0c7#z z9$n6c%|nPXOI@rne=Py=cAa@Q(=x>c`=eEHCjJ2G5L4~aRp#IOjps+~!@8EJ)Ui-5 z-RLLg`XU0dG5mCIa(p&;7tY~!#Z6alB5arr%Wn)`ktX_e-Fs|Z@rRr*eQ3WYrxftl zU#(B3`bBOa92KUfsEGWg$aKiP&y3BH0RL?V3-iqyT5QdAT6q0{eZbSnlG#1*Lw%;p zram|Oi~r!^TP0MvEP2)j==C|x`cxTwMq1_8ax7TlcZeAfS?34q=oZ1{|B!=d>Q(a= zP{0wcS*y?``&IxWmk8XD)fu?h`K~7Nekity!7k37bDcZ=5DG|70GxIGfoKJnOb5oN zvx?Roftk+M9+^n~83sfde}YTmN|NtGE<^ojyb4cM^R8FR4HSclNdeC_m8$hSC>;df zS>8X>zyXX_^CfBRRo>(eSR?Hb0z(AGn!zYnC)&1fS4`AR9*33)8})~I-nkZlo*_e^ zZ z96LgqIb&QR%+}x!9-NPP(I+GUEyoG(=K?=&v7(+`6D2&4W?e83&*5njNzHHPvWBzj z*8!j&en=I2wjUew#}L=7lJ$klhH?{xLOOPtoSD!0Ofh)1P&)V7Z{P5ao5DGAmfmUn zNj#%TRuJb(S@<|!3>24CC;%H{I3kpUIGB1`Z^hK{n{vNfm?Nd%d^v!P7r~Q4ro113K@j|n+Lwo+BU;nP@%Wv2QxrE>xM5j0c1MsS6Ls4 zfe^q#gIo?mXj!*JJQX~>!6Ol9KAurcUV2_u&M4`(vD#$kj?kHKL02p-oT%o*Vg0YC zBm6QB>tjy!mmJc_z5>D`q>c!^Q+XAvEd0UWH4eX&c6no5)+6Chaqn5Hhyz zbk;4<0w^*Wa@Yx>0?r$X;lZSVmb2;B#R7>w9$0BQ;Jfq;ibGlfq1Wh5!>2sNO&{9V zi&y`X4*{Y#7qOd6cN6yM`%Nt2KYGf4wjh9#zs$-1iFujzSLrNk=(1s&UpiV6Wb&vy zf10^`-D>Q=%eW4-^P#{*Z8j!X(xQ2h9S&@P0TQ=hn5=fHR)h^4mC_{HG@@meKZyqm zh73=ewp4@LF3lU;g()f&fPh<3QE}RWvSZ&4wzN_E^k^O8v6}kLB^RK#pZaBdK|)@+ zcMoc<`!zxpb`sQFXY_;fT_v-(_C=~<+i)rZX#RH->1LC^QPeuIcJGGbS*eyfft)4* zTAOejec~kMdyb>6361{e6|_APmcHNA)bM(?*U!EH!?r#-d1vfHR7v1GEFaQ5 zncy2-pd>u^yT5+Br$c2Mv+PMGii~7pP!!@3K)55 zAw2YDF=C|N24z+Jt_FhJs%V{u761LyBS=|_Tfb>ZfHASMB`DLC-e^EawMP_rKJ%~v zJ!PTwt$ZRiXmBAau!C)Df3<>kAbw=bu;3lk_89#jcwrTuT&mnqNRZR2q z1k+@Ds=W4vE7{PhF0`L;{FN1The zEyMGl;j-5E>3x#kGxj%Usy=b8#}@d)#(0)JKZOKI{^?A0@1|b&(c4y6Xxej5TypR1oU@j4e zgxb)X(jCfT%amwmbwY;5>sUBvy}h0H+jNdy^j7sWE7138({$Ff447u*x=qCf0kPg? zs_$tn@q3-tdHT0iJ!KA_3iPT!!Wb866ypJmQTu!88=sm3?<>jVJ;y)Lc-#DhUSk7k zB4%%qYflIzRs%^`+=m_t3s%9q8V4Cb)tJBVn?2gTT7?`Z+WN=H@J=@gu08eH5?9(_ zs)zD9c>GJAPxBHA0ca400&b`Q1Dp!E5&08LjXM9qcH6xw?Pe7frztti=%QVa8ES3_ z>0X}3*xND0O?%mD+{@!W>NX@9s=lQgiYoVPWM)K|wXgV6RAH9$*y53yqpG(-q0aJ} zbY;9RKFt`_|01!J!wjIpfiI%WPByR67(OF$F;UHbv(mmmFsu(hy90=me-dFZ!fY4T zKb2uX><{=3*E*awLHOyGf2V=c^!g2#k#6J~-MVOk9zA~6Tk*tMdS2J5P9^BD#-^Uu z&y5_+jr?84j_L^+L|Zuez5;aG(q&F4nU?PtQ`dsTJ3l>$rcMv$h>KTsBeNb zLl9b7wH&K7dsK}^{zDSv10E&w-g~Qxiq&Y*TGcol7sG(}#@J8g3o^1Gmu1+m@t3=K z2<~$&xUEP$>`VU!c$tPC_M&naInCj(!MzXTjlf9c2geJOGObpLqJ?{RJ{G5bOg zRAlmF#rBqcO$b*WqeKVAw^u3rcWw?~ux`_=G|l@I$)gEyrYj_#?P$MxAkAAjNqzsR z(rL2$y`n@QM=fUt=(vDbp#2$IV)1n~{Szo-rw~RFNeh_x+u?EnI*hNQwHkLK-JQ6N z#l5yuMaqE<)?hH~?wRJh_x@%0h(yH@CL<RAV zQ<;ZC2hu3-9VX%{xju|NeV|K-mqrO0xH4L#o>3f^iDdYrvX(WS@GCn?fC`I?^Ibk+ zf8GEP^z>xXPzTqzC|l}d%Ipt^>2*G;f-w78w@R6-!4y`1&yqTpBntAvnk)Nh@22~! zn5G2GM{FSj5T(8)F#IMZuefG%OrzZRlIhI18vtn9Vn*$%K0{m_NUp$ zS5!0sEAag#Lvop4KO{qINttu5HfV2)GH5EE(B8c5Ki?Gy@Y$^>c>QxQw<+;@H?;G5 z^!Ig%@>M@jwIu?+YX%|OHLFFdmoUPW9*^ea&dbsW7{L}n+l0QHZ~nZTC-ajIpRs&EUcU)LVBf)H4B#+Wrh?TeJ9wC2 z=jn^W%}FUUeF&0SXrT;Q1RZT5yY})u2{QA2jh)${>w@!V)6uJYfrx?}gd_h=wd3^C9t)wiaz0gRs=p zeXIVH1|HgkK(eB|jiLyUqB8|njHA&>Z?|yqWP&3;6VO@=tkHawx`X}>muN$#=kWe1jN$ADKm;AVbL$UlPSu~ z%N}tk3b_d@)ToYaVg;V+-SoO_E>ZF&fI6KCRP%jdNy2o|#%cxZeF8!U3m(=x3nJVG zau^W7nmvD2U%nRfet{aArk&jg zPqgi4y3)CN5}Ro?&jlXt!HD?NyTJU|9vwYhJzdi~F@oaa?R4EVT(f}J+rWPAvA3Vg z;C?fw@-T1?>($s{xPLX|iHJ7#4ub!T$&=r`9;)%}S=hOCC&gTA@;5iAClHzOhWp$V zq54|~>t7`97T9o0rWkza*(d_VIv{Vmb$+-tx*j<~pjv3(j|und14*Kgt(c|5-#^g= z8O_$;^D$F{`u7nk@5S5lAfwzjGy1OggnJ|r5brDx-hqJAr)9_GCw>(ZgM`pN#Gg(QEDf8g!o>kInp%ckG)Cg|>0d%&%J!t>Gg0<^)sTxXLebOPs+?&||H z5V-_Bc>Qtgfj1D#t@DYlsM@F&2q!=SwW=;guL#>{bDWvdjY4^tw*{T~b7ZfzfGX#o zM=M8Njp)yTtF)vEtM35krQ*~s%uC1Or_v9krn>6tGpo+>^w0G1gd|#YZS&Tl`SBbi zdTP`1k)Xn1q2*uAb44&YcQi16o!H3uH0Za`qMJ32M@JH6W1UAZlYW2BPWB7?=B)!? z!BO-r{O6QJ>I{xbp|(+tSzjQ~ zGt@~0db)qTJqW!1@Ot!AbXm&YNIF>ejEh;EU6{B0#(@VrnO`Qo>TDX0dFIo6-xJKM2MUmqPA$*73UdzlrQpy&S(4 z>NkmSO7;pH6!gB(k&u{Yc)n=OHmh!RpB9;R@~=+h+{NeDt4k%igtnM8uVezLjI)cP ze|%t*?b{uEs}C1@DxvqVe@PXw1bb@%(a;7{Ykt+*KcVag9%ze>ZWR0J_`GF%x}_Jb;@w^@P%Nxo)kRjq>Q?AU-*jEJPJ6Dl3Ic zcv`Y^aA>iy+~58&DUBS3(J8FcVpGM?U=h^ zcLi=VT={Q0G%Xy3_Anaj0wj_d@DhD_EXYXVyqc~*m#jwzZE40T4RRCWNDWE*M&EWF<$)O;km{iFi2rP4yxGWdcDb9( z(dfrt=D%3YM8elrw<#h7x^|KU0g9hMZRMk6Ex-=`F#+fvpEDSpa|HuV@A~foUq;QI zx6E85dww-4MlKmatzUSF;JSAxmBP5npP<%Z64~H2c)Chm3F&>e$7=|ld$LN z%Iu|yGHXb&$)t=vJPw}4`_w4#8@p^I9zwjJh^DHvc#9AXW`D;I`{@Y|uvdP!)?-$t zv@IcaJ^cn7TL~7Py6F5=R(_+=;E?q7d}Ph)*6Z56u((l4j?IfWxXRS&`w}R~T@|}i zmbCglV5yz<1A6$-7A>^D>vOb$Q4CNk@L7-ep)pTg?~V8OY|zFclDYv;CFsEd$@=uZQI`e1}lpSkg7lL(DB>6t}~m1Zq$)Wv#I44MWo zx&FSssO2Q8DgPMd$~@a<9y6HCp@uDeUrW>8Z!}@D#1C83#0|rd-UIVuz=w9sO>Fqs zy5=7Uq6KjY!*D^t69Ws;?HSHeMmf6uebXMZxo%c(57UB`m~4zc&T1jC&Tg!W!k7HV zU`t+Nh#zVC5h@lM=8_=TG7PPBv?(2>PM3L4A@42vQ)>u|ZfF9Q>Kb<`0vQ!zLb;*@@jCT5;RFB4nQLo7ECaunKIRkF<0_4KV! zsd%+Iup|(KN_Op-dt8?(y>Hq+5LYSpZ%)c3;AL9B_#s^@U%zFx^~1sNYGcQN3X;1N!Pc^rS%m(>>b^{P%k>wD)ok zA(9YIr#iq|1D!@7MPJ$JB=kB{gTrx13KB}w4PvTvAw}c0c1n79Q9Pr;_h(3tcJO++|RKL-?FYD3b?qfA;BMlLPceyRCw>ZLRkmc4O|}7uc7C zz-K`~P5kQi>U}PO&o1++i|6fQrV%ynaN^b5#U`hN3;#enyXcS(gAtniktRa&^g0%G z8@u%@C{qS^#3GG(8YiRrA&K`rX$oh88qQc-Pt>XfIDXy`H*QY-zka1K%}#kn-;LwWYFgSB>P{9#BKCFiGr&fJY@58=AtnAil2YyM1EaIb3> zLiT(J!-WTY$IiNiaFxz`kK82mG4=c=ITM6GUw*p>wvzukt^?Cl!zKj744NYT- zQ|v?gsU z0^5xHLn~6!gGmQDJOU>`!teENU~zE~P(H?S6X3}^`%GoDyB)~!m`r#cmrV1*9Ql4pPAQ3eNOw7TQd^%3@vvC`X9I@4>a z?CIKP6*uxdVS}ph(Og#9<5C8BoGdXz?Wu`Wvkf;2H8>K)ViWy(lZSstZy=6$gn0H# zZXc(-RS{XQYstC$KlS0+{_OJiwMwdB<{}j_7JD25>QtZWfoik4R}Z_gTZN-qj?b|_ zr8b%PPl_ac8^4SLc=F`{LjmFaq1_#JEie_9O=e;VX)6sWA-@Iv4yC084g$u&;$GP$ z`oXH~9Oa@TzF0CE6?w2O6MtugrRKe?J7#KfOsPteqiHU_JZ5qWeKQAa>5c$kd*@TZ z`1B4L6Ru;sh!;J$e&N@nTCER6Reb`}x!~@FjCPq6=}LEs+QEPS%5@{ExDXfPtb>^+ z!p9U$?K_TIPh?Bbbm?2>68yCOXOgytLYx#X5r_@L-zj=JE>7f?EoFoY=Hr0JQ>qTpP&d` zUL>?h@7Fo!cKrJ;b2f!;uB|}gx6g9`?M*aU)Q3(wTdmoaF!7hpggl3Pxg1kjrq1~Q zIY%MQm%m^Q>bZ`kKf_6g9d8lQ_$3LQ2N-W^MZLeq#3g_$x~GjAxy6yA>I zN$DXP;+E?1x6Dk=yS<%%V6$y!Ew2Id$2hwSL>ypUlU9c(!q=4yP1L}KJ59RfC0&V< zRbv)u|2|3Xx~-OlKOY3T)R|s_`NI9CM>03{UEbdZc6_!2mKovS)U3YO*tR+6auB@2 zCy$a;$Nnac`biY>EB>xX_+KNl3;C8_7$v*76-BB#)Uq5IB`97-g~>F??wU>uXM}Wq zpLau{3Y;8ZQ=_gPS%;1xlxaL=R>Plwi$yNM97`%rG0=vH`)8|O$zE*J1p!&<>jqjHScSro~u*if^9iNMd2$AqJ>kWFWZbo zlNMyr{6QnbCwny)ow-+|V*&pLyeiP&-*mgSq+&5#VYXlTuQv5#ALV8Y2GC~i-*P@} zXY|ilE0`&7ES8UMtr}Fdu%=9!bbJo52)-rX>&=OP7ZUMdCGCUYN)pHc^N*&{OG4l% zpA(}UOH2E#IEQ~Tl`|-qwH4#0=6KcI;*8&sFOiBw8%}fxRFvnSIfo?qjoRV*5yBc1 zZ6Rbj)HOm0KglPhGY-6cZ%(pO<4>yQv?VFIAx|Y7<*3@zT@TMuwg2s00%Ba^cf^L6 zc>{ED^ZvP}2sk8%#C6h@Qf#a{RW`Ff5X3SZDA{8%s3=*pwQS~@ZPbqO7!ny0;U8Jk z5FV!iYQ)#&C-MX1V{*e;;(>OWPy}S6cs2?Nz|utTDcY>_9*q<7NnQ5nM$HLF=L@MR zDJex&ktD4b9O=-%)={Py#Svg(*JbBgBHFf`6*!(&J>=o9iCvwNPEMIo(b7wx{Dm&d zfVAQ?Mo~F3Hz6CoAW!v5l}1Uu8G$*|6`1D&RCLIpK-c?~;(@5fp)SXLd=iiUZCLta z63I>!Om--^BzWZ)Uu^agwlLD0NNA!%@c3VT4(|k^efbCu1zt5Je&PudZ?D2?gp#hoV zHEJ6jRdL)LH(6b+d@j9>_t*}65s1&{mpky zx>R%^h@wR`|8{g#E=I0Qk*nBbDEn!cF2TAX-wszt%en{(&s^E2NKKFuLXH}{5)k|K zf&bgZN(tJIClJo~CTNLmEZgGBfks_xfjM?Va~>DeffgR?WAHwS-^3bG!+o}Bk;G_? zt$`y4!W{jarc7PX@41)ke8=XZ#&VfH$qE2hs%NyPyKXW<8j?s{>`P*Lm`7+Im z?mH~4y(|Vhbvs~N^|d_`l8;jt0mtuOF6G?i3f5dIG?mfdDFXAlY9~ch{<6aEeX-$9 zI?W`TT=ITHON%V2n^F=3!D?+(4_O2?^Jo5JpnM!T1;#tNHOt4Xh-~gIw7WpK5j-t_ zbe~<{eFuh2sZd=GV{g|={WqN2S1p)_5Vh9q> zHfTh({cVo1#4+Uar6h<&38MPIhK8Ll8y>z|5(K9?ON2HC?Q9b|bfhB_HHtI;W~suB9@^VqITepp)C znzq-9f$wyHD-n#wG+q`KPHTbpR}{odCHMFz$39 zjPbxXC=+bIw3bbZ{f5bC)t(MW5_3l0g5-4DD8QaM2>d6S zx1G~}u10PPawo*=@-j13k286?8<&V5p_lLD!1~&-#Aj))BkWFAv0$6ntzs}tmSnxT zY~LyvucY}1*t?WWW_Jmq2jga9ia|c^Sv0S z&-i{Jbn^2}3)j}?OOL??p%qJp%J=HhrY*KR!ot-%(Sz`!ESm*N$StJ5!!|6_z{|(k zg0Q!wYWEii0GC?1tQfHl-21~hY!kI_={rvWfQU%{%7HZY(Std^AJ6fse!j09$iiJW zGyO?}{G8nZ?M_WrUV-*f>PQfuYEV4}fLUr&mFa!55XNZy@3t_PJpc_|$-?g-4j{OK z)JH+v8iC#w;7lB1shHf5e0}zRi7bGC(?N5^NRnq9Hby@dCmyt0jo#oyYyqv@>gcG4 zs(O4w?-QGk=AAu(99dvOm|f$1c&Xq0q6+7z%M*}V68G=+6@_;2$9ok=rYeWW6!VH0 zk4aPPt=P~I#3m4xY|dNqi8jG>#$RHlnXLi%Ywn^sWwt`S|CLLBBAbfdjKikCWtXtx zk}z4&gbFDTl}hobj%jcA#c$Pwx}N_oR02GIBJcEuf|TB@g)bNQi=olfF*YrrDJcP#qU3S^6NQZIRyIx6 zRIdlUWrV8*#d3?|aHW@H5#`PKr=YasTo=T0 zD>W(RPi8HS`IQ}c$LsAP+G#{-%FgY1Z#L|>UKGATp<)8bFMj+x5fu?6q^7*Zy7^! zeUwdOlN@rRE)!kNM4OkXpkMGKVbb9TME-?Hi%eyxp#KAJ)?uf$(kI4R*1gS&H_Gr< z7vo8{ZS!x(x$_RoGE9qm0bgQ;qqR_EZ2qV94Wt=W^AXP;kukXS_vp5FmFQQ=Ya zMJbT$$<{w{0~5Y#Umy%7zTeef3B8Bt*08Ox&S)yb29$y$(&g*wH4LWApB$ja+s4x7 zE{$@XJ{Rn3UmovaLAWuBj>Zi%`)LQ!!GUVUChN?vxvcrV?>Md2hiN^hq&6|_t!fIj zK2|Rua`kWwS!(g;lzBse@DUog=yz{dS5Cjuba!a=F|kMmY|V1cw{PC<3KRm$F5^HN ze6a(^#_0U-G_@|Q^CAYG!f;VbDF~O*7yWQ7zySEg1 zi`)K=t8M?0YP<#ob$Ol%=$5u_qV#TSWZ?vqf=(u@$2vAzVblM+``r%OlC7rNBceq; ze)9cLsOwPc&9EFNeM2$|07XXss$Z&I6}A6A7eEhVh@uISgrY_u2V~pXLqWh~Tlbi3 ze9KeL6}FC+p7-rd^*@EN8_t(Q=+!CdTyIe;!?)5_b+yj&P;FJwdSFB-3S^3SPi)h9 zF7ZPKFI-oPiMl%ki$iK2M!JB1;nejuloP&k$sXwDA7?&^yFEW#Q$8OmkUoJS=r)X8 zmNOMn31~ZPe^y7Q{#bxP_C~XvwZVt2E_-$ONxAg ztI__~?SoCn`@{b8NeGpF-hz5@{qk{cKG5k1icQ}>0|`Lzpt+^C1V=N8el&wtm2#6G zoY8gvmW*mWZ%$V0{q|U^tE)jxtN&RzKLWpAPCiMj|KRk8a$~)At%q_KAc?W4#*_-^ z*0A!Bk9iISjq{gzmg(uq=wj-s{|Wi-te}%;L=MIfP>U>j{ zUwLnto0YDBdszIoMSbKwVG?`YQTZL=Yg8g9!A-{Wwa@8B-g;I41n)UJU8;kEs=8xw zy8^c}`PiToc953Vsn>&1Yx*$LxDbY+G2JwQ2f0nNp{EP*e>fwfn|cG?{%lETShI4Z zPAc&V3`-6o`(-}ek1_V+BEpfLuG-4Mf!&MGlAyc=k=FccV-!BKidn}((HpPxr=#;(wnAlQWS;wL zQ7N(;6f76gO^ZOAgZrc?j`A}ieYW9k1_{I5^?BCc9hAJc!3e*CmZO%<-;(YC1c>mV z#l`Ksy*&}7aT*JZdsrecylE&)sU1h#!FL}qA}R_|wx4C-28Qv(cuRy;J&IB$xzWl1 zb-h+lIz*5#`ChbTF@9mu=>4A0&UZ-9&6PtBZQNcFWOYr>lofdIFw5jtnp?bwtd4Z& zTN@YUrHPVP<7txIoTYE&AvY_tCG<>ZDv>Tt5)F%{15u!nlLK*WCz2+p^(RN3iTl=Bv9Kzc*jLl?tz~18A z7I}~4Q(t&1%|5b~?-(1_Sm(A73uk_9{;#edb>v^>vE_@5h|^$vr7m$MMK5gpV3Q15e;9GiMn;g$ZyLO)F%I zXKC_UN{FIFk%3QOG*{i6jWV13j^~DTrcSQ`b*8=Y^!Y#}0wmV~x^sj5gpxBJWGJ~4 zVP^&IySe!4d>KTHgIbadu9+SSazweJ(W(-RK68;QO;K8CRPA=WOe~CN*D*Ip&&$cNunT*XwU3p(8D6pAcJOx^!N>fGT(!DyfETuSf;SETray)Hp+`?$A7B0zui8h{`krMmwN3xBa>7yQARxMW(UlrDkJI zYcfh;i2hHb&~3>rhip`^v~---zce*Vl>tD{9B3JE_`^I*tel|%S**rZ(W{D~v_{sx}86*QMC#JLDW@ zx#9+^pn`Py-DAXn){agRQ3m-aT3<7 z|5ypq4)w}H1sdFi?6ISgOSkPI5X^Vn62w+=ohbDbUTIOw6MJ=ywZ$95y}GepO!Gbf zeo!Y^2vv@eMxi*6d%}obkM6+w7>9S)Fck$|#fT&?z z#s6am_VvfWGQYjWGN0KG1ucLcmrrF=d4(9=io2oRazSYvLL%{es@+H6* zx_ZZB8NfA`=vt(G=CilYY9{t?DT&O}?`!3+N}^*?I9ocWSkg*%t$9)0ydOPsB8Ah0 z?c3IfI5jL=1UOs z*b%*`UZybAawoSs{i_zr-@Xp`5&Hx-KFgOol9J}6ehyAD_tX&+{mOO5)&-20qhg#e z{8Zl{4B!{x{buZra3#pD{iaYw?Ifaqgc8avI9^1F#LLLj77qdF60DD`fDtFheO{^q z_yu5>j1Smn^rdkUT-=B7GZ9>L`iTd+<4V@<*Vn+J)R*kV#ay-g9Nq)ZFIPmlYXtk3 zxG;~nOK9t0#DjDz4v_%yx6ZmXn$^-uND@o5s`ClJnrok2{tOlvh z)7Wb%*Ya^Ubhtgybk{3}3%hJ1Cc7lM`(=Uhk}3{WqkjL1IV?39=@Kji3@$MVyI|1S zhDL(-q(R}~!zp+i4c@VrUb#tDAvIT-$}m1x2O>8%kfEKU3oGq<6&P(SDoh@y7Pk&5 zWCd<9;vwHi|4Rg6kVVuom!Hbi4X4Gfp9-4JRGO=hTBrP8Mndq?*Z!s>1Os)QMnQRg z{Rw(YgH981KWj}=ooBr`9v*|L2Q-wgFDUnfo|aA5T?4K}L9^4~oj--`3rzg-f&{kU zOTt!IsUv_1d4S_3=!>B3Qd&P~!)G|y#$0-U!#wvgC$X~=_}B^QKmSPz8sci1_RAfO zQGbp;icQUtv%>}1?$S7=Y#aM+q}Gb-niAv{Xq;YbBZbvrniKQOvz#P4I*N|2)efAL zTA3Gzaj4QC4;|J3--%yje{2|qGJ}SK8qsNiP6T(ryB6G`*Ecl@Ndsk}>@eZb6u{g=! zy9BhqW=2iIXj8k#eo7@IVZ9;gYn!+PX1I+AT~WuMosv|qJnLylkCGY$)+gTlUgGS1 z7)-*p&HBN%mQPH)On9$gVqDrc1nglq!xSvbO(#d1QK|cp-jyP3s4E`{X0dx)y+e!i zGSd9ym@wPZ;oKM@Ay)tG#++S_%S#{yD#OG9uR|sfW<6`z?b!6zL;SBVmi5V}Q%f(D zIN3^a5WIOPyA_v{QHt*`?B4Mv4^Yw>Q=JpSrnGb?-~#t!qwMyWn10jJT|rvZ;9Ly@ z|M4`+ds$og+VQIqL}3Xl-q3`|vGdpgaCZKW2GqC{TN^4Ko`mtnNZ%<*wnnQeb<$dK zYTJiKlY5^xmz*Wp#LJ*byFCfYOtge4GzIOWmmf`?<~M>fFfsyaDkPDii^OxjQmsFR zx5el2AYekDOrOMlWH54r1|}T<@wYX6&J01&cAN=#w2E0-v7VI38L`%!`C|>d#Z65c z5Rx5`Lq_BTF8NPJr%E#wCT+Y3hj=|LeZ2_r(uf}}31-6I89=1_rb5V{H4^4g+M^*w zP}fto%_fD1%#Nkv3CgQSK3&W+$cJB0M%x*hY4E4&PXh8iW6j_~QULiO75~=tKsd}b zv*$XN=_d}ser;T0Q>PEtHFX@9F){UdL3W~D9xWjsYt9cT&xnA2;qu1Qd%*^*+I$i*< zu&Zfg{OJthe;aqO(a?iI4rgTKfL9zPab7AHFGr7h1mx=KFzpH@xYrTPN;B@o>7M1tsbZ1eojf1X)xh}xyuPTtV1nj&AcQe=EVb68;O>` z2b)i#jD>hnuB)`@0M^=qLXj{52X1Lvu*G?2S@d5TjN%Bp@+_d*>s=Cu}v+avwYu~s`H7VMwf;~~^VCK-v&dIkB0Pv8E}tzUWpv zp0pdp=Ols1{sR1fpDS^U-7R~vLkzP%e@<%-KAgsEl1j`-aJ-p_^Cub5-R}wH&F9*` zrlLLzvgBWo&*)1V>bNkXCtactgt`m@0jnaqW)~wwdWFO;c_PUA(VwqOHPH9}vAaZd z+vcnojffPWxJdFCvtyn-QLjK9Kf~Qx!y2V)&9$(|7{ng4{|Bz&U~;TDp;{o4v^+`n&1w6oED!uy!GWV9&VR^ z3)DKHWd_6tKgOc0nQ(%PTKRW13b&XU8VS*4 zKPHGS6Dpk-3m5JPjs)B0;0vhxZ7G;3p4SS9KaZ7-sz{>%>db!)uF8LmMWQz-UaY>* z?qA*m76KZwa#IcT$zfb{mxR$_3-LOpyE}+dk`l_D*Z!N>A?DKI9FG3xBeD&R3dH!T zN8Pq+HFl=}5UX{eH?>9&9DQvV2SsQtW_H&#Ej}%8D9s;Iqrub0jik?XTq`Hx^88q$ z_);wNza1j8Srxwh-;Cvn!~68Gs^ELAQV%RNE@=B^*N*N1|CZ(AAEg0e)PNms7?1$hI3+hu{j&Vbg3=Q~ zt0l+ds;T@=P7}bA-n*Iu0+AFZcMFASClMY(yYeY$W($%$K$sYkbjX0(>d4nQD=uss zw@GV5H4+jhg`f9L*I{+eSL}jg@?+H3YQj+_;pOSZBkhO{9UX^XH0x$B*)g~mKSBTd z#$5ty@c#2c0F^o}r;#FV{iMgd8Kd?YQ(|N>yWor|S6IvNKuP-(#z85@y&+PhuJY*89UOO42Djg^$hQ(w&G{QOa2 zw0$1xS__51iIuX&vThFXe-%Hj)imm^Nr>^lug`$=%@i+>2puAubKdA_R9(1_iT_9U zT*S@#?mfa632~7mBHfViytEpxCx3mymVi)}g0)&UtR3r$AwtM}d?}HtXNtMkHxr{= z7zKV8N_6;CBm#`pgXOnc60xnU^C&d3U^F9J4e0N#y5vP-M5%%J z#JHl_-bB03$#BoGXlh(i>fh8?vX$Z0a^ss{hW*gNsSdqhfj};z;TBG59gA#5n)!0sXnRb9uG-r~9UxBKM)uZu9TGm=Z%+3PA()521YZK(%>! zdD;JR{Rj+A32K1Jt~+E*E%1LF*hy=HL(5{Ba~u~y#Cv*9wBfTwDlW|1=)lowoRlvh<_lw=S^OLU>LJaDML+;HSAl4+tH=e%1$~EBQLL)*g z`;0?^_H4~#2Z0u;$}O*V)byYvek1qa0f%DcM>3{(;l6y*vY&B8q-BNquiz(t>`@^O z;W(pwdhdr0)cwA9dMp?2BKL%2zBAj|d{aLvwwzf!>%8J?u2g$$JKgK9C@)?ux=qKU z08Eid)G|{u79Bkj2wKdZ-a`W>b6V>MF92Z{aEZCN0C*v3T0h#E!X^$b=@^ot^MC39 zG;^=5pXijGFG)X`IVgJXP7nH?k7fFis4NHR6(5-2ttT;QnVjsbXqmQI(RL|txaPlc z8cRh7jYh08SG7pC%Jr$oE5;Q^9fEsJfqq|;K&@rIbz>lEQd)qtHy_lvLTWy1bto*&E4pa4~G7UZV*glRbx#a+gA)5^a@7j3LT*k4S zm~7p&1B8eyXUvYIVz+MMTTBJxP%H{C z0`WY-oKG7>4P+Ym@vwTxtl zZ5vsdy;_^@w$G+c_PQ1ZNx6OEo<)58a+f#*!*5h(8%b~~0)nsK+v|#OvF2d%Sv*mI zZ?|hYv$xu~Ruuoj$5%bKIbk`jB$0a}NC%Li5h6f&Pk#J3IWewu$kD3KppaI-(NC~P zn#S+BKmWTYc5kwLZSt^11y=SUJ|K-I^FfubC9=w?YBrdm17RepW_|;BVKnv z|JM3`(vDAviXg1}9ymNd3a_ngui+g<%Xy_!D8`}}{z$eRbDF~hr~)8Odn5{VHA zYsa@>`Ep66P25Yw`u5pmwT5m~v=(bbyZftAgSvKO8og<_xF=WefxJW@aVREcp0lCn zhx)zCJ3U?W4hT2aAwNu`O`9F11c!REud&aK@?(Rpjs%&u!25PIP5c3ACL~%Y|GZ~L ziTw-p@`b^{C2E|Muc23GW*Q8JPPj!e9gps@500l!CU5_l6|Y_%4=0-l-CToox+42> z&!V^gIUzh@5}8cR5l0-@wWC3qjavP#fb})6DoyfWrjaPxYRt&PQLmG~aP4MLCsFHF zkyDn*8&$jbxB->Gdc_cC(xs zE2KW7vt0=W)pa?>9h%>z$C-4$eX&y?x7~XKQ;Ur)g?7~kwkd3IuT-79O2bLRLFdq7 z%*QbE{AKH7FkLeUCqhD|n`Aed(&!z(R~JB4D-VkX86#Sng9r=AgTwXy=)UwjD|yy> z4Op5E2WK6PE5KF$hO^b<+#LzbbIzg^AVTr1@)vOOg z?n|1UD*61EXE`Q6A7*a=dipTGKI7mWHuut#dH&p^oPAtZh!Q^MFmH>sRQcTjE(ZFT zND2|(9RJS4{bP-cEdqL){w01L4YF9PJ-h+_Z7vyEctbr@6Tfp!h-B{Ldd05YB_9TO zx)4aE+eY{$aT5uUVzZR{lVVNv??q*obp>?fL2qQ93Iw0#Iq=4QE_^pb@(k#NNa9Q( z%LVbBs62U6sHk{?KQQ;tfE}-Ao}g#V5W2PN`r^v(w+-h&t-D_Y`^kHTdRjjWw1Ssqrj_ z|4PuB(0oqwN@j5`{tXgy<6x{Bx?~@h#|xno-{2}1XK~`p;-)?(rB}+>XkC;>D6;U^ zkY!s7gN#T}9a?UXBaz7RQkZJ^v9fj;Wb9m!hQXk%Zv7Rt2ZstNOi6~r^>vJ&OQ?LJ z^fO?Xp*^n--0OU%u~J?&`<-kiA94Tc|-v3201Stj-7tp4uk!|)E*IhHTo4Y|8aRHLBQ0v&TCFI?RD^% zs&_$F)V8{Gf4YW-R3gN;*z80p*f5Cp-`Br}iHxa8ZQ>o>W^-XO);Qtdv3_#E6;k1? z&yG^IiP_C-t>FJs;Nt%Y&fQc+{bD!A`h$Q&D?}M$GdAhM2DoSY5isbK+sl zrouQ1DFpEcC}eR?$j{I8PS}``@r~pI?;Sa<$S1Rs+&c_p)yB0a31J~%@!S_XWPs;aa- z@g#xQ_(F5{e&AEmA5wz}E_SZ8zLzg?6(B>AscJ38j6M)a-CBcuIv<$ZSPtqXdzFP3m56q76rv8#;Wy+CnxOu zf#w9`KR1{E%NVXrJSf9PJ<8?Jh%Q+5EJRViiHX%+Wg7O~Ix&_qA+Tb}ZX>WVO;aZP z{Agw>g(~_Rvn~aey z!e5+h?|x7GF3i3?RHex=y8HL5-1B}g_5s)_1OVe-;R6H7x6x8_&>rG6ui>UyeSJCJ zLLj8|6!|sdu`bT=xB(s-Ej=5(n|t~;V3DXmNC?@C+N(xRT)bMbDcJcQdPRw1*;W2a zx5=@Wr0U@bVyB4U{e!J4ayF@A(uuYDuArFiI1^2;{68c{v{Ra_F;|;c?Js>QVlZ_O zrO=n8j?)BB7{Un^m>P5N9W|tDJD8HPc#&xOd?lqMCZWu*X$|hOZ{BofRoFgh^q?1AJ{a_(R-fGTTWQF!(u&R0YG;U2_9^}cH42K zOXWLNaV@rR!$S=L)W|ArHbUD!FJCG?W?vy+Txr2|tuV@Hh(jS_6_*i|3t;vxN@ydQF|Hng82FFOyV0(e)cYLl(CWF2#mMra zEvluIO+%6v7YF{j@)$dz&$6W@Eme$r|6Ld4>=K*WAbFu_s>{nC7|$4GGZEGoL!f!s z&Ow3*vhv;E$;r6B&Dd>r+sihi8B3;HSEKbO#_@ho&o7bD>Mzw{xq^%vgVARCJY|e{ z>g6vhZr^^dy=TrB?`(Ln{!YZtJ|)z9ClY0)19PRY?o`_;GSHDH)BtCA&4~nmbQ4jY z01F7n;#NmBnm@AZt%b1Pu+ej zKuMqV1H~0*kIYzA$7dQ}N4pEZO~^A-iTcS6CxSdYQDeE)zsaCX6c@pO5o7EwfT*oJ zGBuAkXkMYysTJVdQ;urxMz~=X674C}a^Th;L!PI|P}%zo%oFs^e`50Dp8QW7(~G;D zZ@3k%bi{rj;})3e+NqQhwnjNdcz3+H-k?lAr&&R#BWe8$ZQa5|2JojhCpSO5389n7 zHC+s*e6i9IEt7@S#$|lG)5+g#S56m45b5`BL@S%53LyaVd$}TnsPVGg8BkROLHy+E zLGaDVL;=uYjV9J$h&LUOu4AWBoKB2a`nlGJb_TUKp@OkB3 zy2Qk3gESVFgf^D~G0O1g>5mfg<-6|ytsxkK6#da$-Uujis>Nva^N^UHd$*Ta@z)-% zdW*V5wlTqihXtt{n~+K&?-dVl)hdzI<}@>0(*-J)98St`b_|JiTZ4|W99r^c?>Pz& zQYDpsI#AYetPtc{vmZ;GwWDSHTZMK{)&HCRzx&dhkBLjPd zq8~!^udgI$q8~z>#BA2iR7|=(a<%3y4XFiUayoltu>E-24=Wu%O0xc7k%oktH%bbj zODwjwmqEte@vrkd@?SmuJPMH^Y(6JNdyZU(5bE$69}bK0DwS+TL3! z9$H;m&*TZWKn}tamfZKt2tk8ZOIc@TPe$4XAF}}l!KR9%OCd=u-!U*+--*DT)>F z38TddVmmP-{#(msG7AX)HOf|CBnROnMEuGSl#*8B9-H95bFgsR4fx4gU@~l_sUWB< zNn|y$5Lk=uI1%nh=F>tjR#82OKs9U%ePqmjB>u`(J}L*OJbFkUKTUp({q%YtyW?Pz zL+F^7mxdN+dlu(=NS`lzYj>#G&T}v&!8`CGR}Xd|Y@#97C9XLb$&Dmz>(Qhx;zn+2 zmdnG{*^OH92oKi4-AkP_QJy_9m@ip(I7?`OB=zSMm5TlV2!Zq4oa zg3}7Z9iy!s5F{yuy?}nUb+&&}{jKN2!Ah)bxP3$hw!|8t?+>p7YI&ogKGde!UUi&B zU7N_9R_R}m&A0CW+Zw7q^BJh&pylNFzW6 zI+Qdx9B3cBo|2`5cz4IYfQhQt1cTeo;DtGa{X)Q=#v*+$52t8QBEWQp^}k zG|D~K4>}86a`k@ww?do|rJ-O@{YOK^u*^^%IBu zbM-QvY_BymyVMQG2HbGtEBv92*}7~6(@lpT24z--%c}1Uo?1<*i>6C!M^<(SV3MUn zr-O{AIZ!mkOxDuwv(gHaRWS~&I9?Y1}R>AGV|eipMs^mF0mq#sRh!cyspHo*t{ zv&9Rqbl4KsqZH{Nsza+O(jAj43G&-jAuI*K|3QCx+^u%B2Q={z2mwv-3LuehN{rhS z4iC+x`8r9y@1?OkNZA~JTwQ(8T@|m~7<%`$GLt{I<$ImiMqjK#zU17y<_hH{jncuS zMJBvNW+EqfbR%$Q|87I@*xi)x9l=8oLb$I!vs;QHcO8*QZOX_IBApcp8qR?cE-W|16=9k@ug+Fr7SHj7fcj9`U;zMoRjt8dalj{dnNKy!w_KFbL^1$*8Q=87A3RZLiIDm z-XDy~h5@h(Y(&;MW>xP4xyY@$9|_?OKm4Jfhs^#=qRrfosR0@7_Y<`;9sOqumB+na^apq8T0lzO!-x4sem3QhU@Oj-h`T*)~f5gd9(PltCel zbdh-WsviH?aqF*R$(Y9qpqT~X?bGExdEwDTD6c;ng!+VnlLMhUXdbXA29IKnk7{3|IRSh_fr_&)=W?wxt z6tmMNe))Sf=gU%U_u1zLj4{${h11aR7|8oKw99qlcv4k2gv`R96AKN>dWJyMO2B#O z!c+a~K4j&)gynB|y+*r`F9VYJf@z+4}KqARbd}SeAR0pw>7erq(vSQ9JAXf?XQ16N&eW& zxM2tO8|6!aQ%_&z(5{z8IH`9vr#)>AB6)A0=JQO1R$3zZA$NW7p_hB~y?JR@;>yF_ zO5x_-OoiqJ&Gl?EKN5PTYMD}tP~>aKbj5Q7 zO6W!PPmXqsCfnYOC1CIc!x@014UFb8a`dz6|<1k{q40l8Z>i*J*(=X zT890oDwa#P8v41d*yqr6zZRj;)H{nH+0E{-?x#OjWIkJ!vcO{{gpQ~`U{JQy;wt1G z`zc9*m`=J!{;@%tns1a+8FOD`K=x6)^uJdEcfx2X)0OBk%%UGT;Rr{t&HvnZJ_#D<`fG9j91 zV#Y>1ZcTWJLwfrxKNnV*zBSZ)5(=@{2dh^8D=$G;1YH7KM?)^tZ@sT|nuB7(r{C6; z1VwCnmYX-O6zVpf5gzJ(^syTm3{SuDajV>&IaqGYR7d*u_Rjh#9_{3p%V{r}p_e^u zn&m~FqZf}4Bg^+d5UE$x`!7W^9?j6Vv&xNQRSu`WDR+UD!>Zbp~Pk(?KArEvv$XoZqS#H_@l23Ut6P**0>s7xlC{*!D#5pq2}ml-k6M z1V95}j8dMkJ?ECal<#XLS#bos%yECsryyZiO-MljS$C~224D$cLf*#xXu32+;$vus zygYZ8I^^s9jM=~@EWoi*C>lfjDZP2FdBgKP7gW5*hAxkg6%Nn(xB5y1;;n#yb;a+# zavIbZh-G4a)o!5K?6*0PXjVC!2~mB7J)lNLc`S6pv~Vhy&Rq6GoD2A?*9KBo_%vZo zWixv<;{EtP$e~E*2bm9(g`!cvkX;Q$t~~=&nDqsMQdzGvK6w)<5rH6o?Z|B#G=tezsdmw7ZgI{po4=|*fb81NL+?H9! zh$=1U70);NMX5i;!b=92h`Ts75@mm$-Ai#4shDlpig9hGg9+AAL#c2zk*VW?Usb3AYT4-LQf2+$h;Y%N$;4Tu%5_U=>m)Cb&7 zXRoT(J#_fYcQ5-Mw*0&u{0WKEL}zUWd{LFmx6*t4Z&Zv)aMdVZI$lK~YIPr?3Vwz&iqrFaMgUgta8A}|WB##r zP+N!0ys#GIBfc80hMSUb0=%~1eFA@vHuvOcrfdwZarZsDY)TwidEh|?-ZC2Z5@JE%m7Zo#L@Bebk~y@_JA6_413-*p#ZTZBrA_0noq_zAT!4T z#$dlj4sWI^?tcq>I1w~(CGr%c=i|fg3qHKzy=gSAP-J#mX??K@bfo_$0yW{c7ZemU zX1w1Y&$#b2XNF>b{}KZ#*MJ{pJcRh0W{xkdv^pxNn2ver_7rYnN<1%B8{*=2M(z}c z+mn*ySk1-1P-yh#ElsH^eg%dAk;NLY)eOfOcD1YYCjF1ms}`b1noD*v?!cWPPF8?ikR$?z9e|1W=+iUz^XTu)CT* z{NSx5o#@z^@_9xyqBJ78|67_XPS-e34`p8{pr7R>M2k-c#bN)KW6MKLKmVEl(job+ zJQ2T-dE#T3c_}Y-f*ZcsE8cPS%rEuk4Kx~Z?p$XSIok~UJO#n?HfH9iRSBA`1(}{s z{)l}Sv3*_3*}3|5wuxvGw^1HIdK(!z1Ty*{wt&(HY4)ridgaZki~PyQI9iw;K-#9MDpGsJ z%E-{gop^X7fz8Iwo(WVae*LOSa@AobyDA3TQz(p z1I^7il|2l8JxH_S_U?}!k(2_l92&kzgBr*6*CO{0^}eQ1zW>S+6OfG1WM9=>eq}YB z=Abhw!=Vmc5@cLVjAvCo`4*O8UzPPAHc9($lR9U9t3B|D1{lAX?P6G5@+3JSgM z`IzR7e-sZ}vpuv)JR-w~|E5R}6@SU9{Na2#U6y|3SH6O}*rQjb{Eqt>`@6x8 zM30e+W%s>*S-~jPA_5yb_kGRJ=~hP6ImuKRaB}Z}Af_^Xt1(~|;XWrxglkRkQLpcF zgjHa3gn?Pqw)OsQa3PYL7Ve9Lu=!~YYA~TlEI;N#E{pt{lGjp3!SM&_f8q&|BxvUP zGtr-8X_TY?EcIjt&ukAB9g@6uq8*oMBw>s_Ga5@=<9q6(Lvrn3zVx=f7aWzT?xT3y zcn<)sQ^|N^TA>Pr?;~2qqPG3F{PQObom$TRq&xjN@h+xAln=UKLK^cD4D2-;iHnXz zB||+|{4apRIIseeTimsNwjPucrj zh9w$IGiBI8U+ft^t2%p01_Tth#m24c&l;CBN1+peMmd5d4m{fzjUEx-XW58mxH_?X z+`{}MLrZikG=eIDYCvOlhVMb2>&ngY#j^KS=Kp%+NM2dV!&dU-yI_1t?cv>sy%)Fv zm0_QA%e2P6?JW*m(Mt82)#LiOx4HNeRvtC~O{I#sOfP4{K4RY{bcP?2EJR2_p z^&S}~xHkd(VIqg_kkvIhx z{&xDxrPa=QK6s8JTVc}PS-od(;6`k2bG_tBjbE`dXN-OK@v<+w7)6i5&RVgnk^x>H z^Wk<~*dX?_EZ{#fX45(qnKKB2|JUY!*iVu9%%|=6XiO!rBdbUG=>Gn^w?K)EdO9H? zWJQkmz+glK*V|YAvu{Id2_s7U7)}55zol|wcy?`xi51bR;B&mKl!Q33PoR=%Y^t%X zC4_~upjl~%+vg@UYYdJE_25zDD^t+AxP2^mokpA$s>J=u;ujhQOY@8y+1FY*8Psy# zrYe{dQF@gxdoQ|uo$7x~iCKLX+^I_EEf)bQzXtkSKE20`A-3M#d`XNB`Tp%Q8+mUf z7<@qdoi|f3j?*~L6@6N#hwOE;Umx`v*x6Iu2RR#bt*y~Sl``0i6^_JTTdLME{20a% zCl2=D63LeaP5-1(=|YT7=e59c{AtWc;;oOB!{+G0za3CDPmZl4+>vc;617Rib!1Ez zeXc&UL_)Wd=euh=@aYvl*aJ`ZZxIE`ct&$LAM92PbZMNj$xvd$YH&2tRN^49*u!$j zEWyqj4=c+pD81fUo}WLono}Xek+E&QuBN{I3Lp9sLTK54ZWkZMGd{cCkYJ!V52Gg# zimoQ|jV-=3D`t>)9G=qgE-$cR)t2Aa8CcIVV|B4pTz27Bpqs-NOh8djfQ+x;#e_RJvkkugHT{Vx~G`G$!%sS1wWRic;8Xn!fZPL*M z{c@+$oK}&y-ZvIEVOKXocM={-iYub3@>A|h)Yi_jYp;afQ;@v4=N+QE{*x zH>3K*zQ{~cL_6HjjIH?1Lx>RK_{xt6A7O*X!@$4T{BusV*&XptYs$)PxPIk@SO~j* z-B6`mY^Xxk!Hqqtn_z44&9L%*Tru?6v9Z?v3@3;@+b9N|KQUufo7Z-DY_zXxKa`M$ zCi%3~@szA?zx>KXE^-yuGnswqc=E@eGqUqt4{7Nsmh@^n+-eO=!zr~D)U!HOjWVX` z%Aeu_1<6~7nwhoTcAum^b)^3Ltr>E$zo5%T*f`50AkZ5T3E+^;*Qc`4v$;*XYo*JqyF8)@hAFX7@Hy%b16V68lr5U0mKo@?KYwsnT1DH+ky$wIzQ7 zpW}{9WgAtL-zm%#epW7*EjVX#FWTK5REqjL;N*0*=b-8?vUDV;y#!IpH}H#mc0=0BW2WyCQvGb11<$V`bwjt+sy#!$9^ z^{uU~4Gm#FeC#rN?XC4xRn;>4?yvPow%CY%h_#!xYT(N}j@PBXk2eR8O=n+hoOl}> z;Xk=)p@u0t?})BuKqY% z{-Exltv*1ARkRVii}O%DeWFccw<|8g?1jRek`ucbx31pKP*|KtcT9+}lTZ=)Y(ndp zRht`(Y0@s}R@afbXh#XF`n)XUrtUalwl2w1<*?Nki>t3i?pFA2ZxyFKkw97o&1~*# zFm=qbs4Vko{*sk;A96oAsg!P zYpcJ%kT>!wBbo2nX{!V#9LPt?USEM zHWNQp5e4JbuZ?#1uv$_O5PPB`md2Pr294+h6nuH!&GG7V@U${$MrDK0GHhl@mVh@A zbARkd@NS}*GIYPn`V)2!@}Nr#`A$at8()16Z_z}5+QL(koYks#{Zk6%GLRRab={>z z_KT;>+3Wk|2^Y{QPKQH&sfyiAR-7HuQA%;X^xNvw5W%bU`EX@1`l|ftOZ84v0x%b^H7uXkPqp2;&hVlZ3Pp^u)s1Gm;v4MDENPp5hAi6p^y27J}J!@)k!ZD4UIWl?5^_vw|r zLfb_<`T0df%oDtP%B(#RYZA*neLLYNNpkO|c+{W7D!$)B_?+2sr`|q_1RN|jUaWk` zrrKceIU`}F80 zWy_a@v}j;=kcJ`AfySGl3QIeu6`NiAo~-hZXDj@=)!NtM<~?t-!QQdo@tLUfR9d9c zS(R?ckit^byl_AKadlxdy#oX2z0m+K6}!J&2i-k{_st*Mx5}qBWae~aXhWwoG}_wT zNo}ZKO44S6! z`ioh?mc2!jh0dMG(IlFnR)68eWL`-gbCex)%(?GahiouOaianJ#LKv!dW2D1K)G|V z?INX4so22z@2q}N)30;oD)DFj>#o_DovR-7(VR(^{-boYSQAX&1MHi zF&Zj=sME??S6A0uwKXsw&(FTyU_8dycsw~2^T!{HPqE7{V$Yk4whM^%!r-Iy%UaP! zi*?e8e6q#7hl4zbP(a5bh>)fnrYAyp+~{dd+dr8r`H+8laREfPDmxcc>$L^gf1KOw z;+8?1r_Z;Iq_gJpy`*J#1VTfVrf4w`_3?Z@wQwuyM3o=TAtw0B(F*(ci) zrxn}X?~Z5N5~GwTL9$fsto+ ze6b|$@Xrdzg*wOd0_I)gsj)3^ECQeEhwGW2zuH;Vw(X9ighyPVx)Z$KOv!p8m=F#X z-A{LMkd2#GCb!KKZ+wK0axWI~f+WQ^gh$^K}8Yd3CnJu+K2_+cM{Ht#k$Smdw?> zSXZ}uv?w+1#?OeUDVAw)7_!lpo@`Eq&hM@V*dZO-rk%=uoKnlg8>nm1l8EZT@43W$42=ad4&e2qg`enntDPXs4{VwX01J_=;*+?2eXX*`H~w zWW3%4+Z>o_J?9hj>JKV+k1&RhN^6j%61Pf2U<|J0A@v;LBRv8e{t@JCvF!zt4-2}1?5QwO>C-X&F}1qv|khuQJ3~lbLhS{lGe3X9;tFL)a0Y#R<1@2 zKJ^(z#IqHDfF6vmBp!dT7tmRYdx=5=-znM&*j;I3bb-#eLmQpgxWeu$?sqF%FIogT=YN6#Iozm@eSN-{8d%PeM+o?ipHrfEBC#bIFVf1s~?*pKdgWnpn2c*a!s|3XYIJBS_+ z^gh+F`(o7O&3@BJJc2?FgQhRz7yema20jf{v8h1Ka78$|kCXpdOoCX5yuTeb6ZMcP z>u8kQg>If~Gdgd1Q@mbcIkVtrpA3I$*o2wrH|3o7^Q!IBT({YryT}ArsNBNn_vhP| z3j+P{7aO(R3}jpOEaXh1_;VIw^F43)T0Z#QNfp^23m-1G_^z+7e_{{xyZ*hgvEe!* zBEZc}!(zC`o7Lk6-GXbm=O`91g{KTkYrHz~H=&eKO^iJSDJ0G5nCC{=%)Zm|VU>>0 z?&c&tj~1*&cBi)lvuFhXMhm(p<)+@n6}V-YRP8NBKo78P|7v-caZG9aE8-o7LqMFg zZ)mNww`t{6pSEM5jFpWQkFGN``Af1FMCBbofu=Dyo7;+5xn7rCYrxa9@@y|ZHPaWk zg3~RQ3Rp!PM{)#6TJU)RiW_O!O3QL;c;Vlan<~M z;)$emVFP^`RN9HpDNL3e9e1JQYH(N%KNh1-yO823$26h9^dLP(j98je{cp!ed$EPf zmHYjb*4yJjzhtug?rN$Jw@2XKc%E*Lfg>!GciPKaop2V;bX}ivE3;@aQvXE6g2~N2 zdue&3rgEaa$<|y=8G1~Mc-=i9F*c}^XTlo(CC@)wj=EPjxlC>GpE&|g!@s0a{s8v; zL=Nf_SyhONWr4}YeBD}jRk!X1*|^?_wUaRqHTprzkKJ9jQE&0iF_s^vG1MlO&|9r| zwr6|tGFfF1jQhF)(`}lyTIrs|vPUJ4>!_8>sKXBrH@8lV(MA=m*LGh@fKwPfE?O%) z2q4N4ehV(-E?gdsMucc=*o_Vg2UR4{rnim`i3hAFYJ2txz844kRsBICnTSxEf`+%x zSo3VChy8hLBjl(DW_@ZL@S)1O&83ciU+?#nK`nL9!UzXZaS|7&W{PXCkERB0pO3iv z%@A@P$(;?0KA|`rl_!<0^m+D4lT}^G*l@8ph8+v+-PEE~sr9|cLMMlJ?^eh26~QY= zOKbl}EmZy#R6PVyI#+(nRi#E8y8aX{OlnB7tls=7dx&QD*igR}BG*O;m56o{5vXT3 zVM|)u^F@Tmzs5Ajs@q97FE5erWq)yya!uBb`YHU`W{#17)3V=M7~}ip=Kdg#g}R@2 z`%VH4-&#aqDEIW!YT=%bWRd z`vY~hvH9-sL^guyW{|s4Xx}gC!KQXOZg#y-(-g95`o3Rg?JPuZ5wN~AC^tBLp%Eo# zGiWvXq-F(`K|fG3r^Q#+%TZlhn`73Y^^2%8(`XVg1qC3A-v9mkcXpOo8#Vq|Gf48c z?$2uiZEiKu><^oXx}+wK-rj;=Yc{5VRXrppVmexyU@sjW)0&PBZ5y4Fap&iHZ+{X% zw)*TWHqsGy>}yY9I!@U%LZ{F}npah;npAUFDSotXqVIfhN+YEN8%MC!;5ag_kR`Zi z=Q~WIUf=V^f(aihNRo)dPc(h_4@}?KbkQ$Z?`l7>L{s;r=o`I){FL-|!DDb|RSs%z;h?F`RIYED$_Hjp=?y*sn@X7~X?vAsm4Er~&3Xr^1()q0%>&ctDK6{JJ zs@kjWs!1;vzAWITG62qTLPEmekPvTbPI9b~U%v*j)s)~5$3S>FYQGGKBm=mxpZ| zE(@XVKKG+pp^Z6JcvCIRcS!2jdDO4VYr;o>BC94ef9G zy0ETW0!@>wQ-$QQXt_-h^fGCkOU$?au`P&cMiGZVemkdxYH9Bu9@aZHxqc=ZdC7{8 zZuV7=;bdE&!sh!HMZ_=>B8AEA$WaugF5EpBVf2JGQQ;;t^S1wC1=@B}3gOxrrj59PDYie}5DgEQ2#htctg4VB z@kRD`wzI&-Jbep9pCJ-~nF~8U`q{;Wr^?2f7O$|du%Mv4Mx(u@C6J6#CBKg!*;37X z3tW;P)k_&PXU50lLXFJSiVtry))q!h`?r)AHl`N z1-3FYu{k-^G~@0fKSt|lQJ*~{A|kSNY>Zgg9o&SOm}DDmucWw6W2F41kyW)heXyE`_F%Uh?UFJ zV}nU3CNx0|Ta318;J`9`iaf$VSu|W-bU5vq%)bUL1EF@sE+OypmI7O-=JtQnpBRm$ zPSR{2gILJEeO(DoY_XbAwXiKI%M|Hb@YvB4MWRBF%jF?SAwN*mhzh~CUW$|9cwzxg zGDtwqKV-GHOK>zEh5U8{fK5n92oWJ+s15i{e0)5>E8z;R1P^m|ATUw7v1fmG)F-5J zqey{_OmT9!g}rQCFa`Gjn$huIELh_??;))_Ur^^nxOrMJnU1b?da#x*mT{|UQlZN% z3#}D0uQEO&R8Acq3-8FwXoA=Hm;F|V;D>uZn%D;43yzg22u*XH9E8TbpV83O-`+gd z-qh68+4<`Xp~wiHxq4$*mPsxXIuQb#LiQ0_S9`lyp`?;Ckf`Cke*`@*q;~D1Hf@=V zkR8~gNf%`~cLh2-JJSk+B&j>OjAr~V|NZ7~@nynaD=z}$-4sF|kyMx=o$wC20jL(5 zF&MU8ydOdSKII?rIVEzSQ~j!Z`(Ul<6EZ+Dw|CPdiA>c#=Nab8lz3^Evr@Yww_#22 z4)YGTwMtL$xn4YfXgw=);(LgOnE=W5;^Je887&fx5vng=h(^8@D(tSobOi_yTwIcECPAa! zo2q#nNVBHGW#PF!tE;bYy4PJOr7VeMOiWh({rk7Ny85W@34m8Jf%gtmH-O0bZ?Z_U z-y-fXY0$DVjRY%XFR=+AIP*YaJk-lHHuO?eeG!+FDR~e8v(e>79KA1`myiw5zZJfE zT$w9*FBj&>2_$7zg|k?z8DCnS4)@6G7RYJ(95il$BUb-Wm}#!hRt%6v>EK)0AF`Z= zhKHwoEr($}_Rp$~?~6w14ULT{iHUzW8e$e)`2W;mAqj5he9p!hP68$KZNdut zgu`80gMN4Ci#U5ASUQ=&Kx)b)PQ#AqzQl8&1}niY40?v}wF|CQRePoF-4w)bW0$i!A-Q;8AB2~BQs@h1i!8WwzXkjDOpJQz`R ze}AtkdSz26)?FvQ``<^3p1bv6(+!wlxoub>W~Z9=)P=ubfO>uol~4;@6Ut8acyP9_u=-<!%eomJi~5 zjn^sCT5H4&l5D^5=kR>-;zd*p)og37_X64z+HcSP_r9&y;6%w(&y`y0!;2zVjhhX> zQlZfmzZi9gmb-VGy;k3&f#2T;c&i2JS%5Kb@QJIyLl1&AE`rws=qyq6hCygr4_*Jg zbzc2gT->=tLT|pr@zuP_g9LxL4@BZ?r*9P$Bq9{;j&=3vg zK2Na4gRlfKY|_CiA}+fc4s_X*1`Uk1(VI1v+jZ|8#9w_!@pwQ{u$hX8{O#;zWfe@D zJlo#~h%os~;d=-~xvN}SYAQ7xK(PR$Vx*#=pdcf|s~1c?3TMo2lS_=GN0q@xM~Ovg z9F>M#`2i$VLCMyQ_wap~Ss#g{=T@YS`^6<@9>+&0oAm}vCOV1veeY&a<5Cc-NWKPh z`fzz^DQH4RMMh$)^O9}`Gp<}T4u{^Rv{?xwKCvWk3zAV%{>fK`&NNai zU-*~zyM(VLgTLoU2^&Zfj?7wU+(5%wRO1|ZvMx!aO-OHfrt-?xnWMswWf4n~EWWhK z6}9gx0?DIf^0(HmTKJzZ5Xp3eaegL+B{5U3D62;%&w3>~+S=N>xg|`?l=!@kc%mR8 z{6cXN>iOiGo&{T?LXnojWXpdYznx$Gcl`NV%KHI|BN%hE$ty}6v`EG=*Cj>mDao8R zU4WtF0y8?JZM)n4pq{Pc=oqS3@Li_qKM%XPqx7AZnEIYCw`F(#n=RAeESO%*W~3Py z-h?IOUdakZZmZ)*EV$6@g8AmKt`p&fy6QOxI^6!PlS;ivMWa|bNWc+;bs+!yeei06 zwP&gf`k(T7XBF-t3T$CR@PSp$qi>=5&4B}93Zf4oRQM)l`h?HeTt?knBy|<1qs(YR z#&YA=>sZ5cz?Fo}ATL3$q`;LVYW&QEKZG$UCos^!dB>2{(`*jsXNK{H)uW5yDc=L# zdv^1LnWpL-p)(UZZcO+Z+KG&OU$rLCPu=;--D~rVIIOu-ePY3baxnotru7&*;$S9| zqjwmUlXCVEhHG_w$$rY<%$e=gqznD7#^gK}p*h1pyj>h^mVx9!7kX{8T$mHQ zx;i@CsY8e}c4~a|;o)JRMQJ45A7}$jIr$dd6lODW>BO?6_ zjTiB?>j5pzB;K%gqY1VFSHKfl`P0`u5>Cm@;ihis?a~`ECU7uUNSI5kAcPDR#=$Rs zyadrkS3w#YQTDer=Z#efo!?=;C-eaET=>Bmf@|zp!=}jA>0%3XL73zFA-Q8BzUSKr z%7||Mx@H@F!VvaYSQ@9x)a@+5yHHrJ^vAmCDe*1&0~Fpf<55Wsfds{a5MfaDn<-c_ z8I%1z^3sxmsvH!lDNeTQp;CwSL-=2u;sMhd{&2@Cx;l{;HyJfXGiSo8EK|0~8Yh(uRxl-V6d;RZdeC>US zAOmig)-wqJg=xP3y{6+6hyLz1^@)81>wlBNwCqP*0Ouzo#-@U z@@+yxLs9d$AozHKk-N!VHZ4p#6?8I&D?birv3jG^g6NBPGgpR&LfiOz%GSKIn2L`^ zb!l*qA}-j&4<$=&lN9J1W3pIicif>X9hvEw70c)HyOm7SgNOj{*vBvj8ae%R^sZkT z7uBLeVKJL9sm7^GJ}t%&^}9G?&{15BizBX`{&5(e&H1P0M}5rsQG7GE9z~haOky(W z6VH;HlCF7^c*qCh2$@{IFYn@Gzb~&@ffVe^$1d7Wk~9DQIiF-V8rGV|bz^lLo4tHo zT=$yd(WOR4==Q{vECh=-+AL->)CPRplz!%-l6<6r{j4VsM-hYsPQXGKaoiWY|6S2h zX%*@3Fqg8ci_2KuKB%?Wy_3spYU9~F6gW!@YK!*-xNtRy#FM?j+b@H^P#H(eH}>PF zctXBL5u{|{#SCW5w_0ghgN2&qSww|xRfXc}lONgMe^N*M4_xy#Y+YPje0&i3tk`1! zq1)KVOQ~k*AP3rN)q8Ng|NVcWdlhiA5GKzOyS^XnS}^N`Tbc*Oqg*$Uu6$m91HZ-7 z(`;gF+O1%i#aDcjf<3w_krs(oK;;gs35@7}+UX8j_u?F}8$I_T7-X#1KNr z60#&@E&JAe%a&{nMj=@;mL&T=p7ZJZeSUxbfMPrHA(L3=?wayH8d7 z_ObYI=A5C5iXOD;mb}_HUt4U=Axy~Q!U_;+N}F~@7o}FV=eSjIBoZlji9PttujOv7 zXmdf&g=bPa&O}XxK#WICPZw(HJSBvX}SA~T`?m2LK9R{QlK5&!Hq_$`Nm|CX(7%)e3 z=rr*aFuf0=Zc(HIE6lOydK4hO%t|-LCh5)0xtd9K96V=X+)U4hQo1Q+h>oWU!O-H{ zLQz;#dWwc*v(-97DILnQu%xg4Hzl-CkL+c@>c!5Vfb>YMfWpC>U_XhWseM`!m(SKIcM@Gp10o?BWUbttn95^pHW+r zq?w$}ujydsIxd4U<8JYtA1tyJyMarqEw*e5f>j}}?z|ZVf>pP`CS7}3m?{x&v$Epx zQuj4U!1U*vZ?fEfDNdn!1-hPnpjZ9pXlhlMO9u7@U^r22q{vsr?}doR9PDh_U6gmf zk{ern*i-oQ}$2+W3ugmg%CLHEBUqjm6S61 zUzw@AJz>gcfK+c)Z{$@|n0zhdmV87k9~p*2+LS%NW4bIm$nxg{^}Gtei>)P(Hx|dA z(}}namy{mg;5>TcgiWsdj)1As@OKI~>axb&atVFTn%FwG=}#v~5?oL6#uP%bIb_{o z!Y$P$cr$EPQ{aU*9XfS!XR&Et0bzzrfkIXNoZU-X4p(N#t-*u;tUf!+Gts@KzP_G2 zN)>`~EfP29MC_JiE6KRZ@198mTdSskxTGY|a)mMe3l-$Jj+{Hg^``|VWj3ihi+}+k zJD)-^-^h|@M+hZ zOF_F!ZONK;etyZ}&`w6t>`NI(bqY5XqPG2UUh4Qo%dLnbkq1ILmy^JAWb)0o%#Y=qZJrJ)Up#{uLehzj;C)zQ1x35yflem*0KAAuaw9 zdO7#Wld`_ZgiyMwxe3YZ-d#OCI@;QHVkehGT(F*J1!)6^=VRhah32QbQUQ<%**4EC zaY}tvf6&=v=bR~G+B5k!6LcqnxATpKwllUg%S`$u7C`*s;^IKf&A*#M$H?u9_Ze#> z^t)1(rBc`AL|$lnwB9l|e^!P07((PD_cn)VDDIe6FMmJ6%zR#7oBn6!(bZ{>=0V{1 zuE6k+j+n@HHW}6LYcuqZ?PWo!!g7F@WoIlBj!UF-Op6K*+PK>YG19K7;=UK&gM5eqVO9 z^FeMc{(G-@&+*vG(&G(5@_u{UpPQ)U+~Bnmb8^FWe1=@$WYpCxLA_^!-V?Z=ABf{) z+eLF14>8ixPw}q|7EPtPNVS`_rTeKex&@wRu6I1~-z0m>e@F%fawel+D?%qN4qVon zOyAqus-aTl0fJ7yY=KsZ>}~8*E!$dO6s#&_j>|haR4_espK5w1tRXJ=}4q<0qtGLV2 zeGdEr+-l7JX3W@Dx6g-%Hn!~BwVC#7KlvFD5akq_jie<{S&E^e=VpCuN_tbY;@%$|0%>gsO^#d-r%1I9ksuq-n5W`9-eurWgb z0BmoPTKy_7wYhF=_m%Hd29fc2ENcxU48lL-aI1z{`&-*<$C_qS*jnw=$4|w%&$)A7 zUk%GIxDa8+&sH1JV)Ih>c}fa8KXRw`!%L-^`GXDvK))Ee4+^1_;nBb2jka+vS8yyi zx^Nte{Eb)**4pXtZYiIoO@9%N;O*Izm`>rX#5=@ve}$-6mz9S}Sp0T{-o9&Ly&FvAL3e1ahE%BN&0MZp$6SuRCd`4E;Mt+kQ561m z$1O-fR8G^d?let?_u2|;WLoW%{1a3!&ne&kE@YH15xmGVMt%C)f<>M=_hM-AnA4AK zx2%!v5)5Y9v1_JW2yh#g*et;o8$H%qm{-o+aqag3EBgg!)<5_AbW^!IrJ3oj?bO$i zky@=)51i%bXCGcgFZGdic^5l7Rg%OOEqBd9+&bLH8P|KMwup_advMQm_RAN2?1r`B zRKfi$UYD}o3T#b@lbf3;I;L}PF@z8a=^3||8lEH?CHt?@H%|PK;p+m&)wQlxn}?zQ z!d`3i_*;<#Jon<^)>butk#*<{F!LkHa(dYPrN+0~c4@Ey*rWi+|J?GkN6qMJX_vpQ zBB1}MO_TPUhHLu)I|~6TEAvu)`>Ds+YB^WE7OuEq%I#x#=<`#gB;*1C&m_<>?oO~b zspaaQ(@uMyk-=WVdP75xwWfD%uCSz%N<>+a9fIO${}>Vzp;rZSbEj0cwse9%YqAg? zro?F*WbZl3cbrRCQ=t0hl<0_ey`^+73^xUzj^*Ius&kuE4G!KP8AilO~d&4tp4w+P*QKnE;1r zUj|iL2k)j59Z@yge2nwt$v+s|en#-Rz2Y885nn~5l8M!K@VQa1lOCXp12!5qJ~{Ls z2{XiJ)CEXuc>>5D15_@s7cDkR|FKzsBkyjTIC~X|C3Q*)deUOpqiqh&FmvtD(xOU* zW!$5pqrrqC4C4Kb3~D~$ zfSJq4=B!TY-K>4DSR(~`V&w@p*_n?qF-67*JC*mIHR2F0XUM#snaYE@ z{I@j+zgKp!>rz(0l1-O@Kcit5QK7eQU^64Gh==~&wjuEmn!e+UgRifzwRK4N`mfQ8 zswzi-)S;yH8i6s7HQc{oof8^=}}|J^RV)|#+e$~Mjt?BhjoauBbX+E}g%!q^Q*@n})msZ9V%9AKI`cP-7 zy83$OVMzCT49T7}*=K41t;+{)>XP1>W2=DBsu3Y~>kXh^It@QRCR_x1mF0%;CE0_SWCWO{ z1C)>2Z;(k$r%joOQP`T|?n|%8?;QKUqw2=WM=AQbxmorn`=N@1$ky9CF+)=8t+|Cf zF2L7U2E6lPaR^7}%mUJ@sF5hE4MdAFy04A;WRr_w!5^nvPTEJ$Tp8PJooWc6BhIu& zy;tdv;-TkX9vm7P+KN9{@$r?4AI6v;J&tB)R>|(0TL>$9h1JZZn>mH($dwQ6g$YjN zP3ISL0{)1a@@d-nz##J6XE8B@u)g?>APsd`GlNBZhD(Jv-cC;9Ry*x8UYz3P<>CsU z{`_Jq2AKy+uJSDz?h`9|VUHinc%6?xKj#*elpG+FH_inwpX;!N@Cr#=VX`1tQCRE0 zx!gJB!J#*E@Xr(UG6#-rEPlK9ibxHG;&bE1l~XEu-5H9DGSSOF-y&sh!_xNyUB{Je ztgQnb=a!fhOg0v#a#V1T=?EO(qQIV;mv}J%oI=`HNI(GnS6RDYQl0J1KOdw5z{to5 zDcIdwzOzLOowQinL}Htv(rO9Pz><4OhfsB??$e)=Ur>*tP&u`~(w)dt(bzlpUTR46 z?OPfbKYw)t7pun4&A39nPWH;n%cD$B{{qDTZKg1nFG-%Y%<#~c;Osg<55fVe#@Q@j z;DI{emh*jTd3$($dAWQuPN~Mp+uP__T|~=7|JV7OXTA33jGO4gng@i}QK&!HK3rIY z?40ETwBg3zJ581zaRK~jSr{+`!!yI%H}=%{-66e#nNVa?8E^E3EcyndT_zaBlb=)z zA2#XdPlBZfZdf-iu262|kp^UsqLdyZv870=`dR(_6cWZ);6jP;G?BVcSOPXD^B-3k zbMcTR1{phuFob?{wz*9iUBHu1QTporNfN@H6T=}Ys(m+`-o1NQUEN-_HBotQWhoNZ zPbMd6=jqKKeBk&zjvkh;mvYy8A+XJEK`=a8LaF9MKOb_bF0$u*+-xoDE;?NKW8^SO zmkIGfO4Tk5XtL~ymo%(LEe3{#Z@TjMrO+7aCuIpXE=C?Qx_LU0crEC;n%A4ACd&~E z3ybvhbPH*BViysGI)Gf%_>VQ_)!kohtk47-=QsZE2Bt5XMe%Wph@t!X`}?8NJTWnG z%ASSz$i(Cj%7h)+Ge_-$;ag%l*h!3Dy2E}_BdZoa&=X|%w;FpSFKFYV;%`1MdG@B` z($R0H&kt4ZLFpU;N(DoVe+^fO#HzK&gkLaT)BOvDQkIrS{X8w5pg!du#ehGXCD&)) z^TN!;1k!bo$by-7tG|Dj){6-yvgfbO8C!+wC93BF;ow7~3M6(%=GFMcq@-GzT5Uu{ zCm2wfqKL*4z3-v5nin)*#mFs##E*dryiuw!=hxEG@}=&PRja?E3QY$N4s+Zt8v=kU zt;$HTXdaMHB|_mX_!o^uMpOe0;?}D2C#XyG;S_(bk}UleB=KbEe?qJp3mUFmNJvP4 zxyEA~@;wZp%6$$7Kr;DM_81H(ZgnMNKh32bP5c0=2TjD4nWO#il@XhE+nP`ZlJ@GK>9#VSauGJmS zZZ;f}1uHEry#YqfC`>qR*{G|Kw%hs;$^nHu?t3LHyF(TeYpqPcDX3_pSOk{o3bvck zGKBv7{d;Ehyi7L`iQq-fBc;4rIzyaT3mNoHe~<$4dh#cz=&q`+_N8>cNXfXAtclE0 z&mrZvaBSN-&ktQf4do*4&uGfsEQ&I@X>WqP^G7+wFP%a=ZRNJ65%h@64Is8qXB?TE z=1(igrr?ZlKoe-}H=o4BT#5GBUY)fSJI@1>7S4g#9b~^%_a6h}P$iH$vq6~E zfH&;v5vA2p;5Oi{2n z+hLQyei<6#$$YVD;*0-A?P~?`qh^>9TWh2x)z`z^u-PJlW~LL_n!>p)d&UEn!nz%xo$J;Ef8;NYAUMr*6y2fryNRx3B>u;epJA}fVEcJy!td_;)#4GAddmY zIFfp2xUzUY?KO9ssMgJAjdDF^RjV!5(K^SM<$ApE!d@5)x3aBN*(qc&v#!Z{Da zs|qO(8a>*Yp%X-$r9Q}Y4rz}O+xo3hnqOS?P22Z!{j1?yD;{J4NOAcnj6bkHC%bApF_QCD`yn z5mq+hvH#e{#?LR;5@wkuOdYXy9k?Qd6~a;&b*%A`<>1sBOdTBlOgZp?2Z ztF)$g$$&|Km(}}=!G$z+H(n#JmytS3Q_99OzpXL)FxOPF%d~A{&%H(yM?*ui`y2zDJy(t{*P83#-^!Dl5iOs0#W1Ej3$tWB}87A z?fn|$t-$UOFQZJ{Y?1bC_{Ed$ANeGt5z7j{uFj;KEMU7H0_t z*2l;UT_;Htdvz2Ps%Oa;y47eH8V9dQTFzt6uZK2|`N*((Q7 z2a#pCB*$>P`P_u|FrI>flrFnJTno9etJ-n{qpMuQt<`0>jJ1Gx;aUJ-FXD(gCr!gJ z<T8p6&&}r@l{`u0P3^Z| z0P4+IN}@p_90>2b<-{Oao|rdUc$|cyqKoNZg%epFqK$$w6HP`u!mjcn9D)fKL5R zyVgp&81Z@P?`(>ny2`^?{4q^UO~CkeH3}_hQ4N1lE**SdxtVP+_xAIsCHg#WkwrE^ znSDQ5L!b}_kU<^-h#$EcNq{=uj*(ZzNw$%sdEXu~H2mSuaUHAhP%S9=h%Jy`n#YyS zI@{Px>}`y>%n}Y{CLvJ5;7;q;b`{*jFBJ?%oh2cBI!9pJA8gehx5ky50v=TTP*r`s zoV0Y_-CGa@+9~7>H4A=Dp!lV{B64yt1C&aVU{i@@dZ(R7Vi&Q1!oSf^bu>yPeR1=9 zA87!y-*=lg>S}8X=gy+Ty-k4SJ0r!0E5(yP0TUAHHN@dUhbEo6Hyn+_Kp--5q^G&z z!}N#u^`yChYuK3c5&v@W|0yJ}@AYV%TU_MjY2DSZV3QWW(g``TxFb12S0uK^zvGmCq70s+lIEZ zgZ6sOM>fVV*<{m1VAAlTnd>+SW0o+194J>XDAy0RnN}1>JwTw$%5T?~HuJZ0GcEbH z&t=UB&@aG9a>D^|%a;DmzGE7Z^{Km?N5=L2r6)K{-{xyv>q~V#*7TMOHlS`8G#i4! z<|3_*EbF}QHS=*f6%}f9U+qlGHZo2^-A^i z4Y)0p+5n(DbOr)inX_r)-4yd*6Y-&rLDpp^@9qt+$norz*4KX;=HL2)xYED>p#xrE zX~i?hg#28!M?JW|9%V3>Zyr5dUwwF8k7ehCG@t}3nAkR;euKjT1v9uDL3$Tw+mHmD zHh$v1RH|04K78M^Sq6I-PNCjEM#6A*P7V&=pJi=tswe&T~?A zX}W8*D|PW~yo*45^OfIj2QsCRn5jg@_51rGGfRH|?d>&w=Db27X68|WkIZ`#$@Phv zg9>AuD65rTGQ5-%fV`7S0&w*O4lE~em;18MFxQxeIPAr;pio>7NhJp|VMo%HJ;0=W zkmo5e&G&y)w?j9)cNLY{hU^8?Cr&$KFrTL=6HCntdzVnXW{4jV#vk8V!4qAv2YBh1PZ6BMk>`{~FQDYx2$kUXr zNtNN*x6M<8NL=yL{6Q27h#koz=7(|A; Np`wi|R<`>4e*m8$Oy&Rp literal 0 HcmV?d00001 diff --git a/ros_trick/docs/trick_main.png b/ros_trick/docs/trick_main.png new file mode 100644 index 0000000000000000000000000000000000000000..ab586779740fddfaa11b1da3cf42052a8035921f GIT binary patch literal 38677 zcmZ6z1yq$^us(d~PU#R(I;C4mx?4cHLqNI@l8S_Mcej9ai3mtbOM`TGNt|!v@817i z>tiiY-t*Spd*+#EW}eMQH5FMbbTV`Z1cD_m_eui-L7;*_;8#)M!I2uKXb$iXnzNjq zD+Gdr|M(3@lYYt#flx!_UrA_rW$Z6{W@x%MK#pAv90!JIQs9pp(>9nV6BCn9yHUQC=l;Xks+-{hF5cr4|B%w5KRA(>818&c8(RNyCXKW= zbD!O}MgyitCWeC3%>-65T9)os?Ks}9eiV%xVbEf~Nk8IKRG)7{)NobuwbO5EPMvyE zr?dr2-JN`VPW=b55Zi2ysdh$kqd^^kq%jyefY?{^j!gn8UsUWi-P2zZERWo9q34Ar-pRLGa?57m=kmn-F_WctJ zWxtp0pXG*7qkbng_EUfT+Uw!Y8)8DDZB<;Ql57xHaEx%FTA4tcVnQ=XWE-YBqtZ6m zu}USW&6%1qZG?zhIIo!|W6K0>YG`?bx`r9TTD6tpLQ z^iHSi?yEH}NZ5Td4uhA48lfuI9^50w@DN)LC<0{jii+k5R$95Er{e?lNy8SSl+~g= zx23#7(*xYaiacWZ8V7+u=lw638*1(cM!|3nyqd}Y-f_h88p*Mqdc34he(Jo%Nxj*^ zq{k9|RCP51gg=~)NbfHA#FGaFt%kO9rNWB}3-3<{IYwXJ?mv$aiObAnlOJz*J5Lg} zGgoi#sKQr1Hl1FX8?5NP%U!dX;j?`KSDJVhPWZY>vLq@mPGc&V;a&0NfMYAnMLTA- zfIe2Z<_U!7xsw`B#`fGzsOw-KV)>LIOqjm0*ndr9=8(7SP)bWw)=+7LeGD`GyW76~ z{phpL2(V!pdXhNewk^SqiH8kgzp>F4`@;gvoh9z@ggP5!RhOgrmEU){uk|tn%;BI9 zJjNbzV!p4q&3q09`2`vS=x6tKCf^KyDODe`TkU zoZvN)zYu%CwUwvoIvb$d>{0DF>x7%@@k6X$!<}4`&f5D^G%BHW+~I3Rtqi>GJ))dA z?hDV(@s-OmN2zmH<3B2gNfq_6GM0uX#G|p5c+!7Vd30}Hq9$e#S`Em_=fMo{A#Os8 z{#T2QUMGLz;_%C-e2!NnKJ~cV9yBu0)8iv@S`H-8NQJQ)wRv@iVUhDY`mJ=d){`l3 zyZ+{HEAQN+Q>w(ZQ(Xw>b1lB27rQk5GbF~@+)g$>ln#sE`oTV?u{PHnVKRA0)w!++ z#Zx9cyeHota)cv~XA(3!@V-81=R+U^WVuIZPukq3D|%jSsNo;%<; z444`G+iDcy*c7joHl567aJe3@+Hw3HjFfTb5z4J38)fRIaH7q4r z*6Ad}g$!4?Ks8SzZx-JSMDlYS?jVSsgVu&-f&$dB?%dytV`K1D&rPa z)a=PcKCmA9?Qjg(kEh80id=yXVIaB5Y=w!jN-`p5HCFkl%U33JumA{5)ao^G`_XbL zy>e580}tsC>E*yeCvnEqJT@9u`T_}r=ppCr9FR$}>wn$;yH~B-i@{5#+!=5$7l#;_ z$fCQswbgksZ7?bZyPGkFwtF5K=_Pq*&Fp;TUw%PXVUA%$*Y$l8J=a5uM_Z`T&&=ma zqM`4_@aMf?{?DPyFDE4kf*Vg_hqSfqP^igMN>fnf78A0NKRR8rM&Sjtd%rjigit?m zk+S3tQM2)rrhy(>nAbmhSm^(dR(N+6#a@3}UC8UT{=(k&C9y0?=XLqPr{w&>Q5ziS zNvFR@t3OzSr!mFmebL1#nL;4aJW&;?G4I1xCxA2A885W8wQYqiTybqw0wUIZFI|yzqtj`Pg$eBn)+y2s1|IS^mF{ZjV!6(`EWY z&fXUHlcPT*r}K5);om)ag}m$QwHO%qh9AYqONouGvFOJyo@fRyYuVa9d?JH_pcL8c0#GMc_!|%I_Gu z)Y*+D|32UYF9TmY7|oZ(c8~FD&=()N8^Q>5Pw55TdM!DeaA<-sX1eW)?Kk{Z1sNk>&a0 zIidJ3xV$)9|8YghG25IY^hdgf+JkPT`|s6iLS_jcKU8Bi^#}zY&=4r582)z(KFy$u zeP7_?!O5`FdSqB5&;MM+`F|HJ|IgK-Wrk5?yy%dCzdOZ&GnMRBK@yMmKb7q+wCGv3 zlzZdH@b>ggisIv~OR#S0J?f#bfMpHK+}aC^0Ncb0YpZD360CsR=Q#j*ZEGi z@jIw*213Z*5Y9EdTT7Veuf1D~5sLU?=R}gk#%oI%306Fg#SI#^_3tO z>hOqM0!2CD%^xa$#|3cZ|GrMht{sk1RolqmAh}q;9r)n%^fX}uIKx#tc08;jigFhA zrKZvl2_^D*@Z&%uJ~G%B&db``;<18W25iYVUoao2-*`egDFYtSC4mY$v`chn4RPN zcWJ$8f9dRllay!=>ErlOrP1sDGuGG741^(%M{+%o?ElxI>i_4nyeChd3|rNm_S*2I z4O>Oz`IYNd8!e9G4P}YW!y>z0AU|GMPxE!w;o-K=K0Cmf55icT?Z52-V|(heotq?l zFH7Zb!9!N5W4}H8KW7v2Kt%3W9186U+pw2@>Mqzxll&XdT*#+U((`H)!-tnwUfUIY zB#(wf@Z>9WO2Ip7b}EtL@hrDg!8aZpNA9f)wDJmZ1!Hz`7fg7Rrpv0n90|#{ODb)S z8U?Z+Dv|$Ikx@|mn+0^WH~ISXw4jc=@FARIif=(Z9kCuJ*DpONa zl^thYc+9}2y#E2$ zAN0fh=oeEShM9DIX;B+Igi!^*D>fl%sos8Oy1jt!m*+npo}^9x#4*CbV<3nu(E14} zP~tvJ=3Rz413J&MK7{hPcB9mTmoI9A2`I%h_SRp&M}Qo2ExK@NMwY6F;C<6D@aO7G z$zzN{=c*O9wki(qboz8@crT=FYiPI#)u|pB?#~oFn_fB4=jw_KC;3i@^Up?d(b$V; z9g=8ww#s}m8P4&qCeWlY=QWQyb&`RyIC~4_^vYKD4LLvNG zLw|SkhlP}+l}v9S+jBzn-D6knc-@3g1B z`4GfWT{C~M>~}Uy*|?mVH0^A`maP3l3Ul>S_@jm8{_;3nzP+MTe9M=<{WX)Nyy$(R zMKt`E)&d4&FZI!J3JI~>^EFL+)%&et79GC_r(|Lcx0dsTjLwcz1-;eT&i0y;qG|dP z#`dJFm;No`X4Rx(5f*L)s~5+wBqM6fubvJdoj9DNZVV;9lI zY%eUVX(fw^aqf8duh)|L^$?=TToM^dVlU47FeJ z*Y0Y!Y}@7EKMAi4msC-f18xtxQJ`+V7LYh1iO;m}t!(iSKduR`NNXf#S)O?f4h{;Y zA$mmOaYm>LKd~*+E169-{1d&_laaNFPmXqa|S0ZtQ!?Fi>A?& zE7}oSbcGUD$1z<6mc6GlKRnu4sgeL61p@yC9*g=N1=>d;EAh^!NkX#9Q{HMP--17> zO(kaEt{5Ms@0LNnDMN;j+l4ngcC%V{TCps*MiC&N9iA~2DRt1Z$lqQh4Oe%xHSIgR z#9?ItWhF9tmb!F(XE+}YsPwvGz_yaookC@*8n7GhyK!FLZJ}h#@x_8?amaGQLsY_{^ zMJ-zLY7=J*3Pw^=GlWl#5h^by4qH7(4WdPZz^}|iA$U9w^tzbRm5HP<8WX4zA5+g}G}UH?)~ z_2b<19MQ<7(1TcMS8U{etBNxL<=}rdag|1=?xSd%j2F zU$%aVN^4zJUeczfFvv>hN`cnjFG6icPs4JC>jxx!(;?;-+GB~>T!5GKmSQ_L>nG5{8>i%`Saq?&|tTA`U0gU#Z2U`geDeo6m?lz6uwjp+q}!=VXGIerT4d34z~69DDM~% z{BDvs;}Rz?=`cJvL>jkjQKr0t{#M)_xWr}+{J3~ zAYxFyWs;R#M8RQ}@NKm3k^M2g?K^LUkpwshTOC1PDdW}0e3a?xo4ncrM2pmDJdW!!d69s-FDIkP0zVKwH2UE%QG5K40|C(?e}6pEiXOhn92pQ&SIfm8lM z7G$YSmX=_VtXm+CD;*=}LpOftreDcd&M2=;CFG!h*@Ce_88H%8*S;8sKTmSl)Z!aF zsJn##DWHq1S9XdV4UqvPUMEvDQT1J%I6PY&wh8hj>3*lqd6PoiqI4&tn%uv>eO#|4eDnH8x6OOg$vSb@YFXs>phYMS;9?OxuCxP z73Ed?)snAO9TG$ai|Y2=6{A=w)o0~fmncfiuV;`zaX7WR&8X!^x@60wJmgQf;ivnQ zAE%a8otEPmJDL_X&czp157(Pa9G5oj>=b^qRUnHxkQObx=R3a<{--LdwRdOmRF?-) zwFL7dOPw973pVZ@co32}RO>aX-p9129zB^lv%D?m%^t}L{*!o@R*PHXp56V1+V7eK z4DWa_Ac(_8VryY5gKys1hDN!vRNLYSd2HL%xL$aa=d6npeEHZ?5ltFpNQE()sLx6i zh3N=ygLhtvEX5#Yx=Nb%j8y%Ps6%lyW!*TIaD#sb(&j9}x?n~wd7bn8+7gT&BGVfQ54lZS9Bp)6R)#72$)+AE#U1>FqLSx}+a z*K?JGih&?4>T(s8dv)TH5nktm8yP{{&I1=R)P$5{n+o}u;LXnv(YEd4yN^90 zj?R~?Y1igRAgz=8hIhJ0BA@&!^6yPndA>-rxJoh%rryQxpSaEw6u==$VE ziFr(x;qA3?&%XPGG;vwNM|?#1+Ngd6ADpC(coROy;e;&uboau7$s$PescD!k?h^~lM>}LH*?<56W z8?CHLs=)nU`;LddgVk=Oz3&lFut~WJRA(F^)bGWAYJE5=e&4|o)A!`Ba3N!_V|A=$ zRR4~Z+?>g;I7FJkoVag_$E-|e_+2MK;l#VFhiCPd6l`105j0%sjEtP0MT}8R;9tPI z+1u3F1?mU-K#FMvGjeOoUvr9DsXT;_!8Utd6r2B}LJ_BPWDM5D(zvJ)h+&+NUiHcH z%2s@*z`+Ie$=4xxaYsjXwfD&;#XXujIz>E&wiYTH+z5X!oS$G8D*mw{m!n{L-=me; z2-VFFXb&={W@M}uV!)+ftA$ihOD>z{%NTRh_+FHiwJ1dWY-YOL{x~u3`EcFpd(?LH z-uL0}Ofo6XQ4+PFp78CaL0D90Qek0mxa!^UM6P`mS-W*#R%hqMW(o}gi3}11WIf-= zxhAT!e5B+pho!C-#oXs60Ue5X#;iD!tUK-b6O&hfWY|x)?PqI-QKL9skXzUOIwB{h zeEIZ%kW7yJ*fY&q+9~1oX`$BcReUV5lPMB_DP`$1)1qQWM+&lNOXpT`PO27lTz$#0Fm`#R)8%P@DXJ*ew> zxNy_*G2UNT;VFOVbP7wE;z+_6Cety+@MoTH-vUHkYF!v2+b_4WW17$)AIs}>psnxj zhti8iT2^~6jQw4=f35Bht#4)d1Z-w{S`_V|z3*5>o*2Eo>}+!$n=y70Fn(jgmwq(J zLCVF27f6ICfh$5+9IcwgvzmpnIZmMLBMM*Gzx`Q11Fhh#p|j13|L;!$H!m*)<% zLM|X1kXqIrk+78iNipb4c?#m|SW>Yd83HaVN#w=oPx}u%mPMTowRH{ap-1eW1r(6S z2D$V-wo}x*W}33053>%{nnrc-GrTN@)!GQ({9U1*cRx7QgbKC&#%AOCp88feEqAp0 zT)+p8k89NH-}f3E=}hS)Cnce_y&7coqTyxp{D>tOa0;ptgXp(xCNWi^{Mf(mP?osT4DjORIj0{iRw}g4FcJ1fZStNe*&cpVno$R zM-u1T{<`zgK_PF>=2rpflgKbc|2#g!>M;gejrhq@f*B@rmSCD&#M1cnXss zkhVy1XB7-j=c8CqkTbg3*=?h|mH#NOU=pE9JgHYM(QNv8WxQ5nG7=fWRXa`}LxsR> zq-Uh9dy`$yLK$>bw8ITM-+#id+#+MaXz~g|-3~w8T!+czYPA$wl)H!+n0#Y5*f0@( zNhN$Yc-Kd@csymNcCuBj(7D*6o@Ducs^pc?N=DxBI-P}vqgz@rs8?jDSU)i?lLM?H z#DYm)cEXNNevsZyi&csf^SOK+wIZ2LZL@}9bx zQ#k8Mt&-zo;Ai0GXS*izY}saoFh=Q-$?Su?yB15a+*t2!Jg>9OZDreZyc?tyU5|bl z$AzGiZDja5m64ShfkTSL-m(D-d+5+qN*B6lrD|yIqWgdep}4*QJ(Gq=Qr-sFWOjNL zr964bocD>egl}tHjT-&Wd7sqkTvmws$WaTV*KewFh#0GD8+-Fnc_9PlZ*X~2hNi3f zbL61Ge8vc_DI?)4$SKhC#MQ8joAOhS&>8idebFM+>nddOr}rl9qL?MROGx7&xUc#T z2;UdIr+ziYHi%emCgP|X$&I2ww6JtcCBP=HF=XzwQ9eNI)DIt++}U<~Iz$2SayK9T zPCfy*Qm1f2S{Zrmo@%vz_L?+Ag-Z7nPBPPcWgwOHZH)8Onrb)XcnLQ;!_9r}Dj! zgWyWXnx@!3sXjXh7@q8R#TjB}X1)wUgw)a!6A?s{@_LwL(=bF+l5ksL_9#qgYwt~0 z8aFuTjd3uz3cKq(O-PoTxDUtayt))7e%Rn}%+j#>j1m}+avAV2yQLdNG3B&vB7dA& zJXY~6t%HSB95FV|P*4V?+nFp$XX0yG0aNN{I4x>~;{pX8+jgJvJwgkjj9S(()MpWo zv|qxiSH~Y+0=F~M2pu&Dmo}DGP7j$h5YnteVD=QjbLV#B`V)u9UC&&~yzj};=ROvc z4qP+R$BNk`vqog86T464_dm{ayK(hsGWlZ|A@RfzljC3S%f$?^AzXt$jp7mnEt|!< zSRRgU6`72lF)83nLyqBBp_E$XJdKM&w?*krWz1~cdW&uQ@>(@a{Y*?d&9n%$tep?z z#@<;BOcBrI)#F6+*5@ot!t5N@lMDK6@sV1NR6J?@2SJn`K3yvHhu&!7sd(qW&#%1e zWE%C9L!KaTeAFo9ZQyM4nD4=#+;eqFAg*3YBfU1$vHI5g$!Rd!^s)b-X8#T&k5j^2 zX&VAraN_96IE9HM58z;F^CMQXLcUe=Rw6f;%4vsJEehXR&GwWRb`N&+57&e0J^1gsW97>;W$McSgy5Yc4Gr?2QJvNO3xF@(}r-v~aXL zmrV;#llu;MF6sgLH|?Z9NQFzgCE0AY#=)UVCRw7R>M?DrBig*yPmluw z4REA7JswSu8ueYWF7kVN?Obe2jv!Be780? zg)*z^Zs^#3Me~*UcBlB4xwyGm_DYMh#!JaESvxq#04F~?=N=WgS30L+kt5KP7Wwi2 zh;>H|;!v8P>uA?=W>Ooxhc7E*!dr{!m8vBkUS*#!=;WVSR(;L+>gzEVNo=%^=t-cv z1qSel8Mt<>j#;9`s>#?E8mE66jlA#rWhbJ1-WO=Zxn=rZRa94tY5O${IP8ws@iXvT zQ>PU1zF1D|G5ff|fGQ<2>F}>|zCCcVUZ*-UIk^Pd^G}Jl3{q_6*h|}TXi6#~_cz}p z>r(ljtDmVp(U0Gu`IkH8{yv3=V{_f0 zQ=*TDPVF91Rky>YFN33-o&j$HEh-Se_KyF?UzGRaEjY#@z!4z7(t=DgDJQ!u{Aw- z)qx8&*Go!K00Sb)*b$5P5=u!kne;0!5OlN{t73<$XA_+wUV2;*phX%2x+%F0C@inR4Z}eDLe1b0%w}>r8i^)^Oa=oUw7qiq z5XyB>bFXDTndLtZzEa&I{bDh@`JE^lg(f5|&>x&2FmwKMMK=93kr-!q+aLBdtD_MN zRR2p*C~kzcattQ2Lr$Bav!XG?3s$ZkfSavLuMW)J}8om0P$;)u3i?qK7<2z3RQ^LCsM$;px zZ)4X{-l#)~5@@}NjTjghCDn%2PA7@Vi=y)dSMns1D7}oCiM*}m&vrJ@zzi+Ccd8H| z`%>1`NTUN_V)DQDNP9|($$3}YW+dQbV_r_?`w3Tatg8%6=>xAQ*Y^C%Mhs5p-O88H zv#^f46Vv5A%mG*(wT(zA$L*pj+ORWPqhY7-up@!cf#h&7HR7A)C?< zhT;2-P)nAub#;J=zO(nSzy%#YluOWc{6qCvUVV%C@BeQmxVfl9)Y`hxA3N@=KmYHN z?pO)1LP6S(m*-DtA^o?u)7>zve-~1Snw~~ZN5g@&tM}b2S_yp(dVM|IJ{Anh|7)XT7?N{gfez`iI|YU&YxYJb}rO6;o9pm zx+oA87ASW_D##Zkz;1}15x91g5f%YM63BmfdlGcTM=50Bg<8i#Knj~=rtU&t!pG2M z-2Ar?)#z7;4b0WRPTAlGbxSt>J%L@%o}FG7*c&6?9SUON44k4q2hSw7>EqKMwlC}; zED$SQ#<08e+11A9!2${&%#gMoO`|+oN_N{cp3vC>w;p$>Pz~eXmxE?b1A1DuBzAlnv!@31aaq`pkxV<5PVtM~Ux;kb5E&Pg7RYt5jPHTKw%R73oC z=dJD7OrC#>FOB@4>puEn1LD6o$NBFzo*2)7S^aZh>4IlRF4HzGNb#|)oiyx%jBCSUU z2IbLW+@3iuxf)A+ccr*?3a>hIdObd#d#>J=le=TSMg6x5#>YQR5Mig-HSfML!y1R7 z_glWm2;azAqM0!g8>0^JH<@AiqTn`1Y?62%w}~fzv&TNLSCw>D{Rh2_vdG5w`&$6^ z9&WO_ssk?TYAsgVayw?a`aa(LG`TKDwbm9t?nj*u`n}FkWBC0M;4(f1SRDT! zW+LyCx7~qX`8^`GjZm_m{a|0+FRZX*H3|9dc_WLA@L*<41NE)>7c@fpEl#1G7Q?gC z=t#K&CzBb6>PMeCb4o%V=KOogRsfLv|3UT929v`60i*r2D2Qp0Ym64m|C|N5p&IKd z$M)&Be}KwsFM}MS26?o~j3e}(kVVI3ptP9S!GsbAQEO;w%0`lO)jA9!h0UP=cxOy{ z^nfpR?%vK6p4Z2#r>8E}Gvp6OcJ(c;TO%Nqaccf%wh>Mh@Vmp`*VeX_F~amPPp4ca zifp1-m1?L;?fLl8&EfR{x$MZbHEA^FGXll`-fWkvq_lLl!~YftF&7*?Q(Dys64TRt z59()np&o@g<*L~){kMPRj*pKYUvZIO8n(Di*zm9s5!CLFTsKs z!k#MX%Ll12Y;CAVX#S4$(wfN+YJhv+!RYt8%g#12G4WC7<#W!sbrRByk*^U;D?jl* zIZ?oZE48e=d~bJGAUb~I%kD6bGB;-alpR`-&Cao!!Q{QF?E_7VqUzb5O>u#qw+s@AJj-!`#kPH*KQb#eapf+U7 zdl?yUNBfy7pcQDzc-K2HTW7tuw7h5MhN<+bSru)+Tiosao*vgW4-vA4 zcboF1Qeexz>b5{bn|rvwZL~3AdzEC_x_Efv^_@xpA+VsJ;Qajj$B!RL7_9U_pn@5tZ@b_)6JID4cI-vj{rP$kRss!lSZ=hUr!3 zS3IA8yofY%a(JRF*ENzUOuVy2hxUwZ%B8z>=Qf6@9zB4hv`H8Iq6Zqo4lZ9U}$|) z)!-#MGCJD$nspUw1ToQK4yGwpOlD^z)~?Xf(MeM(k~5go)YSC7*bU`2%vBSBK-3T( z-`)T(!}lgR6W*oPS%+yb@l;#E+}vV%cjgjgY-qe zvaqnQC^Ee6FzPmKv* z920*j!?M(ZW4A_9ET5X5nUS6RqpXoIR&oT~{}b}GB%(w~b#Yrx z5cd@*i<3TnWm{`#zuzyz=2$r1Oly8i-HI-k>s&N^d{g@waDwN;w(L?G*W0Sk5SB3x&Qo%GJ$1z4IC`}d@7Xz~zHm#eDi;H6=`qX8D z`q~mWh?VOrwgXxTU}0{D3xdFgr(=6l;)G=qSe_u}PT5_6DRpsqHHsAR_gMgVN8p#GW1-L8L5j zbANuCIHwW5={g<#CRt#qt1`CtP0-U>7b|ZBHZ;8)z@~PDyL&v4zDAfNq!TJtD9I!bYO?x`K}|g zIm2H!h?+v|U0zWGeO`0y>m*C9vh9)A#>Ph{UT#8$0;+G+xtf8KCl3;~UCt{nQwX>n z-`$*nQCro`IyNfC(GJ#vcFIPWuHemWM@4W}m@p~t8CCN)rO?Q0C@T;58wZqD zSI5}+0I{5%y&c$Gk(88FG_yzERuM;AI%Xr}dANV#`#F1XWA2M-_sLpcyOEQ?Y@$p) zsfgEcgDp8-WO-;YeYK}#!EyCflgYp=o*I0=ZWu~jSnIb8L z8-SScA?Dl`Ujp|(c0$n?+Kd7DS^GvyDl!uulxJ^a0tklHfk$U4YZzTtO+RNRdhP)0LY+r28_zB?%fyBQ4$LEIQ1`x3=v*$u?B zM@?(kuzHFLxT+sgy2>AaxAf&v>JGT7vR1y`kh{q9OvFd#Y=RaG9%Z)lzoORJ~S za`W;|HL4YANPD{Dh}CnYDgmlBFgOVO7cA`?clY`pvsIC&M!0ErSy0Va>)sn}eCY?0 z-h%lWrBl1Wf9`Luj=*LcfE|sC9_g@4kTjHdmOY%y3-x}(o}tgO~plI?tBL#*M=^-PVVlLu*#ZEMi&5A*t(ye__K zmfW@i)Divf4zxJjizn66((g)oH{EPl%;r5UYhFkHXKWb6>^!eC;}X~l<=A^6D<@u$ zBWHg@P0pmts7f<5Fi<;x;M2Y&_B6h~fCrh^nZORuV8H!fig`Z$Qj+cX!XV7g2BWvV2=Gmup56B@>^RxRI?7 zC$6p@JGc?|igU;$4*v-^7nfi2SR9>VgVS==kU!Z7o=uvHqB2%W@6L~pPgIJzo8o3j zEI-tNNRXTTzWYpM^eo%|au$H#+1VKj3rnVo^{YjPRW&ZQIBJ`;>Aed$TlBtnu}j$f zzuffo^})`;>Tc#Q(O>)u zTyp-VvU}ToK2hTVe4oBRM8-T#6borM6kFC5WY?kI1beku!62&6h%cvN)O*_RfkBhvj7Ys@~NnP`P5$yG51}q zSFW58h`c)B>L67?Z%?I_567l_6t}N-huhoRKUc2&dwJjsq=BR9{2aUVCqSCo346HZ zOJ{3Yy!RH#D$ep5aNv7X?Ep+O`M?m1L(b>W8%cTu&dQH@Id^x~!2QVAVi9;7m?I45 zQt8iPdiiWvJ3s!3?9wig3;t+ktkgEw{`=A}Q`mE4$Bhprpf0DRv=8v%+xOjFyYOy2 zt2%6Xbzr`tKIdQN57PPGg3o4lCW^aND^Y{wz?Y)pnNy1pux^kpV4$OaAFTp0S0*2g zv*ER_Zlmo)5ny7EaRg|<@@8@Kauz(2V`K3|Zma_WI{GalN=#(bwE%9I_mGFO4x(UF zJYuz~*u9paHleNE6flGSc!tOEx6FPAeDPrm`oO@!0Y-R#R9@ZD;<(tth>gE8@6>sJ zS2yaI$y?sfmhJWDW3%hlOW57nDy)139q+gOM^Il=D%J1VwE-#L$8+r36cZA98XB4$ z?+n`h5A^cZBr@ewc06eSUl=`?LV-^}q}2fhZEkMv_)*eORaIN|n7ABx_iq~)cE2pXRYc& zy&I_|a0eEHeA)vJ<{n8WZ@Lm59XpRQVBohnTi${rW_-dF(I2wj=g;g-jE|EogswFK z8-v2`ufW;Wr5_zezLbpdWX8vHyR82VeEH&ET1FAO@F1_A&}H(1Br1x~3N;9%8?f#C z7_fbUnf=WNf%@G=-&6M)(X*ktv0+VS)b9(zM?VJ!^lScnij2gBqyP{EgUlDuf)r2O zOdB|b&ieA7B^fLM5pp25q#Kf@E`Wdz$uJ~5yDKw|E+BQJkMDPEl%4!A;Wxl5EG#?^ z>+pnthw2v5<7}N)i_FDPe|X&Y27)E=v*xeeh3l-MqM}>lw0RJd#(A)#;m7DVc|O3F zIj_Az%T@ab?8ybe&G~d)9_*L&7Mf2ep0=>ELgs(3t*bkKa4ENirwq>Do2&2IVqh+v z0#N92Fz4P;!J0N{cM1e7x7?$$@%kW~`X06W&YhFLyg%1mHl~fErGnm_q$E^NR~i87 zLp72Fu+6h|5kQCigZz9v3*%!&7NMg|`|P#~1g=UV#eb`oRumr}A8cLB%FZ6mI28}H zJaunpYd1ioFx6@EOGwj{kqLu_6}$OM&z)x$@FR|z8v)Pqx!46x3#9Bqc`oX~AE=|= z%ByREa)^hA$8iD?Xz{2IJ-2&7f3-JL-Bk}T44~=FYB-gGq9TW@UE$0gAS>BPNhiDI z)yNeQ+BXWgAsn4|Tp4V7N&eTX;mNFe<9G254F4*)aU_?9OffaBL!m68<55q)9D`Tm zE2kS8>|~74DZe;g?FMxT5MW}9I6(eZR0L`n!?3CrZtIap4>-k%$OA+hf$V37$`*)= zt=6MeK|w(!nk*YMVs`cV#S@?+LdU>RY-q+q2DY(Gfn$|LwsT^$dA33;gVpT~UE)JqYSSGt<*gg*_^67~b;FeFMcinspAHGsDD$1W+lk;^zGELJ2_9 zH_dS1@apg0wf9qOZW#Y7gSZJ4D7xB);W}3)TBfR(#>L0qTep;zmNK!hlvh`8J#XGn z&L5+tqq}MBLJM-f+@BToz043wq*@FFzQ{Vb>(&CO?)kY}a97Th9ch@UUQ!;TI)PyH znU@H5c(+~s^wbp7qSioi&X`SYT^)keagZY00iJSS&euLLML@e1m`X_!ruWq*HcmfO zOv=APqZ}-o3y>uk`(J3AM;$+5P-$BYBhO2(S~LdR`yO!;Y?80(XLA=?q=H@dc`o~V z&emEEi`ce~iF<^`#C}BC!sfXOf3GG?6n|5d$7scq?J}(MRAj$%VedjlD9UTQAc7h- zBF`pG=b`#kl0aGl7g6HZj$3JI=>z}YF&;w$1M(fi@GiE4JjN>H&WE3|&(*ai6WRuB zcsxKp3^D|eFH!<#siLCd=vXyu1tQ{^zjJ)QMa^q;baa(05k1hr1Ydf3wtVTD8XBO{ z8_ck-W%VuQYoRFMT7Xhe*8^Th1rk%>wmFzT!^B|HXPPX*U0|0l2L*^sfH2{_Ge?n+ z<7hu0zcOgxan<0|OM2Ya0CIum{+$kp39zD3(W^Hg9dUiSHj#yBrThDe66aVo_uxBP zV;<3FWPMHAkph8qVPC4{?8*&(zApqDl=hVQFVD%5x?k+rmV%8$a1#bk5JBO>jEguS zPSKVpZ9O3&^89>#-2!Bp8l^UAM2KB$CzCTX2;v};-x-XRmz6!1(_&1q9c?{@G9SSo zheAM2T^(uT!@ce>;^>6PH z0P*}~!}G`zN-*HXm6fB0tv;0$8rsI3W!n)#_C0PHvi)j7b$BpapN^JRDbtLvzcz}cOtz_d3ChhY0?$c($eynsDkpq za5hH=79?*|XVrIvb^ULt@YZ)|Mf5xQ(E#wc-; zMbWevfo=RCzgq6_M@S+jCVmVp>@cj}9D>3GA5{;J%Ro4UzgI`q7UT+M%!4ig0Rdp& zFQDI0?V^&BpLX>!bLW)5#sePiZoqz*q=bZ5358vST1B8L4Y)9XI!93ciC4{1-@X8U zDkB@jBC6Q|Zo25*CP4@B_fEw#;{|0d7ha#d+@^;d3>tMqx z&ERPSAclrs`<0u?eye)v{U0bqlw9$r+u20`JJoxf%~sBb-nGLT9T)d`NLHUh{(#v$UJI{_tp4^Yv;Q+|OL zKRMvo_{d?U!Z5w>FJ=(Jn54F6>$VVZL~=x8nmJ|iPhy~VYarDH_0kQPDtz*w``_~& z?Q$LeyOTbUXhWC%8*BD=KXG(`bnrbC`)WkkX*7ki+wA{q@2$V0?%sa!5k(PDF#tiO zJ4ERQNe2W(x)r3m8x*7@r6m=VX6P;z73uDh?(P`)UgPIHXFcC_&L41ocv$!HCMMpo z_jSE$?JlbjBx4jD;#<%(~*~tKw-567bJ>afsE56!mdgC@J4=aer_%*J7|&7QAV~#x8NZ8YjN?5 zB_G@dHeJ53?=SE2+Wdv9VqG;C`}axRJV#=?V_6xX=Cl)WXe}GR#lvPWs|ukZU^b(e zFSM8b+JyR;9n(5jz0)C(DVMkpbw#3j14Dr~yw7XC8w=gMWV@1IQGYlc47UC;Dv&tPy6wgk>%Q~)4= z))Rt=Kn6Bt7rqV)cFD)G?tlwk$l3DV*DAN*bI<4^YqnuRn3Roxq@j?&neF$28IgrT zaVNIjl(WbvEj51qdeMRZ2>~2TMjNj+uDh6r;m>>kdQo(8@A=F4VchuM5XOLZs2B`R z8*uC4BKoEZKJDF|JU=_Y#v^*?B37agMLkzF-|g&ZftXcucdcUbxLgFH!BGmrRq({W z*5a{q&J(Vg&8qoM1#hj1*jV#_iDWNx+DS1>+0h11jVHjZ+^?Ge+aap8ad^;M#o(me z8c3>H2utgS4)z?u=X@?yZytSoMwi=9`l~iW#*9nvwh zpSKn7zlPl;08Aa68_3DYX;f_ouM{*0w^73d$B_Nq#ctVH7FSSGFT8{a6)w2_2TIbt z(K$E{P-@kAok`0LcoP}KSjC#(g3?NwbkA~cCRLKF%KF>-wRLyez$q9B%9@&_roMcV z7{>KoDK-H4QA)7q2jLR}!0?-Yze9zdDK+i&xM2|X15ga;nqNvv!G*wwp5p2bH|G8O z_fHqD_b)lXY=QukQR`P##B;AHpK&WpGo^fNJ5=~eI_$nimE9bMV?pcoGW)6@4+Ta( z{?SyoG+EHJJa)w>ddMJL=ybDDMkI=*75eTIhfsf>afjZ(o75iG03?bHQ~gsl8BG$r zj^^U@PFwY$IaGL!R|DJgdzv5pCXP*yOtN(CDr5o5?&w*~re5{auragIqbdXtJDORkrMgrx3d7t?WmJ_!h2ID$=3O8CZ1H7~rOz=@=Ja2-=N!6o<* z7pJD7L855ZUnLu7j;fkJXgK%WoFNuh%I(*K<1ZW3t+AVvIiCY&cm#qMHGi~^;V>8= zOt;@$BjtSwo2PIXNpL)3huWMCY!*PpL3<)`$JlNnk9F8?eYex)nvt7k2B^&s-(%Nn zKqUg7?xs!%o4mlsk0kRnSQqYJZyHWZ8^O^Ux$5)h&!4;O4nwRJW04VeJ^OJHkR}Gr z4v4S`nSH)$F3;WQgec8?R8|&-Rh{pz3ktqx>OOIC?4hK@(-`J?B6;Zvih>F&?e234 ze?y=5)7;l77^oJr1|9D&Fio$pXQlgu1b&KplQxJQ6f#qJJ&i&}LUf-sqU^R;gug*}G4S=J(H zl6h_QL9~HAdn^EiH-Gn~l*k2XJISF3NiUyN=-mT;D3tjb0AYjHxRX`+vrkw} z&;8t8d{Uy(I})Y+uy7m%`Qn}z(t5u^;}#G&DeaZ#aAyxH0~Ebo%$^#hF*4`owC2_W zBQvQyY!T$sLl5Ch-+B%X4tsmMS?&_(Z!xj4WPEl%y{_5`n~#=zo}Zz`^D2ZuYG7by zw%=XHdi!Q_gN>1KxY}_A7PhQ*x=gSzW-BdpKp*_bZU~01&Z=6^!VY?FDuAu>FIJ-o zt$@SgbCYpPnDE1uwg!hP6|T{_Q8#SX5$HMg4EKxUEM2Dq1FM z4D1silW-VQ0p&_XB_@4qJd&o&q&rO~OHT(ZgokWw&JI%HO~3^0kC%ixq5OQR@WfVu zp01^}V&d}LrwPQmesKJc=JwY{lew=mDs&f}5S99saZ4*;haID&!4iFevj$} zKqdh{+aSv~pxk13+GHPKcx3Gac#BE)9eiRhj7&;Ojg5?eek*!0h8sJp!kHu{j>0kF zwEv(0(liOmnyV|r?I6DQgJj|K>5{=59lQqHv&~LvDt30;$9pT*b$bIK!JT}NCgXG2 z{FGd>I##sR?7pDUdM;CbkH|#`8pedzWjJ=C z*tOo(3ePrE{}3FT+hvsQYusqtR{BDY%H*@w7Hm}*UwvJ^>fl|KpUdcsC-Z^anO4MW z=qxTm(BQSIs_Gxhr=are9C?JLA?;*jzyQ1N*{Ly9W**mj`T<1sl$3|z7jp9Q#^5*U zAIu_YXldw-UVrfu4Dge?cI_I>8~M@x*#$|N$k|1WsP+Ud^Zpza5YzB0pmH8Se^2Ij z%*oFm2e1c?34=2mWY~}9zayjQhLQd7^g$ixp4gPs?=N))Te*zurTi?{?#9nDhp?g%Ns}W8R9sT%QTo z<2O_0-O&pnP`4;n%J2x3B>vpnOY)o7@!NZCah=1qo^Xvc+@qlksXz9YuYCnY%%gr}MDrxz zPdK^oUZ0Y1k=TL?Rx003O?dp~9aD^8j)%*T@79VY*>lX)s?`IbUDKdP~j41y|K`CX@#V z4l0}t%z$%D4eOuy2@8Ro=VH_}Mdla5x^e+ZvAY5{wY5;&3wBK3dNyEbPkjF8uUK^mab37bS@w)1E4NO72~x+AgC+7)wjWqb9{{ zg;(ksl5#)z9yB&2_~3-rjFcEFzzy_`I-@{F78e(btxrYXLnU?K0mbSCzo)AsYij2x zX+Hc?I6a6ofVgDNqtjil+yN7FKlR<+1ekFGYmRbHpRIO%ZsZ!&wjVZ(1Aa5?6|hls zd<=FIa6!Olixsd%m7deE;ePI`DbQOHE42S!Fl0709BjN>n&_*V4qoaDL9@l!-7 zkO-HtO56PdZ?H=n?{5%>YbT>Pn;A_yKRJTR^+d+%Z?|(UvcYovYE==_>9R)OPsW2% zHOii7>)odg*IN$a_|~XfL5p=2ZUb-cdw1K{9=4qyumFU=l*7zow4C+b>4zA?V*~Fy zpAFehmRDAs*CrnPh$wDrYa2|BXTIa&fxJ~0Vqi&gUv;Jj3Rh&t<(B=d;zg^tM|LO!<`brRe3eG~v)}Q_* znVvFkjVpO#Fq3*luQ=x(oHzs6Z2QZ_PmP7x_?Of_B^D&kM=BsQWX%E`%Tk&%6{SIu<50NV5s z`V7v)0YuMcryUhfao;fyL*7p4YROG7=bX%~m!P6*)i~uF8G`!+PBb1KUVdT*DJkiE zd!lj4QO@VjQy@HGoSl|AKNzbj6N4niNwBNjofATg4W*P=EoAju2O=()LRD{x|8?X{ zkB*Kx7P_WYmG-=jA&ItybS}{@21Zz9K&b%fWd804Kkj@{khsApyq~OSRS6R4ZFYUe zQjHNvGuYeN^(`^IlSU--des*9sA+4D(1(63O2aQBHmvTJo{;LSk}$ho_TzW5AJGrNVWK^!?CGACD%%;dEWehg?hs4brRO94buVI)O6YC9Hpt zq)IXKA_9NqIg7 zMgXIYa=4gp1UD38J&3f_piovIIlR7}ygk=?EwP{;rZ~p8huxIQ z8CVH$z!_c$6Id_wa;j{aasB)D$~tT^I6FHF9UDU(&$UbDf4pj3Rbxj%57w9^Ym_rO zSsCP6moOZ{dR^z+yEkCI%A%FpeP+cyNlF?D7op7kz$&vb6B;;Z$>Q#{pJy}c`YASW87TJP=&{&VY0-=WhXnN?)O3)0# zNx7I#1A3lDmcDL|!~>)o^D7u6RLjh!mUgvehyJdv%{GqCF%Xcs$*)tcNM@sM0V^$ z#g@70j2%K`3MI3zDQAWa!2$qlhO)B<1*6&>ObnmK&oB3`T?73X4cZDMI+&*v?&am> zMK54EIzS7^neTljE4u>S2LceQ&YsXz6A}{I6L~PEvj3V7CfyJ*%moT8s&c!9AT7oM zt_~P9MYYN^tdAv*X*32;c~=i)$VG61ji*@+tmH1gPi>fOn*vpGMr0f zuCpKf{r#t>r{RK)ob6b0_Qn00*?IN293wdJ8HKzVqe!d>D6H#VWwE(S0TU(mWkX6xDdp|bX~CRmXbqY($ZeJ zfl&>>9tFP(1*OrU(hnG}5KMmAK&=UbO4CX1wBVlVuS!jrB4K<(I)ouvwKIi4g zb`wm2oyr{guaIL#;uI%FNPsktBc>@_A@?A#qipF^(AAxo{uPXIL`t%)fTX%WI1Dr? z`dRy`j|~s27W!{IL{Bxf&s}kjCa2N40M2>h1~k0yOX@Sn22H@P4ls*v1zn!QG}CZ} zCqs7uXF(S9z)d(Nk>kbm#sC@4Yx0oR15e4J?{5zRRcJIAp!`ol zbOEvwiL|ca{XB;r^?=WSJOLWHFXAOgfCIX`NrocmvlGRR=8)n~r(6TR#j08Qr@j5! z4xeo#4Nxj{si!;OfeMrEADd*&At519}&3HG_#-0P+}Ok)Gdj z0R!Y5^z?HKaH!pqI^>XGQ7`;ky@J9UiGUEIQ!8tQAfT>bVz%o$Ay!dIR7hId0BcXASBKv#rwk4fqgq}bRcN6E&XBjWk zLl&`ybM>XE#xSYqR;9;froD8hCbY;GmX?+#3PIg%Jt)xHDnYOZaAEiNWiw=I#Is&g z5M<@%LLH4EB!of_mZUrqX$mBEaAnU$aGRmxAJ*aLD{pyA0gjC8&OB86_QZ33+KF(j za%JV%fK8KSP`ZZ;PZY>TA9jvfHQ35q)sJk?%wya$NOB~+((-EXh7e9~h8&)zyr$*| zgdLzmnGIQdOiaXN=zz41Hq4WSFTm9Io(`f1QwXZLV}HMzfTd)w03 zOG{H%`}w|CM(RjT5^6b=Y|YLvlkd~1XLjjNt*oppE%WVi$3IYW0R-))S-MIVK9%*U z3+#n4Q|#T6Qga{;MKIbywcb4PpzJIpz_}FGKPbDm2Xk#<$MjZE5_SxKt5V|p?5xS} z(lr2~)yILo@(L@hqqVL(kfL-1%`}X3;neHAL#Jl2Ku-kpZ?rNg_zZ4vz8H1Gsd8}T z0qnYISuvhLZeHL7d{_8rHp+dqod*We*>0wY(BWTSnXp>d<6YWNd-oeCn;Jj~_uIG%tAo3uNfzlPWz=_ThPT?g#!ymaNhYD`K;kGr_&dDX{ePM8h{g zZ^Yx9TJ?Q=VXnjI^#;rV!clQ5YBu13%`N~5H0b#lQ&E?3@}di1w9p3v`_2s~ z$&RSVGOKYnusjaNol}$Z1Yz$|X);%dx(t9RYI9+bIr?s?>*E1|t8qLBm zGNBQudwF>*(ld@eG9c+d3vNkYc@3m*PlfNE;=^#)9{kDc8h=VkS5lKRV*!$MOA@b5 zHk?C-6`;*67m{nuJc?#g!)g%wjg3791y+2d*H@@o(QEZDCUCI3sCY8my>S3y@TkRZ zKS+1yt0kQ&wr&Sws`+!N-+JW*)=fA-=BDg0=vg=Ns4@ zelaJiE9O1zTq*l1yHSaD3dVWZ+TNbbZrB1u5Dl;A?(*FS5IY5qi(C8jl3;BJ;oMvpsoJdR zPX)fYJCxl_vl=77)_vr=Vm^F$Y}UsB`U8&3`{3YYVd-JvDj8@&30J>eC+AnznaS(r z_&(Fz+A09k)wjch%Wc=hbvg+A{SgIgD3h3$4{4&p_@U!Z*ZKPya$V=MU?mXix zYeqnI=$^#`8;?v#s0Pgd?!5n_R+BEKx!GB0Gl~!LG0NNO(A47aP!C&gsT1TP7U@&s z<9UtR;xU=NCe{v8UJxWeCdV`q0Ji9NuYjGTo(v^{OZ#re{X;~=BlxHT$SsXCfrsapl7`G*wDyG*Y+171S$Gyx*-kWjb71%u{8wU3SKw-fdCPw4tlfk zM#Y$2YXqgZPhGx?VKk~%kn9S9_;?s$S+A*G{42VWyKdwUD4W{FY~LB^X`z16LQ4gaXN5A=W6w!O^?0 zGyE}4KTFflLT<_@L;0#z#`JUF#~^?iX|eaQ#U|RXasq1 zO__y^q+CZ*Kqvq7aFijnJLB;}z}YDsr^bg$LpILi!a4tHKaJeLu$o93MpjnKzAQx` zUM3T@M;Lb;tm#iYfv$onKYvOT3??QdVCog7>Vu-d!ocu{gOnEB74V2C6(X(d@7PBU zGT$)8l!3!e>xazDqgCc=8m@l3t?lPdz$YQez*`+G7x@JcF@RI+Z*MMuERB%~pbBB~ zRZ2>?jRaynzJr?vD2_{SAIv^*R3pd@4bHdc=jY2!dwtm`txGwD%cJt-`G zEdmg=`~Euf!-w4WJsp1$stLm62g)bT8)XHO?z2>39TMUG^Hr~%h0Y3+e43s4T==LQ z^cERPjG(@cIAYums#3(>TKA1U)gu&8QOC&6ng$lb0X8D_`_ZDd+ zP2P1n8#Y)XqjaL<5)w=Xq(5rpTf85uWd1m|*aIPJ7~U4J;}DDp@PD?`{kYbIt_B4G ze$U7N5(vMbXOvlvmc#SchfAc_ z6Qafa9i&8+=zm#B8DpnC5M>a zl zXTTTtAE2!3VdKIdz?Thnj>d@bA5?GWSFku8uIQZ~Lng@pu6CM{l|8Fksm`zEFHfpU zRBiYYcNm8>%9ZlG>Wt(Lu}4Ib(L97k(;*Ics!~$Ffq-7dzx!NSxfIq`0Fe8SMJ%!7 zF^R!qnVAc7b8rVxKzm^tLtv4kRizkcE!=I_I$dh!?;~@$4R?N5;irmVtp> z_sRLZ86*?i)5EQ#q$D`rUN`kpKQOC-Ib#+L!>z-}i7+o=8+>Nxspd}D=5jS&I0J?k z4ILe<4Q`&P0CDJ{h^b;nF@!kyVHUzyf54Z_OpF!}st`nj3WuG*2Z9;?dM}#f30y%~ zIR&{}{$-zN8b(+}%f`kwPIIK=Iv0~J6`H_q_#Qn#R|iNHG%{e27?L?p!N(=H)8EcB zdD^F>aO5GJ7;qps6CxtA8!?r&FG^tpsM8z5EFgSxd&Iw>ZuC$Kymcf`)aXvh%Ke0B zXI=0haJQ0~t6?yS|E|l7$Pd)11%BcNl#-8J#(vrz(>21 z5{FjlpSCuO-i%N|4tHJMlqtpzz6FfcOixYS=;d!dfXe-F`X^{Ld`2pulcrGN{ zHlQzzLQ{qPd>oM0trN5mBokq_Kz^dk-`-0T2wAxB@gm@Y*;aKO9gH>sCPu&`DG=$8ZA>AJ zFtZM8U|U*bGW+8pdJM9k=lZv|Eej`rxgiv03ZYVnWrs|L|7L7-ARIO(zWYM{xIm#H z#8R$LU-vBmLv~sr=IhZhrTA^DcoM=Nl5S&!X)K`TF~Z|NBqs|25y4bVa3IUP`=DC5 zLXfUNqeLqCImkC?7?eLvcT^|{Dpyc7f@GZ_mnDPa0uv780U&}yU}?ipu>>kLmuNi! zW+$}eYoAM9dd+%rLgUW$&J{b?ofJo7hKF}L$+NsPcDELe_gZ9viY?k#4~*KtmTtrMgS`Z1R})%d56Ln`W9@8mY=k2}z85exJGn=PQ{hz!%?sST!4Y zw6g%crje)y<}(+m(okh%lc31kpqX2kI}MF*~u| z&$8?`8I%8rZl?EMqD4k>I?ueVihL4of!-30K95rNw4n~T_To&bTqbgNU|As=J@@EK z-iL79>gH9O67e)|Myk{98Xw8UtCWN{KPOOB^)n5WA*f6s#?u1|WL{ z)yqu57?B11MD#s#80EPq&OHWsLO8FP&muPez{ zPou-HnWq)>Z}{KfX8G>cdkCALcBV0QZAQdv<01y`I{W?32iggd8;wevDcGzyS65F{ z^B4vhArTQuz34}W++_#?fKvmXZsgfz`VxwALDhT$Y_R#PuY@I$;(UFhKBD}Xw)uR< zS;xs~Z8442hkjuDbpKuT8IZRsmCI)0!h zU=&~`;@0Rj^RuH5g2^#xJ3ted40$f9y2Y&`fXvNg`ezU(X5muyy8z$qa(F6^#F5C+ z7b9bUrrY}>v`EYwwU8PP>qp(skF7;3$Q>C4NSwb2M4R|_un}H8?p_S*AasZp`qV~- zEES_3fSC=;@BuSA0zd+TFA;ivYp^abobX=P$5?N_0k*b$Y#cMW(EvCH0J(Mj(R`tK zs2)kF&V%q@2#Pt(o9B7YwQ~)IJaFn?#EXe*xlWWwgM2a2nwWPZsQD{S)UceZOzU$R zTs6EMiDM!b0eY@nruLViH}X|YsMg_1|M>9(k{QzBw+1n*#r0h02pcz*)zo+(?*{w? z64FJj$FHR|wli`o8zdKXV>tKN4v4t220fmAQ!D zl-F3hW+m%e3nwF5fTv<8hs5No7jj6QPZ`*Z^tCh2|7$nEc)>p@euUjGT)(@aUK{eXrx>kJ zreovDHNmE}gkIH=G)pjygkUvXLFM#&jS?e2J<>dqJ^Y@R7vIT+Ni0XqIw+jbaxw}U z6Uf1a3g3YhVQ%`PRzR5Tuxf}8Oasa?A1+^qvUzkxy50?wN9jgN5vi#KrLthYFtW7| zh^O`A$|-<$B7Q@NQ~xJUrczLjj>py}*vt><>7`%(dif*~b(lDJIb{Aa%cFH%xpqv? z1rf<_zaS6t6wdHLc5srdqPZsQ@gFWAwB@b7zjtJP!;qbqSG!g|D#lv~0`x}h$vPzF zgH#nUUYtVw2CiH$5I(RURu>~+TYx;>x@sWpH*;>WM4%8qZ)@gvaUOZp3#?Z*&Ub)M zs8{Q<1$!z$*nnD-IleorM*oqcMKd+(@Qyxn+RQ{!*lXjbHDoiWF3!;VeA{F8o#^Rc zHkSP*2%CXVunWu2yJxl}^7XqoDvcv3`-{@9t9alRQ8A4$aWMYDBf8pb(Sbd$U-&KA z*Tly|cyd*v#LIentqXu8@H`{t#&^Mg=FLQ;<3Iu~pjhBBFth*+m8{zzu2zq5J8dfn86 zT8|emqErYgEM%s28`Lu+9uj|b_JmNy#PmcdaL z6}7u2#f`_q@_jlX(UScnTa>!7k{Pj1-0yxFf+wu?nXq)!Limc*(X{gQ56Y9-%P~fY zV&cQ)fo>aWA{GXF%Dhj~gw#9fbWX?VX*kn;A_n*(E z`eTG}8s9C_9zJ7T?qJJC&f~uw_og%{j(b4)Tr)pV6`{>6v&3}DCSUKS(_urQ#v5?a z|E@FkH?+3UWXzZ)@vgjR6+>|HULt2jd6mt5^~2qb!D)WpYB!_R4O7p`skOKJA~)Ab zEOueQzG-y@S-8JIhy8wz>5GTLsbUuN5|-1%lgYcbG9=Ew5G;tInB?T-NDzb@m69&} zyp6eYA~0ZFe*C*$Cz-q#-FDl*W6i*6-M3UjOy6KtM~sDFj9ZvkZ%#n%#f*GJW$O1z zW+MlOi^AC7@G%cg;?{YbFm&zk4#FH}`kTaV4xIn~6wLd4E+Nx$|KxP^ZZ=gf5?+VI zbxbAC`~o7QbOv=O{mP;_`2oIZIP34aDss##e*7-v+k5ti@p$hI4YISYR9#~pPgpgu z{9)!8>(f%KznYhqm>9cnqumg19+YarX{0;M89pLH9Oz>Plkt#~WHr`bv(lFrYzXy| z^&;6hN@%hrA{R+65$IvAuiw7M_W0+~CbZS@rx4jVLirNl>3@{nTok*yE}Nk4l3TK z63QzEqpk}n)W{xVz0)R}Ty4u0Pl|V59axD|L0_;HO}=COHS%9#B0#$hWfn{{2%}$= zOw3t-wk;%y{PTh!_}^Sf89}{1UY<)8c@CCKxJVo^4U&}K1R1t4Z!*>TjbLPQ)#(ucPW*x&m9-Lz7SnUA?{Uhofr!oSCFIdsA&++cp` zc6rIH{lr?jfvoE#xBNFO%*<(1($ytf;YWxP$QZ=b_rH(FrYMJ%mr5^6`pofD-d#kX zXe%^-RTCjz`oSFQ*i3qYcqomDg8X|wOtqCTEz{2C088m22Rro8?CA7~o{ z<3>B!0UNBTNP2?5**@^$)}MRZ`q$@>S@10u%t-jt3!g6u$>D~v8b%-g^N)0^+tnWH z4a@)f8U8YSR-BSqTdS=LsQ}cWAwE$nOGz91fBqS0eP6y-lch)ZQ*f*3zkbQmG*kRh zZxjV@Lx5#Ds*<;S0fFdZaP=*>f^WVFcjoM!=<8fTAl|rer6~xkX|K_{+`5iHh(5g~ zNQRc#*t*<92tP60iVW#dY23QqT>u~1ElM2`{o2NtVhQs-joW2-C5g1Pe?M4@i!&@O zk4$C4E>b3Y1Doaqc8XXl@a`1v4-Rc}Q@-DOxRl{lwTWh3jvHv=zg5amMVEjZnD2WQ z(z29Sa1jpVM~<=0cGfyflEV(8xv#|~#V_t8K8Ri(e>eC<&TC_PX?JkSU$$CucNJdM z3wwh^*~!Jqu&CH>B%Z8=)O9$*F3`;zExV_|iESoNdF8>LjNC_~OzyGQE)N@(a(RR* zie2E5QPPfa#6I{NGV*LDg4$pn!z1*?fvccQ~E0Rg2Izh{4 zH}>8p*k|i8wN`{|WZzGVeq{ZN&awGej8khblRGcwjG<(NRF~H9>(oh)Hm>K@fHa-atEENyawKL|)7V6a}CyYY$C}x|s z+R#H`PP5rBE6#9R*l6#uHue4*T$II4ZuJglF6SjF*Qv0eI$#`@Vr+(?G{|Lx`{k5^ifC-G;4uV>7u z32b45yrX!E?&wbV!wHIlQegv}xfQ*fPRFL76D_jAX?d+`1@3E6&r;y{pP8Y@oV_$&4XQh_|W-x zxrS$L0qa#$J`>68Uzz?5>K~DUhaU*f-IZDz$dmY{$1Ts~Ct};ZLL6fd2$LSGhN8b) z*nUMQ?4&C6Z`gHdV4a@{*|TAl;$k-UK6_BOEC-gcG$5Ull&~o&s5_`HQ+ebAU=|TTSK2+Z9<2hldkf zAS2V!_Uvr#>q?IbX!iO#*n_rHT(+-b-W>j7yF;)cJgFYjbCQO~?(MY{Lz4}77~D>K z&4?+*ZJ8A;aRHq_D!5eydy@iR)%R3OD#*pgshs7egZF-g{|x%UN0XMCV28a+&!ugx z_!MVDS>yWADv`UtYA%5ZRq$DbdR^x66@@ykMQhZnBmaf6i96U%XTky6dEc-oCC{uW z-f8U}{@B>Db~ovMcCI%$KEE*=>UE9kz?Z7 z#$LBN1|s4~i{a{sA+J5D-7Cl)?tV7bj(ba~Yo89yZ?jRMTdxY-hy=Tz+B&Sc*p zYm3gQO%Ney@ftY49;Ie>mYjLo__PFBr@O;Ozv7KMda9QGsxh+qhrjV-uaKxp1cE3I zDe**E%hcufqjR!fn+Z?n$<4c%4T>fmNxj>R`jqJX1c|h&n>Xz$7qjoZPl=54wyfznB_llxQXbIqnD9?*8}Xuvn&c@F z$FCq=H$~sDqC78GZBSa-2+7j9jV>bc{^O%d((dLsWu#JESvat8O~b@mTJEXmDskF* z(bXx3ux08(x_yJJbVNR1%XC5L@Qv5$N5?n!@Ny^b>^cm1@3hMl?u<_!3e!QmLU8EEzL^E?*O}`%zUZf6goA=3OF|r0a1)8=z8x z6Sx~5ie}Cz2$Ix#8ei39x)bjx)V|M|8`MjFQTl@HYQtsfExf0J7t&ZRr;qp+A33)x zUaZ_~OlNuL{j7CYFScl0q-9K_ZgCfXS%Ekzfj2*9N~Y0`-||*)m-`(p3+fYW&f8Vt z7j1$j+nm3isbwVZO>r>uEsBIS<^?4;XmAH>R#+tuHQc1syB%!6syf2hEQ z_H#d&zQ=fQmxqzYRwtGF{CfPFsVZ{`dC4dG;s#@rrjgUol3pUh5ov-b)z@;0l&8g` z=QU5hvELR;XB(RzEN4EN;asue&@R}J7_=_ttvC+xpSi)}mGkZZf7v~QQx9KW;WKfv zc^aSUj=b*~nrl>VX9k=ZX)5O}KV^lfQdNKB!P5G8&rb;(G@e97J2S7_3+V=kC(qb) zOd3-Bz5Q60mlj!!n)vg-h#iUU&ArpE%+gbr6B2jvJvKMDeYlb;)fmorI@u%@zH)m| z@U7@KxA4HTnKmKP?^=O++8z{kNoQVHPd!T?zSr~kC1kI6y7C}u?mW~{=VjcftBSI6 z-ngTKM5+^Gw#IV4e#*OE953296s>M_8#$B@NaP9{@CcdJl4508D2*KfD6&}rCG?gVp4tc(C3HxAhwgnF8*b5 zXFx|(`QX)q2sBXkhQny7<>b3Rx+v#10&&=nN-siP_({N#^8kVP)O_sh+MRm7Io5DM zKDN~ud9^OURiO)mp$H-`g-e4C`E@iNIXUiqG#LSA0c$`uk5Rq1+ z0%|Fm*bM93qKYSMj9tHGhv*D~vF8z1dVn^X(H|)IpfV0W0+{~#f^-o%=qQ*d6_ONs_XA9-F zkGB2Z6y`m>;B^}J2CU^Ka;<25{De;}Sl4@8a3w z^fiDMu(_L?_g-=BUiYtieQfPc+}i22%EWg6K`xE$vF%}80)A6&nbxdHfK1=G8259y zY&aSVoo@3a#7sHwn+{+wN#8k9VYSgepORJrzgFf+^d_4a_M+kN%qmHW4seB zUFR>0ix5>Jg2fY;9GfQVlLQRj92?>@12EPPD`&o7<-Wb6t_ByQ(r=uE1di+F6(L{v zAJu<2L}Z0w3Aw>PJb!3^5{ms#1_D%sAoV-qe`Ef`Q#H)ng6aU^|9_tF zKUe90hQ|K`^MT^o#|3%47p3UGZ%2F+y@>}R6hRvP; zGodM1h@VxL_J4QYNGjUJYoI}D{cCSHts3JmzOb&;@1LJWVg@!rZ1kOM6sqN*Rra46 zpuW8PB|5r|sG%0tPylr@>_zcsYcscM5ERb>>MPF=#MjS{u>Vuq{-?(L zPbG%YDoXQzwjbB?lOp2(=vTiRZ{uA0&$pGkfE=lhOJ$MmFA8?SfBTsu2D2a(yy5?Q zw~FK$AVi44{?T_=n0|(Wo3SVRP^ZmQ_$DG0e+kz%q<}#HzvNEbL;t50qUq9|6qqi! zHR!Z=h;=qRcxT*;+L9IV=8(X92?#%i?hmMlDg%NB7ms6y6+!W^izAR%)Rz`P5eEJg z^h?}G)HWo1cXpDANJkV!@xki$x1m=vk>+BzbyzyAMMyMt&Y*T*L3E8_IpzYD{P`Sd zP}SAw5(d9kb1?xm-X`2TbF#$UB?wUow2^X+u;PcJE{3Is!Xw-YM*cYYWEt>QB$Is< zNJJejRT)3G>W$=xbv%h}M~OPVedC@r8jzQ$aNm(tgXW?m-|~)GLJhw8BGb)k2P68P zIEx(_qC0og^oami1Uk^k8Mii zmhCuCS`&8#hWOIm-?=VX5Iy{;jTG43E4qEgDgF38-kZ;pr8?Q8scm8};-`XEv3Ux6 zPbrvM78470^Pjf}ZxffBCuVy%-H3CAH*b0j@?HcFzY!cc(?Vs zVq8bH`pKZQ9{Jw2OGYaF4tu{hnl4bJ2|^UO2<6KW&c-my*df>czbF%zf^CMHC zCjWPoHc?g+_PhEz=Gg)C1UNtceQO)yj!|o={>c85z(oH$lta_$$a&88VjorQe#4LB5iB{Pr545>!Y&6!N?5po`Ql&We9XuA#wG%lbSoA0ljsU3W5WI| zPv$tcy5iq?LQ=}DvHUkQR>|eDIo)&g{JW+NodTx_IowO^b_kDdyt$`drZc|PR-ssM zgTTPvTDW&U<@nuakFpgWjEP;Rrr&VJn)CTl$deBl+PEh{()NL8?}uGW%ua8L-{w4+ z=P<3YW6BZo#aq9}wEz0e3CwGgfp;RGniR_k9=7T4h1%TYH>H^n_Ws#*3H}BL`QEI$ z$GaUN7op*ux<_eO^1l9^%{wB8AFl@{iHQ%X{WF3b=I*4!$R!B+{`c{H#h+Ppn8E;i zOxWInvlGQF`zk#?MtJ)(mr~Ui4dw*#7Q{DFOEu9z&T;R^^)oKC+sC2%FBPwGd{z-1 z_xLJe>hNyU=q+7fIdkSaz5C&v3rf0U`+b9Oz&V1t&t2(mzM-R%rxyzEHM@9odhg7r znzlXe1okQW9c9x8(cgmF?UqM)ro+|g$F$(Hc@btV(a7gslfbc5lYfjM-0GA%e1!c~ zBjkD%XW88_BCdt0?~IHHErRIkus8G!)xReZ!7Sqc5InBlIhr-i(6Mp0S(IONWA z6Di*#wDNa9OZVdML!;R)p1+e|VyJp0p%;O$BKlm;?0Tnas?eeRcr!7X)6i^PMVWi4 z$*2k_UGA_1SKm}4)vLSf847~Sw^*)sr~Z)-p9&OS%exmF{l-w8B{>p-So~;6oVe0X z=kSQ-`++j}IkFXJyFzCD8gKs#0}ohI@N z^TJpP%4fd`IiKt)79SdYOBhGUWPuu-DU!=9o~4mb)jEFJjj25MUwdJs)qjcmd{JRJ z%lsAsG1zm7rO^bNC$J|3-{`88$QYA}Z-gXs^q6br`VTzU=e3RxR{KD}nTnP$yqQn+ zm|A>>sFj4oCv5)u$OU6{pZP4DGD?jbiaa5n$KrV#9&jeOKHM7J9E-{pzjZWTC9J|lyy@z4n!AI! z?cZ?!6%z!aP^{XH>GIP1pkzRy)L;J1luk(TwwJT2>(cDMhKGh>Ms;Fps&!FWRv?=* z>k6|`(~{7+EV^e0Vl;jlQ~*Jg24+G^`q-}hvj+&+{{u)KCd=Ky6n59h#DK>(n2OsV l`5%Yjzn9nlj$(JuFYH-Ux{uurtx02) zEyiH1A&hlqEaSUJ@AE!S&)4^S?;n2Sch5c7eck7Ep2u;V$8|*-=&3UvIdud807gv> zwVMENAQ1p)-W)yvUa7f-uK_>kT{TQR0Du`n{i8VpUzG%a(}1Shm0Lb(i#YV-Jek38 zi=B7S0|oeV_n&ArISg6cIzo5z^igKL1DC%E$uSm;y9B>WJP0|kUR}N9umKp#DID&# zZ%p|b^b#jR#RtJ=4vjYc&) z>ka^r*P*oK0d4Xl@6(09-P;2Psk<;VGjm{Aou2Ns%m$`JY9+7XwMq(WIRzLH!Z%sy z(eIE*8pa1bxWdDkJ!A<7L%|W~lZ9(arWaP{K1nD$QyivL4=i}?Vi;^0z1ex3Pf(&F zUd^j0lxWZ~Y5RN%w7d};8{1tl!R}ruBxe#=i{HT4E510Qj&I^XJ!#8{_#nX;zg|KJZ6VLVc}h$;3w9N(Ez$P7@o~%Ok63u;Gps0~^6tt6pNw}s{cPl{p74b%Hh!+B zkEfkWDvQeXVjGu40%rYQve6nGvH}NCH}`<}h-s}pK3v9I_%e4uz&xu$NRJ0Vf=_!L zy6kSI?0$J6H7#oGvU~&Ljh}ASp>E%C7*AH9!p?6^r_}KP@KlYS4p2F#B?AC_5+|5| zU=6OY|165o-)^uDxW3iZ6_tV-TaFmcO=Sjx@A#T~yuW3LM739&U|_z!ZXXf5RyrpD z;L(&^ob%w|_AbiAB+w~fjW%KxX#xO3EymO*b^4o=madS86);_`naZ%l$k0;gAt0-4 zy7TR7O!M;CgnsfKd98!hWl}QEjmuEmRF@_mr8NkUjs6qcOC##%IgKcn46h->3eSv7tf04 z4ZCVR*15yfE46V<3)+9~4t*XxRdvorKAS__7OQZ|%VsMk*$@pzrYL5Vy&IgfO2~IB zFdC;XXpwI7wQHXfxI@2q=8p+s>GSq8nR^}eU%m~T~QWYP-(Ja?TB%zMw@A6vL!f3@Pcgov7DMYgA*p%BhdP|Ap&*x)OY z|J(&-`uUm?tK#D`bijHvF>J6b-nF}k7KphZaU$dPxDd>=an{#N+#)p}yC@xyStBIZ z!0J-;!pN8|KgA~1KEF*5M*c8KCd(46YS2rzEsW9?N=i!YZc@E17Xt(?#Y~c!8&N?h zR3ejNUVvpn4-cd$^oy=;wr7Q3;Ts&dih;A8*Y0x1&;rNKPX^-QR{iQ7jiu3Vowy|r_MiG`$!LvEa%>YI`6PzrT_y{ZMjr~n&;j5`0jdF>Ij8pAU zvFo?v(=0`yn=g#{!N;i+oJLVM`GZeujkbMtQvAku`9 z@bndtW6oxn*dt{Q&skf9ty*`UWZ*r?LxEbK0e|%54V)~HV zTN&WA&|st|GDfcS%#hP0eA$1X&ai@E(B&61`si<7gIS6MUqvd;PZm2P4+d{));D8z zD8-)gH6?%UV`W3rt**3;jKqa6fliPT*wp%>*M-CcZ|tE0mumQylH6x&_aT^+(>?z+ z;ZcN_?L90a->sx;NLt(RAsmMZ=Onc^x83hXJdoi6%B~S|Oz$G^qA5=_+=OtqUi}%) z8DTuCt2YhV>?LjyCEM&ZEV!g8T3>S%ICg6bMR=@fR!tu;5J}jzE~`~)*2`s1)20I) zFA9F~MQgSs=D30{-Nff3Qh%AFLwlzU{&Og)b??U4;2Zsv77$6(09RW2pKA$nk&6i+ zwf{po*|ihHIuzE|duZ=?C)Msa7>Zw^0ZzZF$7qZN_}b~f(d31}ykc|Jx(xe^AhsEt z-ZrjTMq5dMc(gcNzrE>p+sAjH+aLpV}Q;8SHjjdf9Phf zlxYfrJ^4`zvX_3aae7V|i-=Gf{`}mL?lSnFz5g1bOerOQu^WMK(w)3-g-4YyCQBnT z8Kn-#d;QA_PuqeAg2in_6eii`Qb?3jhoJzVl5$`0OJGugtasR=S@Q`GDOmNrlZ=uQZkEY^0=RcN+t35buFlwI{967W}QPXztTWbu* z{x`7Mjpn$n&Bw7g4Xh=3rzMlSiwp+VXaED9sqJPA+7_&_EWiqHxe_f6G+jJeYc8FN z$-YYP%@`Cdu&={8w-CS5_TuNJJG=%2dn<86CkE8fQrpbfI}->e->oin9t;K(!rS8H zrHrhtY}#p)iLvoJ8IDnFchjjVG%hWjzIws4;`*ORYogfK=j>~RSC437+WOg&-DVX?h#y=P(-Zd`2KrrL; zAt2pK^rF=Q<8ro2LP~3AgXQc291dpqCm*$Lh5`9m^Jw(VIuqVq{=8ddG zbvP}MW!BCz=N+Z!QLQ^(5rdm%B}{%i&;Txhu4Mu!0?x-fBUpr8M7Wge8`mbl5m+!9 zNwL(S=$EPN@&91TDm9lC!5TO&rbQPl_G^~5YcHrE^W>c9weg_LM72y-06S|D13tQPV~=)A#81 zSq7n`Cbi-CCa>DFt8@9Oe@Wrx$o1r?PHMat>y(VGMyZ)7*DCp?YFteYSP!wyEoyo7 zg(gcf{+I8ewJ#Rio7pTt9+7MM2WS@J{}JMhiziALK;X;bri!BviRGb<#xaPYG+wh| z=Q{$wP*UjaXwS8oaw?M0YI}_4Hd}q60p`yK3>7j{M>zP&*k?3{@bc4V-@%CSu4{9* z+<$EA%t^aJP{GRd zt~PHhX-3_Kf1U;abg}30o9P3BZ>>H(A4W-|;BA4t5|Rw&-8PxM23$Xj%-$Jc{0DGlne-Xgj67llg8j6dg^M&= zeIi@I1y%fuXw8P8P^sTPouUDPkE#;Gw#^jzSoed~9UT@`G8Sk8COc4wkUSAo9dB~R z?H399aoQ2=1u8wvNvR_(D>3cObRbTtyn`$=cvE#LdS(X){oTm7Nf-cb`{?J68HG>w zOV}L4fzquJea80}nug~jL$&!~L>FHkF)5QeXK_-Ag`-2F|1~56)Tnwo?*e{ihb1d3 ze1v0+J}>v48Lve|Y%K@F9yP(TZbWW3N7PiTP~mlxe}R?=TfQr%Rq%{9_~z0LlJn<; zdoq&TVeplimzGz16A1Z8P0O_(1X0ZMk!_Be<8Gh=!u|WzRQKDddxfEmj^`0JH+O2T z>AU=_x%{+c`tQ(`SE`tHLcB{`^t@c^)^a;RYNB2WB66!k3T5Ik(VX#f=otQEdH zWI0lG$$!sV2Tri{H78ksfD+6n4}QV+@Fvs8zzzS5*$tgFz3S=KgS|SEXsKQu?G(!D zar_XZH;Ak;-r)-VE^wg?>HO2GT?*e{wd}vITA?~}q_Is(ns=yP0bSc1K!hMZbamAp z;Rbr(R>Ux7_3pgwrNz;PJ$ZtOKN&?vC4Be(QMc=6Ka0SLHA9vpz+RcHUAV^&=L)0?_n<8duCkSAu@o_dpADQg**$>ObuQcu)EL- z)ypj^9;3Fj+yBt(yCWRNr!*T>T$mz2dFUoTKVFF3{4;s#H39Brui9v zZEq^^oSOtS>+YC@(}7IJM!z&-SOirTuUhjm?Du)PpKN1oKw3X)g{Ni**&Y8(S`&A! zyx|Y7+=uL3F)fhf*A(O>(Y*3M$yjCgEiWY7l2w9}KN8nR{2VFvs*93ij~#{^tstu8 zvBQYV&pk}LXOIe_`MRVEBzq0H#BS0ZVKM$p8aO7t4JsmP!_Y`=7<`?EKX2L(!H%70 z%7Z`pPd}L619o)G$_$&I!IJVy=ea|Kd7P00vMwl`ZBV9m5S>2P<^G?R`6RwXl%M2i?Z^nt~Ch*uFvcj8kI|$;+%>^_nS}3 z3A~^Ua+-yTryugOL&cXFpg!g`F@J+#-;U<4uZnR>n6)j#A5zNym1&AJLw!veY3{cL z<)bZF?D~42Bk#h@{F2r0y9H#W_j`83u&)TzV=Iw*D{8T;40SXoy~1`?ni?)%0699Q zn-0jj3XW{$+_za3nTav3`S`cTa&$C9wckkg8aeN~6&Et%Mxj*XKDG2;h#{O6$Y*L6 ze>A|q0GD_O)e(vgdjblq7p>7@wgGbRHJSCR;MA)3A_c2x0KXT1>d}Z9@!0F;-<1*+ zMSnpE)ZP*r-Bwvk8n_e#w&03AYbXMaWiI+hMytl3WDxHZn_W<5pYbiJ1hH)Db#7>c z{;)XRnBJMpKe#|Aq9BPEYm%wc3pTmNyq9~wD?8qc#3H8W#Cd%cl$Gg%j#g`49+Qa4 zN#O~{|JyyX`L^IN*LwKx;?$NZNsr1el87@q|B~eDHYPDqWB0qN6<&hqO&(6mz<_`r z%=55be8;)mb_t;=(-_R#0`dDY}GC+IiW54-5!!#*o_ zglHN*Gs5Pz1(CKzNswHGTWFS-&ApRofV;Q1P_DDN-ox9?gI(2b<|GLP5pE#$;S$5_ zWkCYy7puJTL2F(D9ibl9t+o4g!_J#Yf7%y6oE?@q!ldsU(8Hsbd-gyZCvfWj4DfGm zPh^0~XXUQn@k^HgJ9;a;%a7n6fOw!vKX!*v@c?UGt`dEcu!#T{Q>$WfU zslcb0%?^U?JLol-zqKE)okmGV%#@nvyyxgJCh>zFhYBay9&C?ZJkdMzEdcqz<1lDQ z{q_T-HFHSUoD`#j9>3q~*>}u9gtWrncFd^EoUQ%%(e9F>B95|Ky?GY^C^_>&BhYV@ zSq!h_5$9xOuYCKuOHSe!`!9JHu>9Kw8tD+mZh9f#Ea$M83MB2S_adsGr4vpL-iRtE zhf}k4X=rbbyE>q8MSEOY%vL)%Y8c2u?Dq;+J(ehPf%MqVTj{a8ba4|sF?Hn4%`uoY zB+6><#=b9vU`YiDbWL^rgY*j6qK%x2*-yY4M&&U~`@$U>sc75W$so3Cl=Q6H5>sU;XDfiDoDx-s>nYCCs8Q&U-hw zsouu3ZvyIg8Rzph?#!C{yf@*(V%5trxJHe>b=IDz<*sRb)zSPW9dNzJ5T}Arn z>+91gS+lQJZ0(MzSy3(1_;T0#XD8y_V-`9OK93TV<#je%*+d>)2Wk6$ZxCbG-N#$s zmBP4?6PTfIqj8^%LS3Gu&7(LN3PLB}Cw3W!SoS&+J&5V5OcADe6W-AtnU6;59=Ld+ z?N8u#A^bl|^vw+RQUYOaTlWfo0y87O&9-pkFnY3W`;lEZPu(VLe8nbJ#L<)cE@y=_j#q z;+1<}m;GS=@Qe)9!2Gb;@ns$8;^oS{?V+Tml7v8PDjUhH`pDR!u9l;#^#x6~IdJ9b ztJwxv;ku|C!t_q9VH^5I%lpm}9r!`B`+7T`!yEbo9YkX3GP=38OWKz@u5%lVy?eQh zD>88ehT0l!rmXGqFBD@oln&*)>`}I>cKT6Cm!Zq+TYEYEnql>UJHExTy1fq=drwd( zWEa1o(t(AQY3G|-wFVk6Vd*A$-OydSP|2wbi1zH-Y@-k(i+&SE z0(hT7Q*P(V4X0^|y~?5Mhk44LrMcfqZI7xJHOx-9-N=m`%lM){|5~?h^THB?`teTY z>(;kRxp2IpFdFim3|i-hd7h2)6DUG)(1?E)bUk3=4Kfd^8l@n6ZZ{maKnZE}+(5SN z3br&LM7<2J?UxWFW=HJSiUo-*b1+iO3zj`j;#7GQ9hMWH)6w&>yEsEBOl9Q|0TfY% zXWk26xG);UGC9HO0$fScpmLukOJvBbviK<@@4%uA^R0?Z0sE7=UwICx{k(&RC%AJW`x_nLsR}ClmZ-}o zK`AAawTU92w-hlR2??OZoEgs_u=dGI6E(R!J&rv;HB(jG_1`&|G2P5+U;o@iv3h&0 z>L+tx!@v+JIm(Wb4NrfxBkz8HgzA5*g!~~%S~2D`t`0Jwc;;AUXuS751qn*A#?q;| z9>gz%$zU4T5rV=5^u-{OC%SJ?E%^V#@@f?PvQPrHnFXR%$Q-Kb6WF)te{2le`x}~^ z8#O%yyl|+ki~=pL??qFU;11Zn#hIVKzxR`&F$FqEpvBMnw@pO32EJXXv3s2rsCV@N zc80jhy(+N&VJ}J8qs0NJ_0?=a$RbR108J=xKR2`OlrcIZ2U$GSChbTvKaZ!YudkQc z%M?-GnkhKKje>b>iXjPTOq?BYVR}06A=KmWIXOkq9&{zrz(>+%I4LIFY%IO|@!D&a zY00dQymM zm6ZZ(4;5pX&WY1c2(*9T{pIz)b|WA`!E1wg%cb31IR*Tfiyh}?z9wMj@)ebR^`Tci zmQ|k@ZJ>>>58&+IwFJJI-Hl+GqZ5H+T)PwA%?jRFg;74Vayd*epa&OJpo_}gA46?$ zVW*57J4!aLWx99|_hC_eWJ=488ep0TSFv15txHKh->|gz;^d=fk%4E|nZ7G?g;jS~ z_x>i9(ixwuASBSIlyUN=IpdUeCDie4jjJ68Do|hy#cJk*Dq;=9eX0}>yDGV;X99EJ zyOZx)TCt=Y(nFxM(B6q%VZ1cW!!UN=9o2(w^}iBI2U>8)sb>K;m~Nf!vo{d9vE|ZB z)@}PzMAVkf2S-^|B%!C z+^*^dK>#v!m7dP4_=5F-V3}FmHlq|ACM8vMFu25^IizJ^ddIopz=%>woxj=W_w9<) zga9AgGu>UxX>5lBddRol&f4?h4&eJ4)Et90zrEBizWM0{LmC@%@#6bW^QFQeYWKSj zshOZ2p1qek$dR%fSg^$N9AO?e)h8(lTYG|ENAsJr*B&f!`>1S}-|Np$mxfHVm!BqqRMRmxFZcalA*@+lWKSRR>Ez zE4IvK?M2bo>avNmh$z!21>Vu8HsaaA_rX&Ei5@j~!aaNjA6VB-c=BTvOd5P0alhlL z4t8gU(jM#N7%!|5ka+k`H1~lB*Vh~43{Z+{Ey;Q*hGvkhrbi^-?SWxv5|?pbf+&Iv zK1}h{Z(qT)0-OA>%C6mQCBE$rTq3cbTX$2rE%(03>{MDmXG}5PFG|+-Gp#n0W8#H- zjzsA6y?f)85#Rxd;ROJYPu;yb#rJMkm1BPe_qS8y{(f-aAJ%#Q)>a3-o)_S`j^QHU z`*?Pr9UVWH6M1K+xZz0fU`xx@#oGX-g}Obe_Ll?!4^Z$o2JOCWIMOg_6zqJXIlH&i zrOIfk4EFb4raqLKVDwYZl(>Vqu$J>WR;UQEKbuX8U!S zJqDbH?j2wZKICS|QE4(?P5zvLaL7(+tc31WVuJ{SeYk0P*iDjq3)4okBcp9PbkcG_ z)Z8zi;&E5gyr{>g&9R-QDUIvDPcWVr!hZ`}>v!C%kzI6fVW*v~clfj#@$Lwe#1Lu7 z9lP0Vk;vif>IpxmNp$*J)l~W*UG;XjWtxV%_yO|?yyXd!;21t==XFfo%lEazx_KR? z*`?DPN(X*-WsSMh(7crm?DC zm5GaK2M@dG;`h1YM_QD-R!-yb*_*BW#Z%s>qiR zRU}+k@JP*hO+_-u0TA07+tQu_zrB5j|D_4OeX#e8vwTtI&WSY9Mp+hMnE3cw9hq`B z=ID`t^tq=pAFIX+001ctz@ z4ErwyJ*%VD?oJ`XuP}iBaSOl7y)?UsZcIgqq|y$5FN>AiS?H&h<7u;$69D5;w!oZE z<=voD2x?i_9E%mx4my+PXS|urPia@~`LD^bd12M1irx-N9?i^_+?P4Uw|mU=$+ob6 z=P^lyqXu>vL{*szsZ+|ju4enrVope!JYUiZ=u+HRmJ0RMFspuBI^uad3B-k)k((a= zNDdr|Z3}+Hz&soW9Ue!0;1m=F2n5vL~uTHIvR|5!urMuuP@gSXJ$2LrnLm0QkZSITOf-aXXu zR9p~%Lq5Z7;TA2T|59Xmg5grZ*uQ#;P7v?Zg!~nO%pZe!MiiBKw8 zfM6vvN73K@lA{KVLpDkMy`?G^VMlOgk6~TvRF1vn74grQg^2jF9c8 z)m6@bD57FZvvaNcu=Zqsj9>62=2~|GTMDIz)S4{YG&ax^rv{&;|Te}Q*ItJ4A{yF2zQ z)0@=y9bh-sq+(qe=5dJz$a8^oBPSpgl8QLyW;cC|B^ zIwccoxJg@|^erx~zO0&7i-(XnKhX*vMT&3U81NyH*-iJ|VMt;)*b&s!paUDUFoXo+ z{IZW}-p7r(r4QG`)awhpC}a*UEWD#`n(3>m{jAA>&%4a14vkhGi_CYRz2nr-v)2jR z!<`-j8dsNUdH#iEsbc}=*ToK;wO89ol2zL@k3oJmJCD^J^gZnd3>$ZA_zC=m!&5lZ z<*R*s)8)bME90VKxehb`dT(1vw5@q|ul_8(Xn4H#SLi;=lo7%as(Fk*P6bQss`e+( zC-Po#B`N8(J80huM4IAW4?X%$#0*KxkCch5RL^ysXD=h4jU7tnt20TL5hvK0UsF{Z zsB`2DbsSDUl@gzqq9_(S}@?;R$fL*L@Golh`XCFRRj)H;D||e?x11A zM${l2j9b72E7RFO|B>H_h-ZaII@A<5Pt}~fl7^;hJ;_Y$+WK%=H4&>;C54jxG1`9D zQ84&6U};Asv!`ND+vr~HS;Ttz)OEMvWu8R7;TfZaZ7)re(>=p`!>{U$N(HjVQwwoC zx)|gU=>=uF@8@$^?LxOkbl>6d9e8ajIzFbf4!;W1Iyuh6*>*OLL3hhBK3PspgaCrV zVe(vBE3WGuWgi_Df=9bYstr~K`-GXSUtlDLH6enL`U(VVuX+9gCEVuov@xtCTk3$Y z-ASv1l8tfuxP!tJ>M2oK+L4u6Gu>J2BP04Zgyf$CBv0#K%JoY(%)_*;(`^bitdP8(oZDQ3zSruQ z2cy;MMJh4WqJXwEZE&aK8yB~)rFufMcNN_gfb1jT+1 z(g+5#TKLx6mvjC^0nYF9TT7L7?yEU1$bsO5kAiA-D}(T^r2aLZRii>jyK~y)CqGfh z=&F_V&{HXi5-A|wbR^N2*xyQ>j<;;LOII}4@ZtS()sAH(4Tpk>WC|Xr>0hHBHlxZb zDZxpcwGqFDt-Hxu#GHZYsuCy~z?>yX{HQ-mf@t2Hs2|)u|1uEX7Qlr5ZC|{=Qa8?_ zO@3K-sqM3E8|NLU|4S0w>oYX!{rd)dBAM^c6sF5x0MZB^jlcCNflvR~lF+K;9*rio z&#+dmWg(Kk`3XKrv*=WvG7*(5R-4-_R`oKs*)hRrfT`1Vv$NW4Gz!deO**5*I(mE9 zW=xDTkDPz1e&l|wGr=rLskcT?WiJy*q+t90c5&PS1sKS1Rc@K#QVsvJnydu{f`J0r z5dM3F#yXZc;rD?_=>}uaydy6q?`QQBR;I%UKQ=?eQQx+q$}xIcg#z}eVMtqpT|r;P zIE{-2Ir4tFeBI{|)_Kj}3NM|p6!>%#3I(n?m0H@i|0boIAS#3Eb*DU)@=dq3%;Ju^ z*>^~&V374aMyXgxH)V;Ys+r7ECu7eL=4O`dVS#mvtrkLd-UtEWRt*Wu*+JjH^Utwu z-8&2i^E+<~2JNX7&&t)M2sHLJbMFyWVx$qmi=i8*a45z|CV4D23=}0ZVb<;w#AZIs z27%3gK~G)saU4^Jh!)oWtXF1tZ{Ioe!GF_Nk@tazEnqc+5HWHi0kSG zu6k{v=Q^fx6{+=Bjj_mnw=(XO%36J>W#~9=jLbLd({RpJqPB-^-G+78i=i1TNXdLI zWHy%;rvFQ72TUJi>gs_cl&X=Opwq*z`!-XxZSuSAy8&aT%YjXWN%W?p8rM@o4fGD8 zl-OYf2D|uZp#2n_b9iA1yIs!Xd)ZVO4A;mlFcUc-@5k+G;LLd(+dE{NEiXRXEZe*J z^{VZrKdp(w#LFKc`(seegME8Z2V}tmVqXk8HWJDDMLC#ct~;(NkE%^1#fUN+Kce0z zSe717(<`#mn+(3tizId!@)!qt4&8g`3uIeFdrons(ZK`1iH^#|GL0JvP_2=HBF*-O z2!Zrs%r+x6YobqI#WLvKvzZBLa2hIIvug=-(;(W)l)LTsVnp#Sj8weK&tyWZur_+U z%PNXUrh>tg`8`{8aodVI&VI${J*we`r0qSd9WLaHlXv&BY87>)<0(nzNuPvbus_Fc zOA4hyrqds=|8j(lM@;s0KRBmh{t;){2+tw>sL$kr-dmlDplW=sfM|mOcRTHtXY4?7 zSxuwE-+p`Ws9pMd?Zu_t>r&MBD6ZV~UEGUGH)%pU+FUrGh-dENK7S|?JH5BQeAfG3w@P@2UGbPgNYz_j&lX8qYu2TDAVFpM{YB)0jmopb}CAL{RA z6bvaZ0?-M@Z%#bIz*D!ogbk7za14$e_yDbJB82DCMUB)P0J@hg9+j$fv-tdPfG{ygnAQ8$o zz1?og+wf&v5Dcjv<`|#A z*JcpT^c4YsffF3jskTJ5{MXyScI6rTU#CG#eIusYw_15WIuUH(IjJDyKm-)*I&H}M z!H*A_aD7Mgzoymx5xm|kdqpPuWl&Hu=xrkMm4=i2OgP$5U|cH9w+6R0etY$vGRUM3 z&AAwb-tHNJ2(Q9pMql=Pk;^61aaH&W0F%Z?^7c!Sv!hd($XUj5+CLS}tpEMlC_B4a zXLd%M^N%fI{)}-0Y6)?g3Tmd;&ERQZTbxt6-D2_Ixd}dFlZDlLTJCv+%Kz@;p=a^h zoZWhLWT_lS6wn)pCd(Cz9ITIZUh}+de>~mdl%02s-0F)UXt)|SN!e*VoO7^}Bl+?x$@5)-G%|-?_dHtT?Z&L?~NK zKahAry(@xFgH^^;R7sybji4hcM~whFX=cEBRD2aRT+a}LwE)qDq^AbxQ zq+AQk&&=!#W8$fEs?>bn$ugPlql5lgkrSFT6Bc8qiDs#vKol8~ROY@(HLko@}?=Rg0Sn&mPlGN?Rim5;974za2(?O)62y4caCsD<_s~cIYT!VSJKMb14YNI#k07zaYQVXt);%rIK%wX^ZqZwgR?Y^Pl#RGVLNBPFw;a=Mw*a zLN!=}y~h7CU-;zJfq5}MSBF5VP;d_TFt%M+xLyzH^@4wvsaN=?W0{=Nz+ z08LE7s6&ANTySOX#QXlzuiVmW<<5cslP+WTSzJhc5x3);|$_f{ZWnx7jf@k0z9q%MMv{ zF{R#m4d;TITj9wrE3ak^U7*a(sB1Wa$cum~OLFWb;iG7{`pf7=i?=t=7Oj7YaFy&Y z#_Am1jxLpF{s)VHALMweAA)u;lc8*Up}6y#NfF`pl_#+#P{tG#b(UtPCML2F-pjuO zEXI5xXD3Btf~JzrU(M}A2yL(=z8zJh#l5j&k4redTYwG zyN7xA_+Y@06gW7>PGvP!)RKarkM_t5?Sb9xFU#J!%*L9t$HSa6K`p&vNeUbu@N-xQ zSw0f;mt#B;$oVC(Lr&WYM7^MPvm9l&j}V6X^j({;(`@{sU6Jl<*Yl$a!=qVo&NhmI?pu1gNm>uhP%x&Lw*3iet#Jm$F7{+qnSE$sTeayey^jR15*C^kmq>T% zkbw5nWXhR0EQSx2V1jQ>%~EB@X`rT61fu??>z)IBx%zYYA1DB!wZPA@Gni?O_VJWK zj#p7>2^R1jXtEefwQf3SreS~wd$&JLl`?cxl%#a)3%H+ZaIBmY06%}0yc!H{M)7Os z1^nv4`nCz^9rdM;^Iuv>nGZJ%cbp&$eD7gUxKpF@xMox9-?dSI1v3KgS(dyWh${!< zC}BDq*1S@Ghd0e)X;OT%9ZhEVpeem5X;G~_oE&z_=6bOWS*hL=V$@DrJ^IuG!zoci z7};9>xb6|j%_xR$64hg#Oln@p(ot!C3q*wmb9fL}{cIM6>NKj2Ah4eap*-Q+V(hE8 z&|z@*gBIsj08`I?6kB^ef37tiJEc{Kh6ge|n;V;&H1?oS5Cy+b)7fAr3Oq(7IpiQn zzZZ_&ySv97Z+Y3(jMX_T{=1@FTaE_6Qv3@w*!V~=SMG5;I-g=@24?b+XmYJ+Ic;=& zVN)yD?%4e&_VTn!N%9K{S^9gOl@Te%FUMW2Ov3gnU*sbKd}5DtG5}F|z1(3UnmVZW zVzML2hODCx3ZNpKnLqI|>Z0lBxa=@6Bt=wU0<63%q(m;GbolgdWoYo=7$Gb26IA>) zl#V2|s8@0st3hp(p3epAK&l{$5Q3^hb2phBmy#ymKfu}^2j?0#)N`Dy&K|>s!QqVd z31T$;WszM?4HBXGTPK1X2!eH@%!JSU^g3{T=&T#H<2%m{kfi%;wFo#SAFPBr&RU(5fztIqueNs;evvmNIabn2Q zOk0=SWLplhEmV(aY&$ZwX;9{ugP14BwEUL+a-BTOCCj>+;q9xu=CtC8>4=n1}-ysUyZ(e4~_0PvV! z{1(-jZpz{Bx;m$%`J+0fU_%Z#RU_baof4B^Wx}#*^hnni(0I16U7uj;w)Iv7-r7%4~N!{kCyrD7l;ULQn$+_+ib2c(5K=761sF=6rcI zj|YuL`!c^mamdT)y$6(4RhvUEHplqMDz((qOwh1unIIMpQ*NMW@Boh;b{D#G43!Jd z_jZkcnS)H1XJW3;8G*as)2V#Ppv0S@K1T7q_#aTJ&_1czyT^^nlehl1>MmeNqU*S* z38U|Lm=bvT=cO=5j)jDDe7T!pe;h(71^ujl9r$^zGKK%zzcR_|`OYv(7GFRViw@|t zC45KMQTAgo*<_xzPRIFP#U#VgSfK+cgHnd=8dc`h_bG?Zr>brGIJI94{BebET(mZG zKV@OZ!dyJT>DZe_qt{UKgWy@+syo}awf2a&V^DTuj4t-h-i8nOS+k+?1@Nf;@vr5q z0|vNeiwNyQl!gu~_+WH=jv11`TF2(_+ildx08^)i3t18#jfnqub0Z^e5jms82I=Pf zOP$_Es&z-T+)+deR90?vld)zxsU5dMXAWX3yVJ}BQ*K`d>-`TP7y~Hz{rH{#{#?6q z-u~rpZGU(wXd^!~^y2a5yuXF`VHi8<?pN?J!W#e|9UDrUbyMO3kH*HwoLu+(m;w+R)ueE zqx5)(t4pAUt(PDlh;JdHVWB0Ch(KOwjs#e!w_K$CH92IC5GKE@Y;-xCDW++EMwbsT z(JPAmnG~7q;IUb3GMd7cA=uJHdoYxB5$ltH4cOfGs=YMo^A#COEk>TObv&O~XS(ht zZ*&L2bXI7$l&KzNl00hKYYtavvo(vpqwqlz>3z2qN!$-=xtfxCy?-$8a$*3$Nam^) z?q}ubl^r*sH1sW0>!){@-mi{h#nWG65ajTf>@LCr!-?9vHbj+HOG+z-Ye>AxJ;MmvhPtQLKGDhpE_PIy_IA+jsI*9 z%8aHLib$1v=xu#0lJQf5_yy zJL@IU=6hxSwv9;U|511j5LB7n)6qJgfN^fPe};~;3)2q6Z7T&WfAfCX+6xn4F?Tur zyT{P9{eJy(SayIT+r;k6X@5k26wmH0GTeJKPGU|p1hEmLuYy3I-Z&Sh0s{n=*yi2o z3T)-yP4k(eL7}DR3L=m>sN*x)ZBHCLbtc<4iC*3n=J?D~5Ufc(9F%gae5dfO`r>nmvnWHIO?wy@JM4>S> zHo~}qIWy!gFroN}X^hW#7ivLu<(l~)de6+;o-1C>ESxwj*HBUr0B!{xw|iYm8J^-C zyYs16k5a#>$|{%jPNC*(N>_6b@YmkwqO`JI^5N!ss<&8q^jas(lu)_LK`!MR_&91) zp34lPLW2BDrZxrmJiIkR%&!k;(~Qr38C}lT@mR)rz2^wctycSH&E1=|yssw3&RQ>J#q7-)v6vmw zabXL)6~50}UtF2q_vY)fF}g0=0(zi8s!)@3yYCLS2PR{UE<3FdrBEUW1y-nc99DJ0 zA>c813cRMFlu7B4`kmi&pYFWsd61vv^z^&B#tlr007QR8$fcBSJWj%0@f_#FjNr(G z0ssOvug41k-3+(of4Pxd+yV`yl)f<0f1USed;ZTUl_9GvoFqWGUqU{XO&U&60<{%m zK%Y7Rda(n_k%p4T1yq$Ce)ClQmotn2scCY-T;Hy?BT;*B-!@^Gvbwywx}t`bDgscm zR%nXff63dA7tej6{iwV;M;?k}1_~TVF8}q8y+V7s!`nOI0$spmJQW$&&4K)jzMnXb z?2a8WeVYAEdBd`zGT(lORlDg%hYm~l*s@jUM6Ol)!F-agy``4R{HvV8o`?iQb~(pd z6_Xh){zokJ|Gm5j+TMXtPGK;#M>i4D-;0F-(j=y1Thlya3-gSILWhS#hqqKyKIf-t zebL`p9SW0-JylWVvbjIRM#gP@SbfZd2KQhEzzEGK&oY;^Za<`25plYu^LGFG#zsPg1M%?B6 zKROPB`I?5F_jTF6<3+zbz(=q1n&W9Vhlaj%z`h=KCox^~OFp5JljUEwyd0M~?c3dL z9_I3-6Pf-hHI%n$Q013;c|O;U3+S$$x^7qSczdo~?+&#ZRB3dcI5qtKefRu=7}xx| zEb>2!3qx{mj_2&BrDdvsx7YCyME+9>R@nbU;jyu|94_#yQC0t6x9Pe%HZdJ-qxwsG zr?OqAAZ{1Xu`_XROvNxMWK;yANxQIEUYIPN_fzcu*E6@C&Hre*Y#6`fHiLM@q~V=^ zE+eg24Nm`GEX*usfO>l&SJ|Yy*EJk@1{mUAgc^b)3%;&5wl9 zzn(54KQOa9>^Gk_AE7BvkMrH84ewmIwZT&ZkV}3FoTQIzMw;)6Job&Gp=6_ov?#x= zXZ&)zy}B?WfH6;EOuwb>g~>Nxrm-H$=^Jbjd=GwUO6Tp)~!r^*{Y43b&1d;qMR_T z+`+-&O6S9yr9vIFmdtw4`k)bxeUzI0cVVb&Zm4T*&*5Aw7-Gk{NBXmTiTsaY#5hEj zU}5gkO662No}(E*8eX3eI$A%o=f3+W3_*H#W!i&R5%Ak`kIA1^K_C}?YID=&}0AP*%sq@|<` z+Pk;d>v3+w|5Y;uq7beF*`^E{q0U<)YbXpyH^`j%|T0Wwd zZ{&($-H2Q6d2TJt=nhOah9yzqB+n$N|1zdc&bt-gfyWuYWKXrc+(mx!(nIkT%ECf{ zsX4~-69hQX%2cbq`)qYu1^K|dnl>!CQ@&w8d<*7B(UElb$O?iKV^Cm)sq#Fk_PpcD zgyX{~hi(LjiJOu#X^$&ok27+MlM&Y?!=BqxDv@@uwLCHDRnENVqewmsecSiiJqL{p zm*t$53d#D4q0h8=$!f=mG-IQ@o9a0T;ZXU4c=9kFWFUTvht2$9HwFUtopR9zwU(X5 zL!A;5V9wGm=s6T^^S0EP(EE7ZYW}kHIuZj)fvFYg_lJt|VDsO5yARjkIQR_d*X6cj zhw7v6%vD}85oJD~7_9{rur%f!gs@OnLvjXMW!Yrn9E*yrt*lV#T{a4cO>qHe zA0U6`489xuTCM2A@5dLRsxucUxihX5hkt#TSfFwy9E$7}hhjN%m~ zi}mHZvr-Bm+N|Z|#Ii7xf0(w@Hhd2e_(h}`&J?-DY*BPDyNA3oDgyJ+aBQ`3F|cBU zt8Gf+=uq+}mb&4|#CA*U471d+NB1S8LMQgdc0GE6qrmigASPvvI(TZV9Rr}Et}=y@ z)o68)h%zxWpL4c&_+m46;3pimbKStM&1x+;K8FsRoDR&LWYpO0HDam|s;s^)D=AGg z+vu6znk|jlr%K)VGLlq~3jSQB&TP}hVeK}<4u9X$zw_&%*Z@&M{)&MirkUvSfsJkU zBRrI#h{lUIs_TeZdMwIAJ2m#=|F0(pC$yk~dTT+eXR>`!_>+HCNXr!4!fuuR8g}^nQv#eeuiFl~{y)DB<5oAi@-Z}1-$wU$+9y~SEK{(ja<=Aue<(-DW-#Y#~vT@>yktHV1BxKX+%o6RJR4WP({bV>l zs0>`%PkT#jOJQ~vIr8sEJ99?Zh`m3JXv7w9t{8#>3ruTJHW+{64=@LlpL@(f;!;p# zdLX@8Au8Bd*yf6@l}`|;>KSU)G#7AojwIH-efcBK$f&p8nd1xnXZiZ<1=(fQ^{QvV zV55#E!Mgp*dL?flrZq$fPRBt6mk7p`7(TopSEJgxZPr7FkGlCtOoz<)l1aNT60WykO_f_ zKi4kt8K;@B4%k*7`v+0|i9G+kN8M?R7#ahy)`4QN9*8@4BuiAkeI-Nb?y@h^RH->G zbO-Nud4genbPJn&9?jPbS(Shf!m>5*zXI`J8`ipFv}MC6#F`a4B(n8GY_pUS{`EH9 zkogTiCgc-t78IHFY|Z{0+O2v16r3|~*{Tnwg)z*c68wSz{g=W$-bp9@2W`suznov& z(DXN`-_&cO_NC_Dg5fAL z5lL&8syFWOK0=9Ehpv{Q!_B?vR|)3~gW~?s=bM@)Jkd0yexFg%NC9JIP81#|#vug5 ziT&d7)<9o_rO$g!MNs^3t&&FRsoZ@p0^`=nu9Ej7aZ+E5Lg9oeX}QWUsWqualG(N^ z$LG?#WgQ(&aY9&31~7$U9qBE=WquX4U;nyq41P8YQp3RtRo)VO2QU^v0VxF$B${>W zER6 zf&weyv4rO{xq<+Xt1xDu(S`0ap_&1sv&w3;2&TK?e*aNRGtoz%L*$|oYGyhR!YHpL zN`9bT6}w!tQ>5b$2&{(&TDi1l6tK%tVNG4dhbY#2%Ho6t?73>6wF;W9c6X^e_k|)t z|HQ|D4ux)NdYq+UH=iq8NFwpPQmAM9Q8ZjKBEAW|UkutrW1(Kuvc4syKwZy`;+NF2 z4vaVROuFvJk!pTV=5QA>nlCOEROOcN>fABUs(t4rGG;>JmmkJ7=S!N$fYDDyRq--Q zNB3OfjYiM90FfiT2KEhlj zT1sh{JNJ{Tq=MNyz=3%Cg~Z_i zM8VsD-?;qcOAB!HA@D8Jxi{uorEn?(sP+8!uZpYcnE7ymvxwUOMwUN_oj@=)l8P+o z!wI_%S}1Ne(r|zk3FNc;DXGYe6Pp!qMIXk|-pP6cEs9oA$|Z&nmF- znDXYzn=!4`oiVV{Fuc6UI+C>_;R??t>1gZI=w*%=H)Pi|YK@6d1mykY8A4=w^Y$`P zwO$GAHTazj#_V4ym9L~a+*1@@P2TxqyuPzJpy93d%-bMS#$jA`OkT@LF zH7UuBmax}QB8CyM&%qe>DvOw?GW`Rdy%0QK`}JAiEgv1Q)p{`%sw~|8#p=3guKqH7 z+<{M?Aynw1sEPj5i5y3PN?U3Jblk>Q{QQ&y1^jl7-a1?2GM7Bqm!!;hI6pU#(I;0q zbwAvbR%G(SR~=h-l^v{}^}qA>oR-&)E(~)&tqrD%uZ8YJPhF1i@>+}+Dknn*u+%0; z9eon%2&77xQ*^rIL8V4|02Z{ek3hfIlt4;*GqYFcUtcmCPxWmo6I7@(6RkGMwioHc zwL-e80dBEwOyHdPTa>)aJnD+P%I7?Jjl^d!64YU`gg}+PAH62vocv?h(Rz~Jvs-uG zj6|HGQV0M^CR4qa?;5xoOOS1al0GJ6G9IJZy>@$k`E({4h$$N8dAAWXx%0QyB-K1; zSR(n|<`89jI5I{3pGJxiSaK&Lt@Pp)+2$_^J$lRnQ_4ZnARFpQgGolk=RD@u@VASN z>vrj@Wqzd^kEYBT=|Nl+W!9ukH4hW%UjRG7e!7N_^&D4shAUFRsCcdWuCsh!bvTIS z@O7o*-=si2D~Fn@svB>HQ$x$eW+}^fcXPYn``8HV7E`YwfjL`cne%%v1}UKpECSS! z;5;e0ANRKNP{k{;+l`(h!Im(ygIW6A@x7a-)x4+c;{^`4m8^ZJM zDwb9;l}G*Ot2a1|rG{X03{q(&))U+r;)mZNeV%Q0|Z90qX@po8xFWJmIm$$ zlgmk(xY`-GYOywi{Rm88VH8dKtpduHQ@gMaXhA?HhHFv)i?U7)IHyEN&L86s3pVgc zLJ`qcut(n~P`(G@di#g=u6^i;?L#XRFNUNKOcrZP{Md2~N9PmYM_5=PaW^04Z+H|K zAqSJkkj)y;NIya3cS`z+Iw?)AVi{tpVKDvpL1oHKaW+~1Cb20mL_6i$_R%0RU;;C8 zt8r&Ii6->>^TW~7*lWPQ6}#@NKz$J0tmF6AmI~upBn()HFA@3c)kV~kr@pdm$?@^T z*?|We2KWe~qNjE+wUe@E8NUpu@YU0nkw7O>8>%*l5if8)M}!VG*mEKEbE21rbGUrO zxt+Ia=$KJ3A>zOUgX(zd+Z&v;tO~XojI`CLFoiE}a8C`zuw)58{k5m_l0gi**CJLGV5}M*CuDp#p?Q{V6|=-resV+QYz@V-S#MxhS{TE8Z%M3_|t2JjYFVq+^~u8pGwp|szOsbO;E6cP_6SXP1zr4x;W00>M3qfLAT z0P^8xlZ9i@77z?4O9>0@lUIAw{-cyEUPL}5+uRwHsqzR&#c{eyC_asiI81PHr@q6E1D;f16tY=Og zb)<5L&Mv%lb#*zU$|@>#mAbQcH>KDezcTf=5le6Ak$!aaL$oOZG-JIpnBAz8>f8tS zVo&;=Ds(u&00pScSzlT1LHn(n;2soqWavM??|*rA96n+|TRHh`bpMqzYUyNaSsyHl z@bI%mw7%g3*+@MbwTC9@o#8i2f7Pb4YcEdIR<^i@kG`MGp@Fi$htIQLDgbn=D0-%a zldU6Xf~B^RCCStj7&e(hxRuN$%p3Qw`Q;mCs}qgqS5q7qx;#Ylu(Be*AqZCLsF@oCmQc+ja$; zWed+L%czKet8(6}6bdt=d{e+K-`hRPi8o8ZkvSQWi^r2$DF1n^)#ePYk(F~qlC!gn{qS@!j}r66;QlQyNr!{nkLQ1$R`J2W zCQS%IEEr19e`v^3z!Cuon&CWsoQHg*-N^p0rSsS(mjYG`2g~QRRmI1v+yMW8KQY>M zj`#hU0~(es?T;m`MO9nVBCfN3gdZqPRP;Bu4WMD_Gsm;A?%LW6CN0955J;XqR&E7i zBdo6;Mc(y;#smJ$Mzok~Fa~0=*RxEpfkH3ZoG=6)w zNHj3juM8jS@ARWRd@F59FJa7IICHvzalD<23_Wv#>O}1Rq-G_GsHfgqYuLHWMNV;*X)IS$cmwTq^3F-gk97?ABQot z@NQ0$IT*j?`@Ber^>`sa(*{d*dhRZ~?7jd$$oh3(Z`vrc!TQ0}Ro4rLH`m@QB&}f$ zA;Vi}w}oM0hlJST{ORp^*oM2mVkuVyi-`06atKxl}^n!F^Ru55Kor zOh1PrD2n@~tZYnO{6PTmc>Hh&$l)mARovB0Q9=WCArZqg7L;YT*#fjjc9QMw;Jpad zk~A^&xi9CqnyHr)A zWBC3X0Wer=-oHrWvfo^tqSuVVzHR@kO)}q;12Rq)3B&1qXL@Q?A%;K%_x^R!*)>3c zm|N?od7ae@9ze^}@ZsBh>4R8<@e)m+JZr8bmui{&xHkJ4%T9K!yY$*~{-NH<;pc$m(r_F8y@(sf zs6-r-n8fC9RW9X^vug?EW+rq{I20Dn;PJvxxj62utWn%a7&F5*5+Iar4g;Bo6#z%t z*v$QY(N=B?O0dQB)2*F#AKcags-W>m8Qu9y)$V<@fQfovT|@56kZ%ojJHz^w)BKA$ z^@&N}g9ZtXQv0F?bJUK*T$k^9G3!EWKm6TPYJ0Z-P3~j)j?ta093TfnVL+{xE_g4G z@{ZQYMGUlh#c>p21#}1M!~SvWsXT<3;wd>r%@ty-q;8+em{b&sMLA=NA%Ozck?VzX z{IK4fqvi^j@edO|dr&|3+M+c!I7wjz-$gKf4c3Q5cU8@uJfjut_fA=iY_GyI$|0*i zn$E*fQE!FC!tpsUrqQtB+lses*AI}y)Hf*)ni1&YIcJ6em^&RZ{|7+|zqVyuZPmLj z9xee7v9Qo*+_9*(*w_>G>J;ziZ)Hn^5{mAcsq=fK?VE1xW@j^}A1hj1zfoc7bVxp% zT28mTQbQt?(nm6lUz6>0s`C&{cM+g6g8t~XX2E(s+abeb@{R|@w-y^_-j5$7neaw= z`&4*WliN(%K05`ew*w6;f2mg9NYQT`Wu1-_s=v zgfmND<22+nek(-7TekrLaDaS-68wH>SwMGo3VVIF?mOXaJj(6ooW)`qpFo7xzTbhd znBKb9M87{f99C;=!<(Cc`rH0eSghTjkcftRXIB_nNOW$(Lh7!%p{Ri$;8{I+-Q{SKRDi}gW*%F*9aR{p$0Spl>mDrX*+ZO1vlLI5%L zQ*!aIrc5rEwN_ka8g7`cV0a9?NiZH96Us+Z>Nz9-vyNA<673P0-C^m(>6t{8>JevY ze6!8rydc7sIs&m2)l9yM}SdDaepKrCjltf;n5XE zaKOR&!;cmGNPjwI1kvzd)rXh)jOyq~?Fb6^>2~eC*Bx8>;f!?Fbyq!oax>8&y-_++ zs26zj@CvtSRbIAjddKa?uR^))v#!d6iKNvR8f!7t7tn}$us~T`ADf#G1LGe=D2(S& zPuCU&a{mIX+FVY3$KZEMP>TFK%n?}zu;k5IN(Gnk;y|bs2*?uog@8dmLT2mr`6~($ zioCMO@-RfnK{JbQGm5uFts3iPI8>vM0W=%{-yW?zIgIJ2wd~3`30%k6o zCeDGF@{ntNxOSwpM<@4r;Px4Evx4Wm? z$CZ|YXSxdtSs$VfSAa`%2)!s2F@m5l2cv5fV`3^*RN&$Y{&ScqcyOm#&Hd*9>+`;RK5(n|GioSRm|q&k4Vi z)w*Qqv|V~-ck4WvW(MGnNI3s|xVxCZJ|VQR;7%4Adc;qUff zjB08si&R>BS$Cj)6xGnsu(h?7kU-35WndWJ`iF&sL$A}yxm2N=G|XnX$l9=UV%Oxs zPttE2UL6~ok)nVO;Z4bm1v*?z5(ZJ9cZ@_oZR*tJy!wBDdp=BL{X9IDLSVXh0>Q)= za7Bh{KFL79^Cq4(m|G^x&CEoE$+5Gl&3**WHBI97e(kr9Pypfn(X`+i}^4@M;^*CrFs{ zhsrpFn%NzPsl* zNtUj3@&Qs_A#AdWD?(PPEbY9F()2HqEE${FWft`S`BO%r0fWeOr+PK+%fIit0ku>A z&bFU@_$tcsT4^nJ4snrHA9Nz&H!y5C7*GoQk` z+fDs!T0b{8cjF+e@$r#D9|c@BW7u2KvK}r?oo;)9$VYM@G`Ra4x^vB&>--D=@F<3Y z{H$)dX6NVK+jJtgsPehExU%J`N>}Xd?4W%hDz%1oet!N|)ci;#yD2_Ax>V5stYd;e-Xh`#k; zcPx)b6NuJm<^BGRTB(i6^ZhT%3}4%G8SiR3HPXwuFim1?6{h|6cZ{!X!HiwUgi?ew zPA9F?hEn{u%l4ia==F9s^}diu_jOzMy|kHA7$%q%QVk$$&Tp-w>yV&N18+hD|GLxR z_g~29FZalJ-jB1Cc*9-;*S6Jm*L9Tt|N81~+FM{>x&sv5xVQ8vRgHFSw$-NgL5S{| zsq?$a&$H^n4>{fAA*9bwrAaKb(xG%;n`8(x8PXNZ_;OJc`7OTi{Fe^6KQVhREKna#p@`MZJ+h00`Ry{-auE3UO#YaB-mTotx_BHt!=NP`l4L)a6J z-LlPlf1AoTZh2B0JrOhVGu)*@YnFGms7a9H=FI2a{|)h(5!|oqa#T=K{Id4?VpE@rF%zHd^gw+m@@g1kHgK(yzSkM-*5+o1NroUY7ZiC^uNj%)4+H#5_*feu1+A~d&fu?ar8y5@m$y27pja}6@Vs2tOcJDoTiVF&GH4K( zsbu8mlZ0}*SAK$TA$9F;J(T!De|h?7p6tqy)76E3IBpsGWe80F7z;r(t=3+8$`>b?XCPeLT_KQU9D{B~tB zeDX1G$r+wx8&FJ-C`;a(nP*qpRQoo#kH7APcUk11*560RR*3Bf#~#iZK1B%bV_ct~ zRs287zA`S#eT{Z#rI7|nDQP67MM7z$yFe(s;CdsmdUa&B+7o!sAu3(;OD5d@B9F^n`Za}Y;le9Yb- zc`vjh8e-q*vE8HRo$nP)AK9qz)zBk<>#~A%^T+Ce`;+r=M|Z#3>Wfr2hHeDG$))32 zr@6h@t5g23vg=F+EoeN4Mx7~c$w<6c*hBJbi+K(0Z-slbWC zA5LTTF`2`-FA{+aNetxGUi)y90bA^VCSZ6?|3W%D8exBj)EFc*%jCKfxa$8pFcbt5 zC4SV&0e>-q)zPUOrg+Y#QqizB`|r5+?d^A1+niQN+eDc z4jD)sn=_g%btPB94bz&=ndY0}yE*;ZQh65Wd}RSD+3P32#$#2+_4`U4qn>j;oBM?z zLPJBYl+;heVvpTUin12r7Tt;kjo&_7rR!rg*Tq4g+`#X_L&^r6DrRkBkVYCSsWA!m zk05RkC=)t`Xt0h|!UsYYy}$n05Rr~tBy0G`$4`}9kE2q6)fGZ#35}}FZK2P1c4+BO z2-{7J7)G0DASV0>L{%u=px@kQr=#nc)klEl!Br=QSoet>qZd_s150HaAI*56f|#inGUNVCzk0D zERpcq;8RhvKN?N1ZixW>=!7$O{g4-#KkQ9gZaUi zC)SFN6O62}`Si^#Jh&|Jth8fRJ;7}e2I9HXBLVsjz(>$|+3{FXojh=v5{hHwXKSz7 z>h7>8#k;5esNTdnV3SQEX?>z}v{f{EyDxyAC1olKC1Ez>QSRA!-}P&`3-FP_yRRtR z^|Has<#Fv;DauEm((@s|&g*N!UdI_Hsks_R~;-RsapPTT|+Anu3CX@G~Z=C+2CN0Ce6B(IB^)!T=GP>)4++`fhe1xr6 zsTr@6ioSO_S-k#yl1m}>!h!i^H1C1WKzKH^F^Fqeld{MQl24ITV{J;wPwK1Q17W}( z--v^|_jdM|vzhnKuNt>gB}bj(v>zQE+ALS(+Smxwj96digg(Umpm`OgWrRT5KUhw! z&4c`~)#UBVk3#}E9Q0W4>EF>uP*-DB%T_11zJsKugfauB#(`O&1RWhaU*HlMcywqE z*EO2=@TrArKyHuyTRD+Zu{3uUT^`R z;&=9oxD0S1Dm9By3`Zh^4qslzNPL|!@#^@#a%1rlqBqwe-(=2F5_!dLQmzpe+po|8 zerF;>cUqxm8sI=eH()UdRv|f)rzZ+oclF1=u0K^BRa%@p2OspGLFh$J^A=~KRIp8_ z34@Iq$Yv25^LM4ly;cMuKGto5zMufPexrmiwVq+Rz@|-JW>UJylASfD!53E5z9G7f zzjm33F$}9kJPgimDot9Jt7w%?zH~_Ao(pKKg0cLJe&S<%2X~Oeeq?;!PE|&eJx$Ydx$LH+b12XqN5A7rd{cpj&WAExS;_K?*e*xR#{v5$6P7 zT&|3OC(Bb1;$4cE9x7;Iai6a|KlS-quWqARaRdAx73)M2iTZ*YId#JKScHD!!T6IM ziHluQ88DWbr1AQ?OfX5rlLIFdh60XzC8oMneBshQ@%(y^H9vRw`41pGKLOL$ymvxF zpA$;79>hz?7%=udBV}t==AzSkoT|$H(Iqwi5Nj4hSh~)?P1LZcT?Kl&4kHgZKz$n2 zWaQ(+zjhGY0KT3HZ{-@-sWRcrKm4kq*KT56QaH%rNt-N2v2bxLb%JjB$$Ft@;VB$a`wtSNXZ#>tV(`v*4Ci+fd*4NwmLK z>3rRMxU(*=-)bFsCb#G{oI{7Nq>{pgi}SIc74WH+Vqujv+nR_g?@p_?_g1aF#S)Aa z;yYMp3QLU!6J(o_Fk>;(&e76oaldu6mQVZSVWw={cH~vwytDGjl+Xnvc${`zkgn^u z;q6XUOE|q7G?uR40NtL{%prA6$?V&+m7jQwo^`Ze$mJIx1atyf5OM50v zV`4U&Ep#M$g0BYoA}u_dME0|vrqmsW?{4kA)x(}c22~cr=e#-Qr4S+3$dN47#ljA} zx9qeg=kE1sh0r0ewz*kLy{s>1Vb^T?gO~l65|7Rf9gghzDv`(mr{;Cj_-=iIa371U ztn~zXg*4w>M}Z$gOFmd>x&a^(Ms#t{7C)wwz1`yQfMTKq7tlf_i&v1z6$iNLMe(N| z=T^C;ww6`n;KB!_EaEoGMBx$+8b_WU>o31#Ra?liiT-f66ZkPQmkwY0L6_SfUd`G- z0?A815mWhV!uH5S< zA83t}77ra1gUSxTtH&{f^m%$x&s3{P4hWCE2p=DC7gW`-_er6}paIVyU!pe26oa(n zw2tg-ys2(72BF1`hSfBE^EezXOoOdS&R-OtVJ_oI9?c;`nAXs+fUDIM(GmJjmZqun zR}WpOihCu|peiqR*@R8F)QG}$8}`G2o4LB1QL*4A@#M!)CHDEo>L?&B-HdO)Q5L22 zXQbINhd1pw=r0^jdJ*+HYEL_#go0B%Vb+4mveD!r0fj?!U+nWZ(uDxR#@$Zx%p_K| zlzIw}ov?kAq@T-_r1+u+y2e$$PG6;Tec4yf6NBH68xr>4ADnPep7ge^#pa%?d=yLi zp&p@Qw=;b`!StxR+ELPf4P<)mRzQPWrr638I1GsxB3$pr^1jwdK!`$El<=r4fE)>H zeRlk|yNSJ?_-cl4v+hvx}I59P*m# z4E5z&f_zO0ENA0GvR5XdYMS|LF1s^s6-~npjVfN!b>BGR!j-DSkR~p{>j8v4)nDaa z=LCgbRMP5~<}1oV=UNKT9>H6w8c3VH)LQ-QC)u9-*)XY~z2@`&175~`CxL68& zGPYj~>h-dF_|-Vtramhz5h8M*?Y>X!Xue&NU#KmBiisDZLu`H4Wu)olPXudIYhrMe ztUW1M6oeMs7}QvwLd|~NTpui0SH_a|$Gf@VgNfAisBQ-GgbyCS#ZYWsmPeDb11?L) zX7|B_mJ_7VEFCN_zg0QR`7JGp#&wmb5$~8j%V64Bi8o;wA9>rXgqZ@xwQ0$0yag>m!{sTHOOVM|mCy;h zU&{*jDe8N#;lTO(h)AzFImPMSwF2)J+g$BE5J$B4Thhx)t zRp2gZ8^wy*gC3MJA{?cuC?cyVc&Tp+3e9>d(T~YopNc3}XjnQ|9P&NU)huG=NUG|N zb%7ug*)SI=?435dIfI=yonT|BkgPs8lA8ff8CR!cn*@sepim5PX%1rSgkm>aS0m8U z*v!tkg*slDf55?MU#_7PsPw=C{RGO6R2@fs$xrKc;xAK1V#&W zT~}_x)WDY57%j5R1ma+xHe8+10f`S~Y+=_7q?1hf#l_f4p`n)dI3A1~)H40#yu@VN zaE)|nSz0XXjhTHR;34QTb}dfwIsOEU1IBfNgbLDy??f$Oph67baU%2>-``WoM1ACc zZ!fjwJW0Wu?zEMGM5axiT()h5Kt7EqY0I^xXnV|nZ%1qmhIwklHVpO7wq=_+J7QPG z;T9V-AYcHUyjoDfK;$$Z>gn8x_ODn+9=y(qpN~d0mNB_ibtSXi%vjv%a>J( zMk+9xI9nQ+Np(`Sl|frkR^)*e1-czh^A1+;TI?o+oS;Gp zo|RN&48`JNRbw8fZgegcQAAW@>truAMiuGy5g%PmN-w!$q!8UuMhEPSLfTm3tF)D{ zuvG%lByzoodIT&=;OhjC$S|fztVr;<#|`rLI96xlcqQD#NBV(oVd8Sal4dR1ui8q> z{*@?T$Hrzq+O|(2C4{=O+(EHBtJ@;v7XBFckTESAd(Q^1X|H+Oq7#Q%zhCaZz~iFf z7W7YUM)k7x1VECjQvMU_mH4Bvdc!2X)VU5nV8C3yr_4aTU@)6H)HW)f?)uF?1h zJr2vauf0FQxXpY;%1)59B#}g$a#2;&VOH~EL_zt^gK0dU*DndRpbd?ScIyX=7b??m z%0xYNWl*t6`N7>z6#deOfu$pPsNeUw1q=!a2# ziM&{u8BCrx1uBEt*txGfl2vbB*LN#%UyLM;p4cTU+L&xcV7SMvhZs6%GJ?RqB!~kniiS(e4z%%vg_frtCiNv zdeF80A+5YUUay$!Roa=-(jGiR;8kU;m(B_~veO3f87-L&Jgw|zr-Fd*<@D_{oG=0q z6?p)EI2ftu5$ogcQNs%8_NM&`!xcI*-+lD^fskhr8uYew5VpC@yrk;($JEVTH3rHjRrC-aKdTZ>vy zDHPZJ7i3DR;+*twAb7ai1`+?_Vc<}rm$i#a0#qaC2Xv+I{Hyv;E551Qhary&p8^dw znsYA+3=jkQ8}tU7q*F9=I-El-cqBc4aHSGWi58g1SBbk15DZY?)`oG6SsZBM1a*>3 z1dvo=yx)F#y^80PEv=MeI$lSa%@HHH`;55nS(ZkanKJ4$l|K^RGZ)p>XD_4Vc}9-P znIySWCZUX`#PN&%OAf{C|xS@Va}qIctjb|t3WZ1-7Fu^M>p z<9*ICMK~OW$g1;}C-gJ;t0cy9u$q?si2vyD{n~ms099z2GFTN73jrwDqRg3ZqJk~K z+!)1-7{Pb5Ps~o!>)zOF`RSVl`9+Z}#<4>CaN%42KTnx1Hy2-?zj#eMNP747_;`$A zLJUpfh+wI`%3&dTg*I}+yr{?qJ#pN`$Yy{g9_pLfROKIqE0Hz|nniUaT<1(uOMR|O z){=;9G7=Xa)?Tf97NPmBpHCu#L49xe9;}zEtiyc^s5CDDD2-J}dC9X2Kt%j@dR#%Q zP#5f@Xz%q&VUT1B{!^2784~_6#G`l~|5scdh~mKd!SP%r41k^b*J|a-onqo}_wY`3 zuCj9IKQX6yIs41VxnAZ_b+m0B`LZp15Xwwul3a@duGl6^bV7`ylOeJ*T+D#73;5=w zM?cN?fQAxG`M6{N9qiTu@M|1% zXpanO+X&)_U|l+0v}{SBNDFCAj8`9VG1}<=Lr+9J>5COo7#yQNb#GXZYiAYV;3sMW z`?B0Ga}?-w>?p5}rR~4uuX+t!rAioZmEQ8YBJ0;=xBPnX!@Rt##|Y0N3>Gg7rrx=Vr>a*#oxv4XM+aFF8e|S3$)b;Nq^%q zeSuN&*hsTP3#WvTyCOH_GO^!Kit&blU-&A_N7tq@*0}tt@Bk{d_6DFFzf8MRpqPr} zvu!)k2RZyI{l6D5fUy>wXO8@DZlxq|D#Y6qS{wneecCL0#OW}sA)mBKgL zuGq?bb+(FFZ9+$U5m`<$wY47lyIehFplCMrbtVfPrfRrFeAC>{WsmixT z!4y?3BdJNjHOtI`r&c5~?#ae=>UorO&@vQx_O&8Wa8s`{&uA~f?jB|fwyF_O8|H%n zgW_jXnR->A=A$24wPfxfxL$b1O^d>5jfu?Saf7qu+ht8@!8v>;l&FCuX_D>L@PO_K zHF!7F5)*hC*uFX7q^*4VetasvCDQkL`IXei-cBpf@75gfd+(rOM|_Dql1bCyfF+$R z{XyX6+Eehanx_ndijjRGf8N3v)NX2Yh{eOka-!Qt_ojUsvCD~bQM($yv@SkY;ZYy zg7Gqu5-qSEdoVB11_xWCv=_8sc|J2C1$7pqMxstHdtaFtfJv%cg+#Hby+>nszwR7? zBXM68-|N&>6(Xt{ImGX8Gs}~W+D{Y$hNoZ=XNB#nSus1$h#`j1ZD8dM2pP)eXajYv zD(Hhiy`+j_{s}cD$cmle7^Q^<`@`c*OY}4Cqf3qg+H}In+QNJIGG)c1*fuYK@dMkT zmC(Ss>cEOGPu_;vN!Fj3q@LcoD{5#MV>9++NCvH?1@WGNL3UKl2lzP#RP9H_DjI5f z!lx@swn+#{J%6eYocTfwNuSE{q8`q+J@PGMS2*&7`1i(=0zpF{Ezn+~{Xj%DSj{28 z`!=Ze5EX+05#%yW@VFiB ziowZ)O#0D%h^;^+%4S}K>YXg=^wi7a3IxC4#+*o&xpRuDg7#;Drq)ciQxA2L1n^xs zhW12)6a;;~9&~5?j27_`_FVdPwnlK>XXxO8Y+v`K*+@JAC?2Jf7siS1byE`5D>{zP z<2ShNKl?aS^SyQCTl@sH9WV`9#v{Se)2g~H8`k;VgZGLmW{SobPx*Q(nqdP630NWK zCE#9*GURXWEKLOA1k^FI)7H?GIqZw%1jC323}v-UCQEjWjdiP}vC5)cA3d_f6gCTG ztOA%MY8aj`XSxd{A4iJbs#k}D+6{PGmI=YRy9K66fq6xDTZ5LN6`RKM=NyMvK!x3Q zqo2b=y0(nLf?cc%ffkL!t?%6*XD!9n@22TZ9E(-k1$HdTk&Ml{q*kuBeByXih65rbC^%@k;Hx8D1L(c}W>_ zA^|kkoC@>%s1>tBY-9x7V_BqzwNNv5sQ%2)i4we$77Ki-a*LJTgBu<nxXE3ywinZpVcXH%*ct)IA; z@~Q01Io|d0IsrqI?@KJTm)z2<+D4Ua<4Z814rvAe=#2b{Q=$8?HIS)IR2h-6vP~O* zk=xB_9VuIbCKgpc`)whKUgS`3kS?k?;m0;#oeXP^Brk`GlUbk+{!r*DU05QJu@n=T z8~qGUqb6}wCAgd(fGDv=X}^P1T;`UF1bw?Lf_J6MGl~^DrZ!8i3R`-OZWS&UNNB4n zb|e=s-f*8b?ccXTBPq3!V9OT@8Zi3tM?-A{8zFEg7G@#@z#H8zg)Q+R-xj@^`X*@q zESZ5gohtUdW8A-NgI7Eej%zhYlFrv%#Y#^G4PM=qi_Pk&ha<3fO~+ zEvJ%4KCmNT;A01L6OnGDtJZd_9om@k`whAbjWRyXYt>M4?U1R{ZTG>uTcdeG%}G5U zgd>gRh0J8{b|T!PBv5=N^}Mc+M8URShj{QV3s6IlAY_3^Br9Zz{V+%nm&n&1MyMV#DaL-_@c}n5+6WG9j^|N52mL^kF zhxY*f_9xavZ~kW4C*KKyNx;aV9y#EpTtnurA4MT-0TGYTbnewCA>iZp^Bh0UCYOiO zI|3VTOcKq3)yIsflPScR{bot7Kt$+6=-$psRnuGEo%y*mU6cOV-ruAo+f_+aF!kBv zzwcE4-fj-xlj+-xK%g8Y(R^eh6?<1hv;CbFpxrRXI1(2hS6fs~5AD)D4)QVnqd$=c zRrQ3n@HtV%OI!-WPO|WVI?GuEIQJ_%#Ig^e;8c14J9r~oF^B{iUx6ib8P43IVp;lz83H@<~SoEv`Nd+IN+d~N`h zvO62xXSxW5$u>Y!t#y=X8m9*u{jD1a(vs0DrH!8S89qL}d2f|5@p#AT>MFxW$R+T1 zYaePFIm~Rf(PwFZbUoc!<}n5RK}K-+&Ri;1rNnDIOkUmdg86fH6-2)o!r=$WG;v1J zMb3?v3_L$#FC=uDyXF^Fr-8qKeNumb)<)mQuK1BUd0G*on=7I&jNZ~w(oaF z&DFPM%gg@<04l_9JAb??{^;sH%yJc3Um6Q1<=G7P2(I4OkZ&?fmm zZZP@o{^ZKB$-3kgTu=_ew4_KEnf{O(0ska7s*o`|B@P4%05K{lWEMaEY{B`|LPMBO zLuLFLRg-1wK|~ecn>_%YizN;cVp`uGayqy{nuvi$Q3HP^QzyQICF-tKtcW3E`t?w{3AgYtAs-w^kfE9~Ec1A^wfZak-aA@%cR!?8kNrIA!(%|HQ37h)4 zsrD2t!5za)k9htdj3Cd>e%@DKWvZCt{Zm6^5=Kh+APyd8ehz%W1aAqYwRo@ACm$`f z9|B6jEn_-VGYeDqo5ueKr2yPGGL+699m4m!WMf9N<)Tb}re)4WXdbNt$WgKVYRx2Lki4>sb$yd$r6b4X-}>|kA+48fkemrS<3q8}oT1FvyVI6|6hB4{(F6JAR8 z7{gEnwrFr0qg~53VpE*py z)O*E>|H6>TM(kfE5UbI0+XR*|(YuT8*aEEQweX^UZk6U3>Fktj%!0dC@$RBhU@KCM zdsImTT$T>(`Xs!yZI%(K)jUsW;qhk~zT#|sf)#Zj<@)zMWvv*6m6?-!V` zbrOPeF6X4j%?ERR)Q;j z1nvPjlL+`7cJ7hw1!4S6p9h$joMX2kA+_7XG5SMIGncB3lW>e)(VVGq8tDbzd<1Tz z>*NoW5NDULTVe@YG2a2RoXG7Y4BSVnT8RnAoOut`jf^%#4y8f zR0?7oz;4f_LWIvy+Ucs2DJfoOK)k@G+5QBbkuiloeJ5XS{;pGQ7a59)*{PF3PM}_30vGk@aeco$x+)_-WPwv2{4YScqpP1^by}yr*qT5e zS`ER{;(!_vka0{GBSn46NQbQ<%12>~z;?A(pdz2Fz{vntc)xtv1#EHez6#Zw|HiZG zXG41?3y9<4(QuF`6=!RHhD4?F)j01#4{LN>g|fBox2gJrbHj+-cb9n9DScFt~}Vy-P?{b9!AiQyTck5aNpia5HrZm^FMf)M-6k1 zZF*w|{i%)4lPUE;*?pyY`|k!P`~Y`q(P7tSZZKj!X67)dAiC@c)v?#*pw6&43K^V6 z_XTP#S+rMr9}~cz1?|@7_A`qkbDS$SQ7i2kiw8pth+$Fv70UD*1d?<|noEj!(`#x) zhi~SL5~NuL_<#HIF{jls+q}I0YO}Es{BguL7LgD9iygED%NU{_lT>b({OEj}97VWO z5__E(-7TCnoOn0vce61*;R{rHg?Jev1Riu7CNtx zwy`_m!wm`-n1|j_wA+K1^)yQbgZv5^n*s8nL<=Z*=kjqSn(lSw$)O+u62?eWJT(IW zM#V?j#c$oNAz`~kpRyL4LI%5uxI~yeO#9LD!)c@YCurin(G4fLc}^wJ5`6v5B5ual z{8qQQpwe!lMQb*A6a8i1zD>If_UnpQq^-$0`hG|ss4Zc0hQBQC1kVaVO^?u)DSvE;M; z1~{33i8}v0K8py9bf-IE!HElLsYj+p1Fdu`R3IO?et~)t2(N{^m=nqfr;W=#VY}m6 zf&?grr0>b$fcFCZ&%I|EPq>^ZpRUn&hC7>zMlt9f0D}D+n4c@H%-vjL$c%COe`iKo zlhC`V``#~gA`wuBTR6#ix!#OHam^Dy3GoM4kh^2`A6VbaV&4i|00Zb)x9zp4mI2GL z{3G8ZnIh7X6O@+Ovq)+Ax&ivFQpPl(dUgn=JbUdaV8u8oeyIp(n%`HQu6#W$*rOXNZqRZ5*+i+O2A23261ujK%#)#J;-eNDIXgJEP2i7vUlgUJLZnfxfiFkv|Yre=df*2M~a%~7R4u}$^~@g*qrVK_^gHq*r* zf!dS_t4{4gzQsPL^4PKZg9@7d4V|dy71V1z`^s%Boea2t83%ht1b~%f&u0Di^-0@# zW%D9{F5PY4LhyL)cS(9MO>pPRVM36NG8Lbpz$5j-dd~Vr5NeIA3RX=?#Jf3|jQibq z=gc*^8qS$b2=PAmSNW8!xmb&SFI7J8i};ummQ+1juii9OT!OD2DwHy-IZGj^6tUe7 zl4su8^*EWU5Jc(Fdj?s>4@5y4aQv1aoT}88T#|RPQ=|F2^dgQ=)7u>D0b<;=);f@l zmgr~q-5qL`B=Fs}rA6N*TBc5>5=MDXGifZb;4<6M|87@nI2%1VWAM~f5e9NvOpSO< zzrHU%l0Z{!oaFSH6NqAIiT?H))D3zRzF(He}*W&GppP!X|?D7Tnr-*IOX zFj@B+uE;T%;eqf_xuL@G+1M~7EYb`0!@JNrtt*!>diq>lt=^%d!7|zg>DyMtt`^DQr3{4Pzg3Tc|=CVARJLdw~?i*VR~U@XUoY0TnL2&z2bKl+p0<1 zxw(;=2-ak6J}ZCa6#>Vmye|4se=}%s3fvQ=a;0>{mhx@B(1Vn{4{-uaqezo zeitc|y1?XWaEf`_jf{F9PYrZW%mRcEpvBauQT1G{&-9AJrL~Z-IB`FX|CVI~(hm8A z?5Re7g%1!bVcZnW^w;1ZQw=3^Ef~q>XqlumsP;a`&XS2#b(S7vH!}XMFHv`xuCiOa zh2f>`C)7GcfxM-j~YV(!=< zeow0>fmk`FXsD7|3BRBeK!T&nvV9RjkDf@c0*S+jJ6D~1TZF5ut4SLaAwMdVm&jVR zc#itwDtPh+e5d@{q`qgGCRDAn{Aebh91x5eDry*s;WSz-YqnovVruEvQ86sS$oqp^ z3g;&*8gu={Us$Qc{l932oUpx+4S+yk*7h>&YQ7Q?NaWA%>YaDc{k@t3%{dDw=D8*8 z!h3HEF#g%^F7FihzXdb?rNECbrbT<-hfLl{fyLO*fJD^nVi&3F z?#?IHYGdn_yLU$;wtEE#@6@QGnU&_>u*ifQ%(fPDTy*`MTewbK))#fd^5Frt1XCdk zgJknFtUZbULw`@CkCThBi1F#a?gmg?g}wid4m^h|^sG*nm~1Ne%QjbQLUj}1R`?L> zPFEw{?CUoAubUj?`niPmeO1?I5TsX^VtsbXK`57fjk2u=O3v4l3ybfi(~^rV2iw-v zT-X8ZcI*O#0#`*OlSe_zaeB98)XwtFJr#o-F23K8=-?cSE)a_n!<(qCNonQsT(CR& zs?Q`P7ELmP4u!#~pQ(m7K?u68Ctb`>bn6275yi|n{}c&Rxds-qTX@_A7P+EF|H@{q z$W6t%Sg&r<5a-iiZAeljAYE|JB1Q0*INB92SCB&}=>QLz5hxVu4q70MGlBuBK2W>= z59~DV!>!{CSVVf?kqn6ezyV@fc$?y{jVt?{GbKx8Vq3BpR3{DB?HUjKuN|Bz3XO+S>Re^5#m z3~h}s%7#}eSN(3eC*5Af*2J68>Z|niYe(~gJD}0S3*3_A)pT-#Tx9=y+`1n z-ZkXyp(1yWfl;wM7ju1TyTsn(yz6dPY^4d)=fyppN>XI@XBBECut6ag1y%W@@{<&E zPrEz5pSV+g0RX~$d-fpwydf9J;;bCqHHSw9VTc^0*=P^g4l`UQ$lcff+zjWNQ)lTi z>JbVyfIp^o`|t(etCO-~2c{fomV9>r%L>o%oP&fAs6Lp38T0EE?&E+cljUb?qNp{>hA{IRm8zmWOcN2>@>GI3X1B((pSHQ8=NKC@ch_-CISvL@ z0HgR=nyw&^+mB#fftH$x9isPlZ@kvgD?Vh=<+Cb5gADqQjSz-{+be~>bp>Z8hRY@!!{2){9KmD2LfmRW)B=c`&c)4dgw^#jfC6P|CM-uZvX%~iO0 z?zrI+EvZa+mf1cG5>%A{U%z4L70GQUh%U3r)4VecPGd`&0h6Stm=O^*K=ipNl0V$e z&=q>Pxuz>_EJ~G&KU;&w;K5{GII4LE*KzYz{LaGS#kY1j-Hx?Br~MNB-}`o95I}nG z()Ee~c-qWXEVs#Wvk{n8lHxnp>rX3?byG$i`{& zVfs{esHMkVhd+>j#GbA@rU4GQ!_K^C7vw3*`R^2gws=(-7vDb{Vj-oG!)M0d-Idr> zSe6BF*c#7btWKBLG|swE$X~Xv!wL#En#BRN+39&z04zQkAPQGy#9xdpu#^8y!q~Ow zS*OYQA(dDXQORa}tYI(5>}j@)PPkCxG0PnRLy};VhXd3LUm~n$;RzNzc?M+g8lpIO zpYx4Ih&6U1RhMK%ARy!H^0oB;uI;Xvh7I?^et;P=aK2}I{$NzgGYKLz1 z{@eBYss|=LDxWpJ8+`9oQCEBUHG9HIp(sy=*{vP^K?hZx-=n)OPRzeqSRDlA6>D*u zangSjeU2oa$=(;-WUfkAbE^7;7s)qyW}PB|^eijHg#{jKRZ~nbZna_n3l0+~ zn{-d;D8xAacMr=nIS{q}1udavfIyjB@b{2ulI z^#{uv!lYN=kF$sj{z>?htWw&?{B#GBeQ}B(k4~Pd|4Z+zHK)4y3bw7&xI@Si=PM0$ z*?-PMt?XrFmj$k@7THiZxdi}nw#V2tX$|3Mndo|x1X4A3SUE9Sw3|k;X@?AOQB4NG z)h!hAwiy9DHQ}?~`+wUO9cp7D-^HRpM-_Dk!%9fAE9s8GgHL>Xa%5~GP}e?t>BOx) zcDYqJ05!Bu5oiOL(Izt2U5vW4vy6LhWy)GrrXDXe2W&DM<243(p&$#1m{Sh_#KQPR zW5K$Vhy89wJ#erXUxYAY?tK2LH!Dg71p7eG?qL{EDq2B^m|RV!KC~jsCw}}>#gMD2 zf@_2y2POg~GAh0^rJ`tQauj3lMeDcoO~>6hedw+$R;%rg^|?Dje)`HGnajh!n$2)= zl%9tqN#&2|GGHn!u9Gs(I2Q_jwo^!04O4m%KeEhLp#gi;#NlSDkt|sy86`wp)fcYn@{=zXyh=X4T z$&cy&DX*BmxBq0ZDE~u9 zQCwerxE)+)cf*&yM1#@;vx;De7b?I15>RB$6HI;WSjt&hwTt#i*lq3oT^8W4Ey)04 z_zQR*v-U23NKm)p3Vwe}Enr9x%DerK$jRGlxB9k8D)w4(DR9w>fQ+p;Z1}(g!pOF% z0bVOx|NQ#p@x$MnQZ~VXjV=cOoLeJU_yMTa@g($bS~hGy2^B5umfME9X+`?Vx#B?} z)#{+_ZW z3WNR8KohLO$mOyM)m-iMebs!kW7Z;(XLHcbmu36=!qVHfo<7jGmRa(~fQZomJ0Qb2 zng5iO37k#$Cl~^(>Lo`1u1@Hp134`aV$X?ZMT6pE{EH#u1s<=k*}(|!DlB{k8wA?5 zi4ZgTWO(1)T{oDjdi*%fdj5`13MMw}#}H-_`TtLgqp9p`GX4Jw@5?>B!+0INhU7mm z@!t)OmorxOgJ}_hoxhv$P_s+?<$vwRqNiC3wI6*3d17ekn+eG|?@)p#J z!M95oMMktJ$_0czx_c6iOmU^E-);8tUeQLNnr~}r=26|XV!aYz_HqKKsQ2UpurPYP z&p-oW!cEKDkkz+Bzef2G8PTcY!vkH$r=lqWdMRZJC%uc^1A!I^swCtv?11f9 z)braIR(t3}f6buajC?=@-9sGvyz#BLN!L$l7N?(<7QtgMdSyle(-nAL^fF^${`0oz+aW|;I!Rg-xi=&SbC_WvuEWLYV`f>;k(n*C z?7eo(JO2=+X%GsY0~>NxzP^j9q$^t(WwOqr493-7v$tbZJs8Qy`y(=Z72n7}G(?uh zj2at0{*`Q$@iAxePz8CT{qC((1`B`Wy{Xjrr~JwZncW8FqrNO{XxGlc(9HF+Rda07 z1!YW@zKZ)<1vxtG76GL=U{~b84`7<|zxx@0#c197>PV>rMW%dOJ=~`w;o)JFBwjY` zU%*n6dP8(F5>H_Xn1ApY;}$;X-EAW-z?qm=kg=KA3%R(F#niKpLrN-Pu-O4?xcf*Z z##Z(K2C5O7(dh;d09S0j-b*%;pQfvi zEP3u0Nz_=al>`gsy8xF~f5vX-Ymz@@@v+Y@@~~cCN??*{^I)qgJ!PwwdzX2C}P|5@S0 z@5)qn?MJROHr{x9f_G+^NdX=!LBiM*?oEG2I|y(aGXp_P=IR)k{`jOCN?o6m^3>l+ znQ5Lc=E=1z*;>}@ZrU6!?$|C$s9Vv)cqc5`uS!A)95CFqjSXsj|NMmcLSS#+_4j?{0z0dOU2R&))!~R#-g5 z4axm3#IAn!_Ki-z{RaHlM(c}DctLzBjA1DN^H~*TA=brD+jblwxRnlIOC@U?gqegV z=&;#Gow-8LqrYnX%;t4-a?k)Tg&)tnD(8WWU1A|T5Er8|TrxE8AbZ_=7evhWVQbFa zNQ{LaA0Up0eWk+DID~QHr>fzKM_F@VIt4@2+&c_5uK{LES6=p zXLAYfn@abXna9KU!^R~M;xxKXQk<9f8|X$y=-%aFK7g?;e*kfW7iPB@rno12^{RYJ zO9-&!ZB2jL^0?uI>&!J4GmIM{ss;Ye>a8{OMo9@xkcB_y_d0bp6gMbCmEB_=426AD zfC}&L?9PBpDq)D>{PU_1we95rh6P?8AXl?X_(Afn&Ay)OFY6yc5wHZ=XSoGZsD@9% zsdML7a|w|3nt(BLd#WVZ>q`KNV@?&^Dm#*j(2IqFqON$8KNfuZxk9TkzS5+=QGicU z`PNo8-TL&|!7_b%2oOWmrH64J_H;N>31IgVChNWCFhC6cFzJ)=yy|&>B8IrC%BKix zWsGIFqkekbqAi|}^;oy=-L0#Uujok{zH|`9MuekEL@6%C9e?p)Rjb8&``v=@pDp@& z(e=yq{KOJU8)Y>H$UqfI5^38`*!M}LBv_+`obnz{`?rDjKTa+PI|kMrN_l2+Z(ClcP_1Qob?EMBe&BxjLj_B74|%QWlFehfqVKmc#6A5YpNGjH_5Z!U__V~PkmDt2 zmHTtpnMi$A_1N(E?gsb-f6#bYMl^j~sPY=yM zVnb^~-#mD2z~H*n&Xfoo6j+^gysGEY{V2BfK3W7Vl=@u8uK9QK^(5A?L|>&^``b{! z=3sUqv^(ZHpo+ID;Im_YnavsSs|eoGtd`J5#hrQtFMqve4byqwwJQ4dxTSC2&)K3W zL=E2KM{w6q3`_8kl<4fhPAmb_pBTxNfoG@z_<2c-UkL(OZHD76#93a;r(LlM4a}_h z;Kj2|;N@Va%Yg$8pQtc7;RO$lg8I??K8f5Moo~8)K3g-JQ8A@ZReG7kB>w!}+|~8r z48}eWslfuu25_Qfg*<+(;p}lG3wE?$xUC3T7{iyYW~0HdIDDXIquwzpu)qR0;M(x! z_HcPway#FKl*@Xoy(Xh3tDXmSsF!_(81*ixv&39DVA9N;iDt`#FKcQ%`(_c%MME-b z7hyMG^^nXD{X`<~J0_G!ebqa;*k!&y^&YW>V;Rg8vfBg=SMa@_o ztHsMv3q(gJ$lgvtd0!HbU9p9kUiIaLk@Td=lkw-H>WHR)=*2rZCeD9; zTmIF)e147P_hZg{wBtDGvzi^GPnvTfphZEi1%RZoiiaLt8zF#l_}c7dqMcB8rQKVJ zg(}_;*pcR&c(s6uM}fpI;S~d$cnyVHoGcHIacy;;Wt5OQ5Uwu9V3sut+pUcI- zc|uljX*U-yChX2&?>DUP`$IpZ1JU4Dbo;|j1mL^7ROrrmJjuMi$mnb8>+1_1?2G)8 z@;h6@RiKGRP@EcF^1GPG;5$C9t1HR)b)~+1IIrG*K@bD|$Uf$dH6*SwzrT8tx9p@^ zmT;&%DKOcISLh|5&VMsa-2ZFqd9WhPzx$L2jh#QBZh@10SSV2uXSb>xE2L)+d7W-D3<-cEMISUiJVtOU!B;sYeOEkZmGUi zt$SxnT>OwxeWyAi#ZprKwwISBWnNmmBB#f|mcSrz$9Ks+cByN$$19h}(q^%Z3W3YU_v@4{~`}K^xRpr*F(=X*uWPE+0AKgJcIre4Un zY$eq@Po3#-pz}zZCW$IdO$N1d^XsDh(iyEhe(ok)4Bl{y+XEkqq%1jBd~y<{ zacQqQh#~0YCR;~IVo0I2>DSmque?=zRcwGkXj)E^Ixud za)!aBq{F)&6u1$i!X8n$UWEOJaGw@QVTu$DU)4hI9Du6Z_KMK#A1DXjl&TQ`j)rDS z)g5_QDmhm1vhNi1!lScH+T(UgHp5aEIKV{Fc$ z3CaCTov83@C7hc=Z$4#Nt0w4O)j473os0?$dP17P8LzN1dpI5%73-|xu%rJw$ECrU^o=-~beUUC0 z&_MfrsL{SGjRq6E12^v}|GhTsgE<;{1Ow`GWQAh%)VqEBXFi2jjxc7XEYTJ$OpmCp zn}F&`X-7_j3ST?ih4Vhh-bNqxU3xr$4Y4}jwB6&fo0hdFk3gOH9RQo=J zGV;?sbFZHLreUL2@wZ3)`INs=_9vmt{IIeU26UGa|3rFQ1Ocd(dYjn{nw~5M-scV; z%jlKQvM_e*M#t;wGuxgpt9cSUDsdtxg?3kn3}d1hLxv)XwK`i-ignj}Qz7LA!Fr^1_*->3Iof^nqA=q{GKtE*B1 z4O(4V`#b#edsBGg#1>>RoRUEd^-l8DpW{Z;jcV~@=8!@7)Gpd{%sT7hSF8pnRiAnz zd@-3|TWN33`TGae}MtAE6jK0rW{;W_{Jh{H#(b%q`aUs}fv%OrQ)4ogv$U zqCV=>p=l-Y;Lr&z!Mj5V;wkN`J_kEj;b^#p>J@P>>D-wNxUgmV<{RoxdNQN<8nG$H zbqjHf;ge>p@yFAN%GRl~J9C^V4y0Mj?-H5V&w&={%zdS8P~|w+23dy@jomAjK^772 z2!mx7Ng%E8tIS@s3=#>gK2Y?- zSOeylEKN?%tq6)85(hRuQ2&5G=NAu-qMZIH?<3e&B7mO7W;;XmMjZ=>SOYThyP5PWY6Js_TkXdiTv~gJ~pP1N3DjDYmZ1 zPC4KYGSRqmTKIa1gMV*o=DX(g4*H=Mmk5_TyG+wzk{-+3lk2^|2b?I+wcz8h5W0e8 zkH`FfkUL=c4mlzqY4JkkZ=AiSwxuauFPx4in>q;6PGnpclBftq?6>2kYg#wu0E13+ z({6`gTwK|41{NCYv(2H141If`|P;2ECo87Ko_zLvX}?iWYq|g*xFxUrmQVkK@!t$S^Jc zb~{S8DdOOIKK++l3T+6V&xmH4O&JjMZ|UAFQqF6WQhecF#Qq44Y7ZqNsM^Q(%gHSi zQv{i>w4>TMkih)5s+V zg4V>CgP_A)79w#grF5Df6Yd&8P1=>3glc-&We419tn2-FP zFFfo@WX^Ccm2)|tMHYZRs;GSOEV3$3wJQVXTUeJTSmoT4P1n)(%DXPebuvJ_sJy{S zHeHTf_F7!e^W+Upw`GowuM3CWyTe1nKZb{Y?7mAO9e+oKtgU9l9#1tfA|40(QC}OU z(3g9$nZxgqflFP#-ui8J{ldh4mu+(4?aO$;Njx3JK2PZ{pYVF(Y`uKocKk+owgc`o zm}!%`n>X$mC3Z%0Vs4haI-JhFhpzd294N}QtRBI7Csn<`%59*>>jI$Jv7k|_L$+~l z(HsyJn*#hbZ?EPT_CDl`0Z_B!xRV?oiJy~*B$K9P0Mw0&IVx}gJgX0iYijZP<;;BVPSH36fM}AHl()7?f`IKAwKQ+X8%m@LfV|s| zn44mUgDwwAb>|9Qm$~1#D|G6OOy7HAX!^u31-)>6k_E6@fNIN?GSs#;+=xnNEBUHB z7&npLM%pBO>_;~czN&V0zob@QONvLZT13iN9A5?+3~KOYmZlF+tAD^wG$)I3M60AF zZ_Sdj2b#^YHSUD=KaEba&dUX{Xlr7><{mT=Uui^8rwzeW@*1Gli;zRpqVC7lL|z6| zkEEaY@N;1hB0BpNfLri?glU zsDM!AOIT#tS>FyGb+bzgDa6PWKa8$gueP7uuD0#A^GE&`I5gcHXt9~FEQIJ?ytDEl z;L%D4Z}RY6y;w1h0Ad#=>+!&~xdvBypB6p%G@t{u@7*Sgpw#)YV5i%5intdUBWQ+d z7!F)>={72|yBlD(z9~C0?C`Fm^=R>Fr2z~=Y}f!zt*zbq(z>>`_V)-9b5^@@^)|u5 z=`a{n9l9+ablTQ{{q4ufgi8Ju=)sxK0s{C6@%9_f&H=(q2`C}s#vvbO`(xXj#u$0T zU8U9Ss+V~cWsC6gOh0qK>wLIJJfeUV!-0w8!z%7-7p=C-Zv<8+jWzD`u-*}P$KZe!!tvbKCA{CYi!y!#Gh*DB+Xg)xI!3-kwy4&inz42e5>#z-Hi+ zb>5qc3Nnzx5&Gmz6wEvBf_5Gv}&7A=q@K!$?Qk7Q z#KM6xG%9e4J4Iuqlt|d~V0IpTC?^tmL;)RuLNp2O2C+we2$WrkWu}y(aUM8`xV?b* zRD&q>v23aM5k}2@F*tWi%D`2J52ee zO6l_QSG0nY16DQ`?0@xW0kK}S!UVDN{G5*^U!)2W@{1&wK~UiLyOM@Vl5xzxZ@Mte zHQ9y@oMQ3~nH*9iq8q1%fyThI^&V9T1~k18Kg$GLr#A@**`4*1@zUw}BzQ$-{;{c9 zBY>F5oHoV8nQ;Miiu5R^D2LVm*=gdoWNm}1AphOJ#FQ9ZujHq&@*xvLb)PM30(i7# zZAAa{+A$^c&GETw^!Xy!nJe62crfaSwFGr3Ee?&2h^%we{tJ|6>%dH2U}1CMqVs{P zY{UHrQJ-y$sQ3QWQI^Y4We+AOG;%V*aJVLZIPpg=LjiSR1)C-ow6T@XV6>%_pyV@;yEMeB`N~J^DYXiqkGT|GI@`P3+Vz&Xt6Y zztgWdPRjES#QZ)~4z#o$D0?wrAerOqGCdi8fnD#D!RHpKA@jvE=WghGygP;Va_2bB zRaJ9tTDXfUe`a(lE|gUaCI1qs)Me}8!b!Sw(~sJBv(DNZd0tFg=I7FmU;*x+{pwpx zYd6^nlr7Yl32oug|CIH-Nm=T=e7}3enDCWn@>M)52a*TUx6)o!HhOI~Iu1?TjhQfg zVB>tL3;sh`KQo7olpFe#D|tV!)pVYH z_i5_3OB+YMr<93BqWDXhfpz)w%6D9BQGT4>2DbLM1!u2_M{gscZ62Rs;w>F_z=hpe zvSLfGYb8&2%yMMiWNF}%_zDy~VYWP`=e4qG{s(QGH<`z|0Gsfr1#X*($*06HJdDh9 zs9$otx$xJeh7H13jjAOsHoW$6vhDg_eR@0+yLp-hY9SI3-}|fHf{` z6e-oecEROhY0N?6n#*r-`Lq#N=x7~Jb;KQg@ceIe9DBD$7mCBuS#^TV!TDthb3C(l zlGB@?+Un*!2zHYgeIxRTb2;33oT>t`36&B$>KikVhw~8pMDJ6Sp3j~XuEheb7j-!`^&kjdf6X@vW-^M+OoKMsIXh9 z4yFQ+9{ck4X4r1cIO_W}d_ay2KQ%U<+|lt;#8x@hrnS_?T2^T*|MLcTIRv;FAyM}! zLpUYS$w+Qf^S!6T>qmp9>#g=>B%>D}3`kVHl?%K2;8LMqgZ0#@r>?qL?xx1w&RmUG zc|T58H@Y-7f5bUj6<<~4Txn0nl;R$hU<47#QUx7{{0~VWxvraK{Wbi2L4rS(zU|Q>o`aM57!S2qW}N^ literal 0 HcmV?d00001 diff --git a/ros_trick/ros_src/canadarm_wrench_publisher/canadarm_wrench_publisher/__init__.py b/ros_trick/ros_src/canadarm_wrench_publisher/canadarm_wrench_publisher/__init__.py new file mode 100644 index 00000000..be353d1a --- /dev/null +++ b/ros_trick/ros_src/canadarm_wrench_publisher/canadarm_wrench_publisher/__init__.py @@ -0,0 +1,13 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. diff --git a/ros_trick/ros_src/canadarm_wrench_publisher/canadarm_wrench_publisher/canadarm_wrench_publisher_node.py b/ros_trick/ros_src/canadarm_wrench_publisher/canadarm_wrench_publisher/canadarm_wrench_publisher_node.py new file mode 100644 index 00000000..ba38587d --- /dev/null +++ b/ros_trick/ros_src/canadarm_wrench_publisher/canadarm_wrench_publisher/canadarm_wrench_publisher_node.py @@ -0,0 +1,117 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. + + +import time + +import rclpy +from geometry_msgs.msg import WrenchStamped +from rclpy.executors import SingleThreadedExecutor +from rclpy.node import Node +from ros_trick_bridge.trick_variable_server_client import TrickVariableServerClient +from std_msgs.msg import Header + + +class WrenchPublisher(Node): + def __init__(self): + super().__init__("wrench_publisher") + self._trick_host = "localhost" + self._trick_port = 49765 + self._ndof = 7 + self._trick_variable_names = [ + item + for i in range(self._ndof) + for item in [ + f"CanadarmManip.manip.applied_torque[{i}]", + f"CanadarmManip.manip.friction_torque[{i}]", + ] + ] + + # let everything start + time.sleep(5.0) + + self.get_logger().info("starting trick variable server") + self._trick_variable_server_client = TrickVariableServerClient( + host=self._trick_host, + port=self._trick_port, + client_tag="wrench_pub", + trick_variable_names=self._trick_variable_names, + trick_var_cycle_time=0.1, + on_receive_callback=self.trick_data_callback, + ) + self.link_frames = ["B1", "B2", "B3", "B4", "B5", "B6", "EE_SSRMS"] + self.rot_axes = [ + [0.0, 0.0, 1.0], + [1.0, 0.0, 0.0], + [0.0, 0.0, 1.0], + [0.0, 0.0, 1.0], + [0.0, 0.0, -1.0], + [1.0, 0.0, 0.0], + [0.0, 0.0, 1.0], + ] + self.get_logger().info("spawning wrench publishers") + self.wrench_publishers = [ + publisher + for link_name in self.link_frames + for publisher in [ + self.create_publisher( + WrenchStamped, f"wrench_topic/{link_name}/total_torque", 10 + ), + self.create_publisher( + WrenchStamped, f"wrench_topic/{link_name}/friction_torque", 10 + ), + ] + ] + + self._trick_variable_server_client.start_listening() + + def trick_data_callback(self, trick_data): + # self.get_logger().info("received trick cb") + + for i in range(self._ndof): + total_torque_var_name = self._trick_variable_names[2 * i] + friction_torque_var_name = self._trick_variable_names[2 * i + 1] + total_torque_val = float(trick_data[total_torque_var_name]) + friction_torque_val = float(trick_data[friction_torque_var_name]) + total_torque_pub = self.wrench_publishers[2 * i] + friction_torque_pub = self.wrench_publishers[2 * i + 1] + now = self.get_clock().now().to_msg() + + msg = WrenchStamped() + msg.header = Header() + msg.header.frame_id = self.link_frames[i] + msg.header.stamp = now + + # send total torque + msg.wrench.torque.x = self.rot_axes[i][0] * total_torque_val + msg.wrench.torque.y = self.rot_axes[i][1] * total_torque_val + msg.wrench.torque.z = self.rot_axes[i][2] * total_torque_val + total_torque_pub.publish(msg) + + # send friction torque + msg.wrench.torque.x = self.rot_axes[i][0] * friction_torque_val + msg.wrench.torque.y = self.rot_axes[i][1] * friction_torque_val + msg.wrench.torque.z = self.rot_axes[i][2] * friction_torque_val + friction_torque_pub.publish(msg) + + +def main(args=None): + rclpy.init(args=args) + node = WrenchPublisher() + rclpy.spin(node) + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/ros_trick/ros_src/canadarm_wrench_publisher/package.xml b/ros_trick/ros_src/canadarm_wrench_publisher/package.xml new file mode 100644 index 00000000..889b15db --- /dev/null +++ b/ros_trick/ros_src/canadarm_wrench_publisher/package.xml @@ -0,0 +1,18 @@ + + + + canadarm_wrench_publisher + 0.0.0 + TODO: Package description + blazej + TODO: License declaration + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_python + + diff --git a/ros_trick/ros_src/canadarm_wrench_publisher/resource/canadarm_wrench_publisher b/ros_trick/ros_src/canadarm_wrench_publisher/resource/canadarm_wrench_publisher new file mode 100644 index 00000000..c21c341a --- /dev/null +++ b/ros_trick/ros_src/canadarm_wrench_publisher/resource/canadarm_wrench_publisher @@ -0,0 +1,14 @@ +// Copyright 2024 Blazej Fiderek (xfiderek) +// +// 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 +// +// https://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. + diff --git a/ros_trick/ros_src/canadarm_wrench_publisher/setup.cfg b/ros_trick/ros_src/canadarm_wrench_publisher/setup.cfg new file mode 100644 index 00000000..b76e8f59 --- /dev/null +++ b/ros_trick/ros_src/canadarm_wrench_publisher/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/canadarm_wrench_publisher +[install] +install_scripts=$base/lib/canadarm_wrench_publisher diff --git a/ros_trick/ros_src/canadarm_wrench_publisher/setup.py b/ros_trick/ros_src/canadarm_wrench_publisher/setup.py new file mode 100644 index 00000000..1917642a --- /dev/null +++ b/ros_trick/ros_src/canadarm_wrench_publisher/setup.py @@ -0,0 +1,25 @@ +from setuptools import find_packages, setup + +package_name = "canadarm_wrench_publisher" + +setup( + name=package_name, + version="0.0.0", + packages=find_packages(exclude=["test"]), + data_files=[ + ("share/ament_index/resource_index/packages", ["resource/" + package_name]), + ("share/" + package_name, ["package.xml"]), + ], + install_requires=["setuptools"], + zip_safe=True, + maintainer="Blazej Fiderek (xfiderek)", + maintainer_email="fiderekblazej@gmail.com", + description="Get joint torques from trick and publish them as GeometryWrench", + license="Apache-2.0", + tests_require=["pytest"], + entry_points={ + "console_scripts": [ + "canadarm_wrench_publisher_node = canadarm_wrench_publisher.canadarm_wrench_publisher_node:main" + ], + }, +) diff --git a/ros_trick/ros_src/ros_trick_bridge/launch/ros_trick_bridge.launch.py b/ros_trick/ros_src/ros_trick_bridge/launch/ros_trick_bridge.launch.py new file mode 100644 index 00000000..1a616cc5 --- /dev/null +++ b/ros_trick/ros_src/ros_trick_bridge/launch/ros_trick_bridge.launch.py @@ -0,0 +1,150 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + EmitEvent, + LogInfo, + RegisterEventHandler, +) +from launch.conditions import IfCondition +from launch.events.matchers import matches_action +from launch.substitutions import LaunchConfiguration, PythonExpression +from launch_ros.actions import LifecycleNode +from launch_ros.event_handlers import OnStateTransition +from launch_ros.events.lifecycle import ChangeState +from launch_ros.substitutions import FindPackageShare +from lifecycle_msgs.msg import Transition + + +def generate_launch_description(): + ld = LaunchDescription() + + namespace_arg = DeclareLaunchArgument( + "namespace", default_value="", description="ROS2 namespace" + ) + node_name_arg = DeclareLaunchArgument( + "node_name", default_value="ros_trick_bridge", description="Node name" + ) + autostart_arg = DeclareLaunchArgument( + "autostart", + default_value="True", + description="The bridge is a lifecycle node. Set this argument to true to transit to active on startup (start the simulation)", + ) + param_file_arg = DeclareLaunchArgument( + "param_file", + default_value=[ + FindPackageShare("ros_trick_bridge"), + "/params/ros_trick_bridge_example_params.yaml", + ], + description="ROS Trick Bridge config", + ) + + ros_trick_bridge_lifecycle_node = LifecycleNode( + package="ros_trick_bridge", + executable="ros_trick_bridge_node", + name=LaunchConfiguration("node_name"), + namespace=LaunchConfiguration("namespace"), + parameters=[LaunchConfiguration("param_file")], + output="both", + emulate_tty=True, + ) + + ros_trick_emit_configure_event = EmitEvent( + event=ChangeState( + lifecycle_node_matcher=matches_action(ros_trick_bridge_lifecycle_node), + transition_id=Transition.TRANSITION_CONFIGURE, + ), + condition=IfCondition(PythonExpression([LaunchConfiguration("autostart")])), + ) + ros_trick_emit_activate_event = EmitEvent( + event=ChangeState( + lifecycle_node_matcher=matches_action(ros_trick_bridge_lifecycle_node), + transition_id=Transition.TRANSITION_ACTIVATE, + ), + condition=IfCondition(PythonExpression([LaunchConfiguration("autostart")])), + ) + ros_trick_inactive_state_handler = RegisterEventHandler( + OnStateTransition( + target_lifecycle_node=ros_trick_bridge_lifecycle_node, + goal_state="inactive", + entities=[ + ros_trick_emit_activate_event, + ], + ), + condition=IfCondition(PythonExpression([LaunchConfiguration("autostart")])), + ) + + # Add logging for debugging + ld.add_action(LogInfo(msg="Launching ROS Trick Bridge Lifecycle Node")) + ld.add_action(namespace_arg) + ld.add_action(node_name_arg) + ld.add_action(autostart_arg) + ld.add_action(param_file_arg) + ld.add_action(ros_trick_bridge_lifecycle_node) + ld.add_action(ros_trick_inactive_state_handler) + ld.add_action(ros_trick_emit_configure_event) + ld.add_action(LogInfo(msg="Emitting configure event")) + + # Add event handlers for logging state transitions + ld.add_action( + RegisterEventHandler( + OnStateTransition( + target_lifecycle_node=ros_trick_bridge_lifecycle_node, + start_state="unconfigured", + goal_state="configuring", + entities=[ + LogInfo(msg="Transitioning from 'unconfigured' to 'configuring'") + ], + ) + ) + ) + + ld.add_action( + RegisterEventHandler( + OnStateTransition( + target_lifecycle_node=ros_trick_bridge_lifecycle_node, + start_state="configuring", + goal_state="inactive", + entities=[ + LogInfo(msg="Transitioning from 'configuring' to 'inactive'") + ], + ) + ) + ) + + ld.add_action( + RegisterEventHandler( + OnStateTransition( + target_lifecycle_node=ros_trick_bridge_lifecycle_node, + start_state="inactive", + goal_state="activating", + entities=[LogInfo(msg="Transitioning from 'inactive' to 'activating'")], + ) + ) + ) + + ld.add_action( + RegisterEventHandler( + OnStateTransition( + target_lifecycle_node=ros_trick_bridge_lifecycle_node, + start_state="activating", + goal_state="active", + entities=[LogInfo(msg="Transitioning from 'activating' to 'active'")], + ) + ) + ) + + return ld diff --git a/ros_trick/ros_src/ros_trick_bridge/package.xml b/ros_trick/ros_src/ros_trick_bridge/package.xml new file mode 100644 index 00000000..389ce4f2 --- /dev/null +++ b/ros_trick/ros_src/ros_trick_bridge/package.xml @@ -0,0 +1,18 @@ + + + + ros_trick_bridge + 0.0.0 + Bridge between ROS and NASA Trick simulator + Blazej Fiderek (xfiderek) + TODO: License declaration + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_python + + diff --git a/ros_trick/ros_src/ros_trick_bridge/params/ros_trick_bridge_example_params.yaml b/ros_trick/ros_src/ros_trick_bridge/params/ros_trick_bridge_example_params.yaml new file mode 100644 index 00000000..b7cfcbaa --- /dev/null +++ b/ros_trick/ros_src/ros_trick_bridge/params/ros_trick_bridge_example_params.yaml @@ -0,0 +1,8 @@ +ros_trick_bridge: + ros__parameters: + sim_directory: /opt/trick_sims/SIM_trick_canadarm + sim_inputfile: RUN_2DPlanar/input.py + sim_executable: S_main_Linux_11.4_x86_64.exe + sim_args: '' + publish_clock: true + clock_publish_period: 0.02 diff --git a/ros_trick/ros_src/ros_trick_bridge/resource/ros_trick_bridge b/ros_trick/ros_src/ros_trick_bridge/resource/ros_trick_bridge new file mode 100644 index 00000000..c21c341a --- /dev/null +++ b/ros_trick/ros_src/ros_trick_bridge/resource/ros_trick_bridge @@ -0,0 +1,14 @@ +// Copyright 2024 Blazej Fiderek (xfiderek) +// +// 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 +// +// https://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. + diff --git a/ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/__init__.py b/ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/__init__.py new file mode 100644 index 00000000..be353d1a --- /dev/null +++ b/ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/__init__.py @@ -0,0 +1,13 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. diff --git a/ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/ros_trick_bridge_node.py b/ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/ros_trick_bridge_node.py new file mode 100644 index 00000000..7c6b921c --- /dev/null +++ b/ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/ros_trick_bridge_node.py @@ -0,0 +1,198 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. + + +import os +import subprocess +import threading +import time + +import rclpy +from builtin_interfaces.msg import Time +from rclpy.executors import SingleThreadedExecutor +from rclpy.lifecycle import Node, State, TransitionCallbackReturn +from ros_trick_bridge.trick_variable_server_client import TrickVariableServerClient +from rosgraph_msgs.msg import Clock + + +class RosTrickBridgeNode(Node): + TRICK_TICK_VALUE_VAR_NAME = "trick_sys.sched.time_tic_value" + TRICK_TIME_TICS_VAR_NAME = "trick_sys.sched.time_tics" + + def __init__(self, node_name: str, **kwargs): + self._trick_subprocess = None + self._std_print_period = 0.1 + self._stdout_print_thread = None + + self._trick_variable_server_client = None + self._clock_publisher = None + + super().__init__(node_name, **kwargs) + + # def on_init(self, state: State) -> TransitionCallbackReturn: + # self.get_logger().info('nddd') + + def on_configure(self, state: State) -> TransitionCallbackReturn: + # Declare ROS 2 parameters + self.declare_parameter("sim_directory", "/path/to/sim") + self.declare_parameter("sim_executable", "S_main_Linux_11.4_x86_64.exe") + self.declare_parameter("sim_inputfile", "RUN_2DPlanar/input.py") + self.declare_parameter("sim_args", "") + self.declare_parameter("trick_host", "localhost") + self.declare_parameter("trick_port", 49765) + self.declare_parameter("publish_clock", True) + self.declare_parameter("clock_publish_period", 0.1) + + self.get_logger().info(f"Configuring from state: {state.label}") + if not "TRICK_HOME" in os.environ: + error = "TRICK_HOME env variable is not set, terminating" + self.get_logger().error(error) + raise Exception(error) + + # Get the parameters + sim_directory = ( + self.get_parameter("sim_directory").get_parameter_value().string_value + "/" + ) + sim_executable = ( + self.get_parameter("sim_executable").get_parameter_value().string_value + ) + sim_inputfile = ( + self.get_parameter("sim_inputfile").get_parameter_value().string_value + ) + sim_args = self.get_parameter("sim_args").get_parameter_value().string_value + try: + cmd = [f"./{sim_executable}", sim_inputfile, sim_args] + self.get_logger().info(f"Starting trick with command: {cmd}") + self._trick_subprocess = subprocess.Popen( + cmd, + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True, + cwd=sim_directory, + ) + self.get_logger().info("######################################") + self.get_logger().info("Trick subprocess started successfully.") + self.get_logger().info("######################################") + self.get_logger().info(f"Trick pid is {self._trick_subprocess.pid}") + except Exception as e: + self.get_logger().error("######################################") + self.get_logger().error(f"Failed to start trick subprocess: {e}") + self.get_logger().error("######################################") + return TransitionCallbackReturn.FAILURE + + # it must run on a separate thread to avoid IO blocking + self._stdout_print_thread = threading.Thread( + target=self._print_subprocess_stdout + ) + self._stdout_print_thread.start() + + # give a process some time to spin up + time.sleep(1.0) + return TransitionCallbackReturn.SUCCESS + + def on_activate(self, state: State) -> TransitionCallbackReturn: + if self.get_parameter("publish_clock").get_parameter_value().bool_value: + trick_data_callback = self._publish_clock_from_trick + self._clock_publisher = self.create_publisher( + msg_type=Clock, topic="/clock", qos_profile=10 + ) + else: + # we don't need any data from trick otherwise + trick_data_callback = None + + try: + self._trick_variable_server_client = TrickVariableServerClient( + self.get_parameter("trick_host").get_parameter_value().string_value, + self.get_parameter("trick_port").get_parameter_value().integer_value, + "ros_trick_bridge", + [self.TRICK_TICK_VALUE_VAR_NAME, self.TRICK_TIME_TICS_VAR_NAME], + self.get_parameter("clock_publish_period") + .get_parameter_value() + .double_value, + trick_data_callback, + ) + except Exception as e: + self.get_logger().error( + f"Failed to start trick variable server client: {e}" + ) + return TransitionCallbackReturn.FAILURE + + self.get_logger().info(f"Activating from state: {state.label}") + self._trick_variable_server_client.unfreeze_sim() + return super().on_activate(state) + + def on_deactivate(self, state: State) -> TransitionCallbackReturn: + self.get_logger().info(f"Deactivating from state: {state.label}") + self._trick_variable_server_client.freeze_sim() + return super().on_deactivate(state) + + def on_cleanup(self, state: State) -> TransitionCallbackReturn: + self.get_logger().info(f"Cleaning up from state: {state.label}") + self._teardown_sim() + + return TransitionCallbackReturn.SUCCESS + + def on_shutdown(self, state: State) -> TransitionCallbackReturn: + self.get_logger().info(f"Shutting down from state: {state.label}") + self._teardown_sim() + + return TransitionCallbackReturn.SUCCESS + + def on_error(self, state: State) -> TransitionCallbackReturn: + self.get_logger().info(f"Error from state: {state.label}") + return TransitionCallbackReturn.SUCCESS + + def _teardown_sim(self): + self._trick_variable_server_client = None + + # Terminate the subprocess if it's still running + if self._trick_subprocess and self._trick_subprocess.poll() is None: + self._trick_subprocess.terminate() + + def _publish_clock_from_trick(self, trick_data): + ticks_per_second = int(trick_data[self.TRICK_TICK_VALUE_VAR_NAME]) + curr_time_tics = int(trick_data[self.TRICK_TIME_TICS_VAR_NAME]) + seconds = curr_time_tics // ticks_per_second + nanoseconds = (curr_time_tics % ticks_per_second) * ( + 1000000000 // ticks_per_second + ) + clock_msg = Clock() + clock_msg.clock = Time() + clock_msg.clock.sec = seconds + clock_msg.clock.nanosec = nanoseconds + self._clock_publisher.publish(clock_msg) + + def _print_subprocess_stdout(self): + while True: + if self._trick_subprocess: + # Read from stdout + stdout_line = self._trick_subprocess.stdout.readline() + if stdout_line: + self.get_logger().info(stdout_line) + time.sleep(self._std_print_period) + + +def main(args=None): + rclpy.init(args=args) + executor = SingleThreadedExecutor() + lifecycle_node = RosTrickBridgeNode("ros_trick_bridge") + executor.add_node(lifecycle_node) + try: + executor.spin() + except (KeyboardInterrupt, rclpy.executors.ExternalShutdownException): + lifecycle_node._teardown_sim() + + +if __name__ == "__main__": + main() diff --git a/ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/trick_variable_server_client.py b/ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/trick_variable_server_client.py new file mode 100644 index 00000000..b5ad418a --- /dev/null +++ b/ros_trick/ros_src/ros_trick_bridge/ros_trick_bridge/trick_variable_server_client.py @@ -0,0 +1,85 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. + + +import socket +import threading +import time + + +class TrickVariableServerClient: + def __init__( + self, + host, + port, + client_tag, + trick_variable_names, + trick_var_cycle_time=0.1, + on_receive_callback=None, + ): + self._client_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + self._client_socket.connect((host, port)) + + self._insock = self._client_socket.makefile("r") + + self._variable_names = trick_variable_names + self._latest_data = {} + self._on_receive_callback = on_receive_callback + self._trick_var_cycle_time = trick_var_cycle_time + + # send configuration info to trick and ask for variables + self._client_socket.send( + f'trick.var_set_client_tag("{client_tag}") \n'.encode() + ) + self._client_socket.send( + f"trick.var_cycle({str(trick_var_cycle_time)}) \n".encode() + ) + + self._receive_thread = threading.Thread(target=self._rcv_trick_data_from_socket) + self._receive_thread.start() + + def freeze_sim(self): + self._client_socket.send("trick.exec_freeze()\n".encode()) + self.stop_listening() + + def unfreeze_sim(self): + self.start_listening() + self._client_socket.send("trick.exec_run()\n".encode()) + + def start_listening(self): + command = b"" + for trick_var_name in self._variable_names: + command += f'trick.var_add("{trick_var_name}") \n'.encode() + self._client_socket.send("trick.var_ascii()\n".encode()) + self._client_socket.send(command) + + def stop_listening(self): + self._client_socket.send("trick.var_clear()\n".encode()) + + def send_data_to_sim(self, var_name: str, value: str) -> None: + self._client_socket.send(f"{var_name} = {value} \n".encode()) + + def _rcv_trick_data_from_socket(self): + while True: + if self._insock: + line = self._insock.readline() + if line: + variables = line.split("\t") + if variables[0] == "0": + for i, var_name in enumerate(self._variable_names): + self._latest_data[var_name] = variables[i + 1].strip() + if self._on_receive_callback: + self._on_receive_callback(self._latest_data.copy()) + else: + time.sleep(self._trick_var_cycle_time) diff --git a/ros_trick/ros_src/ros_trick_bridge/setup.cfg b/ros_trick/ros_src/ros_trick_bridge/setup.cfg new file mode 100644 index 00000000..19ca6234 --- /dev/null +++ b/ros_trick/ros_src/ros_trick_bridge/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/ros_trick_bridge +[install] +install_scripts=$base/lib/ros_trick_bridge diff --git a/ros_trick/ros_src/ros_trick_bridge/setup.py b/ros_trick/ros_src/ros_trick_bridge/setup.py new file mode 100644 index 00000000..f65525fa --- /dev/null +++ b/ros_trick/ros_src/ros_trick_bridge/setup.py @@ -0,0 +1,30 @@ +import os +from glob import glob + +from setuptools import find_packages, setup + +package_name = "ros_trick_bridge" + +setup( + name=package_name, + version="0.0.0", + packages=find_packages(exclude=["test"]), + data_files=[ + ("share/ament_index/resource_index/packages", ["resource/" + package_name]), + ("share/" + package_name, ["package.xml"]), + (os.path.join("share", package_name, "launch"), glob("launch/*.py")), + (os.path.join("share", package_name, "params"), glob("params/*")), + ], + install_requires=["setuptools"], + zip_safe=True, + maintainer="Blazej Fiderek (xfiderek)", + maintainer_email="fiderekblazej@gmail.com", + description="", + license="Apache-2.0", + tests_require=["pytest"], + entry_points={ + "console_scripts": [ + "ros_trick_bridge_node = ros_trick_bridge.ros_trick_bridge_node:main" + ], + }, +) diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/.setup_assistant b/ros_trick/ros_src/trick_canadarm_moveit_config/.setup_assistant new file mode 100644 index 00000000..23da2f9a --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/.setup_assistant @@ -0,0 +1,27 @@ +moveit_setup_assistant_config: + urdf: + package: simulation + relative_path: models/canadarm/urdf/SSRMS_Canadarm2.urdf + srdf: + relative_path: config/SSRMS_Canadarm2.srdf + package_settings: + author_name: Dharini Dutia + author_email: dharini@openrobotics.org + generated_timestamp: 1672757808 + control_xacro: + command: + - position + - velocity + state: + - position + - velocity + modified_urdf: + xacros: + - control_xacro + control_xacro: + command: + - position + - velocity + state: + - position + - velocity \ No newline at end of file diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/CMakeLists.txt b/ros_trick/ros_src/trick_canadarm_moveit_config/CMakeLists.txt new file mode 100644 index 00000000..29f23015 --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.22) +project(trick_canadarm_moveit_config) + +find_package(ament_cmake REQUIRED) + +ament_package() + +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.ros2_control.xacro b/ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.ros2_control.xacro new file mode 100644 index 00000000..8b5dacac --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.ros2_control.xacro @@ -0,0 +1,90 @@ + + + + + + trick_ros2_control/TrickSystem + localhost + 49765 + 100.0 + + + + + + + + CanadarmManip.manip.q[0] + CanadarmManip.manip.q_dot[0] + CanadarmManip.manip.q_dotdot[0] + CanadarmManip.manip.input_torque[0] + + + + + + + + CanadarmManip.manip.q[1] + CanadarmManip.manip.q_dot[1] + CanadarmManip.manip.q_dotdot[1] + CanadarmManip.manip.input_torque[1] + + + + + + + + CanadarmManip.manip.q[2] + CanadarmManip.manip.q_dot[2] + CanadarmManip.manip.q_dotdot[2] + CanadarmManip.manip.input_torque[2] + + + + + + + + CanadarmManip.manip.q[3] + CanadarmManip.manip.q_dot[3] + CanadarmManip.manip.q_dotdot[3] + CanadarmManip.manip.input_torque[3] + + + + + + + + CanadarmManip.manip.q[4] + CanadarmManip.manip.q_dot[4] + CanadarmManip.manip.q_dotdot[4] + CanadarmManip.manip.input_torque[4] + + + + + + + + CanadarmManip.manip.q[5] + CanadarmManip.manip.q_dot[5] + CanadarmManip.manip.q_dotdot[5] + CanadarmManip.manip.input_torque[5] + + + + + + + + CanadarmManip.manip.q[6] + CanadarmManip.manip.q_dot[6] + CanadarmManip.manip.q_dotdot[6] + CanadarmManip.manip.input_torque[6] + + + + diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.srdf b/ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.srdf new file mode 100644 index 00000000..3b6cf266 --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.srdf @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.urdf.xacro b/ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.urdf.xacro new file mode 100644 index 00000000..a1ffd28c --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.urdf.xacro @@ -0,0 +1,295 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/config/initial_positions.yaml b/ros_trick/ros_src/trick_canadarm_moveit_config/config/initial_positions.yaml new file mode 100644 index 00000000..a60f036d --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/config/initial_positions.yaml @@ -0,0 +1,8 @@ +initial_positions: + Base_Joint: 0 + Elbow_Pitch: 0 + Shoulder_Roll: 0 + Shoulder_Yaw: 0 + Wrist_Pitch: 0 + Wrist_Roll: 0 + Wrist_Yaw: 0 diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/config/joint_limits.yaml b/ros_trick/ros_src/trick_canadarm_moveit_config/config/joint_limits.yaml new file mode 100644 index 00000000..276f5eb3 --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/config/joint_limits.yaml @@ -0,0 +1,45 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + Base_Joint: + has_velocity_limits: true + max_velocity: 0.1 + has_acceleration_limits: true + max_acceleration: 0.025 + Elbow_Pitch: + has_velocity_limits: true + max_velocity: 0.1 + has_acceleration_limits: true + max_acceleration: 0.025 + Shoulder_Roll: + has_velocity_limits: true + max_velocity: 0.1 + has_acceleration_limits: true + max_acceleration: 0.025 + Shoulder_Yaw: + has_velocity_limits: true + max_velocity: 0.1 + has_acceleration_limits: true + max_acceleration: 0.025 + Wrist_Pitch: + has_velocity_limits: true + max_velocity: 0.1 + has_acceleration_limits: true + max_acceleration: 0.025 + Wrist_Roll: + has_velocity_limits: true + max_velocity: 0.1 + has_acceleration_limits: true + max_acceleration: 0.025 + Wrist_Yaw: + has_velocity_limits: true + max_velocity: 0.1 + has_acceleration_limits: true + max_acceleration: 0.025 diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/config/kinematics.yaml b/ros_trick/ros_src/trick_canadarm_moveit_config/config/kinematics.yaml new file mode 100644 index 00000000..f54b70cd --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/config/kinematics.yaml @@ -0,0 +1,8 @@ +canadarm: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.05 +canadarm_planning_group: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/config/moveit.rviz b/ros_trick/ros_src/trick_canadarm_moveit_config/config/moveit.rviz new file mode 100644 index 00000000..c4d16195 --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/config/moveit.rviz @@ -0,0 +1,448 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Wrench1 + - /Wrench2 + - /Wrench3 + - /Wrench4 + - /Wrench5 + - /Wrench6 + - /Wrench7 + - /TF1 + - /MotionPlanning1 + - /MotionPlanning1/Scene Robot1 + - /MotionPlanning1/Planning Request1 + - /MotionPlanning1/Planned Path1 + Splitter Ratio: 0.5 + Tree Height: 165 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Acceleration_Scaling_Factor: 0.1 + Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + Move Group Namespace: "" + MoveIt_Allow_Approximate_IK: false + MoveIt_Allow_External_Program: false + MoveIt_Allow_Replanning: false + MoveIt_Allow_Sensor_Positioning: false + MoveIt_Planning_Attempts: 10 + MoveIt_Planning_Time: 5 + MoveIt_Use_Cartesian_Path: false + MoveIt_Use_Constraint_Aware_IK: false + MoveIt_Workspace: + Center: + X: 0 + Y: 0 + Z: 0 + Size: + X: 2 + Y: 2 + Z: 2 + Name: MotionPlanning + Planned Path: + Color Enabled: false + Interrupt Display: false + Links: + All Links Enabled: true + B1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + B2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + B3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + B4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + B5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + B6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Base_SSRMS: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + EE_SSRMS: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + world: + Alpha: 1 + Show Axes: false + Show Trail: false + Loop Animation: false + Robot Alpha: 0.30000001192092896 + Robot Color: 150; 50; 150 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trail Step Size: 1 + Trajectory Topic: display_planned_path + Use Sim Time: false + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + TextHeight: 0.07999999821186066 + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 0.25 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 1.5 + Joint Violation Color: 255; 0; 255 + Planning Group: canadarm + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 0 + Start State Color: 0; 255; 0 + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Color: 50; 230; 50 + Scene Display Time: 0.009999999776482582 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + All Links Enabled: true + B1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + B2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + B3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + B4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + B5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + B6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Base_SSRMS: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + EE_SSRMS: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + world: + Alpha: 1 + Show Axes: false + Show Trail: false + Robot Alpha: 1 + Show Robot Collision: false + Show Robot Visual: true + Value: true + Velocity_Scaling_Factor: 0.1 + - Accept NaN Values: false + Alpha: 1 + Arrow Width: 0.4000000059604645 + Class: rviz_default_plugins/Wrench + Enabled: true + Force Arrow Scale: 2 + Force Color: 204; 51; 51 + History Length: 1 + Name: Wrench + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /wrench_topic/B1/total_torque + Torque Arrow Scale: 0.029999999329447746 + Torque Color: 255; 0; 255 + Value: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + B1: + Value: true + B2: + Value: true + B3: + Value: true + B4: + Value: true + B5: + Value: true + B6: + Value: true + Base_SSRMS: + Value: true + EE_SSRMS: + Value: true + world: + Value: true + Marker Scale: 4 + Name: TF + Show Arrows: false + Show Axes: true + Show Names: true + Tree: + world: + Base_SSRMS: + B1: + B2: + B3: + B4: + B5: + B6: + EE_SSRMS: + {} + Update Interval: 0 + Value: true + - Accept NaN Values: false + Alpha: 1 + Arrow Width: 0.4000000059604645 + Class: rviz_default_plugins/Wrench + Enabled: true + Force Arrow Scale: 2 + Force Color: 204; 51; 51 + History Length: 1 + Name: Wrench + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /wrench_topic/B2/total_torque + Torque Arrow Scale: 0.029999999329447746 + Torque Color: 255; 0; 255 + Value: true + - Accept NaN Values: false + Alpha: 1 + Arrow Width: 0.4000000059604645 + Class: rviz_default_plugins/Wrench + Enabled: true + Force Arrow Scale: 2 + Force Color: 204; 51; 51 + History Length: 1 + Name: Wrench + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /wrench_topic/B3/total_torque + Torque Arrow Scale: 0.029999999329447746 + Torque Color: 255; 0; 255 + Value: true + - Accept NaN Values: false + Alpha: 1 + Arrow Width: 0.4000000059604645 + Class: rviz_default_plugins/Wrench + Enabled: true + Force Arrow Scale: 2 + Force Color: 204; 51; 51 + History Length: 1 + Name: Wrench + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /wrench_topic/B4/total_torque + Torque Arrow Scale: 0.029999999329447746 + Torque Color: 255; 0; 255 + Value: true + - Accept NaN Values: false + Alpha: 1 + Arrow Width: 0.4000000059604645 + Class: rviz_default_plugins/Wrench + Enabled: true + Force Arrow Scale: 2 + Force Color: 204; 51; 51 + History Length: 1 + Name: Wrench + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /wrench_topic/B5/total_torque + Torque Arrow Scale: 0.029999999329447746 + Torque Color: 255; 0; 255 + Value: true + - Accept NaN Values: false + Alpha: 1 + Arrow Width: 0.4000000059604645 + Class: rviz_default_plugins/Wrench + Enabled: true + Force Arrow Scale: 2 + Force Color: 204; 51; 51 + History Length: 1 + Name: Wrench + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /wrench_topic/B6/total_torque + Torque Arrow Scale: 0.029999999329447746 + Torque Color: 255; 0; 255 + Value: true + - Accept NaN Values: false + Alpha: 1 + Arrow Width: 0.4000000059604645 + Class: rviz_default_plugins/Wrench + Enabled: true + Force Arrow Scale: 2 + Force Color: 204; 51; 51 + History Length: 1 + Name: Wrench + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /wrench_topic/EE_SSRMS/total_torque + Torque Arrow Scale: 0.029999999329447746 + Torque Color: 255; 0; 255 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 13.27796459197998 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 2.8083510398864746 + Y: -0.03512916713953018 + Z: 1.6076182126998901 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.40500012040138245 + Target Frame: + Value: Orbit (rviz_default_plugins) + Yaw: 5.786983013153076 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1080 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + MotionPlanning: + collapsed: false + MotionPlanning - Trajectory Slider: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000001e600000397fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004600fffffffb000000100044006900730070006c0061007900730100000025000000e7000000ce00fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000112000001e3000001a300fffffffb0000000800480065006c0070000000029a0000006e0000007000fffffffb0000000a0056006900650077007301000002fb000000c1000000ac00ffffff000005940000039700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1920 + X: 0 + Y: 27 diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/config/moveit_controllers.yaml b/ros_trick/ros_src/trick_canadarm_moveit_config/config/moveit_controllers.yaml new file mode 100644 index 00000000..e38b88b3 --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/config/moveit_controllers.yaml @@ -0,0 +1,18 @@ +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - canadarm_controller + + canadarm_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - Base_Joint + - Shoulder_Roll + - Shoulder_Yaw + - Elbow_Pitch + - Wrist_Pitch + - Wrist_Yaw + - Wrist_Roll diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/config/pilz_cartesian_limits.yaml b/ros_trick/ros_src/trick_canadarm_moveit_config/config/pilz_cartesian_limits.yaml new file mode 100644 index 00000000..b2997caf --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/config/ros2_controllers.yaml b/ros_trick/ros_src/trick_canadarm_moveit_config/config/ros2_controllers.yaml new file mode 100644 index 00000000..244d22bd --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/config/ros2_controllers.yaml @@ -0,0 +1,77 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + canadarm_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +canadarm_controller: + ros__parameters: + open_loop_control: false + allow_nonzero_velocity_at_trajectory_end: false + constraints: + stopped_velocity_tolerance: 0.001 + goal_time: 0.0 + joints: + - Base_Joint + - Shoulder_Roll + - Shoulder_Yaw + - Elbow_Pitch + - Wrist_Pitch + - Wrist_Yaw + - Wrist_Roll + command_interfaces: + - effort + state_interfaces: + - position + - velocity + state_publish_rate: 50.0 + action_monitor_rate: 20.0 + gains: + Base_Joint: + p: 92000.0 + i: 0.0 + d: 2050.0 + ff_velocity_scale: 0.0 + i_clamp: 0.0 + Shoulder_Roll: + p: 92000.0 + i: 0.0 + d: 2050.0 + ff_velocity_scale: 0.0 + i_clamp: 0.0 + Shoulder_Yaw: + p: 92000.0 + i: 0.0 + d: 2050.0 + ff_velocity_scale: 0.0 + i_clamp: 0.0 + Elbow_Pitch: + p: 92000.0 + i: 0.0 + d: 2050.0 + ff_velocity_scale: 0.0 + i_clamp: 0.0 + Wrist_Pitch: + p: 50000.0 + i: 0.0 + d: 1100.0 + ff_velocity_scale: 0.0 + i_clamp: 0.0 + Wrist_Yaw: + p: 500.0 + i: 0.0 + d: 50.0 + ff_velocity_scale: 0.0 + i_clamp: 0.0 + Wrist_Roll: + p: 500.0 + i: 0.0 + d: 50.0 + ff_velocity_scale: 0.0 + i_clamp: 0.0 diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/launch/__pycache__/moveit_rviz.launch.cpython-310.pyc b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/__pycache__/moveit_rviz.launch.cpython-310.pyc new file mode 100644 index 0000000000000000000000000000000000000000..6f04eb38f42f31264325deb164b8361b4314205c GIT binary patch literal 499 zcmZvZy-ve05P;8dS_-5Bq=JwT8%vfB%m^VeF*F0&x>#2128;Yuwo?fN6Rf-gj64Hx zl9h>9VB*}gQYvxMozCa``OdC}!yQ1`l3%l!0DQYcS3Epip_(%^0tCsSAX7q|@8w=W zrxblE{8yOzqL)C}|G`WMNi&*M3wdLss+_6JT-PcWQe*rilcm($N>*TkvP>`3Bg=VR zrgy2UT?_Jnj~bzxV>A}$3s2BD@11>Cg$${7J2nTl+DtT>VjRGZ#=)iBxeE!!-KI>vozGq@-!QRni~ NJ)`NP2_PT={R4oygns}4 literal 0 HcmV?d00001 diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/launch/demo.launch.py b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/demo.launch.py new file mode 100644 index 00000000..61fe9c9e --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/demo.launch.py @@ -0,0 +1,67 @@ +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node, SetParameter +from moveit_configs_utils import MoveItConfigsBuilder + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder( + "SSRMS_Canadarm2", package_name="trick_canadarm_moveit_config" + ).to_moveit_configs() + moveit_config.move_group_capabilities["capabilities"] = "" + ld = LaunchDescription() + virtual_joints_launch = ( + moveit_config.package_path / "launch/static_virtual_joint_tfs.launch.py" + ) + if virtual_joints_launch.exists(): + ld.add_action( + IncludeLaunchDescription( + PythonLaunchDescriptionSource(str(virtual_joints_launch)), + ) + ) + + # Given the published joint states, publish tf for the robot links + ld.add_action( + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + str(moveit_config.package_path / "launch/rsp.launch.py") + ), + ) + ) + + ld.add_action( + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + str(moveit_config.package_path / "launch/move_group.launch.py") + ), + ) + ) + + ld.add_action( + Node( + package="canadarm_wrench_publisher", + executable="canadarm_wrench_publisher_node", + ) + ) + + ld.add_action( + Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ + moveit_config.robot_description, + str(moveit_config.package_path / "config/ros2_controllers.yaml"), + ], + ) + ) + + ld.add_action( + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + str(moveit_config.package_path / "launch/spawn_controllers.launch.py") + ), + ) + ) + + return ld diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/launch/move_group.launch.py b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/move_group.launch.py new file mode 100644 index 00000000..31727c2f --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/move_group.launch.py @@ -0,0 +1,73 @@ +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launch_utils import ( + DeclareBooleanLaunchArg, + add_debuggable_node, +) + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder( + "SSRMS_Canadarm2", package_name="trick_canadarm_moveit_config" + ).to_moveit_configs() + # print("prinint capab") + # print(moveit_config.move_group_capabilities) + moveit_config.move_group_capabilities["capabilities"] = "" + ld = LaunchDescription() + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ""}, + ) + return ld diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/launch/moveit_rviz.launch.py b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/moveit_rviz.launch.py new file mode 100644 index 00000000..91b265fe --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/moveit_rviz.launch.py @@ -0,0 +1,14 @@ +from launch import LaunchDescription +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + + +def generate_launch_description(): + ld = LaunchDescription() + + moveit_config = MoveItConfigsBuilder( + "SSRMS_Canadarm2", package_name="trick_canadarm_moveit_config" + ).to_moveit_configs() + + ld.add_action(generate_moveit_rviz_launch(moveit_config)) + return ld diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/launch/rsp.launch.py b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/rsp.launch.py new file mode 100644 index 00000000..540aedc4 --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/rsp.launch.py @@ -0,0 +1,32 @@ +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node +from moveit_configs_utils import MoveItConfigsBuilder + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder( + "SSRMS_Canadarm2", package_name="trick_canadarm_moveit_config" + ).to_moveit_configs() + moveit_config.move_group_capabilities["capabilities"] = "" + + ld = LaunchDescription() + ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0")) + + # Given the published joint states, publish tf for the robot links and the robot description + rsp_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + respawn=True, + output="screen", + parameters=[ + moveit_config.robot_description, + { + "publish_frequency": LaunchConfiguration("publish_frequency"), + }, + ], + ) + ld.add_action(rsp_node) + + return ld diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/launch/setup_assistant.launch.py b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/setup_assistant.launch.py new file mode 100644 index 00000000..2b308057 --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/setup_assistant.launch.py @@ -0,0 +1,9 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_setup_assistant_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder( + "SSRMS_Canadarm2", package_name="trick_canadarm_moveit_config" + ).to_moveit_configs() + return generate_setup_assistant_launch(moveit_config) diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/launch/spawn_controllers.launch.py b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/spawn_controllers.launch.py new file mode 100644 index 00000000..449daaba --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/spawn_controllers.launch.py @@ -0,0 +1,9 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_spawn_controllers_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder( + "SSRMS_Canadarm2", package_name="trick_canadarm_moveit_config" + ).to_moveit_configs() + return generate_spawn_controllers_launch(moveit_config) diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/launch/static_virtual_joint_tfs.launch.py b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/static_virtual_joint_tfs.launch.py new file mode 100644 index 00000000..0ee48dc6 --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/static_virtual_joint_tfs.launch.py @@ -0,0 +1,9 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder( + "SSRMS_Canadarm2", package_name="trick_canadarm_moveit_config" + ).to_moveit_configs() + return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/launch/warehouse_db.launch.py b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/warehouse_db.launch.py new file mode 100644 index 00000000..7673e3c4 --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/launch/warehouse_db.launch.py @@ -0,0 +1,9 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_warehouse_db_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder( + "SSRMS_Canadarm2", package_name="trick_canadarm_moveit_config" + ).to_moveit_configs() + return generate_warehouse_db_launch(moveit_config) diff --git a/ros_trick/ros_src/trick_canadarm_moveit_config/package.xml b/ros_trick/ros_src/trick_canadarm_moveit_config/package.xml new file mode 100644 index 00000000..224b2372 --- /dev/null +++ b/ros_trick/ros_src/trick_canadarm_moveit_config/package.xml @@ -0,0 +1,46 @@ + + + + trick_canadarm_moveit_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the SSRMS_Canadarm2 with the MoveIt Motion Planning Framework + Derived from spaceros/demos/canadarm_moveit_config demo + + Dharini Dutia + + BSD + + Blazej Fiderek(xfiderek) + Dharini Dutia + + ament_cmake + + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro + controller_manager + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + simulation + tf2_ros + warehouse_ros_mongo + xacro + + + + ament_cmake + + diff --git a/ros_trick/ros_src/trick_ros2_control/CMakeLists.txt b/ros_trick/ros_src/trick_ros2_control/CMakeLists.txt new file mode 100644 index 00000000..dde3b3c5 --- /dev/null +++ b/ros_trick/ros_src/trick_ros2_control/CMakeLists.txt @@ -0,0 +1,81 @@ +cmake_minimum_required(VERSION 3.8) +project(trick_ros2_control) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(hardware_interface REQUIRED) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) +find_package(realtime_tools REQUIRED) + + +add_library( + trick_ros2_control + SHARED + src/trick_system.cpp + src/socket.cpp +) +target_include_directories( + trick_ros2_control + PUBLIC + include +) +ament_target_dependencies( + trick_ros2_control + hardware_interface + rclcpp + rclcpp_lifecycle + realtime_tools +) +# prevent pluginlib from using boost +target_compile_definitions(trick_ros2_control PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") + +pluginlib_export_plugin_description_file( + hardware_interface trick_ros2_control.xml) + +install( + TARGETS + trick_ros2_control + RUNTIME DESTINATION bin + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib +) + +install( + DIRECTORY include/ + DESTINATION include +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() + find_package(ament_cmake_gmock REQUIRED) + find_package(ros2_control_test_assets REQUIRED) +endif() + +ament_export_include_directories( + include +) +ament_export_libraries( + trick_ros2_control +) +ament_export_dependencies( + hardware_interface + pluginlib + rclcpp + rclcpp_lifecycle +) + +ament_package() diff --git a/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/socket.hpp b/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/socket.hpp new file mode 100644 index 00000000..bbfd90fc --- /dev/null +++ b/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/socket.hpp @@ -0,0 +1,51 @@ +// Copyright 2024 Blazej Fiderek (xfiderek) +// +// 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 +// +// https://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. + +// Largely inspired by +// https://github.com/nasa/trick/blob/master/trick_sims/SIM_billiards/models/graphics/cpp/Socket.cpp +#ifndef TRICK_ROS2_CONTROL__SOCKET_HPP_ +#define TRICK_ROS2_CONTROL__SOCKET_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#define SOCKET_BUF_SIZE 20480 + +class Socket +{ +public: + Socket(); + int init(std::string hostname, int port); + + int send(std::string message); + int operator<<(std::string message); + + std::string receive(); + void operator>>(std::string& ret); + +private: + int _port; + std::string _hostname; + int _socket_fd; + bool _initialized; + char carry_on_buffer_[SOCKET_BUF_SIZE] = { '\0' }; + char trick_delimiter_ = '\n'; +}; + +#endif diff --git a/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/trick_system.hpp b/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/trick_system.hpp new file mode 100644 index 00000000..a9630c1b --- /dev/null +++ b/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/trick_system.hpp @@ -0,0 +1,142 @@ +// Copyright 2024 Blazej Fiderek (xfiderek) +// +// 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 +// +// https://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TRICK_ROS2_CONTROL__TRICK_SYSTEM_HPP_ +#define TRICK_ROS2_CONTROL__TRICK_SYSTEM_HPP_ + +#include "hardware_interface/handle.hpp" +#include "hardware_interface/hardware_info.hpp" +#include "hardware_interface/system_interface.hpp" +#include "hardware_interface/types/hardware_interface_return_values.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include "rclcpp/macros.hpp" +#include "rclcpp/rclcpp.hpp" +#include "rclcpp_lifecycle/state.hpp" +#include "realtime_tools/realtime_buffer.h" +#include "trick_ros2_control/socket.hpp" +#include "trick_ros2_control/utils.hpp" +#include "trick_ros2_control/visibility_control.h" +#include +#include +#include +#include + +namespace trick_ros2_control +{ + +/** + * @brief Data structure representing robot data on ROS side + * + */ +struct RosJointData +{ + std::string name; + double joint_position = std::numeric_limits::quiet_NaN(); + double joint_velocity = std::numeric_limits::quiet_NaN(); + double joint_acceleration = std::numeric_limits::quiet_NaN(); + double joint_effort = std::numeric_limits::quiet_NaN(); + double joint_position_cmd; + double joint_velocity_cmd; + double joint_acceleration_cmd; + double joint_effort_cmd; +}; + +/** + * @brief Data structure representing data on Trick side + * Used in the file to map trick variable to pointer to the data + * Used for both sending and receiving data + */ +struct TrickData +{ + const std::string trick_var_name; + double* const data_ptr; + TrickData(const std::string& trick_var_name, double* const data_ptr) + : trick_var_name(trick_var_name), data_ptr(data_ptr){}; +}; + +/** + * @brief Mapping from the pointer where command is stored to the corresponding trick variable name + */ +using CommandDataToTrickVarName = std::pair; +/** + * @brief Mapping from trick variable name to pointer where its value is stored + */ +using TrickVarNameToStateData = std::pair; + +class TrickSystem : public hardware_interface::SystemInterface +{ +public: + TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC + hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo& info) override; + + TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC + hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override; + + TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC + std::vector export_state_interfaces() override; + + TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC + std::vector export_command_interfaces() override; + + TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC + hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override; + + TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC + hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override; + + TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC + hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) override; + + TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC + hardware_interface::return_type write(const rclcpp::Time& time, const rclcpp::Duration& period) override; + +private: + /** + * @brief Represents data received from trick + */ + std::vector trick_state_variables_; + /** + * @brief Represents data to be sent to trick + */ + std::vector trick_command_variables_; + /** + * @brief Thread used for receiving data from trick asynchronously + */ + std::thread incoming_data_thread_; + /** + * @brief Socket encapsulating the connection with trick simulation + */ + Socket trick_conn_socket_; + /** + * @brief Buffer for accessing incoming data in realtime-safe manner + */ + realtime_tools::RealtimeBuffer> trick_data_incoming_buffer_; + + int trick_server_port_; + std::string trick_hostname_; + double trick_variable_cycle_rate_; + + const int MAX_NO_OF_RECONNECTS = 5; + const int RECONNECT_WAIT_TIME_S = 2; + std::vector joints_data_; + + // parameter names used in URDF file for trick-related params + const std::string JOINT_PARAM_STATE_INTERFACE_KEY = "state_interface"; + const std::string JOINT_PARAM_COMMAND_INTERFACE_KEY = "command_interface"; + const std::string JOINT_PARAM_TRICK_VARIABLE_NAME_KEY = "trick_variable_name"; +}; + +} // namespace trick_ros2_control + +#endif // TRICK_ROS2_CONTROL__TRICK_SYSTEM_HPP_ diff --git a/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/utils.hpp b/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/utils.hpp new file mode 100644 index 00000000..c6a73e26 --- /dev/null +++ b/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/utils.hpp @@ -0,0 +1,52 @@ +// Copyright 2024 Blazej Fiderek (xfiderek) +// +// 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 +// +// https://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include + +double trick_string_convert(const std::string& str) +{ + std::istringstream ss(str); + double num; + ss >> num; + return num; +} + +std::vector trick_split_response(std::string& str, const char delim) +{ + std::stringstream ss(str); + std::string s; + std::vector ret; + while (ss >> s) + { + ret.push_back(s); + } + return ret; +} + +std::vector trick_response_convert(std::string& response) +{ + auto responseSplit = trick_split_response(response, '\t'); + std::vector result; + if (responseSplit[0] != "0") + { + return result; + } + for (int i = 1; i < responseSplit.size(); i++) + { + result.push_back(trick_string_convert(responseSplit[i])); + } + return result; +} diff --git a/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/visibility_control.h b/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/visibility_control.h new file mode 100644 index 00000000..1996b0e1 --- /dev/null +++ b/ros_trick/ros_src/trick_ros2_control/include/trick_ros2_control/visibility_control.h @@ -0,0 +1,56 @@ +// Copyright 2024 Blazej Fiderek (xfiderek) +// +// 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 +// +// https://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + + +#ifndef TRICK_ROS2_CONTROL__VISIBILITY_CONTROL_H_ +#define TRICK_ROS2_CONTROL__VISIBILITY_CONTROL_H_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ +#ifdef __GNUC__ +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_EXPORT __attribute__((dllexport)) +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_IMPORT __attribute__((dllimport)) +#else +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_EXPORT __declspec(dllexport) +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_IMPORT __declspec(dllimport) +#endif +#ifdef TEMPLATES__ROS2_CONTROL__VISIBILITY_BUILDING_DLL +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC \ + TEMPLATES__ROS2_CONTROL__VISIBILITY_EXPORT +#else +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC \ + TEMPLATES__ROS2_CONTROL__VISIBILITY_IMPORT +#endif +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC_TYPE \ + TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_LOCAL +#else +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_EXPORT \ + __attribute__((visibility("default"))) +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_IMPORT +#if __GNUC__ >= 4 +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC \ + __attribute__((visibility("default"))) +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_LOCAL \ + __attribute__((visibility("hidden"))) +#else +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_LOCAL +#endif +#define TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC_TYPE +#endif + +#endif // TRICK_ROS2_CONTROL__VISIBILITY_CONTROL_H_ diff --git a/ros_trick/ros_src/trick_ros2_control/package.xml b/ros_trick/ros_src/trick_ros2_control/package.xml new file mode 100644 index 00000000..ca76e06d --- /dev/null +++ b/ros_trick/ros_src/trick_ros2_control/package.xml @@ -0,0 +1,29 @@ + + + + trick_ros2_control + 0.0.0 + TODO: Package description + blazej + TODO: License declaration + + ament_cmake + + hardware_interface + + pluginlib + + rclcpp + + rclcpp_lifecycle + realtime_tools + + ament_lint_auto + ament_lint_common + ament_cmake_gmock + ros2_control_test_assets + + + ament_cmake + + diff --git a/ros_trick/ros_src/trick_ros2_control/src/socket.cpp b/ros_trick/ros_src/trick_ros2_control/src/socket.cpp new file mode 100644 index 00000000..09ecde6c --- /dev/null +++ b/ros_trick/ros_src/trick_ros2_control/src/socket.cpp @@ -0,0 +1,109 @@ +// Copyright 2024 Blazej Fiderek (xfiderek) +// +// 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 +// +// https://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. + +// Largely inspired by +// https://github.com/nasa/trick/blob/master/trick_sims/SIM_billiards/models/graphics/cpp/Socket.cpp + +#include "trick_ros2_control/socket.hpp" + +Socket::Socket() : _initialized(false) +{ +} + +int Socket::init(std::string hostname, int port) +{ + _hostname = hostname; + _port = port; + _socket_fd = socket(AF_INET, SOCK_STREAM, 0); + if (_socket_fd < 0) + { + std::cout << "Socket connection failed" << std::endl; + return -1; + } + + struct sockaddr_in serv_addr; + serv_addr.sin_family = AF_INET; + serv_addr.sin_port = htons(port); // convert to weird network byte format + + if (inet_pton(AF_INET, "127.0.0.1", &serv_addr.sin_addr) <= 0) + { + std::cout << "Invalid address/ Address not supported" << std::endl; + return -1; + } + + if (connect(_socket_fd, (struct sockaddr*)&serv_addr, sizeof(serv_addr)) < 0) + { + std::cout << "Connection failed" << std::endl; + return -1; + } + + _initialized = true; + return 0; +} + +int Socket::send(std::string message) +{ + // weird syntax I've never used before - since the send syscall that i'm + // trying to use is overloaded in this class, I have to append :: to the front + // of it so that the compiler knows to look in the global namespace + int success = ::send(_socket_fd, message.c_str(), message.size(), 0); + if (success < static_cast(message.size())) + { + std::cout << "Failed to send message" << std::endl; + } + return success; +} + +int Socket::operator<<(std::string message) +{ + return send(message); +} + +std::string Socket::receive() +{ + char buffer[SOCKET_BUF_SIZE]; + int numBytes = read(_socket_fd, buffer, SOCKET_BUF_SIZE); + if (numBytes < 0) + { + throw std::runtime_error("Failed to read from socket\n"); + } + else if (numBytes < SOCKET_BUF_SIZE) + { + buffer[numBytes] = '\0'; + } + + std::string string_buffer = std::string(carry_on_buffer_) + std::string(buffer); + int last_newline_idx = string_buffer.rfind(trick_delimiter_, string_buffer.size() - 1); + int second_last_newline_idx = string_buffer.rfind(trick_delimiter_, string_buffer.size() - 2); + + // it means that we can clear carry on buffer + if (last_newline_idx == string_buffer.size() - 1) + { + carry_on_buffer_[0] = '\0'; + } + // in this case we need to store the remaining characters in the carry on + // buffer + else + { + std::strcpy(carry_on_buffer_, string_buffer.substr(last_newline_idx + 1).c_str()); + } + + // Always return the latest message + return string_buffer.substr(second_last_newline_idx + 1, last_newline_idx - second_last_newline_idx - 1); +} + +void Socket::operator>>(std::string& ret) +{ + ret = receive(); +} diff --git a/ros_trick/ros_src/trick_ros2_control/src/trick_system.cpp b/ros_trick/ros_src/trick_ros2_control/src/trick_system.cpp new file mode 100644 index 00000000..2c603e9d --- /dev/null +++ b/ros_trick/ros_src/trick_ros2_control/src/trick_system.cpp @@ -0,0 +1,268 @@ +// Copyright (c) 2024, Blazej Fiderek (xfiderek), Stogl Robotics Consulting UG +// (haftungsbeschränkt) (template) +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "trick_ros2_control/trick_system.hpp" + +namespace trick_ros2_control +{ + +hardware_interface::CallbackReturn TrickSystem::on_init(const hardware_interface::HardwareInfo& info) +{ + if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS) + { + return CallbackReturn::ERROR; + } + + if (info_.hardware_parameters.find("trick_variable_server_host") == info_.hardware_parameters.end()) + { + RCLCPP_FATAL(rclcpp::get_logger("TrickSystem"), + "trick_variable_server_host param is not defined. Define in " + "it 'ros2_control/hardware' block in your " + "robot's URDF"); + return hardware_interface::CallbackReturn::ERROR; + } + if (info_.hardware_parameters.find("trick_variable_server_port") == info_.hardware_parameters.end()) + { + RCLCPP_FATAL(rclcpp::get_logger("TrickSystem"), + "trick_variable_server_port param is not defined.\n Define in " + "it 'ros2_control/hardware' block in " + "your robot's URDF"); + return hardware_interface::CallbackReturn::ERROR; + } + if (info_.hardware_parameters.find("trick_variable_cycle_rate") == info_.hardware_parameters.end()) + { + RCLCPP_FATAL(rclcpp::get_logger("TrickSystem"), + "trick_variable_cycle_rate param is not defined.\n Define in " + "it 'ros2_control/hardware' block in your " + "robot's URDF"); + return hardware_interface::CallbackReturn::ERROR; + } + trick_hostname_ = info_.hardware_parameters["trick_variable_server_host"]; + trick_server_port_ = std::stoi(info_.hardware_parameters["trick_variable_server_port"]); + trick_variable_cycle_rate_ = std::stod(info_.hardware_parameters["trick_variable_cycle_rate"]); + size_t n_joints = info_.joints.size(); + joints_data_.resize(n_joints); + if (n_joints > 0) + { + trick_data_incoming_buffer_.writeFromNonRT(std::vector(n_joints * info.joints[0].state_interfaces.size(), + std::numeric_limits::quiet_NaN())); + } + + return CallbackReturn::SUCCESS; +} + +hardware_interface::CallbackReturn TrickSystem::on_configure(const rclcpp_lifecycle::State& /*previous_state*/) +{ + bool trick_conn_successful = false; + for (int i = 0; i < MAX_NO_OF_RECONNECTS && rclcpp::ok(); ++i) + { + trick_conn_successful = trick_conn_socket_.init(trick_hostname_, trick_server_port_) >= 0; + if (trick_conn_successful) + { + RCLCPP_INFO(rclcpp::get_logger("TrickSystem"), "Connected to trick server successfully"); + break; + } + RCLCPP_INFO(rclcpp::get_logger("TrickSystem"), "Could not connect to trick, retrying %d/%d", i + 1, + MAX_NO_OF_RECONNECTS); + std::this_thread::sleep_for(std::chrono::seconds(RECONNECT_WAIT_TIME_S)); + } + if (!trick_conn_successful) + { + std::string err = "could not connect to Trick server on host: " + trick_hostname_ + + " and port: " + std::to_string(trick_server_port_); + RCLCPP_FATAL(rclcpp::get_logger("TrickSystem"), err.c_str()); + return hardware_interface::CallbackReturn::ERROR; + } + + trick_conn_socket_ << "trick.var_pause()\n"; + trick_conn_socket_ << "trick.var_ascii()\n"; + trick_conn_socket_ << "trick.var_set_client_tag(\"ros2_control_" + info_.name + "\") \n"; + trick_conn_socket_ << "trick.var_cycle(\"" + std::to_string(1.0 / trick_variable_cycle_rate_) + "\")\n"; + + for (const TrickData& trick_state_variable : trick_state_variables_) + { + const std::string& trick_var_name = trick_state_variable.trick_var_name; + std::string request_ = "trick.var_add(\"" + trick_var_name + "\")\n"; + RCLCPP_INFO(rclcpp::get_logger("TrickSystem"), "adding trick variable with command: %s", request_.c_str()); + trick_conn_socket_ << request_; + } + + incoming_data_thread_ = std::thread([this]() { + while (rclcpp::ok()) + { + if (this->get_state().label() == "active") + { + std::string incoming_msg; + this->trick_conn_socket_ >> incoming_msg; + std::vector trick_data = trick_response_convert(incoming_msg); + this->trick_data_incoming_buffer_.writeFromNonRT(trick_data); + } + else + { + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + } + }); + + return hardware_interface::CallbackReturn::SUCCESS; +} + +std::vector TrickSystem::export_state_interfaces() +{ + std::vector state_interfaces; + for (unsigned int i = 0; i < info_.joints.size(); i++) + { + auto& joint_info = info_.joints[i]; + for (unsigned int j = 0; j < joint_info.state_interfaces.size(); ++j) + { + double* state_variable_ptr_; + std::string joint_interface_name = joint_info.state_interfaces[j].name; + if (joint_interface_name == hardware_interface::HW_IF_POSITION) + { + state_variable_ptr_ = &joints_data_[i].joint_position; + } + if (joint_interface_name == hardware_interface::HW_IF_VELOCITY) + { + state_variable_ptr_ = &joints_data_[i].joint_velocity; + } + if (joint_interface_name == hardware_interface::HW_IF_ACCELERATION) + { + state_variable_ptr_ = &joints_data_[i].joint_acceleration; + } + if (joint_interface_name == hardware_interface::HW_IF_EFFORT) + { + state_variable_ptr_ = &joints_data_[i].joint_effort; + } + state_interfaces.emplace_back( + hardware_interface::StateInterface(joint_info.name, joint_interface_name, state_variable_ptr_)); + std::string trick_variable_name_param_key = + JOINT_PARAM_STATE_INTERFACE_KEY + "/" + joint_interface_name + "/" + JOINT_PARAM_TRICK_VARIABLE_NAME_KEY; + + if (joint_info.parameters.find(trick_variable_name_param_key) == joint_info.parameters.end()) + { + throw std::runtime_error("Missing parameter: " + trick_variable_name_param_key + + ". Add it to joint parameters in ros2_control block, so that trick " + "variable can be " + "binded to " + "ros2_control variable"); + } + std::string trick_variable_name = joint_info.parameters[trick_variable_name_param_key]; + trick_state_variables_.emplace_back(TrickData(trick_variable_name, state_variable_ptr_)); + } + } + return state_interfaces; +} + +std::vector TrickSystem::export_command_interfaces() +{ + std::vector command_interfaces; + for (unsigned int i = 0; i < info_.joints.size(); i++) + { + auto& joint_info = info_.joints[i]; + for (unsigned int j = 0; j < joint_info.command_interfaces.size(); ++j) + { + double* command_variable_ptr_; + std::string joint_interface_name = joint_info.command_interfaces[j].name; + if (joint_interface_name == hardware_interface::HW_IF_POSITION) + { + command_variable_ptr_ = &joints_data_[i].joint_position; + } + if (joint_interface_name == hardware_interface::HW_IF_VELOCITY) + { + command_variable_ptr_ = &joints_data_[i].joint_velocity; + } + if (joint_interface_name == hardware_interface::HW_IF_ACCELERATION) + { + command_variable_ptr_ = &joints_data_[i].joint_acceleration; + } + if (joint_interface_name == hardware_interface::HW_IF_EFFORT) + { + command_variable_ptr_ = &joints_data_[i].joint_effort; + } + // TODO(later) - parametrize it with joint params + *command_variable_ptr_ = 0.0; + command_interfaces.emplace_back( + hardware_interface::CommandInterface(joint_info.name, joint_interface_name, command_variable_ptr_)); + std::string trick_variable_name_param_key = + JOINT_PARAM_COMMAND_INTERFACE_KEY + "/" + joint_interface_name + "/" + JOINT_PARAM_TRICK_VARIABLE_NAME_KEY; + + if (joint_info.parameters.find(trick_variable_name_param_key) == joint_info.parameters.end()) + { + throw std::runtime_error("Missing parameter: " + trick_variable_name_param_key + + ". Add it to joint parameters in ros2_control block, so that trick " + "variable can be " + "binded to " + "ros2_control variable"); + } + std::string trick_variable_name = joint_info.parameters[trick_variable_name_param_key]; + trick_command_variables_.emplace_back(TrickData(trick_variable_name, command_variable_ptr_)); + } + } + + return command_interfaces; +} + +hardware_interface::CallbackReturn TrickSystem::on_activate(const rclcpp_lifecycle::State& /*previous_state*/) +{ + trick_conn_socket_ << "trick.var_unpause()\n"; + // receive first message to ensure connection works + trick_conn_socket_.receive(); + return CallbackReturn::SUCCESS; +} + +hardware_interface::CallbackReturn TrickSystem::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/) +{ + trick_conn_socket_ << "trick.var_pause()\n"; + return CallbackReturn::SUCCESS; +} + +hardware_interface::return_type TrickSystem::read(const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) +{ + const std::vector& raw_doubles_from_trick = *trick_data_incoming_buffer_.readFromRT(); + if (raw_doubles_from_trick.size() != trick_state_variables_.size()) + { + RCLCPP_FATAL(rclcpp::get_logger("TrickSystem"), + "size of data received from trick does not match number of " + "declared state variables. Expected: %d. " + "Got: %d", + trick_state_variables_.size(), raw_doubles_from_trick.size()); + return hardware_interface::return_type::OK; + } + for (int i = 0; i < raw_doubles_from_trick.size(); ++i) + { + double value_from_trick = raw_doubles_from_trick[i]; + double* const target_state_variable_ptr_ = trick_state_variables_[i].data_ptr; + *target_state_variable_ptr_ = value_from_trick; + } + + return hardware_interface::return_type::OK; +} + +hardware_interface::return_type TrickSystem::write(const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) +{ + std::string command = ""; + for (const TrickData& trick_command_variable : trick_command_variables_) + { + command += trick_command_variable.trick_var_name + " = " + std::to_string(*trick_command_variable.data_ptr) + "\n"; + } + trick_conn_socket_ << command; + return hardware_interface::return_type::OK; +} + +} // namespace trick_ros2_control + +#include "pluginlib/class_list_macros.hpp" + +PLUGINLIB_EXPORT_CLASS(trick_ros2_control::TrickSystem, hardware_interface::SystemInterface) diff --git a/ros_trick/ros_src/trick_ros2_control/trick_ros2_control.xml b/ros_trick/ros_src/trick_ros2_control/trick_ros2_control.xml new file mode 100644 index 00000000..b87eb63d --- /dev/null +++ b/ros_trick/ros_src/trick_ros2_control/trick_ros2_control.xml @@ -0,0 +1,9 @@ + + + + ros2_control hardware interface. + + + diff --git a/ros_trick/ros_trick_bridge.Dockerfile b/ros_trick/ros_trick_bridge.Dockerfile new file mode 100644 index 00000000..a8ce66ec --- /dev/null +++ b/ros_trick/ros_trick_bridge.Dockerfile @@ -0,0 +1,112 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. + +# Tested with humble-2024.07.0 release +FROM osrf/space-ros:latest + +# ------------------------------------------------------------------------------ +# Get Install trick dependencies +# ------------------------------------------------------------------------------ +RUN --mount=type=cache,target=/var/cache/apt,sharing=locked \ + --mount=type=cache,target=/var/lib/apt,sharing=locked \ + sudo apt-get update && sudo apt-get install -y \ + bison \ + clang \ + flex \ + git \ + llvm \ + make \ + maven \ + swig \ + cmake \ + curl \ + g++ \ + libx11-dev \ + libxml2-dev \ + libxt-dev \ + libmotif-common \ + libmotif-dev \ + python3-dev \ + zlib1g-dev \ + llvm-dev \ + libclang-dev \ + libudunits2-dev \ + libgtest-dev \ + openjdk-11-jdk \ + zip + +ENV PYTHON_VERSION=3 + +# ------------------------------------------------------------------------------ +# Get Trick version 19.7.2 from GitHub, configure and build it. +# ------------------------------------------------------------------------------ +WORKDIR /opt/trick +RUN git clone --branch 19.7.2 --depth 1 https://github.com/nasa/trick.git . +# cd into the directory we just created and .. +# configure and make Trick. +RUN ./configure && make + +# ------------------------------------------------------------------------------ +# Add ${TRICK_HOME}/bin to the PATH variable. +# ------------------------------------------------------------------------------ +ENV TRICK_HOME="/opt/trick" +RUN echo "export PATH=${PATH}:${TRICK_HOME}/bin" >> ~/.bashrc + + +# ------------------------------------------------------------------------------ +# Build SPACEROS workspace with ros trick bridge +# ------------------------------------------------------------------------------ +WORKDIR /opt/ros_trick_bridge_ws +ENV ROS_TRICK_BRIDGE_WS="/opt/ros_trick_bridge_ws/" +COPY --chown=spaceros-user:spaceros-user ros_src/ros_trick_bridge src/ +RUN /bin/bash -c 'source ${SPACEROS_DIR}/install/setup.bash \ + && colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release -DCMAKE_EXPORT_COMPILE_COMMANDS=ON --event-handlers desktop_notification- status-' +RUN rm -rf build log src + +# ------------------------------------------------------------------------------ +# ------------------------------------------------------------------------------ +# Parts below are only required for the canadarm demo. You can replace them as you see fit. +# ------------------------------------------------------------------------------ +# ------------------------------------------------------------------------------ + +# ------------------------------------------------------------------------------ +# Install RBDL, which is used for calculating forward dynamics in trick +# ------------------------------------------------------------------------------ +WORKDIR /opt/rbdl +RUN git clone --branch v3.3.0 --depth 1 https://github.com/rbdl/rbdl.git . \ + && git submodule update --init --remote --depth 1 addons/urdfreader/ +RUN mkdir ./rbdl-build \ + && cd rbdl-build/ \ + && cmake \ + -DCMAKE_BUILD_TYPE=Release \ + -DRBDL_BUILD_ADDON_URDFREADER="ON" \ + .. \ + && make \ + && sudo make install \ + && cd .. \ + && rm -r ./rbdl-build +# make it easy to link the rbdl library. +# LD_LIBRARY_PATH is empty at this stage of dockerbuild +ENV LD_LIBRARY_PATH="/usr/local/lib" + +# ------------------------------------------------------------------------------ +# copy the created canadarm trick simulation and compile it +# ------------------------------------------------------------------------------ +WORKDIR /opt/trick_sims/SIM_trick_canadarm +COPY --chown=spaceros-user:spaceros-user trick_src/SIM_trick_canadarm/ . +RUN ${TRICK_HOME}/bin/trick-CP +# include canadarm URDF for RBDL +COPY --chown=spaceros-user:spaceros-user ros_src/trick_canadarm_moveit_config/config/SSRMS_Canadarm2.urdf.xacro . + +WORKDIR ${ROS_TRICK_BRIDGE_WS} diff --git a/ros_trick/run.sh b/ros_trick/run.sh new file mode 100755 index 00000000..cec12614 --- /dev/null +++ b/ros_trick/run.sh @@ -0,0 +1,18 @@ +#!/bin/bash +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. + + +set -e +docker compose up --build diff --git a/ros_trick/trick_src/SIM_trick_canadarm/RUN_2DPlanar/input.py b/ros_trick/trick_src/SIM_trick_canadarm/RUN_2DPlanar/input.py new file mode 100644 index 00000000..9af246aa --- /dev/null +++ b/ros_trick/trick_src/SIM_trick_canadarm/RUN_2DPlanar/input.py @@ -0,0 +1,31 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. + + +trick.real_time_enable() +trick.exec_set_software_frame(0.02) + +trick.exec_set_enable_freeze(True) +trick.exec_set_freeze_command(True) + + +trick.var_set_copy_mode(2) +trick.var_server_set_port(49765) +trick_message.mtcout.init() +trick.message_subscribe(trick_message.mtcout) +trick_message.separate_thread_set_enabled(True) +simControlPanel = trick.SimControlPanel() +trick.add_external_application(simControlPanel) +trick_view = trick.TrickView() +trick.add_external_application(trick_view) diff --git a/ros_trick/trick_src/SIM_trick_canadarm/S_define b/ros_trick/trick_src/SIM_trick_canadarm/S_define new file mode 100644 index 00000000..aa74ebd5 --- /dev/null +++ b/ros_trick/trick_src/SIM_trick_canadarm/S_define @@ -0,0 +1,49 @@ +// Copyright 2024 Blazej Fiderek (xfiderek) +// +// 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 +// +// https://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. + +/************************TRICK HEADER************************* +PURPOSE: + ( Simulate dynamics of SSRMS ) +LIBRARY DEPENDENCIES: + ( + (manipulator/manipulator.cc) + ) +*************************************************************/ +#include "sim_objects/default_trick_sys.sm" + +##include "include/trick/exec_proto.h" +##include "manipulator/manipulator.hh" + +class ManipulatorSimObject : public Trick::SimObject +{ + + public: + Manip manip; + + ManipulatorSimObject(): manip() + { + ("default_data") manip.defaultData(); + ("derivative") manip.stateDeriv(); + ("integration") trick_ret = manip.stateInteg(); + } + +}; + +ManipulatorSimObject CanadarmManip; + +IntegLoop armIntegLoop(0.01) CanadarmManip; + +void create_connections() { + armIntegLoop.getIntegrator(Runge_Kutta_4, 2*CanadarmManip.manip.NDOF); +} diff --git a/ros_trick/trick_src/SIM_trick_canadarm/S_overrides.mk b/ros_trick/trick_src/SIM_trick_canadarm/S_overrides.mk new file mode 100644 index 00000000..7d855259 --- /dev/null +++ b/ros_trick/trick_src/SIM_trick_canadarm/S_overrides.mk @@ -0,0 +1,18 @@ +# Copyright 2024 Blazej Fiderek (xfiderek) +# +# 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 +# +# https://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. + +TRICK_CFLAGS += -I./models -I${TRICK_HOME} -I/usr/include/eigen3 -g -O0 -Wall -Wextra -Wshadow +TRICK_CXXFLAGS += -I./models -I${TRICK_HOME} -I/usr/include/eigen3 -g -O0 -Wall -Wextra -Wshadow +TRICK_USER_LINK_LIBS += -lrbdl -lrbdl_urdfreader + diff --git a/ros_trick/trick_src/SIM_trick_canadarm/models/manipulator/manipulator.cc b/ros_trick/trick_src/SIM_trick_canadarm/models/manipulator/manipulator.cc new file mode 100644 index 00000000..3adbb88d --- /dev/null +++ b/ros_trick/trick_src/SIM_trick_canadarm/models/manipulator/manipulator.cc @@ -0,0 +1,112 @@ +// Copyright 2024 Blazej Fiderek (xfiderek) +// +// 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 +// +// https://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 "manipulator/manipulator.hh" +#include "trick/integrator_c_intf.h" + +Manip::Manip() : rbdl_model() +{ + RigidBodyDynamics::Addons::URDFReadFromFile("./SSRMS_Canadarm2.urdf.xacro", &rbdl_model, false); + std::cout << "Loaded URDF model into trick"; + std::cout << RigidBodyDynamics::Utils::GetModelDOFOverview(rbdl_model); + + rbdl_model.gravity = RigidBodyDynamics::Math::Vector3d::Zero(); + + q_vec_ = RigidBodyDynamics::Math::VectorNd::Zero(rbdl_model.q_size); + q_dotvec_ = RigidBodyDynamics::Math::VectorNd::Zero(rbdl_model.q_size); + q_ddotvec_ = RigidBodyDynamics::Math::VectorNd::Zero(rbdl_model.q_size); + torque_vec_ = RigidBodyDynamics::Math::VectorNd::Zero(rbdl_model.q_size); + + std::cout << "starting Trick Canadarm simulation" << std::endl; +} + +int Manip::defaultData() +{ + for (size_t i = 0; i < NDOF; ++i) + { + q[i] = 0.0; + q_dot[i] = 0.0; + q_dotdot[i] = 0.0; + input_torque[i] = 0.0; + applied_torque[i] = 0.0; + friction_torque[i] = 0.0; + q_vec_[i] = 0.0; + q_dotvec_[i] = 0.0; + q_ddotvec_[i] = 0.0; + torque_vec_[i] = 0.0; + breakaway_friction_torque[i] = 2.5; + coloumb_friction_torque[i] = 2.0; + breakaway_friction_velocity[i] = 0.005; + coulomb_velocity_threshold[i] = breakaway_friction_velocity[i] / 10; + stribeck_velocity_threshold[i] = M_SQRT2 * breakaway_friction_torque[i]; + viscous_friction_coefficient[i] = 0.001; + } + + return (0); +} + +int Manip::forwardDynamics() +{ + // calculate torques and store as RBDL vector as well + for (size_t i = 0; i < NDOF; ++i) + { + // https://www.mathworks.com/help/simscape/ref/rotationalfriction.html + double curr_to_stribeck_vel = q_dot[i] / stribeck_velocity_threshold[i]; + double curr_to_coulomb_vel = q_dot[i] / coulomb_velocity_threshold[i]; + friction_torque[i] = M_SQRT2 * M_E * (breakaway_friction_torque[i] - coloumb_friction_torque[i]) * + std::exp(-std::pow(curr_to_stribeck_vel, 2)) * curr_to_stribeck_vel; + friction_torque[i] += coloumb_friction_torque[i] * std::tanh(curr_to_coulomb_vel); + friction_torque[i] += viscous_friction_coefficient[i] * q_dot[i]; + + applied_torque[i] = input_torque[i] - friction_torque[i]; + + // copy positions and velocities from C-arrays to RBDL vectors + torque_vec_[i] = applied_torque[i]; + q_vec_[i] = q[i]; + q_dotvec_[i] = q_dot[i]; + q_ddotvec_[i] = 0.0; + } + // calculate dynamics (q_dotdot) with RBDL + RigidBodyDynamics::ForwardDynamics(rbdl_model, q_vec_, q_dotvec_, torque_vec_, q_ddotvec_); + + // copy Q_dotdot from RBDL vector type to simple C-arrays + for (size_t i = 0; i < NDOF; ++i) + { + q_dotdot[i] = q_ddotvec_[i]; + } + + return (0); +} + +int Manip::stateDeriv() +{ + int status_code = forwardDynamics(); + return (status_code); +} + +int Manip::stateInteg() +{ + int integration_step; + load_state(&q[0], &q[1], &q[2], &q[3], &q[4], &q[5], &q[6], &q_dot[0], &q_dot[1], &q_dot[2], &q_dot[3], &q_dot[4], + &q_dot[5], &q_dot[6], NULL); + load_deriv(&q_dot[0], &q_dot[1], &q_dot[2], &q_dot[3], &q_dot[4], &q_dot[5], &q_dot[6], &q_dotdot[0], &q_dotdot[1], + &q_dotdot[2], &q_dotdot[3], &q_dotdot[4], &q_dotdot[5], &q_dotdot[6], NULL); + // integrate + integration_step = integrate(); + + unload_state(&q[0], &q[1], &q[2], &q[3], &q[4], &q[5], &q[6], &q_dot[0], &q_dot[1], &q_dot[2], &q_dot[3], &q_dot[4], + &q_dot[5], &q_dot[6], NULL); + + return (integration_step); +} \ No newline at end of file diff --git a/ros_trick/trick_src/SIM_trick_canadarm/models/manipulator/manipulator.hh b/ros_trick/trick_src/SIM_trick_canadarm/models/manipulator/manipulator.hh new file mode 100644 index 00000000..8f283636 --- /dev/null +++ b/ros_trick/trick_src/SIM_trick_canadarm/models/manipulator/manipulator.hh @@ -0,0 +1,97 @@ +// Copyright 2024 Blazej Fiderek (xfiderek) +// +// 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 +// +// https://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + + +#ifndef __MANIPULATOR_HH_ +#define __MANIPULATOR_HH_ +/************************************************************************** +PURPOSE: (2D Manipulator class definitions including kinematics and control) +***************************************************************************/ +#define TRICK_NO_MONTE_CARLO +#define TRICK_NO_MASTERSLAVE +#define TRICK_NO_INSTRUMENTATION + +#include +#include +#include +#include +#include +#include + +class Manip +{ +public: + Manip(); + + /** + * @brief Calculate Q_dotdot (joint accelerations) given current state and input torques + * The dynamics is calculated using Articulated Body Algorithm (ABA) with RBDL library + * Friction is modelled with Stribeck model taken from Mathworks docs + * https://www.mathworks.com/help/simscape/ref/rotationalfriction.html + * @return int status code + */ + int forwardDynamics(); + + /** + * @brief Calculate state derivative. Calls forwardDynamics(). + * + * @return int status code + */ + int stateDeriv(); + /** + * @brief Propagate state for the current timestamp by integration. Called after stateDeriv() + * + * @return int status code + */ + int stateInteg(); + + /** + * @brief Initializes all data structures. Called on startup. + * + * @return int status code + */ + int defaultData(); + + /** + * @brief Model encapsulating kinematics and dynamics of Canadarm with RBDL library + * + */ + RigidBodyDynamics::Model rbdl_model; /* ** -- class from RBDL that calculates forward dynamics */ + static const size_t NDOF = 7; /* ** -- ndof */ + + double input_torque[NDOF] = { 0.0 }; /* *i (N.m) input (commanded) torque for each joint */ + + double q[NDOF] = { 0.0 }; /* *o rad angle of joints */ + double q_dot[NDOF] = { 0.0 }; /* *o (rad/s) velocity of joints */ + double q_dotdot[NDOF] = { 0.0 }; /* *o (rad/s^2) accelerations of joints */ + double friction_torque[NDOF] = { 0.0 }; /* *o (N.m) Torque comming from friction */ + double applied_torque[NDOF] = { 0.0 }; /* *o (N.m) final torque applied for each joint */ + + // Friction-related parameters. For now we assume same params for every joint + // The friction is modelled using Stribeck function + // https://www.mathworks.com/help/simscape/ref/rotationalfriction.html + double breakaway_friction_torque[NDOF]; /* *i (N.m) */ + double coloumb_friction_torque[NDOF]; /* *i (N.m) */ + double breakaway_friction_velocity[NDOF]; /* *i (rad/s) */ + double coulomb_velocity_threshold[NDOF]; /* *i (rad.s) */ + double stribeck_velocity_threshold[NDOF]; /* *i (N.m/rad.s) */ + double viscous_friction_coefficient[NDOF]; /* *i (N.m/rad.s) */ + +private: + RigidBodyDynamics::Math::VectorNd q_vec_; + RigidBodyDynamics::Math::VectorNd q_dotvec_; + RigidBodyDynamics::Math::VectorNd q_ddotvec_; + RigidBodyDynamics::Math::VectorNd torque_vec_; +}; +#endif