From 1f9700b7795a5b300145755eb2df7b34d94d43e3 Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Wed, 25 Mar 2020 19:39:42 +0100 Subject: [PATCH 1/3] Create jenkins-pipeline --- jenkins-pipeline | 2 ++ 1 file changed, 2 insertions(+) create mode 100644 jenkins-pipeline diff --git a/jenkins-pipeline b/jenkins-pipeline new file mode 100644 index 000000000..59d9ff9be --- /dev/null +++ b/jenkins-pipeline @@ -0,0 +1,2 @@ +library 'continuous_integration_pipeline' +ciPipeline("") From a573e11355d152e5f5b37f5bfcac844a87a48f47 Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Wed, 25 Mar 2020 19:39:42 +0100 Subject: [PATCH 2/3] Create jenkins-pipeline --- jenkins-pipeline | 2 ++ 1 file changed, 2 insertions(+) create mode 100644 jenkins-pipeline diff --git a/jenkins-pipeline b/jenkins-pipeline new file mode 100644 index 000000000..59d9ff9be --- /dev/null +++ b/jenkins-pipeline @@ -0,0 +1,2 @@ +library 'continuous_integration_pipeline' +ciPipeline("") From 928e216acdda2696c5994e49bd81085880ab5834 Mon Sep 17 00:00:00 2001 From: Idate96 Date: Wed, 22 Feb 2023 16:50:55 +0100 Subject: [PATCH 3/3] updated pcl and sdf packages --- grid_map_pcl/CHANGELOG.rst | 3 + grid_map_pcl/CMakeLists.txt | 29 +- grid_map_pcl/README.md | 28 +- grid_map_pcl/config/parameters.yaml | 5 +- .../include/grid_map_pcl/GridMapPclLoader.hpp | 6 + .../grid_map_pcl/PclLoaderParameters.hpp | 5 +- grid_map_pcl/include/grid_map_pcl/helpers.hpp | 2 +- .../launch/grid_map_pcl_loader_node.launch | 36 +- grid_map_pcl/package.xml | 7 +- grid_map_pcl/rviz/grid_map_vis.rviz | 162 +++++++++ grid_map_pcl/src/GridMapPclLoader.cpp | 13 +- grid_map_pcl/src/PclLoaderParameters.cpp | 54 +-- grid_map_pcl/src/grid_map_pcl_loader_node.cpp | 3 +- grid_map_pcl/src/helpers.cpp | 26 +- .../src/pointcloud_publisher_node.cpp | 42 +++ grid_map_pcl/test/GridMapPclLoaderTest.cpp | 2 +- grid_map_pcl/test/test_data/parameters.yaml | 1 + grid_map_pcl/test/test_helpers.cpp | 8 +- grid_map_sdf/CHANGELOG.rst | 5 + grid_map_sdf/CMakeLists.txt | 10 +- grid_map_sdf/doc/anymal_sdf_demo.gif | Bin 0 -> 843793 bytes .../grid_map_sdf/DistanceDerivatives.hpp | 62 ++++ .../include/grid_map_sdf/Gridmap3dLookup.hpp | 105 ++++++ .../grid_map_sdf/PixelBorderDistance.hpp | 104 ++++++ .../include/grid_map_sdf/SignedDistance2d.hpp | 59 +++ .../grid_map_sdf/SignedDistanceField.hpp | 152 ++++++-- grid_map_sdf/include/grid_map_sdf/Utils.hpp | 21 ++ .../grid_map_sdf/distance_transform/COPYING | 339 ------------------ .../grid_map_sdf/distance_transform/dt.h | 117 ------ .../grid_map_sdf/distance_transform/image.h | 101 ------ .../grid_map_sdf/distance_transform/imconv.h | 179 --------- .../grid_map_sdf/distance_transform/imutil.h | 67 ---- .../grid_map_sdf/distance_transform/misc.h | 62 ---- .../grid_map_sdf/distance_transform/pnmfile.h | 214 ----------- grid_map_sdf/package.xml | 3 +- grid_map_sdf/src/SignedDistance2d.cpp | 290 +++++++++++++++ grid_map_sdf/src/SignedDistanceField.cpp | 312 ++++++++-------- grid_map_sdf/test/SignedDistanceFieldTest.cpp | 305 ---------------- .../test/include/naiveSignedDistance.hpp | 116 ++++++ grid_map_sdf/test/test3dLookup.cpp | 59 +++ grid_map_sdf/test/testDerivatives.cpp | 31 ++ grid_map_sdf/test/testPixelBorderDistance.cpp | 76 ++++ grid_map_sdf/test/testSignedDistance2d.cpp | 112 ++++++ grid_map_sdf/test/testSignedDistance3d.cpp | 193 ++++++++++ 44 files changed, 1888 insertions(+), 1638 deletions(-) create mode 100644 grid_map_pcl/rviz/grid_map_vis.rviz create mode 100644 grid_map_pcl/src/pointcloud_publisher_node.cpp create mode 100644 grid_map_sdf/doc/anymal_sdf_demo.gif create mode 100644 grid_map_sdf/include/grid_map_sdf/DistanceDerivatives.hpp create mode 100644 grid_map_sdf/include/grid_map_sdf/Gridmap3dLookup.hpp create mode 100644 grid_map_sdf/include/grid_map_sdf/PixelBorderDistance.hpp create mode 100644 grid_map_sdf/include/grid_map_sdf/SignedDistance2d.hpp create mode 100644 grid_map_sdf/include/grid_map_sdf/Utils.hpp delete mode 100755 grid_map_sdf/include/grid_map_sdf/distance_transform/COPYING delete mode 100755 grid_map_sdf/include/grid_map_sdf/distance_transform/dt.h delete mode 100755 grid_map_sdf/include/grid_map_sdf/distance_transform/image.h delete mode 100755 grid_map_sdf/include/grid_map_sdf/distance_transform/imconv.h delete mode 100755 grid_map_sdf/include/grid_map_sdf/distance_transform/imutil.h delete mode 100755 grid_map_sdf/include/grid_map_sdf/distance_transform/misc.h delete mode 100755 grid_map_sdf/include/grid_map_sdf/distance_transform/pnmfile.h create mode 100644 grid_map_sdf/src/SignedDistance2d.cpp delete mode 100644 grid_map_sdf/test/SignedDistanceFieldTest.cpp create mode 100644 grid_map_sdf/test/include/naiveSignedDistance.hpp create mode 100644 grid_map_sdf/test/test3dLookup.cpp create mode 100644 grid_map_sdf/test/testDerivatives.cpp create mode 100644 grid_map_sdf/test/testPixelBorderDistance.cpp create mode 100644 grid_map_sdf/test/testSignedDistance2d.cpp create mode 100644 grid_map_sdf/test/testSignedDistance3d.cpp diff --git a/grid_map_pcl/CHANGELOG.rst b/grid_map_pcl/CHANGELOG.rst index 533a43142..ab8d2914b 100644 --- a/grid_map_pcl/CHANGELOG.rst +++ b/grid_map_pcl/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package grid_map_pcl ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.7.0 (2022-03-17) +------------------ + 1.6.4 (2020-12-04) ------------------ diff --git a/grid_map_pcl/CMakeLists.txt b/grid_map_pcl/CMakeLists.txt index a8dc5573d..d82b918e7 100644 --- a/grid_map_pcl/CMakeLists.txt +++ b/grid_map_pcl/CMakeLists.txt @@ -99,7 +99,7 @@ target_link_libraries(${PROJECT_NAME} ) -# Node. +# Nodes. add_executable(grid_map_pcl_loader_node src/grid_map_pcl_loader_node.cpp ) @@ -118,6 +118,24 @@ target_link_libraries(grid_map_pcl_loader_node ${catkin_LIBRARIES} ) +add_executable(pointcloud_publisher_node + src/pointcloud_publisher_node.cpp +) +add_dependencies(pointcloud_publisher_node + ${PROJECT_NAME} +) +target_include_directories(pointcloud_publisher_node PRIVATE + include +) +target_include_directories(pointcloud_publisher_node SYSTEM PUBLIC + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} +) +target_link_libraries(pointcloud_publisher_node + ${PROJECT_NAME} + ${catkin_LIBRARIES} +) + ############# ## Install ## ############# @@ -125,6 +143,7 @@ install( TARGETS ${PROJECT_NAME} grid_map_pcl_loader_node + pointcloud_publisher_node ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} @@ -162,6 +181,14 @@ install( if(CATKIN_ENABLE_TESTING) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pthread") + find_package(catkin REQUIRED + COMPONENTS + ${CATKIN_PACKAGE_DEPENDENCIES} + roslaunch + ) + + roslaunch_add_file_check(launch) + ## Add gtest based cpp test target and link libraries catkin_add_gtest(${PROJECT_NAME}-test test/test_grid_map_pcl.cpp diff --git a/grid_map_pcl/README.md b/grid_map_pcl/README.md index 51c30ed55..8947b5a56 100644 --- a/grid_map_pcl/README.md +++ b/grid_map_pcl/README.md @@ -14,6 +14,19 @@ The elevation is computed by slicing the point cloud in the x-y plane into colum **Authors: Edo Jelavic, Dominic Jud
Affiliation: [ETH Zurich, Robotics Systems Lab](https://rsl.ethz.ch/)
** +## Publications +The code for point cloud to grid map conversion has been developed as a part of research on autonomous precision harvesting. If you are using the point cloud to grid map conversion, please add the following citation to your publication: + +Jelavic, E., Jud, D., Egli, P. and Hutter, M., 2021. Towards Autonomous Robotic Precision Harvesting: Mapping, Localization, Planning and Control for a Legged Tree Harvester. + + @article{jelavic2021towards, + title={Towards Autonomous Robotic Precision Harvesting: Mapping, Localization, Planning and Control for a Legged Tree Harvester}, + author={Jelavic, Edo and Jud, Dominic and Egli, Pascal and Hutter, Marco}, + journal={Field Robotics}, + year={2021}, + publisher={Wiley} + } + ## Examples Examples of elevation maps computed from point clouds using this package: @@ -30,15 +43,15 @@ Examples of elevation maps computed from point clouds using this package: ## Usage -The algorithm will open the .pcd file, convert the point cloud to a grid map and save the grid map as a rosbag into the folder specified by the user. +The algorithm will open the `.pcd` file, convert the point cloud to a grid map and save the grid map as a rosbag into the folder specified by the user. -1. Place .pcd files in the package folder or anywhere on the system (e.g. grid_map_pcl/data/example.pcd). -2. Modify the *folder_path* inside the launch file such that the folder file points to the folder containing .pcd files (e.g. /*"path to the grid_map_pcl folder"*/data). -3. Change the *pcd_filename* to the point cloud file that you want to process -4. You can run the algorithm with: *roslaunch grid_map_pcl grid_map_pcl_loader_node.launch* -5. Once the algorithm is done you will see the output in the console, then you can run rviz in a separate terminal (make sure that you have sourced your workspace, **DO NOT CLOSE** the terminal where *grid_map_pcl_loader_node* is running ) and visualize the resulting grid map. Instructions on how to visualize a grid map are in the grid map [README](../README.md). +1. Place your `.pcd` file in the package folder or anywhere on the system (e.g. `/.../grid_map_pcl/data/example.pcd`). +2. Modify the `pcd_filename` inside the launch file such that it points to the `.pcd` file you would like to process (e.g. `/.../grid_map_pcl/data/example.pcd`). Set the `output_grid_map` variable to point to the location where you wish to save the resulting grid map (e.g. `/.../grid_map_pcl/data/example_grid_map.bag`) +3. Change the `configFilePath_` variable in the launch file to point to the `.yaml` file with configuration parameters (e.g. `/.../grid_map_pcl/config/parameters.yaml`) +4. You can run the algorithm with: `roslaunch grid_map_pcl grid_map_pcl_loader_node.launch` +5. Once the algorithm is done you will see the output in the console, and it should visualize the point cloud and the grid map in rviz. If that does not happen, then you can run rviz in a separate terminal (make sure that you have sourced your workspace, **DO NOT CLOSE** the terminal where `grid_map_pcl_loader_node` is running ) and visualize the resulting grid map. Instructions on how to visualize a grid map are in the grid map [README](../README.md). -The resulting grid map will be saved in the folder given by *folder_path* variable in the launch file and will be named with a string contained inside the *output_grid_map* variable. For large point clouds (100M-140M points) the algorithm takes about 30-60 min to finish (with 6 threads). For sizes that are in the range of 40M to 60M points, the runtime varies between 5 and 15 min, depending on the number of points. Point cloud with around 10M points or less can be processed in a minute or two. +The resulting grid map will be saved in to the location pointed by `output_grid_map` variable in the launch file. For large point clouds (100M-140M points) the algorithm takes about 30-60 min to finish (with 6 threads). For sizes that are in the range of 40M to 60M points, the runtime varies between 5 and 15 min, depending on the number of points. Point cloud with around 10M points or less can be processed in a minute or two. ## Parameters @@ -50,6 +63,7 @@ The resulting grid map will be saved in the folder given by *folder_path* variab ##### Grid map parameters Resulting grid map parameters. * **pcl_grid_map_extraction/grid_map/min_num_points_per_cell** Minimum number of points in the point cloud that have to fall within any of the grid map cells. Otherwise the cell elevation will be set to NaN. +* **pcl_grid_map_extraction/grid_map/max_num_points_per_cell** Maximum number of points in the point cloud that are allowed to fall within any of the grid map cells. If there is more points, the value will be set to NaN. This number can be used to ignore cells with a lot of points which speeds up the processing (but results with some holes in the map). * **pcl_grid_map_extraction/grid_map/resolution** Resolution of the grid map. Width and lengths are computed automatically. ### Point Cloud Pre-processing Parameters diff --git a/grid_map_pcl/config/parameters.yaml b/grid_map_pcl/config/parameters.yaml index ea4854ab9..4db5d418a 100644 --- a/grid_map_pcl/config/parameters.yaml +++ b/grid_map_pcl/config/parameters.yaml @@ -15,17 +15,18 @@ pcl_grid_map_extraction: max_num_points: 1000000 use_max_height_as_cell_elevation: false outlier_removal: - is_remove_outliers: true + is_remove_outliers: false mean_K: 10 stddev_threshold: 1.0 downsampling: - is_downsample_cloud: true + is_downsample_cloud: false voxel_size: x: 0.02 y: 0.02 z: 0.02 grid_map: min_num_points_per_cell: 4 + max_num_points_per_cell: 100000 resolution: 0.1 diff --git a/grid_map_pcl/include/grid_map_pcl/GridMapPclLoader.hpp b/grid_map_pcl/include/grid_map_pcl/GridMapPclLoader.hpp index 920be8e98..e7ba410ab 100644 --- a/grid_map_pcl/include/grid_map_pcl/GridMapPclLoader.hpp +++ b/grid_map_pcl/include/grid_map_pcl/GridMapPclLoader.hpp @@ -92,6 +92,12 @@ class GridMapPclLoader { */ void loadParameters(const std::string& filename); + /*! + * Set algorithm's parameters. + * @param[in] parameters of the algorithm + */ + void setParameters(const grid_map_pcl::PclLoaderParameters::Parameters parameters); + //! @return the parameters. const grid_map_pcl::PclLoaderParameters::Parameters& getParameters() const { return params_.get(); } diff --git a/grid_map_pcl/include/grid_map_pcl/PclLoaderParameters.hpp b/grid_map_pcl/include/grid_map_pcl/PclLoaderParameters.hpp index 18b2b2e7f..81f2172eb 100644 --- a/grid_map_pcl/include/grid_map_pcl/PclLoaderParameters.hpp +++ b/grid_map_pcl/include/grid_map_pcl/PclLoaderParameters.hpp @@ -46,6 +46,7 @@ class PclLoaderParameters { struct GridMapParameters { double resolution_ = 0.1; unsigned int minCloudPointsPerCell_ = 2; + unsigned int maxCloudPointsPerCell_ = 100000; }; struct Parameters { @@ -64,7 +65,6 @@ class PclLoaderParameters { PclLoaderParameters() = default; ~PclLoaderParameters() = default; - private: /*! * Load parameters for the GridMapPclLoader class. * @param[in] full path to the config file with parameters @@ -76,7 +76,7 @@ class PclLoaderParameters { * Invoke operator[] on the yaml node. Finds * the parameters in the yaml tree. */ - void handleYamlNode(const YAML::Node& yamlNode); + void loadParameters(const YAML::Node& yamlNode); /*! * Saves typing parameters_ in the owner class. The owner of this @@ -85,6 +85,7 @@ class PclLoaderParameters { */ const Parameters& get() const; + private: // Parameters for the GridMapPclLoader class. Parameters parameters_; }; diff --git a/grid_map_pcl/include/grid_map_pcl/helpers.hpp b/grid_map_pcl/include/grid_map_pcl/helpers.hpp index 824787076..d818e28bf 100644 --- a/grid_map_pcl/include/grid_map_pcl/helpers.hpp +++ b/grid_map_pcl/include/grid_map_pcl/helpers.hpp @@ -22,7 +22,7 @@ namespace grid_map_pcl { void setVerbosityLevelToDebugIfFlagSet(const ros::NodeHandle& nh); -std::string getParameterPath(); +std::string getParameterPath(const ros::NodeHandle& nh); std::string getOutputBagPath(const ros::NodeHandle& nh); diff --git a/grid_map_pcl/launch/grid_map_pcl_loader_node.launch b/grid_map_pcl/launch/grid_map_pcl_loader_node.launch index fde5fd36a..06fd69ed5 100644 --- a/grid_map_pcl/launch/grid_map_pcl_loader_node.launch +++ b/grid_map_pcl/launch/grid_map_pcl_loader_node.launch @@ -1,24 +1,44 @@ - - + + + - + + - - + + + - + - \ No newline at end of file + + + + + + + + + + diff --git a/grid_map_pcl/package.xml b/grid_map_pcl/package.xml index 557587061..e8e5b43aa 100644 --- a/grid_map_pcl/package.xml +++ b/grid_map_pcl/package.xml @@ -1,7 +1,7 @@ grid_map_pcl - 1.6.4 + 1.7.5 Conversions between grid maps and Point Cloud Library (PCL) types. Maximilian Wulf Yoshua Nava @@ -12,7 +12,9 @@ Edo Jelavic catkin + + grid_map_core grid_map_msgs grid_map_ros @@ -20,6 +22,9 @@ pcl_ros roscpp yaml-cpp + + rviz + gtest diff --git a/grid_map_pcl/rviz/grid_map_vis.rviz b/grid_map_pcl/rviz/grid_map_vis.rviz new file mode 100644 index 000000000..4e753d636 --- /dev/null +++ b/grid_map_pcl/rviz/grid_map_vis.rviz @@ -0,0 +1,162 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /PointCloud21/Autocompute Value Bounds1 + Splitter Ratio: 0.6114649772644043 + Tree Height: 797 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: PointCloud2 +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 1 + Class: rviz/Axes + Enabled: true + Length: 2 + Name: Axes + Radius: 0.20000000298023224 + Reference Frame: + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Class: grid_map_rviz_plugin/GridMap + Color: 200; 200; 200 + Color Layer: elevation + Color Transformer: GridMapLayer + ColorMap: default + Enabled: false + Grid Cell Decimation: 1 + Grid Line Thickness: 0.10000000149011612 + Height Layer: elevation + Height Transformer: GridMapLayer + History Length: 1 + Invert ColorMap: false + Max Color: 255; 255; 255 + Max Intensity: 10 + Min Color: 85; 87; 83 + Min Intensity: 0 + Name: GridMap + Show Grid Lines: true + Topic: /grid_map_pcl_loader_node/grid_map_from_raw_pointcloud + Unreliable: false + Use ColorMap: true + Value: false + - Alpha: 0.9900000095367432 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 4.018562316894531 + Min Value: -2.210437059402466 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 164; 0; 0 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 1 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /point_cloud_publisher_node/raw_pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + Enabled: true + Global Options: + Background Color: 46; 52; 54 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 26.305757522583008 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: -3.3914899826049805 + Y: -4.434649467468262 + Z: -1.8720630407333374 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5947977900505066 + Target Frame: + Yaw: 1.7004344463348389 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1016 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd00000004000000000000016a0000035afc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000035a000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000040efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000040e000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d0065010000000000000738000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005c80000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1848 + X: 72 + Y: 27 diff --git a/grid_map_pcl/src/GridMapPclLoader.cpp b/grid_map_pcl/src/GridMapPclLoader.cpp index 50ef8a8d4..281d39dd7 100644 --- a/grid_map_pcl/src/GridMapPclLoader.cpp +++ b/grid_map_pcl/src/GridMapPclLoader.cpp @@ -100,17 +100,18 @@ void GridMapPclLoader::addLayerFromInputCloud(const std::string& layer) { ROS_INFO_STREAM("Started adding layer: " << layer); // Preprocess: allocate memory in the internal data structure preprocessGridMapCells(); + ROS_INFO("Finished preprocessing"); workingGridMap_.add(layer); grid_map::Matrix& gridMapData = workingGridMap_.get(layer); unsigned int linearGridMapSize = workingGridMap_.getSize().prod(); + // Iterate through grid map and calculate the corresponding height based on the point cloud #ifndef GRID_MAP_PCL_OPENMP_FOUND ROS_WARN_STREAM("OpemMP not found, defaulting to single threaded implementation"); #else omp_set_num_threads(params_.get().numThreads_); #pragma omp parallel for schedule(dynamic, 10) #endif - // Iterate through grid map and calculate the corresponding height based on the point cloud for (unsigned int linearIndex = 0; linearIndex < linearGridMapSize; ++linearIndex) { processGridMapCell(linearIndex, &gridMapData); } @@ -125,7 +126,11 @@ void GridMapPclLoader::processGridMapCell(const unsigned int linearGridMapIndex, pointsInsideCellBorder = getPointcloudInsideGridMapCellBorder(index); const bool isTooFewPointsInCell = pointsInsideCellBorder->size() < params_.get().gridMap_.minCloudPointsPerCell_; if (isTooFewPointsInCell) { - ROS_WARN_STREAM_THROTTLE(10.0, "Less than " << params_.get().gridMap_.minCloudPointsPerCell_ << " points in a cell"); + ROS_WARN_STREAM_THROTTLE(10.0, "Less than " << params_.get().gridMap_.minCloudPointsPerCell_ << " points in a cell. Skipping."); + return; + } + if (pointsInsideCellBorder->size() > params_.get().gridMap_.maxCloudPointsPerCell_) { + ROS_WARN_STREAM_THROTTLE(10.0, "More than " << params_.get().gridMap_.maxCloudPointsPerCell_ << " points in a cell. Skipping."); return; } auto& clusterHeights = clusterHeightsWithingGridMapCell_[index(0)][index(1)]; @@ -165,6 +170,10 @@ void GridMapPclLoader::loadParameters(const std::string& filename) { pointcloudProcessor_.loadParameters(filename); } +void GridMapPclLoader::setParameters(grid_map_pcl::PclLoaderParameters::Parameters parameters) { + params_.parameters_ = std::move(parameters); +} + void GridMapPclLoader::savePointCloudAsPcdFile(const std::string& filename) const { pointcloudProcessor_.savePointCloudAsPcdFile(filename, *workingCloud_); } diff --git a/grid_map_pcl/src/PclLoaderParameters.cpp b/grid_map_pcl/src/PclLoaderParameters.cpp index 35c0fd817..29fc80380 100644 --- a/grid_map_pcl/src/PclLoaderParameters.cpp +++ b/grid_map_pcl/src/PclLoaderParameters.cpp @@ -14,36 +14,35 @@ namespace grid_map { namespace grid_map_pcl { -void PclLoaderParameters::handleYamlNode(const YAML::Node& yamlNode) { - const std::string prefix = "pcl_grid_map_extraction"; +void PclLoaderParameters::loadParameters(const YAML::Node& yamlNode) { + parameters_.numThreads_ = yamlNode["num_processing_threads"].as(); - parameters_.numThreads_ = yamlNode[prefix]["num_processing_threads"].as(); + parameters_.cloudTransformation_.translation_.x() = yamlNode["cloud_transform"]["translation"]["x"].as(); + parameters_.cloudTransformation_.translation_.y() = yamlNode["cloud_transform"]["translation"]["y"].as(); + parameters_.cloudTransformation_.translation_.z() = yamlNode["cloud_transform"]["translation"]["z"].as(); - parameters_.cloudTransformation_.translation_.x() = yamlNode[prefix]["cloud_transform"]["translation"]["x"].as(); - parameters_.cloudTransformation_.translation_.y() = yamlNode[prefix]["cloud_transform"]["translation"]["y"].as(); - parameters_.cloudTransformation_.translation_.z() = yamlNode[prefix]["cloud_transform"]["translation"]["z"].as(); - - parameters_.cloudTransformation_.rpyIntrinsic_.x() = yamlNode[prefix]["cloud_transform"]["rotation"]["r"].as(); - parameters_.cloudTransformation_.rpyIntrinsic_.y() = yamlNode[prefix]["cloud_transform"]["rotation"]["p"].as(); - parameters_.cloudTransformation_.rpyIntrinsic_.z() = yamlNode[prefix]["cloud_transform"]["rotation"]["y"].as(); + parameters_.cloudTransformation_.rpyIntrinsic_.x() = yamlNode["cloud_transform"]["rotation"]["r"].as(); + parameters_.cloudTransformation_.rpyIntrinsic_.y() = yamlNode["cloud_transform"]["rotation"]["p"].as(); + parameters_.cloudTransformation_.rpyIntrinsic_.z() = yamlNode["cloud_transform"]["rotation"]["y"].as(); parameters_.clusterExtraction_.useMaxHeightAsCellElevation_ = - yamlNode[prefix]["cluster_extraction"]["use_max_height_as_cell_elevation"].as(); - parameters_.clusterExtraction_.clusterTolerance_ = yamlNode[prefix]["cluster_extraction"]["cluster_tolerance"].as(); - parameters_.clusterExtraction_.minNumPoints_ = yamlNode[prefix]["cluster_extraction"]["min_num_points"].as(); - parameters_.clusterExtraction_.maxNumPoints_ = yamlNode[prefix]["cluster_extraction"]["max_num_points"].as(); - - parameters_.outlierRemoval_.isRemoveOutliers_ = yamlNode[prefix]["outlier_removal"]["is_remove_outliers"].as(); - parameters_.outlierRemoval_.meanK_ = yamlNode[prefix]["outlier_removal"]["mean_K"].as(); - parameters_.outlierRemoval_.stddevThreshold_ = yamlNode[prefix]["outlier_removal"]["stddev_threshold"].as(); - - parameters_.gridMap_.resolution_ = yamlNode[prefix]["grid_map"]["resolution"].as(); - parameters_.gridMap_.minCloudPointsPerCell_ = yamlNode[prefix]["grid_map"]["min_num_points_per_cell"].as(); - - parameters_.downsampling_.isDownsampleCloud_ = yamlNode[prefix]["downsampling"]["is_downsample_cloud"].as(); - parameters_.downsampling_.voxelSize_.x() = yamlNode[prefix]["downsampling"]["voxel_size"]["x"].as(); - parameters_.downsampling_.voxelSize_.y() = yamlNode[prefix]["downsampling"]["voxel_size"]["y"].as(); - parameters_.downsampling_.voxelSize_.z() = yamlNode[prefix]["downsampling"]["voxel_size"]["z"].as(); + yamlNode["cluster_extraction"]["use_max_height_as_cell_elevation"].as(); + parameters_.clusterExtraction_.clusterTolerance_ = yamlNode["cluster_extraction"]["cluster_tolerance"].as(); + parameters_.clusterExtraction_.minNumPoints_ = yamlNode["cluster_extraction"]["min_num_points"].as(); + parameters_.clusterExtraction_.maxNumPoints_ = yamlNode["cluster_extraction"]["max_num_points"].as(); + + parameters_.outlierRemoval_.isRemoveOutliers_ = yamlNode["outlier_removal"]["is_remove_outliers"].as(); + parameters_.outlierRemoval_.meanK_ = yamlNode["outlier_removal"]["mean_K"].as(); + parameters_.outlierRemoval_.stddevThreshold_ = yamlNode["outlier_removal"]["stddev_threshold"].as(); + + parameters_.gridMap_.resolution_ = yamlNode["grid_map"]["resolution"].as(); + parameters_.gridMap_.minCloudPointsPerCell_ = yamlNode["grid_map"]["min_num_points_per_cell"].as(); + parameters_.gridMap_.maxCloudPointsPerCell_ = yamlNode["grid_map"]["max_num_points_per_cell"].as(); + + parameters_.downsampling_.isDownsampleCloud_ = yamlNode["downsampling"]["is_downsample_cloud"].as(); + parameters_.downsampling_.voxelSize_.x() = yamlNode["downsampling"]["voxel_size"]["x"].as(); + parameters_.downsampling_.voxelSize_.y() = yamlNode["downsampling"]["voxel_size"]["y"].as(); + parameters_.downsampling_.voxelSize_.z() = yamlNode["downsampling"]["voxel_size"]["z"].as(); } bool PclLoaderParameters::loadParameters(const std::string& filename) { @@ -56,7 +55,8 @@ bool PclLoaderParameters::loadParameters(const std::string& filename) { } try { - handleYamlNode(yamlNode); + const std::string prefix{"pcl_grid_map_extraction"}; + loadParameters(yamlNode[prefix]); } catch (const std::runtime_error& exception) { ROS_ERROR_STREAM("PclLoaderParameters: Loading parameters failed: " << exception.what()); return false; diff --git a/grid_map_pcl/src/grid_map_pcl_loader_node.cpp b/grid_map_pcl/src/grid_map_pcl_loader_node.cpp index 7371a6e75..16531050c 100644 --- a/grid_map_pcl/src/grid_map_pcl_loader_node.cpp +++ b/grid_map_pcl/src/grid_map_pcl_loader_node.cpp @@ -26,7 +26,7 @@ int main(int argc, char** argv) { grid_map::GridMapPclLoader gridMapPclLoader; const std::string pathToCloud = gm::getPcdFilePath(nh); - gridMapPclLoader.loadParameters(gm::getParameterPath()); + gridMapPclLoader.loadParameters(gm::getParameterPath(nh)); gridMapPclLoader.loadCloudFromPcdFile(pathToCloud); gm::processPointcloud(&gridMapPclLoader, nh); @@ -37,7 +37,6 @@ int main(int argc, char** argv) { gm::saveGridMap(gridMap, nh, gm::getMapRosbagTopic(nh)); // publish grid map - grid_map_msgs::GridMap msg; grid_map::GridMapRosConverter::toMessage(gridMap, msg); gridMapPub.publish(msg); diff --git a/grid_map_pcl/src/helpers.cpp b/grid_map_pcl/src/helpers.cpp index bdcad43c2..4c016c26f 100644 --- a/grid_map_pcl/src/helpers.cpp +++ b/grid_map_pcl/src/helpers.cpp @@ -41,25 +41,27 @@ void setVerbosityLevelToDebugIfFlagSet(const ros::NodeHandle& nh) { } } -std::string getParameterPath() { - std::string filePath = ros::package::getPath("grid_map_pcl") + "/config/parameters.yaml"; - return filePath; +std::string getParameterPath(const ros::NodeHandle& nh) { + std::string defaultPath = ros::package::getPath("grid_map_pcl") + "/config/parameters.yaml"; + std::string pathToConfig; + nh.param("config_file_path", pathToConfig, defaultPath); + return pathToConfig; } std::string getOutputBagPath(const ros::NodeHandle& nh) { - std::string outputRosbagName, folderPath; - nh.param("folder_path", folderPath, ""); - nh.param("output_grid_map", outputRosbagName, "output_grid_map.bag"); - std::string pathToOutputBag = folderPath + "/" + outputRosbagName; + std::string pathToOutputBag; + const std::string defaultPath = ros::package::getPath("grid_map_pcl") + "/data/output_grid_map.bag"; + nh.param("output_grid_map", pathToOutputBag, defaultPath); return pathToOutputBag; } std::string getPcdFilePath(const ros::NodeHandle& nh) { - std::string inputCloudName, folderPath; - nh.param("folder_path", folderPath, ""); - nh.param("pcd_filename", inputCloudName, "input_cloud"); - std::string pathToCloud = folderPath + "/" + inputCloudName; - return pathToCloud; + std::string pathToCloud, folderPath; + const std::string defaultPathToCloud = "/data/input_cloud.pcd"; + const std::string defaultFolderPath = ros::package::getPath("grid_map_pcl"); + nh.param("pcd_filename", pathToCloud, defaultPathToCloud); + nh.param("folder_path", folderPath, defaultFolderPath); + return folderPath + "/" + pathToCloud; } std::string getMapFrame(const ros::NodeHandle& nh) { diff --git a/grid_map_pcl/src/pointcloud_publisher_node.cpp b/grid_map_pcl/src/pointcloud_publisher_node.cpp new file mode 100644 index 000000000..82e2b8e0f --- /dev/null +++ b/grid_map_pcl/src/pointcloud_publisher_node.cpp @@ -0,0 +1,42 @@ +/* + * pointcloud_publisher_node.cpp + * + * Created on: Aug 19, 2021 + * Author: Edo Jelavic + * Institute: ETH Zurich, Robotic Systems Lab + */ + +#include +#include +#include +#include "grid_map_pcl/helpers.hpp" + +namespace gm = ::grid_map::grid_map_pcl; +using Point = ::pcl::PointXYZ; +using PointCloud = ::pcl::PointCloud; + +void publishCloud(const std::string& filename, const ros::Publisher& pub, const std::string& frame) { + PointCloud::Ptr cloud(new pcl::PointCloud); + cloud = gm::loadPointcloudFromPcd(filename); + cloud->header.frame_id = frame; + sensor_msgs::PointCloud2 msg; + pcl::toROSMsg(*cloud, msg); + ROS_INFO_STREAM("Publishing loaded cloud, number of points: " << cloud->points.size()); + msg.header.stamp = ros::Time::now(); + pub.publish(msg); +} + +int main(int argc, char** argv) { + ros::init(argc, argv, "point_cloud_pub_node"); + ros::NodeHandle nh("~"); + + const std::string pathToCloud = gm::getPcdFilePath(nh); + const std::string cloudFrame = nh.param("cloud_frame", ""); + // publish cloud + ros::Publisher cloudPub = nh.advertise("raw_pointcloud", 1, true); + publishCloud(pathToCloud, cloudPub, cloudFrame); + + // run + ros::spin(); + return EXIT_SUCCESS; +} diff --git a/grid_map_pcl/test/GridMapPclLoaderTest.cpp b/grid_map_pcl/test/GridMapPclLoaderTest.cpp index b9e52e009..5b0f10913 100644 --- a/grid_map_pcl/test/GridMapPclLoaderTest.cpp +++ b/grid_map_pcl/test/GridMapPclLoaderTest.cpp @@ -37,7 +37,7 @@ TEST(GridMapPclLoaderTest, FlatGroundRealDataset) // NOLINT // allow for some difference (2cm) since the input cloud is noisy (real dataset) double referenceElevation = elevationValues.front(); for (const auto& elevation : elevationValues) { - EXPECT_NEAR(elevation, referenceElevation, 2e-2); + EXPECT_NEAR(elevation, referenceElevation, 3e-2); } } diff --git a/grid_map_pcl/test/test_data/parameters.yaml b/grid_map_pcl/test/test_data/parameters.yaml index ea4854ab9..772a8dadd 100644 --- a/grid_map_pcl/test/test_data/parameters.yaml +++ b/grid_map_pcl/test/test_data/parameters.yaml @@ -26,6 +26,7 @@ pcl_grid_map_extraction: z: 0.02 grid_map: min_num_points_per_cell: 4 + max_num_points_per_cell: 100000 resolution: 0.1 diff --git a/grid_map_pcl/test/test_helpers.cpp b/grid_map_pcl/test/test_helpers.cpp index 037fce436..44926b205 100644 --- a/grid_map_pcl/test/test_helpers.cpp +++ b/grid_map_pcl/test/test_helpers.cpp @@ -115,13 +115,9 @@ Pointcloud::Ptr concatenate(Pointcloud::Ptr cloud1, Pointcloud::Ptr cloud2) { Pointcloud::Ptr concatenatedCloud(new grid_map_pcl_test::Pointcloud()); concatenatedCloud->points.reserve(cloud1->points.size() + cloud2->points.size()); - for (const auto& point : cloud2->points) { - concatenatedCloud->push_back(point); - } + std::copy(cloud2->points.begin(), cloud2->points.end(), std::back_inserter(concatenatedCloud->points)); - for (const auto& point : cloud1->points) { - concatenatedCloud->push_back(point); - } + std::copy(cloud1->points.begin(), cloud1->points.end(), std::back_inserter(concatenatedCloud->points)); return concatenatedCloud; } diff --git a/grid_map_sdf/CHANGELOG.rst b/grid_map_sdf/CHANGELOG.rst index a685bd101..bd9e5fde1 100644 --- a/grid_map_sdf/CHANGELOG.rst +++ b/grid_map_sdf/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package grid_map_sdf ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.7.0 (2022-03-17) +------------------ +* Release of new implementation to convert grid maps to signed distance fields. +* Contributors: Ruben Grandia + 1.6.4 (2020-12-04) ------------------ diff --git a/grid_map_sdf/CMakeLists.txt b/grid_map_sdf/CMakeLists.txt index 34b8369f7..88eda8145 100644 --- a/grid_map_sdf/CMakeLists.txt +++ b/grid_map_sdf/CMakeLists.txt @@ -8,7 +8,6 @@ set(CMAKE_EXPORT_COMPILE_COMMANDS ON) ## Find catkin macros and libraries find_package(catkin REQUIRED COMPONENTS grid_map_core - pcl_ros ) ################################### @@ -27,7 +26,6 @@ catkin_package( ${PROJECT_NAME} CATKIN_DEPENDS grid_map_core - pcl_ros DEPENDS ) @@ -45,6 +43,7 @@ include_directories( ## Declare a cpp library add_library(${PROJECT_NAME} + src/SignedDistance2d.cpp src/SignedDistanceField.cpp ) @@ -82,11 +81,16 @@ if(CATKIN_ENABLE_TESTING) ## Add gtest based cpp test target and link libraries catkin_add_gtest(${PROJECT_NAME}-test - test/SignedDistanceFieldTest.cpp + test/test3dLookup.cpp test/test_grid_map_sdf.cpp + test/testDerivatives.cpp + test/testPixelBorderDistance.cpp + test/testSignedDistance2d.cpp + test/testSignedDistance3d.cpp ) target_include_directories(${PROJECT_NAME}-test PRIVATE include + test/include ) target_include_directories(${PROJECT_NAME}-test SYSTEM PUBLIC ${catkin_INCLUDE_DIRS} diff --git a/grid_map_sdf/doc/anymal_sdf_demo.gif b/grid_map_sdf/doc/anymal_sdf_demo.gif new file mode 100644 index 0000000000000000000000000000000000000000..1e3fe5d844d0c2df59b36b1a35c30ea4fab482e6 GIT binary patch literal 843793 zcmeEs>0eUc7cOu_IDm@cfMYo39L}hy;5-(V8l@JFp;_UOSy_QclyZnt3)4)?(##6Y z%F+tNv9zentgJM(th8wS+T`zg|Bidli+w)l#o2r9XRYYwE0LJxf&k-B#^X;nSZ{GzVibpo|hBdlE~@|Hndw?R_7ZuVu}>{|wzLxw4L4L6P$#y-=D zePx_BX})FNICjBc%}0YEg_`FFEstr-fER`#_jElT5mpXq89yVLzQx=9!0G+KYyL1K zeqBlU;imCD*l?a^|CZ)5wbuUqX3g(RweKnF-?Itd4ygPrQTthIyl}$tTdDJO;i?Dw zR(0jsHs@O%-ENV;)qLZ2OX@Z&Z^$a3%70Dmx|s9+8?IZ%w6E~$v~(Gvdrzzie66+m zl~%&sip`H4Q^qWF-dpT`rk_8k%^N51-V+Xg)HwdipmtjG>^q&yvud65s(lM)eIKnJ zECgq!_9nwxcAm@-y81;4yj`6^de$Z%h;YJF_A_Kkm$bzW3?X zQ^myCm+$XC{a#%B^XAb(w`HSvd`{J5NO9)p`gTXr;{&N5#>?JCTC^ zkUay@2k#~n-rsRxIy?RKmZYimTV91mzNSas4GzB<6mi}?s@i?SL7(+`KAZPCrxaOk zsjy3`HOn}mw^O9gJ*!`S+MvAAqPWGXSnP73+hOlLm#uePGA_IP`}^!lEyU>!FoZjcq@O+#yg+fMhD5S`K|2HVaI947f4G6-pJ9ICKf*Ah3>e)isR za?;(}kSpg#YAD$sCWfvwJvc>!FovNW%@5B6S6Ij2?KuCqiE$?MWa!nFCl{Dk(qG=a zdg1A1mh6yW*tOPYSJ;nR;_qF%_~JTe`tHfF>z7`3<$e3`^4|5!ukUaHtWkKUcuFQ9 z*lZf^Y?~esnugVd-)Nt`Cvw{QYWT*LcMt0QN{k|IcD#SwyzauLxgA$O7XPpIR^2TQ zv5?h~t&banUH|m@Ux5Qj`R^|Bmb-_J+aIGQkW;W!<(k!ABA)}dtGdjuwK8)H1{{|1 zR}o8@pUa*UJM8M8loot>{#beI7*|SO{8t$uS;hIiyR0XG1y?p{<@WGQH3^$zXYJ(N zU0qt)HQ7>%LXF!isGmZsQN+H0k)z~wK{9e(IB>Vr&CuabEY&SXVc$Wgu(OOjQ*{4=%;#?{D-^`HN&hdXCvzexi%_#sOZgSSqw1e_? z!(;cnX#`+l-GjCf;omu+m9n`GNEieoYgm#$zz58d!W{?j72)Ki0i~o;GTY(?ZLfNv z)v%Iw_;nnJkAuNa$>K<_&ICt3JyjVN`fDY*-B*8W>k!F3%}GmGUx2Y{Wch+R&cg5} z6l~pg#1NS*bx;;>Ers{vPfJK@0*(}Y{OwlyX`RZwG_*Plz&V-}l6tE9Y}ZNA|3yB_ z;QaGCZ`5bd<`TvCB)#akO?CUf z{(2{)ySF~;8&NhT5A>VCa60ZpuH5ZFk7`%)=RLlnQ%zB~4<4 zv09~`?~Fz;BUs5AeH3OgWR}RSH7v0I{it!vJ~(J1tp8nP);hW8SnAVPR?HW2qf;(#-+iWL@o(xabL~mu>^GxV8Vp#s*5n~% zFwI1j!~N#<5QbvXOgb#lG=s!+u8@XS&g9X8VfX@?)HsUlqossUM^ls#M#2tn-^s&a zH837AICy;9h1eI?jV8M6RVrhv`6jI=;Te&zjU`(DYWAx&~~E^0Ur60UB$OuhXlk zk&~-;r3dd+UlPV+Q1!myxkq8wNHhyKE5?6Me7RQL$rjO;a!tKaSUbbm4#zFsIEc{g zZnh-vmzJ!*v7qC(=TWLi>Eipok+_>3vA@K5eK2iSX>>RjUbvwz_4a6WQm-jOgIDUC zqpq$L+-r<6M*HIm@W#RKNWo-uRyhq{5d2}Sig7eYucro*uOKmW3VeH<>g;TI;D;N7 zcqUoN2CZaDbbtj7_o!Q%Nlb}f#^7d}73FBl1_QkBfK9k@aH3P_OGYch6M;ESJxapHSziBp0g zYLB{=QZo&OkJPx2sH~1_O-jqe$~>-VtEf(43~jKn6DEb%#e6$_NvX<;MV)JCnq5rw z5ZyR6+Q0P0%S*>wj#Q8BF!tn<2h3@{ahcaBG5$_F=LLR3jZGq3m`P4I+TY;xH6F9q z7-1~f5mOFnu$A86c$5$42<#YF|5*$i{dDKL1Xw$+8}x`#Izljh zNAT_;0z|G*$5`NXeZvEY?Qe{BK(A~fWZtz`GS! zb0)G7J@`p#OSTMrlBM@_1%aZI#98Aa@|G_wDq9FXd9 zr9`pczT{U?*RBQh!ns>ZJw8w1i!Hwzf6qtzh1cNM?$1>|`DY@qvf}pMTqR@N z6#AYP;^ral^wEm&`;HnfO4swhR++N|xu@FZc|`v`&?S!MeP8vgu`3hL?(OiC``-C> z@^jDY(2@erJyWIU43n(9uxr)0g@jX-^IAI&u3fn_-Oi>28hVz*YF^$}_XE}OyRB`0 zBqG|xW?R=y5zJQ}CED#-_$TASN5jvHirSh0V;t<0>x#V(#x`AesO~24wSAdY*2y)k z#DQKxiE~0B%=AP&`n9KFc?oy_-&f(=cL1k9tlMkMSk8(1#iTS0;gY4PeX(3lqg_$u0%1a1ug zX_jF3Ai9zT{?$Sk$E+TJUs|+3yM>wO=11r%3#GLHwF%>ir zzXhzI6{U2>EX)?AHFLIBaY_Q$U;9Rvx)#m%p$Y4El*tbu9^<56=V>B$NtmF z&^vcP$cgOdVBsvm9f`20Q_xgIgnSKmIr4Tw3~#4(pC7y1{NN#3uzOLkdi1Wgl!8M- z*pksbwhbdUS-=P8cr(xbew}O zW?$vx%|BV5e?NkYmbxxSP0{bFy#HyHA1A^7B0*j-78Atkk_feaW*#JByC=zn4MbWp zuD1dvWm#KQSsTrHy@EVVs>2Vm*dG08b1?4A_%1+%^XO=&vrm02lYSWOV}U? zM!15UQS?^=__nv|T_E^KRCk0`Q_eU!r3*4JrDf#GYr2ha7TCtAOVvB~cO|TfCTxds zzaFf-jV^Sz_WUF|Rl&%|=#*FBVcUP8i`-!59>*#IVN1XHkvLtL{(vxf54IDAy{vHQ z!efi({2;oSjO-<4_$x`Q5K*4Xr5H_O)IqR4?k5(0#D1;XB9NadN&)*7=*u^1D-^Yr zc>gja*dSv6H8u!;c=>;Z@LKpV-~Z+@T+3>|tCaa4Zx z{+=@xcu)u{-Szxv)Q8eIy>rLJ;BgLj%bs(`@USX3Y#WS=VAV{!m(Gr}(-!$G-BZ03 z@Y@siW;AQ>hf7)gYf3`6RsGmQ)>w_-m`(*&BF2hg)sa0!xv9;iO0Nr9p$mvW$E!@9 z)=?!^{mr7PbM6IMMIt3J7QtP@?c2TmL38Vq4Pcx#c$*DY%a0y|q18E{8I86+5j5t4 zLpQ-{+Ok35-Hl+-Ua*D%l3U8;zbc2V&^*Qk##V4B6dX@Ozy5$eg0G88M}IrfQAIwN zbo0`+>W+|m2d>EYOm6E` zWZqC<#Q17$8S$+nZ|Y3gzIE7}QCO7XywM!}k5+6>)0S^%kC)P5?c(-BeB3b__SNoE zS>9P^8*p0<9xz+>=Mihy(K4@pQDc z9Nnqcn6b1MJjN=MY*=Qv#`P_S?w$~=4&wrXEAQMzNiA1p<9SDPuptNQ_M~6_RW02A zyyP#}z3y8x08e@4;Rd3SffHS{SyIi>-%Y4(eks4Bl|Uc9Vrl^@n)ED@QnBLRa_oyF}!wYt=TH4^YRx$U@6AZCGmVO%A4Yj9WJz=ym~fBN!DK)OfW6ua@dn7!0XY&^^b zzw_^iX)Mn5%x*Fk&6L!TgaC-GRn*^rVNa3UE>DW_CD=;}F+Qn{DBC^A!F?{kp&95N z&FttIx?p#}-fGdCp!F(SuoptG0_*Zu2fM0RU=gS5Sqtd=0*oC7r#PTc4w`E2UN8Vd^TE1Fuu=}ziDmbxBd^Yb`$_2Ic(f@8ET~5uk${&b z!ILCRoupS5)>WnGecRm|Mjc5VzTd`5fD0w5@%Q^|M%GLSRStF}O%KHge&=P2vc z!d0|i^(C&yHe46hEb7#C7`BFXIZ(e_ESI2Pf|%MNwJvOR>jv$7Y4v%W<1ttfA9pGX zc1__Xsb``kA;oTo;o{@d0~|{`Sdk0XRv%lM-@%FR7Li8o|Lxtp4Ll|8tz!wW-C&&@ z6?74-BVodapA7zca)JvUP)x)ubzgb-4+WsHm*h`2Eezkd*c-ZSY|FpiY6)0FZsQTL zV$OZG%F|xYSK#yeefRo0YA&G``znRu;<#b z`ehGybiRBUcX8DJ&l3@TqQt7LjsXUpoY-WCdGQYnUAVuWwG1)(fKYBCe1aVYJIR>M zFGpovFJ7s<3jfzzD*6tNh<6rN=U~W=)*SD9g)AJo7vJlS2rd<#jALH-` z?jsJ#*>RKgli(6^J9w~W=(2pM4Tfo%#2gvIsu)$5JDByE;+mqcbt56!)z1liYxXhU zZ1cb#gIz|56O5h;5%nOPbw8_Na z+_9HCbF3b95{5bQ9K6WFgizI(&zxO#N@9?D@@Ufwpn#Ov}$cW6&NYe!#s&0fC`HYg@GFQ6L8*aLDf zU$KO$Q@{`4VMUW4eC%hgege-ZUewA_!AmHAL(p^$<_rlVCbh{UFhL9R>t9WT4nLtE z_}Df%e@Z+%_Y(Bqe?L5<6>T@f-oKn3U%q*b5NtpsMSke{;iwhDU-#}WeE4+eUq{-l z$xHQ^78s_1HrFitd{grCO4JlLfoih_ca0l)m4)k0!q!Hy_{Z}!-d##b$99Zhr|SgQ zC*QriH4(Z1o{~$>aYlXXChFy=1_^2f9&w;n;()mMl?)#^6@9$U+5g{Rf@7+9~UliM# zTmAMoo~>NZp!3wCTsxCAS8v3$tOTP!SXBxWb!}{pkMEh)YVXea==fg;11NQw5`VuS#BvvmKBrIh3GlxHawYdQ!4 zwig2rg&d}azL#mP{Yy(x^9eqZR_PPN{tQGd)|*UMF(4@RBhgGY^U?GsCsSK?ssRezZ%cM z20AD2kAzjn3mf`G1?bT7`VEP?=+lP~<4EnK^0O5tOl<&pEH?XJp{CdO&QY~>pC%_O zy}XG#kzPwI`osSg=aMQJEgI%gYsv2+&5Zv#p-Au5^!L^|VM}eMRmcCKQx1E<3dv)2 z@&JDKF;Z>d>DM9W2+jo}D% zTIFhAcwZHh91<2By%tW@TDLkag%}?tJ)@NnxRtMCwZNxl4P7pE+?@PXt6V!4y=?6p zlbZoY=TdnA+*sCmg3hKa_pwXYKeTK;iy653`O(_Yhi4A2ee|VX(>rxgcDVB2qGXr9 zJG@sd5+kjD@AJtLS>gGeGCTbu?0k}@=RC2yJn9pdXX(>hqt=7I_cVhLm0z&&{WW>d zbFKAx=HRh7$4AL`+Wl`h5K?%h0oPOk4My^5jT*FMe5tjnEpq-mVWZR2*HLhclZRZDJB8`M zmDtI8YC^&_FxlHmlg^U)hTj>7Jo7TtTn1$xYsJOhV$vbcPGAL_WaRT#s=4a1%&7D< zDk}Ve>h%kdxRK zgGa&L>l9M8;6`BI-E7audS9n{$_m5(h%V@pzQP30G5bxC8Vp6_$~r-eIK1~_s01V+ zy9BZY9H8EXY=!bI7=-Er`7fXyc%B>@L%<;ercMfB43cONzR^sOap|5vhM z9^sMMjy#lq(1fTwX?qI&!X_7vF)+eT)Tf$~U1r_|} z7LY$Rs5TA4JVU37y}w_vo|ynv*dAHxqS7v_=2H58&YypDkD7+;{fM^;!(4gT@I8%$=fC_dJC!l3lTVwSBCoYBL}H?6 z8mewkkVY{Nv9kBabfj~A*7a?jmhdN?1N+JCPF%Q6zg{~zK4}?Otdd?)NLKV zV#cfR%owW$LcoS!a>SX2dbNENsS(2gMKNf}+b5Q=fj_$2r}O@uS&X=XuQNUBWs-?g#lmQZX7SS(Q29uv4kB*#mx0+H8BJ1i>6AV z<)fU72Fh7ysVPt9-|E;q_uF&Zut_X!;`QeH@6+eC^}qVI+{o)&MU&nn9Zh7$pMCHk z>UUE9hXmElBYqxZUGVg4B*XU<>Apx-N6s)^Z9g-}YHb@_ynRw70lBsAn}XdtmY|x| z3>dy;6jO$I2XB*~S|bj6LONi>NR=IsEP&b}2w?_Mtj^O{%G?GaT zrwP7R*uy?jjZ1Yz%^Q5b8&O9##iP&Yd|Kd>^VL!}we0=aZI|6TV_tuIL@4s}7*E(@#85|m3@+Zc0bWL#Z&1mS z%Wy@oVioo`)!kg+M{`L?C~7KaZ+*Ez?5q1V1RWDU3Ja$x63sl0Yy(1r}k!j z)@)`6ghys-Ngn=Qd6B}f+-P#FY3G}Co3?0+mY*1%q#U!11}&qIL=CD0u6ABvVaS{+ z**uY>)r(hl9+YBUl4Z~PMsmkf4qo2;cWkw0L-5HD$wxAax3zc6VLJz&g*I;gW{$Z(_!8j53ishXCwn04p z{ZE0z_V=qFEE%ijHTzAkZ#$G#>HE0Gf^YqE|C;(|Jk?$3c`J``OmtzvtCa@=tW{^m z?}`?zeRU6-n`<6rh*GMX6obM0eWfqp`!vsyy^Kz~KW0;JR6R06xnox1(t@WyvUK+T zrgxU?^xAdYBkuS~)!jF*cX<^|$BdY%%mJJXlT9y?Q*#S~USSrYIV zDvBXe!nZ=JU%>U60dFoZXB<+^b9N0bR{99#uvSF?-A|{T%PSz)W`H_~jHw5*=A6r& zIy^g_obPscz-&Y%=U2!~m1Qd{JIVF#{BM#Qysu^v@-wW5O24@+t7*vhHY+3#O`nzk zu979-bq(akEn*FlVg#;HizKR&)wsj9kZbr($dsi$-@UAkDvB6d@3p;qO`xxC)ffW}WWL&~P%K6aKSTdE?8kta>#z5BJ0P@q_ z=iT|90+P!c-L;dKGKWkf2hW(mF?tYxHM7-&#J@Ri>M4L+M9_u?z>SDXrI=IaZYQw$ z6mF3@RFo+w+8Qg%tu$zV(eCk#?|8854_x2igkSU|GFr};={80!QQE(?)ZHe~Bt3mk zV#Ub4fIAC{E`_Y~gI!s)w0eIx7UbO7ThiST*4zsG=(wP!xgRxf58|TwTRmYZ~G;xs-rCLLCNof zlG+vExUOr?dB{Zo{I*0c6%=h6gh1s)7Mb0?`*KyV?_EEbt z_uB8to>UJc(T{qSdhW~MYi3*4(M{F<1bEVJRr?O!*$TLdXa_3?OOv5e0~ETp2<#nn zVFJ!Vz(o>V)O)uANA+f)z^)EY8C0GmS)y}zcTF1uV!GvuWdb}|GXLg_qgZghKmwChm&D0?o3GSF~wz$zpoLB7Q4nI zBI^>Bv&cS{WF?RXVimHVc6p1_Vz3HSQKp|gueJ-SCj&0)KXeWu$5S^uJ9au zqF)@40k}zq2f7EH8S=0=XegPVODU!V11`c~XJN35Boz5$xOk#B9~$(Ji+GX@G5+>a z*nkDBPlXHQDBwGZ5q{a-(c{ikQAb1#x%3|8QEz7xcJ+m1vdhgws#*N{;Lztu2c4ed zAk3k9WApN))$SZ9i@Bt{z8RnpgJK4uRDI=(o&$C+DCf8b~S>wy;8eW~hk**L8Vt%GTwOK@DgkbmjEp=eXBWuB`T4_*8Fg8JjmY@u?z!g@-tXp^Lm{SBFB ziP}7PlTG${6S~IXN6gb^gO`?sl?liF67RT<$Pxzm`=j`qgOO$%kgvWOQ6;8pd-}X0 zdRNQ(ik4b^T`ZwKf4QGalz*9W&LljCJW8PfA@KmlYjkxA;KBfMf{WMM0j;e)VWq+S zxF^xn%74VgGdiY68%u$8ljsI4W+UkZ=21=qI!8@m{x@>0&IKF zI{`f)c}aV{H`GY8KNMlF%i4>K}? zi!x|nw*RBb7fpV(VX~DT_|}LQbzPT!&D$a5%efp08?BW+4MSn42TM zMFko>bQ@&$Cqs^wfYaOy=keHovoD-2Q8A=vQZL9!5{y_4IdR5aB~YMJluI6TU>jgA zVGL78$>>p6ONdMaBJHAAFe7srC`Sc6Or`HgPH$Poi}n8oBVx}#E(N5HH&*l-VIJR# zVQ8!js2aD?p%VEkN_w-2sOaF0QyN8a@{3W4MPr4^o4G}IW|uCeU3v9!IVljhTu5b( z7Zd{p2hJcyMi1CQT>&Ty?u3c}Fz;jzboaW-nXdRJ41>sljKNIit%<@X?vyjcG3Vb* zF?IIV*G`~ZX1X3$>q#ok5`}-yg3QPGQO!__AcmNMykbzCO_8Na(lR1~$W^InuQs(W zAa6{(iBa%3jla1+{w4u75XUVNrSqSdwj%@Mk8F>lX^sDj036u}M^Tc8{RG^I<&X!@ z67Y6%Kf-?^To$)PUY&G>L8}x`LsJV>h!cEOz>zlNxG2eH0C$ujvXJREKIt|I_s&HC zXIbm|hyAw?mMV?*85A$=o$a*lb>8due$Vd<$S{87TzypDhHx9?dZyR;GUaC_fMY#u zE8Eelo{J)(D0x5@M>%Z{kxjm{iCoNPK2H@Y=RJIW?$yTpXNkEXFW6hx#S2_pJ_T94 zHr%#)hXp~rUTeSbinW#r~)ar!FNr1{i0(So9(LW#u-kM=@fxHsdlck%x1AK?~| zdFN~Uxq`)_kE_VVif`~-29(1n$mRh1=5}OHBFL7CetW-56nSw%4<<to!X8O*E?`CinUUjJk)LxP2hif8Ln#4UCyO0}icyowHk}14I=MRqsC1@d8c~+MEB&N( z;$}8AQL=sDBeJEa=u-c4g@0I#P&vl3*iG_2`_vyxa}@Q?>+83-Iw^P#Y{V)GWIv85 z=-+BHhsfZdI84OW@q!(LsB8|jud|@bPGL?#8;7Pg00Z8K&GwQzc#*vGAp9F`U330`**|Uu= zF64T1`wRsz3|{IcDM}|7ucD-G9Y@)YqcR4$#sX9>3zqHUBOch)u+iYcPvm8&Xy*bl zk^R3b^GLQpIdu?V3yU)Af4NH1(gyc-qXaqcdh*@3C=5iaw%pH8>q#CGIc&1nGxf$i z{J71yB>A4}_RUvUCA2ct{dz%>`I_DiT|z&2*dk3ribNrC)kdpWrS6dONY5$S1JN%> z<+AEVpP_oVUwK@$VcNM%Ay8_Wo^x7z`pKmesUw|kv#-RFS5nJrJ$AkwOdzZ*H}K4T z-Y?BQbl;GgIZ^6Vm9ABrdHcjd15hkO=kA!9Yv9_I=(&wwdOzL1s;0~A?|7P6dE~g5 z^)Il(e%o*752G#XuWVoV?J_@p8G8R__TE$R=G%MT>s@PEe}R3w@kgSC%88E5N0Z$= zpsBVad;0{*ANAJbX3mUiuKUxoCC3F3wYH#>Lzs5L*^$Lgvnnsj~V`2DavboPtyB!XBq)zLTK|;)q0>6j8z(T(|<-~4_6KUtPaW%b*J>jcv(H@tqdPr;v zTQ!3#o}kDpp*NK6-I+!DPfsSTUWYol?ta6cdDH$~Z@*9asU@-=B6ZeF&Zzi&nad8K z2LBbqJwr3({zOKcald8+7tYsg*=}6qLAH$y)Jyb#cuF^XuGdc&x4RABmO80f$Iw3A z(68}P)S$Y~B;9;8W|M0))=zD2uw%U3{a>F>Tx|tX=XDxfl@cj9g4Cq8URh23)B89;Gl-$yrxwYO zuJ-(p31gHmdl1I zcdJbecg{9Ps}4YzL=L!Ae?Q{PaGKSF+RX#~_ga%yY#a>I9OFU8Xk(*j&Sq*k$;VcaWca>QS?f&@ zaus9A*yy<=Nb5FCc~6wF$?cn?;@e`tK)}OA;AI+ut9biDICeY1-1=aTZ7$as7p^$? z;*GW&+VHZ$cKPHQ$&;dM$^6)(7w&#LAvxwEfa|MDfTUI)FW1sobw*C}++H9v4~Jt@ zIX#3oN0c^#r7H~NH2k=<)YdmCaUFG~$Js#(w&eVp+z$cHLa0283pcbh8Swg&rn)M> z7#k}{3K;7|hNl@DJ)11nZXt_}4d|GV<{tG)_~BiOGnnDxjOWP6(t4$g@M)E7TCodT45zmN`tErJgmGbco12Vwd}0y0ZQb8T8rI zxetF?bD;mrsaQ#mR)-?eTIi2itB@|1bCz|i7tvoiD||ZI%C`xVy*_pZ{@3|seBWRa z=6gLtyPs8PN*Mto$g(vhZvY)zx_Q`SQ&{M3zKy83>9oOJ9qTH-3ay2zUBGCo+o|fv zHMUA7V`BvEVFM={RCXMc>Gj|XwG}+oOco01Dpqn!9xz<`%j(ge5UZM1Dy{q?L}=G? zl!AVbcU4GJ$`IDwAEdKdw&Cw5AF&nU~ zIi6~r5V>+@)W?hItDVS!Y@Lm<$>RkCu|lbY(b&{$;-_(+TfS11g!@8EDU>smQ_KFt zhLi6V3lY&OHzTnec9>qR9HBZdbsrZ?&X2*0ap#)J^x=PR9yyNwHzU2c`qon>TB5y5Dif{$oK@x2_~BSO z8qi>iA$N(fA%P3i)Hq&#@?<$U$MDs9i&S3GEK5(S_f;>gM;Z?UMt+@iR1r(1Ol9ba z_y62m&q%rH;eH0WM+2RYE_KZ`Qm#yo_oT><1llpB(tM_b*iL;bIa#eVU{vE4~{ETec-OTtH_28AwCEI z0~Q0G5yy+&5$vnkE{`%|pShS4TzsaETW(L1qPu(%UZ3cN#)B-ho`9QpYVq59?6ruy z%w=7Xci9%_Hr)|c>*j6S%3t?IUa`EN@!wdaj}hu3`mbeyrYM5{g-$nGYuTg8t^J>s z;(tbuZx6V3F1Hh*Kz_N)jLciIMmtW~r_oR+pGO@9yohuS13qDVU_S+ZpT;9}oYJ)A z5jls|*mSj}85oW#Rg-YFDLgfWgiwkKEJXGF;(F)9HO5DYR0BYluQ3l0TBWiOf8_`R z9TxBXMV^korl$n1Po`rV75`F9kBi=&+P{b&2 zBHZV@NRtWwt4kl(Ez=wX{G|`n!=HJD^Smbj?+hr!o$kf)JCY##Evl?s0KCKLUMVuy zWXLsHx=anY8Jg-}?pQvL5Pm4#kf*&!(_Do4%)nH;X{w7b*I6!+DqX@$U_KrMkUd`89ePy`ftrgu19!knmn~d ziMoJy)>5QNf@_$;H3lWP2^zJRtJ(`tsY~>TUf2_oRJGSneO^K{f#Viw+6u@cgT611 z9(Lp58ap__Uv6&^@EkTcmCrlJkm$>?o^lDcR!6^^PG#{DTi^sGI+aSFIqT;!9IG8C zbtBcg=Rpyd{5*4Ls9_p5PNM7#bILFJo?^y10UB=F4CE&};UTiX%)xS{XBojsGL-2L zT>5dsy%(UcrSvqJCmV`?3u#(z&=S4S9Q5;M!v7aQ*D`~9WxR>Bc)c=9HW5(mCD1p2 z0(p(gTor&voS)Y`R2d2P8iZbkkhK1CwVVspG9=1MQUZ%k_)AltwEx0Gkr0dDzzlw_HUScV&w zEXxT!xiHt|>mhR{KzU_NOCT99`{5u#P#{N~UzWXJu@)pUdzZBx=jr0-od4Q681iQN zxwB+@8rM*%iQbg8&9lpaV5ZIBsk2@#nQLeT^Sow&=i6ki99hgO$Sast`2a15z%9VMMTH!6TBo(&=w% z&8F70jK&~)nv*4vr2*7!RCieP%lg?6Tog!kfGAWMg&|vR{V(rLlHO$74~=|<;`?Np zlaOnM-`~6~-b87o`D;yF_`091yIwWzyJQ&UYpyvAS#F11MS$x#q`j!!k-*amuGYfC zwUeb9lO}4xBU<5QBky51qotm6M{u1Ikj17-xP|>oGPM~PRen*`pRG!wQ)g%dCS0up zrkW@9nCE&^q^j~nVtuj31XtxdO<%|(D)H2E`TKreqmXy-q-K4KcCWTi9OO0nI(iIJ7}B-!czd*)RZHmv1x;OX zZ^I_|CXM&_W%s?BdulS?pzlHFB2wK=Xf4$D|1AmCNb>2w0AO}$q}q|nvz z^pK%9{<~=yf7?%|VQ3~q`1k4aZ=lu@rbLwhWUk)h^NzLiHT`W`3uz92fk9vB-bO%) z?YE*Bpb|F(aX)LaA!$VV>rgS`GPH-f4{SHhYL`gkc70>b)@hoMgGisRf_W z#78XIx0CTqo~l@aMZ@u$aBUH!W+~MrN!8~7TrXFplCDO{R&_p}f}q=<($VEeFk+gT zS%8`Xw$dt9FCR`jpIvejLm0Qc&%C0}kW$goub|X(7)Cq%Uip9oL2A;yl9r$aIXc6X zXp*3tUl7zB1E{qwm#NsOz5)Z0ErI10oM-1rmpH%RV!eu?#AfraZoRz(VOdv;7iw#9M!W+V9z)JQ4*ynDEOVs zB?Ag>dSJ>Q^%4W#G&^ce?4N?u8LrRV*nqj`T83MSw;Rk&HJ7Ya0 ziQ24_T7`7$fi=7Jd0H&Gnv%4D9ictJT;?-X8vL=sPId8X%rs3^bi&i@f+|TG|G#!} zC>-BS)0pF8Yp1lEW$L6<&kU(YH&=tpbA2iaU7C$mXVWkWuAWG$oG(GmbBS?i+_Eye zclnB{1h`1G=PGrZH?&qR^B<(1kMY9uqVM{tPfE5umk>@%FnKT+N@QBiwF@dT!<%hE zjyGy={tU9`4%lxgwu20lavVA{Je$9`l1iGAbRJ4VwInYcUS6NQ zfByaj-`nlFUHfgf+payH&+GZPKkkPOA#NPdwKc<7zrBAVgZen{3Lwat2XofCdLlmr zEo4-@8c>rBFxUeQ%g*u|R3?ZY(E<6-R$|KcaEhuyaZcb?+ZEBjk9Mlg(Q)N%*OYn5 zZ~)mgfRHI!`fzZ4T=|vzL8Q<}*GK?z6UB%QPYpL77A3|CxL6ub%MBoKxraZE<2tx& z*cyfTQAn8!FQf~nA$wJje@}C8r#kGEYC?(XU|x@s7#0vo80X?%Uq%ZcST5HFqF(v1 zf##G~b#Rh2QZN98k%RHk!PRv>93&l$IyTD$MPJ>7UqZL zmF(ao%p33Qa?Boh^7g>mY{tJ1=LcuLx~6zi%hI#1>LK3`C?!~PLjcWY&u2eGT@`>L zbJHrBQR^&rr-< z7+C2qE}5a&!;NUb3YAW5*8hd4AU5C@f*|5mH<*BG3mz{Wyx}km2c=(zed%x@z&7{-J@^&8LkPGCm&43wrg_ZDc?k%1CJg zed`AtY|5UxV(Rjs}Z4_#m^7X6-E}+R_T}#F21H%MM{7CTcojEO7jF>2Ewwq z`t;?wvAcma2I1}8;Krk8-OW8`Uo<)XJ#bXZoLNJ=vIZTr-6^K8s5n=~`BxbQw}jrP z+_mwPl`m%R5I24kLP66!L9iFdL*lB{wzZ^a4#x}@TWoVEXIxLgQlj(rZ`$UV`sVVU zS3^h7I9__$^JoSWq}MVo%w|57{Zr3}RJ{LrnFxl!M-_RUiC1-@f}SB`$$os2u3WgDad= zGBl{6lr#I$CUO4q2DTAxbT;z|2iRTgQmWZd>QM?{ULTkxCh7FdnqTW`E4;X;wg01O zYWLWX_WqvxAI~KBwzZ#0T@)8#Oc$pw>STA{zjsz2Z2D;R*X&pe3N!lRBQa(CGz4?F zaQGuy@A5DdV=AQOo;5ou5n~K1j6Y+{>zt;GOe%&KF`6-aae+n*1zN0^(Q_1eFvZNS zNUxYM4R_^LiAzlyC-pGYLd{0_x?w(0fEz#HfmvrNqZFInmWdJM(&GO0HYd3a#b&+q z0j$-_@6+YhvnqMzR$Vn)%B`f-nBu=y*RB*5_f{)3!nG3U1h~4T@sM0UHWL17&y97T zJQVi!-XFm4J;>ti%GWckVRx)6Je_RH74ee$Zukr(FJ8NFW>3eo;hCf^b~-6j+V+5y z)c3QcoqSV#Pp7Y)pMG{v>EMO4hvpjYl^)1P1)j+=X0Fy|h*&J$ET>`L@?nFAAIr=L zxomLXgE^qoh>yBtXVmDIi+RQ6Ou^_pN>L9@t|Sa#jnerI#YVjnwWF5Z(*82bAx?jZ4oqVJ zVnYnDi!_B2WOAk$H<;380+hyQk zRURft>Yq_k-oxlaIEjdVrk{s( z_FGM<1^K+>`#SZ0(w$P2WhiORX zVzyg4r63D8h4fp^Rdb@}jqKy%J_`VNE*F-$C`CBZ`ju`I3U$0V=RSlFzvFzp;Mg~K5b^_0iizRED>%`1m zcAi>(KuO4DYu-7@MdI_C=MJq63bVVK4*u6(_`Po|IJ4seiMMz*99p8-4J#qZCZDgD zF%sjCvfe1gB3nG zP_o=yYBIKZ{e1{la$~eAvA;V;_?H}{d^+IksF$m8GqgeHOL3V)D-+;oB1j(-MDD%f ziu08w*x=S&jX`FCDU*iTh1#V0MWy}BiAp;wSrs;2>qgTX1PW}FrE;WF;~JU$SBY4y zhf}bhD<`_i0L4zt{9Okrt{!}-#t;F-qo!^GcZy7T=Z(Apzp`hDK*UNf|a-irF{sPx}dzl&RBD> zSOhz}?dX}2jXrm)o=V|ig@1M2HQUxUbl_8^{@=s;=D&o#ZcD-I z4>Bp_ADu()U$7P2J&eQup7+oY3E&pyVq{Q)2Y&T9%vhDJyMeMvtztC~>TQ9d6Z)g} z(P0ONn@}|VQMc(|wVIM8*yGOrU2PIPHid%wLm)I~eIolHrO>>*!F6j5R88;9u>wkQvz4FPVo_*mOfDk7X^ z!A<_q?OY&=s;SR(ELl|aW+_ywpHgT{*u8lxH@CV%6?Oya01#UKFxweqT;Iyse#~es#s}eqqso(pIb=h$csJO;yBIX%( zxyO%M9m<~32_3%od+{57Imz?Ddx)=N2fG3x(s_DXG*21>k ze0-y7fP-+z;k}8x46)N421Yaw=5{%Mf5PD3~vMv^%A^Ngmvt3&se* zgY+wfbZmtbUP(dreUdlvm_m`Z0|j|j+Sx(T$zZ{*v#@=FtGIjdg?DjZ@{%o^Fs&l( zms2raY@N3a+DTF{LEiMx;o%TcPivXmSClVud1zSb_g9a)=tgZrPaXRQg$1=_LG`%h ztzxZKhLI-sMz3t8gZ=(;(Brue2R7qL9gU<`wr)RFcS%fw#*(RsUUb!gcA55k|>D7Qus?Cw43WpV<9pr*cv(`mj!Yl+Lu{~VitzaLLO$7 zRM2%h=oPg?NW3*y~v{jeNu{Ul@`}YvE}-)UjUtDwC^kfEEIvNX5YO8a3WW; zu;C$JrhUyDtx<};k87-xEI$d7 zJtj2+Z$|+hfo&`CTZh|~JgT2i4gr4lpyff_UN@Eoy4{Jy1u81(&-eNbyBhEMF%?n z2KpMvojj6AN>mTREKgwvDZ1PWbd4W!ntE~-Kv&Q)gDmtafQ?Zy-bO(s#h$A1(Xk=8 zy`M_J3?dvn5z2#W$fPv&R}4(A0GCPECwLlFNfEE7pm-csS}u6oO(hKm zgF?0;YSiXl%Cbk*zEC8T#xgnxwfh?E(58Y3lF-oj?~2>btsa_bX_7uS41WCH()!dn2`phn~*0Hn~cWx=w^#f^gcpY ziaISN@FW&JR*Hzbi^|LkLVQSQj0a00C>IDUf`#gA*S3S`bcnDM48-yt#5jP7TazN* z@^tJ(=w2=|pPri`bvrD87tY#8vnDH8C@G-R$@ZXfKqnSB$&lZX87y=;9n((HdCjwG z-|g!_hqCC9yQ7Ba}U8=fq4cJ@!{tW5b54M|H>(jdU^0C2@s zgqvdQWuETn6nTk_4NV^B(shSLn;Rf#0sZxSzUx^!n%lV+^9_*!s-@A99hST-I_5o9 zUbzv+MVL4d)JA~nmSSrKh-6G_g8y&L>$hkMNW)Z48H6gIO#w8fh z36S!+x~tSH30#B&OM8L`rbxk*Fw|SIwv=JkEk?Xzz!D((2_rein)v*Q$<9RftCNSnTh$z*|C%I+Q(GF|{?%AqI6G< zk%Cd*h3(Nmqz(kRStCj*Yr5qWoqRe2$WgpRNzh4Ji!mK0>Efa^#NTYzR@u}Ia zufzwyogN5jm92XgGrq*YnyQlrA;`DXRP|%7{UUS+T_=^EPua`XN~c)WY=li(W&G*y0%~e>Tc>bO*qCKNoB5CPz6A6#^+-l1a+;wd zqm zF3N?AU7dnoz6x@x&^D%kUJ%gW zB}n@V<|l=k2Be<47Mb?5txC`PuLIs?Q;e(|+p=$D=H9Tra8RqZ!RT;*IeFgD<9q(8 z1Dxb)&%jmAqm&hO7Fp+k{n2V7k(CahR|8edvL5d!S@q@Sr;7nXP&-*DCf?>2zoFoC z)JeB_X@^CmQQjP;~km?x#l_C)A^F&5KKz9hLS%mDI zy$e}{r%2%wROBEXouVN33_#S;v6Bs8AqATvK=DNjn<2)r5L6`{6C=t#t!#YV5|Q-k zIk^MwE>~Pot~edsX4-Zi)$Wc#%GkMQxfneN6?M(#1_#jCv@bPr7* zFR#i*>-uY{Pj@w{3w{tEU?2V3R(}9+v*m1`EI-)gTl7$ixF68bXiSgz$FGX0DJA}q zkqoz1+@2~@h?S&Ik~)LP9pYc@)O}(AClHXjrTZQ=$oJRI9LlqJ8|-0Szq#{=;a2D>s(zY zI>L#*cQXW8-CdJ?AC)eJjqG2D79@op9BErTYAXdzrKU%IK}|)ppL<{w)+5&G$X%zc z+gwgHop?0ws`J9zE5HBZv$c^sV|R161ZhFtJW+pi-u&99+_z6XxM^=n&lz9(ov3hWvmUk_I-n zUlnq7{utai_W`k437I6&wlPGx(cvi&=9?<`>o{$v-H06{pXR8TY?kgpDY^R*B0SNK z&(cYkVj8*NYc_Ub>Lizi2o(IcnT1FfZN5AT=jc0-<=$&tFkVDX=F+3M2#gaL@Iu>* z1ygpi)@7aCqt!lj=p;7h&Y5RgKW){Q#zW%b(1XX)S`+SLirs6gE3r|1}<^=>pnub@EyAiiPFUb?jPU zur<_p1AV-Q$1M4Q{>&`x6PWjW?@i^koM zgwy?X;%TTAOZ8`@ih>{yWx9oS#}_ z=kB`K6XpIPa>s|{)0q?IxgS%a=ar@edZ%;N@~>Ts-s3*g{BvI`HC0fai?F2jF7Ozefoj~47JTBM$-;X*+M`+UhX1Kqc$8PLDO7L#LdKXFL4VKjKwC&Sxdd<3Z@GBK+d@^mwegQog6pEJU%{5c z6ytOvBn-F~lg~g<$^}p~d%f(WZG!mj$!*c$ExV!)Sm@(+7T1@=*Cws01;(adE6}Pt zaqZcQSV2k2#F^9r!&AE|?FU34PBKCK>&m0TZK*vLwXfDvi!uApH1L<=$soSj=Mi+$ zPh~Us)Q-8yej?wq0-Va9;W|BaqvKuPo$%aralCrVW~W&iufi!()f%Q48!bLYV3sQt zs($HW5-{e?v;j8;_k`H>yHo~TrHVa41?$&Yc{mH>|It_zc=?1s%N%d~pFY{3($=it zd{t)3H%~&8Ujq;4)Wzz@F4>(JD05b2d*N)!@PXS7A`yV}N#{R9$kBE&e6!DsQKVTb zEf=NfCYabYn4frI*9m+5PTL*Iv9q<7cRCDro+*jeimPC(sMj6eG^<&6z_jT!?I3UE z`Hr(D7HhM|n4;`Z>?J*76%gukv?P}V*@>1S`!PQtoLarVzrrXWdp=FFyyi7?xG zr>7_O?r@e4MlHB};>sDUK_Wtd%C|VFr$#JgtU}ePjx~lselBAmzV|&H#pu3f4!T-q zF+n^tS`1)}-xKbt>3XvZRDzc&2>j1J+K@`9m(o|oaC$Io!?qMAh-CDL-c5O_1y|#( z2Kk=-o8AyWMVCQ=l>#|I2B4yL33!p3eBl+8LAH71qbj95n;p(UE0h1kt-$yGn#WGW zM^(S@*OHWh5>Jg)UrK~!M~y4*qqje5aV&dKo7_E%L!x%4 zDhEEgAX367vyK8!K2_MaSg$D{yGnugS)g1yd=%aRY6pmr&LU~P5sIfB(9`ekAOZHI zu#xJCJc4ozRJA7$^#vl9_Z3ZQ)gqV^#DiJL0yP#PnBQ{#Ru>0uRL=AKgCZ}~i4^rz z+1P*h&{8J>j1p&ta+wohv)@BCG}#!RF(sVxY!&`B1?4!$#mNO83SF@=8VN;kOBN56 zO+RE7Ax6<8+-sVj85uFm@PkukBGL~LBdXxoI=hAl!scO)!>18f(m){`02%#D5oG7;nf6bNTdm^S`#c&QbKsA1^p3dSQ+DB2%uMqOB( zf^}W`F!xEQD(Zd2;At+LPJt>hAy9=-%XB+FPieLR)RL_kpbN{4f-m#oc|)FPKbFUQ zi!9fS%+QUX^)Gg@URsc+U`7%}m5);vlwo~e#?KPG=IrAt%#^8ZD-Y=;|C*F_AXRR_ zsz=Brv~tbOP&~tjXN>$a|ISXo5x1-G%G(vaXS)5u`IB$G!XAx(wTRr8w5zVy)^V)O zHe>$W;p<&Sk0F~ZE-9%32WD!~8%q=A9LapO2zE4h^^%ykuh?oI`Ko^t`NHw|ed?5o zbXFBGPe(e`Q7dT00NPfq z3a=^jnX+8vehFykG=+@fGc+st#|-GaHO!XQey@Mn@V9TIa2sg9!pasH+T!t}jloN} z9lgi#aa>RX1z>3c9!lOe>ke>Hp#tdVFcy$>zv{vJT$}5I-d45mlO7t>kDvW_!1~gk z7rR*ZuhykSJ!>Kp!_jr8A9aPaw@hS&gMCR;1`5ty71yA<6_VTEycDYxQvTjqwGUO5 z7lIYhoQE338+Sd`dL4ZaVK9ft=wl(=Q3GlY^!58vc-l?g_w&@7XG?RqAf3L~EsX^; z>V}v&J3(*%&4F7-i?`AwfN~bIP%~eQ{BSKb-e*c<5dmzBgC zyt8EjodBNvd!5nKW%r+ocFgDJ%>Q}#?-5B*P~9K*M_a!`I-VX}3-fFlPgBU;e(}eG zxWhgvrGD!KD;Xp^gwmOA)2$X{xi$A-8^zD52TP01FP_MQ8EnErHr*MAeBjzY6)>I&V$2bw2^OdThf;*FNCDn~ z042mK8492b3Tzby)ndW^;VT4tIA3c5E#<5qLRx@W#a95|PCx|6U>iiR^)fJk1OAqP zkwTb{6uwQUNTTI)UCBkk9A9yHD<|CTfReEm5e z*0F}f?5v!rd&fCXHk3^g{b!5|^^TD2xOnanbAR^F{UvLsN{Z9TY1fFYa=C&mW!F_; zo`N5x<3B<`J2^%xgT=~Ub1ceFwvsVRS6jYX_<$!<@i_z_vT}0ThI#c(G zqC4%tW(l}RP;`XAU0B)sH?oWe95MZslLG`pUBQDfa1{w;3HRzx&3s8HyW$>Tv@jY7}UI>et)~p;Xv~#q@z2JYcJxu>t)V7?M7g6~@YPfc7 z!$aZTt=?LH!}gtzw5w)A>ArW?xQAm`^YbC z&66hRER$3|o=Ag+#^R@$VCl7TA|(Ac7fzDyv82NoGC-dReqq7B(g78Yf+t;(OsJ64 z))*|9s}yYB3iA`f=9%6>5-=75LfT;)1ky@ z{3O(ZWk90sci`@~{%}Zxm9EF}Q?&oZixP{j(Q`Y!rJH*JBhLNOpQ24@5Z{nta0!aO`}i6VR^=PsC9#S}z)b zF2YnV4rt5*mxZY=bS0yLTubh5SHc!;DL^EwqtdbmFKk!h0=s**XmGU7rG*`9@Gony z*_OW7wbwo1V@@Umcd+O9wk5vS{k=QVjl$O1RkFicUeq3$-23t$#Xf(-=rFr2^T)#u z5-VCOnIO4)==`>s^II=evZIpuOT-baz|+&Xr;-u{2-Ka47gF(L3g{{WbcC??&^4$Y z6O>O?j>Z9GI&7HT(sLx3g~hhx1<9~+(r`@ zK$8YFU=`{S0FUz9@2djs406J?XFz3QWAEcjZ8>}t3SO7MucpeTBXT$cpkCO=qq2^iH=Zzk~V zJ9rl2A4J0>{BbJeP57C~OEgVm&loQJ8l%IwFgNs4jFylGOZegDmdzgIrm8RJN%i*^Jq z;6TTp3n3aY1qPG&ER9YBQNveB8byZpk>Uw5$b>+_o32QtfebqAtAs|Pz)YyHAPVR% z#QPJjvLWD{1l;u#oM*yhG+$2^?57MC&hLAx>}$aUGmG5 z+1G%h)Sqb>JN!of36_k5I$YNG=bxtrlDt~_0pJQQ`Rbzmx{iIPB+<B`T#Hc8-0ibN`9+ z+WgqhEs3Mg4SkB#|6?XyN=!^`P-npb+(ge#&xgN^l1)qMe%C%cdNbMg4Wyq4{cVJw zr1k0up+V^{UdT7_Pu8k3{1=G&_B6!_2%sXtzohuQBEY_g21o)m)n4F_0RNGKAVHpw zC*a)$umzd22Ytv-1}=#dZDdg4R(-1wgEy5>XBmgN5nL@FG+}{$Znrbt*0~k<{qoD! zV5%E4??k%Vxn0GL3Ti9HI!^G$nm^lodfD{sSI+5?SJQA-*XOZ?+T%yccJfffHTtW@ z!Arsnt%mXSV0^}rhdK1kmp(j8dgTB2{q1!RwX2%Nf&B-Fl1ubcHrxx0H*3F75nmmG z>(Br>OPRn|@SuZscP~g2UJxzkanJ-U#&O>14`dt3Jh-ldmY zQeKrr7@iw*e_i_|Of4X3Rs9j`{Jrh3qg*~53;7^oA9=i?}?gOM*aE z2s#RqYi815{+2?L5csqSm=q|;WPqs2_=Lw2r zY2OKbm>(auyHEF*o}xz@D1Hci+v#N`NB{Xya}ks(0kj1M4v=ZmmISIu%_Ja5pAQXJ zhAId&up*m&?(`%^Y;k!ZsqyfyS1&J^G==Y4?#x+ib>4YKDW|mf3^!rsaPi_|R1d}C z^E*?Uj%9TPvOCf+aBLiM_su@N=(L2 z#|?Gm=5ztj5F;7>PovW1ZJ-8WogD${vo@&44n9p~0T#9CWKVTPsn*Qi;Rli-*qL;*Qg>zdp>kok)WA`OGCyC!ZCPq z#IVfL@AzM2pB}7o+(4najT`IY(B@$r-c@wmw#c*GWu0H4U)sG?PglH2#H7==++w`C zMk&YMa zyCVqf#N*G~deT0Op5ONT%bUY%{l#kf@!b*D?15?%(#`8BFJlrPDq|f|BClRK@+=_L zEvsh3K*@hC+lQ{(OtB8Re%%$g$eG#oK=VJfN6*i(Bo$#rvlmxrSK=S7nZ`;4VsJN3 zPJ<<6^R7~gQp(L!8anoA0velI}r9E0tN<$5;Z-walSlxD+*=Y3;Y8L;nt2T6_IXnN`labq< z`FqSQ0R25SL$B*TpSvS`ZAQC#+dSkts}z^IQ zM7^JMBzO?p=!(z9m`8})u$B}?fojPAQcUVFQ^pv>EJ$ujzJO7ngdpmnjBOwcP>VAR zAtl?OO7e7usYo(ukPa<1<`>7*@7tmG4W_Z#iCu{23L6Rzl+wk8`=g9`1zHnLz!26+ zBF!VjH7kLnv=lCY>#-5T)I1Udr|Dq}7XzP8)~2%yH8vmJ__Uh0x6?XJrOd(Zzv;aj zht}fEI)a>$3r^Q|i40n-%nQ)7QyvVTu2B}v?Bb)BcE6WK%GhR`I>!-v5xGdy6QRzV zst(~@5VZ4OJ}%T95b@eQyf5E`YqpBU+AU;CQbpVok+y=DP!ygyt2LeXz2*rdA7`iO zQB2Ji@Xi@SLp{(sgOLOn(osgqqe@FY7Uy)xrV6y86T}F7e!>(Cue_TF*NC7~;dr`0 z?2fh3rM7D=+?892Eq~abueKJ($VUw+r`%`fkA3biAa(zn*&DUdTvH$L9Fbb$ui0#aNm6JliOqi#;z`Cc%;X_sbBp|H)7`RjpRB>bgVTgh% zZ5BY;+68+8lz_QOef=k=@uvFBdOjl7pq63ezwVIomyY6_X7%RQx&EhP0tz)t@8Wmw z`K1%%FzdEH2W=f=>a$Y)+^{+a9UPNhKiuqCyCElNS1j)6&L_?1%l@5V?~bBBBVQx0 z*k4F`>i;t1z3-h*PEtT!^UYdcY~80oh?&VMIXs*ORTGG`*Isd7!i6?@3c>+-Mt~R* z8bdJxbr52hk$k*h z&N;W`z|-Q*ZFKn1Clf^WW|-+}9E!{*?OxSy7=?^HfVl<@T9(^2P$zfUG~M#r(2jMDJRPf;CG0}~Bj^#8hrU7&tx%i6EQN0|6E`1i{(99X1hH*-^+KLS zDL}|lJbki2yz*Cv`H`?3_y#&30@?rk1*}}@8@(qo|_q*|Nbl8Jl9?px# zQ&`MHGABjKLx6`|j0t|86v18%RqPv-!cAyAZ0~Qp?mSn=#+c#V_bm5L;wVDPFHEVa zQ-`xz>Z3Hgc}Ihdh(MzV4j*5e{73a<1a8LLJ`rPlDkI*|O*>;_T=vuYL9eS7-LuD> z9#$=xKCFFX|5bN?Ag=L?otx>rwZ%a3O!97@Gxu?Y!DmC7$GBL)cf~59yd1Lbcpv%a zy8S>@tRHiLn_A_}hVVlqmcNr9>c=C#Le0m?5A=7Vxe`3`vUPYP{>7RQs6wuNIzd{TW_SlC)8w*2v)uHK3V@C7i?fvH{ytF-H7xRa_M}qR-KHO^#|IaK{wvrY&M#POs@-q+>CDV%wX-IdEwZ!xb&>qxGobSC ztqBGg-bsImVDns@_!WtSA}CV`Y{-VlGKabCG6Ip0Rva$T?gg?0EeH6(*87&>0oQ$J z`pzslp^CZ92OwiJ$B#GZS|uTDLT*fu#P#~BgT+m<-Q5hn-PJT}!bEcUGSEq&zskvB^stITJfiWkyON6p;Wu~0vnUOt0%8BRD&XO!os>x>L{ghk7f z0dyisx&|eeo-N_jGAd_pFp6K^=&-G9N4w5)Aa99Bjcks>i#}4zo&5vn#dDZ+P?_*p~pT zI8`Ky3eoi3%pS=4*q~tig2~xkdLL!wJRCJE? zsZHWdmj<7y+*isLZ@*|U983X-BKyZnxC-dq3){MHMcj`EJq$a{ z+YKzLP0Y7tw|+YCXaagvzpv&|gvvyS!>go#Ym%eisg)-f9*)+yT{Qu_nCCvu4b7o= zm)!=2$n|8C`gDW(NTv1muPTX5F(^MT#a5nL53onB zAEaxOIb`)oh#H|i)x$UR=V+*NWADL{A1RmBiXpgG2-WjOzQ_8Jlw0nM@|dN2XGSZ zUcTp|0HP@1rX(OybH{vC0Ih@~+ngdL86-;tsAQ?BJ2l$YsfFI?42?WCc0)-J2|-32 zYj+Y5iXlV7k^Xkcgy+#0u%?=ks(S*JnW-z23-%|cR0^Xyo_V>vRM8Jjz8zj(btH3dRZm5yilnXTw^FWLCxb?n|gw|7yR{qB5u(IJN_MJ7GJ|Djp zcgElEZt%3L&fCZ_Goboe1Wp`t_oK7-+bb$}j2(7*DdYuIJ*e3vad9|a(5ro`RSN5k zfo$sL;!Dsj`wxzGvZ_%%%}9Zxz@<^xJoqG0)#QT(S!q1o+&6GR>2?$k^6Xq@xX0jqoZqs-3LLF+#14wy z^x`3=dZn|kIdbz6x&<*+gn1*pGz+g>c`jDKAQ|sXuP?JpAj*0 zT&Gak_({1|6f8hO#GXdqzV)y9)AwTzFV{bBcV2htto^s05{0twi4f#E9!2Yd`G-rX zB+~B}s^r8@@_qc*E*nDp39k5Eb)`!ioKTd`d>dJEnJDGr1c1_{0Wqs6Ldn)lWxd21 zbI5tXzr$-Pp$*0H!Wq<@(ZViozwv^l;K;sRs%I{KiE~J=uT*$pcJfv&S-06dAjhw`>Us3JdTH+u#-D zuz_jivD26yt8LAq+J)#^dmET|Yw39^>jq-*4G6iqB4{MZ%wJK9yU#3jY zAu#r8h3+FqPb}^@qGQHB9j9Z#s}*xjtI01FBs%^QhB%aGkQpWUA0KLW4-5rW%?7N)ESd>scYOb zkC>;So8D~ldAP~9H{7q=$-mDeyxWK^BC#KlLM0lJ&vl~TY3-cX4*sm-^HI_J9oc8f znl|NV`C*;Sth(b@1*3U9=`%rjSzYD30r{J?(hq0yXJ4h2O@x&lCd=_UQ?b+sENahg z?fbdfAG4KL(v_F<)R&K`ubfq0Y*Ch7Q~N$>`Bmb+bj$7QIqz@9F*5FcS>3Uvs~z8N zcg(lfe>_no&d4UTJ~ zhc$S)*ZG(p_i^AkcpS9Yyq^}GWgUIQBRthVjJ4j%wN-sr~+}wRalzytGpt`xZ@&y0P+0%_}XIrl{{@r=Gsp(Gb zsaH)!@4AkC=xzMieP#Ogtq1oXK6v_UV)WsxL?nCh>dVag+0P5#SN{1qzxw^<%KYOW zlLOxtx|U~}KY#5Q`+oBNQugH1;ZI)=FHPFRtRR+wREHd%xuf7Yke8r`Nwr zD4#rhcsxIGB4ww96@HDm^Va&P9y9+|!;Q6eL4^kEIX{2?{QmuWIN`fIdHuit&y&|D z|ChYJ7XIzvrfpQKpsUFXmcwQzF251Mmy*KFRzJN)CttHUd-~M({O(ZdhSua0z8@#A z+8(=D7Jlgycwp^WF66A>d*~(m*`eDHPo_tGxPIZ%iGXKc^Sa$$%)*m2e52a3JJB!< zibVncxqn^V>Lw%s>(QH`e2(*9^Yl)iQE#EBu%4SPGOVXi&g7`nbHtQNqDDfJR;hGpbIZ{ZIYM(Jp+c8RzQ6tc+h5!J zwb%Rgd_Ui>*Yo*!*gQiwctK>Abe)!;q4~dA+_c}~Jn*&NDa0QtKr~RqY zSZn`wyE1fB()-fl3K_>T6ZD-kvUxgHrM$LQbZPY3+~r?p7aoua<<|Spz{N)%SV=N3 z9{^oKED9d7{bdleDiI9EfM;2yw6e3U9*ORCdVZH&SN3=+Ip1ly`lRbm zk-i7IZMFHn&{%C+*k!M5^`(c?=}|j>ej}oYAc5dIHUyZdik~#grq)}~k^hKHfXOxJ z4RydhHU{5lo-?^M@4stxsQmWB?T0>BmGyFzt&Cor>&&@12v>fDJgFms3;H5rJ?aNJ z0gr$6geQ93iz(}XtH|Xjn(jTh|4Fzs|KZ&>`XZ{LAufAVOMOx z+FsX3wsl>0r)>Qs+lQvs>+E)mwGm7h##$wH8fI4sM>a35jtQP@OnfNpyRL|ko>8`e zm&8qUSX?eY*D?8XkR$T^#xn|Vu1&r9dph)FZ|27y3|RyrFy0~&T!{cd@Y_bx zOxL=nMtN>upM6tu|BAc+*Sbl1uG9MdbWGWQTMRQk3@Lc%#1B4I%QLgN&OZ5TH0fi> zajWDbdB56;oty7@%rutWxA@f@{tB)*a~)U@x-S5;->!d=6`s}|W_=yuYTukTbflK6}DK8*=7ghymmb* z^s#x;BnaWf$3aiF4`0;O&t7L1_oQl<%@oq^>CU{vtH+cLe?3&l4w7&V8@iQQ<)X3! z`#Ji;dIg(VTWs)Pgyyfp7WYOfmN~^SkczxL^%v^xq9l;y(B1G| zk)Aq{du<`@BUyIj)`&^2b)yje`nCVf&)3&X^-*xcV-uN7&Jv+j?mz-|w8Sg_Y3GFd zlx@!LXN~Gjk}{ja)EwOp;rJfgv1@UPhY3Y@`p3; zpo&#whN6@B^ZFC05RaoOx%rD$x<6;iJeE~*Pf8~f{*sN>FO{~+)!D*AySzQ`W#*yU z@0>|DX4Jpcg8q|}0-tisW*x&Y%GFK(Ev!=70^}ar!?b4EG6Jv{FMj{;^vW=@cv{Y~K82`#byv-)b$&x=$J|YFD2n4|$U+US_U6 z9WLE(n|GihEBi-Pw1;TX+hu!##&}`6bBa6xmOAYz-T?`(PiE2L4Gh9YqgGot~vXVq!TIMz^ zD;a0d$#u$qu zEIrK%Yg_HaTx-TqFdeqY`@vgnS(AU+BB9UW;nr07Ehn^d%P`5K3 zf3lYS`n-78{_4N@HiY4F{h=(*t$ojH5%$D=o9Q4d;@>Vn6=#DGpXV>lU0<;)&D%8Z zW$=Ch>GY&D_i*#1?viNEY2q(S zj^fjZ`=6N#UkwAoj#nA!H{+3?#}YPTKbC1W0gH)o?V9_$*t?9*?;WjG@FuoSs0S4I zY(A225ya!@yLFp8=jh~)sqWNm!nIjROCy;n*B`y~sMUONH*bcPduy^i&Dk&}Z;poR z9F$Kq{qh=+GbX@l->Iz@y?DIY{>ks+cYU+`rzp&6T_?Sd60fDO+F#rDJD4lSp=sEYKwOJJboN~y)m)7 z#2!q-Bbf+m|?vWfL zgE6|ze_zMXwntsQ#n4yqd@>KF<}~R{LJTK|yYZXd>BYYnrk$SM%yX>WduzoHaIP=H z-Wo$(`K({Lt1T1jW~8q7J|@Fu%oYP(i+J&#lHnxD?=qWyBpTy6hrBM$g?b<93`x1y z@7oSEH*k_a`DJ9RPM!=qmO4CD^t{r|%5wa|sXtAZO?*QFhF&%meBO9sxF!1|EPFTL z!lay;@QB%He-gJ#_fAz?9&7ZSA!kxuD%e0n`~_2;T@217KXf7l#h(g!SH0ihzSHvJ z=Oal*4WokOspi*XhuAv|q#=hrTgML{nZEwK&*PCtL;Hxu`+v{<)}1O}ZN z^&DY%3}@t~q~2aV9d+m3b^WoJ<8>V>i-)^Pbfz1kO`1fx35qPd*cX}I$9NZQE0nBxz{tz%T%|aD_feR9F(?v|4V?yPl;6+Np zE#&TD+{roe$sr+z7<8iU{K<>S!D>$EtNoZ3k#Yk)tj-CKzPIinH)3bA$33#LmxJvjcB+M8&^5qT8m}u*i zY|lvwPBG8?0S@CFFe7}$X~vNsQ2bvBxa!1xM}U-gkX9SmSrvb{e)EXLcXWaKM*=Pl zfKe&fX&m)!pJ#Ga{BH?3+?Fvy$^0Tcp|E@w6$4E}m=^lhv=|8P7rK&!`AWci26B&G z0EZ;tXGZ3Y0g#2?J;XdQAjFiCj$T`r(#+3lp`UA#VCE@_-S_bJQ?#edRhtF2@;G_Z zy_Upv!Pwv=EU$b=qjR9wg#!~z55mK6&)pB!Owe~G}c?{S~oz^}_W$e=SL%(D{^wn&KmGT{(zp zCZHP^E;mCa(ciM}LzX55G{KUR(GFT|X2jPCfA>TzOaoIK95}uZ+0A8+i_#Xz*eQwU z#K7SxG8c);8xer-$e7?07lvZ6o?e(=3yOmPb%27IUWLFZKIU5?coo8akQ|x!JFX}J zKltVL;kh&Zxyyo*WlHiV)BpZRa_6cNy0q9|gy5VI?7GQ+KXdII7xRTssC^0i&m4mD zFu!i_=Cye5XCTy`(BvPxW`&p>KX%=Y-Lw4Q^B>sPhcGrl=oTTmLA0$Ehjs`&W%E#Z z?>D8d_ljyi**qd+9}%tyrAnT^lqLv~K5yf?lat3q;EN%!xEZ{U+ZXvLXZH8mDN*sL z093yTP7AT$oTEKC*aImb{y6v!0yPHnmWAMw06R^`D3R0uQZOhH_MIeTQV1$iFz|yI z?To7tfA;^OVE&RTep4`v<+Iye*{h3`{4OoQ3G*B8B$$tML271|Vo^dfBR|2Fr&N`9 z8kNW2buu5xH7qJznF{_Q%xWT_I~m{{uE-=7-2k9XEYOTeyyaVLJOOMoaP#(qoH%v($T&NtPV5T5&@*rja2kU!@9lNZ^^uI8i z4303tx6(qXD`toZesry+Uj~MOtJt7pKUW>4ltO|Fc8< zYr|5EQG0PlmSF$J{7;nNbLE%RE(_p;`Ty0&W`6>6f-_Y%tiY~0B+o!^V$>> z{{y4uhn^KE4=wn7pkoxt!ruaL#O3y|032X~%S>=uaQlN4_#jlo60po*P=>YaqvXGZ z?(8`P4$#53%vwbuc2MFgtAkRcW10@$`ROV|1l;JIeK1AGyki!>-dJhmmp>rFd=@;& zdIHYGRuSt#`90`sml9_9ch5Wqo)*htcIOi zm962+*mHB&bT{1I`}g@29h?(j`z#(7EdWQ4VfzH&TQb-uZ5V*ST{1#*0QiAla?0{S z^4#X-YV1TT$W(qbe6!>)zhrgpMvzT05p&gnqCW-6KLfggosbqT8g(#y9Xa z4jZ2^?1T#z_7=2y-=JM}jBm`)B^>YAgNyGa`PT+PbFJ_pGWtpGJyF%88pqcR%I{mtj_LH0!CIy z(hTg@i$%}V^FPtcx+Iu3`qOR+x`qC%3_d zpkL&ax#)HA#J10v+sqx5U38w^V?SH>AjY6_>whHd)$E%S43^O)q=e|B)w#CK!QHv4j!Y6`XsN8>ottYb-W~l zuW;azl~&m82YI@Z?|<9BSW0rAqObn$?OJGn=}Ce%zsNsb-3s*wfsghCVmfk!eH+#8DRQz$a!PfdI)&uOOKkeY7MF83%9?faQKdQ93Gr=+O?t6M( zd8aY`wr1wp@0fhQ%wZ9@NU6AG)lXd2==?+n)y!p8YOmhX!M%IizFLBVbnuHC*h@w~ zID}3J!Mvu7LHk}MT7!wVu^-6bkw9?!(-K7i=Kg2&8(?rs@72_4@W^cm92~OoXzCZB zAJ6x8lE*%0_xDTt;r|+2fsXf1Dw2@bv%Ohe#%##n3YA#g?T zu*rX*;-zeHp?k>+tH+85Cq1O{TfhmAF{cppTM35jF{bqSgS@_^lMY_mH<;qqu-**vU zZwX*C16`UqJt&&49GgD01&pI({x{P4bFTld;9~~?-7P?;0Fq-XZyC9xr!lXly5F~w zpLUbM+OCPyo39_!_QdOg0@~5XXXZbOs^CEJvNQ7zS zV-WvZf2@4yWp*Y~z(gDvuL~~SMkm^U3UpaIi0Nj$h{u3OKrj{q^5WjF?ZMuA{^-;y z`jxb^TZrY0-k-esb>r8!^Uuc?ZljN$Zh8Z~dDMkY1Yaf0EvkD;ls@+pP8NQ_ zkRJAYH+kAG89}|o^e>2%t)5mEf&CJ+Q|jd1+@@m`g*MT)4u-;djHCN$yzf!v$8=g{ znzB=o@`C8-OFgXq!%Kw6v04`~O+s0Eg8s}`Mt{cGjyC*SeG8p#>Z1Ru#DE`GMaW~g z|9T0)lqGPS41SRQcmw==_x?xh9Qp$t?4>mH@V~qQzytv7fza)A@S+HL#7cp&Wvm_h z{?Ot7y_TYdqtgqUoAh7(28f%b4(!fCt*5?cr4F&fRr><`&g!i@JaRMz<=5(_Nus}GUD9j zrd)>HNK-ESu3a^CcWC;$x0QwkQI~cfy&P2-BJGGO+5k;cYyN1DA#R%wf-Q+d3oW+dN&@t zdS~#Z=qCr|va|S?f|D~3TnckE=HgE@Soqf9E=L_G2_H__P?&tu7Fnnk98!UIx-_}D zJ7%^pA~#kV6Aro(SdqB_hIfq+XQm0;wGf0%U$|pnCncBkJ8H77rTVgwYTO{yH2UNt z&j{0^I+$?Ht&HVm-_;ve*cQ8TsD6A5{ce-i0`5)W)&n!VPm@t;Dy{gU4~M3=d;bk- zeg2bCKID6Yr);=>yhW~PUbonh&w)prc#j@w=?7Ng&sel;e+2^Z3s0-BtA~R z6tZ9IXUQGj-A=vV{Y2lP@ETS|NpenbE7=N}6M>)Ha(KsHkMcOWQuQWhDGL)~U zdAVQIL(XKCoKODQw9a;({LQ~r)@DSBpf_ptI{SSsOgMWXC5MO&<1%vYV$KIOg}#bG zdS6tyCqpMW^;ID^RaItO^Z1H6PADR$wkil@0LY}soqxX9w*~oIYd#jG--#ACgaDk~ zjBOY1MJJz4UcQ4rv4|pH%s0%oHPX^ad}ANoD9Ra418vg0(2vv=9BafF{D=q%@&OlJ zQCfaG^vWizF_yQ*F)_$X*XEJ7OPU>~w75x&w%Xz3;%=yV>|K7C>-DaIz=(B}G`(4N z3O-ubYrVWf@Yjp1*2q5C7P%8V2f6;MANDojl`~N}Ri!z3sX4^xdH=1m(ws;s47>8_ zs($Kg<;72>n!dI;19?{o!sqku$M@1}p>YfYeF(oudfj!gO*53wvF zVnt$%*R#Svr=}FeQx$us!(2Iq$4$7HV-#P#+|rx~zzE+a33BqNxRSO|vH5MGZwznu z**JkpvEAMBqctj54@`YLaQLOZ{!eH%N9Gp6Qic%vD;?RVr}G6FKJzvAR3C(lq@Rg! z+x9lg7X1`|U0eFw;99P2N96Y{x4P)uqjla2y%)1i9*;rjj7hoc>cYT$h+}L>RPYO= zV00yrp0g14;%3-hB?f1mg%IhIG@-I4q{*LHx~J#gxkP4ru@3hocS9f+TbkCib$8R_ ze!$w^J-h<@s@d51=+5|HJ@vVXpH0r|5Vw{Fl`jBnpfuP|a?T?u;zvdf+|#y*|dN&a#)Usb(HCec1`eEkBNVLa(9 zc%FCE^-pbgz9Z&HikD8W1i7kxhX}4~K^QA7a6!Bjqep`L-vAjy4lIl!Bxio9lWTIx zu65`vF)3`m$i5ziVK!Im(|#id9Goz}RX!xowHim;J+Kc^Z>`8#?2qJY*w;4gYVEQx zI)IPWI%7NOZZBW_?)hCz`Uzi1-aW$&-J+RF@#36X%yyr#7pQO@!i@skZ^Af@%?mAL z=x%oO*?6sM)7iF>X0r~*AKV|@;k)mylYyzVdKH{gs}pS%v93G}%&SKjqa|GZJ1jsu z1!3H`&>>eRc07dtDesvXH*t>&I&cr`mLG}=+jyz-qJ@p`l{i9{= zcPV$r4>tCM6w#-zcQ6ZEM|zI;U5mH49q#uKKh%*sZ=;Alu|6aK;q{0`*4bOBHov*jp=H593M9a8L2teO?xcS9G``Uqb9!KVDl2Tx-@*xOZ3Sw%ub^o3^tz=A5ls zbl*JsSL@)Wv-UI7_Bx85qRcOup?{^>9&*kTIX#HwGpx4E-6KmM|C+6JIJ-D@qVTxI zY{^>6`=O-DRTq3ColBmcymlp|e|_@8(T}bQlY4H3JvfACX~$M0{eZpTF2Ip?^AF z<_dz~^N0Vpt+mJfc;N^xjrYHEYQO~|co23g-%+ZQqJNK;;kXa-VXsf*D6U}{P+z;0k;z_dmcK}=tM?*vPamZ zAUtAL-JNlAw{-56%iP#awLP{Mo*xC>+HFEz>x+d~ofzkeV_fvd*FU-cC`Q0NeuDcc zEaTs)OS`U^tz%uX7dCW>p0p#7ZEJ8}t{Y`!yF+CnpGfVh4*8sK@(&i%C2q*@8NEJb z^Q^gLS5)k2KL|e<((1&Nn|b5&iN0TIUM*h@Ef z|K%unb4r68*7KZ~b6z=IP|93`gYWSRWA0E*dcz&@j->Ruk?*ok*_v}~+Po2LBj*n9 z*LH*Oy~VVPY6vCkZtwUyQ^J!sIdrTZVov$>MJq)92t19|-Dlhppzi;5Q;T&F+aZNr zS|Fp4q>ZK7y0>#I&U?zFu0f~!Pp`OEPTiZGYE7Q9h=RB?aTcaO&iy5Cu<_!=N20Mdhka1D2Vypn$2y?JTdo49>Dsy?Of7@{g9=s@;n6+kB$>+*cu(Kc3T@6S&@cvwe{NdMi$+F2XNpqo0)B ztvi^n`*6U2s{2va;qMK2^@jbn@F1n41bBy5u)_RA!>fS`>kF>Esu=bjJ8 zznf}T@A9s=;c^nkH-KxFb8of(9ARxf=guLQgMaVcU~>Z%$!;V{;`c4qg9sLt<1X2X z+((J&-NBSJ)Quxh~`laYvnJe!;-S z$PPOhY8T*m$M01d-R(yJYzT<8On(_;!fuAWmcX%FVB3lik$NMxeu#hjIGUo}wo>>H zd4|mFY)$AhWx~x!2w$F@X$nk3vgyPziN)W(tMiDORJv~|IEyfLtq<=; z+nh2w``t0RA5MXuU)|@>EHCzL~8Afu$Ho|C2YIGy;l55SvXUISYo}`mcAp_O!$UX zL3As~FvD}K@vIFvjw&g{`+3*ae`A5)_jcDcxHGmo$Iu4aZ7eOlV(=78Bl1c;r`Wje zYRYvJ38LYojQZHQ3L!iO<fK0LeLsaMQ+?lXzUyB5dn26vbko;=JC1GXd-7nq z?jPGy3YV$V*D}9Up7}y1q^UCD@D#XhA-O3);Q<1`CC1fPl(yYjx`QES1#nEIGN1vJ%QJ@$gLY z;kARa;1RYmfo)fnW+q`CLO9P0nRQh~d_U9{6a_ z8EUA(lBvzo`pvI^uOD5KI}SCxtE~NYyA>`|mRq(h-PVvZ!=-HuO0$O8#xWsA%WShk z_KsI@D?Us!1=d``(h|<$Q{?;!vh@&I|fot*D@LZN9#L{5G z)|tVy`K-0=vJuKbM`E?xXI)?HU3q&PUmv~FFl|O+IXklc^ZAn6znf~t@xEk}ezn8$ z%EO-5?H!T+2hR_9-@m%*meRQg=ja@SP?E~YZ$UWHNPdfF@J=)RZOXvLG6uRpxXwlS$s?eb$1 z#My|J9Ph;Z$;#oU3!7_!lxYn%OL`ozk4Z)%1d|$!SVzF zCYZMksbnf)$fM6!(VK82JfTCeto=jAZk^nEtNY!q?_}Swx-_6~IXfQkAa&tEbM}Ap zcboP9bFYx(_MFI1kKWBQol@BqQrbe;h?9wX?CT_cCTDT57Io`7oR6~Qrq`TRrL&uQ zz0_!ff))*0JtbXjL%ZMzde1Wo8$5MpyhYuRNAN-$7f91vQ%~CZsN0ctS82XkHyeT` zLc}Izr4|A%g^^?ysu@GyQx#B@Yug%7hG{-mDR*Jict`@5_Z60pz#o z9ibs&vx6HgP6VrN_ovD=RE$D$$}egqaCMs$k7jVA1KY3IQI6P*wTq*A6E{U}Yf*FH z^AD(Rug`8#CW{st71qY3I(MWV{n>KWTGLz78p>N_8;3gEBCf;7S5~Vw?2DtG^Z)p% zUA00txKC9}`NC^+tq^0|0lgS36^<9vjR0T6yI8+6aq!rurjUAhl%{pq+Ksqk)rSIE9z#?9vb|Tq$6ou`X=a*Z zm7H=GBxk5LjwHo2uT(Q{s7nbEUNLD#x-1?EO-1c&Z^V)kP(*sE@>X)A+A{(|^%-Te z&J`+b4~~N`6v^8U7Isui(#;oY38vo~X~mPeYh<1|ataN9E#v;U|5xm^7=>>a=wC`r zLl=i*@%Zyxdmd4F3r=3YhmJG}3Ww*?y>tw>v2?mtA;nEhIprKaUuXIMyO&`~hv{i5 zn(=oTBi9oeu^M8OFQ2XKi)$oeSSUQ5ilXvp;Iy~> zWa_wl5`0McDjiVig0=+Jn{`wO?yY@TlcLiEN4xIG#9OiC?1HwG%c=X~(dXQ(&R>7s zu%P+_EvLMf!Z|HkkW(uTS3FEdn3)1>&0?`?u@F$(REg9Zk=m|>;FxmJWt}P!@+|2c z#zL4Cx;(D=+SP>4d1m^!0z&(5#X?5R^&q(u}=xI+JC+Jye>&dQ6@8}rP_x456&5-TliG3XJl@+ zl{flR*k`;%aP>=x0Krf3(k^By2E~`64;6YFUBz+i+)Gult`W*-$nw^8fPzcC*jJg7 zxiLl>0#L?svSR7yv%9D<@H14=1s9mSi7D@FM_)6}-&X;?JXRf|bfqR8lzY|H7C16)pNhpY3tKKJ(Df!N*{o7>)xUmX z8!CLbKNXM<+n*&dP;rH{e+ZdmS*e5%$ z(@vMyj-dwjwo;H6N9497m8meuUfWF*5caNOMQ?#v?R6Yhx3=s0-s+*8WG5Q z$FRUX1bMNqSkAF(x;vhbc7M;G#`Vi$7Zu``9Zod0?WATR+BVH#>Ig~`$p+bpcLyFz z!$OK-pn$MT?a>w`dkPG!r6APvDrSu?ipPaB=~^jaU4iYZY@@-k%0^bH+#Zrx!vT)8 z@{WF>r`63|cP^bso=}MN`c6A=cCPvk#u>yM7qhe3Z{r>DF=#Cj8RmY2-QdVvWcaf3f1=Y#MEsPZf2{? zLZdFG1X8(wfub(mmly(j9V6Ef$kJG?d8_G7HF2hC7kVqmK?<8#hg{gk-mIfc7)l5{ z?hvgphN(&^MR@i;59;)1;PN&&YJnmjL)kjiGW+1_nzC~?eQ?WinnexGdWvl`Pg8@# z<$kklR$!LEHG_Ih@;_L7t7?H*cbzex)__b z1BW8W*mXE#xVhS>nj94az#PZ-sut`q#EGN%fD%unSOPl)b4c5{k0bHJMsM zq0V2WSOkWMK>`CTrmRxL3OSVi@m3YwRZZE9%jHEyiIodr=twF$MBFNR&5fdJg~(~3 z#D?y)BVuS3CMQBMVOj;$H8sGyOmV^{xXdR@RcXXYC^FeKQH`eJz$V}u4P^{sp%xN9 zV%$eVEQ)tahSt2j&YKFhu3=jQmRirS*Uz%8`xa!|9XGfO3i zr8(1%DumQTB2{-5QMXaU2R7@_sDf@Jk@lGcLGp1TAPD+jAA9!ob&uqVy;GOxZ?G-u z*w*v#`G41Ko^40?5ZzZ<*8F1g6{@8!i!cHZ2~@)ZqsyN}L^Ux^C{e2s$*^-6HF0oy zM~^%eTme1-B`)bZh~BW8gizcdfVC=dbP=1$SbufpxCP2;&>9@GN1Z8Fo`H-7kg)_v z7=aY0l(M@+z`zLwIRGUP8C%^@^rOY1#VnJXRs4o?uOTao=B_#sCXhC^j%u=+N;Bz#0-lLLrV76BfTA}HOr9 zm8yd1;JOsR3P3X0)#c|7=$r3dXtbGvTh}yN)WKyNK<9>O>tn}v&%iZ& z$3sM_TmP|2O;{uX)yocUBBiL!WaDIx8x^?E7^E@+_5A3sr0zRbtBqL!3{m@tRocJ& zSsRxqm<2#ZWc)j`@yIj<7fHnw@5Dr+HJab!1cpgC)=CJFit4$w-fHE(uP_!mh1PCB?zebcUm3}W*F$gwZOi@b}X*2`mhayF(|8-gN z6errs7O$cL?&g6b2E zqnp+Gpz|?pSxWC@S!Be?@Qu@vk9|$$Ng}u$1dssuCb--W8tnD05A5{ygN+s`G_!KJ zwf8}_=+fs)wDt6xHY*&P=9ZA}EVZlb#)~wgLYhfnW5}rJk)ikkWRRc@SCWhGU98x+ zaZm*cB~FR34vojO;g~oBZoI*-g!!N20M?tO60^f76^=o(FjA2kFuTU#ym}-|4=GlF zcG0UTXND*T{9wvS{zk=+5+nj-t#ql7LX8MTVJVU>BF;dFB1j>XB4Y``APR~HyugVS z0btrOck#rsz!ZwA_P+mGKzdG z0?{lqouya>UHK`(IM6U55FqQ_lM}&E06eJibI05V&#VoioSP;xn4F1M?)D4-NjP@~k=P{1H6kq2p{vW$fn6#UqV&5*)K zprQ!S2oi%yvdCXd!N*aJg8(>>lGOmA(qz<)4R|K&=|V?Wj%ZC61_(?-dR2@@+ssrMZBhpf|aK_yB$%A0~C?~zH2SK{H(hp(f$6I&HSY5g*IdIUnl_TYLxu~Y-^50*TL-anECv>S)q*V} zxD(MdtnlWSRgp?yl22YP7Qa?N2`W7u4e;R-@nR$%Uwo zDF=i>mS;?UjERhK05X-LFk*(>L^Hv4n%@CX-nUUJ*DUV?YAGW5Vv(93OHnX>Fpw3z zcM}i<3^zh5bs}RDq!0)u?AeMDu ziV~pzNU0ovlOVYB7Z?dLV#-HuNN)N}v*cBHe);AZ>*#sDV*O7e%9q9h!W|A$%hFf)VXwKFv_NNFw}pX21XO0gBsQr!qfYsYn&bIGqcS z;TOQbiKb%JNHi9k%}@;AQPc(X8hm3}qK08sBL1w)wk3R)0A_apwK`D=H0xdhV5)#K z+u_J^0EM1bN~6HkL_h(BeiBlcxvet4Q7uFioeH2J5hhPGdIM1KqfuUqMzlq!W+=P% zhk~vezF9;z$feGAWOPzil|=v}j0&QtMo?LG>2kvVC`y481&14xUzis7n`hmKx!;`g zDruI|Z)(+WwH@a9-)I-N-;9}SGz)4pGrKSVt^82v4L#G))0^5=EHo>W3X}W4VOfQa#RyCe2om=7E^l?0Gd4TM@=tArB)YLLQ0wz^P+qKjW| zXBj&mRxA)H&QM^wki4#%B3>5QD9Q{mTAHg+CsP02iVCs!@@5=MLJlh?f_Ru(p9mBU zcVAhZmk*&R#EHWHk}bZo++KWpaA^0#(1%f9>pk5*d3qi^sN_OvxVru))hw>jEUod< zWQ-w+ra9+mh-Ulevg0QEan|rl1~g)qI(GS?*9N@q*V1cCi{A`sJ_y+6X-H`Xzy`9L zcf-|!R#Zg=Y69m%K>Y5pIhpOW;jKumc@5$!#*nrCZE@f4<;Rx=~vWRHXLZW3`xZJHX%FI#= z44M+D`tS<0EXs|wUYDikXxYRRqP80;DOx+^)G(-&G!&NTo)VPW*vwNgqZB*amhnJ! zJqIRU(3D=FZMtXVqH20mhP4sKkS>CEYAUO_3VAe+&qwVY4QanA(q=WQ{f()Q!*A5* zSU50J^X+c5E^E7Y7E-{h;yj6E4)Tn(8L zM@c)HOw7{e1|3evx)T@>+?x)|SmRBOPuKOtQ`2x?0>ubT0Z_`p7~d6hEvl=+&goE= zMT)Ar=cW`j4-3m-=ok^4i}7?0qX&dl-RDl!J*D-15emk$ZEDEjN?H{-n!Mg&=SUBO z)(IE_bfhypxwx1cl~-1kcMXPRJ|~GTtgdP;P!N0lKU~`yGk(x?|LSXhGf(HCsWsbt zZGBXBoSXQWu^mU$tloAKXyp57e}bv(@FPazXsX1PeH#CfnltoHY)Wf3K>dcH^iQGf zU6Yi8oLilbLqmjWtq3B?}%&pn{K#p=N0&C5lm+WiiAo6*@f;Q1PUMrT6a& zDs_0h2Y@R$DB#6uSl0!S3Q0GAic8$Wgem*OrTy|2o`npyYK(v-hjk!_A*~{DrI7BP z`o`>;1|hA_QaBxi#7Fz-AhjXqvUIH=-bQ(Y)50Hc%xu6ONPb0n{nC{x>s|vDXrt^ji%)1*C#Sl#g zC>-;pCy4a;xj*t7y|6;TR3`nvEuBsY8KY@@@Rf)F@dReQFhWBhKxGTWR(qvRO-=0U ziU>qhl>lW;f0{ES5JyhP!a_@*?C6j|I@A%YyWeQcPCiJX$$-TSKg=(|(UDt{f_%5; z0Q6FILp#J~6+c|tF-Dm9n5fb0CpsTS!nXp+#C8^nOSCOHOG~C4?_9aVK!=tv^p0U- zjD3j246L52$Vy4}AhnL<4}uI7A{-<|5%C;aB1NneL(dR3E!-IxC5?qBwQn%5<)Lh( z&s9=;A*GgrtRfDU}!b&_KNVIEUQM6Pv$+@v*7*5Zd-AbGZU%D)_(d9&&)BWbXLYV&cz1B#AWG zq9}Yz86Bmh_HIEqgSZ`l_!C=*wNR#L#7Mfsre+LRooDU)@JPm#GT_5vfs! zJ+{5|41iML{BYRNXJ>6cc&<)&5<+MKbRb9J1p=WprcLcd4wI| zA}#K4QfOly)`2Ae`2f<8_X1~^15u^Y5YwW^SWgz9!)5PBHj0erUB$W)JTkL4e6OP- zk0TI36uCgHl`AI4^T-x4V6O8rq%j~v*~s5dkNYCDmhKY5`NNb}o`^1ovCO5;N){hf zWh#+Q+lo*>1xF`h>&NTIwy8y*er#;HW8&!cF|$}(jX1wKgL5*ZnO!zMvK^w705>8$ zh4=`)JCs(VF=pAUO|JeJvyk_3y9cJ#1xhH5Yu~7*RDbCo=p^~!m(1NOr6tClXRra& zY|YqYku`P(yDoRQ#NP|SJflFDFPN)l$0AfH@MV2D8ym&bp~&Y`S`+RbrNe~=`%(p049ZTuGRe%*hFZ432?ySC@X&nOlr#RI-PODDwxE<|w$H&rfruf#5 zPD+Vl)WkUhpWBs1E#;jwA0IpUCkeuho@gj+X8wI#GK&czL58(A+q`nKi55(eDrfj< z2aQ9G;E4>&dPVx>m2adFmxn6b-(GS}hO~g19S4e^`k05wN?nW$9|2^zdyS1~)@w zo`AXxVMbHhr+_^3m|-+kBGTxFWoV=nh~^EW9VC$2loW3yXXCj7NP~;Um?~>J%!A%H zFXR90zfaZExTT}V!2dB0R$yE5&o0qP=6)cCB9Br2PmO&GDCc|nyL3+JPD}=D30hT1 z=6YLdeQWnI^ZZgAkvpP69w1so-RX&xj!-&yKFp{utGyaqi~rHlXCQ4|HFtGVh9XJk z5A(jTu`O0STZUn?u6Ry!cWV;GPmMz5{VDWRj31!)msLU6v72=}K?p z)$UXrN*!vvf3m8F{ij^H&BA}7Z&ZK`vpS6w2TxgCFW?27i^6I0p)ar;Q z2pIz!aLZwe@nQ@}4Vj_TTTz;UlF zsLCcZn|MR%EgPd`{%L6~q7(oF_+g^+TV=cVLWe?Q<+Lh-L9ONy!;)~hz-E;h><|wt z5#SRQs504=02ywR6#GgI9sj`%Qki$AV>nV5t^&CiUSmBGyl?_&QmfT5M4W3QGi78! z7~0WDc_G9*0GA>ZD^Ruq|0xMub}KI(KsN3`;H3y}g$oQLtYpy0C*-mj0xu)Cm?Dz} zbVoeunF)z0BwGo=_+GP#Zt}8B^Htgn!!25=y=auZxBo0FhY$NX*f)qLxUIGfK?dcO z&pz(+u&HmHmJQsNRZj1V6~`zs?3$dqocqJ;m^%G)1fp7p2_ym*{K#)oSCWzU@LoQSTkf6KcrCTTulf42HEm|~& z)sS{D`R7~6j)x48Vp@6FY=OrsJI?9^gwknbbsz9%Yt5&bEr*?XyO2Vok>wA{CGDRknmEX zm_*NHiIgDk1mY7eK_RDT3bAMCq;8l{LVqKL|MQh%x&;K_^xIfo;8r?DB!zbMb*gA0 zcJfdhK$Zz#$-Rasq2sx9hH_6VQ6M#W8Zc?AwG7}WP)DSIlBuzijwpfAfDhK91@Y+t zI*Mocz&?Bd>F~*yOdGC8w~(Ecd$3^Gf=#xg!z*S0LZxy_nn%_Yl5=++>Z}4`wwHl1 z_QVIBoS8zutw(atMi+16I7CpxPOvV8PDD9u*vRRxrfSGeXYeA}%{ki-_EKnO6k-T5 zqy-l$T!m@*ra;}QNG0NhL|7DmwTP(3rrciR@KlcH+Y|K?h&ns)XXu>+0(^P^a)%Vl zzm0zGdpGmbSYsOykz!JFyQ?V#wO5eL0uWI!)-(zT;$dOzQ`)SGobWOsgNyHi+a&lTjh82kz|oA1(mbE_HM-amRSCVKWC zyFaP&?-`qx44&;226Jw9a@n!N#b2W)xh+T4*bW#(NbE1fmj`+j`Y(Qrxsr$HI$v;X6Y z(*Yyz%$@>ty~T!?~OmQ1nHgvq`dvQ>^9_VCH^%HeOLC}0S)D0T8E%yzJU>pbc6P& zr%pBggEw|O*q0;RZ~kL#F5|$*;7sT2OhJ)mkRe;|I*O^Jt(obCK4 zs+KT7MKbK8g=euXJ6?v067Eqrx0yS35ork(oEajQ;ouKa&(W!P2GO;hz+wM)gpNHU zOE~v82}&UR{5I4lL-AoAV*&vw_YormR#A8ue_1D}3rU~f4WOI>&_cNb^H3}Sd2k8e z2QXkBGDd(Llp%Hk$O;+Cj>j@(AgUE;J3z}M(qrw_gvJO*ASV4FfVvt ztl;c>V+Xi_yShpUE30$_XewYTo5mIb4bGsa8Vni>*qu8s)E#P1`!=xQ$+1Im#tVOG z#l#NUUbxY7$SW|mre<6J{=ti57xkluHTLTW%Lh9R-VXh%H`SFxG}c%Z+%o7MUg6h5 zL?+mi*rEd?_+N1wLsw?75n!YC3?5l*&9GOOCQnb*Hr|dqk`=GlWYY-nhHQK5oCc_ zeUT|$Wb^nh(;>YVX?5u9d)FR$`rP#TzHd%ua`(*i!9{nQ3D;eRT?w;Kt7<;)wOf3q ze=t%nA^Tgb5Fgq~{aH+kwV|HbmOWq8t<_Dm2*Z71;-eT2+AS2Bz`ucxQvnGlI>9^s^JginZ5Ws^Y2k*A_NEEFK0Le*8x=c^w-B59 z2vF&CM4te?myWDQpo-{t3XxD2jL_K$c*01Y+qD^QWW?3?UI@YOyL*g$>Op!sRvzV{~wW*%v-v*-=z zo+fehz|7ta_a7P$eZPG@ZmK+odYLq}7_a9wqyIXTjr>O=e*NV=Hg5tM)aS_*VCKYm znCjhMGC-%4@CfxXO1G3!q`>*fdBjDm#g`O zB+6Qm-^@(DGM2=*2rC>$6sc;PMmlq6!ch1|(`~Ubg+PEN7@xU&>_q+QIG3E)-H`;d z)kg*kR*ch28}1$mI^?4)^Y5=W{l?}k4J5EyEOmvdbs7I({2~; z#(wjU?2bGUaklSJNu9-|Zun!Q&m-&SQC-*<4{nz1*m$*o@btk}+JmmB)}>R4DEx$Z z*zvF~j!E}@DK}6_aT5m+EZ6}}&7A50Znc^4lvRRiUa0xX>ebn`op~ns3VqWaEQP47 zOhgbbm=or4Lmb#^@DG*;qs8IU%ZnD}|AiZJc3~Rd#YE^MfT}tcTzA zm4=*q#km>1`jcHP_rj}@ny{f5@#YHGPtz2e*pGQpu`Z<7_e!?>7A00Ww~R+tyRAN` z!9BBtYUGJFbOh8NK%o!TRc!FpN)rDLpKeHeem20et(kno;;@Nt0KN0{E_`ZJxgplP zlh%UY8vG$Dz`TQ%8K9Ym{5q=PkIc+pQCkHw@=50RxniyGIo>b;s<33Bz7o5v?5M;3 z>b3k{7{sWx45R6_d<0gH8MBHSdY_m_GEur!)y$=^w`$aY#ETG4nHeUo3rd91`tj#S z)DTJDd03+!iS(>yj-)D+M(Jf^NbSn2vSy6TzmO7>D13 z)9(~%*vR<^6YZdk6%@sSm5Bf!p`^oj8cixg*3R+#k?06X9$p{Y%f_ze4d;O%k(*Bm z4@y8%tz+2G-yXfZJk2%OP&wXOZ+Jv?9h@ORyJZUmSThPs@XRuzHZ)&X2;^Z6T+R=p zw3Pn6!n*c~2~+$)sSNu1Dez(N#oqCIH9yD?O0GDsUc+A)@p^5vfjf^pJ+{f?;IA0= z>L0JHR~#-3Ri%T;goMnExW@6k2azUC`8fx^@={&vQx2Y#M`kv)VEY0Nb~hWA(DPsU z95g>B?L$s=-0u=QnhSBq1~`Y?&tb#2G0^LlVIyM(LWi4(sCFLF_;5`~RPYdwgzNDZ zzzRs<(J?v$6_^l~6tC29OVz+H?S8N6%AH5{b}cpcb?rmQjnynlZ-m{!2ae{i))&_ z(%OXojf(?yi!YrYHwmnF5BfJ~r~g=c8cUppGJaI3#qFEin~RHJmi_enS(iuJktk-? zN=012P`!iJWKk~_h4so%0Wf4_#TA&1!&s%HN9lv}1N3BT(atg;LY}V*3nE;nLCo?l zNS7i6pmDmIA5S@LL&rzSMs~ULkQys=A(9IZ<95UO=FKu}v@^%ZmygsaJJ-Zv$i|!uhs0Quv@TY}6AG3a6 z_c(0hHT?By6y<-G-M7B4J99(+*|8_4$-IJi#qZfQN*iyOkj@w4l6dF{-Y{fw8VW|i zK!WZez)G607m){H24L)7U=R}VP!3#S2bvFQMYQ0lhDTfSp>x-aZ>gnGc8&1uR|*czXeFP7)vq#TUL^Y{CftdFKnt{p#4 z^E>*XW`3*qyCk-6ROL<3N24H%@C>|FOJZG%-|PP@`jMux4-{pxpT^xYC~aa3f-3RW z)U(AA;$>K;+%F|Ae0?=R3AuB#DcX5W6}2}PS)wYW1hEiCvPBe^#wPi3krcU%@5~ye zDi0w>3K=>aI}BoZw}4zl+_Z}j&zx;GFW>=sxnEH`;=ql6aKNs9??6*|vF+upDpqzg~;&2);pWcmOvSSYHrX$Vh65lt!U*VIak;*4v@&qLe8PB) zvMSd=^3_c=={Ti{6-kC~19K;)&>q&Cv z{x=ymIjM0>%@vk$d_sg2z}H9k7vBkAnSZ(OFX7rYk!N#?=ixK>b_dfRYwYvr*yG-` zpZD;AM)>1PxGLpXG^||#Lsm*+1s#e2P&HDZo(1Wc0w&Wzco=k3Ac}c73Ja%mA9CUX z+AMl47eKOBuV!tIVWCWwqLc(_#6s%RQ6*joQ##82JI7ZJ9jpN#wdf&Wz`QppR0QGs zNV;r*zEJEo0P3_L2*c>Wm<{3ZC33pFm!KCm&vZmvjz3yzndj$Ruvgd&e(?1f^GOIkT5wxcJwEFMr z?`u3Qx1{AdudF?}WGWukX_ewTWVmV>_T_a{h#bU7x1L9Hv|yCe!WtczqsvV+S0Fs- z_^5pRB;D2yn#-`=2c#t?9Uix7bKNVtl14$3no+6@Z?- zh*klvR9fsR0G_o&hKi*6Meun9!c+l;DIkYY$XJRrT0pL1A&mKmP+x>A5f#Qo`1V3k zqu{^i^R7DslSzOD8bZ+_qy*IC0xUo9xDTkp1si#w3LPZLapYcHjyagI3rIBvyCfNB z6-E~4jjtceu;f$-Tv&oy7DH>V<~olG^Ty@zJw*|XoLR9;LU{EL<15ECtRP92ttazp zL0V#(w97Mr)8u0k&~YKNRG8-4k9-+zUwsFsyMPUldY~1ns8XO>!qf)9?^~=J7tGyR zIE@8dofP3JL)6imofS+Jk#5F1EXsmbyaANY0(6Q7<fEeWvhtf_ZK|H(jils|B!?bL z+_t36KaecE-d8ar@$)f#X|~U^TkG+0`vWof;9jl6Qm}%K`%`)7}CWIpki{OK)kD8rb1d$Syeecd*KPVgqqPftEA40EQ$cv9C z?hZyMS>%G1qf8n2#RZyb1yNF96(2Nf1P`%r6!`%a7;Ns1?t6@DTu?tGC?^0Qp&MwF z<5_l;n_foCoqM;OrfTi(24AkTp>A4jSWxtEWB(R+<_N)T)@ZSjdZA(C<$tMybA)y8 z_f%YHU8ig0de(Ntwe5IXkCRT-M2THNsMf6;w9dx`tr0XwEqu2GQ?E>A(nJI;I1*SO zv)7eE#|@%~yy&jTl%S=oB@l z8rKDYZ*~JLA+B2zA9~0mO=z=mmz9->g8~fj$Eu|4YKBiJSww`YD@{uV)0eUMSZ9DyP z0M(o2SPxt@mm}O3PPM_fVj04A7_8$%u5w6e)}hmJhAbqFKP(D|jEIQ!ENC?hY=ogO zIRum;xYBJ^VwdI-r9Tfc5rJk4j?N$I7{JA;RB+>{H5i-nB~jW)2ahP~RpkH?4poZi zQ!jnZzZ$+Z+1v4R2+GQU4KL|*D-)jk8CzJN{4!TU_h?p`UxM@YYBv~bX@rI8hMj!t zcJr9VS=eM-Ow$^CVd8&hKV7^$iKmsZO*dpVrCsz;pRhflaIF%wi-!SyI!;U8UM>NR zbPd(qaMA|IjSn_Rl%gNjO&RAX0Hwd!T3pao3T@d9X%Ub3u%I3PLS73uR&i0)a;)A5 z$Q4FKun<#kKz*6H4v@p-0yk?B$_6K$<%nm+;bHQb9P%4OP_iv_I#v3ob^|0~9FpQ~ zq3$2E>MHjd;z(zs_KvxKz2dCx_HfS_q82*mp|%xtXV@D)2JLgPxwtV+5CmN z(n`7h-yTcOl-^m5ZlcyExAD1)E1M1sWqr}D!kCYf{b>&COr(!+zvA#(bik+;;7X8X z0^FBDDMb#{^C3@qsD=c4XaL(R2XrNfP&u~M4o8z?3wRJiR+bOT90ZUR9jcZ=cC21& z{`STkp(7u`luVu|h4we)jP`(@GCh3(WXFISV7{&#h}U#eVS&x*f zPKg`Xcg}3DqIk9TzwI&F98~#iEMt~-Z51Z``noebp=P+{wGb$S`GD|;P@`x`-S0nf zF_Ln&7k`AfwsEIK#lv%t)w#AaT3^qG=MQCSe$yXPCap_Ac?zwO2-GMb;sP#Z99PB#u|!`jps)En!cB%~ zmEh|aCO(cR4<@)#rQFT`+sP3}eFHta1#Y##Rri9ly+{^OSrMIDiog}592|4+eBiJ; zYBeBjHFtWfzY~!IaigCEg(hr&cm)+tpaWTtyKbP2wtsQ|A51vYdpl|P#qaG@W&XTR z>Coyh_hfcvIc}=tx7)@3x&P^>u1TDE@ZRmSO2&rx%3sWP;3~@FEG_VdM3hl5pJh6( zQ*{SV`zqF6Ix&01<;iO6szXFTm#*IoJER8l(F#i`2Grx>8UTE=pxHwL;Q@oob~q;& zh_L{US^+h5T*U&okq_A^pz;Nz60BFv!%h|{zc_@I9AXn8+1>+CCe)t?8nx6l=S`v& zZ_qrDNQcrVK&qsRatt6!N6B(mhdXz^^x-V;uHbKosa*{kad)O~2hJh-sWygtevXG} z*j&DhIQYYF>N~UGQJnZ+ziBsi>uPFC$a@`0I8L_xF37Z)u*^_X9tfv*6ZKhx-6 zT@NYh8+bS;9?*9oS_j5~>0lil-y+A69ymJ6u~P#FYFIdwT)$3$FOxyq+?5b%q0;sf zLB~}Rp<2anN-tN9J&BMYOj!_<2BjQ?vcyOARf!}=D=t@`MC9tYi`ftECg0RNx$)x410^Qn(b`7aDv6eu@-g>C)?nf>Lh%1YE&FI&LY`j&7+u8L)oFLOY7cR z$DNJoKIU`R$TD)JE9`98gY*a8QG24heqy?*CoXjZpSM4tMZCCH^1owt&l(>bk7(3n zrS#A_NR%p#S1nfv093s-TL3g&tuW|tPiW%5%M+t?o#UNnibljls}k7!H8KE8p(@kd z#wIw%{^fpf7sn`oU_^J9(uptvqmDq*6m%HItAbeRG)s83AdjkJmr7@F^3f#2onPDW z_dCjS=v^Er4Em99=qc*zN~D#yJRCXzF;H#HBG+(_3t zI%IgmtM^&!R`av%u6S$7&UfpWl;Nh()fZx0N#^>MhTWRo4{zLDd*vs&=kFU~Kh~X= z>8xa_^cgF&#BA5Ycgp&&xjy!WP^*5D!9}9fSo}*TR*)CyiA%0pW#&Kp;Q*Q{%4yCh=zznVQ{Q%T69%<0*ZMwc6S#ivGgR@x_$S?0Ig2n%qlC5 z{(zGDBe~i0?5<7QERB19Y2R6w^uTp~IB8G(o%T)HkGtC2b|2L2(%nk&_qq@iJ602c z-a6JhY`S&QpQ)V{#M>A7!}~^5-?pNg%*ZdI3o_;7SN1V@JfXfdPw-&ChnLtsh zZzv{jdo`tiK2xB^WVEBa@?Hw6!khY~)qXB~?*YS(PD8x9D|h{Qf(lj&sHrR{1R#sJ zKA)f|=OJ*W1N1Z4*zLD!f<3FK6r@gXP7*HmbVfrZC-JZ7hJrQUw-2PvhWZU~!w43c zaro%RwJ9nY-QCx2;r-4JnAHR`ifC=#1GW@#R$FTSpl5*fn ziCwQ*^q1%WE^@~*&zzb9*cJTyv+!@MsU`rH69>wZLb#!?J*%Txvjve1$r-Y`wX>p{ zYjH;gXxh zX-(9Y(ww>ocQybapW!t!804~T!}y*eOHRgSI^w~Y^<*f@$01A!{m7%AiV?^AF>Z#; zR=0J=FRc5+c4BP`vH{uD>pQz!v0-*i!%62I{8$&d*w>*BBr!2S8GKW%nKV;14E`L6#jw4!l{jl4IyV zBW*xtpRGU9d%}yA&NG{NqrUaqYS9X39#yq%wCBW7ver0sjN52;s&~35Ba5AYV%KU$ z_etWt@)F{q>owKQef$&g^0HNrs`pd)#{2J-RvW(5y4MwA!*(w-BfeP^aOWg<8^0?2ltA!obEp8 zqc2q^T)0(Ze`#XKn^W2!)0-D}fg4~vUW0yoe}lJei~rASO2?F#d2!i%y?jOw8Ek`iQ|h!Tte7GdJsEzZBc}0IUPTHwh_) zCS~!)5Rpqw-F6HJ@>T$~3c)94uSJcmfNaHLqp@d-1Dau^O|Q3k2*?cdGbC%pjG~~i zJmWIB5*(mljcuX!V*mo;2<1q*kg)Io`f3&Yhf(io?5IUf*TQ;agilBLzE;hH#)?p= zzhNVr+u@MBBj`*31y^#j(@Z6rDZCJvc;uvct9Qa#-(?E+E`PxKN7Z?&&WKg7^M-Ue z&Hi%B3$24b-rrnt$zRF0EY4O?!}7??@45#=SjN$9TdQlMLN7i&eIxOti$E}!FF>Ux zfljF_BGkh1X`)C9PiJRGdAs_J`fmu%KxG3&DfBp`eIx4;4=P? z&{=~K_b)FjgdXaoZAY4s0%7=VwG(QL40?K&N_P-wkBJ z-JyRTh%f%y>-6J@hxe5HlK=3h zUb#9oZYaR5SMf16xbyV)(qi#Y(MFTxD_=`S2+jsSzV2wFJiHi;e6EGt+Uc(yZGls3 z>45ROu9i&r_h)sLjQbO=nLBrmx9_=1LcTlSZ$z)@L~*4<2daiRHH6qyRA;BS?}pYj zX78B*)Sbv)~R>HF)u4$+YD|;yIO0Bm(xZ>skTOJaMG6IFyIam|J@)h8S^JyzeB7^J#=7CbNsj%juWq!GbR_kQ3>_L?$V$0LrfQap)Gqc)#Jfa z%U=RPkxXP*BIqSKY6rP2rV3PZ^Hi{cUs7>6QREBPK25I)QHUaXMFggxR45?$f%)Sg zfd%OMfr|s>xK!0UMT0+Qn5@&DHY=}eG~%gwjaV)ZkJvDJ0L!}EUAcZqw7wVRJk*DW zj?G)xU&yNZ(Cs*Uu;JHx47FQKK1kYmuO6|tv;n|zzZPG;K+--aJHr}M#}VvblEyT= zRVS+UAJXhuE>zoAcH0H-^3tTI6NQ*DD9cj0e;Ru!>{1D~=hUz$WVteUdZau}bt44` zu0d|xOf_eitn!e8tHIJ0+iGzP%qz^L4e({9Z>dA}*{G@Kfl5XF=H2+1c zozG9t|E5LvLmhAn)gc3wPiIg3O!LW;V_$~m>EF=e@*DyI?@C%&Htl_WQ+ub5vn&S21IO+Kt$Q^kDQfuN{kjG$c|=4yz#TYEE3MEY zeJxr4O~;=0xMWYDtiBsn$WRgfKsKn@#l91*|K;fue#T1s>a(Wu$BQTLw%1e%fsn=v zoc}OU3oGQHUJ;`cslrD>JV5yo z=;7w_h$6fW$i6Fg*zK^Mk06|&5zciwvaLwR0xW)8PWF!<`nA;w>(D{y)8s-n=Leh; z=iM&4+aFOJyKLXEYlH5swBqG}(NBgpurevC=g^WBxz_kZ1kG?gR}l5gvSMDRDoh-* zz*&0Pgk5g7*@d-ZmsjoyeYio~WH06{j{5c@RhS}3UL;qDaMOTF=e2f{Ky?}<+%%P^ zhQ;+%@<-K!8pBS%H*ig$M*0!Q+E6S?c}T7o>u}fTsMoe#_(rl5kfgh_SnK2p?3eG3 zcRzcRc97t5KX8+5XmoFLc5#qa%Ory8jT-5{7C+j)AjRmLZW5MCSq;A|yMGUPpPg>W zm@!DP?6RBbjQ*isBy}hKR$mQ@Ly98SJwdMLPdpty+}ouR35%QVXkA}0K+Uxw;2Iln0tAP4uii<^i96-L>Yy`ib~~ zf?rPmP@l>+mqa=f=g1{hjrhoz(a1TZIOg1B%q^RiAwn}Yf7k5##_7c0wAKvQL+VEID|Iz|PP|?O}Xp?kS=~7KqH0-dt&IGy*)xcEO$kdQ&$uxJ>Gjb!E`jA(Js9CS4 z8g3+8Zz5W6Q#Z}lbKXhz%GPCXp}ED;+&3D#Cpw3uxdfy$BXa0*dAk022HxdbP8BrM zDlLl+s@(;RwY?faeOlaO^x#8!8|sbXOD)qXSM4sL?>JzbkztdWI~l^gwkc|Sd)x@m zuPZ&MG0Crl>zeQGn$K_%YBR;FSm}nAkq!<%p6>3h&TH)KSvKyb4t|CnL3SQqp5DIR zfq{WRk-ia8VcS9i#OpR>`XqO8=sw8^OWg!!&Ez3m6BwlsKT9a)>+?VWzv zEqBPAKVg;m$ZF?n8~$Ur%;*06`FQc$9fgyd_6=~0kB8?SODsRTy>4Ld!4ri|O$S?# z9qQ`p=sn$g@#4_6YuC=c?mN0PbmU{BcY`|eWN$M?s+zQ6EIetYTRlc&$_+`Th({l&F&?;qS-lrJpJzJK%X)29#bmzVxs z{{8#+rqWg=75(@B->K+-znFidesoQK@E(Ro%GoS~XXhu+etNO;v*oL*Ue*-h);h9NyPFZ~O1@p;uSl+zrc$k9(bDQG35}!VaIBi8pEG#4Lu*z|j_a{~XH%3seiki%NZV&u1bDyB~|MsN;zXN{M}$G06!+3>A*I>@7q+b4h! zM7jW|X`fYy{!`?uuYJ!?RQLRMX>;X?m8EZ2r;ePe8m#pEInbfb>=@|iv?n}!q|U5f zcJ2!Mym5o1{p}k2cF*=8I~f4wTF9VItG3Fn<({nduD|p~#u>jl^VMDd?ddOby(!Jd znwJ%g7@Icwh1r<4H_lHQfBSH?(zIDxjq^D5(Qkdzh|`-q_4Az_`jvYHsp9airZ;DlxplZ12p%GRr!RDqNa* zc4ltBdc9uS|Ne0ANzZ|KTw7>NMF*cxME|9?HsEFWyz8&_tKF`@q*vG5cS@^on>PtM zWlyaCn*DBkIM?tmv!jiD08`YNU$NpUZ%n*lo{TtxxAo(teE$>?3Oj|F>h5pVc5La@ZZJE^?i;YlIJckI-pow=bHRiC0_B5foBO* znq=s2R&&4WvT4r4x&6jvWmy%CFbmZbaU# ze{+Vz{t$rm!hVSGy7*+m;;(;xHhq40S}lh@6}RdY9lS!dRtQUz=9#0e@)m3`4bm@^ zJT-K$!d|e2$VeIE8&-k!Tb?1V6wr|~u9^d%!P^wg|0Fl(MHiNWp{!b7Tsh13lvm?R z;@jMW-}_A~vJ{mE-ZDk5r>51snvL{}co>yOwpX&7t@LF^TAo8u-BBBeiNOS7M$)=N z$3EVUzjU#X{s82t70Bb~=IIWuMe1Jd?}=~2Fdq0Bx9Up^dPRQgj5aM}*6+u; zEx)Qa6j?WI)))C*cTpQw^FD(p`ao>cdQ7^d)ZPxxu?n44S}LpxPU+9eFmAUKy0a(n zIVXn;|BT;!>|vE@B65Y0^x3ao?eCn0xOe!OiSOqsy!1HwcY+ETI`4)*fM2vl%U2mI zf+Fu<38drkG6M&8fUn<(`q7wCOPik)K6^*h9fCxQwBegNV;{F4=E{zDicj zuH;DHs~51m4SvZBJ>$<5dVUZwHBMu_b6eG~C3&m5rQO+lThhLtD>Bn$#NN4~N~z36 zUh|AxJ&=<}es^&t+1i}sbiq84B$z`Oe3BMs5ofm)3|w9HRaWS+Fx>f;i*fmvSFyJ9 zrP{3VamGXT?H?JR^ghtmML(^I%-FF;@5w*uQDgu8bE+UeyVeUxin7eMb!_Ek&M^yQE6Gz<>_o!a0cr^8Dv!ro%T zuHGKvsa4C8LQh&`^Q~82F4-63-Z*M>epGzXzm|acC3HIR}fN2M^4)BLVLSMS}NJOzx}gj6PGjHMl67R3}~bT*tvCh zKX<_Zd#4cB7E#;w(bz!KqsWtwlcdmH!B+oEaO&5f z-<9OT{QWTxcevdMRg)*^3O>^co!MFynK3z0wKJRd|39kEJ+7ty5Bz6m+c~GUwsq6G zsC8epYF(w0wJwrmr4lOZMmJd$mH3>UYF!kg5W-T(eT9m`S{J#LMH0dy3GoRbzV!L+ z_xtbncVyc|asvnWeG&BOCsTbhKt$XwSb%F}q31+Oz0<{rue$ zc6p>)nU9CrVBs|0Y~HTY0Pkmcl%L(ke}K|Otl`(&Yi5nL_NLsOC)YNMN;a7bPfam7 ze0a#}By;zYKQJd`mRbaL2W+_U(QEP&?Je`-#hgVkTP%JYc|X}Tf9vw3N%xh-w<5P1 zPsy^q`B%?voz-7>w=;XoK|J-XxN!bmQ%Yv5`RK&X+l$V=*uC6FBM#*gbviXP)z@=WF-(9yV^QmIz ziMMBB*vhb&G}(Wq4LXr-WxwW-L;rxZ#-I3l{f{dpo3|L{Gd_#A?TqpBU-<6It1j_3 z9+LHZ`%_tKm&ey>m#sDUAFHiz4>w&bIQ2aK!`joH3#Bn7SsmskpQSq&OXpsl#0IkGKSh~^iUAjLn`Jcg0RcSxlYrkqN@{utKZ zu;neE(s2OxIl0BpozikUu_rmkCpk;*Mky38e}m@SKLBq-;gzB-w@+uRgbEfh;Zaf1 zZPa(@`rCz+Nw%|f)dDpUbugP+uqumu zK&T#_Mf5=O*hr}uZgoS;QRJ{pC5chX6$`Va=!1!s1JK4fwI#?gCA?j{W;l42fGBtaOn$nNRVisTrt(`)nja6W^wjYIM2N!Q;HvoIR@m!onUr27sh zg(VjZp32_F$QWqJXr~u7EkMQ@aGo?{SxIssn=;1p{7ftUS4REBD-LndUxU$5EvJq` zY6-gP=avAp7yIuUJjF*QP->xy2qj+gaW+@?9hO}RYo3Iq?#NMT3C;t};pG+!;8K1? zHV-aj!=)TV<2HiQ)C$?cN-=zh1&o4E z=#Ftg+$>Q1MoIa4g+;2@-+qGgk!L$`g7RL)TQ{IvI~UHYd3 zI!IiI6t}|o1xSTr)kEC4>K*2GsQgS{qWROL z2dCj>?vznc`BnkEl>uk-VgD#f|7?WR6vt|F}0O{Km3H#`3`=j&4bVPIrF0?`Z)a?ESW2D*K2Q7zgEZngbg^%bTcE48l znvHy7BVJ{7`tPvrfSA!!RVwJ83WL^f6=QL|>Ww7nTw|esS|T91yad_tApT0 zmZ$P)VxjEFAqK2k{aXogT!7SD!25V`jslrr!-X`sF&geDgR>39>SdBjHZo@)by{SD z5NOC$8O*XhSS&^o)RF8DNUmhBP@26)56)#!Y7f=XgAeOnKNEj7r@y7jF=$`y9eBPi zg}dOy&FE7t$iB5DrCS-rZ>?Y@BkDOs`Hb!eZ;SdDpu7@Osaor*!tDM^s53No^KUM1 zX%X(*U@s*0=}_Do8Fh|%%&ZX>N*c4*sP^r676aa3i&Qe;U4S~qNqEaXy;*_u^dXrH zIEPoU1-Q70e`*i!w3vZlQb5Rot4d);(COI>PsH-Se&RPZa(jroN+7#$^ygc+#H5H{rZkwjW&wZzCLaCz@SGOoy-!5&*;k3+sfcDVfx3W`0vD!E% zVKbmU4zzAkLRm5>lYK24fH#p~)DR&kuNE7q?crY}&~A!%UE9LBlx>S7?}C4xmE{1G zaWSCt0CyHYw}gf499u?m5zM9h$$&NnoKbz zX(V@3$CZ>Rptgts&#A*0zeVF-=Y|guhTfXCMLsVJ9+zB9BC9q4&fwk7;&*P1Y27l7 zY(XV+Y9uv{=LwsqRbkUh$w1Z~Y%`2$F))I~WXjkyqy(tr(@+ihPL0>aq-8BN+gm?R zx2!k3xVH5O{V<##Oc`{iYzHXz=S~DHy`ww{$6H0cUQhXicKML0-hUw9yZ3x+shrxa zDJAEdPf-3!Lx1p*_xylQ0(foYjjx5&c(=+~&b8G)FRBQj0>PzB4khbc??zs0x)S;| zt>JU7Yl95RkPd9*Lo@dV(rNGp3A9BCseOd1f-Z`uZxf`wwdk!JMSsn`(;B<3sqea$ zsf6BST$@%>9w3w~1@v{9!iaq5D7o{qtg}Luph&M7+&cotT*^~YobO-HL+8%DjiM}e zD-IjZxqS_)p3-=ULYtKBuM`@dvE5%JkL1hlM+Z?aJdFFxpfE2}>+7$~DgyrH-FV*H zvraEc&yb?^r)AEwbdCA#L_K_ z2YgR_CQa>~EfTGSHVJM|k?*{if&`3Pq}Y*-j7QafG}4uq<-ax5myhV}7|a{(G3to(YY8wc|G>3#}JSLjoBjp6hu0v!ErN4PydGsDM(G z&`0m#MeWc_>2QW(_^rl+jW3{N36$iGSFe>~G&PNO0Fy!(|H@N>lJ>qsU9V`jwpCo)Y|l zpt!>M@WT5F6>DPD9*&km(H#7GKrPGxdC7H}@+Cld$#|($K(7EwNan~R`#YaG@OQgg zmG@T^?ckQ)1|d#E*C(NiedmJmR(3ZbO&ZYeH6sqD_J z%Jwv+#?>1dslbPp{yB|NTKBY6V-!8#W4Awc%euSgLVrzDJaB}q|PB5 z1yIC4P_$HS0|&oKJh56joFE!W=m+Tp<2O5uoj^}LX8Jqf-O?}AG==n`A z+(*;g!r3=NiS&y4E2(bWQN6C@onkMF<~rKmv~w*K__Rs|Xhy{Bwbtivn8BhBmOF zEyst4Ltp0q_a%DM%*2h$ujfy`@g7LNc^McJRm$8mN4v8gO*~()dDH8n?e7MT8fCri zJDK`T6l&&?W2n~d7GzJ6J}<)CBC&29gF72f-)QQPYNaW*uYl@Vw zSuYYj*H3o6Kk@_ZrGu+eEO@JXD-Jm)+>cp!c|A1G)x}*c?afc}fhB2uVkhmuwTGMz zzRaKVad~r}|FF>OK;Y%gZ}o@Q2VQonKlOaUf>%RQ->$&^!^LSsZL1Td8b{nVO?2a) z=o)!=Do1yG`!S(W>z1ata>(y?{}H#ORR@;3XvMU;j<&6SG`#VMd)l|({qZv$X1iF5S!t!BS(!n0zM^JMX1UG^ zL{0;3T6!{+SE(-YrV#{>Dh@& z_hHGLOZ)q+=Q1r_p4D9L*x2a1;>gC9JG};Z6KAXp^J<@MI6h}w>>9q*(sKIPc7yKI z$8*^ION=g#j@>>d{kjxythV71+pVhQ8c5Q=SR?GxzevLiSuHlGi1qtAh-0;sWp&#% z*CauP8-T=S>h0-sWLA+sp6t{&n?Q2;{BXTU|GpxUZN1D;<3bg?a5K9z+}!c1tJTbe zp~)kKR^9k(+-=i^1#9ay7CsagF86#><9Gda=Gyly9_PL8SY|@|mkt)ZZn82=t=(5* zkhimWQ+VZqiP@VKC7bWs?4)O$KE6#h_U_2mz?|E5+Y~bsN7a@GcP)4fY4|NMxTu<< zHAtC5>V5cpZdGo#bEDhUs(><0?r++}N4vwj1?sm9@Pu1`kD*bHe^_tmOS$NXF zu(fNowx7$l=)-3W@?MWw9r^LcH{x)fr`3(@M?dQwhjxCoxpuTvUiR)tuEEspqlY`x zNXDBY-rT6zC?VECWSl|N~3k{i+7XY$OdfO7pD^kg1r2j^%dT*>~p3kSM#U6NU0(jOKLo zDD1sstnhHW#}J3IZ8lJ2`EyZ@g0De|^D`Lg6LrrtQBxzj7SX+8)g#-u|D4}Fzb+qM z95t-F6IEXx-+B8#g9z=+$%_$Zzr2u$P7?JCI@NXhYQShxcb=R3YZ!R>T{H)Au^ffdZh0=TZ8W{q1*i#wgHseGM zb^cJqQq`WmBp%AZw)5a>|Qr79Ikcu|BW29km zp#FGW<=s47VD|aMiphocvpuEkar67)w)h2^_Z^JKR~P296N5%-gc`&JejFeHAithiX(Z+7}485~z1x)peOG)Y4JN z$qw;E^EJLpo=SxCE-HzRrDLSeQ<%=nX9MgAzeV2&g$5-CbMBEbR!d1z_3$ap&-liya6!@yYtpc~#cN(V_vDNuZ zt?6#bu?$yx@~lzD+vcW28z=V}eEg;D)`m0A96uF|4@*j;1VLFj?*#Mr9-;TjG~6mg zyRYEqV&z>u$1d0^hFko=w-Ex#9%93M;hgdK_p#NM2BOtWKlh zSAV_Xnt2PakTlp@czQzOg1rfer2pLB>zp;!NR2V?v2bo4<}aNQNc#eBCg`^CLk#^_L7FP8r!k}WY#OD<4VBMRsaG5o4A5swCY{MP zvl~{bM@lizI%%9+zL2!8^y9VD@!|XD%5jFV(JuMi*CoZB#I8%^^LtH_R%;tMhJ~NlZ|G+z^MeXD#gj}1dgmQuXdFD?Ves!6(Zuh%J!v6t zsxJm!dmsHN`1JkFIhV%+7iZ@w3SakMoLEh7Uy&c~wN`k|S&7ZdU=TH<>&jM2h2-l> zU%$x0rz-?pZGT4bGLN6?Fz>8Jpp^LY)OU4v73V-gTj${Kdo(P1lUFPML&gxFG{W}M z3p%_0#!gexs?UxgoDtV;t&tf|nbM`}#_w&cZ7|ObneBYQ8F3NETMjYtk_S?Y`ZT=Z zJBJXx696&3yX(=DniXf>elw1*n0sk$w<7PuN{{xP-H9gc1tTBU>jiBD^o-+E%G}Os zHkH0um@s(?(`}?BWbk|mkz)D8m=W>RJwJmm1UGb4Wq^#}61t3iwdFU7Zo!@9YZ`?b zZM>~E73(evw*E`&5L6n(_>rzhZ&9H`AKEMaM_PlJ(cxZgkPThDRb+h3QsQGR26weX=?v=z+r=|mE`3SoI^<$ZF*qTI3~9JJ zZTD@>Z8YZvDkJ5qZy2p`!M22Ri@t%BH2Te5oP(Ug@6r1<@{dr@X{CNKcON+(;@4{5 z2bpRXI;bq7(Px}^T`7u^aQuy*bWys1n#aC2Z&zo8_t6^lLyymt#g@aVBTktkC26H< zd3Md5nOovVi_+U5!$!<11#~Y0trc8b*WPjM8>-17^%N{&Tu!O=ap?9>EW(&l=#PqY z^v3g>ou7L(XvX(5q}?K?fHo4$MkcaWS~yM{xqbxgbKAdz-QUl)E_!oK<(_S^-PbfI zdOpWIdym(VI>@eneOw-1&x|H*Ou6*F3v!+Ytr4s``08T=(VokFRV#ZcSw|mdl^fnG z*%7UiI%4_qA(Sds^V8;P;!lR=m%V6*Y^6dgPVeC)?0tK0_&J=q0Mz7zR?(nCHfBk0 zud4uSLwqu7z=^Nd%<1jp_$3~Ot<w56C$E@0P&iY=noC_{l+je0xq&wVLe zkn7j_y&1{`>b{k0O7|XUNh-s875*r@r`Kt|?z)BdJ+ms$yG(|mrjBSuEofU)lSdQ9 zdvxjy!8)(|`Xb8pX37p0mK@wpHM|d}qHro(hXR_KlDpVsrxz>Fy!OK8j&v_gGzyl) zfR9;MRhpn<1^t#hOcH^m#(*{oxz&(7{R+0xs5il={guT%t6VUi+5>y6ys$` z_xfqDAjjZVYl4fL=XvQAc4}e0%LlOKX=`y9rzzg??wMNuFpg8oIjyx_E52dY065qr zvgY|}9meESB`Gvf>SRfvZ@?WLUcDqlf*gAKw01|MTKK(^v=NvyCJ9ydTW8cyalUF3 z)Nf7?PA}?}6!hCSh|+6Xj&&@z;$cU;!?fRWErSLU3NXF-Ee4G^eF>(Dh$BN>vs}=2 zWYG2qU@rmm8!=ks-SlX##gT!phPN!QhW_|~Wu%xl@10xLlCQZ9#6K8=Ts-!i@;!Y? zxZq*0o(}5Vvwh`%MhY)W#VN_2T>8oAUGTdj zCFNg2qy=T6<-8pKA)7WxB|Wub;507uADQ7%cYv142b#J#i`hF`%fl>rpv~+ZYdU5z z+iy+B**1cFnGoQcUWwztY%5WE!m-{&Q;$!V) zi{m?zRydASIHu5fwuS6y$88_Z#TnSdORODLGF-Yy%k%!;KT(R+AwO&2-fSK3fK@|> zV8eoIBUSJ_7t>s`i2dcfwzYD9w_frN%y2HJf2l^WH4jXsiBvUGOQz65+W)))v*0ba zGr~-B2UqPMY21Y~WC#=f+^N_Iu0Dw|8!>}YoL109!&xA{2CKT-W?|Ic9C9VygkTlJReth*v&(se4Iw`HPU;Zr54w5xd|C8-FON>c+Q6jFHv9UFFdP7!EceAgzo-`oSVL_pDU?D@>l^+jQp zHBdYUN8w@X=%8f~c5BCo-VLECis{`5vp}y~j*OTymUy^=bs3;J1AAX}$4~-xEozC_ z4_T{jkm_3&7QLr4xN~P_dYOVdhjhJuths!=|B3^O-A!G_Z4$NE9{=7B#h21GpJNPu zNaiGFlk%t_`q3V{Cl<3Fd2~p3bVcR;XYUr3i@%fGO`ObgSvLmK@BChnX=!hU^uC7HLMuG-5Fe{)ic1=~`OUvG8 z^VH{tc1mC7dD!Pk;=*_B(NYi7#^1AK_1feP7Hix!XW-1)uS(`e0vFc;5N6u9ws-2e zaSCScAv8s>bqHoPLNujgW{LYn{eNHbi_FO=-Y-$LQErO z(}s)W6~~GrBl%D~B1#cFN~KL$x=+j-U-My+&M(^1Sy`OhRnaBFy(>3F`>#Wc+`-_# z>skXq3y*bX6s&|81Dr~9k9(Oii;Lw6%@B-F!lAsyWplus2%A?pO#V3{ zdBkugWWvOSGK%R;QF!&UXfJaV!8OO&9Ygi%poI4ijh2!5K4!>WHxNuW<3HbZs`yA_X*( z328K(CR3>L9ESDu-wf@4ZiJafgN&M`nr%W!k!R`7sb}Z!SToK9{9V4wt|>J5vC;p{F7eORL>osambNL0 zDN5uK*G&qwnL^dK#!3~R2)Ec>MaWh~)aZNgYOffYp@FejppiGQMJebVO+_Li-@x zvJpa(1bjNLI5CB9$SF>weN0FxCL_35RG7@}`Q>q=K~b_{I%_xiP#!b$-Q~E!un&2q zqIdvOg?B6hy_*M`Aff~SGNEA^dN}pzP0QjkO=oc?3Sk`WThqKvQ6t3(xk9S=r_(MM)Bj(I({6MX3Pz4uUQjr`sId zT;M3wO4;&hKp3kij!_U}J#ac4p^*wMBt_}D!t7R}+Y{V;C2sAAu;!(3uJ_}gfp5R; zvH8+1ttwLz?M-X!E17+E(eja!CAbaVVC=}2z$G)KD@LAVV{@j{vxnSzkKE_}JRyJC zJ(65CPu^a`>`gtb5s|V7N~rm2g+K{((M0Cwc!`KVi{mpz35e+39L}f)Rr3(4uJXnQ z!Z^0jXhf(3;B@y7$Ezf$rMNQ8pOfs7U zo+RlpmsJFonY~r3Vmy&9uiKp9XQMHabj5k@DsD-YEnDz~ftlkSv~LK)FeR?{a^9oy z@8353ba>g3cVzI<$DfW$83t=RWX!T(%l`iEe`IZccr>}QRKw7HBb~@HO$tMWZu`%Cr|_eiWMV)`q^lez#dV*CLc@Js(T#=X>UU{~DiOvPa8?$(uB7 zQ0_MNKc#2m?B9prAu}<})Z%2HxnJnv7%r%`)jZhK2v;_K>i(hNn(im5h3Y#FhnGHl zr!}OuBkug{uQINhCmknlhMt_tV5K3aW<^H=}GryKU;a3M4~8BgAK>koKet!Mgc zxs%GPjf3?X1*D9HQ;Zl#&!K%Fi>XsZV)ZDRyQm#Q;YDdZlbi2pnn`54s5cqDM``{@ z(`n5Yf7w{h(ukz)?KXQ4YH2Ms5@IxuB9%+|Lyz^Vr52p5R|PYFEwuH*JWL;H#aR%m zv;s3aRf9=Nd6{km&lk_EQ*w%R8)RaxT7YDl3t#{6+E-n#sCg-L=l-JyuK%lt3@1n8DB5qi}>=@CdV&APKsDffWwU3)_(!lpsw`t@j zJD7}YzDH~&>%?eY9erpx$GU}(m)T#P0q;31)@h0%Ski<9#6r^-RC}UP_wJY%`ow2d@(YdDQR+@+=;CnGtMGvqk(_bI;<&DQe*A2>h0{?~o9ICj~a zguj#cN|*cIc#X2J9@-kp#cQGt?cM+Pt3K`KI1rNF(>U!*v_S>j8+If6y6oqVCy-&* z5J;M|rEgir?xlB;SRGU0_wCZYVxW2pL+Fp_N_YgVCE3<;nk8`eOO9^_i*VSOl;2!e zs-BOj`_!Uyep+S63ij0ndYE!`fzS`#3OA=O{yHHMI$YgwcDz5iu8$L-<1Bcnj`)oT z?nBp`-&az9X=9w;(NvV?h8Unks5?POjc-8aNC0ES0?#f zO`sd$=%$mtS_6K^#2u#z(OoNM_HlHMOOlWk4E5l071x1Q46_w7jbn-;dd8d?v>*l4 z_4on?+Bf4{6+%WN!-%C~_pp^kmJ`i;u4n|B3`7q*ANwMUYz|+eb^bPZG^;Z#fgSUE zEW38Mrn&b6tr4X}8odp^;opmre_v zcB@#8=jD2ra&d?FO@(XDqqUdCGQ6>pWL~5!Zl6t{6~tp&Q!)Z`Isjq4E;I^Jt%!+J zbFgU4{V|wm(Ir&Fvhb73?^iIxK+V8uf|ibu;EV8lar({1xgQF&=>fX6>+vhEytZ_& z0pKV`(V6!r=q7aVTeM&oeH?(K)2KQ)BGj9Fb9(Uivc>*m740*HIy=H_^B>uDwlD0$ zRz6lj@0;jnKPR63zQ4rP;hVicboJU?D-V|*E+M_F`93ct07uCR+ST?jp;P0S-K0;+ zu2o8mew!cQ6t#C(%zd+Yjo)fHoc{sjk&AGk3T@(}UC~iw5P7thzsTYM+Y1@G)lFDe3_Z zs##Ghe;Lk(E!P%^NwKpke58`-#F65SRRsB8uTe|BRLJWKSpDidX^}s!vVAI1hZXF2 zV)aw1x_kZL`l_>#OWRAe!<9~27JFSv>&g>iX6c3#{f9T1euz2GQOU%{uq^s2XhF@q z#o0Nr>*9q`oHM$8b4-vG*EF_D$2|TJfq_5*d0RtwxEP$3`o*FjO#Q z8AvTvEtw{ymZB;!ig4eeUcBiaE}@;tz4Ud6XL9Sdmqo5zGtf@UreqxUXv6Ig(eOBb zRGrs`vvKd_Sr-8~s(3(CkW~>2bP>E6kTZGnuBg86;Cxglbr9n6Cd~~ZB9E+-n3jM0 zU2lBSBm2b4IQ#a;=9`+YIKrE3*0l%ZPqcOny4DKIlN!0Y$A$wO;`kL#m6`pvD3P=| z%dg?|<<4`WfWmZ5Qe!J)-eulOR-CdthJn{R-`HcPzJ1r~nS`z$W?)Sw4oB{oCIp?D zLq7#G0<`^Q04()_7-Fz5k^xcCN_At#HT56{K}VIQcv=yRB}&-32DlR>Ih|`KOt_Kz zQ?ry`WFijcbxitd*GdSc9RR4(TWhEA%VTun)s{$PINPn(+H^eq$g3Xq=FY;$?-3}s zg#dwl!YHNlYItVZ;=^I;J4OTE{S&otM$=_oiff_%018E%%)i&@u>P!J!~vhor(f5z z-q7z(FSJ=xH)lGL5OTu2$|;&pcCLH2<=oc%!VS1xlv^i=zu{Qc49B4Zw7UY@&0tP^ zZBnk5voqa@ehEpz-;XP1-jtu82BhE#jYVLO&8d2xv08-6C z=rTfx44>Prl2TLuaEZ|}S_F#x0o5X8xie~NAt^BS4VGA!VR8s$NEoz{L%i zjnT9D?p@ykj+@v*^{dy}7awo!K6=;9wV!@9)QORzV+(ua_P{)+-1#FLWe3GCFk*>%t!kuD!=XX; zd54N$%u|~|sj@g6or518A{3zNjgmQHG~fVeBjb|G%Q<*Dhlu!UmI8}b1B;gfe(x!o z8Tyb!7C0rxtJu5|#?+*>YNadGW&$-laEH`nxN(ja+gGixMlIqPG7dOSqN~Y;4wGCm z(8adsI;@YklgX?YGC&8lWC3Ij#QWRhQw?4j>G7$-Z2y`Dfv;WIh2P^%Ak7oag5y6f zJhAJ1=*;eN_DHa;#cXQiadq5PSL9Bk@`)PC1>tU|$>Zm4V1IY)KG!23`XaWw587u( zvqos)W|j^znUfKobcL%)_k(E%SdsztS+3(102&HaiMQ1FGT0R$i~@_ez%6|tca%d6kx`kQnnR(lO*^Sq)~QP%=W%&E-OpLakI6<2 z=K**c08Vy!le-d7qsybkJ{5B3nxM_bkwHGzdCB*9PWWGLc-JH`WG^as{ABBZ5xl62 zry{tjqzMWO+XgJ|5NOv3+SP*29YA$WXzZa--m}QLevmX}((~TL&hstn&jylI#X#j0%F>}wZmCJQ2M;}6uy9!d@X1!)zxk%kFBhAQuo z>*^M1jBy>JWj7?iF(&{-WI#t9KH4IVus_xt&m^zuEeG#DwVCoD%6$%XNua zSDE@HpfYH+0~*6Qj^-B9e9ktOni=Ej-C`eM{=Y z{<{XAv$EgW44iw2vBtTiE9)q=-~~Cyew@qtBgfvNj@cX%CL=bWa5g|yy+Q;5$S7BB zM()5-X~H5ve9A}lXc>_sbNSl1F0{TyA0-OVtw{jVaE~gH(byCRl!Fi9P(x6B={e8O z+^cSA?i5Ol#vn0AtAc|gqj{y#gYveI^|ELp658mAnJ`A^%=||n}a^&l43AR zm9!~{<(~jL+`-4QRA|9bXEE0VW97f^>fhIJNAxad81HIiwrEPV^2a9vbZtxJ#}1sg znaVhE7Tey!&2t{N{bS)Q&#*6uuZX72IXi?%z@rm=V%9ool z_odKT{v#MHL8+zhW3H`%V^B*r=iksNfF^dmUpW7;oH-P~*!Aq!-*rCXSIgw%&f;~d zX#c*P7m>va#!P-}bUZ#VeqtagWOypX7H>zB{JMzQjO=%!^DV#DIx$Y#wQ(*kPf#6l z=R7a4+R!s=n%_-htSjGk=zNYKtgD%q2w}4 zhwY(dGW84&Bmm%)bMT+dkeE(5-#AA!Qdw;{n%&L&CRNJ%E0|yVD7GJk*mB{7~=5-Sf<9ZvQcBTQ>gq0c+dyavK)@ z_}Bfm7F`O+dGI25=IrrCEyiE7x3>PtED!s$y_n@H=f*WhSyNnxku?q}pPXbe`*D;t z3pnZ=pem~gQ79)DxcoHQ9|hDyWG^Zigg(K`gl{)gT0;R!phqLvDT0Tr{40w82vBEb zhGRgP**Dzm9Eh-GlP_h>UmOTQaR`qKvIHB$0K&**u7&VAVXNw|j}%Q``$>+YPN#Rf z!P$N;ELBzWICumFRCSsR)LR_RSKyfvtZb-@$>wqGt{8YZ=3LAQ@#!LNRM(~0tbf1Sc?LtfiTF*_OecQcsPj#*xp+gdC*)3RxKJ7|7Sb+(^n$-vOH z&1YZBStHLJ(9KSQ3zW7rw=eRpZh(SvV16@3SaAA|klS!w4<%EH0yGTNU&*>lm7g$ z82H!5|77r`wBe&4Y@20v_c79at~IBOl@i1>@^g}KDINpwa^7NJFh`}18mh8|?uKj8 ziBOs5XrTHuRr0{wD$jiy;8KBYp)5S1oA>=BH*M8A!^O6)oUX-1>wX^UC%pHwDR4iq z=biJY`*GW@plu8NF21v&FF4c+2H~5XEf&~K(*zG@{&==N-g|Aim;IToT!Xt@>J2KZ zLT*p%B8>yoZp_i>s%>J7EuYMN2(}RgLRDNeF5ua40&dYrQmI5@KZP+4~5t z0GN_{6j_oXBUPDob{nIoe{v6P=8{9Apd>Cc8>JNJs6rhlQ9ZVC`Gg0PU$j3QmQi95 z?TD2mah1mVSN|l)NPI!^in$D&OlInncXXo1hL9JwpF6s1d-$h9gZlqnv%a?1%kTSo z1+%}lZ#TH{UPJ%Rf6ZUl*=X;_vawTl!Dmfe=W(Dn{cTns*Kw8`{|kdBU#Ju8H0B?v{Dca>fXMyivU#f0D1Tiq z-z)V9%=?J*kP!<|e2~|sM!@k8CY_KGI2=SvMv%@z8S)YDVLT5TQ(uB5a!6Legi!`f zR@LkO0GTOsHxSy_=4ijkB-ProB!81GEy9rjj^yxy3+ond=>PNgTdO$!R@h02{nVUISBCY$V~XQ+%nrrklu4@8BRovey;w%NZSU+tOKLrf|yBko_l zW~rzq;s@92pmFqAPfh2}Ng1dW3i!g>-l{Rp2O-hEuueo@$mM=kBOg=uZd8JJPf5=K zHM3j}N@B5PDA|JTTVljh_#$zhjYUFS@T4gg;x05T)Y<&BL5mU`gcB`uke(!%3fM!~ z{43fk+RZAMClIX)9#%q4voR~vj+(C0(@Q8T4x+^IQ6C&(j>Etu&wks$JnVX+q$+uG zHF7xYzJ|yqdv7GmVTTSvMnr}~6S8$tpbPm=bI^j~c zFkQ*vERlX>MAqB=|E#nL&|R79`jNOkj()DHiM-W!e{@`KF+TBx_o*7&O5bG1M8Ox_ zp}73jod@DP#C%xCyU!P)<}Vz>lLUaTo;Ig%3Lr7q0On~o%g5A=rOLtww$cC$vFOXd z)AA>ai~B-HdN72Ci~-ANiX^<5$4FB3azrd8touUqn*qK2`@X5*Q zzMMOw$+fE|OsZE2Gv}-JbXOcdLGe zzIzXARkUxw()d+2T5lrxyxyAC6=NrZ6QahV@5M#$?VlI7a}2(Y|(a}w- z&%Xo79!eaZ#osk#v>eo%zE5EBg%ockuEw>225vw@j|bYZu+QfSIiqZ?W1ab;lD|LYhvfo z&)B|w^E502PjG^l9^R`i)OWN5SH8664PHM#Gr7(yJiv}}=0GUBF#nviW(|J~i)8u* zOX;tiN;Sy|s&dB}WdJ*Kki;lZf<6lEdKQYs6>x|q(*bJvUsR$_B>>B0xbj{hIhRi~ zRu#*Z>fwrAIsyRqr;vj;QsRaMlKq^IsC|^+G%|e$FXD1C zc7Acz?dF`=Qm0~=b&#`n^34lz%U_n@-t(mQ)#KUjxZ%L_e&hv20TjRzY zYp10j{LA+ZkA1N?jrN9K{9nhxyAe7PWWMhGe5u4p}|`YLBeMg}=eCyP|C3DsTj=F#xFm2*`*(v{ihD7XyN4EmJne z3b1t&1~@<3fKtxuG9lLy7OENo_DPB?#QYte%1-s_r6l@&Y+h4t031Ur4-Pq@^;1&@ z);d+@H8R%@nkihaL{h^elCI@UOwx}Zc{jd%LFGa$F!=pk6FIyV(`hITw%Oc$+xx5j z9+p$$RA#=o>Q9iRrEfsEZj^L=+XBYR)(Ycfyn;3jQT>vgK$OHSs0rFR0o4$fuD z*ajuI?>$F7ZdTZx&43Rq<=}&AUFXGcz} z)S`vREC<;wP+KmO%+r&}Fq6?;Y7ug+8We@Os#6-A)?5GO9v}{(p~$% z$PrJ52Pwsg6kUB%a!BG2LNYYXv)*_>g1BUci+8#DY4>w3N>(;~+5PX$wI-YL`g}uQ z1il+Qbx$Si$zJkeKlAYTgmYX&`Z3R$gwkCLo!^HC{B?}1HPgT25$Ig*n;q3)@VGno zIyJjVZx7BKug}J8HhmG!QEC~m$tze+&kR>N(r~6}hGym}!M(-34Y!sinyG2^M$^<%BU@$* zn_5{~nzrc6=lk>LANZWZ5B$X8K8O3o{k)#nbv?+!1OiNj^(~qTkGIr2(IlDD1bt{F z88QYtz`*GQE+gm|90>anEW>?wI%-P!$FlMtc?qK?>5FZ9buLN|WNr_TtWx$T)@u}M z*|hp_ItL+I{TLFZQ47 zVp2a|Kh#;p$dKWA%Mc13p-F~+{t7MNK_wL-OxUCxCsk>`9+JOOA2kM5Vu3TVC}=WR zhYE?KvbQQ0~WaBjRe{VCqsw_7PMp1=P)t^VNWuiCJ$AL z>?d&q)>x>fCCr*$kq4HnS7MRg!ve^&1+*aq8S5IYW+UJBFjFPUYOftQUvqre2|Pcz zzGqJ>O6_d{>uy11@ln}*5@hhMC(KhVQ4n1RwvOKEn{ zO0$zhtE&Wa?DwqLrC6{uy$PZNk}7C|ntpj+#OQJSCh3dADb<%ryt61WkDS20?aL!v0zEqMvKApbZ> zz{+yGO%txVNiH@hfhCVx*48$*Y8H9Dy|eO@<^1-rifFIHj!m@4Q_6jXIl@LK;R9Oq zey2KSpG3L5MA6vAYI$i{cL`FLl&Ab9Q@hoiWxZ5OVI7uK-ZJ##J%KVSrAmOQgQUn* zya>qWj|x_vBPmOU6xqSFI1_nlhh*u3v7uU&j?s~aogahKEbBBm2qpn45L?M~d?f}# z@`uxc|j;Z!otQ*cWL zLZk$3+Z>^=P-yd}qyjxdlL39W2J#LDtz1!-&k6sAg}$8wixR#mP$4XBoGL?VH%K^u z&ywiOb{KZVDg_P|P;k*ImIfgzi?D#&vC&SZoYOMSbxb-wNG0f=4fYCw-!GQ}|1eD| zCL=qJY8AR<-~#5Q`SQg9Q$N>Zu5%-aJ5jAE<@WeOA3#U!U`A{8m{`8NG}}s=viu*( z5nsOiuv-bL9th6?e@UQ1K7Iuy^PsVoFd?FDbc8XHu5ya8h!hB~JV^ozr%Pu1iUwxm+jYT9v}Ma)Ea<5FgNu+b zX-c7lj+%sLkA983RKJ9jISUDEOE+#n9f{`Bo)^fsOG@%-2_{gQTDnpuy-^7 z@j{%-)=0bI;RdvJO?(UOH88gkaY$4~sGZ-@UHOYGS-7Juk)sgx^S+Mm#I8h7-}@Bb zjc}j)2EP8yXG;T*)?2QYf+hNq5{LImxE_?wX%fAV>*JPngjitT zbd3gOr~x^{Q4Q)&T8q=5?1r1fG&KYfuu?3D9UW19kl_x3JJBtOst_6nPX&Q>SYQNQ zb6*ok;Q3PKL32cME#9OG%ykfbr~(KoOIH=AztC&KSS`ceyVR8*0V^{wHu|JdhrO;} z_MbCQuLZZUn!MbW_k(+q{x!)SKb~@{lQ27^+&Cx~maXFYMcNmxL3!<+xK-er-5OwT zJ3M&avFHrVi7@xLWP97*mVd&B_%mt_wOVc|k@Rp?vmgKVuz@ZaOI?FR2SPL%d@UC2 z*C5`LFm$`9l1zVUundbX?bjQ_c(W)XLom^Nj5!bQLWbFZg~=Se4OvKr45J91S;zuO z)Z2=Ox1vL133w46Mw2Jd1|d4E9!(DPi%^8aU`VRkw~IPhIWkmzInUY>D@n~i#)~ov z#0X$c-_Q!(UO$k7c9e>Fx*@L#~e2=qiNI`wKbp3Xtg zmi3i*a4VJo40<j;F!5~v90YwS?)g=%9B0<5S#WZw|Ib`7k)EI59_Brr}i z&L*r9E6HQ4F)&CWEJdhoWP3kj&^9DnTD4jF{m$Wi<#L!``|-6+wn49v5S0_-&1NCZ zz!l(ZP<$!P-?w82S#v&L-!{h8Ub?1Lv5<_l?ogm-XK zX&|^}6GnvhEQbeP$4VaH2)SoX#Dk#bJn%195ZAM6Ki!ad+f{hFzF0WiAQ(%p1u0uX zU5byL@WHu!W#h>hNG{n`;jp2JgwbZvkDh$?<3GF8ADB%- zny%78ESSo&q8dn8lVKDM_7UcQ2d||cVY%#%tTF;&M+RUA=-{ly&i&Nc*3wftpn7E% zoWKiPipG-(FdHZ?(;X@Tf|kDn8H`~Zx_gvaRZ=-2|2~B4@aa&iA;Ce?Fqe#VIfb(d zw980Ol%QjjENx@q67DCGel8ZcF|0ipDh_Y&ML%L0{*FC--Ew^q*gp~lyHyS+}ngr}6&4h_+^Ls4e6GxuPnp{}a}`htl=s(6&mz_*)gE% z9C!g;NHwr3QC?^u?BF4K(77f&l^2;IRWCbL=@bQ{VXBL6=f0aer^Ns%3Hs?-7$Y!N zRUWtVE@{~Z%rU}-oS1*PbNl!QX%^!c8xp`jZ$)%%NYXW#Jl-%F6BPf__DSTpHRWh? z#L>3!>nr#ASpR0F&#O%D-Y0=b9Ey1MaT))KSm@&qpQ)%{lE2n=Mvr>EvCUCkDjuw$ z!oZI7N=R`8i+-vGSU8W<`>EgA<50LL6{I=_^Jc-+mtUH2pjzo568)l~fcXQ0#uM;b zVBw@Od>#mn*n*sp7dp>^#4@1n^qR9AC|yx##1B$g`#J5tU_ExW>U+3vu>NP8mp@Kn ztpYK^AP*NY9JLh}{urSah_Pz0z7^!(*wlQyS;c0IxH)Faw2Ge{zVNT~O8QI1^&LQQ zDdh?5N!`o+k;hk0-zdKFAMhlUugq;Lp4PB+Yql!&FU?NTy{j>T_PJi~HFW>e(xmw> z-`Zb2dLblD_i;MRWtjp|+{G<#LhH2n5qQLF$4e@0$GMwQ`oourFxDXVs zMPt$!U=NC{sK~TZ9;VH$!=~xAQtkqzue6e(bLND!S@`D4qvSy`8CAF0#z)Sf$VXjC zzgCP}j#Nj#ILDVUIWJ<||8}Na!!PT3@2i{V;U4Gcz>bBQ&1!u2>&b#Y7dtKkLcspBc@@cJm=gZsabQ42!)5Q1} zOSvi^8efc@eLHb5g4bH$t?eYF8oF3v`GB}bQiqHqj4gojHAqnl0{~nzgiW^D7e{l1 z08un?h{#(|2HMIyjSR)EQy75gb4c2L=}j8ykTh=D5-R3hD#)Wmm4Y=zH3j|w^}{3v zQBQ`)5yCpK8Bi%%_Ka|aDhE(Oy0|;3g~jLq%E<1D8J${Y(DR5h_uIsDYwKUn>fU21 zc&i`5*xl33S@Sq#QPndORu>gEcrP-hHeR`QE9!@DWK33;%7tHlJf75?&J~sky71_* znBLviZ*~0W+gr-@(M9L0_9Wgj#vYBkt!=%heb%Vs*_rvMDYe+AZU@w3#^tvgblY4Y zNZlD(-CRmF>Dmln7fuFjU?dhDB$@yM6YF;-#)#FLTo6h?Kz{|3OA&Y)G-@z8#<#%*i*++sFJo0Qa*Un z9RSyd=r}63m|hoADG&Lk9)o8VI{#XhE@bY@Qr0udjt^_@FuO9_d~erKU8{?(%ASWsUv78BO<11f z`=4%3^F48~R;MT8;=IqAh*~*4ZB?gcnmJ}y71eC{tb(iu0;6zrODIH>2SI7MD9k8H z4X}nlXzxt04cvPjEL;)7vKAvUX%P5e26|S=^!~V@VY8d#41*)M9DA4pPhc#fQ)UFr zR61Emg34rocWu@Qa9Br!I7AoBHGo)}6Xc}ULF#r)Rw@jV)a@*Pf5gAFAPpI_Ss&}9 zHviUEuQI;tY3$BxlXjokU*yvt8hdK&q~=!M82g=A{a}2&QQNxZbUg!eBF^mIzB26> zIUgb(idQ^H`(FHdz1^e6iEx%>ckzqOR74x;Fx39jl8DcKIk9xwQ&>%!&AdY6(8=^mMR3s$iDk+g#cs)8z7@7Muu zt-Ekg3dc^fkG&^~;Jtxy0%NFFLYf7(8jECz(7H8$Y8MMsDJW+XT{prBe3V_f93hH8 zQ#NHu5>{YB8S7wQS%R<%djd@DH~=SrRMD0V?C9kdqyvX0J4_Zf05O7c6>um5Mpcpy zcrdMSUCe4F1PS0ojN=mYJeq$@h`eqKlHQ`)sZmPuj;}}Qu3&eWaXO}}U4>mUV-5x# z@TtAT&%@zwm87 zmhJ2HN0MafzkBy7)@fPaQvCxPyHIMTp-6~qS5G}xi1+pY-ARDiMM%+=qAl}}(1Z5x zAsl^SekpBY(peA)vK6MX(lO;M1Xj??q0UMdv;~3(!pZx|wESa6bdW?|j!tGUCWxH+=459L0- zxv4;()Nna&H?aFJ!~J-x^g&{3yUMSwd+mptzc)BukurN$Y>#W5(2ly>xaGkBK~XGMfXM{rOO zf&*Q|{w!U_jR<8`(@Uj643`jry^-$aN3=v1HCt)UM4r86r>(w!&mEUgW412K@_vbA zET7U4aiuO;#P zhDe>fO%0L`ZcC`PGt##AIHhOu>-6mgr;SRTQFV!qgn;_S7>D$|M@wwpt^P^6ZGL|` zORHHn?#`E1X$M~nrOEVIZTR4STe1At1C|A0tiX1ied=_=URRpAZS28@qc{2f$*hjn z)2k(i_j%liNL;8Mv#ag+_FgoajVPAuRg^|yWqCFmqQ)c z?TPqqaeI4r)C7^aK*8z)wrM~a=p0HJU@;|YnaJLCWQZG*|1A)xA^@MCfEB`wq?jma zLZBMY5-s2cqag$|SaBURL#aIfGEJHXNjAYs(*?>43XyyPS zT&1NBP%T;#MRq%P97#Xz7B>L${1%?oEOn1fywRts=!Kl4OT8>pRx|QXunWN3JD!Dj zUN%f;E$3g@R{2XvB5z6Go=)dgSXfEu^=;_BmB={bCR@42T87jhS$N~hJgqcWG_Vo%i^Oj9DkfrZ$RJ=74PSdb{!4~s@t zvrPyqN>oexW|k7e(!Qfp(mzYKSViwISLD>jZZ6$@vc*5kQm-i^|I{F@Zo+K$wi~vp z;H$1@XN>YnOZgJa-?$9FM0B$7l9>s9=4To1H=4X0rbYA&W21f+{&!?gfn?Pk)I@l_l{N}(R7*K=OkkLLN@dYQ{V;ej>*`Vpu%BmAM)#{GVanNHZ5E2aw1Uu4 z5_Cx7X%I0UFlK?5no(D=wlJ=sJ4KP32AWg=se|@gH-TVG@UCjG7zfmL8@RhbqF)J= z4Mko+WJPKNvXAhImVzr%Dx9iU@IZEP17ejE?@OD1Xi5BNtWrDSZk*fjK2t{gNg}^D zM!9a=eSD`a{hL@_l`;vMA!^vz5-2k`)@Zw^_FL_O*Q6S4)vGe=!W(Z{kLe4Lj${d2 z0Q^yeXvx|IMYeEQYm(K%2fF-9mD*{3Wn_C1Bog}zBCQ{~7cFv|2At77B+U{RCj=|9 zz(yd*1SRzc1M~zJBFcgkIe@Mxf+R^45rih~&1n&`y^=N{v~<{CaL&D^uHBCg5l&>| zowDR3AAJ|OybwB&(~;lQreoW_+fdayv;8u@@r290cDy6q-Oc2Nza*eFFBM4C%gT?Y$b@KIht;w+RT z<>%|UulPtQqdv!-_YI%=iXJ_giH5LnW2!bp;B3VoBS~9FYN$gkg zLeg+X{!-QDbiwUYrPT+tldkIef+}|eBzuSq3#j3Mo%pS&V{kB>dI?4W5X@8Wor5k9givFBF1oW8L7QBdLNcY_m?tC5MD@ znarl7$#8tc_|5eGm^ppVwWXUi8#mWa^uEum_()W(hpWE!s#r*<=nE`x_i?&8MkHq2 zH^mOKTfLrHItNseZ@TFh{}_IhURkK3Js`BFnJY(a>bgtnZ+PZcg~VgMLOtv-yDHs2 z_Z>`41hlDOwSm1dBq41yWH)V8hK>Fv4n2VsDt$z-_ zNmRYC?S8`7{J_=rxyk?9w$q&^0|L6z6J7LnG%B{Z7kc$%??jNFRv%kY9h)g3&(XtH zrS`~}TFPn)Oi5I1-8E{zAevKML%D?i4tU!swY&HU(cJ8HKw&w0 zDrL$;TlW4|M1?CNYooXG-ZpgGw|}oyMs2s{mQE#wsj|vtjMa2kf!$5n_o{3zyRJIC z%9W};vO9jmf;n`7I5c^DI7!bVWxP(=*iGK z8+HtrQn&7u6A5P~;}u<6Xx)MZm?0M*b{bIU8q}{FRINj}{d>h@z`7^EQWO`qwe39{ z&~x0Rt$S9x3vg_VRK`(t%V#*5fWqIH_Q>mT30>{q{Kk)@Wj5VjeXg9{>u5A` zAOoet24v)cT0Rpsz1wqj@4Cg1bL7C-+tobHy#x>Wse`f%ePIJ>0ic2i#UC$ElWi8 zE=ue^yWvi6uF%Yxjy%9+luCaSH1_{`bw-?*+&UeydX)pWOvo)F;_+pF$)$50ZFEVg zhRQuJo{H%oxzWauOxAExkg6Y*JYmV|JZTuNh)jAaSI;F*(V(UUKs5_c8v&}>2koao zYxi+kZ@^Pg&xyFvk<8~9>o-HOllRO3QpZSa++NF}-AyIRn=E2&o}R)PC-?LD@AjFW zAAQAd9~$Hrwmba1d~TQj$=yzI{`ie^uj;dVKVI^ZiL=(JkM}>Niy39dfDxN zzl<0rem|{5FCdG2P;%kzzJXo3xuEu zuJc;Y?dNkER-LHR;U$2oka#_t{B@6t+iy>G=e7YOJa_f;zV9;np^ezz^AaOF?sO*pW?ntC>fZLD9RB$gZ7u2c;_Xu?-TT!6U;TRzyDJ9-x%;Q@`T0`+ zcR=j3K2D1}BX8b$#BKdn_BvMgDhjmo!SimiM??r+f4NgSEf(aUHzFU zn3Nu3_D{J89@{`_6T$bCH0vx{+oSq~m;B};PhfS&;K%0X>a6PN?$pNtXZf2~shA5b z1bn^tW7|{GxiM4m<6rI>OI3~E3N8&m!fatg{Kn=}o+wML7j{A zRt08@4n3a>1JtL{p7Vl7w8cLm;}BV4)r5pTFj(j(cH!Z`OT|tX97t^hhN!kFt?*59 zWYtveCYOg+C)#ySu%uxX9u9%G%R^noCvnFoK2BXoW$OrX*S#|NDtAQFFX^xi@-?~_ zsy{|(UVmO&u&-ycse9`Bm*yCqwtYIxKEDa75whV3&*WA3fSz2knXOY zUy%GOsj8RYh92&Lx37i;?baIdj1E3M}2I7eT5-o>t1hCFPh4qbVz`5N{4$5J_G+L~ye0A0V&QdeEeW zb^SpVp$=o0^uoq9-bo*~F@}}bkshen2IUhC_77#47F?FgbXl-p7}<2%FYox>ZQopF z+^1eY=g4k0d-Lh1{kwl6_uZbG_={wRTGnYyOGLf}UW_(s@2hYR@VG)e&L8VCd}8nx z-?5@2{>Al8hDVX{2i4p!*M5d9ttb^?u6i-Qpk)laMQ{NIG%x zV*U2??(gHXOM9;<=MPLA4LN&>@WyvgLvd=U;C7o#*<**8M~(P__@07f+pFhiKRV1C zq|aXJRz;y|!+cvFxi0-_I5=EiY4?tJoP1vhmmz-7V=(h~+~PHRJS(KM7~{YSa#i=& z3#P<94#${T%lWi@RFZ!*R^}?hGKY|;4j`Bk_{Fx1O=AWIB!Cig%9G-Oib9#sW)&Xp z;srg%2N?$>cy=@R{TD~K1Mb9NM}1H3>57W#;Sc_4ESb3+{M^z0VY{q}&$YkzJDhrk z8-7F%{fUURiP-8n6$2)OR@+n#OV0!ZCEC@|#(PsqP>E|1b~T^ddh6-UF(ZAl|G6^& zOa0G>YCr+@R{bUA^bkcQpqy@Zm{quQkOt|JAvT~=?!?zx zMbp=bAqhe|_4c?pWZDiIi>;@aRclv^MD!kJfihK@?lm3d)5*a$_buut4bDag>m3t+ za!jP9f~}9*f6uAq+JbPE%9u9EEa-_JGt@wFBi!Hg7v^ZzTgBZ?pY{c4w-9FZFJBE5 z*2~bCOpJe^th+B*x;!!K#>dPi-50A={=BN_Nmu#Ycj)_vV167WkmmtxJJUpS)?56L zRYQ7i0j7F~qNXFBS3J;fd|$0xDFj~%5vMBI)jvOtY_@Td>Qt;xP;l%nvp!g@V33-e zh2LA1rw|KK?P9^D=N!8epI-7wD8L_?xZQHH=c~pKnPWu`)_6hR+WzQ*O7OO_W`EPC zDEfm}g+^DditDeQ$jn{%t5YVy;Z26$Bh^PHgxAYZ6&*fF{C%@9yTT4uHJr5-$-nES! zKv}?RE###K1eM0Ss-$%By|NMef84qdX6J$DpyST3-ihQX3ssHlrN*B|T8pbO@_MKbx5~X#G~PZBM&cPTq~oS*#Z6fpG3TRo zQz_d*Fp7U@^mzDL=+H&alk*^?e(o|mv!6G?%r&9L}A%mY3e!AVfj;K@%+%B;nMxo`Cpi8n26fY$)1#o zzuEVrzVE+RI(~q-hu`yd#K^0O7StA}kQ?t5)Np@Q6FjPvnHFIEXr;gk_mR<~uYX${ zbH@dgiMi;KrQz!OnMS_g_u?(`EYbsKgVmJ;dgDFt8|AO958a((5C0D7qG#zL^*imJ zPL+dSwVitKEZ2wPAw5dJq$PS#^>OK2O&CV+e62KfV7yX-R&tV=eiEaEH;P~waaY@LvhO~&+6UoXB`nq|J z?y7fu;25szOmT2L^nMhf&W$zZR~m;A~?U zx^aDZDnmJZ+@=iX@Z^4h^5o%~hT??sJ07`Uj@na<)Drt*k&ys1tLg!Q)$h(c`As~? z#O#Ysci$zH+O11wcUsQqVix^6HWj)Xc66UbqF$fY{O``Cm$&lS^v=tOo7aDpwx{d< z>Dw#q$S2%{TErupsa z0P;L?D99OBrq5GtfIK?XaoyG*B|ecs8`Lbcff1+lfN8Lx-`bQYFxnnG`6{%E7pDE46;fse*!OF5EpYP z;SG6)YHl~6Df<-F^GtE&nPPunM^oehnLn3!Z>}z&yUl#_!qx?fI&4iU(_lHnpihge znF$wxt^C}zA`c6+f!UV;OmuGTh?0(`X~R-ZHm$mRSUI~|?1Osl1}GPo)>cevx4%19 zR6Ttw6eRwX%&edegd$J@PrEz`u>9A^DawROPa>|Q)yB)MLEg};~AzR7E7eeL|dii+cS}E;r{QiE8eVx`WSFNb^Mo}I1 zDQyk~7iX}lkB{nwj_mar+wFRHuhk7n*Dma#P9>iP*;6g@vxBH3c7e%O{|mxPD&OpF1rgQi2#8>FkzTD zPMn}f&`?)V*3wfqBx>vLchS{0G&V4|Fjcj3S2c){w+bdXn3+3kTiKi1dz#tWSvxv8 z9ddK_aB}nXay#O4`0z1Tk7ygSNPks&gla>qW@DC4W|jMq^5f*PK-)_$7Ci?Hht)j$ ziIkeX6hUiSv5a9WUjOPI<4KIh0}Sbvti>C=%O_2bcLpB!WV~mw{;$MiS0v&Wh;dK# zPQJGbf8!qZA}s7d8av`+!0AE}+Ir|UjvR(;AYZAAU2g|!}_uc)daqXFG*DcwShv@vzQmpr4y`RMX`zk)ajD7S)>g|Ty z`*-LMuVg+h$bXu`e;wKP`O5CEm*l=)*t5kXyeP)6(PbXQscgpUu0>!ssd`^1d+vM4 zy|WkJbdugM#(h`CZ^`WaidFl9)A@qcc}Gxuwp(*XQhj#6^($T5*9z9p#mQ?TZXd*t z30_a|$KT6Eyw(olk;C5{ihJTnpLM2B2V_1yS$Z?Ru`|1&v9`IT@#3ZbPcyzgIyF5# zG4lNO^)I*QzdyMD?Ai0@FJ5lFdH??5_LuiRzkFHy@#E*uU%!5?uYVobNfn@m|NUP_ z4d448)bIv_2Ok}@I=?sk*-L-)w)smz2IuV)@ZR;gKc$M#@y#!-;(rt!e+mEEu#x`T zo#VHtHL`j4_aZ-ru2N61K)=M^Jk5WhW04~JvSROavGw)L^)F{#=1*NPOWv9|?VlXI z@xayOzpdNFCSTUGDW+d(4-c7sNg$`mP~)0xB^74vS-xM{!AE0%^MVhVt`A@#re7Yu zAz1zxxaDRVo)Q?0JQmJ?NQJj?BwBp83}2(_-ya2OOT&EAl;# z$=pu_-8SL-Ca^xjec8uVeg9k!RyJ2`)rLuW{gKf`e4Y;eY`RS?{cIM&Y57c?nJ)vB ztK!gBNHsRYN+z5>_6ASw7C&JYmBExnP-)!Elz*HDnI>q7q)(LnOA)K)J0~!E%@x=s zlfC1v+T-w=>t!>ccU>jMkcKXL@1$`y{+&DdI}>w|Tz@UGCqq_gie{sNXZMd9J%=##MhVYO+<&Ov{o< zZqk+s@bte594_N1U#*k<%s>!QsBhtWq!L?^imjwH!SVh&N9I^LZA$TM$PR3GP(9O* zk5932pHZ#{-E=go6Y9xr+hm4!Tr?9qqB_6-<8$U*WnS*;@;AbzZsi(oI$&07)2*re z-JxF7r23)TxQxnT;P@x@e_C7rc|Qy=k*el3%_vr7{2lvx^PgNAQVo4C3-6h}Y%A@R zKBhdyJ*zFORPKOrRAL@YH6t>~?toGiEog>VOI0ZTP!k<1)>--Z=+8OGi^_heWj@W>D(ONhdEvP(Qfb&Cqc(YW z;O@caOzipe4AaAjVk)8sarMJhzc1(L{^}M!_WACFIcd!JU#J51n~~yA12CZLT98sn z4kCV`=bl`+h5j}@q4l@Tn@ zvRKlyN%_*_&SOu%xK+=-B_GMr*UM=V&kWB{Jr$m7+60N)8w;?_3fM)Hr|R~r z2=CamhO40G0R3#3k+Dx-pA~aCQOYs+^mHZ#OTvd?@21;Z1b|%pOgl97kW0fRpLVY z;)gxFTKN8ftuw?9FoCtKcDFZK)u1kwX+wL_F6DXN6{{P7o9}?$|qw zV;H;>!AH98xK}PDo4n0X|10U?O#hMGz!P!~P68_L=(X2#_@Ts=KHy7kUTw=l#M}YJ zjzi16ayvQI18=pple#ykHJua0O1~U?BS>F$kDA<&MpQ6{9L#>AA30=;VXcA3fJ5W6e*HP$Ezbu94~`es}kvZr6LjTVa0vV zc1^?+!8RX!tLV`aKHfA3$v9ne-n>60J-BQGU6Z;~P(J0aF zYRR*l^(|_syzwjBf@X+jcxzOTejYiuB!4rK+)Dq)hEcb{cY;{)N4FC`M}8P<_`tUo zEYRU(y&!b?dXv1I$uimEa5Iz8MpQP*S+mn?F3Aa1R0Sg($ph$uoC(on@7zx@!)Vb{ z8A=#A;C?`FyNTv=Ly?*Lxsl{E> zpO(hZL;)ChZ%j1!x4a1FB{W2ye~D)qRgEcH8zQWnJT)m3#C`qhG7HwXSmqXlF3k!L z{;TEXh#Ti+zoIEdkLBD_G0iTgoi7(`x7XbpC`OO0fo5uA4I_A)ASV7jF*6tthXMl? zo|PQn`#PeU4TwEFT1OA50wGQf!qQ2?4%u-T^tf~oLcAT~YW32fmUy6|~A z;yeqU%TCS)A=1c*Y#1V0C_VEn+>Zm#Mhl+ z@wpj%vpIo#X?uoaJR7@rrk;5_*w*@j4 zk!1u_BTbCINe?pLiYWyfD=pamVKFu-Kn=yZ-4>XCcQlbkRrzk1P7u>J6i(s6RS}_K zi~c#(%ycRuhy_n#3+shL&d|ehXeUpd6@2g5EN0$t0$fK`cw`86j)n+g!ZeJ8lgS7= zi~666&snAP7~8zH+wcT3!gf3JF~Y5sjyUIlcqtX}IJ~fk8y=>5zVvW*QD{;<=Trf& zFvKVub2YGt6!G#1BA1CMIG$C&)@dRHWqQzuxd3XKe*KZhOo>I~6|s66FavYSHy|6m$IWe5Ip2VP{Gk-&}(UO%~gMu44#)46G3D@B>4tXEP+ZZqLWi9W}T z&MNo>9$H15lS1T@5V`cC^(pTHo;SiU=Bt4K6dch=F)KwQn|VMf2|%s@eI)gtYydiw z!z_{AM!Wc(5yN!?SGHWj-r5wA#heGcUwJyE(cBAYVg+P}Yz{n#j%dz7%>78urX%dC z5h*OVUUfi!4xGqDB(mW7?ATlyq8UK!&xL1#;qo*%(1?)5`ZRX@ znnP9z=+xKB#sW5?feXYYq8i9zn_NIa85sjy_(?*>OCx`hgLe&!S(aHKS^yabkGu%I zH%eZ0T!e$3v*@pboQDV%Zh9~saW@xH+trjxN93~WhDgFm97F`#vcL1d5EY(6LuIoN zL%gOQM?_C?9zz zJL`wgwfSgaQev|*6?KLroX>^}>O!+vh&(2uA_+CbL=3VJQcES-B;i28`;WDL^rlp9 zO=DO6i%>*18@|7$gq7Qx&qU;-QTZf*REzLhsz2*pnSrLa~tU6+B-NF=qVDsAgVEeXNCKt$} zIHj|_Vr`yc@_2P-&Am9%@=FM96XCHLxG$;OED4on z(>KIMi(~ ze8~EF7y)|D+C(Qda}mvKpq~R2pqsPlsB9`~|3$=}WW+U6{|F17M@6Mj;DcP@I5Iqn zifTJBGE5n{Mj2_19Jx;DH(SaGrna<>!1pA!UL1jEv1?~OHedSKtoiZ!APF`730RXs zmC;9M@<;EDBAUn%+dC6~4H0q|n_fSS{rbV%+Pi;%1mqaf>$!mW1Q34!bsU9k0-**- zz0oM-Pgciv{(sZ*DyRXmIw~MMXx57Zls(*wlf=r|I{bV#ko%-rCS`1Q0cwy8A7LTR zuuvVBP~a|9%+s4i-Kgu-nd{8)ngY}n7OFzC|MI1aV-YArr#l`rR5E#Nm^GTu86D)- zCXxH_DPzOz$pKc?oI1+l(!_OBz~wrk_r!o5YIc8Kv2;9wcO0=x6E)2BPE}=AFcUVZ zRl|hd3nWyB2C9D@IEg~Gkp80VLFc!epdfrV;WzsaJ_+~A@{*xX%n+-p2k<>#3cHvAf`9^U{{ zHMtYWn^r48T>~wQpf645qy7mZ3IzVd0DG{X1e}#Y4p2w%vv-FzQ2%M7wxwpb!%+oQ z0|QLNC-s2{m+_K#I@`0coCh>gQJRv-%OsTcK@@5iN;*?IueI)1~C%!+GsN(smT0r26xv7!YC)%Ayw-oAF>2<@I&xqgSQ0_? zab^~~C+0t0EMp-W(bsz#9*{m>%%P*?Mjkd%5Z5$-MrK4N8gW`0Wo26RyZ}|oLaaYS z`4&E6uLDQSkiYocN0$ln$NYoM-zbd5xtFaV7BtM6zA?@0;kZOjtk1|0Z+eJ>vbv7C zJn|%kgc?N)-yp+-Iot*gD&2ok?Bq<|UsT@78F@3*?pc&7dSc24b&LZaBnbzzP&5_- z{P$_i^`~`a_tm;lOS1npq;#kh%*h?>W6n|=sUyaJCzgLVkC~!|ct92z7$h*=D|*T) zISQlQZ0-Wz6kx9-dpUF7YbdhTix|HbsdxS#LuVcq)7!@Jb7ncS*G%hFQ%xI1GVRmq zOnWItrA;#Jd!~dC&a_M+2}KA~LI|Nq!kP9>LXspCAyjYHU$*hib@kW$(KU0+Q^=i$GN_X=2M#JgzFrNLVSON12xef zH_Cc@KK0%f_EyjK9vkm%7#iAhneurlrE;RTqU3}7EUAh$V7lzg;J#Le+H)uQ$~AP- z9%0TYfTFvv^=et~(2lXhPj6PwQm)F#r%`f!!|BUIT;O^s^&4pi&e&r)S z`J~b!%9DDe5mrtbKk#L2=;Ga*;mas@8Yr!@(QPj&(Q@)8fN+c4z&W*b~d#Mftpb1$*Sp=hG#AF6wQLYS; zub||N9bYfg$%i$`_jkRVyXLy5ecS49M_vEj`Zj;-f4;?N_R%!T{cD^@mE%LTf5|ss z!hK-6Rr0-&LwI)&f1eHshi=Zw=TQ3pP#J}+*A`1}Ym!iY(4KCR&9&1B;j8Bj{>&;^ zp?74xv%5xHB}4ZB@)6gCwFhoqM;25Ay3U?_yx93k<>0^-$E#Z|5Y0zO62bq9Ii&2; ziCZv5MgObouA5DC%2j~O-S9N*B{^+Cxps(rmNRoss-I6Jl`SrAR^IlTT~4UX8k&^TBF5^~jag z4LJ`YDpNJg!%qvpw^gis<{o)V*!xB8qN;_*VaJ`n8hZ}cgrm71{IdH)uB^W&yxaC+ zrQv08TPIIu;N_6N!LQ{wI72ouDu-9d3^1skc;1b%)T-1n>d$S zWB2k*_SK-pYYxv98on?Kt_!bO;+SjuX{|J`u@vv*t|bD;mT*`h1VDD?AuJQ@s7Oa@j9lX?(ov^8yVXIpSy$_dTDL`P-F5* zy*{*Y@J+$@3+hX&Ruoleccz3b-TCL+_xD9hL4t7uj8z`~XufLtcK6{O1AX19YrcFi zc3bsBWOADC+Uu>cW_#Y*qx7HKJ2fL-7suMg2z1_Y1Stmjmdg;5k=0n3s+bv5@-x14 zSsW-Xjq!8JJi7jMor!Jqu1A*M7UJqR-Z8_?>Av@JZd}%URc5WUaw22twWF)!CJXO| z$NVgCh_pIxQtK=9jZ;}2^I2|jFg)#`iAF@snz#q+vwRQSZcX}W+I$)&ku^di!V4<` z{j|<8Ly8UKD*}(Wae@Nu-v$SrEg$n%+iqGdJd`^%&S~R&eD-kXdu)5FTJ>Yebj1dt zw)jXK=FBoXhnw_-N=}ro*S-xY5XcEk!A@MYra{gRMa|pI>c9mZu$6x@U!}S zo3FkYXHY!Y?|FNDcCU%1N7Mz2XhGhdoZAP!L}st(Lw+VJ2!0NJkN^2y`xbO0 zH1Y0c(7oDQf4j%zVh!@$F9oMpyJ?xU^I@&{tzqta){a!osV~ubd*GN+X-vl!?PGBm zACqI|HKlH&R@dzkQkNBf&Qy<)amC3FeH&em>7LN_uWZ_H=~WrxM%r5;xOaBOZe*8M zNoDkrs-qcKYITNg=V@LUT|Y06s;1zecq64d58enZ_pP7D@Sp$cu!xAR4fhvn_GIEe zv}|(lx)77y&J-^R{Hz~bm#5}ufJY+j-L*&N_5B_VxjIUf*OVCQ+not7fDbCay8CfM zS3dsB9KIy9IYudqAH^!Yi8FNrwX%rF5vzKoHOV$%T56!oXFOh|ogivGEFPIj(hEblMo)n^ z2ioQfUn~ha*55#@{x1t}>MGS;U4l`gd@D5Fe`epl8I1jn27$$oMU=3iHuYwr_@ISR z$&ZECSqAy~Htu#80vp`auMHE-1ZM3~KZeia^N#IyWLzYD_g6!)ofloJl_l%5)jAJP zt-e=rMxY+6G&uTH<&c7O$9h8xQ%7wsAtgq^)!Qy|Agjk(MHXx$ES5i^S%1NKOWyJm zouda`@7$8FjvKnptQ}Hby4Rp&=j#I%SB4(FA4@#;yJ^1_!*lp9{q5n^)%|S79GALP|2|}Jmk_7w*{g`(9bq6`?isR@Y3dT6TjVCI z_U&;~7+mey{jsd-mfjq!(}9BzceW|-8t_Tn5c)aP>w(qP`5O;!joh>VubxBB3h}D% z&*)2Mdv?vw&wJPW88mf2ciK4Mj(%+8X z6$-3&twAATM;6Y2&N3}!j)5RtL{3UF(jE|cY3Ko7W`ogS*k-`?r~$#j`7`*TUi3wshF!(%QKo+0PLD)=jrJ8flSn z@6V|BrhA&b`+9i8|DKh0hIL&#mKhTdBLLm!hc!z^O)z&??_=XFo=Bi$ z%i2VE&2%3!a;0TmR2;Ltf8k}K^`O?f7_LmKb4&bxAJe+MJ}i#4I~)6A#JeQyyZ zeg>S?j~XhRIG27^@?>e);gH0DL$*C-kWDZzDyf0{u^%oB^cRtXWI0_+2|H<-l?Nsi zXa45)zn7O9{!CQ6{(9Z+Z>KH&mPLgy&uEPaTJ}_2D@k<5YOfc2%^y9uH_O9Ciy~`& zT5YgDu}4H&Yk}AtdKAB7b=0;erR) z>i>ReSZzL<1P)Sw4vF`AVihu6D8a|>&v8gQ&9O$+t-kM`$rKl#4aDXkR_M*e{)NG?BC%1s zC{|VXx0}=N$My@)mHEZxbD1YLCfkG}_@l6n|A~uhE>a~-ape-RfC!7_5Xp#uJ<3`v2Oo{B#RC3b>LvhhrwZV%)Xrm>NbdY{k|abQ6wKN3pF5hs*M380$OXy2LS;o}=%h= ze$x@JZD-HtTdR)UO-w@48XU|1`0V}G?`ne&8iGQmdXnnIp^f5{GAKm?y?WA~ZraNn z7AN{Z#4rr8SghUJp1|pSk&obEC^0OL;6pfJ=&-4(O`a%d*}!uA9k|p5b3EY1`Oba% zip;jx&(l7=$Foy(j$Bu63@q#ywQl5);}>i+QlRpsg;@f47rQW9cHw&YAoi!)u4Xk) zYENUm*<;>GuWgR%V=l31XVi?RxY3TC>$&IK%Dv9`4B|kdXd^(*VH#X34`Zgu=CA_f4kgpx?{2K*31i+Syh|R zoPdN!PKlHHp*8NmnyY?2K6vxmonC8kC{vsu6K{^h<7b@V@%Adm!q?WfgM4m(`1T0w zHG9=Z*g09;sRpoWoc-1AgjyjHS{5wBaLADQ|G}*)71A$#>o}u+(YuZ4TX`#YJ zy>VWgJP+B-K1>jZGi3v|e|`ScLx0M}sbN6kCb1%)n%3N&F65;rL9I55d@+H@zm}ck zH5e)854dWj^_nz#Z1BI7z3;TDoMoQ-TVrK%VH9w4@!vfm5rqltj*w95pQe|>r9I?nS_jDar%PduP6P%Na`$IKk#Yz@qjv*QLLi%vwa}g^fLTr5C54d}dn|SL85q$5%XXG~OV2JDcV?xD zwWsdJn-)Dh3CYuYR;J0s!*|8Ms82?|Lshh=Xd1M2TJdCxSTgY@Izets$QTvtO2nxP z;*2sMMPogMGmtth&Oo7L1&uAq@l~2$6?7dj`sRUtC@o z`QQH%v7#yKNVazU%%@W?I-I^6L96@=Hx+BdB|*fTdV+E5-)cv5xst<5iXs=!TT*VYKj2*Z=kuVvZAz!?1{sRy8P zyf>rBW|)vthR_8fVgm@(cDv0yA}oqKhg4V9n0b^s9^e&51{8X&3J+$kXWoT2CMk?1 z2-G0nxBz9cBQob9p6K!L2^b#{w>u9Uf7+kovp!l6*z{7AUfjCuT+e|&J}G=xmlD5KQ?gBgOI4i~ z|Hy~H5^37RTk7$z8n6~-os^?DF$<-K$ToTUuNk{64qbP=^j#NuNZIr+q5gPlM> zWD!^LSNWf!ZS`?D7cLyoz3qJjez>e?uSLt$M3aKjy$-oQ&AnX*gm{IXfVpe5x!kkEN`YC=r0Q$U6GX-=xohkg7boxjt zop5$v)ar7dw29aEaBX_HwnU-hs;Rr{T)NkCOgA*z+kd*A1VeShF2T&Ac&<232w{Ch zT#h$UhHQZe1?!8b@P|zTk(I(fi~@%&*XAD~?;0hvxlWH~JI^A*;vzf>9g{&k#C$VC0XGFeIttxEBtM?JllP7*;2y!O^Oo)VzQ9uzz-lLd?JyM%FVOqVsz#~H9ppe?%^Fd zf4+`@zaIu|uzmQ%??80-fTyg(lRz>i&|Q-^p=q1AgiQ@1*8P`w;%l90kv4x;8^Azp zg*2F;=Y!yxc?QiQB2j^q{UPj8i0G$;b;(dzkl-Hp_U=p8Lik2moVoo+JQIPE5cAVf zb4nr4M<9qzNNWZ|)k5y8g^npB52wuvQ2Xj{@of z5#^OwjfsJPcWT0Xy=D+E$g_tL>cRok|F+*za*l#rdh1(M3d+=Z%)~x_Uk+rCLbMfl z-z(GEJ_H?NQ6`t5Y+od70QEQkc3z}CEy^qd4!=`eUs2?Lpne#FW9JE*MFy3C#)4?$ z{H$;YRDUnh9~C7f0mtk!(i*_=!Yzw8MsMUG7*w1l0PuAW(@iIjtN-_A|Lc??NMm#) zzAJ0`T~BoSK+TDPqvf3kvU@`#|NA`!y$otGVv7jG2lhmf{gB8h0Mr--Gl~)S_u%p6 zSPLIOLr{b-T~#kD+JX}HUR_xKOYPv&r}7{{Q5H--jd88rJ>#A*;{EM!J% zM6HR6P9YX4R##{`{^4AFd|}2$36vpx4skIlJ(KMPbD7V6q~?ez-HQEB8rW*r6fxHG zqWNBSZ+a49&%xxZ$WsG|YFaE~r`PX%?1+r<23cl4o&x$r)b$GXs@*U7XO}fIeejK| zvewU?=E+}-`^uMuUQhe*Xtns?}L;{nb{9XCj+3?Q^U4 zv3YGL47^oXpjAPSvOX6nXqO+X@TRg<#flK5dr>HB5*e+VboaKyuV{NT`y-(HR_m*d zonI4Xb(&jWD&nPE0=(^0pVkGONO&;Tm~v2Ox_L|7i<=n7b8BM9M>i#QJv-$vv}jh_ zW^lO1GG8P8xJ^<|g#Epd0j72G`1V%cA2U3hwONVHK6;*Kf!>R-M)sjIge*4kP;X?wF{@gb*y`Pbctm#>IAeIa{p@IEVtKpk;tcHSb#Mz`Z0ZhdFgVtQtOP3>e~H z1TZ$5BUE{^;v2@Z9_yJD;~dLkJ;&_cW^I3HgyU7&Vpnq^z-~NFE8y1dTVCU(D?)D>yoi)_vwn@8|aY9{wsH z9GD-zap3EZ(M@Z%%!Pm4G~{+7c2&3?Fzt@J|oP4@fqlr7! zJV`i-*NNowlw$<8qz4G3@yQENFpHY9^L3n>58fPl3_wZ!z$AKv`zvJs{psR$yN<1i zlAXii%i6Um)0Aj-yH={;jkZ&<7@LjI`ZvGRt~+)pwpFx0fzxj3Xo|soJWIEy8fZT> zMYYN#RRlEy(6t$~7b67U1d#LqiCod%EKshfqDh`AQ2@iA2BIqneQXGB*oibKbX%7 zX6QWFE{K5_n5pagbr{oKw7o*?MhN};Vzsm+fbz{phye~H*iZ8?O4~$0c{FiZF~Q8=pw&97R?moI~C~`8=XF|yW?|w{>O5&VQDYbU&e|D-Ec8OdF&1evFIDm zPy`oXyuKWS%BPG!EY3d}D8ZQ5q5Ad?;I&6=Ib@?a;vhhEn1w>b$OV?pzQaQN&Ea-Q zFm}6w<;JZ52t6R!9D!gs63}VrMaiE)rZC&nOl34c>DP5$w?nD66SEuhx-cL$^3A$e z#qX^vhw~Rze$eXAbjRH^*iR5nlBlvSJ43X|(BQHe7v)h|HaH{BByAa-|M2FMq1|XK zj%u>U#REC;$gQzy>87ZG1P$e?&EFEVZfm)w9MPRTW|%PDgW#;_7%Gf2RHaJ{MD%=* zuI!XxYXPY5;H!ngL~B`cf-N7sx*jGl`5&)rf2!f8jd;jtY9p7DSZ>~2b{#(b}3!4(T&)R{0|#tLp*HM zR~pMB8hn@o;S@VEl=h}LT-au#O9z)6awpisMUIAo{PHf8NEDQ*n7+n|pzNGQ$weu) zD$0zR{H7}|S=&arW?Nc~^qNjC)7h71y)OZmXzAqX(qy$1(Imd8@_dtz&uo5drjc*@-JQbS(9o1agz`l*|=Otbrx0l|C4ip`+N1^9T_9 z7FGmfId?~BAYJ9)}PgcreK1962c|ZpCvQSfp&74 z)LMgG+GqJ;Aqub;sOx){#XlpJy?z78&TV%ok-=_9J-3OOh|E`T4U7!7`akID6=rtv! z95!yLKuT;0sXjGvaS|@$(I5LaT?m*x=TInJWm$TEWoe*W{5=>-K|}_88D0$)QFDhh zjG56SkGh)Ry>J1(pgm*jndM-x7GlDdymzew5jB3n_a6cft8k1>?~n?o0G7khccm&x zzFyC9?WK=-;B_95!9)qTQK{{N3R-XWAhe&ZAwbbIul1W`hJ#lPjO#soLOt} zrSq}zG181gzk1G(7TBRyhlRbB3317q<&`YJA20M*N@0l|;Z?6CEF5Mh>uZaU6 zniCzMVi+{wGaydSUQEk1#F%QZ#5HWCDm2B)G*?8d>M&|JxB^U8|G-$781k+Keqv;R zX0C+$?g!1tlWP= zV{wP}_C%4X7xd+N<%@i3k?fp|tY8tI|0Z?oL146hc!h145pfkhkCon`ol|6D=N| zD(2Pz=I}O#h?|ptJ1z#3+fF0Gj0ISYiQ3u#m~j~7BADFQbW*Z=Uo26{s_)l0=Qjc zkcaaR7M@AH#&FI-R4uBVX4tylCHLYL)X!rs4ebh6IiVO;eQo4~pelKY+Q&DG)}!Pk zU?dWtmWQwYtB0QtcI$#SH=(P-k*~cl-q|?AZAvj3!EHvbAXPL32yaHI1?`kNmXZyK z2^)()OT#inR|@k*ty0w?6TqAYaHI^DXxC>HU?qvER-;R88-I?e-qZMeolUfx)2skyj z6FAS)0>U#coS0s_+6#3jmLQ7TPT*9>>zNS|7|H?mN1?)sV^ACnhkUpkjNnbFADB;ackKr3#i{6Wo5zQq_LCk+t{Q3qp=g70813jpYK zD$YEdKS7l#-Qo!PE_WCqIL`kS)nF|618?@pUtFRQbc!DYsRxyPQ$INR3 zwE?!mW7~dN)XtqQqUF9+A|fhuks}Ybv*A&M$LlQ>#%~c2lMlv$>S-r0LnuZPpJ?1~ z&s~M}q1sOaG#sd0d6J5n;5o!1S5Z*{sMa7|Wh0;PmAR8^U-+0uAB;}Dc`tuIRJFea zOK5f{^k^LTQRiV6?p%PrtkENK3yJ2+R=Y}WMd0Jt#8NI zyB|3;mp=CnKeb5PHICMb;Qt`>nZD1@kQi6vft3ggWclc(i6aNZ5muQcIP1v+YlD!(h=&2A7BiwAP(gOM$ z$Kx%6DK@;=yR&L+aGt8>*MZe(ZugPplNGI~P>#p?`B$r=AY}`c?eMt)4fnexad}bX zT3Ajw6GiZ8NUS+^I1j#?g+fW8Z6Q9&8=ooWlc4&1X$AlZK2UOK+Ih*0C-2g)WH8P| zCoIc6zBj+q;xrXCTQ>?|MgeT?fs^8PWq9q;S$4NrswHpDJtetfK$x0 z2EloF(HCH!%>#@nPu(1`?fD$+%2WOZUrgj(j%3BxQ`x*>Hz_ehdi@Zvedw}pv%6iXhjVsp^qAFGSr)YV)U7XB&~7+3 zLYa7HK$%?aQVWpjDtpGL)j`hz40irq-9N+12EP=$B+2C5n#raK?pJ&hFS zW*X})S5xR4{39?`+C~~EV2l_nNu;xpAP1hB|MKONXoq;05TxG&PV}%fsb9 z(Y_?5%K&?GRLk`0X*hVja=cwG)Ln zJo*htm1M}3%LkM_07X?r#JrTI3W&zIrU7Hs;AryTnivcfWrYsx9x}Lkzosun1ZYUL zIEre%$d3$bRPnBQ0~BYTitx6*4FG;aGecKSDu!*o7eV>Sfx@5z!5=O0DiJ3^C5BM18h5WDAXLU zGyoSF!&RM#78^WHXnnd1^&E94An@DhGlVJ)S8nuM&sOb#+@Os@2c--`)r8YHHCOY1 zKzlpo#eeaxb8l|$A`0Py8jckD_*6RL)I0&@AWrpwz4r}@P{rQ9`5D@TuLsWFL7`TZ zT&LzZ1k(;=IQpZGCGCzKhy(Swx9irduE+gvVa9M!sWqyEM9}Nf04`63h-^1lPiNLB zw#k2|w81cKm`wx(dqga!U3BT^fJoe;NPzi4Jk_tG;U{iL3X*sEG~-RjZ9YrioM4!N zYE$(0`%SnR6WPe`BM-D~Ssq#0Z$_}tetp}5p0dfBLb|3u2EO2iCm*5Kev@J!i8egl z9eSVb0mG;t;GNCzCo|N9N#iCdi%^eMW$*id!qAF z=))L#{Kf1k;rU&mHE#tM5Dcb&5 zha}aVh3abN%|r8;d`NRTF067sKVQuJG2_x zAOdtiDiRTgR2>8YAP+|-vw=JW00H2TDRFTrBtM|%yo=k0=xPfwWYc?`m@52ZAbF4B zcCH)EAP1d977>N7TQ=VN@J>gFe(pNHF*`|6q}xLBCS+`pfJAoNPf*NGK%{uhlDyZX zv$e&TeVcs@;!i4%G5XE7@J+8T$?=h)7jH>Q0{hG^7%#QBGvBfgyOo<%wER9-CezKC zccAL$&TJzT(w&p)Ee%&xQgP}E-!Sg>#D|$H)Nj}Ov0JiVNKS5cZ5N!RC@4dPG!81j zQdH8TZ%r6CN%AJ`U~kOS$ezh6VpR}bEAG!wyq z6iKED;PvY97)y_h7cZPU@u{WPi=en3ip+fi5mT%ghk&3#vmmeAye{XwTA(X1&~x35 zKdF0dbdB`n;!6WzZ}y*UJ#^*vx4ujL%Rf`WQ_|OFCHj{=a;*L7Tp|yr76?~gyZ2?_ ziSF{w@nbgk`FG%a8jDh`>t)$2v$fYtFS@xo=dh@7v)~C(?7ujyyDEDTyf`(}W+9rz z!WF|s*p`(@G4s`(=yW593aVU-Y_2J*=W{Z~jkNy3vXzu%mma{xn z{jGfD*h#JnGrGVo&_|@JoF%@0W7+>c&gfda_$a8>gsU49j(x+%_Xr|%LXa!)KGqgu!ulmw+jqp{u&$qR{H{EGLyi_f!PMZ-U{S6OwHxs03RONhwcL?l_9ukA!(HlOjnuj#0_;j16&L< zosPwg!X^IvHWek{w0Ukd(as0eg1;1Kml%rkDi zZGXkhBA0_NJ>zo59-B<^7VQYGFE+l0UQ^N|MaFHmWG78G>Euq?1JSshz=FW(>TS(K^`zEf!U_4Bq_j| zPExteQb1vGSneF{0wI%tTxlquRl?ADJ}SjfpY2bbLLk>sO`3qt(Q1{Lx(VF08xj06 z1^4%}z?@ zQZ*Em;-=UH>=T}wk`RlV5|DzqdsGF}rzm$fZ9Mh2e!I|?qp4zmnXG(6AB1Bu!fHxD z52UnctJt^!CQtxGbr+gvq9_xsAtI`$0Kmf8fJCTUtvZ&B;B6#2PW(r-6h1fOj{s65 z_E8e#e2~fPq$UtIYBmCehpYd?{%GiS?Xc3=C1m?9+0;#R29mu;jy^fq`oAAJBc=Cd z>MvXwUb)_pzSu4s#OYT~t>>66`rG$w`0r(tQ!U4R7j&25|MYKISL9`bPeD>X@(G2h z4WWsFoFG#>!kH8}z)+a)N*Sd+0cP<6`1R2SB*_ z1$PM*X2}|OxCsu9H7_Fu3EUWMQoyJjBdbD6NxNF5Z;A(AOwGK(9r0mwZBq zqnWL%ly`3bjSx)SUv9uX`BgEy;2i}c$JX4j8aX_({OR3V>-$qB(hcADZJ>{X)a+he zJz+P*ZBV*>1#4SMzUfeYQbZHXvzB@lIkYSSEli0g7OUhb4{yRk!$ZWi&B`iEC~?O1 zs-Q0u#w5VFH)NQEdDlN13j^)Fnxf{%9Bbmu`C&=lu#s+yci<0v`*JP$K~v z%BIvJltzFilj?c^PgwhZzvlgxiD)pY+jvzkSb$q}?$6+I#w)|WZu|c(81A@<`{YOS zUFff9=)UyjfBH9zK269CR?Gi4tXT3Vi!53b?e1NvXY#KMM|UjhIc6tem0x~tg|f0x z5&|Fpf(HdKAr}tI5Gdw$Nd9yH0z#_kt$J?&`5nUYNd=;A_Mvm zN{9p>2?)XfY?uJAh=Dc2z3`QjjABked*|Z@xrEYcP%p}$Vt4EJj{%;;TCfVKAea_WN z?*|z0gZIQP-FW9${fljnT$9VMcQEeYRPK^Tn!8Pwo!il1A*T;4QcY9yJag$(sj4b< zX4fGp)cLeAQP&ZL#{6dADPjIgVf|QwX=a0cB7Ct#PSA#lX^TPJa!8MCUV%{FK|MWh z-EeSd9+FWDlg9H&f_|Wjx3?U|bW{@#DdOJ(@LoL7WeFL=tgK6l2e=yo9$jRU(@enQ z67oAS0LjE3+e2}{vJ)t&8P>wf46Y-x0>nO2hT#MFVU&7ZAZbKsGtsyqirxaBJ2{Ev z%MJ}035uj^%5Jl|64d}p z%S5Q*)0j=-^&nv5<4^U2JI2Vne!1z6Mq`@Ay2H_+mQYti}M7oSRCZh>q))oPDQUEdqU=>1&0SG0g zgi=0`hJbx+%bnii&1|jiH$X8G3LzQgiuAd_C8|Q{5kR&Xq_(hWW0ROjm==N#ZO^8( zNN9@5gs~3aTgv)d`t%aI{>_7W5$}v18pjV6_%Bge$++fsp_|jts3))XcUF*b8nDLs z!#_SbT+NVsp#D2)0o6gn+SFA$zEo_#p4fFU;L?p%4+eFo`b_^Vc?A zf*%m!)!3NFU)G6XFay3_C1BD}(v^!iablPT3_>L+ZNyqf zuIR@Mz$Xz@A=MxW5Lc3<7J(^rSwvJLMNzV(p&1`z#W~Yf4{6lfLQ=U5MkPasP)vjX z&p~jJeiY~*k%7m&IXsHP5zi<;TkAI~wbh+nKUopGU|_%LFlT11 z-^1FB-}6cjyyFrc2sG0UIkM@oS-Uu&<#t=^xtWVLS+zmJl|)Yc&A}Pe+Tl;$%Euta zM4~GX*7Y;NckwVikAOb7dqP6Y1_*|1GF2Hkg;@4}p$4)ck8;u|Kq>&hUqnC!5y-NL z+TUp72tEg9F;U=@fS7~ol)(GwF!U`J6a%DPFqw$TiPt54M_{ErlD*^RsfRy@a$fX z;FjuVo0y8rNB#^S8wX>-$^h*)T2?443)zX680D~at}G+wvI#11aA!TCV?QZ(hN1+JFf!6$A%1Bekoz`d za5mIViLC!Re2rvCz{cU46X=)IedQ9mujKtNPHyu7-BEOAqFQgfdK)Kv{c@&X`};@4 zqxsbx`MR_ILj@d_qnR7D3S2(u-^{jhJvS25EcHsxRv#EnTG-%nYe%c`D&4fA_rp7K ztrBI~o7dBvA4w0l$HhLH1V-q%QW@(AN<}Q=`cdk97w)WN8_3?1kt8EpY`=}p=XnC> z*pwQWctl1Wh7I@?6h&)uRRPfRme6u2q)-542(&h=C0Amo<%srub8VM>_??AJT}SPQ zY%)0@@exeB2ORW3XcjPT45qXQBm*#h48dU-8y?1S6u;%ZSNL;f=c>wof8_nf9L=;3 ztFZNo%CtE9$<|(uk1bHQKijlC6K|x4qvL*^9}$FoaF(nzT$32-yJ%aO!0DPbTKccP z^nRSL&6dlHPyE~!@}Ft%Dn8d;cR-4Exp= z8`3*pnjkf>b04Mq0TobUWyolfEnt@jI0T%^V-vIm#1Siqh_YD2r@Qu$j>{ZguLC=)Qw9HE(GTiseHLoog^YB@HUhyBm@1);Frd#7vG zxnLy*w}iIkffBx1fJ-?_^SMfeta*b8#9DUF`Hkjh z>}X>6bUC27QSK)Yvh3$c@lgsLXcEh|YXYo`A`l}WUU@^T=WO36kffr7a<(oASdicY zEumWZNW9BRt&N5F6TpwMwoT0dxeuT<0{H2v^cM&Xc2qP2X?)z zGP-!G{CDo}b4Pbnto-uGE$4jxcKsTsBM)n%+W*+DKNh8b3p?!Ww0c%wj&r!I{VeUl zg{+0AHy7Eex6Luwa)D9 zo&bmi66!q}HT(RP3k{?}2?c627(|JyKCR0#0fk6YsYJYl?5u>|iD>k!X8)oBWI#ZC zcl$>9H6Wt3tH^}ZwG5aJ|1l(?HM8*%uwCN2Gw#~7#{ji2ai#o+e+?P$C0Hpb$1Q5t zWj=e?ay8?xLB)+fOQxD`7iqUNUCmT~c3z(rkTDqL$!z)bec<8weMGRX*&+Vx_EU)c zI9*0#za$n)&`U^A(KBi@K&tDc`VrRZ$Cz(ZBpeVzo&=H?!}9`wL=?Clm%V=A4>ZEy zA;c^r_qzEV5*Z}{=sujs=rJ~V945iT)DW05&MpV8t!fldKK`G(^L%Qe4Yc?syPJd_ zdWXccS0|MgerDGI)Vuu1Pw(51r1HWf>BXXK|_(ED50pRr~w2KMFWar26IelzaqCoq#js?*}w%dZyVWe^(A*Ld~^xRyP|cW4acJ? z#Cx5ta+fN10>{@#2M*AIate>tmYfuUYkT3Tut)H!$G0+pdNM|Yve3Dzs$baKct0e3 z{B9%P)G!mWh`PI$GiBXB^!-?{6TtVF_W-t3>Ag$EQ#9ZtOo9O{;LyQYaN%T7TGG!JGlh4m-~X!nvC}^Pb=qBF`L=Jmd_#t?`%7;~$VYK?xW?MPOs&@6 zrT<8+zf^*0pl=Lu`9$FEn*l+=PPx4SAx^@ki^b9Lb0=gXFVCF-&`H!0**%?pD5)qX zKUg9(2~i~48NGnQ>V0=>z#`_hoRHqNey2tG_%|R?^gM7v2$mv3f_z7BIPqhKDZ>K7 zs#xyq&)q@+Wx|v>fN10A!d-5%h7n$PVL;Sdip-Rb$8QXu2$$+8-jPtD;~aS9dJx6Z zk#1-gNtMrH3Z5??w&io*D|nNs%5W66(eKh0wp)LQ-hX*>z^U44WA^t{_Mg((DHr5# zk7}>p{Mst&U$;1aXT|uQPaa#`FT#i|28xzDU#YJ>F89`HU$Jbt+p|D*qqJH7ubH@6 zYx^wm=5oh}7O{R|Vj(U&8R;HJg~b8f6!N4yMyW9JDDTv;7`N&Z61F|+ zhdTYz1ObaXaTr5LD>?i?9dCUDAmR^Ek^w)rjbVfzz;F`1@@AzF0VN6(q+R9wDAIdy z*&`z11S(24yc3^~)+%M9q$<-l9!f^er3PMGbFbY&^2jCOrZLJDfbWgh4L_$YT|bv= zW-t74RQ|QD)}QG-yznOx&+Yz7vd4C5o8p_XA9ww2ys{{Ve4o|rs=Yn868FqrE_3xt zz-QdDXtCb8#ORRK>)Xw~!Di%i_i#T6OQl3Y zCVtMMM2K}=6u>fuMLaY&j74?mv?7Voy;KK`a?b|h16_$PYD`SVj(I|m{$bxX*;Uqw zB`CyRl2@4%vpLtUyH!6L1QO4p-+?>A@j*^%>Bq<2d^W55Z|V^=!s_yaSA`=HnjtFl zvYsc}n=;+TxTl`;B}Q>q#%?~=IeDWl02^|ri-tM!+28MOcYe*mG);jhPTl<;GHQ^q zz`uvwL}SoSYw|DTB)Sb^tJ$cv&dChG5fDCCSfu%$AZNq$7tN$q!ksRFy#>V*g`=v^ zl6m-h5ixW?Ro0fsa}~i9#WFg$7DQgJ`u8FS3Xou}60c9DqwEC$CDKOZ(*lSX5)0AV zj@TDDHkk3Mned0d(^7Gjg8n>pLii{XY`TcC=^Z*Jn3q(~H-$M?8blW#X;VpiJeGCB zd8mfNTcXi}aoxRoaVNpb*#0j*I(xQ=Ko32nF*l7}a%<~WR{m02dsfb`y7QF!?n^o$ zT8q{@L?1y?a@kk6f*}^C(F_RWOKTpaxoN=o3uKh|m<%rsSEvbmt-`qFN9Jch^72$U zD>e~Cu^_`O9B>!|tlN!%vK9yfwkQ+e=ini{5--NHLgWm+2!WyGd9Z{<>EvRuHYL79 zH^i(POHM44F7SI-ppH8h2_-lc7%niUd#|4qq5)9Eu5s7i8l4-$M=qnHWsR$}%w=yu zY7^yXm$iamWK%~G^VMs&wHxOS-sQEIrIy?!Bw6t8O>7cz*b_jXb~=3JlO{)uH^^+b z<;YH2{Qgzd4)l+*THk~POEOk7buGV0OO?v=YgZr!Pk+Y8b&US;IFH4Wth8;SF}AEh z=@YC1SQFs&)kK0REDDCuj0Ag$qUmIc5}Jr ziDq=~y%hCp&)Ljx;=Hfxyb%9lmH#l6-kM>0`}5Yq)_949BQbaA(8HwSb;@n#;H0Sc ziECdfKE&n>ia+UEJ!0FVmT;#9S(5zxMi|30QT_+4&cN{~Yy%j7uI;d5$Dh}H*?}pQ zC8d$rj9FNv0&6J%7j)qAWDcTF4FP$J1s^?&e6dC>000D@S{uTdvmwRWnn12;je}S% z31zG~z`vI=DEZ?wN-Pz@?;$|V?J9WSyjKark;@sXDcoo+Q=JVg!aDtz;GX*+QBI7} z!Lt~3YM!^-sCIuIslGZv9;2%JYt*Fb=5wBRoQ7Ar5*f1>oclQ8-hP<;Sq)+N22_&aQpSiVQPYe5{@8%Qmf1q79hhW zBY1gw4~bu36v}dNNPoA%4KX@I;EDEx#s+{SR-r7Ou#=8(tKgi&7OIcA^Pt@nk<(rP zB2FnUo-h#6LfSBkQxee9r2C%&^UYGJ0uO&VNYt(gHe9|)&?c=}uMM1NYj+O&vVAht z-u8Kazv*CGx6(V0K`)t$@4Iz-ZraY)UAlR{@Pk5F(p8Im$34>4kZJUbQa;(w&3{2B zPT;j=32Xhv)Mbq-@2avJn?lz;&%UaLi95WB#b#bPuLGn^q~@4`_(B3G9*V#y!*4$} zDj^))@`;ylni5jlyw03@;3=&T`pyIzga<_rFbXl-I3OU2f02hk@i3$2I;|!H^Aj+F zFd*Qbm@k{jWj!!k@3mJQB>h=bH}`vdJC6N<5^nhP|FWOS(;PG~*s&n!4X>K{=r8;g z%fauptbtqVoUXIK23sfft{#&urIHktU;mz@Yz@FYgj~|-8 z(aC-njV#mD7&_Y~Q~uM3L~(2hqaTRFKjCEa4B{rtMe37Fkkd*?WdNzdL`ZREh+3|R z7dlLJbD;xaOjJA;fuev2JOJRKm_?&79N?6MQal3k(X-1C0Qa;A?+nM9SicK^&7Z-} zDX1t0beM?>n?|VusP6BS1RT=y6qjAo+(*jzWsJnOC>p#V9K<3|E{PX{QL4$r9|-bO zb8?bOUaJ{SIWA=9<@a2}Hk~K_(Z^!*UaIP5-XzY7mDrc;%V|&9A~*@9_y|`YliEb6 zUDub0(c20+xV!3D%(XP_>uKu2F>+jsxn`^!>)^})%E-YgfPy-R%Q(nH75p$&q?u^3 zQLTm0AqsM`3gyWOcV#5Ib7eR{4FnL}t&Iy{1hPPnB*>eIe3d4NWJ3NdNGA#9YRze)07Viu$`YW0%W|lgXBBEMb;`Aa_OgL?Y=%fG~$anKyXYC{| zrj))zI+bgN4O|d4tP5RP6jWd$l*whXcQkk5V4e)g zP-z=a7U~cOiU3f1Stj93lz%L$_`+@+KGEO8Ac{he2e|XDkS5J!orBmSP?cGT%`LOr z4kx!V&9ZxSReE$Vb@G4MLJ4!hw}Z{`(ZUC3ymgXw4_WM=k5k+-Z1B^-#vP$)594kI zIxWtMf59Sy7A)0b#FVbbELEr7a`Fv~7L`lUm%}5aHDkZ*kaKRKQO-B*RZb(l!J1|< zswPvgqP3z)D5ph;pM=^K2Vt-g-XzGCEa;6xJO=I3{ZJojfc9n? z6b=U2Q1^^&7#meE)d-o$hcl9YO^5wx53>L0d*wSEUbFWHrRWbJqzMGo1PDDRBG<_Z zYuAKbCCSCVh=0ktHI@$N{iD@u8>R|N-lM&8O7~Z5o#FqbETbek zxmhVH681GI$^+6@LQ2?_D^+zK`)MMka7Uk~(B~`3^WHe>%i`Io<~p~f>f`RUez^P7GNhV-Tqj1Qb8l+IBbtu6q+f{TjC3TyH z(`0yBR(UEhM6FUCrTv;E_MHT@TA#)VcReqjic3Xgg{)4s94$!21nZK}qHE2HW$q;( z(EHi9g(pRXIBdjpirDws)-?xhy%8V3sn&HT-yX|!GNQ^M+_R;p&22+a{lgwrhNlW^ z_W?#_Q~d5IT#gbR*#VIXo};w6x-SNHCPTMNkWT(d0Zd4k0lZ9tB2obx24u^G4iRJl z3Vea;Ch!e%BJ5~5kdJ?iJ@-omjv!c(#Y`)*wT@RKJqvb+Gdx0B9+9Ndvn#qUHw52e zqD+*i3eW4KPhGs2ZKgnsdQt1u^h$BupQe0K@oM=+Esx7)uWuyPHyDcb)ZfX~^AizI z=&?MjkQW~(%7gs#A&>RQ*GEa8G<-~sUDZ@`Wmkx&Hl^;%rXXvfg=t)eJVVaa*Q!h{HM1!bJJ96JOV7H#Z# z}Z+Ke+@cH%OeyndN883rKsT^!@qt{1^s4*bC=FC4ie{-y8-%eG)M%eoNI`$C1s0f>*ZB`UIJfS);f) zL1jSxKR%RdH3FMt4Lob#Mxu0YFg$SZKs2z>3I$R$+m@_I+{a`w2568c3p~_#69~q_Q zm^wabGaEssmVeX!#TZ7kzDe@}}|3i-BXhM$ffVJmgBAM{eLE z4UxbS{`B-M{~K`He0Tg*W16dTR{x6wEJ3&Wu0)zRhi|tC37SE4U5_P6x1Nt6)%r4Q z)B<2<5nv$88hP{OsG&h)5t8nWY+aAt2h5!Fzbr>b?dBV6ySrb7rYIKvS~2zFW2c6U zp_19Y8&3D?hxvwLPvs{w@-Bpu`kiGESp6DcNd?vd^XlNqK) z3xYX8w{Jp1cQTHKJ4UJJEhegnbo}-lzNh=-DDlB1uh$*X(W3LyHhDvy4clzR7M~f! zw21G~dxI@4nMdYH<`Zwk97kk?xb)5DsQ9THVpYq6D)^3bvzx&2m+w4S) zj{Pp2mS4*QzRPI!r6*7B$!m*DBOQ8!16s-TMu4~>Zv%Rx!mm+t{Ve#jQJBj__$^6feo%?jCLL+en$FYz!fLPFbUw&6u*92xp_$$s z7WHdC{e`4xdSydkAjGxeWWU!;mgD<0d2+b6zaGnaNPDw>xM(& zgFlRyz#;Iye&5st&X^szOF+$__?Hb*MIU@)9s2rCJG7@T^Cv>#VeZC!GuE&rvJZ%j=-ZHvW~#L;6M2~_x~a*OvGpLm-Vq?OKfm-#i77uD0o5- zuh&D$H=eZGDQMxH=t*onKI6aZpur2xvzLy)v>|`E^;A%W+LXSSqoE+^#wHYD-M0y_ z<+}!+yX%{?M<#7P34hf1&AGGMZf`7-)K23bBQk$!Ym;nXQ=^X^z~r|8Vxz7{Xd6MN+N*_gS$!EPC{~yDta&OGWomjeF+!7paFv=P zuAM)3kP&XG4wEXHYK5DgJqo2(DE+n{Xla() za#INkD3)&ijq*RW$K%h;ugT4QB4N#$a|r6tLv}((!8?+~KIP7nMlzw~tHG^vCMTA) zD|ZfTO+R)U@74bEnK{i$=DqbQ3*9By@-M#A1&*SvteY>?ey*BckzxM$ z<(Hk=!E^n1d;OVuUx%AERcW79R(|<-l3WZoY3QJzAH(wW7mYQ_-m>yvY$5bPo{LTs(icw%af&N^7YH)J!|r42hxK{C0Rs-)(>)r# zs?kQIGB~i!_5vbgJ+UObt`)hziluMd()d^VW4CrZRiNwu`Nj8qHM5ER)sm1Sjro!~ zO(yZ>{Q}S!r@KO(MChL=Rc3ym*0bvADV;YpT{5u3(jAi0#n(I(UDQLTgO^K|v*bIJ zO^1GIPO6#wnbfQNW&OHqkK%u0D;HhNul=;RSRBw3=%^h-lfS=5gMY_zj+_5j%Si(S zJ_NSz^)GnzR4HCZ8$%sbUK?ZTcJJO)(Fk~@pvi(-oo6WhI33^3$#^at@{IMn6dD@!)o!FJk@SC*EOknTA zCy6knJ!-;k-U3Rbfe?2#V*SKy_|ZE{r!{L(<`wbUa^z98Kl}8v#ORt&s))BMBL=!` zJp&q1F=nsogDgWcvy;mN-Z}i-FaN~&4FZCffX^4|8PJpu-Dw|k$XQsMFgbmp1taWv zN+hnDU&Z*}jCK0m#~R8&+$5eSskPqE9b+^F4FlE_N_gQ-#pCTaJV z9Cj!jXYQPutjI}!t(*t>*@(rIWYo=K|5V(3*xpjES3NKJAYI+d`C@X|>EV-QUP0EM zefC8!nylVxb@(hrjhuJ(wbUwsG|45r!?lrOeWLpk;enl(XJ*^LGXpw34Ib#{p80n^ zKMuPv6?=e5(Ep|EbMR=iWADm=;{HeR`dKLIzqyT~+$$@Z1{JR8qiOwua_F-XhfG?D zD>J{6JhBYR-WVX3V=C%HPv4GD%6);s>X1KsJ9;`m`bNKu1Yw6?0IV(fIhuc*3 zH}-CtwRBd`m8c^9SOLgGhx^8h1XNc&Fm0cxfw!oR3V^1~@svbi8yBP6Fz@;ci`0GK z^G2^}hXX5r4(iReM;)Ad7fX6+_kgjie-trv%YpnrXxoy41E?d)y2$0wKgt>YdmqRi ztUAUTweMPUPZ7QO^<0wno;SK1WorJf_U>!UO!+V4(ay)WO{Yg#qmTM#CVO5Dxu|KD zN@w`ym-a! z*X@@6glLjK)VIM$jVT~o?Q-0DzFlO1_KJH!tZn}NHvW({K6z$dw&iLDF7|KwpCZJp z!v#UR=T_Is_#PiII-g(v&}!miiS(vWSG9he*#Wju3HI9C-*)?HSOv|Dig*V zJcsNt!eZ?4($Ex{CJf@18$u+r@#qpDMv_X$Qn}lUr)7*!N(f9Gny6iQA1T?1KQlrt z7YgMwW>#2gSN5`HQ>Ycwl*RxDyM93SJIp9X%3f-DgSy&7 zm%6XjspW;THT`<<#nX=+<$ z=`oyjI!Bz>o##t{1B>_nD%q7a=uR_nyHG*opu2H9$ z*+U_V$Ff>4<;~w=%{W-?FQO_OVaacjxJ@OA4PCVl#tMrz65m`zSHs1>?vZ-4PwZQo z)c2FpOI0fOOO5VaupX#$SSfM*e$w;%MdR-`b=F(NzqLqxxh?Vak^0xi`1MzY?>@^e zuZn(rCGc*QfBd5Ya~XSMRjlQM+NoEvWs7phmK4+8$sAaej#&`*TT*vh5x0LYqQh1( zeTnlLHFg{@IMD6l((PzOuJiTsD z|7h3y$?e70h*zA0iyLWc%ey|kCvj$?H}9uzbRGDTllm#R^lfUx+lmXHTQ7fQoZlQe zwf?^5^XBERKW=|}`{>K#spqWu`L}O2-hTYD#@XEb@$=8hhu?3%{TlzcJ^$k8+z4lM z{M)s;pJ(TO&>nxga-DPI{HKRq9|mr}8Xb8w{BXFxzwhR)o~zfdT)f=X(b?YGNk89p zhJOA`&Cfqpa3VP~J2NTy;J$tFadG55nUSd# z8{9Yz;-r(Sf@vaAko}>2OO9Ad* z!-z``c5if@R}|d72#2n7wP|s$DbavIN$-9IFNUb^MK#a!dV%#S2~E=RbbQDeo9J@G zq!J}^p+s1^tY?;tPchEBT+F6gOtV-{B~eBrg5PAXFd;*f7%f4FQ}c*5C#4yOr#gfl z^x3s5EHEIz!^f52okX5x25SCS~8QIpRH-@sxN)A#cAeK+gUqofWq48t)1CslkulVteblI+6vJ} zGo5M^M13ESs+&$`Z_afEpoLq$e(5hltKE^WMQdbgn!i!`d9b!bxjHdL(E7`Ktdhza z>{h2xL*71_lEscjE0?D(mMT}M_R0~D&u%okRP`(gT7OPTIce3{`>o7gBfgVfZ2nQW zOtp+KSEf-<9^|q5OdsM=Py4G$+h4A^*-|U|tKg|dOpXRRNUG^iNdkfYi=5u@2fs^9rKZHDdpKI7}eNmI*RU4`BC41wpue;TMf)q z=qQn|_R24nKi_*}^4g!cSAuHCN!QTg$4Cn$O2zmVA0?KD^+SaKoY6z&`qa&F%a3hC zKGv(Z0$Nkbdun8xKPI;L6r7ohJ=bmUWlikje@7p!s|L(1xLc2I*67;*h!YtXo02hl zC|2S|#aNfRZH$T)CT))2k$4+BIr^ou)yL{X>7O!2`%CF7*GiPK28g#565gh3m(cJw{40*JXCZI zY#yI$sAzis@=WGnnMPA;3y+u!bMLTl@PW^QQC5!ACv;D7oG0dHT|o5M!#ppMGBL--R>8)rV=ceefOd#UPL`oV`PM9ey?)Ie#a7BhFM=~J71Q0l}2?-qT%=GK?FW+%220 zJ1YI{ABos5WDbhX=Kr*_hBD%~(GigcGcSZMGM%1%Cqb>Q{%g zuDDqG8Of~lXg+XAyjJqB6^Xk@fA}vbnm34s6mLYsnyOUZizdUuMj3^+W68WW^|HW< zSs{@ZApw*Y;mUA@=_vX+#7-#;tj+m^iHS&D1dA{F{fPF1P?gjkm2HPg-XzZc!p}ea3S`1#-Q>Q)yB9BKkf?UXwFtKq?B|~^a4ek z5)UgUQRp1A;GyyYk1Gb!zJkA3K7FOlKfe9jbxvVm43*E1oiEAVk?YcXPE8IuNL=TH zJyRI$DV*DJln7tzQq~?7v*9#NkP^(jK0^;3=qF3nB6 z%ho^k&w3cx$}pUSuklXDGepk)j?e`Fz7Xu;U=W~u$&&;Y#2rG$9~E4eX~wu%eBBYs zr>uN?_2TlOgm2hIuifT+WB>^e6wyhS0So*UkwP+bJSilj#S(~kju2D0IK^j=7__NR z(db|4Q^o(d=Rr9n5?96@2H89op$?LbxP3GGh;4qWJ>r4;Uj-&mv5}O)vV#@Vx_!_2 zlq3?)S%}(^(u6vLww3?mrJ4`|C9!jD`KitHLg#Pf0oi4Qk_bNxYzqS!KT=``CJL0H z=<`=KZ-h-ntSE-QM!#7$I*Y&+D$jotw=ZRfMhTCGV5lccM{X#hIp7Tx^D@!m1{Nw? z&7TyX0?0@a|15aePHNhXO_aK1#FN?JRRz`wNi-w{p$IN*v#X!XPEMPnBB*mMed$0`1%_FY*)>N-pg>3gz7K-es6FZO%K}X zKGMJEMCZlOhIZ;@VSK~4L4M6*Su_j%PJxM zUGOuf@_1ux1sxthva@Uy{V=lhFblG0D`CT=B5+)V!nPBGeUK6?^&fLW2b<6P^L4Zs z{T};+PeY3pP$>A`F3mpW<-M{UsxZ>-A4Ywkf44z?0lb5w41c9Rw#6WY+7t`FNhrN_ zTqOeY*S-Ru$-u9bjJK1088+{Jor@6sFGF!2)PM$f0X96@4!%8|S+oUREQDwsnbIqe zEg>w7k>t*X^?yeAupP`%G2V>i-3&x4^LElv{z9R@=fOhP>_29$%M>4*;W@MNZ`-}xmcMx1~A-_;Xj+As;#<6!d zK`T~@7l9&m0pe=&lWHEm2(kiFyjaw;^^mef zz84$BXXNKI;9XcuE*`Us1?Mx-2ABd1M++3~~AIUI~>{mpg488F7#Q7DcMfcQr zS^<=wKlApC7RL92mTb_T0orpwJ1n$H0TU#MmKgdGlWV1Naw z>73JG$_LkXw@a)^c?%y70>H6f5+@_;GHn>(-&M$(1zXWe|Mr4Pqa{!&)R_wTFem}H zpoSli8x1}?k~z@}no~ea7Gz6L_GUnQ4Uh$aT9;7e#l;74nB7dcfQ6y+d zqDBfxq$FFCK^GcG;O4$=fgfE280xI!`SR7;3-VCJq0A-A^*Kl+$r!7+|)z@i91Z_Z7)P*ocaNChf_l43iy*= z`}bxo2o%T7)$U)3$OtYbZ5Mtqr%Ao6iUjf}>OrspgjQ+030dysqenmH#-ENp`79PO z4xWG`Ug;SEU+B}pggCt#s zkigxP@)UA&E)(5ufk~m9X*RUTVxvphXul+kjg!A0uF(57gl&Mr7-vICK}sl$7yHt( z6gLsC(JZOWl+|vU)MmzRTMPr8IXnR#;2NXDjs+R9L6f9xizLv9cI9O_xK3-#CslUdaAlgGo}?87t73oPA+WmnYC*O##E#U>iC-8CF(4 zPX9Xw3DtqNOjy7s-J1b=Gp`sCsKDQ@5GLGv2F}A_$N;MC<25oJPQjw%u-xuzbP67o z%qc$;t^Ft2a<3DnlI0)5^1r4YbgB;a;y~e~Aa8R1`A5y+B+wWKygYuT<94rc5@?76 zjj$kr02&j3C_<$x0G-EyM0&p|02-1&1MJ8P*@vfjmya6QmXAb0<|*X#NDil=VR8(tJ1I~Gpq+J*0b?s?OJuO~MG+?538lZU0U zZtuQ$>g6AX9TT=A4e#Q>S=k_-0n4iosM?^U?^ee!ka!#_hJ=b^Jjx{xGA0bvceQX! z#q>;foMxV*pNsAfWhRGHz(T@pDxUk=e3aB2fd_XndP!anefS>Qk@`*96VLu2@wC}o zCfuC;M4$e|R~~%D|0K|M#0U=<)1DIW;Gu|zAgRZgGyK}KpCtE?#6Lok19h;dXeOM` z;aVGz_LY5Q6Hj+hKq@)=Z{Ml#eK(_$xU=!Fz&gB}14?OQn7<+-@Mq3Wz~^Pb7yuQE zMd>gHlSwEY9IBfi{b&l^c(CPW2-l8g5=y^onE>Z8!{^efAH0Ix=mY69Ls>K)GWj~_;?INQI;hr%5DAC5um+Q{!$?8UG-(Wd9~n>kl9tETCZH7b(4B`+N3b#Vkfr#!t^_EE`aLlg;Q8}cHuq_2rS76fSMen1_z-_L29y* z4L)lZx<6?Aoz-J5>5+Ce#{MD2k3G@j%o12UiCzE~PY8+t`UH_@1xHwY^F#ONUtOMx z!Oj~BzV*pt2ll`Dsf#gYAcM}{eD=7)0>8Yl`*wvOCWX;ZC5tBa^%`=6{=HvnQ(mHX zqY`NBJv4Sg66!F!{3r+Y?d=ERa|7oB^u1IQDjOZjMC-4h+n-g__vV9F;TRfcsUNwE zzEpP~S#pdmb8?>4^ih|Ch)G&gzr3c8-&A|Bp~=`hb$EV!9pSDAKpdo#!t>9xk82z* z{eiIlGJzLdA|Bh0<{(Rt%^E$u<9*`WvwKrfIE?zCMb^>m>O)hf#>xvwE2g*LchO;^GAiaIDv5?Z3ZN75=`}gRz69^@L@J4233KCNSS2wr2=le1e8+9^9}Zrhz{mzUEdxaZ?ujsl@Zuxl}iCm`07j*m^CG;b8ad{X#uI_a82MTNL_V6Bql3cqx3 z+}rsn;|~+EcG-W|eo2OM$b&@!iY|?z8!;o5^7h3Qp_Auqvwz1;fu&eQ{k-d#9p&%s zlM+PgtvPAc&Ph5U|JE47IDzlDc&z31#H@U$GNdM{y{O^H#8da%tO zxw|~28der2w0vhOQrG6F#R8FRg;XUvpBzt4@Oq^aJUp*uJW_6`L!Oh=PVn@X^8H%! ztEJeW7aNDg-|t0K7~Q={Jg!boG(g>!)8?zV^@X#Zzg(jrb#nr;Ha0{w(8B15RPt*=T+)ia5-5FI8vcWa`=(#d9 z`@bi~HuKw~cUb0V=t;3#QL1Am|sQ9*n^$IYRb*4CN6I?VMRyedyIs4xngy&{Cqj z!0zXKPW3H80#gJcb;AR9MM!wMXUZe@fhOdcnlY%-i|!No(d4d3kr?kb0FwxuCk0|8 zHUSn{#5=+!EoaAkB_hZRdg6i#wHFGW@v1C>53vOm1_x+?G(+U&=wf_$CJ`mKZ5&wf z2fH$EC;9djo-FC{hELGKtWU?lgr&LR6q&JdXU}(vVuGRIo<0 z)H=7{B9XoPKj;0ML9pj}IEcNApxzc8RHMor@xi~~x0r}K{YGHhl&CD|@77%KmD3;4 z`pGBhMWG13F>6R{F0E6!UORh1uUPhkR*^(oq>`Y;h?I70O?>Zw?zzOyX04xbnoAw{ z-2@`4d@Ou`-}n*ZOp(|Gq2Sq^t3~Vyn=iC9!SG`%{Tc669v9GT{?6&r?DoyK3M~(@ zTXiglS5;0}yvI5IUKzojDw3GbZh{2(IRvoVb5$J@TC;4X9CBG5X~gr<-*^em*)ALu zv|xD`aw$LnvUqU(>{~A1mfnm5HQW%=J8V{dLp$a09xC0*hm}tu7OF^m7ah~xtg~C) zgN>y*<~|ZZiT6@83=?_zBN)h;0RkKi428R7NZhVq@{6g6UkZ0diZoKe?!_TlCko1j z)>&%xCsO28{qXoI(Zzbv5%+^6V+UzroyrSle`6&r3#s}cL*cxE+#frO4XntH{(MwI z$w;LGn*>MmdB6N@%9UMuz31i~|=y@_2gt-F=DO7lz_5~!?Dumj<`3yU%5~wbi zU}3CzexfDvCg0K$sxf~ENGSJNa~UVe|@ z&bsH+-4Hx0^t;AmhrO$85QHb+Nf?(=CB4k1XThvfmKDTUGEmR!ALcRC#423l2^)4Y zeVl8n)!a9~tnbYA*02x)j%@`BU&vl>)(sH8E)>_>BQ5$tIwTm{h^lZ{aBB zCA3J_j%l(};8FECCJN9&ifZZq-bfX&a&%>#jbDff5gs`kiKUj_aMrxPoj8GXFOk_JMtgtVtC>wV^fWO3$XVFX2 zTb;>xeZ@!g5+kpx{JEN-+0Jl`IoxFw{t~wVO-P_LMghG#Vr@n` zd6e!@s#d?3ti_=6F`t3&+1(k}#E~H8I=FaG0y%3MB6xtpIE(|=U6PQ(Y$0lb=D=O9 z6@q7z1_jkf$G>S&x_eoIACHR<@Zr7QLMc>9hP~bgLZH77 zkokf~n-l^DS#(e#JLnQy;^kNo!YjUZ6m7Ih%ub;UeV0=1x3f9LpU`=TslFct|4cHM zTh*^0M+6@xiz~)Hb3OL6D%j$_60|i0WEcQ*7C8jD-JgmxH_Bg#$l;F4*LS>L8K*{1 z2npb%5Hf;mw-wHm9X|2g+snP(?BMj1L4@egn$NO=F&WBNl6~wYcm3)!DwThaA(3iK zFh5p?1BZH(sU^gcrl%$ysi6h3oW<8FKV^FJ4A)pRzQHF}X~*L_Q!v-$VsC%04pJq( zIOIeLf}kJ3yq*s7dopFugbKtpAOAe`yO_x>5s{`JE-TWKDR|*G?$Svaa=>YF+2=ee11Nzm< zEdg5V1GF2EDZmnVjS7C3{EWiGA4UP&!XbwD)?X{UTjX?iz0LfKzjR|_Kv%u;i9aQh z(e%5ak94d=8%sf7@qkJ?aDTX$LN+E)dE0iVf`{pV;XHlDq=&j<*Pr$I)Gx_pr5Bw? z>)%Q==tdgrrt067n?FRhM$SDofkL;sBb<`}{-gp~iOl=34Cx&n+Z;xcQ=%k8MX8jM`tkNx|;@9Vzq z`+i;5{d&$lFcCSjGcCIEb@fQ{;t2Tpp$H}GN`>^m>5=n~lmeQcNZ1*!g5)*q>aszO`8~~g zAnEM}#jS=TV{JOqbkV*CJ1w`Qn*d*K-1_>DbzrCRh790_lU+-2!%c;Cy5b~2v`-^p=H6Y&-V?Uj!$lT{iuCiB z%STr$^Jx-~jgf!+fk`4A>Ct_PGy(>3g`&;EkR9q~KsYK0!#AEMay`o4RT^kI)21D!*jK06XB;SlltQBvB*3CnfHavK^4C#v%Uy^glo@nE2ZJQ@>5=IK zsR8;QE?t;5yB=VY>BE1n-`Y}qg320-Q)V3{(i2dII*LFW+U>umUDB0$lheC#5G+#3 z?c)})qz|Q-Uo^Vif=^V-v17vPjpgWfDO+O=_vzCupm04fCfGKsm5C!A47I@1(+`GQ zoM$I+Y-^u7VnGg>Ao&Gpir>)VVsmq4mS`qehyajW=SQNsWk2{5eE{n&#Su0&! z+hGhzpcdQ9v;%bd>2XNHSBQ|O@TgiJEL(n~Xb`aH)7Nc_F#Pjy7*u{EF8qlT2>FM7 zdHxzl;_rcs1Sh#&P2?Gk75@u;k~l^6X0cVeLLZ&t&a{%xmL@&29~hwwNY_|7T&!^R z%zFA+`TCP`&;#7{`j4Q;WN&z-N_4&H>on`bXZE{vI7Kq)XRo2Z?h--~t7*96 z2fxQ2EZGj=^#dpf@2(XuovNYgDo66VnP?YX3VTn=9ia91l6{wP6BI0)Ib@xF0M$=l z=(W$l+h|_LXYH^2Z`HH-frWWx{!ik){Z>pJKallun@lYrdVqPhgKj;*#F3dYvm={p z)?f6e`Fv>~-1SSx@Q(A{_Ugd7@q>r&@6|O(A-n$})rU_|sDNZDU24lu;?ALe&@9Lq z5XOm#X&Mrj7>y>40&W7L+5xf%R+KhN2klk*_c3_#y0|GzN`eLI0!U*4b+ZFHX`uV3 z4@l?VMmf)#{~(w{r(|`qeW!PhW+)PqsEG0C zb_*LSbFPvejb#ZPkm54wT}ZI>mY6u5E13@v@0$VB0lbbODT#o-2CyjLktoekS{n>1 zw?*&TMGnxNZjLr52B__w4fs_A)6(sb_`y@9YCgVC59Z2C5Sf(Ps{@Q%HJZ8#wQe?D zOmq`qMAR}Sm}w8Nv?ep%WGp{7zBqqY!O{I`Fy)#301US~inw?UU2EKZdupNsa7+LH z-BXj=hs4$Wqv>>sOnTG5ArdH$7?Lx!+E!8mEGAS`uwv2LETK*!Q9_rb3h$YKP|?G} z%ew>(kZRx%zr~68YeFu697PW8SYag$0Mf7koep|j_~_xR1Hb%-`i{>2@7-{sGP1-y z`=7cd9K+PbYT}=7o)~u!dKc#}?-~2zj(srGW%e3|Ha=>AKX0%wZXojnaOgp!O7#$| z0di2b|JvU9A7k&(<2GmgqlC7QRDf7HK!Q#er@j&w7I4~vj>?9{Y>7pZnbs0O4+Lu| zcP0|cB9mDirr^|@Lz0<*_ZI=;TMHMhSz=q$@!EL_e0M1!WRXq+%d^ZrgYjp_9&q8G0^XnBlUjDne-o-}h+^`Sbbkp}0!mz-Pmii)c_73n2qB#~ z$8~EyD2dq%ogNwhIk$tHNusXqIk?Gi<=JcB&`VDeMsUy z%c9&cXK1<#R9OxFA~S$96%g^6(@IC zjP_WP_VV|d%P|+a6b&reM;9f7zg%1qE?dcEuT$rSy2gd9L16HoPkI&7$j7k<`qC^a zKMh#RgKu`z<7-(Y3E&q`G0$Crs9Y||Ni0@f{E$R$LgowHZku9yF|KPZeL&Q6Ajh>l z=kAY~hShmh=u>awHBAvkGU9tGx z+!$1DBsSNNBy1K;5DR9B4X{k#v-DM8MU%j>5{ILM!9rmiECG(^Cm6f3#I!>t0r4LW z0))#X%_R)n1n{LF7L#CwIFE-oN6IukQOLaE&>Wr95U{iQ`ku+7gok&d=E2z?0a5N$ zclTV7Jj;_W8o8HCBIl*j!AIMfI4bjL?7_X^0j8IGUOHC%e1@o7W=^Fe$F>V3546+< zU3r-AJP5-d_F-B(iHRDr$U^wI1Q^_YBzYc8+uaCvO^#U>i!28}bJy}0}XNG4jT{0L& z_VITIS*wF7yOIAztX=uC$5KlcE{5dD`CPwpu)kAof)&v;u%b95{T0D z9Zi0t5xC>O9ueR!wl5wmHqT0-vSN0{T2#dnc5@>p#S&=X)R)QBOjblKD~-=0IcZcmbtXUR(t>XDukjaUEF1LpqSl_n)_z5z(rf=Phf05bUS*PI0R_asza8i19U znU}7f=i3f)XaZsAf%^6`F0^l9|K+%lb6f^;>?AT8nD?t$DxsPOZLne#*Ieu1cc%iF z{UPXP0+|K|W5E{YDF%<*_M{Bp0KBZTzB8RO#+QwoRaxF#SUUx zm+vfD3s=xym73U5+JBLg;G>gbNpx_;WG;1*70%D4@^j;ySP6jqgaPNzD=JBcd#LvZ z-W|{A$VQW8ijBkW9$c`989i;gp1BFkDO1qJWe${Z?j}hqqsz4^YkaV5p?5TCJfvGf zPPcD!BTXb%QXWDD;1dbCG8$&2J`_c$d>)L5>g%c^h{i6;k=yqMWM{FyU`8t8@PtNJ z!lj8lMKP%*8{hX%Qwc2}%$ELl`q%f*HzZ+p8NX1bCLNN8-VPS3StW1oTCDLaj1CQ- zx%x~m;M#mw0x@qJf<89iZhSLN_Gskw|5^MK=vi-kbhalJWE7TRmfN51;$K^I*evXR zYk{SK$;+Ol`^g?_JL7eoF(XxhTlS<2ZjG#4P=GsqGqRl?6Z9m+f|>M3C(cJJHnQW52gEujD}~CRd2Z;-zf$&$~db zy@ZvZS0wa{JACsrul2HBHIMa9fi;h{}!aSYwC*7MYK>T`v(wZN%zTx1?yDbp;KdEva}k($;wC*;d>#zka0 zS^Q1*U`4oQ3B61AeP2Gg7<(#qFTVXIyWafauI{sA3uNZAx~aZvMGaH( z7i6vPuUSeNo9tbAYI3i=$J4l>JZjAJo;z{ObQrNLJNOhkAcK94X!5d>3jZ*0V#NJq zM5df}w3nq)wKB)zvL{LL6s(}R*zz?>o+E)g zmQ936pvyopmaXoDw-8F)-YD6o?NRgt=dfn8D^<5kakI589uX&(#mu8K(x)ekE;rpS zEB)2vKd)Pbs#VgM`OTQH_XOcs*J4 zLeoMR`qdgCHThA9|1(qM>$GQxyItXXo|b2Pl*UZ2loQ6xrvpHxxJl%UlV?%fgJKbB z{Yu4I(y#vQbdr_BlKZ}a-X9_(fNd`e8Eo`5Q1Ayepx<|1v8*UhM0WkHg~@=jq|>so z)L`KmeP^HqH5$5rSneMGCKHL%Q{E^CTY2fok=$3+^mN^@oj_IJztZ7FVP0@tb_>64 z6>j?=&**fHq%*xU&+$hi{9}{E_zU2^-5wBZot$UCm@S)3BgS_I7|b>{D-Zo1LSMma zzH(}@>F;(;P6G|2f?8Dj028JioNoW+D3$B;&WPgMQvS3=pQ&IlaphY{5tIphMsu~S z@0K}&js`xZ4cpws8+#h>fqePpk(o8%(P;PYz%K=WvsoM&vXDy>EPcqUm{Tl+Bl-_d zhLQ$W>C#9PPKHDlQ%98?8XpsRLmI)V%NNJTNJFIapJAJUGXCY!(3gEI`(eCXz@pAR zQyI0$?@f{?mfMvq)7|W++X~>ZT)6{(4YABt@hnrWLSehFLK)V_u8%L9(N0ukW9z4b zEtH%4j4-VhxPopEHSVgn*>JFIxTv_=i+r$|qNfzPLRa~^kpHl(UTAB%sW#B=g8gn$ z7J<};CW#DNs!kR~pj*x})^bIZNf(Q-+HI3m@N-v&%ogCYz1?pK5afPIyc1b-l zo4}^mb!1O0w?J3v&Pp3y*on_B^&3uZcC!M>LrtKDUtJ^mQZo`>+J=oR2V|tPO^XX^ zrSZBytgpCMd{)3VJCUlZ>6cyT*Gf=suVp1V`*Mpz#=TPfB-B-+CUahKn?T;{rp+7+ zAv?SD*C5<@t;#YkkqBR*FIdvMWsfDUdX;{3(fNkmcPfjgxd>p{G)tFmSMAfgP;vRf zTs$n2rl&rf=?XHOq+fs23yj#$n*C@46sKPW-bB_f7?#T<6t8NibPb?C0?U$|2SoPP z-Agc2Hd%olw{oj z4D$e44KY+^m>6h+;|mp#E~7 zq}`Xy*cP%n+MOcnH{bk*tc)-l?+Xp@om0I-)-ZSXl`EY}P-zVwLVUSj7%|UK6?@`h z)#SS`&4~#y@D8ZIkoq`l5~QVkIS&m5m!@Shp%Q!Gqyd2}Ex%vm)%k$uVv)Zummf(B-(c(o0 zWTk1uo||2Ek{_xt@wcY)KaNCtBM7B_MAUFIm3O?>?06}453^X(8tg1Ad=!*pia(d< zP2H*OF^9*0l>e6R?%u3eJuiy54lQ&jxT`!XFE--dZF#i3S@kn~-6@4KJh!B~{mW3y zwBqEWNNm|?2P)TO(^x8~j|F)+DQ3*oDb36@*IeW4qHEbQ1qpia-&?MZKP>ju=0fF&tTUTabC$Civ2(w^QQ0><+5L<$A6RD_)-&$^~nyE^F&-f$Z?a1Bk`~Zg5tBl$n|XfMv!PT z(Ow>G)E@C5ld-YO*Byk3`?(fW`{?NtKDN%-?`2CDRR=44gGtS0>*>GNCy5xwh#+W; zl@fw2DWs}|FpyeY=}Y_`e5oS!l14|vwmO^Bm`@$(Hts|lWsq3<;BS-@2u8G82RUlfMNuH!CJ2Y3i|PY# z#mp0l!h)hm?_Uvu3@kUqGP2} zKt?!Us(ka>WS;QhX3hJAr4Mbz3U&)W=Ly!6T;w>zRMhMf2)ge!b}P!WG|2tPq@c5cK}Ur%GT{7 zCS7>jS)TnQ&vBXOuu0Ti!$-rNiBbkX~`dC|r@XoGKH;3Z;6Wf*2f>nAd73d0cmrqS>+xj$j=EEax-mubA< zKC)dvENYq-7b}%Al-`e;U9H`|K z=p8@OVUmc>Vd650$0;%C1tIBoLNKBqFkWxdwTb4t+(`sLdz7bp4unGrofMlbGeOpa zL}5^vBLJ8f;#njBUCgu5rvsny9QmMwNIGtj34?=#`shhGZ2Hqt~!w8 z7U;nu2zMv@uxBmIsmX3#!VW1}I?t5-rmH8~VDqTWqBB^RBw|Drk+Br9+k4lhP`!-( zW}vIjm5w6FWFRO}1br$)pDJSLHEY;GKqQJ-qvMj#!mC^iAHJJ2#Xd)b6W`reaOhzu zVc3on3`aqdDf*5OP{BC}bWXDNR{7_<)SAO})on9AGl z7BAD!Ltz4o`0>^QAe#=g#YUzL z(#e9x)Hn?S#TYpZ@-XS5He{l8`E!gjamVth+6djji1$V=vv!S8z+(TJQd z!$m4$Z4MF4c(Sl=vKUtNg3Biv*8E&YE;b;s?AW^uB%k2;;1e>OXo_X-?;CdT0PWx6 zng(xJ&T=sTo=q?l6Ar?bS6OEgw~$iUEh6x)Zc;uow;Y5S1l3b{_1R3vjylJ6A~q3Z zj*HLu$$*rX9XDWN{u+a*M~!!b4rLIH2SR*|dFV-yLn2c&(dfVy&ql_@W(|Zzf<#eH zHgpAZiKl7KOf%@AiW3Q@gUtP35`iCyR`}XZQ$i{Ks1b@_NUki+;&yA?xV3lm_6D#= zOtX9JoxV2LUWaf5a|0Isy2yBsV3b9mL^1T+sgyVogBUJF_q|Oh0};+O#4eZs8Wnch ziSJYga&MTlbK~Gw#STYgK=Q+<&tmLQ7b2=c!Ya)H(4z0I z5$DCjG}UcZ@N7hxq5zQ8DJD_*jpG`~#+fd{CvKY%pO!4TY+fQLJ6q3(5frbP0;mp~ zn}JKj*hhTnjiCrHZsdl$eWJh7-<7#Jm;s7$pxm@e_w{nyXJOiV*!Q`JGyiBHAEr&v zqcM!ysc-j=GRRRP2JRw8?gYa@ZR1%gwv%DF8+P9^xg>~ZqP@X)W~}xwo=k}t_lg*g zGxo2oKAhm1qbR0>Tx6CRubhEE4H#^Sn1mCp*F-*w5OKjwD`AOii)%S~rFoZN(-2fzZj{4h_TJJ^ zL6DyAmbBg9TMq3Y%38Diyu1;rM$e0(i);|ls(~XI`e>T|Y>%Gu4ZS9x5_-{IvG1xR zhGFgfNq>N9b%sVs7Lkl*Xx?NPtj+PEoth3IMu`NYVlF?JTYc)237;TykKi~VVs~SE z-)k;X`?+;yC$frRvNo~)o{+f6wG3d|gfoRhV6Goxg$7}3p+inQ+~gOv4?JEbsJ=^M z^xtIkB*mcvgqs9i5}U^K&$`sM+N^`NPJvKlqCK5yK?7||Qf>5^nLBYd2q&vdqWxlr z7a!#QiEH8Y(OO${dWC>iPNCtt@h`a6+H7oZ6r$mp<|1(3K*ZizZs9D$sE^qZ>O;N; z3Vchniy=_-!*tgy7eA+&N3ZJ5em~F=OJ>ib;lA)b^*+=d_sGz?z8BZ#I$~+X)QHTm ziDDRdDX;8>l~i!C^*ocD)z!k|GBaG0UXkeAjD9H#yLhwxd?D0=XR^h`T^7N9;u`*C znCv!LCO$Wl>97h0Vb=*(wL4~id(Fqq9J9KI&+_W>7l-P*zn(A-N{hIoPyA&JsHb&+ zkUZxo=7}!^_y`e`2x=T+2IYEU`iXjPWkBOZ#~flS0$?L?XfKIpy3BK&>bUZf?h8%=rZ#?imQ($STKI(fBtU%G&bbduTa(f z`H%e-su7k}T%&ZZUJOB!*;OcIi1rsT*!!y~I6|bciHUBo+K*x*TM4$61SFqp)=2!q_pnH0++QGAPI7Hf%*5wvDnt-Q^yc(?0&cQ1 z@u;%vIgpU{iT#^VEqxi+w^EM%XNDL9`7xf@}Qcu*|dzACAE<`xBRq=v^J2 z2&3L6Gf%3KXiXU%LAMFh?JEkm<7O*eDsw03VpWT~?i3jdXP3Mb#g!hTT8&U6%63fx z7$zjED0nh9lA%xH?im!18+0+EHP1vp>5G0U61}=w{G4l4%eAIuB9ThgIb2IBVVPQH z#wTF^GHim0+*qc0)m;q9%c>Xid76kN*)*or+4R+=swUzj;_K#kHhrn)gKijS<}8}% zFqx2U!L**`{cB5vJmJ~LFcBp@+j6FMs`>G{MT_D_OlBS?05tUVcCtIschv)1#jMnL zLqF06e87o$BXMNtBq~j0KPXy{%5WfAqrUS|mfYNP5At(QgX~2Fzx(yKPU@2xy8Xcx zWj-+;TxKP$>uEdY0aa2h4nap5%u3>=(UE+>82Gf;yOZX z0)D%hJ7STCbuT`&LV?T!Mli+9XM1eR7@}RHg>5av3XQOpugBJc?8guYBNu~tW|IxE!(rBw$C7Un9cpzBEP@WSg5dfhw&ibbRl|(Bo*MoA>d;O! zL~M`0E-$hqNMpG3ANwia{Z1ug-)w}#@joN(5#8f(B*TctEqY}=&m+H`vy(Zk zCk$^}=Q@MU1BO*kuwf!j;YVXP{PcrF!n%)E)7Uq1dIIh=TOX`3D7@Vn=m*-9dT}kF zA@d?LZtRt5%)7_G|FFCdV~#zj58=&uT@WGv-kqAUHP`G*S?Y3`dH-1x+cLkl!DD$} zcFcNv`X}KE5@JmquRl9;Pd2=t_HrqSh)G(sJMl}oQSqhR8w_=l&yiO1USNtXb#4$? z$hyw((JJHZr#C`6!&47qgbx9P$l)MM^UDg3;a%dUvxY%?R-fw&7%WJDNNr`+}rOZvhRUt zB{TSZn^Uf0TC7TelvkT-koN5uSwE!3JH2R>@sRS-L=VG@DK!hj^+)bbxvC}fOtI>y zX;Utj&VE1tp+0Nn+prP!@oz(|V~GXe2Ix;oqsA-T-|=b@wb_OmF{cYy@XW0cvRcxX zf>A?i7yC+MI{lPkW9q~yHxK`@3UO$yGQw9amcHQ%IZ~C~R7a%=#JZ@7_;H9|azaPr z(DJoB%cnaQ9~y}V@K-OUJDyKMpY*c7spJL4kK8$qNQgQAPWArHzC(D~z**n_Y|ZY! z(@mAL^Jx9YtUtDRW!T%Y5t=snmXgqs@v4pj2N{T@{E*54}-(hH=b1{MC5 zYt|3(Msg16Wb3Eq9ylx&{!TGOwEkU~d!oh%wWB7+VpX1`-xBIxUcMj|zs%qImm&wI z;_AeDbW^ln24`TauPrOeK{_)E|yQ}3^y>Kc8inRNa4Xu}oVBZeAB(iUPhBDw@| z*-7i8;+M0UY=ZV4-~|y8MjOgU5H7$2EGtM z>%O8IcJ!J-iaiveK_rWVRX`6-(}6L_Y1Cr zv`ODQsP(0U5%`HC$qBHu=Iq~yh#Gcr9Dmi|47;!(lT$>Mc!qk}m20Yayksaq4}SQz z%z-aLHLVo{+YqX0>Iz&JFK*(O0q0YTg8FYrhC(gbS$8GKMq{F!mEYvOv{Qq8@~>V< zEy)@7ajPtZvZBP*J=A5$k@U%0fnMZ`Cc(c+tl^?^s-pKq&xo!`c;FZ+m!nlr*#Vml z4y-74&OdhwwkQnjTTy5w51F`fIz!u|WZU@>ET3$tz`qlk52;{m2Bj))Q$*9`&k!d4 zeAx#FV=V!>7If>p-q(ax$P%^HdWB+{xRG9SbsYRCF#AZumMyq zcFDK&1c|BkczGDx?#ur%)vED~1}@4J(4&zcH3vU!QI*@Z$NqY#25BnC9%0I*L#1Fk z$~s2l!*U6!T$pjM_!(7!ggp2>>mB+-yS$DI)N{qQY_d7M7vU2Way2MpQglU^a_I-o z$8j|6s`Ag8MiW;?ZujVO1Nc<_XcFVV->Jbpy-<8X(3X)?2i;jsuc9z4k)U!kUH+k; zuViG`G1)efi@BXZwj(%NEqpW=Q_Q7Pn+TeQJaLENDR<4YM8mh`zGc@>S{w`J8UF;h zSvEII0}S;b-zN(!B?`(WP&~D@U1z&4g)(HxDhzac0lTgs_X9|D6ZClo)J#3azvucq z-N^rj#Tz`F zBIy%wOr>Vm`Hq>dWDsse^@5X&@g5_rD6ln3whk-y@O!&dB#i;Tf*P`}=a@%eS0kkW zBVpfD%T9;uQKXdICbM++rT$1aJ^;*f+&N#8lIWFvMj(deX3M&bfwXpO!RFV2hR5?; z)Yiy(*p;-~ULV(BJ56qw2LjoY96k7VM2r=L&X3p>Ido8IX(mpA?AO6i-lE0D?qxMjMERe{UZyQ;$<_*-A%XdRlSsy9Xki zbJeEv#Zgc|>FItw_`>86X1cpH@vpAt3Vpk9l+yZE8O^JOQhisAEpu9$Wm zxvcWjn$qL}>*Oh;Fuv}g{5rl#On2$YMbOYMYMpHWQcJ<^6Y^@exKa8$&P=9=ZBekd z9`0xKiOaX;PB%c$-j%tKkqFyh43^>%wim)luP2A4b)m_!>o6yWhc}1G{)uKu6O?E+cIy9jY>l10hMekQz2PTaN&FL(IlPqkAfBM3M``jAt;>hu-N++wPnkGp?C zRay>JcS`PdTb|OOz(gpQP^(>hZofb6(KXF?c< z7y^m1&uKq`PRDz54`d$nF?2dt@Hb220Q|pP1HbHt?#rcX6W%T+q-?2@DkgjaJ9Myz zQxTgbHhERPv!E5vYwLWG;a4h5)Q1cw#QqcGBlC~c0w z=LI1_WeUnbaJ6spD{tFm>i0x>+ogiQd1FPpY^7Hl;%#~or>Hr~M>T;y{!Z=?Ss$S> zs@*HYK(x_qXtp8}|Eq(fQkDD52R~7NBLbtd%PM>Br=y$!gmejez6&5dY}Gv%Et3}4 z*1Qkut~aDcjXLrF7DKtcuUV= z`1fphM;vsJ4PVQKXoDdVvSz~+_%aaA*O_1DK<7AfAMwz=;6#L0Ga3=CwWIU3wIFHU zun{V-&+l$5-8b z@x?f~7j_|`-HFg^eAq&Z0s>#?m8@b2RMEzVVzL##bl*qnD-CxItl*VNc;!qyl*`cw z;L6^UhL{kwAg1mnqpnaebX*h)Y5B084ed8SHYw1^Vte2y(9S5$Wj1V(qtVFzv&@0K z+6OS|K)ijrH^xS^QD7uPO^Em70X(FYgLpCVVor#Y9)`C{!afSDSDwSWz|1cKH3$6H zD)&3V2-qTLYcX3Xql@W>KwAR$6Z7{P2Q3|$#C`nltO_r_vS(2Z^M^?1(=-e5DMi%F z>Ft4Un!k@rKJrcJ9nWnfK7D04;?%AXV~#3ONbzDTnq!QN> zfqC{Q;qY;b*;cc_W3@eroA|FQM8`o7v>_hmHz{O>;&yzJ76pf2xhhR`%l&Bb)i~t% zZpQbslL9@qDE#Z#*4~vsD$ywA2QIJZ zdj03#7d#x9Kv6b4IE)S(0xHKSD)TAIOZe?q%CIH;+f5x%w_(&*Ali|681pm)4J3)( zf$8cf?M$3|rQ?9eQwrwW?E&|FAMn*w@vH9k-EIo{sI8Djb8uGix0XJzPkA)W_ionK zc2&9Ao>=bzjna$3cc_up_}CYR9-UV(0X{3vutTNGn&_x#>nNSRRf=BG*iDqh=s+$3 zg;Sx{M}bHwo>?x^N^?HlnGH|VhcD|Wa)j}05;@@3->U;3=Ro;D^->BX(HmNi2a*fm z&1|)FAS9ft+RIjJl!7Z?ga6nM+tPv0>cE=?kbxhO?>Js`UG3kWgzQo%fit*5fzIpX z9v!!?wTya=SE|idbgBtVlNaXNhF5r4TALF8xX+0;Ta-?tdN!?xNZTaGYQ2axcN-8)a6nNlcDG`*RBAo@H@jTT(xfzdC|YY2PH!IkJ^Mpk zEw?oZ_E_-3i&&4Gd>z`7Nc{$%$16<=l(O2CGK524?(x6wT$~`|f4+^5HHC)wpbnl~ z;bB_Uy%FdMTJb%(#(Q#61`1FeCBygwCrAMxIVTu!aen$DUDYhiI_o&ef7*hLjQ8(E zl$B&8+)K3$ZEu?JoiNF6f(i~>>8J<~?N@^~cWsngDVl3Qqt(3{U@uC+1Fu@q zy#7=FEaBgCpC9c~{wy8rZw02leXej;p!izwJd2ZkgA*}RNFNU{Q@#evan|BDKO1eTWUcR{+pnKGQgX~^^_CaY*s2_snCf@BCQCyArM-kXQWVf^D?h$cDB|#h zuVN>t*YE`GBYouVd?Pe4zh15Q$^5D4HaTUTz*qixsADOP=9(XP&{b~<70;*dv3D(V z{pXDfA8eNW+AXWZ_>-lb7Vb5v>ojdA$ZBUdH6vT?bXA}nXsD!$B_3Lg4_R$a8R9^D zuNe31YGn!S*9`OgpQ&cb>8QoIBYD=qm(VM0wR#|Y59);^=tDbzY8CiYV~NU3txsg$ zdv0XI)NjJKDDCTl+zs~WOiOq_fwh{AxOxpb&xY;bVQBMiYB%lzBCTCd+>OV~vQScG zE6r{vsslr~sWjzmnzEo!>)6HE{MhYfyFEMmCEMbeQ?xI#Z!fhuPFM!gx**0^F9)`z zxt95B{rTZjRAO%~Xe1UYCfjxuUo79zV%P|JWl%aCh4ed$1ghe>GDU5H#u7!^imlwp z7Vci^cXc%Rcthzv%fwE`r|dTNZ7Ba3^b6<6O*Vrv2wCGm9kZb|6y&fR{BE|!CAL>e zHma0kuu`tUPqr*=@apb`&jX>toa(VF+}K~7&nIwIZz9)qU`I=a<~e>7Y#2-7*aLr9 z&AQbku^g^P%+upViY`f;*@5Y))`mK?b5xol@ZyWQTklw>#N6TncTP!b@}$M{&7k>l zn8vy2+uC2Y_0Ob!R1XZeap>eu*~3H=pvi5XZ;G9L!as)1=k)}k#}ps}t>FA05Vj&5 z$bU&Eq@0*@)=?>i!oT35K05GeiY6T&Z#Q%8k2!?P_MV|YQP-?gN&At^G84tUAN27{jurvl~q-Z22!D=hu9eC&*h4mH)PXtEZDKwPravkJEt`eX) z+ZX+YUK0ZN9Hm}#@2ijXmOaN?5sSz4Eu8anhrxkLazk6M*iX4$p%5MWFOVWmEv@1( z7cUkkX7ob#p&a-j7cYI$3VK=ruaF^Tiz^#Le$5d%ZM%|m=kGAo18Tdcb1C3NeDsOo zkjAsWup_C_%^v0gML8wyY*|D0(fu5SAP-9-Td6M_ZgyW^gM80F^n9~*)RthtU2qVM z(p|+@>Q%rOfm&T0wN^HCJR8!;-grRif0e>$(Xo&#Fz9e4(SInv)6rU)gd;i_+fc2H zVa@Tu{aieJqEr79unWUus*5#z%~ox&gyDd&!RSqCyc! z)`BD~KH9|N)^J2VMtwr_&iE_J3Cy{D{1G~;|(EPGf zaNj=j5;l0Q=)XVfN&gl}YhHX85^I{pQ^FUA z?slyIP)uRJj>9OL+)Y~)Yfv?>jGYV57anQ$*4WAwa$J<(SugmUKY-apdVu4PV+w5DTmaMvXv^Wld} zz)0#6KlA%MKE~+KTe~dSOF_r)+pEvAto68!638p==^NY=`q!rPUAqlzqhueR|Gf9A z1pd3UH-Achp%`IW4;wwdwNjKN9T{^*!N9d_eIgnDayQlWKdxMSRhXatiO&SK;?H#x z2j8t}2P?6!@B`<5hkrS?`}vK3>fB0O^t}nMZGoQ8p~Km$MV8N6wQK!hcE3j9!B+E&60^l=!#PNFI}sphQ+j=nyQP43aC*ra>ZRY(?D?{w%}qx zTz!Jsl@aQx*=#=b^0%RvjhB2eA<_Tk$7#g1ynC?_d)YXx!SI2{h494NvhiVi`lCbD zRJ~D$ign$Q?4d>4sA)X3?YV&wEVCj}{K~N!IiokJC8*|xG)1N%$^bPs$fjxNH!pRbg&eKBZt*>OIn<$2ckb&+E1!KBJ!%eS-sC1y|3S7mT7 zf{zzsuDBmRP`vRabqU8?$;iuNHwgx-1_fE z{N?|GS!zct;#qmr5+DQ;b2>Zr-LX4UhKos&4xZPh@7dmWPrI#gbwh6`;`3fYaFfr6 zwZ#8uM-$SEFyHlCD*vjzPG8By%3*~TvOf0zjGxqUka?!I&-i6KbHe^*c;)jfi%0fv zZ5FDImpvKR=RL!HbLJIUK3@loSx?6t_q2III)2ab*XQjL+;3;4Lk<>GEzhl&wt6#| zpXipQxQz~GVgT*3KgsTr(~0W9&GpCCx{ajieBH|SnK@phlt!D~7^T8PzZg5F7L)mc zJu>zxMN7TmQpudvxWmZrw0ObcjB~$RF4nkF4c^Ka!ILHm_?0^UYgWJ^;`DfRW2uV*T1N)*bw+H<0y^?zZYVu#9 zYXCP@B}*bldlTViJ@&0saY7IBTU*g_04SH%L4;2Tp9GPvmc?f|17Atxp?d|=v|@tc z3SS(z?yr@VQwqPb&2n53l%LIH7H)01I?O5TJKhh16RwLh2UAPan|QGG@?iVpevDsv=+)#I zq;c?QT*b#TUQK`@D}GFxPXS4ENdG+M-woG<%0HffeLq{>y~LF!Q*%-XLwDTM^X$rK zO(%m4V3MI9F}|Ru*K=Alz5eDgKhxb8XN4`N1I(O%+VcX}fwFt27eOYg?O^<(#jT4- zedu>5fdijSk3sU_zou9seF}0}vjoj2RF-)cr6@C8PRn8~&oTJNy^{i>X2uPcO^5D2 z^;1MwfxI|wj$(>=oOCkrcTNC&t}Cf$RVhQrl2_J&I^H!XyG3xb-{eS|Em$0_l&{o9 z_~+r!X;<>TU5Z8%uUx23i2L$dAMrKE@$$8=-nEbcnEnvU3?UmyYr=z;aA;z;#lkx$6O_*+0>Utb~-_+xU?xIeovX&I#TtZ>+d zYteT$SntxGEf#LqVqYrB*Y%UO8*Wx`Ib-sR5|o(dP|vW(Dqcf=+!Zx26!>~rM^Rjl zj&zj9hn*xd6f$Irk{l}~ren&k%znNUhubcj9!#l3-B21YKRWw$1!(!XAtv5=)$;N? zulPNBCG7p-JckmbV&j1Fw+ubwpu1ys90i}CO5*s2%*c(f&mYbIQ}7C%GeCCQ8HT<2 zC_%Xttrcs`4_L%MJ3Sbm{7|HK)*;)uZn>-TEzuXZoE_$NC7tSX zxre*O%bG55+VLB$sZR&>5#6e`a(Rlu7oF3%Cm(GDot$u}lxaLU{KoR%=>GGmmt)S^ zIeKIW0cX`A7q?d8e?_<|6qY+ze!0=`KXsH1FC^f9MizHAY@3hql|Ln7|AoHJN_cib zPL2kX(e#G4DR4JMov%2%o#=~pG|0-sc5-hVk6|cXoOd=2X3L+OJ^4MWrp)S*g8Q@xj}2n+`=IQDp=|3s<4xM zSnw{jcatp7c-hr_^|2b zLEt5}Bx($$(0?7V@l6%)ByGRb*CCR=eOVx@gL0$JPXz$z7mftSl*D@5c z0+8c^_x&XA`&U;bMPDBVvIsFe=GUzXch)y*lWW}aZ3K8p>ly5H8I)|<8&$hq_?1#L zNu8_Ia14$h#EM5L9%F;#ejBoFn+VmNkv&?l|d_IUd}2_7#%Y;d3z1msVw zh@ItG^2@WA1y6V5Mf+``d2DDJo$nS-_JWUB1{wO#R&-#TubAWVLJw-Gd}(?PU+yOH zA0}4$^*Q#ZOK4S#XDLU0Q^o!x#r(8MvgI>)zwK?XB)(6yPX|<&`DF9hNneW8pWIOX z5h+!koLqS^&Ifxsy1KQ`5{|iXZKLAG4o7P< z8!5YiXwOAJ^{`IaR9-(SInNdqobLS!dabtTnvG~%J6|d1NN9jq8vE>|JoJK)s@Iuw z?X-ZS!sl!vz2lCUhlLy!={a}1@=~i|tc`MFG3AcjCG+b;62o>X&w2|x^G;d)Q64Cg z&e@P=sUCfLIJqrbBVAqUuUe&tNHN*~niqBIgq7%3`Me)ErK{*D*I)#73tEaQ@dPlR z+0gGC#2H)qClZW_6*x7BoM8zhoks591iE+l=LoRBi8DWK)^>r3L2xaF&pg~M3ghrb*h2ht{dS*s%Bwp+MC_FdC88N_r7n<{ z*_HxtW7Anm{}M7AKdSSfeJUh1Mh=DkL6d&B)*isQ>etbVVOsH@vi7%tl8^>e6&XsAbXhEV%gtOda z54)ewfp+_c?j4q90Qp@b(%lr?3q6gyo?-&aE|V@|#pJwZ4fhO|BT8PcjA7gJ()I_l zN%gI*!$-a)F+=DvS-2l^8Y}RPgven*7qJ5Gu?REuds`gaWwP^&AU|;rt3TwNS7^j0 zSxz-1^^YKeLp*ROq>ZnLjlNx}@rA32X1f?e)Z&Fwx}@e^=(vIFs};2BUFh*Q&;fDB zJCvjUnVf`uE0;QLAPQ+v=Bj5v%_swTe>1*pmS1aVqkD!d9aBl+@Rg$C$HJl> z$-B>v1?7-&qg(2k*hamx(y;xAtZXv$h-qCO1AB+nc#GwDA-k!Vgs_Q1l(P|{;Z@`j zy42e=Z&4-WtRtJ<{SyT99!s6B06isLSYvn1(Yt<<hiUKld)Rj}w3v#;1<99Oo8)97Q`we8bG(%+hgqs|SBRe*2v>6Lcs?eZ0I&dwNU zFpf*71s+cO!lw%t4eIp@UsO80cHijsg`pTV$3Ueo6;3lrj z@>3!buWqV*$75&|-QNp-<98Ov-dY+P(U4 z_tatcaOq>y8a~;gc2`>aL*0q(rv8I2jYnvfLjzAQkM_?(&+%#cKUW-j>*#LjQ&u6m zhW1NXcHxj<3s?cD{8{Z8P3{eWAE?}cC;>Mm#5&s;W99RcbA&W(`0T}4*LJ!%Z}^MA z1p9fu6wH2x>S4RtLA~)@L>BR4l$%V4phW&c{zZvH#igouEA3y4-`ZA@KoCEaT#=e-+=@3g2vL~s6+69cBM5$Gp}luuE#a(vH5CJB6I@Z}SrF6*XWu>x$I07O~t zFX`Gk5m_6mz((iHkqNIh(9n~pq+N7i7&?61RN2kSeI3en(UVlVd~${_m0dRU)y}Br zNht=J#gWKsey%Y)^xA*{n;)FNYtUUcp?9HBH6b|mm5=g>2ICI#mRoKz54~HpEv^=ejpNTxUn+)&W$`Az z$R;X}ofDggi<jV)zO!uXm(?FHK?FKsRmnr4l2jEFq?8&(kcI*_a<`b>na*p!z zIOH&wOlo@QEk=gO!=qpAXIS+GxAa0j<$o-=TqvGlkk@ueu@0gw)5gEcQ2v(~(X9%U zycLa^ktjTR$7{An4?5MgG!=Z@swa~zxLkc?`5}BU@CEeJFQnzb>}6#`gaOUNQq}`d z5_u4*V1ixF{&ac}5xD-Y^iovQpdp6=|AG7rP(&1cUkW`v=5i?+dTVO+?eGK>vP8|nz6Jhk8osK{Ie6vcn6X{|pI}81OL8BSr=T&GZt73y%B_Ka@ zG?f#PZ-@$iysS>->B#AKhbH|9*SY*?39a(-b#!L6bOhqxtcz8M>twjHiOSbvvekwP} zBih97%%m_>PwPWpw#igH%IwOtE7qti!5j@=Pqv!*=KN8Kkq7PA??(R9c3BG(nY!%a z^Yy|>mzN)IiEOC8i{8~MT;VH=LKE&Fkd}s<^QJy^$R&*PUa-jgA-h$vgcHwyIA;(1 zyJs6S>T`M#TEe*OzbVIE%$J4gL_fZKN_4X+hp(vYPXJg_;Yo1Lwcve_H@c7^|DKcc zbbAeoirialOQ_2%qegGMuuQb8EK7*w`>Yp9$dWZnS@UX6Q9Uu375;VEWt_EWml%Ok zw(7(S*V^Wa8|QT5T@`KhCB83r=4LzDrDJV2BqoIW!%9V;dwF)aI2Hcbes{7EQT8Bo z^~IZ|p4NAL&R>6j?^r>Uy^8p6=H2{_)^|0|Yjf>>V)pflP5a+x8tw=Ee1A0l@Az}6 z-9lO8*q_V)F3kV-?vMDo-RM`BA9CT|>Vmy(Nz3<#EqiN$Y3PPoMF;v+ZD`_`lcq7d zM)G<1jgJ-!ec?YpznlMaojn+8=NO=xEtA75^|ew!u%_H3%~_#YQBVHZvbdnU!cOZ! zbT-PvSuC}UXk)rxq}mv&_v!Ix1sSWtmaz}JsnPo~E4?y{RW{<4iMh5#{r0#!;$H&m zY#fBs>dRz}H5zJ5{?Z!iYaPZkVxGE=l?^q6*JW=^o6yQyUj;SEIGP2n=uS|nU$h>~ z*^kLQ0xexCi-v7Z>BSHA@piVz&QEJRo$FiELMYF(47#oMFRv)ipe7P!V%B`>a&58p zs&+OyLMI&;Cl75-8=MNt!lWK@;6wg4qSl)vZlIo3{d!d+U`FE*xCM=oR;dcsoIShj z-$ln$oigS+o*->*@fypOQfJ@1l2H7U^nKL(@kJ`Ezm>J@sGo&-yRd{* z+?kW!F@hMPlM$a)&(ChwNN;|vR+o0~-i^0I5V<&*)VJ59qszzby-n{24^O=H{UaNu zGGQ%bD`b2ik$JH=l6}_RZLB-)zwo_a_Sb2=|7TQOiiz#$SskUL%0lX91v$fJpG-1O z>Q-A@+eMwkuN?FE^+zY|nqq;rki<#nchx%m-zC4)sGN+Othrcj+}332tnZ^F9A;EG zV&(atrDtHRajc|%#DbpTl++z(y|D zmxFF#kGtvz-0P3g4WnPZUPc;G#9B5!m`*=_yn533w~flU4S^a$<(tI2n!HsXQ{?kO zL@p%geN9~RTZ+P$5`5`-U*rY(WAIaHxk7JV+F5Muj6YshG!@loG@kI8u-T)?Bw(!s zZ&f6!#J8u|22d{^FCI|@7pB-?tORrG#T0{13D@W)36>Mzo-si)rED%9^AO7Zlaa3& z5$j9(Lw~Cpp&;yW^|Q3y#D{_H8HCniz4b5FOxBf7`R@}?^wmsG|K`*dKMFfQ;4u>w zlqys30j<`}l_Tz3L#dFBUPBH;*tA4`v;B#-(kN^F`Xs)z3tIldk!zeRv+%Xh z$}O+5&fzi|y*XKJ`sq;ZNlV)XdmoML7g5AHwIX?{iql@6V#>B*(LK6}QFh|A1{$i> zJt^$9lP?yCejFAHc6a`(Am1}18sV>eWak^Va8G2<2_?9vQTv#xiRGc@yr0Jtr-V*% z3M~4R={m)gQ}Q=!@HaX`1xq8jRh1GH!_9n!&c2~5$&TA+>>npo%u8E?!m%sUmm&&h zi>$g0o0H%BuAh?kVq?o&2>6fpT)uLaiDJJr7X#^h0k;o{wMFj0yXAB9{!84c>y1@>wHq@oHeiZW6QE2f8R9nJ2gF52P$8h%N^msIQ;_IiMUL~Lx+)9`Kt8a z$~T`Fw>&Y1&h8hLRWf;*iXa)EQhz4U6IQ~q2AYDzE(Pc6mH^9Vj0D{s1Mao>U8S8d z-x7OJUoZ20+&UqMn%WWj(&MY5m#TT2M0nz-`!3Z##1&^HCfso^z&Pq)TC18Va!*Hfie&DI8j`j#u-P zzDO$I+aZPjUHa%=Thoy0@G0s0vUJWK!PkWU%tXPgB}dIykp3dku{mvIFg01%u%u=C zvl`Tn@Uf{hpj`5Dn7iK7PufR}-zyywd>zV3yRyde^q={X89I=1E1x3uTtWEaz?Yub zM5og)P^PK*dzl`(L3SH6dSe#PR*nd&bY9oDt=qvrm;d83!8;pTw^Mu*D97eig zi$cl0My}?GkJhSr^{LBIU!;r0OZMBI!p>{YUl7V9j#$)Q9lg4L!G`>f{vw2%d8B&v zS=_zJi`!Cjy1`HMeq+m(4ppWY(Xh(nDl4DzoP9`)9$4@mJUzxcJI)}g(Sq=sxQ`rh+MM`S7g$4GkywRzc?hIW28#& zPimgbd9EdDqk&v0VvATCS3Y*eBnfT5>Unr?R@GWyHc6_<$ZjsQ|L1tGOTlO9TJ?}& z2c$vG^`PB_Uq46>&z2Z7B8njU|Kj_;zFty6^sl`s{#Po(Al< zo|c23;nQNryw%aLd4Erc|Xu)x}O$N^htYh45iuk9EV8=jm2| zu*K&`OwWF^Ova;s&S~lGXzM}cZPcOYDH%@a-8X;LF$qYs?L)bJDe@Z@iAD%?g5f=E zx4$LivlXpvCe0$W6)It8Zv-hl=Fm5kV?Hn8=)rxXx!Z=5h*E+#VG10#$|ttv;{0^D8657zlBRC4cq{n-Mr``bSqF+B|^t?)zmYN zC>Pr(*Sjc;xoSKLRq4o+>gyJonG#reFZ$_==sdk@k&<6R zB|rJ=uACF&oD%tIsWfk*^FvQ!LtAP~7V}F;<*TsPl9c*Oaphr2!$C=#QDJkIjO~J? z#WK=_BW}GZ;PwOUw}vKulsWrW^!#&?^W&nv52Rd}QtqAN_RS(EtK?nVb%>RR{n{0ho1f|9+A}=5zEiNdEfTJPYd|V(9h>MF$L0MK+ zLqi*T=&+%_$6>8w#)r&~nphpPIPf?_dsRIPMO_E!!>;1S=j5$@PQi!r9*CEdI2M`#JxU#B;=eE0-g}E{7!hB&1)VB*sTYMN_;Es>=I>+fw{2vmJ5y zN3_yqRIe#n`per>Wbyg3n&k?XjSAMiy4XiD3J=gquf=uPB4!_i96zX7zc+MvVQ_j$ z)%TUy#bKd~t3t`&(21`wlyQTo6`R1-b?bog9q{9J3%!}gB$ z`o_Bzjk$Nq%8H8fvNLkiZ>1C#Pzp1{@^ganv(KldpUKW~$xgG%yKR+OemJXKEiF|u zEmntm>2Qp({?#kWB=P}TOY!O*ndn+6TC>c}0Zb@U=jt;(pErj7Y}?CA#OPO^(L)}| zQ&;lF$*J#>GZqUf-V`>zt7>0pfAsqPBj%&A>Bmo=J(-=IeKz{x?evfNHy_v^KR*BZ z>OSX9@8rXa$uV#Jt`Wmq#aX>uzJ>>KK$~W^>=ecVy{@d5CIX(UB z`jh`M&n@ZMOv>QZDx?KU$8g$A`qb%Zm3;mUJ2~mU z5yZ3qZTn?lTmIQSGyC4zF@YW8??5IDv1*@NjDo=9m_)A`h|=wCpVWA{^3fA|qn(Nw zdIcWT43$DheZ10bjAFH=`n9bSO8FSB2_??99=}B)zwdea<$ng#ddmX2K1$jA8(DHU z+(H~FkS@RJj3Itkwo-oQEDie-pk`3~b551%DLysRZZiZBeq< zcI}?0&8lZz<;-xF*^o3B(o6!J4ylRSuAI<&CM$d*ZfrbsTJB&EKB&9C=9?-fW%8CL zhhE}4I4^Nis56)F(8rtYuob^46|OElGaub{xnfb~DdH8mVYQ90FkHH=-uYcEmVq5~ z1VbOk^C{rvC`vLZhaC-%LiOXlawdmm_^KyVO8oCZ^}Q5Br&St~ucqn_qQEeaajW1}*vFlfSKQ#b*8lznIcUh#v|GMzzVXB>=dJThC&mGypL*-&vh%t{ zO#pl9r^I&EAV+#{hGHf;lJJaoV|8ipZmOJfEBo*b4e3g?{D8)O-1L4JBVD~>ZDVJ@9I~Ot$lA!4b6Zb!iuJX3@tk?poy^a$ zp`to(zr$Qv)+V{E`I>Je>cqFf&tJhs4$U%kj&R`KbdH!5Yn0clA{`OQ3|Y;!Gc&>> z#$yl;ANe?37+-w)Dkf z=FKJozkl5S`{%%0Cj!_a!}FtX`*Ap;6PxpUQ%UvBX?q9Btwgzl2FH(4&iUiGq?u%1 z4h7&Rf#fhukhuddm@l8-sx<9P2=$~o%k8?{ZsY}1_8&@$?F*j)mM?@{nJ)G@ulT=M z9;`RT%47Vx*m_Zku6t#=TeFo&10m_Kn|xZRGgY{9bwt(mIrNl~{>?IvB-N)!+zA1{ zGR}1IHZ4n}m@iu*qa!bS{bY33D!Z1K!_TRC3&P1?s}dNTQOz(x5AW5FImo*gHH?T> zf>fdyhGWBPoT3Z70qX3Dr*1cZ+d|%3f zt)~+=o)9&ZR|PTKVO*>oVl<8O=z6cG2{5T~4VX`w%h~Xgs~;O0J(9wz=UoqNosg6I5x>nXmw9zpdr?_bu zh%$&gn(ohE3uyiB9lkZH!9A6J&dt63AyJD@OLO3$*bCQPfqO{?G> z*J!>2LaF4pqd)XI(_yVar_0J&I%+cw@51B3XfG!lH5GZ-sRf_XDx=MPIg>@`epjEc z86ud@zf9%oV}W#I1=Bqu z3&i?Z0T&KGS@g~;;2Ivr;VlRh(bXv3$Lr3fgn__*Qiv3LbeQZj zC)BP`+ywH2i|xWs?O9Glxo?E=OvA3me-v)yct!NV;L3M=MPknJXgE_IIoDKWzjYc_ zeJpwLcfk%KGSjc~o7sI+xsdYpjHk+DAID@^qZU5vX0T_VsMsYlogYuO(?5d6Ff6;vnn_t_ zd~Ktj%-T6E+8J*Zw-=9dA8adpHXqJ=eQdKr6#xMWm`++-S*pA&p{x&|zIu;ACo zi~msDb5^82VD#i|vn_Y}{U;IczpC?&zcJ{vH z_>EQ&yoCv6u<#zQp|+o)?hqJu8|GFA!;ZsRh%mdAaR05Vey3t?l3{B$u-;3sg^P*z z3GPe0@L;8+n-#Dq+jyti^Ptgydu-SZG5_zUL;u#oX)6AZLU{VC>ndB87Ox_ES=ZBR zNfZ8og|AOPz>zavUoQv`5@Y&oGhH5#fc>&U-{L{!e?;A92G%{l07($P;HbTtHT92e zU>nx!5gR^n7cN*3*FuVMPJ!91!dgIy^?a}v(vbsvLT&{-vj$$ufVXlkbXLII*)RqQ z-j0E{vC?9aU=%X!E(TV^hAl0_wD5_i#$b&V@xu_9;dZFDQT)y?w@EwV?j@SPxPSQT z)0Rg9B~kEx(v5qZu#E0h^dFd9#r1!`VOc%o^*MMuA(Qrsc6$|;rRs_y0gV?^6fPXC zdTyweZ?wTUTU&UUuHqH@k{0{eQJMp*5QXosyuKWPwcucP8CUPp)Ao|n$}#X~qPAt2 zbjdAfAui_*4&I7Si21w^>&JOSF2jy{z;5Dh+$6#L1Jc3_lLyAH57xma#l!1SFrB&B za9Ub^a@Gg@jkM%UC*xqq>(j}0UXUB{;>5r|w(z(=mt*Iy?-r8(Tnt3h0i+RtCZ}MC zfEWn8jRKdAA$RD=a+<`GP+b|enKTBOm*O(M2^>f!D%`D_#~dH9V8T#12A6%-7&c#< z?P>&HI}ESI!&|WMPGVXI4c5;>xpSNzF33R5}V>!7rW&8l(a53OyWksm^!gO@<#HCX+J$UUnRhL?#6!? zGbQ)geoYwoJ!}*?;(9ARnEd(-(&J2!gsUhSu8@R8ii3AZNO>Y4Pbw^22abiA33Z*^ z-~!9yQcILAghn09w@);`hG9^Fawzy_1-$D9tdj^UPK9-1;d>sHbp&`W7T$}4wM6B- zy9A>%ireX>%9B~$6~*mXcsmJBXJl6qU>zJt4H;IAg>{f%akv-Mf`hNuudEi9sr1=z~vVK zY6|>vF;amDh+keMBKLhX>41hjkKQ zbwv1sGw=>9yc^Vz3xoEM;nfxJ4x&KMfsG?!bRxX9xHQ)R-c4xi!T?z}V3k;S4F}Re z&aFRq#13A~ye)JP!s4VoUWGjfEbetkXd%Pf=>R0M^oc$E9wG1+gb6^eQB=|Lhn0zLq1_N|B zG~_rm2yqw{m)pwa%utJGqhiJ~TYQRA7LofrU3fPWHiktdyjLBJuN0J@?@`C!^Zf&UP| zKi)>EueiofAWiQgCE3&FyefesQ}kN`)afK*K&H3pt~yIM=U;U*T=jqPvy3sDa`7&Ql= zSa=<(=~gs6I|yDw=oKZv7fk?=ao4*vav!Usnc43Bg;ZEq0#?bSUMxGG2E-=8o5=7^ zEFeSxGLkzK_L)Ank^yBuFp8Y=hXkOAz-LdeztkNST=%8%k11^$3p^d|-AB_jh;k-{KwZ$)n%2B>N3y<-X&1~s7QRVWgy2Lohd;RRS|FK!Tp zg$r^(T^taS(U&U;pfEu3@%vSz{<^dGZ<2=89h&w+3xZa0eJ4lG;SP6UKm zaFkTnCLVtDcBwc9{s2|$Hy#jogG8K!&HW{PI|B$~fvmb(kUd#~kg_RJ_Xh(OV-$Sx z1b>~Z^<8TThZ*E=09uAFvfOF8DrN)3Gdr)(Y}4U#C~!ZqUX%`W;YPbi@O>%G`$8mm zq8U*47bL_OG}#4Vh~Ntv4^SXLW_l3C0TpTjMFWF^j6p@OcB3e`kv*)347p2!qomur z*?siJMx^ElGJV42cx~|8ezS#1l<5eL|KJ-yQRroORO!lgBz^{v@*%t z1n}il;M_EL(GytFeEf%5yK?z)+plBALdd^lzilQ!y6=e*^AWKNmdC>P)8Ratb;4w1 z7a2HtdAy50S@x|@5I2rQP3(FB8D3ytIH1J_32;CHY>?C%s6ZMhD(x%K0tD#K;u&q# z$M4slh1FmIet|a0X_jDVW6|DZsx+{b3KwGz%g5~Zb?*(MG4THB$=G z5l`VGW&>EC|K{LvQeX@Y*xqN?isNQvrddcVkiFJdYzp7?g2Aq`uK$}CB_XvqujB8% zUcL1`rTKmIKTyS$_9_ri&4wh#LIiF<7s5Qa&Ho0)p4+2R@lxHZol z+nek}f$LH2nh#)Ev!0j-svlX`(hy@sBf;5+~cI>8VOP&EsbxCTNn!2+E58*%TW zo#uGHgJT8e1el<>I93f7h9YI)&0#{UPr{%{{&&m-?I8uNmrbb)8*p0kG*H%)&hWa99WYC?vDd2kiber zR{3{brb$|1lqnn1<( zCwA99TRj}yT^l5RAJk$!Gjx1HJvvl)7U;o%dkH{u>9`Q6*2-*1hy@?kD2#*C#YinE z^0W}+hZX_Q!hO*uf;EX?RnkK>^1&6XM*kQVh*V^~C=Ax!Vgi_I-uveC6#SrN?Ztc0Nc^$}XZcYaQj@tB{T=LnZEO14rxy=5 z?R193|A9KNd~gCRfdq%+_+Yp-IQGXiXBM)874rSF77>u0{=9ny=(z^CO26SY2Na0# z-}@}GY}boexWC7%kZ5>+2%t*ZrrEigd6dvG8tX zNOUgXArK-a^6p3R=oziL9V|zV04QKKg*m@?-z^I;e(~pnOo%wso;i)2`y+;fzd-`Qvfq(Run^`;^9isLZe1h` zoc#<53eMtAjs3?jYh6TGv`Q9`F;5hC`DmRcqPVeShg9T^+rhGzP)KXuSP5L>IO!)f zDOPMFwU^X7bW~W>+Ko6kWXT0F6~lU<+;|eeaI{f$@KzFFr-KkNk{`0>5<7KnpyF?p zM#ep_b4((OSwQ8rlrU0wi5aZtsj=MNJzw!0s zG?yNm_YdO!j>;RbqTOBKh$ zMhHZ<4cJZtfsXbWN5M)2e2M=&PklSpjP+hS!Augxq*5prRE1|eT%ttzB;n?&<2ull zXlCNe)&8ayh-5tp40Wt$128qzU;&KONEU^vqbu~E-@%xK)703-AXE`{ocZ`wm1_SQEx8M9I z|LzFVQx)FuyoVP@VE2iZ&7dETJ$nkb zIA#>Y>s4==BxXxI$t@zuK^}8i@tp<4Y)3h|qRyny5h2F_M=(r_smcxa-ori?Q^)FY zLv=jZUE<1-WXgae4&V`S4`6orLnHxvp&yHO6@nqVbq-g1K6TG0hE3VY#hY)ZfMd0K zaoh!t0fKUZ*1eGTr;ihTl0-sG20QI88?nifLY&v24Ma+1GB_uCgvXBGMVV)_pPs;kSmw>Q4W2(jF9J9$u(4lvN`!SKq z9(@VkZ@ODB9zByiS}IN_H;Rh$%~%R!JSw~7@16p9Vt&85#NG5~aqMjCBi`GF8QlxC zzS!<7I&z4OHVk+8DSdf4QE%!W?vkzO4vNtkQw)Wh#FPi5{UDnmyM0?=PG&JY`U88F&+%u z-N-X!_OXj{WDNN1m16QSsCy_e38q8JponF3o#r_ri!80Era0yaq_Vu)FF@=4c zC{0q!k(VcOVN$I?O?m|6E8JA{VLKlrB3|JOQ_BLkgm8(EFfDa@$0{eeG+qZ^05l?B zthv4fy((qu&PUyW9xTz}qbY|9KiYF=LMV3XpGDS zhj5nHt{ekr6g^8nza?rLGAne*2dAvS%=i(IgA`u4!n5Uh>Vd3M#ee=!uY-mugZnR& znQfHw*Xk+2DxD0T2Js&5wdD6FC8X#bfRWE4nL%{fC%*)EDd`?6ilSWTk&E1#6>~SY zHsyH92&+?-aQDxyBEn`w?A4JsJQ^Gg*&Sst(kP!xXcnX}nF)0DzE1Vn2Mt%U82D57 z%lSP~Hb36jrYW+=%z1s0>y+muulbz|{<<9beeap_m;SK@lDkEz{pc;-4l%WzO|S$8 z0|8H20@pz8k?$+W&_i>WM`VOVO$G0fUI4k)m*AK~@&hduede>5m3HH=P;4sVw`Ea< z^4J!6o6l}~bA(&jW8v}ylsLNz>FQDsD3 z!3uTm9~)%P-VhznGorVxMY*zp2;M1IOLRCcA(Z=7{jYHd^dbY1F~@b*CFxq22w3O$ zCqM2#<8~zjK|QyhTiZ9@^4w}Rl-j5j0r;4M0tf;~8pH${5xD>qjut-w0KE0b!1V!K zlB=L>aMvJ0JP^cP1R+L#7kl)oUzKLA@A5lw(Ab{@7OKJ2i!==;PE|i|-K$G1l)7y5 zL8+bXd$(%HR|M|BRBY_cvy&=0{w30MYTrk8vV7pG6EPfHv;P$*^OvA=wJP=CpLVL> z&Q`yGF@=nJ&{R4;V!PWH?SKgp&?ft(Fh3;c#F!OV^<^ zf%{wUfhngGq|sW#eh4o=9u-FXjwWEtXjYN4ACkh5c@vu{1cPaNn)5Wz5syx?EwjO{ zkKM7mc-7`4hHHQk)T|mwRy!Bf*xY#yyX9axi0uV0ekDTm=P1Y#m#jGM0&cG+h`_aT zPD+0yZ#zD7GaMzr;sTZS2-x62 zAg>3RO85LAhqeb1ksxl$e(iiYAK`jQFcHTkG{*vWs4B|9E=sL3+aTLu{^b6^LBwC) zJBQ_=wxs%;2`2BoS%=y`?RWOyaB4K!&#He2ANzMuovyI9D3d29L1qsp{S8Aw#4| zo8k(2R18@yFu8vNlql2ry37c4s91pIVfL9lu*19R1C)4^N7N*o?IjD%|XZ7 ziA1RZIiw-`l*{ZFFON`NpSHK*X2l+?CinJ@1q|a51JfT@kttZJ_^R{bnDIzuc69SG zMFYsuC%Zt)cjo?ar#;5}(J*hHJMl+iBvks*m;6AAC~=a}oFy`i$z}2%^UuSvL1g2@ z%!o}{zQlh3G7LmkK+~Q7>4Uu1qrJC2&;R|s7J_*+kjYfZ<<*Z|20F>$*C%hcXJr)8 zOy|Mydl=r{g9_nm;6b32>y>`Ty=K^U3_oE=68cCO!+cXn%X71Ewqyhr5-~?( zB{0_o75y}i_)O`%6b9}|P+;i=u=FbHYRXO6pkxt%#zADn4^HAAEbkuuVES;Wnt~xf z6cisy;d^qHOd=HfvQl>TcyRpJUTMk;lFhzD8kl`b97Xd%@2GQ)+Rbgoj@o`&Uoe*kK=w9g6SZk!A#~}*o1u-}wG`7ELQ@s*qDcM`j#X5RAbWqO7 z`~#ed0f7lyfP|xH%r?-xL^&})Sz0=(VALAlr^`+3zb35KaZFd9+dzJeB1_T)S5WNl z%Z3qj7@>7vo5bTn8Ba|f(KIRScHrM}v^X8uT~(5$R>Grut+S8hwv9Yfu$1A0gy8{c z5IC4fi^f6Z)F9Dwv~Uz8Jf&6#HWIZasyC#g(+`P3@x>H%#)#(#?)Or@7Xw0Qyd=m} zdR3Q8jjF%`8g>D~)=@b=8$#kZ21oPvfym8KltEw&k&0mhnG2MA)#e^rAOJ^J7zf@j zQDiuV_C~r3OO(sQfXw!RnG-@Q1n%ke|7v`gZEZT?qXf4amQ10{e!*(3WsOv~pOUw@ z5PJxJymJSxBZ7h$C62h6LE?xsQqe#L%k1+EEsWS_Q8U)DCqU{GeYr#nEIt%pflRtj zlSmP*uC}g(J>0LdR`S57nms(RHlDgSl7_Zz>YGsJJWvMNk8DvMAG&{4m@GGUl;&vu z{u>apXEv!*A>dY}NJKEC2OC_VjaZ#)!7TjQrmv&W73!P0oJ9Kl?Uae~C5oLd|J z@NHyr4FJ#C=pUn!=0*W!kPJ(*NdhlpWTiCl5ZYy>8EbSQxR)1imeN3(D{cOuA*4`w zLew@;jc%PZm63Zx)RXz~W90JSX%^ywo ze^{b$jf25zRGCQ4yfsRQBSeU!9!j!TS_T-$v=khjU`|@OedV+%r52X$QTa;V)jGBU z@DwObs|13LAm?%ck|QmeK=bhHi$>8%tl z9FRs7*w&-m;7o3?f(KY0|4^PiwJ=PzWm4tmMiua25)07sAaLQRGUDJ{()Jb8qta^q zHzg;w_Q7frNAqY<)7>^=6|-K1SXh0BQa-)0$>%; z+lsrcVJJu_3oHYI>~qspJ*b*EupAbwEDpw?sE_%(1=&nwA=b#D7wQ zL6t+1FWP|BwkZdA3uP3w$p)+-4weUjl~TY8D6qT{SQ|@~$54O$rRv{xSEv90vL_g8 z3jPNKeHvN5Js-{EK>jGL6=Zv}kq`$Te9YxQh4nG5Xu;#vJ;PufR-zOK&}MQwVQKOp zh+{9eBa<3jPm?%Bo7R4pKF5vkO>~;$cETmo55Hqw)_L_nG^XNU&Z9hQ7C@tD__$|H zd552D0(!qFBoIi8kE}qX5}(X`6o4#V1%Ets0O!~Thv2E&1aBP-O}U<`uYFLco(dv= z&^iTH5&xiUL{;1#QK|rIfWTWX!CI&f@&vF3imXJO0b!^n*QVQ*sk&?ci~`AcxQZ@V z?|pjEG6lRqyH!>lv2l1pZ8MjR#F`8P_9C?PlsT*snQ2AV#_)!MXmS{uV{f819c)m~ z?ZlT5GVT@O0jX_FiDPkFk-43WlKsSa{a7@Sg1!Ku!q^%}LDQ{*yNi<@u96QXm&_I( zyHS;J)Qh*gRb;$BhJ#55m=O>}Z4Rsnf~aF?Drz(>ahlF5SVIw$!cf~AAw3c+#d5vTwk$oS#MLnyK` zhN_lA4M$LwiohDZm!dDeQpSPRE2y!&)9cD09Z}G_09Xz~RRU3UNHbtQ+JVQphvD6& zC!`im?;l4uX2?#Y>N!~NYty7A7Gckn9Ki;tB5o8-Ydp~bPnKnZ9gTQHKoDp*w>2kO zw<0krC9tI}<)&Kl?Z;pI)OdYR$v)eG74aI)Z7p%QgI+;Ik3yn}|D)#y)4Qg$F9u^E z4bE>#;l8{QJnv$fGO5N`6TEG4NyZ*f%pZE3oe6H8~^?p5xlxcEcsfit)H6RXJ@z;gG-{qCn6o-x@ zU{M1=jfDtd4zX#0*ePGw02>xt1k-da z1tuio&xQ+2b=Qj5sZ5DIAj#ge8n9`q{z3C! zYd>k468m*4w3`Y~W9Fo3HR{kCK`*DGFWTl@^!sctkOIXLJ6&YWqMYUb$Q_wdnU%USp}#usmfP?o|A1;HBI~BVVSG zIEdg{=72m!B(WQpgF28HkV8{QmNrV>FPGT4OO}N~7S{cHbbel#{hE#dTv*U~-8IDw zNNxN;i_+Z=ADzw_aGB=Tz3dgoBv=BCdt%+hb{@ygMHTZP2tb1tATWe}!f~0s5&~s@ zT{0|L+5z(qgT@}0RcgEP8{Y+1!gw>#IMIJ^YW{oBi`dK27b0>pSUI}^#J+c@M8Fyo7X5eR(tS9dGAdb5^`r6%smq*EHp6XUG$F{4;jxM5nJIA8qKu9O)~b zILiR4?Kj-C38Zf`D7OtNbq{Zo<>6{WDq+HI7sMFVuc$?Z6Cp|(xiSP&E1Am2*u&(- z+d3JDVyl&sMm*cLIA9k9M2X-nt)1dmtyxcC;@D_#I#*BQeJW{y?>?wX1;}=YHde(j5 zU0d%n_Tr~k1E2MUoHY;LRO6d>>?0XBA*c-?1tPE_cDQ?*4De@8Mw(#Rtv(Uh6%X+y zfmE>!;N!UfnV--A!>&T4_F}dmG*GO+;*Hq`AB2j(l~19rH`YpixAYkQg@ntt{AI+B z#CrT<$%tEAMy1BlQKd-pfVftq?M943&-Q3kTp#VUu>1as*_Jcp)Spoix2p~|KGCPD z$Jv99aU{1zC-*$fdRrqHdR@fo@%~@v@()dAMT)mAYc_MCf#yRdFN0~lZktlEeuQmN zorUa0C+iCdn?$uQ*dxJDd)aG(u_125soYSryO}0NO*+P`44ZsF*k{^)7Apb*Seddl z!9FuEyvlP=qzRhd>H|dK!+Qi_jyA6`p3!dEDF6BFW;mr1?#d+ti9kT%c9k z_wc-wZi+SP<0A55@2}T?tB zKTU#Qic61Qv9Co2&Zz#Eo2s`8FA4;hFdI)!gA(nAI zSiEPxNc_=?J!Qq^?N)*2G46AuqM73zkkQy-_W{c`RJFT zW5^&2_Xk9eJD|-nkrqs#W1%BXdrH6GJC_*zTK@CcRhPx%{-jN*6^)Aef`C0LGRs3v zn-yhSD^w_$l4m+*tG9$AJhnEM2NY1VH{WbVKw2PX1@z|28F!^BI@ScyLI>k$h+CT= zn0%nZCV^@1gW#Z+zJ*%M>)A0#-A1Ao8B+wBXaLBP|K{|dB~X)lmEAbjq@H3k*YM+Q zdFdxXZ`_C19%*=MhOHwqAnFya4Co>K$MSwgg<57DVETM(KbqATO!!o(znoPaKH_uV z>L)O@dp50T55bAJk=pNjVL@-MAc-6kW_2#K&Lwzr+u1mc+~t^UVWJ|*U^qeUTs`8v zEkms(4vGBC>bQE=?Obe0+P#Vz_u11UJ<5e7exb7Ql+GEfX!~NHA>Wpk4++2 zM@qxSRUY|kUcj^C7uOp4Er8g978u=|xzv{mF>`P4-sTAA?h|(7(isGs@iJhVE~04! zavEaNuyUZ=t)N&hm;*J8R(997kLWG4kHL-=``E%v{SOhWaU~)cZO|PRK+RzHWm5LqL<-3^6`;_Pb# zgmei7Wl~oxyJ-&^oN?9BFNSm6?44Jx$%MGKDYMfBLW)4cTSZV=vNlO^`2!NKAFb$- z`96!{j;|Gq!V83`?tLk3A&&XAM_-iwTl=T7(Q9I==+TGQXNHehu3V@M&zw;gIj_-o z%oi5LG1VtGC-j}Z*cZ`w?S6yy{OSkxiKowgEGIuu!d>cVx3&jENh5Q8E=6}x4gxMQ zvS};(Y^~AKu3GF?1m8@-$#(jX1Vk!rEM|Zlj}DcQP|H#ihcR+j?`YIDG@o?y7@Um) zqy&RU*n(kQ*FcC!NPyxBieK*gcUV7OH(;DU3hO}{8u$}RP0d=fQ;9U}VE|YM1LWJi zg-Fdfq^kk=ymn75Hiy+i$BgK+GQ@=cQu{rF9-I(H1}kIcqw@U4bks>lHC7kLRCu=WO<`2r~LXqs+=(jWsCK$82stm{n} zGOSpVD-+3_20U+Y0x)(*6{gHF(HnfCk!wZyx^=Z^|e zahqP@sxV2mU8x7R2jm-86<=!*Rv0A=<|MB8?2#q?wEJt!YvNS)Lzhz{g?7}<@2Z9+ zwr4p-iE(`LXuw6XJ%otRU?ar@CeLpZ7as*$jH}+=5YsEg#B#2=2(+Gpc^u%I)vGQq zB~ZpxL~n2cql(bl_nOSC#W5sUftV~P17M;_$MGhGEXs&p|5x))=la-)Z*cR(? zkWS!Y@En>w&&*q8lE94!5t|09?hTTiGeK(#&uT(UVL>Pf-Q~WNU2{@yG>Z59n9cYp zt6yT9j&QFJTRvYACLNgYf^GF`mwzv=Nw7EXzXv@zNvpoXcl3Gbr~}|eZMCIHZKzVO zwS`*5!$SpI%^TM@6h6-UI2Ky+ICDAw{@SO`0{$ zOx?M7imHtU5u7i@4RcA}hGY?+3;^UXE;bSro2rcCRLke(2)Or7LnHzsyKK{Zfo&Qymi+a_ z0Md9Mxr#M6;@wlVVvM+>IPT;K->Y5CB1q?nQYu|-OHn(<@oepN7>b+rZ7}XQTt#wS;n0&|RGE{@Tq&W#V0HqEnba zfDRA<7~tN-HEUP79#jK0AQ&Y!4j>b9D~<6WS)-z51Yp}$RtgYrFUDp{-7@(2Fl?9V zgfj(Z&V*11l6RA0iv=-jOzJrny=#!)i|I}dmYl#qsK2;6bD5K<%25gRi)U0h8qXzm z>xj>ec)nMMJpB}L`TU62L~TL~+`DPYk*ap|S>%)eal%8L>bGZk@@-ktzu0OUCe&r- z{@cy>oTHu|OsZ@6vMG{n;}S-436n08(;KqsZaxhzVNml_Y1m1+N8B5H7@t(BqS*6H z>vI}l98;zkU%(}{b1k&F&nYbpj4&QOOhD=o(`$5y5AfnO)#gWHN)s1wKeIO>$JkZn zw&?^g$OST`WCBm;{UfKU02J5`a?BYJ5~dHY5HkootUU-$aV?eL3j{!?bOSA6K(UI@ zQwkJ_e;0_^K2Vo9zFvd{Wt?j{uAXvYih>aP;yi^3kBt2&mDUrcf_l`S&M4x z`n-crXULz-KY^dTrw*_)w;EFSeUW-0=ovxhY+LI0J4l`C-%_74bX7p;*xvY)(ZpzQ zR$PeigEoAOwBv1X4TBE1&W>ci8d<)9odIexAU8;KOyxRk;WZh&AA9qGW1P zbz(?t)y`LN3U+-_zrWX)jNG_P- zBc8Pr1H)W8O8JaXsjDv>62~nHbvP4oOh)-4nksulPWZ?g)`Qb-)edCo=T;jq<3Z>h6j!ssnAZVrY zDzPM3MH&~A$3SwF1w|po*pF`;O29QfBmWJuT0yE#h(mC3q6BjC%*xZ;iTJztR4JR~ z94eIl`SOy8I7wEgSq`Y$&+?a#@e}b<;yZNpCdl_8KO4~?qj98<@-}7SQM%<<{zLou zlxT&MlT*|tulaDB>->R2#TeSCbes_u9hWk0R|p%-FmylY;P{RUWISbiiw$x zgh=r6F_meY1^!p_crS@m&dqlHM67&BXql0WaBqx@EhrK?lM18l01CKqL*P=IZc3$! zM3CG%#nr`4({s5xai2bJ4SMseI=D{>V)QvsO&VvL`vT+sZVd5I8kC56!}cy*2kd#g|Ep7d(uJ5S54+v|ux*@u zq^@Cn*Wgr-3RiOxboHU5>;rt4cCl$H)fB~H%VdO2zLk5WBrV`zQNMG|@^J#}#Cpm3 zhH}u*8WM8`gl2>0apKFKT+>YiLt~CPEE(GfT9<>?1fJQzj-vjH_&9FfB~Wy&m0Zki zWpYWyVmvE@)h-=#zQ;s&jfyMxfY zzIm~Y{g_%6p7B50@&g46D=5~xo}_h3Lvk2jQx<)jk%sQ#?N3T~{FSl)&aVBB{$BL{ zXn1qmU;En}QQw_e(k0{y=Ef`I8?HS3y6oIOsVne2-0g`9R#4w{!aPIm+zytUQt6k0 zrcoaVtR?Gwzfm}XsU+uXXSvbDCFEj|IM8tEF{q_9a!mucXTrGgxndymMBaJ=Ia169 zB=5Fxtra+`vJP;O*oZ(d3^bLgXpJgBSr}Ew4P$bNaZTt5l?&$@n`sojg};u+kNYmJ z7y>PI4UoZqIeKHZ$-EPWY8yfDceIn!*gC7Yq)$dtes9+2chHkdW>4*nTUar%_r*xa zqL)M?&sE*K!p^<5W%8XFDGi1l<}T96MQUdz^q`xXfoJG21n z011hai$wqs;&szVu3G?z1(vxLaPgY4Gae*Y`)&eavu>R&CjPR-^Ohsj)=?-TGSb(8 zZ$tTCABX3=1#&C* z|2n|e0iS$jKP21K0PFXIGL`No4jh150H1P4K~800nLMN_W!rcYu~LpAdv3ooRx;3+ zS7sXt&lp*!?KL2I>D^&QeA6o-+D4OH?WS^o4nL74wnbu7P~#I@#KaE!-D4k#fM@(w z3cFptbIpa|JX@m^R}&vpMwIPGgr4@!`k=`gyEIG{0}C zswD6g3u>^GRMKPQ+}_%q58P>l&5vVTwFn5v+GC!@m^&J`^$sUm{L_?`1SI|eO23X!_RiaWW?J3FSvZf zhq&!RV(3_~0=kEo(0JRAv_1EBUuD{z+p?O^-HUUM?7EtICV$D;a9^(D*~+>C$EMU> z2A&_Z#jgul6RBqkoyVB33)oMoX9}DiQDafAxVke%zN5vE{GC^;ULkh%AVj$UuEe^? zvn?Rz1mErpuVmRUK~}u%5=(6uh{LK4m+(c!JoUwVF3W$Xv1vU?}9KK(n`W45E9 z^)}sP|BzyGME|n)^Yd|K55l|(+YSd@@4+o`%lj~W;z+n(tDpJC>8iNW^Db4ddv@AZ zB|Wm06DQL*%5h;8Y4U)CPS$pE?10d=Ed6T0G0D`rL$ z&72#30`pupIQKnD-OKG~#=7~hIbrKkf{I7+Q|>49Ik}ghLN`eW_XlL@H9AvdeKT}1&kIZCXbH8@#DFSLSGxwm=5jvNuj@ds`kL*>Yl|*M^*@< z>WmNPTG0y9n4F%^#$vl88=tCf{rOmWJmIN+6)d40V%HZRDDC%tI@$hE0Vn2G!xECK zxV_2E4*kp{K$*C}Z*8CZX%ZT_toHo2_It$2*?X?Xz7$Te)ba@qyeaOx(MKT7D+lUN zIveI?7bT|oVbplWTL-&NE;cz#O?q)z&KA+gPnc>g_dQ3>%6wn2I+cfSr&%o$(6Fhg zP@Fv@XJrg%AXN0s;X%2#B@gvtju$l5f^dR~43bmV5sQHA*=Q~R9q(gL1n9B-pycOe z@{&_LBR}RlySf5(xsq#{GspY_2lgY52CQd6i0zIeUX&Q@Rt29t zlRE5JUu%>MK-r45aHksK%H54>qIML>W@em0q4On#ae*9YdA}K!%VVRs$e@}@GK?Uj zDFwOyjbdzkIe+bo;cKo<=Gfe*9@8SK3<&<496KKFRws5$43Lsu?(TEJfI04(NxQ75 z=%60nu^+X)hg_HRG1?9C{topcd}F@PcI-NS`DSAC4%4$S^xZ0h_pyZ9)~C*29h{?QQwH}JBPkr5Nx9+-pKN6I3`AJOI1-`W}frN3@BO;rcpK&OWA{< z+$?dG!8+0BSKVRy-t#nUekOmGodb8BV+Tx>eWhYnALF&c}=&jvoP zIYq13>KGh?#1|5a;0rli^~zCk9Eks31i79r*dI(iXA`YG|A7SDvh#?afWiYqt!@Vg37Fx zQu@d3&8zKm?8>cC&!|e`g}FjM(j(6yk};a`o?NQtBaQD;Owa^7->+E>jP9{eed--p8^Y$GLDiShD>p zh=b}>q5|%tqb{LSk1T2zcRUhcUHUoR{A!l?5saKh%tZ=1Bfx5+B>-TM2Go1_K;Ogm=^qfAJC&IVVd!g z)B?2{l#qtiV>^2-p?wYk(B`F&FQA{%ePP)&Vu4NwXFjvrCeO8gE-0o9(kMlfIhhE< zDUHD(Xws%c5V)ux$n>^J{VOQr&R!#S|Ij0m5ml1;NRW0%VKk~S8fr9>wHS^zl9@C# zOi+XpW6-s_2`r?63ajLhL};TG?~JCD#?u<3U^FVS=nY~q>M9l0t-zX18sR{!QZ%Z( zdml|h6KFVw3S*#>HHtAmHE7E;?Irl9Q`6Ni=q9eMxQTvT($e5gyU#M(@nFYABQR4M z-!yI7YIhdao~3T=urcaU7 z39+3D!!87>{O_MGuxWscOK?Vy({Th9_Orn4v&Q(;Vi&e}n~yzCE5gh!+QAm$N{5W? zC&veT2oqxbo^;PYl0}nKAyKWOeDHC8#HXSNsaQENfHCZ#4pAfh%sLQ^rJ zY>@O|W1su`?FTuzK|hbWI52l8oD)5zRzvuZ-q5Z8=y2I83)m{xOD0Z~7BgY1$C0mA zQ$3+y+M(z2dQ;^IKZf2nhO9pFam`IMal)C{EhfxgPL7{@J_sUTambG@8!7tGjZ`T&crMzIaG$*@&Pc}q)sjHN8ifHvWsFxD^ij8>g{V^^1B6ny zGUTx~qiH2(T7!msGosSaKsff;+?sb9BMryG^b=}Ou-1@!-2udS;c$S;*j9KHn%5A?Ox@AgV=a%PsFTKiw1cFhgi!Aq16wurMGlz|Ik*)Gim=$h0gDCGGH^K z)56Cbq+Jg}KjO{yU_*Pq#q^taKYwd?!+ziVu z7A~rD32Le|(reE~JQ`(2L(PB1UJ~w}P(+!k3O-SBof`5@RlOx>RH{T^gqR^9rV%hg z)o$vf0cQc$O8AlwO;+?^{4ry+7-tJw{k?PN#~IN~U3oH7F=hljyd5m?rjrnza~xrtPBHREyGchJ&7C*nP}m=Fj1 zL%pPOi1F2)4GY30Eum>8E$kKtyVSp_d%c&Mnf>7&cA2z;u3C8)Bpy%_25A<|Ub6d6 z%2fpsrupwG6?+r7-={%M;m~NBu`(Nt=c4LqMqk5lN)GCd68%+xW{x>W&yvGrI2P?3 z0>A=7EH2&%r2|@XNcEZnt&?|g;GvHiDz<&P`Uzs{z8 zpS0pF=(oNT5xZjtZEqOtNtu2>c5k`f z-6j9SrEW5hxNBt6s9>~FCr>FcTiWL@9mVz~7|klNMFT~KAoU?NP9yN=`=JpUWSfY6 zS&^{H0o|=Z7AgFDHKlC;s#6hh_ebQjVcQm!5gZ(`>#v`{Xj?vAQ798do|S_e+48-5%^l!v%X*Kzikcpz~9jRQhkFR-*zEuN@xr z+3J>Q#UpG5_gbUdM#SFP_;DIbxTxL9{l1tq_n;{BW1yg{s{WHZWgG3 zW^;2t#t;N^gx5;LPCKGPVT=L|VSw%kcss06*6%TRW@9u2Fm7;AEwxy*5WPY_I_N&? z5eH`vqFNNl7Qh6{wLRsIy*kNMC{dl~zG*Z@Xx;D-NAsye_kdx}V{qWgp_!wmceoD) zbc;#sD-P}zfV;4EtCmy#zTa-BVigw}F1c<0VzmhFKNS@fw#VMqo;PW9Uhok=os6#z(PnHfaf%xsm*FlZcG%CNd%l+c zOvJisHRbwB z-t@nx_FTQV{`BHn%$O3^lBfA$dLgG#&a;&_fde9yUk zofRj^0&!>Olb)^LLBTi1@e>{e~g?l5rcx@TLgYB@i@nuv!u7aodsGRPucEq1JJ9X#-{y=(|oGHy0Y! ztVVqevpDTK{tz(g+I1e?jA77l^KSxeRUaG6gPhZX46yC$JNI{b& z`h#HaI++&LiNTBs_O{WC&}~L9I9N(M=BWrb_s>Qf*tUqXOJ-JkT&ZXL&j9m68wT*k zTVlKIjJ`T26gLR_=)OO{^^dj+dkbhLGib{jSsz_yPxSwNdZ2`{s@glxso_qA?Y|#S zoZEGJMdqjZCpG%JESH}k{`2w7@ii|)6|AkDCl;BU8>*c1>^6xXr1SH8?IKPF4Oh10 z^)Y$d5PL4NglmyzXGo7euv#{&uRffu_!#x~_WMN-JzFDs(l^MBW_QmVp>wt>7tfwq zwECp$-njwn?mnI1TF_&k4-3Q+U9-NjWP1`n; zH4S$tTK>Vg36HXP?2KD_ckw%@{=E}kDR@&}`*caIYZ2PfDI*s{4LD|J`gBWT1cS5h zXSx2=xl!A=K6Z(P?FSn5<8e7n3PZ*m%>UGHa3W_-$RFhy<5h6WT!G}*TGYM_nWX)R)=o5j1Hq&yFFTnC!RM_Y2ImIWe|xq)6vdu%jNv zKPa*-YrTMs>`NFOT1Ompw)dWsl?&SL&^r{t{}Ha2t@zw!Vv;xF7oZ6KjA52Xkb+J$ zNAQqWnpgKs<3F&fquyBirl(a{7s8PEhktFs#yu+9@Z`;zDDEq-siMe_2~$=#LZ`B6 zhpD(eTB$cLmvYi09$_KZ)cRA#Grt5dvN!Sj$a(kD`sg{D5`Q{06YEcl53BV7QmA$J z+=4dI`d!Bpto`s{CAW{Vi@DC9lEs*nyX;s1b4aPUInDRnEW%87)uG!7x)}b8YNn$F~52 zi97&VVUj&X-!}F?tE`@*uTc9hPEJy9FobL3Qo0|l{ffpv^3BY4edPGxr7N-PAn*P= z6_o-8vXt|qN308aXZFmoDijw6%yWWA5j4pwaSrLoc=#!cJQfc@D;Ml8{Ia*bq>wWG zumnzu_fAKct^SqhZy6uJ%?7sBm)rwZyOiE@6*RU+S?(Sikz3?-({jiujH87fnp&gO z1u6Y$DuUA}#>rVS1|kg+fPaOpua+IR6CyV>2dz!G2y-fS)D~p7pRpkN3|QIHiUS7k z85d*xE{%V)tkrdE`f)Wzrt`+#+?}?tbV@tNr}?y|C(Rj2H_l1-p|0D(0b+teM426e z-${0BvyK-CWS(2!&1?~Vxii}nWBwHR+A5QXD=zqAyl~(R;rf4SUql%KT*%2|PeV9FLW ze@oUD1ae}E4mZLg>5fR=f(oa4>hr8!`UFSF$K6SAeZj6$;0D+9fg@a z+~Nll9k~(BiMOY$f`2_~pH~?x0(66&pe|3z|ICB$ch|2MpFFa`+)IZz6F^TMKhl?O z_9JSpu$v>N9Q3dYtg$m5a6bBNv^d9$)opkrv!}6#1$SjF%i7K=vz$)N-c`xP6^8ZT zibHt0gn(7m)+H7%-H`fXUp%TJx>OQ{a=XfcgIR`1T4t_h~=Dtj9cZY9WU!x)+!=A417|;J+M*A>E&YIN48TI}qxebE*8> zVUJu`lvmhN1;hlx0X(}V&#rG&(>23-t_P$>Qvp&+!So#;mlVfsscP4u;#}`8A!?6O zO&SLD`R%pXnj~4-G(UG$RE(2B_#{;;y709njNZpM!m5!Kb2T3c!?J;b0>_fPDIZ?x zo9QhpCwvTi8=0d9ul(*Lnp7t+)5R8b@}X@G3BEfv7A>s{Sun#R0-0@nNkJ_xSW~m; zwDu%>IO4fY*rRN%O#$-8$)bS2N}6Gd>)Q2X>teDmOyIg{hm}zQ*jmKe-zs#;aL>h3 zN28=LNab#fP6xGK48dr;whlu;LYclJN@U<8;9Im6!jbF9Jc)T#Tv#aLuwUm-pD z#A9z+cxdr~%*Vfn-wJChI?|kW^1NxqD}xTi_IQ5TSovSzwXe|*waGqo&+Aym{xBIBG^lNi>g^7=53e=~NO1WaYcKQikH6#8tWdf!CU3Uw(-+D}K>%$H!$}k+OTy4-Ie|T49WOWS$t$ z-@_*fBW6_ZH?O>EJG!?uc>n0q!myd>*Hb@_JPiDJutVL#OWrhH)Mk8``Dsx_1AFC* zk=h-rW-P2D&96^%TkpAex822a)y&Xu&%;ZsJ}BdEe_na?4u-XlaJ>gz;u@FmHWSp0Y&C}IHKW){zf)Z z$;jF#SW+B@tQgjxIF76opdeR~o9i&+sc?Zt|Hn6Yz6LR7st;uWQDOQ=TNpwOd?!o) zi2@$2gm2Wq>r~-4AH&bq!`I{*B??^Lm+2o8S=`D-ESov7(QLVF*y1%8pIMsRemaF2wX z+~UTV81lD!3q`%bx%S4D{0%XxJV?=#W=#2Oy z$XJ+^$MZAR3X$C+`oiR@oiI~D>=HvqOgJ0!Ej2mw%^_)mmTz-4hR}9+cFO%f*3$V@ zkG-z3q}n`-(U`m$li2mKwDef@bcs$w{iMM?u#I^NG5$|UT}Gr~8j!rJNm?=L^|bZH z+zm0Zos@wLSDslPhZUBFs>ZM{d>7cxxGH7(ixPHUb3rO+><)Gy2|mQfg5A5mBfhOc z7=P1)Vf2}25XmAv5Ccp&>m{;)qjQMdVZEa1p!7NT&SCu&mVVwae1|CA#@Q)Nqo0$C zkORmqBB`B>T_Py(|7V>J1{HtV&c5Bj?rTmp$4$);n(DFLx1+4^tLl`gmK?44T9E;<}0Ql|CYZuLq-I;9Tr$-lyS%Q>D#p2RiWPVaTGUUaeD-c-G0&gN8>enRS^cn)&25+2Rb&+FTiGOWK%k- z`hj&dfCEa;?0;BVVG~nP7UCEmHC@N4MC4XZ`rylEe#ciThDIJrQ9Z$cAI*F5yBP2M(T* zoO2l8?Kh1XjT1;Y?3`h(o)B>CZ9&RY^-=(M8VgyD0nz|O3J-`<=q1eQeSb}E45I8- zM(z?BMXc4|*aFW?MI;Fjh5g6hjQGE)-Tjoiq_s1cK?**oV1E)=nX9ULrkj^7FoGY;Dt}Q7=YZeWfQ{w_=|Lo{|Xrdp$zP0k%?+x@_27g?-^G5*8Zw-iZ@_*rlG>O_)0l~&iV z%*8xYD%?7`@7%XrTUFM7tup%~`nwzG*e6CER|JP8B0b#@%X3iqtL&hC2anBl#6Q~Q zuwZ`8XNgein9k7Ohyey(6VpVjU2h_`#&@dc3kfBuvCxxnI3mwm~rgtJGmfrq1 zbobbYHv0fzYZwBbhLS7vE)F6_rVzUXb$PUi9dr6|#qeEW`dbCAr;}`LgD#%Iu`_n} zl;sf<$_`FVl5dIyf4QT+i|Ko3R{8BHmI>lQs!Z3`RtpdC%O75u9&MU(Df_uyR60)6 zKEClO^~%KcJx2p>E$24d-rlny3r#*(f5c|>c0=l?;#<}(OVz_UYjtovo0HyOjsH&2 zTAdr;P*PJ@hN`G;>00ED{1YbeK_Lr{RCLYS8Fp+-py!4a^ruKQ`F=^MJ#z4?}NO z;lKM|a;;iz_b+bo*=n=Wki_>f7U@2QqxciMZ-qyOTq;|3#9oQIadsbQ#e#)*GcChB zRD*wI92R@ubP-I1BNL?ZqgG=+-#c5%_1!Y&ZsvS^o1b7dH}Ah@c*P8_uqxl z-!-haCk(NXslOY55ANQwJ;1IkZEV-Ws`?Bu6 zp!=Xh+OSmtx8-np(aG&w{6!Ym!FWM+zKftqCi~nb#pEk_A@nz$UwB@!z6UR>68y>6L ze0kymow?uTjO!gtWoz&|&`S73|2V){-tQM~*!Oa&J1h!M$*a!sU3zE&tNmmKV<UVdApEW%Zh#Z}S`g#K$My>D4lt*Vc|BwXxP{t_-(161SOpV>YO)aFv!Cns?dq z{_^=VzCUqYTwHMAywBmB_xtsFK88j$FDE>xpZJ+`F#h1$AJI?!A$zl}z&5d*jiPTt z;=DCV#I^vpk4FWCydHG2N15{VqZ?m79%9J^$bU?esYp_zY~$Mo{+@W#S{(&d7icms ze}q_8BgXWpnHGTw%@H4sXYzsU!JX-b=?KW5)gz_%14}ebgAz#0dg|HEaI;Ejxfd;; zM@?rE5gBw-;UX<+3%?B6=8xmhLYq$PpVp0jU5_`PlKm6aKO_|4T>j;?8`b zM2NHO`&pQ1pUg0FVJA{p&r~yHcffD&#sgK`dcY06qxR+>dy=m|tvV|n9$K{VAHf!S zoijz_l>R<-Q{84b7?wI*u;jc2r#kVho8b}FxR|h}tYVG&MMT558E+YNsMP^N> zzDLC6`{^p!-V2#}f7Af^>~id@XmLbN<&pNJFkuh*?_xP(A1fk1=?5zk`IK%;=in^j z+2YG_^L54N-@v_NHDfgfHPE>wG$qswdNaL9bhM?xKmvA51 z;ZFXwBm>$gM}>{*I2f8miXyGkeyxr0g6HK+|3eVl6Q-HtR>>SQ6;L+Q2BQE`RWXiw z=8i5xDw6Fv1q!#X7)xlMZz?yiB_9Gvz5=)J*$Ar7)!qMJk!bMGf0YAYZuxgby=V)6 z+p}enc4nj}U*4BCVzMVB#L@R6qf#`4*)dXspriM-xDt@K9 zi9^DV{?u?alr{V2F;|IrmZN?bnWLh?+inEYwETkx%ed#KK(wfUc2J%3VdQjq`_dlA z4q<2ir9JI?O;+{5q06j6@V-}m_4W6g&HCx_M%z`-zE|X%w2fZ9FE8b;GpjAT%s;1h z<;`-0VOyX1g46WqVZc@u3maoNeK|gHwkqXMPR!9XKi93hua2GV#mzAb%3|Hrc0S@kp*`c zW=yeEeB^xXp}0X9vhNo!Pl9Yw9qwq>Gi&BF0i=VJzw^EUUJK{BBzK6_`842jFE zj_EKr47aDo>+T?_{*!6=ra}JX#1j7(y_XEP?W&g{Prn#S|MZr0HVR$s8Gr0s_r2h6l6Xn4^CC!0+bH=&$u?>Nm-mW3bjtYJlZYmj*!MagL>x=< z-*0W#UQf=DJMMl<>%6Ed_4a<>x>EIlGUm{~TW$LfXDr0`Nlc@cs}_&F%Bf6eq41mT zb6WMc{a)ZVtX2SaB3OAt4aLIretu?kaGJ?j&9QA|&kyCIE?V%c*I{eb`|ZE3aq@1s z_Vk?_c(rq=aq_8b_hd(@X!nx?AbiT;#k^Pg!Lilfe_y(}xdl8Xs~TnSmjsjRr7u5n zyqGuO?N>bB6VZKM!C9HLn4KWt?glfPkaoO9Cf0?V2@wPRUV1{wFwFTIrP1(a9(l+v zx{j_DKJnA;i==9?_4rPRQ9gNFuQrGGU6?XKdffVuF`7Gw*XpcP{Ax(Cylc;gRsEJt z1P4>E@2@2pdIhOcFAH1|U(F@Z`F)VfS+W7OcFUp4?d)Zx>-LBsjbHE^--*f*66YQD zu1d0Zo)tVk?o6^#au2Of(jUh?Eey>-=B#AbjxwP}gw|)VFHK}FD(>0e=ec7&IVq96 zKPi3acAVQ>ts>oBV_4c_W3Ni|^`aSvC*6b_a-0*cd!ix3PGSm3?;9+AsTp;yLv*%RwFq`P zGSniAuZ-S3XF~h=p`)++w&qFafJ;BKSkn#VQ_mOeZ#I>&JreYP22)&XQ)qya%%1-) z<;DFTo6V8kD5UH-)c!}4It%(H9U5CJU4Prx!YaB#g%~eAZRTk3J|D<>4in#kAM|}(*5olL>dm8tkAf@xxyYDi+Jf`QbuO`gKrh-(` z$1h>B7b1Jt8a$KJo)}!`&$CV!uUDJPZo9TxY;E~X_~o6#qlFLZgFy*ujGcAU%rVIz zwAQoJdy}H+NGJ_+zq!V5RJ6zYql(r^{_~DXqSgkX`ZytUvH%qX^gkDZJyQ(9mat3waBzKM%_E7$ZLdtOFL_iB@#WiF~|Kt$ElQ zIom7z@P=n`=$Lw8_06uEO55a{xa~QikP-~rxBRB`J^WDQ+sY0XEn9ALP^{r-?RQ79 zGU%J5hr!irRwf$$QNEYy0Yx>XdMy??=TGxU@P9IYC0vPlwpc1P?~WW(zf$XTb*NSH zk~6}gTx1d##w(mn;ub?IzC9RK(L36WAXqaCd+llX z8vGu*jgodf6X`Tyuj{CnQV2#LX_1O~dd+6GL_ov%7M%Z%q0>6a|He9c)Bi5o_bNb!$DMpqM#STyail=O>?a|2*J*f+(ik_!lQMh6^jql-u`Nb) z1T5!8L&K8Lv?8yCxBPgWSueu9)$8p!g|g89o=EY|sK)%_(;#d+9^ofVw67PVaz`&m zJY}uRmx~vxE@OuIvc6yZMS51g;V0z(v9St{6U8L zkDunf@K&9i$79aN@M3~fM5Oj{T6%K+2(ojeFYo%s{k;X*1tk6I@qE{evUJ0yw2dsn zms{#ZRx`SIM|9sQJmV#_)>N>lLsvfx!Suq(0_GB^U+?Bf$}YH932^n<8h?z9lZ zUwNy4P*xP+)&moAY7U@T{aH6M0g@oko3M z)cd{(gxt|^>41+hMnM*32bD*Xhz^?VcA1N^VF;Os!vKa0F4u`j_Rh#=y_V3wnp^p% zJxIwkC!4$q9TF3z>}P{YIT;xTISn?-1(6Cb{mnCxu#i=I?S8$$U)e7EIqvu#34t7n z&4fD(cKUfw>rX5Cqp}Oj8o|>eDK*7=KU)ustS<5*zmK*SmKM*-TF&|n$jz!7b{+lv zR&uN_f3CPQ-K>+>@YV=hqaPrp-#XdO&A)wT^D6vBF9o1L0cPl zZsdWeVrpb*ap^pH|Il3UpytCaX=}VHdm6n$5Kp^v{4U37i^DIYoLg0=beF%sa-*Eq zt|kjBJyQX4XN-Mrg#O6}z3$fxlYX2R+X5s20E$0Be8PbL06N^*20$dw3?Pg92p5A& z%1VeTL1nZArH}C|S_-KcODn1%wY0R&jEoG?+NK^VD6F)O{SkG05fxuSg8(suD1>^N zy!mAbhiFNQa}w6)j#{79bc;awrl35Njye;>11M5{*;?U+s*x2^CvQvJRmkX<$f(~{ z)##D8>5#{E9|>wQ32jq|zb~8Gr&8Fgl2xI8<*xSCLhVZ={j2H5qy!66lIN8?=j%7E z3h!bP>%6Y@oQxfINLlbm+Bkh-(?0ACI(AY2%#=phsPx%6iO{#Q!Jk#mY)W|SARWI* zIJ0D|p2%9Tk67%A>+MKtvm}r!GRUuD(%+8CeAUumxblLh+J>X(H+zX4FR{I# zqdVck|0W`Luc*9@SDDY$>90|v6D=Rbn05N;-a2WK9j+M@rh>VM)H-+USe&O#R*-## zr%e~ys{6Q3hq_{w{E3?i_H9SZ9xJGi$*Mk=(Oi=_{#Fe0Sqbym0JCL=esAyb{cLT)*{^P`^#RzkP?c(p=2$zPH-evs(S=Yu@l);^^1QOS>r>>-lTD zwHy2G&%TY!aGnl*e)Ezuv-*8_@7wdegN>boAHRNm{kFI9dGp==%F};eKHqq~w6ydO zlQ}jvHvD?B>D%if&Wk&H!<}CrJ@|6JV&``07Abq{V&2TfJN-90dpcTL8f)wB*4!;F zFTYh(M5X5E+^is%S0oo##ub$X6_5jSvSRY`u4ZJA2&q?+k}l(u;$p7^#YRV*KOcg_ zoelF!x@>zT!#*e%?U3qi7jzkOGRz?$;FPbgmj~9>3FBnrW`?%1;_Pw~Y-PDX@qho{ zf#R<$E>K)Zi~)0j;tT(9f#QSMw-=sI73;>noZ|w;Q~5^|Z(UUESgov#yY@ZxxYar& z{B+iZ*D`$4iGsJ`6^?Ddi z#YSL{$;&U!8og`G_{Zw62GjGx-}WC%rftiw@{I)2SLcttOHDYNy2QA@VES8w7Ge$5 zpa}yvRj!C$m-wFOmi-oAB4l|$=Pk4n`Q9mHrY33p&T)!eCv5qbz3K-14>=Z=Y|=I% zX!haK*qW858kGPzAbiWu=QHSAF!~#tk#BWinL)U?q{4B(8GGW}+_A?aB>*54ibMl= zws?gon-aff%`=Oe&erm&twvII2JMiQmtdu{R==2-2)_}<4L7454fg%J1T9n}YKj#y zt3CBRWcJwMZ%bu2R6(uQEah!#=e&jR_iu%{XSHY^@sXl4=gs~amn@mX^82Dr8TL;` z#!nx-bTizcn`zPb8#BUDd(Vr7j(xTqy8-O(6V2Bi9UN-~o-5!6zVc(r3oSSd?xpKw z>!L7mYNNB>0&u;AVDzjZOQNpZy|S@mlp7LP{*bjNcx-O4uCVOi(H5l>$Si>lt7R2- zf$Rvw`>E+pUuS_i>b{tVxnT=8Z|&GaF;DFe`w5PgJ@}GZ;6Z)ey!n9&Ly#flYJnZ) ziFTnr|Hss~5$*nA>Y>3j=zm!BW6@dNt!C}ZsBS2)$FYZZc9B;9X6tkS(`J6FAJMpP z^Yn0bd4I0=!zYW>dX zUVYK7dZ*i<2d^h!*uzrF@9*}V-O=uD{ryX~XK=6Iplc9Vpxtwa=%^bht;dy;tOOGZ1YLlN~OF4_-TYa!Zg^ii13);}vSov;C+JfjKb zXm>MAt@r1r(hlJYG zKRz$iCy(m3wAc=Ar6MI?JLW4ad>a&@nIN%x=~KNfeI{|(tO=2a($tnNFq?iyfDoEH^GuR#Wy$_Gy)O&zj9#CGI7E!#HV2w!5gh6iIr{X8aDQ z8ChCa%!H)xyI${5rAii4}FWmI+gW#~RE}W8Z@5rp3LUcR0a7IzMwT~CMPIzWA*j9GQFGFSx=V|swM`$0- zYqweiCfI(Z?LixDHj5}E1#uzfZ|B-uJz7FI9(!LdvIb&GtEq+(><(pSXz$IYZHDm453hdGhCGHD3;s0D zkbT}lxVAGUki@4*R@dAZ+`E|>D~Uew%F>x+`>>69O{01d>-p(qxnRt6hF%rR{`f|4 zXYj2It$j(ig_Rni%QQRr@ARz2$I`-jXEWvZX%H(8ak4#G7avrV7qs`iyH7)lo;Kif z1}pSrQf)8B!f9>|fgwZ<@aYh0(0UE|x7uj$6rv6MPj4-^q-2ljKBKjnpv-wbcSp#v zI3K(EkKYw_9FyN0ppbv@2wl20cI4S_@Uijbl=JhSg7S_9r|9$xM7OCQnFp|pr>`hP znT^SOj$*o6crN1++ET$a9=?@kotv#uI){4%$cd#9p`>!VtWbIQslIZF)`ou-PPOOy zE%gYuurpfy-M{&LRg~;2=bOJS;#=_{MEX(cgN|Qix1(e-Vmd1%_&!ABsr3Ve+vs*q z+c?OB$&vbG1X$taEZFf#-_`+TO!gTaY>q6giNM;WFQ8f1#)5^mZe&z`U|dL{4<*M- zAK;!;b2`ctY5RQ1vI37Idrw{c=kqP@m%~4^#19G4ObryCV;xQD(SsP_(uI2roOexqkkl8l*hJzXJiehELJx z^-m%|>R!OAe*~*v4(X&o%rfEDSNuC7AlGOxa|kI73GX-!`IunUisn9J)r?3uE(t$# z?D!bXrw=JmDhBUm8<%rSN9rtApQm$Hrg7=Q56kq3i&vPCL^LD;MZu#XdnScZ!_A^LA4JR|9Z3k_G|(U7u#Q{qvO+b1FFp9r6gt>iC5{+_GG3T!7pjI-eOCj*CZ0$qH*m5Vax_Y=!P z1!j6-Tne-G9&vfyOZ`=_7Zl!%hm0ZIx;WsNmuY8NnZeNO>3B#q8nVlVTwq|65T`ZC z;0v!H-}s=3Y{)efB$*9KU_w@ZU=snjH&dBl$Lj%RkPF`_F?h%&dNOy7Kb#5vF%I7E zJzG%j-_Zb5$huOP9i4=RoHMa%Wh5Q#%N2|C@54hnv5;0=QR8Iv6?}2m`S`9W$W>Z& zD&x?nhUGfOfj86Ok5B?*RCp7$#O+mLX2l`qF0KR}vk7Pqq zvTuZ=AtxW*IKzKEP9rNi1tO4D_V*Mx2nspNx}`P^p*2RwndKx;6;)F_Xpy8uLVU|d z;-dy)O(cXw%auybO+`UAOB2jr1@)ZD&?tl1|Hyk%4{surnA}$QJ?2=z6F!1J-iZ`g zd}-lILHDm#rr_ZL-LQ~*+@S85WCA=5k(f%j2|Z4^$hn1ooq3&ei@>>c{g4elkEcWc zE+xU`n@?F6sen{J@Ok=8DC6dv9|hEMa5|$}py^ch zldKB|lnaq}T5z;N|Du{JB+C~tmD{%qF_4|?_{#|R6$1Pc6C%_Xee*RX6#!lAD{7{4 zjcQosL`W~7^2AU05EVwE!5(PB7`QXsmd@XuGLuw+&JHaGz%pzxb!ZdDpjkakwo-Dg zXvacYOyFZo$UGf(9eb0224CmCp(gY#KXgkIx+V>cBM6far+3+giFD!BpO6dylt8;D zKGSgKGvsZP@D_Jd*;&vi@OAomzv;BMo7MZ6D$W%6@B+Q+DuxTDkUDxH*MF8v=R~Wj zLu4f3`9I_Gf0f@di%CMll~N$r*ahl8DFi}va}OjH>8o-dVtotNNQF&O;HgwtCkOtR z4j;|L>T@klQDT^XCey22^_ituH)SCRIZr_$`Ci?h7NcfN> zL~RnPBOVEjiN4d$gbm~2o#?|D!#D8GA0dxvE!L z0nTE)?xz%^)85S-@GupYgc3-_#Wv#v+ACn!E2`1~57%EeY?(tdu+>ByID;u1M*#n( z3z0ZN6kJC(5}JvJa+=#nw0j9p8@5yKUyTOG(W}DoRoAqk7o6#tzaY^Z@LFH*S`Lg} z21}*EKibvY{9Im^Qk3k}o(_m^ycI1GMZAK9;}ON}$c(xuZgm2*{S8;$>FA`owK5>B z=$2*x^fIEd76mg4Y^f!54lrA$umThG&e9s|HiCe?%kg0}yoVmz zD`4$tf%}IXcpnz}hylR`R9{3wUkCJN5TF^H9yM2J7!vx6dW(Yx6A;1_M%&soXbz(- zli9r<2#rIug>xS8GkU}D5C672ATS|kT54+E)?ZCrgW*TByjfEQp zcLLfAS;T6}?F$ElE9{WV3`nIz4GC~Qo{;c}(a}nW_0em4z@&bzkWGUdX~P#kd23CqlU9_&}>FUIvXBj`S@%e^hf1nLjGh99-2vo<^mf24x}9t(cshr2#`L! zJJS%n)DYX;%`u0@SU?BxbpxtU#F^f>jRJ8O$j2v59mx9xLi=T0p<1JVQ(l6SW;ECm zTCNVc?{d8KNB=OOGK~{5Kp*oTgxBC<{lCYCzl;rW1{g;MGec6RaBdSw_*NYZ(*tSZ zgiw`94#xyC00NH?&~YlPfeOpO!PMZBnOG1SoZ8`;Iu+I8)!#1{4;yq}hEnFha)gJt1hb!b=}4wj9B z^~l18Qw8kq)Qu(!{KHA?qNZxQ!qIR6^HcR`)8na3*Z>34o(h}54?V)e#<0*@Ix`FP z_(I_1#lU%75NsoMXdDUKz5~s{|C3FJ=AizG)cNOPr}!uZk;A{ZT4k0^JO-5ejEXN`wkkZ`#uNx{_O+k zKKy0mgJBpRN|J*T34k!bhjS;UuDMU0bsbJ=or=(bkpUykf>2=rXt=<`yxE59H28HY zJPq)$BK66&?Si;y=&r?8%T4$rD&#vWv=-H$!FhHc-+T`NYrw-w??CGjut7E#OI)d; z4-5^g4F8tlFA=4Uvbv`~t5*y+2a`y@CHHhYro8LEl!rjIDwaanLX}`0t-79t8Boua}Xj!=~?E zt>;f=Q(vIc77rV+P)Zu?)?8bKz(ZL2!s+HGyA>lxt)Rzy*~4=1OEjxtI-IaW$oQY9 z0!u@2IeJ(f4U+$Mvu6h0X9?>QSbYRr9oahbI{`k;?N(#HMQt_r1AIGZaQmIweyl(P zV6A}(r(hSem~SF)yu8Q#I2XOz1uKW_VCbu*dszXW!!!fnVX)S|oEjdg$M(?ZHF!UbtQ$7QliP+9VYzHB>3(?!wOYj>^ zXaVzE0rLGhh5Z|}4_WN_s4D2&tdHSn=55W%agP@igF%o015Yqfefs3FJSr;2(YNw4mYdqOhBD}(7*ryR)d96 zP}`dCcLNTg-R}klzsNWz33Oov`uj2%oK>m!W9~5m)_>lG%fD?MdKvld+dbTRJqMbH zhBDtnixAtPbm$H2ejQrC>F$0JZGYtA?|d3GpAF4J?Dt>a&cQ4C>Gis`z|s6Fa!DHKKsp+3)QKdF^%MqW3bA; z14u1l6Fj??qQeI4Iz890t8>|XqsnzFyav!I#UHhwD`OW5Budn7u-ZfavrGrcc&}lK zRo$!YZ+ox1+|sp)Cr1gqHaIhkZ+dgn<+Pp`mp;Cye2OH`}swqSABQ!^Zs!0oH%8tgcqhRDle&uhQUv^ z#42wV)jN2JsRkq_i`0(ixNIxsVd86_WD6-8s?K1~+m(B69*TCwP@C+sJpRg5X_qNj zWhCYrI%F3%TlK?k%Yq_Ho4iS&b<^->>Z((r>D|u`xl)bULr4RCO1`wlxe4?B@#>)8 zmv`QI#wVI4yriESp6301v!z_)+>pJX+)@9R+EDqE3z2sD)cf|QlFvjf!| zCL4yaaeFVhgMM1iznq(;D zQKlvOl4e7hPl3!msdFr&-14&)I@lFAy}Kt z%Ckzvpkf!TMEDp6r6W{~LGGduhT<}HM}1OF!bHzL-%>4+e4!=qaP<5>wG>+$y@iSq z)>bXT3W(T?vl10mq|h*ta4BsbX9tP1wc=zUhxfYSR3Go<&@#If36Mz2*iz;4^%p+{Ie$-Ul~V%>r?3 z&&nv=z-pZY_YSS*R%j0305|pa4UWk=s~k4ji@NC4pd$HoQwzj{F1}03_a;cJ78wAZ zl0Cc|nq1o&cdpKeI64}Xmo`c(zI`(xr2Ttp_9{=W)Y(+$dxbu20({4804Z166(KV9 zWj2YMqD84+bsNPmIvGufU?m}Z#eWs{!fr=eF4)V47u-H0o2~hAFyWumq@22tJI5)~ z|GK3-*YFYD=Cg7RwAMaeay--C2ZQ?#Ja3@4tR$ecMzk^+_ zNO_BDk_&7kz3i3x!=PyCTJgvg-lKZR6TruU&4Jf#93 zJQ5jpfEDrkQ1St@H*%oPPa@mTWs#<;QVl!(O3XSdSg z{S0z#1kfUOWjC+-3Z@+%w4Y5Lm702XcVt>TH%M>+j>G#u9i?X)ke5ZppuCdwCw#H# zL_i4D(O8Rzzm{iCw7Ab+dZcguQ`$nF@9o#ygNPhGvZB~+4mr2M%gN=ri(V0KT*d69 z)VFsNn$e0!logiCv3=X(KMisZ1-Myil{=fM)#mTC9Cgnt z36x{&q>ze-G)ye<#_ep1vft}}bOSJvC4Tm+P#38OCQ7HO+{ntw%L+cF0*bLm$ad3` z3|n!MZk8rlNvO!i!Ppj2N0`$?*yJjN=ZV}7*z`db@mIJgi{E9~k2*HG1oiYl1*^5hi@wyHIQI;pOs&O8b zm=U^Zk)c=_KtZw|HK&;>C4e{p^2<^A1l$Ofj|0(CmLh_>nA*p;m?R0U;7pyqe__Fi z+6!kTjcmW2wgG-5snThgE{U~bG>rxo<4ZYrC!$4rYpJ2XHOss{ek08U`ygtb>pP^@ zB3vpkN{-i{4yEp9((Ysx@fsN~&gdlN!MKvZZgyYmNjPY%T{8X14R;(#b{acrY-uA{ zFiXDWOzFW#{9MgOACt8*cC4x$$=mGP7W1R5o)GzN^Cmq6?o&Q0X>7o!dFaM~DN`Aj zrEr-jG#W0(07$Y%T+Cf-VQKT7st2k3Za5w>e{{0sC=zUNPylyr1*ygN+UpSv;G6sM z8Vxn8ygnq{xkl!X(~hUia)PHAXJI`Rpea2<7E}eq%@T43B^cqH{nUcTqHZ8TJCHXhNs*X>e|HfW4%^ z?G^_&LQSiR*~$q9p8vsQYu+cYa%yj0jwd#QU4dh%sug+gmK}b58ygKu2#8X2_lXpV zj>o8I5wpEh-yHw?=1chCEvOGv$sn`wNSL8W&Vt^GR#$jeDBolL5PRjR#l9tDvys@@ zB%tj4`>Wq$q69R)7|y(StxCPYQ}je+b^qu-S!&n~?-n`wmr+8JguTBY>Q-~;jU-B7 zI6+#GD_@DdK%Hcg7FU8x1`>Z8xo&joFoDV>3ltzjzZ~!Y#(PYxMVC(2rJEht_BIz$ zt|Q-iFpei4+=_=dW0j}VL*>)*%U1K%g@`l zp8;JG$S#dsjSUp;(-noLgl~X6`tF2%AwM-R-0nOaohR~#pup7u9UVm(LqzLy#r6tt_Masj84rBkP89qKHcQO0_pF;bm~AaEKmko z%5rBwu%Do@C>Z>SiG%b#x8t|2jgSKs^BvJ-T1r8NM&?j0S!V;}P9S&F$yzj$2eny; zMGnV;qgf!2a&9&tI40XRqGeQjfAR#sd?*({M>=U)P&}!3qLAS7(Fby!AouC^?E;DUMXjyLi)$`B zec3ng9Us5g>em~do0f}Wl9Tc^8xzKo$3eO*vL>1+$^z;zNNL9Q_J5{^Qh^GMz*rjC zqmiOPCtn{VX(yAkX{0PmOxAPj-$n>cR+|WmbdR^%xzr9!*4KhE+-YF9a*EL%a14u7 z-em0v?>c-G?OgWf3F-~#<`WPtCoiyxeC3kZA`tP)jdsrO@Uy8NTzmpS*1!sDJ=loSeGVXcM?tH(d znS7@Id+V4em6Y||>H3z_Qs|o>rjxhTS9?sIxJ)-9h4~&Z4LQ6qTgS zApP<&23OfZ)@MHn%!P?L!~!$Gcl61D&ghu?N_Sc?$?jMNs5hE?*|2V_2!zExc>C-o z+dseJ63EjJ<=qc*qUmZyI{LShP13BWLuRZVnlu7uaI>R#-X&TMq(Z&L~!-gyD z0?9zTe4q}LVQzm6)a~@U5-|7_s6&Tna(uMPNdRsTEgKYrAN9b2BR9yHaUi!GoUAO{ z8{%9WJR$qHXZg3Yfs5D1t{Jv*sI)}D<%n$0Xa^Qi;Y;$xQpq~mz_>qXU9+C1I-tKd zw`G#D0cwl5_AE4xf8h~ySA`-{F&SDy3CH$?XZM!@7af$b1F6$ax;zK_QztS>8uUdI z`Bx_LKn)f#vV2Cqk;H|I&+Cx1FeDAOmnz5SJlXSd=M?{;G?B36lvsjBvAuq46CHl* zih7@pYaXz&Sa|M>HrRU}s952NkoHb`0)fk-Y7u6ijn7hZ^}PF?IiOsGgAR-5rt6GG zWdHq)`B3QWt(!h^I?rysa|!EyU2FzE#~KaUu-)*X9IXR)eFjBC-MFhh(JV4x&CVh9 zxeDPQHS{?C21%)J@zMhyb-ItbG)W2I%^0U>ZxB@oKrIf>d0%dcHP9fBq&98$TZ~7W z3T&KsDo3^GQzeQtT5GX@EnSq*eR516&^?@i4jrbPeDWyZzMrv|xJkuUz`|X!W^SbF zm3p!x3v}!?S)Rp{%jE7A;_=;QnwAugWS7Hmjc1BxJxVuyLx*0!bjUfc{4|{AQC<8} zq!t{-CPyI^xhE>j-)Hr6t{NId5j0SZK)S9$YFZ~MHZEFhds+r@g=G>KijHPbVi-gX z22q*zDj|p~k^(g_z}3G_8hCCU21yi27b7R z-TKDJ`n(xae}G+92@mflw2UB>CFZOrGWQ z`Fw^VpAB5RM~P{qsKj|Q{c9|m{9m2uU^YEdN_%a4p}W`+;{1+e?eJNFW2% za3od6qI&k(O%tFpmWweQ0#z{~>eRDZOk(T?Q4R^w*dRV|CmkgK&BOzH99F*meW}(s zW@$|NDj%pq@Vq8Y6wx3KmIB3*M1{s-Z5q$dn?NnJnca7bm*@r}HYa zPive4Mk@f7@hj?WALC3(as<+mJ|1PIEY$-dSGm?i5mnJ7Wk2AqduV)S$aOcMiXTwL zlm~UlSm@B$MVE^28?)qs`8|Dk=)%Qf6wTXE1mcqJ@w+WJtsgnTR}~Y z)y@-b8p|fe^vTVgFb(gcDE%(Dz|6XW z&*H9org33$Kvp6P9Q1x&<*nxH@SboSIHZ6Q4xROwo@8{ndeA@1<3oJj6EEoUh%r9K zodT*Ukk)lc4|IWI8$@LWk0O&t`~Zle@o1QFcLPb3O~40*C?iQ~cv6Z7@VY>ZD%ZS1 zla3znXeI;I4tP|!)XB*YsO(TJgprsAk5)DbMF+~Ec#!8w%Ck?cj4clfw~SDRX5Oj& zHuLSD9)aWr$P1^?!Z$(k4_t46GWdU2X-VS$#{CJ1D&?QzFT}QMb+!YR==uQ(aA+q%QNcv0w7|o-W?YRDt zXYJPFroCz1_v}zMIE|T=3dq7^A^2p-R?qsGk2^bHtt=kBBezr=Cnv)j!O_{27&ck8 z8{Dc#(sm@$Z{S6!fOH3-GAlssYzWsgk!vJ!!LtWKfr3s%K?aXVA4CO1L~zrG=>#=D zk_wlO#=pW^lZ-Eulo7-U51<&6qeAylKJTMK`zo3Y)NK5uiVM_0^JvlDa{ubbFPxj) zvdcjIOq_X~J=8X%SpL?u(g z85BkCc$|wD`wqJMc`}qmNj;QKxB|^e(nv@KWL;o^FW?f66`E%K^jGBins>n#Qiieg zvoSO<_q<^Jff$27=y-fij!FsDiGvI(85NSqK#{7#k18P{2j+*hPu<>HkL^0{D=nFpApZ_b0TkU@5s)h;` zFaLD*AxY}Pl(L(py8u%$X_#<^ar6q^En9zJuxl31aHs?6V1PoLsvajuvWAi-A|r{$ z!^P84jI94Y5?2~1ikM){{k`jvlr%&_8X@ZnCM(eol6pXi+xQU%O(h6xl}C<7VZa+< zl-(ZgspRaTJaSoqL1BL2@%hLjk4!nr2Jlk>P-&hXF4qN!kka@m4ge}*i3li<5QZo= z{TIO^96^(0sXxV~fu7d;%3OX7K>8{O{N+L79&BPzlG0_8-NR27?pObJX)MiSblyiT znRK)Iyctx@09=I@w?D#YB*m+cH+DD|%d>sFe^vMzI2?Y^~(F(=aZH;T3?ATf21KC{Cs zyjgh?T4q=_(iQ{}Q}k^F)UIF<*N)jTkt>oIei;5F!oN0bf?vhW}I(z9#zzRYC;U#daF{R z%bDnK!Lv_IPW(Z5u(M>?j^r5$4B^z0=&`PhLg_QvJf0Tck%|*iKhOkwQ3X_jpfF3P zbJqJgBJxIxp<ZsAvy6cHo}@k;gJ^APT8e-oRt245dJ=Ryq)l8BgMceFqt=!jz1uK%BM8 zh&@ab6l^bQ4-F=ZIB0m0MbcmVCKp#7A0gwcToj2>)Fg`PAq=~Z3kom1^zq}(M>g#s zaa^h*pTzk|O5mM~FJ&Uc{RY7f{GFGIGR42Qh6+oap?A)oFmW@OklMlXzrmY7pFnyfp`O zcWD%+2~ZptHHUeDhRWZ%j#FKJt(Tv3Q(0h%y5{4<#oVNq?T1{D!9ek2e(Db5r>ZG$ zN3j^2Kz>i1OMJ1HYe1UHwEz}X+HZ+6p4VboE? zi?tk2G5NCIPlzkFZt*cY=Q!DI7F5hnlr{rz8pVb}Nk7(B1+ECFoN zXkZ%6o{=4ZRq|fpCZ8W5A?KQi;Fa@A2x@kQA{z-|t&oQA0r1MP+!9CRBUx%FUrr$L zZ8{SmoJ;^(V@IJXD58j*4T@8HdT_;oJ2~2rm~KPDNw1Pc^Kl>-jC`1V8Avdj0a4zt zk*L6v4PW!aTsoxVBTs|0sZso1Tw@0xp;lO=>FU!sF42f2U885f{8*$DEE`^}SRMgm z4uiiOnF;g*Kru8&lUwnEVH$^gmNOfmU&TDa#q_UfUl$=}kK1otYz7a)9oWMgS`&wt3O)GN>&cs3h?OYG?cjag$a*fn0{DQD22t zhgGP#(Gp#7q{4nOPz<@uuY@CwdGqqkVHCrBaC2kNW%!mHD6qsg`N&>c<|=DUA($&8 zizW$+V|n;Ol3xl}a4C*zG$?0@XmYCt8LeV>@8j!pMyz(>)UaprPz;(&Knvp=L2{d% zFhg7anHo`vL$x0^jz)KiW+I?-GINLkY+10NeXj1k~E^9UWP0l^zgiWAOuiHssAS8-<#p`%cHfPSLv zNP_)VnfYBTFx9(<-@}$9>W!0Eal>)Dwnxhp>?YOhi69>&QM_XVq>3iyW3%&R+8MI1 zifCphQ9R%s9}_1C_dKi_1!<5fxgUlEx8#RtKlCjwS*8r3aI_r&ky}LXm6<3XPC)sD~eU z$7lw27B})no#cTtW=P%r6Xmn}Jn-3?4@cGj@{`R(L1R4Nh&Ph=2!|kCfFg^L*$`Xi zDTF-=h{W#%d0<9GW^aR(k&0EH@5Jue(jWRI~`K6k%Erl57bX@BBM|%;%iXJo7yFecjh{ePuw~`@5`#Eh381 z&92<@O2gRdpbHiaBlcEW`uy|7!NE?-QyUMdBYf)GJqhu z`$vR%1?yN2wDGOh>gG(bcj5JR6MLsL@)?9p2(a57!RDLfia8pCvfjuOlLvdRd%8QG zu4H7Z#qh=bVGK^rm?Of9-+aRoeIJ5})0!DlU-(RO1~^mz#EFNOt!f8I?T6>@SC-UqWdGF`3;U_f}ga? z0+B$9^Mme=Fz_2v`J;9Vm}^&#Oc<=9oXwB+-Dv0GO+<**ZR}ECuQ7V+Wl*yBI!7&A zfKe_J1sUd3v0_2M^I3BaR@@J0M{6;Xhz-^N=4i{wiT#*8VYA84NOK*NSY;L~CXQy0 zQo$R(#aUvfjI$2O)`@%jId;j3D=K--hzI*QlIg9;%PhX?=S~Nj`bw27y{;inLUY@d zyR!RR%tggMQDnd)XP}VkQi!kh)3%q`MQ+ebqMK!KxZc@;uHURLodIXR6xZlXynD1f z5U4C^-gvQh)K$LE>ahd#*YNNArGKY4fQuOEbJv9{ZpNh6d%+5mT%2_@f3ywA8L5&i z>yZ!uq)vp$0-$_%;wnIkhH*&%p|zT@umiM(v9>579>vR?#08 zaI#rI_r`Dxf55b)O0vweXg`?fj!@!J(H4?5KNz&bX<2fU{bG;(f)hs2V=d^}#6&Ox zs5u?_-s~(yYkquU`Yune?B29$HE|dx8-RNh2yOxroGkMpje4iA=eW7U$cD>je@~&K z{9O{`uU|%oU$Rn=&^%^h_ws)O+elq7xf8MC?YMlh-ZTe+f>5z|7?%qFuNJ1(0Fpak z&{?#ukyo4HwhV-v4&+9{*kN@7j9zmTng${DQI9^=Z)Iuhn`Ei!(#AUcT1ZGb<4d1JB_x z6KRsd8&V69JA;6~5s7q|Xp2D6enjeNT=8acDu+NvLR4W0m?PvOglGiML&#kv*Bk&+ z2nxv{Wdi9ty+Vm&x*Q72hpGU4Dn`YE6mjW0#a0oqAW)3-l-hahGp_;5dnzsCAZ~zS z%FqfEcw;KO=npE)0~DAfyMWFZ^Qox-J_HqmVQi?f_@ek{&Li^hRFF!Kg{`LjB82(g zW6gu&>T8^@^d5?h^ed=v+orbCob8UU_gxJIOrreC=e6(7Z)BgaZgsLwhivk>)-7i* zmpEDRYM)g(k%kf9dx&Iply;`NL>FRmA2D&LCG{dLTW1MLh*c|0Y63RfYaO0NtvV2L zCqT*mp|+Tnr%?uaPv zyWn`K)j*M`@(>F;IbREd`H1v_AEj%zj2|qXkA_*~-dF>~f;b{d1D*xoA|GI>0F;hM z&ku-4aw#ECDWZh$8d%C%JU0L#Dxi26&Z`-}Y@4mWbcJ4HkvK`EAwWm6 zJ2eK#HswL7dvUfX4toiQ!Y%gbHGdfE4hV?~Ft!Gz)*Q34+b=~OpqhfxECl-~v2hn}nn+GU|jU^sNt5pfnGZ!ii_5m8Q}u`AlnLLiZmXL1LY zS^;*&UP~;s7Z)NX1wercR>TQnBgFJvEDy%=P%Mcf#zQ6wA5*;%0E=MF9UO@;wiu?_f?{axoE1nT zg;3ED@!?IZ1Qg;SI2eUOVC-7qR5iuLxhItlE#C9p*vVBHjl;A!ecwI*(DSU{7sFa> zCrgsvU#ecikLlGP>r5H4rb&>e?xu$YEu-vbUgy=Uo1l~uE(?wYXCtkKV5=_K9pz5v z9;0K|0jnWIatN`?f2Z>RZpOrJAAkw{01yXs3?ZWS!TeVNMF8VQz0Jx;}V)HizkzGBnL?RPX9 zx;O830eX}x+VGsLCZR_UCR(;8YHy!ae+Fp0-WFQIwd#LIDsvin0I!9s_};mCI2@5| zLP>NEVcv+`(IYNE?9x%3F&yTOh{E}a)h;H|Ai=PJZ76W5rU<<6*WUpe+PSLOj(YlqVeHZ$4WAFC_C+*q<)uk&= z8TXg;}!Fv8l{ch*s)M>MhEv5+9#ygUi(KEVQsTN_7QkS$^+Cxg!*<{o%Sq-f_ zQoHGBk5zFGOW~9H>+f1m0N-bD`VBbnJZ#shgRkrnUyc%f5Je*c`e{6{c=L4hW#Sqv zU4-IbLr?~t{Hj7g;FgqV+}a_W3<`##SMA}vO5FYH$yKq8|D8st@n{L_3LzV{6S9!5 z1Ri7yVAlZYAQVFf#FmRdIF4-%w&x;qc3@~LD;(=^+xv0Ik4G&QaM;0Q!ZLdL?#atY zpSfR;g@UAy7J_N&X(*QKJtp2_jr)vU)ShWD(-S^#j-Kr%StvwNH;}#Y^Yz8 zQ=E7%2OfqkHk^Sx#$vR%Mw%ZxBs-u~%b!-fvxiPWR)Sw7b~~w>t9x```rs+jcn^X4 zTRapvvT?V0?1UBFf!y*2(_M0^7AB6(SkjC4H_p@l7-HGS?n9h3O*P3%IA z=iz^Tx19g=C=VH+C7s{CcS#&uUa#IoIo7U@_`w**u;xxC+ERo%lX z<61Ux552Y0IL$r#jC)r3(;uZ+$#Eyi;U0V|08Inbev}gPe5R>K@3qrYC0N`%nt&ec zC_t_+Tm)qhLs!^v%Lc3rj3X&z1prT+&`j<^DQ1*H;&aZ3Rs<|94U6Ri%nVd?!qci@ zC=|&F9w9~|_68@!(t(XsWaqT>%Qj*4Q3goGaw-%Y3K^U+wPUx-Q1L6wGi>JE}N{P0>H91%e%aO1}@HHqY1No2xOYQ*#`_YU00eJZuBP(BwNV6uco9z`lCgZGN zDAt~pU#?*v)Jm-rs^^GP*OBO{t$Y-(qN>2^FRR;e=g^1emz~PkdoYJ)Zk!9`F&r@Q zf*Y|=Uu^VnY+so$@OI_izze>0u2t4m`zD(EP9=O?x%}ekmDimKe^*+znnwLAWA4xG zIC=Zf44U(2Wz)->@$ctz?-a%DU?t2BRh=Gbuf3HrH&iZtD6Yo(z}p9p-07(gZYi2Y z_BWMJg}xoy5Ys>G@0%+r`8<7Gn&aqH%KVTX`OuHg&7m?`+3qyQ>@pd{0B41G9tuG? zIKH!$gUQAl>-q_X>l`^489fDK#!Rm(^EEfS3}$w7#oU}@ns_rHL7ic2KFkhtB4++w z{L2mpUkUGu!})MM0KwF5qO>!B$(JrJ)8%U%_p5J^&1O5|WP^!dHb%)5e`X# z^^Shx)n1X(h^;QrNsdp{0nf-x>NV9NrsB;JEgweu)HtNXbuAsUgO{%4&uZ7k)-d;9 zju`UPJ{kY2UcxXr^Edu#66)dhFlksUN+o6KBv_l!>v7?90yWTEC2{CIUL|R$d93E) zQg2{xVq`TZ_u*gx2QT6uB6Q{hhZzw|cNJ9AjPDn4rDJ;5XG_})1X!kc3`2CAKb{9j z=yeJ(l#nt3LrhZuV8z9o5a^@003|T9h>qD*z&4DF33-ELdH;{a=cech*^DgJG88$R zX1)v%Wke_}tY%q0iu}v>3ooDs8OMuhWC8V->fI2hTg{?#m>^~t&E^sc_X7}q*)ETs zHY}B=oGjRzpo0@U$DdV{Ug&eJkD1Or9aTXKm@QbhQr<6Ob9hBu={LP}vZKNZPfzXa zeQ3D;N8u%9!_SFP__XonOUemdVT)J$h7%U){lj0*x7$2ve%Jo+!@3JTO8ZcL?vdew zu-q7P1)cnZe#3S6*hIf~*>nYgAYU>72J2)hY-X@>0iA5o6D=5HB$S$XTq+}fa}Jrs zz7G7rD*zY~y46xlq)p6Xq1BTD0>e5L&GOvX4=hRw4N>;l3_k&%n=TN+z8Pf-d_dfX zg%J}^wd*DxkTtI_(8}+$$zc>;hxxKWO=#APt)@Vgw0J9zF1fhZtu|Tkp1`T4oheez zpgy>8DfZq6ZQZzYlQTNK|;qwD~&N#nbZ}jb={_gc#eBRam>RJ1# zoItm~pqxDP>(XgOz^t^^UzQnLUS)my6*X;)-JNVo<9z*%( zByi4Iz?EtQh^h<7R49;*CtUzb%zUPIx)_m(MHm%c=|!S3qWH>_$O)t#@aE~gQ$WOE zKaS_3RF+IS8x(KN!{$%C|L; zRveE#K5)KrhEPF9~ybnmf4Lt6A9FXTig zQ>H%js4{bIL_OhDU~~HCa@VZ+)j}EaH>(~+rWf8O&Qbn&IIVd#B+t46TX}%E`^YOG z@86ACv&8HkZZoz5p4u0#-J|Otymz(G8Gy@!{P7^Vyav ztpGk$HY@Er1hH1pHzLxA3<<;$Lp($qBu0A3534chPR$qTurh|Yb<}PtVYRUoqlJM} zXLGXD%RndzZGij=t{KNel$wTJpOHQ^Mg3axa-{1^-9f+j#JiDebLXv-Kc^j&I)28! zLiu0Wfh{OFP+$KrfOb z`H-lsY|+GL?Tjyt8Hee1?v-TYCMbLlf^lW_xiN-8hTtvM-JL%}gdeSv#zFaER6>;s z9+-`VNV*<`#1MU^44HVpqzOwl=1329g5*iqWh3fKieclFCJ7tOTWPbBNRUo768`U6 zq`LVQtWN)Cmx_2Svy}(CDRf(IX$>8-=H14p!c}5IQ9~pWLf-lH**)d7)}lGex}Q8Y z`Y8r}SK6)IAN@Jaq-1RMcaTBZxI#wY`{F(31B$*s0<6bp$iBiu>5jh$SvijG-%LB* zqwMk?n8!qSeIJTqndukzn?TB`3Iszc!75tBVoROFTX#C_yn37?@g1f!iQU-o>)@tZ zxFE&`!LbDZUR0aP#yb$E3$}kq6=04Y1DdiYAoclMM9R7CSa%%|qKX!EJRi3N9+g>T zL*xa*MmaVpr6m9$cLZ`2jkKKv45>*(PVDC}4i`4S+rA{eZ1MTd1~jl|CYmK7h{#;l zP+LO?HhavCzu8mDe&r{J?71k^__X`fyJ@f7mYbO4|4ZGbe{|Zjw1!h0+d7x}5$&^? zuG6mf-OLZrihRt^(!`pbUzmv}SjXg& zAoSgVE87X+L~0bqbQ!=6CA?8?bu0Z%fmcalL_-*7^E&RLke~Se+dj_j&4nW~HpMU+-S~=)8DF4p>{$cCZXT@>0 zDymD=#$REZeh7aT21Jm~AIN(2aq|HI9hqaeJ?g4^)(@)0u<=hD>1f!ec0R73^W2$4 z_^L-}=U_}xLhlR|%y^K6=AK{F5I(-Ggn+cqZ59H^AkNlv7+cZ+z0Cm_NOmqlEY^)L z6&*YXaK!~@%UCf-9G4tGV?ZR8Jf{i(Q87VgU>57t6ad`hBS1;e=5s%Wfnsz;9d!}0 z0ujqSfI9*cy#=^jD-I8MKv@~-jXz4+22;{NBcZ7uU&{~kNgHH8Mx@W#s4 zi^?&8N(Ud`&mr{B;M+mWW)dMqWE&6=dO;RL03q;;X#-p^+CXH(WVY4Hc?jl-uSc_& zb9Y+sAO;&CGO*($B5&X%OSD7tEWJ_8MJ=rB6V;VEjJ>Fl5&(1*lmj3?6oUnJJ$;Ke z=YjhGyyv<7&TQ4>DBcZ8VmgnI$cD@j+~7Hk?T5f7kKt7gXwFmd+f<0wsmUNrX+Sk! zU8ThrERIx;4?jZJPBZ*Ou^QFuHA=@z3Dw^#PdliQ+SZmN_&X(OR}DY5xP9ESFJ0VU zWq9U7XI+%iTnozS#>CU(d3g77dVd(9i-Q*i`zz;)VN3uh9aXj$JdZJftN}4^0c0!q zEK>xvh{BC7x5a-vZNUQ>aPZ^<@&CBD7KaGBJT)>8JKO_OQA~hSt(QzWpW?mR{SRwn?jbcc-@YI1<; zaGlB|Un{9z?R%ZtZ+^x!r%T55PvhVba=~5ec8kl7?;jXx{-<6sNKx~lJ#(aKY4}su zCGcg6S$X05G7V3UoTvBJ(f5ri*Nowv4U}j1nFN<#xeXH9nHXdEeke>}z>r)vln7&X z0t2O2K?C;d>3*U3k4MT@a7{%7r26C_1J&5Z9>@l8N`h_90t}4}S{vaMfT5K!f)WhS z8Jd|1MlSK7k^parf^1auW9rShSjVx|J}#&(*1gQ$z3z<`E<_+YIl-Z_C&jHQ!B@-! zA8Ae3sTt^nMvAp!|UgW4$!l&}!4;QwzA3+ZCLjx*1 zx>;9!K1L3@3d8BtV&&mRx`LB(XSmEY2jyHEVOE?_`AIpRx4K%luIC!C#3cGLEYp#b zn2MbukDTd#+x7-%IX1)|#whUsd-hH|574|%cuK-Ag1F;sjL&BbnggxQ01E?!(?Z?l z6dmBoC9%EiHgooCmb=0Z6w+fra^HgXu^~z6&5zG2o%(jKwVIFGb`niv#KIwa? zy?^_`h<5+o2VSLeCrA2zscx489hTbE!K8Qa|D^~fVSoAu*`=j*V!d_vPyl1gCN_@7 zI086~V6~&+RA!Dn%mYo?K^1KY)Xxx*2xy|6*(fgjIw4aeMY6#wB(YYh>(vstRX+9- zscqgpn27F-6WPlBYdnJpi2yDXhP>ZkdP#V5V1^D1DWDC)prlj1QqVnpXp-rI^8c&I zbM-%X>^pOVEZbxFbGeU)Tm6RpRhV`0*W7QZ_k)2(89UhDJ2d);!|FGuMP z8a)mDD)nT7bvNwNzE4I;$g}AQ>(3LP2ARrB?+N$n@R@9^Asg4&9v{YrY&~uCfYO#8 z%;QH+1^_l>_*8`yM)iuN>58go{v?y6Mr32NVXOjg8^R{q^3L8~NFXx+8lz7&4^Zd; z6I&oU0t{Uaisq{M3rsH4qTCuw4FzD0))oqHrs4!3hk^qBVGlEJfrH92$F*Em%^*?b zYnWOJ#^Ct8P7Jm}FV@W>VE=zd(;tQJ?vfKmv~2L;JC>zLH{HH2wPkc+=(ApFi4M$&#|7MeRGkM_ajz zf8>Lla=!y13Ep`ZRM9R|%Vg6BXYdR*m@YWvEg-N^i2U?+w|{H@UT7O)uPWH8bl`Q8 zyT0_p;A~V?1SnQbk zV%rAYx9TV^%Drx?*!z7E;u$rK ziq>yE7Jr?|iFEsJRq7Ud*5i}nJ%`<8NwH~znNL?dO5!r@N@%+aLyeSm2Y=LEU3!aT zNezJBmv!h5f;j(tm22)}dYA-P0T_fh`@z`E3kTpg?V2b?rU>ue9Td$7OuVUS{(04h zP0U1;{RP3A@L^pxu@nff1k^Ud(7i7>5^(XraMk_yVDA_F1|E)l-MVE;Lzj$EMTJ)G zrSpai%!k~=TV_>n|0>xNp7x8m$8_LW=b;eabt2_ww379wov@A;u_;u= zm44gNq%i!z%PPz&NYGXqbQTZ{+5W5iz|zm4DB^Ez2xldFB{(s}SW6YjRuKfU7`NX> z1ttPeQWeILuq&pVxX`{sR5XeM&|sM;akan46hu~|?!OPTV2gld%z#o%5O2^{6SH_f z$k7q=Kne<|)PDRM5KlaExA*e9cSi%v)EEOQh8LI(K25{aMP$E!3u>h1%BQc;Lk2=!?LDAPCU9?a361di-A|s0n z4Z@TOumO>mdouDK0*b*kv1yW8ZE%sW$Wi+{xHU7d$7hA^Xo@&^eJdgDLjLs4^hI z?wy$l>wa;fi^{Z@`EObqy(anZQ`9#wO}F=TGB4;EbzpQVvd{j#Z7_UcbiJJ(DXnDV zj({Wi-)N-iF6vK|S87GX)-{;(g~or-=Qo}noPVmK-636E@gEcT z&p|m{0yq2}ug;s?;+3#=_naC^l0JIpa~)1oR5`HKmY9JTC0K> z3<($5FYFF!iK+k`-WmbFazHja;cy$~ZH{opmVt}oUD^1Ppey*^QbKe^)btRIx1)(+ zyf&6zANGH|&KC!P3LJ$80_weacq%I-n!(KCNK)1P`cWPNWh#7ssSKkW2qe&ik}= zhWLhyGjaqPeEd!+fkOO~;cqX><~v+!LsmEPIWn=xb>LtVTY5?j&as&Zw-GL z>2b31NErU@o}w?B|ZW z;xc*|tBHU@ssj(zfz;P{Aan}{?jWx37zU-36;K%XltAU<LZq4u9!kNH>&5H7{$52ML9=XF=3FUH{gguo&% z`J24uj@XFc!u4m0t`r65BsY{;mu{#mj!fQQ6cSz@EprsMIyPx(^D?SVmf3>Yqxso)~)wBhtuR)e-_6|EMG^OIe@004uS^{ic^79Or;)uqfrR^ z3FgoA93Ky1jZqwZnvQ@>;0w?oL+4}h5qRvN43DM!yBP2S@fEq+rDTP+y)nBYvTd zOd1Bj`tD^1o6U~ne*KE6fuI$H0NlhCam@c z&GXf4tjJjVxXnJ{xbMBN`r*U(Lu)>U6+Qi7rF7ZHZU0u4U}UyIWrnC2CRM+shTp4m zT-W4%zSk$~vDTLx_8h`W_=he8oa4U18vi#}TycEM3FX2C_gAI?))pxbVnaUz+Qv$@ za!C8LAVfpt0)b-2D5v-UB)*^+Ph=oq2m_0Z<|X>Dk<$r)m^;g%IVe7h?uX#j6!LNE zdjW{W*xZ;6gR09QnaYS+3qd3-5TJH98>FQoPK+{8!ViE5BEfzsfzl<#1{syA-WL^0 zlbf7WbUn&)X&Oxmj&B_(cM5Kfwp9sffAjO~7taUoOsX0wS=t$CwPWk64GnD_KDwJK zQQ&X?M~} zfLG{`0BU;5$)OCubSo+tjm}jo+&Zm@8vn0oP zkfSkhBp%NROlDwS97C`4%MCnd!DD6hm4Ca}VP1VXw#VVTmW1q}#l6JJp~DBSdVQHL_%I=>^}x*4>UPaX zp8Mo~&vgx4{dKmLCCFVBvJF&{ez`{Bo#f9k-Wu_HiZ|+SzjMocFE7GYVUMAcZI0r1 z!=WVI;{yK8DuENID-EdO1c2o9BEap+8(NgQbXttJ<(2dVA)5z+9-^4EXf)oY45RH0 zU>FN9nYGNtwDxU~LmVK(WyCj_hmm8T=^`OsZt_9g#b3I%Br1o*$j1B>?EbM-M|tjf zRAc-|AD2E~dZ-1fMNe~Ot&|^qFp{it8tn6_bT-T^*HxUJzeIUfC9B%(vwnYpf%LAZ z$Mxt~tF5@&vriWEoN~W@AKhfjDA}Ijbaq zj@6^$;=^{Y&DoDBx-g;p^k55zhXL8ZAsPxuI?G~KkOSD&axks4$4btFX(EB`K54vP zCH|NDT;!cRL7cfNNvvAM3^ zpiLgwP6=4QhkNKw(L}FtSn=p*Y~kXYPd*8;y$Tykk}A@B{Z-s{dU$_j(XVmh0Wl=c zqu&8is?ktO{R;miVL_RAMD2GcD&`GyPUpZ_H<5Tm6*0WCVT`H*N+1eUmK6j-ATSLk zkR5>?DeoR~ z)Q*(%l#!M_*L~q_Xz6YBSq-7nnVb#vg-+@F>-(j5x`wJp{4eNssMi<8XX&9R?c(B1 zl;zb&-r1g0E4?SG`GG@e3VqD~lV-#VIL7pO`#7`oV8@)6obf3RoeeJ0ff0k3{eUh5 zv(C10%SJfsQ8*iG> z7N_C4Q}EY1l1z8Zj~*3s-M^+I4v=JHqpv&**-u14eFkQw44?v7bwo6)kYXZOX*TBP z42FhaxbKue28bO24_W|<(V(24SI3uiYr`1HGEk9+Q7ofKA)wa}s;jiFZ29{12*!XT zi&Eiz{5azmO3wX4j?1C=el@U_Qr!NPWM7eX`-EZJd5wRl&-2K1m6ebpSq-Zb>CF$q zG%S*C9N%w|NYc~Z8uZ=TM?m5Wf_Q}yZ-VhpQ-X6 zkRyBF6g}yXTpjilJ6es(5==jp_Dw3pu(a&kZ2m_26@8H$b(CI>%)3_| zd^j60ac1dDF&C-iH;lN?RLA8qVbL#?BFBqkRslNHz(o!qV~o`i&3a)#GwvqffEU=0Nnk!V-x%0)lcoz;Zr-DJ)+^7~dY z=4syE9}4OnG|f6q!(gYGWl~(i7SoC?W0RY-bDf9YJmB)nzhAn*5nZUPcQQ5)+jCz|K?(T>$3N0C{6@qcKLQOh?yPq+S*&z?LAg z;k@~V_;-Pza2QYql;_LM81aDQvi}4GN+6VjHz>_vMQcd$uOA6+Hz-SjvTNU@*7>jh zv#hYbas9_->6fkKgEO=#9U~Xr683=ltIm=K7fRb!tQN&wmc-7wW*@xyRKv5W)VRH> zqAGE7qVF0}K1XWX&uHJ!?p#}D=IJjkcfT3XFeeM@0JTbnF30rVs?@JxZi#g8oEZ5` z0Y!R*i)PcFkCLsHArr2SdaKT_R={|J=*r7xRX;UFre5J8fP&cLU_j9i5Y0H{qrIBi zK`D08TpNYbM-hXi7Eu6;u=`gjYS|2iCh&*nO~x>lBNCUEr56Q7&)c=8hbuQSGlZ8m z7zNjzu^T5HJbAFuLc_1pdXsKafy)I`nx>tp&zIh_-=?hhCpeqdpUAY%`8atteXC}# zt4+1ZwjV^>-eX5YY3fh9kIrw^#NTJqFk76WS)&a!JxxG-mMq?0m+_5ER?p`)tZxv9 zjE%Q58_93tDT@q-E{qXNq_pqF6!nY#K^PS_a3jZzSjLeu4x$)`QW+awN&^pm1Cd-% z(GR*g>d@Ouxyte!F^}xZH&{DI(G7BWUBW_|Dt+9 zRoKAIQu-db#mJJD2R`p~OB)XQJaUuSvFfaucs#?iwd8u~RWnU>ru=}JFy_u&6Ao&Y zEz*kB%q;iU6w{;8X3sfwQtmf$#d3jP0!ybA%dzlw(u(9mn)K0=!Q!U=%7F9|m8^td z#Ab?C1fa%AK$QVj+;N zYgzIYKo+letelYa+3NIOAo&*~GZeKiwaC!%!v4Ju)_;DdUrTBA>6i6x>hv2=U-fj> zZ9l%?Zp0~6_m$zh&UC(jgURCZCv5y0cH7F`xwS1%E1>Tvx&4Mfv72_%U{G_t)}@mZ zS&ma#%y=pC$k%pSeeI+)Fggb*zftO(Afvq$?Wq7Ui$aRve*#_H@r{#bV*I;P$T#ktuDGFD?SC4u!Y3+a|E&$HVD| zF8${*dFGNu`jEU)^IOAT`%2Hxp$%gfQkpOPT-PKSYP5AEeI%dcE`z%8lPdgOEVI2g z)F}kXyB#aPWu4-*jiB&F|0t#XhNVgN`(f5g?fhq4$}(g9f7M0$nm4Y^#g5f8rMrvr z>VZ~eX)F)aK=&3UK>n?u$uai3T+`Qe6~Qf3O$A^}j-DbxRh|v}Ed$N{q&i0r%g2M- zmRIg~M1so>;V%sKT)$xo(zaf>BW5bESx0`tkT+amhF1TVJguIYh6b<7{$q!DZn==# z5++>E4k301SC^{c`}37URtu~=EQK!RT}CgdRyVirD{w?7rA6b?GZb#W#y%w+xakMoyZ{7ZqqI>Xko?&G%Lv^?hx8 z@QddY|CuxQwv-I~OwSoa3G4Zr`Y&YLwcU6U`FFwPeOvx72TV>u27sy*RRU zndC>9DFOSZejmdNMjs2?KotO)-;nw^r+4!mUU`Lj{@Ai9SL;Zm&rD4Nl&0nNN)pEl z&D4LRe7tly8%@bLE6goKKV`IfjpwN5p7@;csw~~La`Uz=v&KzT3LjwO3mcBEtxA3@ z6Etr~qi`uVuG5|!Gtie>Feu7PH=CHMpD}zoqjZlV@xxUW!AO*`Z{+k8jRJ-9$B4$3 z5DdMH&`WE$ei8K62c?+1+fTSoTrg;nWkp8(puKOo!|IhhdlA?)W$;Q)UTdZpvU%cX ze|0KJqcqf~c(c)t&Z?D+9K=duToDQ&ywsvbUCD2qtz`T$ttSk8+PC0 z)weT`k4Ei#r=C@1nSJEU<#)~JDDux8r9JCLxxm(!lFD;4#N!WtRV}ncANMD^^Ay-i1|B;D36Tb~x?#_-f8Xc?-8W7`wZlOD~}Ze#>LD|vCVdHM$Dm|k*iaP!OCvGyvxS&NYk%EZ~sNH3t4VwI}FqJw;WiJVqdwv zG`QakSM0<9hhutl)P|{k?AoN+!WOk;J?stD)uQss4-*ojQYfc|b9rbWiNnI*jua?{m=G{PVaF(jG1-)@T)*oezn|>nJ zt<1uu@uoX~(~)LP=&YXjxw7S;K@I247j^whfXIC??xxxMjg6)46qLvKuyFD~_b=`4 zLEVn!i*c%J=TC2*F!8xeF~VLrEA_rz!szx2xSlheBGF>_XeV}kd-Br)uLqgkQ?65S z#dj7v)&6)IAh=u?0dT+lE)P#wngTr2Oj|eH_|LpSUyUrgkl1@q2I;FcpPHdv-5j;M z?d)8e||dVe>^?B>CUJ5{T_mR-RFkd!stY!=1A=CCP7uHx>0l1v8nUt3xyKd z>(-U)*^LjE#yA>}owDCka4z;KU#};2)N0~Q>$tyuZF;nv#DqjoT~+V)Z=)YOGh4mk z9c)>uTswBMT)zE|dgRlo%u^BpCPOJX-U!}j?s7-k>QodbZD&h~h3c0C3(MQ#b45FL z=0Sb6+f5$k)gBmqAJvw=I(BoHNHHbOt(wc3YZUE1^|>L6oN-`XUaY5rZvNDmc|(Qg z1BK=iH&?%~W73Q1jej&qqgA$ z#tRQS#|bYR+NR&B8Jt*pSbHdXM~m8}&V4IaGV2d4Eo4||-v03E@Fw0_NYl(vBy{iW zXLxlSHM-aNaQf}y!tCgKZI#pq|4E!7ep4fJ-=nB@;bU8Yg@b2 z;2Vvi&+I;%S2N^9Cf;+0Ct~=sy*dLPIdX#IX8%g+ z^aj00DuZ0Yj@Fx&iZiZiKiPo&(1Qk3$M;(o3eVLRW%G`3G zr=|w(FerRvJ()m{s?Tu|6{DE=9*SfrdODcCXGC1ud4uQMSWwucWIxH&el*>o_A#|~ zl$Cw^zlp%h6CMK&mZ?rZ=`LZ)905_QxwdZYOVV0#<;G%l-CS#*b;}8Zj+Ucn(YiNf zl}d}+>$jS?{ngaSyc`0k{b+8Qrs)5--R;D-Q_4H*_37bT-QopdK~_o$=G#1nR=f1A*g%L9$>1e^#=+iZS4Otxst`fb539oJvZw51L~i`DsEJN`A8!&k9mU+UpEuHHQ=JxM;Gwb{wPI_>&r`R(K`Y|4JZ9+WBDVb6HpAV(<0l_R)1+-Z zN;M3a`j(R>r|v9hu|&>Uqf0b$LwkcVe?Zy(RXO>NuC|Nfl4{-s)8ofqo-4^1I2G6? zUybEy-E5hl6={{6=pOPfcDbaq7k`bM{5{09LhM-5RNal_)y;^*o*x@m$ItvREcVTf z(Zu!H>@L4YP`r{t^fx@Yf8f+`D|ql|2KV7F1`);R66zY^N!ENzRm6V8+*s`rWJL?A;NOm=1#~go%8)w?h$iWFKd?;yEEs` zp1UC0D#=YJ7O{E>$zY+a%KG>}$NwzU0gQj>k&)|ClhU)AV}iaNo0k zj1?V8_kj{m^Y*_6-`X~zm(>%>SGd>9yo#~bFTqJ{fnGS# znHg6RSL)WjRI`{DJLD<0M(lRrSyVFSOang*WjTJmDogwKOGD=Ng*x-vrdKgA%+5eB zi@RHN`{xd>bQxVW`?vMb+{*D!gpk*9LF)yHPVwoj^8UCf?a%MLczh$v~Pxb-0*acJXo z?F6EG&;Leh{oZeOqN*if;|gYXR>FtVD^|vfXxW*WEX^*5g_7J2qdwK@eBW7@v6eIL zlVz&foqG;j%$2*CzHcx!Gcqt()OyxtF*li&zU5xf8A&mLrcg}p{B?23^W~sKZ_b$< z*5ksMmZozi<@e>W6GtQ~aL9rT;;-c!7ZfW7+nrbwY6T4<6EG&wach}c%bc%GVyATa zkVaDdUFie^lZMvz`kLfmCj=BBnHA@qBd2Bh>{YA{GTLUq_V7{wz#H=w8l0yU9^sgnUT4} zRs%bEZAWoE4+)H?jFr2hgP*eX9$BjhIg4aD!ZCTzL{+aNn(hbGJa=ij2B4ihv>l1& z)^?V*jxNT;yeUX!F#wt0d;{p+X4d~dAQFI zwl7;*y)|=uYT+>8JB>oAu4NJiStpWd{ybv2h-YB%7ynnS)V-GG5O#kE^M6l2G#?l7>}34Yl2g-{ z&cC>pxssXpF)D8*^2%Cj$G76U>sRlu58V0MS+msL{&G+td^k2fH8nB*PB^-VzV>uj&}NZW5=df)fUZ-lDPAKo?; zrS*7+;gXx;7gy7DTlIB|EkAVBe<&J#L+ZU!Hh!sN^AtsSrfTr<^ zrfV_FzA($^>^a@D6;9<1uDQ4Oq~D??Uhz3r>A0`Ne*Zc2u_FEB=eA{3>78uSh;7jd zZ&BZUL(8v2+5U!tbHBV*ueN>*VOyCs_Pn8esWP=x$&;lRoUXDj!yq(IY2O9K*iw~b z)|QOKZK+Iik#Qh0(Q#M2z5fx@-~@xPNYvlIe?NX$(bN=qupz(yzms&wM?XB1D+$f; zKCW$X;MUHbpz`~{t5YHACM(6!KR=J{?M|@Ri}ge-!SABkCwq^5J`jpLCjaGVb=%4l zi_N1JXQQPC%=GFN|D4M^bMEH{zTJ;D%JY?s&;R~@9Ei66^JXujS~G4JWO;WwVrvR5 zdE>6(zTN-61KZ*Re}HXjbXq^mVzhK8MKyrAAEq1-9Cu&gK3eQ_t|zl!psd?1?y9_( zlU=P!SKD}Xd}P0Gp5-W(#7dPT!nUR>cx1mRuvyI3R<6I1fQLx$gE z*A`P$BIXJdmQr+2Z#g&ws(EvRVancPkrZVw+T;D_^f|nK_|{0#3P8w6ngsQ=ow833x$y=Hq0TtZmQ^^Y6N_!{@UcuGmCZAI3f$pG$FR)Ua z&(NC;YPShD+vea%L*MVK7q8Al-LrqE;G_1(;Bu>$nCqRu4yMVbq#-Q?FAdU~`tR>x zKZYur=v@*>XKSnwl`&XP{u^tj3oJ!Lxfrt0T5oTRlv_eeKOEjEY=UE}gez@L=65?< z2Myvdt&G@}+xA0;`Z8r!F@}!W7?&@Di#Xt50JI;*#sV5usU;nb(5C zCD&%Wd!PSRaN`^&e+tB92qrzOFLp?JYqml+Fti1t!bl69B8C04l_aL5hyoM?)wV1L z(Ylm}=rE6s%dPb^K(C1ow_=LPgrnFh0u)@OQVeEj$d=(%!A*qtN7xjOI*$hfya%k51oVHk$F^Q#^P3N4`j*;9^ zwV=kN+%T>em)<|5UQoZ5`Q}Z1>coXh;eEGnn5Ha9sue5WD}UN&pm#mVc7*DJfVQePok zWEfP>5J%$;6iRu5+9x^UJF<27m+)SOv`KOQWo3l{?n6U{g|r`?rP_yt8zdA}?q`-} zYAHMS{4sP3Z6W5DbMO1a8Pm^ie%Q+^W_X5J^q+`t%J}WD)2;qKonl2}!4F}(wg`CD z`sD<1k9iTtfC)E?tk;cd>Du*(4w&)gB@POqN&$>I)5v~z$3f_bHw|7B-QP}59TDiq zW>WmcWDd9ZtDvf3-t-I~!(^~ZIOj|e>z!j7HfCDZ~px|cQ z3@Iv>eH_C+pi#Bi4_BKR-tm+tZj~}X^=7ivM1dP>6qa;w)sSSPb)8bQ7^qDpEFBhJ z1?S$k&)EqtKElJ=$w87ed+dWJBqT`9nlc56f`d;)Wa8iq`GOyTx=p-tIt3bhA($L_ z6`$iKeZ)G8_tbEx?A~VPz@BO(?688iq@O6(FL#Y&<`2i9-dQV7u z`NptDHSY%&v$@6+Gc=(agA= z)G@i4Tr%RXEBan&iSAdt;R&EG`$-t11|%Q#KsB1|V6Gyc-&qeYjXC-a0aa}ceyDcW;#kGyZA!v7e#UrPV7uLvjJk zj`~^V>2;{)bX5fzyIy7JJr;IA9f8Yc$TRR@wrc-`qAH8+E%OY^QAa2|T2$P`U)pJm zT7Z-0&!4vYqvbxVC9~BcUI;a+!;d*;8kL6f zSSkz@TnE`NVNVBgZt?b?8Qb;fFp|aX7Fm)4!^>57v*V5+=a%*+$81Ym9oEi(c|^YN zst&w%D6=aJAJM;5Y8vtV22_R|rkB{7__@VD zp?@-RPI#fC)4zZ|YpgTO4?okjpQNUatE}8I+WYo;Q1J`Z?HLgi{gB&HAHtrZU(8x; z!HMlmj?Yl^&|s@W+GcHNb(0aiyvTD*&=y6Iq^3drE}^a%V8x`$H;ZO&PT~(>m46@G zpGJ@@=qb5k(|oo+AuOXo^zqj5BV!hz0CpJE+6>?xqjoy)ev z9#enMEGq{Ja5*l>4BhOUSeqOfTR08NB4EKS@44k_AOQ>CE9z!yF#7}AjY+V*3?rL{ z5)0Sp+vT9#S9PK#!YMV&bYEVI zyegQy2AnmFbXfzoGtVc|qYTp!h=GjeA=NJ|?H@$_VpyPE1C&>MNQ5Xcnm_b7)zV}Q z^kV?zcZ9E7sJ^U#M|fSkxk#thVmUh20@L<=uk&;euEwVz#8ia!GjQ!e|RzPt%_fSGa`nRoot zq8RXpIv7=vnhAqx`LgFE%E}MG$_EA71WL)8c%M=vgPXnp+dh8n1 zkq&WO6R}qSM9`Bwq170sj+K1j)#uF6AP+kpc7giy}TlrtW2vWg8DNx*Y?!dLqNls#uOSNQ8Z_kiwGA|_S4%Nf2pb} zz%378eX5+RiFID{`$FEPJlM3h-ue*~h0OW!fTa7t#(z)^)a|)0(MkgxdBEY1(CsMb z``L8SRM&Gi=&s#RXOTab(Y>#yVdEpPtO1=J5t}gX3+fS@&b{e?igXYH#@6Tb)h)6g@8YUx6~u{K?B%4(zp5h)^-~7y`wJ~UuKSkIx$7_ zr@+_$fX#h-K!>&44r~1VBVq@xi%mBUIna47*gJ8(_gt%P8=#uC>IN15Tydb~816bR zXP+&7IFgJ6{Hp+cOp(c-?)gu8D;<=5PNq zDu-*w(-AyRM6b#96g=X-Cp@W2FsOkzih`e9fWa1Frj}-6VX$5u*tq&mPtf~M=COin zcXOXY!-U1g8+V+mhUPEyN&OkZrz1!_z!~rBin`}m^&tM^19M)FBeU<;pYgK1zBzk` z_#+UfwMWYu!sYA0kexPN_;iLNYzi^9g)oE$C)g2>mNN!;Kh1+g0GCj)sZA#v?)Yyofv^7{V z1ZFM-zHEp#Jb$-`NT@%mF{CJJMj8 zFYs}mjKji*Ki%`i!ym?s5>N&0z_I1g7$JMwd(vnEc_S>@ov31 zL;lRV_71-=Slru(PX+sO;Za0iCKq26Ct1zb85@UH_Q}9D!_KgTffkj(>dS$gDByYi9H;9_isd z>28QaBI+gh+i4&HnNd+ualvD@B6!3)Wb&@*sE;Y)z9|^TXgs%fDup@Kwj05~!xq%A2wxOD4)w`p^x414Hz%6krg9MvFCkoC00s=i zSPMX)LC0SJ#~FydW?vH+o87v`Q`=i!NW}6Wo8ybWU#VlCANe@tgam)~2ydA_U%s&5 zv(gxj0(qX3ZF5%|{+k^L9!YNLv2+HVRsr3^h*4A6cG_2O(<$9Fgp0{1Z)t?a#w6|L zSkNhf;f^maUex5pOif+ud_MU_ZWnTgRSxWy0$k-R zeSRGb!+T%uX(J&K6bK?wINAB%WEc}M?efB$i}-iCXGRaS0R$C z5b45|YnKt}_%BU2e<|HWr0^F0g^K2i95{VqDG!15y!ZWM^U#+slJST|8HCg;!6VZ- zw8tzy9cVle=dd|H_2>Aoq8?e;lA z)2nA=t8deVKMriZcy0Y(hr_>k6ukR`5AFbLAHKw=WhX>Ff~urV6L*!zxek>Y5eKHU zN${Gj4vDL8y4Y^x1!t0(Z-yt?vfG@~sUNBV#JHMe(#y3je+9i^Cxb6@V1wHZt&1sp zBgNZDq(UwAy>k|6?;gor*`5yBr5+eH=$MG<%PCPV*qZBoDn0arwRowvUjk%U3>6lplvWR3*FyX)$5e)kqidS|e#4avWWcg@0DZd}u6_WL6aoF=q2Hb{INMu{ra+|I!ToL?uLxgo7KsZPzNHw*T zE*gtlp5%s^4RjtTYyq^7ue1#Qn3lLUyo`Tua8b)@rC`|W1G^w^efqV`lc5x^ypw%+ zZ>sqaLpSfmC61+s(Y3jUXH3dB25{Iqv{@b|I}DwNzKW{FII^ZaC7TATUU%3Ha&;g5 zRw8Xm=nfvRY|#7m=s3yw?$9#35byn!G+yE|G2BPaKvy9gZBrH=%d9Mmwf=T#d)(%j z>fkkiTSI>-XsYk#XI(wpC`FRF4Al|8B56%)9c40g3oPd6J$vlbrs7;3*Xn@)_0Oa{ zAN9D2s6uDf6Zs)$+n$_4d#Y5vtoA<%Qi1&tI^TVw9<&RIdvNjLnUlSc*HT7PGGWq2 z^<16YlyiKf?1v`)YQ7y&7ie2w?I|jBSQ+9MI)U0}^$6aQ$2u%Or0BYAhks|g760L} zd%qU{tw(G+oz#|t8hjG7(s&>46~+xJn0zpZ%BwY%toX0GfHl7+CU@1$1Z(i6X>%er z&tfeFD6n{$JvK;=g9ge9%w9{lA}p+;EG`Xy)a@JfIQH7g@<&xz-h`l>Bx})&pRkG_ zj_8TGbD4bnmeCAl2!(rdYjrjIgE-syZks+}GxTWE|Fz2>B#3nTIz3L`?^}`1LxIg?ZT~l>uc+^l0;TSt(Dg~jEe`aZEbV8>o0x3JpR%L zgu@`~b#2cobR3^OT>s>$#YhTJ=ddJR`orFHLN~zvaCcFw!;0>E>@TQuUg7p`+2;SS zocLNf?R#i`zMaRO-!Z@5otpLNXn^o@yBf;(%E**#S-M4MhPMag$5W<{jF|Sem!S7;^i6PaYTewN0ol*}{xFj!5rk z@>N$2;J6TkO0B^ms%p>{=55yv%nax84IBWp;^opxfH?JAyWuaVO#)0hLu-v0r!D~*xXo=V6bWbDGmsG8A_cKTxa$ zdn>gxpXD9&proqu$~JMa5xf_sq~cA8B+kdC)3mYCC~w1mljF5De)g#L7?%9Sb-q4uuxH}HI( zK?OYR_knGwO~!3($3kVo)S-~KAJjK8_e%~`>`{Vj*(~a9c^64kELJRp z%2u&#R~&IGo0jDOR?DUywnoNG^Wm@P;xt)kJZFuBg75bw1W(25JBtk0M5W7-bUEWn zw#Lj_mM}JUhiqPnriy{{2ctoPb1z?`SUq6dlMFUN*|;Q9aJMZ&Urt6~l-JjQAw>mR zhg1d^b~}ilKdXn#!jjaug9yu}tJ0@v`_#r5+4vM!>4-?SMzGb+{~jeup3(%=2CwB0U~&ayg2A>Cu9-u()2W_-$zcR~fqS zj9_BG`TOtZTe1+oOk#PLAPXr#iSK{xd**3}3QXX7_rnv;GIO^J?J&_+?IDT51QO#nj2hgpe3?Gt1AavMjq}(NTw|(&TreC57dIy zAP?acfHJ+)w(I@Tp>#H7A>}l2Q*A&dR5+mh2=dJN*=)=jNn>VxxAp#K#(OY?^}ZR^ z&KQfd*<-@ny6P7DC3keT=5JuNmG+8@r<@f5F_HS)4fSgyddr z(hd2vnsh1ScD1Q~+MV34%pz<8tEP?pQc1n0OwAJ2@M*>PYE#n!t+Q9FwBt2+*Isxw zzT97zd+WrxxOzz+b$xBlBU=it7owP{u|^EAjk;}1acT}zEkuKovn z@_K&&dEU9WGmXA^Oe|OidmCe=m?Ia5yR0@npB0m{U#3>&uR4+-e*H|pbT*bfbN};g zbB?xjxZOWBLCeW6#oE#dk=wudkh(Uy7vyFpe%z+~{(0JbZmlSWgV@;4CyB5qpu!op z4ZW4Jh8y{YbFFeBsNIq?X&#(t88$YRp=EtO)@4h*LnBqvYWkXsTVMWed-&YAsT{}_ z!)VR0ZAC(QRfD{P98paFVK(sPi?g)k^_a<9`Nqw~$E;&aI6t5RtB$wF{PL|f>Q4OX z^S!{f!h^1Kkc8c2+fc!^k5KD*Xqv`7bB;o~6x-78-U*4y+MH~lr`&TxY+G3gK(U zwAZy18e!L1QNk~Q00*k=avWAcjA zzd^qP`QJU!cDN36THTE=d3M?6IsXCnAo!!E*F^-@m?UK$;W&gK9MYMI8>B?Yy|hgt zn}h{PdK_vthfp=(;ZG$-+GR$AQez!inx;f<69Ef&M+2laTb0*lZcLIYFicY<-Wk9+ zpe^jwBqX%i8|S4@TRIb~jr=5y+(=NFcn$&$4i#hi zbwM(YO`@~yG)!-*+vN8;Jzl&aBzkV0ZT#`8E^I=?I6`gOc-%S^NAaB_OtS6Aw_J89 zce$xBoTcOZY@JO=@j72zPvGA9si13l%xX$!ltLdN(LnbNEJ>86AM9y84HX4Xo30Hs z34ETafmC?vrd;Po&z zi3X4>IaCyfvN7(4C%a~YZ|aEfkWNW9PSDmO!*59_AN!jC*lygoygnpViWi=*BW0Vr zm6+OY=*37~!4dL9!f(s6ydS38zZ#|BTkZv#G|PRfq=i|OEaJu`O@@Jc(O&?oZ%|V@ z+xPrg8@$h|B}l>1NOX|Gm>>nS15-AAOodSE&POYPiTLL}lQ_{(Z_m%Pn>YFemR!3G zC-8J-d(s|`Jqb({^2tn2LN>>tZc>!q@5N+#GMNY_n8X|Cdo%7%=eQ%M+^aaOJPr{J zQqZDhNhael{NtR#MQ@MzCSoKg9?7AgcM!Pk*7pNAV`Bs?=WF;)TO1&N*Ik9w?7}2W zMY_>EY`z=WaT}W#OuBxg0poSNz}M7O$y@xX$An{xFE*@oP)lT#d2T1eYl!O2gVVi>NJ%$G< zDPVjs!eR417+(%1Fq!V1U;=i^hQ_fHr`l9;s8t{#A{bB(04R?rR1P^3BVL8IE5qFh z@REoT>9rg(HSqd{b`lzty52!-@gh-eDP!ItL_kL8?dt}hIh^0F4nk3gm7rDaX>zJriR$3 zcgHg%-wY4VH}%*s=5oS=$pM1VL_c!<^nodsO)%R@YEO%eYWhdkIF|i=&nqiji!J_+ zRsEP1ibKLazntzz^72ckWVy9GeQQ1C(aG^Z(LI9apqD_t^K>Jboq2_m`Ih5BpZ3_; z;l42rWOAg>cshLII|#5;aVM^`kXSWFpawqqL|VOmE$Qu$?ybivJ&*YW@6(d{;~1l} z%FcUw&?lC7bVvk;GBlGK z2r~)=1BHE}USPeH~zPDmU8jgzf6#VNA$BfqB^)^ z=}-guc6d1cHs?46uqOc$OQ26SICPOd@)jI@IQvk!*Nv97DH94k0Vbh@!w(18-+7K! zoI#KO4Vi@Nx$>KO_x^n%r~pnAE0q+Rg*EL8CGGCU9PNV^W#0oXhvQvQ&e|?R#bKPl z;8(Wzar+sT4Vq}zNp!~xCe)`gn>$>S{En1OkZCX*Jm&)$2r9p6Ip`N{6X$dDblRg?uT9~z0BWX-N;vd3XK-t{XFcc>%nrcMu_NA4u7d6@ z9M^*Ik(f8VC%^;-#<|1OA!dhLa25qijSS)h(m?VwE5MoUGUb^q_Z^fR=T^f%qjBf z0O3;@B^bQ%c>kF2olwpCV}i|D-o_{8=}z4bIL2qXo9UdzwC zrVpLme4SB1_r%gYk;^`KkexJW75v60JKU!QBwhrm^M~ABv!qY1xadt&v4|vE7U2Xa z-sukwANdOi!VTxA;SxhxmCo1Q_J|+RV1)p3c%x@z)mm+A|qiZH%3_ z6Zj?|K!a!PP?u!GMCO;b?^rr2; zjV{;EB&>yy1@;U$ejJUx9rW276btn^Imq$EA>xO?dj~^K_`vS%eRE1BQg8#@fd>Qe zA!I!J)DO^y$JsIek+K@rJqU^(OdjG+juZqd6p@5Sbh~CH1|t%x=DbokX$EU+6i|wa zkj>%%w+@4!a0I$QTq#iK5h&_hkWNauc=+SUb?bwO3t<)}WP5_g0_!7qk`POH0 zlVuu?f04g93JW5(%qyFNF0O)H*!v@)Fm@1NgFW*3k>4?wci%&|n?pX?tciMr)yR4@ zyDa?V>g#~|Bk|ltkBvhof?$Ec;eu6=ZyW8i2FAFAk92^6Ek``?nLbq5j%Cn&h~tGv z^x4k4^B7)`;Kc0D8wa!Ec^oPgaRQa)IUUw)_B0?6fxr$SF2By9Jc2|7tXhuIWjG_H z_@YJXY3ZjSvNWsjcwb%WLhQ~|nUyMAnkN;|mJ!+yxV`~z+TdaRAyFhM3}Z%ix&496 zJM12ui7o?eko&CgY-`j$>;s>T{&uTrXo|__BYN>`q>w{OalPNeJU8bLQJ-<*X)sUG z7TA$#`tqmCXV4Xqg5L>+KUPX;9(xLOxI@|pH9$gn&Y{4B;zW0_aQ?ji`iWV zdNN^2LcYwttP_{Oz!WfW=yXCbD0^)#pneXx_>2-6;CjOA{5Bi)%QoRZI^E{p6FEF? zrVlytneox@Qzv|K6UnZO4b!2a;f_aF;9hM(nWs%(m@U2jVJmdG!5MwByCDK*qjt;& z#}2HY2s2DR`WMmh7-|Oj*}eod#j+z_LK!zl$jE)4KP9`YhNbOQv+32z$%sIRV-a4+c`qR-b2KX* zpOtxX-3ygf@{CWNKCQGfTFQ*}9v;XFA0oFnWc+Cv?nylBN`;i|alPdwyXO&=_bk^N z_Oc@+DEKBMf}OB~eWmn{O*XyE1q_%zbUjJ%w(cjDmvkeO6F9$V>I1af0p^CUJ9apB z_#QT0b4f8dVqG=i_-%!>*_ZY*>BQbQ0g!BR#dO8TaADOo&ZVI01KA^r13nG(R=+FW z8g+;2@f9X_8Y-`Olv~HN1xyrQ@u|cFwv|did(NIGMl^yFq4o*o=w_>H??(_I|uG3CI`xGUd=bhu7_;(F!l6l(f&Mv2VcLS!vW{gTYU z=`f6MS>T~u^4UP0UAt{}(JHHpNAz#Bw0WR~of96m(~)AD7h<}98C1qSTFO+-si=mP zJWxJ2m~g16bwvG0U8}3kT=Rqnx}j=uD~K#_UnX5fzsae)n*CD}bFKHQq;YHK0~x!* z<@f?)Y#emNureB2WLQ*P$hhizBa#mtTLJ#?tc;=$JA zy%$vXrL3F^D8jO$H$jLTl-nRVaTHo7NQ2TCbWQ24rBdA0`FojjBSIC3r=(RX~ z8|~wUlc2C|mIH$-^?#%mUz&(TXNOec&Sd9SN3oKP^%K8Jq8oXve3J*^fS1MIbSI}T z_wRJU)I-W2XU2Oa?cao}AFL;Y#vKkeTq<8|XpJ&@SI(COu`~BdZxWEWg^vVdzrnyPDV+VF|&v0%}(_5}lDaHjQ9zn8V=A#{J^5s;DK`~4s zSfp*Ou{gHpEm%q9(RdLHGF(Snf?XM_P~uK8o;Q%7G!d1Tvug}!)e@bFa>~ym@0+w# z=LbQ;)YPrC)FnCM}+Soq{-9M`kD=R#P|}HAqqmTR93+ zYjRs&YG>&tH17=NK6>%7tovD#)+ZrYPtTC^i(C|2h1^Hu7bJYSIzg9&yU=MA*(cF5 zO5y%FA9oKFcU%lZSBsCF3J8=4#>;FSD;C(3_4MmgT#fzRGj-H6R1Np$7#Fn^->Nw< zb}a;|RKb-rm?0fA##+PyXk9aUQ2i0j-#r;9Cy3&Z@_-_@bM*_IsTn+zCckRY3ks}dnp zU2T`zWnw#Px7Mk-In8Mora~B+Uy%r$px-)hYKM|!Bm(VLEfMfoQl(;^V=&a3zf*R3 zQwh;OLkPI`$eYSQwUag6aYc$=k+07$;b#4RED0k2%5ZY2Svood2_G+g@}&kzU1H>x zdZBFSW$i4Nry`bUQy4flglPXdAd`>)!-I3w`+5@@V&av$m)0r;^sQ=TtpoWAIlMW#K6LEjr7*<;80Egs zb(v^xk?MnK=s`P^*IQ<<`iS2z*^*rZ-+E0<<|GHLzPtLgwOa0>8~8$#1J(J*$zgR0 zOgFp5$N9lL;Ld#c15uE30R!Br`Bn{vb8VGL);p%PNaGn2qlE$wT{7VB}t;tp^g@s%5(g;CCd~~>C#pZNr%8iBlzdDI(cag5x zPNWF6yJs+A5vp>!=(N^#g4BT8>2<&BGhaoXk*g{9-S)J~q^#&(F;C308*nZR7A$JK zWFl|}#FiLCI+~CUI9gyK7Ci@O)~7ImB@0>4eyB>#8kv#N6PlS~*Rb&YhJi=4?B$Sw zak-Ej{gHkdcSbGiY<8f(&ohC0rS4XG=m_jug)I^`t$0kTNPj3pE{20vdK~HMa!gzz zmR!44O&~B(|B8fvp(x+D@K#UqmL!`FRm^+Av0syrG?)FfWj6A@4P@pFy|Q&W$T0Ha zZD!^H>Dtt(e&}VD!*EiKSd9n{W>WA+l6zS9&ic2_LC?3^g$#kN=C>3#T!-et@=K0m zty~IbX@CAvr`o95dRIHmHHdG5?zT5*H~TU9jJTE$iuenqbuJdDRjuzX@76dU9~DVn z{^NNu!phxFSS<w@BI(Sv;DizYew2R+W>N_}!rhSYkffZv&>15`Rq=}JLU6EVGh(l8I{Un;l~2sPYz@RBxQ&)_?x ziyNd*vUfopIzsKop7@0LsZRzqUE;Q>?w>Q6jqDsXdICa=M@}ZoSAHnvBHM$PPpAY8L(UnO^MN@T#{^b-Gf0aW z=w@!KxqmKuJ@-&{Hsr-K$J=~FB>!a<$toM~xI#AQBv}hNoH+$Us_;3ZHrbvFu@~64 z0D2*;#2A)AIe2K_(NQe}eL#iYuZ+`C#V@LK=&6c7 zP{F#dlgHOLf=xOHDIq{?9I5P!%8StFPS#Z~WZu#yw)T__U^syD5V7YW%bx|rx|7tL z*;Y6pu$vECW`nrB_Bop=4ieaN<*` zy#R%Q)$3P@vZVO>)=c|9Z=VFSmhMXWHxP~gNIgkm@w2JEsYw0JgaMpreu~b@V(`-% z2f~ur=t!u+n1^F0%l2fJe%$~!$L;hjFnKt_c<#aTJOz7Noh^^$^J8Wzl%ygKm?v!g zv#=B+dZ)8JpyCz9ARbUf>y-X?^{Av9=}Nyj4zNVACl{U?rtxiN++WJi{MvCb|0ZSZUtH(c*$24!d zXp;iO{{3jTrh-c+;Z~j|1@Y|!?=fp6o0NB$05<;-5febdgpe*2kgP-aR&#)DFVR}S zc9F*0jqR{YV7o8?`@BUHfd~o(8C%?AN5+E!l9Lw?$R>dz&^M30*u_8DHj>PpUWz+s zV^I&KK}Gw^IGpHM4po+=-q@Jhy<00gJm1h7rku+HL+~^;*u9fO>Fg?2t#x-(eUHS(%w=2h(NkKM8T zt%(Fxr^VJM?%k4XD?Pvx&9<^8#hIAD#tXq{aFSz&`-c*ks_07%Dh3y&$8D*d0BGy%;WL7D{ZOPw{#4}ZVnFgIiJ1)Qete;&h(XJF~`1ol3>bN~k+bEqRg7xZ$3;=38 zF$Ms?0@y+TqZW{t&k{=>sP*E)jX;m-q965QbJ3iEB2rEnd($r5*S3RiSkAIwl1w5= z=5L7DH!ShOk7k{(B*ud;Vrz6~E+5soa8%OpVy~W;ZLEqCU)F?VsmHd&0#n?i;;TGk%B{z4x(@GP7WkNcEG_N<) zdIGCU1G|?#2ey)cIy!V?97@LL5FnVQ{2L6YkUQ{ELWrjFfGRds2``4@u>y#;AtX$6 zk$xo0Xe#DY3d>0o4JHsBqw78XNR#R|p*nS9Y0UKly9Vq*Rbvj(B!T2uN<81jGWUwd z&a=$ku*@K{?G+5$n~!@G*kQF+7VAs8d!xK+^i(_Ev=Ve2Zdy5-@J0W{QqZbpdXhDU zWWCZZlBS$PfGuZMS9Y_vmsp6Dvya_o(OIhs&-m7Ows{EOdJ5PMNpK#k`FNVOz1{Xc zhExW-X((VrpGMo~>ED)wh>0*jBC7|M>5`6jVO#+OB*2;};)i)iC^(7ppn0tEN|sek zuF*!GVL8#goaB3o1;aDrE%2Bsz-vy!js`jS^paCZ{>StICoIHKX{#e0FGl8Ng|lpj z229r88VQJr4T|cUEU4pr1m)zVx+xU+>fw3^%cP$iRSaP221M)5QLnfokNxr9c3<~>-LLDqUeC%kgQ_)yz@?{}9im7PEeGS%D;5!t^~jHm_&dT4SLFBT z8&4z|h3FeOK^dRPyTn2bR4+I)6sCpjVkt6p32&W`N`9p;rx^Gp$T zSaUZ5fJl6Yc=F+%?6ViymVEuQS|VfoQ;xUV~*wtNZ8(U>XO&`j+ zu5((R{hI3gR9%L~A|O|<+G=nkw3icg=OH>H5aX{l%-1H7OEK2}p!(Z7P zhAOO=&v%D1sFF*FH*5)be#sBEz`h4rVE(G*z6K!Yx&rUWkR$~_&e5#xVpgqT+vH9nzh61+}Zs4HN$NkApvFPR!K`L9o-JCMuUl>STH>O zxcfacGQSr0r`>{ivgero&4adfllSbN*xX9(==;;Y!@NUF{gIYB-?A4f-U-#Nfm&1+ zn1{H(LNG+OfSwDK@-|M}ICg#wL())qHnKfSn>EcwYT?>%hkptjU|XRxCz-!;N1P&jUQh4YP`O#!%03MGj}O^=YPem=kHF7V{)185OGPWdEw_J zPGXGA#?vH)1MOxo1sHw)xbw(X^T}_$8eIjvem}nADKaayz)ds6u>ih&xeE$6k_<|W zAkyK9hmFp|p|GK;*EW<;qcyr z&l8pm)b!e}T$anwX>Ojb>Xdk&_(GRV;u!Q5>UY-#7UnG~_1~^7zj3VS{G7sz%E!lx zf<5!qh#yP6utmobF3%Z=oFS6Vpq<}p`^%!-)zX?&XrHNV=Td^Ye$;; zFKPS6$dnHnb5P#%E$^`FclunAzr(VjK|n!YQC*)}w8IUXyp!G6 zkL#Y%Eeck9x_d%64|GndnSJtVu5F8~?b!SGQi$%GE9F-s zi>>WVBkNQzC7#=w4c+eP)^dr#etz!|6><*C`g~J@Ja#tmo3fLT1B3OVuemwo!6`8x zB`;x5DtiKn;^eg8+h>X8e9k#?Gegdk$mIvZXV0@iY2m$6vQ+1ciJXM23u}9{!{w)P z`<1t5^Y@v`giYTZv@RNe6fCWivGl()H;wv3Bj zlhYDsNb3xHi=|z6^Hjkx5my^iLh5w;6lWjP$4 zBR;{gO42{D{U(#5ky0n;mRllcD0@c)T$4Isw-68V$OJX&i*)eGyh{VBX1K1|h|@c573XFCUJ8 zDou~UE!y%jyyqcB66^h*{mPj-e`o3rHJv&x=zIPGXGW6*t=}6x`kWz77f&ouED$o}OKwp`0;Jw=+$TWr+RcOZ65VrLj*#C5}MxBap$F6ck zi3dM>DWpdc*W0tBX;{mR9{}QNMAdkXlms3S`%QJMQe*>?B31fx48z<(zw}n;j9f8Q z>7O&09-U@`Ef4X`X;nqD%=z*>k!asEjPyJmfUOxyg&eP#@zK`B#g>Ze#JXnaj+U^W z47uszJ#hwJH>R$3)o~kq1STs%h@)xm3gNcWGIWtssc(hkZWDqmJwR+5#@aA>1;OOM zA@p($qhQ{jk8zLlD#vxgiQZc|!OK|+Plc&^Use!aV;%BSg(;`=c*8QS{$kQ>@m(8! z_Lw74WLG3y%rxuR$1Yp&?ncUTlkKYw6qO0 z+QXcv!5IKQ)@`!RL1V~NC9W_TiW*|asmZ=~7Xjez%bCZ;)b7MQ6 zD4r&k);Z`^`JuOtEzc;tt#Q<9KZ$gYQCWD%=+?@ef-nUdPCUhJR9sUCSwx)m7l5Yw zzzqR7n6%UeQpnWPbAA~`%13cR&kccMTUWN4!?)Q_A^^1F1_)`tL{S%Y`YO6ECbp?PH1~Vh%Uj#Qnds+Oby|x^rCZgai&z_+4Rfju0!LByg0fd077yVmyr$Q7iu!Eg!o`Z15Aaqn+1{G-FtknF8<# zyp0S{)P(?55BU zZkP$3{RTAv#7qH-v-LQh8Pm@rGicW=|BLJPQ^muu%&HZlTl{G|vIv`98btcYfwcHp zHcu&joB{*=l(4|CdL1?v)DHBcMDTFccEK1F>LiFdr-ty6Rcm~`w|B7KBwVlUH98B# zECdb~fCe^8hBe=1b_3z*bzACrFw6Y!iHn2yY(Kr0#i(3Ay``zYu};L^1B6(Kov?jT zu~U>}0p+y*UEe8U&6IpGsPn(?3Pb?sDC~F9Cg^5VRV+p66v#Kt%eQhs&;LM6Kp4Wq z1qw(JQ^zHAIj5|H-_iH>Dh0B`fe^+10FRtcdXs#~RFJ~!vjY2WYtJZqz zjrg=Jj$XQ-)!WMh=`>=Y;BN}g;L8Gjsr;b&3jQ{a5--?d3n-aWM1%YCu^^5~v-$U3 zUi~!LcZy&K9>uUAvs2`eZ?-a20s&|fjjy+YO2P~XUvSQ?U}-Q47#qlT^2099WBvU= z43}g|Bdd$FyFL*XwLRWl$$$@_xDZV))PM~*+mUTR0)Yu&g)7~>HRVN;$k-qxIWRs9 zOFXfb?oW10^`-)&6g`M{?vYMEO5l`NEJ$hHqfiAZgiMjPB5_f$V3d=>JGw$LN4s6j zOx!qVD$!+9EL8bLVv96gdq07iC!<*F`t-FM`s%=Xd!j)jURR=cs}4pm)rtzSbt#-W zc#)@21mgE68L|ZmLJ;31!29z;F9;NB1oFik(V8zL3O^KE^LwqanSEw+eqddc5{|!5 zhf8~x0cjN|I&G&6&X1T!C{cvimSEZeKU}+j+|RL)`bU~rp?r^apD1B)G85V^ z^Hg+&o*LBG=@nq|p(9#zijLMe=P4)W%gjAAY@lHUmQR}YBPt4`g?^OkePyT8DIaMd zpNI9Ha-QShqNXNWN^1)x`%haJm1>(E+K73b81$ht=$T;%ZAq#LKoIl9oTy@j0=>=l zo7c_-XT3_iqId9@zuRXG!k7Gk7wD!d{}Bvow+M+K(N~@5eC^R@PIxU(zV4blOP){% z+A={>ksoq{{`QLY1Uo?>w-)n!WE zj`q>l@U$c5;^KDF4V&w?hs&q^EQ=hy$yBgqN}f;Kb6gM*WG!UP;lczr&T>T65`_eg zsG1d%cQ~kT@3e3>DAdj6+7*%OKtuDR`lh#WI_mNN1LL16SU%SHi)qBaD>q!MC#3K` z9nbcd`bo?b$ls=sJOv5~Tb%G=H$pW}9?w8{jJBdU;=0Nk?`i*A1EHS6YFbD2+ z5PgP_3+_+mM8#VZQv9soQg}9)!lx19tuKDtNusV_5nU_Z@#KrG$-O-AcNS!hwkLpN zx0PK6$^y@1x!|0DMCL=dXEIKu+D(F_XJ=@8Xk_2l*cJ{r^g=GC3o^7M*93|=FqGPs zAQDW#p&bx%NGLXJI~O9$Q0gAuS)U78w|-FZ&7UHS{4r&HMj6{HkoV`261}~9%ZT5? z;a}Y?(v842YZGzZJCReQ-@EE$_G?!~<10hCZ=1P~L)A1|;-1PKzo$_0^sQOP&XAe0 zeSbGy!1HcMA`u%q$DUHSGKK#;U3!s5y21(nkA`n}b0yj}Tt27#PBqvI;&6%Nc>yKf z+bh|0=R(sM>-$r+hr1631JeFv#wl!i306%Anc$J%O##vhI0u2E4Sx%oa+-|c0}{fA zI{cGXvw%MdT<4H9$0$VpO;;BsZHQ&>r*>^XshM+l9}i0b!0rI&rht)ILAkoyNE;7= zV%Ew~?*#eXIWgzVDnI_$E70DfNS9QfbGV+iwAu2O`}F5;ySQMhn>iil+}1n^9%hzL z`s$fq73ju^t2(MQY{Pc{-E( zl9W(t6*ggzu?+DCo{-x{m3i8@&h5Bz!L@z?SnybMwZN)z0R|fkvR0B}gWY*YFL@Py z6Wo_ufFxv-wlPU#O^}u;VnQ@Yy%{2$GDc!yWndDHMQ$rIt=}C>s*s;+qaU@c!=r$pOHPiT*l1t3RI4xG9b}SS*r>(V z1U4>$hh5)QXML@s%O-FuE=9XWIO<5&*fYV6+jx`b(DmrB<&EoapUPS4rMX@7c$@Qa zUkZ)Dp2D|8+)kJxut8D*h|jeC8XDVM&ndr3h8}-MsH0)A)Q^@_vJDN=N@Hf)lh4DC z&G7c!86g!rL*PuMc2_`(PfBl>k71Ga^AxqYz&cp1ECO6}*E?xSt31f!6cfg*f&<|F zm}nGLB%LT$O?m43zVp87TyJgi=hUkP5h53K`uxdu-#3nEC^|FNGyWurvH)%4C=vOj zKpHvr(VY%Fhx}mAX}`W0HGJvdXXvQvQy@Ocw*m1ZvHJS?b4>%%-V3gAmN~0m?j)Gk zKCAb5zlG*(+$jbR`el6eqUBxk`_#Gh?&6d@olEkzCe(m941 z2n?0|b3Z69HTltk%V)MH!X;p=440_)7M^$Z2br;ioXTiLY4@}sO%b@^V|$-1)0z#4 z$>CjUSX6S&BMphC#O!`)Vf~n)4&E1O&J;26O#WYW0`4EJKdE@GE0!& zWe}j}+w#}2X|S+1uqa>twa?;Ya6p%N+>Y+OUJEbEj@+R<+_e$xU%E%ma9^B}{?_R2 z;5$2-o_Oj9-OQ1+RrB$B;Q!9sZ_k^4&nAzT371-c|K#hAeULgGColMD5+er_D;#HA zL+&Az=l9fnKbkBd_i;BXmnvX$OsyhRe)R27Hg`d3%Q4xYIFBpK0e`a(rfV%?mh%Bg z{%bx6GZ!+TD@JT^A3}`n4#jq^J-0>kIcYA>r~XPp$4 zBPJ<<;e)e<2F{i=mP)!hf;#p>-BxjkVN#a%df$1ZG>Z=)$b3Hdz4c%&RGymq(p-XE z!#*I_JcATR52oIM&h*Zs%n|Cq0rSo0+wVfY-jjN%y*#mIZK#A@-e)1Veg&adH>iC5 z$fM<;w>nQ3Uk&&^-jp4r^8;(uaA9Yy$8V_J$z1ghjjFX*@QL7v;|>osNe4e0mMjV_ z(!U%1;?mNuo7|=g$KT(+_;KUF3I4xpA$OD1q6hW+n1;oyLgLJpbm>bbA9bcT7*~2265L?&Z^)R{W(4b+TB{N@h?F6pJ!j z=I>lJKYa}PGyZkv&Pm}KXoU}CS?le8V=&;|Fw%Hk_le!h3?u&X>K=n5ENkgrFHHSE zoPYV=gkL!i2QLkTNBwVAUVrjhX4uWCy+t7>S0gGS81Hu*MOCZbvYG^3Tt(miCh^Sn z2UhXE4oe@kZh=aMeS*{aGBu&EnDn z1E1^kPJ)P=i|s{qHLrC;+~~HdU*s+GZxn;{9hLD}ni<^{9|1uKP%U1J9oQ4=`bG z7o#&^-L+WERvMsWaT=c3qMv?>A%uLdbkIS7=T2BWI8&KeZsJI z+D?qY3v&@diTobR#qOQ3`GKyK0<9YUAZsvt+IbZa{( zudic0e^MUOi=?c1GC+?`U}&lXf=v^(Wy2${Hg2vOn zTkVTaJ=63C12;yBeqozO`ird5s;7n_&s1T=ZCF*e4 zvP`yXJmkekKE@8l#9a723n7ph&^AF1ES_)_Nl+A9|HeMo`E3haN#jF3jLY6f~_Qn$X?t&B$8jMU6G8+FpZd8YyM zeR}T~1}1J=Iy^XWZz1VFg_NR&n?2Hq!aTWecaDlOjRJgedDCxpC7ghBw zF~Y_80%hzkAp_i2^8!&yCs&x*iwUi>Sgj?XJd*(=JlPd%1SJ1)IvgoZe*zu60TNg} z%iPB~2y+I+eKGf>k`;*BRjjGbS$X~2UpM&5{^&8c6JJK2k3|@tBA(%#Od{>P`fUGv@c+CN z76~?f{}#e81idv5@I#X;@M8=BG-ZQ|EYt^f? zZ8U`^0U`tZK+O`GGt+)5Ir1h>6f^hQK7c=F*vlaA#{rydOOg4=|}X}HDBI{8mpZII3(CWjnbx1 z!%uHt3=Vg;JyYpGTs^nlOX1?exiFj>B)MJ6BZV3$I`~)=aOkk149IT>MwlR#3o6y1 z-}BE(V9;_5e-sAsD;LZ*l==*SqLv#j9Xn=?E?t(I79u5FK=Gk{FoB9B6D`S%l*y$G z{@5j=o{PJHLO%G?36#fxQvlkwmxThr6^0Ll4z973KGM;W7_}? zI7xFmD0@&KM6~k}3iYbPtTT^>Lrl94`Y=7=zg(c2ZV^ZjPQ^qFlFY3K>f>? z;|+ns`f@$j&@VQ?Q8t>w-}#4{B*p*`7*v291dl z`VSop7hu%76yj<6r}7kHcuqYm@eWqVfeONVLtnZ=Zm>zN?N#@%!rhYRqpzmia6EHk zY1CIIAo^{O_)_%2GHY_V{+TNGwD{H2#je|HU>?o1D*c;mqja+X0RHv(*;?aMAK+;zWo zZTEO;uBOy6vqu-AH+_rmUDyV7{vS2vX03F&8Yw}7vHU29Rbu5?#!QV#3n&X~4h>HX zk#1eMxe^>B(htc%usDC`$m3i1_MJ)%K?DG@QIq}BT@GggZdEf-zlEU05Q@h~jk$rV z7^yibnk9$$L`N}BQXnH)K@-BF+S0nEaHA%Qm|J5m*>5+H!_~(PdDD3Q=aE-wXjoy}*gU z2#F!&dklMmE>$#y0$qSVLjmHZzy@XuJx!Nd;#Pcc-$j@`C&@?0?gU_EfC2+8!w+nR zK>pH^3d`WP8Z?dy3K?k0A!Ru(I?fTje*{2rfLr!R*U*3+y=as(;_xekM{{t!FxbQ2 z$-Cs}GrC6Ul)G8*gP?ZbiS6z(eFuAphBl3%lOjK;PoYHx59moHw*xPr7plT-NPRH($ zFdg}VFHK+of2bf{Sp9*%L+K6j69e_k4P0VKeP#jirsyRXlt^iPI}L!#TH_EM>1Cwk z5J1<`T4%@{CdfH%twwCHfNVqb&s_9{bO50$a(705NNe5>}+Nt^0bM@Uv#HJJ~ty{k6D z0Wb#mzwMB1OzAf)bUy>4!~j!YA4a*bM4a{iTu{FO?Fgb2h8l&cK~|Un-$n6Q+cFNZ zCv*b!X3F3B@;?|LCbxc>3gEcjcqWKg25Ah?{1>RT3K|%p6+PrK>{b4ZqQ7Dy^#f5seEDQUzk{ z>f|_qm-8(_D0s*eqQaFP0NP(MlZYa^FCTE{UB&^3_G{pR9cqaWe9=VDx}Zu}x}O(- zji!q4!+>O=oN@-{Eu_A$DZAYW{fln>cNsLxLo00nKWoq!A+~N0SkKzE>G0TD0&Nw} zMXVq_3iV&wB1UQuA`72ODbh90M)!xecM4UVjoV_S36~cyXqr~R`nGnjU5(aB4gE~I zJJ`QFBCXA4G`B#_vQ5h1fN@_WiSL!#m;Orq=3-uh`y<;h(xV;D=qf^KME^>Uw2=pp z{2s(l^xrQADJ--~4MCYJ{TzV6xZp1adXois7S+FJff5j~h@K(N1f#-GQZ>Me5Y<`; z^gOnMaJ8Nkw=9GzZ#3y_I&T`kT9$*kAixMCs(^77UMjR9E+K=;;2s}6&mYsK01b=M2gvlywUgYu;el(7NO zYOL3r0jT)fzin4REuY)nbnZuNOmq(o=U40?t-noZwjgb&>~Wsy zE7I3Ud-W>&F`+}}Vt;OR@52fFqUV$e7GmS|CNA6%C^gJ_s|@($0dIuGo6B~DT(nG0P`;?4 z)F1hmd191%;^Q*P4_f;jC@APaH?E>a0H?(CeWtTPh$QfU~j{dkDes692xKqhQ-ZwzH;DoQ^alJ4NIJ?Dqj{37_)g2E+Jj-E3LvhbC@e_7vyXI z9q)g0{8dhGu}+@x&zSbo9S8S58s8QGTF8gNHL={jKHr%B2m#K*XejfvVknY zfQ6ajDW_dfvdfjQwt24=jW)V6R*tsjAbvB?yvGRv5JbS@@q8g82`ZsUZ>F;+A+XU2 ze~H=nQsiDi4P>s+m8O`U34 z4;{UC@d1kVh86TiXF(g1SG@Zd_1H_P2@+kwVFfp=aLG2DSUW&;s zcQE>*C`slrdcZM%k=TsKu)!E@6ZUN>jA$MRq00_df*5RZfh07_gqtW;y{^`K{{D&@ zh4rPRf|8)NDZK7?`!QT84#iEO`&N(JEBFUdT`FJ{sN%TRSsMXX=1|c1u&abP%2$h$QEhyqW&p-B|8xYGhyBqCvqJj z(%K=yM3nZBqZr222a5%TCqb008zKG-Vg?qd2(&65VVcM%;~cpI&x7s0yhjYNa5i8o(_Xs5Z3xV~w{ zWV=4RWgE5Nc+c?1PQPym`i;=h@I{X!sa-$b{7ufH(~e~c&fH+89-Xra7=FQLOFK~g zc$e|5H6@u&E^0S&9DsNgq-igg9fh0+?x35GiX5%{BR^d|#jNf90IGk-aoAJ(&TL5v zUU(C(ZX!&)dBuModZDzT0)o8HsnCvJmlOm*B$|KrP=4KGCWcqvpeBZuT>MOmiSSu-uC$`N2@Mfcj5kwb)%7q|0Y}d5~{6? zCrjsc_|GVvV$IyFFwSxvW?0Gx<2Wc^Y6bj z*m%R)obORaEwI6oS#5Y8;Ek5GPIll+%iy_3X*IbB(MTDJew?64<(sZ@K-tbO_}~Ap z&E@9AdkRwxO#$etegXBoI0&VS(lrblG1vjByoUQs`*HHTs8A|X1-2~(eOccXkgbG4 zaLcGqpJs?Jfjn{T+%NWk=L=ijPau`f(WG$~XIC!*4+oAfS-9kqMbI#p%&tONh{)mi!}s59=7 z1oh!6CJ(?5F$}#q$bgViC^e?bOqXsC7G%?;)%jvXHV|jRg-SH10w_MZl*)&`&>To& z0BF>F2T{5MZfw2`O1TStK?K7^b13upL=y2Y*Kz&0KH6&}5%-p#Aztb#9Za3Uw*fEx z#jXf~v{5ELHGv1tcqqDPMjAtA+x5cFYm79M?|8@?)N}PJ9$Ej-XhkcCx4NC77g6Ef zzXfIkS5@{naaP%Vw1P9uxHtV0h$~Ch5;3NQdsj+RZ+z2$8Oj<^a`)Ds$d=*AT^@S~ z`5UP@F!6k4#rb&v!ZlBk;QDTn0f_W+ zeraY%AVf6ntC-_)e;SgbX>;w6&9MS^gm zH9CB#ogy&t(uk|Y#Wfvw&wgh0*X4;yDfKY>&o}pHa^3N%nhiw!ZKQ;+}ITTWFVpsFe$il z6;!_th?=h9HU;CD@eW(ua!S;LlR4Bi=rL)GEJ$SK$QX4%e&TOfEW06(&bH&~YhcDp zD;XW;Nn!(O7(+btw#1o0BVpNEa1GSTKJwc=$npE-4Y%z09-e?6UYNAEIAmPt zuUal$=393D{{4%-`?y|SB<(S*pyU3{Bc#^CC$E0o5V*k{G~=6+#d=SIth6NQO{eB~_b2QD%#QAR zU;ci7-cV<-p09afw|zsIWhA1raIf31s>%cY=|*qICr_*{x<4HMdF}DSWT#xnWa;!P z#6NCUDGYVXsrCv%V)rsU^6JhfbVK!WJJedn!XREx^ zVFIyZD!$0dRPb5`8hx7UB)6HeGg**v)I~+%M~%bO)bQ_N2eX*u=gNGZ)OLy9z6OyI`X#1s`s1gyDAUI9GdJoCgI%LT9ur6Za(bM z^|z^W9bwYXbIz=}!;gI)n|(Y>#O~s!GsP&&JlmKU|Grb%Z*`4oVZ|R0Zx7?Y{qU}5 zUqlu#dXx+KXahi6gMhnurWjt}C~k8aJvAOc46A^Bv>gE_cZjY}$&MBdY_wNp#))2p zRBlRa2O_NIN-#C0U83mq5tCfcVu{^%dZEp4)VZM4{gLK^5tjm|%Sx{w6nLI8su(6# zO6~g9$A2)T3Q9eAXpn936?-Y5SMb{WUIE-n8jl;SO2Ql>3LaLIO(FDGBqI zq01?l%2d%1p0tF_2TcURS6EkhI-0uJPGZyRdPP7Z7Jiatn>Ix zbqIjm<6*dMax)gUUQ1-qZ$%hT=vyW5BY$X!vDA`~CNPGE;lrhy0o^C$*j(FqA-wiU z3W5({gsIaS&t5$?2r+StrQSPHcqx{9$rs3!;=%&)SrzB)UUH?SN;^&CtkcbqGoDZT zRnzda<6NCpH={mS51ziivMm#k>x*c{+E(*zp}r6H%SZXmR;}_wU(Q6NG8WG zp5&B>?mmwRb58pnW7=PfNlYULyUU0z0N+$F!H;cH=xmHr3K*J}Dzxxt!pbJv?(M-* zLxGv$+G$!IICd-Pl(I}s%DDpAg?S*sr4H3=rgC=xRmnb|CUfPa6)O#vb}u!yP*Lx$ zxNqSl?cvm;^N^!11zQ7Lr=EyAsKEk{ev^NX1^Wj1n|*gK;*E&f*#9ZtmnbTGVT66P zM{oFagG(#1g0{=M?*0$ceV2|DU7E?pJh{qT=Eqm_j4U?R(?JjY5D4kFXE+Bt< zoz^E=RawMFFJ3Nt?z%D{b$0hOIQ|s+#^3TvvOg_nHrylQ^SOCS$2wV zWeQ@f4$a+mNZ-ZE_^P+J9K7wAA-b}1& z_4pa-MzzUXLnyyY{#IJ+GaX|cm|-?+9I=z`6&lV7up63fY4^!xaL&p8X$HH zGa$)_i!Qx!HL!+X?AQ=xX(1fLO7Wp)KwV0!{DvVv4yJc@j;b`=N*~E{xBptB>E>;* zx6v+7TeHSM>w#&PLibV>MEkAzJbh=jq}u#{tIFbsewZ%m2ZycAHG;wwrO@A54h-}V&W*%M!M zU*l>&*Tg%Md-=@$-xuXCEK(JRCkw6Z8};0YSx#45wbXaJ%Gkd)8{XnHjucBi z$Q!_t$o5ms!)`ZP-x_8g>o@vn*BDb$?0INBl}^ho%=I39wHP2FMoTNzlGtySCU#Fk zF4%u5muZ|94_j{W>?vwk$e+I;06342tLULPb zoe4xvP-Pl?swUdzXr%uxjAo;*Tb?WqtRBH#slnu>y`l!S-4Wm7AS%1hPQk;PMUQKM zY6dWQc#R`63C-*uF)0X)WWpvJ&4wK-OhHw`e1&lTn9e%nG3UM6Zh1aeUY9vYdODEy z0aCl3D55Iwx%0mMcS3=NcKTqtAA-0$vkmotC7 z&O?@Rvi&ZXes@YKyvht$mb_`m^Z2DEb2InHS7Qa!?HT-|y2bljTKbh<@zAy8OwY7u zk6(>FJ@i@5?5s}JyDPRc^1f&5%E8Sy>b%tBp0E%+L3FyW*`;_%+&dLiFj#q5GsXPJ zL%p6Z&7B^7{d?{lXrG+I2>AQD7;jYT+RJ*vi#+4?er$aynn`<~{b$;z)cVc(e?KL! zUJRL#s- z;+HSUa8r)Pm@g~NNfnRm^PVda9Q&QFSuDV!9twg#zJ2=bu*=AZo3*=BUV%;hw0+)4 zL4)T1A}y*HkQQ4?_*PGS%f~H|MvAjaenq={v##aQX)B%YVryWPdGibpOgyov3)Ek^%^#u%YU0MFr)-(yQJJwWvBCbSBIFfrC3ZpRpRy<5YC4y z+-EDdrN;F-oW6j`Gk6;?FCM23)4&~nQC%;tIAIf-&D(zrek_cB-1F5CBeTKe{k1Xu za{GJz)}8jmb2!m9-c?-t9`W3y1^M}V*H#v}q2WQ>B(cF{K={7@9;Pn_qjA1ePFk36aToj{nq(eNb@J3Tr&ot^WN8Q? zH1@I8F!rq>H1@HNttcW?!z|WntWm15HrB?H6xA@cY*CU*Wi6zlRO;Jjem~DY&%ftB z_c`Y}*L~ji`!%BV@t3&>0;2K<2HywyKZp)w?;{J0LbCV%VlqOK3P>4EV85D#qKcxL z_5pQc$pfas>ej*E!@!7{!%7B`;5boI%oFbP9YuQ_It(dC&epyrOCNmK$&I9 zV@s6XuWI-fOGcKfCl<+N709Jt+)vI>2)v|yDg#5gq?=NJJzsJ3d;>nW^=NjLR!N1@ zt%m(=)f&}>#$}hVwg#mtLo zspk{3E{0s7d!(JSi%D<^3-ynQjgI%f6zNtP%hKpi2ensajhCeDmgG(>?+e^i3H_`bw}wu9p_=^gfM1uU1JBr$YiRWj zk9%(C^4{Hh-ifqy;?#0j)Q7k;AJbCb<)qD(UzoXh_0^S<)%42GjC)ZEVfBvrj{`KbfkHPOdQ-7BF zf4^w?HPZTPz4ps??$nOW&|e`F!xgIx6Ff?A2vd>9%y;SGl{NQ4hBEjeb`g{B~sg zi_XFq`Q@*o3)^CwpHN%xP&-p%zXtdH>K6aiAiaGP`JIXUeF6O|M{hgZWG6x4SG??E zwDd1u*;Ru2dryN6Z>z7i9-FQK>t?Pq7_&ZYtyTrq+vk(`>)EbAH|8Ek>Q(S2^(?=@1zqZrNf`e zdrwK?rlqX=P|hvl1dc{f=Yi-B#d92a>V5f?fg_h@)H0W~D63|-C(N^-I?;xFGCu_7 zt;Ms3leiBv2RU)$?Zl^z4l@nLZ@5R^zC8SAclXJYCy#CP5PZo02`f5sSbbE4q;|jv zr;3-2I_O;K*j7E5FJ~AtKhjn+d=-t)Q*>&teOjz}qA}oUd)?SIOxS3pQ%C*84eZ&C z`KKLsp54Y#K_%x-_H>P7v3B5SXTys-gc|3Y&i5K$HW52w-i_XCdUcn?%TsdcYJS~8 ze$f~>*46U%e!}wTO_%$v?|M>yY`h!0fA_-^3RFbdwVSiZ%aJ@BG~V5|Jj^`ka?ABW z`|4P^VeI?y2OXcDvGDoIZVx-xU$9R!1FzwR$p@o9O5iL>Ljt&JY{_7s+3a@rcitf zgu)F@{j-c%wlCP^I~1I#yxs|PO4guo>1=2YM(k^oj{7dXucJ-$?{y+VNp=UIGF#37kdX&FOBB-M0;mY1xWiWb?ax2hTsJg<3YCmTebhARYc zwiz;~o7;vINSv#1nOIJu-TQC`yP80rF z9z)x5t}5~S5>#3vl50{MkL1U#K^53tK$Y}W5kCq}w&)I=9-k@bHqb9qkG4D9nJMze zpQk)a(8f55=lZ8!mnj>f>lEmpCqbyP?_bf6%!!Hkv z)v88iI8Nu7zj`44kR1-y4-BFVR+olMMx^GvR{YCqq7<@FcTes(Xv7O9}z~=lY?e<#08hVzG?5e(6~*{4hsSBra!J z=8Z7$v-C9bC%^KO>|-unm-#Fs4uby!TpP;jdR7#@v$%hQESGQDXWkQXfQ{8@BIDO(4|M|;{-Uy zg~G4R8FyASMcdw3v>#+#NXu+0ET~<0OqzX?<{32ezpOV)Q(a5RC2S;>*ZvtE``M2lzqMnT#S%HhH&-Y2+E9yjh0EpLG-R#JGYrK zL%X}a)H+}N_qODt^*(NLyR!YBLBN_oNv-B!@o#2?=cdX7@Ap*qj@}10D^*hHo>Tl$ z8yX@oS~e<~%To%U<66L8#7m#$RSG#-{pH8r_6w9&Kr8}>TUx||G=mj*%thnfS0cxW zRGC^5-I!6;y6~g_;{73?!@X4*-q=`!CoG^tqf6w9&*sHX73&YLClCFvHnAWo!>6Nu zdn%)QIl|1}>b!?&d$41qBA{hr!d(;z*|m}9VzNyjf5fsRp~_G znq#G(Ytzq%O1@0;uJMh!Mb_K;k)Au4)D(Tumxt83Z2931`N`jnj;yL!u1Mtm5V7!O zF+(H?ftTZ=u%0v(WE}Ue+yVwLDG50x5F4*G%K7S9n>DN{P313Lix5$-TmD4iYW6> zX8WMB4^aT@hhm1x(ap(6s3~l-b(5uO?1wD^{MXCWgatKO@wsAOmo&(fQUD#sjaX@WefUF8AV!L%`RrQ`)N+KM$P?$6Tss zde)(``3_(`<<$RWpNnJ)6_QfIDVM5AU>)va9R}oURU;PbWwACIc^HJhr_eQ<^R=pu zDO-*`XSL%n+Of+C*~unx9HAJJy_=-F?_Mx0c<91~cn%PbfyY7sFK(6|7VgQ-@?-&Q zA2ecdG9s7N}l5g6+!lZ~%hju#P?#Kg(Q-z+DW- z0TJFGBfgZKW_e{p%p&SpSHlTl0}3>g7Op{q1>77RRn@$$Lq)1u(#yD-CGGQ5CW6pp zGW7}xB@~Pkszckm90X7-ex5HndG$qJ7{~3330#+*?#Y6Mqv7#rfUN<9vH*KCz>^E~ z6X7vvxEBHb#Y;WNwW~WL=f0+Zj6dhLO~J*X?DGpJynKLE zheAG z`Iil*F+u(=6J-W6aT@2DU>X+zu*Fl<=n0i$R<^Ua~c}B z4cA^bHgLgo4kC>NHgGF)S%?DE^^8QF^lC&#g0+mSW&8`=VZio~G&Yd{crk@ySf^4k zd3Va;L=14p5%8a?3u6K?I6%q-@F59=lLTHR!I!iJqNi%fl$NNemPigfd@G+|29IOG zhJE3#xDx-VmIU*g_k7c1MoWBH@EGo`g#9;dv~Gr>FxnBUz*qTGf8ez&yI6Gc^9OhM z4^Aa=_Bi2@s12sfMgyIg)A*Mu^RST-U2%t1A#ct<7fuMcggtkmTZp>GY~E;0BsVp% zz*e*{3j#U>cac#tbD?X!SHU?Qg1Q2>~$?G|cHTr-)^T@oMA7RYoqT z;S8uXf{l&sTnjK91ExB32seUvIUqJ2WV66VZUdj)&@u`(qrgI3Rl^oo$U@xN0jn0O z9sRv_1XM4v5X63=3JGT#DTq=ll(68TX>6K+5)x6soW}vFoOn6~OeZ`!UJUwD05;?a z|J#lG^`x$P++JmD&*lYmUML}w1a{Ja%7+8LQ-RY_0MnA2qyRsG>Ov)O^>b_YYJBq> zS1z0dyh-p?;Vid}TZd(Nw(HCq(pB_f;Quf;BS=~2nE)*Ts72*`|9$aKcS8h62-48N zcsk%d-f&YJWK*iNU3%p<8umR9D!_I8c-459GjKDn-KC%d`>%&E54K=(EIxyJ&YevJ z%7cfpodag7XS8&})!%(KxfOn{);}VQ>8T`Ao<4Q&gb$*QQk!xEekXy;Mm>3w4mcLT zvlRuRIIsdyI2&U3Js)VmJw>H~VVnkdAUxbb;A8?Iau(c(1vXutYx?u|Hr~18T9unO zfRmisClBt5J&6DMoBcQE1b{0;9&C<*vxHc14WoD#EJQiApzmrXyMIG{p=~V08g`` zoSI5oL=`N;;n%6iPgm7qfJPE<;$wC-0a1+uMK9N8R{}y`<{ZaCm+`$t2M8;|qtoCX z6wr@35Jdr-r=C>&8FtF3WwU@gm~Myt#h~j{NNjo8zjINz(~$(YgWq#eS783(bfr1? zGqQuPd9ze8=kX(b$-&3R?9b=qS*Aq9PwHeELhT(3*Y<24UQ&E~u$q6&{%i zaZVzoP+t2bk}K*+U=0eaMG2pWfCUR+`oi3WX7I{|DfZMNs|Bpb?STg1_u@xRqNigh zU@H?0S88fpSlqlY(wG1cam&65TsQ^TR{;O!G6ladmEsS2Z#|ACJq=?4-(tJ`vwKh8 zY}9ti5!1SqSw8mPJhNQ8=VsdY9TZrH2F>Ri9YvcWA9WCPg`LN%3(>+sx4>!$czX+U zc{H#zzhp56-dzCS1xzmKi16PugDqRaJr9MNIN-#MrrTS>T5kpuRdmeSZE^?!NtB4x zh47x_bGB}CxBx^04l(zoBB%)@GvOtdf##{jBdr4j#bu{}(tzlHTwe-^DgeYppP)$7E9q19Td%?Y#=pFIT$cd8RsxR{%v_HdZy*4!I$#2~ z?JlLg_4%YQuJm&iw(A-CpqS`Z5ZMAVuQC6I`bhQ2Q56LB0MoB z>w5;_7aIB6Kc!HWa?+>q{p@N3`n%-l$21ODuqDib2z!ct`u-TKZ3Rs)Z4h)s+PU8v zj)=5DKG|9b7jr(PzyHQQwq|-{HuM7g(Jeq6v%_lzA0FHBgM78Wbid-yYuPVz0Z+hI zmQWEt0T_EbL%Px~9a9l^>q{j19mDDGlk^{V2(vAy!fMF3_0|EMW5TZ$3kw(C-6ny@ z{{uM--)7uqTM7Rcb!ty<@y;~({|-NHxTq%r+18S%Av6a$`IR7^A0jd(w63pcc~)PN z)(sjc_gJ>SqGWXuChxg2Xq$ul<4Y3~SGGyt?VNdGa9r8*y#3|p2V=Z6z0!hmi*{n3 z)e@MtZqHwANH_U3``p{3cu8w}yZJsX8r%r>@ofuw6bjRxsjcq_zi03kj6Km6 zyZMa)e@Z@jHF~u<-y40YO=$LhkOn_oa@eOz%}(%MiL|E2-J{b$VClNQ7b{y~bF49@ ziRk80>Z1@VanS1YF@5Kfwc;IGo~4^J*7INL_tlB3<3R@ERW|9rm}d%#XV?|y_{&9V z&c|y#y6yDS)Qg;OxdYO~01p@4lZ5CPX|M3T8c<7Qh5Ey}{{5eI{Kl(MP4_Cz$80@_jn zzyD_|K?wgdz`KXaxGe3@sph;i4f_)=W8Yd*+wbRBw>kkvRGpdV9Pby=f8gp09W){r zH(EEZRxFxTBe>~My+C#N3-g%C+uGT~(W+smr z-`&_~z8l(i&9%P#e=SC7QR}uv%D$QKDqGcD-6}hc_3)x>bVw~B_fUOz&E_u7_UbR0 z$hF#4N@!6EC7?5^q zrw$amD}G1z<{cBdu(Y$IV_SIT_Z0M}r6ZDlzcS&6lnz17cVzVF1!_du^$+7pV*UYr z5vBey4fL{r+&i4I`OLC`GT(&yL77kS4_@y2SALk9@g-(1h@Na85gZi!=N#sCQgomG zf6ak^;z#cXNglqZ)#SM;)%G%|E`D_~5U6mP0SJff+0 ze#chbq5VaXU8hiZe&~R5I97_a5-D*TGN^k{+}6=GN}{OTcKi(gl_A#3L-qmgqi%wV zmD-!o)aU=R)kUkIoz_HUpY;y@$Qiaf<$0AnWFfOZFGAI**9K(OD$8B_sM4{^P^kw! z4hQtz@ap_()JUOgC#~eU@7$Hv_XlH7{ivhJLXldSNU|@X)g47F$JbauFC)XT2S`c+fdot zaYACmPUYq?@vVJ~C=aP0~z@)pw$?MXDV{M2e553dHIgW>nuH~Z=Y-AsC><*n0 zD7d3~BJCk_!}zA}%O+7fdfjoQh3c?#j$7f#g4vscOMce?zOF3Byq5fs>B zQq-Pv%V5=aVIo3E>W5ePp&0#}wuB`a`~{UG%G-zdZ)dUe+=Qxi8S6ni$V=zLcs(_+ z{zWjDlZT5Z+8U+gM;hUCxl?cqTcjWoS0O(#V0Yqf_FlEK^m;FQP_H{LKXA@Q*4O^W zR;`QW#;Q*4y##u3yb8n!Rv>Y2Vc=(XP7~7OnWX+$X~SCSD@PiyqI4Cy*b;{0dzGo?*t+p5J6ACk}L zae72F!|u!XLIA^o8&Pk>UdndO4eFINd^O}pRW#keXdUWxe5AHiE#FDDmx-G$08>NR z+8<#*-(;*W+5K*>oQ$2AEIH~HyFTzCcOcGu5&tAjb-_;Op01`+{#aVa5hZE>sd34ZD2FDk-fi|q+G-u$CAHC2GpCs=B$0JxN)s4sM67@Q}m=`k#s0L+eTiB zRMr#AK^wRBzAim9sak$LUAfiVL*#e{f2n;Me}3Ek^mD89zcTCmA3sd`JdXBl9B0na zelQ*hw`K`R_Rb}%YA5E}qu%Xi36|WHt3o9GS90AB>HSgjFqdX@?RP=Oby9 z(J?tj$&E!(E$G2_i?eV88&+;0Sx}aIvggRDZ4v!XOR^q=U-dgGKk0m1YIrzh7I(H? zhrIXP`M{k8b55v_aJD+4`Up6y3ThdY&+JgOK zITdPn%1>8s1GcVm{nI+EDOPqV*IGYT){jefU0^%m*khUZ7XQHfKGVPako@(Qwwex8 zs%=>gv)LIbR(jj!xaaBp12$U7N8BFe250RtS8R@>dgbP6{tK{eC=f+%--bSkBry`s zGD65epd1jnKo6dx`Qv(EJMe&A_}{m5(iHuul%avhz@0{u?V|PomO;1yMQ|S07YjSy zO?O*>XBr+6^VExSKJs@-^>11=LqPGs-#XnsD|gBLLx<}RovDs~QK_eT*I(|@kLyOY zo*Fj=;nA}mCwP9w>FXIIjGPTvvT zssz<0ZPeXv?5`TFv|FGBnQOVTY5oI)-$kB;$N^C##uh#^QjQTp0zx29u$B1V)ML&g zyr2bq^c+1H^W-A`A1~fQb#v6fHcs2P^F9i~b(0$|>WBYsf^R;&gVOXtmDrYi5M@Be`+aA8#D*=Jn|A1wd8)@)_=BQJbB#hpIR5 zgjT3e;a}fs?Hd;I(Fkb-_rJ| z?_YkHxlPgBw&+RWK(g9iCh*BpjQdiI5S&1g7bJ9-?n-iW*aJ(GoP+0vlSBaSKc3Y* zJZOZT#M9F}%nd+T1fseA3v?GvduL9MWnANbKTI=kjI=GOHsRU92D<-uomT9p+tgw1 zTCC0YfcEM5)iZLf@A}m@6zRqD>UD~3qaF?hZPD#F4T9J(yEXlHnXur_9=}~$=RxQ4 zG1!w8xO*xrcnj`EJQ~JguX#F(Nnv8+GO0H?-A@ZM^dk-YTdIU7_K#x}DF`{R>*N+8)XpHoh`CGHE;5@Vz4k zSKaETQJ?3gW?p|MPxOxR&>3ul5wK!L@(TKwMB|5tfD(vg88 zI7p>3{&+cmGbGSYfhC?uMxV7d4A`l27Ga?|2ksY&n$>$-Emnw1E zLD-JP?S6-DL;Vt4t1!b$VdZ`!22tPd`%+BTAJqHoH2TgTO&mCO|KO4BGZrNE4ibXl zhE|5CJ-6%bI2aFe8=?3AphqWI1T4Tq5sZ+3@L&vMZ2(r+3$tBdCy2fBEV934^s3hv zmec|xrqeo`?zysIaS_MPm(Bz`x77yQc|t;73uWrdyu3C&7Y7U|Y);|68Wt7@#wpxRzns zxhvH=pS7F9%HjWTmQ65B!9-b$hd)kZ!BDIAi$hS3HdplS(Go`VPwl`h`pw!(znllB ze$u!7jKgx?^TYgt%kgV!W3F79EBdhmmu5%s*PB4nm_yx{{iEYx_Ng=n671etm`MxF zVU6B+lb8E)7!YHGI0BJd^dEsh1jQi&8xTuiM3n>CEe!fiQZO1Qe*{ZoGRW)&5*vu- z%x6n4uH738PaW29arr9(B>#gat(ZiS{CZ2q9RW^B7llltv;~yP+A;i17%C zxnRg+j#z-(2rO)hwqwlbj1T?|cmEmyyF+_>Ig94Ne)G@HqBr@OD`7eJCq296L?oAH zI|L)+=7rC#(8U&G*bC9!faqiYG{RggdO4OjBQZH|C(U>kF%}6C_*>u*HATN4&d4pD z>uIJ1&INl0F@omcjOM-de7v>pSc_-9QM#(Z3pn%hYOQ)lQ@rh}fra7QH+L=S-6r1t zdrK3zHG6Deo`mT++Dns_=+$nm8R&ke3miU;R+0VnGeljkjqIve7sU9A9r;+C zb|PaYG{=3-h~bjMaN)qxI5d1}RO&_hm<*NZ44TC`+Nr>yl73p_qYqjWupeS;6cfhT zi;TWx;I0OPYEP!O0x`t7Sj=V&Wlgjd=2pH&9$}y+8OVAD>J~uGVUW6yM=%|(x(o3C z%K$n%pWQD3)r{UxUvtla19M;--{^@5?xx+v4ptzDOxB8=7Rgcn*`iu8T2|J2E~ZUVHEADyW@E&uEWzoj42sL6d@BuVuUWN z!G>tCb2N1<1hqwvBxfB#y2>EOk989DUw916&_ihhh6f{cp}5}`{0%p9HT+zUWXzZg-*w3$? zUwSBYab=jDLx|g+?rM#mEea`xkJ3Eu+l%UK%V27Owvs6%)2De+I?W=PbRbZsa1A>SvQAVAuKqLvm4gCE$@VMW(o}ZTENg}g> zOmFKQ-oLRY%Syk?f4Nm%nhTb5cGD!d?b69CMi^>^l*4%F4y)yx*>YepthqxbjCgER z50CyL(%lUKgmT8%CJcR3#t&VF!yGB1B&8wgTgh|Di1AN{C+=C^)@^@Gb76gxd-YfU z)n8scNcW?1ejW8yjY~>wcq>aF$5+LE4K=>RGD<_n%ksXIg zr3#&QLS~{c0oSgQ@`6ZvFF}!x0`&#ykIJ$mw&)Ralk$)FNb}nhs^<#FU_2E zRyeEhNwGB(jieugusBGL%e6JLGq&Fj^wU6DgSfRVm4O_IL!Ql=`W~uw`7++lu!iYs zhbzjNI=gGn54x1;MSQ0VpQv}8W(W4zyS+Ax9l5eSeoj|mD$eq1@^YEmjpOl-!|M1U z$ROs>+v>u%krM%K@pG&Q9{*g6pK;8~df)V4wit5X& z3NvvHY9mcDoenE*aym&p7k_RHid+i|dXVtn8?Ri+yTK37==$`=zWNxLo1(-YJY1|1 z^e98@e|1k!)(7bZ*CRE=PSn_!x>|VdjLdbCIQj91?Z;o;4Q$MH%K!EGT4&g>afm_W z{G3bJj&g{z)7`?st)=1OBf&?fj}^ehb31n&3u~CFN3_~ulK*r5JcyCDF!{0HWK{It zWlwm_iwXU=8E0Kh-fOO2Hkivn@$^k9mt7^_;)(@LXG?0tj9(`#ml_*~)VLW#ifU#J zwaSY{jc3qjuNa8?QTu)P=iCfk4W6NkMfLkE^$Rdhi6`caa+SKmF;D+{9v*g`e8%_4 z-9O*u%X)V`{fhI&4PA?ePzMVPTfP{G>JKPF{f|t96y==iB`-OuUbB^)*Bf|UTdooP zSMWyklX0nl>(8X}0`-UH4oO&lH2bSrTj*YbaLPAY^0$7JTjF`};Ojfjon{~HcwQP( zEVe;B?JY)|zE!OAGJTivW5VKF#Ca+nxlyolK2J3s z!SYs*JjVVCh?+)77Vt6smQewi7-X1|fqa~qm_gFfB473WO8Cp6kK<09D9V#J^fnsY z%o08_(5-MeerDdzn>I4TEU?t}twy93y~!|~T#V?h^_>`YwIJ*YxIm+hn{05P&ERAzr{82Psm2Za zF5oOW&)CUd(rnc-U(EbdWk=}AS>g#XqtRNlkFWkIs@sE4wly{etJ;Qcy+6|;Z-gEP z!U~RDi?i9ERA4+i7y9hy*k0nK#>4ubDi#;$^F*N&W^$;^+*mc=Gp-3wP?ByYVNO3P z8}zH2@9LkkmgKt{&CMk1SMCs8Xp#w!bG+R83t= zwrhKS8~aHl$je4DE9-sKElJUX1{#JgMSu~=Fv!vuRoccdFw77rNFvF-;JO`LE4;iQ z&C?vRa5ee|wfaO8-9M=*XB=rDc?Mmx{}mnp;?VmPVAd#Og#&2lI(uHTKkDeRyc1$c z*+Gu~}Y~uTme+^jpH!(N`D_R6tDOZr(n{ajEvbSQdrq?GG;z)iBhX^wNJC}Zns8~y_OZ9 zX#(J+idYmOY`>B4WY4+6e66F|a*x=yF4Zdg)9jY9jrk02nVM+A$JKMD9BXD|Cruqw zBiBzFQjv2Ki{=h_2lt)8#28HJszho>OtZ+YJ*h;r3b`qJHJKGP6cOD!`Q=@UD(CRP!==;JH6Q&vG4+#l-1 zFsLpp*mH@H7kBn7x=uA%lZ%ucj<#pkwz=~xg>I#I78&*aDaaCr?jIov=x=TmoW)rS zr^y2V3wJeMM@sVj)>9*!8)DZf>e!LOA>;Ziji`XwE3i?(Vlq+mJYo;m!Olc&Y(HXt z@4Aodb5wbEVqdXlsKwQCA@TQ#x%JaE%ETMPhYkxP&sLHI(70@ikC{jqh6`IK35h%} zyt1WdtmI-WBzmy|senER=->cBckbncW}briNS(>J3G&pqBb*=natOP@klN#moQ|@J zy?<-ERYFP6FSso-+yNsNmC$AO3UVmund9XUOqfgV)7au$l5bK}gcVj&ujM9Vk6YST z<-hOeO2#EDlERn5Ms!?_mamaY~DXVe=t@wd78c(mPTn$ZVsCPo*e9ki)kJL!MN9y{5Q9kns#kmfE)=rgO{# zFep*Mb5i{dzaoQ1SZ3C<_?rFCHSL3Xa$l)EKxR$w3+;`|R`M+_&zUT~Neq3`hm^t< z@7I~*O6b^%idv$fBXXJ*l3u-PcGNvJT$gE=fI+HXn8K*$kl~X3mDn7-^2pq>T!TUHv5k(xxNx;h&akuQd0|ylZSh#LkX5AJVM8iZ38ch`5h+w@nkiJr5i1gk zgC=*fvM#x2n?K)+Axa3A}Ld( zhWtMeZuzKtvW^xe1qU1mH;7d&2oWFf{>~E zRj5)YPSGUC+FXVUDSCBZVUuHRj@7)S1q|YKN3p#@eaB zVXQ2DKO9@#l{)-(`)1{~NRaQr{kd*BzO9Aj1NG$DS6lw3>V8ml7FSQ3Xd~r`I!Uf1 zSz9h{21z9Oq;AB28Op8lUxa^EgqkTrEqd{$I==5KZdq}ms9o^|;af0!P*t%X4eLh} zZP2we^%<&qI4gyir6y*3h#zwK#sw~d_DYzfEYeIlf8o8b=o|B99ykR-&ZChW=)M`s zr!VhCn@@_)abZS~*WIjrwNO(S@xlfCtJKRT5W*`oo!adzBtY*ZL%{+lyAEesf|z_a zah%CBAmEjysfH|yTPnTj&j9Y;B!-34Ul^RaCvB@qBJ`#gMj-!z@y!irGYzilqgBOD>BCuRU0Yx~6YCypuDk)|(0yg!sWYEi3xR7RI zRi_#?_X5>G4H`93IqpqurMwAniAllUz`q64`do&B@TAGmib7x;0%gqu|uBSi?T4atQ zavgGB{LNlC!kB}GA0eVfH6m*e?A%FYIYf-ZGyjJZv+R?c;UZjd0U7)nA(n)JCKpj& zGuIr}Y!pH=A9)9{^Uh=%SRze`_)K{sVFqTZNeQbPHJX2ESa4&xVAf0uYJlPy&Czxv z=H89?8I$oZ=Ld}n@RD&9FbA$;(ud6%RG7t?St702N)@j!cg8_|UfUWpPdrCc{hjcb z+`YP?lm%A)z&nT~vBYYH`WsT0WMg|ctptteCm^#tkm{;lqzi~Fogf?CMwoi@eIh^AGO@>n!8rXnVx{a-O77W?}dEo>a^%Vax!5G-L8s3DAny&RG=rc;9H?NEu^| zR(PFS8_2tUnJQLt3yTqOSmYgr2v{yqQM)TiWm@*#OUcMA74+&kWgAsk3EI-eV<_|> zEK6tx;+Z(^e}jga5ujnJJmCjCF&6Kas~c(nXEl$vTEn5XphxGSs=fXd{FNJ# zQRsiXb1`?|p)?OL;vlhKMMqF)lqXRO6)Wd{uDT;SLm7JWn)L>P?1b#K{a4*oe`;`0 zbcJ%Ui)%P}2RV;J(x4(!lzsEKeH`AUSqNy!6-uB8b;=73;6y8NU)y+|y3$|{<9|6YhX)ypNkDGCvP*N`v>bue~PY zwc7BeMp2eCkZVT|9UXxr{R)QxI=$YX(Esq~kXeWK+oU|yQbjkfKW^|ivu|%T3WY-? zEv;{d9z;U4P2NyM_jcwyYlN>ivVnWL!4;W0WLSnn>YT2+z(YRgimtHsaj5%tDPpx0 zXg3<08TK8 zD}ccX!Pi+A;#ECzaf=ad zMgM&X=wxKGq{TKD z%o10#mKdpn+X_f+k_#fDH@~uF-@X>x^RpP)l<$G;)A@$%#^GntQmsTp$OMfgjrB*B}B9wCy3?>sqHxxaRrhnzyNoBkZXFeMhtQ= zSeqhP0+pIPZCV+od3ccMO*ge1BOJmTllOd(-U!t#V`=;6C{O{zbyEtJ?F}_!QDCl+ z0y&<9q5vv`>Z1s?#C|z0=WejZ=QnBUBq1rs5+XpP-T=ue!EeSuG zgFib9vHXWC{|Y_U3lYE5VNSieR=?i=@W%(U?G0pBKOd^ftrkc3i7Q%5*jh{J2uLBw zUo9V4tV!bx}IUaD#LeSs9{Y$e{rE8jp)L_z~!c#dk(O~v*?E$1Lu zBZ0F^&|_Tc(JdZw7jm@oM%b~gi5xvNiKU|0?BR2+NW^AuA)p~P;u&30*}urgGR2Lo zC5!}6#8}B)2r5-S?zB$aEBV-EoYDuA(Z`hd`)#6J+&-_<`$llKw>PmyMo6_3iyews zK$v7D6;=ze(82B9#6EhQ9n{~WXg~xzcOV$t?RGB0hysvt-bIkwVv1lY7oy3<;xO18 zJc4ZiSYcWOQU6cTxyLj4zkmEb?ZnKSPaB(aPR%KE>>fgnbEqWM9FwFeq*9-Ia~g>y zNm5M*sU#v%syP((kyfd69wAAk^YOFqZ@)kHcWs2L9-NJ4Shki38-nu(Xju1m?o=;pha*03FA;Mb=Q1&3@qB6PMM`PdzB0lB5l7Vg=@Zl1L%@Q@dxL|2qZ^CPmb zi#xFYIrx!Uf%7MRvRhHeT7j*oh6(;syj0}mudG#mY6X53&+g3A``LN@B#Q#8^E8j1 z0#Df)$A9j;7Nxm&^miu4xogwhTVbz(0*W(8k^1?}pS}DJ&VJdiuKnrC8?vc3sF|0` z;8}UU`xB{nv3C`NVGU}^xAfX_H2?a&b^a?Y$)&Ocn(SW9=O|Ta2S`d+OUvhcLFs=` z^}m?bSCo?X_trJ(=ey{pA5z~-eyYR3CfgsB>MYW*)a@(g@m%`v3XJ$%3Y~bY68>0X z0^I$P519i*Yv6vF6rwfZ^8j)-2Im7X13(!lzmI-7d*){MpXocRF7sbKKj?hGp~y9v zfinCEioSX_l|FPhT1q)wtoCo&N%R0JaLRZ(OlML1>Rh$eUFx6ZsvTnIjkm78Qgd!K zJ9Df$$M(RvRb`vLT)XNy{r;J6@ypu_+EXe1WgDl`8LyX9j4yBe#Bbg57%}eI`S<74 z>yk~cDhz&nc;Z(*vv%$Ee?Wq+S1muGzeGbTAZAju_a=s?8z#?)C;dxpRu~t~i1%6q zSKGN)Axqbr2Ul6UZ=AeUX~jvi12vH#H51p(KP8b##UG5F^Zx284wYz`IHgYJfjxs1 zy@hMKVhKsb74(If)$`*mge!S2btld;j@=~aPXsk{uS4-Az(;~Po9QbM{W1w}tzF#b zr-0Ng@ye)Q^;jx_Ry?rulvz>NuYf|_sA@ueZbs0wp$^Ie=};8)4Pv;Q8vyH!x%a}z zkp{d0j?Cv7Y^VZzLA9IR(`R+!<}D9x=y)4&`oK_RfKleqFU!KF6KB#J&g5qhl&f6^ zgu~k6NXNsu6~Z^gxzndl;q&GNsx7P^jIA$)}n(#jR_FM=XfdDAYGfEc1i%? zW92XoiDF!*Qi1WpzoFPTtf@&w0ep*p;9?z_J1bacHoB%hD~6g-r0vBTJZ$KTS>gy| zk(>gJBayv`rcYkfA?+h6jDzXbSrR~}t2@;;=h3HBYyNWHpwY(dv{SSV9Sa5zWi=gp zb9igb9Nsj~A6kQNx3qJe z79=wM{A;` z#Q!w|kv}LZDf)%#C*Z#LQ$a!63YHaZ>p%jhNIzYD-OJ6b?|X6&y0aSaxESCK$)K8P zRk$ToE`haM9p4m!5RpU62uPC`Xq#FR2KgP`Y})6uw{9B2|1NDbs=E5t@=!?lt`g?{ zXO4ja?VH`ABBSRT>Ure_Ms|E(kLQu<3?kQIv1;7GUE)gSSW;L>yBv3*hKPE-U!Nl+ zA0dNH!x;euA)>zZRXoIx$#k`|)7GrvFS2AYRd)S(c4qq)o6CF7kX+bC8h>*;O`2{K zh8-W0>!V@AQ8mKCApxZ|NobIFoZuo>5T;~Vpt9XUSj553{8N-18W2Yel0v#b0WM<$ zjwD(=7l#UQ)^hm2tR%Lq_vV*Um~JdXAzyAq*1!mj$puuFQ(Q$L2OF!T%~ zcrIxZCzvb{A(!E=#)(6W%2GT(Alc+uW(2GR(s=(*VbkyQ8 zI7bQ)a_?~zd1Rw(C=m&q+QR$Sp^B)V`RX`lNfCxRzUKl3e~eK5OwZNrMwQSE2X+y{Fj8( zsEQ;B2H@GC+l4kVZUD<48!BFu|5&XdEorCGjsrv0zE1qE0^<+p!9^@xNIUsH;>hKA zUIQ!hG79L9KLMw)-om`DB>G~lXxZo90+Z(j!~>_NQyfET)jaMH%Oe{Y^X8(nf(O(B zz~8-6+V{^1vCFggK97I#3)-(vZ}QWy}|5`3vArRFE{vJip)}kDgrqh;ZVD=8@Z(pgr{^Nm~x8 z4|jn7EGconKeea3tf0a=XmIxSr_1|Wu;jN?kjNEd+J$C#BYlp$mw1Te&%i%slt73K z%T6;3Vx;wY+{cj$CY$7s_dVrS72~7IF9p*9aMePCe-YL z2`*in+Or2r4HMxEU-R2w+uYaAD-_y?f#SazzGf zDt}sDTv?;to|O;NY>flGWE%^#YNglD?FQ9iWffbcuZ?_`RY;S9>)(8)?*;;eR#-%SA&m?9U3!Rr>eVQ>MM8~15$Y8B6dA~R=%8_{~B1rhE zjv9Zx*ZuDHmv8tx<*@Nj2An@4eG#6cC@_#q2^K(~PpYIscSx?!W^ugIfuii7I=VGW z&>F#@_@9Ayz-+0(vn$xx-lxc^HHV=N%38#ZM>nx>WDgytXj!1*X-q)!!GN5?B)X%1 z@3|=)OgJH-o6Vp&8wr?O-VbXq(6GV1kbiL!ZE97Z>X2LY%FD-%##)PaeOXZvTGqex zH7X#mSy0~dr$*CV0?0{Xk=;{3pG5=Nv66~y1D5pftj$jU6jwHYy@cOggZDIz^T`hN zj`d3*216_S+{Wn+{gP3Qs0~d^7W5L6a$_`m%0Wx=IKdZ%G^U>*AGR(YS+KQ_|0ZJ* zxm9I(_A~pet=GON^6g6K-b#qot9vuKO+0u!uaB64B2E(e_S=kD20hgVxcLEQ_3eq1 z;wJlj{CSUk?;xpGfDg*Nt(J5jq-m;|b)L+*&pf5M9ya9R@|qEf)EwZ#WFC}(;X);_ zDcb+C1T>W3fOo5JCeS_l0?9(!kf2}o!Kka(koR`y7!#3kcok(^!%=z~iYToSnG&O? z4fZV|1e^CXHZP?1R$JXtlWcX9x(tGE(9co+deQlD4_i{z!in$4oWkD~#;N{B&5D{f z{SKWW5pQtIFrtVt6-6X{UqJe7*Cmwy9iEQfE{*iLv8nDXp<{sbb3Ohi=$ZY2k*{DF z+uhKz1q>FU$OIE{;n8E$gSq_1=8+u%j1S?w9I6zKmu#6n?qk<_0_6?#jiaoEbWI?* zuK^c;K5Tx2;{hkmwC+&Cx5qdzOA4)_($fJr)f~5GdURB9<8m)88!+w=EYODrGfR!+ z>uPRtXk>E)mBVXpBdNu>=S;ex8Zs-u@ul?Vd3kjWU7_reouKjgk9HKpWRtP7t( zqIH@Y-6p#lWwYX2SRN z#0rd*xVftqAnlT8&~C7&=Q7PV$bwJOQ>CO24YH@b1Vtuh_+}hmD96u^L-!N5E$V}x zf{is({jr}$N37#QF?~WJ&b$@JE{h||;Q(Ic(4G(acend6z)+O~*^-mDtBeyED+72u z77sq6)c2*3odnXw=ogrHDhkJ;oM8c-SZ?%a-M}@Db;~iEV!jg2c|ub{Ki4{#A;nLE z#x4?-O$^%ijku=}fzg-sQ!P#2XDl~0sj_44kdhzFGgJ13ncie=w0$66ZL?<)4+$T%{N#);gOXM~U(GEnRVbf%&6L@jw?wt|qo6aovkY zQL8i=J|E7)x9&7n`y%@2d4F^!2mr@GS~i9RN#Ix@$w>-2NmRll3*7-nZ?wq=O}a2n zi$NFPZZPT_-}!weUsss)RduVBqvVb0rvS$H#$TiX#B90hCIESvVDhoW{(_7YirUjc zLgzU@@+--AkcE`YMQt6d^nKya#g0I4I0Bk2FwGDgk3L zI@b}jlfbfuk7UMtfSj>N3iGA5fdFpWA^0Xpi{;@mOV9Nr3}`1mZ|Y-=h9EJLQ)uw! zStsRoDr-D}AXPQaMw5~yFkfzTw3_?_G|7{ab1GdAWh}h#bq&FcS|(j||s3Yq$ z6;=JybhpU&xcQx1YhR6qy!yIc9Fd?`R1lj+tdV9M!K*Y!A1%~Wik{OG-|+doO&^Zo z3nkX~z8H@>8&CE^BVcq{(b_}|F;B#0qkv?p+zUX$3zd#Tysi{p0|Y8U0Ysk%>0yl- zHng~9^yze*KB~X>Bs{`=6emHHl3~CwLXm@cr&MeufER@sH*Z%L0qakcZ+ ztqHzQ6X@}1V4i=2z>)KA}2C8p?`f;iG>4=0E9Y3`@!(M2+8^9WSFydd= zsHhKwCTES3cLYot@y~`$PaE*Fqd2jYu6+?dIZiJ|jb|IY&0G;f1}z2v?g(&k(p1ll z$cY=}E{vFebp3fMcvOn`ZUm}sF#8(lO^|7EuHq`vNAsfMT~IjVHjZ%%prQzy0U66d zJfPgH*Nw(1bS1C{f2T5nBypZ5qu6F&oEsS5C2KgbS=TI_U`Clco(K?vc&oiJq{AO? zz79@hWNt;t2T1aHunq_gYx%nQqw5wroc{CSmPjWmrI#8y^Ey=X^_lYG=&E9H+@xo; z#B(<>BkFaF9qDuS(K2~PA^LYDAbL*lCur(2Uru~EzG#*?C0=1X*#N~dqLxU(`%D9+ zMB#A?Cx@>}!}qvIvkd`!GS3HFeywAqTw9Vm3hunlAtZJf`Sa{Q>IH-_l>7OKi2!WL zgM$V^Qyyf9!LiZ=vO)smQMd<0a$Uf`$9CAiA_e zLObG`<@Ay95BY(68j2P#mU>a8S!<+wS&7JIhWO*9JxC%hsGMnivvE19d|C!l4n1B9 zQ&8}^fS!y(4jAn56I78@oeYF6B>+W&Pi8_Lx?y#3iSXE_z4Jf)XrImX}D zFDjPf#f){al4HeEx=6a)4aH3`i5U!pg3;4>2-WnvJPA|+aI$lCQ{*^V6B3Hzy)p2A zT07#;5kpAtm#^%V_R<0XI4+eQ%Yz*xu>Ws>Ckoh6Gi%w_4^K$v+GL$VoN!x#+hh0 zMWA?+rk~(#f{8B$#7xxKnt`|6LDE9$bK#sLIzHLofr=W7Sm3I@MEA|-wV`1keiF%e zldnE$^mH8lKC)6B@b69d-y$BACc!By5fOW!D*;_3Fr%BlR0?_kjYe{Oq8uo`0_&o< zpFzCYnbBA|O`I_Ftk-al=Q=AfxJsp>@9{uH2Rt1@H{2L93OZ!V&zQ{ESC_BZ34~F5 zui5KeKU{oB0k-@();?<(Sp!I~#7MmrKW_iM*xnR+$Uyg;28|>yC-R~WjTjJpHAU1m z(j3RQ3N@sr+)`>w|BZnhTg-qh>v9!2Q3{raOhM{tt~^`7z0?kH{= zBu#Q~R0chn2d~-map~=L&JLvNY7P7p=Bj-_?|cZDg?ApHZSq5!RGE*y- zQ|f$bE!m&^oOP)r#4Tee|x2I zehIk8J3ZG%gBeszTWUBNptj>%#i*H+TToS!f5yNcG1FKxcLqPeKE+&pSEsJ0aeL{rZ0KDrhX-4v$3`$b|N6qa0>6BHeehfY#cX3)i@qN zP}5IN3zGHqBQ&3&QCU{h(gi0A@B4Vp6!1b=22uOC6dz(jq2|--pd$YTMG4Ep-E)@3 z7!~I%i)I!RiJHjMLQhA1Zg0~4oK_8(kjCqSh%`W`$n&a3rFgq+KA<+=%7b!EMO0r>w2c^B zM-sI{M3oMpA2KaR`?OqT${Op=mw^Pz@PU3ZTQ2dVc+8neFuT*$3?KBTxRN1?8Ja5` z@lmyp7>?5)(g-pydLONye%4>}XZnFu3OzMoP$)OcAY` z+I@)(|8k7@R)i@4qG|rL0m-(W;d|iPJ+uJtFwB?YBfRbvwpf4qa<&!Ld{*V-ISKFc zE}6SJ*Ktpw*2NwEUNFQgAe#~yORN)OmK$b1Yq+!`#dZJ6u)QHIQ!||#+{^!08~bRb zwdJRXQX72aU8=RNqrZmhkh8kxH*L`08y?IosM-*PL7v8cEu{dNEW-$9c4C0!5c)*$ z)Q;?pJz$tf0nf}t3{;(vFi^y-8Xh5PXS0MJ?`yfeunOJ$g0Jz|isuB&6AK^$=)w|$ zYJbcBM>3D?ylB@8AXdcQGt^eGj(-?v!sd_@B?WtOrnl0@P&gBV4S)ucfuvV8z*kX~ zKL?v^SydWBEp%ftRH?;me@5KUB^6v|vCH4V4yr)JnY+UmqR(Thc>4z03WGBa))uIo*o}45Q&%<A+FdH zF(qep(M`jtrSQb6j{Vgm77YRW&Z=nMdsuxzzNPF#)P&aHg#U4o#hO@z?lF6BiNi=s zkVzAIZ88gnym&_Rp;5fCTpuh<1(lW}+LBg`$j5M2a%E@CsGCHjuw@WHu*3vet!8*F zK1LjB5H6}>&|Y#u=m=JjQ!arid7)5%($C1KjHCf%f)@kO?2sHs53Srqr9x^frM0%Z z3JTRZsBg{RVEPk-LL~*~+j!|p7&cj-3mLF@c*1c3Ib5jDd=3*${h1m+e-G!AIYe}* zk+~*KG(d+Ai>RlPOa_|!6yvP6Vr!a5PM2G5=9UFZS-#%4mLUv>C3c2}yO*;{bZ)G_ z(J^nMx?9`r#)YP#&EvuUYDKQlYmv0TI@bDoh*B&!6oWqn35@7pK!hy^3=Pt8u_{8P zdl9eB!Gp6dOv92OX&&^SuZ6!2i9yf zH~G;@2%Tr%*+Cp9Jk*9%FRd5#Q%r9bq{)&tHSaU3`%>@h5byEubpMv`{PsYuP;^A| z=|dYun=P}CRsv*2Jn9@O4NY*$uy^A=yB)Hcw>R*b7!{D_nu16ojBJhx^Dy9euWdAF z+HOthk?hiJ!pL#+0(nOX2r&RCLrT%*N+3tH#9f6Upwu3xTQ{vIJpw7d7YJbWE|f6$ zM_`!8056tJZM*Oe#Ocd%u1)e<8wR9Xf2w(<=`z(t(4x}Iixv5 zHui5`W0?TGlm0Ym&QDgNC6e{)W$w7?*x7dR#x_5bkF2%=DRYANbK{oA2ZJxjg&O7Y zceko!*}i`nf9=`MCD`vRt3$tAMfdb&ZdqSc*06sNZ_Pb$++PAbS1yAs;$h_uyz#LY z$%wW1m1ex+w7EW(l-CasxDwKgG!!8NP^N4>q%epbbQ|df4EU)rEhf@{02D^JWx==o zX2G5g%&=Svl2{zF64*uKNn9*tsBo1$a6avvv&xvoxg=JB-msix(Dpzz&*H2euwg96 zsI6_TVJ=afsS-d%-1K(GdVJ00>#cN0G7sSVb{yEc<2WY7wwAp9=i&X8!3mj@H<`z$ zGB4m#{0cXPG&&^j&HNg$WN(Q-_q+E0B#1T&wiTEv_v*|TQH#V7PFYaU1voyyYBk2Q z;+)jSF^nFq9}@B~V+1y*tXTI-YpucTzz=G$< z`2wl|aNZ+uX6E0*aOJ92t7)*xF9|OY}`3FC(?fnXS z%|qs(-Io&4&(;hFf%;+=Qs9b|_lNIztuB;enQquUC;L*d-@Y97tL&BXn;UmeZ7hji z>0VemI}rZy=$u5X$^8Va-K0c{SfCIM|x>qEYf6$Yfwgq*wpq|6|$3gT$^s|Lr2C#t3(Pn@y z`c5D703~G5QO?rhLJI-di0V{d4OFxNb}UGVJl7Ia<}j$`2RJdWX6^<$h$$0d%DFWtqHn zb8;2~`h~FDJmk*OWVrlewmf5SQLeAtzPupTyL#gu#kZ;v;l@|X*(bZOtM2u+DP{KA z^)HH7`rZr^a?3YG#sylYBnmcJ&a9-@#=ZUSaD}+7-dPx3>L0>ND@$^SoKL+|0G7oR z+(-g&t?>h}b=H1R7X^R%K?X}~%z1!5H*E%hb~Xa9CFHHQ){J8m6)EVU?cSha*zpT1&csLIN{7h~Bm^*!D7WKsQw!E;`3&pj(HjXSgN zc}G|fA6cCpSG~_+dCjKOHisvhcem_sOaqVn)~=3OsXe(KoF);2xj@eC{k;jayJ-N8 zU-%#mevKOXyQ+Ij5YI1J_7D#Wk)#PTa)r5|5mXm4#V=3$`Mxs_gE@<=BM^N131U3NY z_G|uI$1oenSS%Hxykw)qI0Jg15xvlD4knm1_cQR+Ue}S^?38vx< zsED5wVR%B0(pHeWv&Z#-4ex-8l0t@2UP~azYPsp3S^_s_NTWuTZ^BYYXsae9s~!L) zrGVw`C}-{-F88?MJfiHKa-wM0p{pti<;a<4oq)Wq6$PXgyTS3pU5Fo3wo5akm0 zzedU%2|&c@|3ra~Hz<2dX|K7I8DQx|t@1RT#%BQwHy9{I%v*5az5XJ2Ao4&V;J}R{ z%anCtuM;1%+YcH7aJvxD^{}v#EXx~1?B!=ZJ_Z#m3H<9}f``1r6KgIRTVcK2?nmp2 zynPEd*C9ElT4ww^KkV4J*{aMrpe*Oo_3e7e8HctO^@kl{m!Y}DQeMmJ*}>gCVHAC$ zt?A*Pg?W`f{8Z|9J4`qf?v_%AGk@1<>*V)V{Q%UJI0Idf?v({`fje5jsS;)K2pEha z9A)*=0!^pDhIN1eMww%Q_||2wF^I@q{zk4wrUFKWHK2UmttoK(ePB~($+ri<8Pmlx zy~gIUfbAWi(>(O8bh8l#TFJnbW{^v3_MQc>kzm)|(c4dcw{3Z2e(%2xTPw*e{|uj->F{$u z(W2lXb1Lq8N^b2wE={r77Uj}4wth)Nximlnr^5%$@(_)AK$NAhf%Dtl85ckrz!pYpVH0w7XACI4KRy)uLC-QqVvOMaaRdlV0X>M|a?mQa>BIef$q!oj7sx zVWHcO6m{n+ZPbOR;I1s)KS=sdeJcIrtFJ@F^<@XXg%$OL5%jN%(0g8`W&duDZ8#iG zYHAU%BEkYTSt@e_8k#O96dpWztXZwg3*3Bj1{B-2pfgrx~q!=ueM&MV@;3 zP{y~uO};#2-`vUtZ+(x~J|P|UD|r6&$T`2;r>}cWUO(Pd@AAaAl##S=$)&!7#O1e# zX1=PMy#J@9e@XAv2x${Lpji8D;$ic?xFrdPQ@~Yy_S>x9uhhwS4y7P^^G6;JJ+CwZ zQPGq_odE`XLP9ZQ0Syegv)@2M!Ikux^I+uwizy+`$N^2|wNwC&I|4A(tN%-XQteup zVeo?kk#xP1`alONY{6ejmmkggg_y_zT^3|12KUs#7BbLqB|w~qbhbfGvJEVL6bpd8 zuvs4&Y}}~sS;rs<8MkkSDrZh*1&F1o4kk-_eCCN~o15MpS>w-p*>0C=ANro%8NP6! z-sEa$wd>Pe<@c<1oji2sWc)yjpHE|eaYS=U;}!cQC)>5TJ~~$P=UfzAR$&@|9l=Sa z405&y?F3ym0zqM;kurO(7(8GFe(whFHxWLvrTI3GU#ICW{ zTT~fdM6SzS4LXsvY;P~M-V)NI-q4eQydKa+25E~6jAY>UJ*W|N#EA#4&>J^dpt)|& zR)>O=c_Z7B68(7UKjz`IaeIu4TOzS*jGeGlypxS|RzH+&SaI@A-PhZtPiu#Uyh=|h z9^X59$M4^XiK&h-Oui4c&6|T#o`$DbeU4bMJmo6=gQNF{jJqv*{14;Z$Zn*2a2XKq zo~Bdpb0y;hmk%m+ShhWAwieWE-DU_Nb5ul^p=@TM?Vo}Cos=zW3O`}4fy6tvUcWt3 z2>ciVTv-+;dV%P^)9TdA>$jZg5tL}~-Wo~3lM3wxP7F9K9>4R7+&Zg$>E5E2C9ix#?+*Et4h7%7SDydc zyyB^=?$BWOkOQ*OiXya*FHnRv#y|O- zGJMc=Q>RxDb<(dG@9l%ElqLD^U2JBvGf2$zJMHZkU|#2ve79}o(bU!3sTs1Km6ZL8X}q-6U7aLGh+#78Mx8QK4NxA+7WowA9*xZ3{xiTn5fa zIkN(E?sKg06ut@%AP^ZSK%k0y3*h7+9*nSqc!lcPD2kodx9%-y3Q8LX)Z)2POf!hj zfbcX$USa{_F~b1xowp^$niIEsi*$o90iGe`o5EK0GD*n}pu40be`1s{lD{h`(cQem z87kxCdKNmPuugXS)4vUOI$!#(+IY!lL;D@-Q$z#V>mRdW#BEg5ps?HD*XUg5^qS+N z-5ihqHg>#R(07|~~7 zxFCH1X`qhrPT|XarLaUL2rERA)07}7FF*j2U22tOn$14|8+znn1;z?Wnxql%Nn;k1 zlcmy9wWtwkfo9%3NHmNeV=mnJwav=J80%U`WEL|_iE;3PW4$O)3O$S>EZe>wU9URn z7=18F?f$F82QE}U8}Gud`{|x)?vI0UIWA*ST7?gvG`{p$76vZJ*|0Ps%t8FvV-KYh zZHlhxF|VF^xcqb1Go7A~L(X=W=bAk;9-Ah*E+Qp=TJ=b@VIj60BhIyB!aEHT-ZAT{ zt|5-l*l-?%A!&TEp)nQ1KyHaI$vlHqa#+o9yL_;o$dU+@eWqOb9{*QfjPv5|%A<^Fx>6HjIs08POTCW@3j!W0RpXOIe?Ca6eROFd#EzO zxYCz7VQNh9kYU9;G02_;LM}joD1`@`j05;tXHdJRfsyX^!@5v0w^ zg-PVh2;%3DRqmL1O;G%jmQX)rsqZicNn33qnrkqmOIeZHljDvzeb;|+;?9Ph>1xEi z1;m%;Z`j@OVVm_q|0Lg8h7X8TgVf_OVD(TI-;j_@3YwVZe*0EIrBV(U5d#9IgyG7-VLUo#w^+$Cqr7|cyvEM>DMC!|>= zJ({QRi+R%bJ>)JbPM01$H1?>m^CB}aS}|02D)YgD4ShP)HfF^-$s*A*i@r=udS{dQ zH}zmr;<8n?cQw+Mo&7|eq{5i=dL2;1R*`z{X^SAWfipW`)qw3rsUeTRSq}R$2FLp~(-l zkNVmF?Cj65>@8}AcJ05{`kodGqg3xWU$Nv7M;cw#PN)e7zZ*TxxELjRs)%!b*Vxxh zv2r{8d3fD-l|@&ISx)~7M)HT=9*+O7zqoSaTnj(zkZEZ>V-rIyKpSEg}@o<`3k!wW-YKKLcLfiL`N=e@(#N3Dl`5{=U%( zfrI3Qs&Z~`)G8&XO4{_;<6FJkf=M2%^Omdx*aZVgsnP=47!L0)Ip~uM6q;mc-V4{M zv1xxmx1M+105rO!n&%mwWwPB>imTI|{_7x}dYG=+5~gC2*V}n@ql@)uSoWxmNTbfi z?by<=du!@ooClU0d36c;$!5E3un?%@vCC4w!gY=Tkg!yFIRP ziw3FZ5ny!i)RKkhS@Tudz5zT7Jc}pUaym_-r4Pc%@+;8TUeG{a+Qt9ZyK*&#*WD)| zvgR!+o1Z`)ho$iFemP2-NsTaO7`v|GQfe znrS&5gE4Va`wzA*WS%^oSbQ#842?InHM+K}RC_RtxHh3* z?aL}g88o-`(>l}E@!^c8-G@Kd6OOz={5vX^~>}G zRYAL<`aNQ;|3w2SM$G4Us+gkw+P|VX^2PEw6ja1bV(!<7-NyPTWl<|;nI(mkcLRc~ z7pTQcR@=Is_!fYI2G4l_ZXTsjlrp~gXHs~cFI@K(u>?Q@^==4d`b4GiR|YFI&37hS z|MIPKZ=h4%v$t1#K%-9IIq=XcW+W`y?U9$gtIPR1mrd6W9rOF?ejh1ZoZOzSu~k2# zv*z3B^7i^qSMIorzC3%?x$AI?-iCK?GVGshm^(`gvGzS=MD-=h?mk#5x|2mLn6Xds zgjAdKiX^~wxbV(65oTcZM2y771o}jzNr0ex1w$&3`1r?PQiZIgQVRZi1yqw@dVG*9 z#>g{(iWDfXLfi8&Qktf)uxolk9-@2|d&Nbq+ z>!o{V*Vk3Y`|WQ^s#t%!;v2B&gZ#3|LRYY9KvrB`3bu zJh9DGpvuC0RFw{w1^?O#492h^!vmJ{;NS6HJvq38rOYcJj13uH{aw<%lw8HKvySz! ziFa2qTHIvd*rF(7q?=!Cw_%0-Qo9<}aPk3bc?czaR=dI0waY;5s%CSPU{Fz}+`aX1 znOnH+uVGFM<`<0~LtWqy;Ns*3+`?4zAcD+6R<}egwxmJ|?wa0~BkJEP}{EfmQ^k{q>5tv2WqbXO+iv4adB(YU7=}3%$3TXfeO1)6@BGL;o1aZh2%nH z{<*vd0MsRYeEPtcIaoOkj6BgKFwU!V0lGBtbAv9=Etm?b0c2^e&1S2PsZfTnt{IRq zFE9`Rgj$1LGlNRg^PSd1*1*552(|yo(&*PsR`PpaH&s^kdw{mwhhVHJ&d0u^2a?#D-!>_gCV+eE2c1q*FXYsy< zt)&!2z2zEHHJ`AG-YCid%Wg3J0{V@t7@jtS|MItEuR;=uI^PP@kIE{y)p_LY~p0M;-#R<$Z<;uk`y6L3= zMSQQ6ZAz{MRjK9`LsskG64jcpP@4tn^Y`E;0ZaraO#;iITY7myeVVzd3^XAMjh+ik z3vccURa^M}5z95Ask?6BSMBV4KglzT=(o0KIS6O}#k)b4`IFtIXvI-Ko#*-uYc&m* zweN{odKs13{*AxDi~-&Ro*-TgnaZs)I#eq4vCK)iCXx>arfdK0qQ$$p1tw(W1(97v52L= zES&6&x-Ry2r+3F_s9nkGUw``<{(f9eXyKK&lCBG@yvZKh_uF1R_V4N>j~gi-^X-Ff zw6!}6)ikeE1ZdQ4?l}8Z#}1#O{vH(;h-059Bisw)EoM%UpVX+ZfC_5ZI)U&WU2L?< zsyfU`aCvq4e_Vq@R(2kG7hhwVwY9%l3gGa>YVgVR-!e>-=V^ee(vy18nv_34NNc*G z#t`Unl~V;M>#bm?)bCu!nz=m_O^%Gn*WLMc7kypTIzh{8hR;qhxjj(OW7&%P!0;FQ zz^_Rx?CRj}sTJRzM~C;WS|2x-yuJVT{s%t4wBLx5dTbu_TUTbM%L$#&!358LE?{_r zI`T>-tj*4D*1l$59WbC?b*vfSE*rUB5B=iaed|~eV_MPVHFCO=NEMS#1BOGGe!akG zWc=Vp;6oOe){QY{yxtogrSTxE_ky>-LHqwC>E(%YJKaIpcIob~=$XYn)DXO>^f2QODuZ|+EK^lQKiZ3n4) z68<#)VCxYps3eh4#?KLnh#owMA*po0~M1Z z74gio)y~nmq6H1u64R7Tx2$RwV20}tSYqJGjW=NtW;G_Tti`G)Kntpl-xwiSBXw?L z_fGpk_Hu2ROf7U(U_*lC^{W1VXrohNSKjZs9m(tRD*9!4b*(oZP=24i6uS0n%;oKB zM(SH$Eqdv*BYttZS7EQ=vjsoQalGTY@LFmB@!`Hwy{09WGn(nlqiPr= ze0|!OA@rB;mJw6yDbbzlEn5sJanY98K;kQINd7ss^r+Xr-X|SvJT%VQ<2=y!+xxOz z?w(y1*YTP|==;>>)K-eBtbKCUoz`YMV%g(SZq3%~*)1OKrJ7#@tQl@YQ@Z#Dit2Y7 z@}yp1LsZpQFY3&^<8*GsL(eX5ynt=5Jc;EW)a{(6XnbKQolTzCJ()4^^#fqYG8ewX z81azh%*Sm9!Hu}-cVQb}uiC>OzMCEMDu#5(O(#kB^V3Q0^DPzA+3|<2oSQzmZ}0{& z{`(!pVEVPxx5poB8$H|OE`QQBZ>qmR)4A~}JEq-Lw*5at_2`)Q%Y=Fxk6FIAa;P)4 z9@52bioLoqOIvDDS`==Q_PyB7ubK$_Y9@iypD!!R!{&B}Q|bTdMvwH648+byKN?5` z&&L5m9!AMqUv^6%e2tavhQ_Yku!>bntLLk%?LNLL@bdkaInDi_-@WgRIqP}nndX6X z$&Tz3F9#!fU+36C9}levS-Ah_aG>AVtDe8*XMLXa)+e>(W|;+LO<3mi#b+&QoG$V< z+Wph&W20Q+QfWkZFTka=2EO#eP&OG7N@g!&}^{ZEW&W)s0k5#<5{*Ad8{oiQECA})y z^h|p0Y^Sil%)~HZ2~^c38ej`8&?i=-kr%&TwS4@X@hGwYee#oC|3g~Q*>1Y9L^t1f zYoJ1Q(UwSe{gN^GM4$Y7#o<^|Eikwna1HrwAP3ZP+bz#w#`6*B)ju*{bX-m_BJDP8 zS~J@c@G1A@nZkt|(mMM)RwwzlRyaP7*ru(vQDHI1&-Qsy7uP@E&(Cu22n@?gx0`&Q zIK=92U7K^&TbU|5WGY|0S=H1gQEch^#8T%Yxq*Uz@_!VacUV&I!-r8B4i4Z(bKneT zYGrC>h%-lDD>G-}HYb{;WdlWAnPC&n3e(&c&eY5hXHFcME5lXpNX=~VdwKbXzs_~R z^E~G{2hQhn-(S-vWHJaw0T=H0SmKhSc5h$mh=>+`mUcEA_B#S*V~l)sx2Y#OXXGUZ zq!bDYbEJyedtMPpt~5-!HsMf-93_E3D!;%GBYS4*qhSf^3NuuIBrP{N^E z{A4-u)C;A60;7m~hL?+UZ_wql%5?6R$=}bFdvaIpQHu71G?ORk)-=kg2e}>v)WFh5 zv5%j|-_1&(B$IOP+zV>gaCm?SKDaY;baNYWDNY$IThe z=KRvv#kKW?we5|a-R<39zrSq#nx5M2-~91rVYh63t90-OZT!cr#ck@hnb@`UATHbK z+x)S`4d(%F0Q>v(_MM~>Zb0tVnL@6`{ck79-}s`Zt5-f{^AV+4oRW-{S5H=&Dp%WC ztM9&#HF8_aH!B~0ucmChh~2Jm`B8pm`xfDQ!ubs!(u!;D?5Sr9v1Q$%jg2?jt1h+| zdUrpu9;tKg7&|^UXgJ@hKUrb;wnC5o=GdLC6DbVKSe6-Kz|f;x`9iDAwI;c%eF`@} zs$c)2m#`!g@=ZGUleGIB%5_QU)F#qqTgrY8Ww9oHm?L4djl?cXDs3Z_Hs$yIP*?b_ zFS~25xpGwRqmgD0PNUsJW%iWR_fv8|&uQ(RHQn|$`VoEP2TA)!sv76I>>^QOFIr-o zg4(?&yGs|_trFXMr@Gx_veT-)^#So?6#0ElYfel+zj2f2+_^J@Frh0B&`P7tz^SUJdtGM0@ zN_JUEaY0&nP*JV>fYzX~!Tb@ck9Ia6opB4N-4^}4=P&tiLi~r_y*opEt0TN0dz_&< zIX?T(zS{N}Q^)L${E2$`gT?!-9x7R7Xdl0hIT-Qp-#-R}VQ!%%%me*TM8TdxZzBs! zYJ2xE3fj|9Y7Y7K)z3R`p$~@5^i&si-@#aADx9b(dVddlrri5|&5OQA1_8bKCu)la z9-CZToq1ndGV}~b7FBepD;+Mhzo+ffTURz(;!^1F#G$_YLxp>7*r(q5ijS`d?U{;> z4V9C%p`+zKeGOI9uZau2PaI#r{PZSad-YS_>sO!Ok%YvQoEjN(?dg&_=ldJ07rLox zj!&JMYL@zF2g7Ikn`*xf(XDPNIXBm>jFz6MI6pD;?BNH7;%j`uX$#T{~D^DoL`o$1#5mo@fSeAp2$diQx}hNM31&xs2) zj7-VzkN^06zS}B#Zv*IZx?7guKHQn? z!)#Q$EqGX%F74`i3Ud9p#QhMyaxGyrD++od@Ob3qwt4B$Vp+dMv~>8O4~=zCAdvm3$cA#voc^l4eo1c5Fk@06ychgX*c$`r3~lF}Mq zZpPR(#yeerh$zERB+w3&QC9dZVK_|5lVvq@^h%>>*U`e+Q{h$dW5a`ro9u#w^{#%}kjBf4S{#66NI;Y0cA5o9r^Z855c$BcmQVJw{Zn%I1(!dU1nRa&@WF zt$A@q(`9fZOlbq<6E|$RHjEgGcm0KZ^rKOd@&llEz&$jXk_xo)3@gehNRwwWuwx`%-MVYdy=ua?#} z9^IG_-<@6@7bhz2KN8vbg;137So&jwZXx~P)I`Jyw(-Mh*|60XyQbrR%;TEAj9bL9 z6DGv3ES`AmRk40$nfFHV$GQMR=_{vT(0q&2jTsxJ47XV|r`)-k@UV zyTUNDjjW3Z)5VDZgz3t}0^-;Xd(PtM#gDbf<6m3algzi{*e56d3P0{xXJ(r*78Frx zn8g|KL-7Wchy=Qw(rhs-!3lNoo4s^f)PuBRr8@9eYcmZkB+Umeur3GsfIDvJ5}DNt z|CJr=U#;X)3^&>kN9uewFDD%R^e@_v*BB0~LMNnM=IX?LWq&fI_8hnjhx_j|www13 z3&i%2mHvP%g}DOB*Vom+OD1jR+*8Pl>1xPTQkv50_te-4A!VXD$n@z~^Beu**}qJ> zO}mnit4|i9w`tuLJr9vL`mOv{F`WOcauLd+IexXhLQK}>GL0-dJD*ai;DZUp! z7Q+cp{8HMk*sFq!qYf)9@g~wtcao6N-o-+tqN=5`B$VTeo1r|vAc z*qKcTG$k1iB9=*uiW4!gi_2{a5AKIR3*GLBx!t`NP4rUyVgQS8QBk~HN}dP1ZM8e41Ij{;~YE%S~s}wg?Y; zF1C~_m3yil?Xo-`L;Y~=GP=7d^AR6PN>*54@VT%mcdl~CN@|QWiRGj_Ld@ap^^P8yJO2LlUH@C6_*l9O^qG1GfYp`NQLL)_kA__eY?GK z!5!wl;s>MT{im>&z)N#HCNdIhvJT7_lARPyyk;yI#c}tvjxHOdy>0W0iF4FfSSA4` zy0QqJCqfFdTQ- zQva8coshMl80VsEZZU)CygH$D|3T%kS@*7i`C2}T*)I4BZn5u0{2(DruyKlfNRkh&(*TGT^X9z!r$>1g7HuO)GFt^8- z+BT)ukIq_Vd)y)S%u_3p2WYKV(#bbx^Pe9Xj`!Qy*qgZO-94ci<~CN|u5=lM_UQcX zdu&97d@3cfcG$1l;iZ}aN7&BfuAX6g6`!*}jqPL@dVh_LYq~hGNqchZ_L0W9{?SVZ z^EZ4xMJ)aqjOJ=7G+Ksi_!rLlqJ$J`3}J?#X8pR9Q?h1XDdqUgq@qj99pg!9mx_Q& zQ>8U4UZ){DHgF{NM?$x`cD~=vgZ7VG?%##&aoG}tQ~B>~VP!UY9@kP9z+V`4$F@|m zujU&o6m}W>&azk+^)gv;DcKEOp}Ukm9;%WUU1%ut7>T&)H4~_(axMbNDS+ z#@y{zzlE7kd$z`{F~kG1visos4>~?R3X3o}G7$grh};bOXTsN24iO_H$6-V#wKu`9 zKD9D#?7+0t*?V2V%ne?1)2|pmd7&vFO-bo8EUv{e=0&`>wW54>3|*~$9or4-slIcQ zWvC#7NHhH+j^G)76TW)8+nhLfxDmSZ?nio>$+GyJtLo3%wo&!e6OnF-S>%aLUAyW+ z-pQ~yMxoN`M9j!fdsxTG<10%ag^o?BWJhIL&CD-HD{)US7;3Fd*Rhl4n1jaY8XFW==cyTkXIE2Unh#aD%k$O^t zOrwD2>ehMlK!b*R#)~xua5ep{Mcf+3bMEJjMAyhQ7sOvzL|g~5@f>2|%e6TJ zECI7*k!o(*p!#F?f{;9klP(E@ogBkiJDjb zmlh0f1g1er{MgrpFW!@!=**u`VKm=(6Cc(UJc$EhaZo@4N`2&bQ6)z5DU7K)kti8QEJDt4%{j!xJyaCzERq94=13#$3=j^4WAjpo z7ZQlUcm#)wSmpp+&b9eK#GL!#U3TJ9DPfVsKlVB)2)T{9@wMdo0^Kia&(l@b-(L1o zbqQ?O0EXW6y_{e{BwSq}Uf%l&a4_*a&Gb7ozEpw)`v@SgSBT@J`?L)35udDX;$!R; znS_KtA<;3!^gl;nu^cGh;uVE~#SmRJCS>Zyc#zs6NCF*l1%wnL!|01RnAH)jPHzr_ z|H*EI96?+{Ayzm5W#`;a67m-+il3yt`@v#h!i|l+?Z~|507CF{Z9hYhKfeO+CxGuH z#QXioSt59cdQBaK;O8KhIdR>>c1`CJzZf9SNFfNNesJiysB}+$syNOC5!rK{5fr=2 z1}?d$1=}Gmf|A!b)HxD0)-L`tDtbpI{_{39Sp%gE^=qG$l$x-&z(8;v7H!I1$xA#KKO=0ekCD3rzcwcw0%$e?_T}GA4D6F^!3ZMJDz)CLyLjj{ee{Ut4_m>bF@rVe<@aH>pm=w1QXeYt};$JN+DKJ z>A|q5G#YG%f&68V^_lv_KbJa7Lcr0;X)a=L4`D+>sIjkY83=waA2R!>$@<`I`#zhxHQJE--a>ANR!7de; zcPn?vppuuV@bq}W<=mnxKxzW;*firK^?9*r<`{?ikq$ImdCd10C2Bt3ZMZwe1pq8C zh69c_10RWx*&H|@3KK&BVmUHFr|3d8W+0BL|kD5MoZUo zI?ySR~RwNMXXQ}cFf!Jan;{B00;C?_{zc@5HgtnC$;uoM%1H8?~BIqwN1GX_W&(z*au9;H0HU5XQfszP(%wxujFNQ z17Wt%7*65oL|_C1+-=N#?~pk(1&yIr4ilh_me2?n=t|I)FBGFd32lK|eR!>LG!ZsX ze=`nMm#{yF14^28flhJ|&hL@GIKW>z;9LegE-RTO0xKBC4yneD12|A0e0Kp0{z33O zk&_&tpaK{(K+ckY+G1eeKBOZG`I#y38&tD-BA5FM7)+>6ZU%1=U;QE0sNbsn`4Ko} z3?qeJ7B0)>qykGW(0`4ku_3i$>3~1sYLdxg8{QkzCk8Oa1k~P>KCqvsnp8|ZuDsh# zoVQ63M#F+!pdsOvV<4cX`R%3-EKm#xzYL6_fJhY7@&lA@0DYSw`_I7WRlw`j)33Wt zwI6L)op&?TeUPCVRyl)eoMzmOD+Yd3kyA|MPdczi2eQ0?56s3f4lvDZTqXi`{JI1K z%sVYO#zlN208=33p$OoRH-Av0{QI*PaMSj%=%cg(i08tzu2Gv-*LQQ!6oQO$}rN8C=Dm?WE=oAf^#sD)6 zAeIW;HEAfGd>-Wj4euiH_OHB~uBaU2*1x~{Tu+<7CgHn|l_N|jqU0`{4W0OXH)>e( z)0E}wSXf59PMMKwJn?FosW%6A1YrsjP5>k_>UHFxG4v-{eaJE5tJ+Gy(UG-H2gd2h z9Rq;RXw$%zd0PX`S(PIOEKEM2rrSQ@a(J3_65TKGC$n*?tPOKCBRs9y+8FtpTN1Pi zY_623zq$D+mwG+4Q{;UuFBJ$P0Rc1V2(9>wPQYd*5JBj63h(~NsJqhg*gi4uBM6w% zAr&PgMY&Xb;y|M?Jy-tL_sBO)h4&Br=0kYjjd0-+Ow|AmJaV7fq=PJC-iWzqxkmR9 zfWZp9dC|8UZ>~@?uEV-!aj+N$B8c=@M+B+Z(l|wL`#?mFVpzWWfN>Y#O=X`p0Z=Cj za;ZpJ9AJH|-zu`Np|aBVC`*M7EYlB9vki|{Au%nDf3E?YE5zE%$Z3$>&#>lekO%r3 z1(M!xzUo%H-y#JP;FMsvaeSUiB<*XgkG;p2tz+d8muZc?;) z?s($!*pT2!Mi;#C?Ul;PSms-CG;GKj_(1Fr2=Ax#567~h6a|>*1~hfxZWI%G_a8gf zW%7G?-VErSuMTWz75?-SJe&Y6-K*49at$Rx|Na?{DbVvyHofu&mXYQVNQE^gFAzCC z(g}HmwC)ydAes#YUbAzqKN+UCjc`Us>A)xoc=&0C&s85j1}M-0HLifkb-^Lr(hvq1 zButKQN9U^m{1fD4_@C29mISyI9aG)jB|%(j_0jdAq2YEB&=m{8B?x%g|39|*6c`~~_VqXmw2ztRW1 zDkk6O%|)Wd0E=(OKd;=lb~n}q>hNv*fzS4m{$%a>ZF2OtA^CUM&+zvoco+#o5%rp4+J6j-eXF^@bkg(`jNwlX0c(nNY#h!2H z>k_9bJ^JFS@(xE&6`iecciwmSZp_Ozm4hW&`z}m0o~p2oo$ikuYp|>x?{YpII!5oz z(%i^XxNz)+T!fmQmSsqIe$M@_E~i|R*sIxw?Zvr=!XUYZ;hHXa`5}ZS$L>AcjW`$* z;qP#3JWI~#aPa(npMzieWDoVRQ@%@RI_DiY|NFdc2M}m48mNZtLdgM73&d#U^;g)9=ZAAtN1LD7qVn>O zM0PRfWWH)SJwE*F=AZYsO^U8$>Vy_+^W3d19ef$l~K(!1(zUHvG^8@k>c< zs}U9}_|YiTa^W1EPPP zA3WlI(YgM^yvxRI6PH_sS;q4QR@ufyVgUf~NUKmTXwkuTUvR$oV6Mn*$3e3t+8mI# zT>O|PCTCnd{ZhAyDG@49QR=mmzm7_`eRdtZC9JnSl2@F!=jJL|^_4?V(=wf4i0IR1 zr@rKdfz8YFLQ9iw>6{ib6V(dwzgDbwuqGLrXKd`9s#lU98=PB1OA0sf2@=bE6Z}xb z0TV(y12kGNV*i5J2s2^f;E}I+kAZjP8uG6o+Akm7L2C+D#C#bQcqW>ue)_dT1;%GM{Y%riNy0*I{4mem z>Z9Ky53Ae7Pepz=Z;q$e=KAGqOIb-hvfQK9K0VPz3u!0tg&U!+R)AslV!J^{v(3@S zdKIySY=fDJg}MW?_B97bXU}UPj0ph?r$blog^e3-O;rPd{~|BG@uQhS{Yc`r6KHz3 zy;ZJ%dH76Y%D13m%;M(Qe&yh;;gX;mY$>LEnsuabpk-OGQk3>7L5nN4~*b(MKO_O!}1Z1e288Z^#6C>NBqc_}wA+fcJ} z{`^ch+~nE6d3YdiD;eouc`PyV&$q7)-TJ$#!Fob0;GMF)%8vOi7*;2`q3N-J|>1gsU>OfuD|qv~eyiNF_ZOoiU0 zCVWStKsf1PrKA68bo(CGkklqd617S24hZp9+<#C!v-$9M0Jn`VpO3aZN?=W(8=#*2Il8*&M8r`lE-AF^`0K!4=h zaIW?8tXRcxZISmw%R|Lg0*O7Dv!0I*TDbj&mUP)$p;?#Kh;D~>ahA*rlUQBV zchM~#e4&Ocg}6Y}`r=mtx?uz%qCH{GAj zfxEkls*)1h=uVE1EcCUP33MFp%fVyPbI$4iwM0=)=>}-%vXwTLZa(b1ds3pQ9A^9V ztgqxWdXRYPP-y{rT#?_GI12c~t%}|W+wOOqnF$Khe9YQsTP03S8|K=Z7Ovrkr+ zq-ZYs7djP#FaUzx3p+yXg?s{jy+WuKR;@bCJk2+5%YX7wYj}bxKR*dC)BUC!fvIe* z`Ffh(^y6+fAy4ChAADb%QFs@l=HTA6iQZ)?>n`zB%pT+8M)fy1@rI1dh(XrDYbs(P zsGa)NBYqCk-|T&t)6hM9pSqP>$5h>Ixk0LIP++Y-T{`cS!@M#&5@Jbj+) zFH;YNW(9eV1b~Eq&Yl?gKr#3vwEbSKjh3OOuJ@sG31_`c67a_Zen{B=X~)|^4WGbI zv4}H%U0U`=rx&w;V+-(0EAj^?aIZ3W#u{(;6qOIW`zm`FD<-G#B&4Ps)~71Dkhq|h zYM80A87Qt+9B2kL6ilMD{d!@SX<_SIO-%KtZrPLD1abR)E@a2|i9Ho*M|T*crloqn zQk$h7sj4UlTapF}oXK)0Bj!JL#mUs}b;850uMz&v%QBa34qO|&MHt(Ym4fLRg1+CH zFnasd@IjRU+aB)rn)aX_+hh2A?!8V*nSGy}DHpXE>Y@qnrMF0?+X>=G{w>!Ba4D3~@0Kou^tZMqCV{jzJ{v35!S zB-w}kt7NLzT%Q=kp>I2MVpFJ}}X0j!SPkChGKwy&DTZx&6?ZR1VC$Q*( zhf(rEVSY_#*GgIh8`{u9{-_lHQWO6@h#b2~uCbm|aoAJ1nNNC@<2F6prW_Bo$P@y5 zEt~pM^-9Rqe8-kqx0NvgWpSRC`aH4Tk6RMpe%NixkQ1vX6sXZ7U|uW#%pY{iG||+; zfEuaHI@@BliF+jxQ0h-kFWw>{77QRGS~ax?+2Wr$}f9g}wtR(KYrLgXUzGo!_(dYVUn4nd&ua4HE-vnnTgydMAyn z|L15YOV*eDzMn29b5Ji&(AiB`3dz#{dHt8OP;5dSgES=-? zWZMqIp#ZZ_i7emJ!sATH?Ffb?=B@C)0m+~&$3AgGVIdiy>c&+|3)+9ZCxk3OV8cCf ziz-x8Hx-A4I``ZAEJL0yp5PP-cw+}W=@9xgiu$pWUX2i61`h)JLp}*lIY&M1H9_&E zL!MO(9{53lLM*)2stL@diFt_s!7dzq=#X&A%MORK?Ni;`>ehjJEy+eDq@!+DEuYF8 zu!Y7#>NPYxI;g$9N9+)-zb|~O&t{{#I)Lp{dd7c(V!0<|5nA?T-!Vv{@~|p+vb@le zgtrs|d-qT*(8CrWXQ`kMQbEJ-*cAp;oX3ZX*7CRhOhLcghE z@15|*oc5p!aPpJf-A{*XP&6S9UepmB8jNF%xN#|-36S89ku|>GymHWM0)pvi;s~WK z=(cLz#}kMQGY6;0v9^wsW~D#a_d+Qbtqv&j^c)9;bdt^(n?I=~XxN=>K1Yo;m$VWh z-!jWJN)7KnOf_;R(B0m`Q@zuf@+WF)hRqR1Li>Vj%SR#JjSzynJ&sMG>?CKnez+6y z;nBaex57fY)Kda~gnGrvYze*LOs4Rdxy1y8@DGwH_0iMiv_}ublbYmCqU)+Ys zr$aa?5O*%+9CPFxD5Yp!D9Z=p#hmiwLfq)%t5W~@a4FtQ%0j+?XJeBpxYe7DmosQk z8nsvM6#Skqz;3r(>TC5cRXaqlJ?4De8ln~0^Y-Fj2tvD(sXFmLqsB@938jGgj&(yp zjfRQe)xnjJNx?GT1j_M7Y|tMe-hog9owu+P0UZ zOb#EqdxLW*rn*N~vAU(%bwG^FNI8UKjN>LK2LDF#y+?8$KuR7^+!^OR(>>1-A@T_n zx8>PNjg+DtvNtNlmFZbo52;yl3#)=)Z})!Qu~}4S(Zjtsl4c=0Y#Kb}(5Eg-dl#QZ ze9+&+W6y_z*NVvh^cdxhyYNPw3;BOj=CT#lYky3IT}_HpTBCP98)a3M-fx|#fp{+q zDYjYicT-(qx8}wkY*nvL=SXxvWb(F)6((hRi98TD`AK?!xtHg@L_WYF>(W249}nG% zIJplS@h&T{7u+<;g$j-MQ( zoCbOA{F^!q_3{Euf8Me58*9?2_kE&c;bGqz4LBZrAmBqy(#|gP;qyr2&SduYMQ4?L z&(Krud+VQGeJ8U@QvSHDc|+;GhH$W(@{=xq>*>-z5U)_*+`Lw=bX@M*u&#lR54Giv z9$5EZvn2_lTQ%mDK=DSW;4ol36Jo(k&hGb9RC4x^CR;F>mO8WILSQ+5MUG9m1$V?F zMoJHz#rllQcLa$SQ9O9_QM`G>%~?10EWRhmq9^Dyk+NM+iE|5y>hxTGKsira$j^uP zqEF896b56Qy_TL(z_`{Kr(QvQD30E9XRGM>pVCt`diUhB{Mk(ZTYApmW8UC#+SO*7 zwyiLD{AuC17k$+GVhI0o=H564LqH{8cE~KSJ^0R`M*hI{dNZfI(%C+m;Nu)YYg~$i z^p{T?;`*Sl`6co#^)QQNA@xnNx2?yEzVwCEy%1l|vRBV?XAiuD z=#QU2n9bCNQVgRgo(7)}TYNsZ=e)f1{&N;c&i%9}=l%JKao^C{{hDsa*#i(7g#iv- z8lZ4HLNPj8|u}{@~=* zd7)`@!+qC%F#pbLU8BThpDr~%i?k%e(I7bp;SPtA(xUP-qEa zstQP*QSU9iUzH`5Vp)39A2)rN*HjV#!S@JmgP{@|u;~vShRfuNU>~@h@A&1&lGz~d zi6Ear!Q&Gv(_I@9Sh(RgN% z4g$=N#ap_Agh46zgpvCZ64q>0TOAp2d&qkei zX7PPj=$GN-$Ojicd$L?SMDJ3IFOh=%XIgpqY{<^G`s)k&^zRnzPy3GBs7)&SwvH*w z#_Do~@_fFWfq?OQLf*v}@A|Bjz7R09_-rs9Ro)fr=1$R#rkoC?xMCq;KT~`*g690dvdmKl<6L^>TtLbxr2o!(d4mY! z8{f2?SkKnf4=6%^2llS^c|-mODS<-S+rAp_PF4>%_wyi=8Xh?>DQ?)5P8luB(#Q`V ztS5BOda)thi9Rb4E=!t|`?F7aW5M#8DauE{F8P-{kF<@h=gi7%9-r9ZpALET!^;07 zXH?F4p)Xh3Y(KgI3GI&Bnq9qcAO+vJ8xjwR(}$eKLfi}j^kFIdj{G?i=Pj z#Ox=;hraDayIP?SwxC9yZM~9z{Oz9HDyYySZz*~9d}ASRX#^VU(?vN)h&soFyljQ& zeVKJ5LB7t0xnU`I62t{V**HLP#X!P8UOm?ct~k$!7Eu(5lv9kPQ=t?m(r)cn|Fi5c zH-7(y7^|C|B){ihdy~!yOz3zQywJffI ze~o-7QI^5WXM8ujzxtum=N)u*gtrt+c8DMQNo(c%FouF>vHTSSUU$b)+b+U`|uozMM*&X(Z|MIShv zo!TiqO}DSscP@9;I&JLgOtr)&BhHxLI<>69n&hk80X(M|0sX>DzCvFn%ERmqVL`50p1p5K=x&E}hve_hFSo!?lq+5Cq{~7jbyF=8R^c!iVVg}^U zuJdV)i>F;wNR^Zxwz%j8x}O1S6tE|*isf*tA1BQD>V!#@uSIMpQ(4Sey!Mr+O2b~o> zCaD#(S8gM9Dy1($bAGEAF1#_~sQVI~?4FWB7`9RVvatojyuiSo=`onbInHlr>DxLr zjMGB8IpdrfglV9Jtg7u*%c$lIoz?^bMX#yI@A@IlUtTwGD@E@}e=UVQKmm7!5GFH3 z5vH$dOCA>4jxpI^uyZ*>=jft~Fj%H>gp4f;t>J^A%kW!TFP^}+w2ZxttblU5k;9hp zD2`_ZkfvthV@56+i|HDC91+v0y)5cfa{O2FS)1X_BV+%~J09bV3VZsTDyEL#rRq)$ zp1!Gh;68@!;T`ck?Z3G1Fl$n}M=RA!+tX0o$D~5)6*DECP>^{F7bd0WNKuI+iHM-v zB%ST8l@YJix^fsPntx$_562+aRWihW;73}ae!>Gj#i&&32*}QljPAe*n(}E%<}n82 zB$kvoAB1H-EOMHQlgwi#iJhEFMoT3N$k{_S0}C_G5C#9M7O>H_eQ0>*{yJ2?P5=O> ziQZF5lg^H{(Q*AQYBG)q>9n%ZVO!l2?&nCC5juzGx62-}^(>kuY%o`2Z&kVS7WX$3 z1NE;OzWXm|^;phxo1!dw1(z?EsZCE;ZXrRe66{ddxGB>nL3JZouJk)$F$IsgTkh6j z$I6%;SZsQRL)LQ%@ltCI2Nx0DbZ$zQd2!PoPFLeZ)QM}tAMZUCNw>g=pi)7U{lV$N zRtYRgQxXo0PZP1;^Lza1FL=KyNnJhtGk8>sS&6d;qg? zwdg5QGQG$Jg2l&>m&b6hTpXm=K%7jC(aq{PWdk(SW^x+wrZ-PN)$uP7+Q4CCUV|2_ zzt9d>LV zze>1J@aWPlZ)VQ1>ta(_LXy$h`_CU0m!@cF$B68A#fx@YYkH2#qZ9rKh^5X6wrY>5 zzwdaFANoB7Acv+~VN_v98U^60405czAWedXgTxUt9NqmT|LYKdyHt}uG~pzRmXpNd z2%V?)m^HxXwXdR#C z>|OBGEj8UuX40V~s!hyuXa4Bm57%G8p1009-3hH+er!!h%HU&|!L8{e5j;`QTKEy_ zy}XU!Bw6aU&0&kObeY63L(#K6c$r3K3J^iD*)rW{_BFW>sn(NzGrnTr*G0J5jEm z+7nqU;!43SCn9>~2`@T-fQ@tbK|K;of5KAiDw8a_&XmySSY9|1lM!$eFRA0cE2iH@ z5)4d+J?4O^XG$_0*Egr~dw7akPStr?B`m4H6le5+V%J7ba_{CB_pLCO)A)!|8HNeu zU16p|OZB{r5y?ieyOQ}0F8{j9388H!YIkOxkAxI1L)fzgf~b(c@yUT8R$ zaLz`j0Im9 z8e`77JldEW(b|*LG zLi?()RMO9a1DW7G(C7)~ZNG6OHs_EX`-Xx+}I0A&{E!DOWHe3(lnv`yO+Bli?(olSO1Q_Ya(Do+J%mI<>EL z4>aQYdT{z3tTXjWiCEbBTz_z=g2Ja0!IuWKy_1Cx&1f<3U^)mMct!=4*Onl7^@ZT` zB|7ic-`m!F+Af>4wd|sMAC5%hH9@0t`bn?8&r0ehCk=Z`KU}!uJtyOCDQz#X?QAJc z>XX8WRGe)aa-LA}W>u*?gt+6x?D-@}8Qe=6(uG<5kBKDWk;?^qs>ok~HqAvGvPBt5 z5Jb|M2)@S0p6}GbX?Bo=teIdYP7^D&pUMiOsk1Oy8hKt^DjrD3!&~kF)GTgRe=r@R zO~>i7lhfW~=F5`b_n*=NtLZJ{|1t1%_1PHr*>MDwbLDAZpXQ5;_TFwk^#^?74KvTcb1AP566w1GLd;^y8FV{ zfMyovCmq^$+`Vn^gsp6fW6fU$pI=EDbms08kmw$Bw4U_g7YNskLo)cLV%(Tqk>zO+ z>Msr-%i5pvMU;r&4-!BYF`sylU>!I_APJ1aLDKP>223G)T+r>sm7*eSV1GDUofU+? z@qwh}k~{lkpJ)RfVUH_XBw0I2t#|rsRf_9#@w!=pI#?>J8ZW4ok3PF!JCG&fj*IU~ z=4+r4PIkKeAkjsTHUl0-L8HaAxQ0s$HWv@fQ0CcOWvO^7?AYgn<8G-6|ahA zsktVV{Cbfx4>6MumiD%kh6l@d3RH&*c<1N&^ZeV&RgyI#9&32>Cnrd>l%`>?C`Ql} zGx5P+)(kQ73cVb>pY#P8r}*0=S%eEh(r}rVL11&HP@o{fi3w4Es7Xu~GuMKrBl6(l zG<4Rd2e!Err1~c;VA(~J_<@++e}N_l6eWYN(RJzjdofBnDK9S2@wPD;)(UC&CY@r7 zk|Q|d+B88poe2j!Ec@UPpiKNS?$OAIR)U}^Nl=rRtuw(UcG>C>wXooYM2kDVRV=U% z3y3Jx@J<#9oRU-*{HDQDm2yux8R~mpMK(}H+NDj}J4xDIz%RB`Hnh#lrA>;|M^?d$ zluiiIaiW!2>T?jXh^CSMnfEJFvsN?kZxt!~OM#`CdT0#@MNHO&CyDHV#NCr2M4W$_ zAAfnTwSYv;FWd`bNzLIj6|%Gp{Ap;Za2gA6_nJw9KWBDbNLkV1fOOVfF1IiN>t3L7 zApBF->j5Tq{XNmdLw~;Po|YYd8WA*-?s^#{izE`5Tzn&2tpAbr45-sb65W)1Us(J? zN{%*W66>m3#AX8ONSqJLUWug=hgYSMG|ZD!)mdPZQdRG^^II>3IrMd}J zg|$heQe`5NWSo+u%_UpZZ;4Y$VsxBX5mwZ`Si{xlgGd=N{~0e*6IBU9Rc;_FL3PQ+ zwfc*pP+l7{a1G_cLLHJ3r-5w4a8MJb1{Vi)WiqyKRd1PMjUYIa1U6xcg|Yw~2yBmA z{(I&@a`MCR@UF#kHwy4wpL`y?5X9n0+HvYPR*IgcU9* zB9?|LQ)B&vZaPzhw2$u2LiB1hcf_@EYmk za;eGUG@J%*PEEZHWuB~R!a6S#DQz?%-LhJF9xK!Q>VKf(G5m7XWdUzp%kVIeXcm7L z2>kUcPsBYqOY}m`L%rXYYrm>DMDvwH%RzO!BvJKK%9|t<7pK8zko?7oy9>g32{^H3 zk`THKDx4kJzyvokfkluImL$lB8e{nWOOlv*(*1y>^!F*K)*LF>oybsd+D-O6b`8&DIBo2|z z0^%gouZib+Lvg!qfVx+L?j0`3>^`-N%As;tt}c(R$GA64zQCb~ji zQ`$YL(z8v5XqkFhKt`gg(xFPmyFg|qNebI0K_|gzOp(8x zM(TCtdMNgWs0$P6!a{#GgR%Vd8VPEGgVceb1RR9G6!ON4xswPsB(RG<9QSgm1}c9~P=4Y4o2SVF2pD#T zxy2+QDp}@+L&u-svF6Wp*n--aTnJ&l5@^u=&crV4?DU%04gSoy-~$I!SyT zH+duAr+k~}9!ZoLJN>c>Rad3=mA6%0jYI7*ML=yTdpJ-9X}pTW(>RFTF9T8E6ylPw zm?(%8Nx*<_tiTDXGoivdqIka4;6-&=sNX-PafrqZ^-9uYBm?0Mg06$03e!R}6W|Wqeshul3M7E# zR}@G>JJJ7pi6w0?!R|~>FiAj{sqt5`#mFB%gG0(nnJ2z%OECWOG#R@bsH=WO3v)`c z8>AVUyf(iba-GG$Z-HY$U=x@&x{d#Xh+dGa(H|E^by~)R0HNO6fs#j7LbUg2`)T-= zCJ?|}l)IU_<}_8L$kI$;X+$IpS+G>hS!yUtwe+7-{rOk+NnUldRD1I?)i%;a?T1WH zxm1`yHJ`w5Vkyaqmt6lTOl3+KB#9JV5g}dj;gxIuA4limkW~A=@w1qsvYa_UQ4vRI zYOV}%grN-zcECL{+-6p2YMKo)D=jNDEwyFaHu^Sfy)SKB_T&5e58%M_ zocq47>%KnmEAPch$)tWFS&}DESM|CXIj6OEFu^ z*M=l10pqQ`d3QZ{T0rexBOX9jYHm4@%!7_h=`82L3CePsh0IQgC8J0l^sQ!b<;_m^ zb}764GB9v*>H?31Lc~F38pXqo72JneZ!aG>=XpyzuMuG>{ZD9K?*J_d`gfO9Cq`=1 zW9w=A;|kkjzy0@&sa^dOR>^PJhQ7-}NWYQrTc<;d!c@ z*FJfQ!0IQ&@SnY%d7dyg+w#TPTwRG`^R%Kb&Cu}p-N>G#2_|N`V zj6>KSz^2=s)F`%LqktydkgkO2tF;#LFz)~MJf6n10PFtc^%h22PsdmnEwAR3twtfz zAYkiqjoq$DcSMow0XPk?dtr#v3eis3i_p=G1P?e9Ac>+#MLa?RU%gyP`Le&NBhcnI zZG_Rd>h(FM$=t1bTKZe0+8R2$YKiIzZ}bJ4x%2T zF5l9``Ii2Uv#B8c#b#RH+x!fW_vKwmKxwUATwiu?*NV~_>xK395&@JFV9j!@WhBom z46 zzMo99>cEXu>oUtMh}wKdZb-4)AY3NeO9882i?9(Grh8;d+9@{88d#ygG+ z@;QaA3mYPiTHNcPwMQQkJXBQJ7O;gE=Na)|yxH8bs5Rmq3Or`l(CIg9Z!z*b_Q^>VcVA(ux56hx~cJ<+~O?THWzyRq3Bb zRGP;=EN>>-^-UFONxOwYMqwZsw6L})DatFf2p&MJxSXb9vc1y)&N9S(0I{s4@{5cj z^HvwpqKu(p%REMNkwt`Zbt{9d3@T#8O(E?j>^20i=j|lLEwt|eXj&Zg1V~(;-GmFK z8_I!h!x(w6K|;F`Rl1nE$Ro9NN0sS}05VC`0%{!dN~J@VUWUwXLUqZWOUcly1k z{+~zggqw10F?91rpS;508NQo@n!@xzDi@d(v#0{=*i972{YUSAxf6bILn*sqxVHFy z>sU%Dhsa?!+36pV7E{FLfvwfH)k&TmB1<{1<^O4|(yq?=M zJOjcaGBK3L!!@e?ZFHPULV85FQyul|P2>=?#IeJnAoNaoLhj#CVqG}}o7pGtUD``eXx{49u=^hIGU zTC{CJ{RkzB!EM0Xv*#;|b%T+sp@0M`oRScIk|Fwg0An`hk7X$dh9SIq$0^?>N@snX z5J2POP=x3%(R;rE)J+9qGUbF&C4hBTm0D-2P*R=)twAEez8QoMJ!C*S?Epd-=7wnK znq=8EH!UuTJHn@P1pvem5qknqTmvJ3!;|Eir&)+w*!eTJ#dR1{~UjBWv_}2^A zeLBR*m@(gOR3Nc$A@sewNi{JVQQayfeB=01V>0tBOeEem!>nSV(ju@LAn5u*v5SO@ z8|1?&yXwO^(JI(ns9M3F0?Axqv3Wg%Zk_6D6#+mRtR=KB8^pLsPKL74U{U%Z*i6;+ zw^tcPbzcZy_SY07C~m`TiyPuGi0}l!QBzUKOq?6u!|N_+0CZwxhLQeCSbrD=&BR14 z5f9cW@@21Apg{Kr`igi!Ylfdryt2BCc1RFl+dWT7?9O>zBl`AX@ti{BnnZfoew8$(0d=Ymb9Cxxo2GvV=-k zAi8<7+}?;u9RE|l4kuZnX+9OT?ZDL(6=a^74=fu&VY(7%^c88Mxv08qt^^yxgQFUF zI_|gHSlCxI`<6&eU2Z^dSAq^oP#lj+@XLet8uajVL^8?$bApu!$3nv>;PDo@qMEGi z8L%XxeiAodm1iraxku(fdQBy&M4##6=Q4g@q5Gg#Hlsv;oF`rLd(tXX2AgF|ae?iF zFXXZ!{}?I7xu%2VX+yAJNGK6g{2d?nu08N}N&C@d5WSg)flTia6V+1vO%KjJaL7*7 z*(59}Ss=9#r3To4TBAV*PX^b1O^)9c^ex5~32qsucC`2>*fEjNFO1{wALmhK&cc); z3s|>3PpcjQnX`B+LzeO2+ZN!e99xK*3S!KJ609%??)RUx>Fz1MxFY3R%ETP}uP;xD zM}WvCaX;+Hkj(wu12Ytwl7j)x`$tK4Es|iZ#kskaeA;~37x~=&8AAA7<*kdpdLlk( z6P_idd5a|o2ZaYN$T>~fNILf;-n^)p_Oq+oBI*+#eX5 z4OijIL6SREITRa4vtf*{XbV!(_n?wg=H525gkFrkEDa-Ys?koB!!*MH#7zmpF=QNe zyDuB6D?aG{UA$MLEEt;_x=$#vt1kCzKkBHRS;RU|b5Q$Ylf-yao{akF#URs#8N-lM z?{|7#u=F0hMCtn%Z=6gq?2p|v`ktkJe|!DK@$&i20FNZqGHxE%vCo!X*=&)L_-sYC zKqKJD5sjCt8l4|ZA{Z_r&~K_)i?HUGlg}`1eJ2Br@L1ri*Ex`FOuNGa#pc`l_XG48s z;Dtr>m`;eR1iv-ojOEWbqNmPsz@C9~RzY1GH0fs$i3eYk-T9V6BbCrg3TVQK=4Sk# zIGvu;BhyK$DG>t~F(YTaI06;@`&ZL9_gRj~(=cWdI%R_FerO}ZmnvEZ*5zkfh@o{A zabu3{(+drnLS7KmlG4Pw}_Th7B&sIt=3M~dWw-EWQ0zcpSq z>5sikVN393N_>%=x?MAcPyXx)VyI2Dv36>bipo;K{N$bX{TPm1$h{8q@$K>Ny1S(# z)@bcrft^c=FM;fCN`uF4bY$yZ3u~AGn0UINSehRhcPC$GWOcdeLRImo| z%~4_MSAuK?4R{U4$Z_7xTWoFIPiW0{Ke~QssY|lGF%Po8G__u}-2W9sZo1PP84f)sUETL901FZW8y@b2LTZ+VIKzK2|(UWSS$}zi7i~2 z*MNh4Y31}N=3*aTnz-_|1s+@7fpL`Jo~)Xo-JSwBDUl2vT+6>p%s?+sCWd!{`eMA!uRg-DOr|Cr-Ke-tVM!?6t0;$ghv?P5iP1iNBH}l@ z`0NveW|3xYLTpnKkIA)8GyD#|?O<6X{#(9yL3dW#S3(1i>mWmJaEzDQZ0lOkIa8bi!T4uETFNJx}nSyF-nYu9OK4ZYRU*5&w{-fec2-Te?&Y@gmyCQ zsf1i6Koez`DsrxJHO_^3i^rtvzr{L(2l*42fq}3R+MOpjGY65+W**2%#yQ{dnn5mI zVfW)Waxed^wr9f|@zs>&A9%4}qg(ZTQnD83AAa!dAM*y3D7KNAA%_FizI+}Mh|d36 zYX9q9+8zeH?-oC2*TrDff8AFW-&qs4Vv@gKb*V&&qbF~*bh{qIVsHjlQI z0sF&!aRB0p0{o+}I}i32r8-N%I24zuyavE@eQn!qyh$D={N#JL0|dxtA~@`}#015? zy?F)w23~+;Vnj4ECcItlm2mx@H_pzeKPt4CGWf6Eq5ILD_h)w7lh^(g5D%mL4wd6< zDG~@E?3DS_MfNB2cmA*=-mblfe9pS>M$li`S+64O|9Yuw7t)9xktvZQ2a%uO5cWOK z5Hy3@zhE}6wShsiM*({#&YQO{rZWW3BmG*n^3i02+YM-Ys;ixRrT8=G>AN@kGbxz| zS$_hF=whEH9QnrY(JQdK($$6mrWt@@8rB^E^%*!4WyFj@YsO=5yCypM-gf^$rDn{{ zpNkuiE@#Tiw1>4Ul?txI9ET<_Teaf-O`LtxwxuH6Ve0nPC99LyQ6{f$r|{>+x$anc zPpe(I=Ev0?ze+E*^R(L0&1MKPS$XmPCWD7F9ne=%Q$&CU zS4mU`m*2pee597-r3Zo~o)fP3wf7rOfy0x94)3N)+VY35LHZ(%?{|pGk7Hl@7++tpv(lT$R)SQ_Pzv8KQ+gb;7P;StEdffss>%jzYZq=v?QRuqh+ND z0I^ktx;KK&L_yB3qJ!5~u3^8vA;U~hVyzkZ1|LEmw_W9;u%{f%+yJzGeBcGsCix3cjDx$=fv@Rwkg5w zjN`W^t+t?4w~166=IV=cx7!-u$9_Ss)j6yUKe+Ui?BVw{bN1|fxB_vP^L@@fxZ< zW693lHCZvM{Qn3Dc=w7@9M-QF*$;G`s%bwSOxfPu{-GBk`zGDEw`?De7RLbIeuO_w z&g7jR_?lC&(@c&#VhigW!#Q>yHejS~;)SwL?yhHE8>0Bp^}`A^^$qd%$ge3D8t z=z^cDYSb3NRC%te3h)-)(Bw(GslYhK2@Bwb|7kZtGCjDNl`yq1Cej|c5n_bquux2o z+9|0Em!QI#NuUe=;4T>Ojz>_F;;9-7Ki4xMEne0sKls#O-OhCczC261&7kU+?52Kf z#jhUM*xtm#-kO?=wTunBRD^1DwqGoZlT2`bLD2Cf+#aTqlF!nZ9LIiwV=@k}#AV1~ zr7gyhp{XMrejW;bk`3C=!q-PSTreIXib6e@v~L!4c~Sm*Aw6kEshPFSbp*a40c8n$o8XB~V%3$JS;;&pXC>J@E8#ifa7KaMFcN|p?Z}vjJAN()jHS`^BtN9i4 zb@RHy_^Jbqiz^;KNZ=ByqbWrULZy;GZwiRz)-r#Q>jBDsB|>5nGUZf`65@b2wxB?x zHSCs*q^ndc(F&iv%YPK^Y`KJU0gDYOxaL=yX)Ng6zut`p5Ibou zD!6-*i}m(nkvuSB9_-vlwbuMA_W{nz))`|ZB-GS~M#ZCF9GuZpmzx1I6+usa=Gr9Y zkqu^Rmq)A$_j|#fNF|b^!e7X}obhC1{k(Gaqm44TcN_1~p~N+v^Umn*seJq`=G6I- z1z#RK(|@wacwDtVtMB}}o6fz39OIL}?N^*VL}N;-7!<{}n!RyJROa*9;0sO@!M-1n zd(u2bhZ7k$59RF~F2j`NoU!O!4p(MqHcRL{QM?>?H!mw7qg4D%x>b&G5doD_oTCcx zIP~6Sr&bpgDwk(xELZQd4znXX!2$Yz2NGJe~nXl(lwGegBzUzs)W&;TS1UwEJR_5Bvg+6OrXr%Y#d>HYgMY3JWF z|K5A{q|@Z@$tPDqsDx%+Of~Abt4S?o1(B_Kmve7bQ41YoxOWGsx{#M!*097j7Y8Cl z7F#hPfic=KA!3z?pKnSxamgN=1VKpOCH>Qg#gI)Hjg&ULd^Dgy$1EZ3(L}$Wl%QF} zA}f*y5M5IegDbyOiNzRjNvV?d0gS0$TU^(2-@*!-x(6_=8Xevk1n zWOua^rqbJewHi{pigi7*KLu&w?NI`o&R{5Y4&+q=k+v?vegMP^fu%ZzA|6OIR0CK8 zd$BJ@-%upM7$hkDti-WoJ?!2nC>J4DyMP!61pp!>d%1y@y+F+;nkAr8f?gjv3bwA7 z`xAEyZyT*_I5n~-H9dF$Pbp115x0KpzayHs(aWdf`Tg2w_oWa1X?wEqmEIN8nRJzd zF@_fYTi=#m>9+YvW`1Bv;^r57R(0?K8GM3Yn4rbqqNH9tf-z=fk{30*j}7P;WC9FO zhbsqQ8eO#nHjYxPNThpF2Z39JBRcx;m6s5zKX;;x)CcrKdOd31Li#jEg6OvhK`d`t z)7#N-TJnt*4;BSMXrMmwCR=u`5M9tap?GM0DBmeq=A%1Vl8fS6|(zKWks+(Rvsl z$-Ymi#C&Q~Kw1Peh))PqiyvC@NMP~s-aUOrt9ON@{GkX!l85x;Qa?IhbJ@Kp=RlJ9 zM1Wqj(CH1ePtPXx<{s?z_NHOm2AA6l*Oq*_<-g44RM_gbUIWEaD#uC2j(JN6MFmtk z^MJn`fC_~CaSgS>EK?5EWdpcl{25?t@_UdVK*g^W=_QkxQfPQ?5VG*xVLH1)v35)O&EcF&*mC(E~r31BcMghP`=>$0k zLGFhnGul8CW_GqF73DibN?4C;Q1xrMh`F6abjk~GZz3*M3|Pzy%6G`#U0Ij* z_JH$hj3ckI{rMffUYp{Az$(w<=9@jVh&PQ$SC?l~W%ZWsjTaBxt3>ZQmA9n*Fii}8 zONc*d#nnxfXls-_Tmn#J!ssKJFqXK510k6;676gaVpbiFW%DFUX9x^HU$g{ASHiRM zpavbZUz?$nXp8M=I)-Q^^$}R9QS!>)9D+Dw04Y@korU-YM#6_^8?b<)M)MLNLpu)u za+vDBXehgk=~3bOHcH+$4lN>n;lX@EDP@x?cR|9+IpxzGtA&Baf%a1TE?J&s5t>J} zpCl|%FW2i9<+Bs|5382#iu~`~q0a#kRsLU-Ea#43IwK|y_r*eE=p2^`v?hGP=RJQK zmMvzdzBUiotJ9Kwxg#+2trvJCsbZp0Klr2(Pl?hFBG)1fNG+>=Xb_eDWKw}Z; z7nvy`@Kg&q?zOuXN1y;h)2L1P>o_VUhN>AJH2(=e@~&8dw8&}uQD2BEJO;fN1sWL& z;l+$g51d`Pv}5jj*Z_LEvTjJS1to#sQ2ST_qA2_q%(|~|IEgxu+>`OnKpvx>vAhER zg*Eza&uzApl9T2yG?3)cfM~*}^8<9lA3=d_){CY;xU9Qz2-C6Exl+AjL-eoC5panw z@ludll7I5#l2yU?&r4jhW=>4R6}le#GbgI$_pMRwMWX{$M@D+3*vyi}WHPd&siT3O zbg>Gm&qhl(RiYqCes$3xFIaC3B)^wqv<*>kScCk|NTFG)0lZ5(y!O|9Y)iDgRzVkx zVaY)uOIZ`^ZwRmB%|JvuB0?G+Pm8sO4cLxdQLjAr`1%CeH$YN9zTP_~Q=$ZRYt!JjgN($PW!pu6nn2gWg%yM)^PAw?CWXdb@)h zJ#*vxwy1yuKU>z^`7dOA2`MEXn{=)->wku4MS1k?! zpsiMHOCeCh15?UeWX}zQj)Tphp#r8@fqIP1I%9B@1-KC5-pI;j zeubC;pm`nCUk9+RKoWh#4v1WT+bHLSQMm%YKt8W*ETc@VxqC4)o!^q;xjW*-n7^_e zk2VJhvoJH!Id38{yQ9`Tzq4avv&P7>2KpA%OkX=VA&Rlt`N_s)#xj}r*(G@6{GYk5 z`fh2&K_o)F7+~)_k!c$$L@~)GEQSUE51R9~01=KDXCVBGe_%Q|TLqHbky$a0YUgZF z4j6m_@LYg`!m|~c%qaN47z?j}=8qA`GR@=;zycs4Bi>j6H2U#(hJ*8YVlDM-Gc|0e z;VLsgx4V!JBc85Yx!A&rLiRd$8{ml&N_;`49CB?3?UcDbqC}q3==XHS(08M<`x%G& z@dEk0AdzUv*LhJ2fqDqDQBe5LXXkiers&Vtd6Mix8LJ4a&HNlt@!vhn)|lu#0Ve7U zTgPqZ>U+^Q!grS9U5njaYwJyCWW}p$Oq2B%>SIex6(%7fd>{kBi%axn;B6LwldrQy z7|*QZC*0O+u2h(j=oARNYyt6On${PlkgK)DOsbOZAhsw}00Msis{ou*X-&)c*kxQD zAPs?kF0`F1riSAe6YeaE{_h;t8n=T)5uyACCuFAl4EYPW@~$txP9Y^EjeL_ zGM{}8dPmD5%!HekIIk@oHm&}o>o;dD&Ff~t^lFqj5-F<^5w zxB+IodgYG;_;#N_Q#rKrH3*9VXUcM`X4r@fEp^`Fi>;T7VL=P%JqGVl1DkPMaJS2# z+kkLdfje#R9y!e7d(D-(V^vU<4fuwi-m(lJ zk}b8ypk?V)lK8-hEZPU>t?Tu{43~TxGNf5-V4z_08jzv_x@llsiWN;^H5))|<={M_ zA^jvsCnG*;_}o^bItp?CJTg}=3ER7;TnIrYOpbJ5>e@CgmK%GXJ-Gdo^VGr27fUd| zPWc?&a`f{M=HZ&0wr}%73XcX2Rd^O2jXAZ(^CY{Xz35|I>xb`^sY8udf3$jRF{wAi z9RFfE-ZY0H-1l$-fl&abXfsf?J^I#W`N;yW0&V4OW{Mfu7F}_+hgwwwG>j3rV<1iq zxT7!$)#J(tdjJ@eTh$5y7G#P2T)wOc&{9LVdmac6Oz46#Ul}?mK*KSHDGCNo$5e(} zk-H8@ED!j{FyE#HV#y(2hCNSKf374$#y~2>+c_nXEy+pcm+>X!tcEF{;8Sbv5i4$O zo%QJ1K-E=jGW$fQnE zM9}6pn&J+0OAkNcrvege-}EbE$#3TKNoK8q~1nMDOWEoT99AErQXb z5`2!8N3i$7`KhN`>xbtz@HZ(kO)0geajzRI24)q+i~f1DHcScPWW7BQ11H+Ne_J&q z28}dtDH${x2x%C{G1h=VE4XDV=piR8lDajKVKbSd0{}Ow8Gq>vG}7{W_X^)^8t#;~_lNhI zst3#&mktRofoS!GY=EEueTxB0A;b|v^GMJ})+MaWaLF4`av0uX0FXtnD-fq6hZ_Lc zKAoCdSSnj1jQZHFYt?sY1=n;a*W|m00RysL5kjUx4ocXV96%MGpPg(lFJs2hMgjSX z!N?-8_{WvO@14@$MxN1v<|h2!Ui`9DlL&@O#o)a1vK@cDMvf=vwEWnSq1D1%y(4EB z1GizAy*?)&7RIYa>#%41hmOYcMmNrCnK-<$GBY~B3e)G?nh+HzqMFoe68jeSo#iOa23~%ln7Sq9nIdaAwc{IhC)S17pL0rA3(no4!jJ)TyU;B z77+vb0M$wC0UZWz4+@uVTA{$jcqxI=_DRPRXVCiC^GhT2zKZDRy@_gF`Cw-Ai#<<2R@#`@4%;3t z|CE(}&-Sdp>G|a2vD()NClJQiJ-`mS>b-xNX$@3*-(?dNtUxRjNU#_xISFc{oSj?s zXzGxJeqaw7#E1b$MB}~$XRD=$vup8>sPTEe+$PX%0C02y%XS^s9uVs@Ky!5rsZMj7 zKv@#dOa#s&uX^{%!&V3#T!+vBL{APB8zB+DI^Sv?xw5Jt{_%DJikR-RWs!H>IkflY zqsJ$2&D*jNBer`|>9Xc-aFlHMQO~DGj~Iz&(mU^5-HJ(6jg)7O`Y(9(@bKv})|q%N zMzsXf-*@#kv)AK|%i4QSL3&!au<^gq5F8m{;z)kn!6M$qVph_l zJ4mE@*0fi{kq)0F3S;)47Z0>6jbk&1w4cs7Ul{hFpdzor^Uny==vY}dCP{WQ3C(P7 ztnlCLbAT1p?UB>rfq6okdF^$_rHj7s0{E;iq&VWU%d7Lz%HOZ!_K~GC&+eZ<;L`io z?G+}K0_F7P|R^)-uo*h;_ek z;n+Om+21o3FbICiRN1#%3*<-y*%o^m>BQzd-+24ATO3@0jB^`u%uWv{i>Dqj}+lk9!O*A9FHtU4Kul_q;L6VBzgs zi1BXM4MT|8%=4+kMK!w|AyYDB@f@@qyVSvgs@MHGH0{6?lRd@1AXV&sv-Q+5g40;Z zT)rhJW@vHs@3#SnVq!(V#k&Z=zM4y!yFjO^?sN758Ur$a4Ni6I4SYJM3!Jb4pxn## zRor}=L;1E#PSt6`)q3!yi;+nTxir{a0_78YsSz!y6B$D#bvb`#LR(^PO$L-{K4(jI zK&d`wv0+9Bf5k!rhb4!z`vx#AHC1uJ84m|4ORhM^w+kn33tuj9VEbi!gt~&mb}v4X zQ0y@jT<6H?Z228yHCkO6R_nf++FIPt4xjO5PUwv;u~|*n^dVTCMzB$aMO8l!R76RFnQgR7Ho8`lBNBfIf zS(Qw0wHW9x57{H~Hx%_(N|#d9dy*m+tWjjX6yZZ#~VsCC?|)*YEn3#?hd*4)4i7TTNqj; zt;W(Re#X_-u@+Kv8iBPx)grvq0VUeDI~=Z0(Wa1lygE@U#^59+9r7~p*}`9CSyyPcN{7z2}t)(f*{ zsUBMn5%Q7RFno71RqU+}YNF3h8qPYnSg?<2G+Ap5fP~ zOeIR=TY>|&o{)|*tJajvZE;9=V*A}Ba`FMIJ=Nr6iCw$6gw0Xrmy~pR+T*$B=2}byZ^r0#OYnU>%Vc1|v!-CPa>-@xrhsGKp4# z#g{o4i8yL$$2yW>=1@(D7rJ}ab@ z5PEpLv1KgJYWRh@ZhGSTYuU`|X&o!p=z|68Gq~F*?=6Fyh`YDn%`eE)7_W^g^-D5X zvyY^6J`OC=YfJIAO-K&pJ_^!{Tf*XG_G?9J;sAINT^BQ7n%8Ziju0&`92br_&b+-u zr9U#L-3f4!Pj*$bK=Gjwt|HaK@Xp@FTL5>5WW-WDFh=I?X>w9H&0>Q@os$4$C`3Xu zEBl#hsgbb~Fig7!Ow~$B=q|u3J03fD8NlIrAZ8pD8*>4xW&lrZpU~lwrFxpCH~BH| zx_{9ueNsPc1VChKAWu)e3LnVhQ@nvAT6E36$)kjw#vjK5(GJGKsakrV5-Aw$EL-)0 zy`X*o!wJFcHjS%WuvkiSXb;y~Y{=@%w75-)&DgCYNfI`Hr&k+Nmxh297Lg6Z?eAY$ zFDyKs%0P&P0%nG&iyn$1 z?P!F(JrBQC2@EGHVW%&=Rm<>@wp>-g6z< zk>=#zPt*vq47_iwui_|~s#!nhLWD9QVre#7)N?m~MM%Ar_QHVf;J>{0dh5o3HpYS- zTLuG5uB~RxiqM<#9ZLEy)a*;2`u60#QXBRj%P(EC@?TuOTj?yR?CJ4D!E2V+Nq7{puSbd2GD&V5 z4|a+Q+0WO^z_%}k?P5?M3P7L`oR5uAU&H~ z+E+e%+h~5?obBQi&(W$` zeeqk${0=SB^x9TTuJlLe{JC$+G;e$ue=fPx=wk;bi8T2?n`j5dxLFN?#X{f z2(KU3?d9xuEF;t!AHH`BDyeWRlo)Q3P}+-TH}X0ArweP?1jC0OJKc{vDhv*>D~rPi z*tUbMpG&{ZDm|;-A8?IE;c@qD85GzL5%w~5Qpxvk|iUpIDMIK^Wyys!2Tsksg0o<3l_8WHYZ>H#j3 zI6US+nlE-W96V8t1PBpMw*I#MgC8v=$eq@U46rSGAmc@QN6e*t)B8LQA9RpO@7b1Y zE-rZt*7GX&yXKiyCIZXI?r|J?9TM>t2a7o88kP%49oJWLuUO6FRKbEbNGqwIWlq~ zmG-!-nxsG*PWV4_mtUR?TDV#n$3llKy>A(Ux?E#jLr|M%obUvo_W{7$X=5dFfI)c+Xh7(^Yg2``{weC%B#IDmRU@quqtHtquAt6h0e4YAS%)Q^<;NBBQ71{}Fo=c;F`8)oOL4{}&%bJTu*RKe`j zIk`=&2VNJeDOz`*%usj6Tvsr_eOs=d9@grXbA#-Ih7^OYy;U=huisD%w%)pRd`}r! zF>-Qi)l*T~V-t<4sXI7r47&$v8|plpHrA|^j{u9v?h^fJKwFVF_!&${a5k#6Zg&E3 zY8{dqBmxq%VT}`-pL6mk9nCZED0UR*eI9jxJ_oNTo%8qiqVeMWh2i__@Fgw-wu`*3 zwZ)ijaWM>B<`L8i?d<6$x!Sfdh8K7pYZtXpjuLp)QNbyOwM5T`gDpKo;Pjp3mBVs|E9Y5b164q{+Dj1C}M~l_ouH zhD&?IX?C)_Q{`YprT=31lVXHNtMc!>JOwDOj;!8Cb11%D)e;fvEx*J*L6-whWG8_3 zAy{5xL}d&a&bq~u%=75lw6Es!GVob@b@UNWiaTgd?ne|3SF|8wRzeVuIMdEUX4lW# z@XIsnO->ihfA$3qU4AYQ>hAHX;H>N!Jr7Am+)HuLrN>KglraI4mdr zm$JWrQL)dH;CFU>@}OUMRyS>4Njv$O5-I*UV0$mWWc-wEg>uHH@sWPvZ@+M>Vxc85 zMC*E^Kw#*U9NfhcdYwHvWq8oR^G$q5Yi0Wx(W8^@rx{j^Apz+@BlpV=TKA)8N1mP< z5$%C#OZTR0&%|1t;&;w9s?rvM*J%IfxG#Bo*u9&HSusKHB-l6|othTUk&wpbb> zVbYH3awRz$buJZ=v_cDdJOZRDLYvC-WQ*&2iq7g{pUM_c`(c)U$PxDbLYGRvz5FBG zr@C3k!*d07?20{Fm%e>E7!*;ozlX3-Cf!+d(lPa=(6P8R=EB?J7S%3k;dHT?q`ML* zv*uEJ*+rGp6c5CpW~?N4D%?ggdFZA27mQb2!>P?P8y7zwY`rF8bUjwI?L8Ya(0cUg z9_Q0Ze>`YU`od{2Zm# zGL~QEoWlGUe>1Pu3T_GG6Q;J_H70Zf-X~oD?b51R@kWb9eKTe~=r^y#$2R84l3gqr zT4%YXK71pzQ^wjo>u|u{dcG!|T^X|A_QTH^4_`F<>~eg_>A4jc$dN@??8Beph-62_ zDc0^Jklhf`=zs8`Me<{-&w8|_carvQ;bK#Qj(Kte?W^IRt!_rfXR<<@gJ=y;hOUrF zI#c%hdeP*KRneTea1XFKL&@XCqEE4!(SR+^f@Iw>$OD(@SHdmv7;9H#fa}a4*JgxosV{@{owKQzo4>s+5t3 z{r!Ak`nWB(`5zm-qRs$IGqDN7g%rBoz&X5>Vf3GGfX62%$cuxJF29Zij5z$EGS~ zo29d+-;RZ^o!y{gYyNQHQDX7X`59r2K1W9N^od$sLK!pEIXm=HeZcYXLGtkUp9=c* zauGGk;i&Do9O44K_vGd{QW4w0l3wS3g&*Y z?3^yV|M9$zZi{W-x+UvZJi(mu;(Rg-YANcG)(yGWq&_{+Hc`YlwQ#qY*Ql82Hcusx^7@l^!FpBR$1(*Qhcn>-oQ@U!K{Q{&?iBIZ(!R8taC-?^1*jZ_js z6hbJXi{EeiWBczs&iQ=aXXkT1@7L@3N}kZVugdp>2+zOukBgL?CcDBSN(qBRJ6;WH zg7P3`&vi%*z7(r-KUo&aBj+@T?8RG-rCR>KV_Su(`4YN5_wh~j1H)o^0gdR^iPs~g zoS6B9R;y562@TKYXiN2hAu$RkP_h`qbdo4Iec1i;?y8NGYw^)eWVGb+=NCHe^tMT> z&|v55#znV(28Rw`*E-kiyP$6CIB@wa-R8ptZCI>A>8Sz*yiE7H=FKbcb0q|d5Ky+! z4zda!3Q$wFGm7n1vB^<&Ez_0~A~}e39kH6(P&gnX)Sa{Z3a#oPBoM@$fB;#=WkcYm zf-75=yCDMCzQy_e3)+iBYI+rLje+{t1>|-8)vqe_!}(94WD)N5gE=CaSV~Gg;+}2w zzr&!{_cKoY+MN53ET~tLCZXxs#twOv78aUbI&9 zG|EfZDS%?b_Rx!|8xZv>pv;R(Deem&QqKAY!Cbudt!*XvT^I`%ux+@=WiO-RQVB;( zhV2>u>k`y#V;984X{5WNhpmrstVp_`iDfU|g@*18bkVj9fh(ixd=N@G^AhKkRg&Jr z^K#jlQOb&*o=cUjlD)GgA+wFn3p(V^!wdSa>wYSkR*xA!I ziUZkD5G=_1AAZ3`)Tk65f6Y=T@|dXG45`$^MzY56yl7$~L6Tbutwt)nU~V@Rs9-og z6`(xIMS3PnTa5{GHyVeEDkDvSO1X-r8#fXks>N1ad}t?wPiW4{tV6zRw?vdg5J_-Z z1p)xRdy7tj%QLp15@$_=+#i%KRzG?*2ZI8N2T+(G@IOEs;C%3)VIZ6H%lmOd{^NJ^ z$xYMVjidj47Z}(Q>{t`NyDoC`yL#n!(cDdB%BEQSTe;X(<)Cj!zZEg;rm*!_Wz<)3 zxpfJ-899{~va0P;#~Kt}9~^b)H*@ZFbb8|J-t6Rh{iJ1{`YE#9@e~F9U^qV%DK021 z$0MP}Bd3X!SCUatSJ6RfpD;n`TPx{Vim4lmDj(;UH{w#a;n8&GM)~p@xQUp1$eNzv zHw_fG4?~^|L!OA`(t z%_%I(EiEsqsVi%|RdcVU_Q8Xe_9tzfqcy{$b^QZ9uU?Ifb${-@v)1-}vu<$b+P&|$ z>lO-VADS*NUyfQ1!B6_S&p4wO%&;q#;h)V?zB`tFKS%x+SFs&>XFH%{J9Kb|@L?-x zej{pqHF4`x@{h5AAEUNA{g~BH`dbr6*A^wWKJsp?@NQ4>{pdfk(3i+T z-3p~$ioo}5;hkiO#c~~Td4eS5&MOfS}{}|*HGR;6I4RO^9W@k}qH@QWvx{zM%=zC(;M(lG^n{@16{$YlbyShP6t>vSb1V#NAmk z=x#}?Mp5f>G1rQt{sn6O#S#~?90y`A>Gcagy@pp6P!XPal5q5RwTruFZv%^$;Ww?4dG zo1L9oUjF#;+q=P^Q*ZWG=XZXttZaV&v9ot@FgQ3gGBWbyN&8{LIN}iaAGa)qN$(*e zL^S;enRR{HNM*-rOl$o>zNA6q%pfO&q)5R!PuAff$4{W{+3Y{`@YYB<>ilrE!=u|{ zRYvh^GeeK=yskx)dE^}17~>6?YntbV+nV0o!8SPFbbQ?W_O9=v$l2k?ci%t2_2tPq zwYPkDgn!d~ZlwL*$0vl(!#ACt+@F1#@?&jw;7G; zHJ^e1x_YTzFIi%)rY9N%>85X~j|sl|Osf82uJ7Nm#Otc<4acKlJ+4eX(}u65{J6 zABNk=ukEsz(Uw!Mel4vLKo7#j<(m%A2s#u))t^ z^`T7n7x#0&tZCKb@O5@F@`gR(wHb#W>}38VD7==AG}Lqx32bZ4l9H`h$dZbgY|XlL zadN?~bNPkh%dXh&h5It{rgdQ2=DA{yKMNYAJj(xK5Ks|}(4H;QD=hTIr{YvkY_BGhx{?PTOu-fVPUWP$AA3figB za-q&NF4^g|zgaR#{m1UhB+|8BcFLwRdnbeTz}BxuFdxCAJR5~1+g-b z>BDM_1LmdWi@&QQw(Xsj2m3nmgx%#@M(+ub8gV2nJP zsC>X~rrSv;7jhWB!Ya{zoaqo62`Lx$xow2AIW@UJ+Q!vL zE0q?xRrYwt@3^pr8`?=3Mf$B)?!-l*qDx*;1d_}biX~%$%|u4egB9jwxojlCyf{EW zVhVuc5ZPmAh+r|CB9}H2UYX0j9BWiJn)1TnWZTF&Su9z$V=v3FTOha6&l)~Sf20&l z;E&r1l}_7(nL7oR%=T^a~!-5H{y2*V& zl#a_3ZPABHVnXeXW3zcWf*>*k@|QiS34Ui{mg?A%x84q2+=N%)N7|wP)-Wa>FZcvR z2P0fQZdpvMwh5H9^`VR-L58Bm5Q+49nX=CRjw4)}CKDD#swy=i-+^v;z;1|au-+cM z-IJS)CX37xvr>qjj$!;?ONagBS8qBT`S7{s+|M8`zkfW0FX#KD_qgtBkgoE7;;H$! zF2Uv&eb*2*ga z7N&dVKVDy4d{)L`M7Udy$)C65w+-H|LYG*NPI7i3jsM+|qxoeTaqzi`>bLb8988RD zO7X8AuX#PXWO+*aM{X3ePkNKX+%b96l}u2Q+uS-G?I%$k&v_^6zcFXf-zN}Hvo`68 zfa|Ou#z zH9=VhcEi&ckK>p1?L)`=`NkiA435J+>_SPlEje?wEWkDcyo1Vu;0Xl@^UmZ9EU5G4g zofh{kc352CE?>0kMd_(O{TavO1ww7DyEf1- zQtl|;4~*t5ZxelDv^&g~!&4Sew5-E4?kZpQ>w~W0W_+c^J6ihzgvU^)Yn(4w8o3NT zY{VIJC()&4h*si8%uFphZ8@uSDat|DT{iq-|DB(^QO2`p+)j8u>MPsfN{R9htVI%s z_`76vS@%pPe-Fo3ux@Rz#v?g;qj(xR?(Vw3QJ>Vz>ayn48~*U5D^g%2fjBKk9D}2P zPZ7j;xnZ79do^{Ne=lF``ror=;)7eJosN_3Q*E{i zH6yy~ZV>&a(IvGfZIjt7Gyka9|-C`sWceyl^;kHUW47VH~ddhkLyF zHZ^)E%f7#7Yy^OL34q*`Tqc}yd{d}HQ+i^HxZj{Cm_T5aui~=T2O#_hw*tAZ3BFYp zJcCs)F0m_r=rtf>vE85(OFurThIN;Km!GgKBwxBqxm5ZRbVCFrM>DB^32Howse2C+ z20VmlCim?f>cfpWZVlm5ko*^rFwV+&+2O%)OXDyTsTUzdx6VAf6V#)cI4PbWiiL|4 zxMb!Ngtwwco{+rCxkMG{_^S1^m910G8FL?OEf5jRS>!T%n)T~mS|nkQU{K*CEz;ad0@ zk#I{v1#p#(r7$|TrY%((h>t~*~tk)k}cf>8V(3o(BM{ zr^Lz5Tb%5O5+hzxq(?~*9YqKx&)!AZy>}FaV==xacsgjH+|%c1h8WUtaPsnm&y^-4 zc({0SJQ5TL2MN)Eh?l^H@;r{?iWddv*#ZPuz_*tdkVx-sw)12**LUDbJQ0p3z~?1F z-|lcE;Mw~$_>`m|h!Gf9ulmDF$MYv@(j!IUnqCxv>$ix-d`M=iC_JE@=*Yzq^53#StsH!qFcKzByd;6lI9U-YhXiT72gRcD%nmN8 zV@jT4a=U#?6jUAWC*?~eMqw&EMeSo*$D`v3AUrn4my7zgBPN12{&eyiE{; z>c;?nOMoIcq+Mdtrw)M7loavn^5>KA2&CX8pb&|M?_=P6?8`|+_#uLpmID9IR!y_? zq3Y{=FXbxMw{AYEmPl=N$bXVUGR&d4 z`NE}f@cxu&&@SMeTRL(0t6;o5FIfQ;`ztiCJWpsINJeKwpS*l!=qewpEP|1=(Fq*9 zFB6~xmjKtmy{wdZV0oyVn^}Xz7V>ZmcLewrk&DwQjiFXt0x3_6pf(??l?-P=Jv5?7wSz3Jl(a{m<_ zj{|L^Kp!jed~W2;F~X7n(EN$Qu*#(9UjV3?x;$7G$5T!?Q@HC8u%49|0SKnjGX6OL zJnXW=$WDNp3Gi?L5omxE!GHjQe~5zkEe1@382d;yTVFNH1Ae(wFA@j8NaUJqbC$5l z2z(cFMmk)Oz{P_ED-!aQ0FX$3t@>K1G`;M^RJGt%N$V8n3izp(=8b!sA@2-rP2`7*{G`q(k;v5Bqr>B4V~x87(WS@CY1W- zBz<&9T1|q-(zqhNa)9GCyz^H-e610nJ&38y0zTFxY=uSN2}q^E4;(X6(C`F5M)nN` z6bnSZtAWl76t4+D(M^|qC6Wm00uDOS^I<|CxWbvHHNzSclNs|#g~3gSWt-vUvA;l4 zK#2emBsC8V4+H9&<*Q#q>%Ib$$W(bYh))5=zXfQ&1O}Ru;?QmNoHP;^)Orns(mXB* zfRFNk9z<3N5&dqfr+TKjOVUA7#H!c(1qt++cY~GHm3gv{?+bF|DMxEQBJRu$hOK|S zivLyqRf4{ZfrD-&C7>7wYfttn;faJANIn;7^$Co|NXSdd%41wY0|moOj>|fAOK%I? znSG`yAyX-ON6mA|bUWo?b#vIb>V@-&@W`)8n@=up(}8XJ{S!|CMK-`s1X1sTc-epy z4QT!hD9nR+nS728ZAZ`@2tt+su0?s9-J0afp_Je4jp51nva1>nbGX z3j-yR1o9C=yU}XsIXezX@VO8n=A29*9tlt34Ud#!uDlF`G7C2jYU1httqc~fJ}ClM z!J}_q*~EG$&p+Tr18@T4f>do*Dp2;PBg+rq!nN+xxNh(gWKJoct5Q08e_00v*iyQ_N4O=Oa81XXw7JYBNa7`0fZ}ODHcvT3a}fQPg{;crrUR+;i;>36O*))BeVL;b z5*jW08qO&yAg_x-&I1rQ;6@r9iUZQH@>|Fux{O3Q4~i80P{`P}#^g%jrPEW0z;&+j z$jT&qB^S*ZzK;bGQ0-5v0MD`xS5)bMPCYM_}W@M&~#;trNmz zRHXxOg+rj|w}7e{ApTVFI}(wG^hpJwB8h@Rs}?2_uEdlBpZm7eU-*vB1B}6zZL!dlXSi!?+d;hNqY&%&^Hg5 z2Y2B7{N;i=gO#T`xv}H$Q}m!+flHSdmrwv03kaA^z<}~wHvtF%fS>^M%qVDn0@TDv zB?vCp!F9*z8FjXC4+T~3zVU&%)@$m%@4xWd7ru%C@>}4DErC=zddT`Y zx~bJ!NQGBOddrYAu%C6+POki8%6$GtI{j2u1Nj~$_2K{ELuaBucT0gy&30$0K> z&EFZ$n6B3W5NLq2#Ht&eC8aOs4ReSbJzPkD!h+-JJ+Q6LErpMFP4U_!)!ziJpdY6* zzJ#p}TuDL&B%y(S>b3uAF{Cr#n?!ih2>?Go%AWy95rF?>dS+&qxv+>CIbddXaP2s7 zOdhC{1=MHf2)T=OvOPa%nvXDnVo10D`a6E)*t~Y(VU$Ge|I!{Un8J4|ixLzjuHJlE z@|0t@ho@|@_-AXX{w^NfEIQ0#LU2QZ{KGIN{L(=Oo;IAy9B(`~5vsHJs)eEa49L?Q zCPfyOjm}b$2nf)_g+go+1^4N2@YY0A^hd>(K>HnyT8}OvY1?qrm4l9~6c*z!g%Npg zM$82;J{0)Q`W0+}Fg zJ}3$)+QU)mlelygkU>}wrCQnuN2k$~|IBksE?xNaJPoox^ResuC*OymV>Px_-Wz`H zF|*I9`Qk^OXBZ@-=D;QX`%O6v$ z2+9*sJhW=-WaCF0xMA}Uy`od*Aikiae~;L&0e8quR-UmXLJ(mSqCm5ud=~}tTd78D z0fSKGB0C-8%f=CCjcM1&H zIbZpX&!2%DF?==1TVt?^h7|P)D-(}i-}8+*o(#@}-!_9vDi}=g9V60ggf*6E?|Cl8 zI6!%W2!hGK5$K_DzE1uVP(jwt@eg1OngS6$V+n$K06kB*=)pfY9!UK)bw<7Zp~5rp z9%@hpwvv)VT*ma`i>P_ck6g)xk6cth;8^>j(gZ#g^^=0tV*p6|u^#fq!~Ri=YN({k zt3Obor3nTy8h&IDI)7d(eV-nA*Bofl>=V2=aNOtI$h6~;jGf#&w*Sow@d=tjPw^F* z{$!Cqm`;+Ni;@qC;ezJ-zM@_ecBhswHo}&T4r(t$caC%U{7`mK>C7d2!Cf`EnE${+>qY+oT%8&dV1vHbC)C^^!;h^Gnec}Iqx3Y* ze5K1CX~EL>i}+e=A${cd-VkrC;k<^sZOWYGXF1tl3c$-PvqHg|$+=j#yxoDM4W{GM z|B{N^mVdQeeD)#62f24U%5=zb{vqGsFWJhMl5 zss&p1B1hS;g_SpFbe~6lTNpkfFrH2SK-L{22Z-L1Ebm(X%=eqsw;_X!C|2_zj z-oti@nGgiOZ(0Awel4`)94HrGk}RY3T!#B^LfNafNGhHqtRdW6feo0n@NRmnK zvMv8+>Tc|l6{dSi6B@~vf-8fK1`f*T8-05CDZk0dq3pK=XEpr=>r>Foq6d{1{bYD4 z3Rbjs7lnF}LJU;p6&Kr{IaZXra#kMZfHA!Mq9{4K{NH*?j>&!A3%M&$t4i9qD~*WE zAUZ1utll3*XaJ3)4h+1AvC~4oB7)mSVOmH5A{$&LCIkFld{Y}JY=z7OJj`K1h(P^K zG#M|Y{K*GlzHgXdaj>lSE57oSKKO{mgzC=J`{s-`h)`=6++=dQKep^`OZPDR+#*OY z9VaM1`$zJ~Pj>d(8H$yDamn>*p~HTSXAq$)07dplU5*QSQK*X0ugqbYzBqg%giq^N z1g3RtMU{l`hD*g#0(qWczq!(|(=3D_OO87U#he;+?7O!n%{-mbLZ z=Go_AWs8gB>>sU@(@pI#mV>Vx8yCpDl?hUT@(c#Ww|tbujmWz_ifja5joxa{N%(0A zfY@KW3)IKb{(^)ufDtpKr46Cx?X$(kIqK5*JKaU)jP)jO-t(!~%u&OFE6eVIpDJFz zZrrG)`K|{W2l=`gfqRP3GSgkl2y69T`G}unB~c-6{)^)DOY1U9K(WiIMVG>S;Jq4x znd7izP(#@wEC2D$R#D&KZri_UJ*n~Ff zM5I?A{=J3nA2ZrQP&{` zFonU-ul5~nbSOUS$+w#Le4`6hBCYP|BdjTV)JfNV<-c@!HJ#U*uJ?z{rZdA*R;=Yp zaL`kGJpu`bjHl1yvYz~CS5g$~x#LcCc6pF2D#GxAm%a~gw}H% z4Wxy0ZyFvwl;XC*r?NM&XH}GDa?D94G137xc*B+)*M!CBeEt<#vGKJuq!N;dpqF4i zo-EfBxFGqlEQvR^x%P13NeTy|!j+lxUV!_8#`y`wFZ*%6iQk3{lX;ZuGNRE?aUn^O zkYEsKGV5s ze%PNW0mxQM{ z&?o|&_iAWQn}hbalMDt6wToxkG8?16bvtx4CNsJ$SPj|Vs#p(=^Yu^Ef}y(z;90Zs z?caJ9`w;a^u~n_gqj#08`)Hm1a>w{M;Bjb3yKc28`?ou1+N-TbS zc%Y2;sxb@heZ69&HrhbtYqiaxBy2%^6;0CAmDK+9B`+DFaoO?dP&-0)@^xr}(SH|y ztED$OJ(=hE(+fYyf6D7#`Tz+%5!q1P)Xgh$Dxrf#O{X|VYh!3o&Y8<`hJI<#l?8Rn zp$z|oI&ZPA6+jd5@C1b+djR&To8tMm-;Q8(`5A%8ZcIN&Smq%_-uo=4j-Y;j%9>*Dp-j-VY|F!(Cd zR7y%hwh0(|ajiKpSShW7q7IdJWKtggBqvr-?1&?2nC$q9k*+qkb_DM!r_xhztW)sW z8xFNrPTBfx-F91Ku;EkePxQbKs1pt9#-=zGjJmL)E-a|?AjJs@!{k6;iNXZE;7RA< zPB~C_BL{w1k06ElYt+UeWvrl}e<0WhZms<~9_ru=ABdcTq@ggc!}b)^@`^_ zv{hTLTyK2Bs(7IWOT^q^`|Yb^ZZ@jCWHGOwEx}hPR3*>u|2`3vmG#Sr(IUgRVeo;#d&`) zev5LJN%0$idL+IbPdLpFqtc#1wWvb0OZ$cwWLj%%p#q-J(1GrCe;cBP2vHU&8{7ZKIv0F1vM%k}Jvi&+Jp144)0#$(joG<^m+$fe) zy3JHK6!V$A`}Yhsdfp+0B2j@oE_ycs+xP9b?Q3?yf}DPAurlgar-+>TIGjcQR<#< zm;#BYcl!InsoE?%)VaZlj)e^V-G_P#umIY#FNMI_`y;?Rem;W?0woz9Q+<7PvA7$W&KXP@o#~hfb(2c&{uu8&RFqsaO_{`;g*H?}xRpF;f(|K`3A8Ama1_dlx-?)6E_O z78%TR?N}UeIgbn(BJY^K39iBzK`n@#J;4DJB5&MmvP*e`X``;fr>)UUFXpYb{t31l z+Mu+W@zm}-wX>xgyp9h-4vLvdUF?)#KOUIAFK0L*)z;)q!Fz{FsUsFk`f5A*Cq z+^Q4uGbOB(F>(Ih}3in%1HQG4i&NxklVksfw^At&DW0vic7_T|O z{x5CsP(xNOZ9--(0R!LVjZ@1e`#t(7Gw7MC(BuA`!jVDRggOD?NK<&=Hkk&QPsF}{ z$~Ey{8Ppa(pMT$r=S6hJm+(YJb|Qm%a>=K^tS@d&^T26^D&U@;vrY|wr?KCR+>bIc zk8vFIcORsgBp*6c_Cmz**+3_R1X3SIrlY49qcqnJw3nVjSj`a zsGM6#@c|pY7vWxkUAlaTbIrjS+=3=By%JW`96La{)gY|tr~aR4!>5f|(68Kg7ssql zws;SXR=G?z1{)SphN)k($83b3jd#V&JHBOOQEQLr6IWw zZYUUzIPZvw^;V~PDy({MJ z8T0OMp|$t1q5{;~3(Ioq7mQA1w+}#_wxF6mXe}bevFz=&nd$J+aSKH71DNF!)x+Vm z`?qHShKG0F$P5InCVh9x3CB);Q4EKfB!y(Wh2NC3NWsCqQKvZ(5O((|*wKEA2RM+A z+i+-tBMP1f;L{Y~sqC|k$xoRqxWOs>!;JMr$^BGy>m*-zlH{)O{h9X1As&)cET_XW z2=!vZ&SGNyigrEeyWX6p=isg<0p{le^Bknec2LevWxi+uV;Kh}t}u7}MrG})8|*EX zigRW|-yTk4bCT2^_*VT7YX6R6@Bf=?nW9N#E!v$i*Ht3Vuqc%&YF%HN# zlat+}`N@JI3Hvs1q}S`)-Z)1bb@=h58|R#lTibP9oV@+Vjsf+ez4gBhb*z~`9J&=^ zcQnyXZ=Lt#hrYf2KVAmu#OSi@^)xI#tz#=yVRl$7vEspgJZ{em;5vB(B1v+`!cNl?eJggQejT_YV=I5nyN*$c#jm*M zB-L(Cd31zeS)-1OOHPtmupbd7G3Vj~9S{v~#?Bu*JjMP-oyvjb*p(;=wTZ4y+#=EB z9oDW7m8f87DmNe5xXLwzKbnY(aEz}y>$meR}Yom)p(=n zZ5UJe^zp5luEalChgy+8)h8Mq%k^W{erilIJZd+e-VylpEPeOg!ui8HuWP!B52lKb zzjT%R5U=<8mea2ik9&b86j0RZZx^(@F71AaS#B=9=X^UQBvovrOygYbh3yWpmSOe4 zCfBQu$D1dcJQ^_(uT1lUZxNGwG{F69;U?TlKwKUoXNu1^;M^% z4kcX~-+VK>ey#{Ld)A?)LPAzWRLfGnI;hn#LPj(zy*x&A?(&gGb)MiYUts?@Cn{!1 zMRwF>S+B;wHrrzwl$qg*2VBionU7wX?6uu0GhSl}Z#$fIdl zznG`h#46!Inf?Wj=#=gY^Jz5$LBlBhnO+C6JNsa#%ghk9X^lJdhad3OmD%~4m3S~8 zsxpT(gsK8WhSeWZOB~ebk}22J$`g9YHaF5eW(j@99<#B*>KmdevY9KH(yNk6hy;ekR;`->!r6>Pwg&jyJi@ta3B|+CI$7ETudg z*1S>C>qx$<5!oN%l{NXJ-8SxcOYqd*3|YYUU2{W`vC>0)q48HnL!oiqnS(g*cbCk~ah^$gGSwf30HY%C5a|6qiX3?@Q8-rQt&G=AKEpyM-$T-C+8$K`-(B1@0FEKh28Vi$zRHI*VSsNmbw4* z`3keI@Oi}}fzHR>aU&>`E$nxl7FKV*-hY3A0=?cXaKW)=B*a?Rw_Z3uqC;X0Ga&Y7#a&Pf4^X192|c zL3!0#DfgH8S*4j@b5}PUj`p4=Jy*TERN{0Ls`R5@a@E(0`_!+BzC87HkzB`up{VJD z$piDCJkNB;nEy}%M|~G~y<6&~pD+fFH=_!5SIFv@{wN@{M7jR?h8hNOyYg8JuP|Ur z%9cD7!l-#8L(tOvSj~;ME#{xTRYsepa=R0`(t;*!RYVQ>#8ExmwUIBg{aRm|3vY?i zp)jrJW>c&wSfq~r_A>FYn)m$TVe&E)tkY;ojk~VQx6D%2YtTI1izi1L0KCm4;}nMe!vQm%ML}-CB*U_`Ad}Sn+KUEw&o|juo8QX4?mW= z&2wJm1+=fCzBssU>I@w$K4&_mm)^sxdu|&OWCaT|k6?gi^(Cq>V<9`qmO^Sa~4=&ez2g{cOdfpIx3hzAXF8TVqJG(CLs46~YJ=GR!1 z8XbCf8THaTR`R-^QF+Cog=V(aW^jJcz5?7r-R{Jdt+C*hMXA^7Tw*1~eBnQP^E;*n z4AO=2FTMav_YG3HlK{TR{@$K8jBVDF6<*xDm40akwPHv4_Q@*D=qz}qH z8ch|GK0Q*jLZ-p4=3d_&()}^oofp*8E8gZ?V5pS9?@v&aS&{2Yoz+^|^FGe!cMm4z zEt(Zy06KT=>`caxyMW*N3jCxxSnx8794z{|>h(NTo3z3gZhBt)HI1OJ^26s0qP4FZ z*yhg(qI&g%C9WK9*lKzAx+Cd&dSKXU2KdsP#NgRt9uhXncMtAerec@FP>Bm8;+5j{K&- zlzhP|L=}K^`a{O^f)fIR=gONp*i`=DXZbEy-bg;(2k8}nDB+af54s7crf2(n!3v)x zEN5VP^kTl?ZnT5*zNJ1+q>6>p9^vQ#`jd7&anJ(*$%1yERDbzqBw9#|j7Q>*=_Ssy^3!F0WwUp++*CL07 z^{L^k1lCzed=QOgd*H)l)rQ<|%Qz%?E52gUn{;Bqzy|2-sz@S4;CqW16-85>b#3q#q)3EXD7b>6Gq@)iEP$ zB${ln&)SQrHNYP+H0(3z?$t(2T6wN)_U4<$5eU*@L=Idme3SBf0rnTfCwV2 zQTwDn8?fT3TAF`x!O)ZjVEwW3rdpOmSP0h-q@60VPZQTGu;mE7Nm7S8L{qG8q`!Pw zP!d)#I;f4^9<^Zg4B8e1F9aH($xQ=_hW+3p=GKPJ zWCJftvH4zpCYn#X2escTfb0=OTB>YH>xo(mj8gw3o(rh9QssGFKy|qOw@|35clzIv z)*$c04PLeN5ly0%E*h)me?FSR)yrR?vOi_pR8duogwyy~KiqokvTD z+>B|Ek4&(m^Q%IkDvb*8(YXrnY7Po-rRiS?odxSo9g>X9t&LMGg)Wd!L|dPjB(FbK z4w9#CSSni3EX~$$p9a>wT8unL?r}LMmikFVHbBkiLpaQ^Y5E z^NQV=BS_yRZG501K2W}EVRx5gh_TjFw-)0A@rw57D)fZCBkB&4biK|U+XAw-tx&$V zR04`MeaBUYLpGp&0V}SkrEInK-Y^Be?Y5z#TZ^hGR+?e&E)V*ur;wOSg_^j^ZF;Yz z)N8$!-sPK46#Bnz?%1*R4Yg*1qae|unwl+ z+;rvf`Cg-xOo^7cz%F?&F}3VMq^Mnx`QZv=bGdJW-`4C4*|Y`|UrH8rwiJ@>F;K9! zwDZ-MwHBMgQ?5=M$dctvrgq1JWc*a3#ryVbA-2+F{dtn15kyzpT5QEiSfz(w8+2?2 zED6pO`inlLGsVBe;$smF`1|+qL1ezDO^;@dl`6YRe``sDVW$W5o%8B7 zcnJ1uQc#8V6;IB;Adz@O{Wkd%G_qI@`CE+ji+h}%w1rcP zbCRPCrfZPAIpx;p4We@ahwx(cQ!^ZtSMS*#86h?!T#bzP&OGL9t?z7Yb^EryDMaSo z!X7L_mTQ$UKx!HiGnnZ$RPWQaA&c=@3XAsWN%rvXqxrUodNTldfyHO4#6L;oa~2Um zS_=*mb$_z>M`41JM>pDfwQ@Ae>AlaLvouE=tHTzLZ!WrEdNijM$iL+8!vkrOnJ0&7v~-(v2)58IrkwF zzL}y5AYsg5kG5in7&gKY!bx`-_2dV~6ks+KVunIm7_EX)s071?mkA z$@-{1&YaKe5HBv01n_=>^MK$Wny-z>%OvuOTI&C0g^Bm@uaI<+)&inrfuHC~wXYlN zwpA0a3Yi)k>D-$8qzY5+ULi}hgm6uo6?HXxbIEF&V5ivz*10|!&LE*g7sF@35`-R| z75jb%$Yu`bf{7vP7c?ZV8UH0ak2h*f(amxz)K@Ua!$@LHy*htMIt66yj$R|*K5f1r z;~esdoIc~Ox%*igFLKqHYFcKmKA-2PH8j;)b-zibXNq%NNk*Blv%>nAOnbkcV~6Z} z_TD{(j*w4kjhs?nBHgvg(=w!K85l`^lJCqoE5q4{Re{F5wh1&~ky*?;^k|4;O{S7?JCA|Ik}1L+U|^a;!aO2Kl=4KGSc zyw-&F>0R$d{smvyLTgjxdjHa9q>4kJxc+`1ikL;gW$Ivb^l^Pg{tcF@?g1guI<&qk z!%a7MAkYo8AZ3o&>Y_IaX7cqJvB5eti0$tO|GNM=>6LjRr{|lh;sarn-oMDrtC^;{ zx4{+**wMZZugDuhT9O#1INnm+CR5cmQ`EobxDn@@EQZh2S0Nwj)27=s`{oXV4Asf{ z1!RN2K|C@S3{d3%Q*_>ON$vk1XM+sI!ITQzTX1VufP0minx+{z(bRBMX4Yl6a)mRq zu7NF6D{_>Y6}U1p!=`P>hK<{`ZR7g=@%xj<6S%)5#a?jAl6p`ZU;# z)(87A=%aRar~M;=cEcSG6d?8qThGW6J@$|BAf~$3+xdHrSKa7B~LH2#1^Bp2>CSX@# zY^$v^7;Uhg&N7N(y?6q`$NJb+1QGvJIDRm+fd&Z{dIFm35>2X)O#k< z+n4MV2tHd0_RJb}tMG9JoODY8KW*uW`tO}q7((PL36t|SRSVn^)2DV8lRK37ET#Q+ zp~Dv^eCRSiBn0>@QR$K(WSELC_~#_96T7>Qdf53mJA$STKKE-iE3bwjw#I}0WZi&6~AgCUpS0~r9O+_OgA2in{?Vy`4u$5&tik3|R__*lbwR73$S-?_PV zdNl4_KR%1)kPgIGc;Jt>8KtoBiZi$<@YYR2T!J%hL4yhLaka{Kj`DHtvvoncIU|G| zl+fuGJIPjj-~d?SXzgI+VMzK`w768zn6VcU7#t}dZ`8-!A+{d@s$(r2*{D8+DKM@hHr5=Zi(@Vz1^N@td&awZ+2C+mtc3uanPyPP+2h zXa-y{?^GE8#0!>s1AvtW3$-^1&YK0x1_mt4p1b8=S}*2o7_D&xyEgKjAwsUB_>!|v zlH;iJ?y`#)q(283ei&(-7isU2j63;juJxi{0G+L5xu` zvkxkCh%t7>Gjyy^>G+6kRs?-v1nt|de}c`(GId;F<{JQc7&|+vSbt8ciw0tbVU|cA zy)l8spGJCz0*L^hQ^n(s#I}4G@k@h^bcgKw3av|VGI?KMy%@qcZbBd4{P#a2bOp#$ z4YH_8zMm&{m-x6BfTMPex-R~DFU*$zwXBkFXA$@;yZ~5U-f#E6%-;7t>r#}493b9T zY5!LtUheAf53<-0h7YY*%he6wT}y6hAxo_7Sl0(ri+{chB!QNzwU zyNo*YEnW%H{!@tUuweZKkm85PL9Ng;I*$?Lcqf0-tA6{s=(MOmUvGMC_SRzbG;>SX zeb)a(^l8fBr4hXk6(2r=%nx6iJ}q*133#i8Pg!*|eP!woD7O7!Gt}qh03U6!22;{z z5p~<4gWWQH$GPLL>ThhK`?>XoI)Xz@wo7crBvZIN65R%}N4qj1wxTY)eco+!u&JfP zWB2SQ1KIP<+3^<`zrX)?XJEN5IpDx5R+*7!eaiK^pI5Tp-Zl>*I3>TndFSGWRivVy zuV0ONY`@W98P^Aawwfak$~JZI>gr!r;%U*{fxYe1_igP?9V){P-aB^vEX}oKyn^d<9!+&CQqY0o zYiB9+yhWAr*qk1Pnbcy%JvP^!I9%}7>V8+WO`1etm(p@A4kfl~%*nKl-D#DH6(o~G#*#&I z0;O80ff{ovFmN*7*1v3Jks$lvs)9*bIVEpN2=@w`WD!>;X*M*cS7=x*91#Ob9M4*m z5u-T|PrwsP4gp)z1#`4Uj)ZCfC+B&X!&fan(Ga2wnZi z>l00}Ma#0%OJ8rtpSv8BU|oJBzC`Dn(bht$KVegvEVU^*$MZE|^F*D0Yn)uaT#-F| z{I2wR zW_Gt&SX0aIW|FowXH->KcXX7IvpNP}x7rSOzDD+S9)E40Ce;y<(rYs;$QiA5<`rAU zG`7vDm87JKgrY!`7S~;MK$us&gj+^TlK|nQ0{R4;iIZ)U|Aw(e=1?+ z&W2Y_>3JQS`;&G?m=j4_Do=Sd=clranTnVoSnyPkmJJ6AH4skwVTZD?XVYy6rvPKcrSF9RF>zD7w?&*45!$xgIzq7HGJIC-oJe9HFGQhefZ(i;-!T3m(k z_C8>MNlvE{W}Mw~$lA2{(Dp04_x}90Yr36O zW8mlk7`$>8=(tmZ=KNv9+!uxEQL{*{N`de!RO-em#bheW@UVQjlpf3!t!NoBTFq2q z3P0IKkAcYJ;kT?eM^wjloWh;!kS%!su;bPE5C`WDpOt99@xw{@bAf*LlZ>jUuOkT% zq|d)&pRn+t<1EA3GD6x5@1XU0KELNS5q!Tw9f+w~GW)Z&>s|Dm_~(+`S|jjR%1ifK zLs5~$Rk&^j#x`6?{**6joNT{p5d=)JK78BhEDO^Y800X$_}poNQIi}xN}A#MIiI9r zlB-SecZo0t#I)Lc!Gz?u#6l-xM~M6ym^+`0-p3&k7XaZGKONRf3I`c>@bSu`QcQC0 zh82@cnATr+YNtkwM{5XOfEVuy_~Im~3UNw3zKp5nl$c|cMz@26DBgS(r4Il<&xG1m z0x`MA+l_d|es*O-HHSX&!r@mNLYT?Zj%b(LXb<=&wQ<8co3HNN;lE|TtU*?p?!X&;F zA)>Km2K$6nE3x1s)ueR2MKj}WAr^LxDtquJ2JNL3WDcvx*IX968Gn|-SF0`4_ra>t z(LlHl6?UpNS8TkfhK&|ZV3uPA=&cl1<%Q2sYf)W^*&oHG&V^D2d2)r5Hn^S0)U#19 zp~BCfAu?YI9V;c(Hg^GpyQO{(jXO}F!7$SGmT@+s0F%QLZ_&snOwQER%tu!wM!WK( z&s7FF6nCI>o$C~h0eX8?$Nb{7Pc#`u=Ly>L?57;TwS}LsT$)5$j&}X`H63GppN-|1@ zt+9eVbm@TSoW{{#G z$7a>|p@ne|zOZU;$NMX{DoQ=Z&SP?`j~VM$PX24OyQY#SR=~fzM*m>Ix^q7J9KJh3 z0F@c;RhOWDFYGVvl?J0WWhJ@YW=AAgms)vfbT(6~{);-@Z1EnrI|5V#7B?&@5dp zq0E^OEjX+rTY=Rpx?ktd3(FXsh}%(PcMtGivUIk1L+(pjT$WimRr|M7k*x~LAvknUjT{F2JFM8J z_=mh0FfNdgKcs(AiGn-0Uz%Sg*K;ZLeB=a|(g-B9DR&;{lGBvr&D#;3RAL}NouXEI zcTEj-Lo+!W0&Ni@DLe-NuK>cozJzkruou+?EmTeWqLRSE%krKv|1KvbQFVBV?0S|?!v7Z@NfItJR1Ggj(1E!X?S zMM2B6Q-|Jslq*o5-yq4`k&Bisv1#KYXUNC7#vKAmqmVoyM1p+DSxQo;lrjM{PLYvw z8jx}TK2QNaE`;@MU+=-o%u>KkrooPAoNAe*G6ktx%ke-Uj4WaM)TAP==Uy6KFoj4` z_#7s4$`vbgMi^LbeUi(0!0GMCvH$ggg#0O-THjEv--!+hn^Yg{?d#v5>Jv-DCVLFLvI^m^wn1 z%g7eKyF>fpd_aCakQFCB`P62kC#b6?sK}{z#)qj^m6)zSsmhgiwkkMtF(yy6t-d}$ z;I}s)TiIvj8l=!(97`o80*#`9gie5Kwh$M{#eJu*eqcr9NMTq8EJp!J zQfv$7;bZXdEGDZ#L#pLcj@ZePJCC?-Uk&mL z!_wnix;oNVPAL2gHuz6OH^jVH<)ZU1-v}M^A{XpzbyhRSPD!QTL7fGn!Y6`mj}$I- zB0Hp%ZswJg4E))zc)1eaErqokp)&Ki+Z0@!Sohj#hFLwV7~p2|5mre>6jL#mW1_2+ z1pm*t=?}Ol7GcaEzK@4*6IvYF7-4y;Jd_EY%SRm7q;I6^Y*xbxgwRAO^hr2O!bPO1 z37;i|6yS13K8?`wk=Lb$b(CdymK}|n43CP@J(b5eqJjPTL@M(m7X$8})EK)I#A@Em{IK$yyLgDPRg14#Z|?geW8ihn=8 z$W?mSwe-lywROm(Le!+tZM%}3qrrCrLe6mUa>38w|KXQ-v|0NxE5B3KbY!$+B$6WcTiAFmt50`Yty@_yk9 zvqSp74{Yd3%i0M<rJ6-TK9Khe3bCCNa*wDrDlWBj8nJ~Q1wrT);z`$iQHDwQzuurqR zPjftt3)=~(m`sBgbMXQ(w2({NMukR6Av`r=JqK#@4L%8kw@}juFBa$TM07}DpV5dM z4s55Utr#fy{RLOVWMoQV32GRnwjoyyE4GCdaeiH~fMxy*8;c>Nu{y?Rwk~%YH+T}o z(GI5VCOtymnn!VUWU_n4>8{q6jqS^i9p)f=NxAnPJDT^3204_Ag08Corw6X3=eSp* zllDqqqW00xoDopuG{TgO+^44WF|WuuxK1fFM}zDZ;1j5@91W~d&5al69!op&Y%ueq z8H_TRX8&=0o)i|<1oyq2U#uh*X^a{#LWkUONgCp2s?LQ{;(9=&j~Lp*gvN5dCvcz% z0G$LXX_BV1o|6|2Ak-+Jd?8VE-?LO{wMWJ)=j_~nCt{00_qmEBWg*myh-&q=wP12J z0MRKRjw#7kSY*D!_{r^|bH;39p-G#KaY1{>)x)H>tcEg7f-+h;eHf)WeEQzu&WFZ% z=7vu5@kIlzU6sp&3GNxF>D1D(=_F20gSJ~%b8@Geo77# znk0oTniX@8?XRM_RV#`~pAZ+OVN2H=W*uStd-;#vlVUW47jK8XposfKLXr#-LxoDz z&?EpfPyl^~B~?({;hnIY%ZSiF_znTo$_3^jE!9mo0OXDf-mP-oc2(#b@7nQ?(bxnp0JVTKy@XP#W z3Xch$@@L#9O^v;Vrce&zLJ?CHs?-R$Bh<2HAp}t1rNPXCS1n>&~Mv*+d3RkzO_>Kfqel}qurXHh-0ALoID;oaqNQrG-d#g3D2 zer{eLsn~yM`rKCP0A6>gmk3+`P+NX zuRl629V(e`)yHE$Qc(vTf*Ty3-Y&gy=lGT(-`U8f8-z0VH$5KsCYN9}-Ct|m)!i?{M9)f+!$O~Ojy-ToQXM<6)&n=rEnm40 z@gnT!v@?tl$Gq1V8S3YEKPGxh6K-?#X=pQkYaNcTl{;u2vnk>3x2A+`{i*ZuiB>pR z)Ye$;de4}~J6dFFO+E@W*eD+Ns10iHK|1v2tYT9fkif*pS94x(G>+%bca%Hnl=t}~JF+Pr;3x5U0_w$uzgom+p zV@-HME*lqc94kg0?%|8j^kM2KhCYTZ(Q_FKhv-iN^#8_8yaf2@j2X>`WCs|rZa4%T zSA*yL?)2ErmOp>Pj3P!Prj+i5Uz@cboweEA&No4Q7uz zcum{;>|uVm{S2M|Uhq~=^#N4E@VLWAV>kLbV_do6$}tT(?J>sv8RzjCwLHA z_%d$YZL5Pd1^fGxqjKYN&7yYh6^3}m#|o#BlPO|9&(RhsO3!MT!$vyxsZZ!JcsoI8 zrb;rVKLwc`#RSRKVqK>ex({P~U<%AtY3C%vwfM(RRg-31qF*u#IaeU=l>uN*Ei9+? zek)9|XQ6h5K;2@_vY7f(4RZzDMAoXnW_K0vb&EhWN3n8+8h{v|J3O`U5}j=KlIlf; zohw#XQ@fd@YgD%Dq^3IE?-)5ra{uKpqb5V)%YLe=a=jp{Sv4#6O(8}sT^!+Y2SCgBWX>h{?)XvI3X~!5Db1sDDm}v^R0u+%zKv5ttfrV z1)>uM{2c0;CBF5eNK0+3IN@#)DC2B&>;UR^`h)Sz$nrp~t%gYiduymL`wEsGhlSeW z!Gf-t9H+<9t+tMRhS(C<>m^7*-5LSW-t;i0{?nnGV*td=qSjP+z2C!C16xA}$tqdm z<)PjFYdr6=bSs78`$SWO7vPQFv-wb(2N>=nD06D2)#iE}BcXy-A!CA?Y`!V$UT2x> zK<;49insZnZ5|N4FOKKe<;ptpA5;Wi9Cw{buK8pVkcz@o8O7y6!8gBQlX-_>c zx|(=JaJ*?v3^Xu@izF&OX7zUWZI-E8R7#`)^jWe3s>u~uqpTvUzW}@!n#zV7!j(*=oaxs`U)mt zd`W14x2lRiD}av9jq5f7?!|r(!ECKWaG!5l%ZHTc#$#dJ8sf+$7OwwZXSwaAi*Zab z(ek@czg_@NzZ(vJ|6Zt@XC)>sF=^|pU|10VLq#h|Ozq%CJFAq(^g%oZz?~Jd)t2oL zO5>#$MuW10+X{udesd(iev$%{-CC$(U7+yUMC)ePu{k#rbCVe~W&AU1|L{3Sj$a$p-40y<$# znu(P#uH;I0ZxUa}{F(?kD;v~$3ys~pc-e&I!QCl`)bVL6h7))Fa<13iiKy`yEsZ~` zA3f~5{lliJ;#19g_Y5Cc*3?Wd3m1D~w<{e7Af?QWTz?A6z|7>W0%jkV7>72x`C6ogq9RJVR z8BsF;z6Ek)dia*xd^5~u(8I2UL)K#TAokod4pY|;EY}r#_HePNz8Nf^a1gXH|69kwL$qsW# zzNMNtF9t0i6@tvvV5S6;y8yW+K-Yr6rOBX;IPj1J9V7?&3s4FLC?o)Vg&(4eM~%=S zTI)JQA8aYvmioZfjk=-$2XW&-=<;CZSFk$=(o&i2M4Iq2;W5VI@U+k2P7;)bB;V^G$cn#0vNOX$3JH{;+b1Eb;cRm{$We;ArUr#-v%b-Al#&lJ z1Avus@{1l2 zdwPNOG4Pw?>t?@a470&wSPYX2ouET#5KP${JIN2sY3X>2~>6W(!=uk0_n22Id=F*{Zzg7@N=1a95y?x&y%JT&t56Xbn))s2pmjR%)IuLF9EsS2^$OM@w zY_@!1%2g;o`VLPlTKHn$_##q?wV-_^6|z~pi|e~g1P7NthdQdkPJHsSmn*v%!T`F9 zzZ^1c2Jw}ETX2mtbj$z5TBBn2bvon@wT`Vo-;|bk-A~0QEJ7sKhr9wnN``e3D8oX!Gh`DxR00VRK&I4S z8%`^&xz0=h>J^}-2AK*#rX>e5E=8_pf-U*z^Ac-o0fkxxBW6R ze5SCkJBCTbLTgV$ory)saYxf0dc{LZM$8?ucl$$a9CR-7vE$;}NBpDW=0|hQIzuJ@ zdl8VuNYB>zuY6#_*EmAOvb5Pe@$0sAFZPUVB>b>ye};ovOF$<`5_3U&3^>D#17Qjv zVQMXN!EWCI=$aawJrFa-glenIzQ>R*;q9d(`&vJP!+p@^YEaPv=&X{m4hz1yc-&0^ z+L;>V{l(VV2;wAwtQGw2%SXF0W4!5*K=oQ38Q5FRW=J#EFwxt5ptm@XfQxA6%k{Gg z1H>haMseyneRpWta+Cco%)1~*$9|&|&M=q2qvelix;qXojx^(-2MusVAY|^k*qU9} zJI;zvuj%N)^(SnXK{r%v5kJhGa_?QSDZMm9#^)CMfMEYqbmkZl^ub+L2JLl0T^B05 zvODsvZItaA~?)(B?lkQNhv zXL%|7=k6Z;(xPl@hXySt&*pS#X3s9qh_++Jv79~&T&ehB-ga5KvKRk4P`0kCll>cC z8;6f7>2IXF*J;77bt-E zU`cmfAXy-1ro=`i)u#kPuSsI}pF-aPU}TS}mn!_8(RTw%{TwSWiBy<=FEm;0o$eN4 z9CFErd$8u6xS{p*GsN)I3jcviNByh$IfwNAqaU@aD%$F=_jtimZcJE?pl-pw^LBLY z{l|l_YZgD5zbBhkTywf5=#$>_OVF9lKHUaraQKxssEogcK^u2LHUZkhB+xrd$R%LV z?}%197Ij%*WhK%6UtS%uIX;*RO1@L5t|uC0Yqxt0UW2Tgk%C>A z5J{JI^FwcxAMj8^{KM^~kBi}lB1>>QV32mP8 zcVhd=3BHhC^wOJlqB!w+to~OCVo5x{D8vb%qQA(B2%aK^HPEKs^uGXZ|JV(atDGj+;xk>og7H1UTWQ zS~*4syQm<3>ixbPbO0SPMTdk*AZwWr*KmlZ>Wnj%t#~xJF&yd{1->c0=SpeXF(seH zhClAHUssGtkZv#5tah>z^Y@QEp&0E)?zy(Q26?UMTmx-<+l=z?rNWFfd2chh{j?0e zdi!o89Ih4_d~3$|GWpa*I57~FT>HNdvgy$@xeadDFa-Y3mU#Lh)C$SPchSL%DjPW{ zOsdUK(XkR}sEQM?sNEX=8kd3$ws4foba2`nsGo`sltUb`%*zt61s`P2sejoU(^i0X z7W_;XxZLJB|k zbbJc-sGe>vuO$4ViH2+tk>NY@Tj6I0;)Pb^#S`(MWV&lr-dI4fcC@5%jp|Ceidk>Mk$w89_(@GbxQXBN~!COmFqg3## zZBH(^k&Y^@57yN$N1H+zDwac3mV3B$rVZrpNys|+UN!(TSC^E#1P+jsc09NnrT%*{ zGwvo9b8Wb4evmrXj^W5Ltqqu@iiy8}_;03(UnhvcYmLBa z{YLW^KR)hTbAr^`c8IQr{e2BxL0yCy7 zgMRX#FQB{~tY4N{S6;Y5av?{O(9qlHwbX(!KG>HDaZ(qoRbW@6mU6U9#U~X3kMX_)rL2=?PjUk>rZu^Mz(e^gG=*9ZMO* zCL0cJNlAE6Xw?5r-SS91_+Hc8mUc2Zmpg5=J&HbC1wC8q?bYrrxF5OB>Aid?a=%$; zfav|9F#7hWR=32LUS}c7E869^BSh=-JJXNB9}87LvMzz5IM5*AJ0BbR;zvvDiYO}CO|fe(GW^Z+E2WhFicMQlU&cSc;u@=u$xMx1%84&)&-sX`ds< zkBf_NO|)O6FR%ZML;W;eYf zq|Js=+b)5E0NAmLpxyQD74+CO;ZiEM9f~HHC*B4XOemxq{mp0oTw$bg(Ll@eO&Q!x= zXCArcJnY-?I4wJ*nUOr;`xBHFdT@8j>zj`se19H4ko#)pMErw~PY0L3etmb$JuPwV z-k+0_>j(ec{^+U@{vK65M}Mvqe8Zf)cJSGw-A$H;Io&bOw<G z6d!WXo|7V0em4J(f4p^|;O)q`8}Z4dzve&MKX%J`C|4F-zdb(CY!}wd0WQC)YIZ;e zb;s6=bPV4Hw*_u(H}NyHi)c&P-;+{Wk9&TYno;*+Kh83=@68g_uH3*PfqD{d5@{ua z7$gEfWrX#GIy$C_RwiX;2^?7&UR&raGpGfE%3G2oz=~C|v9$dwV>!wS<4B&2WYS0+ zAsK~wz{<@k=_5Lp63-U_CKXZUp2~(a;&;;d=vf@~j;pcE@kD552z<3*3xbj*xjT zUg_=EF`qHLu>V|3ATZ8+NW4?$Ti=Q@So~4d$dS!?ERZ)&cO{KQ5b(HUk)%vDI8O!U$p?`n0Y?)q2UUi0B#f@?fcKhcTujYEdtWEFKpV{fq za;3Cw0SNnR(a!!qDf(#ev0$fSU}VRUsG|yOsr^?A_q2H_+|R@Kb)#Q&wvQ~!uC#0L zIuad5O+p3=L`IaV)vRHfyiEWt{1psk*=;~p6rQ&CsDnJ?D(&-V#+C+Lgq7@t|A#ox zP7Dy?&-5Q0du2j!set%1H*JVjL(=~M;8Sv-VS72me8E=7J(P_yD5xeL0U&NlMOf)9 z+8mNfiWv~$Iv6#nST6GETyVpMI!xPUuyLH4oz=J4L;*$+iPRE;RAA}tD;oLWQIi=8CO=;)bFaON$tv-wf1ns~ z?GdhUEMRThx7T84%IV-!?C7h7+=j#+B=HEtKON*-Eg&S5dL87Q^`9fHp|1V^J8{zK zi)6W`ZRsntQ+85e6r+v_NoF;c-fW5}SUrE>+JQ%h&#D{N z?`W59T2t^s!~ETLNv78EbIsQ6%ll7u*0df#(44onEwK;LvLu}Km%VWAm%8g&pA zNiVGeDdFt!GJS_P)djAbbnGN&FRWL{4AcO)RR_?yg9R>k6_Y|`Ww?_{bg};RpnEMK z*G`(bwXbI5?4RK6%XL>yzTS1Up)Ex4xY07UGMbM3Q@zPK`9W;ay^vB_Xo6NW7xZvL z25}{3D}2D>R(GrYaqhOvUoP)o4F}oz-DG!+U7#3>HBkp!F?q2^C=<^nP>i9SD3)!|U4xloKfuAWIP{SRG3!XQ>T+_ByAxxn-1KlVc*`Gx%`5na~O#=cv+J(nWg$EHE z0{e>Gc&8H|PXs5>8{5pnG8(T!@8-9j0QQm}bZjX~?=rd>d+-oxtm2+X@~b*7^XEPJ z-HfI!leTStM8RuwT_X$c*>2S7J-{ebI;Jd&n%X^YzJkQe-70>ZbD{BqgPF0%jkc!h zP0aZ*)}Bqm)#?4)W7|k4FPFVZ8G-e?j#6?Ki?``LK=?~(duA3PlO4kHWnv!a!{(O| zFW?!&v>uQN_1L9}0ihuv`(yH0IntM@gGrQ%9<8LUn+o?Ik^&bp>fdq~P!A;>WVgfmpX0spy8mqOHx0dgbl;|5K~ovt8&BGN zp&j-QS`}Wb>?$QKOob(@L;+Uj*-`x_iJ~i9sOIUC3^KaeEa;rli1kI zQ@`SnM z`RCml(?4)jzTqa3^i*$W%rDe&eOu&VS97zqwtGK}Z>>oVI7p3qk(?AA*>EldB6+p}5t zV_@Cj?{agGQ|2loK$MVTWAji20t_CuxMaV_3uq>wprU6Gtl=jvIizp*a zrr|9#k1}&=FF9O9Z4vz>ima=IO?;r4RAepic8M3Q=_<<{7~rd%b2?7=%is(SiN4?H zQHAK3)8P$XBaQDH%v_A(IuG^ps_yfQHaWFAE^|9CETGy((YpbSfi$m;qw8_UM|rn&|;*NRZ7JmhS4Ps}XPevp+WlP%gb&k}>VvU)qe7 z&KW14x63viD@8Qh(J7^1$}6g3`!=V7-c$GvkfFz^u<8m}+}}nOOq>VEh9|T}h%8jj zZ}LR<^NzW`SC}z@1$BrFI>?+~#^a6C5Zc7&bOui^t)mP-2g~Le(q(pNQ;2FwX%&zha*GW7={nSs~CdX z&yRev2c6X7d>%D;QFGtoW zyPzRQ|5wug#<{99_+)Ax`L5!cma=l2Z_aypYag>Jrr}DziTHeAH)4&=Q!7$*#L2$N zQ#1(fdgHn&-?NmVP(To#JuT~tufP?GzRv|Ns%tLaIk2~qhU1B5B1PEHBbPn(pC<@? zvS#*n$!01K9341f?Qs^T0L~kLl6hh2SkbG@GV4On-@zbrsVHMWWH%t<2Wrg~@SK5$ z>>U$~2Wf5Mcx?=Vd1ymEfz z!3A_x=Vqg}$Lt+1<&I<0KC7yLr>*|cqeD@sUXLnM+1jR?0|@G5XJU|E~sDf z3y1ffr?tG0JPn5t(%zxN$*q{=)xcKky9H?P}Au4c^Zek;@~8&3G> z(X8-1QgHs^VGohTr1cgc#X^14x>OUXC-5hV48H@cWKX0cZ ze=h`0*NA=uQpyUWE!ma;;mH`!PD|Cg(%!K6{i5AN3E5!#QfGI`6h6D*p84eR3SA?R zP0NAX8%1dyB4kDxB1`mY2xcAL@>eghwhLw&3(Qno$ALC>|DCvPx^oQ_%>Lv8964mY zw!f#avZDV!1Zr}r(8+At`K+leY$gx7ahr{};U{j(8jtW}c0J4sSWfqF8 z6|jk=+y4|K<+`G??Q6Ys#YVV!YB z40Wz~3;JvF#%@gb>Thy~C=zUH>zf4|On&mWhimqFge&>A4jr_xf2PNNmRs<--J6Y^k!|_JHRYYP;Eh`Z zf?T_V>Hp7A0HrNzs1H|IEA%W{M0}!NrmCz+T3$p+A62lY0zj2d;EPBwXq=ytw5W5QAybcnWVm|7C>k zdA5d;*4QUK|400AcRT0%0PR_e`r9H0xtxCMwyG*^q5l&#uh(+fXhAF9JW##1xxi$s zTG!;jdddys$VHFUHbiTRoDf%Y;J!EL$z@P{DCpgoYKn8Y$ZALQV_q3vVFwm%Jb zR5s~l8=dbDCO@*-W%fK{`Tr<76Mv|__kqvu-m#4}YuSx`Fc|wVNQki&*~S`DO_Efq zYsNCR8W9p2`&yPHMK#v!DT+{yQc)_T((>{B&F}sP&wV}Tyv}pZ^Ss}Wjf8TmjHx?4 zI$uu}v?`gDFD;C;PPbq2_V-@6XOWY5Dd1>?#`!zp4GphHoM#)!4fnSY^SGfPmm2-jXF*x_GaNoj+^PRfxhx%Lt z5eey`GyYh2J>4nB#jhnlAd%g2Mxp){o0%f}au~WW&+&QAPg8l>02aMld7D6vG1eSC zWa(L>>G_}hQKV?p@a3S52<_p^s?nIKc1{21BU*I0I-7B14q-jt^{pYNtelShW^F>e zw^S?pc*Utk?Bl}~ar5*$7nBOB4;}1?b@dL*{g>vkWK(->srA*lC%nRAe`92+-}e3y z%LQW_lV!r&k1d=RKBh36Z?&2q_)K6=EJEd-GVL+Kakpr@Z1&g>+Zdwno=?p~OFr$u zn&A10iGt_r!_@CPQ*9D@+{w6;yE@175*a}!I{)|jdU$k~L}nh_2CmLYkK`$TjyYfm zeYr^9a;PJA7#*Bu^;uqeVj?Mg7B9FZIYU~i;ghY5N^|z_t>MyyKO>Pi+g!x?RzH<^ zx?ApQRmcJPrhD^m&dnS(n`u4zu(kG&da`wUk4C9d9O5Tcd6n>d!!Q2oH^z*YXo!D& zxYqM_D3MSx$o`|cq98Qxf^GGQ6n`0MDVpo>g4p0aYdCb+P7!}%_M~V zAxy7S)bX3AzYf^9RpvYRj+IEf`@WxI?z#6oVb2!IF!1ol;dQz`;oiNT>4xr4#|mR_ zd6}I1vXIbe65X0xpvO7v;we-fv*oO8-Y{w2>E8IPeNh;Z7y=jNZiL2W_(s<8^pvCv z@6h)B<9Uw=@A>*WuFbGcKy)(IzwYDVDg*9%eX_<%{o!e9_&&J3%lfWQQrdnPh5ZbA zv{Qc7>6RNE5DcdL8-*5y{ST%KJpg;*R`G%7`>@dfBR_9>;U0qwe3vP z{;4|u@%pHT)%2m3qe_z?KhV8e}Cq%_2|%6YvNWnw9$0oTT%8G=810! zzTb{nuf=Ii#wkDWSG{Mi%$K+Sa1#6Fsq!;K{8xlxS46Q#o4o2A@u8- z;LldY@7==Rha|tx2ygHdzrB-OSrdExRq6RR(TR1L{;!fU+lUDe&%+Y>a^pcd%CrP_EQf6P(G{1<;e%U2Ir=-kP)9b>U)$Fmq zx`&)-LOFfNGe6Mlrn^U5$jE!?ZUS55J+uzl&vkJb!78b@6R+%1Ue6 zdU^G?rka;+tt|~r)fE+G)i<(Bu4NV!T)Lc_mXQXfTs(W`bYeXH#F5y@_>&&26mN*_ zlUZ}9AdgmkCAKZ^;H^u}1y^h`GmV(%4CsmY*c9u~Y@%P5W(Zp*oGBfUw3~WC*)>I+ zd`{e$Z{j&4q7{QB1PhT4N}5N@SjCDs)1^EP@7^D(=^UZw8%gpHa|#OaJ8;0qZNH1N zr?tJKorRT+xvjCaivihN-ONpi=%he!lEypYv^)hBJ%By7pcIjBP8CuylF~NYV?fl! z>*y+Jkd@SwWtDb`$%u+73h;CP&!0cPe*H?Gf&n|Q|A7k5t(;yaAfX*N+*;9}fm3xU zb#AL1%$6~ZT^w$!dVE=llBKY(y?P`c@7)+U(q1!GL(5ej?QDK|J9@e?Xsq+* z!d?2i(K6S&w_bH8egE`o>~71OM-WnQw_8{1Qa?*VCwRQ8?cHOxs%yF1z4rHG#l}Zo zkKeof@d<~Ly?g)tj@9WKe}7XZ?uUsVx*5LLjp5pPRHLI5&*$cvMr-UVT(QANEQ+VO z#{T`frsjO>kQ+{8^|?c+L|}i>k;L{?X?=B|XlK2#d<>jWn{;0!nPS5}%?j{%`GYaKhhL8P~+SP!*}TJ1gyD`VUhjCQ0{r_G8dXS-)&L zs2wfKl>P9`)%<;q@g?&QbKaNqyL2~FC6F&x9Q0gd>Z@28X@0y5Zp5cgB=7PV**f=g z^25wOl!lAi^en5S>FlRAj23tiod+eohBr}C?ru+0B@x)i6_+e`oR#ciHivx}|788% zL0(h%cam-c?eBHG)_;#m-r-%z*6GP%UbgwYT=k^#!Sa<wW=!FM@c z&KoFQuV#xh?KbWvR=0IvQ?p}CU+`vim4f-8{?goSd}a2ZN>}kJE4v2WDrdt{?Q*Ki zsAM&@ZM3esvwieIeMh{Dc6})W`{;i=@>!(!Gx^b#+r0Qj$u`z%q{P007@F;UOm}U| zuGRZZr3mST0ZAnfc=oVr|66Pa{(AH1$kZ*NZ0-DqDh73}!}01`rgd^z_+QJ+C)VUQ zs+TlwBk9sjxy zU&?w0YS!_&BA>hqjP7bR(ZfbHuG9PWX;yb+W3_G-Y#MCV=6H3kS-v@$@bcLI{&p@n zk4=~?9?#evTUU0gav)$%>Mmw^!};F|x1L4C3zy^B?1nvxvvI~y8!_4J*7yHbWvl)mJ?Z7*4l z+pB3WhV>vHm#A`;(hA$KqCyObonLbU*5r-M`BMnVa!#3+Q6A_%eCx~y&XTo7UKVwc zB6)0Kc6RaOL!Sfu(D#~F)`-twG-~ABW<4M2Ydtr=buQBQC!-O*zk-2!Q51Js^KXu|Kvkg zI~0n|vB8^XLlzFz6?A5K=(m+zOG-1Xn*vE1#u6nw2Q8v<)=F;WuGWJ0gp`$@&|{Sn zwLFwU!$GY0&jhI{`N8j%`>g zrCuzaT!9U$pAKyxxBd6qgO0i5%Ik43im6%im;A9fRz27}K3I8s++vTfZ7g;_?RkgC z`x))9icI$c#+k|Kom5Sir2)yIE432~sT#*ho*n+FBJp_>rF}NfniFLpG38yZ?Q$aP zO$AY6;+=!Z$wsTDsJ@Un$H9cF2eJ+*wMgJizG&S)ci^C(nS?@fmAT>5!1Filn}2)h zSo?2e`L5l$nGor?s|S{OVC~nf;PsYWYoF5eI}qaRb$i{Pu71{Sj82CsDG>IZE5qGizCSS7+&5s%EJfMb}ca^FF%a znU|gKm-M2>=#jhss{|oYJe;cLwv^`Gb9$nXj8@Z7KHyxc z!aXx#kRtJb2R}lR7JYGi7fc64A53|~W;sfA!7`mYDzQE*_G*51X#7Cs^iD)+gy3&8 zEnU0TqI2kH+N*Y7^o1WbsfTJCwPmTFrAqvL7Neawo2eFWU)-was7Vyddh_LyM4Mze zKH~5EEB%16u@6C-VRf1KdjHtIti1*YlrW-_&ydJ96<< z-b4vERl_fI$i1UdqIv4%!`a0aALlUfJXWf@iZZxQEm^#o<-kyWy6*XXRuFu$1t~vG zqf*`q2J!l8b|edT6M}3MYU5@K}Y(S_@GLclq3i0zpuNClY%|YwSk^os^lPKs-HS5`0|5fQ@LNTX6?}*Vc9BU z%Oa<{2KOKPsP$XI|MkuL(-Q+G?*d-UzB(wddVc&51KdbXlcCzKaKaIm7o8PTYTy`Dr_+7Lzpl);`(=#EU zzG^Pz#l4+dUTmU7UU$yLR{ehu_;{@gdzY72Q1q1J9mU?;W&1 zT$sN&A}7T-edzax_iWuPUHx&4@JDpu6#Cw#nJ>q%X^6U?u6f=_U4t36R<-Ycl?L_V_Vuk! zvueI8X~E4(4ujIz$&cZVlBbI3-gN|QF#-Fu;CxeoVEMY2t}nKTip?jV_W=T{T94YR zi%?9lhcyG1(!erKfTNH1v7!s(`N!UxX4qo9j-5JQFaL-x|8)j!8fvgh(2I(eEQ(R@qU&y>`A&}g zkY5NF&A7d*w;grwnfiXZIlaTFk-qQVoK_xP`!@r7Wy;e>9n>21JsqFtC$Dgpn*Y2U=abl6$uVFVhKLjL0DuZM{pXC)fu#MI~C{u zlS1pf@cD4Yrwrd~IKcyh7i+I#qa3hxFxFC~aW#C~t40ai4YTfo3h%EMluae~ZGj#vZ+DIJ6&xRT z$Ve;##o1?A#XR)iB$nhgy5#TpW&*9SHSaP#uK*9;_y}C#rO2^p zS9w6;I-sN(dj*QWjsa`uO7dmnb7*HhVCd39Ka&P(=q9SA6-D@tZ6|ov#+z@d=;2o# z2~kOk15v_7VEQni{%2>TQMCb4*R=<T*S)_W@9BxQ!?=2RT$%%7Ff8FvZ{4f@l0Ojz0B*|Xtea%%UrY%!8RWN1G#9$ zhNMeVKz1t-g2Sln%IA*{W8RwGHru7xPL1d@yJ4i=tEK(v-Ts>dunh;szA#|b(Q9$w zbuLz9m*C_t@JtNIp@IeLV68b=%`K~>fghZ)1u&r^o?timMkN)zK`mU{mlqWSh9C0D zrwX|b2|l2MA69Zd-z(oKBLq`1zTadmVcJ1O5Qr)%Xol$DXX)STjBs(m`^jfT1bC=7CfDZWol$K zt%L27*sCyXXJgHKwl~r`YIn|R*!4*C(X{)5N&;UTC$1SXH{+{Y*p9cQZCQ6*J@?9{sFv{%09U` zgnqj9)dhTjZ7o|*8l-{`rv$4A;1Un0#&x}31s42${>pWA-)_+}!S)ldXZ*qOy^U*U z>dsn#GbGS)2K)zJ%56N(BgMviE*A1{zr0>t!*0K&l_D(Aw!8jz2muVHmN>gMns+xU zoGHm=r-VRtyOXM}l24#DIs(~ef?=3+dWWQcm8T#k00Q(fO9t+vsXOZ^-}R=^#yjIK znjw`ZuOhT%U+@DkuDwEQ<{g&gbMp^^&FcVO0KBeowLt0WC0uRpR9WRdFnhf$mvgIt zERsJZxJ1Af5JY~DHI~hm{bzyQrG+iv+w(9zC^EdbolXMW3fyZr@Rj)00W zRWw+u#TdGxKC^xm9l!>fEzX1xnq8Uz{ecA?v93HV zZ>o0K*g^fh2diG(EO+V2FCGY__GD89Pd47l#bI|Ga_(NGRpoMl0v?bG7n-al&*#xa(J~0S_!rZ9IV~3;O}!atBpmYm`ehrlwer9 zKv%<+h9)Deeu=u2&VZ`svmHkBS6sTAOh6)qr#iB5 z1I%V%uoOs#fKcj0F046&fH{OiPv-z(1XU^reTe%&(Mk1GABrJW+H}S2tiAj9liIic zoVc?PBb}7jualocjpvU$G<2bJxix!T!Sv=S)_9ZO8jwW>%elY@D)@jPf)Nt=PY|oP z3JwOAfX&mI_M}{Gh@5q~(xr0RfS5UmbInt+Olb)K zY0#J~X}B$*>iU_g92n+uD;jsRqwj20Hg)3pzovjzG>u+$6W`H=y>j6E^K8ze{;aAu z%@e)zO_$k&=^XR{Dms%5gwfE(VdyZz?H)8M;pQy@ z+Y2N4RLj*vqLG;n0{?-{pIY)bb#Kh;Xj!*z<~|GigTBgF(}Rl!qjbrA1Li?!jr-TS zN5`5+8(kitb9QJ|-Dj(^s1rT+fl%0kk$+837STP}2Vra=lnc!D^n?mO&7uMOvztsC z0TvxNeiR*?47~V^dTfDNI5%|4j?^b6_@R$*wvtwt-i%Jf2DM^${W=kt)5KYW>k&Hlp(=r+z?Tr19~W#r-=#I9D# z7IT{B7GH!@f2GoZqvwHC@~j{A*TNBWByQ-G^)BOf=XNEO9yYe7R`WW>?~GOG-#f1& zcP5@Sp|kn_h5S`=5*?1iB;T6Y6$1RYuyO9vr!+E9oV&S{)9i_R5C&~BpiM%^C)107 z(&dTEbjK{VsoimrA5EVFg+Q^~yXjW*Rk?Scoq92%OL1} z&K9Cput+bc6WVBxd|F5d?U1>mf)SK1V__Aw9qOsdl$@b|ZbYJ(vfVyV(SjH?R){wn z1f&OJ;WhhNN?wv_>fDnL%R5CMLzKlJ7_M+oNw(zt}{*v&(*dGvsl3P-U;?vl{vd zFLmhxKd&&~2Ky^xMS6k2MYzPpv0eI^_oLzA=sU$vnSDaSS-1)}WHp;CBUX(g7l%>n z?HW0wji}p*Pg>Pj&w(z=6^jUQ>M%B~`P^uqrh!wAcf@T+nKRXfPSRQv#K|ZGCEJNx z{4JZnrRwH6%D65&IL?I+;Kp>Pg@zuP`V8O<+mlvnberewg&blfnIs-gR@K!o-Z(-> z=x(!7o)hQK#8@3nK9+6NEOV1>*i7FEGdF4_3}-P)r*3)J{*RAdV_F$KsnV`yzX!J} zc`8|3i`fQVg{?xWf=`pO7`BE3Q}&ZEbc73z?DU^1yBRPv(XpdGZ_%c-JLA|W!D~`v zuFUTS9V*^#IsY6Ee6Q=Wb*8OZ*xL1JmqXy+HM7GZvEpLJA!pSdz8)`-&T*IvaLAE_ z|D9-g1C525>2*R3mub?3(Lvr&S4@!RV;Mr8A@9pGGxLnU`*dr+`q<}i+M&Ko{4g&3 ziP1PG{|R|dI_WK|_Q+dMtB|Fh^<63O$pd~x9@D7T&O4r?o#b-V#hocZeclZFjl|ht z9gaOm`}z{H&D)Zm&v@S6!8+h;FCYdq;VFku1&$)JCxoc>$#QvQ#6}LOdP>2JQZL<$ z5HdVQi4b$7{|gg)R)}fJE1`EBd|8o%oMfLXdS(AayJP)8w$X~UL-S2Q+1<2~_C2A2 zgAqec+(gM%v(?c;%M;qD4=t9uL)=PQ3NYjx_Qdv=f~r=vrQ`!PeW2~Z3x}_VvQO@H z70y0zTa9UF_m3KZ<7{j*MQzvDDKqx}I8r$8|GKQOx|k9B1GW(+JMW8*i!|C>;gy#q zPBMB9>-l%!CP(aqWU-Bbd9j;p#Ygzb$Ip(r9T#g$RtWe1UE;H>6(cHpYm9IQl6W25 zmv3h^s8gXb8nYAqoOHb)3g7hh*>Q$_g?i?wXq1vaopeyj&d<)`0G=XUO;McUkHo)> zv9GjhN9p5Tu<2ovskLDeI!8xOoqFdX4NKD0TO5mI!qR4HO<6YUOQIJb%AOr=_ec2K zGk2%2Z7xb$+42XK4hWSi{UK=kqlGCfj*v1Qo@D^3>?xS)llu8H0|nNcJ)WR?!bd`* zo>)ta>dTvJR=fFUiRF6!`-oDygvQhA+SrIz#{V#On9ZA6IzQu|H5T+~ab9A&}fliq`cdvVOG%D97cepfG*kWn^uwWYM!sT!6ht)GSUW!ayr??^kDR-0k^ z6d|3kla!_fPGgx|ge)pk;Z1I1)?U=^-BBMhY<$E--4mjWZnpLqZ7*fL?oo-qAPs1i zjFuh-2Q(P~mZXG`wCDLqCur)JVbsYI3Zu2d2W?u&>J(N|=D#5h>v>EHg$WF7TX>t5 z5APR>!1pVyn_?nAT?$UaRZk_)N!m@h3f|aqVSJ60`|iIkR3zapO9j!9u@$s~g#PQF zQZd9<@j|mfEeb)!b*nl<{=z>F6G*Fz+bB)#qpH(-7{??EAn^1o;Hp#3 zG-!>uppRSSl}TSYi`FStzUCe@C%?`X5MPFi(vz5pcg6&)e7v(yY`-%3%NaVlQz3Mk z6J_$3x?lgSMAY6bq_UHx>rCML?zTS5ftqR5TY(-sPQMJ{w9laIJfeEba`H_Y`PF9D1Bc|NM_@0tD)*pQEo@)rs{C}e-Nd*ub_@|+5x_OWLVdd6o#BmHPV6_q7APO>xd zB@bPnuScc6)fW(^AMDuhr2Q38vwGZ+bQab*a_Y!m_+ka&D#7#Yq0bR+*B%7z| zD-eX@DaQ{jx7lbD@$b`L_4@am)r^YoPZ|I4LjT%y;D;|eS7@S%GwjYG1U!=#TCUoVS4J~}dC z?FYLSYe(rA)5-$}{AKlS4wIj9u1Qo}tbaxEj7wjsz~UgM=*Dw(8OEr+xH8>hE3s>% z^!#VQ**TQ4TpcH*9 zp1igsn%!|vc8hSEvz;OuorG|`rdjstt?733FlGM@`j+(_@lQ{_P3PALzsEZ$2XQ{$ z7coCIqjh2)h?X&uyC3t@y5NDRI_$W~ygNc1G82gpF#{(9b8Wc`LQaIf-P`3ER&&at z=V3kDSuIxE$lodkHeBriZ{yfciXJM+;y;b6hUInk_;{?8uNF>0hpBr){1`}-SgL#R@jwZ=v(C+$D;L_|jwK1%?kww*p&$rapv2Dz2doyD+bAzt?(j7iK*iiPzQ z(^%&=iG})%t9quz@NKj8?%$QQmiS6*eC4{ffz=eU zIo4M0o$VQ8WJ#7RZ(q~L5r$urY>_!?mxP+RT4Dvx*Za>hVGEGU$2unmR{h?-pQ`U;Y zY7*jQg_FB+t(I~v0cB2H>Fa*0r%LRzBJ^96%^I?pVh~d-$@ZkNnK%n+9{tFyKHYj4 zX>QC=B{PZjOsg)YMJv*Br(ouzh!pzH*Rb)t;hz+?~uE526S1&M;NjO z63n}2JA6`P-*R@9DQVo(Vj7W=pY082V@+gIP5i~GkN0U9CutLTw_C)`nm#dgusvt5 zm$1f>)?K^gXOODJ7LpPb8qQ4XbtJ>z;zSPuAB{9~M&fA*QyNkuy6^D7Xg2lIN0!m& zCL4OjR<%w3S)!z#!6)QE@}fC=a`rgF5v#?~83dpzh(5 z@^Rwbw-wrT@UBFf>xB;HY7f$yjqJMan$(Oro$y!;f{{2#F%}XaKQ@ncvxr9a5fN4- zCYFP=fMEQ1EchCpe~*&8nUru!SHAWSWKZwHUAeJtbIWdre@x>QGrI!Wg(^8%A7b6V z`nA^8W)jj2o4V7XTUTV$VGy=R8ysKRXWp{4zq+Hux93B53_t=$~?~Y zbl~3j@c!PhyOz_;_GWk6dWyB5j8si+xujGr;vSh(Z%ANjic7tDDX$0hSh8gKiN><9 zd@cEO_kXrFBqn*=QToSi#Q5Fo36(Ze-eEl|meEY#`w006cMUw_e>zOOGhcx-u0utd z6(jjcp+aMtIy2SDhy#BnjfJ1&)JuqJd&HLB9Z&Jzo*7Es>0ww?k;JYio_CP8%}8?@ zILL;~$P_a+5}^neV)FH z)$e+q^8fE0QkTm7c9t13<8$J(TBuQt9iDRWv++C;IcJ45W*aQ(?mHp);`b-d-Z7sm z-cK(!YuM0S?H3J_RsCBl52#Vg^L(772KDe%rg^=GdIA)`AE`oznNgYQBu4BhizMsm zPp(Cp_$NBih!!{G_5eb4ctM5lLVDl(Ct@6RlXlwd=3PPQipnSAMtg$#EONnV-p3Gw9Q|$BfDMFUY&v zX)`yo9W^WGl}iYfN& z(s4B=bpK`?`aSCNo48{itvI*(&o;V-ne_lESA{eqF=8Z9#?co1y~?Wot_~iN_kd|l zgJsnqtvN0NI5!Of;?&WQU%3Z!2p+0av*${0>9o3=;N5DEAZ>3U&v#7ONb+pr{Jw1Pk@6&(~u_QgCak9d!<7kzw&0@4E<@@@iQO#x9n<8d*=3l zYTNTfh18M6);7hDu@;ek7c0p!R(G_yEwMMd-!lK_8qBn^{I8!OU;S81V<1{_-e_jp zWOrC{l@Bmwmdu1=eN~ln5x!nbD*&ZSLYUHF7P!Zz)Np=HR4I7YDae$*EWq*GR|{c_A;D+} zgr%Kg?8OeznabzPkL-7xd8m=-#N)d>mkJH%%mg% z@viCXiA>A>ncz;PKjJT(2N2h1%-}swUa5|6S|ZJ$mWu;3R``Bv8JdO6hn?=ZBegRo zevIl{chzC@q+}SpIJvU+iQ?S{e@gT2AT$`kQpj|%rmuz503++^mm6X8S2i+ z&sGdouI)pUIQL^nBF@`{wmkHu-zFzQJbDG7LphzWu|!yQ=L*PI_;s!9VC(rZKNv6- z;lA?%$%29P(Lfgjz(VItsU%zqU$6(@;Aa%z7D;mtQs)4v_qqpYoioUIb_QuB=HjbR z8yVipO_ldj1KTAAniGsw$)^Y2+ge8>cjVnpba;4{w-9OJX2av$oJ9fWV1NcC3ipLl z7^X^2?g2=%$*;orfZ3x=A?nKMV3+`~W&- z+WGrPZ*Twk2;}^iO`Et#>#kMft|vAFf!0+_f%*e#D`gRJ4Apf?hcN@;7qN4MiDAW= z`F*sBKz1Y|Rs0wxI4DA59iH(p7hnA8w!81?Cu&BvB2{kT-l6q<{ZF#BTK+8tfYjN(E9T`*w?mURi*_b?D-kBLKb zVy)>UHVi06o+_A9J`AIue+7#2ePijl){H+2JgctFO`S)n{kN_9%^2e|?v+8zQiGkp ziGKp${dHp!Ig=lPPg+os)jG?VoupAKCM4j8R8jb_Jo5rtbTe`OtQ>XZe&)6-VDm#g!%aBUIBt7Q zC>n;wuRfhTg=YU2CY%uNg8kJ$A;f|mZ%sGD!$ToRYKkt-g<*$b*T*w21uU9@3N0hb>g>2&Pu4X*iu`hCu7*7f2?&(kpey4WY}g9B28 zXs~N{e+%;H!gDZTDkMC7YUv4t1K?u#6!Yj5iS;v_qVy-7FyUgT>MbEw{Fkw1 zyMks}CZe7-Olx?Q6ORdXR-AmiU*0V4L#uhXfPE_3EoY^n3NxCoa%^SU@V1j(nt9^S z#ZWG<*WOG>(u&T7gprv?5>@Ql(^>hP|D}uT#ctuBRl5`!9sRVW%hKJocpWalCf7_j;6DBxJowxsV}}I5+3}BGWjGS1NF7kx1*W z75#>BEaWtlr-S*X+I*U5|LLT1Qy~T2=4oyUTCA%k1u0Byg~?KzF@iqc6TptjobSQl zq~FD4fs|`XDT0c4SRW`xqzEI&QSZ1|g+O{QMlz7y8@bCT-5-6!mj)M*AuGWFbvB>v zaDuJGh=RN0>`>wWK1D%XH(WqLZP+dYiQ8IQNSG5ddz^q=tq|A~U0ShMK0_rUP*L%v zUA@brr-qNwC#Iyu6cwGJ6os?Zh8ajfsOGWaQKhE?V&|P2hcLU`2xaoeIzBihiNIK5 zNI_cbJYqKyvM1~YzK@C8Sw}11p0N0<>t$#7bXv@%xXa;ycKmw@F&*j9*K$#9ZLoWK z2~hYojRYzear!rFmw-atIvl$vi3i7k5RVLMkO;XZ!lgK&9kec;ozio_-CVsW$ct8k zQAB0JvG{-5cED4X68tbO!W15eL&+d8;+%EN?h^xcd-sUa4zJ!|h`Ue~^J?4nDr(Cf zEZcpqbYp1DuG{IlLPxLiW0XnwB6VJ2!O!FXqM6@ zOw?&q2)?G@YS)un$Fsxg<9WSUrDF2_o_(<=_X`Y2C-d*KeCS1mg5HVm1>~r-UI7h! zZf{HUXeJyKb6Y=w5+0WA{UYOr+ploE`xyN|)%VyiX~w+A6)4e+G0f5Q8fcXt|`03P7Zl`NC&Y?(NKyNa*!z6Z2GoqWzk2Xz=nj z!%2I79FD-z$?UhSZ6d^-cf0PeMdjH%l$n!~SB%&M{VNZq=LjQ-(P2@%4!(C0BHvhm zVPRwlJ)fh=(Uivv<{ie*NNd0`yVy}R^l7-~jI$Czv$?`zGgR~m#rO)FjMrb*NioR-gSa1!^kGbSR!c*ndOM^W4@igYTw;KPQyFHiLH5; zj<<4Ub@+tPVrAjONwf?tx)YYfMo32UVTR6RA}?it76+ksQ@H}c1aB=3TJ|pIvO!)$ z%Fg~(qabVzpg^NOgRU4Imn+B6j2Wbvr2un@*9x8Kic5Api_|Qx;#(@Q$Sy&|gqa`J zuG%vjmyT4P;s^Nss_~^>W(cnT~(_q5R#YnNSir}{<-lHy2 zwW3wyU+f{o^SN6_28lB0;At4CURl&Jnp{?JcrPh50+E=+y{^W|5a%2}uq-Hl_yV$Y zV#+5;0cIyFI*Oo2R8@@w2#JSRB}`gbp2WcioF>BgNYv-jd9`kwj0 z1rKl-B1+`z8qRhI90wt)1j9sMeGFgM&B+A|Uv@9j+xz2e-DWYq{ z8xwPm3Tix9RO&kc2O6Z%Zm*Ay=3F^h@4B<|eJUgGM7vT_4uYiACXIu^`6d`xG+#S~ zs(1oDB%Qm)NxdzZ0=K6=%}S+0eK(h2S>B5};JHK6A9=f^HL{y6Q8Kp)pKZrGrG$8ovor-a>K-&TA zSFK}CyNK5udyPKegfzyKiQH>D$l1z;eHJX9uo~g@a}A!{MC#W5VdG^xxUrRBDNVK) zW{0w8U!v>wtH(McyB}Ye~%i)G2F2Cc1m0)oB6{yV4KuB5v215cc7;7r^M_A7f z@wL4bnd=+9Ps0EOkA8oJ^PBMIlwZ>c=@y+EIng9!%iyCXY{^p2F5-h1M^c}=u zrGB*Atg;cUbxEQCQqb^oB3jWA(ao@vCdWToy}y$p_3QY52SrU2x=}@_6%l0eOYy^T z3URZ|WDox27;>OjfSwyLUIvZZ0poTi!*EowXjFn*UL=O+Oa7nG6BLb$)$PXuPe2aE znn=M61J_2V$erj36bV8sdsOF)AtJaNsfu&^gb)#AfmYc2F0Nh&7Y6j}pvg?X($DD7 z+gnI|trVPEFAfFa=v49Ha=C2>rX*QBS&At{hIetX(G=r2n7GBDGNP)-0!ajzHIngYW^(Se!B@f36f8G-@=Y5or-VLMtiFt`jC zjzbCx!4@4B2kda4L1nW~x#DUmIE7Ggyj_Ljk{HbW0Nm~_0buHi7&lXhx_-og=h&Hd zll%IEu7=7sa*d0Xg$kDBoo=MoK-h7vpiBgI05VEuT9m>-cE4#7(yVpLv=oL7qzLBa zUmllG?!56lCg?>b`5GQtP8e}}=@&WdVv`0#B|zYC3cyoQR0xcWgWWfQ3Zo${l?gOG zNBiv!yGSyY#_i{qzW?lr^c++&(}2)#b9D%@eGnckO*kZSJ%#*S{d#jf=3Da+@eUbS z;lcU&i9*6TuVLHVftU9BN5jn?)_9S6#brWC8ohzqJH3JPkrKLa0YjEJ5fDega2?Rt zP4ZYu2(iPLZ%LTizelb%)OIucyLHsG)Uut6-}ebfNU7hDFTJntw`gYmx<)o5P>kvQ zf#yg=7uPh9X;KUeuBJ)c32AN)c@as@N`cL#C`S4YMd)3>Jz|IEaDkZ=1>OF-R5B(S zlVIl*qQ%*WfT7~{+qS*5Tm6uo0yAFkV^iG>*c2cxl3$l202p%11BoXa>%k5ua0S%3 zfKq^F*?w9nxreHV=_13`sDcX25&oqq&@T!=qW@rLd({~#XfY!=iBW~qg)`^h2U^%k zpnA;_a7mi)U0rwMB#K#5zu8VQ@^^|{y$QwIsP@Tk1-tlZS^IwZNvLsx@3)8SM)7jx zOG17(gisWVWSTJtNz|p7_4tOhe;~4N2qcsFea?Lp8c3+;`NER}gi}axg;18n`_7y#pITpM6rGrdNW+JID3@MX9 zhehU)K@No2a*_Y{7ETI3)0)E12$I2yAU39>0R(A_0+dlQZ?*6gy7;raQMGIGu?i(dae-x*}|BgY=8*SO7$Qmt2|U_ zJUV+4+R2HnHS&qdEnhMo=E9ew2}%^1N{U4@(xMn|njm2s*N=5({@6#c8fIE?`%MCu zO?r?fKK-JhmyZ5niCpvh%+3LbPYK6@iu&?FvOEYuWeHrQGqnE@^dbmC@?1@#3!`~a z%@OGlnHY2&L=fu7;vxmM`)-BpL*m~EG~ejG<=HR5tL>q^vP#Jb zw!#PuF9R0;Lc@brQxR^|xIF0H!|bc~Jpm8F=h?<42>T5PUp;#uI5&LN-~M!6rk^ zsa#eH7tt&@@el@Q@BS$VgRSx7heX$5qA<9G+R^Q-<9brcsf>5x+enGhmZ6H-Ca29{ z3p?={d%b0Z{u;x8#WdgxM*ku7m+kcz83xOJ1R?#6z=Bza_V8_tUR51KUW|_-XY}ltQ~+ zlqGVySX(o`{6)NpC&Z+1zj2kNURk_JSvyVDQq|H@Ckmo(Wf|%iZ`{&u?C|Xrnd*yNh5C3MN!yA7(|A_ zhSak){#gJ~0IZ&_*RtU2*+ZEM;3yxfVgS0RF@qZ}GHwncW3FrldrXTCcEW&hfNDD$ zRHlewuVdrB%W2a-2($iRPD?15OIj(9sBjLn-)+UT$yN$#vzo3nL&X-*%(v5L2Ic_h?JweoK=wwkU;ti7ScCWt;8w z6k(HQT;oOj*a#;G{AXlOtfgoa-x$@2aEL!_#D?nty0LU!9Xg9DD$0YyaDD1Q4`3)u zb&+(C|RZXa?*?ryx0{wCW09F7%BJrSq zd;mool!Jh_*jNSJK_)izBaJ`vKcwY|8L`EQ98K6yJ%L)=!IREbxMtf6HZfT{qGE;{lR8)ZM#j}+e&dj&BKvNWlOn7nE?YlLKWLFOA4^vYI^V%zn~_V|2kfd}C*m=+D^=`7Es}Dr~ zaW!#Ac0AT9*fVrR=T|g>2tq7|g&rnkyfxzQ~P#*Q`F@#{CXf z|Jk;0u5J7AM{W|NT~nrAW4EQII3&;~_SEeSwf&Y;O6@0ew=^c6YAIXNDExrCjVKC$ zM%B@(=sKB}jCf12FlNSy$m^jH-{fn;-kxOZDer}i1Vo=8e=>ml@{bo`(RCT&a3~%5&%UZ7zgLaE z>7#+P^6lNl#|QzCkgc@{V1M$ld4C=pGEnPp`=cVLBt#!D*wCN#S6>CYez$N9-F~{a zlve%KNZs@4-gj*$zH;AVAzF-BR92A$jWpJR{#Z24;5o|aIV$rs&7elC5rE3h zYd5k{s_{CRJ9DiN!&s)CX1lJp<#p{Cla_WJe!H<-yk1SHsRu+itlc-gY6NSH^Y$b_Lu8HCQ^ z>nF79FCRm!hIpM66>)%w1?{7GiC*711V%fGxq z(d&16QrVkDHMX|I)9_k83Xxi+``w^AKEjmZWqi|~q3+_Kax}r@{M$`IC<1%e`1Fri z=j_dIcbhEWnKz=SDt&;s9VUD$l-9} zk#{eGIOw1kKmvATl>K~J-H8tbR)d%c0TtVm3$3ui(4_o;-K+F`Q62FlHbe)Y9{^u7 z1OOQ^itqq2LQ_NpN^&^yK3a|IRO+Gkge6M7DIR3N#(t_1LU0d z7G1W0=jBF$I<4h7zZY`7lfDRWWnn$TI7YesLf-Z3F4leu-g#7bz+GoJ-1la%IZVot zlAM2fDA?K|U@HGJfnPn-M>@Z`uWE2$zOXa@T>bA*@&%zGr$DmMa3&tAM`selYB*g9 z*s`WS1?L>;=858Fyv{qP3&L%nXoszUg0N}x;`lS;J)N8oubP11UFss{cOu>R46t~~ z`2`r7*3E$6%=kj?5?#mxcWjS7jDtYShbaUJdZTq-kdYG)B5lDEm~CpNlqZ5WCFwY6 zFu-Sn{u#rQiBUCFylm_$Q#6Ky^@xO8Ag~YWJsV5yoq<>!Uk~El4Kwc8D z*6tC#s%If5b<6gk293OrRG#K-0>jl;eAJppr1>niNokijYo+}_5$xiT+kcHtE z=r}DHSw?_x5~4y{AjGMOByBHo@M#u=cmd2oj0A8)>gB^eIN2cVh3Nr+8gWkzds}~L z7$fdN2PSKYGSX`!HtI!Z|su{I{tT2|-8S2UvuKEC}rXlUV% zGVWB2Fv(<#J2{cZMK}l-A?jjA4_;-WK&Sae`stu}+JI)V-ZpKND>(#_{oWni-@PmS zst+Ke5-WhqG!Msl(IKL-9E6poVfGnz**lQ0?uFQsXB{BLRlXq5vi3eKn+Jj7_+U6I zje!#GY*zSMA`F1D$j&sZFvp^};uY$7f`T+Z*VJ>!Pij=}AxS&Qm>FcA+tX~C*tNrP zB_-b;RXl30TEb>$z#adfBieJ|Og6CR z5S3VKJ)8ky&%}60)=3*(0t?)Hr<8P~x6^QB+nIatFodAOS3buC;-Q}OGGb$O*fP$-5J49C`jav^RXg>XZ_`sl?> zTln{>2L*+R))ddwA~sY(?)F9V>*@{|OS)amzdH z2|4{gFLS-T8|hLm@?(|S{6_}B=$^4I7*d3;4Gu#>CM-M+06$Dx2*gt=9&tcf^zjcf z6UBecQUa+4g={{wdZABLw#4pNo~az}be{B6;lZcvGsoTg!RPC@oYnhJBi)Vqt2N4p zkB0rY={KZYV@EQjt?fVLtJ4na(F9N~l=(B$p3&>VBxH^WcJJ#_jf=&91~nHkFISzO zNxWS#qr|2gmGB{ip%P@J3>R7-xunGE)Q;Gn_tjUPAY*H;-3-E9u#yLj*dmNtZ)AkU zLS%oZBn_r^7jAcjGfGt!ck;;Zg42EJ5dYK&rjoj&x-#)NJ4K8_Z~|b>AVP_t+$|88 zPXW&OLqvqpo~HpQ|9}XP8ACyYoJNERaf=v{Kh*CInWwCMc1~i_@|yK!`lY1ejxYtA?iDG=Bep2JT&q>wheKD~ zD0p}Nj^_%-VB^h%#2gN6-kjtH4CO5JObY_dkijXiV2mZ9)tXoUB4=t4DrNvP;jAhI z>?Z8f%o-yT7Nv%|wF#*J0D6`B7cH$?rP>IUhmXM>s z7ft){9Ug951z4R8p*w0+GYNME1f{Q|?hN8_x>T+?5lkU9tOC1tPO7YBI3K|9foXY9 zxDbE>2<{C&yr)9=O&P@%b<`w``ir_aO_2L5l{79maoggYsyfB2C9Yf1=cg_RVk^a@ zxtXv?rc^9P`XHGu_}gA4d0w zIl#yhR5Uu{wsokiQV_wqZvgB}{7~GxEax&&_0$sy5@-C`cDh|v{Om51;Mq6OV6JCG zC%Djwj0%_on>a`%y77r4R8lX8TquA|7n6rT1P1`RtF#A{3`5GsG4q{&J<67-I+02uk>LAH@d1Wh*I5aNrd@uNE$>L|g_4 z_p~(jB#2htfN{{I9aC-=pnxfp)~RAR%_}wEf7HgYQu?A*dt=Q_oHV=(mv;YqtUxM; zSsgZW>5O1KvyC~s_rc8_LPV zbV(+<^G)ECvE#yf7LRaPN`Ao%5X**-XJrPR&O8%{NDDz+U?6hr-~NoS+Q-$H=^*?U zu@m6nwWDv)=O+WWRa0VCN>JLvYa)uGw9{is38$q}xY9Wmmvgvrn>Tzf3)eG?!5k2f z#=(m)D1A==Plim{j5OCAm(vLuGAGTOlSiz`aoWM#+$HNn#408+&%B^!W{Yk8d;1lH zF9Pxu5=zXW>T`b@W}rubT{D?jS6&grmhgm1T4j=_Iiw+~^IIwu7eNk4!n^VCKe3Q) zJLH~EhMn70*mr)8P+bj`5qygOhnQku)p4V8H6Do_JmK^%$XuFkp_wf_7{i(LEJI+|-S(|p?>$C4?b4>; zhs%nVI@2ZfE-`ELdOv!A=IlEWmS6MA<5f~99WqE zR=^~PP>45Y?lq6J9=)}{NC3eI5$qqpnT?RMe7I2!Jc9B50$&|#<<^lyEdWjq+^DS7 zWvKXhwTi{bJ(j*8_+E8OWZ$~hmmCqrs#r=DDSPk9V5$n61G~bsPT@%XS*p%(l0JG1 zCI#RVig&gM?yXc9mx^;2k`}12L37d~$D3%WLH|lpella-hZnAfj8TbyM7auQoYdPt zxQM{)8I9A$1RVgx;Ke%voBfY9WFmwU#k#8?*+CF#ii2MQ`8i8F1yw)yWb9l5W&}V+ zN+AwBU^s!`lNEhsJpNVB-B$SFI#x{^Ip zt$H07Q2cnI7a>BI282?Zp~xR|;r;>ATo5n?k~I>ZZFV6M+VyQxHNZbYr7E1aT}VUF zdM@0N*>~X>A6CX8O}#QYpG)X;fR)*iY64`FPLMjw$Vs_GE|Z*ej)%bYO2=Kg_pxo#64 zql<`PBQReO1tC}L>P2aCZRH`b|DCZ4*)AcsQO~c%(5Mb)6_?$=ZgMuHIA4!*u0U~@ z(WFwYM<53mAwX~iQVHhLUXh93bzl!Zq*DOpGI4+~UV^f-ZlumtFZ4HkgzoKn4oPoB zBhQ?`UdL~PgXXC)TV>F3A#^tdG{QRK1-Lvj_i56Wt$*O~6C_&$A~es)h((iHXRiG) zC+C5PTe>8^FIia-4&u_SsZX`T+26kHhiw5beOvspq;^e)J@$CB{YdR<8 zkJh{Eaz)92w0T8#J@(pX1X#&8VCL2FSb$Zmeg3>MR47%FE7QQlaj8IqxvT*%WmA{;S>W`y zjU?mC{qrRQc^sy6M&pl<>^u|3N2%QbeJQ5~He#XHwM3&8ppX*_@g)BgkoC5I;m>Hv zelQ_TaPSjM`~nkSBG@b`CJRBQm#E~%8GPXkq@fg2vP`X;*<0E#bnwSF7LzJzgqtA3 zlwjUKY?psHECWQyVs?880Sx^qtOS0 z&R!4fzT;`bnYMm(ONy2x<#s-6Vo++;maP5%Gd4IWo=k%|ZZ?_tQvhi#);CuquX0EU z`J`$p=}B<)M=EKWO5`yMr$GdrQ1T{I_AUryK?hY&J~gW#)gL49K%^1@RGg0=p~_Yq z)87Ck)Kl-QFl8rZ{MU+|nwX;}8LuWI$t@h%5cA)n0dczmL`d5rO$#*rB)C%?6^{&= z0xGV6I$Xmk@>_ew94X4B!o^l%g8m&p&0qSQdm^$0?pK8y{4{Czv+J>Qw{P=QZ8+^C ztgU`S&_*J0{=KvL-S{wi`s|og^R$%01E~@Z9GC(`fPf%@d+!Vs;61o+F6$yBt`$2h zQ^|Sd4*YjXx6S?TxMAuzBnL-%^U#7Llplq*Zg$U8=*Ft!!Q-ckvY=L1V^IeV}osC>ONT z>e;OD!}CFe%$=tL6Iy2gFFs7iXgl=A`_5;Vzg?ya_+A=+sTS&WmEGj~mu8l)|8tkl zTlsYNdtuy}w_49+wYebh+bWNzL866;sX324KtXQ`ZXxMxCKNmkc2Y0E`T!1#9w2pD z)AO6c^svB@Qzo(B>K}O^PM>TDdpi-_2iNdwIsM&%mnpT#BD7YzKhAY+Z?mvIT(+~xtn_W<7W71jQXj%v#le;>zylvhNw07;}-)53XDSs z%VwU&pfz=ZH5v4|2Fxj=phP?Z(hxS;j7NA04Ol=|`aq%nyRAZbn{Mq);nH1_nC~*^2XnfY62bjp-d&HRVgJ$AupL-sLoF$*QFfrB9-YMbm)=x5B z?5k&~gxlJ(WV)Vu9G{~zq~qJB`;(VFAWE@{%rH`J6grr0EXrd~tQU?B>b>S?zc%^i zH;U0)tAb$le;D8fOqMGm2hCR4>jPfiCrA5rzq`bj>3**m8_^kTTrbfXWJ$JbtI#D! zHH0#eC{*{qkpZTTkT;3;i`hI`Q1Ye*g6-P9-Y#LGDu7Bh&m;xjz3?sn{u#%uI;d4E z2vKMW-Xl$l;5(lqZAZT_HFAnf_4#}!=9bw_Qu%w)dC&86lRiV1ZIsn?ebBtmA5qO^m7-1Fb(dxsz2UcG^e2Yq@xwbR8k4dMrwYs&KN`dWNezeX=_JslM|ONU^MgqiJV zy)nM!?M{=|5Umc}F_c=Q3N=AO4KcGOu|4E)`FG=&@z(?PIsz*Ri$+1I@Po$?ClzE&3%^l#8Ig313L79#cG{9sg=^9|2=uFO0iW+~-_4U2=E{x!q9 zygIXuIloxCe}#e2*-dTTwiVbB?SMyFlD z#co))clc3EODTRiwkNH*mK$0zXFVl^>nxaOMCGAn24g#ogqs<$!h=a~fbo|*(;=r7 z!U$r|J^E$)pp9BU4)t(=67VU-hyc(@L?Y;;6TeAW-(VkZx#=2V_= z>!3uI-D2`@^{aN{TRozxzD0i*$7s|Pn#j|txmLE8tNu52|FEHYEj!^J7-1t zgf6qKIWU?hBnpGzVinHUBWo-zhbhTMg~QVVZM< zuPI&c{eEVI@q9@u;>r3ku#6CgIs6Z|J9?Gj>3e>DC5$af>(x8sI8QaLH8TaY*yJ={ ziY5Mw=4b$m2a(-kBMf87a;d}dK50n^Qv+*k+Hm~I*zcG2dEf{0GJDEK`j13c9vfUr zs8gsx1(xi#5Rc%bdQNEES_}0rZoEcvr*(xe_b|*waL4Pn&jvS^6@cGf6ZcG$CxYoh z)oDoy=?)dyzj?Pzr-sun{roKR+yY^g_e0?({ej!x6dR-gn;X9E&<7c+w9zwSaHGcJ zWt0u*I*XvGOLm6?ZgW z=x_ISs8hRa1`}2xR0)df)DtU31)2EbJdawVd}_ELH#kCX!T}Te2U0*D!L`>Mbez;d zdD_0YWG^Hu-V*aRExvx~zn~(Qe4&?8J<31IhpYTPFw^s&>QU$z>_4%N-dgyO;fF~_ z&_?p1wZ(`WOvX*{eeJuA8KpAM7~MekjqB&9K8G#wdd*e^dY6_Vg#UDweVU6gF%{jU zzivau?wRRnEC5teiqJjI8;Ybuo_qkLji*5B7bdnpD@EQwnAC8L&)3M4Cc96Czthq< zFH%KbAA+BHqLt37Zzp~8xg#ci)2Ky8nzv86SFA=0i!(vtwI;GqnYAPMS8VM-+B|jU zC&YJ%ceq3Iu@-CQ1tm%&YvnNb=p6FPWSB(d(R-tNH*VKGu-4W6=9+&tX1MSZTNqEw436f^I+n(*AFx-fF{*pzsIKSf;J(Er4Oi?n8w{wvd{<5OkCVMw?=GdV zSYMgXnZ^3Qw5-mn>JVgB`TA?c8Imb<(k8u&CO(9U8fy3Y#zUAb2{3@#&Eoo%PVEt` z>(MMU8QjT;@FLw=$ndii*&UCp~HtP>}O5v zq2r!E zT9uD#=b`xG7oR)}C;DD|mJ4~6c}!NHKx85xD%c0&pn2s`*Pz5t@n(m0Baa?TvSVpG z`$vBBPkP@@+e)N4>hASiG%HmwpFE*+!$N!`Qdw;L5T=v#Kihq?C+PTq%dYa#6Sc@I zBIKsk(1g70ltdBst8$<98teie-N(bsYGO8O&=Yj`KNPfW!^!=8P(K~p5dfz0<$ezB zP_e-aYyNw4WNB@fI<7s@d1+_mR&s8Fb&w^pQh$fjehcx;11MBuc!)S>_9Z zWFIJwy&5g#AUEkpHf+LPCZ+i4W6PdmKQXR;1~8wv8oF@GbQwmS5BjKy8Ce4@Zu=ck zW`W;2g$;_MOK)L+3}G}Au&6!qMQ_yWEc8{Jou`DTj9=(UaqJewYDpZU!@>CGpl64i zulb{6E#oIxQkp!l94=vqh0>}))gmDD3Y5QHf?f?IIKoy(mvG>Xl8GkDoWZE)MVj-y z?b*49I$ZX(C!UIp%qUOXP)^E^(Y9E{E@cPvUd8Pqm=(LYKCMBf8AdT(bw2+{y77Qf zua~@;eH>vf^M06a)lTPw3OcpKKhux6m>+rBa6-;JY(Y+Lj*jWuxec29N=-rM6EKB| z`H%@F4`IH4#;7yEZ-(SXGQp!xM|7q8YOMfdUgjrW2FGBI;(?C20k zo{dp!11s^+NfSGEYKV=xDV^Z`0Ch?tU5gIMx|UG3QxP_7{?`QQ98xl7AOoW#^nH2O zx9j?dL`Jt+<&@p_@+Z50e~X z6sYu#P3Q^ZD)|C>O!Ui7&+=c?%KUzZr1X?LUwygp3p?tL{X{RA;US+3kxhIg(HbkH zV;1NILpk7&49vVxFWVNo!UDgTlpEqXPy2C5IP5?3fJA-ldvWZ0-USb;yABThofr0j zp*N%{dCvmY;>`n-C*^$N>g& zVhi$-%6Q60zPHTHv5xcdB>Ml0Lx{bw>q|5k_1biMZFDZuwCjb}qUo}{y=ka7uRiX; zvo8D5?T4tb%frJ@;|rO`BE^$UO2eLZ!#T+G{+CDPZzMF9mglphPhjY~F)xJ3?qMWR z54$62&9X6x2ACOf%zvg2U`%yDO)PASKTB~RqPm~!heR$F2^}1GvaJQ8;K@?Nk{x6{{xCIKS=zR^5Wygq|wxg>X1$~?WAp3 zv9s$-g-jS%CMqTI&{O^27RxiYa zeJo)NA_mIspgz4KHK8idSqd6}nOr|!_6R-_{<2TGm-S2li4Z3JQ#DDP$| zz0krDiaVy>6hpDYY%s7ND5xg-=mG_+Dh~cak@!e2FVj8vy4=Sm=FGM$75jx@v0Hcl zpD9_t^4T<{`bv)RIJ_1 z;h#ee#m~{I0kY>MF+eW*U-8av5~CtSpT}tUX`Sh#n0y%8#+ZqqXcWj0L+jUzaNj48 z)^{Hb6^}Ilr~?2LONw%@L&DVdid2579}WsF^p>nPyWgArG!|wCDAN z2N~63X1fSa&4FECRik^UrQbdF&Hif5aAAHNW>yT$?zuBHOIbc@iCl2{mgshF0mvdI zJ!(O(Jm(?rsP<}`VoJiWb3){)?;te_c0+vgGX>QqM4k-?zgtyPIWD)tQ2$bn*{kQF zQ_`+U`91>0j@M-WWT}0yI=jT%JmX)M5bn6ry_XPKX7Mu%bpAMIGb-1x6k7aK+<7Arm_&DH|-~)n({#bgGoNXMMnM zuj`?d9nJKnPH@(%o&$|LDA9W!Z@-;t*^YWkJDH`>lci{%r@Tw9u}6Yxm$&MgWhE+9 zO31ER`J4Nl(RHXmbC+B~5A!7(7Pd%B8LLNtv-7=J< zaqgSv`S8zc(XxSq(-xN|pUfB|GGtmWbnde$I=|^GA{!^Xfgt7oG`ArK4NV4;&p*je zz8%9G?!0q;HMoluwnhympM7F(lX!aK!BD}4Ygq`{=&|7ByHQ+2Yw4hy!Jmn^!lMfh z?)$_h-S)c-fcMMB)!a)WU(@Quk*l`X5_2fri9{*)m>z#oCC5;?9dp=j$^KVnUnQP) z1N+nZ8n|w4SNSr;w7${t2(G50(50l-^rMSh%F}-*S2P7%aoO6`i7D;c&M}8HwJ8~7 ziIitSXogh%&Gplbvl+J?RgXk!4>nD={Xy%$k9zRUX!dexhxE5z(VEsJs7_aNT<4FD zT(77ZMYD_j52|G@TFD$aehF38bvGjCBo6}mI%-3P9CS#&^V{}XGCqc9x0ifQr)_W1 zrSYqu3!{aT3;F*u2)S<+!)NX#MRoTmkuLrWM!Y-if(wD+<2Xsg=+=`9#IgvG65cP% zSt*|o(Jg?JVk%~OWG_>aa30%Xf`ig;Szr96sId?3=_q!(od2Zt&b{ub!asb!(}4J~ zex27_U{#%lES996rEKJEeUA{;_K2?{S#VWl&mQnlZ_3>&(J8T=6q>j8FGfaZLyoC8 zId%2Iny<86JJY0kqGQn2TdDvn8##zSLjStdx3|zM_I*cg_`Kfz!XL|%dyBl3H|~)W zp(uobd)vNb{8^ljE&1F?uuW0;7wW#E^RY(}M4ZZ07cqAHx6GY0EnhTA7x=sO65j-` z1>gfmhWDNVzb(E`_Trc)-}UpOmv;pgM5w^!(tj5teAu;#xP{wsPvB3YK)1rfx$IHx zoaev19ve_C#~jR}zl~^Z_lmt+*6Jb~S2+|mL6`qMm4obFwEh*AI{$h*DzawKU_s*$ zE8WM(S66k$N4k2+J%&44IhUfS@7p(UfS*)Z`?JJo#?8ZRD(CtYp(S-wWc*`^B8HPv zD*Y^c+7LKV-mB64 zqbB7I-$%L+qiMxN%3Rb#jujr( z5_hR~$G`%a=AV}X4C{s{u||1{zYYA%Hu=e>OS_)^NRdAgJ9i8I^~d4JF<(#Ge8*W# zvSs9=rv3|@$ZVFP9CV-G)vuZ*Mpk9m3pH~VYi^y|)#mb1Jc!Is!0F1)NT`48F46~9 zm%(v%`lT9q_G>TKZ9XzH|JFDXs{1Q54e!9zyQGP6u(pT*i9Ul>utexRbU%&SGHYO+!04z05aZ$cewoAdKq@ZV34uk*X zp1u|_*Q@z~4{0XSA?nU(kbi|H=xYcW8`bQfR@iX0PKGs@iM|M5aZ7FM+Wk<^h&xk_7WS-Nn-3k`g z;OHIjzW+tg(u!+5!%)(#O^M*EzA~q_N}SF%ow>6za_X1vOpAe~d-3=@)D*#aaq&;; zkVw#dZBTSz{+BKZ+n7WDJvmbOr0Jdn`Om@Irv6G*Yl-)U116=q7;la|ZrM`(elx=Q{Z)I%pr~8_vTjp^C532I2JE`% zTQPXD6nb#raUq^5{W0W8gH)y;=$UxjO~fl?&qJ@XDc2d_EoAmd*%-z~F8gV`qsqOS zuA4J_7oL8IJU`JzE0~beRQI+1DPeOyj^q>>7mpWrhU=8W(pACo@b|}e5a=<*soubx z^!fr^KY)I#QsIOsT|7-Zj5@KfYLN{852q0}#Tsf)RGag4*k)h*v2j>}_8oRl@!-kD z0@IL-b+1s&w58sYe;``8@82%IZ>xVBWjAI#cjy*I@nhTkQ9+CID#XrT&{+OwqHoNI zQIsF`wK4Nm%*#DOaUCC@ee-9JcNH4!Hdww8^+J{L%kfF&!GT>Cmpru=Gj%?JR?gJO zyLs1V2$yHl&r%Sq6nK;YBDygtLKC+GNJ*(cu(py|!lWJN79$hn;g+P|t3Pjtke>u8 z;=qtUASEG(Dnvb5O*~bx+iRl0!zpbD`J#wWuyUcvDnEN|R>k?@cKw@_GE2z4(N)RK zAE|%v$a0H&>v+^0q{-7>5g(P^>Li&)EI9E;=i@Qd6qH@y4YtWH?exFa7DLfiVdoMC`hcHqdXQx#vC>JJJHICZTGKL`YTe4Ue}d4ROrdlN;XJto@+l@^Du%U zO;0e2y;dB{HM+F;+^R+OEIs+Gc*UdJ$-u5;39aOd=69sGk|OdDj)hOo8zh%GC52Zc zp8=kg??A4AB)k(`E?-R6mMfE4^m-MfRDm>YhsFF%^ib~g4l^hceSBvZx?!U1XAhpw z*LLa^WFA9xQ+P$g+NUlQjq)qEN_1pQn%;p1sG*4ppB`4u(4zpU*? zL6Lm>u^W_A6R_E#r}f=7?u`3CJ!^W7qMMc^I2 z@)sB37upkjfn+ZrS;)-s>*nmN7*$!Y5XO~lRD52c(Ba-#UZtJ)Lr_H3ungv2uF+|# zLaF~Kqy4VWdagkoQ*c)%6y+!G^gG)aXklMAT~cRoqJG_loBuo;SlefQUeSJspn2o* z7tQi3IHRLYiCp>o69qTDgs|g>EWPtIU+HxJsd&zsGW#o%!wG8Uh`&5l;m}x%N$yV^ z@Jo?9R$DEZ$vCNXNu)M{O$_hdPL4K6I%9h{96(&mOui615FwKMi%*NeAp+TOqATcs z9?9MS!ka&ER*Zc8H{7^D-=C7~D+G~OL5dR`3C~o`aIU)>cR8%F$h|T&L9u#DP$p2^ zm?W=Icbn85d7Ee8wzjX_P-8+Ixw@QcbI}5vWx9>xUS2&?x|X^cr`Y6aG3vJa5LfcE zNSfV)-7rXo$3!CRPip0l(Jv|LZB;|P5 z?eBkJ)JoMNjy$};xF24V94UMVP-|a`^0!A31odoJP8SuzU+C^^aRma zpc=mB#5_#5nQoSoPoezJ`B&bZ9(%;T=klt?aJ+JI2_=~|k?1?r;+@HfqSX5FOyu!g zMIq?#tHI|KkLZpET`7w8?|N+`M)fD}y4YtYUhT^0KDVVSr19YakC2u!A^EycDG*j=mXwWE{tbM`=#= z^d?2ui0+|GCDtIO{=r^ZA}+ci{OC!i?BL$E*Zj7UB5jjMd4r#!I+U7@IyLXc)igcR z=`>3fQ$ZS^p%EIVvT?&rDOT|rrRyZCz=(<7tL!;}OLcqFcW}7u(AUa>qiMBKDyn1T z#*MU5O~a=7*GXvfQdVCptm#j4lM1uO19-ou&Pw98>M2pI*Mr1UxT+VEx5F9OMB4*z z{iVWj+X|Dg3|6-^zPWreQ?+ws&-c8lzYM9rz;MyW`((Dw@PMXXTxtNCt!oj@^ z;JAw9^CIM(F?j|6|LSIPbQ(l%y!Y7;tgh=#yKH~OAk82@d&L<=&qjSCSnGLtDrV-h zJnucljWvwD8&FO=aPr7w)q)Uc<-BCugRmo+?_RXHrXARaLSYV>+nJgDFnFr$@?UXw z%looW9psaeo7KksT{3Sxz9f3_`>#*#$sUHGEhd>?F>mkO+P(W$O`cIdzP4pYKJh#` zRHh`p$EW#=E56b=;o2jLRC3@D$v-w}j8KJ`c4q-e?dyq2KVacba2CK-h&`wz;+?sz z?Lph_co3%8_(q`qCENaak+nR*Ri!mDO3@vtWQC!qjR!BUbV5oV*P6&qU-alttbZxa z$h^J#{*xD0Jt~jKKA)KV{E}p2YK+hH@O#!>dEf@Rtzzh#o6*Ty>{p!g*9x@fkgm7p z3?S)$N?uB4F!vWO8HoSnp4W^<-Y-(Ca`Df3chJ>iy{p->s+pL4*7hY!F6EJYE%IcJ zs#2{E*KTet(a&~?1tfc~N>UmXKhH0m**ZR3Sdz%BAl!GS$SWMV8W49(ONV} zRQR`)d|6pR33}+|og+*CN71>*Gx@)NeC)hQbIiFpCX_j!8Jn{-5z3)CpP91?4YMJM zP;wk{3^|36=8$t4sSq{C9Q#bEbn^ZA?VtU(`+nT_^}ZkPUH9vHK6Uw(o>gfY-}xIn z(0NVboEQq|S>1|u=J4OV+_Ntj-`r}auId&p zQ5?^Z(Sua<=8BCv)s=2DgC^*@tB>&~%Hi#useXQIR;G>Zi<@P6);e-1ez&jv=AwRO z$ugXKWOV)cwO$NPM!i>X%TpQ_cvzrt(;~JZtsRO z)u+Icx3c<|wrOd5^))orMd*kc$|_22DV1c;1phEyIe*Q#h0i9j{@$On4Qn6%zA`)G z?JXztn7Z*sQOx^4N6xmcD#Zi!%Tk%+U9!OkU3YO@eVBn;9j;uy24-^fm{9-wH+2pi zhm}A&GX;-|d4w-*g!TWmcGvfqY&g;P@ZR0AB7xrmZVw+bC7`XSe9fK9JkxB!e???| z$xO456KCc%_@e~=um$ucAKK7-HX&f>FzhPcdu-HI-d(2zqh&hpkIt!Mjf zRb4t`Tyd}LpHcnZkdW5aT!k*2pZzxn?ngXSeD;q=JrBoUdvD+#pCVB!XuD!fEsUjf zhL|xZOU?RUcXzse@a)BNkHx)6*x-{v#P2OPYSk?f9RJI!p~C5B?-iek0tyHn*}U z1`$Ee%FS_{Ci7+6M@Q#tyS;enE9UnvT=s_Hi8J`Jt6`xE;UZ(K@5VmKiT=5_h))oq zt}RExwCLP;1HPlw#d|pZUkAA|GBL*P!wtMahrPptuP*)(&QDq`vg(fva2N2k6dO zg=q1AQn!c$GJp>iF0*mbrhZ?K<m{|FObbvoMrakW`N?(ClX2yb)Z?C$KbDyn{`gGa z^oN}R%=di-&_bDrcd?vK{D0d{zyOlJK;V;r{{fT$#~*)=aRBZ3`@|^(pFB+TEYB(N zQxejWGH2x!l+Vg(3CrrEL^a_Oc$nlRxS|!0`Xzovr<3P=x#h0&>yQM^VosU+3K_Zz znz+m0Jrytbs=9<|Ifcl2$4NLO2wX~$G0zk;xyP@ZCnQ@ftk5T<-zj|Ixu{D&`f8IH zfqurfNHVJMbii$q&{Rq9B(>OtbJXOs$89fqw)6w~>D1D*$xWv-I?oh$s5Fl%zZg+r zPMlvEkzeZ7_|%A*FHxPkuQQl~@5{CyqdQHuxeQeXv_1@KtGLmWCo<&4oyi;h>4AKi;RnNP7k)I@iBhxV>|7y z^C`+Tc7$&8KBM59{_?p04*Z zhQ=mFXJ(im=U-30-W+|g|7QC8%7=sXwN>_i`#%nUeLnpD{^ysT|Go|VTD(`*2~5(esS4ZaoHbBJm|Uo-+jNYMK=3odV7`Ur>n)+%T67X z@qd4E>f7@(`(r#`-^lFGOYN=6Ep79zZ1K+QiVp7xKHC*&*yW>tktyBeySpWw_F3T8 zhCsxIklz-+>t{Zj4N>b6C5v&4-G;Kkj;O&pN_|B{cKxK_1|Q$N1aH4AYDJB2(MWvt z;@Nq;%&>x7pERb?1YKjL{XpkT3R*tl?AdGQF-BT?+G_fW7?aal7bFb`ipEx2#&|O; z8%u(drQ?;$j;@|QzTTd}S9~I@Nb$CDlq-}B=lf}wvW^WtS%yIm^unu*Z`NDq*V@sZ zJ3j0umb`PNZ-iv+dePRbVz%vl_O3eoM>N?B&}Ao`VJGo_%S3&T`0NB3Hp}yuI#C4WZJi#Oi7N+sDprflK30AHRP>9Lx~6?r4~A z^M6zCHqp`ep_8;aUSi$ZwA2&#ZF^~=^U0?dWFS()rmJ~*FpW>qeX^@%btGHby42=b z>-t22TF}SIXKkOS=(yVw7rNWG-jx0C7w%Q}O0nGku1?4axhxl-ed^a)y-LX%(6!y( zJks|&A-W9x{5Rs8-XZ&S^qh8pDpXS3vyYF{{7C=Xi(Aq6j+%5<~!pgZ462%(+ixBs{301ussTou(#5uT_=bEm+$vA5MZ6Q??POjS$j-vC7h)CU^reLBM z9{K?W*}@}qmsw+om>+{*AzL zfQ7P=d{GR^k?LxREB|FQHRZ|G%NaVCC6$caRt6`&%Zq9l2dHv`7QqPK^`P5GSY z;SdaTF&){{$z@+VMC#?Fb^0<*Y=pfS9Onf63OGUp?__vT1wVxDgmk&AErQQIJIF+G zfKi0o98aTm_5^*ijUghw1^o@Zehd|wNW^4$fOurKh35<25=2lRWbC&uM{SF87z=m^i9*`pbFy(^JsVgi=t}j;2*W=!3IkFxE(f57`!_F*3&3x+A@2r@R zGx%D;ydg>x45a6niaEQg3~zMynq;;)GAkwp+V#V=RVYPZCEw|cpjT4d6_sG6K#$v3 z`B{Qb8DJ0`d)sAk1ws3e{Mo_p*|pgf!LCtGVSf*@;_Rf$Q~N^U(3*A?^>MCpJ)9u1 z0IcC^&4uY15FSQ1Dp5SRjy$rL+g;Nj8eH1}5otIPMBb3rv-E3!bo2e=XX#o*ODEqn z+#9iX>dzY4TvoZ|AAIAE317Pcewa!TUk;jz|8n?pGWZpnmU>$IF}%$g%yHF@47o}Y zxB~MY4OF>(C7vk&!pMMt&bMFY*dnP7FBRRFjX4T=kTkVbL90{eKQxkjy@h}?A7S0h zau5D5ia4PgwW@(`LHy-NC&8KQR27mjSH+@0R}JwI4Z~0%mIeQNk*6S3Zq3tc+4*YM3j9gh zORp;)VCM!-LByj}fL}Sok+JgfOiWAi8Ti%83kL#C7{Awf?;0%~51%fIq#VZ?5y+kj z{wwr{Fpufuo1KiTV#*3xwOFYzVrpIG6*>n14keK94?I|3qk9+=7^nB$0T#HUQzpg^ z>NfK<%RSEgPt9)j78BgQEY7nIGB5i^$L%e(g{m)AtE)3QxjZrL*#R4$E?mvxYG6Am z;YGWg=T-#k7^X=`9c(Wz`${|APqBfCc<)&tfbca{^6y6sHV#~=9Uf4)x}R}rs_>l? zMy2NXUH#w>k0gAMB7; zE)em0AlEtxVV{@GKcCoCO#Abu-0J6KK+JieyallGq(j{!ROqD-ubS0K#$68(xU*>s zHiKPt4p$3-KLIbFXQV!kSh}&(S~-~^95E+YFV9d2_COAK7Qci(HBma+)IsXa48Ub2 zIF%4EkGMWhfflTM`V)eMBeHqmf9kH1S2L}=uuxJa zNI!6Mt*dzjcBDuOK2K2Xv{MPyiIx0RwfUn9dgO}9PUf!$D4gvQ&A3IA+AAOZNqUC* z_{ii}T_8*K>;QnK1=FAKe5z_^?L%4}>*w-32W;d2@41g1k~>`!SJ8=@IM;5H;%E*Y z(fSyk^>{$APJ4eG+<>@eE_q9y_VT2=3NoW#3UTM9Qr*SZfhIRZK7XM4DR?G1mrBRH zg9_?Sr-nT9G7_h^qf?Sy9y>iRedpstJZis^l;J>^8n2k(d}e=Sm*Mb8e7AQkw6m=- z1`}8Qkzm_dY8j5O&#u_3)_ytvoUpX>ZRt}rN=|Hm@m-|)%Acuq=?Eezh!ht=bj(av zeX**U?g;UwL)Mca18;R)2qE4i7cWM*cr2ifgnR+L@fdKio(it=16Pe0$=4w4NX~NA zh`J6PPJZyQr_d3N9b$MW+(%H_L+a>=a+-5JE2*A9)IO8U_;GRYOt3^ME;JP}=|pJ) zBrN!P)DcqOb%xfVA+;og<7UG95jP)z1Hl*J>gU#b;EnY`RHOX@N5K0JVwU|vzg7DJ zwQLTZ5IzKlYDR)P8+_m-_elVfuyM+02JKuyI!gWu@j{(dmUVSwBi`QkTI&E4s*isf zDNajoB_Ugz(`zwEF~^`*Z1RCaavM3~F~PH}6LHx&p$?N$M<(Q&1DwJA+o0WHl~;3H4)J48J?YTVgF&>7K4cWGj0&Zj|ao+Y^X zr&16jHx9iMHsP=1 z5C@;Z?kI>S7(z!uo_@WX5-wHx6%x+YGm|-c9)C`A$Y3DfIzrQDEEPdQ=X;TJYOf<& z(8vmU;l384^0=@G$O;`~wZ+B97%oX&WGlVUwJY^80U>Es?2H0GrkdBHBaEC&aEFmj zsN$!rD-95e?G+D&t&q~ylpFaWH{OQ4qd^{{NlpH#`wtNQHCDSvYG75T> z7EbDjfE>g?3a)~4YjPz4tPHongd4-9RmAkm0rxNa-~SbZ@VSC;Cn4yhQh#B@Mn(eyc+m3%0ydBmg@Gi(0)3BSgIM$_?ytS2;M<;ZLh@e+hq6UVSGm}_+q@OSfj zQ1VR^kqCu!b*GnSBMTLB${FS5XhbUj(N028)eux1QgWrv5sOIWKSIdqA!^VFv{h?M zb6~M0*y*_5*vJ~9aY-7|buQiYRHV9ABycvoKHJ>TxdiCv=K4AR!`09=XT-^|ysfQ9 zk28K7_eaLOy#s%NZtDb83}6tV5s0qeEtSNkN=9@wv6XI#Y`lsrs`G4R znm-s%f6(!;l|^a(OsMbytBzf#TrQc0l{R3h?~dN5uEpG67C?Gn5R0jyz5$4ET6Y=N z_vd)W^}_Cr-|#X9d_ntGtX@al)lLs$=%Z{%Alr>jpq4V>WdH=>W>b0gljt2VodGUm z!fzc@qL9z%en+8Lby3fJ_(I%WLQkrrP~V~kA`$CQ#fFFaGd6xF(AnTZJ;XJ@@gYY1 zw&C#IV|?{U5(9p4ritR>aO7g)8qS99np25PcnPM-{g-!y7^0K`FQmguP_b?dco7N~ zM|f6BhyPx7i(?4Ew4f10_ZQxME1fa!7{o22Lm~^DNOy=~z^%Zooou*R;Kct#5hdi2 zBKCkgGrf||Q9%F?q7hF4TnaWwC4IyrJw)}*(jcYQs++x*z3CO%^%bO2ba&4c45A60 zBU=BEKI+j_hp^v>Zqn|2=Y$A(53ZlggXuSYuI~(~nJCA&x-;O{|JL+O_Fc~$Eo3~Q z17Hb=n%}~ZL^iaT0ss6MUQ8VMvr`p<94w*3i-?^YziS@2b_K9UQ?5c|+0ayE!Hx3M z{>-!aQb%XQvLQY!XwIbq&33nMf(X;^a1sMfBtx%}p#jV%rL4LVMtLzay#$M_WWk>= zPHb5qD_HPuG@@Du(Mkdv-5D)o!DE!#;u`86>b|N90u*MXD`g@d?X;k8yi-%mQMvti zIUZ4OiMU38P{)R^+-WqA`d_8h zpHp|euxA0fVTsv3zCWQAM0a;Kl=gGt|Ml-w^J(#A1C~Ah6HNzhsp_dBS z;N$#NF#&v;(dW*3L0f`9&wLwa)$P30Rz@_wBh}8h{#`DVc32zAeTe9uj5?NbrZ*@CS5w0evBnG?vd^y!HkD zko-0-^DTUF>QT`U`T*WR%Bdg%-s}#TJ%81SeDyg1p(=`G>9`&(o5s}LMyx9IRg=1% z#0SVI1XG+D(on{6XXK1~CmjVVQW`6HRRdZY*4cxOgp82saL3S*la2734RD_?^QTMu zSa;U*(XeaG7Y~{l9|d4!rcDg7EA@s9^b#~tYdqkG!#7_CL=p_ZetfQX z)+-Ix?LWd#8myO*;rB5M5?S!FB1jy4H;=yU^ksQ!=>_ZGQW0yQl!$C+!EGitI$3bE zcXxHr#A~jKd8Ib7h4d2nJCC>^*O>5H(%azUXHZF&N#f>1^vFsdlfz))!7iM%4ZSP@ zyWR^w&kfuCbG-YQCpI(PiEwGdja%FBB=q)_!4czT2AsR3d%9^muX#i+6rR9-qGq@g zjjnC8ow+V4b{s!Z6u;|1gzh;%yR;4s)$NL-!^v!DAqtvA-_tW#wF-kjzFTxRaS%_5_f0>(rsd%pw#$x>Rn`h|vBoG5jN=Mv#j8S7-mg4Nxz-_y`!@rSwAil);oxQiiz-i>|Ws! zG!FA)qYUnS?T5S3lF!si5fOQ8F4-D@|MvyHeWLY3!aJu|eXqHO$^b)v>3}!Yw#A$r zU%$!{29!%pt}lQTW@|2%>n45W9Y&%F4-KO^&yx76ZBZ(21CO?*N+`_sY*i27?YDiP^u2`-imEn>-Jbg;4ZB#P z`){(;w8(MqYDdUYU#h6n7uRmziF>lvpD&iE6OZEIz|GrbDS_(0egR<@=~{{W(7@|k zm#VDfQxku2=DW(8URKCC`eqYwsmhRibYOgTj91ReM3LvYIFFP}VN0)E3vWHXmVg;{!3ca7PP*cM`wriE&yhbk?Mv$)#NZd4CZ zJUAmJ`L;H#l2yywWkzSV=?~=Kja!D+ns6U_j$GvsZ(4H2qq}-X%(Z)lqXRgUaj(?l zvRm6L&A5|Bpcb6&O08Fx+%`e_gw9Nwv}xn4MR1GuZ@?<|8$rbj4b}%mlzT9Zx)okq zj2%A5N^`#fF{Sw{Ssgpztc0?ZucKJmD74^JZ9+x1ALUXeQ*&*&QR~PhO&!L48{N7S zXKU_Rf00Yh4m`5r!)hnh^I!JlzTR3EeW|E^@O$ia^)iVYPRwm zd%R~nxx9HTx=LED>>3wTtsl$uco(>wF9)B}4==C!R4KIXP@Ci{I^I>(S73`y>sm?FOS!1a+=1^R_mcw)8Eu80LSYsm9FnStyK!x>$7oxJ!_ZU zG6Z5Of{(&cCN_}$dXtvXfy?i&J@D-g;NGuK$6Bqp%qt|j+?H?Jk=lef`0 zsLnvX7&x!WR}f~7AdR0_`C@1#!BG_Zab|k_1@-eFjvv1*oQ5nz>2OcpTlAs4cuEnp4R z%Y*Wh_cqr*vaWahPP#3&CS)$~!wGEVO250-Whxt`Vxf;p=1pf7Nq?*&#BJ{-T(8WO zt!F;+II!dICsoRV`=R4_6Z=BWE0v@NR;D3a#3yx21cw^9@tkF}Bo{tFJt^0RW5uUu zu}Bu3Tc+)4sla}8FR|-sXLf&ZaK_iIUF?dU6_)dQB6?+dmxQ~rEXjLM$XXm`2YV9y z=JB-z>pAxrSrdT{8YIFTPDNnkx23nj#YcerO`Ym&23KxDF89n3zEVoDcvUzjlKX@-{!{(nt+_5h&onJB+e&%cCkW;HDYdhm$j#^P} z5C(nwLM(5Y<2ZRi%vyri<5es9ZO^BFh;MAHhIZWDD>W*s0bj7{u`3*pXL766rI*vp z^(zt=M|ZRZ?OsTIH{n@jhk+!+$s@~Fyi0^&PuX(kkuMieDXb4wqsy=Y4ojYq!A8C_ z(=>B+fgHoU2Z^8@d8L-K)Y4h;`|oPtU-RXRR{snJ#~v;pY0m_s@?h4ohZ~002dYhm z2c%C?+OliDbyivaLoU+%aKpvrhwTUB;xL}{rnPcZ%Rj{Tz8;^Dcam4*gajqn#HHL{ z<=m&X2hmDreGOUV8IDh-B6hBRG9`J5rPW62bho5MU`%-Wn!S{H?Xq04$){eRDfyE9 zcLp^pM6>-txaG5cqYCOFm(e5A860z+#ucJtQJ<;n7OUkMW;Dp+y~_$}*<(r=YvjHa@mx?|zWPvG)6pSfulaJ}0t`QNXmxKCCmy_}|H#1P zVazB{idUsvPfTjT6%wmi?z^P>x4%0hooB9I=(*~V>MtJqrk(hmqO@@N3Q>xXd0$V< zoe1V1&MbLzAd%zV|vX z!$;3fI!S<}wu3$mo%a-5+N5@TbK?%ns}x&JBQM>SG;-4(;OxOt^2Pg4gt3-Hv;5;d zrAwF=*Ib`uqz@0~dx1B;KvkCic2LNbBiK5Gt5_vr8*h7M;$8w>m=>@Y`Ex%c ztSbTYM09tSI+Nd|Kl$r9Xdh;dNk+-n4M`X3U%s04@Z>u=ki-`T%?y9~LmCSgJJ|QH zI^pGFtdN@H5Lcp#`3qFaDDD87qqzP)AGOe-C_SXY9WFC)l%P!0mSX>euH8Jf2-7xa zfg`j*TGk*uQ9TSrGxOJ{;V@>|`WD(nrrBktbgZc}W!MU1R@)tW)yN`;I3mzTDp%GR%K~3MHM~urK>uYX`u0&l#fNq<}hJPc|#KdWsFQ2 z%IyfgE}_Q)re5mA`!^jsk_;F}hP|vlC0CJFv|0z}3qADdn43Mx<3QK5wdV35e0Gmn z^9wxVNjwfj12X=m0FFdy5d^Z{5ZQE&s_(Db@PT?9&kch?&Dhjo(IM*No^Ukng>_Ny zC5jn=0tuotq)-$*^(ZUUvj!uGmmQh0t+RQpgQeFG_S5uX4{J%+>43M za0{j1J6$OhibrN6B?W7lS4I(`S4&amRvP!8skR!oic+4KW98j0X#38>OS} z6%3xqNPn#OkfIJN9(y^iXJ}DnG<1$kWc_Llt~SqvnI`1M{hz%&8j^I z)DWgMi3km2TK8I;-_V;Jkg@5R(E2m;#EOCq%N_{yYz-;UHr>RVqi7rv^%GpFf ziYXS~YOCvY73;OT1EmWoN)|;g4|95ddybgxKxjMtX*L(03*$*x%Hs%1KyS*{pB%Tml8Y&32RFU zjvJTOaO_|pF?k*O*sh=P7Y!|X_jD=5J?g$|R|pdl2}nYXLU8`(U)A5JR!yn-K#x!au+35^^$V#P=hluV$ndHVTr;1>aGpAz#D>&FFqAJ~{w$7^dQnzE)57Ft23ZUu3!G`O>2;S|J<9Vofo8SU_%uL=scOgL(JVzne79-QF17w<^J{$bik_=_ajQ9&0=kKX9%x5; z>*F$~jVCW#v`s}bsnhrolLB2!LgrB-E9JtPh9TA-6a)$Z%oqK;9LlPf*Pz_8cujvh z{6S#Br^N8%(zwAK&}eo#qffG!H(gLDT3v}z@?^KB*ihT7%XYk3&$k|JeCw#9Yw7J* z7LU7QQ+i)!s^jUpKT;Mu)rahT7R}~TUU)MS^rnm2r=sSlhx1y7&F6y#GpY|>R_IZp z05quU@gxDBWI>DCyv))7;Yf0OgKmq@Zwo)~)?=pluhs`f3>Tche~tQxopfwncMO5i z)C}Hi=YN#;rNxde#Eu?)+*?oiB2J4V&>{<<5wdT7fRhG-KfzE?6ie@g8cjLh2@`TL zL7#zZP6=E|!DR!KtDk)KS+dZ(Jg%oSPNB^4vdpZNvYyWTzCqOF9}4u*#_eAI6F40e zJQsNGJ-*9=gmN^bKi<`)gmx*Iz&y-u+o_3PjJ&*z!+?Sr$MtlKeNPd}S}u>Sc6v*c zZ5)vQ2$cMO8J{*Et?u;A6&iaiXh$VQ(V@W>G~On6nJ){x?kl`hXs|!D`K=vEh=zjs z#<3=1EZ&5XKD;PefMIA~7LCGTG?F|`>invOrz3P^&$|b4Ke_%#IRv%r-UvAg9)$$W z0s}{ZOBVv9pCeoSx164Puo?&M8BPTQws7)J(XgZ^zGPGZ&7XTaYLptqI36y5-oymP zW46^&p;1^GBn=SJMUF&4Z&=V`ggCbE(0GRfqvJl*azk711O}SXB3RVUbDsM{TLIr8 z7uUhoOM6Fm%=K-tTe znsl%B%u+QW>%pi%;=A<{ZjN|>Z!j5J=?;zWq6W){#*v|`Sw~PFIuunvj`pWUFsWYJ z&?rFCb${q}A~cpni*csK_|wjf?4ej+P%vl|eIpt}L!pyGY&}A-6w>Bv9t`cN7|m}^ z52Own=DXPAHevArau;}E9yB?8(=Md#5>&}zII{PtzI7EYX zF(G9ajGmX+;fNQ1uTZ0iQ==C^zwi`g+3@VwRHv}df!W_ho2X@O`_kf9qa~~q;=>i9 zf_gw7oo+>E*m}gGl6VfcgBZ}8*sn5EG`|{XJRK@?nj=<-!@ruwOaA&|f*k1&Y=__Y?21UsG*)1>hnWrs#v&=ky}TR*7b*?{n4cCk{>tNi!& z;8!6+V|W02!UmUMI)rm&;bte4|M`;UE_Y4(8|#CrY)HXaim?L?Ue?Eo3JKn{wt+-s zCmgTvfb650yD`%|BaosFNG7*CE^XK49j~pQd}BT>Do#h;9H!t=a%W8hJ0w7 zA2bS<#K-;-nFc^%p=#@alxKxQovJP&)f7 zPM|{*(`X4oNpS#Vro7rK++;VPgdz^ofo5or*ntwY}{GWqVYUW`1bBjj#h^7vuH(pEvh2q1Fy#9 zW=OGiu5f=9?q`Tw7ikOs$o`C)TSw4M#C7`zAs59BGj$i9<%X1Wnx(U!dqH1&N=NR@ zCh@($BhekR&73Yeian{)Q=@inGDSymi<*fas1{=J`6~nIKDWYh(^rlOQFe#c)#A*Es)##TbT*xoqHe=?CRy%cvD?YSmX3N+(U`k0!$LfR@IBM@2B>!ey9xV!)v(g zrgYK~a9=x;Q`2WyEv3+L_!qZ+=W}5Z_{}T~C;S^4QLOici{C_d@>$BJzEp!+L%mcU zFiSEX?K!F;&?vn%DR^nzBJO2`$ff#<#FQ+Zp+r7ztu5vQTWkLCx3BfjD$CLjsoXj>P!zwLu0gFmz1s{PnQtG4jdlhRW+2ZS8m4fhLa9(z@~GgQ9nj zYV|+tkrZjs_rQGJnNzu>c;)OQn~^VHN4alU907FF@X47% zUpsXiR>kuc%rp=d0{7$h3_sDc=NK*AH&`ihhfMPi6&xpmiqS&T+MGPK#?YQd(-etb z+4D{^(z?w46QKn-(Rw>UfiLAJQbolkn^aDCtD`y8C|GF4e3CC63lyeTuNUWVCT4z- z_(|wD@MUu(P_O{WIoAPiz+K@@>Eb}Cev~y}`0T5}Al`2$!up1@)UtNP&*YAbuJF{Z zT!x;Z9u8}pp|Z-JdtJ&yIK;_-Im1D(vhB++CU6BF9qv!@}~M{!yn-z4)}nR@x;x%-xz1rhW?XY?35!oQ`-a*@Nl9^HUE51 zF%a_s{Z?~R5+025=(Tay4s@*)M#VAI^sq_XBqFDLvl!y|Rtc+DM*Ph-M$80qiaf$f zs97XwL(zAAqgW#1~gQe;Goq0eo zu)DI!Jf#U3Bh99nL3o*DxD5mN!_*i`pmQP~X*3-v5R4K2&pEc>Ki)&{w;+|dQV zXIB2O0Xz^fLMH)2IS|^Y_xz(|utGr+*ZDhJ2?f~3$?PPvYnt$TBRtM{Qsq(zI`Kx&A~LaPWVB*#-xxB7`{V z`5PX%ag|D-_(fyHSH&%U0=6IhKjrHE?vo-+ELfi2Z|I2u3I>x;%g&{O6o?#N&S)X& z0sv@pJ?VNJ8TiNIO=IMeGf(ccR(jx7g8_@)s?|5*Y?v|g*!UNcIVik?9SNyjnfi42 zMihmC!hDO&i_f3A8&-d`s~31P8TVFMXq5O>2a^qIss?t=jhg#ZuROjK!zI@#TnaN` z3n+=yOB^uG+bWXA{lvUPrk#h?Gl?LB+49%$|Mi}~ZV9CU+m;hcf#Talcg?x_6SneZ zK=sn3dFjd@W1|2yM?i$7^^F&5T{~`VDAmD8}%*HizDf@!d9_ zCptT6wjlly$Ee9so0kzNmdM`Vf0z+{F`TmcV0jc)g@`p|;55mD-h^R2??Fj#pyuK0 zQT_~r(G=K`(6QMP*xKggA_pl6cU@kfc)X?bOUe;NUZ3(cLSe zSb=RzS7jg6_OvlCwjaKktPD$0@n)zrlljGfYBD%AnG}I)M$Oj8(Qw9pudrO+3v87+ z!!!>>7nykWld95S|1KvCe;UG0R#^m|ymG9R#=+SsAm#+<(U<{+2YYrY{Mp!HKce}q z*^_fCdI0{v@r*g8D|-55eODN}eX4wD5Y{#L?xD>{0c&!1p`(P%MrXin`j^u0fHnu< zXr`|AxOcC^48Vw%h6!M=l?M<5)2r%9Env;Gt@f#E(u9Xl1Bkt|BowL<6?E zUjRB<{PiURAz#LxCV$;eK`_W)#{efVKs5_M-hT2y5&#ngfRLQUZjd1sWGI%*i3PmC z0DxF5h|KtMAR^G8r%zt{or47xe@feIRgDf&#T-WHIj0IOcgeC=KeJ2dYhy^*NonW>*dR7!dhuhOMq#^3GgqgIr33 zSI3SaQYKJ;fHIK*1mFyskA3G1Ab||Wk^yMO@m~@ko)3g2Los9!o(#p4KLbwMyc{Im zLBmOpGD=QIETj}gaS81UA=0pK)CYBg*IY7hq{=74_uR%*pK{cHf7i94zShR)&O_)|up6?Nx9 z183j~eVn0Czq(DzV!JGFua9f;NBe&%8b?|0-Ns=K-+71r&6mj<^Pzyp4sC&WX#sr> z74*h&2`E_gtIFV1dsk}`3cY8rNM=6Q5X0AZ1HvHtajqeEfmOyST>!c^Q1-_v zA0)SffFM^gkc|V$kU7P$oChYHXfoK940Z;9wSk}6av%$A827vDrJoJrvG6D}P}-;P z;cMu=vGUCcr@04uab*4SL4zST0bwi9V%;3}?q7|EhR!&6rcFED3*MXpI~+K#J-9nL z24$rfxB`cmI1OiNTu^7y--Kp*SX zjXy`r51bR@;gsCo7d~=$n`8tlFS~O}yn%yHokIXNi0Rto_YUI2^z*A5?_DOSSs1Gl z`m;2FYO`eh4f*blVs;1_$pG{YFmeX4A~OIZ<_-iis3rpp=mR|3Plh&QG3;VYCIBf9 zP?pCkt7FwP-f*y!`CGBj;7?%e*n=p>v9zx=(AjVnXn42+W#arc&A`DDKpiws9?lh1eYplNe33kY-+bNzqZKfwnNC4U^zRC28u|8e$}6804QxMu@U)ILP{5f1>m7r}kqhS*tkXm8 z5w}0%$$kDdrwj&RH*AkR?jIO~`s_jVv_=hm;E6db&m2Glq$t4onCFOTyr}uMjKjn2 z{>Qkzs^cYqGI<>LG^t%Ti4Vh($(zDw^M4dwc|276`#;O9W-yk_3}WnKiNTPB4pKxK zOC?ETO_GLGlDcPR?CV&vry7H6n5s{x z0yf?oa&@BYNk<8B|Ck=$Tm zn%bJtGY)J}(`kr$*AwF{!OuMPdp$HcI22juiKzqNR~Pr61pf4vuHjsqc{=14GQ^f4 zZd1T`jNY~vR`bZP(>3jL+| zlPu-iOj{sPgR`&jeVnG1P!oae5YQe-Qce$jjdRyHXstMo`CpQ^7N6~aq?;pWT#5{| z8xi=K$l6Ir#0+5;Ajk>*e$K>Rm!~^zz(O*F`(O%y@@#08>sj?iIQ%z>Y1OZ8DHJg<8g|y*{_>`Q|gs@)asm zKowng$_&89xKmv0*)L0VtfZP9?mC@PN-0yVK2Gf(Kkr^A>Cbt^bh;s!xLu-C@yo3;E zoRj%tTmJdSm?$^)(AxoRLOEdmX^J>Qyeao|T`rf{ukUP~M#Id$DkDObfnYpM&*XzB=$py%SV(d=~V%wBSB?Io2|Ii(~Qj!}3_m*dzO#e5D%3LJhHzrlu`L zm2bCRTI6ABk4e%@Kx5+(oe?0q$a?=A?YG zKt3Ht;emG;E8uzut`0K8TS>H6BUmR1rV7dWKvAkg2pNd0H$p%Wi(=$u>PVSbV&4+t z8V3;S;En$X@k`Jb1R!}MBLbi!Cy78QCUhdUVQDUPD2pK^_T&;|GA(}e(&c1q)^4|Q z6qA#NNq5c&9TKe{TmJTb2ww-d(m=L&((Wzn@Jy1416445m1ltc0+RPHJ^#v5{zZG8 z9Nzo?=r(5;Qdfa1$esmC)+!Hq(f?c0_&t>WG|uTjubnrjS!ZNNmfBH3dvDX|SR~5- zn<`UiN9L1Qw)Po`n(YyZw-s@~rou5`rdNUsMsN!-M1z%(9=K;sozVd=Hxyu^7%}oC z-Z;ra0ySL%R?Y##@`KzVtoTTbZaM;!8sQKaDD%L7N z-=mMTzuMRv{erb(c%D?-U1SQgb%k@A`0Mtd@s^&~HQepk?wWn5Dq-O54U`mzlKKF4 z--q|HiEbm$-X{a=I0&l)fOO$?82F#wpY(N-&tH#jm|g?7AQpR!VHs6B+eP+duiMf% zQSzg#d=Y+Sjj2P^+EBcU&&>s)y%=%vL$N&y1y6v6BKVFJ2++ZEjTa__m?eR2j$~~) zfMdXjQ}+*lJtew5Zm^pw#ki#Y`1sd&w#|#{YDUOF8EY97W*qzV<(9qL-6uEFe|d{K z9XHopj+HX@E{_X1v$4c<>(%nTLFfG6GLr@~#xzX! zzv)qYs+?LA{v>^uM?qehdC-Jg>#tX1<$w6g>yLY6ZqhK@T*Wc%1XrO(S$h*E4f1s3l_Kek49cK# zL;d>)xApntOD!!mA%fg%rQU;uYi``JXmM7U#;kgqL&mMl>e2S|{mpTaN*0#}0+pD* zJxqmBc1s3y!*T;drCa4{9(e{?PFV!=@}tsh{Vcqj$08s!^IsB_in(gsBe%| zO|e)FR1!sQ(u>gwK>)ldPY(X2HUDY#i!@Iu2;w*l*Atr<4Ubg)m$(=;KgIz*-k%}8 zs=|;b3RK^eycH@Li^Ky**~TQ&tZb_PrqjR@NZPyvqX3-D(&Q|0`Z z#t8q)FGIxLncyZ%;S*o&n#SaRdU6|sORJS%)9Cd_1?qmB2&}4`tHFX=#(oqcrh}k9 zkt+lQY0Dm+0FAgl=Pib;x00i$5sAz`OWPFkDJ+vy$vLfIRenH-U9f#tvnLqE-AeB` zx<{|_dsnvppWE#`y!IyB8D<+Eo@v1A=KzB*^BRi7e>KdDl%hX=xhh)Z)8Ws2lk%~XS+v*VkF~<@g4?tqyba1HMJx8T z`?y%05UHD!hEQ|Zl4i~Wa7z#JNycL8z!R_L!RA(6LNutt;bRyS@STG0sQD$v`*8%v zp20j@D=FSo27EzK*h0RM?}UKl6fwrk8@$M1@HNU&Sk);TZ!LjHx^mz%u&fB31jt&W zo*`CTaGmBCkUlKd`;?mPs!%nLNY3be?c3=3QLUtW!V_A_-GFc8^VQ15AcxC$TZmEC zW(~o=<@kKEqcELw#^fQ_gHpu6)B*;CwF~s3JS6+w{?am}(Nn#S=lXR`gtD&^Y30D+ ziju!$EIyHfLS=zk-F2^hZ!xm$n$YW~Yz^oE-XoMR*Jjr zP5|_{DK2i>n@^^EW8*i;X}@`hO`wdlo5uo`7j8lELx7rT$?98^g-XdVA43p>P|hPa zH?E-niKl)>?LC*as8hQe#P;Yz6lTl#s#CDyMGABoOXCTS$1y++C#ki+423^>AeT>Z>ZdEJR~i* zVwi%f>iLzy^yXLkiagZPTFFeZy^=%F$Zl1Q9!W2Pvq9h3iNV5H8Gto)4OMoMKq?ra z{tCHQ%yC;_w}Mi>3K$$Y%;c-5NmgsHv@m|cHo!%kc;P9Y=qIz9K8`}FjA>Ul5wt=9 zK)N>by{d_RW$>s10gNm+bFPxakRcYlkcjx$j3*w zozmb+JlAsI*!3{>#UX%XEg@Hg4Vh@iWs$$n+QiG`dTUsMn<}woHS-AGOAb;_EC>w= z4aZzAy%)B>FE-Z9C3?-Z?W#gom>tbji83ec?2O*lBQ7S!G~~0g+%wIY21Gw(M7`sS zX*7#}AutZA&+2TBS=?$nP7^40rvy$|9{mA|^P94So8B4W*kTZG%Gz;)!vOF1p*EVG zB)?M!og=%IF&we~m=6OxS%Q%8ouuc_Jx~A3?RHzBgOn<{vpxcruaSVq3y>=-QW0{% zvRI&+fndR+Nj!=A{*s+4y-BCq?@;(K)sZ-iwS^LbGMS_Tg|bf8&6rF zwMSoMz1hW!&$2Ig%Kxqg5_48zjN}{l_;KGd51<&0P8F;!YgzT$YYHr#mk?7+NV}sK zp*aPrpL18$Vj1CnEcqXa3Rg|vWDSwLvnv#F)wVUMP~D-JM1(jPo#}uS2s)SuACG$XEK0 zKwP`)0^fW-3W7rTu!57Ez zkN9+iUUUA~?@w6EW|e8iLR;Yiw}aSwUilet^2T}V&R5<~=X{NeX&*fno1pS4`4_wU zM5OgEr;7^}a#|xmFBiw^3JJd=>0WaBu>IHAg&J~b|?H_(rl)0-Qx!TXh#8eois z&XiL%fvsBNIlEh+1$X~MKIkTP`$GQZB%jSQ0xh6_ts?ao4RUE*$Pa}axmR7dxDzDo zmk51b709mz6O7DJmL;IE{7y;({X2gd#|;d=13HW8!Cjce2%JAxFGb})C+^D;KTs2x zTDV9L7SsL3bY~Q+n?$d3*XE$wjRtgoIXxcHb`xoTA3@AF^reur_kPhZjU5Tz=R+`!Ool+)`$?KbyMjS*M{x~)fWYz9!LSR0B^vG)Rs zJV6%|M@hoK;Ze4>1ad^FfiY_>N>-?r=xa$Z8@T!|pPc8duuhCOaa^1+_oXh{y{sYz zJkEBfL{KdxjVcm=f&NH0fYYRydH46xk`Ko5S?~E68mi^4d|;%&$)yC=!fG2!6sG{C zkhJSTdRv5ci@~g>^-Ll||F`c9kAc^UHA|5z+;lp-xrB6p*f;lN#MZVpQh7pc<=H{q zN=bX~s?V}0Im>Ekt*F;tnbf& zOwq>ma-&!T>xja%eOJ^GFuvVsfd%3u02)Dcl0%dB%OG3wz!REB?r@CKt+s{AEi$3-YwYL5m6IwnvQKJ7(fWBG60=d}2f_!Wwa@MEyZ4ZqgKSYQ!^H3;Ca^{7ST*! z?QJH!85-<^iv*j5g@UH1HL~{72Jb4K->cyZ6$r7MPt20j3lLH^mvnZPe!-xtk&jIS zv2~JFN55hO{{&{*{PYV2acb_ybZ&WHW8!2k*Q*CGr~ zlo)@efCK={YN3+F{}1+>L72=1Quz=?0v(>+XAJy`1J2EZdS4pgB`LjLO5bK(zpM)c zCBxazTH(~Q*))mS8ZN9Y0iERkqb7B{AE?OyY)^hm z$Zk}w`L=PDO?#WNZ?l}5!&wZQB0TK!sutPX|6^}?fH-)WSkt-j?f$PGdx_J-e`zHX z)z1*#Jknmswh1<-Uub}>6`R8hdZ@$~oc2=#Ue-@Po8q)oyGqDNDDcV z`VDeDzcY}VBoXt?$ OAatm>WNu^$(T!@1qci?DfH5G)d8PFFSr~PL_HvE0Xo4JkXg=KJYjni8kC71-pGG661uFeAA4B`j2c^*OV zS%*UMA7OLkc!}En|E}mi1)|oEh3#D2cp6DBWwopK9kA@cDgU$6_h9?r_7)F| zJjDb$y^uUc$SLeje!YffQG1l5EphSDL&i~qa)djM}fBSfRtIPwwTUFsi_fE?N!=V z2vu|i&=z;a1A44N+>&%#Y0G@-EaY)EWbPpteD~!*P@nF!vvG;I!U>zmg&Rxs1@d^| z<$YyuB|U0{k=`ep7XK)7Kvxy-U)ABYayjIddf(G!Dc@w~%Z*0@8=IZ`Q|v86i0ppv zg*^vy7yZk{gc|hZ1CCNbfnQO??pg`Gu_1GdJoAA@P|+E%ep+kYtxCRat`+dB;-Ox#omGk@@iaML-a=j?ATsXK6SwKtQQ%K)WEq{D}K_dPyKd4)yrK zVPeetStCEL^IU88d^OeOfj}2nZ6kqLl7BIeiVn4NM&g`H?#Ay2Lii_7{7lwSC9gl( zKoChv{`Xk<{kGD5QwP=r-NICPDR#Zr?jZKYZ#1j6&~@VZ(0Tf)yOeF{)8BNdmk3P} zN=*$G3wWghxxp5M>I~Q{i_z6S@=P_xT?zm;!`qG(JEihLXJ9J9Kf!`qf7l&>#980@ zTPbP~feYAGhH>;CV(copq6pzeDGdi? zrZzw>XP|qyOh3|UJ)qbIjjndb1~Ra0WSo-MMgP+*2*pM+6kQ63+c2XQ8uFR?M*yql z1h>&#dw*`mpmjp&{m>;+{}TKKt+CLD&ei3Ser|IWg_DScHXZ!ufdHw*Z??Y!d33nHY#j^j58Uq7K2_Tr4En9>_F4+`T`j7 zcFyRwsn)IeuR%5gE&%BkQLu3wJa~_9{clY$q8%s4g`nM}YMVobN0A;+jgHNCdVB7F z@A*(swsk6T*R`gbkM=)$dwIvx-XRBKVaCQ<%IMZmL3SO{bb^=zC@p>_c&GLYuMwLX z=&1(!-cH(@D0LfSsri={kqc%W80h;Y*5>9|A+T7x-Y&Bd*bha=={w5rFLl%{#pHJF zgb3fvEyb{Nd#Ga~ghQw}2B-&U_of1U&0rCTWl5+C)IYs^F~|y7J!qF}{1!9eo1D@D zvCnkb127APwsF~xVr;0KRyBKr&DH)6!kybNThcuPIQUfLC<^$e3@1dS>&DcT`Tp8K zwOP~-;r~0mVe>C9?2+48o7+bg1^IOrHJrsz^4Mt!p^e|}q)ODgq%F8c^C-zE6lZ*& z1%}IkqL_3o&X06L~N%2nhUKKQKcV7$W-0Tb21mZ$Y8&w;Ss@-wT4NwSz zYvPKw=;|E3;pv`2Sg%8T%CNcwoz$+LUz=+=Ah6x}M)%75$NPG$;$2o|pGxe0w9zEB zw>|vIsS{1uE5!c#r-UuU`q^c|@T0Gy2I@kCMFoSV&cKfTH_QAsZu8A=mHu1tKNnYv zgJ!xjTbuzWt}__vfmi=&N|2jGyugRw&@E@$&I0^!NJW=L5rbI#jT9nRY z8N*$GC98AhQ7$UPV>FRYS^ilJLEXtEq!Sp-AW|4sEwX~40?idQfh~+EVF6uMWw18( zqkyd=OT_TCUU{qNtwjOir6_!{9&)1R+h-x6)>y%+?sz%!N!K~${o=nQr%t&vgQVkD z;M6teoc^w7?@(-Esrlv_){a2By@u)L3a1@k4&2!@UVk#>&By)}jfcLD_CCq(qkfB*^IFOQ|)UClUxSG%GLd3+_^)bJ^oe(%q+_Y=u1zLLcR;_kijcP*ss zd57nzWIoktT;`#fgrT_T-q#x0uWXxP$6*Fk>iDD_t*lxW7aac{YqtSEu|L_zb@avU zHB^nDxU9D^tH-m#63;)`yC}{!J+jzPTHlL#SYUXkW^Wm8bzSTESo`78Oxvmjj4{#x z;F-W-2+)JlbAVVQ6mXnGaez=U{Y$J5H!OoHPKqW}j=K5FNMw;*Pn{+KO;M{|^MjBn zQ;Jn$p}PnY07p0pGZ~;V8v#}10G^_$xA(IE(&8zm=>`Fj0f3Yi6f~x^*Ric3{hWYf zaVC6CZ?U3}gN4E60$K|fw)O_?Ln%V7P5@^s160y@aHpKHDvBsjt1`ndI?oa|<#_DO z5o1_h2ht8q)*I>5X(zi1Y!2_O-u3>=bw|z@+auDuzkWB}7%zCU6QoJz@}d7PI0k^p8|%Y(bKtmcfTTc6yS>X? zVFHk@&FEVu$%gdkPAIf!55h|VtSQUgCYcXl7X+aMS|gm+ke?EWLaR7@sMl)^e&&_2 zYN`ZRWe$+mH&N9UBwO$yP|0Q9j66T)A7UudoZ!MMIH0n^c}LB_;A})5Fh0{HzH8^-3XfHNMPC`sIlId>aq!4pWJ|IFB?dx*Oq+n zx}Bs0D*|xOm4Ne32tVt)AqcZJDCvnW*eZ^TDq4Y|IrHhAZ^6!Xz&=ofDvf^MZ6R`3 zjusWr1{BOfpF263Cp7sR={H<4NI}ubJR+YE+9=R?uWnZHfNkUQw{=Zl<=FMGOPeb{ zmImA+-B@ssC9ckIv)XL5>CeTzacBFL6W$-Y11?9|Z~rU)VR`4)S*J~HBU18?149{M zn&PS_M=LNx+W_K6NRWIUVWpJtR|Inh;W!E8?F4AddqNl|#6ypPLh}NQSsw~gI{5;p zkgcyhBrawPj!LdxLz@37ih;u~UKk!aAG5#1`a?fyVR_J9W0X=DI&Af#RSfP+kdWQ9 zVbmSQ(YQh%XC(W<6Nr#n*&?0ii(*82`=7)(VAIgdk?>ONdhJ+_k5!x3D&H zz}|6TggO8eeZRr?J|q{e#6+wzH_6}8GZlN^k8izi>G|Pz3%u-$2{wWgL8o`zO!^Z3 z%(kk|{#*S2x@w`m>&qQa3ht%F zr$r3zIkDlGrdjyKjY+laxRaRR;x1fOlG{0hO&<@^FTJAwj?($z$?Pi8IoFhKPu=$0 zA$j@E1Dz_{60%Zx;aqeak)s=FRR1`uHMUoK6 zM6wb_z+auf>_))SKu^=o=tp$o<^b?xuX_I=5b&6z-U+DEjJhsq;5jy4xFckV)#i#s zl}@PV3`wEatdK!=407pP$PR!lcn55G2jcmG9*AwU6pjtR#J>p)gE>sos>Q2H+71WFyPBWgL*63By!sjg7+Y3~%Rocp?bH%Rzim zABIt3BDb(;*fsIXp1Bofue^#V*1v5t;M8NfLOCF^F z{W5To2T=_H(*;nO2S{0uwDqpmzCy^^3v7l!ioy!%b+9l$}lKcclEKZJxM`JcIB9&AX^Y25+ zXN}kWgmt90$i>A?!+5U0z3%UrgBE5;JLur%Sv@?9=|?=CRaTR-M7PRGLp<`d7gnYE z_*D^S_6o^L25L~qSUK<;fSLrrT`ojn0WH&OjLV%q*?PSz2Uf}eOF3Zv8QAkf4fHx< z&fPDnvept?UKQ0N(bF#p;AT z5S|OSfM;ux$j4+m(t{D#f@rE2P5ft6__67V#CNXgtv=R4tp|K6uT*9vAU;<1aY{8w zY$N6l@7)>w?AA@idhvTB``Cp)waakFS6>Of^I5e56!inyC*NUiE;J6Oh-!93Dld|P z7BIoQ6(a~4CnBY{Y}2DCQ)QxSolTqb0DYF~?G!*$Qu0U>I3SF&*=DFD0+nPW`w~Ex zTleA%pu}AxW3N|iV^DaYmZ+>B^*V0?;f7_n4f09kA)3l6ow@SwXAO4`^ELm+1A?O4BW3mLTFoRmmL+~cI;=x z>yY48*D6K)qCR&l{r$17nsuL3-72OtYp0o;G}?`v*Hz6H!?@!oKVu%Q#wN{RB-~Q< zfR6j6H8;6{lu_fl7CQ)#RU}Y$Dg#DA^<1!ncvibp)eHqcW591RfYaubWN)y7d&SS*WECDDLCCjIvN6S?9|DynDJw-G`kc)NJ#$qSJ--fH zUvLaw zH(K|>Rok_OVCveO(*XdsOG-arTFHLI>(4hm<9y8FWUI2pz$(jQl(wYtos|REDy?2# zJ5b#{bE|R3jP|y%`eQi=3^uYrD)C;H7Qmv(oeGAgj>Kp;M1kT%Ck5 z`TC+mydc&~Rl6W+sWd!Au&%;XH#Dp#?4w)WB%Av?crb|`?Q-y-;fLtfz zcd`c=HyYkt{`^5W43Kx~kR|9cNn)(bk>5~6YTgi$U>39}14)j+UGYj&pE2_ae}V|G zTF@hMEOp$~*BApUIqI4#H2hPxU!C+{0g!7CnipA4E_^0w%E;RTK&l-2UwLPM*IPRgXLtAcz@<5OK>apvZsr>EL+eU2)75M5 zCfFstacIyx$J_4x==!;K-){}oy-b6)b%t%a{_^5@Le(9Ev^gE!_-7c-Rj#at^!jbQ z1RxI~tA-J*zRpeJDUy^z?ng=8?`{NBluOsvN;*mZGO)p7k}3}p5OVZlLB%w6O>!I~ zS`}n!c-K^8<#LO~Rha>}Fh&lrA$F1|6!2%LBY_1P43Ly1&~*vfp%cW*^EE|AI-T`0 zK>5RAc*CmG106y&7-RDd_GDmu9n2d`FhMe$OqeuU_b6+2VoS(?T8+;crA+qDq=(+& z$9gMSAJR@&a6{7+K+@$9``wceYo znNuSePCS4G$o)Lv;BS(IHTU@OjYjh)N~X8xjxlZ`MokVjebZ=Vxh!%#j89UWTBV%x(@mNl1Ksn4gk3uy{@Bx6$2Dm!qOg+rJQtIMqZ|M zzNR7Igou2bJEeOob+2^e@g`vaLxB%5V;syrR8bLoCGNU}E3L-e&tnIt$J1MnNiW$A zCA|o9wLBR7`W7wwL~G>r`MHA?NdliT^$g7O@Ulw{o}LGfTxVOo-Tis=u{+5eU1Q$s zjumXatfS)2P$5TJ_Fix#7iGIRWUjz>5sO1lOKA9zjs{_1{@P47G?N{Cpj{-xHGYYv%9HV3KuM3|D#1I;glR%YhAyuWPy`fG9d_mtS}`Q@iN=Za=qt^I~H zzaqsqjr2ZTE4tZ8eB!ch&MMr`%$iJd2OPFM9;T4ZI{!7E;ovjHCE#gq=*pp$h=qQnDBn_<;;VZ8$||QMaDkrQMLI8-}LQ0^Tkl7 z(EQK7B%kcfJr@hI_ibTP^9S=><=~V1*nrt{@Ja*IhU@5cu zW%29Hj+-xAN7!d8mziy@Gfrx3T2*G^SJQc@-8gYq`?7DnRlt|~e@~nHUAT1C@Z;mM ztG+cXa|A`AAe_qYUxxsiEmunZt-j&on8rkZGC2OtvQj~ZP_|Ee3kiAC?~@lH-^h^s z4PaDerZ4+qAsC|>%;_|AzX%d=#xo8K)S4u5bmFi;L8d}+{QLba%c=`p8jd1n%{pe2 zt~!p+ytc%W$P)#}-72hh;HWm?0C7@?r|6|FfCQ5)R!&Y&M@^*CrMjxdv-yq|dp(pa zJ46<%?|f-JTQ8c+Z7VB^95d2f*O(C6yYK(fuv zrl#aO65KwI@!fsF9mL6H=8%bhn9|C!OVEkEWp^E4q<;k}-ZjnnN2w)pLM5}1A^?+I&438bJTZ0mBxytUXK3Dp4_JgqtH_RV z?o@gt2UpE34|r1*rHE?Dj5#5{kJn3EkY*dCvsw)Lr#bubj7uq5xm1&Z!$~8a9wluD z@+SjKT7vJi$0J)o--FbF zc`Pne1acL08i4@VTOh!$I0mhsxnjDBryo5f!H=hcfsQxR(o$Xt1v5Bu+7-;C+7M+n}0+oC$4Y``0)M9258ZcX4s>zsZ zQeL{VX*MUh)arYN@+O&g0b{Uq@GqWEO7-YaeG@~zBgXJft*;_7y5KS8z>bIQ;dLiU zBoA^rfU*XUh#Nnu9#p-t9qyZDX_wvDy;O9(Jn3{ILkK95k!X&>0ao?kGDhDZ&N^I%g)AZ1-H);12bj~0Pu$V==h8Hx*+3luv```u8f zU1&SUy z&p_J;+iuXb$_sMp6X#2)2M4nf3^PsFn*XKS+*E38H9_2Wl(aiz^;u(YOd~03T%+nr z##_*{c>2{DR>zOqf4rJ==&yQM)q^Sciy~&D1qCeapWZ{>lUvG%3!~ng(@|!&p@k2; zq6w6n%3QhajZW02Mw*WamP3T8Oq&z@%VE)CSmL7)UQkqX-jF)6EJMz*xdrCl25>-? zhh{|=U-=am?>Zw56`~m94h(VHILp(*&;-9Gf<}2CyL;7o%~We!qs=`;=le1K<~XdW z+#+CG80Mt&%!TlUOC@hI)@%Op?4G&a9C3qn^2lhBnx)y3b3LW#+U}NHHA)AWyBHQF z=j#qzPZzA(@YQL+EM=;gvBG@sjrHidUQ>Yg%P3|s#WRBa2FQw_{Hq=^=HZHSxM~29 zI)06Uucn}@;-I9P_ETr$xsb|ICY)Ep57UxBM4BqpsZkJ~Afeufi^YWkFl}N#tT~@) zmjRsY`%WMxQUsf((F!y25b<=wU}$oS+RY7p#?PVUyliLVYnpqRd5k;TGiS#_?tcDo z(8o9`+um+P1EwcmKTpY3=wYK>-PNrN&A%OCmfXVF5FI~^e-X2(*QXrMgeiq5w!RH` z7zUsb&UG;ty#2OnWWfWb%}A!x zLV?{}28~pA5vqKjzw4s_Q1<3S1QGNT!=p;LQoAB|viX3Vrm!@_l?_4$MoK`?O=>Ob zPfmn=B9gFoJ#rtY6SG5&eWk3eO1KM02S4b?y1&g<^X;crehRhxWsr=1DvHglPr)C7Q9LO(Woh_{V>53iuPcirJ8|;bGBN zbaw|HuA0NHIv5Z18Ngt3xxGT($W)l5s+Jpi)QaRG&WzcYjQ%ichz~%mp9vs1%o{9ohI1N~b7Swv% z0u=2%OB)q?*oG^J%B4m;eB#5+RN&+vh0%`$IwQIvC;mM#kMZ~)=G>(IMz66|pX*r3 zhir*#)fTX=HiqEj~}oav#sc#})UDVZ-O`FFrscS-2>)Z3T*BilJ`xtlvu(dNOd6 zCuD?HimOB&Jm?R}vTMc8+)FdM+ek{MLg2tMvq~OyB#_1{Vb6u*Bdce?9p=fRd+Gd;bcJd+Tph6`T~X<6*9 z{?T4v6tMP}M&Tqaiz~Xe-lB{b9oEI#g_yz2-GDw! z$TEhrM$RCAjn;5w==>;l_h{z%C)g$*Z5Y7O5!}*K6qca090AuU>$iuEvP@mi36kVl zZu+yiWR$Wpx?gT@c66*lklS(aD#0+X&Uq=jIW_Mht)#mRILj=Ku)yIL^cF-do3ES^*2=SJ)lnh^?41Qgg$QP3}ytA3G<8cNM&=UwX7B^@h^ z;FhrsvIb|?BZ?`7mSr*+y-B@PqP7TLuD8kA6!6^MNX2En-!M)To%in58 zO@?~I7KR|2UzV{(#g1FWO~dQdahUnc`P9PQTm7d?u?3z;;h zo@k(b{XQ^Az}FMC|FKtCtg)%__g$N`js$n#+k4yloqbxzD0VNSZ5QCE(Y zc|pf2b&pdyL+?5i*F>q4bG0KS&-$suy(c#gNBFi3+zI`vWZfq0>~On*u>RrS{G|IP z?i~W6W-`OXXqFDTg3C8YadaB6n+L`qJ+Ws5T!woDlC=`3{9ny7Y}_J!G4Y^CQrC!h zG;$0X&l;baQyK1+R+?M7f!l2ZIdt3GUk?u6nyeFaRj%>AX>d2^5|`M<)HObT@38J| znP4a^|J292%VOTuyH^LpcPicB5Z8pQyFQ@TZ$Bz6xa}dRFk_O16W&$oS=c%?Iu)vc$io4FDXA|7`Jn_gn31@%rGwibpZx4OT#8X3!hAwok@Y$sT@5}W_ zOxf8#|8R8F%n~3T55`Olp#@~YTE^~$ zmdEMJzQc%?Hvo+Sag?lGGXQBcQwz3+ohzE9~6cCsJ}86w)#+t4CrWWM3(;(%eM8#*SZoV)N#nkUBFFVjg6^$<<`E_` zua08fId(}ogFC9$@mq_H3$cr%awZ+g2>$u!&}>@0ooxZ!878W$AEA|TL%^YZ{LMn0 zcU#%J<6woYB6aW8dygKJd-sO9QukIrsqS9c6J3Jd*Ww+abMWsu9fh!(N zt_rqoW^6ecFn*SIk4N8jDsD?!(y~%ZLMT&ds5f}qS*I%L0L_u^jW>`jC>I=7sGT7i z!ruiLyU}&C1?P9Pe7R1$_E5RluApc~b$Mv(gV9V;qXZLr?Q_ZSuk&O9JhnScV}Y2Z zHILmT!+Nz7gqSO2B&#E*-FeZF}}acQ18% z?_dw6k!-MS$3EDUd8Vbs?O2KDxzX#Wk0Ts(%C9@$+@&iNe(X2yaUhy%we{84f1`Ch zXhQZH#|Pp4yt3H*@K5j95=~s;z{B5%N(W0ES0|BoRYfAX>+ZFXk>k5dE)^*KCH{G6 zII4NdX$%c~HS|x3ER2DZEyG!nahth)eRYUHPn@@Ql*$aMdu#RwnnO%f+nhyK5lNb;kTjCB+Gb1+rKBjzu@pt6l1?+Hk!pk}v?38n zQmN$o+i(ADul=*__1wFj*L~fe>-{EzRX$F6Bb#+_{V;;b8Ts#*1UdWqjFnFfh=7lm zUND>Xhl^gUs8Oz+xjS+zFA83)ct3oL{|l^%f)B}a-~K1K%gg;8dsd))osdnvS*K_h z!^x8$_hv^xH(kKxRyoTFfkf}>i(7Up|YvRz9 z*=m)^?l81`UbWook3XWVa5K@%(c}6qai>+6@=qVwt+TE;SNCpiR(AJ7*2gcO;RTX2 z0*RLVT1cOBt*c_6oYSqm;&b-dkDNU7qdIG5e^=*U9PTKKy(U|ge|hcgecMjV2vI?L zKCkAW%;J1^QEY^P4u#P=L%AVYxv`~=FdNvY+t&gRSFZ4B+ zkK8@RIN$u@@vAD#+qP|z-5YP6js0Y=B$Ii3=$5R@tv+)Hordc(-H*kg zrx1)d+X7BVp$T>@e-LGmSaiC#W3gWM+)v|fW6O5pSn0`%3tJpE)qa>5h!Ud@RW95+ zd79CAMF5JkZd>o)vI^X0$q*nK?`jU6Q-VQsf6L0LK>mZ6L!^&LpclfIKI0ts;rx?b z=sA0+r8_9MoJ{NR#$`BC(>k2M!>W@)8gkK?w9=TuX-uhWi%|xHs`y2W&1YSw1uNHS zn{8j!cYH-fen#&cz%pC366*DHdn}Jn>n6^rCeNtx7cj*$sOm3fx93pz=QO(J(ZgTN z`#)_OoTV;Jn0_B2%+08L`iz*9s4exQezt4Qv?71iBY&ME{5Ws>qsD3Zq{Z_B!tNlQ`c-@|pkhhV>LA&hU;e&>w&u~Gl4wbpkd?4pj&7qsygHG}usI)emK zpCS1b+WtL;vY_JiS=Db^GvqTibWAJy4L)tmiuu+dyxW@jRNw!xo?jQ5-mkymy{YpD zipwYWO$!I8OBtJ&SbM)7PM$k_YBDivG$eP>=Ul(jmA*~)yEnY(_8fc|Joa$Yhc=@( zHHJe)W-m&eT2Fda6*v~2}b%CjtAt#I@^RWTN8h+J8_ZwQ)chQDdaYi?sY)?}hPU%<{A?ZBS&J2v# zQ8Xh)*DKs|(=Pq>LF&|f2u}Wrpm56={1Uk&fL&b6{(wc#{qU)Ga@CFnt z(H4cXS3=v!p^X%k)D=`Ukm@+JmY#-=EbZr!&EMUB$JXGGZA@lJR3!5#i*Yn6Bt0PZNE|CYBR(%{e_>icLGfm8<*p0myRMvx zesm$Cw|38y+lQ||Nqo|h+w$;MQ)7MI)yhkkOUp~L@^bk+_SuAx-WcC^Axu-uQaw-29U}-@3axhxOv@@0PE$I`ErKhr;cPkmf@@nZSK_ivBp7H=$kyD(bJd)0mt&U71HWI{{av_Yc0B0Q+`oVS{{H>Dyu7><4S}seekDE`p4+w0&XdD?%e?Mf zd47>{|mwX=F{`joK_TWU{gFByIR=DKheOsGnUtRwD+vRy{)q{wc;Ae&_hu=Tgck942 z_wx-Q^n^!8<`!ZQA(Z!W&mU|3(jLEkq}}O1rTgZZ-!nf&pWZd%^k@3`f8sUGU6`Bq zXbBJQ>C0ZuFH8A)q1!^{*Ck@=59sKrdX@id9z=ApHSnyD`L+cwnV?i4-G{I;O#nN4pD6u)T(7O5OT-RgjH5s&%ClC}Xt;~G$t2s7`CN(*FiWbirsteYSHcUQum`FaNZ2K;v zdW&tru{+Nl-m$7**ndv0ezE>tS<%PyGY$F&a;NjdbtzpIu(1ou!wwM_*BpkjYf4SH z*IrO&lJ6j{&e>I;wC{^-_bp2K?3jD`PTzUooBZg^Ew&S~O)u=n(q*pMzGF@n*pJ3! zKDU3)nzOJUO@FKG@W$s&zGZU@H`ipbikrV)iK}UJ@$k~5X@l8~^^7NRxtgC#CYZl{ zuVjC|P*B5P-`eEx*4%Uk^7X>fg7Fn8KHKIw>_UOV%j6w=s8oBT6wIH8wkkQCVxIO*wk(rvaORd*#eBz}<#QrGXd4)<_hXODdyS_K-#re|MR`^vuJ>R&)LqB&$IB38Ai^H7rE3;-9G?@*^N-~nx%;g_RC%qbt zS(^d5h;WFwu=k741I3tXs;wLrl43jRJo#na8}r!jkjAMG4!|`u`#I#A-S#8)AFpg& z=pJS1-|imJ=RdApKU){x_}KSV^t$0SjO?Xc%;V2Nb(cT)lHZ)5KPu=yVSiz! z=B3qB*8MrO1n!^{K38Dd!&u7)d1_RMrR-uAbg1}ru~Qv(2o{JMN*nFw|Z||Q%<||T}$p^blBWJ zm-}>UfyaBtU6I4KBpnu?OcGzHV_Lmiy}4t zLeOdYrt|I)p@CRak*zO-k=$>0bm1KR8xD3C+bBKh+a-*b7w!FNUG%_Q`^4W%_RVn? z2j$>eW6#QLZO#`QWKC+F8thspTkGipkKR58d2uc};L6QgQPDqt>kQp?mv&xfai1VX zDoS#;g(qV6jkoH{tclo#78OV3f;=7!Z}mAKJ-n1lmIp3`ZM3X<2?1bKO%)czMqU6> zf{of5pNDv^Z%@cN=>FouNJq)(rdVH62(XrX$4L*#QCxeZX@98=B0pcW|LosMu%!*M zu)!+so%qr-n@`V7Z!4c!em3@O!3ZAXsUN8r)3t6PsV&R9U30uC+s=Kb$$^;{hh~F3 z9ENFCzC(&$T z|M@^R)hhZP9FBuPJt3yIQz5cs2%uOP4PXTMw)X7}`*q%}pvA5wZfcyDO_QkN5~|!p zQApy)tD$E13l2oeXuXu?I9l7+ZwyI3tmqLz8BfI?|gtc zU(gea*3$o1XXhSWa4;mi=8f?oyBgZHgHrU?rZhaf$wNmzZ0|Ja2(~W zkrPxZY&T$I!|- zXYL1XJ59)<*8@r;;Z+)ATWFZ#{=ciCAMxWaWzUJVmDt%leI)Sw!VxJDaamT62p4aI zXrb8dc7|lYe|trD$&u`+&Hr9kJP+0yEBsQBWiSxQ-152~8Smh2Q4pKnepehc>%gAR zAII-c_PA{_(sl3T{v&e{$ohA-8^`(%P$Z3FJ2qBT@ElqJ0x;MSAh~V-_Zv4Q&n=>r6fE&i&6T*zP=-od*1KC;h7czZ}3K5)K zfSuhb%rq>UN(K%`Uuql|cgS7nao8cha&hAD&1#<6#7p`7*TBAG)K*Q#{v~_oex(Y# zPEE*2*IxY(uRAAu%5Hs=r?4l>p2&-6bMadaj!f5195~?+0u-yIG_T+DdmUyMaDJEM zqhbJYkW1R*5ZC}&q7aZVZCPnM6r14c5~ zqXfZ!@khRw=G|i+muCYl%;Wx!d9Rb;RJV6xs`mYivaTpk`@L$^cvVppnhex-!K?2E zHS9=xVjoXQiZ@O=V*fg|!9G|_jweqCZ`dC*%ueeZhQDIQzh=Vw3%x&!;W#m(c}gS1 z)^L?Y?v?R>cgEuBU?5>#*x4kX?gTiDk@33QckFB^^T&b17+(d6^8Aita~NQE=ke78 zi3*JUb4eTHt{yv-s1#NUVH#!c4T{Zn56!^@1P%J-xyQK;1)l9e7<#%(8UPGMicd9ZVQ#&%QA+tuH ziAnN@f2$pPF3##BAASVMhAl!6tb(_Ji7gcn71l--$>HCbN|TWg6{7oIe#X`n$al<+ zqv4U02BCk{?0p3Rw7Q~BVc}ZS zCp58u!vO%(6l9PD*X`tzJ>$`Zxuj1J{dMquvhlPSE+)fw(w+T2!S~qOJMCKwDfqBn zsVKO87+zlsFLwu2nDA2htWjCu+01cO2%sP+RDd3zYxnqe0CHD4C(Q;RDFuIwl2svx zV|W{5>?5bQ=g$}<|NE6aS?dsMcr4{eVp?Emnp7EJAEYdZJEy@JU_;(DK?;&Ns>vr1 zVz?3!eo7Qp{WGT)nu=lqW%~icNI)w)Eq^Dc!Ctx+;6~j+rU98+k?=uw8a5}hpA6q4 z%v2Y^?Q0{r0Pgk(dajiGAJ+cn5(G8M&*nGmvZul2z>I z286q9ltz$S#Ie&FfJ`BPWEQI|maTq*{5rRLem|rIvZZHDAsGfKd}We7`)kj5jzf5{ zgX+BuMdLFl^2O@J^9_dQ6CObR&7{cfEWBEL@mx+Cyp(hN8b`IF1b?M8tEWU&oOq1J^#K0?v;VeX@?ssNJn9DR1QHnCrKL=NfjBd1t zqYL5qVfMHfj%*5mvSKF_As`V@VFTDj2xc*(O9B3Q(rs?Pv_2n}BLhhC4kQFkxnz}!nmY=o%Z4F&K_?mvf#If8 zOTVvF{fy362p*=URoX{mMpLt+j+h=ey{4Ub8Wnv)jR_1^oGyw=XulFh-U082RG#>g zs!oLuO2KOEGz|eTRDt-nh!`ZpH^QpY0NmaIm51>N{*u{qo1&_OVCrxwVP~ctHeFo| zm-6IC&jLL;)tZcI?BYddMPRiULT}yJLWaPQN*Yv(A{me)0$UL0AH>vfvs zQCC!VS<4&9o=w##EOk7eTiO%d&%UP4YC^H0856r9c*r- z9==b7z!nuXDj;Y!kfQ*6Dc+5tZe-hEdVT@|oCSam-)qFPyYJo*dvA<0NDdI~$;NV~ zKL*$DxU4#I>C{ZzJ7mNO#j6+=(D)iaK|ryjLha&x&V@SFUGeg*LG}kuV|qD0HE1!W2jE&|xUIXXmefrV%k0mDqI992?FyV<$;z0WY!HFtyUyTh-z z0ds|!ck2VX^&)^_1NcJVas3^T2*FAelea4ceN@B{V{=XJY7f_BY2L-I zF(7xDHAzPx*O(aq1X%Z`Mx`)X5d!Z=`zi^1UnfHXqfY+qF8rYtojiIKxf3WYx@aDp z+IY3(`1SjPRA8J9;41E?I>GVeN>ntU0|B*6fmZ@Rj{zS>MsK)>_zKBYWx{b(xCZMy zW)Z+QwGbBpf&ggLfGgoZBXQ+fZI!yuh*<%4rowdR68w!MO>12~B`{5$3?DD7ukJ;> zk|69x5I8~ohBQdKQ!|ncY?uRzcRlLKgDel1Z8->ew5wS|+~J)1fA|tgP<=ELc-Om$ zo|l0^{(pMn>F?+mb>H{DF7B2CWERU57PD)og9ligf|>YBIY-v8Vz|a)1!gA)<0VMl z1%D6>Xw~1+skoIQRmb!Rq}a}3F`(7DO)LKviUG$sRbIN^f*}itj9xuK2@V44vA{** z_3O$idzTPK47hcSb9&{j$`9tk+X$~tdau8UmL_~$42Ua48`FVt27E|>*boHQVZb}g zAnkuU*1zo}7T(t`1au@0q*rCli-6zQLzGst2D6#&1i`Qa9_2o|hJ(6}`nVr>ZFpY= zphJcb1l9g<5IP1#SUhTf_Hgh#0J0Uk9|k}TLWM%jG=1Z;4IWBwvolYLlZsr?2a zzDb~u1TP#KXc!;OR~{uGLDC{(sN$9$+2sqP@=l2hU-~y0ppT2`wVj+R>M=MZd63ck@$#6gy>cPlIL%XsF}0u4}S%3%mi-?7`^+;`$;}RtvTRl0l+%+DY^_;yCS}` zFb~KQU%oJTdC0jzQ>qu22&@w`Um<}(!TsD_CGZJ}ayooS0;sKtcl`rSS@s7X>K%lr zm@0!>^}-hof|ok4E(HU|6CeCDfQIr9x`mZEBxrK%7C1Jll`%{-Dda;Pfg9w$uih=JhJ`g4C z3rH0ss_@+7X|pdA4L3%MH$TvA`dFF*=&@(7hk)i=gkRTgZN!6%0z?=}<*#7*%4d!E z4=!c5x9Qd*h9TqULgAN62djF&%t;WPp>V?{l@GC#k$%%!QZ+0U)FOfg#Oa9Gxyk1U z`^PE<%&#j?-aMZ8u2Hyvx-kkajsq2+q%#XLjh`MLgtWYvIOE&go(rhJ+d>-q(0^u7 z#L1KY+R8s))AjpI#Qh0|cLtY#AYb}u)TDCN55B;BOO6GN1Ru?bX>h^3QX1iC-}63JT$RX0g4L2FOLhb2AV7ROLyh__D=W;m4vh>9Un zC6ch{qTYdO!eznn;LD2r=U*Se+d}}&MK(Tys+@Nv$8NH9nunME4QOV)qv4_ zB+!?qkTf&U=JX9Q9-Oec^6!Xt;6h02(JvF77X!bBKFRodGvF#>{Qlw3t#^05wkW?F zJAVB^^-qMw!;HnT@<@%BOA5(D-t%j=l>znHa9wH%5()l*sRHhiFr*%v4F@{9cG32B z=H4`L7b#m;>E*m@qsfjyz<}&G%`zpZy0ELhxo~y&TFQ5BQ~}Y|u4cz`kRJ{AwMEm4 zR@Z$N8p$7b6v}Q%#Z6GRNfAly$?UJlWFFOgENA1&wrH_48vHl_%tn73vU2 zqc*$kIWA`(^mycUK>1PShXEel#JRZ33FN<91ADfNeBzDY3<%4DH{YhopteP+6>GVA ze(^#n51f%j2Qw?PFgqZ&Jrgp!>Q$A2H@1x*6J{#855e>aO;KfDb8eI+`o zq12^?J(2i>!@qFzgS8UAAZ18BODYV1@Ve%d$HtUnknq;>!vnMKI!SNBKIwdJTsSSd zGj;;wnf#L$Mo?$W1j}K3upE}Ex40q;ElZ6*1ozR^7=wTmUA#sRD=Ze1_;*|EnW@_U zZtRz>gVBzx(TVJI1!_`jO0NKs)RbqEWn@ztlvu$vMOJj${T2ClSJ6Rm_jQj*O~%Sp zWo5(JuO^#&cVvlvK7D7G6HGeYbInuSBx$ISGcJU7drB%V1srr)fDsydPpiZ=%USkj z?nMU-p1V>Tt|JcT=fxhqtL-&y6ets3$XL`z7h1{f4+*^AS_?E6Gvz@~4s6QfDW_2B z_@9G-^3S9@Ng1=pnM?YQJlpR}ne5ZQb_Vi(g&sxCjZG+3CqldiovEKJO>|Cn`rvgIb8LUTB;Cs1RS?yrH zV&vMsb4hhnyx?M+vpdOczrC89f5>Ks>kh5SJmm-{r2)TzO3lUcTlprCPpx*yOzadD zVuj36z=g?Z%L?SQJmsD;!n#-6h^NR*4t~6|8#CWXw??b|m1S!Ibws(Zu**(T-%(<5 z#pVO4x%Hkc1T|RSmXl5>U+PFj29FtW1~v5QLzr~>&QI>5skh?wyQe17PZ&R$)l$TK z79YP&lr!+`-L#zr?!GCIBPVkdLWaPq@>*G^xl(6D@0}D$IQ|7M+W*(yb9V=Gb?#pG z-#_qPx2MSkKU@SAZOjG-viz>RPv^j+Su&bZ^6NUJKp9a9Xjaf~)UmWp8JTOZlRG4r z{xutI8b7cj@!Oo-QdPl@iDDJ6tVlVDtmN+gD`3Iy>t^P0V=#vU_cO+(!v`7O4PyF0 z#+1I?=|k_MwpQq>H6L^cJ`uHII!I5v3pw}sk0G00)U8n=*=~RL`bu)Q?&4h;on?{7 z#{4wIq}R}c7w|VX-h{aw^*7ZCtX4ib)sH~O6s6&pRAygLLPOsWp_F8rA`_YEGQyTW z+XN{4Y?aZ@=a$z{FPbdzGo8C6`+q85_4!-MJ$4&%GyN4rDWA?g)@nxh!vJP>2pFwL zdxRCF-dNOG(yJL1m9VAF+4IxMM%0NKBe6$nk!<7I?s_@-p^}x@>lfF)-J;5^>2hfM z6b+NJju5P1wDZG1xEhPg0mhOcPksubHX5$;J(;#~Bo2`}R*ievdHcwJ-&6!Olh^O( zLX(cm4zKdo;e|(ll@M0fy35uC$|A7qKvO6%##XvfM^mQL-fa^HqNPc3U3Q5KR?5Ff z%?BvkS+?%KjyyMLYTGV508+pDo!W{aIQ7kd1aEt@zaz7d1Jj;X*O*L0hKW~wN1u{aE$nK zGU4nbo{ZeO{zCA{>HVW`w~{c6!>2D3vK;$#-$px4eH%iri6$=^w`krDBWB`OAW+*9 zPGtrwM;liqzmC%R^jEq}U>Os?P{MJBS;%OjFNn$F@c)jrPHQ`7$yzbnI_(R=yVKj{ z9WHi@$J)di%c`MIwt8o6DRqErFLdEvjTqN^S=8P(WB+}Kc_fRYmYT-*f6-f9Q`TCp z^7rh2{4G~0wBi)5m00=_`@s6K^C{awhOJd-Msuz6;7r-(LNgmQv;fKs)>p%zOSX(pu1=n?P1b7qjtteiZoh<4i0z^|3WO zd8#-za~X9~q+gL9{Oy_tR+5STa~JCwlAy)k z!ai1IjQ+F zX)LI&VX+bwREl!}wrW;ghQPz(oxErOtiCPAi=#>1kOUAUzeZb^tm|id6@Ymh6;N*KU!+(V5}6 z$WRr^s023WSUuoE;jMq>DoO+Xv!QRez}HHLzFO+I*v}qgotNK?x)|T~o6SF6WsVl` zCwecZ2We=#a?-Jv{ipOpA8J-8U4A=9@R&5%HF^1m(CCAio!oM+aWym{hp*rB#30x< zx*8f$WD{2bXfh1rM%GW;w6j)=7j5(AZmBPnLRZDmq!Oq}5s=gZeOdHS*bacr9vfUi z!{&!NlI~*-9`v;Y>ZV8hsd%W|JO>BiX4U{Yg8Pn{&NyQpwuOTu^Rxx7+KT|drf8F8 zRd|%EMbHeGYAF34#?vhOj~n3vCu{w+==l44^~swQ32qlS8qc88#gh12w6@dEJ&%$> z<)pwiw*J-q{@X;P-Q}#+alv_`W)puY&pm@|8CTbXWaKy*iH=Bjwu zdIU&kuX{5o4T@L4`D3yaRoJL?P0JM^DOVi3;Kll5@+;1PxZ1cj+H=B*{vg~=Ap|H5 zwpzRGs1ezrBWHjt-asx@RRCn%scqPSDSH*LZ=W<7b<9h^m*vwgO>o^^Bf%{_nD7KXN4;j^e%Sr z&4c>7JAkeP!S?~)U`Gdi(ZMCC9=q~Xr;wvvLXGEgJR8~@1^kK{AcF~mQ@s2t1 zToxaS?RbADH$j}6MF%?!3%b!2y(y16TAyK5iaf=6%RTg-sc#Y04L zvk!^o48ZR6LD=2FG^8(ng+pZab&rV$oCEO0p{?bzKFh%7Mb3bfnq0`yIz&Z%oBj%8d+7U^pco2v))cf~lQwUlqtS;Y)zz?|!K*>a6SPrtMcx-Qs8F+oX?xq6Aa+5D-VINS_vnS{m=qtcQ?58kok+syALj{ zHe!%o8Y?ZLOp4ZuNjj{@`=}?xx%W{!RD*IaK3G&|Vb@LSz(l%QA)$J|D^0$4O$cA6 zQ9Nh9aCv>eoguEk_2rFfemsT$AnRQ#`{nu#E#L119_BrJAnT7u`nUOvSQ^W^R`6UG zITka3OlXiUYmCTb5{*GUEU0J9#kYjKyaUCRaETOcB(7TqyysIyxTO%IXlu zQU6>-%k9!Nn7ZtoA%Z5J<)(c^-a|t-mSNMdZgug{ET~?F*J<`eR|{e;v>HGW2hBXY~jfujYzl#yrq2-`D0@q z2(DgakoN+|xDKlH6L1#=$tU_FLxb?rrtb=8`vzH(@kcLXUg}@YHp{*(M_oGxImZpC zX|+&uf4~anTan69-_U&Q0(HX&f`YjnafnZM>H2TU%H<$ME*}WKx9!*z=g-@h;6D>B z#t1Ixjm`{sa~z8CG)y4!(^gtCBKfxtNwaPtA`;cgbI-hNrln+kViP}g=HB|X*w^vK zPB+#03C!)yBxqd8B;7Lb{y6CRg~R&@SP)0N$RQTSV8IaALJVfBg9`Fo1LlaH2vqzD zT8d@2{mUeZq~Q7y`NuxJ&$&+{qF&)f2_qbDV_wmhZn<%w07js0`Zam~e`#UhsFJm4Mp=kySZjFoV86&Jj+7frWwFV#5E`K zx`$@uGe&l}g9J|=J@O-AhC^Hd@PZD4z~>-*@VoCz*Ul}+zr4jJPo~vBC0w|(78h+` z(fmlsI$gXe;@Bf*tTR5+x#=v>BrE8$>$^PsjOxa~2kq=$o_u)_*!MYHC)qls3F>kZ z$f$VQKDb%d*T2<1&}s#IXbAl|IG4DAzcw760B_%QDSQ|HRVpMibw+wq0Fx3~y2hYO z3+P=3_72bM3Ahi2L6b=Ca}3wO6Vz|vdcn9Rky9>O8>J`6Nqa*;_R**YNHQkF;s z--HHb%W=)AT;4LLbNDj>8!$A)LHPB#NC76Abx=#JD<0N?r|humYby?U({&^o8+kq5 z%*dsF>;710nw_0i6Exe**`p7{Ge)z}?<|N1c=KQ!6FPedh&2m5G{H}0vAU`^C0+X1 zH4h4F=h~k@#ez`6=U)3*!Yh8?5nYcq%CpE{(}@y(H7!%?6E(U+1!D&Pu)NOo*{63lR^}-C71ckJ&oUp#)HznybD#<91$=kjCApkX;bRrEuL+G3R; zxM=@8aP2T}(Tb9sw2(kv;Yy(g=GYV?7HCN1(ON(nR@StFYsTW52|zlPM`VMvx)f&^ zx9k9Dn9S8>a-j<;FvOor?-HbW_U)Uvx@7-NNM6cYF z8G-%%*-;miKXh5SEnr{=(BP*$7L!_{E9S?R!-S z7>gxX)jmFgGRP``wL)>y?pQXnO{3)#MbViiTl&&(4y82nLHQn))Mb{nK(|YlW zdYiVT|1-s$e7C9m&#&)azy9~1w`uwI7Yr9w%HW16<9&V_ztTB_8liT&ZX15Ezqw&| zaIB$vIm&c7orICFPE-JimZO)cj1sA5`P+EvaOMFKTzPoHV6REKCtc&uE_f0Y? zPBGTI4mr<=4G%lc5X%s|%1T{SsLQhlE_))+@Kk&cg{d%p&Wq(XtmaJ0A)Wh}e%Q_F z=e1O}{n2!Zb5rhb#{@-Gx}|N4IPIpM?4z1(b%a;F?HHtYz1fYs!!@X59|yx33H|*t z?pcE2$t?6%HZ32!ovQ1e@Pv#yLFBG-pm@$;m>cng@flIBx4*SWEjI|9B(Q#?TycKn z$_}-ZA9a?hZpLAq>Ta?e-p(LooUCr4W@U&TrdYj$SzZWbY^#^2V6j`L&fZX1S2Wjdb!WZ&Ys#MrlWoV}{6 zfjt)#8h0Jz=gHw&h4FNAEVpZfpB&ot_V}hX%a0x}{On%IoZKe5f^IJNJ+ysBhJ@XE z!ri<|mGxJKxVlK~9;G2UO)e9$5qx;45Si_QQ(I)}n^8FmN1K!$dh)VNVO5IWl01~X zhSWdM1@nNEpIy_Fr6+8GeOs!WWwYhph$Yy&b2N$wLdThTcLGitfW*Z&lUc0erg|57H zB@=(rEkE#mw?W`Df}YwnLPFWvByJiDb?j0V+{*F|(mDgy;{ioab3IgEWCg)~gt|dm zi4!Y!;H8;5RBRJM|2k-h)`e|*aa%zzIz;CjQ_hsprszlP$PX1+8Y=I%a-&RJ%WQ{f zPb^x|s5(;cL8qCrRGlLMQOku!g)8z&+rSGEsccz1mJVGnC{gp<|L9Bs-+S9Op=W-g ztn(n37K()G&+1;m=1eN>45Fh>7s)*=n|7e(RA0U=<{1(J*tVSB{8Uvr>%K~ry_9V1 zH2-pt$?aqnKLff}d|v?+$1?f9<-Ep5f&~)V)*xZOLC3bwsLl zd2fX{y^WbIkj+O{DQ;NF)V(LkG%M_i{GcXu(>ub$oxMXrYj1Zl+o9RxzaKX7hjX@& zs1O`UQ`+4G)t|d1XNB#=Zxef_jJ@LZLY~{jDGM>pY&iq0E^I4f59X%0`**XqW(QGb z<0jL$qfdCJPw^s13K98D<<&Lb*Tjtia$Z0TU9EuWN<@c2sUc((a%@&_iO7c!04gcQ zwK~_ehbWX6s3Iy)zpj>V)Ypc1RV$;`G4RYVh*t0XK`HR@1s^@Tw)kqZ0c*MKt;JGd z(HdPuFG`T)kuV<=wSVtN;PyVEFBU^<|Lwe76Xi_w?rI8L;Y8$6b39^%Pk*^Woi2RH zN(&Mx1dj+YTFY|guGvZU<{&1O7;NsNOWKm7sP|_@cJEXe;y6`aGY3G#qtD!PcPHuV zJ0i|3eXaS3h5kFn9gt$l@I6hP`gY%7UMsrDE z6}ME#r%-8q#|1o+;b{d|9Eizh$&#*9bKJ}=J-%dtr&60Wh#BijMXQ^2YZww5_PqzU zwDPg?W*9y~S7oD^OR#Tu(Uoo69`R>OkK(N?I{Joiz^A0Pc2JgX{JuPSEvNGVmmzm~ z&_!{*fWNIq%u9;_V7p*>$mYdN!b*j{2NCOztY-Z31XTAD+fVLt%XTlU#J0nrryWzL z;$D9y-0S?ZsVhu}rDELcyKsW?nWnsFm8O29?jm7{+Uv|4J=<5{QtAMMQpkHHNiCVU zE(p}goXceiWC$P)>JO<${=iZXcjS1$0(H9a+s&y6xn?m%6h$ zaud9vG8d8?%Imj|V|u}+RT;-+9n!aP{WXJ3OA6hrgKoauWb2WJ_zUPV&_v>IeLtNs@UG3 z;EoDvQ{D~WXM{vpmu|DrG^7nB>TArQVLbtjvp#4k4^Nk)%kHQ+8_>MFO&v+cv~;V% zURd=3lZ7;)x{P%n2k$DeLY`>}s4&0B8>+~BM;q|Ul6b8{Ig+kCr$*_x8E{Q`V>Nz^X0?JwOfzv)6)Lfp+V-Vi8Dt4h)I0UQ^iTq%`!ckYIVIuu*dAebI zIyL;;{^+)eBsA1&UYfs`vL*-V%JCG)>4*TdtJIwc=+y1Co}yWmaK?Y^J^frS;7t`Q zmKnQYr+0~q#{BjDK|LS( zB`^BMCH-_qKMR5L!surqlPLDKs@#Ks6G`W^>d?+|zZP>c%wV{hZ5^&fO)7 zI<5fT7r5sJSW5tDYt34A)Qb91lbz}4V-WCp{K1V~l!Sfq!Tcefr0B=qhgq2l_;5>7 zyG_%_;6HRr^LC4Qu7!EK(vynq-j}o~wV|Pt>ry8L-`YN{_0Xm}+Y-h(+p;I7-UFlt zP@g4i7QpqLg#-rIhzS}cfG1PwbBv=GrP>I`;SW^zB%ZI;_CXWFbrK=O#Ne#^v^V{O)S zo66qsX^t_jgM&{9Eql+z_0g=vw6dcEYx;~f!)1SoFAchK33BJ7)$6 zc0zp$81G9r$jOtg^C)}Zq%%!dSx72#qkX_D_rFnR2vuwL>lu&RtZO4-g(^)jHD{no zb4P}*bgwIPw~Pqha1A@Cq$(bz~6zG`6$d&FQPwFthb=S(% zsB%#$RcZ~-U34XCX91ZfMw+e?%|~rkWm28N&RVU}O_Vc%_M;SKm{$Otv%d7`qRjfT zL2L8O0n7Gl*FSQnK^x;QmgE^5@n?&^k9cwI)J|i{i&A_`n@;2;e+ifcgxVsGcG;Pb z7XWU)O?ze^saZ&fSrZcaIQq+NMiq495V~=?(10m4at28(&8{CbLdff|XifbH?z=4q zFs9ix|A6-lx-qz+#+g=FPV^VLr7@j`q8rG9QNlpA71gL{jw)`8fpV^TlgC?6nkte@a-CPt;iwIY zQr5R=p53ciNYgw^vo2}Vw37zYulr9o#EkEt6b^1uo@p(2*~BxI|7rA2!GeOzfmTE(g=^*aFl(N&u_I^uh)eCKH_R72n}56 zDpFe_7#{OLU!{3!$xaXq4{fVIAD$Q4co2$&-I9*MwxH1>NzZnTW z&OfJ@GmmB+Ks8ItAzJLO}Mp)hE|r59xdX|ax|6OHCt%1 z7?dBmI*&No`D>SO>DvsNg=&$)@$34e7P?UxS$cYA z5JWfR(Ty2&gON#RKOxDO?qdy}{9~c6%++C)l3*a30tBMDdj3L^EH`%VGriC0$R>0XqFDlB?iF*G)#~uF@>A+&Y-hVwr;;>?B6gNl0O2>#ewh zz{1X-Br?Y!sI7IFRz88%^;bCZzMt?vy3YI`>i+xxwlOPaW$ZHy#=e9oG&8m#G#G28 z8Cw*xC808meH&}G82eJnnkAJ%Lh3>)Nxf&JQmKnpb!qze{sG_LUca8(^L0DV=eeJA z9*^Del?X%SeBO_0vTL%TLM2O|`oSo5LgGujFh9hEIAQ$lq=AjRN8Fodsp)4o#OQ4w z{_5x-)ofq9_(hNZZ_=$6{m~W^mwz&Q94MS}<@ z#8YLR^GI=dYN>^FU@?{H&nVcqYNEWFFAH6{58;xg;X=lBQ&@gtDmZgZf@FQD7=y^e zElJ_|*H!1z443zAHHtbhZ9Uo`yh0O2Z&SPq&=}Ib45svOwO+XMFh(q_%Q%|7-SCJ! ze)fz!@yp)%8*#~sTWJp=6BioKId+_r7eD(ufB}r^)GxF(scl)*5&vtTf7L_(>gO9K z*FKbsP8f*T8tU14>n0j5Q!>9&R755W2}9{$#Z(2!xk&IoBfV35n@sp; z@d~vp`F^r-x2VOp^yYI*7Wq0twFzTV)reGB>H!Z6qsUH!?}t`zfDMR5-AMXt!>bPM zD&0v(f28SrWa+Q7(*KGr-#B2nXS-;6UP<0B~3K3>Xp+e#ds5=~15M-eaN^?bv+*6Q;b;u#b8wQ+5O*pp^_wCW3I^= zF-FUz)(5sOD_Wk3*na*sQ%1=m=7Zjfx^Rz&X60$#OH*?yt#j-(8eWOd3DK;mAYG^? z%pf)F%OYM46T*?2?sX)0Cp$-XcO7pojU42+Kz zVdEbiJ6|2M@v^Xzazd#~xLR|wbN%s4*U`gjAlenp!<9IQ-Np^nL{`&M&#YG|)+)W4 z@T)XS8chr;vy!*f%q=y(y^(Lc@0yG8zLS|?+c-&A#ej)4%)zX}6Ok_lW8OWzU32ct z|L(GYs^|3lOoAVjDDQJ99JY)V%rzYJd33DTZ=@pRNX7A6KaM@<{^;Ba{V!pAB=!AT zNS?JJ+8jp;_zlutq9=$$-h0GwoFMqg!Wt7EyO<<4+yt@5 z6%&y5B}0^ADz>V*gzOL-0w{AKE} z=H-CUo)DRkje|t&PK3~S8g~?VYC`I0LQMK)^B>FUGM3XrucadYj)`*$H#atl?L!+T zWL(}d2o;Cv?+GXv8H^}%)9Gm{fyY$$Xxkfs0cZ}F%Fb=)bf!a`^=1gAgi3CDG1aJp z?RaoA)x%EZDPC!ZDV75;JF+r9@wl&#LmT;GLBZ;V9mCy4kI6b#PAr;9kYY;0s4q z*l%BCTuu|>24xO~pMM@CXS2Hey3lehTAX7g+n`Ri+#C}x_7$-lyzD@vhm^XQ4o{XG zF`Aj5pz871F3zE+bl|Rg_O=N7_Vy--Zfm>kFZDfat*uizO)YWUg$HvEid5NcD9bh2 zfpwLJg(c1vLzBgBO7esp+rSQcxMoG=9)7FDH8KxwaO-o(*S6T2Ry@d|Qi_@i3wQz) z2+5^URCl>qhu95Af^oKkYhx1Es+iI=s;&HVce~?xSL`@RO0oT3=AP}F`KdSolo_UY z6F(8z;Ot;gDPFiysqXc5`Dj-OOV|GmB>R@y5&f{9{NoWo`PtZiNR=(uf~{k6q34AY zeTh6EYqLQvc*p*U2y?(HJ{ZB;m_Q5X!PaA+Q60+?n!e0~74*P>a{iSm2M0K>C2ArH>vqxXk zw*s_1m|$%J3vmPc0F%#XA}tBPZry3hyW_2zG$t}%r~Z5ZL?%01CF)Kt&)nZ=E(k1JaKt3 zNg``L$SYj$;8Y@!J{>ww4>*syVe z03w5^6ftC3d%D`^=q4wLap`k3Hl{tg*`ZPc;vL4;RpS zu@pY?-prKSfIThpZhxM8&86MfwO77xM$I)mQjk4)@ctgPK31;tc5L>{r3aWUxMSTh z+;;tx(bWG!2b9OQ#iD*#wwpw3Paa=gv;KI#F-DlY4Gr<2SLI=Cl_fD*%4T9RNuZ3u z;O!jOy-IiW&z>bH*^opJ)GFt8xY(EFcreCg%Cp7t+eHAn8}YiTffD#mAjlzALKp18 z)(DWuwx6DsxfnJ{uQvj?wx^*!_l^_%5m0A(tjmSxe#%HRXpiiIRRh6WvhLtO6Ezv9 ziS+DCh@2Cq6d1ER4K0DsIyA>itJO|7d$7ebsTG)p?3w>On$KijV`3wg(=GCtH~%rH znrXmb4my^@qEpqC;!CA1Vz-so;g9NOL~0Exi=qCLofc7jT``c({MT?Oc9=9}AhD+M zZK-i+j8UO~5#hG}xlyjB$JS6NB*84#nXtH2XVouUpgTt!Qy*reX)4HBWs0G=AbSl0 z`PCtb#+LP$3tH&mQXSv7V7Iscj3y7%_%X_tp~>S_Y3gLZ+Kt2^na4_l`lt=16PSb&b^LV550H5p%vQsq}$A9M+#kg{yK z!)gwm_VG{|)^s{yx4WN7q(}!v?-A_zNbA~^H(E!QM&hhsX0;8lucZU-S~*n7{mJV~LO}|14Ur>9&slI$X=!Bev*x3ksAv(w?9`5Pt;L^T%5g0+ZaVi;spd+Of$EyhZK z&=Hl9V4;jSFSZ!uFOA?v(pUsg3(Z2TLlSc-hz;D?Ek2XlCif*3mMf4+;mJuBOwIC7 z*$}0S&X`%ryz&it#pd;{;;@-4CDXh<+8OYI!}q#~pWJ-9WYlZ|z*6L-d@n4gH{D{X zBl78cY|5Gbp=kL+-oquBe3-!c!|OBi6S9SGY(Bh}<2u3Wjtq~bN~a3;8ASj01&3~b zfFX%;%y|nYlL8#g^f#ZuS);;N4hqxBWkiETBuLPHE2)k zqOBUx=FQEkL?ljtz`~H|Im~Z9Labrw15SD#B-5Tst4l4kV~>6YY}Br4V0lMP(q7yt zNN#*jlWm#*kP5S*zLeFF%H+W`^MDJfQrBW$Ei-U|>foww#e)E4?|=TsrCkw=n*IFt zV6?ql=*I(`bm;RA=rgeV_?GhX_csd#vUV-7a=ctwgH-}KHus)&0_)c|9PADe@+B2J z#g~)yK(;gfdrPtv;bE*qIYXyKG1}*-yxn7`5F=WTO$3NmHQG_KOe39_5oij&HogBKwAC}M<{=%2L-g;zS>gytxZB?Z3gdxR_mP&1qqK7FB zEhv66u^8J1zsOX1vUw$+CA;K47t6{~dZaAqiA?#&=zmk#vOUFL+Mc1Yu`(*AB3q8b z^3CMol6bNvadIC-u}LiK7GJuQDV@}SM1GP}LpFQh(XmlFmZDq78qqop$igT$0v?Nz zL`I!Nt!0#~KUm5Z+l#7`7>Z~g1ItPT8Z_8iv2G~|WK;xbXCA^u4CBE%V4Sn}T}j{t z(H$XmxbVFd`eqTZCKF{UK$v_=A!rKWl=YN4u@ZtP@>CXLD-Ka%EIrMgY}UTNPI7k> zm&#_oOymHch)6wU>}|8x=F+hKRPevClw@_od&XP`D1R+fK7cGM)V5r@X7t|Om=|s5 z8h@pvK~~9A<*eXgHOTH$kesx=!~fE;$P(!?GAyNmP;u45OHefaFVYP^suqe|)7Xfg z9F;6;-^B@c-^hwj3qPbvPwS#W!5xW&DLxKqBiO(((Fb{B-aIrxYJnk&IneOTLSShr zie5^?e89oz-QgkvNIQ4r)%0kp0m_Qmirzas!)F90Lefn7m_D+)vADZX9jPuQw&ecY z)#IrN`3X*HiSbHSXo`Ksl`6@nSbyI?CIB0kU718!p5kG0ZLjd%VKba7!UmO>3o50| z@2keD;?k;yarP{xd@c(+9gS;|fi>TdEN8;@{#Y$0CBswv!txU^8RDgou!6uXzF(%;Ov8U*%MQ2eYtq0|S#~@8Kh%{uj zK!(l|Q{|z4Gk8Q69KL=^qybWilQSg9`ZuIZJwhe{Q4tTH{5C{>Kq0MS58p6=?~E1C z;!af>-=D{wUSuffmy=({N~O)2F~q@#zK5Jur{9Y)yaj)#KuvCNa{@L=^eR9+ikX7bqt4Sw`D*`>ugN1jP$A0YlbtqDNS0>LO~s zA2G$1abx-`G7;ZWF)B>d?=gf0Io_-RCBZ{@3$7pg1a2IYu2f?^{70I|OE4v)j2aL- zTohF=?KcCXz(OGH&iL#nN9nN_aahfamk~b`BY*Nto^L=v3PG(7lg|MP@+H!53m|98^Hhp$D>c(fRk(~7%OE1W{cOP|+yihs|SKET9y5YSX6 zn!>d8=V3CJPI;4~7jDY!az#IVMeTBB{6&kUe%>(Rp(u7o5MH(c29v#$h!mF05D=*# zii}D`xLi)=^JQj5;ISMTBbirv7;?#kr*D+y3rT+FU7 z+L%d=)Cn|*MBqZL#~Q=^a(ZGSdFhrV-VmR}>V zb|PJ#GJ0xcbM-Gtc&U}KuU0oa+J-%@EGxX=O65l@4Gq^=n<-7kD4jL8zx=cIv={88 zS3&v@yMpwS;ZNrL2kP*jlW)&qPlfG80^9k8ZI?xDjrrUglcA7h&`B5v76&jGXUr@4 zv_WY;Ks9Azrrsb)pJZ-gbR`-f)on5tJE9Ogp$M71&-J~VC`Nb&l_qXN1s#4hIitsM96R*@`Q%yaZz4rRE(Hw!-AwG#zOFC=q9i5IwGPMB`hCNz>n(e z^$g~N^W{;aZFbS)$+(2V05>K_;*heF2zXGYa#2l$cj%i4vRCreqmq}ga_8>*W4jkX zGd!h@Q1g}l4F18>AIx0uyo>wop_i zdPR2fr(A*%kA6!+%K8&;C2-D4T#i}nd)|kTm4A$UkFpc^r$7GCnJT@MhY~WL_Btb5 z`9aR27!Qee4h<+yFv34BQoeyVf?g!(qoxmMsW!Nt_QmK4#@L@z!XWSfF=m~bomKB2 zP1#$D67V&W45?2>tnAPqlKdOe7iY(zv*v z91X1EsQ*sC@E<~fCv)J1OuW7(g^Z{kgVc^gYPpDtC^)qm#Sk=q{7~#pz|ipTD6uHv zMRcTMGaBiO#1-5^E?+$Q3!Q6%yr`V<&;6%mgt&7OiH{tS1ktV^rxDqim0!oya78jn zq6=$W#DRZ2*yOLsB?Yf0{Ttggvm@9kGQX~g?iTX!FaFh=?(L*weDq=c-KdjOnOF^$oT3|%=%n06ex}F4SvAU zx2n*SpUjxy7+)PS3bM;a89VPLZmLcf$(t!0o$67u3qq>e91Gp7>Zoce{Z&iKa~3R~Fg#-L&YEGe1n*^C2dc_p(=%tadfUb!HH|?b!q@y+T>lq;FSbx zm1;Vd=y-YT@!FREC!QJ@|E}wHD>qAMdMH~C5zbgX3zcR9NgVctGAN>O52R?Y_C7aa?E;EKO8FoRZ%+Wh8v3E z=i`swG(Kb>toGAquD;}w{MjXUr@!+1P)@o7lMGkmhDqe%X{E0mlL!5aj@W(jO}Q$Z z{Kg!u=4eW;)@Af}sz(hLkfZMYzQIqcGBp-VY%KdSiJ}wN95H8u$7gg(s6E;0wG5Mc zsG_piSz=w-_zbaz)H|(Q$BuO(6f+hp>mwT#n?N53kS-|m>P8Q^Q7Lsl#n7UbjSQ9imLI}H_`j;$GVxsV8 zKi8JPY~FMRdsqnCkTH`87n6mhMYgv7SICi>R93!jYwensHZIA7u3Z<5glONe*3Q!@ z_}1g3TR;?>DQG0EO{!kq*=A#k*lJ+4v-HMX-O_oMqi!=htx~788R@Kk1N9UN)SQw%ih| z1XzxgJid8-VB}9xJjlcp(fwEIW3h{Ze7k<1wDy0TXGF7&@BM|(*!m`V?mHH?H^xfx zd#1+L?yEP|2F?z*iX=crn(V}!b-LCYzz;h6*FeM;_Lut_4W#iLH4pj%Ri_-DMhz(9 zlQXKjBffw&o153bgv#cYSr?${d|-ubA}_Xx-?HTwa}L;LQ1xkdDfZ*cVbJ{ z$_z@1m7}v=5A-NFb}UH>$KlsIRU?~fuFd{X`ME1@qotR~ADT321N`_{Re_5l?k&Khx+u$SLn255}3{6r(uCv9sYyPN&hAbl6$u|v=I()VXMJg+~m@H6xl-QSXWo+jyY!6GeVz8X)=JmJ^dwVEqQ(u&;im=;pmP zB_`?xsXgeba1cLfJ*<{ZZnmw@FkL@m4qK%{=tC-+1{$T%V`-WMgxVu^><@X_bv-$# z=3?NnV|Mpwona7pQy5#i0ex2Hc2HqBiF)3#Q9Ho4_)M&sa;unb*u zJV+-Z4c&~*c*I~ryr}?q3(j6k#~ACt&QCtqEf z0JT@={Hj%6wq2QT`%#xUz=j<&cfKRA$jb`ggx}8gj6WPuNL^Ov(;eIs*AQI{z}PiD z*!>s1VLr5oqy(0OqU#Lp+_3!~3Sjp#}XS4}Ff+_6#y&2N%d7ZYth;8Z9G{~BkfF*Q_W14<9P*|~r95q{8*l}_2Q+@!*P>M0?0 zdsV~V*?IR`BnIaB>*8qxmD>_h7ToQ1)819l^mk zm$oB7Hbvjlk#GmtbqAs=aCUer<1*4R8CgpO%u;ywJ%iVf5z_Xa{bfL^L}-37C<7-y z0Xpd0h~{n}^>lhnP}XU(d1Dj7dOcWYJ``1%^N@}l0Ch~WQlp|L6cek)_W6E*1t_~2 zwR$U=i!@0Mr9#>ACI+3MLdb--A$`SYcxLAlK8H55~5UuZQ#LJBi26fbH;dI92Bl7)cjM4L*XG5=z?~>|VIAyjWUP`&Swr3f@@K+z93bqy*oaz9 zBl?nYhL*QG#Aj#?b76i$hrR%|JR?@n&^@7Q{v4M?i6Xq_N22{KnU7P-1D)eYql=YSG8w%b7 z=D^+4_v%hN>`eT6_8Y8qjU4&d^?M9*2Z77EhtPIF;RUw2Puw0ZTFfKQ{U`8+2OhyR zz=kE9i%}A#z2>F#urbbug^m+ZAqlV&pfsTl*0}4 zjX-n}`!GBEZwUtvJqFc{VG4{);O|U0Ti|oteG<0dYL@4UJ-FaL=t{J_HQ>-`3i$rH zqz)eFJYTB_PDMq8>LZ2au2P{lO zQ)h6l8A1Cv{w?Xi zlWfR!I4FV*X(WNEsi3H*z(fY1ln=HERY%@qS4N{-w!o}1;LHTL3TIs)0fs+5nJYrD z(2(E%8pM`>_Kd0bbwl7G;J~NH65uCqcY}7sffwe1DRAH|5nvQI6SS1c>sN~8UwH0F zzQxt+2#w#~FVubBbCHduZ18+M@1F(;PAd>D-B2^XN!c$}?9*=!Pcu{f7{mN*tb0%P zQVCJncoOzA#z9Boe!d!LO7|wf5oBgT#z>jthNaD!}ys!Ye$N+O0HWl*_qpzSWN7+k^%+Bb&Gz@meo2HBb4~YX+8Wm@0CkEU(1&viO zZP=u-(m2!X-n=A_2GhbL+P&ekcJNK(Y;2XzVCbbU4L&1J&2_bPFMW62V*2O}``i&$ z*;6gf&z627AV*Iy@Aye?zyrsoy!VC2PnRUD{Hk4;(%VyNwaaa~LS2V{ zH`O;`maXQLIlMd91g~qw1h;b_9b1rA5$FI3I>5jWh(J5$L5H7$Tel#ozky*n4$Whr zG#t2h3{q|cIuh*=7R>gd8*@ZJMU2FHKIrlm@L?197`gHC7TCfJT*g87b<4~91k}zS z?-G$KPleR2cyhLYJzQXDJGg!pcxE1SYC|%Hb|MPbR4A5Ju_*cCr=oY9S<*7R&>nhU zq#0r^Z3m&K%rv`el?1#i_RxWg8<$|rBdUnz${i)cH>(XgYN)xjNvPJ3!6@iZmUUIa zoYNI3-tM{65i|l7T@8)(M`$&`Y(m@KdI!4>Cu$}NA=gRJk<>a?Zh6Oilu9h5hX%db z4Nc-e8X4ep61ar}=}iUtwOWZJsbARwcMXCKj&cj&kZL&gT9#bi7{&q++qnfU>IN4u z8WOqkeKds{oI`agq#Wm&V_a1*2)eojikXK_{Dz*|k-VH4UU^fJL#g&I&6;4C!JUu~ zNKigQn*XhNwbT5#R?QEsmT#BOZf|!*l>2m8D!&tH(I}(Ddkqecmjr%gZlt;#b3S|P zOU{lv{%;a&gpd30!wn)6we{`BvmAY6rX6Mo#y$W=#UTHZ44}}o8)I#kZJ{$%C_OwL zP?O&Shi;vR6dD2Vbl2U0L((}Qb>Tg5no%P+13PR6F(^kT#~*w*0W>>EWl*SQP{<`C zjLK`PEp_m}R7?*Xbdd(FO|_|>-`64n?dgYJ90PS3d5!b{CH%b3(6s&Sl@RDtUVYkC zCYE`n(66lcuBn^hsOx3zH94R_`e1ePgR|Js{atDBfX+)^BRRKbm;p3&B zkv1Wn1!l< zlu!W0nKEH1pkd&6WZ7e0&rYjaMCzlNVX7Yjf4a^7W?S9|NUsQV-)NiCi^z|D?VlW= z-MY|WZrvRm2=#hIIj!y@2Sn#r99!DsB7{AKzq2l;Z09S7Z-AL@#K#_ zaJh(kEe-tdO>A8%B!LgC`5&|Xf^j77O;Rb6up zWd2R=1=ovtH@!v{=HjQ@y9QSdz=c91 z^QrEZH+)|pSm-1nqq%$+qBw zs%_~jZ!KL|uB%(&+v;MWZ=P#xEohIC$(%Y9> zH?<2%`rWqWRA{_*Z^t1H5nN@hIILeWe@H zL#n?KhoP#2>&C!78{iZUxWx#Xx;1{4LGPajo}ULk*n&pm?(c>)HTl6NL||(tVH2i! zDFjMxQde?{QgdakbI~=vuQ?1_I~2Y`)2c~1dRAs`(dy1?!g*=-LDjAjWsB=BxzyV8 z;`=dRRr}9bt(I&5geJ_%vp&;T*9Tjzt>4T&>_M75zCj9ZBfUi4N@V-DcXp@IoywbU zC2p@lc)Cz8<$o`ZJb2m)jV_LAG*YV}skNp;rU3`?3&E*euz)B$j@S8L9qni#15(3? zy{@QmO$1zG1f@VV+8jOH8X%opk~hb|bhGy{-N0GCr0i!&(O;mOB=R{ur6&3K1^0`l zJeVoDCr?Qlq5N@;d{)U}^EFom*pRIbPJqDnnpD$2?l(`VT$0j@z*{R*Pn?B%t5&)W zT~i;US!3g$!wAd3tzbY9g~^7`?W2Q>G!T{WccGc$0x4l`T4xF$Fmlijt}k^Hv8wU^vAj`Hf-7# zKG!u}dk<`OKOt>w4A+af(s2#3V>->zbE}yadX97ym*T|?ui`kiq@cpfu%Z|7HS8!nz`sF{9 zuL=KsP>?oxcFlKSO1-Z#qJrdmUFFV)#7?@7&oMHf+%IfF$k-9Vh`W6mU2gb zzZQ(ofmnj9mp8(=)XF6{UB=&AFoE#h5iY;sh9o}EkPDbjvn?=N;>Q*YU;E}JKl(%L z2N?S~#1CuvhEncVe^*$wu&neBd+e#_F51c>^KHi#qbmV<(Q)KO9|E9U#7m_vC z`roq;YMMW!d@LAw*!}vxWe^N-eK3}ke7!$7-f8OK*7V2Em0Kj|O!=>qwwcynV~aKJ z{Q6Kj&-F=z#mfHiK>1j3N-tO+r zTrakwkijLcM&TLdHvX)P7FYk`dk9C17y`;k*xe-K8`|9L6qCGUR8 zUt0ReqS5IBrB#Bh^t;39$&tgC@m&uGWAlw2!lDaf_H(5)PDMMr zYI<#tC78K>Et4y0;zokam=0n^AICl0x+p050xny$UQE3v1zwpF}uJoIMVIu>Ya zk!ws8m2Emb&>f)fl3^V(mv(?HdIAr%JhVJ^WZyveLrd?+cj}8@t8Vy~J!$srd#)6D za_AS#q9Rm!b2-OSSk_#08drXI<=T|#F4j?7`~6sLLsNKqL-QhC5;?jjRdz1C91v8_ zlgf3G9o~@!mEtK#Ng`Ftg*iYRR4w}^C3`6u;L0$*di%{5W`rau$t*5DZEcX)Trf_j%QwPP`r_U=Epxqf3j*)D#D zVxoJVb^JCud3jF$kx`{taIR5jmDgH-Y2K%Gv3MJ1|FJUvU zoYf#Pjq8NBO3pbh+u1f2*_y4XY;~0eAoMl}(^Co1^KBUM8Vy8TOuQ`X)RXO)ABZ~F zo$)cS__?)jg#0a9yUMG1NsE3_DY=2BsCn}A_^!C=iX|uE6u!Dt@>%dGnJykVv2SBZ z^W>dhu%|FDg~mY519NAC|4<*dNff@`v!pLL)$QQqvY=^pb2Ret*tYy5nkK8)PEx#~ z;?Do_b(8{hj{q#Ox?h52k}vK1`0VpOim-j4H^M8lH$_8_&X$&q*UvZ}hsYaMDU?q+ zE|e4qM|{h|?9^-#xlF~Yz6oD|vOOE=u9>D#r~XFN)nowfH#|?`KP_~F?>(I`1kk#+ zQ6?tLPX9}H*6pEf%+*AFlTB<*40=Lo9Gf2)98?^l)E+$E@+C;;YgJR1-u|+x^$;RT zr&hsie?n{l;a^AX&Ve(j3!=D$WBY19OMP-n_jprL9P`S@Tk=w`DgWfntHehU`lf%| z0}TH?T}M2#pRn35LydcLg2gfFl3kZX6D^NEa)^mf`*N*=s9}h61=EVkl zM7Q~JoI9WB=FHpq7QK*A@@;4+Tz!nHws@I(X)V{WIc>6*aZgp2iLtg=n@Zx_33Ye6 zK|${W))I{W8UamW@t<|t4jN14&jp)L)I4gJY`x5r z+Wl7MQD+QkpV=;mxA5!(Jd!z8`CBSs=V$Fg`xlQ`?+?wpth+9LQwJuETg0IjwS_JB z>DSk;E_w$=IUE`pFP4r@)p=2TS1>|>Ezm9=kb;&Ct*IGlnd!MG<8yYS7cVsd>_SEL zLaZf7;)^}2JK|_isT$^+T8wU>Xaw^o)1hG5E^D+M=-d=8ctSc>ZEkn~?Z^=^3f~ zR8I^c=64TulUi`QpI-O?7C?GS%JiyyU!AZiR%h21yPfe*$O+OAELe1iecj?0=y=R~ zpSf||b*}wI%Kh-N<}`V0IS3^rCN5+?jbPeO`{ad(f}e=_Hsk?{>4@Sq;$uV#HrtN< za@V(e{KqwmRZSHh_=w)xm88^k1Ak@{{TokeWXRrDFaZhJ6NWfVbO>D;tJ1vNu`lY~ zUFK#1ajsJJhjyRt$AT}+>&*=a+K*v*t&&LX1!wY6^ zbpa_YlBZCx&AiVG`LBrut0GwkZ?$~lR(~29>RcH8u_nKHp8RP?Xz1kG`c%AvZUkRy z0{B-B_fr~17Xkj!84Zlv|9gFvCa#vr&G26?zv~3@pNHRd&&W?yKJ_7+l_(duFMD?* zSM~iBA4Y~ZQAQ>IvVTb2Ck$X9ni6slL$DpmF|@du-ITnhi62th_UR9xVot6=nSqvNMl~V#3wwgESosJkKaqm_(mu}6tqJ+ zT^owx_`rw0(&S&-UL#$xTXRzJ9pu0pF&kO_u~m{Oh9!Z#wXLj0Y#C&AI={B%sEK4K z4)g@d8KBr4W%jcx0k=q$j4?$oY%U^hcKNmXF&#|sQnt@@v1>9Yi^Mq-$Z_5G;Knzn zCGFatYszhpi^3rs-)Q!cY>2YDE_GV`$$9YrE}&;wJi8IF4$ERrPd_9L@?bO=z0g67 zy8|vv`3g%4;y$Mu9+EF~NaB`k4$d>IR_qAhtE*mRqiu%!Oui0g9Im!Yd04$zTH8jqRcky#?0H@1LjdPX(m7+&b_bCi28Hm2OAw zDmeVTK-AT)wyLVgDl2N7$_*^25|rK(=LKW)8*>#T*Axa00y(sU=w>Rx)&jOv-`3MP zXAAV^O(Ql3*EUoKKGI~G_q`|jSv;WDoiG16?d;!OK55Cp+uiv@5niiFH1Ed=iLT>DR#XU|3k~6cV}27Dra}p z9iN`{OY8};FnP`}87FEdE4#e!Y*|hm`ZzA1in4z>GWpeM>FvR>p|Am(a= zM-0GIyL`nK)!h8thg;{rfw^5=L9o``8#!$*xIHh*Ib)LH!3W7x@NA@c{k3ZyEt*$b zR*0hPz9mW~HDkC3D`8v_o|MkRWmy6=4n@2Wd0AD~N%Ly1|ED(p@IvV?CVi^3&`nh1 zLAIA$a7*ymK5B=8{1uJEpQ@i)jXvR{7832oiCKB8B#}m#<7VqWO1%1{df$80iyKQ{ zPcb&PsFIBj$GZ#1`#}L-*;g(+FVyzePU#*+O!>_h5)XrXrk#6}W}`ZfGqe#;586Ea zC&gJ8k^!={`tS=B? zW>TLKq{qa4E#Ul@w3gXmdIr1tG2H$Sp6r}^!ZVluAiD2KyOW=D=9-1o^3IX?p~C!8 zg#%p*>tY5uT}z^Xh1q2^NFVkous}+prPkDSbY7a_3KGbV`-|i*moA2+0V=IIjNr^H ztY+{iN3d1+FE#V7HUhe!%Mg83U+MrwxV2j=35{OqUl=)dlp}hTBjVI;=-=&aYvaq! zIOC~7uIIcuPIOWO|LGG;${DCER%KSSs@^xX^fvwch97e~#61~YtL z{+&4fz5sOi+ZU7Udv#*3@7$tUB>3_od#RsJJl=B6AYzVBKTi*{&g_Oie=(&!=ZAX& z(Eg)IAF?c3kPb$?Q7yEVS814Cyb6FKZ|LoHW zd;9Y^JqVZop;O@rsh9m}t~s>DyvHK<$-~2cR*MH(E{eGNlX53yr%d3t9nqrT9ddtVnOyJXugaA|Zok?Er55fLFw)N5&n2d%bmMDW&kyX`F!fWX17-?x+Didun zs^&7W^*C5JK$>(6ZW@ZQjzQ_g%4o9@Hkl~fi%Oms(ZQJ*-*k1q45Q$r zgHbHQ^JnoH;TmUxRK0_YU88jDjv5|1i96trGxSt2JB-^$(lS3_s%>toZtiD8v2k>z zxE=QN@;P$i#L@7u;MnLh=aT|65{_KBNM+@dFICzV*E?okJCw$AD4KU`eBd=WN_jY7 zHp|tU&d?dlr3~bIwWS@dJ9n@?mT)CqwXRIFzKu|D6`NkK9$zhgrb_R`6`apit;1X# zsRL_TtBS9aC2$SY2lY(G4T$&U$kU3nDLMB?TF0mHCvOuH#|`3M=$#T6d#_s^dS_|D zC%Ubx*uO@azr$#MMk;@hMSoFL-6F_+)mIi6sXw(*eQT@m&06V;qwKba?Drtt<_XQ& zaNKHw+{OikALr5EauvQ-B7e63A9e5j)I|HnZHENXfzZ2Dl}Gr)y8)46!BC~CU`21``{tQaKKPo2Ww8PW$68lUC_KQ0LDZzyeU3$gdbU+sxa?+FcW3q9SF=$Kc0{7Im0 zU%H%)D*Pyz@>%NNZ4_Zw?%Ixw=SLYY_6gq^`G9WO#O4$K=E_|nDL5o6IhCC-dn#%A zLfDiocy8~c`JSBizR1ZvA<-Rqk)1QbyLy5vXGB@5qQfTAT{_aWr)2ZaoKCY>F7(o< zxM+}0uq}$V?hUY-aMgcdrN3rrwd3l#Z|A>n9reL3d*@o-HX&{&=-OVS_X;`ab#c^c zLDF_!?#KLxpX!?ryXy}}8a}rbFFh!`UznGlo1L1Lnnb#jkVXv4$?`8x464t@*OzdV zcWDhZ_iJmaA2&C3cXu%v&&I}v$KLh!A9S^CH#BV(7VX|o{#+P-ka2sT5cuha>p|eT zFF}^yNM_#)jlOp{eQmq?t()|fdGpJ>=gykd#;(!QCnM(mrKcaSz5R4^`4egRplIrA z-o`=Br;SI4?Dmg`koe!PG2b$b58i-m=S`H2s+qu<}Z{k*;ViT(5YkDtH){Q2|! z`}f?fX^yu3fB)}m>-+uwcu!JlA202{`IEF`Kb9@K|K`DWtGv$N^nQ^aF<%usrDCq% z8KRs#H^vXPcsFzQYr4LJr1@R#lH=3D1zLAL#1B49$ae9qXxZ7)tEB3;7@SM^{bjhN z=COhK^|>L@E7u-#L8sB$LpUT-vzwL3`ElVrhQ%H9o>;J>ICX9ab=3i(mXrd7L+H3E z^vB^_e#t*zDe_mv;M>_~8FR%9gj$Q-8W;Bv#=-38;Z6Q?m|YOBuEv*_FV3m&V8Z90OTRmdf%>ZY5qRQ z9KzB?QU> z3$ypR29`bqRXF&H*EzWPUknX@`2$=<`xiKv&5;I@vrBpz!Oiyvph8os3#mqriqwS% z;bza);0|g>!e0kWyEg{mtsR{}q-G!cq5Z(qx4HJ3-Ai8%G`f}&?Nt>YwwS}gRqS8{ z;Y%XN>wW-2K3ai$2Y1ZFs!rzFhu!#?^?fwBT61^qd3euuBEsxX=fhiS%zT|G z)jIC=2~E`Jhb_k%UHkqBHSfoBK-Gq-mNZR`(%eqXjL!o{YdwZ#n(I~%;1^a#*o-(v-Of*7|H^3h$fdl}cvYTOWtH4A;xhES=k zbv^&8L3(fk)u5a*!LAn%PvffC-?K+I4bg$44<>FfeoEKSj#Odqzw~J~VIBb0x*OXD zR@2Wk+rQ2^b0TBl>w4LwrrV3`7xSG1i~GK#>3KWmvP~~9nE?Xp%rnCRpX_9ICq~p? zEmLsgDf2Usb)6Vo)?vPImJ ziZrG5pZ}@m4Tt1;Fz?<&Tp3ajZ&Y5=BD5m*e?1iGYq3&`BaL2KN)&54NFIv+-Vp!I z-z$8L=kA}V2jNW)R(f{?cdmIp8Ey}X!c3IT7K!S5N~=dg-weYdX45Wr1I4-l!)lSM zX+D3}M4sDiIDT-(h>tlQ=J+z!bb5`$E*^02VIAHXdIc&~*$thSvGzto~5)D3TxaJEv#$ip?~P@?>kr-uBw;LdCX(Xbmln!bnd=-e-2ol9(uxCn#p>F_J~ zo z5#5mcM%DJ-Z`ZnTuH8#Di7)r`l}|78AjG;@JZG=C%tQ}-5wTa~d1=l}rr2; zsqk9$+JIlDmec-fXaA?@IV@UhAos44SSuvZMtylv(XiVYfi#u){PT_KT*Qul6*Yye2y0 z)`T7eH7GlFBf8QC@?<;TX!=EHSOs_I5KUQX`r+pPI zoUE4nbaOJ*X>`ZGd8110-`I+Yo{3la_;o9epcdzRkT}-VlI#QHP5*8DI={vFP|etd zmFCh&e?rF(2KYJqdL6ZOj_GP~k1sI4n2Y9|DA4eiN9245zItj{prJ6086ec)kv4&DaY<99=*5#?(@LB>o|1U)X=YCB`;p0F+bnfNMuN~(M)|%cA zdIoBmRB)yW1Hu;Z^`{@6P1DXU7D=+VR*tJn^J5D_wX5_EECdGsX;h#zcnvG}j%|Lp z>)(7ylt6W{+8t;D_2Jl;$FA2_DJ+4&mD zZx)u7x74H^edN9T``7tNf1y^}9`yiD!gtDFD2oIA#c8p;2#G=pomQhaNb2uK2gDc` z+SOHmr)T`{PoNg%ux`QftZ(X32ME8~Bz+;?H>mtkEA&9^?r~hSTZ{rvrLt92*D>rt zn!?*gaUQiHz9f8zlrR?X`DP~eQb_um_|W8|)835RYw!O4d2n#$VM~C+BOr70lG&@U z&H1pcQ6kpLZOhVT--^J#=9E(yln=p`vtZ>oJoE?r0Sl(E4a>Cl7b=L5t?{pZ{Sq*7T3zS-pxu_{ebuS31fbTl{#N4N9*riN4|Yz&q-*#)2EalxSf0D z;rAoZ(h6DU3?HGv%ju3>Ua@l`cjtIwAWLC~Tf}2zt<@F;-bIVO?%{O%XEYKb`w*cU6Vl0so*0EGj0K-biOT|zn+hY^G2~J@th6&k`Z|Jf{Z0!D z(W-xa9_0j!n)bKShv>hskb@YqMB+l#OV07T`%`2yv{f4yR5j^KSLc;{$@ z+#*c)!%dN|@cT4aRtu@?cEo-3F`@)VZliM$%#oQm#4}n1n>${46xNx--${d&wIrXb zg`F}&G+##y*XEzJ5chV~`Hj=$m}(j~5p9ZRD;KN{mE&ZtMVwkhl%ld&Kkydr1w}Mi z5eimGgw+$^btuq(*G*hJ!?|K$)y}d0M^_pT+!~0StR1oeeT{6S|9}|1a-qQU0=$8J z$-vUY_S&U=PtPn!SlYEan*p)q0Jzi9RidBt*fvRKdtuly2ve#6g*ac&pouH^oMw1!_crHil}(TvU({@=KaC(bTowPN0L zN!Dl7pPaEV5WUfPjJe5F@JieyR1h-X#Nc`eFpF;%C3IjR%A=4CE2I^CoQGwjJql2u z2Snt*61U3^fHagx5iX|;btz&DUd9frK!bLQ93Nox?Y9!j*?8hM{HB3Nl7)#|$F)N+ z4pCe9K+dh};0m1qEA1hbvk1+Ak|!u)NefAODYg}Z=qZBLoJO=3rru|9LX_k#xysJE z`wfQoOWDvTobVeivIK)LTaI9U3AxXT%{-`b>?N7MhL)bXk%>Y4N7qP_*Z9rm|2Oya z@0PN=>((_Tl8?2ov`I1OGz43HMjE)=JFk9Y(s7R`M3aqzq=Ip)+U z2k&CQgtcwQwJyOLyz*=%(z7s# z+^sn3w-DY@#7Ad@qj!Eg@xJZFhYe8j6AWSpgUDt;(^-7aX8GFXntfg?Smg4@n5&yh z*xwC6l#YZng2|n9SYk5l2#uf$!&IGNg*ZT=GfWi+E1(0T<7zVCumU2i-~d=mLuU5C zwOBBXmX>Rkux27mtq0afY;7VI*0T$u2I1;NnA=7|H36nr1ncxZz7}X@Ftm>Ua_X|b zGG$IA=_vp%(glQ9cKmC*cR-2cfD{{p}|oMAc6uzNHZ=nkxa0HXmyivh4g1~g~#aWM;6kAwMD z!fJ7_5IZ<0P4>A5#)&ir?|2l`9SiC3;}YPmk=5r|!0izDJtFMW!Y%9QXmEG5gFf-3 z_mw7GBp0;tUKi|%Sfh_P!s1O;%VPVvxVUEoSjRDqGd|xpDtR_mlIFYDkT4#-?$eO05t?y4Wi;GpcNj5fSfw}KuzKgdO)sqDAT67d@OlG%axk35fTj`em!s2moDppY4TDR3j~CJj z_$K#B=z?nEvTAxe4SKz_Gqr{9_~QBI9XWpQIPo7`$_87J@lOzqJ#m#q=`_yBOyTcf zAr8@q{I|n71ehuSMnl2UcgKrZ(9B8buF8P-dJmcn6`5>lWIzjvl^JQU3_2_%7FKdl zuvH8+D+M0ILrV_IyZ%6Fn9wE$>>dvOs9`EGhNxtSFbYc3*v)mBga!GGUpt%EoqB)y zcU7Bn_s#+I2?M&JJ`>mo-Ef#mLqBiFAuW*daNcurUDQ;xLB(KAW{CPhv zod#WPn4uE+4(0fF=uiqkiQ@;~Lv=+WH2=^~AAPx4`Qv7Jfz9Jvh{r$4Z7jY_x$$;6 z{(Jb0Pc59w?f7w?6fFHlPa)&+`+8uG94yUepa26yGobY-SPLH3f`nxGrZ4sITzz0f6mG#cNV zkc>lA)2|ljo--nY$d^fns!u-#6MOEVd+q@Sa$2Bt6T}D()__B%(cn87GkXqG*~g5R z#d1B_sNQ?*$s8Pj*)(@kmD7gZI=ml|gM+_nn&SFhzPbo|QWUA)l~yWNHTwoyit6lO z&$MG2yNWBl8(+MdXv(5NGZ~}BsCjroX9*qJXEUekjrhpor0)B-z5v@6Ubl#5sPheZ(lo$o$>rr=y?z$Igw{ol0hi z*%0UsaWT(yBL@Q;obFC%bf=HO*Wo;p6XbBFpgaVG!4!jV2MGuO_xBxXsvUD9seHeQD%cDU^J$ zT+sjgqALF`aV=k0T%*lJv9dY0bRlVSwvW9YoG|_j(+vH~rl9y!iF_0ql#1I=1He)M zun`#;1=C_526GI9-D7V6C!tAl&@hUuV2Og7zlGe{ zr}qyoAwCiL;?)l*g#8Eohh;OL8%9S{aXY`ukJ%$9piREpRL1i^fYn`=)PDzjUvT2y z{+hez&k6-g%M$B*wb_%blfoAuCs^r1;PABE1BDhH*|c5*SWTpTO~4V!U-<)A*k z^!?}(4oE{oi3I3!*nScX3gm^crbqisTLwZW%J8t~8ZGpASku9{`ZV)1tVc_Iu#Ew2 zXTWw?h`Bg~SToe|#whSHER_v?cOH>Ke^I`&lfoDk34>BFha$4-bt%+eu_wNK>RCqV1ZLF=`kBsA=wa6k&$N+lGQEceo} zzZ;B(g=xWj`F{{``((@y<>|wqf1w$Z(7@yIzY{;;H();fZ~zx9x7r@42%8dC5vsI) zBB@vJFC8uCjeOX-Nf_x!I`I%isR*Xvh6@w(PlETWg2^ z6?%U3?hJj`pZtHd^?waSKYAtfA6Yq^ZY^xO)gISz|D@LCv$uDCXxyTH`arix0t*O6 zc?c?4=JB~4*Sp(VrJI9Q?R0P|xg@&+S9MA5ZI=9UDs=kVPX1;^eY$%U(Otz#X%zx; z_vaq3vfdi!4{`5F$*Hi}3F;wRs=aHx*d7oZl0Q~C?m&_2xM8VQJ#jBJ-`J|lNubwz z@!ends<3ws1)VR78|qFLp)Mw&a*=jQLf%nllT@r@&TP;y0PN^93+@Q2>@d`Cv>{<$ z#YVmT;Q!aw=UCqTHhz8B_vlx(SVA1LrqFi{d%8SoDH!=6YGHP^EM^AQCWGWPvY}ys z5=tmbB^4z>b5>mdY7K5j60~%9)20W4%X6b906m$g$(TDksG6{w*@EZe-I!ggNqNUg zg7yV&N=CL{0+OmsJp7YHy(O_p1~vP1Vv>JsnW^&Lq&NNyC}Cm`qILh(suE76^7foM_e<60qoY}LklNZ)fTF(wv zM<4rc1XIgmUe{UKjLck~`VjL;s;x2hG;)X^vtbG;vs1Fe3Z8ezBnjGse|72F_ey)^ zV!0vQ9G;X~N!O(6&9^i=ce$k8RV8_bp#8CkzqpCr@;EoV8-OD^c)f^aDQ((oC zS9-yIfgO^`<+U^X(NNSsE^{krSNBA;Z^y?0%#!=Y?#-faPo&v(51Qu7>fm30-veu> z%ihNCrah2<`N2jea_IciyZ?O-w;yb63;lrhw%(lWN$TX6v&)v<>VEO>F|g2x`4>y@ z6ynZTvaS}!r3!k%Gr5#W#&+uHn@&P6XEbl#_bFBp`2BE53FVTS>bM4oPRnyaC*MDw zq8MDTw^2k@J=$DK3NXj!x(I5YxvjqDQPg`PF=imkrNdHY4=$BEGpkesOFa4Yytr{= zZb}2n|J40n)CblfeZnC{M+@d=#I7i^0Hn+QM}Ww+KdOk#A5=RUyn3QcPc($d8+J&e zp3Ud6ZECWx^;>n3OLpgrGCkzqB+zA*cBtp%9-@+$Kn=0 zJU+<6lqsi zKsiRo1U|^IU!`=DnCu@E)2_%Of;1*>>`G5`iDdD|ZCl9V(p2r{bW0Nemh$?_un`YD zIcHMP_^t4iPecSoU0_JQ?V(D+TWbNQXU@qp+71_HRdwv{oc}6$W;(h^u{7yu@Y_O8 z%gKZ@cC#BnxtD@l+$A2me>JAfmEP*d0PN$61f;T3=8ySf^U3`C;^~HCt=Wm93oT(g zqvr%C#e&B_N}Is#mnL{dWA+_$J_i+AciGuNO33`lV}sIPP%mdCvIL3Ufx+%XJ`mc8 zC+1*K2A4Kb_=Cx>BUAShE+C~W;vYp4m&rdqsjZxR4OQ?Y<7Ld%Qm`dg;Z$ta$MWFX25Kifab;J?aZ#pq#Q{su~s#s<8Rs(G2eby z{x*d9v+7wJ5}tc$)8(eK3u-S^?1SM1HQaZM|Bl>fg8G@!gzkE^|6)eZZB}H*LVsi- zDN)#85!rW??N3a&zF$ZT%;M)t&DoEkzF6U4B=3q3#RF{W-At**Q}VCk7#7mz_Y=*A zRo#O-DmhFtqicUeC$dSK&A@AEv(XszbXBar?!eUPG(aavd(-}z2Vi_9zWmWZj z$YM%m-FrgcdMvI(`5}l4cb7rtPly>cle|peH8q|STU__*1iO6C`ItKQ#)m@O3eDa#O_^{U0)iM)#1(#CxTA! zij8h+_y78D$Le3g2Gw%VzaW)zJk0)FTWNfR;&bnk<{uF4lnyZCISc)7^YN&KY{>uO zBK9jJ4*+p8-_YOA&U1~ng&L>^hCtX`@~Hl20sS1`yg#*we{Rx17QZ`Dvwh~wCVuXm zlF|`SQ47CssI_c6GkcC5#b1;j?%0&@Ewf-*x@$9T>xVO+xx+TUq+ZF=(wUmzGiD4> zgkkr;lIfima;b_`Q(M`{pq?j1)Nq!`%pl`QY$dX_y&0fne}`(328n4=jEI3mLa8wT zNF<6{0D>%$pQ+GHjg8pw-My>CE}2p0Lhno&3l6prgKs(ofmG&L1(GDUTo7IANZ zn#{-Qf}S?bdK;PL9Yb!*LrQgwV-%9ijnsPAtI<2;b8_;M_sbjPdYVI?-o%;qrav!f zd-^7~3PXGFnVH!GAbe)qWg{M!-7vh z;mZAjAP62xeSe0D2T%><28_geU!NUd)r%PwaTl+X?HFXcZSn~YK>Q2Y1OPb)#hQ6R zB9G2&PAb{aP~@HrpNO{DI^<1uPDGw80cFsQphkL8|94~XY=E3m-&r$u%eijrtK_B_ zpWd^_+oR{$WK#y&|ITT5DM$?F#5p-?EDLoLki-|P>;AANqV^d@ni}3>Nu3(Xa>!{N zOE>spc?(+AA*J_B9uhavM}R^i0Jeo!?Ft%A&O#wZ^h6bBkas+JtrFzDPr1}i4hM|f zi>HQmgY@JEBz3LD+d;*7iAFRa=L4saXC*c4a#e~4K<7+}0!$PMw^r`QKRtUfGuW zA?E~u2q}hmIvHO?P3Wc&TDoU-U3v)*61*xieJbrObbak@-Q2N};t-RTu>!SL0?Rh@ z8%1SoT5lU{yiJjpnKK}ejnQ)kG2}IF7w&b+W)kRR^fBn{(R5)R$h(hhNCPUTkX2|# z%TLL#8z#<S(S?LMR1xOIS)QA*FggC^l%Ar8o$+a33_#GTL4OS&4D$@aB+hD_>1^psV zU4o}R{k0YVazlnnh)FcIB?l*aDt(+b66aE(C&FmJ$jd&(_j^3A>Mh4Dz5WU=k)lSh zog-L2`0gg*Jnn=E1JAdhzsBx;Lp@DMwddy5%MV8gEpF~lt)ox6`T1Ct3h8?fk*Vu; z#$)6+z2uWJkjx2?+a~q6?6P5Oilt&{O$2n#Zi*5{02!mGAqU_v!H=oR3Ni;PlcQDh0G$Ni-rd7bk~}Sn2r+dQH!6};C7OZjNj9}kpfaRq43wwNvKX$H^DoZz}*gCT{LJvko@txKU#UAe42ukd#@Wr*2j^R-Z_>= z`AAd&_rAI8B>~|KSK^TA)kaV_0~C&#aY4L3%Ft6Gj_5ezxQFeJ`^d365NJOLl&lwy z>Bu)(zGY>uSb9m?!YWhO*h{VTow~#Ica-Qci>%Og;L|=15@Gl3@^y`YppWCyTi`H& zOWYXchHazlLSTpT<;S*Y-#5#n_G=Nf48IQlixls`Wb#f~qOm7PZ);7{8laa_Q3Z}UW?aVu z+VMq3oLizoBe@~pr*BHyW@IFi0V*5B`Mm^X&XW@np1dNREBQ^lfewXg1K~@K?m$1n z4CQu8Q~0)DtoT?<5d?ok8B?T&r(7;+AnSgzGq7EkUg7KqCSI}eNu%#_S0G9!P ze4X$5b;qj&&krgzV6-o&rVLb?|E#0h%KNS3N)qTrJLhZ<#l}F&WL!*AhRx;7Qv-vT zCasA{IL99iZ|xU#E}zeA2l)<>31gI)<{RO(cVZcShDQ{OXQ1Qa1&ZY!$k-Nb`4aSm zMddIz%3dzY|D`PcN2#p_5w5kRT{ zPPP_g&=OW}`oVC-4o(B=agg~mrsl_S@kivHf)C;1R6ia_NQz|y9h`Id%}l~@RENeH zjY~^UK$x>$SJjOzMh@QffeMhG5omLzz};}%xX(T~jM2K9z7Q@xHe5w%+Ie=4*1gz4 zM%@p6;S}`Y)mZIEir+LPlufyT@d)+uSlv1fPF<(ophM)#sUdVo2rV*%0j|vq3$wkd zPkbHpH}MR^aVHt50|03i1#;v#I^rO`&tP3c@~=n48eT3bXAmzAq?VGXRUW=y?QJmj zS(ymZ^8yh@!g*VWhADoE(KBJ)6c>*xp)FwUnkjCr)|x5uYas{msc-+i0(GyG74k2g zWz4-po~JkAr#+(zg{W0!bIZsNTD6pkw|j9x-6W(yh%#pbS@jcz)&zP4ULZIxZ2th` zYyA};gF}lTCqKW#$*;u}afI!`o6X?0YO1^At?e*St;f~9zd+sXFs*|`Jp&N>XBbB( zrY%lBBMwrN1DX6UQJo0VI&LAJat5I=AT@TFt{g}o0NTGy)}woumID7PScteq4xITK zeEC|h=$sbIQ8fi*xc$*i>DBQg@@l2gTQ&V{_eG@5@Urem(##c~syW}s`%@0D#rw%y zQ{bI`ayY{~lt}e$nuj#Fm=PfER#*JhJoCei3oCF&8$!DVDUVxmeB2#*^s zhCaO07Q%S-F&65Si~eJ+YMPNi`%6RDMM zHPiP^Ztr$iS$vq0IU9ZOmPv+`cAZ@xAb~D?xIbyE8$1`gKA$;l5c;-zRlg?703W)~ z7C8Q(;Ug8g&UhD_7rJ5=^Zrxc{p*=N_l?LyEWr~>1<7v82q#KA=X##?);X^Q|rf)!T6;%kF!%BJM{5y`{NJW z9N%^IW5&Kr@DGNnbNb z=a+RyrJbJn33>di=6WUR>X6TS<^6`Iqv5T-*=fB$Q;JzK>@l}&ef07nufbJ1lS1Uo z_iMyt?#wP&OL@7w@EE)f8g$f~_p;zU_rGs1m9D#-H#&LG!`tpf(6=dz*CsEgEMDl% z<8M0NcqJUXr02C%a6jjbaF3Lzu!#UC)$X;LBy!Qj?>djCGnyoMpbQBnsnos#UZTM#X5S(>;`*6g;{$4cQ z;1=yGuWO`>vV5|b{&(SQ+3JcBF;5oLQGd+eg5PzSr6_55Ibp|2%3yhQ7~|Ze>OlgzRYrMKX9=7rv0uV0#dhZB><*HyC${7t_r>%Z`yZ?BuyTih0<9P2j) zU%ek<W%oMIJT+X;^jUt9_ge{kN-wo_PfI_bcZY|ugs<4*TRFA_KtzhSX)H|=AdNl_QB_vVP% z)4B22xMN22qXIzxxGXZ}>l}liUewNp-gb7A+qv&x>Da&^*;>b)c(8};FOP$|Wka=| z`H@zB?e7_^c`5IS;E~Ui%pIqo2x|`oTR~hxSWxsK|mrM2>_9#?bcI7 z64-w%QM3)MlPmMszD#FDWrOtP|)rHKb%P;!C>PG&XnUd2opjvVqv z#4}H!4n2w6EETTUNtMn458403unrwo_#$A)@xbK4B01h)<*dC ze)whfLQ|yrj6m;ttDk@exXi8)K%uo59z)zJ%!MQ9DP{4fH`zzX^_|p|s8L|y>|{BJ z-qrewOpy~{obPrbuR59wqRxa#EHS`33~q#p8_21JQK3oT(YPds@Mk>|5C70+65-~dte_w!ncibDEH@r%3?%=GGE}*%5*4<8TIx-=g*2cNjBZ)w zOB$*qLhHoNW(-QLY!@W!=E~PIYAUZ6NyX0q>_d{)Egj};tezY2hY};tz3Jvt=GjmN z8>8}rXmrWQ*U7h5QmMP%u6mCIBz(5oj%%$u95%jH@ZXtVm;BD4=;a3RV8ch;u1yMX-R5$5|>lVfM9bAH?Q0o#M#XO zp$_(at-=ivbE>!ZK+EC$Oq7gJhcZDE!@=;s`VoVZ26L9_dT!0R(s!CRJqh; zWu?QNeC~z=p6tw34&w?aO2_c?s;1W3{MC$+b$fhD<(2(+qP1Rbl%&o_q660?7J42H zL}UPNiQ*Eub(~44c8{iGG3R%JM^BTVX;#2?+<})R(1ub0B$(tFmbVQ>QU0xoY}x>d ztH<-KD0{Z9Toj&|10>5QTtDl9wyhCGj5vAt!QVMsKv!CLm7^SauXVF5!nuVEYUQQh zY+K*(i+qwf0#TT^u>BFXC!bu(qZ^LleVQfwJWTp)Xayb=v%e;+FCCzI9SRb!+T+>p z%mNw_2fzi@N^wbD)1jZJuHSR`|2`*Fk33(?|NLz| zkKms{H*g_pNxXqjUeivd&$!=JDg42R9(a(~slN)I`PzArm_X5s0wE(Sfsz9)HL50l zKrd*AsBSIxb8injYaLSdQT_T|br0G9jZv=`g%}Q&U6VqKlVFwrj^Oe&7@xUW@wXvK zNeK&+U;qSZG;U6(Ijq3*ok%{d7i`I~m(vq@1aVw~4s@8nSd{3Oe4g+hTQQ3g7BPbN zqqyr=@A<8)i94yIz8G@5UrCXW3ZYZNoN;l}llnG07U4!?tJh$#lQWHuC~dvVFQj~p32sx9&HJ!0Y0M$o455O;FTo}^IAxbY8BV(8^l3Lmxd=)=WL`ce>NeAAz95)3osCP z3n>D*Kse8!ow*`^-l~=)#!Z#vO}ACg$I^4lP*iaOsjQSw*pL)&#MC}^cXBgL->PPB z4Hvs=U)t8VcYT|DZo^``%(~DJglr+gh(rXD2u{NAEn|4Q%MbmC`zM(^w71Zsl}~}h zPdh7B)8&Hc4GMcP9PJj}>Bzz|uGU%-=Z~!nxo3{9{3>P&l59jA7%)5|6`Na> z#Fer!qQ8B=I*J?-H7b#iBo1(wBy!2ey_d`&C5zbb1(8H_iQH%=bcqP|0Kx0&8rQ6! z#h0HOlHg7A9h{|KXR*(W5ursGesdumJVs}WB{)w!218eQr^*Gtt?bKlaic2)F98Gz z*a=5PK|JI%_()7D^?(W>DAJ@n8 z{l+b^LQ$86kF3WT73Sjq%uT-*C)^h^1PGUsz(i6&u#K$*w^TjJ*1@w%ms>HB%Pf^C z=!~@~;DUt!M4tRZb9@(+tv$9PJz45Oc?h$CI)WE{fH{{@KDv1Tg>kfr7ac z!Il6%LSgQ_g=<*NRrSEK9Z=~ry6FL^)Myj23p%&NnXC;W`Y=caKv#l{M3RxhAl{^t zcNd7fQGpi=-d4L@{S>Sy{7_ohO#aXh0Exmt(O98U#>HZc$O!;Y8N-Fda47*`N<;t+ z0}WuPSwG-Dc4u%qV1)Zzua;EI{z{EJxO&S{X7%DJNg7vK5l2~cO+*)93$3b1;<8A| zmvkXbdC_j%&3SW?E0#dw)y3X+Ac4DyxdkNQB~~Q%-zX2I(R#kbOkX zyhnQopbaG>VjGI9x%FbB}tuDJ`B=ZoL0UL^`jbAj>o#7Ct9QN&L&SOF!bK*n1E zbuJx~3~&a9TbL+B0{}}IFlpiy1tP472>cTWEEVD8tDyM%+=k4Q*Oee=OoKr7ajYem zXkYH3vchW9s*w0U!i-f*<54jT7TU;UCn*H-*@@J0akOwEF%T)%Y7dfI@f!9ct3oJ1 zTDS-+>41UhGRO0oQ5S>7l!i`lq&dX*-6l-12{z(WYK=qT#6|<(B`$G1Q#1)Hw!skG zD6LLr@WsRQ3`@%-ORrnb#6+Iht~ecMebVhW*%YvgMpXeM{smRjt`7uRX!!)UZGd=8^(a;4NV8H(qy*aY>UTXo%%1B?4Hx z&8IM&6F!mySmGl>*(}~n;xdKUaGt@927tV58f3CX42eRRV{Fkq2N5rB!`t7TP^u)5#wW`2TSd?oQNfHn6*v}zGTQhhAV5ajR*RXw! zSCh!J#+a5zaT&hRTW2#pe z7fvznE-(a+Rv_Y}SxGGC_yy!N{wx6a@TB=j%yYge$m^i0Xz=B?@9vA&oW~NbI`1|J zitEn_Y^^9s0Pqo|#N<8rtiOU0zyWH!Fb5gQMLWT@;ZLD~A6(}e| z$b=|q%lwLG3Y8XR>=OCpxW(B-G@2}?)C}TgJpX+~xa#Gb1#2;N$ompf^s5_}&AoB`?oZbVbBN>jBpLwG&g2JTJ*V_c7qigw? zy!#A+DGYCt>S>=Z0(g=@JV2;1Qcac!Yy^O4L?Df*VZZ=#V@wt*K}%P~^*P)b0MKhy z$nrR1ACn>S?LH_)nb1B{<_s{4!~V45;-Qhs-)iiaGNFb%O#06w9800-((lSNnANr1KlEMEp%^l#O@ zHDXCYHP{4G6~X95mRd`B#PN}JquR?>Bfcn<4%iLKRknYx$4`{E%lT;WJ^ZF44bqk# z)Uj37VYfT}yLoqR|H1j65;u&u5i2_Fe4>b+WZCj=Ak|?f2Ej;?d z%XQ9j5ibk_GQ<#t_EOFRKny2tWg-xY@!uU6O1U@8%^#pceC<6YWW;epNxv?SVoF-K zis@pZ?pRS&Nu&ut6ney6$^{x4UnyaVuos6oQbIffVTk<_;0JTam~h5?@9_R~i>p(I z$b)v^>&p}6cKUSwmWZW*XRw7RfhoEH$p1{dQukF9i4nvDz~6{IrQrL2Z)v_N=BUSY zlU8gdm-CdRdAC4(-k&4?i_pevoqrsKgoYr4v=Xj$eLFFD>zpbptn1DqfH(f64mXxp zZV(lZd3c9`f|3M~SO}hY>Rj*XpTs{4pHDJBAq3 z0Vkf)4(_QowewRt7XbtUcGwaFatD|V%%v!Ji?qDFJehhdiguB3$AH@T1ap``T98N( z5){B_m3kq9&Jarx&ZGiFi>OFEhNsa@MDFJIU+>K)HCGau+%(LYUs(`M=5}+QNCqa> ztB#LGdXW_dHto4rh!G?Jxc32kN?<()3v03w^wshiVa~wzb9{syu{RheSYL5oYf92$ zLX<4)^H|O;yyBGVu-G8)fsxL^FKy+)3v-PSD3^}V{KtHpji(i)cp+O$t6@o%<{%Ur9ph$jYxHp zLF@tPX=ob-D{hOFD2)#LEWDx5Jj}#?bj9K=@M4x!Buba_KCGt3)s(EwAWk^-4g17T@O_aJ0u7G>hJ`H7$dTo!eU5v&6X5_} z<)+EXJ{?@wZKZb3Lq$A=pE?-qJ~~X#fFHCCJ;JmDAL7% zprDjcL=Z;<2+|b9hUGg3Y={jJ8AZ*!`8Qrx)*@@=x0L5R=X3VnXY{N|#rd1@!?ntV zaoei@?)ts*{y~L>_SQrii)a$(9oiW+lqb(n3F~}K8ZH_kTDQ)1##-gbZ_a5QCCEDE zm^xid&ZEbUWlklenpW{*TK(~4$JfJBy3PfpuaS*oDY_dA4%?J)_kfU;9}-&6=H^Su zsn`hw{M%Uyvc`Tkp@V~2(h6{62Vj8DHdLw$N+@AWz-R-{puQDnM{zzzR&+&#qf=6Z zAkL7)+ls4m7vai0(;yj)ppp+`nklbv>eh2W5koM?g3U(rJZ_j^rC%9V5Am6q^15RP zWO_NxkzklSrXxkGo*BZK^QqDYqey0F;iXOfAnvk<8n`USk!>e-0QBA0f zB zBA=tGE)as;F^1gVXpOXme3Qq=bqh__HaF+P7sP3N4pzSpm?OB7=0OU(L0GVEoH7(* zT1RwvjyAM;#UZGTdFT_Z6C4TjatRyeO!P(J4I3)oOPd7UXpuIhkT_XHK}tjBv6>m7 zyLnJ@6wdIvz!7JX7UY<3QYm8Po2SkVj_W(RFJ#IlvEoekyrq4ZEcN%Tn!L^*+{1`m z?~3=aMg@K&-_Dy)?yS`g{MZ?#yJMTx5w!2+pMR&L!btIN?|dNNnk}pHNnqs-z8lTNSl&x< zr56vDM(4?AkykBzhnS;uJ4RNE*{j4cVkSKjz>H zigZYyI8&ic#Kk2D50a3Ola5qQ`p!sLCeIN?5oE)N2z+u7!i5VsG_C_)b9U(ZWj}UUOg2tZNXRpeil!15EpgU8e5O*SkCzqc(k{I+>!`BYmu(i~Ep=DuAW<5i z(WH8e=G>s&XqQ~+;F+^+4;3bt=|w-uC^hX&RRgItx^Xo}?VF+MbcSjjP62Cz!)VX8c#*s+Jt%|0ywXDmlp z_l{|t6`K%7;+*uRf~L+av@SnHF_{kdzZzJ!*AXAm~FwBykj2ix1sK*sqg9cfwc8I zleJq=YRASWcUJoswa|u1Q)&F@HbVlr^{w@`J$E12&-rMlG5lSZlkvr@thON@aKFkI z=gk8!6cMOLjY20IfJ*@ggt@*5sZb#dwjDn-0V(#TWaG+;9fDc=4tzfZ5^Ux}Ra4B- zYNIfY$And=8aSdDY5T1Np#6k6>@FVHlsmtnAFoNG2wMLt-vAN%9-%7vN}8d-O>Pg{ zzoslmM#RUbdqWs=f!(IJr}6I1gBy+tvkbnor4TBF)q24Zl$_Q6*uC7bBY(bEw!CUO zZ%Eb$X+ip*VMLRNjlu)0@HIcMG#63mv#4N$-b20#}(kE_;nMofroGbHJe@Fnk z9TpvkNhzoW4N%HM2+AJhaR4j=!0tj21H>u@T?Y+_Oi1CGlcC>d2x}GvrG3{M-l>BR z6AdZqiq1#70FOG4e?wDv=+nD}I=&LPp@p zN0LyD%Di2us&^q%vt8)7HJwtT&Bt7?f*}WqIfg9Yfwy0#%l69Ge^&V2JKqh;r=z%X z50Tb~eAjaJxwU_B>K0jl+@hn_&U87yLYLBLAT63ex&dIQq`=9~x&)P%O|kbxy@cMs zDh|7u(eH#N)AMw)$cU3AgIPv2-G9t^%U$g5jzRf-to<5u%$F#3J%sg}hV@0DbaQa} z&R`DiMZuC(i4ZtF=QNzClN!YvTObL>@JcO^LaDK)K{~I1Q4g{%GSRLGq`*84qYySo z7op`_+2}7<9RsU)sDeH75bnpBrlX6-->447J1Wh-IucKaH9u~Y(wh+~q_D>LvPC%C zJ3{FS6wW?hDwQuq;7OJ9Q3d=iE?=v;UX9}YNuL@!r>|z2EO?tssvY#^-6b#WW2`J` z7v+EX{q9SS&exc6GM}^TyA0=pYB5>QHQY%W7UZapNzF#&uF<3$9$3fb|IM`pjO9qV zevwEqFgC20ED9L#C2wjQFd7RgiLUAkL0v>=B08f8JLQ-g8U&Y`N}>qZI8)ZW9zG;7 zPt}Ut>OAusl5$}-Y%Bvxvrp9_C|^E62c#Er(C(tsy=;_?L}WJ@{qyEhAL^bT2)gxE5}4TX>{ z>+VD}O5gA&dL2IC4Nu0xczQ#9`D!F-t+8@_-?nhx ziKTbuGxYLGfAU#*GrbGju!ZDJ!+v%1q&TJ}GM315xKkdf;j@T|k|7sSaYa-q8}`d* zG+DX!?`o3ji-6|LFnvJR=+b6KKCFa*nZEfc4GX6Cq;*9(8Vk6G%iFs|4~dQYh{&Qo z>%p@Y6L(;yK@TcO0KA2b*ZGh&>sC5k+AEaSKp5Xz>?WKh)k;BEmW^F{wd3eZC9@T{$l{`z}e^*jDsoM)`o)?WDG0f+j)w<|nlPi1Mc6rAY zalWj{Cfu8iU16Bv&TOrbH+wokx+?QE#;7wvxSTx0Fh+mN!G25&&YDfOI?(n~7ic14+O!jR58<_K_AFL|7n} zr7v0csm+i|MnKdVo*^(2=EIhe%e4;pQx)B%tVWD?GJd{?Ho(+028c?{29D zM)8<>2|0DrMSZ36Z(S8b`j_3@!?gSV;wD59PuJ$G~> zMF8mExzC^ZF83%r59gu7TK)eET!xg)_s5(+zzM{y&++gh3ZN6;E# z#)KSc^bTL#=xS(%aMPQjcV%o;2_IiB#EcpGzA3}jt_0Y#hVJ=p`*}F>zk2N#hZu{w zs^3aa6wIS{iO9VBrk!+V@qy<+huLnP>ic*TO)CN7PL2fvs4C>@dFyoravFl&7fss7 zB-_8of zlhu>=#QwQ69^MuR4iW7(b%WUYxN>2j4fFA7q13{v)Z4N>wX;~~i)yV7k>u2EKL@pR z*FNc6N1y79dKKt>npSQZGQ2D0#4|ei%>&YvyZ%ovld2;zT?%TJs1+odRIP)})4`V2 zcf)~JseoTEvgOBKs}G6b>>8{loKO*I4@BcuB*?H73_0Us;v3q|jC@#hw+=8Ko55A` zH{r)w?lf? zQLjo5>%5AJJ$g8}BKlFu3BH3rcsPc9Huac|phsSLud%3)-Cy2Nf$RS2-w$N$o)Io+JKZS@I)^|R`W#H;E$$q z+gLbj;It1D)he01OGfShlp=%)fboJw0eBJg>IuPVO2b>g^ZQ*Y`;WU(fDtq&jY@Nr?0=9cE=8_U@{GOYaU*3D< zen9TOf%fO>y{kKy1#L(6RFQx0tGIB{B0rK`l2(<u1uT)8*cCmLnCkxlb_?VPmymoni7(2h0|w&+z{ZOe?@A@TWKa(0>OTJV9%y? zM+CItPOmHjn73jLU_#=@UAfN`egvs}uig46Yqn%Ugqo%HtMH?HzJ=QGUTNP%&YJccJ?UCN z`gJc(jU`>j!nF@W6hjmu+?v{~=OP5#`+%OGkoOzlvlBiA07JT+9GHi^nKj#lIo<%M z0u*V7*RNgNpSKvy^oRHcFy9$x=ZfPki=BTp$*MxBhj2HRKHR(5czI3MK z;}Sy9FF*k(+Dr#|Yhi(fA@TdZt4WHmNb}HYyc-+s%`Dm)H1+TUa_}KjZD`+@PJ(ht zY4ihl*WJJpK4vAf!)*^v;TVdER(1>X9r3752e^)Ts8pd^bENT+=ZDUIB5`VS1CNrT z*q8jD^l^R%)T>uk)ua{=G+%gLk?o*XRn?5&LrP^@325=d&j%O`AoDcPvvCSxPiQd= zZj-|&n)8%|t6IX8+W^HFkuv3<^JMZj(ZGwjI6s5$rX`ZXlxYEg1is{sb2~ElIGTOZ zzwCSK8PHn{peM+%cz7#uNH5}wUFDgugDaaX5hVk|tUWB;uD!N&QXNwml>p#U5!}sv zL9UhDzeG}To6l}$VJqv^62htB{dZbQ;xcWAEg$FP{~kMYBU<$l3EXdjE_`~-CgA*U zG`es(BMkj1o^-KV^(=?HfG0Qq0@h`wyhJqrXu8|I`h(^5m>G2sUo!AF`eVgMz7}>8X>c$ zcXebN7EW1F3|JjoIuA^{9=P)ppP zLxr+@Lgt>#-+7nls;29-HFrzSE9d7$|16&0*?;z2^tqk6rRgybx<=Can*TR(B$q?R zPO5#p!|2*1MFetg|Dk!Y0Lur~&y65Qk^R`ZyQ&Q=3=Pqo331)b6;oiV5*cXAh zBapWU5Ph|k0x2EWi~ zovs-WCBCmyA<8^sm8o5evgTvb*rI5p}d8t3=yW);m|KfpH!`< zbGI*YPJGJPMg8HZmRd>6d@)z5<(HMd)ymK0f1dsQC)?)e!_NY8`|paQ&;RqR?KxDX zlV3&ayrn*aLUM~JFh*E%{u*%m@!y^kTg!s$kX%T*K?`iaWy>2X*tK-shBJvOBqb_a z*C9uWB8yN4flM5lVD5|sIh=fqf=VTcSnmK~^qr|BohWCtqMmLMK&y8g#>uABSq;vR zqKq6f$L}CGB(LvIrOX2X<9P&i){Jm)-d#@5u}J^b{oy-jwCyv1uT1V3fjrh4)~#x` z+dgq^W$^ALxi7c=&iJ+d2X7+~4RY~#N&nGle|&xAS@#AXwVue^dA5p%Q%?nx!*w$1 zA>Q8@Q`Hum2R=USem^zDZ;9I(Uiof(I?rJ;gRIsme%OEX+rGc5*ODVA>y)EMlPe{~ z9}AQGbeS9!tfY_lLEKC!iREgJ$v|=C2};;d0m1|}MBa|6LLv*ZK`GCK&L{_NCLzL< zNa3>~1N{^sPCtUhfzX!AOq3c^pox-W3Sbo0l*mDWzD!4)o}I`MV<=!j8Ai53Hp(^@ zsdv+HXFDjkMd8zy<;zfM9)| zqy^&f**M)+1X9H1@q`$eN>w%xmPd2MZsUICLQ+NiY(;}sW~O4eyPxnR3Xw2lw4L7t zN7Ako2*TMB2T^KNzY+*P)5ip5%lsgme4a29LMn-aieyt>)HW3^Pgjw|B@UuJ^f?Yf z@!LMGyf%|4zUCUjLIos`LEJrJ=j60^f zb|<{ertjQi|JX1lWoO(}Z0jk*ceTeydl~0X%07$dU(l?sZs@VPPHC!nbFnHVbyHx? zo?2bLc-Nr~uwV&5S2Be-e689LV3>?JdQk*`0t&M88-i5IQieKw1mPpfYWfn}pKncFSYq$=fT< zcAxpfvUu{*VB$!dQFjf`BRniFb?swO>=9_M<%J&kq)YXg^!2I4($uwW56a)>^z6GZ z9#`|s^quWer0*P-3gFV(!kQ%lha_YZQD_W8SYhfcgH2=(O8XK)Y@MH&v)xFDOE)26 z5gzbfgAI}s0O_6)HYNxFr4!iKGbML>8xdHxLx|mX)fR8ZH&CQ-AXkx1tuxcnS16Q7 z1+L4RI=}`ZA^LEc(nX2`uGcA4VmSn5GXN>KA8h&4EUuc84tCo*NG#d__YfnoV`({- z3k`DD=UmhZJ;K(+Kin*v#*e4HkFNO`;69cjXI?^gty|)fzr8oLE>(K=n-Xi^*l%%S zZBKZd>=C2co{J|3z6JtcUmJaQ&IKOouv?V)+V5bIq^g0^<}(Ut0uzvN-v*chtqKv1 zIN#-PsCtI!J24$v9?w`n8p0;!m*|BDpt zaernypyuK0``(Afx83^^a78CP>9=ajy|g$|3jsI+Bbgvk2t1+%gPysW$^sTzHM9m- z+sxh;CK=ryhE(m3$0FcTK# za+dWwO|!`HI?$aWHX)Ka8Z(ex7vU-Wf`*%=S^cWB7k36!WbSVYU(njw@RdAi*S4*y zabMzFx0;hFuBBcN0{MuGl|!s+z+1*r9Pe3=jn&n&ZKgZA#f(eKa+)1Q@CJPr8lb1RNJH0lE>U4MEHO*L56Z9wwn&F&qJc?8xvPq3 zdrJ^o#^+V&^LKBl5-L=(Zxg6!RQ~{5rd+{Jwvvs~Bo0bt%w)-8JFw0PpNLaK`WsG( zW3f&Eh)qCHk=|#{tmk3Qx~aV|MH$j0yQ4g1e$Kug>goUMckaK>^z9REE|AXutU7r3 za`l(lZ3E}$&HpH6TW-y-X#TACFzqPA==%g62#SsE78+h|xp)?HH3q~x3#{29p&x)vh-|lSjU75>J_((bQ)u$ zsEd>cztpag*G`ik-%hTTZ|=4z{W$ei_R!yhZmL$>-(KJ36>c!_>r7MXMsf3ho5TIy z#TY$VC0mQ}mb4s)N3F{1Ku}W>*dUEu+IRK}Vl#LW;u(MEGVy8>&8#JI{xgLw9fSoz zED_Y;ez(m$#WxMxzHUiViHSA{vsoBw+TfUDb(4K~$Nz+X zUDJ7Qrb-`H>d$SgiVpCMs~K$atsi9gx+FHA^nP2C2YrbZ-w%AKzZBp!Ad{$8_s@j8 z*Mh|*8ZXVOZSvCuv&tApMP29uv0pK|&CTvK&ry0yd>GUyw7BkOI>psL-{a{MD zFLSzU9!qJm+tk0Dq;;F>krNyW@lit3O=Z<1#d62*9DT}&$W>+JKitAqVvNK_SiXu4 zdP`bS3ApA!IJI#@M<=67|5zC%uNn zxXr~shNj{mAgE;fo3jW!huC6{YG^8Z?i)STKjPqhQuJDEazK8CJG+XsKl=_z%yZiX zZ5UckQ4h7eqN7%_F%WfWgPx7mrX!hN3`!}SK2*$UYt*v1<4Mm;FK`7YB51P>!EzZg zrE20i4(cMC4U(JF4D9CzffvCr(ZO~}5~PzwWH9333=uQsr5hExa{#?g_<$bZ^-!Td z2l$`mUT+pe;fLY;bQg6%WdZmm7u-aLNCH?L*gHnF!vT;B046D^XfLB&XTlx*Vo0Si zQ!@ldDy;cH4B4jbD+FauCCHsg+mgvmQ)-UbH^ep=4#21FUw9S!GLSxMrFuqQrb1rL zCODJ%oltTuZskG2@sjxYV5@#`YsovZ$zqE6kAwZ8>C+EAo8keC0HRR|qX>BoM@;+TaDJAA{xwd^o-(?O1n>ar*C>*z6|(GNd%4*nH}RfOVc>ai^h9i@Q;N+}$^F1#Xh=c7Ln5lhHj^ z;}E#@Qe=VXtXl7U>6`Bahhs+URF67`vaZI$ixp)aq4LU!1R9edVa}dd$V>>$9)!$A zkj@P3Lj~^oLpuPp4)v@e4|Nmvfrv>a<)AcVY#>5hp8yAjK^bC_#aAb3B4{w{){I|4Zcpe$LivjF_;mYTSs>WQ`60%nJYYu+T2 zFiwRfQZ3sA!rPG8yfV2z%xaTBMuH(jaWVhYpxo6Kw!wofzp1Kbk0Ls8hRSI*M`)bX z&YH4DO2vZO=uE*sF12?OYtOzbecqJvswrq1r^ZMq69)2$ttr^_LXF)#l;u5IP4?7y|zLX@e3RaxVk$ zT}Rv-L2?wNKeH!DDSJ2$x|D;`VL?P87z9%hKh(xNR6}gTlTn^_3cQuglNqV}66>;Rcsz%-E2}d3UZ}Fb<5^wyEUYoMBs)`$~DlU;1(A(2{ecnuamPsd%-EG|DuO zA@FbViB=DMu(QH#*BM>r-TvB`B*Mdaqw9TT+z@#aHe?}!q*6MbSDmBIK&eZRE@EcN zLs1bFO$4F&U@-9%+4+P;yjbgfi z02PH$nvpkw2H*rR*{_bwO#M?S(GH>_?ICM>{w8KNyiBYp%bu`c`# zly@BR@#9i7btEP@hMgb)@^3hPD`sQ@NL=Sq}wlXN{9I0*4G+My%sgI+QSbQOQ% z;}|F_E`VwSA&Q?C7J*1CRN-0p%bjRCPg&Cs<<1J1`UV~f^_LlOJ){pOKh$@@!*_%i zO@)2ezms&|xcToe4EfMFE#0(lAwO-f@!oZIo&!Ddiosf34Yj+mp(SpDX4OWcq&e39 zF}XI-8UOcJb>?`lZ)wmcPfDFUDkvM`{L;SfSSKZd%$RlFPa*QyImOlvQ{hE#GD^D@ zwB@y!unw-q64a?+IC8!jvVBw^wkz5}nzvb>2l5xLJKX`Unj9|aK5Qrgnpbq>Qy@h) zfE9wI6dzAvs5%>#P;?I>q|1l5je=GP%1sConLKUb$YVpd@}IfBT?Fw2b;lGD9u)*D zk3-Wu!q<~v#V)5NA;B&oYXZtwN14n(`n4S<%g})&!kNN8{TG9br82DKkPyLE zRLxNq!7GL9OA5K0sq=Ku^AFDUNsKchkPNQOD?A}UI`oQ@!nH0A0$lZbdEpWUCrKDxz`}SF$^j=smfqwKJhW` z75u!ZJKp+v;Hvd-K#9)uX)mjzD=E$XwMSiRcW$DT7TSOS zU<)=BW-z(`*}2q$j*WX~vl+)PRRFuhGce5$plkL)Kz-BmiQaN^G|%b$x(398Y8c6m zWm;B21H8vYdQ2U;6deWR@b81h35tT7uVN$#D6W362aAe%b>hIkHx%E4?u7*BLXAi2 z@I7SGz-$5_$)r6b9ocF4KgGCzHPUMGZU(8hZTD(SruPQbT;;0P9FVWkbZPsxH}*b{ zbB`$F6&%0nbZj{Pn7i_>Dj)Japv=<1s!ryajOnww3`zTjs{5GmpLEfS{;W2ip&h~L zg@w=VbzYwQc$T7#z6CvFs zDlaz~*$Dr=?n@ZOhPotf2N zTlUsQz%u*!l$x~9S2KQ3`!2o9crEv9Z(3GVTl@T-{RiF7=op>Rk>M9_*fL_dxhnIT zyqe}s3R&zS8O;X8c3l4M(L<(+-e zT=}u-LZCy<#)0zBLI6 zUI~UaxP7$P^P&{rA^prml_^hi7-&w178)L?MPAYnNQ%F!IeWy?59NWt)MfJx{Bwwq zrig>r-nnjB{_MWTo_8G3)<9j4ojctAC9}AiySMj&;v#hwyk8|9~trI=@4vD!hfvpYiW;{=&oc9#eIohsq_l&s0eOp3vM|Dc~wbL za0k1@ga>W=JB~cl==^+d)0y=f@5$70~S6?A) z=l2c4g)Wj}F+kt}o=C7;?Q>N@*Xjr~B2=NL5XOiGPae}W0zW4m_-uZeaEC{e^(E7Y zb^B%5?(3xETMfe|^JDSE+10O;m$seXavY6woxHPcw>?)5zf>BxA8|?ijkWh~o~dJ= z(*7iGnqZ+emNDJ%a|h`z%PsM~=}O_+$MeGl$`?K<#Yu2x{7^0WFKdFDU;I#=eAeTK zRnr$|3drbm%VuiA&@K`p970R0n1%=vXpcvvQBnjx^8hOwA3aiZ)$jQlfQQ7epZ=-N zOeWZ2QmL|+lgVTQCsDOj2O*PlOG>Ojy3caTyM=crU};P)UIi;nT{DI_c?$BTlw!6c z7mGnDV2OSJn6D_cDaEFflO>RGEt+cnI*)>3gjtAyL#R_a&UP?vB|3~3J6vn<*Pyj4 zfu#KH&9{H2e;-?Y|EMGWcmvt=;co6s6}r!6c^5+w8~~{vcYx zhUx&m%KO2=x^3az%ZiDiUysp|OEDrLt!=@N_@@1wtwwoI1s+wi! z)r8BBs#MLIkCLx0OqeK5D0sDAyD9x)>~;uS$8`L0(0}rhM8Mq7F(nOOix_X_1CV;^R3~4=alO{1iEK7c2*bhWvzFMPb1=KryKq#OT}e zB~na#Vm+!R(k3TQr>shc9LsgT7>|_voF_&1sK-_MZqEbT@jq!tk}msPooV`|t2WIq zFkhzx{qC&`Htg_E&%c@N8a~s=4LNnuq1-ZPN9YbIuIpgD+x3)N5#Nu+IbkXcU0?8X zpn{g>qQT28kp;HWuH=93PN2tUMh>7gZ>ixAwF4h4cl*+EKe8ixmab*10H-5ax25fE z*r?=J!2FG5R5u&+#sXX&|7J7J6DBE=du`JZj*k+CRm6sq(imI=U$zJ%yQ?`86?3|t zgVNsigN4!AMAXH~o%m6IU99D;_O_B#qBUB1>2CNS3E$Mde&Y9|=jq!!I&&z(!jHMy z-Hz@ZYAf;}jv9B*gkt?TS)hx(oa!pqWiOxhdb6c!4(kP#3ljU@{aIBN+-d2az zJDBq!B(R{fuhqtv^4fFawei1aySWC3D02~bVroUN-CLl354hb=)S&7<3N#-YT*#3} zp}faEF*V-6EL8PuFVp*^KNBM@;K*dO1D~P>caB05|FsCvvjIUz0E7@W>P8@0dY52J zREh|rUO6a_%rwiHW?>uwN8;)FqIk<_vc$nnJpHIID&tb%E}b%uj}=?J7vw^K+vAtt zMi=KJeqrKfT@NYc61iVQKSb)MlxtjxLaR>W9(fKiJ7PgDDL+1#FoAWjPV0@R)8`f_ zN?#+sbEJ$=O?aE-LnP)j^?D@tOVX2__g2pKly$nnq=mor53yVH<=xHGIEttI*+!B6 zGz^{z_CBN%+3zhbpzwHWKM3XuckA1*vED*R!mQv~JIO?d2w-cIQJRaFVzze zYx5xf_fHNy#llWfMu~QtG!d#E_Q8zX7V-Tvo#V0SWb!06w92D0q|E`H^w`1l^?6|J zpxs>s-d`FkRy7ADyLlBKXQ*%;{#wm49AAHb;_WxyMM|@w?6Vy&d1oJV_w#ocn~tce*f=3HgZ7r+^AE%P3!VO6a&OM?G|3kk zb2iEB;I7OQTK!|3wmoX3%wGOne)OU&EblBfEE+vvVm!>6*y`vU zqPD5K2zI|>dCc8MwJ*5MuCXwpCGiRB_6VBmvUB&2Ai`nYxTa)V@gz@{={v0Q*v)>E z4DqP`sAWC?69pe}Apn%P{*8}z7h>LC1yyVLk`OGARs^7&j%<>mqjT{MFsn zUAm0U+!QH_Y2i$6g;F&??d+s>jE=tA@~JNwg`n=9K~-1x1BT&03Y`Sp_UcNnC&fS3 z%e&Yk_bGxXLV>^YzRwiQiR_dQDGy(&Dq%4H>rV+4M^+eIPDbfcrgqz-)I4&tO@&Tu z4P`$zUY~<86|u3hL?}kcCaEtA2}~46@gx&_hlCL)Z%Maz@paPk6W?L%qTXc$?wELP zJ-tmnz*C&vIQb+0+aq}OYJiHD-u4j>Z~j2(_Na|PwEH`1>#c|re-xfe zIkm^w!F{^}yjxkj!^PA*^iFQT}?2*pB)yuWBVrP$sB?*t9$?++yI>E|KYANCzOs6aAIyVdnv!z zQqL^2$b{hpr_h)5T6q{*%-V8~?V!I~kQtv)^ZfZf#D!mfrPo7$-;R*a+k&l1qrWTs z-LdlA`;SgrLf^U2^sL7x9s9og%~>ADKg+)?o;a?M(S3aTreY7v*U*KN`WabsW(BnB zV@i2fln?FsWN~4Bg@nd(dc&B!UN7dmB4x3aM}_Ky-0m;^bcE|ShU*4DXh{r)kR z578U`JC^UKV)Jm|!AZ z^6)|7BUHt$p~BmJLfmGyUv$3&XSp*-(%YfVuAd(NxZNe<^iV>TEH3Z|uz>FAerT>;X|E#4a8h3l()_Le+ zqZ%*ae)sk;V{AB2I!t~0!5W!)skKc5SNpsF!^&s;!pep>-MD{N`hBice)Wn%PQTHO z732Ib^!%u_`p5)4grz2KQs{Hk)Z&1=UnV~eaH7(rqfq`c1;gnB)-1zI8K~AW81ekv!FK4i{serALNX#J#oqg;I zeO_o33|NlnV169qG~$N+l}NtHCEI^9VnCB-UCb4U}aAq!f&O3I1CZ=L3)VZ-RC|5!2~(r!uNNcjhd0 zfcW!=)6N6NU!N&wYuF``yKOe((BoTwY<8}p=eHLV8`kqqQtGey*Pw40(4W(jt7^ha zx;L+G{f}23Pwf$(iZJR+y0WLV@Kz@1b!Dnu(dkE+W{BO$ErDJDY#GG{!!rtf8VmO; z6z-=hoQdff!WMRn;p+s)^x2wmbn&|mCwM|wZrM_L?7Pf@AJluGE#>Dm8*pR~C{VcHmM{fDA(_dy> zquu*Qbue1#9Cu^Wb1~!b6pZ0Ge)h&iy<vSE4co3hujIkcEn?Lv8?Os41)f8c5y|j zN-&-Jt=Fyyam!$&XSK_e46u9Xvg^H-0Ir&d`Bf|Tby1y2zKxqV@9_>a&F+?6Y1*{e znA5kpaPEwzE&CXat?-(8b6wD}$8+L$S);rM@6gQMBJfBeSkhV`^Xc@Bv@6$0g__Rb z81JgyG*A6M9Y8dz5!C$R*NlXA%vik9GY_@w$=Gv~lk>`kQL2MqI+qZmSEt7;*nJ zTe7*>DX<@h3!@XwkLMU==j@5Lbw|tfVX3M875{mfc{aZV4J* zEEt-p?ChiZlwB13c&JC#_1B#1NxFabncZQJN2+M>>azSp1tnuxM#a6l$^Bj=7K$Zd zbQZ}(Be}Ji+;+X3c0!1ExRd=(gY+9-n`>*hJlxXi##$Qcny zwq8dssKnkU@&vPczaxhyH(H@})*A1ji`+7K*S1D<7w65uJ4!Y1PNFU!j zBts|uhjF=c`410Uc|wWLtJ}UbwolD-qU}h!gXR>jNDC+Ud*|HEoh|tfOadMW|I>Xz zpV*>JHGnZ(sH7g*>NP3s2SHNznmB(r#=t!Wrv(p0a&pV5owjr>Lm7b4zp~Z zypEl8(sz&Fx$EiGz}IK<4@K-cve)=Y_D1K{?uT!#H3m!p*Le^3it~-$JbU>48BbvC z{t2h@Lsk{*(n^t5U9TxmuD$fM*jf4R-B&sz@-Ht*VjvuMS4X_0C%xSEyWX}Q z7`;+!#6M!(G$H-nQb%^MrPlq%<(=xFV_xi2CxyrAPPHvZYTR!QD%Y}OPBK+)+<(zg zh`(R@urW<1hEuZjS54E*=_W~&;@gjJq=x>EynP_&lF`fKoT%?dywm5EQfaOxS{pnV z&$VW2hXQtMdA>l%Ichvk9J73@BIFg8^Ymcxt!J{!uA>$KCr#W_4PExB`o*(&}(DVlN%!ZYicZ}Uel>Dw~M_pBo8`0h|V-Woe ziFl{yDNc1(jtr@>f08uXJR=jP{CQ{LxAMgR8=-yTLG87d`wv?_z1aG7(tWjW%UZ+s z@0I($Ur1jaC|bSQ@_n>xrKjmjecMz^TkDmpS9^tn!ikBAhYuf4yq_BWe(%=W!r0f< zr>kEUf2^#1U;pyy>)Y4MFJH~SxW9Do+VbrOD?M-5`0u`-`sZ85hj$5Yz8oB0PHk8& zZu;2N|Ecftmw~g3O$8s$op@b-_(^``lVb<|_gC7dsGOzkdp>!EF2-zswa;s2=hnwQ zHjB3Q@6A0vsrY_Y+5JvF`J-OyXX0O9WQx9!ik38s?rL%_Ysb}V`1GnVXUR67lqerm zls^~~-)Ja4A}QW5RlaRYe(a2lhR|>L>vr1fT`@Gcq+wXDWBeE5oMdgE8f0CNL@hsV zd-^mp{m-92k_GLGCZ_-Ix3mBGmV4c5WT#77f1OOHw*2lMr!UXWraUR$_4hCG;JN3F zj?m5+?H4Z5j~(@T3XZS2aPz*svCG?FcW~$W+nqfH;xWg*E4is$!S&-$K3;J*<^Gwn zC~7*fBR*qh$=DP9;S{Oy6|Kyw zPf^ZCTmT0r0)32_1yR;g)E&E%$L3>i2CGiWTl3NuK#U}}SH5TYonBh!s$L`W&+^)t zB-hKmFAFmyU#4Qmdr^_ctu=^DNh_N2=5)_8G-WaMdu7UedTMCcd}_7J+v3*mp-GDY z;nT@811;9C&7D-nCr@@yIeJyNsEx;j3^@FpK668|TfHGACyXmET=jc%Hgs2F){z@_ z5Ac>ZnBVZ0_oliDjA>Jp4D|_c$k=kq@)dz9p3eI@NuT^(;%yMBgWMf>H+ALL3<|~XGm=ncZno!cRsTmR!T9Du@}xxTHT5m zE@VuZGUV)Ay4I&!9`m1hTi&-hl}S*@L>eXhd`K2k;H6>4had}UAFIP z|4fCoZgo_#jd32+tx0y76q6Ea3j^?m?Nccqx+bS32E!?y{R8>{f1P#P)M_EHfxxhw zN+Bq$3{TrXxqSg(d>p-Ce8cz7H*dRj?@v>M_gD`ImeZlHzFYmA;%&?SrO!KKWj&U1 z%4&xBpvZDx>9el8^pj-6_UoT9m&9B1G3oTW4cg=99d7((M?ZHc{eA4@6jiI^)m@u= zge&)i$M4eH8>EXEoptL|j2_{G?^g7_?rnCzH1@9Ax2m_Dk@+@NdS=UZukI_u?`-~ub0(umMqRx3N~C4u*T3U4I*y+`r2hFCM$oqN^X_TpZaeoQ%wtq1 z&fPwVmob>idU4O|Q*)5|XAQByF}iS44%Vk&39~5Fu^Op;{=)p^-E>d{?Pd@_Y8Y zp6B)2ANzB=cis1{`}$nh`#sy&x9h0!$HQ%^AD(TA9%%GKR3?YSr{}&p#Iy4P{tL>o zoRPke8l|IA`!U--U=VYzMF)gyk#G=Ej*|OyRNn=OL#nhc9Swn~I+B7dHo@+Q0Z0yY z+Rf21_rlV19StbM)qe47YkY;wnPU)Li>|B-_EtKoFLDM&BY18UuSds5_4U>t3?QST zZ=HNgt}$;4#M8VZbBIvapXFN3FG72gG6{70R(vzlxP?Cw>!V`kg)=X>1)zQugU z(d?GOFQrc00trjA?H7wWQfhqS?poaLX_UqwA{g`!<8I$BM|*}e?TVces_4sSaj$27 ztLnBmV&15AAwK3-l_XK#ylbFkdO1H#(q4aEEX%*m+gSxXeP^=Wy>a!N<=NMyEQ{Lk z3t{?^DsMJjcF$Su4AJdX>_iOM|LuJg;~+)#_!2}}n7nCn{J{}nX5iwYtKsO=;ls0# zddsFq7lDpQW#Lq|xy`*xr>7#-*J32>0HaH%1(BNHsk4q7V2o5P$DlmaJJhe3uRMWAY=@_~hfw9c)R&!;MHkLgd^^iKC$N3{ z6@84OlOH(ZYT5E=_Kt0D>^r0(cPd!a_Ta7ZS6llTN4YV!#8PF##>hH12N~z*tnxg@ zHKVAiAj_c<%g?`$^*VEW=(hmOXbH-mN;?{L*0I^Pne40_CJVa{R8H2)hKbPPyi zoS8_vWkp)1PI56RHAxyPQ`uL1|Ddm+_oyPHzWA_$XV)V>Do^EPZA0rjXHU<_CA?*4 zB~MnN$!Us8!omT&mZ}SJwa%)>$%8)Ja^x{ThRQhL`g7P8*t&Q6*>jTkp~@m;6f#kz z#C4zw-1Roj%UOAton=+4B~_;WC*VZ?fRem2%KB&j&8U!_t%ofgUFJ-$OUm9Bdv5>k zjJ>mJaJ}2{IL8H3%gkbkaF1m7EN#()!N5%8p*+rQr%?(kpM~~nx6)i-n|KMfY zFL8rYIqm8jrEb^e>E6>9OWsew%q@J79>X06=?9C&t@QK#2#5C{TWK6fUNI&eL#C-` zES<6i4x%0&y!GlmY0#?W(S^8;z-QO5W?Au%2}t#Cjuox{cYgbt^cU})I!a?URP#(Q zGOnhq=Q;MF8TE%S#!m@Pvn#Qi@7rb3ZyddNYTDrsct1Ft3Z~6hAK^K`~-#D zS+x@~Mj5B;Sgw~2E?+!WVx{_xGjQqGe3W~~l=|hZ#MoKsMa@@l)v1~Wb~6Ob8QM?v z6`I{#QQC!!k54i_gzTB1}TpL5|;aS$0p&NA3o=wGJENcN?IK8ti2?j z@a^5TjEOIbGd&ff+7e-y0||bwY5wL{pLk{evQ<4F?dDLu-ThqV?Jedi#f{1eIr5gv zxV*3=VU=fmN&R8cEo1+|SnIqfT>Y(OoQ&wa`sv`oF+jvD8rP7D1L-yVGqI$Pt08pa~WIY(b(!*433 zQd{$6CQ-wMfojqGaUGu(Iy_!Foau)GyB&0K!@mb1-}95E6;Jm+J|~Di^dBzc z8!js*Fe?&{c|VE%f(!n_KmUc2T;CeGJc#kTb7bi4`Pf?Y4_*c_AUGiFOtQq8<5ovA zOHi*Z4l*XAzu-{ow4;}Da<2u^-wM&s8`1aMPY|#iwd{GyGtB;B zHDUoAfhEdX)BmFsPEc9eewa$X`0Eqyx)zwP*hniL+LDMFiVRsR#C+zQUnO6xI(>05 z#x_9DUA4v2m63ea!s)%D(~yGQ!kyzz1HthUCon^yf0vMFA3LA5rot!D93k3#nXXWZ z#=$Y-t|;@mqV(uIofOKduoQ1|Smj;*%^_6HCSsO-8U8ciTozJS@oWt|?&)O87%ufr zJL-cF71<{>C`63ocRqNmn0V4Cxnxh#N5c_(#BVcmE*4(_4_NR&n*J7f#otML0$mvu zzX8hlOh&D9P+QbPe+q*yZ?^=;+(oT6I!C)-j4(L=4S#yQ)He2aL;XoKHZ*sFhaTah&2w{$HvJN>B0ZNguTG^@7{uM4LYV}mol~fi zd5)Uqp>+48jtK*5+ZbFL@@6Uerm(zrlAiMuHB*Sb_D=Lu?Bvp7o~7tB=5m?e_obkn8-T>iUUK;Ca<|kOncihF|D1WoWEzrb$rZ$+xJhL#SCHN+KZb zWZjwTs zbRKepQmYc1S5%()krh_gR`jK?db+UMBnMqr{%DnVb_Q49R*r77ZFr48yzh5_`JT9c zKekcq+Ui-}J=tGH4}YWB*l^Roh+dxNb0NYs@05emPGIx;2sU;EYSeiY1-lbasg&CG zzV@py?*mB6ELjxu?n|`R{Sv2t@=zO8^d|~t74QBr?ZI~{+MxtJCCS*4dgr-3W{Zvb zU0B(7$Gty`^(hFm0nk65iTuk!f8|yD6kU#8j?RDfdm%ikT3V{AUo_74QjD!LEHC>) z%d5XzZE){V&9$<|d#Ibd6al|%_u1U4eB|Y~p{j( zsOECylSZi?JgW71eY^Xv7o6}u52IK33ih2A)}4+qTHf{*WVfJ`E2`K8qb9e9QNQ@8 zCF=b*e_98YPyy4Z9WI!=y|$kvZ?DnPmZ|8X;qGM+#@8cZ8Q=C5@3hQuPp)_WRS4Rk zW<0F%c~7m}p&P6ypV90>e@{jKxl;svPdECDY7kI%U4Nprf~rvI_&`Oz!8Xr`c))D5 zzDkqkXxX$7QSk?%n~&b}F6?G$Ob-oN{+`X}b8DpPXW92^&i2mW(8?7^<&o;AJWM-C z@+N>BaZ>8!SpV~8sz3HRb|kYnCyy#02X#dyyHGxWdS|Kk`O~Ob3VMl(4)enBf%|i8 z_YF2^iSN9`!Gs;dEb&pF`KXmNbd%lfn6v1E$1Y3^yQkF;Y#;Q*EK@C9k}dpHf+Lh0 zbLH4OfW9~7_$f6|^JD45Sw&}1Cu7q0sU{`OiUeFwt*KMH0U&soJ|s$DRf*x>Ek zqFI#c^q-l!Tc`(hs9{jOm2pq$%)L2UaUXRX{ef4<2Mvo5V+(u~n^rY}NA`jwA3kqr z&aHkbK$xeG=uV?Fwos}g+z%l1eBnfsB)XD{?4d~wfzU(L(I)`1nk~g77^x|kd`aqZ znU)$3 z<}dx0o}XGTOf}k1|E`p35g-O>Qrm2)KCGnOi1Eh@isxHZAMvCbvytQYu)3hPj#AhE z{HyAjeLF;*xrs$@S8_gA;?bYT=+Eqd|Lk8vK?8KuROSW#C)z{>Fg;J3(7Q0va(rw( zeiDv<+4b>dfAaic^iEl z5i!7~Ea1_u@uOA3Pf2D$glVZUY{>`~+4I>&Ut&)BXKaf*a*x626Z~o)NV11F!R8?< z8W9yd!~ze|&{#s5AeR|?=X{x2-LjEw-jLU^o=rlsvNK<*8izb!79{o!*+o6c#W%2{1ABy0NON}q5 zDOYB(7^5&${;mO&r(@=`D-A2X+M&-CX6}uzzoa~-am_se7V)oiEuIbRJ6{ovF|1CMyG3_54@bNq-?Z=uB6{U39|G<$vitRSE8ED4tWAvT7Rx~mr|kURcW8~eR*89eSc+6R;RUjY#a1vyq+NX zqMFT#*@onLk5?5>PR(|ogGj7jZ#ywQu3&kb^w2g z$-VX7AS8@^y)Rcx;>#31B6hF3j$WK^JN3F1OJ>Jzx%SZ;PN%oOS+pOrd9~o=`$G?1 z>pcMwBvq|YGkOu7$*A6f`kN0Ts+ntl6hk(t3;h=~-EM^ZKDqRw(yr~P(bU7x;mqG2 zdd6jDS;#Bu&RNHN@ezv7MHrTypMH^!TeOPX1GV@>i%7$O752Set5#ZDy|sg z9PVkd|IeS1+HTw5`f6l*RafN@&g-1gA>eP8Ls5_P?c#j}?}%~-N)~mWzvB?1We+rp zWt;VGejAWYv{&g@de`Ir@Mg%xuQiV|miz4K8MPV3@A&KoU|=-uRu75*A@S7*no0JY~a!2 z-#i@KGGc*X;cvF6 z4||FZyyNcHtS1dtp;^i-rO>1&w@a;8m^Kl)I}cw}Tuw32S30ugr+2L@bC1PL&Pju4 zr2?kuK*}h8S=&6L@=v%Bk4J-GZKA z27~;@RJ|P&-3FDnOn*y;xi9lO+y}?8Q*)84Jeh+=wq4n8NmAjB_9 zsb5fmPxD2V{kWLsRx)FwOE>80x+1wx4mznkJzM%s ziJ}wfKU2wMr3u`mMeXrHp4SE3XT=w#BF=SO;LZwpNwM6oW`>6j6c!NbcH~ABmj1p5 z`Ou4ap+*gy?(1xa8Td(i@Edto z9+m{{P5YX!G>27euf4FQ*V94Rm8H~+T|gRb%jjtj8|UM%m+9(O<$8o<%FKL(qSm$Y zNE~33gdZ7o>rx1~>O=eK~y_aM@g=WZ6LDv|eFqt{zHwVr3qo*CJo1?=o_! z91GJURyh`KJvgpv5d^r*>xFJSP?GX>*&&ye?_Y?%YTaLV>d)6pmD|pW-8Q~U3bGGe z=c}VC?UdpRxOYl^B*@j^`t^-X^L+Ze$`);y)<#-4J!dH8|DHfG`r1g}5N(+&>^@!n z#9a59FFIE_%sppLB8;k;YUSiyWlO?#{pFeXy_(X`JE$!K`wAFJQ^6>2s;<%%g>R6v2Pwta^H2P==Esr^j~N>1 zdrQ_(jv|!aYg?WeVBQG=r*9&zel7eq8;*r+X0YHmB0&R`2L`D(*&0zH4o>hiUH z36~cp;z>Qad2_KzX;(KBipzDIwhYx{=RHW@!k&GP$^C}5 zF(G=^Pi#A{gb!xE4hbJERBBg(MWzUxahI#T{dT$R={$(=jc=2?kkY56;yu@L@3c%p zLj75Ktz>i0yRteJ^8yp^Ja2NQgZ(XN`eO0!8!WL4J55_4p7pOUHMq%rEWP_UpqE_; zx*b!-LGI+|OO4`^~?mOn0>+PjjwE?kW}9wIe*&J>A^@1M!&o6@y&o zs8ed2`m7`AXC@(+ZXFdlOgnV@4fjW-6+0x(=p;fX|Ls~<=!3)JJzR5>ikv2vs}Gyk zDNa(8f7al_kO@oC(T=wQf!+)e%OWwTw`ddA$`KMAMhW=4qT;KYl@Sy5btPC{KAnlV6D``+GV}XP+&Rqp_iZOSnE!E^ zWgO_=MkuKiD)v=$kXvHWtLb(zClZJzzT4*lobxn;+6!?l06d+1cclxbm}>t#0FgCYx=WFgq65$Z>K z>M3A$#wi~#!&X;a^Dx!zdZhYaFEkRzI$u_ zB59#yWa676=Y?arQ<=>C5)TqAl#`?X`+jK;bjBT)Fx+HY!1ST8Hk*61={?6vN<*g% zrh}Af49hfoU_R}z_58g7`r>|@J?6;0en6YKy>pu#)Qai+ccs@Y2kI8X^rb=r$gqIY zXU^LsD2Zk#F|(J5eP~%Q=nN;i1JEO1?x=Q}wqAz%>$^nI?scr_m5o1~8fPkmbQS6M z6I9rbbXfbe%e7Y;JW8RpUyO^LiCZ2|INyhSx*mP|)>bNOuHT$)J)0$qP>xqXQ zl@09X0N^E=VN3tR_-AGJY0kk{6_pc|DM22Q;xRIu4#KI9`ih1gxXC#0ruk_HF z0%0XVQA#Fg8|c5w%#4*g?lh){@QF_p%i&bBFaELz&!nvf`UukBIsZVh*K*raN%xxU zaIHsKLeuk>%zakJxNBzOiQn741-mPayNooL1TvYfWLRkx)VEP2MOJ6z)_GFo4pBTJ zDXi!UW=6rV?+`2$KQiAjyjD;gy2%Y`hY2TkX)X>o>XgNH*(KR``;lSa>OH@W45l0R zy5gCZeoP{n=|Y9Nk)dv-o==RKBoeecgykkG9>|S4H4a)AGrxP1`k7>O4pTO0C@a3% z+S$mDX1MNq+gIN`5~%+kSLQ>8jeWQ9Azx9b@v5FT_wlP&U>agapOW-1q--c}jvjjv|=QzucY_@ap z(dNm`VU48PH@KE19-AXeCiS-L}CWxYtWeooz^ z>)IG=2TIl-XqK^OwG$uuQkX_AEYUuOSGLoxA^!{ znQolH?LN2dl3_mp=1lf-7QAv;8-D_2I&E+I{x6=TJ5DF^K~BKL{|cD>Q4A#6e5hc; zGTyq)Zm-JhGZOEaFT5=SN=WKs{xWJOmsU`99v@tE5A>`57U%C{Z*-%t^{me88%76_ ztzPsEo)6IbH=pUSVz;4PzLD4Kcl%iY_O`FsgN$BgI0@zgm{fHgP}v1@Av0Ym2V7~v zp^YrP#kciqZ^J32D{{W3{vDf#Scgck^Q&CfAXaU`uxpCXmKW2deav=)Mw$g>du<=5TG)hHYWpv=tLeUa~~7{$eg53xBIU|k&iAEL(>MGshoDzQO8xgkV@#GAXu%g zw{OnVL=r6VqluL{;Yy#$cFV$qfBQa_r(PiyOxMi^C$2Mn3fo%7_NJcg@UR)N_Ih~e zO{mtn_pM?Bepuh?I{3X%^P&ir3-8%CkBP4M(DbNIKMFH;78a;<=y-o{0;=*vE6h~= zRjgl=ZX_%E?6fOqF!nfexqsZH^srwL6itDkgBVUi2(SqOIAIw-7@hvm?tM*aBqj>Z z-20EwQ|ajfkXRuh@K7&gj@w4$-u7|-)Z$@(o?o;5h&LJLn&TBBH~U`Be4^gpe{6T_ zNluH*kUP!Amt?jiPkN*7_1MmC_%t-t_qiKC(5=0VuX|wK>1{K!KEfuL>*t;>Puflo z_ANYY>lNS{wB5bRikKG$2xnlTfYEG;(5(+X-{q518Sv9T?B|PDE)6xlMzec$-HXe&p?MQ;tel@Yrkg*OdNz8l!?k^s_|iMFany}GT`5P- zxcz!75^B0D>zhZnUu`EflBwbd%QzK$w#4)2k5@*O0fBs$3-z&n^wQ^BR*C+$_h7I5 z8(Ds}Fn^_K*PNHOQP8`gQ2W#G2_UA3KHxkB`W*_fQi66p4cn6c?8y1B7hpN@m(*}j zgKap}L4)bA1KMHvk>u|zilX)?ub~ppF5{3hr=h#q_>)q=QJ&_4@(H{thH&aH&(xqf~2tKv+ zww*rm?C~c%Qt9E=$i-q+tUCJ>J-B;vtnA|nA`iHL_FQH&(pDTgryOi>@ODjbFhgB^H7Q% zAws?GbROJq)H5o$dOKuq#fd zqNE_f)wvil@Q=9HO|X={7`Ge>y|teeO3r-in4tf2zhBQnXldN&{q6VnZuk0AVGZbG zuArfjlNsfNGaPCy8cv&HIPn>O zf2?$)p=W0UyC3}b%#~q@XFeG{0SbdUr$876}1xoy;cqylAv zHAyW#4|NfIS|-Bou0?xY82;(N3U_=N0d&?i!(4|va}eB%JB5?)jIc_DZr^j@Vdr57e`3j&>y>XvrxOr_V$;O z*QC2@4o-d(uSbc&Qi-tbn%X0(*Xs7~@aWI+zUN*ii8^^@_L&`fJvkAF-dS^kX zbAAGh*X_IFFa_n>*V?Z8$S9xcD0ibnp7Cpcj{ZM8`>FNS-{t~dwOjGaF2lh4Assc8J79jXi^J`VyPDD7a+iM&GjU68oB6 zdg1pcAG2TGa6E@|g+db-ZUUJTwXw1}7bGmgrKJBbWUy6RyAiOsW|Fr|QEk((K@q76 zzN1iI-d|Tr1?H}^pYVyqxFos{Yv`qFdwxiy~%JtH9@A?Ekm3Kgr+SI@2S0 z>_O{7-Yzf0gVXW*1Ow3H`&UIhok~$OaW$U`twH6%HL#mRYz^26r%nbW)S^~RVacag zP2HT&#LFGlRQ0YI)R1{<8moFd9^`X7zCjx9VJx3{v+xhhX-J3BurOqJ_l98YxKU8W1g0eNy}<6cbu-78x8$OWQIokixbcF}BRp3WUXb-oN^V#q@_ zb&ETun*q)WZ`cUWkw4Gan9RcM8*OJAxzoysyUD?OOrHLDulj!X@9xJ^r6I#pk_l}) zs;+O#dg?xcs-H2=?L){U;aL(sY;RY!Shkj%gnHwdY*lSRqB!h?z`LIvO9Z>Br{g*# zYR>Yx`YCC`*Ak}_YIed&85^c>RrRjKqH{}Nv$za>dQO;@Cp%Nps7^O?I9or|#*aaa z?a%SOWAV-Z;Vx-0?Z%Mvf81(&wjTxQM4Lv8#9gpx8s7cb!aGN&)?$IEp%4BMcsG|g z#@3=!^lKh5{Z(>0q93p1?JoXw)?~5B^YD?V4tDg2VQYJURFp@{ijr*Gt}0daBNb%2 z3BhZzoT>q}lR1Tha?#hm%o~ z=@aS8jm(O&x5v_7=YFsaYmE|PWF$$a{ z*MmrS1T!K(k__F{M!fZa8C~T7|6tk}=|s(}v}`}&roC9QT(>PfA;7WJEC4Z0fQ#5)2*#&?p;|e52of&y*wt`J9MxHU z5hr2m2Sz{jWT-r#W}AkX<`0@*R9m7+930R>YhRaBH*6~UT5F1xnRiyTXmp&17m4?F+Chu*-<2tDg+~S^_|yA zpgtQOT{11l32I9fHx`CVYSJ+U{*4`&{+3iELgT?&3{#?5|o3ocf#$?7^)Ue$wRqV(-b-=;oMrzqy*iyY>m%zm&nJX1G zQQhegZ9a%LQ;GZDPw{FJA*>xjIQO(tqzP?O7x=-C6gZrZlvkhs%7#bvvk5Hvi+ z=qivC(6~T+5k7JoO6TV3Wxktj*3269pWRNniix8#ROhg)Ig8VE4~hbBm}fk6knrU( z6q4A8HK}0YfILY!FX_k5luO}4txLp|kRe%yx;Eq5ycW14g=LgOK}I%azPir|GS`=o zI$Y=^Y0nl{qEKMF3dO|Z3dQAOKqzH>w8|J&!hXxv{>qNWM>==ju-pVMoD*O)#qTX7 zKdf0br;8qP*|Fiy9PnPnM*^pVW8!YL;40=QJfrsR0=;JbrYf0^P%F=C)7J{UJJcq- zAk22(XNZREU~09xt$)i#xK;hT*H4z*gSf76`4-Xy{Ax0#75=N+E@ocX*LBYf4x zW|^eCcGATXV5T$z;v{yD`Y$h&XrF|U@af`@YzoZBEQ%eZkrO` zAVp#z0tzAWGi=CC!9$6VLa<~F!RB;KNs8H_gLxKF(MR{*KRedVi&#nO|7ftLSpw3= zJ3-k5tuC-86{daxmBD0b)gDldd36pX*8JqUrZH0$>h$h54Z^15kUf$w;FQ{)f^FT= zSZOCY65(Px^GQ2FWfpnbK&-=WGO2;iX{C#|&^4kecf8A#ZP6$-=7P8y(pR%qQ$yB& zzuUc$X@U=5``u%V<)Uf<6dw?R!HTOOMH*M31i+rAD>CQd!WpF~73D&X5)&*LLYL2> z%iGg=2kCGMSUv}=8Vy#60wdUTl`a~h29PWPi_dVBMM%IP8nm4zA@VE-(Zog0c{MkU zMZ#99`i{Kp?KOfbmDBr#tAUhrL0!Ye35v*a1D2iWk)7&^2YDG421%}}SvL*e{W{ZF ziGUGuP%|Km0Kg>C(Nwx3h^|NzNvQ$F5;-hO{D>xLL1zhGOIE1 zK|?ePP3s%sgtb`aIk`xV)PQk)Tyb~^TCOK)5v8@t;(#YSkxr^9m=Ez#Cj+_DF>K96 zuu9ARv>F1cOH6iyj@xvVo!X|$rejosGO!_egJuT19m*d>UqzhS}m^ zqO_ED>nf&m74S8ROoDneS1p3;aNuh12B)FBO>pq7+cGpdm_VQVk%e z8Vx#8Bl6z=U$-!lBMH(L_o7?G(r!kLsnoRXSmKeZ_rg10Z9_wgII}>Thi1QpWMS$ zZ4}}7Vra?~+Sx|Rau@eSDN}ulu0agc;B!?iyftDbue;DxQaI2Qu}(oL$3nZ6s|%tSSg097(-W#qKnWf z3QUoq<8FBbIPtyKkGj}b;RK~5f_oYP5yAnn!IH)tq_GG`4MO4psTP_Pi6eSp!4Zyt!H56^N8t~`)bn*>#+#+4AL?#R7gaR(%cyvwS zf=2D23W<)&>JOTunx1OaP-*anXpz2d#Ie(6L5>1iJ%5F%PudMUanJ$A}ADa%CkTU z)Ww1I5CxGHIi0RZj8|kEC|7VHco39V1L*@GT{K7wN3shf*+2tz0g~x-1dS^?AYMcR zu&H1u8MH&=llKz$Km^BPcywn6SEZJ&0aOSG)lE+bx2VG&l1_4^;0;<_+9KgLWr}dz zL&bQ)WtE^#B&hrltsp^U#Z^rLp%=FS73LsrX2+!WH7z#b)&N+dQCTI0_Ry7nwu}Bs z2-e_%)v;Ls=Q^%IAX`|J`UO1h&h4WYeg=(J_SbjaQ*@ZqFxhl=a0+J|Xzl9j;fm3p z{RCk*0nFAhj9R=X9O8ZI&`>&>Ij>+JUn<_O-=`D1mM~xx?D@ZvL#)_uvQ!85*G<_ zP_T3#U2ofo25tb=2p+0;2}U-#IB0@g46Ue-AOWv^_=mvnrmL40AjavIOI$S@u*M8Q zj!1Y^4OZcS#Tz+tC1AORm2^6<^W=k6?<<0(6|A1tI$duU$B8RL|6*oP@@M6l7#Ooz zziMW@Zr0$Wy{J%VAawjsA%`ox6Z`d!!9Yi%LK0Uk8(f;jmA3~gB!N{gfh05l(Ki<( z0Z1ZEl0<{TX%H^}0tcW`oCDP$m?&Fm1c|c&DSH574-%&ts!@?DR1gf=c%y-ClfgM9 zAWU4YRE@dj#1^PVf%*>8P}N+ykXu#uyVQiA#)t2!f_frN>6l+&%qj4;46;Wfg(HRp ziTe?Oe(u9hTvt9_c7p43_=su=AlJvW8X&0h2JMnbetVv0(k?b{cnwHk(ZHVlc(-Dhs`LM6WX0c9+Tnyd+%=Y+QH`FC;+Z01!_X zG73OB03?J11vpT98c1Z6_X2tEU66phwC5U|2luNrd4k4j3I< znarW1z7UibO)fm9O9d5(6X}|4Kq5X;qGg+_Tw?aWl-IJrE6q``s~bU-uu8SlfHm%u zgxQCd9uW`pC4%zAjUz1IgPUH^zw!xcYy!>(EGuZ#CxsPjL6=QN;{5DXs&G>To5oT+pSO$!dGZv}F#s33ICvmX? zfE2l*kdj0?239@K)i^=NmKr2Qf)VKiMPVZ8C|GqVTtneMrHGqQIgkiLi4@jpIfJyF zXonD>1{aQaE%$(jrRc9wnF#1OgUELX{qY>hQreo}KSW5Ycsih>zuP2}bMOUWKbJ1i zPM3`t)hOjOo&=y>T;*+m{E`OhAu{G?P$Gk?RWnv$`ur zePWk5k!E2DR`;rQIA><}k?=o&UT#5<tDFFc9}NcQ zKxwom(X<0;pqd1bI6won0J_8AfHNn}Gieenpp4shHKLFbDZna^AgAUgp(`y%y`if6 zScAgZeh|wMkwN}l)De&3tucZ8ZGsAoi%J2S-3g)`MnwQlU%HlNwF7agay*SASwVB~ z_m)fNggS}_4(T|!m_|H7Jzbz&%2i;Qs{;i4gCNOKf>aJiE=2@|&+kZoBkBL-#t()x zN9@@}waY5YgZBfaw<1qOK6>V{{7eOmwNF}6;3`50()Q`ns~iPRs_QW>Hi=M{%+)xy zflcR%Vr1kDUGzp#q>|;+o{x0(XAuzXrmBa*XTk_d_8t2)IjQ5cs-8ch;}9104a(*~ z<3aEw&H+QqiR*tLoHmJ3?%i_GTHk4jMnJrz0~SRi@7EJg0>Ob@>OYbR9i$m4GGD zKk4mekAmeV2mO~UIk%S0cpOT=v+uxqOp6oMx?BNT-!P+!F3+qLi1_r zk=)U@fsF&tef5R?cC8YD!V0Y$wA z1L-mIfU}CMzGGud5dl)}nBbT`L<@&#+GtueR5fmcFDfIm-WvnOcbu}UG=QKfeir72 z*&eU1uiv9xE*hl$>8m1#Gj2Gf3ZW>;!3)E^6!)n~81eR^c@qH(APe<%}{FK_yyIVaaqY^2m!A1=a>M{<#HlMufg(7Y2I ztYA#!;HrDGP@38?SOP(Wd5#_99At#O*v_(u+e|r;DIN^yps@glEhc3v08kFNdjJHL zmZ`%;j`8?Vo8cJB1;C+FNLwbt(jAxXy{ZC?Y+c%(GqK%@-Kx7e=6wwbc6D9p%*9 z@`3SRk2YG*7x=#1^WD(vs!jn;Od&X}igoq5+VpM3u>HH5_Y zqXqbC3C~tec(!ViU;(bxE^x}32GlcK=e*Q2+cc7SRqgnbQ}g-w8@&sXOAVZbJ*GYF zIM7;qF*s8^q!c9fZTB{ol8N01cRD`Rv_}EYW@YZPdn#=)vAD;kEK?mw3*XFj3vN&=3FMSy-=dv>y*F?}NXcS_Br!8+yv( ztMshYkH^ZluwmB&40PnQ6wWsVM{dnybY?gbhs?!d9$!^?6BF$nF;aku=RhX0^YGY} zeTvj#)#=7)34*@ZF)IF^I$SHKR#8fj=v#5q^Tf@mqI$0$$_W?g=&0JNk!y9 z)ye5qAEjj~R8V%D0udzUMC|lR03^?MhV2)MDU|})w8BiZ7f!;yiwlXY?NR?plh`8% zJ)1&fsJv~YBiVdtBAcOcQ&cr1a?z(j5V_$-bNv|tRFmu+I3yHin~@>uCn~PwODE`=->lksG)GuV z+?6NsuVUi1NNKOB28O!{_F-w9>zd->3FXpa+c9~vOpQ5^gjJyc>(XCgWIrz%k@6Cr zaD`=P%K=FW(2(H9%m@NMV)$DKY?uv33QQd}NeWO6K3(fR(k-#pNn(b7L&}RU=1YRW zEhfP>(EpH$0+18Cm2M|I1~cH0HAFtfm;N;LZW>prnys6A6^!1CaE32Zv;Pl8=N*>R z--husIDmkN3vnYZ+_-WVu2Qo^(^6AA&eW`MmF)wLTosz-$O=cLwwz^Uc3h=qrR^Qs zvTWGi{$5_Li;KU{ITz>qJfG)&?t8v$k|wt!9h{Z!MXCW>U(bLpUnsVd$`qDh{i^i> zB2Ox!ua@?+<_n0*W1jo6h6i*{0FaA7)V^#ORQMf+D5u>L34?Fdq{S|s*v;hSS0jgt zg?St`klD_vNZ8tE8XmRK(fDtT$BIXq9p7-GQ@5HWrRE{_0k9<^{Y`VTcWWNW3P|TB zmnaqpV9sm@1A;ccQfF97EUK6!7>%FS3YS1kcg##n z2*SK^5jU`ow#($6D0p&y&vBfKrmWap^B8-k0oNJ9z)+Pl|P#!4ZLMm*2VXA(AQ z#mK|Zq(%1_h4&?0?Sm}eCVB5R!zM3sy)@6r*+64Ws;{-5c9QM0q0SsTajLQ*b%E{W zD=G-Q2NjYIPw^D%`jbB>3)Z63M-Lnz6*UW$_w=TPw*a@&>eE6~YD- z<(|QjGDxF)H?&4x+s5fAJA|-d&G2m2pJhAujZFGy-vaaq**WZ3?5_=#YTd<0nO`;1k)TB4YhYaKUIGJ zB+&+$%}-F}Mia-F#=UtKV|x$oz;m@F4D#xvx#}W(^{b9EA?uE-2{*;J7&a}eKP>8e z^r|3tZu(48p_7^y^AMW9ghUs{{QL?u?FK1Wq>dCcVc!t|kmZff^uRBXR&puQ#fn6~ z@t5?k0KEm{#I2SHWcz$jnvaaOIfWLp1Rmx<@newOy)#rs`0y5@VSo;Rd;o~aD1s3b z8!^gte)Tj;3+IC#SHcPC#d&-JV0mv8Rj|dOGyET)6|IH=`G(*QhM49G>=;C8FL2>o zoPL6@m`bFDyrK?DDNQKBOG-H-_YGt(DMyo|JT*#{e!UYctq6KiyXSS)o*+&xIrM`y z-#d7-jQCq2xaP*#tWOteaB#Nq75*^=1G-DuWHCURO(2K+N(<&N{msKF5e?K07&XJ2 zwD1VE>VtyA``RKOSFE3soyT_RY)7C<-_{}~F^tTwr zLB?eb!{ai}AitfD(fow)G+S{#Ab+(O$phqAd?XP4(8^Vu#vv3Zdf*CArOO(nw4)f^ zC+MOb3R|Mk-8C0E9LQP<@iEE^z-qo!FBmWNYNa%#Yy7ZHZwe;7!xKM94cgd>^%$*w z9fg@eGq;wfR47zP4PV#){J=AMZKQM~O-V#$HeL=Y#PeT`k!Zm$=QaJBN>jd3s;oQl z$LIPO@hvHCG9?hHGq)ud;yWFXi8-SdN1wz{^CjeRvanO8a0a6`VL*&65QBq69LlgQ zJ%4?^Y-Z*<>J?Y2Z;XRce9xa$x?bt~n;0Yjkh{3zH1Lr%t*==~;Gj@xzPkxqLzfSR z%V2X11XKw(aae~<Zje&*U0;STBs3r)ntQpL1Bh zhZEQF^9nS`CN!1NUZ5lIq>1a^Q14%-`2-LSVYJOhDUED}>y7GD^~@|!qaxL%lmU&J z(?-F^e>roRTJWpwxN-b+NXU$GM9E)vSrHfPfY3}}%9x1g2 zQ{wWW7(TKb|NLq(-44C@ib@zq=eK_XVt2kcr{{_K;B*)#2kp&cKDbmtO zdB-N4zz8E4El{S=`$n|YfWEWCd7`uPH|Vly-HW*LuI+$vyoi*Bx^CLtH5coCy5kr7 z(-^(MB&9s)zdF3UzRt3iP|W#|C6FTtkc%bRDS1uu)OHr&7s(Gb zmeEFK2wjHY?7d7jpo2s6WdKtapMldqV5H|LB>*65VF-^88{r6LcBLbxUzgZxf@+nu z$Suenk4qOT(LdgnIC^5#A*sP}IVYCV!r6366Qvz+dWq7=`xWhFb-4wH_#MWirj(}Ho=$9{$e9Qs1D`yT{bHcNc=rG6#qlCYLjst{1@x8RS zP!B>-9naK~fus3|q7-bzY2h+J9!j^}3<+$BT6e6GE2H5!^%X`P#}#BK--wMwGBSI) zkdYMOU=O6e1Zfz@3nf?rgpqp6Wj<{oN)SjNBp1*I(Y8~3`a3o~gRK~_p8i1=t@v5t zRX$}3RfzIbxId_#+Lx@iA^X#mv+;)b__`%K@Us>lZH8znf&rFfYnIpiK z0`^IyX+DEK11*<K zARgP>6b0D)OTvWa^Yw7m2G~_bld46(WrM~jP&fpVZxN(Y0#OP?NhKL`7*U?@G=?HZ zn2!bk2cpRysO}peYZV6R0hzVRTg~wGE7_pqdRjjlk&Df~C({g(j5ZiVjo!jf)|Ji&#sPVe5{Uy848atL zG#m(LSA|N!(14i$3@q=0djQ%P`_a3$cXJMGxLYM_yA~9VB7Oi>fD!!Iq~9B7xHA;; znaVpt+V+psCfuveObA>mrmZz53AWotwO2&_W?+D*c4x_jY@s@eJmBVDz`L#UnD=+#>(ue0oJSWxn)u4N$xJXKzQurQniF&pI87?~i57t-~L= z)HdHQQqp*1e$4rFrJ@>#@_AB8_UQ>e{2wHu}O%AmAOgx^1?p|VOGt8C&^rJ=OhoVEZN0IakMqOWz!nZ`^Pj*pu-7{Bu!dj;ec(?{>GaOXNIhtCC@t z7*oi@$P($m@l(*&?+5_{ck6A@#*Ydp_w2Q&?C|ZX4|tQf=c$(qKjl(PaAZ05c$AOC z#Q=1?QR)tpRcEaEw4O5e`O;n02j|us^TqF-c!mIRbm;ax6dCh{&G+>7fBszab(lY% z{@-27DH-LfzWgXA0aH*B!>}h1%xqYwW*+wLF=%)!V840L33p`!le|LH)m6?Z?Rg`| zBRi8nJ?y&r?9x8VmFKrA*dHCMc3AVU^ug)Fm!f-187^^+`=nx`iT6zONDUZn#fT+CfTJOIdhK2efunof#=@J4MOwLPjKQJ`y$v4e_yyN|A&@ z+zTsV!j?24*6#&VV+6H1ZCHL0S(#9XNn@AhtFD`_XddrVtWj5XA1mAIHAGcVfwo%xC zFb@$KoG3lVj-yq7U9nI)oMV8{d4lWHSo=_khFOBwi)Onks>`B0CsgAk;APFF&Sitj zewJl}7M(wDmiYJ7c3xegwQe|e=e(DeqwF@)RMDo>>JVMB8Y zR-FKdXh;nDV%5R{PXZI?c@oVV1qB4h1gwvul_t-5)Jouq5O$$RkHRSxf)uU~HpE(9 zwGmO^=Giv0*g0kWbQhV^PTiymA*2yGX1nuLLPF?M)gazvu|=TKWU*!YPp`$6hUGa1 zHs+fO*PVZRzCtzN;@AGgHgc=g5=&3eHZ(ZM*f(#5&C-1~c$mo1D0JET95qS8ziyiq zizG+X%RKc&2`jT6eA^oX6L@?CbZ^D?sW8}{lo3yqPi<*qLz&F*S&RS)Qg-U4R)`kr zB)Ov)C1o(ZpF+#w@6-et^4Yl+E&$RDYH=J?j6y{e3%}X9#|o#G3RyYB)y?88bDZ6$ zXoX5&*QlYZ3lOzXz$>nOw@5kXZJ6z4)`|q5%Ui6+Y=0>LD5158-ff2dt{DEa{5w#7tn}8X|!;F zV28Ib0s&YV!`FJvVx%YxGDk&OO!gcoFACs9IlSf0iYN&v%%}p^|1JWyvW2K`EFx(zejZeL&A5z+N3kqMII4;%3dL^W|Q?3_NwdWT$fz zj-(1kDos)oyvD+QNUq=AYX}Wny=0`p)TZ~wUwfx6|#Nm0>OYpI={O(6AS!S0W~Pf-6r?KkngvJ(s>Ky?(~rP9xs@mu!0ay9s z`KGhC6y&w4{JvnCaxs88kgJu4_Qc%=T+qd@F3f{QUd~a{Eqs=U)Pn< zNyuQT&Syk zN61!vIHeh}h(q0%;PW4FuP4AK?}5KBcbQA^CGoNPmdC?p@LsboTUQ%a6|7jb(? zs&ZewbE)ORs;4pA1LR$W6!5gt3|Vv;&>F;u9JGbNa}-@9V|3y45v?hiXjhkP^|@e- zbX^ERY8Vg}hgF2{4`d|qAp_p6OiMW==c52|94CB^1TUsy2wVmz`XxFlj`1PQpZG~T z=~6|hX}jUD0p%1rU{O(bMPt~2?jsxICCrKBDqNAK4<2b2Xh6N&-meiZ5bN+_SDs29 zI_rLZ=tlO}DBQ|^>BAu^RaDZTnHXJjultp9^X{1Ml$6lNanX&plVcwzQdg8h!%szL zbH=n!8>9qObl$eT81MP?9s8UHl(rt=vG}(j6jQjsCVV;x#zwGnHL=x$!?C-lbXkF0 zttYUiI9Gv)UUkSq(}Hy|8}(U?l7=Jn9R4vM9@cnK@sMgMaKi@$xnXRGi}Q)*f-yBY z21t};BT;OSQHVlMKu>#5UP07EOTmS9Nd4hJoJy;dwm}XgBejXP!yv^c7w-I;gs5cI z5h7WAs-tM-^6?FG*@srzukYKp(B7ifI5EqCsJ@+S~3G7XL|ddTN0#tXqfE zlJ>RH6vme;oa+-d)*D!rS``)yX>U2J-l>!5=UXKVI=ko@)9Ey^LyhY1B81{WWh%lQH{KjFwzo>fngjV_%WG z8h|RJo4BFIo5U6ZWT8xvB|nK9p94Q~XJJ(dZw*HR-E|j22YfFy64>^d4GJ4bkj#A06z~icf~t(1u6pGQD(kjnE;W`w1_05BPmJM1hC*Tv16j%^ zWdNj?^N5iGq}7oqkRXW?c~iNPqY|uSy7~wy>X?Sjl_Re7vkP^P1o!Z4W;4<=E^kh$ zi24?ymR`Ye7cVj;x!c?f!LoS%wthpe-K{q=4M?_jKX?X?v4mEQIn^`S)kguj>xi7} zeRYH>awr49-TNW7A)43<*$LnjK1o~XU?Cwk$RC!Jm;!(v*>S0Mz@+B_LMw~ey4H%# zWnhpIo(i#bBpGq0t>*fC&{_hg$1Tx9VQUGCj)D3-`4BCT3&^hu`S%HNszBre4~_t` zk|4ECP__W!2oO6mvW$l$2}mLA1=_Jzp@7&$0G+~I+VR}ux2Vct27KpWuc{=qjC8Fq zgGe=-tG))BLwQ3lHzyOev^;lhT}D^{BrhM{lKe?&5ubp)SmX<;M@;6=b-S;sVqVo? zCbEp;MFk(u7EEY_u6JHlUf^#gn1h{A*r^pZWk6H`*Ka7)93ZX6JfK!E1C#e(DVb8@ z0$-1rfz*Q>F6_7A?Uz+*5|)Pi6(k7I<}ZL+)9#jmkprIU7-ZI}C4bBA&jG1e{MQu` zU1G$yx+EM!0(}^kLa0}aB(jO+i;!?WDF`K+2pIwlIh&lj>cKt^8#yJQ9$Y4@y|uDe zw(Cgd<_oR9Nues7n|Vou)zej**L+Qyx}S71e)sj4uI+s01d?H5>^`r3(S-3<#pgD~ zmyKLQl92~$TPoD3hM5$9g0g0c$_7BmELL@%2O@x6Ww3`FQSxA7D?kOHnGV1Lg<2}M zpL_v%%_Tyatsqreka}|&Ebvs67rSgw11M2qfT}_eo1CXA-K)eWdOU!XrJ%4fO}#ZP z5rA^*K^vJIGC&kzpa~999f;dEg0VcPZ66Xnju;4F0|7Maqil#d{oO>&mX@x^*M$ip z1t{APhw_GyQ{w{F_NZ^1-K#dtp4`cAV^sSG^GM5>`+x1RS>dicP;Kk$SI{YuyxRWthz5zbs%evhtq^vf zg!r|FW3KGjeC~MR9Kr*wLLs^|@CHa! zkpWi|(w>=OX&XUJ0eqbZYP5oy(nCxJ>>?j`$mFWSKn{kO3&G_=u-1`i*ou7lh4fUx z!&zeaCMbtT8cHTb2uK0}F>w~DI&TrkCoUHvK|Ep@gLE2b_{6bRZFiO0*G& zeaztz^#zg?clAah+uz4L_EVU)Ee`w4!tSyf^I6244cqaz9q!CB-Q>WPO9X|G0}s%f zP4zGa)hj%#FeoJvfRjNJ05n1amDzJTcOpRMI0Rw)Znl{#kB8=F=cuEwya80?1^n6w zCE(DP1PdeJ@bYn_Rh{U_CjP2Me$TTaiHSJ^QkIO6%1%7e6&b`QhP7fY80^ZR>Yd-! zGqky3#qmDlsHR*YUX%AlTz|Ric;>u3wriEPqqXuzm6j`&!*8v=6sirX#yAeC?>pzV z^%ZaTrjss_lH2>3Pa_HQWtkqnHS{ewi7_X4X4~C_S+4B zgdc&95_q+g$Q)m$Bm+ENLh1}i=!#hh0<8wqRK~+yHFZt@$d$rgEGcLr04;IsTA5tJ z25oT+WxMHd=lJu_R6#LpV#F*GDMeN>h-_ylmfr(%pg#%34Gbh*LR`ipmD(c$R5=bs z3;_hi2{C!Q)H&8^K1oX!t0uondO4hz&aC=Rcw&mYM?hZf*S*~M-@QJBw+PrTYGPh%sU6}z;Ol)VABx9Kq2^mN%CrlH4eZ{ z2XBhN$9Hu${D5duknKZcN&!PuU@jmU31K4)32=nmFgcAD3>y($2*kOvq3}f6x;>R( z$SkrH*Hk6GaYye@| zk~Z>5sW`z!75Tzs$4U`7(u|NH3tBg~38Fmw<|?|X538m+n4{n&YrZJC!1Y9Z=X#(l-yd>LG*Y@nH%BW}W~@0DR&X93p`qcC1Q~5KRRzMFOh3 z4XBJm!@sy`zfCV>L8>yO*CZ^t@+h+v>bV@jQM;}(3u$4XF}~Igl`lX-L>a_pz?Kr^ zUnCTVE?FgjoKeI}nqVks-fBgx32+Kylm2r+LIuQ_aqpGinX>sNW*Fowg$(%6EiQ4T6j?Ej$onA!;P9t;ki6VC;vwl6DMUyL#)#Ma zNWrbjceU3oPl8){TQu``t+{;Vq@t>~pYU92UT16FwXjF)Hy9Mx9%rgdEJ@Dm1-cgb zJ!*enH}_M{9E64e>FT_PkKLdrL3KQFV~oEYbFG2x^Dx`%x1Mw=r^u`EscZ05^wm>o zaPEauPJHdUd2pww(PR9Stz=*=175kh%zPF|9Zr=PWhW?}M8|#QzyAWV9t2pk+h}N_gDlb#fa4gaV;DqlcF$=?qBUDy_PKmXBeG`+ zLLtdzF_Iu4MvWt`IN~RT9WmHhmf|j}d#dtSsYd8GU-dX?%aorDv*uDbJ^gT|iqTXZ zt1HU%lhQM&%g}svi__!Cgqy*q9_BPx8Gp(TjD0nqZJ4s|jQx`2^}W?g4CY?n3t&EZ za&}94w!Q4O6Z&-N!Po4uQ}11G+wD2LM zRyLp|R?8Rz{ z#3jSW;T1AVqAz^wF%3b#0>PQ0PKLXt- zd|c+4r=YI))v<(WQ`njGZR+J!4Xa3|!Sx!XtMXfnu3S+WwfV7L14O*a!8_3UCAWgQf&2jl2 z2Wu#B9v=rD%5%wi&V1angvr(6vCzrBVvtDmt4f~|%ZF0S$Na!Lq*UD;ZEEG^5~>wI zK_MHjFQI6oA$XI>d*^P0=+3QXBICR&MuK!$!8^ZH!6s5N-PD)Am|+%EkT&7vbrnLK zwvLH?_pZ26+PT5%#j|G%cC4B|T38vqwamD&*t)!kQ#5DLYVgleg@;3l6H3Q+I;3(N zAzeFvV+D(?$r?ooedBfDHj(fC^5n9Ycm!tGzw_9MREoukrp@MyPR{)*F5GdRGGl&v z_wZX{XM&`!9k?$)N|1!PrZq&(50n!-_1kL=cs*08?WC3*fn03HdPHIB_oTJkcT!L( zLZmpO7&2ukXD~(#Z-}RdPJ#-_0uczwmWc{f>{@{WO&`${ss^&R@NN zdxOxP)M*RD?Y#bl%}qDcpY3QDza$%OEgiCGDZJn2ceI#qcd|!KqIwFZ3uGAnw!FMR ze=euBZ>M%L?tJPD4Y)OFd$lpPz+NQS8+eAvl48((FA$N(?P35J#p2t+5H<;_1%!(n z`bJfS=Inu92!-y8RTE zyPJz%izVrbhqshi^^S`Rprr1}ov^*#r~2#zVO!I4-D^_%_HO{I+9j4$f2gHY z6rh;|1QzsI7Ayvlr0Lkr`bpi+Jnob8q84qkYH5LeQBL(WHN9@jq&Y8YGG9y$X-&fx zEKZikZ-pnzIXDw9A;PGfg)=0v2(`(Rs3kden};L6wsf!57ZJr#McrTuRdVpM7CSS?$rWL+`UC6kV{(IjQ;Du)e9{%1~+6F8Jm9^w@v^{?j5xD z(wy{j3G=Z@)Sc!qeieHsq_gbjs7&X`cYiA|_0R{W5h%X(qEiPP1$|182@%J;q*+nc-`P>8w=(9x^cvos-%ug!LrQcp?@ z-}K)DDbX6OSjQ5GsZD&E;hc~UgpP~h>7z?Y61AoPiIYXL0fMq%s*yl0vo%0WzYT05PzmRtCH7^H^ej6PO z(pzjj=G$1pjh$+{?|XQsk9CZ?%V=)Q*9Qk@6PUiUqOx^)4bAt5cjo=@Q)q?t7pKCyW5# za3JDX<++-UW2(2Mgo<*}x)^@0#%+MuP_0Q>*!s*`!Uv6J#Syvuyw^Pd(WVunX7R;l zJ|Hc$X%5zTCpgZ{VN+x-7Ao7>H({eaF)F-e8&1$lxKu@4Gt% z^#+w`XADQ)F8ANw9fQczZ$vh3Q6tZLJ~ z(_mWqRTu|A-V3(P{!fYi`AF{3Ll{DJ?%VD^j)4-{rLi~0G@OQ+6GFjGGj~s1)OVk@ecU%|9(QP99(m_u|2T!%lFLW8EuV9B zvQy5yYs9ZfoZ9{5&4WKpSFe0{JKjdfI;_h~_KoV~h~_rcWqr$=uldb$;KbvFA^?f? zNDipnWYo^P0yG*rX2zU%czj+ExHKAyicB)Hn;FHgdz(RuWa;XfxeCdW(S&OuIAqe5 z2$qzY)3jQ3w43BgD3n((n1xpL^Bp1fZ4hUFwkb6rIsyaC?c<200|_yZFV|%NW1Jij zHO8+_wRSd-dPz%RapjvYPs{ywc$M5=rca)Enl0VN`Tk(>ZoGX_U9%7rD+F;@n`w97vV@jF) zphpkaMY!#76{n>i%!e9&CzA_R^sMYz`9+A9f%|D$*>|yl?Xn)b<0?DgQro>MW+^s9 zhTWruBF?l(vxzo#!QL>ZV>C()Coq=NpbHGd+b*8OU!w>xBB|6=Q zX$VDHD5%XAF{Lz(aFMnEybyv}v|1SagxEjDmct^@Po!K0c8VY~uGmf{=E!Y4P_exP zGOdER$zsDMBpO4s!yBhX$X}ttr-t);?lX5`Ct6pwWyQJOux04yo;3N>i#{*f(QUiM z#mX%~1CA}*LzZYvD5Vyk$BYVWICkecG%s;zUV#2&PU3yBr#&S;nj;74;lvCR=oItBYKbrqV6SdMwgnSpMtRB({or zCbV5Jh+PQ6RHX4BX>ZnIfoGfx4z8+}%x1&yTO{EF!dxKM^b8CN!!kjMM z#m(rzHUC<--Lv`ITQ9-CCJg@=z;8?=oyFN@6L&0+v22xhp#J8mg*h4R&;F7PV;hdh zibQ5Q4rY)`J*7ONd7HQW%gOSFci=A`_45nx$Y9BLPGfJ5fu=(Md-&85hUOtk>5C%0 z#?rd#QNyi!sg)0__C-+7byJ^&YvO)jbF;{nZT^K~_IaAk#6ik?ZO*Ltxu3{_49a)$ z%}_{}4{@D&junt$xT}rxfYrnNw+hv)S&*mT8|fDu=Y6oO>CPxe;{fXSd0@fy(J++` z(?cxfRk+W?TJk||lXBf2qbEfvTP(AcFP!l<&Hhq;cU`foz_*-^F(265Fe>OCG14LCiGT+zxuxG7>(K9<&XrY_d$* zr?bNj%KB2aW|O7K49OI3GCf)UH+;d`i%YW3)$1iz*3BY2B%CBg3T!LRena9#`Vib% z`rWLz?{M28-#rr=?CGkDRm%F|w@!9e?ThWW<6X7Y(|HbNbzu2@)91iFsfVW0?T0KD z;;p6UhN-VSD|C3xwp39-tjI!eXoVR3%stRkCejgT{~+Y*u_3b@$cPMan{uyg9WxAv z9{KLyA&fc@=KSEZ?zuax~>k31eZIb_{Nix|6p^xXbV(0+~N#M z%;A3nd#ZePNiLbV%}am7G|Dy9KE5P3)kh_wtWe0QsJf6@6Sp}+L2YFJp9|;VY9HZD zq3OxHf8-Ww$y3>%NR}I7)&^HbNK0`4Q&w$y+h$56!Al>y2J}is^w>AF*$sMJ)mlX7 zBKgJBPhj(jX5^J&Os1Y!IhA$@9W|y=qYha|glkFZGoU@p7OA0t&a{UP4|>}#vcW|f zg;(^P#Ww5#HWvNmzChpE+lX8K?|%Nd=~&Iy0rQ7S2J0-R92xY9{g6((;h9Ujd8>-< zFG;Z7zcc)q&U{Xq=!{`>l397A(cDb^pPYm5iZ7Wwu@t_1wwQru`aV1G_{MQ8Sz0SmPq79oJR*K`mN+c>7lPatPV-QLQcSG>d^t5MM@1dx=7t`e- zJ$7Ab=OrpEAXhoZ;Po%DjZDOz7OU_)`!p$fEU|u5O8P-qDG_pa7OyOul?2ob z0j}j~)Gf44yx^)I-^M(6;md`#*NT+XJ9iVUbk@@!W~iTBAHn_DHF(bcFcIVFQvrN23?q81S@uC8>-^?u|a(l%l-p&5|?g9^K?DN%T0Fc;=GME2RGrSo^JH zchQZ^F%`~u)6-8WKXhs(W&RvS>F{;;<$p^;Ys%WU0uVje#uG|f6`x@e=Rv1xefH&<)+MRy6MWcRy zWj3_t*25*0eydHXXV2M-r}X?sCi9El=65(s!liAyb1sk~%3=hc7wKqxTi5=eKEESh zWA}?}^CNHlZYx!>PQIISy#6&tcfId^*2oO!C-~-#$R+JbJ?bm_t^D#u^pDU0+Xzj@ zR{nB#*5Omt<`b-jWcg_R*GSp6kzY$d(ta zw5^5W0g2eSN?b3c9BT^GpNv(>OApmJW;u1~I9zEOcd-83g4+8AHz7*=KZ^bZ?{SBs z_4}7Rek|Gj)z2CWO4e$XSWz~miwF1l?Y|{{=+PPT+2Za` zZPtwOG2PK`3oWm|U%N^&`*+31{PF+lCTuoD??h%ChXX3U-Ff!cyfXNX-Q9N&|C&TE zSfAJ)GtEM{$yz^2dR$8FV@m1y%~}5yAH5&&>eJ@2LtxHET9aw%l-U-GzKt^v*7V(1 zp_S@kA4~UT{K!AJg{7v`NVDy^Vm+AEps!b@kNaDPi{HA@IDB#V-m}pfWXwH4b67Hz zu@(DiDrEPGi3pJZ82ln2O2B`BB_RJKgQLJs`7cd_qOPZ^VoFhSBx*S*>hsifjde^c zjLls2Y!>NR2C5o*tLSRO~#YY?Y<8}n5K{d<-2k9@<~!g*gxmVYT&{;k2| z`$_KClPd38>7OsLKaSEr+|`?rDa&4P@4sb?zhMr{s9$)a)ApQx{GHmt*Q$~?YPoOJ zcMNJL9o8#3Xe)W*xBKm?iubWC?~?}J^9N>vAHAFZ>gCc;*MwjDx6j_$@?y5^-j@?2 zUvG_m8SMJlQ}_0G#f$w%KkeG}p(1y3PuAqt*eBWRpJr|NuxibRsF*i#fzMYi9u1p! zE6jY#PwSDRs?6Ewj-Bh2=i+zntKV_g&Zw<_ts4DWHF!qd_cg=m1C#rPuJKAk`-Z+w zudYk4j)~Ng-7=qZD%89!(f*LYrpVG^r>=W}j>`sp#~1^vKr>rcJ4ZVw4+j^2bH2ci z@8jXO$Y*houON7F=yE}Lv>t!IJu@J(VeCdo%afZYkcCFOlr7tlWF(P(?$d^u)=ghO=e+FK*d0lqk9# zl|2)-?R{eD2VvQVZ3kvcc6~Wg_vL8&=i{yK8oO?sK6mc?;NazJ*RJ1raQE7moA{T$ z#&09_U!NZR@cGj0*E`=nJ)e2?;@S5P@4tQd`Sb6;zu&)q&o})`o&)|U==ilt`*O*u z=263~bptyYh5@yHZS_MXEc?{Q!)aO$X@QUmZ*{TBUdYV@uRi=9Y?Pn zaL#=Dc%(?o;cUi0YD&gNUk1PuWP1G-x791rhEeKOj0{N8DFpjdbD znG+8>l5e#{Up;g3(OKd1(SwW6o_ca2=gZqCSI?e)b_s*2dV$@olLLjS7BOSpZO^Yr z3>O~?JlFp6YL)$(r(@?jUf+;;H=^*?m%?e<^>qdt(1T z7rmZ4q+cn2&hYfoo*w>{{^->@C(rFyd(;=~e*DF4-LqOHHNExczrU^iF_%44AaL%< z|J9WHZ0yF$vyX19UGH|9_wUEI{lB(7-*2Puz7aTo@0#5c{EN2NudGb{?G9?A&sf?p;pL*k7*l`pM5rY)I^mYi{IqUknN*pWqw0AA90U zZOC%L7X*<7V zaYbWQw@dv^5275J%_Xw^m^Jx!2G!<<&y?^;oR`Y0V{122xuC-@F`Byk zxAaC2*$|LiG@4Jdxqy0=m^!Wr>9FcYL#|p62%_w5&iZWcFezWZM!~q!LC3%TnCXci zqrg>bzg?mRE5@XCnPX{hIgP5>))>q2r>@BaIc?IsT@STc6vX zY_PvoVhzr!7}=2CaXx&$!Cn?v>@GJ{lt#%-$!socEh)0^cFr7mIWQeUn?CDs-G91P z2z@cGnO!xOblGZuV!vvI(ua^R7NH=Gztpg+sy{{e#BI=_M=2`&n}h$p!Z7Je^iM zJZGMf4OtS{CDHHdi_Wu#jM79!NgnaqH!z~Z|0p{1aH!h%fzN8roUshXE)7X`Lu230 zm?3KoDaz82N>bk;3aQR4j4chRglfpXH7F7Fjx`lENm8koEU8o~l{W8he%CdBoNN9$ z*Zo}2{anv;pXdI3T37P+nXl6tVh(OBP9O}?KB@PuFg6_G5TX`etCxhXvvO(q$Kl;l zesL{dard~*q2!9pxj4}VP!qo;xL3uJ5VO{5x+y8ZK($bY5-=?=^BuEPL8zWNILfEl ze`tsll`E8rGtH`Y)Tiv*{cP<9nx)$j)LzjPV}l2$EpT{IH6tl=BdaBM$AX7O$4ZoO zW>jt%>5A5M?@WvMK>5%Wl!jEk8j%v4yM@)OdcC81Lp$=;&pofTF0s9AU0Zy^re3Q% z+`p{ju6$?bRE4?&dcf>(W?KrkH@|W9&$zy0AYGDhUn?WM@?L)ibm56qZRM--FGqGy8YCbLA^?yzw0aA}TS`}92O#?%_JxJxk zOUA;t!C@4Q3to*GhYv>e?=euV8$B3jQTEwkU)GbFF;cWerC(&r>N$10085KKjvG53 z1T|k2mn-bvzcp~e{`Tw_z7Ycn&gO7QSF&d4$_v>6!U~m*O^gku1^B_u*UA-|*2Qe_ z4a^Fm2C%jGdYV z_a~E^jnfq4{e>DJDXh2)JVIq4fq?tQC9wLc5^aA0d{>#*v1qNmBC z*+L+>V-LpyYqFD;6O_kQy}YoN;a9%HbE{@j<}!PabK?{-gj#VnrGMXAv)2JdT-EpW z{dJrC@SB<1Dg{#*6aPk~Z3m(^Tid;L`*Y@W;ahZA7G|$v^i`w_}cFe{44gjDm+WPX12419mMVx^3s#ce0$iQm(xy` zQrITuuVSTl(^M}~z8S4LM8zqYm8hI9URWKgVg)z6S6%N`Y^2u|=reRvC3+NNVn^GV z{&T=?cSTF@;P|M@==QMGqB;4;rB4GpxT;>`SgSof@pWHctBw6VxRLca*dVg={g!R- zx@JzzZ^`4{clvN-W1({-_0zVS-;e(=6DbfvC&OM1cwRmJ@YSx_Uplupc3~p%0VxX^ zeyYvHfnJT~g@6SOso|jkQ%%>;7q>dioN~Kf@%v7y;Qmcg%}~0@_Rl|QOpiB}(9eA# zYw+@ye<=%@wjKRN_@J0*f6<@ZgGN24b^aAsNSrGT$@sR{e?Oj0K6jwUGb*lr>v4_d z*ds4Jt#bk;9yRwZs+9{?cMgj$hpBhh9&LMcfUrf{+v((4ee+wu(rfjjzk=MGZ-0BR z{OiY#W|4Hpu<*k!j~m>dElhli1fN@z(#(ddmcX+Vut*x)Bmo`vZ8N07c2Zg3OtyRd>ug;=-=aZeNV(* zLeLwqlbN4vPuOFB^7URpN>=#3^C9Ide5LdR|3?x>laQss$(R6}mO%TOU4;V9dWVE6 zIJJ(PN(6FCm*6@?npOu`Pf0Y6Jytc(K1bfEt`S#%F6S%@Y#`>Au|VzQ==Dcdb9o6S z6&cRAH`(<*hE$W&G{@a9Bf!cju!>w%CI!zSWW(>*$&Tp~5!zrxu!g_)K=Sja^1COF zk4%Bv--6>u;Vl!HPg5cN4%3^*RJ3y%JKCR^+c*0ZvUI}!>UQjI(CH3&{&4OqhlD?@Vl zlt7(3_`)e*Lnr>S4{+uwsCG6x?`! zG6dnSPj>DPSYrXy3I)%x<8nd^h#iHe9f4ExaXc1S^Ii5G3oJ{$aMdI_*K2=8d+eH6 zfG4{cUVEVik=w`u&t-$%KY&sZShQsFqje|yv(@hCGj=$rijA)#ay@g-*KEfRUBL4Z z_?jj84&o_qBf^*opMYGcr=)eebr0UXOS)M33Eje05Lw>F==$B`K@GU3T#f5O@w2)n*IovWecXLRJpZ zpr(QKkiqK-9QE82`-^pIYOjz>v)+iz_SY$EUa1n|FUEp;_dsz6s9pj( z|2SU>0b-|AT|eMjeQfm-U~+ynyD7B66wfimU$KY-ucm=q2%o_M>xuR42}&6(;0IGP zj%#e4Vm!d36sqtfZ=tted@l>K%QxX`$kEjzrD_PcCX%5vfO;XJlSq(}NTU7P0l2Ay zNN8CiRKoHPn0s#^np?!+oxb zy&3-toXB(%q|}Q=3U^{_BvF^hJd|d;;V+gD>O}4JA~3F@y;UTGtF*`H5N<=@AhGI( zM7|NK(klh^{J_KaWvg+^*gepVbm~(nVGHI&@J+)02Ete0h&?e!Zj&y1pF4UdS=`hS zd;5J?Mh^E%4Tzitszvxl@rAct;KdTK|96G+v94xmosmm^S#@BVRbF(hI&FwE; z!V4Yxs=DvhiZ1Y2X*J>s+G0u7BJQ}fs}^cFJ%!h*&B+wwl^t5IPTo6zudBwnQ+I#c z4O8H_6xU?lkS+yQ*h;)9T&A#LG<+bv<=CD={D!@hA{APZ2mT7$vMdxR?x-l5!WB&c zd|2sr9(am%zZM2hiU>>Dgf}{blVU(FFntPlLI{fFa|aIG)EUk$&2Aeh z>pdaCWwDihkq5fsbn@B2DbdJ_VWrQ~V=YH1SI#E32olSLiM8$SI?sW@Fd$^zz5qa6A86XZXy@>!+o6emSO(g%h-3lXW#kgbSh7**&0YYn{|DEHygt+Xc zrzM1L)+4oBU_dRHlyzh5C+KZdvnBSZmMvV|~lQO^uE|uKyApYg%gU`O@Nn4Ob;nNv6i=f2}? zAQNh>fdKO`z#+eN?BL69!~JPwpqe!s@ONxD;?>08ithKgV=(SJ;#$~orS>SLn5HXw zMY)yB3MLtc&rU%lgJ)J#{sOP=KmGv$nUcOAEFfzMc$7DtF2=oX!hM$q^!0{dcKb~j z0V4n;40cHfwL-!_Q@9iuCwFPG^2BuItLf~3iTM{(H(ArAia;Hk@Vl`+SCf!iowa2J z{Ljy+X)lno_vPAq^|mkXapBe*4Y>NLv4Dt&?Txq_WnhHmK=sr@IuqbBfo?w_pQYrt zxsTR>%a5GRyFKl2ANM|DzM2e#xdOJXeHxc=f+--A1#bB`AD9jtdZ6^3rS$Df_rcFf zH8GTeqQnh*eemnzelY7#OaayV0D(wJumqf90pCTki3uDN;`U#{rAl$x761%Som|4H zH?K~?OE}~du1OK-gb|u2aGI|^=RH`M3z)k50hjr50uX`~7YQdN4*aHv=Vty{@Vn6{ zxvdx0>ktNByN7SdD;fS! zRinnO_zLXLvrq$9Z%+O{z%yduJLNO`6(E3dnpZ!UAHt=wzJMnlc9MY%3*Z*}ElTtS z$9{{G;!>G7P0M#1-Ct=Ox{rH>`zsHaZjl1%w_8qrY2E3S-}x+i`1)Wvux<4KmCK%W14mCz2dtStarH-})pz#lY(D%mO}r?OeBN>i3_k&!YXYyF z0ES=w@QeR%_yI1Bjmr{_A*KZn^^g5o(Z4q{ME-|yYUvwKGw?MdN6jL#zc_HlD}Rlv z?`+M(DZ}GMrhx{_L&Wv;jKytfm7|yRH+^4Ta2~5w)?=hBEq2a)-F(Tt6Z7Hu`mFPo zwA+ZkZ_g5>9QT`w2vq-pEtj0r;g3kd_-To2k0K^5#7ws&*wG?FS(symiwyZ z2G?(E*0*M`+S{o7Zsj#U`bv41wIYyF6g6 z`!NBaeQjS2`JWU2tscj$jr^1HMQ_tb9>eEfL+^qycW%t-QCIp#!b|7n+Jf?9P9OAt zDJe5Pif8gg^8I~^|E|bvnAg)%P3zs8?`8BNzDuqsia$<(jV`}x8|dOozjzu@qP2BH z1VU?;=uYZ?Z`qAN`->&!X0s&v_PY1Yba}@rBH43h-B}mRv!?Z~%TR_A@xIdmGe+>S zVPg8uV+sYXX%$V^To%PM!dAK0Z-t{P;@wKYa?1TT9)xz@-zfhxWoq5(w7}# zoYJ*vvwA0%lt~7k?$N1%o*Gp{Wbf~F{I#p2kKYs=`*>lCoBx`?w|a==-c8QXo{eHf z6#m+}0(ZnCw9s|?2wDhXIKtCt)CCGL0yT9-aqB0k&`!SZc}}}a;-mH3BUhk=Cy3S9 z0HwWma<+Q82M4b2=#sJD#8Zp@p29nF35E_D9~g{qdi+;&B^Rf!Dh2&t$o&P!LLVy> z(9={7G?ahQ%u;g6^kCR?j{mx=WNkf5r&xV}`h6Z=yYi9fs@-E*0O36Q^}XEX9AlQ$ z4KAp7>qQ-0ze(}!RU`WH{{BnuA0E{yXMGT%Lw6nCjPa+TR*^fEBECs8o~ZpKBA!j_Z@A$R!#3uUF>6iRJtr7OSBnbD@Gf25~kW5Cp(rYjFdKT1M_ z+_0`g`42w%RFVs}Y;sM`>QK#IyJG74Q~6l<$EyYB_7C3Cd#Tz}Gt+zg7EjTsZ1a;E z$9WO`d}NVty+*_`ajI_Nn=yLA(f{J^DfB;ImK15BA7)NN9Usx0@D=GEjpf6s*QwFj z*B<-05mblT^p0-6o%^@MqOFgAXxQtPogcrdt-NMG$He#_WX{3b@6E@t zQa?=(%)bm?xzhxaaa@Mo)ub7}Fy^nlR1x~o_XhFFb!kSH&5(0*Qr)JhnV28qJ5`{8 z>5I>skNz#c@JXcrn8sTvZ@xk|_$cjg7^5k5k+rufA_f|CJ#=!ReuH;xm&NrDpzu@; zab^X<%_UH2oANGl?@{XY?tA7@)`X-LCXkRI=hUNhCiIu+DyL(}wz-F=m!h)9dSKZ0 zBN+M6CUzrI3oy=}3S;&fYGa-^QTG2bi0HNvJEg}S&aS<47S(ZaF@8}m$D1$uXnj$m zee~?~vpe{2k1ijlRv6W^>^aF^ARc?mPlB~y6X#Yb{sxN5%6kDmNB9Hhj6o5T5!!kv zPFApufpTs!UH3KnmXXne;M?zJIoq$}pvBjUom0>CjuZ$Q&MuhuqVDVb6$v~-aZa`H z%yvwo&f`Td=tzf*a$I?JVnI=V*Udg<{54#bZ9gZQdKRreZz&=U`DC+0O1dj_E*Ixe z(*eD~rMC6%&l(TsiRf?MwPdBS-<-9|*zYMnsX_I_`x}k|#zzGr;)N$UOFav6dw9XaPkkH% zoZDa`PwCj+~Ua#t}6+kQk4~MJ4J4tfyQdGZH-SB-xtWu z`#ZDd6mJ4D|0CI(LzDRwvqLWqwx7K`oUD{A9tl&JUV9q_DvfZSU!BB0_}`)Il5AGvEV6Wx(MuW*Exm8b@hUSnEoxgukZsP({(Ruu!Zc=XMd_|95ju@Az!I`W% zlziintKOOi6Q&N{TVp?AFH!GnZg*ijUcgnnfAz{q+$udASL&x5N|meqyRby8P@T8G z`Xj&@VU=Ccme0vN+MQ!F5dyrbV5LUmJcsmYS~-0NAJQ-n=9woJ*{y4_BWjqd6{YC z3wmddBx_5B0WUo|J2=I3Y4ml%2BR|%V1%*N1HjV-VPMRfEKR=sS{3`#FX7nZ;^f9F zUH?&0RSM@eY9t%ESgz`A*>yxn7n!|la1ylbtI(oIS@HT?=>Dq#2WNEpI71AhpW1^=Ia}cO zZ0wNjUB~d#yBcN`;)wKu(+vSNJHK_Xq3;QtbBpe5TcwNgm^G{7&7Zz-%xVj_lO-$A zX2tlpEEWTCI7lfjPM|!#+<0}C@+RqV`GbG}z5%hIKRz)zcc^dnLE1SZ!+8hVu6qft z+s}~|Hlm_6&e7>h1*f$(Ml%mm{`9L^wdOd-oDFfB&OWg3h2h3ty<8TusBY zMUOZd)7VdIR+rvDhrDUwKhMrk$5kIa@-L5Ds|I7Qy=hhbUv5}H9W3e|*!f2OW`YRK z9F7cj7}8f#Xr>;YTz`?qxvT$$P1p6^aC%o4O>adg@DyLmS`iOylzf>Ie4=FW8w7ce z*9e&WVK?XrH@Wo--bbdI4ZQ1wR9t;eeE<6%6-KeocdJT?NY63p9v z%rS(=+X(Pq`qk@<-I~(wlKHDE3we}bK5cJki*VSwbxU+t~$n|(;N()W9t+)I$tQq zz4Wcx^&46Z()VM9h!h_V29Q~+&ozf<;X3!szP=(H7E1)?X#*fWf9%ie)Ex)HsnqsK;*wl4^6 z{FPSwJR`;#b_V!1#k?^3dM6m&a`>Mse%I%R@E090yXveD`ii~0uRDp&4Mx3e`@Niu z?JVOh?OA*$ptb6qh{3Y7EJIVXdZr6x-NU@pC6bE}?f%)^St2;@EeKmZqnH-zYA@;} zRmu*r0y`m&X4s#(nB~`1#Lpe#b`)*pQcDhWY!AnHuGs1v<54>tWmWYD2Y6H_dW$^L zM&f8~OrwwotN zqqy2D7VTKvtpDy7=K}BA@0$D;D^>xo#>ssVeWz}@(Y(;tz;Dog!l-WX-urSR-5JL( zk7auD=0JJ$abCT>w_sIj-!~&j%d%%o2}&3qp5B6_B?xTvaUT|>#`2(~p*z&mSlyy+ zadm6s9K7W_-C{6A%w7L}hHWg*mN;TJ)qlp2hbN*}twVWCzK^9h&uWQFSwSU*Z@bHnLtDbKWSOw~<+Yab2r}H(LL&wey6(W7eQa5!zK+OtG$X;@MZH zb=kycMWx-D;cPbWz5deU{@T*!qe-^QR~WhnoWs6uuFd8J##`1#xuyYXPFWBSGWj6E zJu9`8Y3$1?tw%{dzxlT^456W5=_$=38h-r?q@#D&&;>u5J;mqYFe5;B#LgS%PvT7n z^CtNtGE{*D9AG&VU>C|uf;qOuh~lxkPvv)=H1pCQ#2T{lIt^G*OIzs`KzsO8*Ht{j2uHT2G57W`)-Z3-Lhw4bhg&dx3;(* z+Z1)?z5~FshUpBLm#IVYnkw72lRxK=@nWIR$8@*^&{A3GQJ0})))01mu#jA&8ZEhP zNctVlPiOIyY6bRV!vWzVPcQ>#|2$3tMy!hwHkuqODeBoWN)~{uLs|BGk&3hT#>unL z_z5mW^9hyhqss7u8#G9Fh!E zWamLUO*{v?g`h`4e^HjuGb>|(+6UNHh%j5>S}bwP`tLqQqa%aw zDwA)?VxBff%R8WLS)Jz}OSY?`!*-j1lf#4;g{)W z>uWeZ&qYV6w%69nVnBb<^`xwDqqaV<3dPAkzHzP)=Y{C=8p3U6^fK6C&woQV0(cX< z(fMa_sSqxy*d$}mWcHLSy&e3n2)0F!r4|d4;9Kt7MmTB#*2V&Ba^Q`>D9#7eD#?MP zDufFIo>(rRtR$%5gU`+f2#yG!sUpy33*3?npB;I3BldJo4{saY$io|>@nrOv>QhR` zbtS`*bXlo9cg&u7Q)kw3@<0VEuX!ejUqHW~VB4vAt!4dt`nBM#KdJXey8Aowu5VR9 z&uhO-660)x`EQGHvW~-Jl!^J9TdlJK3<&-+%rQ zBzqoHka$YRQdb_ktbg=qB;evK*AjuIEO0FxkdHl)Pd#^74awY>&(6%DtjGe+S)_F_ ztb*WK3`Ja=oU&RPi&)RI(nMbQ)*rd2bH-x(^IV@D*O-bC80XlI$!Dv>406E61>YB6 zeNC=EUomVw)c<-8Ga4On%N`i<-O3M)xjSR(>8Cpr7>+IuHzn>x%li%T;;okt12S30 zOAkKr5BK5kr)7Pe)B%(_Buyk`@+vJ;y`ni_R}-y$J#orGbmRBvzCgxB0RuthcOUk>VQ-!j*^KTEk#_@A(RCIZOVG4x-zCU z#g!R1MmHiYWwb5UGj+Wu>Vq*>vC}HVK$Vws!aaAjEB;#LX6_Xoo5L@`-L0&9mI zMI)&3^#bAp6sZ`NsSs6R)CM-n)O*fM$X!)gK*>N57FiriB5u1E=j?5+sT5`65T)z2 zEoeQ@f*7H!#?zXBZH5A@Ap>g$jLR^60y&8j*VD42)3%U@+Mz|9l)fLady>cd-4-fI`7Hkq-+{n z$D;EOE?O_WIb4j(HkSNz#G8+ia9zV?8H=u&kS$cWO@ekA3z8LKK7}%cxfWCL8x~N; zFv_$TW#$l}a1v!AMyW1vH%!EnWUWa=&Y4RbjRmgSgeUBTe0sm{;c2L76DsOR~FlcVB zRzM6ba;Nna*P4kN`T8-V-~Df!AeGH6ePUEb;Ei`VLJt@><|a56f`_((!xTX>6pq3z zp44=6eDT~~N+c#tbZy-1u1e)LOZO*%*uAum-L|2Rdm}nL9iAi> zOQHh=>8qj3n!5T)B9v9iJQWH&Pe7X>2EM4z+S&?wEpW-kg5+WWZ3~OOp?`C!;JCwN zYA7z?d)pkBl+O99FYM@wG8&I!_sfBYA=Jm50v(Y$Fjc_}^7 zd$QjaS7;^h*^qkJ7-z&rscLdeyg8(lRJG8bPcFeEnPfcWxY`g`AL1AlBQ?b+gAT4q zF*mpxWe%Mt}>1@G8!}nfx=g_C~VGTqqb4DD7TGba&bn%LGJOwy~sXIxfRcle)h( zW*TKwu5G=m8%93H`kv1Vs)&EvJ3pzJ_(j@u|IXF5_litITI1h-SwCECvv0IqKpxFmlaSFk<$K({pc%}{~aKE;`R49rSLe5m(+tOjthRnt|1zGUJdr8p%G(YR>D%q{JkQ~` z7hy9LltjYqYK(~`4}h&~jg2@Oz|o-Z7(1Im;_jD`2iBLd2h>)BiYO>jSa?s!?(kUa zM;hUk(=RksPn}bAJz#FISu>_+$y0lOO3Ti(`=#oc2XY%}fu51+fy$abiFb4~BJv!o zHFh$s<<7_F1wL?DF|T;$vT_QUsk2;5->l9O>3eAe#ZD8CZ2F}>Pt&?6^uUJ++lo}Z z>eeYaFP8B~-M^>)GN~=^t=#P9JlD6`?dPe=F{gKst%=jTE)FZN8^fZ>yDdw3N|ah= zAE?h{@qn0YDT-j{UG9M~6-qtSEQ+TX*+C@h0o5(csHfq^&(*LU+e6Dez@T8x06vUb zT?|5TJt3?Ybw3BxNXH92b)qZVhIDfCh+bOJ)zcHJ`_;DXr)d5?;ZuF#Re)WAhKB(r zQzJdWT25!zk%R{>xz`?fIaO6})ON)>TE{SUF^p=@6|KKe-ECaU^w2OC?%rJWZb^gX zR`Ki4M(MY^XC6917jsOUz81CR2QC(UrK*~*z(_O+2<%hr9wgIox=D~Z-keXt5NvCg zFxyQXC?4B`vxXSgpYHYZByI8UA$9}?BR%nk5NAN`Xq0uz?(HI}=41M?TSWpN&!}Ff$~gF=gZQ%El#_y z1)g@9V{&R$x5rFR(03-bL};G&j4x1Q<}p_flO`^;<*UBO#2)j#D0j>C$IF_cGcI3e z=_<}&G1nEHS}yhRL91A%q>1dpLSm?6QY0X2fAavSNt8Z991~?4TZJ7>^T6bI@;7u_ zV4lDp#MS{+*CS7?nY0v)Mr4?VM|q}bh12=hu%!N}P0+nZYVA{{TKdfiI~TZ`gR*mP zaTH2RIp}`>a`9}oPf`rCZ}&aJYC{vH1P_l%wavtq+YUYH2UbuzX?CZR;9=Lz6TKSa zl1!trTvn8@cPULXGmq6m7;#3DI-*g=#q>4vqOGG73Hbr3SM!fxp15Zo>H0%DxaLGU z=rp06uVoG+)oKw~8FvP2zKSRy)xu9bm^^KOhNFsPGFB-ku7hl5?huCQwc(o(IdX<+ zvQ3tRd$TDKWJ-LO=fBV-%L7&>-6$ElIAc)0IUx)&)3v>LofU+{MvKmBI#5s!o{ip@ zbVffLS7a(@_1HVJj7k)zilCu<+^$+d}q8T1Go!eUKb zdREO|poXUkOR&>_y|LRhC)LiqyYde_9T7qd6159alWdmU9yX*^7>pIvn#e z!?6ziSp(n}?}wu(N2!bcwYEzGc=zuGN{>F$H+(L}IZN$N9|@n)l*p*MN2J@<4vVxm z7Sqt&9#}^{3UKJ);J6S*m&5@!Nsxq{Y>YaB1DG4{$J0-XZ3n-{HM96-4GG_k zMP@G^!0pze9(i3M=cP*defknYIR~1gtnKO86pMNmO6HS?V6=g_2Wx|nm)TuV{k0r9 z4+L@)E(Xhmi9Q!Duk)+{E=!_1rWsE-~8{`Rmo5lRSVwGz!CGB1C5A*HX> z`&Q#phE4DpLRZr84xL6Usm_lOQVd~-BpDOmt`l~z0$PsS5gDp7ZikH!IdfC=zGTg~ ze)LL}TCDoRe#1u?BZx-Ilz6?*<{N(PAPL(>Zk?3>xwdN5r>?Nf^he4%857*gI==-e z)AF`Ism)Ys)DLpfd zSNjJgnxP6C5QYEqFYf64V@xmxdeGV%GhOcPwuy%<93!7$148InnHX){kBpk$Q%=|{ z3`t+VE+ZsArFuK1N5OlEKX#73rfKKuw$0Zpjxy&M*Nm+17W73tPw($rbKgPEIzK8e zBB~GfH1>v4eCf)XV4j>?@kdk=b6%G;jsDN*tIFzeo`GTcuEzTIlr>SuKFV5zB5#a#vRZwMJ>(l`uv%mYTkHB(cgZl)(6hi(hi)tUX7=h6}CL zZ^P&7cG7$!G-)x{q;VsQ=kT22X&kckUZ#00L z#rtH}kB%EdMSw_xfgpt?ZRgpE>w$vm;Wg+70^x@~xBk9YfBW1deX&|vE**V# z<~$o+o{b@zx(wUOc3G=C(66`kDVe`g0+2)*^3Gg>6YiLcc=Zo<@}KLFB2!OUlSUxZ zu(1eqk)-b@B!}T)4Plgws;evG??OobQP~o@m<{2JAvN76?JQ2@p{+sgp1!VLRxuHG(zzC;`1(lTDrmm(w`D=7#PSvI|lcR z{=FN15UEu}!wo^5u|0$=81zT(OzNMAC|6}{S6!N(_@*a&9nJv;`LJ9bI#9@HC{|iy zOEw$q7e0&FoE291mcKc@&(4@H0BqPveJbYtFE(XFj!dRK# z*&Bf!lK^EBwIjM}i@QO880-j%NGgwzJXNE5srz$W@DDcQ#j* zRMG8?RGVB&s?3PGCBfuj<;D2Q40jI`jGp{}FfL2Gw_^a$vpA~fBelnFor^fc# zrLVU)r`vhcZN1U9%aGl&f)5;cS<(IGCvO5rdzbQO`Xrstozsz^QB8!ejcyhvH5 zRVv$I%a+KIBytb}B`d6~aFGBV#gd>5Wxw*LE2UEJl~4Vl*iC3 zp&ofM9VMF7Tq#fmO4R(Jbvdx=Qr6Y8aJ&Z%=bdTzZdZ(Bk4mjXeQB4fLl1sPf)OI{ zNf3_8(fy1&xf1x$dr$EA#n=J*=3)jWa_Z%+K6`ebT`Zl-7Fl}G?c?e8j6OSWo~=23 zXLFSu<&u)-j3Swn`AdT8UZ=Q<38%i>V=EW_W)4C8gNWMMr-lYh2riY=Cfo8r2wW|!l!x}I+=B9`IuTd884{gT z+)*d#dzGQi(XO>?jHAk6d-+woLw&aX^d0%@ss6J2c~jP_h^ul)m05(6F)SAYE6P0A zZ(k@Qs#ldY8)~dDggoFCc;+oq{#|d#Dgniw}{VV7E&V z_#zIzIAB*i2c#lND_Aul-L_lO$wxRHL6AawZltcSu92UhG7>R)pWEjPmM=gwBSCOD)#tJF|D>GDu%IMY-SyDJ> zHlV1myu%B_3dAipSfQ~IaRkOJKE7Zuh|f~ER$fL*f&qxu63%&=*Mo;3l7BpYc;bHH z1dzv6HRq`Q8Bk4%*N}MQ$Ph9QQWGK2Y{;`BzI`bRACG*RM_2u$@^2-an&ydbl%(C3 z5K=No=15g}@2lC8Do0pBX8P$b`J z4_R@q$}X$PjvCwPNwF1GO$VZ78S(FGb!?8@M$Pj2rZu6D?XidFY*Q?_k$tu-^wrxI zwkxo0$3Y^3wyL-SqyBK^NC)um5lSluiJ|DL+Q?}XN12RNGCz=|!XcU?6gEh#yp1U2 zX+<6+$81JB$maaOVt@vagy;zRc&r2>El0`?Bh(Tz&{;BV87#{P(~+?qWdUjo&QUL# zfimOXcb2j>q#N*Fr8W&(_)WwI&eKx$zJs2yreOWS<)klTUcCmfW6IUr$ecN(^ z=+^&9Y|BdJ{ONY~W=g{cbLKAn+3id$0fheuEKe-pZHk$we4k4e~fPs>VR>59wL-Wm($%*0&@sTIpeh%hkms{A6=vhxUzk04MVg59vv z&|4#~9z(aDhjtwG1_a3gDX-Z|pmJP-U;-6kbPy&~ZqbPdBhT#%)+w@2?+gAKVQzH6 zWbFkz<31aB4s9kz3!3cHKbRezLm%Ze>_ywwez09-(yey${`~^y>_lhn;@JXphpz}* zCQlK8RBG(7ef*(yXPfevs09_S7>SsPdvAq7tK3#cLf?~|hh$n!h2cxG%@$??flabQ zF19J8go=j|zz_rkLxJuHrLd$O{xC2!i?4;ZON!6kN8t0MM0*-(3r8lP1Q{Gm_)djz z2@r$yONH=IkD3ss8uH`3GGJSBK124>3! zTCLTagI|Q@T{vK|86i|APe5X&uuAQ&(PBC?EAixu0%tbeK9uDW%BoE(#m@Ix+vD$x&9Pl-jrd_h`Gc}vmb{4UQ)+Z**Epa8 zd{nNDJ&e><(WNOGa*>&&sx>Jv^%CWG9A4eYO zqmJpNXu}wclbQ%hNx0dDG*u8Hj%`QEPd@x#KK;Lgr--6cZFjFC3yvyCNQ5CsR+R*# zFir{)uF)OM0h%%?_-dN;56_vr6#P%$jcp=KNvpka-&50$t5@IE2c=A$sIn_gMxDH6 z$67^G%T}lz7R2R5I|R+1)koRaN10u*nQ**%rOpElsD%~O zf-#yTS@)Ce#Df%K4gm}VhI!()3@L4kj6LkR>TM8z)H0?NR`6GeeKj}k$pMDD=1&0b zVMupg2x_7nJ%n(l!)G^-D#i;{S0HLE+)3?`kC$`>^|-GZrE)y6;VSYjVQRNwg(AAa zRf#+smZ$WTwrc=HnyNTB@EN4seSt2Nk5k5;^t<(gdCPwCi@l*% zVZeuzgJ}EN*LE%xi2c}(t#jj`w1f7-j#$#Z2e_p$YxH5$>HV&i5%0gR@^;(BJ*(c+ zXV)}g74^t1ZPxk&j!1S1*M1b$KUA>JJAU3F+E9>zKr0$Di84hNOCF>O#VnYosA$X( zQOXC=fW9$Nli9<_*764+~0nlm)byUdM- zYYF+LFbB}ooZ{d`y+{mb$eu##n35&lKs<$$tsE?-$-QETWaztfLW!Jd$+amC7}-Vx zv>k*jlujnI2UImj(8MbB9SE*Ax2(4X8zXw1tyMS;Wti44aL^i;M6daHIRaH`Y)13| zjDjhg%r$#O9Q@&Pp}knebasW0seiEut5Oo{k+Gp9G%8CyJhnVT(;OzDwUas|8L8E0 zHeGx-JN>3RBK59r@?eX8|WRYvDU+|{iM&kj~Z#a@V^ zysIw#pG*I|cAWU9cW>fdi^21|(#S_A73qICxHuT{z#E$Q4MTUtCDHp6IgZuCZte52_haXtqDN7!|ux|%T zc}sXgFNjHcl`5p{>`PQ1{BP$eUZeF435qqKlHz7SJ(N7Lr9`K^!25lz30aR7A!A zM;MJTax#vKQTHbXG?KiVW#+SB04dOkBlhrh4tXR0uC*Xe<5k>-L_DyVgu<3V7zLPy z<#Ui`c`V%BtW24TC_|Htz;H@Xgm^O7#D5xZo&uv~Rba(_mTq|=P2P!u++ZA~Yd*VE zwV2FX3rSG)TF$e1FI^2`9bg_yBgT^X3NZ-0`Vypa0?wC|^Vs~yPhN{OJx%OBLjRIi z$L(JgoIWYNvJ{m8CMCIfd!RT!ZyQrNSX1MGKa2K!CFT^`B$TF*Md9P~B$${W4qzxnDv!dTxmbd=l)%dV z<#JdF0&h;_fef_Hjs`EK6BLXIs|Q2QLSSScq*NS4zFV%)4bW^|rsd2c!pr~j05g*L10 z)0xjfM1?Xu$l7<;q{5g4vhpryNMo~TCkDn&Z2%FONXw;Mj5&l6SrVCk`b8N5aiMAXt~Azqv*^7ng0Jc{`u^)la0A&hR={( zF_J6CMkGg#R4UaR6+%-vlJpsxTQ$%g$&-vyYIMCMSEdOgZYshuM301Y;LvQvaun%(r|K$ zFs0_rF#ph4==z_YW?^G8vagUHvU5@`1y(n4s81yAfo)Tn;%?);#o2T`QU`Jr%s>D{ zo52t<6o;)AQ0J(4YmCgPW|j?L1DlPg#YFh)^flK6~LJ(&nY(KN-!x-P#` zg6zC;a|_N_+Cb=4@XyIU3{M%_%&Z!>FAMb>F9C3&0Ez&8&U^2vLoIQ@1_;_zT)9#e zi3C#`3u5YSH|l;AVf>v?T4%&)C3Fb>+XWW67~!d!wL!}%t5@w=-0-YpO_}uQEH3Hl zAE)CPC3;`VX@?goNju>vx*B1x{ZRSU>Er|VrxSZT{<$)_cNMg6`ukARwbKQAe5)y* z|9U%=g2k>+{5?}f^;cvF(IzmRu(}D`dO!#%>YqAiB?Q7sTro@$gpLN#G~@y~6L_U1 zVnMCD5rUYBeqf)dZ0BT34n*7&c2t4i-iZvJF56UoDaMW_x4^n%j|Acb*-{>i7+?$ z^pN56{Q9)h+MKkS%I#m$=s!tup`RTPEKtRdQbX=C2K!_N3Md| zMvU@0iJ7DUBh=L2#sSbGkhDbDSmy+wV=hwAQE-;JKt#|-|LlzeQ0l`Htm6WpLfx5V zMCPF^$>7bwE$_{2ME1%H-i#VDhF}6vXuW{4lcZQ-dQffg?HH=uo&Y}@XZI^YF7 zv-Mo~`M(mfK$uQj1>@A^GBa@p5I4#hNPmjmSo|EUVt@`7IH*VE=ky+#Jgxoxt$6mo(TDnR7StB{R86=^F$fC6 zb^9@T?iXr93X+C9$?>~bgxce?zH*>S$~06A$Tho7fl!yK24b6 zW0)}Bv+IYu2r7p06ef-@!3>Xo=wGKl6fPaMQP)~JsX{Kyz2-667CI4rpmKHYNxOiaQREKPDSL}a6o5EVAAc8y7)UaJq9v3Avo#x36NZRX&Q96uAS0xLyppht?Zj zCFSW4tW!^H++_CE&?;zP%QO9ZZIpaax3Q~w(cok5s;lZ4xh6!u)aq@1H(VFb)lCnt zrA|!WtHeooR3ouxU#rzwit3Ap!KM049y04W*Whg^zNfr(6z!$$6U1bm`}DpM>kDSuef1f77?hY8CS0svx+EMJXM>?=+P-P_sQpCoM0tXtQ`)BTo+%P*l$%bic=`AjK#cZ3ut4 z{S2Ia{>6Q=V+w_`=AaahSv(At$7B3BXxTAL7zgEtpr6!Rw^zOM`viv61C1Zcm0-~C zq5WYH+9jge0bs`X5rY{(lLN+zw#}MjD`1qBJu1T#639W+7nG)H;KW21m466E{s?Vw zTnSWr({U?8h?O|G7UC-;1OW%Lk*U}}JeeTFCy4MgKYY57X4J3t5!6rk=JF}TweiHg zwCCpkRn`budgp?tN*b#d!=JsH15~B17_M9YTp}}8Pqv>@+LqW-88$PmC)pW%W06He zf;J21FluFuu2LdLDAuk-bZDH;Lhs%~`vu{G@+L!4u1N$dB!w?16r9@$0Zh`-a zLsl;&0NS#hcn+8iUp1Z6sS76*@|G(rt|SbhL}vNzeuqWWS^(<=Kx-MOZZuYz2{K?* zHnPlG;_ECy`K?tsaT&##!8;sBWpecoY2Y$Bzq65$LgsQ`3GU`~?`$uEHG(RE)t>Qa zyX@AUzOq(#Xzj|}$vS~+!yflPU(8-+Y2NS;(%PVPwlQ+WZOxZ?7VkBZZt`m0J@u+( zErwiTp+abx&ph0!s6@^%ib=%4C?!ouF{-Bt|HR9{1QB)799Ux`L6<$lQdQ5zA(&XE zB?CAd%N%>&P~y&AhGT**9K1E>paZZ`gGnJua3u&-x;ivP1kF5C1S{dfnApzmBX;$2 zb$*GpRe$d-e8f>GO@<2Nqng&?7{#cx6LY&}u$eOKaDe{dY6Th&pXRl}_npGusEdmX zmhzfwBiHIB@BgA1aokR`Io!R$e+ob7I&y>U>|p+MF2dV3>To4^)t?%orZ+l%pJ_yE z9|zu>>9w;6x9Nni9IEFEK-(YC7BNp5DNGp9eR_A280E@|ri(n+FaT|4$QE;@P#@G} z!ME*JYc?YIy8PinTj0#)eibHQC0bNeMLGv=qS6sa;s7bE3{9ru(b)d{B!z~2=O=NN zz^JMK6d&-#tD@FsLDH*ucMde0g3IQ3?*mX=nc@~5d-MUD4&(6_A)ZX^qLwHv9#hO* z%DzbJudEuP|Lbt)=w0KL2kq8D-wh3_+?wai?z}MfxE)G7IlcBy&Ku=~nhH}-|Ea_fNBrGy&|HwGxe{A#}xe_;Qazm!efQk35vdV zczoYSmccn{-Nm$LKkO^+(({MBTpw1fygX~>eEZ77xx3d-ExKO*W^xalZfe$xwxA9C z-ulm#1IQ+tgr#?lb@tP%w%eh*Nr2*;gi}Nc@J^)#aLOXYGIj{_PauXZyX~?I+%7tu z9h1HV0T+r+JTGfElG&-rPzg^D+sID41K_!@OW*P26`mH#loty+hCyxg7(1z)TKS1>k z+S0Nm21f1sukJZ;pPtVwJMiE5X^glaZDE~l>5EkbPXep76aAjX)P=e((_6f!Cuys` zIg1k%v^kkSgJ8%&23TYOv7>;i1ZM?9eAFq5D0D+TIt)fVdWUsI6x$al2N`HThS6@O zTuU`P0-m>(_?)OhEi&N2Wr*h+T?pzAK8B2#xcp1oJplAjL#E@o#(pbo9S>6z4lSDaZ{y%P+o0sYrO}e7RzLS0J(VZj zHumzq)VJ<#-9z|y^`k$>?-toz8KkxT_`BcZ&YQgVZ%(o(*&x-oNY+uIdEKApTBnai zOdVSgU272(P~V4$MXUT;rmE)PW2c<@r0xKd0y`i5Bim3p0^-CIg}&BY(OU zP2Vw!-6alNL``N7soNF97@Qx;GR3KY6Tqp3viTU%qu#>?A9#O<=?1{Ww$^kM?!)Vz z>*w2#67^it@wQc+$22Xi-}UU3wWiBmTK{yDDjfHY`s{<8)nD}`EL~TKK2~hNwa%4>KnSBnU(+sJ$`;@K#fM;oEyrN9GPZ zyb4H+WMyN}+R`Qthl$1In*)|?x|djQr8-&2X~tr37@Bb)$ocGasduytE=edTiV#14%wac5mPOP>0h1OiVlHNsk zTtn&#aa?=&t%}1idE-f7t1ZF;2qy9k(YjV-1k)!!` zImO>l7yL(#rVBLud^NHSeEtO5d0d_+1(4OfBLtesmJyC#@i$1Q&02hB*#k5JVzwE; zuK-l4*sD-NUcc+4jw@LLXa$hHH65=hOL$;7CJikZ=HdUGQN8!hFbyF=J*D9SLK1rhOJCR)>X7fZ!SbDW21Biu3D z>w84}T0M|U_9CuCe_hN}^0fcDO3hj>_F6HzjH-~`#aV^UAH>kpL$t9i!nFHO0`GYL zoykfOPmfKVSA>kai5&3OgY^MYi%D7b+M;)bw*oh>yv80;nS02SowJ`6tSoq4(p+%K zlDPqrrZVqhQ*TMIDE5Z8*f!}I5SyJCHV6f-qO%yP^=vN?ht6tOayJt)@t*9F_Za1S zwM>kf8Dj}nb(GVFAufCZ@n|xW3MngC^BDD+Ny!fNIK=>?Hf?_!T8AtH)tp0_UOznF zF&<#@?E=yGo@WT8pDM!-$`Ix4a+GNk6X!1Ak+(~;X*Zb!)-d>+i=cJtujEgBnd>{NIre zAotW3D>xHzvbguQ>sS#OPwfvK*^e%~9t(*k>nP%j^>jDdzrInlSSYnHHyZB_R=-oA z*wr_&b5`;_fa*-t^4_;JNHMS{Xf`RlVCtn7q;ayhz>IHw;Lxa_j^)NB%P~yQZMY1@ zF9KC0I|DX51B_TQMmH`9y%gYSt`ujgQ2;P|+z3S$=|~lVhUddJfGR`W!)HLVJrYQ9 zSEB@7iXmKPWUvp9L##v*qW=j^s{!z%GRQ{%2`(Rd%ZS2q>TUy71ON~B1SSN?5#=x- z+e9kDXb88ED;RY;GaRZ8-jmeLD!lb97M|3_Bg1~}yZQ$cbc5Ed*dcg)|Elol$jsAv z*Kf|s%lyqJ^o;BNlGlQ+zkXo(?11ybF|dI zz5`K3!t*&~V~Uw)@$TJXlvW&*qUu`?F{znaz0-ik+}LW{Qb0jI1MTITL72m%UwF1o z%~$tq*m`75|K(;~_Cwo#G*N|22d%FnI|T|CK#JhCn^=1(Nob?qFHTOw06tp`8IpMr zoZ7A-kfL!)AYnDaQ!WvqjZNC{s|7X=lD5MA(I?!dSgH*ll)`f-Kf-@Pr+t2Z7`o?o z;;MD0-XY|cBXHQ*>~XNL`9Q=qwCz#Pyk&8@`pTR8rrtHKXo&l0r&sK@@%@csU^MDl zZ;+1uTOB<)laZ}f0Wuav7RoYzZ2mLQWy>1S)QpF9vH(?U8vvD51cg84yDZtKR@upT z|1$1#g%Wijwh@^#fk7 z-=ZY86^kwgo{5P>^TEL^nlB_$33X-g3s3m_j9Jc2aD5>;2xw(p0LAkXNEL~Uj^ zF;wwDl1WG{FHolJxA$Ghs0;gr=%8i&klQ57=^b4)YPKV^diM3@^<$6jzAw0ruKeKP zes2?pb@poV`{Ox|vtktZH&;&$FnG|4>ETw%8^Vb$9k z=Is-=Zs@<#pM!NDGWd3-ipG~CgUtZNKbT3xw1Y*w88fL zMFd0uHzDyAgY*I+KHvhYe2h^NP+tPduwZcyu-Oh}C-cUOxZj6>gNbR%ur7t`#tjAp z13SqwfW%3wHeNXJkFQ5Z}oHn`dwVv5b&$!He|=q?A_ zWS~E=<7Fb`2gF#3QJ!qbM!w^}ll#5dM;G12(6}gYmK9j}Vbf|{#{F*rcT7F0V3L+8 z+5Cdz?TvxW-JZJ7)ch|6bhR72fnjo0#A9uZxor3qH`J+3<8M#$A`TIpjDQ5r7)m@o zHC}l*(k(fDz?ArmOnN0G_K`_cx$*^j-LHjY#6AYn&9J1u7%)zmS zyDSrKEvhD^dg^F@09=8m!vEOeAhU)vWZeL@frKv ztKyP2HiQE5KIlSiT!6$zX#mC#$k3f^qmw;5wK;|9ANKwz_C+%wA_t_%wTWWwN}kB+ z1?VuG_5>ngIiNN`Y%-(zh(W9z^yPvyHkv2~DFfvm^8Yt0^a}9iN0cR35&D4k5}~c7 zpe_06>o#Z&N5xNSuE%B#0xDmGfnVBk(g!QgO27SM&C&PiAWC*#@RGz#^Fed(o@IA8=c)_)cxP7pBf~M{5m^&DqiaZ z#V4ECBU64LA_i9ypK*D34zUX+uHQ@=l&AEI06L6fL;#9(hBh_@Ej<6D#`~ZS*omVm z=YSAEH1ifc#-l#eM(Iew9yW*(1H>(m8XJgdGtwr9(GX}$ll~_!aHSafy8*2zPIbv> zLj?4K(M%y^DS;Ne{jFqZx&&n*NBILBZv=g33hI*^+?a5P*Yc|0d_ldz;NaV$h93_8 zJ&w1XlZ*yVr)=1>akU`Pw>aC(QqEnQ*+KeG0`I7>iu9}Tm?u5`rTkDFv1FW{bwbms zVO4(gx_!Ak&&`)w8H+?bLTu*{)%=OI3n{NTMA;f*Cj#(4La#(5H-vW`PYhzBC`go* znG3FG$SZ2L8wq9(gL<6&9wwv#1nV32rDS<0PQ9`Fpf* zEN;IIWA4^K#bWG3Qa|in@@#WxHqgZ(;)TQxMr|uh>;t?X%0t_QB^^wnZZz@LBAMi- zuug@%E{RR2i0H;fnMgN#cmkCxT=dz1VNwAZfgrhi{3kFkCHQ@0p{{734seqQ5OrZt ziM_r@2A#46zDIi7vx#ox`qGf9)d1RqT)~usS~4)_1I-ym2T9RZQnVwivhxp$A%j}8 z(Ryss%hkkQ?w&t#)?e6?^x{X=L*7GPLSbbkcva47se0Lc6}VqpdSyPs-ca zn-1h}{Ra2C6~rs+@sMLSzr5b=YwibiyCRW1=!$E1N{-&A`W=_R4b?g!LgF>9UjL$i;D1|C43f9n_(5`#^M zUXQG^`aAnXE%ka0*RPNol}Vl45)ZWoae3{XX(K@qP?XF2^KSEbt+3BVfDY$DRFTiw zibQ2*DI_^`wnB>}+eVhyI-Rhu9A9+BaiKl8A!oU*vpD;gQ=vPDx` zO*b1WOxA>7{Ggh)qG_t~f?inojeVOMJO}BvnkKyBKf55{m!luM_Hy^<~vK6hQudQb`uVuMGt4?Xs` zL09NX0GqT*L?QxcYycxxXj-E>fHsw*{eTNfM4$_7gMrbaA}H#nVyY5s6+vzc(n~H$ zs}@`-1@Hg7H)IuE1Wn@tU1H)Zrlr9T(%SnKi+$S+ zr-R6}Qv=k?oBn_g4G9B*ju)?wX2ca{ScHUkkHx;>UNoq@xPork-e)zq?;pKJ($v4| zpO-a{tG^-cd%SyF-hfa1#SZK?2dW1?(s9cp>b4 z4p(T4!Mtw1n*?OZ>&YfDPwt@JG9h;5h5;#re?sc`W;k+S4`;1m%U{bQ(c$LyduYkz z-04xPcklE5v^^Pf#5Zgl9OEQ>m&~_3jDKNZHQ>nAdyJBLrPlSYBfSp-$HB9$(l-wP%@6m!iUnQd-r_FioAa&2aif+Ci<>W+0TwT{ zS6v3sh!=#|6B$*7_`XZcgX;JqlP}Nd9s&;S3S1s>oUJpkH|LG zW71Fce>4tlA(qT(T%4o$pnYD86o)@){9wtUY~WPVlUIvjC!TRPkBn?Ss3>Tb0Bz(- zEsa-EYFm7pAhZ;ErAIY*(?E?(rNU^+(o-?T%jKR0C6cI2%HlZ747MldT&E13w2iskf%!ys8-f?%Ba%eEfh*_USG z4?M~w(&4bCTFJy3O|2zo7RrMHw;YcfzournQD>wv-e8?)$;i{c2j@QxUf=!ZpMU=d zP)i+F5x!hVKd$#{WVLS5d!K?;v1Z1{H5+>?b7cgAksu;>w`s~KYt2QRMy>$PjZG7p zo}CCfRwrrEt+S{W{_3u~Sdli>c~R6hRi`obspjsrRwaK*ME|$``taw$(?C?o8Xw*8 z0Z*pYH8M9=H~jbSX&oKjVrGrFL&<9fK{I@1wxBpW4#Y4PV5HqaieMq4VzY;oPw)Z7 z_Pz*3*-C~8lu)S%AC)n}T#nJicb7${34JPJ5hv3eBP$7l)edVCK`NQgM9_ePoX1z$ zE@;Co=?sdHK_p7v!!XynOT=dq41W)E_)GXj&GU<U`PMeDzFCCj~R@b6Tr8$U;oXity_W zZ*sXpY1pSo5^Ol2X^LDEn%CR~$P7Qqj+O&OYdW7iH}y=YvCj{%EHKdkAtw&dV6%(^ zXCaF?JpXPh8P6Y3g4qa#qz&)775OgxDxk`ccR~7@Z4x|DGyQXceh=BU3YW5`*gU#wk9lPG2F2$ zX~%(0V~Ov(%C;MPdHk|I!c%*?%=+-Lu<{+f#QfguumAR)jTfoO!aGgf0p76}_Zn}u zw$zs+u!A6FdAPlq&*Y9==Wa+j9rS@X4kFnNnk$o;Mao>m%!(ATuq)%mzc|n$l)S*q z(hmzY!tN>M8lB;Gwtc9GO_NEe^kQG5`dQ(uUV>gW-=G`QFcGbNErD3|+g`*@Nw7mN-4+6azR?dFJk z)8=J=y4SU~StrG-Y(KYWd+UL08}X>JZ7W=EQ`*!rq|ecP!|t|;SeiewVkY@-`|zy1 z>aH~%i<98Dmm#)5U*%q~Z6Obf>Z*ytgU|y?9)k!Y;Jmke`!GP(6axBxIl3N-+4|CP z@Tmz0zWBzMHmsi7kGAgJINxyE z_uG#vx@-Lt_IC(9teVvC+2W1res9gJf3Fs;X6dU&!bh0tKOs6)g` zLrpBCEvvE>u(Hr$Oz4Ptx6Pz4G2*WgMfo#N5yXM0a^rAL6d!E5h{pkzrjLlRxNL>$ z`DhnDpvi~W`!#dVJqh8xoafZuRxp$Omi7%Sc}^o$5r=AJY48ucH>Af{El;-3<3fP+Xqw-$J-0Fokg~iPk|=XE>Wv!v24dq)X{@+ddHg3)qO$%G*2oJ4dv<(?ZZ>Y(2&h-$iEy?kDZk zdo8B3tJF&pOcpGaYjjc!;xwhY(4L2qvMGzvC8~QW z%@;fBjfZDDi;+m-(Fl~6&!Q*Bn`rn>A}alj!5XAdv#F5~jg2reL$ZHIqCAs1C@lsjyuZziEQ%d2fO$fTX@4(jf!%g$s5 zk>VF%>_l&&#$q``MVkTA25axEY&uG;%+eozEn0UFpK)+L``z8_8yl7tm{*3i>pV%h zTZ-+QyYk(SA%zbJj*wTK{5=^pu9+DdcvE>9rBT>=-s3taP4HwozSlHtlZji zTDN7f4*lyiZy0}4cq}R{=UXG0QYEm_^kz!zC5x#<)pDof)`bFMrVtSf_uUeG0Ti<)& zLRHo$T%4Z9Dn2OZglBZQw`k7m>anu1826pz2Qn}0q2Svsp$*2DTZ|i4D`_Yz<$2)# z6n)UskCXxQKgy8+UsXhbn*b#}vnYRlOcS;V;YY|3eJ3nN#1A;bTY|^Mq=IH5!?NF4 zZYszXAKT=bOWMkhmX|(g_SSfGZRKki8>F>y+&e0YT(NL+rmD?p+FTuVKd$7M!A-%6 z<)*D)t=*^Fluwn$M%Co`(t;6LE>3^oo}8qZd?IA^hiUmm@;4hx7SYkz1K|%1f)17q0_WF2Ty!>7q>3-RxEQ z;^oTWPJEqeW6jgzF=rBYig$bjG?wxW7C-|tEUAeno?Mn7#qR0l#|!zteqocBcO?S2 zy>hz@F0Nw!=-nAV=y~76tmVHdmj4o1RL_(yN|!jjzRz1w1m^kIM_tFN+aHsZ#{9}@ ze5Y+NW3E*UUqL;*f^Od(tmU=mKCVIax$#3%5P4y~v}05)4O}v0&VM&?$Nn85l8tSx z*G~!Qh^CY^zv4%WjW(S&y2x2^=-Z`34d%Bvd0k=3gP&@$&?|S|c!XKG+VmA*FnPO~ zQ7{_>8217j{5zt|G!0-r$qB32#5d&f5}E?z@ryV!GS0B}yi7w$JdW#K!@tVrpAnKL zI`6qgI)Oz?lv#BpwWnuLHR z&95}_xpwkE9ywoPlj+Mh>MK%8TH5OOtlpSk_ptR2gC8&F-%HOsC(>yO#b$j|ifE!? zyOeQ<*h2>c{@I*oFrwBMm8UnYLelEof1x^Zf$id1d}Opin2#+C!^TQMF_38>$Hw&9 z#nhgUlVQtRum|;Us5$ct8MfITyMtSFg7U;j-)ZTRzIW2`j%;u- z`<_@<_`pdy+!x#X)^S`}njC^nsq%KlEQ#{%xD<+|vJjuoj0i8=a55k+A4rHb@c*~W zFfsH`zWa6A2Ga=u4sAR#04SE@j2PGy6Rd0=JA+{3gv_{9&~)KN$3qh?#eGhOi!XOi zJ4Vn#4RPF-hy8MO-uiq;Oz;;JVRs__Tzvc3y(gM=!pj$Yrqk(5GzFHc*2Qjk!a?=_ zZ5-PD3%3j77W)+|j_;m9_c-2i)6UI_rdY`pIobBuj++dZh^p^%mv;E_BM_G;0TvkJ zUthQt4VUj=myQ3yF5V9;zGq~{T4j5>#rD|I2YvSj^4>Qy?p;xdR1WX0Mawbl#wz$z z2Wc2|c#gy^@C|CQal?F5vz$2Oj`;%r_vJeV>cp@W0nYl^ov$vQU()1sqH=o?3s+1( z?<#m|x&EVHovu;$Mf+~2LxdyIm5%S1|J+9iSATs!=)R`XmBXUSQz4-S?+Bvo3yexd9%a)A?!?8sI)(OAObw2YE zT91wCd&z|BpWDRoPCJz*9_YR>oWJ}vK!^?3irB6sMju-HI&dY`{-WN>&f9=!!0-Oh#0O1ygA zdS+8U8iX5}wo@O?hlR^{MnbG!M01=3n{|!91Q_rb^yE@FEc-H4l!`5 zd<1V;j6i?#My=_e8+*L6ntX>oF{Qpqv+mw*lluc#hD?(2mb<#=e{ZD7i8lM|g-IH|sR8vIQV0ZeYzhW5v`{Q=|yd>7wi|dWz&}3o;%Wp53xFK?jQNVH7* z4BdLH*EBB)Y@=-L*4ukeFYb;xr_ny4az&iTDCM+%)@iD+T0j5llEMn}{4@5#^Q(?F zc=9g?Cl{~d=Lcu!vQo0$vXXobaM_0r>_|@K#>DPCxHX|LXy3_$yN~kI_}Mwf3v*8u z9WE}9E^Ul1yP1CWdR|5OiOO>owRP3k8|s^yn{Hov+H`WdR`{_Z^HU!0oiKi!A3c;3 zHki2geN4t|@S&MCv7duEZ#nBe?{NFH-ez+Bis3N#?u}OWqUr z)e8MeiJsNk{|!F)iI#lV@X!g`X+&RCzvO~~K=R4?)TCMd3^`j)D)~aJ{;bh31K*!k z>z&el@qX#6X_Lv1suLg7zKv;odtyE}>^k2^|K6$fv&Hzw4Xq!SmVPhO{wdV{o~iyl z$@pus+t+w~`A(Ie+qC7O<`ZG&Giwb$1em<^p-a3CCYaiDEM2+1@sx%37c-qNhE%zR z*^C-}T*vx7P0`A@4QcvMXsjJK@Op3NG3C5|YE|g4=hngHkt0hJ1}ygXui*79&zIVs zlzNVS3xn*{B2ZlnvjGZl1r8F;|v1d#vRPsMX% zHB;a6Uw_M-ojUw=B>L-{3qKcLE|0)30)GfJ zU$Lky3$I}j)+?^;$RQj1o$+m`>dK=mj~(r8sO~uqd*#yBG+yXCVYa?5tgrFn!!kx> z|Cu#6Y960<+CMegcjMC2^UN$IeZQNv&#HY-SZwRRdHKa9cD3JGzgu;KS3+;Zj`iQV z^71;TBUj)5cKyhW=ofX{9^StC`VRMP|5^V#*T(Lq&P|OyymS4{0|Zhw2xt> z&-5!=6F1biI!rQlyc=;?_>z0_=&zRfAD@3c)UxSN*8VRu%z5tV?^dSA!gYVwcbiHV zcf5J@#lLLw+1(t_Cga|&kGI~=y;%J~xqJaXcQobcDZ_Hh@a%DnCOb69TNA(WYnRR( zt@C)s=dZhUJ;KAn!*%GX@;01-34-8)fJr!8J@&^sSM3ZnRXl+^38HXBAX9*Sd}qh8 z@_)0AAN|@nHvypVKonpI^sYNJ_myv0c)Zf_yv{b6##0;tZ5{=HsobNKxvyTw(|@g^ zzbU^x=)*qsY}tVervhq@8fGkpm_2n3+2Rb862gkGZjsXU-7CLHpyL#}kfo~o_g=?S z%J1|wJIbP}n%|}WmKm>eos(6stB4=!jPZ%7(EU_1Z%^u?CBTQ~{8W zfdP~Od-N-fDj#iFr=Ru+RHa6i2l?pkl4f%b3*~VQS9fAGUcOx@4uZzF<+_<|k{YOk~<&nbhTCMFO9v??XfObv% zy76qjo<+V`XSb%z%I#^@_*&iF3`;&OLKNPu8+)cm5rt5l$nV)D0=-fCX`xI515H_1 z-S+2>Uuync(D>A>GPGdcqQ0hO`TZTOFKR2lgxa8rlpg}4u z{xOC+kshb}%rmgN?n{YZ_q`qNP6zJ#qx5fHIQe3|y~xjT+3(3OCC?6Y*Q`s&4jiib zx^Qkk^EB2q=|T`rKQ&L^Va$_1eOI@kTFsYlV*p$OLQM^s!nfxVeRN~8ksRugz2%a* z)OWmn{XG@7-E(hF@V-(|EB}1F5pf1w_vzgAspjgFAB_#~dF-)f$LIbyHNUu6OmF!w zU-|rC`|8#&YW}1crw+X{OLOcb;l!QfA=(Th$Ag@pLSOL0&vJ0)1K~=BXEOB{*nqoY zTI{eH0?%^!&Q1@N7}?_<_<^gLJVi=?5(^((>ZtmNuCmw^Iow;Nzyr{xiQRTtgDrPf z6`y*#`JM3)tygH5`iMo`6+P4|>ansH(6_A5DlMC=tUX*(=P(!i@^ANm>WXfD0knD3 zu2`=+pB4T4`?icduTRGA{$)ej2)#o+W#E^0f-2n9EVvuMxm@6>Bul(tGK_bVkE`;k zJ7jV>7&tVpf}i$6EppqLnv%@yKO$N^!gmq1DaD9|TKO7BT?W?f%`hI-qaMSl%6KY! zQ?vBb2{=qEi*snXsqP1^6|;p*LejP28_`{bm%~pz3ZBq>A#aEdeirp|KJ@0W?X6_9 z27_5fN6i$AAGl&_---Uw>~~(L0}uB3D-xH7R)#s*6%~Z@p7ci;z2)}W6Fs92l()mH z7H}FBjjBh=QTpxz9NTpM1m1s=HjChtGm(;m@O$H}y8ce}kBc@6A^i`M=gxwBZnCdP zmZ6)&X$Mu4eJ`w0tHrKr=ZVno^_D*)cBy>K_|{i0W-V_J?gxlrW*8J+M6&f#p=O55ucMZ?~;@!4U~IIe(D2 z$1Lm6YY{fNDUy_+kkCfPvDIT``q5E6?ouZk`~Dt7-sP9u%dl5HPR)k;FW+W(iQ0PN z?6|P40HR~m@EYn9B^jcbs4JE@XQC(h_+OdlCHctF=X5fDYczFH6p=j=T&W*#Wq=LO z@!+VdW{SP^Da!9&6WTMIK1ai-pckBTph`3|Dq>H+V=G-w%3>!(9P!1vFgKApmv!#j zR)I}0ogf`!do3Et#39bnn@GL;yfR+8Z2a4D=bmh5kBfW{_Qto(Pj_*>4!!uq_ZD~5 zAKis>lU4G)%PS4$qrISCL8{4S6T3e9LQiM?Y69E545Nl~7RoocEW0*Kio%)E&Az#DgJqJ#cN(RuhK`F?#IMBqjdapS14OwEZS zrJ>@;OwDj_!%>-&%*vJBh=8*wXJ&@BTq(}X%)pg7iqgzd`{61xD=jN4J7{ltDdv>l>=sEr`66b!td*!2iQuy|E(iy=C}mzbKQd`e_$k}>tgT9WJ6 zyB(`JvAY%8ogbOh^JEBNdw;(B_pvAYHm?1zwOMoaOZED8(X{a5`TAa&9CD)71dp1s zaC1wJpToYD6cwlQC%4sP98?v~Hhz`EvX3R%t42w^7arduBWYzH5t|PotOvfD=GV1a6>MK*2-Gd?XUx*#5kbaEdK0VLiC~W`F7Z|}q z*og~#9h*(xy}+MOC&{S+13@1S?q2!E4$#gl`ymprzD$+-pZfZ`tcIaVy4bawN}g+(7%*;dlO z*B3suJB9cFEJ`wiLQ^gU&RQUM+y_cZlH++Hv!@XfA>-PK^mMU%46oihN?%37=mz=65xS{Cy|j!WWWszKqu3S3(tk? z+OgN8&w+tbN@xEe!At@u`t~8#1rY~#3d(niktQB%c)#~Fn0VedDGLky@;t%n;RDh$CdYlW?K0#zbGFbQ%ocq)q4v;4R3ZEcaJ|LJN5Jf%3I3B5v zL}q|Kp9P4DCB$bQqVycFV=ymX7!Mhc?emqTn`p1U(52ZOATR76&LmOUaeM~=ql5fP z@lQscp>$ky`+!X6W_?$QO@aXD@bD5ZmTm+SvT*^jgrrlEmKJcr*?s&0+y72PbBJIj zzKy6z}%I9LfOUPz0^J$^x ze+Y;S`Mq^5sS7tx_g95PQan#_fp`jVij${v)$7ybMVAjqj}wQmuiVcGknvfB(}QO^ zyuk~COQK060}Ie#;R=1Wa=VeJW6@!ytgj`3wAHYY;=qp6VG0kxd?)g8wo~qX@ML5% zjpG%KzoME%yLuv$F2raI0@5YPS6Kj)n^DUutU={!W&!yEV0TB(;txco0P*--LKY$Q z3nZ5T0;~x{?NjQua~UO1fEXdB@DBAenD+G7$zwvDFd^oJgzZ;CVW8-$>A~ud+G3}= zlR(%3fc*4gt0VJk$+@gZAe)C|aghm!&Tuk4J;{Iv1qtEj*otS*FSw18wHOu_DPbCL_A^u4A$i=N-`4*e8wlM4OTv1ir0CQ`tN71 z&QJ!6K+hKD8Jx>#SxPcq0`|SRwj!kR{WEob<)#cE@`TyOPjjD7inR;9{J3)v!%{g_N0-q5-UQAws0A-*MDW>i=Pq?EF z5R=J(Cdi6A0d%yLYP84DKxEoSTl2HXKPnfXr8JR<2$CXPI(M?Sw8lKvy1ZG!%%&h3 zw2$8?rD!8E=|F-UWO7y(ED8Aft70`P8r5&>K>@Z2kl8|H5(S_lfoyK6O!lF3 zJio2@Xie;0)ZS`NDUD7EJ6;mFT@g$Yu#^0PBTDW>32ByI-lNMV$Mp~EBHf9Hb-nRlU;7ZT%3rnNy&kpZVuP zC=v;>!7~JZ3Ed7l`_6yaED#SIXD8!;vKxaf4wEOs4$#GIy8nJQ_77*;bnE9BnNSSWOQjUcRdYY^pwJ_c{0b zT*SYuH?@?A)vYwxu!*UD{kJ9D^*mHq^Sq*K~z z4_`iPR`#oX0MHww%fcRX<_m#hvh369@)Y2=&TZn zn81I3kSSawYt=Lj2a1c+Qn2D_AEv(>em1&+wtDHC$|aD8DST2%AXZ8L%J^M$)LFg7 zh-l> zDX5P^paef$3K5rI0=NGRd>;aeB~itN0G#BX0(sbiLZw5V?5hFR(FNxI&*zX#F=ib# zgakmK$pTDd1D%Y((^x>Fy5cJlY%dPMN0yZ$3oe%A?1(Mfy(zkKGN_<&dgwsVaLFq0 zaTO@$0sLH4sZbm_8EyIlyA3e2T+Ag3Erv8!0x7ur_hqAN?cT%JhBi8lvr$*csA4W) zaSt=gk^Mq`2-n7ZBv6KHWkY$gPfZKopbVYEk2<-upC6#rKWY0!L4CqwiYc<6*qAx; z!xC_eD1%CcpkQnuN?(vB0H*Ig|MvEI%vGS2i@Jz^)#5+&w=VZw9gxHUR*8*p5IDcu zo^k&E%!l|3?8fOkB_QvP+iRq_k$qzk;}8XO)&ly{t+)5~D4jrM2_IS*4)=Tl9_S7i zv4JHHuq=F5%pJ3cMHS&67Ti_C_k!+Dd}!Lc&P^8@8$gN9SEYCz}K^Hk3NBi_qC z^U~Pa7t2h}yTFeZYkBW~#Jtb6B+3K?gS*VW` z*+0BK$3XR2Hf9Mjktw%LR9E%t3srYjP_V+mL=y%U&Y;%W7{6H5EFQB=k@c;>%-us# zx=~MEXJp?2^n1t@&hs?NT$T)z%|>0P3d`7I#OtU_=a-Qe$DscbbI5~#%8@e9SUKeT zYbA|;UBF@;0H)h(>0A~|L3Q{QIDDDvel)hsL%bXYs^3kOa-Z#f@VZQcjCY4Vi4n4xAcRIvVA0uT+|#7b&ZU=Mp`R_pxB@=kAzAWf3cIP zAgVlFgkl9lE`zA+TvV9=MG<{N#0f9W0O>;D&ouC71*vT`o4txW$$qk-#!~@6rE9rO zb<`2JaudUAEnQP>D_ybpM`NFX+Bo5sie;}Y)29qEOXR*wq`EKo8E5^EMIgp}22i|# zs{OK(Pe!H04tYF!=Gf3xM)~;aI;tFx`6f8#D%t4l(hnWBOF^6PJY6M&+n*R>p=j8$=Y~aydjIk)|e-CD6 z7Pbx_d5noAEnXu3)eud7aQj$}UrhRUt-E~j6Z^AI1xE46%KSZ4Ts*4#`WPi$*k?U6 zvu*5IIx5cQ-Jt8&SuqBMjDl#!ZL>L7^j48WBA)S2?J@AiCVT)~~g*Y+kax9;-La)N6g(1VDd z>kp^=BqyXi-8F7?)#B94@k0vF?_KRonW^1%WouOm-u7+FUAb*7C3?Y8g*BI}Y%Zwn z?5V4E-*NEbR;#FS$1T?^E*WSx-}-WSyUQh<$?{aB=Z?hUm;NscQJ!~PE}GIri{&-) zdlTo3vIBL@W&#sGfX64iYTR!-7aP^sdwpzq?^1&M_4BRDx1BGVRo6zx4{`R*eOzB_ zVR=qJp?3xe(NO zOBTG#t0+*eEw5@sb84y(yMF`d~vm8avHQ?Iop(NFqr z#WkZHpB2#OmnHRQYU@W0w;HQHYd=gl7121_)fpkTVDZ~QqcqLo1b(B37N?OYToDcK z+xNB4?0NP&?QX^TVCjeJ^a<$`R^t?TR_nDDxr5~?)-_)=67ANs6kTjk@UbJNl@V7a zw^wFfkuZN6e#x2rHlkMI=VaeYH;M7up6h8+!}_hJd#GZhWbJ~+n+>Ug1A`i&3v!Ru z{2feO2$x4MPii!MY)niW&n!6DS0foX7deAgFt<$pbY+i1o0iia+PAgG|Cu&vDI^j< zE+`x}s#{QSZi{0w^LQmIa5#3eV({vV**y5Qy&?|mZG zog_c|r%`wP=tDWWhhIi5*H}qZJKWjazvc9Z>z}>Nm#3o&O`3%csSeY}>P9mQT>IqK zYAZ$@JzpMck-2MnO5c6(U9&z^%H9>nEV+9wP`Qh0Yz8e5LLy} zwL1^MN(@I!(#qhC{fP>FP3g!=sMqVe{`8kQo~?v6cC}T{Q;RFE_%*5e#w#RqUrBGh1C0<9$iuMmImH;61+VAw^Ovq z+|}#9Q<0N2)85l`={zM@`>zuqX={4%*{ef|+axv5ZCu`ZO3-^`@f7RE%IrmL?+o{- zy$7u#uCQ78_L?7vEM1bO)Yfn0a|J?&yF?ntNrNJf$3bWaww{&lQ$TUYJ1s?w?A7e8!1V0mNxV93qOZKulhW69$jBMyA?rZ9U(wldkszik_=bt{h6=99MxLqR#|E!$Ue9K}jT%(ij zNgN5qFp>$GcO7;f?E8L6yNSJRi4yAC$M0d*JUwGvk3pV6O3i#^D^~F;_kbc|_91Y) z*9`$oN81+k+=*9Q01oaMph>yk3R5g<_OfU}J@P$M>skK|OVgdrzJ2|+-qe)y?}2L6 ziKg6;D<4CSq>UFuot%@u(ka!x(5jVLb4cUYT%V59Y;Dqc3D&KTlE$`c+x}biI1l}I z=y-;_Aocw5%c76sZeH6Qp!hIeP~+fg9d@zgP58D2EPR&<@}gJ!_-(ldIC#GT=Gp-Zi$Gevr8Y}aAoJ_o`Fl~y9Y{{KkCfV-hXB15U#x6J89Cr##QDBbTwnfq6=nsXdAF^J%b2C-`>#e<6o^y{)m{!_#vSXBU^L*II$ZU$dNdHJVUE$-Z z_f4*48GEMA*J$4@LCgmmUV6{5qPLlLwkBmFD}t`tkE1)2779j=59l1;&5AWQ(UA&^ zwi2AmpHI@u8NJ@B@rRnV>*(Gof$fv6e>g}hpU6wp1^S&+`u;1D$9t)y0{X0OzizUV zlqb6F!BazqmYzwrr_&F`o80%iT2pg8vLwnDb)Wb=)XO=Xq@?>cs9`wrtg%F>iF^S7 zr|maUbVDEOE(F5Jb8oV~6&dciu{PyHaM<Ilt*uD8%>cUX9LqA5il2R#u#jm<8eysq)a{aQ`lHsCVR*aE(bU zT)){ss_|kKYk!R1F1sHg@n$qbJQ>;XYT5{7=IM}hd;p}O)= zxm&6IHYKlZui|@M zc!5jPj8}xJ(j6y;md9+4yVLHsb-V<<_Lz$aiob?$QW<&;`(BYn*OC?QQdCW{RkQz8 zoRKdJQN^-wwRZuy?thgZN|twOCa*=*Gjn77Ps{Jyll@I&ap~smk?CHi@1`%SRvjAA zdO5E9-Zs4#=-x?s+U&#F{!~?&%qh8EfPSm+qL;ExD>u76cAJKqk9l3lzWj=7^(4>Lk8J4k9woi8bM!a3PRfG>U ziOYB$tMO7}=k03eQwNWvu`a&T+m(UJac38?pr*HO9=eB$!H9}N%O(kW7t1dCUJc&w zTd48guYIf>Hn!FD2qW(^O(tPbdFk<2jMLeW#DXE5#!vFu%lx$s|0#0Wq?3_eN8O*= zqrpnmRJef_G`Hb?&!>9wfwso@`~>z6%?0j&UdQ7cZ|U)OI~%qvuB5uxIM|aS_4&C2ze@XsHMaWr}A2NcY-?dKUJ1>XIEoY2Q8|W zoLj4<&T{WC@0jl>GGW*+6Sj2TX;)?3w5xWHG(44+|L)2IS5+ic7a66-N);l!3Gn$| zM6pD-W?w;RGwZ_SE;VP1mhYxlTUa-T_^Td|JUDh<9U|+WE{s)A#_fQ|K1a)pBZmtt*E>Ck zXq-9_m&7ogX2oqVDeF)3@p~7{YUb^`&jYNfhx{911Mz+bVsvdRA|6+J!K2a`(Hut~ zkP(;#^`*jnsPOm*hEEpb^awnrgE^N&Ls1w(#3$UY&X|Hs@2n^Hat|INGovhmRt#=UiP}Cq*=I+Pv6*8&RdhfKhgh67#93lw@PZTm+_rVh$4tVM! zse{a#E>`LwB5tYehL@Xn#>Mk^aan@h_Z_T7X*Y4Lq-kq^wdCWP)}brq&aorTYE*_V zFx+H*q&)^6LU7S2q{01$n-qt=BjH~I867K~_Z~7f3o|$ST*4CUKM%E^d&uZ7e85t_ zo&V?NAzg;J*8iX+&)McfT?vW$qOQ!Y6x~yodnW@?E>ePXjJ_KVH5yxXKDtcVpz=V#~Ou>-UQn$!C z#HUtA@nE8YL}E9-@Wma`YeVRrVFYp+frF0U6uBf9uyVoJf-ppMWK4i{1 zJJt|g&>HAz74?0u)vM+cUA$l6_7tfD3dd9@3K_nBuBP^GOGNVzeM~QoVypcVvb4)D zGe+&mfskotOb1Kzhj%uJ@iBOIeTUC?GuC-sWL$NBzyhLmnCa^WZ;*Vh-}e92!qG`^ zqepOm+_1^+=Y9fsa27nI!$&uZ7Dxg8D8r{?JewjI{(cZq7sEdb>c^&aOz-{q(E6k3 zT6^O)$1hhpg_4ai1Xj}J`^bd8lLbV%&zc*bM%|Z_c1*q z2fTET95RD@5uOz7f%|Y6HjDecgoyMG7HX;{4fo7buqAHExjXNO;rvj|2s4U1k+#Z= zTYYpi_!(u#P`q%@!oF@TCAV1vWIS~=nhLME{nD5F*0+>V_XrWq4N&LMq_~U_z}HmC zm#X9&!kaK8`l7Pn0X%rz&avNVuamDcHg668yY)Jd!q}W1k9yed{HWW@uiraQ`!tXF z#2$Y5yX2YgE^I}{%jt&W`pBm50s~KY(6F9f;UVs)&i2%H4_?n_4+b}eAtDDdJV%*Z z-ZsYzk?s<3S_iUDYrKBG`%LchsBlJY7qgJg}kyjtF z;)Tq(4rUaYvDOtZ(;pDPhWk}J*WHGzv!PNv_)!7F0%(V;6an{ zl~)X(LC2<%A%B6R@pZT=o3^=fR5}Z45MyJpve%<@C}@TGr1!xoJkkroFpQ`@v+3Z` z)o?WBeiYq;F+KiEffDTiH%+s=^2*OJ)jQCf(NH$vLuIT43`gNvLtgN>!O{fob*g|B z-+}O#WO!g*vicgP@_p*O8BuMBn8-S9<6g;1BWdzQTO|0+zZ2BY||2WDn?1KT)9W0F>MEr75jp2GE zsl#<+8Na>{`ErKt%>-!tWPb3Q)BK$EejQQq5P5!yndTHSzlr#?fQW{$e5)snL}9^1 zCRHgsfXEEyh`j<;?VznK!b8NBcv*~K5mr1qX#N~fs+6HrEw%&^FvtjA@`=002;efL zh`wsv*C~rH4T~g=_aAIp@2P1!5HpBK7-TM9dp7*2Tj4m|EbvM8BMN!TVjz9dqN}qZ z`th2grK!Qw#=_@K8t}+#1BCGg9|0qZhj_2|H17e)V{*?D+!Cf7=C5^VHFaRx`?z-! z{6^c`s6}S{Br_!cxaRfu6qk^Nl?S^-OwK<5cKlC}Yg)5F)cZ?o$W|Rn39| z)!_X*AA$&oU;v@YWvD07E`-qh1)$hk+Sb=`TgE_(2=&$f?VkCcGM8a^o#7Y<_vd*0 z?qYt*obVt|1S^huEbSE?>1aL?WVulnlrJ;s`&lf2*c-n&RI|m+ll``x!H6;&j%LH1 zb{`BTA*|oF#|V&qX%>tZO#dZ4k0c*o62tZSyVV_sV%nTzMm=tfhNW{6ap1lBiKv%X z7vA^3j|V=bO(G1^-!)^x8>|pVv*v>*;St#I2m<0LmnJqql>=4B&IfP6Lzm!cJVrRc z447nW-T0uzWhmieD8v(?OA`Sb;d_c10UeC^fAc;a4CO4Ee-^`^$M}7QVgJ*kA(0UU zF2vzkre2ob)v<{!cj9s_^j2PX|L6n{?<+ZOSk9>V?8Y8t zgby+kD5BA5N^mNcfBg?Lig;Z49)b`O=i0|i41ZiR`t(Y@b2JGNTOAkO5%szF{q^t6 z)JfLDXXc#iyVwo)INqE=yH9Kq~s=209|jTqh&azd?x7EEEbH_*bl zG-Vz`35eN7`9vWiLN?&Rl&{n+|2wmoXyX=X|K;UoA;WHfre4jM=z<4;4F6Kbm9A$V zOU#-?MtIyYiH3&7JKc*GFJg$b(UFgj-Z=8$$3Roz5#vmT!K0y=z6lp?q#p+!Ez{^D zd{t0on%cn<4=H@0+n>Ww>NYZI9VjV&o0$79iu*Q(%ZyrL#&MbP;BhnKfOMyjco77d zwt?XMU~>B3$B6+m_)k&QhzO^11X8O>p=Rl)ak`>(ZlSd^cP%?oL`4Nts(ERKX&D-KP%bgtylIg2Bw<9V!YR&L@- z^C%88YG<_dT|@+A!&(OshC`@T(?ZEm4IXW)A2XD=F2#k0o8iSBs%}8ULxTM%3F&xN&B~)# zBD3ngqxuru^vB+ns^msjhTXe?>VXMg0U{Ox1iWeYfB59^)T4AM71NldRn5LEc^!}X z$hGYQjLq)khac8L?x${fbn5%@`~`m0bbIWWkIdD!(s8!tn1uo>PpvlrJ+;U6V1Ag{ zaa;?&*H7F><0JX0X>L;Lc5miC`H4?a#z*~A*OoG$0WlZoqJUbBc<3~5W49#T3!!i`WW z?pJPT=x+_le|BfNY(AJ78g$f2aZpf}5>(9-$ZeeVEX_nNVpQ@Vm#w=kYjp#K@xX zcCiffU6qSbQ{NSroCm@%7efohfhv72^``S4k!6KE-Js6g0(Ytod*W*NRAIuX{^R6< zoScRckMNLdl^bu2IyF2;_3I<;JuQUn-XZ;W3*Tid>I%c3TfSNio76Y=6SG`8$G5wL z(fNM!1{Qhmr%fJ`#}4nFxb^16xf#_I-Ky-6_3PH}(!!@KH7h^lTTE*ds_ib4U$3wT zY$ZX_daYcs^yU&sm(uIv*kN|#cF-|Bu2?$e-@hw%1gBQch!oasaX3>&>Tj+wAN^g^ z&r-1JEn_k%7;Xvrm@${rI^Hv6*b!6gVpxZtSK0HfH6a(>!fp18E4n^~3$61zJ!;s< z?Jv%08uS>B|G8`@eIkBsPTG)belA~hW2W$C&hEDh1+tcn)uzv^rtk&1m!6`>TypyP zriLf1m+uS*wTvVvhYV_*Znhk(_WEd<5pq{|#ALX9=G?TwX7%X1rTY9s?-F}MdZx%` zo~D6$1SrZ{+!iHoy)Ld#CU&jbNf|6)qwehizGtAT2maX8cj%7wV)~ZIc?=bK`&Y*O z(*!iZLI~Ouc8`j*6vA;-7|CUAk{^`d6IA|=YvT3 zL2+YWYVISw6i1gF{j)oV!yZKLe!H8ykdSAwNckRTxj9{suRodOFlzFE@>42H^~u%k z26Y-gl~2sSqevUJ3KA16%}y1FWbBNd@3;E#%2M*3RVcMk)~Udw?489-$(%yH-yEuguzr-=I9!o&P5TG(&}6w>%kJ-Fw8bry*f-uuA|>T z50utivpY~3=>Et-dxv_;fSHZ?d)XEVw4TTXH@=!{djGQQdB0j0^fkZFt?uZs%NXTB zz|lDE^aF3LONmW`#WLR%^Tq|Y)OxTtoFR*si7%TfF{6Vv-A!(5Nw?H(_GR5>iv@?o zbT8RRk|cpLsO%~O+X-q(r?0}aJA}w*6sS}hRYGHlg6t*QN_z1!wg5MQy+k`{w?mo7 z#tTKbU4u~l(;Nw4*P;r4RS1tywxo>n;{9LbEL?>4b@a_0eU!x@P~CGQTzi!W9G(Hi zJy-EmTixWy0p4-8&a1Zm(`_5Gt&=&!4G{-$ubi$M^_XkFJ#W9wFc5R4HdHKIicxMS zIx?rj8p8#1xYM-^{jk>D@T>!>tw~Q^>!H=FsGJjjl60dy_g&7-Wy>#1C~C|i4F!Bz9|794iC3UVu*JBE8~!Om zKz{>jc9utPTNIw`BgUIdXd6^VRr_^k1tP6*=)k;w%g#xG@iD%%#^jum$kdN!h{w`L z-f<38-kf+uF`-8YK;<~iO4MEN!gi$X5OdWy$c?8^ zS#|&#e(%1@{dGLE?<8FvvcvxI(gB&XP&DSBewOl3zfp{)smePJ{8jY<*}Pf%^UGt1 zGgtc!DVLu&P+e4lW}}%2q08tO6nG1{&0_u3r6|$|_gA7N+O2S`SY@AQd5?%73}okm zAMZQ&Rty`)K=azQZfAUb@Ny$*pvC;nslkcj`7?Q&*HcG!Z2Pv#+}}ZF$gx4#d$%3{ zd<)xFPm<`0wUq+vJn&-5a=0T6n+eI>2GInLy3sHxq)bHuU&5*yf;8ZWF*0}wEhxsgqxQgy{2l~@$>Zfq0nG9RznOh)A7EUJ4PiB@jp zGMc~FMqy@OKPPW-ghx`A!zWkNp{a+>rD6@&mkn8oJ_;-Yr zR$yGPiKMa1yOg!6c?P0u(tq5fRl2hd%-lLAee56Cumdvv zKSG42S_cK;E2r2id@C2L5#HSb(meB;HY27f2r=Z-kbS??{ul zQHe1b6$M_)C!*uUdf%+e{4Fz!Fl(Ni^#}~-Km*Jv|FhzY3DnB<5czVRTsbJWL6SER zlQej!O%g(q1|XnVQ6WSQfOgC9F_L^NhqurqG*g6Pb#0}Ekn%?)WEV*~2BMG$A}5u_ zdLhyPNz#u5=kcURcwX3Cf*&xow3S)9Z3qqvKL%up(?VXe`;~GHS0vCR1(1@VU`Nd=M0wg^RAY`G9sO6s-^>6W2k(fkA`A7#K7iE+fJ zNU>}(36u3sEO9SZ;Fr)4^8i7y+9KbOhX?}yr1)Bvt0?yuhrO0zF z=%{zL$-@7`rqLQt1y(9Rzu!!W!;git<)Cy~UF zDkl;i6R~pOR`J=#r`@-3z3R^2M+?p zeuj@99cT)d@#4vNfu;f;3FCtF&NlMuH}X2*gY89w{b-F|87X%X5FrIBtYRf8SX^F3_?!q>@{3~d|&I?qeeH;vN!EG z@JsW9j0Wt4*Y-nd^nd7nIb3h&N$A1V5$8m@A2p1kYxc1~Ukst_a2lJigi&0mT(e-&bCx79QUFIBsUQlurB&=5`} zSP%%&f`q)^DPaIX5=k&I^&^HPEn@QkDk#1G&0Pncv;#>}K=Q87H~c5D`RaxmV))5o zrrY=pV;+NG;A6ZrZzSLWBRyldUbl6}fB6bBPQfx{Z|hf+N6bT~Iw0u%N;NOkn>Hc9%-EF%<*qV95HU(ZqkCltd=p6z`AGi$ z^1kO}DG%n|B+RjywcfpJz56ry9w9U(FPdlboKlkQt?myBcw2cKR3Xwh2vtb>cv*}h;~~UI1~D6Ygtz~mjG;H!{*Hv6CRM$Hh(myora=&r&?BI+ zQ{~L6gvkPlFb$@!WEgCrqrFJR3w?wYi9-#L+^w*0GWKS=_Dld~X5NcVB#X}@vWjn| zvM!lorA>tpc%pv991kEsJr(IDy2I%Z`-FES!*M$^5}>APZ=gXp9f26F*kOn+m<}*K z!d8Bjr_Akpo@jpvyvwPbNE+JWuC~)gXfM!%Rv>eG&3Auegi~T@#G^&C;)^>ii2Nxj4R?m ziI7%no@8Nl%ath0{MOq2*&W`)_HP~Q1jBva|ylweO_Vri_NB3 zm(ST~MWvply$FCR*2mw{j#c#I+Yk-K#w$cX6>&6qzkBkL_a>D2|CL<>2sE%tk6yt6 zDmZVVVinL(a}rDr$Hyw#zDAHB>&uO2Auuf-LUc|M27pCH@5=d$7eYudA}BHVM&nx_ zI0BIzfxtD&#bzMLkh(6JE5%z0ioM4$bZG%-f@Tn^A?Wc8Gzk=sxDGt}Z%e(5@TwU> z(@euQM${t{!xLlUcLtDPd5{!CpQ#1jlh0S=g^=I788RKbZ>Dtn29lJRa_-bSw#%OP z&5pkvW;o81>X4FCfyqZeF-~-42m9~qrH2TL8}j~_ug^hWZn4?4mtfLVaE3Qc^-{Gz z+q9lg3bGwL%fEG&uYj`^#YM?eX!5#z9|=bwW)d1CvHc>L7AP6XgNdow*jadWBpjy=CzB+}V5TWp{<%+@NBRfAf4H57 zm+S9G0AevZ={ksa4e5I4OJgCa4MUgc15L;vT&z(?22BTfXg|omWPMqVpE0@@v%xbD za+0O2xlTaf<`C&=qr+HOrfx1;oC;ZKGFf_>zRr_);6X5;i)V`BN0zA;-Q2vFU@%tk zbd-PFSqa-}j_0R{9|XC`=Swl$eV^MzUUPqW-MT#N{wzJ!VmYPxu8zv*KLOA&?bw&j zpHuB@m33*#k)K6Id{2E_IdkYyJsyf;TU{I5Z3tB`=gS*Fm2glw61{#q&3ImYatMzS z_wYgih(yv&@nRTk!!vzMf{-ARuHWJ0x^_pBSSndkxEt=pBXeJ(fl7Gk|HMY3{aR$A zV`Qqu#8{T;l0y}oE~dO!@F9zKJSRjbfy|TMMA|$d)h>WB?@8m+B+`9QA#rQoULI`e zl80`8vK-x5$UArpg7y-an)i0jf+hxZla&n9{V+2{dy`e3?Z&%*&O$vq?~X59 zDwdimdqI`<^F2Q`%HfjyRQL#U5;D_NiEOJpxGbMXl00Fn03rB^>UNs1H@}g9%9V<@ z4ITslE%ZPn7DSeFVXh>}mEDJeLAa|K`sR|Pq6J(x)C6mS79NzX=D{haC09quF^~UoL8CO1j=F=gaw`g$@b105H3lQ z#1|1Dy?T2ry{B8?;5H2l`^0;^$%P#lU6>iR*9?D-fc^D`G-@KWOETOg>qn9?r(@qk zREWKD=DmAfW!_$qOSyZ0%T=AKFRg;@dOG)w)7nq$Of~g5`b{q`;g(UX5{|Fnx9Dke zMh?Q2GpC7iNHcr+%KMX)$$WWpTB8C~ZX-ohf2nO@=gkExx*3{=BG?iNIwVRvg2PY4 z@D*jU@8MjYnJ<{r4Z>G<|1aUY>87O2EuJ(N0&nGs_sD#E(7og51COuh1<(xp;ok@- z#R-?ueP9|{XKFx#ElI+~6suc2$uyw!dV3R(r$FRqzaRyBkjSk$ndQDS}cb6_9~hGXb88J8|f6syr}qx{A8yD5vqbF zW`^_Y|8_P;#~Ld{66Vz9@SX8Ku&1dLFjo#qX8pk2+793Ym8A0)#|-YRAAU?er=$-}SQZ5PQ1=UP^U) zrqg9jolL;iUDOAKLJ>IKRUsZqN62iy1&Hys3~2)cha?kC3A8eH>wXSt2TMw0cg_PU z6m}54O;L}V8R~f;7ol#!uC{fB=SeB)j*FQ-js%=yQuSaIOd?nHQ1Y8Zn*Ahq>!GT8 zz-NS|AVW--Nww8Pnmq2M`1v(u9K>jt_-t;>uJ|{F?s9I8ET%s(R#Nd;!r$5PgsZVH zaS6xV!N^rL)h0$>uIg{u@vQ1lo#VZ??QzpzevCc3b}s&Zk7-C1>++;i^Z#uu{tbhV z>`(jl{^JqI6obh`qGr+}C2z6qg{t~rzpX$g?WP%-KtWdH#k zoI5JiW(ZTG^y5jUhR2d75{IYYB`B1>C<)wgswQJwfFCDAg^EMqq(X4b8ET169#?TV z+yERnzQK^#qKgZKhi7W?v$f)|@0mJRgrT@FNFB#GEUGk=sbWA49ab^*8-bt5@poh$ zOBX`3)e_iHrivd$+x%$OspHIJS#ox`a34+r4ysM;$&lwH8-c!*T3Vj| zt8q{F!)=xe>(F^A+TJiHD-p*rW{9 z-Y!l?iBpzPq72cG$^fQ=mVY)bix8P@`|Z^yhyzxwr>?~>;Tm2e2eIk%EA~t_RU>sFPu}l{3_JAPe7a1Si*?`{;lxD_SsLCUM(;$d_8j+e|y64E0e(uf1f9LLj?{76vMNjQ4F zBy$^ZQ}qy@CY9rkepyY$^-gY;G$24#T0!LgC0p4ffkc%e{iI-nFIQ%pr^Mw*V*O}P zPcF=UcQ`UglSxPv6Tvz_sAUHTOQViP66bfnN8HPj0auj z?o}0B|3-MW@6ob^XugYk{eqXKR8ek^O3x}oFO4tlmnW+XNO_p1&!RLte1I?C4U9R8 z)(%M-a>Z1vMZkipJ-$cXg`5cogga!GAlqa)V1biRLL!OBvQwl19XtnPdrUs6V_<04Qd4}qTcICi#ZqQ`8A7CeR-vfJ>pz>*gjIG38)zLl>ZX_^K z6knY7K_pD39r7qk6kspK7Vh>F5@(86YdAS&QR^;qo>{97`SCfP(R<0~Si?Lu2n*nNG?)k&RLW?sOH_@f;XABx8g7?2YoTOqb8|Gpb+44U6@ zl+eMKuqI@j_$da$kfA18F%ZBN z?Afh~yJSM8DXj~EYXRaGI*5Iw6I*qJOcN8g&FYzE}5?RE`TkeM{Z@rH~2B=di3lV}JrKVFu{M;B_+Rg`uht;kf#1On8~{l`;XLLrlG;4O2IQna^p z(j!ye7bbup<%M8!AUkg>$yRc7g(j^b1Zjq(8FS5XDGzqWs>yeTz=@BV`*^c|KRr#+ ziC<*|X6SvtrrL+=@qgfh-cnCN?8R<1Q-1npM`Wey3*J2o(yRP-q!0cri0Jxj7ti+JclsrR{*S%q)T26)JAnd4OD6X`t0Y5W`ahujKnbNT z@_HOxSK6O&UA=P6F|wm%yW`}^hZ;Nx6bnM=i988EPTXv;5H1ITp1TVrq!%O`_a;@K zsm!JpS2Ro&v@HM$6Nz^q@N!x^%skN;MGy|`O=^?WBl8fTuw;9+9Z=5BI7+ZbB?o~X zO63K@qM4dqk!8}9IX`7{Iz08pH)&^{1Rncw=f1%_OzA9I6HAZoS?%Y0W9iZ>9H=Vj zD9sj_8}1JuJvEQ8v8qVBAZ3ZZx+Cs=-Y1P@f{NAnndH;<+`5Z7UGGhQ+2JfdS$}=L=n<7Eiq!o-iq1POsrP;3=NzVj0#0zE;>r>3nc>Wpp_w@g zN2O_nTBc@(Xl@Hf<}4hQnHG-9RpH3oVOg0i9NDsRv@AbLH3 z&K)y>AN^V6bUj%DqA-$VfOd5NFyfoYu>d))lOGK(N&+S_;FpAOFCiGgMsWL(C$Y{* zWc$G|v#CQ{b;vMJ@>~7k!`ytdHu*!{8nFGah-`h$y+w|;OP#<3;8f*}c;QF^dHr(>~KEJ+i z$cD?eo5I=sg<&dgqR){ruWuCO(=b#$g+IFh1u`P203ZrM>?W`uE6^-;gNm-F26GFi zn-Tgf)YZZ0qgSE00z?E2q5sL*6pJVm*ER>>NkY+XM^UH2yqe^L&=6$+Os1i%0k|ny z%#TK5^3ll*mwWgrajvmug1h_^gZ? zVm^b!WI;?Cf(XF=MkJIXE1P=9d(spW8nB2bN6U6Cbe!kj2bgbp;=Elpf@6!H$0XM| zlM}nT{#;%EvAn?t#4W|e@nn$373T@XHeB)=xR~5?J%4MOdPkfG_dR7<3G$# zaY3;#pZ}SYff!>%{A!`)3L<%DqIo7rTiGYtjx7rTb%tIf16ei@#j8d6Gn)4~HF+{1 z$r$NtMw>8K+81|#C?b1c|3BsjM+*To0OQAPR~D%u{iui~BywwmIazD^E04?tH;#mD zo?Swp)oatP@*$&Xx{d}iBkqih1lBJWA0e8vuq7P9ppgvu@UBHtB5f*@JJistaHm({ z==>kco2IcPmVZFAe@Jz)k@vQYy_O@AvIdV;#&;Z%{%@J8u`ZYx`K~dVy>N3#%=U18 z57$ze5Lg0;^OIt{h;7Cp`Zs4@UKZ2)O)HtARxz4#cR z@Uj@OkNkGzCP=0^r?FD#EcBjT&LQ7@PXmZl2CCE^{Y00YKZ`7**@iOErhK@&9-=~b z_rWQJo;1;N^^G$PNS`;Ah+E8@+T#GI+2ooZh!2e3t+9gFXuIKdNLt*uAa`V|#HpL& zRb)#eZM%E`(@w**a_brxQbsgSln^v0Yv2ARB?jo7cXwoPWhC^yWR_NcIml|)k&MIp z66$vbZ}pWm1ymTzT3pan7^xHmSORS{E}+0_@h1byWHWXnyo`@3orQ1QaM59mNMhEg zEI8--fu}`q+9#AT!||^%T7=0frJ}{99m>G;A5Q9<2N{(mYD69$WynHdxB4Xs3lg~H z*^f=mA2Yph`|znc>$zS@jq!=D8yLw)>y%Y;mW=vW&mf~GuD37Lb^Q!_!2Q7Ii}Sea zeyw@zwEzwSQ$iLM1R>9ETd8tGxNG}J-0iSmAm0;xM#$Hv^%7Yx6uy;YA0hcMl5}W& zv`@~*MGv$iNu(zdxk?%gKu(Ab7M(>xfCxOZ&-Khv+FpWZIJ`9z@stV!80) zWNuUic(l>p_m@~ev-#=r6PsKCXR;#!_rTojH$7&@1m-huy~o4Cs3`g?R@{~ktL3K_ z#S{74Ld`*P~>zMF-S^yYx3pWpd*^e~cxe@*VOvx>& zORIS!40Z4;%9s1?5~@TC&{le`@!7d|^YL~I(U!%~%d-F#xQHda1Pm826~gZqNEe)h z$uXcUwBC|&r|jJ8J%_^PaRLK{^?r%<6qS-+)w%utHT=q zvtWfF&Yavd^lt<hhiDvEK^+vj8bC zJFK^;pFi+nb!^XqhC&B9zC$QJeFC$^2=L+fz6#FkD_ey zNRf5BTW1x8`85}w)x19$lYJdN`En~2 z@ViI79ItvN(zXgee>09^22)vRcOm>+A>5dOF0Fw#zCx98(ccVEGhrx3{fOyORLCvv zd4_^50=q(7C)>2Ht3_+S3bbkESRKaczEY3%D*Up9!5hYsz;YC@N~E&aYa}n z31QvWpuh)`jfe#9?_3)Ar+C}0CJ^|}n=1ye+@_Yb2UG^kMF2_if%g(gk$nh1oXPX2 z!?FXpnhbbu2i%jvFK57=Xoz#0j3062)rwD!XM3p!8U2^a8J;YuY23So-|i2pX3T*c*dZ%)sq<8c%AjO+vJUen^!8OA3$6f z1rAH-F1LYT-ws0}*A4R!NED(PQPAA8u#ZN&{2AJZg|@O>M8qV*l1yI_4TH}BB^dyg zk1(Z;<7ki%@Ob+jh)gs59|rLF^h^$bZ21pFmo6g$6@#G331RDK06Q3-8lKU8+IIXdvn*Q1u{*1J3`7nsQU#aRU~;Yoq3S z(}s#vO!WoxO~ruQ*Y-SDE{|ScR6VK;KJVY7Fy67xc46t_OyU~>&qrFfW29(C*Ph#h_2ks5jxe>GWe&c45}b@2vlZyz}}GBwcX z!@#;rOn1VEUg3w(H?^luYuF3h3sPUaIr;qJ=AQ>R%pHEW&kV*6co4G#+`J=dZ(KzH zo1m+IFT{W?_&|KAljgB6xFbfk={x*r6IL`*W~qotTHX4#!6&?%#6Ra^?h#Bt4MK`Zs!;uTvwa9jyj-?`ubvAN!^jP|5@w;Z^3q!Hq@2D1xU@692OFji z^OB~N8O0kdWTCZP&*guN?MF#b0$dsdHFYoZum&ku5@Zl)8a36p=hgEguP&ynFU~#{ z4Iq7RJLXl_X^h3q*PX||%p9mRZ?-$VzA&68KbUvHa9>x-df0T{#jWWNWL#1@Fl7UI znnB2U#8||mT&q(zm0XNv@aWp$a_r*ehyjMu-Ct6Fe;%Y>>pnh<7YS3F07ePzPbae= zP(mG@$einiBgEvY{K>N!d=w5E8>(@DB*UyJG#=maAzRXb`H^fyV~Ot0;=D(!G(LzT z`k7iX8Em*bQ7)K;pA;vEHcXflL!>pJT$#O)QavvXMC~K@VlW{b2t(MQJ9!Z!=n!E$ z9E5ujflvp$PQ75(WFmq$M(`kBaKemWpL$B#QS2Qsnv9=Vyk{gq!t`m(yoCIWKP=Ps z&zLmQ?zCIZ^ANv%IR{E(-(T4q@W<6^mu*;Pth4-Hr^SHssv~~H$_q6KS0mc3Tt0+l z-FxXAQ>O+zJkZdR=}%0%iL4C$UzOi9vh%ASZ8Moj#PgA>R#X6PfaU{Y;`)3RO1TWM zhy6f^G^|oN$9za?iVnkIDFO(mAHxAa9GVJ1XxAwk1hZU*kV-@W3!$aY6%jRk0Z>fJ zibh7tqoeK9?<+^Tqz+fEE8khZ~Urhe}$s0;(!B{SHkO{U;qHTkq_>Cg1knDuC#GtMpn;cEU

pu({q(Ecd0L497 z`cRNZNet}CB@uEWC0Xcs>nBi&Bz&9X-qf=Dd@ zbRsw`{WvOSX$335*e!9Ead!FSe5y6I&Jn56F6hHe*uuue0$9Cg2@{cR<8q;q{b!5m zekm=shfjN+{(1bpX6umF{MxR7gP(S{?q4Af##P=)GH*L@vi4wE)z`L9GY8z#LlI~( zU|VIF^V5SrHquk=wZ^DBw{?fIjx}VmKp7zfCj<48+_Xh~d)WRPXjq&^T9}LmgkhzL z2je#ZD27YaC)%SZTu9Ef8F<}=gNXdj4l^1g%>-N3si61<8HNJ{kUG9GuVDd_>l;Ft zlA)eh8Ys^I;Kl$P>-ip~Wx4kQoz|5==!NSV+l#Z7A#y$gZfog4C`*HBZZHrwLVKgk z754rmvLn$7^2=>Mn|M4N^E}&saG8K>8`5y!HInsHGG{22sjGTu@{!2vF|;EU$5|7+ z-Jfqx9Bs$#%t*@*ox5AE_v3L&OxXTOuiX#+UEgKyB>jF;UAkgx!&S48W#DF&AM2eG zmWF#ie5e!f!gN7nSN`d3C*{lnI-+NgwaX#>e z7EK}O*ncn-^k@FLYMI_mLn!b#5*!vnoC&;@WTr{M&mqhQ_#cc}Y;2?uuFZVmMbBWr zs^-G&@FTbcVZN%&JlraBP%>eet;7Si=m>l9ULp{1B&gugnrU$#L>74Kd#+|L{E!lR zs&C-qemYj_kEcs%tI$_9weU&tfQ4OY_4ne+AC$j~l#w$sgT~b2cekmo>(gD;I3yC2D zV6Xs-!3*~udUzfr^FRcV2H?wbYvG5~;x>H%NQO(pq*xV2A7KT&YY~~b01y^KhUHvf zNt^K5(*7)GVk9W<&19=p9o5#Q?G;aB5?f) zefUzT%p)<5iZfh)J81Zx&Uko)(bsPw4yCyJ8{tK1Q*STUPd%+XymT!rH>-S3rhJ_E z%K)OM|>X9KK%n%)-injFZ_#srJ>JqJ|vCDyJ5UNW1hXnMUbqOG45POHeBNct#Y(Q2|hTxz>00O;XQPcLtJ_c=?BB^`$FUDS9t| z_xZYgk80AFQ;aB|h_HJU6K7=XIDUFGVx(eaSL!bq^&ougU8A{dX`UF@Pkw9<>U%3t z;6qEcrcUD$X`rWokCNoF041`8q>|3V`%iPBz=iJ75?dGTkQ9-Qhyklr@lm&j8>QavJR9CzfO)1GMCVM^%;~6(?Gm0sYm{ zxPG%>12_yP2=s7z51hQq4fvP>NWy5!N{w*j+t4A*7N8oNG9Cv9K8nEVY|RL=^Xx`2 ze)@!=R=o#|ywWSGsbK1_kD|6G#^WMcSkh}QGRFLci6;|MbqdF927U~;F#a`^$lB%k zacAd<^sr`X$$_osv;w&O(eYpJ+1?x9{ym`|<62zs*fZOE%Oz_6@Kna&$C`6H|JiW> z;E_d%OMJm0`qR%(f4na3o+?O>cZ)`t|A~TxENLztq5}wZCQ!Qv`dkAj3SpKa*DMV* zW9}4*-1-6-EKccJsUl$|lxYT%L{^d~Qj$C{YyK$nH}u6GAkaWL7AVU|lx2cCqEqsz zsyG*v5**QEf#M7ZW&!$^fLEUyx&T26e7F`F9Am;MOt`HOZo@w)e+5RQW37eQEqs_- zrnfyL0e*-LSeB4Z5784LVnXE}y$CVc6Tc}_w=MsNrp+_?3mNgR>h_tT+~WP+&dIpa zeTaTcU!N1c*F&|gMjUVHjUo#{HT((obbLjcLU9Xm8AbEmac1M>nX^~UNXP*Qa)P%I z9snRzSgOiQdx#GWA|X|Nf(%&|&wv>){N5lzA`z70DZ+VpO@_U$+TKi*6H(|iI7uV& z*h=__^ftC4K2QNqN3r}7Y)AoswnM7H5!Q}$xU%t9O_9f20CS^4JCIyD0+g13`mE)TQvof~3z1#dl=6NU0 zGikVyN1U8N&dBdg`SVi>cGrlj(%J5!%zw7YepWV_mn}T0U=eRph|X^5CEh8a{mRP0 zmF5(vdx{eFYIu?N>6i!%zEgUyKnv321Hs{d0U0aH$t7^1HrJTr8fG{up&dzRI6=;W zfeL``6bM>rvEO7fmDQkc1E79dvOXDvvmlB9pm0D@$*NNeYH-x;>2Mb^T%BVmB{)VF zT6^%})-)`=1FOq~TeD!pOwrnb^>bh`nUDa0D?d6Fj7Mss>`0DsXME)bQ5<7gy3^)1Tl$U1tRD1!~K(>39SUh7jWdssN-;1EOUibpgy|*)+`p!gBz1F4Rwk z5r@o3(^k_IHTx(Uq41bC8O*tO;XY_p(=R2(0~P3Cq8q3PSh1f0G>%AW2Azd)B9&R^ z43F0hqB}u~Ovn}Pjk}Gd@v)CZfOQUbKmZ$|i#jDRXCW+@a!ypBs@y&Gisy5t*L7g8 zTxNT@vb6C#$0)lik%C8=g~yHiFJ=`Tuh7)c+`w!74=A+C;#_d5KNV@ZPh_c#KYTo_ z(hq<5>OfR?XYsvtg*Yi%`()*ccBL5A3@t4BQ$ySA7Paqq#pvZKfmn6DeKkcSvLUOz zXbLh+m=VWAY*~a52any>d4?oo$z~5jp$vDxS9kAL7Yia4%zLOJ#{@}C@L?$U&IMHA z11^Ky+=&afHG(KC2+M-p_;8Vg-uCyR{2uJlaBM#S>lVPQ zmmw`aOvUVCAZJIIkJ~E0LS}7ug;m{)^liRS{MZNiYXQ5hU-;NoMB2*Y)@g+=bN6}m z;a=ySCaiOcoC?!SU5mXDl`Eo<2kH0wtnc%_3F@ZVf55-Hi?Y?U+tsr7i_;#K)1KBV zeh$6bS#A&Pr9^4j?P-EM4)WLMQ&=?0MScdJOL)$q)I?GsXKHL>w?%jt=Kh8Pj@Af!Xb6R@e zt8`m7n6OaM$1`?tenjA9nki_^s>q+b^|~zQ+@9 z){B!&bc&{VS^XBtYNBYmS~i6;PWFACiJos25$ha3=u>*90jXNYv5X!GUynqNR)7FQf8MaIRkf8(fBV2(7hg zaBX31QBHhmIZhL$HSzgQY_I%C7iXJzRDw>HEUe?{=ghbpS+gga?YnmW5AV98>+bA) zv!CZ|S7UW2WJb19zy|7VM z*&vlVvMiJS@&So@+k*!e#rK1GS*#zFFm>ZUJpSI*io##JUrXKw8 z{#JQ8$7ZeHn)4^*qFyy`aPO+6-0g`mVr3BRvPg3~hVrKL5IibedmtfJ?9%2+Uon?VXeKNpABJ= zjiY0{w9XH(@p85CGd?=c^?~Usm5#9LMny!I*1&bk7U&}{JA2$F0Qjf`Z67 z!G#{hZX>|EALy_2kYtFk8o(04a&_|Y_#B{(KiUy?eYnq{Xatg`kp%>=i`T%vC4dee zt|VyO2|zAXxQD1-q1tP6z?+-mK6VT$O@JL=zVQ%`9i(GNX|R77stgmZ$UX3@j8r0r zoPKn^cH`;Ev|dRuyK`EjFAyD$|M49U$K!K$o9=0zZ=CWr7%j<=JLmVNNbYVxNPl(> zF@5%#VHK&UFn6pEXL5kk z%7|?LGvR@N8-2j^)XAIz$9~0^y2$Hqh&5$%B{=RwFHimV@qVR zWpCQS-75ex%`}z4Fl}8gJi%576H!Y)Ar6IA`o4H~Zsi?l*S+^zF?{94C;1mukqAKm zV!LfiqenDi8N}Wk*bRfOTbA$Rz~z`H+ZXr1d4K|Mx)ZL9Sq730kV$xl2LzBJV(s$H zL#4rc-A+pMc})O5bqDPFXdx{GDNN|mAY6lmus;e{<2g5r!}XYu8|RfC2M(A(ZanD0 zvdbU~HX?xZm!D{I;emX_Uh+12QT#->vAFHx5u>aZA`k%>Ork=I>O(&>)WE z7M#e#vkXdPhQ2f=>>dLN0C#c}>@WmW!}PRi&?m*AJxqv>UvS1lE>x$7g z_c*U+-uQ*MX~Z{2f<#UN#$D>pSazjtT`Xl?0y&H#kE zkHeGNHAJ}K{pWL{)grHlU1u8Rvf1iGwF9IDoAVi;0#{W^LD!8){dzRtLUeI@+7Fc?^fB2vi=T9$++u|9z(Qu`pZ%yFWC>zIX8l2P(!^&;{xDC`+cT55s4A|nyI)IU z&QY&(pA?PMU2^K1)Nl0~ad&B=ZdPfx^xp*LbE&KDtXqBPwlLnAE?a#gYDWwE zp*;-=$kNgz0?8tNyPS{(Lk=jKnRxFa_ky4&S&b!as>4W^wzlMp5x5`On12pbHXKQv zP9sVCFf-Y5KJ-w8M3H}J2Bmd5^sH=d3o8rDwF=F__auI4sNnl=QEhcK{T(b7>%Ou@ zC9kUGq4f3)cS`#~C2@n)kN>$D$ewB>ygR>;cG%^1=}v3e!)_~B3$#J&~=@w|HVTiM~C7Vl(GrLhLZhWn-ss6SR#8Yq(r zIZZm13vP{h?^hu4t=4x|$EeK>UoM~N`NMWEd?37$Z2AnFcEI9gMtLg?82<>lp|F%6#I;%QIV`DX=pvuZ+5bG@pF z>0^}oOp>ylBo-*1AXDLlz(#<%J}y${w1oEe=0#z9>7>&~*Ap zT={Q2i)Q{c$E(zPCph*S{BhR)^pav=w3PG%05}Y+1r@|fl5dZf@PW>nx<>C#kT+pG=jIhAfzrI&oih~qPy`3w;@&wT`^fd? zsdc!XAKZQK+uMejy=PUi(s}P=j9p%@54fqUWGggV;_7{RP3sXmqlWV%UmPd9f;Y3*$ruADP9s}Lnnj|S>K!}4M3 zWDs-*)bLwa(Mgk%l}>zcK0*j0v!9_d_!*B#YH;t(AxMt93=*=r7NliRK2VTv(9R+~ z6cK4lLi0mJI$j{rUe0AX?OqKZT`dMGy_hb>TIHyIpe$uSpYv)Oa7;MdBHll@az5?A zd+nW3le9e+0g~f7`+rcv3vH*oF8eRl*j2p<%)Hh;1MF-ajGhRZ%0>K6|($an7d z-LY*ILG?d8rh1yFU49gI=xl~GG)>ttJ>+)ol=~+odxjFu_TcH>pET85aMGKF<54Z^ z^|9>63V<343&MzE$}|>?XpyGKxRPMa0VVUfXj1lP7@FF+x<#12N0er1Vq~ailf~_s zl46&@f-NF_YflH;w8?%iB@z@HD%;F7o=JvDl`w3$;33(ezVmtO7}c|yEuM2PFFbml zamg=sB*#wvarS}t2~CxSUoNrF=Y9I75!xWX%cuTA62tY;fq_Haz5~?Q*p_PJA`h9x zFymJgG&B0ukZVh4+dxQ@f2YP+VtCmE&1A5l?;68R6a^)9sIHn>@N3| zh?L@wOboxA(uGuiF$bKdc9S^c0$?m^Ddh{{DgqV(9t;&6uos&a zdw${)Gh>TRFKUO--ZZ}^U&Ymt)Ysr*cC|*rkYW#N5_^y01a&}zjD;JncH6F!F(%0-qxFCm|cyMFOE>w*XX$+Wwk!x*7V+vzs_aWz(-Umb(=m=_hjFWUj~Endd?e{%QM zVbyw7uym9*#)58JRJ#5xzo40N3aJC?-Tjb;aEe^mcrKl+e&O~@bSNB|y-TKqk+CzH z3%}>fLYpqaD2ZxfQydr5(zN`;WDQdHNBhRR-U#^x=c`#gQ1DpXk&57u|9;K9DI7ka zpCwI=h3l@DRFeJgq)ExV2r#b0UrdYZKEuCuo~}+=Ytr=4PWr=E?JnvE zq#v-@uj4MMtg;JuQlG9{494F}QLHEvYdb^Mt-KDEiNZ85FAYyu7=G+|T-kBH6M8aQ z@92IDKfQU0TG>HOm)_oKVm*vC8tr{N4OkG`PAi_rkwH!W^Wnxo8we7ZICvskA5Ycc zvIDKtX5v}iYit55(_o0LK}JTovZH933|B|WN47y(CV`oW8@b!VG>(if>-E`wBVNA! zW7WT>E!0(c6?^^DN#?hB`YO?PsA%&Op9;z8+AU?*atm87i!5Bz`d66Z#eB}I_3D)J zfw`QlEoH5D8;S~+*>yV7xU|ci{Yn z>i!y;*nqn8fx3?qU0$Yd+v-6^WS0ki2COP9MgEnlVlte`?r!azs0{;Y-1R_haq~t3(5-?)ERiwJ?R8CL^VNdnZ@cCxrRUCMV^mw6?)A59 zrMbOrDf|7&csR1BxkO_K23CrJnU1!T9FwZ{@==qUHNzyTB9>ZaFe{LzzOs{(lsu!)=2@Ey@JzBpCY`WfB(Y4ZGKsr=*`EHi9Wg3nMYFnz*-w^qxkp}>n zAq_fNpBXXDrZ8`B^-s$P+NSO3EXu`IM|$2EC7fre=dFm{EEYF3u2WOfc@x?!=#|g2 zGR{`dnX0lmy_$FL6zyRx@jCu)(z4oFC9$-C&Ai`=8uv%Xo6&c(9GsO+EHa~-MdOXiNx{|jANc+5jN?qG2xn^q>s(X)a zvP`-BEOOW7;3vF5P2BQjfb?*@I`p*RBWELHZic|85t4>Q+9nQ|+1feGOXJ zY4z#)2k!_)9N-B{e9zlh2V4Qrq@Cq7s^T5bOc*Ww+ zOT4kSfn&WocgiPeJwxwjhL`0ee&mh*+jqCRqfhDGSfsR5^4^-sydmKZxWc^CmXhDw zw!II7wgv1%kRff+=p{?`)tj3HQWY! z7=4Eg2Gxg2r)rDdDC;#6e47Pxoz*khM2kk^<&Sr~23{&1Y@TU(7VAjlcQpxLia)g$ zJD)$GHaI)?O#HQ#-#y3T=>HxzRnHBgZ68e2?h_U8_=3Rp8Ixa6;2roSqmG|RT{ZTP z`>JM)HWPx@PE3@!g%e67jP**Y32oKob#TkHbMfV)cm+c~RB#(K!b_;^mnb0^!fgj#r@E4UM{O-cN;^pQ_!Himf>)|+tv2h3863FQ;G|SAS^mqYkrDDr7qeBMon>Fw`wMgShtX|Xncs!Jzj`zg5b8>za+~n=J0q#8>}T$#ft@Dr_bvvL-snGTInb0n4o`XZ zq~80i()-uSD(9U-9&1{VNGc`mLtFoB8L6}kAz{C5qF$NjuR2=jC*_aMZ#tV)`#b>Z zXW!QUiv27rWBJ}tf@0fd)p$5HhpwsG)^;MJ|gmv4MWYt;*LOY67Uv(P?Od5v~E0{LFzpMUBCF9C28R{vrX3;NR)wH?e|ZdSVuzT|a$@G}`+bBq0{lKfR#?`62h z7+W)Pb!%Eg@-Ik#h@JaBdq&7snMN37v3nM0wxznIRb{D3t;Iv)Xh3Zpj=%x`1M~sW zClVY1vP9n!vf?rd(j;|JXH;B{Dz30iT-8jPVyZ~iR8`d!Wg>L+P4rAGjcgoEZMSW6 zc5-m_aCGuD^9nV03ftlsu4)sZXyr#X@gVE(P||jhR&f>A@WUAHl`#sH)H*1kaa@vm zLdxo>ltY}fSDcdP85!DHIfE>jtwl06)v`L*WDJ`0G#hO-`nHh=m8pF)Hr+BV9df%m zNr4aK_dZk$5m2JvZV8xE-8Cb>#eooY; z=KibKdgZD1k145@3H-`i`K9+V^Pfr6OR|r@kRE;}bS@EYe5PFcY*qKgvVK_aY^_4^ zFs@>WQ1DGRdr2yFN$S{V!v0SL?+{7Jc1D!9eFhF*vZ7$tfS!<{e8+$(#s3o zD~kg!6-Cxmow|5FB|kqqJtH-}ASSVN--(i)85g(5mTWzmVIG;}7#MF7m}wZ2s(L6> zKD1cYyO8K}McMx*HL6Z8vOzhvf_UnZLi%Nu+-h~sHI>Rnwd$MZS+`A+?r5Csr^NJY zMfY2sc<7S-#OCtkuH5e6jQdCPMvf%R?2q~uaP-?z-{qv8Yxy2OYNA)JrF=bm?pt=% zS5ED>x~8S3tE-*&S9(X@508wF+~?nGzuns0+}O}i$K_U6T|Ix{LP=I?V>07$yw9sh zm-#^Yf?w!|U5QIa&U{HbHCuS}T~XoEmDIV8!lllJrJ>%{+S_YqAFW37zx!SP?%MZ- z{_3;ew|B=@X4ot5idNp#{#dy6VfFs6PtX5+dOExI?Agqlx5CAbA3m!FsqN9W0oxk_%W z^~1$FyBmXtTd#~>q=t`FxwTy#ue6N+{Cc?U+T+W#ba7?(_J+wi*WxW9Bkk9pUZdB! zSG(VCe0IaX?eLqC+c#d^V)W-Kd)#Sy*%tYZ&p;-=?O12qhsRvUJe8eY?Vp}<|9dl^ z)n)o6W8;Ux!Uwm6=*d5|vmV6pr_mW3y#MZhEq`Yk(}&xvG>_`&6;9;DPwbVb{K_6} zcGgCRSVzuRuWssI_B-;A|Ltv_2WI=eZigSAtk#0gY*n?3db%9c_I&v1wv-pL@ck*3 z%`e=}-hH9KjXu+!EeNu(f`{p*{}Um zLYH3(BPPvf{H@Yi%qdxjpNrq1u2;l2m21BbK6I|LHjnyTM?{-Rh9a!~l(gZjHcE;g zYy7Edd%W$hux(dNxOv55-JZUL#mYmslfue=Ew??ks`~ac$81Jvl@BB6KMBpMbHLkE za(s)ktv0jD`iD#xIJ?hTF2;nPGyjnB^oG?3PTTp*i!q0HZ7Fl5z} zyIb$(%u=A2~1gw;$&-MHmU32ef0KBFyKLp9S9xOjU!C;Uv*k{pi3`WZc_qg zKGtre1jSfYwR%c+8eR;KZeHZXdv)D;n zubMYI-~ZUQHfH?q^o@6m!a%(T78j$3?9P&7hSc%^DOa-n({5TJgk{EFOvyHxFn{8N zpNB#eqW*po7v1F^ED)hy^SQF*A!ugcZPtecnW}%5n~R&@oA3PX*5iGe(`b5CG1K4N zN`CbQzkL&{clsT*|Mf}Xi#(0CUw0(G9kY7%x~t%Mr^UXZb+#=tOEqN~%qHiN+1Y9b zg4nL=xyx!a)qlThx}X%ala-{s7J(=AF@e2quR-A!|jMLQ5O=>uxN1ov%q z7`Qb546;69(8+TmHHSG5d-6gwML{%*(`jB^d^RU0QbVzN$R$H^LCoDVOe%{upr-D9 z!=Y>^{x$0zY(s!L8l$0z^UsjG>qmWafF8X$gS7U^=7p^1;TLF{{Ry&;@ups(^NE_` zq|6(#tK!Nw?I^?9!Rykx$AX+}3%7rCxgw~~ar1lfe0$fG^LKvgrJTj9{)u~3;2Ri+ zKPyD4)snI;#UTQFIvrXSWLc{?5Y95fmAb_qIT0PIbLjP&;)Dm7Z(u^^=AUr2R&V>* zi2lM%%gbtgAGZE35a5-tPUd$*?OhL2(*r4RHDs@Z4PHI(jivv*p@L-oo#g{y@vL}v z=((e;$NS&@3I2w@BaunaSDIZ$dWJSiFf+oHUN0l91>m_O3rr=UV28=07K34 z*EfGw&))@a?BaLr6Zt{fzD4aiS-KErE*6S9GBYWOnNIir$;`4_n61i6yrwpnot<>z zX?3aPK+v;Bv)azIh4IF>!*mVu5!5DDPfOh<9V3Q4efRTlyqFWlkSgG(lwT zOgp^0vhVoa9%a<7d*HcvZolGNUe-2NvSg~hyz+h1tg_Tk4I+Xf{Yl%t8J>Jk#g#9o zg7t_IcN1UQFNZdz4)rH}<)Lh+Yw&DhhO(ql_CG{zbM(#u1;Wa6v(FaizWZj7=W_Pi zzqY^0=IHI~jq-o=wigecSXNQ`G94qS-m0;HbbjyQeS}krpCt|`egzA*VYZ@tk zrlF3Ut5ckvb~!Azg0#w*mw1&p-FI~6RhF~<75qPg^ErwUOgyRK4S+Jdw}RAMYagx> z-A8AU=PXS3stN^zcVh1N_6+2xu7518841M&pFX#LCi?XzdbgOQMD(;|aC^GtvH)eb z(2Gm7Jf`w(W8WX~xqAt`?>6s}8IG?*@n`Jbk)cpDtgWRoyCYo_o3h^q{YUb*a)vtp zde*krvyxJqrV0`p0fTYRB;N>K)C^Cd;$$51{5N8*TVO_?O@NYmsr^omW;0`7s}01J zr7L}=h8=5?8@O(6tR&1`cIsMb)~z#v|94M$&m0mXr}jK zwEd7|POopYf(kt6D{by5XLnQLQB~4PQ``>szj>IfL*&oNS-)mM+^IoW11|KF1 zdz>bDjPH2o#p$D#L-vw8P$zGxE*2bh+W&W`plfY*6aTZWd-k(uDU9>zKZ)aG^Mm^y zXL!WWXyj$}JPsld$h=KPr(2 zoGL|KyofqMN8OM|pJ494bWkku0y^pcI6C*Z7XSbMZ`azjwYIg+lgc`;TD1;HinWeX zSqGHDs#Q~ArLvN2S8JsMNeE%3h)$yr!qqxTSi~oUbwDNFL&zJwfBXLa+ikb&w%xAR z>-BtIuj}=EJ|1@oFS}3hu5MeRirGwOD>$2TNdD(GVORRco!E@wOE8)8oT?u?h<)iN zGWUEc)c&O0{-o5->v?-5`^PZ5=wQKa5@zft!F9zh|DU3; z!k9^`%s`MhVI9+EnYa2oAstSgK@ih;DR0U%Cl$GyvTUXq@E#1pgoi17i9!Gv58=*koo6V4M=M z`=4fIM0BJoWnRD} zWo*xoV6Q|Ttf@*nF3CPQTFi%wvl$pnR+`olzqcH9p#)RugUJzRU*_f$FJbhP(hFB$ z?J;{uD;Gnjtub!?eA(WVOx_j+@2Jcw^<`xII1lrl5%YFs!K0OBuSprh{7U&xf{J%> z!>`~87DLi0bHBz(lW>w&Vr-5P6Zt7mLCjOWI7Lc4>8$xyN%$sD*qdhdB*8`d>0bAF zXKj?z9l(ihm9Q}hGv<%^@SgCVhbf_KO7!LNFSutbK$Sg&kh1CIiXA^)Vvn;h5DQz* z<%%%Ldl>22%8;55*=LuWOzgqrutIVaYYuIU+>7v=&&N8bhjdhx>?P#}{LBsJo_0G( zgrrCNR_4mG#5^UT;~n8+Kxw-4(5C)9&pT4r_k*eQvOSD~C`@L^dqM`BIxQupE=p71 z3cw)pnb@d!9t@@^2`A$;KPm|`QcW?^bJIkOO`GOQAD3&#!VU}&hW}S~r!TcLi@19w zk<)|8kYjer50Z*7#WzpxyN(givES-=hiotjPr+j^DlYUN6jSnnka=DsS#OqXL;&*a{_zdz0<^#v$q-4s6!C>Xv} zHauO)Ra9PEQvD(;BV+|}q=+~p0H0zpTmhIus^dw(2U(?Wq#&2B`JYwrn}Lc;bIx4jq#vPFKQcv1P zUBB5(zo{NfZO)PY4;6etaM6YBmj^JJ5{%{MlCvF)1lL4SFSh!64)MY}LNW={vpF|~ zijmy{_sll-6*oUvfqA?Hv+_4#;3v3wu)N`*0Ntm6A>hgWnT4aoEwB+#Z9YRLOPF6_VHN-MoiMl@4 zAqtC3NQY*n(uQyPula2quv+k*DhWe%^kxm|Ypsp&E7YBOE?;lbCWzbCv>54Ia<=;`CQ) zv#Wb`+xNJhg3N9IBkPCyA4D5z( zZV3gBnyr3(AKZz!Y48H9zPwE!2Q}ER=>VoU(oY2Y~TKI0Yv0REz)Y*!t^O~&Nw_R-MP{?<|Bs4Re-Z{P@(7v zch{Uj+^GO$=~S)cXsmnX^|E$N?@gKsG< z8&8AxmiDH}?~Rp!t4iycop+`#sj5C_A4lbVC@1$iChX88>TtSXc2X3E+p-`lkOdN!XYJfm&`KUZv`<;(eqYv?}L>1 z9)CBEeLYVFVQm5zpWYO{!lWn>MMIeV5)cJT^5kHW9KAyVvZeP9;0KaP`5RUZ2o(1z zMyd-Ii%!MBXPZ=s7jwuLTbL!`^c=LgQFLd;7KPOruTy2cjUeB)|Lxd4Y-xSy+=DpP z{4@~{q>gZ&*P zb?MIU^<#4U>sV4#+{4~``|8g%gRu&52EH>=S|9ee`F8d3x3A3O;N)N_ zj3vBGB!MGMAhh^=oBimEgW!|9#5od}OaWit`otV+PJtC;XW=)G`W42{W@wMPX8RNA zZ@Eim$5(64Nr=`^|A#Ff5}(BEC?)1S3jcUVB}BFoov1)- z|A&rKVqPGynr!gEYVZILw{i*t_m6cL)A zfM8Wp>5r4#0q%SXrGaylo~?&J#j$7e#;%2(k&nASf3@c2;XmkEL4WQLab6KK3lmfB zYkrjwzmWdNKN3_bv-!QHpJYBdl`{Q$z4E}J{ymS0pJ3uPC3?GxJPD(>!C&GP7)|M~ z!>lDhsPCXWr0&l1SHz*70^tx`qvf9OsBe3tG86JgBZPneeKzNALKRP2DHxH%9wfn&}G$O9!+LyuaOo!b3zM6xPhOfclV?P>5nZ&iBoPOMBC zU6{Dlke<|W;r^f=ezhxiw0<%EQV2dU>)6HgBgyYetFCR1D*STV?|YoTmw(7mROa`*Qxupjs{ljsuuwMH( zyl|VbN7koXsb8)ZJkbC3HD7FlO4L3{KhWa?6yw**l#|E{e->ni9cn8s+d2+O0vjDW zW{XSL4ppfE8eQ5FLgpJSRN0D=j*^}gqmkymcc#9sH(uT&wJ)PTVW6%Uu3p_;;v#dS zIXl7f&=r?2pBgSbHWB4tn)$ruqVbtW><=aO`VoYHtWG}9Hmis0SawO`j4HD=@J=JV zs7p;+KL}3v*VEsR`!D0a6fRnaWKU&3a`*f>)%IBYb?(EtsW}y3JX5~z1HEFv+p+UF zBl?hu!&q$Ln)Pj?Obz=EsyP)6FXWdxEspN6L3Z=mRJ5)VDxf8Qow(!JS;ex&o!^og z;S94BheMAf`<%7BPoF$|o%8C!(47f4@76~#sdlBEvVc_MtS4?kL3E>df8(rL5w7&~ zEq02r{K<|uEuuN+N&Zr{wAAATv+{C(YZK9)g`PjP#%>$`4LY|1Z5FU>@5GK>@sHPH{z~@a2#&XN>b$bg=E!Rbhvz5O z6`tkKh2C5@ul8gfXU};)f!o`uxUaEJRS~aPr>o2;_0wMXCA7Z)x0le~e~Y&L756>5 zME$=2j}dK0sJ^St<~_Ly@%K_5P;?1_nUcT{(R(|%g^iCV);*0^ ztGID8V|?!n7L~mCNa~tpu}gUPekj3TmX@?-Ih-G>h-QRW{ajXgv9s9ExSi?94b&o@qoS9{@2J~QH0x3JMx zTgGwg+nK8+jDmHkru-U16bh1c`qTe09FPNg(sH!Q-*?ToBai3*=r6N_x|rLgtR)s- zFpia`$>(jo4gc_#FYNSPzAdo(_>(VYKX#&BVuk|~ULJMpID)ZaldyAK*&*}fSdFk# zk1sSS$$KNajGyh(9PfbZsr5Bph{;e&?=!R$*Ozy^`ba_(MRPwHhacGSbaAdrGsjJ9 z!_|+~_=3e%LB+aL%WjYO&js`m5s%`xzMeVMJLT0=y!^|-kX$p}w?cw5qXr#S4(T?* zMNSc>s54t&vP6OB515-ok>d3w^nwp*T@_F4M)jU>(9Ud|h;4kt0sa%TM!`Rt+l$nG zit7yF-c~%)p=aauF8UL>cCq@!iojd(foiX0Lw(C_>^dj6qMz#KI@p$PdH6v? zXfbxIqvCvZP^*37G^7_1u*&U=x5+2dB9F@oqTBGKal1ug*s(!Uo^CPg($kvsTSpJ& zqd|X%&pnri<5YJF(hH;@SH4-$fF90J)<9E`k?(G_uwooo5yw4gUMyI6JyoKUsT~gHIa!h=$E%-PEC+ zk@E*C%!&0QS03-w{im239@ zdGC=mI93r;SHdg!-f|2VRV34uk_v2tghg+9f!qgJ&nw{Z(&S^nk~#&N%I_*|hk%ei z#JPGA5=bCFBj06-yF9UY=QxayfvYL5OXK3EQHU|`cQ~gGWiq98*>d~(bBnL{kKj(d z9MS895AEf4;hujBzF;`L)aYp;`_$~zp?iwS3ab{4&4PYxH%ars{rH@SdVjsE<;)!H zF^Xf|uByVQ@~I(nlQkJuTxQY6W6#V*N^0xAM*0U^R?WTfYUoU(9J2B-ZJDkAC+FMh z0&9vlZf`}Q%LO@<{p9Dt1S9&A^W|)+2NLJCPPwcF9uFFJxq9S#{?h;GahFO*@w`_C zxgF4*#-frnt~0nRc62abquI`7UpT4IrESg^Izc-Ga<{7p!@h3?h5YCPbL;QKZ~{r`gNA0UABEZ zROJ|puWhiHYLneMhMZ#U`*OFf)3f8v#Hn~Rr1 zh)+BHYHn#;4RPa2P5s70y>Bwx1|P)~J~pdw=s$9@qh+KdV_wzbi67 zr`IlRQL`oG;ZTMAyESxQ>!CegS=ftE()HDxQZEg!E`T+PjG_lEuCpz%@%#>ABISWY zo>zAH>$TIZ_eLO1qLdcqXh>3Y6xpqrc}qygj<7sC$>kwWCG0<`X9;$G37QljOJ0 zzy1CGpJ?Io{~p^@I=jq0tcrj|J2;*XMCW5zJV>A22~mMk7>`CZ0e4c>Wa#9_5Ir;9JQ z8O@t_uW`aQ+Bs-ltvZG@Yo2w!x*Dvx+O|;K`ujYfmJ3;T-1D#i1m+Bxd8d^GvKZ*L zpo7*tF`ohAcz_if7?@oB9cr}tKVJr5{hu59Y^0TfVIu%eE-|N-LwAc2s^-}&3aTcm zHY?KkPKCB}#o_8xYputj?;Tfyx`5TIYu)$M)|fGGLCnN>$IubS2|MP9v())&+tQLH zp`{%`_aST@R6h*aD2y^B2ebHO-J?c1bTM`GDxU#+A1&n2#h1@xIM@r$9RC^0pO8x4LwfDB$1TEq*WYv?9tLjJ0@u|j{87sqXLG*lSbOZc zEoBI5tBP|2AMJQ>qw>MO)kHm}chfDM&qs}uI{L44t}V<3#B*&0H1VFMd+`kDNCZ$6 z1DHlamRP_F3t;tt`$3=u10e8*Osj_cEIRcS2r3uSVF7->R|fg4Td3`>8)FE)8^2!# z*40?VOWGW;bhl{tRZor8p0*|$o&OGDtj+q^JYKCC=xl200ak%br}#qg)Bye*zYWr4oaT|Sh61;@rl%r6s|`{=~Fv5m-*Q8 zp*GoS+m6du%>h0^Hv@f-#1k z(I7pyhdMiv5uU@AT!6IGXG0nE{ZnsZ(aK}O!bIMi`}>|D?L7WgxRFG%$ulnPQ0D^f zV%JdjXS+pL#~#2iuk*tlZ|_&v`%*^YS&j3-(IYt1Jl2DqDTVw1@$m%5fvL5}w+?tj z1S|xBNo+BP>cDS)+hNh>-u%Dz;Ak#SoWu=J5KP9gK$RZ3&lp-qfJ{3^%~(hhW2>GU zWPybW2!II-peTjQuz-#ynuq{(=s>sUl-911Fe0GkJF3SW51Jo6GC$%kO7IFE{MQ?d z7qmH;Z?UC>rr38}yS0rd3Z7j)(dNDdLir%ep#Lo&sWXa5OK99P)JT;=RArDQ^}IX? zyuH8nQ+V{W$csaHtJyPf+!IVr96)-?ITVn?0=W%^996%=h3$s6*ww!M6N|~9Tl#-uIS1{>bVKY3o4}npi&)bybYX7 z!CjLd@!^svfPV~9e<4Oc5<+GGUi$;s(zTwsm;_djQU)aPp>ubDwz$@|isxoo&r!J{ znb%u#V}C}P-(Tku+FOow_tBbOnB zIxL|94{0tH8Y_?{(?S!ju-gHklnYDN2-&QHMME-R%o;UfOqJ`;_U~ zp5uOMQ5I|nxe+qwzM#8``IJXLTpxb4@35_hEK1??CPBZuy(RYB4jl^+<|lHf0oLWL zIQd#z(#KfJdYecnmM`Y>%j zgN*q|Vcx0>rispv)3xev9_51FXovDt%k( zdLn0Z#ttDi$3n*)-Xix8Eq>i>MIS<0g4aTTIG&ip7Ux!N|9gD%@8-gv4?pAxKvj^h z5l?0YixUErrfxu&mDqe5`EU&s8!%@qN0N9PJ%w=T|B!n9NWINSy%R!XN?I&exD^W+ zcchxIVwS<2f@^HD!3@q4c(M^F-V|ZR+qo?XDDrq{Hr=+zqyN2O^wTLH8sVbF=e2n* zBWnAh=Xucf13vd@v9f(~ONQNVojH!eXJ9_svlOzV0tu2TkMnnPr~@9}z?19A%sq0C zRKR6%Z_jFL@x6^7&DkGw^CtiNP<1|%>4{g8>wq)LFhgNXzhCg#1C8_l0)7O zq_QH9N2s3-GH-aNq={pdui8Asrera*6{3#b&5Z;t%K;07c)J`~7W2liFQ+gAX({-} zVmhhY2+UjqB(lKk8^JyQ{d7aeGaVf~*DNGT|4CGS^l06qhDj}K{nmA1VKG)JB)cIE z%aO(n!X@OtWVw*c5RzF!l9Fel6mAaqrN_t&RU!=sRDMOmpdZ3Fn`3(Svng!enRCFtsN1|{m8x#=(Gee?dzK1+Gt^u}fX<7&_7O&d;L<@8iKg|A2*9ZFcS z8yEe~RMbLl;YcfxsD2GydYJ0hCPatGF6o{Be!-zz^=tEnSlEtDmwe3dj>nR_?X>A6(pDt)LRY_=`h;|XW~qm^iL}?_zvOemal#&*K5BT74y9cw z!uj}IudeW)jr38u6`9tPa)O0#APo-bCf$8$tl{`4bisVAQADRr`W=3Pqa>kP-^ z)6I6Af)B59+8Y1&GF?sE7hWM}`r#*ooF97}4f6aG9f*s?7Y zH|}Hi%XZlD1LAR2!o36km7gFn=IB07NkpfhK&6}T^cp$IrN`+J-P>C;yDafkdY6-_ zT1QKbubHez*L#SLZCfLH@E|v7(Pe&k{f5vS%klS}>pwlbSW0hhsz9pjuIa^g=Su~H zSc|4G2pxJpOh&D(eiBG%4ftM+cM-_-9b9_C@(Do*+>(ao1FPKFuhJzb!yy5x zK$yPzzmnb7v&U};=xSzl4H=Av2SvwOYL?UYfnQ8vN{jE!PU^+&-dq{3SPBT#W3hh+ zwWmK%*suEAjPVPQz0XrdAd^BJiPHE zwy*7=!I`v9pI>v?Pgk28np##QPNTvfvDUfdZ91BW=mrd@5g2#2V0BBYTHgG5?4}xA zWG7&7(XH2hTUzngD~l6)u5u*NO#tbTH4F-9NNS|;;P!_Sux~=x^7#TPAdd@a(@HdR zl`4=AOrvW<8pZGu`H}kVBRELQHD0LWBSh2SBk6g2PubWAvEK3_Tm}97?am_X(3F1Z zRSU1Bc+*v@dFn3MiP9q$=g9*+@MlBS2|bvN>1(P!E^#3d-S=P|_zJBov(i&WNW*HJ zq3e@|$NLW@Sy-B?8|`~un$R%;7$_!fta$!fowaH~;k}e~N?c^agx(!0$pIL_#Y{5| zT6n#-Yb5zPB7vSI!^_TrRIFPLU|OoW2K1=iXItQnav zwV)E!C6T?F=_8O{lfvhix$N5U8AG$Gqdu`-v%&cEWvhOqp8n%Oi(BQa&84B%*dq(n zsO7>R#_781DqAI*T)vr?RjXZAU>j$;B~nq_zOtjhE-n->R0!0Tjl$||<XV8<+-&e}JKj6Z7)k!#vz9IOw{T>U)fG$-|c&=;yl0$(svCiqUiDTzYh6R1gt(=enECHZH_O%Ji zEoKGnL>b6we`30#BHbeNFO{S1(~U}EdM5N5%Y_cj)y$F+7vMxY_H;~Z`dmZ%;@WPKlFU4dHlgj9oo3AHPufmMoVO@WUTTU zNFl|*B0VFo&OuXVC8(k)Nnm?{<+;TmJ;GcNWG< zw4@ulEFEBOAG$H3gt)6*dQxZ8Uhhw!gcJxDPS0uhPUbV&+1@k3S|I?uqdNIjpUe}-jwh77= z`VFvk_f82gVJtwWM;9YQx7c`A>R;;+fVRAZvvqH06E3jm1=ANVZfnMJjAoRS;)}yP`)F}3}oDQXzGlXI7aTtt^%qC0; z#9vqWM3?UP+z^mvUZg}j3Le<{@5oOWLxhfi(r2waZ)!UyCVfc8N zNtgOq36(^eW@u4-sHGro4sKU6Nb~UOGuTW|Qq%}K>N^7c1tF>|z(v9~Mo7|_pLW+a zEhz)r1lU!DYd66*Rj_76$+C$WEOmtH2JM%7GNV_+7!tU#mqnDOnSM@g1renAfv)e z`>9C#G4j|QV{{+WUO~Qb@VRXr@SDt_7O7^D0r&_|GzLINpx6u$&j8&7iwBJ>(5haG zTmf2uz&0?5Qxx7h(+}UvK70~zuS4p&DvZndylYI{9AJR+(vk?&JCD-k45v@B ztl0jU5y8Q_B4VdNqYk#2gNOpiPObZKkCxmOW$tbklqd@5TsG2s&NZUenmb|n-eSeb zGHW)|Mg&m>GHa5hO%V`w2trmspc@lC!lc#7>;|{m4!oufFzrWWYInC@e+ayJC$lew zOwllsgaBd?C|4Na$^fgNk{t*f$iB4|R-6H_9*bv@xeP*b(N*jjcNqdp+gvjvz>yNs zT>{1?R%9+qQ_hGiGSC{@phfo8Y(n6;HB~lVI(^!@W#(PO0z1*9My1TANpJ#zT1)p{ zW+J3V#N$Vn1RewIMiE~h3bdLKXRbk7c%fFij4%(=8w>@{1jLS~L>1(wM}Ti)+9_a1 zN$Lv&gkxp;DytW!8L%nhS*C>RA;` zt8!UboWA;~j9Le63SrxJzNX2|(0#8Dm{{68fo!Xo2nqv95+EtCYQj-PY!y1#Mi)j` zR@qd^Oiw~yp#n4+1{Zq-z}6)OmsM#}1xxQuzl10*t}BEYLthYf4G7JKfVOE^YmlKe zhp-`aY2`Bh&jpiTpe2?0#Q86So~-$ba2RFSenDU<2n*d0xJssVjK8K4(nZA7yo}cB zsJ5ew6Zwbni1PbOcBs_p1SJF-ccET0?3B-NsW0(TCQe{wJ%FIn^6Ar}bsasKTP`;D zp8NCKa1B3cL-9rawz$6=yDcm(=j6$(+4*(1E>g)9D+^1jp2MK4Ol=gf33#X0XJ#Mw zZqtt>d(N!=7(^|X(Hdk_5(A+ItEL@bAW#e#IhU+ri6ObLO+c`UNrvWfe{*0YZQCM& zQvNu5dw4a%E?4DEmoy|ahonykSYuoVf>_7EFTmHC8g}htn0W$5(SU2fTK39`BLW9_ zoBTEGdkL+=s3Jv-Qw0oEB|uOLv@E=NeGEG-BsTK-g?Z|nIfei)OVC0jeP zY=sZN&%0>NgIIY?tAJ!`F7r<*(~4?o6T?KgL27Jh^OFfwaWZWPu-~!21+}@E(B|!EXx~ znuag%FKr^HVf>Hiw7U%40)kit6CpUwrcSE?f$4y80tTV;DUKfCFbCQX3c)lb(3JPkjmn7@Cva+EX^XIy8rDY1AgJi@Fl;}{Aj+*&pB?`&3G70` z90Nb}FyNqIOs(5tnn_<^)&`MXs??TlOd2%Xlrxpz^2}l_%WNnI;2%nQC{Fr&FzL}L z>lG}(I#+el%CurLt%{h7COa><+uOJb)B+GTwXT&h`1BR@C4WxLVM{Y^-=iiR|LKtAPl59ddMB{ty*(TJ0ma6`NwJ3 zDa1JlD*^~=-i~VC7uk;)y+c1Aomw;I{os14>r}VrG$$u3&KgeTJ74B+^0w$nwGObg z_L#Ni$^IUK>?>t|lY#xUqktOE%BXoU+472$vOZ1*?6!A!YHc52Nh^hrcm{Ney{J}c z4^j{SB^Z$kV~gOos_xY~!E%U!B{R1532;qJEZ&AFl~Fq=I{($EE411Vg%R5zcg@#X zcVNS}44g-(3K5|JGmsu*NRQ#iQHge);jfyY&AA1(l>jsiW7HU+$FM4n?2P2c_A|hF z%$pv;n_(y7g1}BNIsGp){<;juYH}PwXw9Vs8yC^rn;l9SSS9nT)m6H@N2^n0zV@nk z2K8s=l;vdi)7PjK0g#1~Gc?gudwutx9~nb3nq>@1b-pdvu2+?QsDjJLZOkWtRE-Nc z_1WyEQjO(k>L1qO&^V8&oV55m$|ezgI{kQqmI4iFcZwoL$jih-A! z6Qr_;F~ZeRgo7$#F4#C$1>hQh;3E)rj=4U%+d(e6NDVZ~b`0L|I4HzyWIW%Zf7u^j zZ|gr9{PeG^HpdOM|5!*{m$RVde5MtPX{9RPc`V;=@{Y>>ZtW^S`M|Uk*`|+QEh{01 zkItxgndQ)gWzXvdunj3{Ml5m#q6^K=#nP=uN3aWOI{&>^J+axXyyE0<)Lwyf>WKP) zK)s_1ohxW^YgDvAa8}C7Z#yG+XNjXcm8b;u2UZsd&Rk#|NYl6DV~Ir!)+~eA&YU>O zQ1LXHXdjQ=fz^W^etkLUe}(C2RPI2E!i~bAJqX+Y13&*9Uu1!A_{QA6l2BfUmO=wR zWR8D;pw5hfUqeBKD-GXuyZUt3_<27FeC_G;I%jYCzgEfCZLPl(YnT7Y58DmxKOnQ3 zcHS?JqjGLRD4uyL^Fj)6$=gj74Ozy>HYL?Ngf~a5P(&CCnurKYoyvw8F3A*tMS`vC zw;ARrUDlpmR3FH33IEb}8E#Pk-lwI=3>c)bu#!P+n@nZu($P{r%&Mh%hx zH!TB20%8+Pd8xVWA!6_o1PCX<0Rga)fvs|iGs&XNK-a!Pc5}?&{d)weceg26qY}pU zK!j;Xl`n8opmLI7*ACz-83zOmumQ5Gk~t~?xRLVj5ATUv**zU~ia)`l^c(=w@CrVY()(+5XL<+*6!b}2=*5pcJTfh^eo z6b;$a_lsQUV_n8Jf3DI}5y%K>TN&HMgaM8%N4mKX4#ObjB$moiM=V~q=t2;vMI6VZ z;wNsnPJuc-OBDt99>&2?2DSl#mp{~qoK$a+UH=Ln>4j}+7I+Idl>7@9gRnu=;5(sF zy(B#8ogL$*${<4PEkki0#^f^8hpccS*z6>1D_@~G5A_~q5+(5CV=#W2x$Xl%>-cDA zw4M-&SWzp*tNKVffU`d#M{GBJv?sS(jepc*9(&8W?oZ8|e2c(1*U@vVJFp#{(83rd1xaJVr)Kl3AugRy;uH0$HUppKM26YRtKO+CA#OKL={RM?41@ zrN#B841t=V1KUji3x#+?Khh}MOjM+8>{cp;7flP)QL4=^oHpr)U*Z&51Ap=A0ZEj| zljTQh)z)j-WSyjV34L&6n}|z%A>dQG(JE$6p+puIXs(WkpdMjvE;DQhY##kmt7pM- z=TEy`iB&sfv?`)#ftS3oajD~qQtfM(Pn2!Dv+Yt`g7*ncLsP$oCu!c|7uy;W6;)38 zeq}lo)eF=8;{Q2rzng~+UqO4(#u+;GZt{PJGj=?^7*{Srat zOczT1^!4puAI*f-um5D9Fetiz+&=U~V*S;PAN3cTBX7D{$240+PUgPT-OOK= zfL_X#&K-}QtsNKXx^dB#CcFW(K@3lxAU4Tq@X}kxqYLvl)5_sv+XXj=P9#)>_MPNN zLNA;hj%yrwvfk-orR)9+T^DY0m0kTS^X9eemu)b+M7TL#y!uhcctxAoZ9~gG(a{Yp zU+PY6xctRO=O5=^%Wnr7@esiF<%=~wI^P|x^k{!RTi<$jNBGHt;}M*$dIL>>qL7G) zazs9nF5n`{-LSF8i0;(btr~%J0pegBj4V8v9DqEb_w=s-rK!8LM&uaJJ#tJpgzj}r zI}kP%YXvmGB7=0crAU`Gsz4jAzGt;JY&H1DPZCu7pA!cjH3(^A(f2E=_Jhfx* zvC#RKT5Zvs_8KsfXX+)|7@|BHa+ep2_A%Oa(yMSIjUg1H$kV;Lp$;0o1_>3Wi6;{) zh2mv_%k5vywb}i>_%zwQ=Kb|t<&xiL_k|qudA9M$`WBt2<}SaR>nyTG+LH}kU}v!H zNx%PXUp4dS_68$ZaD=^RSJRWmJ$H>0736Tg=fsYbO9ho%;)L&@T{>=vF%*4NQKLnq zGDKPoa!LM1Tca)cfIGsgz>xJa65JFQiL@%!bnsH!c$J3K(}`1ffst{i=mil$5-(6I zWXZV5fM4W=Dh?X>-x1c9nwn#*HR@>4I7}izX;OZ(QA9Ut7jQi&($`?S&v>yRYn^T_ z*>`Iy9kmgQN3V#~u$}u_Y&gwOTQe<;OH{dXmP*W*GSFxmZ^;9-e3!BuvGb`=&GzQ< z0((`lOZr7KWkA02C;8YKfs6XPu}^M|Pmb-e(ozqgCK*1R?pf|0O6cBExOuceY}Nj) zaf6QpskN}!W99tCWIm%s``%Tb{qN1stsjlk|NY`HH7-=Ri@?al#SS2y%aNKrEoyoP zNf;l2miW^n)Y3pao?8xVmQH}n8eni!4X~+Fq1VVRz*DF0kt!*AmJOS6aj}3#!+OwX zJ<^Ur0(3bFHNOC%ngik>YlH#TOML9UJ`2;i0vuyItT7oU!{rO~0#rWu2a zaBpR#RtfrZBS?XlIHZ3mju~O7t%7~y(v>((B^&JQMxz6SOSZ?v8$6(ZPG;y+ISbtd zpE5qwyL~^L9C?2Cvnug!W$0zD%0Zwt{m{i9KMvmu2DFckM!zjCA|%h1=>)2zKm6x= z%DNLKka)I_rJGjM4<2*R<1L%W2VzTpjmGIp&igw0$(s>m1%SbxK+$+YVy@uOvZ^{! zNV!T?@fiUYb*ZOHfKT@YV3UH;AE!Wy?<>%^1O>L+zN{;8Z9Zy3@w$^rrxPO?=4t%IQb)3gD9{F^eQQ~_d(6S5+L2B!kT88o|zP(&KuW=(LJhmp4@B0x?;6-%1qya z-es3TGL7hvfmg}uWrkV7`?L;&COkC30->>8X-2-=(d%4%1fP_jKQQ`*+wg69Nb+Zk0O!Q&uit%tQB@r$fbB9X`u% zHK=!A>eo`t#C)Keo_qWd(78rJAK=#X0T~)7Bozk9Fp|I#s4b-kFvqX9WHbYZE#(NL zb5AX~Mfjhr*lghpa5|wf!2lPIV@a(TI3&#|uR*9aHae zQ+N^LOi?C2TwPQ01smG8lI^to&~rOL7c1Wt&vvc4R&D6ud90|+Yy!1w0b%s!ly~*( zKu9|<=GBQ_TK8N1Lx#Oe99~%s7TM;-MeX1Axb^B{k$NyEbj|#w0>|Xx*U_bbo~=EM z#;J^Pt8O5cki9@GX;MpsIABGp{A~LWxoLVrt+CvYuuTZ*RZET(7FY-~Yor$eN3`BF zBJUelKuA@f)c4>B0uBPCDRh@px-4F|)X=Ld_5^unQY6xt&_(@<7#{aoowqLDT5k zwq4EI2DW9Re&&Y5M~KbO#~$AuesM6Qdck%22=if zVf`&@zG?O5k^YuMSHi;va4Tq7xmZIaQxHyVMIwfLX5$>u{Ct2AUw0hfwfZodcwKl^ zS)}2SL@jKY5a~+VtR3SSqc)8wT?zLQDNQJpo0r5;3mHg1u2(}sgE;yc9m#awf(|l3 ztl#>3<5s<;J!fu{`vw4=NWCjX?l!x4!AqOW(4GTc4(Ufw`m4nn9{Ir&b)C=>{o#TM|jydVE;4X>E z%>!MkK+W&gOC1mKu+v>(z69=DQWd*0q!qh)KmiBUOsg+t6d0PB7MXczSDCA8hSW5% zI^OU2NhA(Ax9~0tbsD_1DK$uPjn38ezYGUg+agPx#}7ij|K=if))eZbjvG|^)T<#- zcOB=})FJ`|(QXoi8O_&E^5<$Z!m8}6A7Un1ftCiNNH%B>hNJHLzN?=A8smuvLN8zu zM#$c^21pRLuwDQKMWi4>g>Dc9r7uASd8wsRbeUax916-vMYmIREY{V(9NbRcq4y`j ztnRa(j|8Yp?%!srAF1l=Ar91r=*`OX66pr>Oamnc6WP^E6X@l10XgIPoY>&esc%Kd zFjjzTDc$&icp1F~SCCSZoUd(2(Wb_J9~%xQwMNuj4uPOJ~A;y8rAHS zcBNGY=twj?JLBb2t~_;ok4KWuXXS4!4B!|DUd#WZ=*k0`{{R2`z0K?}W;W)YdyZ;u zAKiFh*7WRuJJs0n`d&YfgV*NmbG0%Fz0# zMgn|X6$Hx#w#i(GUpRoELVXq??1oG;UVer&riFB9_Q(ALM#*R-&TC7bDG^B;evT2dCF_c|tiU&`A zvCx_%JiSWLKg zRgun{2K9bby*0cO^N0}>bXk<9fly&zjio?Fj}Ad743bOt6_z>;~0s$Od!or zkxrn_mOp71iUsD76-xTg*aw%D-N*^5 zD|Ix;dcO-vKW>o_$rW`9ggXSDseUL;4^%y>Ld;|tmVuOCtSiETi9-W+9^T0FPf%)A z_KG^nX}S)&UR5SDOPW%S+Fp+G0!hm%uXI;j11l4$m#(?X!I_dY|Y%k~CuNR6wBn&KiZi%d+KxvRl@^jV8vK z2lP+vawz_0aOw+c$Bm_{7v-ws{dN}{sNb*Gc_4a*7U*JXYTTmZBBu=G3T3>_?65ePG)ne{z zwzl$OK?qhxoeugQA691qSRmf86e7sCQx`lVa|^@-*7@O3)PBNx1Js3uhxJ4LxZqu^ z0S}Ncyn}$+X!KS&e#%-V0h9?@#4`laaeM?_fDh%vJXK`eNHU@M(m$7_Q~HG4G})_x zvOG7t=F;$+(%Z^c!mj?-KcMqiN$WAHnP-p@5qZxfGG;4M-a6`}Q5E;2Z!;JjY)Die zvq)Z)ORk!#HUj*zL*8!1;Z;Fk0Dy&R?EQ2#1Tq)I(qTvXPM#Kp>X<;Y4algtAN0{!|#l8n%@xO<$A_u)didNX+hwxXO}E zHa`EpOL_jOlIi26we*OK>kiQNWP%QQ^Podx{DmE37j!odJ#&zvZGN{}lp*dW@<5jM zHuWTwkH5DMu+s;|?Em{5;rccVuagUTnL|R+2~1Hq2v{KJld7TW0#A=D!afyfM^o^`?E)Xxj00Ei+N~EZbbN;w z-kX8P$3wzR2qtlaXu7+@BEi=hpG=qWGrr7FndgSTGWjB%P$iRaQFb3$Fxi>!xRrm2 zKstRA_Zx2TU!p-V=kZu6XSboB{^v+n@ns_^KMSy0|FK2oXr_{mNn4*xNf-pR^jrP^ zWB&Jnr(rPaJuxP1CkdL=>FQSXpO5d+VCuzq0l|!_8s-6`1rkE2tnJ|(fR_&t`K|^r zAdy7a$p>+K@LdKBOQ(L;B5YyvAG_A?WP(&CWGD4CmJf}9z+jSI_OXFoH=*9v!X9sF zr$C4c>m{lMg8znR)K^~aggJq^Cs}ayoAy3cac5bZFK=#IddqI_$QLQT*7#kyy2`iU zj zC)c|Q3JXwb741?|B(R&atA}IQlifb|s4~-}fn}h*nY=qtm`ZW=xeQU~E-6HQ#+P8jun{&|9bCKdRPEX(6H3uQ_OXIsC zL;+yOS9|@jA*n252f&VGOHwum?aQR^0Uv9YPrE*hp*Wc+pF|Cf=>D z?|2_PS_PlbNpJ`hjSD2irr_tdx1^K6kvMDHcokyYw@RUoC;{rb<4?b{{o!W^nTFA* zo(|=cMuz7kF1WtrjxcWZ9576~-99vtY<#M^HBc%^g>$n{(&uo8BndF012ArpJl*n% zcegXW!Cn@MSO1JkfyD{V?^EA=lLmRd6{~n+6+>13)DJdczQ^M89;ESM)qkcP_$znxu|@J^s; zBFkW(iWH27_oRwuhWkUtb4_w&(iaiip2W<+=-6OWoj)@kAC(h>qid}XnDibxcWib= z=H1Qp$Df}ba_)V%eg33aLEYh@$oZj;`3qNvwY#Ovx}}m7N17Et92E$Xza$59k$eOC z`Gu;-_d*2tt|eF)AQ~pPZ$g#v?Sp7?VZY;bdWPcR{L=SDfQudh7Xnb|Hov9l#}5)h zkf4&y4!vB^im7#^4>FC`zUPUx1zwm@pNOQx#FC%<-9vEV@`v4}15^m1Tp8c06Lu<6 z4j?|eRWzZ>jmp9oY3ChX!$&UO?0h$7iKh_6l_SZfam#N!l%j^=8C%xMk)!GCoZTVG zT^y+X$tS2_Jlb&Q?SH2^QL{f1Zm(!d-L5*Y`eG`x{Ek86qMW7NNS-=SeOTi7e}EIK zcn5R4QJW7Mpg*=4%>GS<8VcA5UHQsp z+~=eeTM#Cr=gXl6LesHI=59Y3!X1T&yiwdJKk#A`r`@wkPT$5y&rdJ7kaiK}gY<0* z8cKQFl#Zd9_~oJEQM0Xb`i%Ex$C@BIhdaWue%EQ2QG&)wjDzRhP@p6$EdESN6JPYxpvqZ5Rj*F$_t!v0w5Fh)^LbA@9;Lfvyj9Gp|JJ;34hO? zETO-M309lF!S=&sx{7Q-7@G?ft8tp_(-D7OYAq^9TBq778u0+ALW7MBtnITO1cW87 zTUW!0lT;C9?v}MEflcp&DbcVj5j7&0rPI!!q&PRkby=1^<$Qhktawl+*p0Kf>G*liZ<`Vl%6ymf#HL5jQ?cR3~hrU;U#F*=EY zpkXwA%UgenjR>q)Dsf(-W0T6>m+j=!>ctwd0vCf z9e`5$Fkwt4w1Fg|#_>jm(YGNmF**n%Q)l2@5KU+Pzl=_YeT>P*hout^iHN$CT|*fS z0^$Hm#EEXZSt1bXD}}5j4RRot4{0m27xgU6#$^U+++M}%gm|J42vnsTMu&FzwB;Q6 zQ!R5tFr;&qnF5cBz=n-<_2}TPWJ&cP^#NH$i=sjfzHJ2=%L(Z#D>e9j z@qN6Tau)2F|Lq?VdiFK@GputjTN+x;^g0-Rtq=?Jh2Q4?e5+h2)Zhs^4S#)Wl>63v zl#8#qUcDpSB*$+ynnJP>qcJ>@PWCVo1q_eZ0kSLHkwIK^_%Q%ZVt9*sPohwiPr#i+ zRJg??Yg<&f4B(_bL8Y29MvM14he3q0ndCd8l=~$eLG=vDW-VBci4H~ z_r{PPn=^l39v>U1Z8uJpo7HV(mCvm2Vr4Ap)Zn@*(3w0iy$FCQP_u>T905dsZaKEC41;s6Ron71Re2B6WLX?b6 ziS-mfWw?BtD3#@Vgbr<3y`&SyLdncmXWjMu4-7f0NfeN zJIrZHAqbJ(UC|ynhkpi1G39WE-PN@h19oxrTX!B2BDLIiw+p?q9losxD42eRm(8_%pEoz{Ol2)2suLcFg8mAYC||=U>n! z@yQr>C`pAST9yLIDKCMmV_E1?Kvc8L9T6>=0;lxDjLiBX1@*#W$VsRg7ZC3Hm@9F@ z5x>Ah+R;)XWa&^Pu0EKUSu~6rhiU)9W);L$eSR$CXS@Gfr{l(GE_I|8R~~zsCp9RNw+Xc?8t`{ zi7(S4dOl-HqtXxkuZ9;)n(R4w>HZsHUoE`2;tVEo>D&Xie-H2fB+On8oBv-e{O1Gc zK4AL!S^8m}h1pw$fV$j9rlV6e9+CK58$n{iowx*{f&gM7NFjz%0kOm(v9p%)kV-Rv zx#-4&g)ldtXHJnTGpFUcEuj{eNm7zlpYk2f~>ZE?+8 za^|ubn25^_;|E&aGdNKC<-xx+D&(&ga9Ak{?9}I0$zijcN|vOGnS6*e1;k7^5b7yu zhjwvOB}f3Mz+~yF)8)OcB>E;t?K4#jVM^DlLXo87XnPufM&y(sKD2>k1B}rZ-m;_At_NJWaFnx|Zy$ zz7Fk5smeX(-B`CB_pGb*yXDuipw4=-%=k#FsKMoe)9b|w9CeJB{b zzgs(AZtuZs=Q0AeY7UpX&rkj@!n5YO#{f=#-+llZru|LQ=dX!d@SwV;3ev@CNm7Pe z4hEJTG5s;+}L?iqhW6rKUpX@EE^x|Rzz&}lO577a`lbq21Mfx3qEXuJe967m2Y z=twoFIS&<)fbJlnhmA3nG>mo~;j{{7L<%!472BtklpCVK4oxZ;)IS{N^)MrB$B5Uq zGW66bP+GnwZB9!wCdK>9#ekYw;>jY->(+5sLQkyP%I<+`xpgK>aHt{2$W10T1QX!- zAW*%CEXHO@(m-)OLW%-l1c>}eQ2t`1ya1&@3ev_xNsJ)Hm>>lKC`AI$GyvCU4C5;) za(tirkoFEoN-{}#$0Sv`DHS4+inpLB2fW1qGm24l>wfA~kYt0ZsySIpKPklNZX2WS zaUi!YqMHEdZlU;%1EsE_swt>jG{}7_)rC=OGXenaPY2@0v&`?0qm-z{UI<`RO!@Qi6TR}hJ(dT`i`s$ z=MAVqN6FAocPN4C6jVJ0b%%tirgiNLG_KfWOz zJVac<3Z-3Mg-3$L(Tr1#uFjpV@PvENBko#%!f&reSxKOECs zSw>2pxp93F=_aRDf0?*aWBAo&?`G!{HBv6A!$zbFErG|@m`VMMBlt?yET5!|$B$yqnlVxM=Qe&pZ zOI*_LJ){k;umHF@V5SRRO9ktxsCGWGgMzwdsMg3NQEX7%9CR}sdY6d~(uCgNUuveK zudkz}C`~DMwa!3aD(0@GJDdnA4qQ1;I4;kG{5`Wgy ziMAXImjI*qSWEl!GXjlsx_!yI;X^C`B>gM!XY9nq zaYTd&c!haETl;Q8KO$@lamW-|u%0ZezCbcS3ghUu7ahvi_JUGt--7o$f)(jN{jhsN z>OBNEGSc*_b~>23qT>bKK@j?DC=d-AAcIZY&ZB{ohf(b`^fel)7mAd43$`;+CA8G9 zvCv*F+H?|X$%R^SpgIg__awTRlHWi=`Fy-TyYBQfRpJoZ`}?^Eks#kdD{Q+b{kfch zh+ewVrhnqQYNg|sp)XqvQDJ+=oB|fBRi!Zg)5M&`J#BG)7N?HNPgv1(Zn}u}zwC6e znCU`oCFelE9e;o#0Eu0%lf)u1lfbVPx1I^sQc;|B zWCssfM@2C%Uu)r@)i~RSvB#mNOen7g-8_lv;G?ZKkjIXr%5bP!E^-rP;2$G%xNJ|s zA9cD)%}-w$*pXJ(BL9(<2TDJ@epC6;#DGcEd5qgB= zsinl!#C6G-Bs3MDF_B zk*0|&-0tI1TJ@zskwB(^C-47z;;SK2t0Sbhq(P1bK>5JeUe}K;J)Ws0@7@8xAb`~e zKcs`XSV?4%uu4sVupSLkP@h?T$^oOrlcjJBl1LE>lfjWc#vMkR2>ib zlnRQ|P&gV&Z3ubZU|LctY-Go&zEA40FIpqW9d8eenMQ?eH%rWY@Z6>}@x#eud+x>R zujD`RuVzUXB&v9u9CR+4lD$HADF!rIqvuydE5x6@ZrOO9Gd%wmZ+g6#ZXc5Eg#GO8Q|A<*9}u@ls7l^c#d&Z~0si_Vcee-h9tXNd z0Nu@mn)6YufLIkBCChk2prJTap2X8;){D(C=8iiDi!A+Ist)KWkMHpY;D_y!%+ z!`+!YhZ0h#+{x`;K8nXhH!<_e_sA)VK5$HVdzk!#0b+lCel?!4>)QQuQ{o>6WH8t6 zr~HCj*{#x)2Ux$1d}~En4c}be&S#Kfmu3f9#xXd)3pjwc0#N>iox`(xFgF*)*S2n(A3^7eA&R-mm2;Bkiby4b?-euSqFzZy}y!trI)t8m@mMO>19+ z9+zv-4!3+?D^){s4sWclKcmxhg5L73srL2~iVTNK>87+lc8O^1Af6$mh(MfxB1gH0 zu1rzVHj@i#Xn`omT_wgFu;F%jt^NqfmEJzGy$p?*#bX2~AKUvC=sYXU=(UOGZ$)R8!C`%4PZJnJ%lDyUI{ z-3JbpcsTvifO#L2OxqvPP?#=<+bo1@o)})}~^`dtW6Xq(?S6^bS=D?&iqES?*&PK3M?r)Gw#w5Tu!+@%nA^LUtSF zqq^4{5m;ibP|rQ-#)LYNnQXXRR?CiA1-g(D^L9Q460NmaAZ;?jb_E?mOy<|>AD&Gi}f$rKR3Qb z_nyOeJS&2EH<0c(W29A6=RZ1?$BU>U){9+YP53FAIPLNioVn5m6)%IGu9rpHE7Ybt zb%*(6RKFh_b!?c{84hnL36JOgxdNxp?YSJuQr^JfoU}$%%a%lH*J3CnEgxLb3C%OU z0HVWAqM<IHb#ECJWl4ioZro!L<@&69=JJpJq8R-3-HV%x^9x_soSGf@_V-hg>`WSO_%`_wy)>%wUO?rNHtyB1i-c zK#7q!IBE`z3}o#u5gK~AX=HV5ws%N6Vf!9pNHZ}eZy!^Y*tb5oGjVZDo@g!Oh;`5{ zT9)hY#mK)jN48pqm`cJ8*}5t(#hT}eA8X%WkLbuSNwtz0oKatieuS88Y_p$n-Q}sD z8SXAPjLhrQBf5jw&ISAC5Y~*Qy7QE}xqeBLUExvv=|aMC*3gT$`C!jxPzk@G2kw>& zp40Y)xeX)2ot6Tj^kwMUTcp#dz5y{3fD*B^Ue0^{Jw@nmE{mCt)Cq`G7gZa}rHC3) z&*w4hU_`2rScDLuRFN7NeUuZ-QEG0%PMZWEMTN$ADZ$V#@}l;^ttGhr&oqo2IoHc` zS&l0-lF2O+Z|S9}W42jNJoc}--ZNxt5tULN_IOdBY;8=|Ko+y5Q6gMJS7oAm(#~#+ zTkL(K+%hDyg$#S#FFR-#SL5(rkd}8kK+@jd#m$&mRB|pzg#1gLsP;Wex}DfaaR?lQ z5H}EpU+s5v8yZ>I3!h&&=zyicMF!)4pr0$37v;B2otzgFPzxSRdEhzG+MvpWxkzOY&Z&D*$GM8up_ zS)$#Z^A+23-F#$m?)qul-wjie&ePU0yG_(R`qF71WG^-khLJTK^t?JCHF`_pftS8r z34It_D@wJ&6(riJkA1apC=-LsG3}sA1H%Z4hJ67b3)kuh-m7neD=x#yUoV-;{FXM7 zXGXmmdbkvgI1NdPu~Rch05C8CL>&8Bk8Xl?rv^!Nl)>tpm;f?_3c31|O*UX*0=AZ9 z?q|N0%w??75X*8;f3med7cp}j1X)(^D{a4?JK+x!Z>SVGFJ)fb!MAaZlicm>w3^-} zgR>)vPCe}24#b?&gvDTXkJ9rF_@a;HAO2HzprtKq=XU)_+*Ohbq2lXc{cHrTz1)9W z3+sv@dVSZ6`ZXnls!HK&3sS|IY<2Qf?GAqn17W(k`ce^KVo2&9?4wi`)?v zX{To1^MtjNKOrX2R}*J|uw0FxbbZVS2tgNn?{ zF*bJ&BezcVok6QheO~M!8>zCB$ZDPGS#EJ*9JJTy&EenJxBL@%&ffM8kN1uFJlAMu z*COQS=q|a|7Evn45?my^a@2{|k^5;-hT_Zp~-|Tev_R~E`zC|e59dAdy zfbzW1jo*3h4Ab}LUxb5LD2S>7bZ+EHi~gCAtYc6gQi7)h)D*lV2Np}6LZThGczhxo zdgK=}GHFTXsguqw^QzZ!Vgrq{t8z58DH$g-RUEJx=(t{WYV}Emzx-8QcCPc5U)%LE zr(Flr@U>>8b^~%#TzR@_t5W5g;4BFxhJyl|u4W}ZD4M;uCt!NK?ZGXFD^xcpQYGh7 znIeBwi*yDim&3fUVEX5Mj{_IBT>*<+=(tzWev=OD=jlCkG97Vgn3zFd!l^ARW-^`Dr8d`1%4vvi{JX0&cQe+xaUVF|u32Tm zs5I+4+muSL;N~ZNSuHht!+$nk;v?9kYIrkTuBe;kJD^-$@t^LUNtFksJa~CmMq@*D zf(Jsmydq=@nNmh*<-ksygYAUivcgJn|&li_{4ymF9E;`aq@lc}vxGE;=X-h5_u7?I}5XD^aK4@w$>n&$Dx z%sX6%R+b(iNDHUk3|u!;>q-ybHp9%0={u42Pc*=}^0oiA zg*zKC{8;VCgt?4b?9XI-tiks4a=1>;E)+F~Ns9;cn%T?Q%V^6sv!Yx%AlI)q`|OU% zuf>Fy_DeB2DtFt|konBB%$rmZ(JsJ)ns%ql%xRSE{*zrKcgvY}vGHr#(N$Og5A=y` z@@vwFz^2oA@U%iUvtOCuoLNZPo1icd8BK8b?w~%*y-f6p(^DNUyW92fiA&Bs-(KmY)_2HOlWxmC;@FgT znN=3xNf8-wZ3P#!Tn*Bc{)355un#R1ziUbNSWTnX(0_SXT(vRw*`2r}GKVZOv-sHY6BB#> z$d3+I>3B}waDDL8u*!x#`N$G$|EKwC8Qd^PZK1z+V-fAl>v_`OYasv7fuU8B2e&e&#Ow(STHtBF~DRH0WS%0X+r(Br~f+RAb>RnXdCk(F~N^MkUNuVohpI21;$ z?}NK=*=jLt=LOjQNw&Ly9c8IO$EM4L?G{DBZ{-%s4cQ@x&Q$`9kn$(1@)RLBtOK$gwGTjG*0TUhlk@ocAoZNKJ9HqZ{ zy_B4(NcN?0D*Nb9k-;%m%l2iR z5lFfhL_{3{4~qa4U6~F}di!~Z|BAd;Ehr~GXnxJfY|xdK>Tl-z-8uY1h>2WsASedQ zKKS}#wh%E`N*np?rFEmH{y*4t@xa;Ml&s`Q(XimX+mn<2Gom9+x9|SO`ua-}0&x!p z9)`ZMh+b~(CVjp zv!3Ok5h5sGz-gfeiB0n?8>S_qsD$+$c=EE7g(%#NNC zO-!?@AWE~{6eJ9cd)MwiI-+tIdC9p2E+}OQULlSdw&C* zwg9{FHVxsni~jSTVp$U%5DC7OE}F^a*mP(GAwy0az9MBDP_D2qRo7^3H}n+pUv*^> z*BEoo+vo_gT%hyw81irx9QN%63|Z~6DIK>_2`CoA4rk?>Wnmt9+w8a#8;p=0Je z+nH|}xX@xNxPWRBzs2w$oDf0uZb=SaRcZ0kkgg=M^jhk4%EMbQfl z!CjVv4Z@fQhf!pJ(?5ci-R-?*SJIstI(uJO2%(~m7klTCiw#`(@qu0?^uwp&IadxW z>h!}qfE=0E&n6+-A$5VfbaMJBeVQIFi{G5859D-&k@0qZYWmq7Wz4@G+57nJ$7lQs z2H-6lW7Xy9bP7Z_4U!@r?I|#FQb70&%#GEr6 zRe9(I*1?XlQS25kmz5Ki{iCe@mK@?-@_m-Q-PWmsSmzOk`wK_4uSiUF-z`ix&pEKk zq}F$Z>+UzYT9Fmu!?R}^z&-YF|n*PQmbYH=>Y=TZ@FueNL_12+|d zZg1FeseLL}yn*G?J{^Vf=t_$q`&ZF4Xw-Ldi6wWMCD+wEhR(53i#OR_D~O8V)bGA0ev0~~Hvji=;B4yz{e(*2+pNxe^<&nfe>GOA z>K~gEqfmiq-6$0ghhFGrz>J{@E|BL_yzr54)EXirq}mxGXX&57feI~_y_0#!Yd3M z12Tknw2UZL9)l;!$*af{$&$jBE15l_$`%-9eS)fvvZjviF2fy$mOIR?P4@1k+B(>{ zxH-G|TDa18*aoRMMiVWBV5jEW;l)X_Z;pknVIQ@9s4i;834{MgM zXqzSLm8*1!E#-Yi;lNq_;M85=nMzRw((&ceNf%Ya%E2v&Z362Ey~b1O@3qZIe4M&kP|@vo0aTO;JncC*cP*NvM;w|Hm2wd8LV zu{M}tn@rF3gwW5yaf|*L)6ty1go@i4RgD$buV3f2-E0`Bs(N2gy}@nx)_UiASIv*d zgWpHSem#Bs^V6$eA3yy1_T%U8FP}EwzFB+z^7GS&UneJ)XJ=$_b&d!u5l z{>Inaz3X@8x9+chzp=4#acv`QcKz(ir{kaAo|yi8@bPEIq0f8f*WBK}G5z#hdv!@+ zWeM|MAo*fZarT|e#F|RqCw%vseESQ0-D}DEFH)tSbj#km)V{a4`bw?rrebuB{K-Cr zw3j&6XZ)!Tgpei4L#udafx5#h1Dh3V$N$-TtvDY2;CJl9@l&57^FEzsucdOn6cm1} z%zsyY{$pX>D`w=x8Nb(Io`a#*PY>z;&t2ome!cGfYOUs^>pNxcnc-%Q@UPY6Uf~tq zpcPjL`YTd~&!xzZhSEI+fU6chU~|(Gr!=YTN1YW(%-*- z=jP{RF?hr_@E=maiO20rMM&u!8Rbch*2x2`|AMomR2y4-G^ZZg<swYvl>oHb=?5`}X^ps=q87_us`I z+1G5&`!x*WKTg$YUMW96iRa9r)Gl@_{=U|z;bNm`6u>@hvp8sbp}ZvN*Tw~OmE*rZ zUrKNu^B1@22g%4k2~S>K6#KIB+?Y(OAKX<^`zPu6vP;~4gCO;+LRA}BL&X`+w62J7n9d}7lw|H<=QVf@e5t2 ze;~=9?i?Rv^xm77xVYech*s|L*-X=#_A?AR@naN{97ySkQH6sGO0*N2hBIs9ZwSXl~~O&CjH5W8*1 z{ff~RtNi+iyx8(JujR$4dA8|;^c0t>W<5FivgUi=kCE#tgIvfD{ru*%sG7PJ7S7d3DjDwjTymnz!_wTu6(yPLX+Eq?C#QvCr6vvR|+aE&j|HXAo44q#0GSBu-H zBZz}OHhGpflh-f6R-#N_t51=j#yB1mT4;o-k3HHxB43a4AFaQwaq&#(xzT*cn07_I z!5DdGPcBO56?giJ4*#rSq-j_FG{&@6uZ(T=F3}d&yW!cZ1wzU6Hg#d!?k=6**uWc z%)EQGUS}XOQRfxu^{z*j=WJ1?1H)H-k_CT0JknXrtfrX0CF}2l{a)Q1*e&^!dArBz zW!K6Fvk$4ibe!!b`4AX_@#a(4<_QVx>p{$8Q|{*Gz@Fa}(mvBF-ItHPqIVtrzKI=C z4Uv)* z-}|TR)Z>5OxsH3*Jn|81%S!M#=59KnTVx@1zgxu!@Oa}6qijjpd6X+OC9@HWjSi8z z2h7Ca;>js(N()i5!)Ivp@29+L82E2;xGor1*g(+vD5xWrv$L0#U52 zl(SEzM0A2`8h(tvbG?;S(yrjC{XXeLa1KhuwAZ+ESmOp=9J!X5%pnT7?HE?!qne*1E-!zk{pg|rj{D+)0 z{q00yux*w9U`2OtZ7}y;{UnbDAhPIC3Jw)1f9xZCA$bH7&UVkRdU??dkfwxVThgKb zRq1#I=0ym770-wwItQ&MypvLBL(lPLT=LM<2BcAp`Jpmz>1=Oy5WX|qS6kSPk$$;N z{*9U1?iQ8&IL@PjcRyKHOTGnhVu0d*X3wW4+6uPsZTLHGtBGQNwn-?jEi3$M8G%e! zu}`k0X1t;GKkee$<4*do=A(Z-)pkFw&%d+%Md6g)2=GL| z;0!nQ!rRrF9_d7*#Jh!vWQ7#@Uq2j9ZQWF0VnppOIOcE1%qqND$k;s=GkUAAMq!1V zVLWY?KT+Ox`X2hd*>F{Uj2pD(HP6AU#p8K=L$Km}*|vj82WS%StETvhm|=WB1{2M6 zufPAtp+D(^7XyDlzVS*c?Yz!xO{i_d6HGX*vnns*XA!{}<4E>V@eT`o>cJ(wi=-|# zG@EDmEp3hqI=XIsvlfr>%=w>;uNdnX0tuG-5dmK8rhIqHy}H zW5B@TP7$=UPmyB389jb~OqXlBRoEK#v5L5AZR*vPFtvXZ*85}2po%IcBN^k?L9v3< zfp6?ocF$Vp<)2Nhc+)lP{B+R|e>Sz_Iaj~nnSNgUkzl!3Jh*YYJ|=>%CO^$h-+wFz zv#Kf9_>`B9?F__Jho^SWymBagkbCS}Q+0!tf7-T5lLsb>6C^*&d7p3q-Fm<`IO`h! zMkGA-_0!Q%{L@^88*!TA<;IbDrr*#;3=a<2g_HF;RGlJrb%In_RsmaN< zy8Q3z)NQSc>E<^A9irI5@S^eZa^WF`lBt&sF&XpZ({?ij||2jE~F( z(#vyFl|K+6$6j5`7yVPLOm%YH^ViXcSq&XpNxXB@E zosr+~-gJM?^7MgR8^WBgfv!UpCfqxiaH=%w46+#IF%d=h;99w~q5@!87l;yUihgKDZBDeE)uQyZYhw;!<46{MOHJJIp-3Jb!v4RSv2K45aMz?0VGwI1G6FWFt2E8RO(L zLE>{RYC$6!di?k_7n2>U$(~ZWP;XaQ6Z(>i5^!||Oq9naCS+M$K*1O}__f(%p7X_j z0}}rcBrZuy0K?*&fP|50@JCKuMhX4y=^!g?(wP-o@!?#y>lFD(Y>}YtoS!D#qfw--pTMIhuGAH#vAj{EKPE%)0pIkEqWA z@&DC_%n8I(Ort;ZPi7sDdgp+dq+zzFNGIJBm``c`(AASo3`~e!~ zn4Sp-gkp?LQ2ie@VC0QKx6SVDuaVt#!7T^;W(4BRcf<`fj;t9;z$V4NlO)z@2iE`z z$C2O_K*AOgXv>q>SO+Z4BsM0+x7L$4uo7!b-_8+<)pf^Y?<8Ah+$LZAJt^v$w*%_5*f}H8K*}QrUe%Y%rIe>GJbSL ztwM_!VOMI~ZqYgLvIYaFABQ z#?SP*N%2_U0#T;~$Z5(n1*6!Q5ixT5GaYmOP!w!5VRBt;l9_Spxc?VHhR)rnX)5c; z_tVl3#fe#%^FNdGuX}%K3w_Qzo}`I-cFW!qsxMRn|64laI<#y4PH2n?CUYU46I`_Di{y&bN-S3y~>&CiDQY%S!XSI^9i>N48Dk02Q2;r=4wQ3QHkgOy{SSms| z%c@CNk|eAYxleAn?f2W`vB&<|Kl^;n`<%yT@4ep7=NLEkdp{Koo@(|2zG|pnShP=k z>U(<0H-5<%HR@bP)WFoHcMx^5pQ@otcR!BffXUFpxc^dV9u9jyYu$@-G23l&_a&F@ zcvnoB;2s_5-~Yp8=fi&L6DDnI?auF0)chNH3{xu66B-PLHvBwxaM7-;tTS6rEMw|-%^Lc6K|d#ek>!(=)`Ag@-S<+STOffl2e@~t&W-2R2q}^ z^bD4`Wdu0&SOYy`5{LLgV2JufR@gO6Z8fF!(WTQM?Td`oJ`?;!4SWW;iWb^K=8j1g zWvZV_%%ze$s0T`717fLuAxoleNVTcSxsT)iZQuI}ADeQcd`hP9XF62z|!Kfw^boK~drbHlc~(_W8SFca8<0AE8su7T1pQ z*VkVMKFimBmPtQDXKxWG-!#-|8SM*y?`*qznnwDKNeg;M)c~~j8fshI#wpF&uk`wb zS?=%q&-QxJw$JPzZP_p-L)#B64p?;X&Nb@nW7PK$b>#H{{?kkAOj3uKw2Kfm-((B2 zE^l|-(fxUpk`Ze0J95d%y!K+rKUG?9KUuut{IGnhWCp^&J7D^h{0X1{^XiHncOHC0 ze!wNKT}kOvlRNr}oraaLVtuWeV53UB$km>F$=_;LMmhVo>RC;mAph_~i1ma?Jan8g zAPbn514wsZn!90#A#L~sxr@jh`d!}TNb4Gre(o>)!mW-vvE-2&^*zAevw}J)qyD8+CwQ5y*nRJ~u@@$f|MJdzY0Tfrpw{y!+IQ66;ymMd#YmrBpPBi@ z_Xj@FDWd#_KA76UlKnlFXMK^PH9PPOCKjE_d(0)b^Ur?(CC=9Y4kg} zhflUO*CpV|7t{m`)q38;xuXE_cGZ!yggw8nU)Y{kwLdTGsfL)fI`zsPvS1JGKC$^T zpZ1l$WCo!8q| ztj_ebKa}*n$=gfz-Obw5S4)X7K9hAJZ+xg~TK5%C%6kFIq2ITyNOhkz7n*nt#Uo@P zv2N!(Y9F862X7?~7i)iS9tKDyZ;xlJBzH3vhGfM)bIOY_=rK%g2S|TkljnaRRKUb` z*3~oKj9DWNxzojilgqIuvu<;CA)nOBxs>{T#YH~3zQ3WPpL}S9{6%y7vyA*%L%#i% zJV3hHDV zKPpJRji(_N9oHUse>ea5PU0r=fSfo0QEDHMBQs!vPurmj6v{|mq*L4ed3D_y>g5gO z5tx!bhkt>8<0C|Qz$e?3=Y3?=9wOGEB{vCSWF<_N?5%5mNaJJU~CL}oli5yQTF zUSL(7{F+8x8bgSq6m-i5j zUj#@GK$4Pmo9;vt{-TbO?i4%LE|fGK4_@M#PU~v{xEG}Z^6ED%$|S_Ae^UP}E3?^A(w3RKo$8x*$3S3kdqr_uo`9HGZzB;A+Ms^{k9@Hj& z=ueY_J+)~!LylE+==;93}i)`am+pQtV0pj3j+hqi)Lru&(?DzB9prSsl zN?m-mf6HTW))TcXx1Q3;BQO0xY-Ewb!bwBjLlPzWFIfY%bPW%E1t`BWHv9l?`wgG^EU$i4Ox<<=((R|!OK{gb z@Vh#TvxGOV6yJPmwMiw{kRR{|dgSCo*>#cOBaQGtb;O8WVvlSyxl!Fl{Y|U~NKIb+#SZ=2EcwoBl>c93NIp3uZ4*`8v28t{9jUEclsdU0QA%t(KC zN5A62CbC>Z3{4<+@_O$1>7E%hw2X}A()g6#o4bd)m^4%|d22nn86fZ2_au4#kj16} zx&?)sK)Vmoe$pu@TbgfOJwkbEhECxxq;&n3_CA$<b#v-4 z>0OujgK`b2kwtdi^5hU&Lz*Xo${X%v=knP1V(<6Yzj z@`1WUQjO&Un{KjQ#K^*rN|vp&t668{GXZUGc22^;bPH>_k1C@|CKn?0I*oSM`8P zdX(@aYx752zc)>5ND9^~%E{4Lt>ixS^G2xG`Z>9oOS)1ae;|L9d`b8IRh~UyclxpY znkQTCe7+V*D%TJaE{(<*ks5$o<666eImA#~qP+i8@-^b;PYSs#rin+s!XIn`NC~$; z!xdj(fP6L{kEVBi<{Qq@0mPd@YjnCg-N{2m}wllSgI)y*aXqF@$q&+l&OWY>Z%BS9?K$Etjc>fP`q045uI|{zBxU%23*Wyt zncvu)*8C7VRCY10S)%tR^K`BWpNZK)Y>pVbu%bSuXj%J4 z-n?~J(jV_xK^m&R-iU1rowaGD%j!GzbDHkd4|k=^9DCl_!nElq^eCOYx65rzb=6sX z*!>slso!UJyWplg>4_g{U&g(*2Unbv?e09WzWT@ovvn8d<}%imZ@W+zFWq2&rd4(5$t~7pQc)!|>dsgL(jbp(-Zwy8*E8W88UvHf@Sn10SGK`D+a>?k$D#dG~ zm9LjkjaRMuA~uTSZP2zKTbZsSnXX9~Z8u5Gyq|iUH?0?Jnv}EDo{^%_v(HI6rWaL) znDq|t$15Jd+`1hSaKHN4oz-b4a3$=HitHmv>WXy|6+StYT3FP#w||rHsiRB4U=wB&sL{hayY*2y-}owoZ+3@T`+KS)iJBNCgw$o zu*!r3Ru62?^&@kSC#G-Um*wb0*Ja%vjgvi5p84mD=G{Ph>Ie#HA7?+(eo-EMF_dW# zwJNT1vNZNZPP>Xe3{<7;*zOeet2_unw~YFx3iQ;sZsZIWH`ODtG2r)NEo zTA+G!d~pV%CQ6*6U5d98g(7Qwl3uUIZjeY_?PsU1MCvIoSMQNttdp`on5;LpsX1}w z;9Ps-|LkmPj(Hq-o60cRZsj^oII%74CXeSjWUNd2&STskTGvq~%=*c4Ga$0Cop?+lGfxo>A2<+1nu+MLBWzswO3F?lqa_ckTT`)ze4OhEfHdvgxQGmz8q_E28=60CHMR^9$Q(Qui{ zBq^)m;2++~o1OibjcuJ((?=uI%1TG(g}qD5-u${_mEr2}d0Xn*Pa0r^rgLkjf?G7@oHWPef4nFz9V(BSnr;Ydg`W3 zLT@g2P8iFNoakL!B}^ixW}S?dwuPUYikQb6%a4_eCqKy%XY!sD#5UzfxCQO=QnnS| znjDX6Md^T~R^${X8;0Y83YIb5|Flye&=;2Ltd$qOJKPXOs9W>hY)MCz)vNUT4v*bz zk5ufPSjYXvo!vt2Y_6reVl?8VNh6DFk9OB?ZB&I-jHVPeea|s|r~^@2AM>HPkxZ^L zlU%oaDct!zKw$Hq9xL5Sx^_ZhW$JG1YIgqEx_qU{zUfkzm=@c%+v5hlP3<3i$B6OD z90S>xQL7uK*|ELncPu9nd>#aZkfeLOC^%3ws=K9S;TmhADkt_ksa@f{^$ zMXls`@9yPJaqQzhdS8s>%d0+J^IAFgT|mLrkPhY#ND49oqu-zd{5Ot4dp}em6j_#5 z{4s4_Vtl#;8S`u>2=|NU`;(o<^GtAzX7wjh^Q@Rw0U|+LpK~Ch~A0SiJDmK8A9(mW~JiTA3=B$GgB_UZP=g-DRe7{tr6dA8$j4 z>|PmcA0Rod{G6_6sbXac9M+PF(K8OK{Gp`wlKxuL%4EIyIj+%`4W3rYkaaE|raoGu zNjHgnGUyhP-SLS)FM#`p=Vy#Li$ApGJDkI?xWDHtoVGsI8FG34ev_wqUjpbSxQ8*Z zs=&1~(*~D@YwphMAoXWF>0XcRarRRXzwSvkF6X;=RDN3#KYGwPth8Of(-H6g)0E!g zfOf-H<^|Am=s7beODqB({Bsc4mtx2ruA?DIYur~B z-BK;-UG|ZbZF|q8dKE1+gy2#U6yxIJmS2i^bAR|o0MmG{*l?eK6!7if-q|SAGv(c` z@lA!*g0}Tr5v7IhH#gn6&Xh^FTeYtWv8P{E$6kN=H#I?%>|S0hW^NhFkI<&H(Sx3k zo|xSCTJ)vZd1_yx{ws_1@ftVdw?p;@B*mLxQ~+J%fVM2I%wxNk_X&qD&SpHvu?++A zPdIR@{y55G1R zM!twIXei$L+1t`>PVR@Ot30L*eQMp2@hrFf@3NR?Z-D$h>P;Ah`Oun18OTAjvMqg(qvif~-?c#4% znoQZfS${Qo?eAmh`!#|0aBC#t7Hvkk!+{Lu%dFtNX7pP#_hw}&@(yUVV=)B*!LMWv z(!_5_)4L!RLA}_QIuW<`-FqhIahBy8-f!k@RbvIQ%%`Z`_}VST?}LH4Z>xmTzJMXi z>FpLUm?_^g`;Vo)d1qn6i)6+i6>a5q*di(6>#?g2NA9kvd|SOGnLhqM^wULx=hvRh z&b&S`=H@j((5xz4`!J>|RwdehRE+p=>t|p~fQ_hUUTeS<%6m$v8;4q42Ktx5i_2iP ztR+w-3Li!X&7kzAgnA!b{AYwYf!H?E?RIlrfcVBgH}4dcc>Jw6&!IWn^K#uiIrpuY z9$+&OCb5sNqE?B0=Pj}-6t9+uUk=o4{^MKxrD;yU9kBSy@Q9Y-SUpG4hVf_L36GZ? zx`FY(cw@DyDUg9b%vco5w|--N>-W`T;SAAgUF45{JzRd*r^Jdkj^5L7?8!ElP17RV z{}x3uMS(04yr7B0@eE)n+RPPxA-;rfC_g#qCxiVRTKyQJpjzM1EWu(xsHfzBYTti3 zfIp;co}TAj>{+~kU5OHvJQ90bo2IC|*)sX53pd^aC)Pbi<^fao z_T#6+zPh_jdqx#rvd*+VbjvmYY72Wc>rG+M$#>#{2k6)kw*g*dY(HkT#AoRrkJuJ; zK-S{O7Ia{@NL0Dlx4LtFQl$&ZC6Z-bsJL372d~ts;Xu~C0G23#&xz)Qh(=LfWvI|{ zWoR~s)QwuKRtD;@I5Q|OIZQAVvDFI#%0O>G=*N(IK^#^YoLvT6hWQ^uqlg=U6g9?s z%KhR!+Z4V>`08_a!l+#i^EWkN*i*i?gQqpZ`F7PV{?A;0PkR<8xzD^42TU~ulhF1j zyTWb-=YK7$UoDD|h?8Xp*KWkb4`Y1lF0*U9-n~PCE#gQ}4=)0F|qt({-d0emra6wMw+=lG)U`GojS34<8ypg57L1a-JXsMm_RcaP%_qx}1Y zzEeUU*pupsSloj0n+o@XVQu@XaQ`ylVcYwD!ze!nYcVhA-@De67B-*^l?Y)i_M!VhLf~s9rZT0e zegXxmPlFm^V7gWK&CB7#0sLE{09If1GLb6m!gbEAcWxrLTMx8KecrU_%c`2x-yMPJ z*QrgufleWTAu4py9{->I>JwLG3VaE?h!F^P#nkb1n-G?Q+|zRZFl}$uWEFke03$U#dh=f zmFbDb&2CzBV4OS0rrlt|<=-Aw+jx^@(Ggujkp zf?9;C1){F^!oRI(4&L#96OWwhiu@+-zWWbD^}Q9z5-Hq85mQ3tgfNH~{y-`8ZRy5E zh&WudH;f7|itz*oe1~J`J5YWtLZxlAzvqDAKW@hdpu~b@ep~1L_BBs!3A#6+J>u!l zYC?2lP$HMLA?~-2xZb^G{-L$UcGAVs@M4h9N)YdRDqQLB$#%61QoULb4|@J8h@2F) zJG? zZQJD^V~kR}3kOm38Q^ehi1O%wzZ_f~$4NGbT4vk6>A7f47kb!H6hL40sZgBMb92$@ zwsooZ!){fxln)i_+$E&eK(OO)vabOrsw1;6AkJNNOL*&T(_%Si5{35Viozx07d|4< zwx|TnxiDx5%n~cBIcyf%w_oUU8yy^n{yvBfl3Z`T_vEf$(dv=okyB41$^vP&-5jHk zaMd$hqR6iWMJ`=VNgY--je5=GP$fc-;W)$FaYd8Ez7ioPPNdbDX8hC9Q9%Q=a~wZO zPhoj9E4}AfkZ(ysYr8?0TWV+isfPjJb*j5)H4{B3WUq?wf8FZ7MCdY>7?%J3%7k4= zpaYzH7G4z5(`Js|j9f|(c~(w@d(QZNQ=-B&-igrS%m*03@U!Na>p{cas#~JRexfi* zci0p<0z`+GErBOrJ{%VLeTYRpM@I~!Q9YtC6*@>R3Ti=lH7BT2)IJiSr(~3f6|(Sx zMe2k_Swc@pxJZTS-+?M z4o-{uvFK&9bNH~Z?;e~?5&fHXzj!eoEY`kQ%|Pd`1BvC}-{j6fRm%sbs8Dw{C|`+7 zfPWXj^xN)NZll7p#0j-65mUHWhwF=efs47<1LES+zoT-$_xrb?RfEeTLeSw;FF_B= z&S!Vq{=JM~jz(m4B0JE!vhO(eQdOi@wF^D7P=te{o($bGP+k&L(c|IJAG}^Ms<#NG zM_)=)37w{RZopXK$C%;Gsv+B@M@7-j6(H>r$1e^YI8PL&KKJE!aL}-r9T<^T4NpY8 zNKI`raF?&9FSktdeVjeG`@1kFq3Ll-)3j4lj&1wT1rc6ptcK_DX+5Gy=IE~iciq)q z{OqFVR4O>rjsJ+sZRZARv*I}YqCZ9xV8`A4J20FV>uICtaL*?<{=N#`!NYb4bFWP- z%0f{OCb;R4QFs)+Oz49jE7~D+SD_Y8sa*k~XIwnXQ{byXx~YWJjyOYcI(-UyTAFBD z5odZ$`FJAyQMJ-%AxHG5)2L3SE*9x>aQnW7^&6#=wde~RG zjqWs8|LH-8%SDk{otzfb&V$`PkkCi2+wQ4_e3TFLp^z$=uLfLsXdf|3Yb6z<8 z!@B@cSlOnqM6@bR1ZDbs&gmGRU%xVNpW)!E@UE<+XahY z^qz4ixUkMmBULjWAdwE-F~wjRC{XF!gU<{8gL*&6aiz>9lZ~hj7B<4-EmI;`&bml&-CGn{O@KglBbwN zp-6cj+*+ns{7I(}lpFoaLRF6E%(uRssV2Zvqw6_tSty1}D&dXV^vz)W^=+oc2$PzR z<~yJJm5mWH$NZ*H9EYY|PMmP}`hc-N~0X=2UIx^vq zm*I~-2np?vX^Cjw8km#1D4^CQB}-(mW6i_X?)BGEouepUt!6tp72Uc*6bhol`bGO@ zebZtnk+MxuOkM;&gX1v8Y5BP?3QdZg>5oJ$Y{?)+p%%buI!ovtB6KSg_P@wk$X6Qrk6Zm{r3iO^S`s82cKPBZ~J*MLU-63}$7zu83+&YzhF8 z3}CDeg)V#^PW~1X#N+s?z6Q1Y+}pQ4C=$*7-%tOd#b@27_CFUJNP=is1!v5Q=`ra=c{&~nJp~D?D68Fx3-V?L-%sZ!Do}*OO=!PO`s@q zZSLt^Wgo+DPICJ&N%YB>MNn*Z?i)XN6^ExgwB2fZgxmJoa9@ANzn&uv^ z;gqrLt}0b})|`BX>&6m?Xq$N}E~F!@tiz5ih*e6z=+}goxvuk;-VX?lFm>9TkW%-` z`mL$^#=)kf#v01XMe)z!-P*?2Mdog4theV@_+Jms^L`+lnwkIJHE`R)3`?f7aOY2kVNS^e9iZ+feIq=xf7lp!fK z0s9O$|IVx{KI1nhp;~aS^U#@v2?l@0Y)-Hey>@<5HygZ}2#qMCC;c}3;`MFn;rZn* zGjFYHBFq=1ULPEIc#gA^aZdCUf7p)W`aZ>UTaw6ler$5a7yW>uW3I_y`u#S6l(Aa2 zE!Q|Ke=NoG z>~jsL5tdN5;#txi#Ia7EcGq{;PRs48FDqxA49Z<%!7(PBFt>aiJz@T8{=-hI!ePXb zdBSgkkU13=50_+kwWzTN_p1(fY`OkVFK^c2rS>Kkh4q=8CG(!LAKINvSY}zV``wN8 zfoHPD@6WN^@PuG(xm&cxx-=nqsf}}G>{8>^E&R5<&KUv>*;%R)n8ZuQ+VN}3^nxu@ z5|}!9KzVeB@kVw3+~w#C4Z%Wcq{L{&rjo{<^9L zb{{#tc{+H}ooJAqlIB`^9)0-k8{UeMUpO(QIj@ z*d(^xRd{hVTr4z-S3<$2l*sm{rj5D~mvL%wG&btPO}$|Jx@vZZdHkiv9p>A{^juRi zZw=I2XU-t7jJ@5ixPvF3OV*v-+B0dBwl%uO^y={qMh%Uh+um=TwLy}pvMPuhyl-DEh|gRaw9|fiAk2Bi zcpC;E2X802z>v0$U=#xe5FVbAV@whg1Q>#A^~nyrr4$xFa;qI{GhvlO?M4%)qGe`@ z>q<*ZZw0UFxT&|&=s5SkmM?c#j%b{`AMT71*|MxR*hJiALNv5P%*5u(j3V@G?+` zTRG}@J@;7I9Lj`V)SQ*C^Y@Q#*%g^xRpCE&K8kD$9niWi2nQ`n5#645m&{OZ4#8J)1%z(`Y_s-+OXNYK^zrure?5Aa6Jog zzK{Ug))F3@DRGL->1S_BdQk43bexl!Qy}3gtsIjvwEIca$!h{^3GC9Xi{ZwR-&P18iLfC09zl!LsMRU@1 zS^`ZDLk8eHmnHz{@HaQla6+eyL1y(*nbfrvD>mxZ7-%5)0(Y9cEB=x z`dqC0C3Z+a=#Z0wkE89UJH@#=iiR~F3)92(?Aw&2OYe~m9TSvgPutJ%Y0T}y!q+yE; zGam-9?wVkOZnfNz#U^c(=NNT^ShLFlvU4cPqD)3wl_iMqkk^sR1xTDH0_iBj&@u(2 zf6<#`urW(ZUxXf5H?MT*6EN3(D(ygL!CO<74c1#dhThKOSem&$8t<4^?L!4x1PogN zpFBi-*4t+zJdD!|1XZfixBkS%dK)S*i4K7ltze#)h#6;P{m`avX_>s~dW>dsplLl1 zleI83+Uy?3r||8|pi|2W&H(Mf-buve6T0f3QlMpdLd#YF;|(K-&U^vIa8UQ}5JCsL z%`r^R!Ys_%k!Ru)@5EK?_0ZC1Bi+RUnx`7M=7WOZ#>&ylf=I#dM`Cs+Je;+D85uFr z&Dc4)>hdQK+GcK;oO9t9+^S9J+yO2!UH1Q&f9ESG9ES323}lP+^n~Z#|Z)3%D-i{y}JD7(b>RR1yK@T z!=u~)I>Z#r!Xt3LDg^N$lw+^5z(tpNiK6-2&FUenJC{vZa|vnI`up)AI|VUCGaMVM zMq+g+TU$Poz?C8Kd?&J#6)gcT7l78P~Nw~ zJ(6~FHG)HsS;i^m#Ir@}p*dp3oBSe^>@HFW+o+mtXG^Tw-Kp{Hd~ams-Tp$gFULXD zHrGL*XQS)xh_Nwcl@?%pHKp zwGgoyB1#Y8xB$i-G~t0Lcks6ZbHLht{^w#%BWfYy~4L@oGf7+0>HL3&)E~ z6_;j+t*Myd4eiG1M;RecafaL*smttdv+*C;jA6vH3HssZUA7StGYN=;q1c2r6$`l~ zx(k;sD8A25Qa}u4#I@2;V@953wIar|$Z|qp5r@#CbJ(UL2wyCCn8Y@o01Y8dRyMk; zsX}l6*+Ab_4u1nxOQYwO2iV#Q^qdq1j%?jJsTK-7ced{*nDPOB&;XLuu)zlyod96v zX5z=t*9ORJ2r$>LCel-g-7r~plFUb#n}QfAfY5P@9YB<=4uK2JPJR$x)0Ajn|jESXVOg>mr{^EiR2j2qs9 z@HmIy9_%s67MNx5s++VBHBRA^WKm_+W)Io$W})>9aty@*I?uMP6I=i9Jp=zFeOtD- zy+Y3yLHlN7I05K4jn*{)i>u(p2a_lk)nCQ-X3J)?^=&EDfaOgy(kLj|3^0j6u!pWi z454HYIt7p#ffyOIc5DnSJB%v*Ahxovl`6PX*ogb=rn!@562YcsgjtHfl%rxmFd^ijSr$S+E5N2ju#Bz1 z^`A4BDsZAyQ#i~r>pot_&KYFSQi?3qD{Wc}W%-ee6a@O+z|d{LFkN61lVkI3(q21b zr-!xo3>{GAkDkrXnQL34@0q0EGG!3lrq2>k83H|~LN~-q^+gatg#oXU{T4>M!{`qX z#bV;3-&(fg-0uxK|NP0LBM_0F_R|zVqCvm!NxJ^v5^I={0iq-+m~N^02^bR&qjkvq zY+zFzd&iNUH~R!Q2^5w6A}V~2F}{6Rf*?pE{Pg{^AU9q8H)5Ql%d%kR9gNO5go zFtnFutOT>`1SScm8MOk_IFL30*fc3Dt2<4y*egP8OmsY>5dotKCR8ho;t*Fnqs&@) zZDRr>hpAVGDRNC6zMQQSaFbI6Htub9wMx&Ar2PFhs{914mo{*2{gl3gqR~vC8<#FL zRy4W^d}k?&tOZo2!0(#9@eA0%T|t@AQLiAsBUbFIutkLxrFs9)#b#s(jJWOQJj5Ta*enx)%!XHF zA+Waa@@hnud(Nrg5Ii3=F25aeRe5WnhgCZczhBJL^Mn1i^p5J}E{qpV@$TS1d@ z1eqg9U5YR&TXB0s!fB^y155421ML+KkcC5bz})b*#(;}HW&-aYn+yGG=)MG#i1p0J`@G@Wn-VeitJS@pL!^ zk|50F=go>iTsa$`1({1>EXc$ao8XI0Ok)7<(1mwOfSjPPJ;5er1AC7lt|USx#T7dz z>QCh=5FdG8GF$%+}P?J{3D1jX=qyH&mU)#((Uk(ID3kwFx)MOB(y%~=4tE?pZJ%Mi_2W)p$n+gf z3L_Z6^ueu{&9<6kDYCa9aM=hP1meplYkf<8%)B(_oHCU_7pfynGa;Nzf#U;Dw?H8g zZy3z_kz&e*`_+tEfM^lK$bfYh|FT3u@@n*`|IS`-(akog-)g^F zq5H^)E4X+QAUkR9mI`$H2z>zXF$i)9n_SiwM!vWz$pp7czWT6SyS+SpE~}Dm$ku0l zEwtW33cE;fLC~9~8fPI6hSs#aU>U#A7--fJ!yzOOq>XB*zJiUPK%xw2F`Ik)1@vuU zL&=3P@33uvEr{)}!Ezvk>y2WMFChj7vc+yt{$M_S85^zA`l(qT*{Y?8s# z{C6(!fA99gONMI|Z!QU(3IwJJFrywZRLcH%RndOuQ1qa}xE>&Q;>|MHUyBh@L`Vld zt(QOqCsmBB2f>9DyPLobhjND4-BQpfMPUS-{E>(-<0|;SQjF>qCQYD`L|~lWWgMfh z;UWw@iMypot8_->ffsZB3LT_;x3Fjftd>puGruWxliGSq;pMaRxJGYBh2AKj@2Q~p zAoS7Orlz6IKLFl>EsIY=gyD4tpZP@S{kNyk>xVFT6j=B3J-~!9Qwwx11yl-vVK{~E z2i6^Eur7cZ=HN$iZ|(RdXc)ZsuwDClzyT z+4RQg!Z%@Jr7A`{QhuB|7{-Atid4JW6PlK~VVFOPDZ3=362N9}a>J)S| zQZTX6x#+Cf_a2ba4H82d0CnSfR5iyO1TwmCvgnV=S1K>>#7PSnnrjz$f(#o#$D(c6 zC-}Jr(v`X?{^yU#^ClB&lS~jVy%BK|#HA>{EVDsoBeoUwNAZ09$Jfdb>d~X(|H{s%=B<$`S(YHIosAy;2zkh=gZcMNh(}~D0&Z%`~N{Y?KSXZ8_m-C9CEu%tp;glVGECx zw?hy`4t=e&FTOH+vpu~2$x)27LG|o%Z(bkH!evt)Xi8QYi(n(qOyg|ugTC0*$!RF* z($YJy<$myAouYk2xuZhBaOhF&RhXs#R54ha4N$8QKZ`*UJ>Iey)C1Y}>jkCP3idAA z+LO8K(Miw{p3W&lJlu>hN)VV0JLAeXlZV}nRZ!$tr}njQ&mP$6i0&Y)u;Cz}GfS+= zejnq`4J@tu`kJKq2+H=`eT?MKN|1*D{Qm#_o*cS; zYS-46cLg{T|MILaqm}maf6aLt{hLU}d(`6v3lbne>@?`PE)RVZL>1BKwFPJc zU57=aubalkIQGiMF&3+alMCj$-IA#s+xn}D7&VegqWd-Z2jcuzO_fd^uTrC(Bg>Lq z+nw`2>T^6Alpe1@%8J40rOzoh>};2|l`M(>Y8et=&Dq;k(_TbQD~>K38r*@FjqjbSb`@~ z=7%yBNP3LZ82X|={j8YY#X2jb%3&GG=S~Y#$3B&}ku3}8R)tPAZU|AZk0*ejWoIkI zCM}XGj7hJm4bwheZLL}|uiyHD-YU2%cV3Fd8r_#N97ZcqAqB&214bgUf@I``s?5=IV2nxUwbrU# z=-D^bBv%f{YVQw0=rrkV8{oN^S^As zI@SUvgK`Y53_`D{74SG}u{)1V$}ts~DCx$SG#REozI&5JbbeS|fPrL6`J7)CX!*&0 zYwg2c{go?-cW-wYiWZFO4?Q})I>?$3?4V26@lJ>64ECWCtw`^J17W?Nm3{&zC*Yu( zgY{%0Bf)@c2m31qC>-32RnHC7SweG_a{^X(@bC=~>`a6arXlw+o^UaXJx zPz&5r*eC-{fFZ9~$OIMSWE}{>kmqtT0S5ea?ckdLYA$~a6SRSCIAM!9-^|3kdX+=2 zUxv^H%CNC;n;}PzaUTRJ8{q)LHU4p;jEBVT5!uWdKszQ_>m7s9_AflHTYfrv=Ipz% z7aN;JOG~Wz{dxg<#bwHNt1mv0;Za(>Bl7FFBa*8^%anSyNzwN1ivNmd#tpJHUU=yz z={bW$8vd$q%X5(UU*=nj4LqUWb5{V-0%6g`2y6<3G--jcc(|Ijg2{1A&&TN8jRv zWjad`WH%jW@js{xUrfMPO(QK1%P_WCf&o4cWtfSlFLXrYIhtAh+TG$`#@1Nk?`YR)t_f846QAqojW7S=n89sHvU zgt>EKpRvacw8DPR*`YDA``er^NMWU;Tjk<#Zh)S#8k$|UEmJj)(9iA{Sz4sTKS+N2 zJ_8ia8I)l>WE+6rxR*%XNzYskV2Jbw>@Hh-%XBs-vbtn`))*;1{enrG1|iGfl2_|` zJ1x6dMk*%ulq<7eGqJ5#-rw03=0+ z@j$V&=P;6xp}?oWVn(eDT_WZaRzkgVA(*&I!!*t@6na3pq;NgmFIgusaRMYpbLZQv zIXgG9=f|~FkFSeu8lEM%;=F4-)3@C-aI&gjvUS6;sl~MpTt6R^LPl!anILT}8V53w z?V&5Pj zwk0bh+!oCHQW+@@FCg+a=g{~}7wIS$@$j2~k^&-TsRB$}ixK1mH9AoS(GM1fS!rYl zoEjj2vL)1vQyeeT!%{z1&VQvmdn1;Buo6sR+L%5cEo{SK7YK1hOwya93e%2$F(F+* z!ZG_X)f)V<;4%H85VZZ&?!KrKC&rq4E}dMygZMHsxpx~Csk^Pw^CAsb)FyAKIAcC7 zF=p#GA5qdeTAsUGzn7xpy(~-hIjS684Y zN+Lcjfrxu=xZtjFeODbXK5G081l)D#R$UL=9G@TczZ?i%8}%MThYm(E5%>uZ7p+3j zc0yz1a5YjgT7XF}Pg>QdoNF{y*K#;~g2?o`-%`OgTGo%e$3--{0_-xk##-kR0crZG zfUuFroI5NdVy`PVZL00dJ+%MKjgMKu=d%i0d!FJ0pk%#kDDJ^0@jXX9Ejrg9aV$=(zu=7$olhfaJ;);c$-5DU(Zi?+l|IneP*1$Z1D_3%L%n z5L7kQNDB`kbxcZqH~jr=zf`+-k%|h6R4N5P?W((&E?vmct$jVnG{H?|~yalh) zwre6gz3fZL$5wNp4|c zG>5K+ufxW{Xz&Oo>oBQnlHCH3Rzk!$NVF1|rl+Bu)kOCc;*oCbDju;G)}sqHZ>&CA$iH~h$!a9yK5E%` zn=Vu7ou3#9Jde@cnofGL5XO;-DXvEnw`wsdJdASg0`y^Y3bQd;XVJ2b@?c_G>aagV z#A`CWQLJ9|7kv+fvypp@<_N1#4-fUb_+0*hd~~CXOFY%jo)hY73C1~W@tyUxZ~9(* zX5m@-xE_97Z`ze8Qxj^g{C0x@Iqgl#H>4qShpHYmZa_IB*iM5SNC>MPOCu;bBg$Jy0r{zqMNQYX9)ccYPN)hHfJ?%r;^ zsEJX6_TrJnv{gwlJjWb}Zb9b37WzR>?ucb;EObp6+#nardC5<&|- z^iT~QK_v7lhAJRvK%`m%ND)wnD&0_|i4uwkf=Cw;HK3v(Xs}|vf}$d#f)yM7a=(B6 zfoJ7)*2>CRbLO1=-Fttei3a@y6F&!!(mQHA5M^-nbqO3nQ|ry95&kN*QTeqx^(vcs zk7@dtbUD`V98Cb+kHWZ%m3azVmap#!;YD8NYIn1CZURJ1-@ra?6`u1u$|s*3npDp^ z0txY;uM!URFCj_ih48YyHpWZETd}G)XO-1OuH6|4a z6r@G7Y$Uyrc>^RIB^o?GZ7|zMqG$8`ikt%u_)w5#VaOK`4am9|7x((gi z!JO8zJ=;xTfv!`~lT%_x_MA3F0U~cprht}KNZazpx@Z#GZjV&;omO5_lZU#Pz;m{@ zh(7Sh_4_8B08$hexi3J3*bhe@9F1mEvPIgc*cK{QF_U3rCmES<7&@5zPc`z9zJHu1 zek|TTF8BMUy?4gSluRn^wZUjPYQhCc3AI^2mQ3>{)(j>Xo5b2c8khY*48!`p z$M(%sfW}y}V0Y(uZh+er}blga(bnSmCpWcw)dtyK(s+WC}* zWyKS>2-SKHpkzSB*3{!$>94&BH4N)=^_YL6geZW80FkX3@R@@N#9GAbPvbN`Y(pXSyg6`YvLjE$=RY2qexCkyn zuJU42#YTXeol#@@RVLpZiLB<60m;7ELOgiDG_@bTPr2kB0R5QXP} zOQfH*+;CTvKvgXoXxn;RAYtwvc%AaT(;U=tYmEoH9Hpb>+52ZbBQR-`M=cq}aF>W&-y!Tg z`vHUd#4M;{X4C`dS;V=Vyq@7;3?LaFfyJNjWdTOR$9iN0v0_FA0UbBsk^~(4TPV{teLC@x4AbD=#a~7Qk2tf^KO(swzvK zO4%WE(~B)Y6tiIVIC7tga}_lBqr_kU6F(DvsZ#D^r z5L>BVS^;b@FG5Z=kF1J2@k%AS`oe)_e|Ni%-wCxzde*H^kH>$yFe-nsfqy|i_Tt5h zw>0NE?io#8x1L^WBupJAOa&2gq*Ec`%i_%8o9mm_0~(GmyWVwm-4MU5HX(AGnmfXE zx8Vuj|A;O_v_=j5JbPJ$0V<-9^O|U|7Hhzabvk4Ia%mUFow39mYchjRS_?ZDdC2l7 zjMj-~B!Q;uRScWOGoVTMTiM(>D}#J9?aqVmf5z5RMb_l732wOA`AuPJJA(n(Ky!+> zB(dEgpE0-ZO~OR&$l!KOw)>nEH)Z(56YCbmsE((p15dwSK6q#7IEb>MuPTo0_~t*F zPOnAD#h$>_1jvapHvd;AzLrw1d~SNHXrfE0ys5+ha~0I(Y3_B$^$^ zLT;bEw(a;$HArOl6YQF06;70f>!ynJGop1_kSEV4kot>@-aJ@yQn&HRQ+=rjWUT z#`>iZZ=)}ISvai^!t-n7;Nml~%-t3Mr#R;$*(mYCIp5Jvs?I^mb5!c&&c*hVes7GW z!jbn4>T6QHJKiUqYQLylx89VlTH4h6WT}Jp;ivP6cI^bkG?Wk9fuu_fBwxC?_L zcxEtXQ3rw~mXx}{76$l5DVsvNd878;;uKmSm)ZznLFs@N0kbhDSJKQgf@aq|UM#2A zd)u`qJhxEJIFQ{qriqnSlAelCEyIcw$XI&TQ&k-b#S|>4c4;$h-kMiArYFdnlYZ^Y zCa+wgKhf{XbiH-@ny6L(!c2=t^%|@zMPr`QIxXYxUb*Pg8ru-u>sX+%=H`*QzTnz6 zpBBxEG#BW_)76hJDl)zpt~)Wbf5H6_9cYRmFTW|{rZ=o@{QX7K4J%3_@puRb8;jC- z3}6P7C&Pg^mvbC>xc$o@MCha(!^!MkmPDxim3BCC2nT}X{WxQYLO&NG>eR3qM3a2~t3=Hf zh67QT-H6EQ2pAX`DTV`8q|4eJ>8u=>W(KhxCob@rCTMrOJw(Ja^+AznHi(Gzr`QqjQdAY3x*zpEsF>P4hQ&%1Wg?&Dnazj> zhuMhpY3vvUt(BOgL9#VWd!EZfu01h&!$huVtiKUP*0*2aC`zwcwwJfOCge*Sj0hEg zxJkOE#?g&FZfXS~O>R0zbA>U$R;v7DgZY2OCeaPt!Qi+vVOoWaHJg)zPH=e-pXglQ z@N1#@nAVZ@{TKI~k7;j6`?Z#hX^M4O-2b25*2Pq35^KBDn-~uO(thSH9JoiOPo@M?s>#P@z!_Sw&nnO?s7WBs%!!Ky=`_q2ANrM!EquJIy;iNT$#KV< zFEh(m9tQ8J(8yG1xqd2E(aX-j*Z+6r1KP0x6_ShP^oo39i;Q_dnSmOi=>c?GvOzQu z4Uis1VP*OnsN~55F`WE^kN~>K0w5{AaA7!r1biEW_~=ESCIA**q(m1UIo|wcCC=K5 zQCvk4pdaK?iy+BWhUYp#rYI>tQCSGwgQHLxAy9f-I}f?}vQhfJAkCDXITpwsCwpd! zC}e}gCU%}g>KrjN+D>#k3N4hNL=%>;Si&-1#}XtLupHItcE|76hevYpDiN`*mtEZx zOg6@;{KflUX}qxBctzp<9lEcAuWQ!fzeSbz>+{Zhlp^_KVJ{8xknZMP+SdPmH|UIN zolxWK0VDeah6FBv6$LPocmSg&KnV*szyr7Zfpt7YJnesC83Q2lbJq+~sStT#n^RY9 z<}bJpl4d@8@ztyhL&{Imdda}0LDV(j1z4F~hFI}Ikv}kAnu~&TMz+#+?s^(G^JpMP zLxInQ2oBA}KvouIo{BSKWQv?2ly- zDJ|bZH$`13(}DIRFv;}9_pjw26W=k#k4^lJuO99%D?XE;uGqC{x_#Ph@f4ie?&1Hf z>cq=+Daxw@uIMo^T=P93)9n%5cp9()?8Q?_IaEjClSl=h!FKM_`xAe@u)AeB{sxREnV%m6Sdj~N(G79>{B zLTHpgV(jUQxxH%)MBG19)RhHM*s3@>7g`t5jVR>vh*8~kGMzVaWiomopTJS6*_;s1 z-D*;=UTK^xjlBGRGRSnPuYsF^-R@Z>tRa0m|2Jnc)X8mJ>bm#Xy{tr@?}sfuRSB=} zYpi7B9MQ|$UrpQA`|fzTP`z8DlS)5_2>uDl9HRKF%m#Lj3X2;sNM^_~shPt;3=td+ z#g0((Bps=s9QxEkoRK-EwgO$a%foFHTC#_3V`SOS3IrEA*0HD<=I)oche@ryiUK{M z?~#y(f>NCfNRD(qFq%28dGsQr&zB`8a}d2$5EtzVRwapKn-%j!!=mk~eh+2IFx1w_ z%r-|&!yeZM#p02S?D=|?7vlAI?;NDx60P5rC^!48wk$JJ?8Zul+Xs1nOSf*nrhkn( zt(*NflvbT{OR>Vnrp&skW zg@PK<0zDRJw3T^EuI2cI6ktr~7qZU%8cY3$vIzS-Ixh|hkPJeflph_Dah;1O9m=^S zwM&k9U+d6H_G&%G%yw$E`Jzh0f874#wHtlUzuZ(Zt+nl*$;42x#hNomDnoku$|@9f z=IF<1aVq^?*W@4XR^tcBE!Y#T_{`m9k|>aT`PNBs7!t`xC2~kPnv^-57!!b#yEEVa z5i0d)0ANr3ur z(jheyMC%l$Vi{k_Bs5o>o>L8FN2WcLrk(gIPCa63tG>OiMZVrIostrN;fG1LYHn>m zjdtGDbC+3N!uD!o9pBgP!g@g=fANYDA$UPyZM&<7`*OxWOUykBK)f4xcte>bt0!q3 zR{rpyli-Lmm-Xx|K<0vCe9Q(mY|qY+Az>SL0m=->kZrGorRqY-SQhj-OOM{9j^`Rm zdV^*Dz+xGCuN5@KLVAGJpP3-}76%=MlrUlET?R?=HFv_^I;fTo(^7_u@$1HDv$q*h zF+$5vq6Vhu2tp?z7ORjB713v5Xwpa>&n-X8^gy|s6V1(9oz@gZv_cZ<`sI_L?OQ3O z|6LDlV5GY=$J=J7FD-=RwCe7)R1Wly*3!=Vfrlm7dC%=U{M9{fSL-~^+)+k?@5`z@ zbO~4*1&Ayq2`VhIyaw1WA8}$F5?RJDgw1rz&aOPnMk=UhPYR-ADa#llko2DhP*VfI z0xLycX5pzVwB>TVK>gPbukvFXW%!u;k)V}1SUMoBDcIsQ>M2y`B>5Vm+#+i>#*B;6 z?#5VBHOPF#xEmZd0k_c+wIrnCytgq6G2|nDbjX2>7?2Pe55oiq24;kwYIaFPZWA-~ zS-#1}iX6wCQ7`l3D_5eJscyZarOQ`KyH!n{OyrKlZ2GF6`ynvCY(~+U9bH(Z@b6W$ z_XCB$tH4mB?(Un4|Me(g+cWTP2iKt_OGop#0pM?75>ar_i3B@To86ECMRJOwBSwiK%a%A^Pt87XOogjQ41M|;qz?8MYhj0_tLjF&WE zfmk-A$vM>ERBzH~MuExGN!`nW^nNRA3#UDL6IcL5CD$BWuja&XAbN}g>Uu) zyRQQ<0NQim!f2%(0?4NOxE%>8PgR~xFetfqSPnI?Zv@vOngidotCnj@ee!W2v$TXx zu5a@o-N#9aw}u$hT#d)@j6XZ7*! zdMdjC;sZ)lHI)QVmuVm+oSF*OFbs3hf`PGEhG{%VEDVxlfPG1j2^-SkBEpNM5f2;3 z#71;uA^Xk#0??ZU`O-02sz^DTShYehlvLQ1o!(Yx(lr;~kQ4P?GTp09KIvtR)$5!M zam0V9yrGld;MX(f?sosBvK23@s0@*rmJ z=wo^K(cIDa4m0~3E#g#tf7vb)|Exe>A|(|_{RW8f!*t^T8WY&Li$oE+#>NarwKm8z zPJV4l`jkKxp9Sy&DT@UV2;9>3N}WJYCQys!WtcW7vkZkSNcI=W7(-#Whl$v*w{2x0 zm@~+&wbf%WO&Du_4-Eh}@-bd~#nW7x1D=?uqmcTp&*D|cliWt@Z<~gQ2^x#OirSZ& zTrTBgl|0g;4LmUkxD`34?mm>MaC2_JD>vc9fljU*=dE6%NQ=VE=?sp!>dm*h&yRTS z)+|fagV*r^Tl)S((MnPW&cfZt|EAgzdVzIZV4xQEiZUPSRpU7ZA#6JWo&FbBp}^Sv z@bqq3`U!arkV29qFN0$AJu+O#P6n_x+HkSFO@{|CS}|U1%>N=z7oGHY27HAEN@?ehOKY2F*{^F# zt*_^tSs|p_56s`}@3SZkST(62Z92vCb658WNjJMEG5DfK=ghp)Ue_zEigFB^vGcm} zn0*;z85r5nBFa|sUpyj#wn%V}<2RmqAffVHHl~(LaAg}jGF4p~WjTzRTloO<2`QEd z;aG3-e7R7R@_hDFZC?u1Hb8!0ufj!`l2lNejd9__W_*kbwSmlo~KxyobKNB*d{c)$M-SHZSj!SIC##d$oi>^&u zE_QHY1_XHGXIIn5vo$ljMml?3kCojxX`gqay0&oKZ#Qkt<9QF`n*#VK;bw$`o(v2Q z1+`TE0Z1Wm7A;1E0M~^p{qs*E@%`QS<{&RoBEB`ho-}V7K>sn6SW0$NSUGmZ{#r}aGZgmlNtiF}@ z4c{?3mcCp;n>kims3dm_?DWCFWmWu9-J6&Twt_kSw8RXCHIZr^AP!7$Jj*y485e_2 zJ&#r5`~f8Fgh!OSvN^{|EM3}Pal)Fh>U`~xqz|Bo_k4DDk7=kRZ#)iW0%C%rnw=mM z+_kX^eepOB;U6AM#%S>XX?M<+Q1(WD6uU=A8bh%$RP4^b z(BoQ+JQcK|!b5Yedz3;`l5Z!5$~RUwe*AL#bLu!phc=)(+vSoDb@g+?Y6yG#?_Ipp zwEXb5=%(?Gcq@PJ;25ntO9<3*tHE{nls3f-D+}l@XW*4@2x;F252^J zHQ##=;Q)SyD$+c_8ilr?a4!Y6;$*&fBO!@?sx%Rv(;#U!b~hhO+lF2F9_x33R5rc# zu-HDdfjd&!^WTw8^5=);5ANwuKHWcfKK}me_;e*d!(91*p)(KDP3P2YO|JH7{Cn3^ zZTk(w@0NJEa4KIM^&6O9+_{ZYWAmPN=)K-Yy|T!>D`XYSGNxnGUE(s?(gm>Pyut{8 zs?M)F9xQz;JQ8s=@sGs4^Y-AwCi2BSht3v!YB+VlmI|880GB=Yss#89k3kA3XgYG= ziw9FDFs^)zB->JEIYJsmqEW=3g#`5?JGc_5U6>63B8OrmN!N*a3e1i^n^$bo743lc zp`5jv)s5-2EAJ|eF3Il`_!X^0cCIK3u|i)6P5sL`k;FeEG`Y*aJmWs|*PL!#j)mR3 z7fIBY%?Gxd?>NfZ`LdjMu>N3Y+4z@>rDv;(uhe98zFi^T+5$*W6-TeURQ>BeQc0GT z((_Z%Q~FtsA$b|u0C|2*rS|{pMZJOQOZ-!9Ei#P zF2tP603`1^YUXFWyN0W`Vvv!^_*AWN;FRAS=M{`4NKjp^{LeHCg-QDYUH?U2+e#h( zu87BXUwhOT{XR(aH>qr|<1%WkPW45)9dB@-`vbdI>Uf(TE);d@+d0G3v@5A6_P6Qy za-*yCoqBcd_yliuGnRWG_2{s@cI~gPZufQSy_-*FZHpz7@N44b`n6JScQttKmB2@Z zn7iep8Jcp+`tL@wKnb;tt1G0SbhWr)u6nD>G8a_yCH1+iLcsF3D*0+Tgcx#K%VX?` zdM(S9%+_BMt?jp=*A0hTjL&Gb)Da8X%FxM}wwCD6Ob2i0*u~b9A=mhA<(?}pEhn^$ zbTo#1HkP%WPb0?AI=#H1d|YK+3vrmp{;oS?al|^?Nk)k^67ebGHvM z8JT>=RMhkyb#*H9!9zvV7@xxt!y~(|Znk)_|EYn+{WM9yjHpH04-zV`QnQQc`Di9y zgU1Dl^ySPv5h(@_1{H?@3{yLridUX>7{e-O-3-fujq~Tq6qO4gf>sj>m;Y3bZ!B}} zMH@?L+oR_oDJYPesnRXguAzR^YQjFcd4OJ7+Hc&^N;x{kZ1Yu=y56z7T`aDn)490N z<@~TgVM}-K!J@V;z;TIAj%#Ot!Qk!Jx}D7Vq}X!ba#BSVfPcu3E^fa>eB!_w)s}^K``_`hU=oXuFjDf{7p5j@H=bJnjm@0Mi#PdWA zt^gKOo92R|hFAB3pedJ{4Z_zLN2GEXs)%+CyXlBZD(VG_CUDJ;=qVp)BCA;?Nm7PB^lFxq+-P0lmEZS{?1&}O8gBb6J}c{*ENpEy4w2A_`+Ksmgyl=Q9{!)0P6FsJn%|x8Z%Oj8};_7PaWSpQr>u?vP1X7B;R|iNwRZQ z!&xo9UZhd2iE={EzV>$+O>5=onHnVC=9fhIZRrd0wT2F-R&RKxW*u{-*hPq0Q>uy? zHCGiQ*ALuk+DWalE{vHE-!ZHVX8}2d8+fMIvrm%C1;A_nH-#0hS*yEE0Qv@?qNi#S z3d(#HqhwA*6z%geB0RsXR*n1Vs@EjQ4{)})D!Qx7DS6`2Wp|%S-)JwktJ_;0jmBYp z$eG-O@g!F+SG%?udKAw2T%+x*eeO0ME|D!o%3|iIC`zq=bdiGLR_9oJf78%olBJaL z(*-M~ikHa-NI6`I2{gudWF|j}Ug0VhJ)XvqufXKo!$?IhLDD4PuTUUSvgCpr1t6&s zJ&E_E;^d=ILO7{F(KD0i#?6veoPk|tRRc>>VM*l~ybIF~_FT)V+*Qm!>%-ZV$fZOE zHReuTSe@7YuWrT{f22ZUW>1Jtj(cIm*9}Ac*Z2DuNch|)SjGK)<;?hr3$S0=P}+aJ z;EL$!qmH=lwvpQ>a|&MWSl5^1TK`f7xJUlbeSb>yG#cJ-ni!a_{qAf&-kG(xvJ$`==QFtNI z;9>}_03uI=L{177`dNm_YzctfzKjo+iy(;SKpK>=T&vm9btPO_T`g0NioPpm(Cjr* z@7iCf_2)_IhMG3`NDsO9=@sa0eHA_XFh2Aa?ck-g)@?x5kQ*A2kaw!!%HD)&30|V+j2^0ue;oDdRaM=Z*7%JFd5x;Rsscb9>_J~ohh?Nv(ZsR zboXF;y8)|^^X&OX?B+)m5!XIfSKCGI1IP4YR?GElZb#&tA_EnXhgcv158$Mz3@jT3 zm6sThGyUjd4LeJDmFg|N0E+Sz5K~80VgL$e-{s}IXw;GaH8SAO9XC|)b_CZI30F^J zmgm)L`Z*%n!`B83$GxxDKJ;nbRy8DO3Yj(7`16Lu1i?PV>Sn%niwNH2MwPmllWqg$ zmSx;QN%GlK8s76@2q-hU`H!6+n1R8nEprR#V*<{l@zFBqzR zt=Hhegncsf)`b{mcB5VM^@lmFBm1Q<485yis6N1eXN)q6)l?v%a&(VIg)A(`VEo=3 zDZxHSiv*F|mh&|kFNt&(q{$WJyG_XkBr(3K(}9n3CnTEQnR>e!AN*WJlW{owzOc=v zyfWYh)4?T8E8wgA;=T*H>PJqkys3Jy;ROFw-Lq?ETT#QxYhA+V#=UU2ZDe&5YY@MAJ7oNE=3M=xn)%^@&U2AyjEPv&wJHAAGP*{pD z$ai&A6-#E>%gC2yyKc-Pm!&eEs%yOyA79-T;dJ1GcX`F}sRy}5uig)~J!mRhZH_NE z-r*9wdaK+qe||!={4(2K!~b|!XjtQLfor{IXpw7ulZelyO&h=N?UL71uDvF%c&7H2 zs84aXTicdu#yq~$%f`{rp4_=7=W>VF(6)#9&z|?+syailze}~$?XnDSGrTIA_Nw?> zpR!qyyi_1yr`DoVAtlN*ShGJWB_!YRPN~;Gx3eLg)Eo_-t~(>kC0b~^fL!vkT-dq~ zP1-Iy7-*}CGz^(O?O3ykt5qE&7ahA=)=4rujOxjTiBx?l^z+rG5>DK;Ge6;>rkqgJ z@I_&}dQrp}k^ORDfZuV8P;lAGXn#3;R$zAZjG}zI7GDBUMVrfePmb(Fsk7!&lwK7K z^t;I6TA)FkM;0PDXC;3!zrdC^OB)tpOp%oDp~ZLj)M*CKHm%F#9p$|o?W>-cX}N|d zMgCnFs_Y6v6PZ)iS<0yZq2_041!l31<(G%YJ6X=W zn#LV#L~?Ag*_$Gfp|qw7)JimFpld+sb*80JV#eX)ak2Y5n6i`Zn4SxHc*ducO zmq*t7GEr4_&qZqOB;L?aq+v~opD6&8|UZ%uuCo@;!BEU32R1byS(5&F$>niFfRfv2Ws`vvG8_#YtNABJ-5O(c4MNw)ga5cvBG}u=-{gQP1VHy3Edjf z!SXbs3N^ofuSvVgZ109K{n7pCi`1#VqKtxO}=4 zh7=bv-68;0Hl&=NquvJj7axD1lmGqKQLR)sP)#&zssV9@t_DKMgd!=Y4RVbe&I08= z-!}i3sHZwsHaAkXWwvvn(q2cYTI)f_hl`WDE{sbaY*Np1Hw@XprQM1zht>U>&eDr? zG<|xTWF8cv8p}P}*}&5>v0Hb^=1B43wzkqI=L~!$C)NV*UE$=sKX5PitMS}Q?}mew z|Moj<3^iVF#GD4M*(ROmw~6W(0V)FUfj9K#g0|N|Fq4txzBx-b6?Ctm_Rsl^@eIK0 zo!|5~G>ZCzn8tnH9`BDI*XrG{`z0~(qW6-uQj4ouDyX!SsH!`%i7n+ITkF41Enr3` zS9N1GeRts@T6ybinW~*bwSmh-O!bNgk{OSd!4|4D>QBk{ctZj7UDo%2tOZrn8Q!XY zK!|7e$m%*eYwAcBYaRnx)HyHMu!1H91z@S+yF)C55+syb_rym>o6H+f~@n z%vNm1KTb0mKmD~@eS^~N53)%;bak+hq9B`~`(WGC!ot_xhsxlfW^bt#*}Vq@a%1*0 zE9)=0YaeP<r|wxf94OsqM{sbBFo39mD(UO`4q~#hR0Hn3 z+u`XeQujc$k*&C{xnTNfrwWa(;Esc$H!xK~QMWhwg}lnhOi4K7gFQAvrdmDyJ$tgBFp&NA4M zXzG(<=pCo!zSF=p$iQKXnWKxN*A_SbV7CxfP)wZP?%mPp!TYN=CZ(I_M6c(B>a}@L z&$y|V(KM5lJr2klmnf( zKI0;V{g{;afy7#r^7>%lvba9vqjSi6H^=!Pn}>T{W)B42K_j0>?p|ac{*YVosW^51 z#G$umN?vv~EOiX7OpbmYUjE$pcBM?PlJ)9C{IgHt&lbI3y|aF?XgjgwIrK50`JF}6 zEA_@P`J$)t=v(rUPtwOeNt{}dXnQ3!^qz8QmUL@D;_+MR{A;lf|E>FcL-W(L)5^7t z-@7zdy2VyoRaP2IzSQY|$tC~DkzY8Zb_LbD8*RS4!|i>b-+yj#b1um*LgSXAqdp$a zT*@tfUwZNbH~mXT%IE84Uv9L0xqWVVaP0Hc%$LUxzJ8ed{_(@luitD-FyEPj= z`KV86(e~`x;L?-KqH{jQeY;A=(wlE2HBWEj@}29hT9*x*<@DPgxvUvP9DTAWr>AqAW{NJ}Ihy(vtl|lU^~G{Nk$m+0l5#nm%u(I&G))*jI5m zMD}a6_>W!l^RFI0e7KVxEQGTE`~Mlr{`;pxXmBMhx6RqW^FiUaXy3EJ6Pp4j$J=w; z{2t4Mp85VMyLJDP7bPP#+WT~bl0|gv!?@Y@`Xi;AF0sD7pXytS`#1IcTicgr_hVMO zl>UtRy}XgKNm?&OPswsWf9xp6rNjU9kP9i}^MOcref*294r1oB-7MJZ=F7*niF8=2OYigU-*ZWUSFXY4F-eA)Jt)`YgV(7IYa&&T;XADFG( zJ^W@e$MQZ^4I|1QVjMbK98Z*ss*E3(Yq{BUT&JmCmDt$Q-%hKH?fN!v8`TuGpwrB; zo78FRB#Y=;o8~)Yi`lcU!URt$2wS(fJIkIpIg{J5)>WlCPT7?cpGRpaj>qbv^071> zRw1GNz~TuvX59_q*EXM1`}hzAWf~8#cln7$R@Z`?M{g5(*ZcVzw`ZA%kty5 zwAOkfVs}{9Nc0Vv9y$Gq+$wJx_fYcj-nH{-U!Et(5suou@92XLVP*CIQOCteuxidF zOSsYS&ih|~z7*TysE(u~N5it=?IMi%h354Flw^aS+jph>H~;H8@*leMz0fJE@y_u5 z@fSaaucoulpPL-+czn3rzOeCrU6g*^qn`GqUSH!oZPDlc9>~*)SZY5ncy_eM>K1&* zJ?~1^E%)&cy|>-XWQYGPV`T0Akgok@X2lNWFN5P<^?%FY$YNJt>2ap?>8Zv|-qbk6YfLG64K4W(?x6 zhpDU7Lw%&H>%wOkK{vBx@|TVtO6Fpohn|h!(XTGdFgX}9c-YY8aM^w5FK0hk7cZxO zRc1uH+u$a%5|x}45AdH9Hr9mwA4h71#1 z`$~59H{X!d;GIZl=DNXIY3Z?y`I|SimUg~t5+FZv` zb#3_qcFuue-_T79koe?H%)b?u$i{`Ne=nk)|4n}?N%+S7J+gdRi5+(QWtF%7erZea{8o=$ zzjA8=3|iOcu6^*lLd~nWd%rboc}#ZA(RbhkD4MK(-C#O1$G~Dzbxib@KohG2y6*8XM;N43P5Z6Ylv3-Md1I5iJL!lzk62*T{I)tuHUEid`(B ztx=9K=F}*27wwt$sh^^9zO>2`wlT95N?2ZltphmEK)sWhoE)tB=%tVQ-)7=OVU4N8 znLKkStPB-keCxV%US!F14d$K=7#f@1I9sbaoFic(C+cD;{Ifd{t)VBqJA^$L7Xe`j zMHpf8P*zdxAH<+CbHerEm^5!Wx9)ELfRVvq`4#??+}y_5Nd76AEJZBkDY4_;n>~`3 z1rf&d3!;s5hhp!>*9OONp5wPPxogSSpS=^Z4>cTYE_J`mCt6<$vHV0{)_(E%^Hb0x zzd=Rk17_0~1_AWzAirpXZM5y~h*rHCODEalHAat?lDp_O!2wvMz6KLq#jzlH+K8Had5l` zYpdpLU)dC_b>-Ou_dt8c0$$3p;T-5Vq$2FP%So;4x$~ZwHKwySM^h?{;K3X_Ud_Lw zKGm~qW102)>r%G8$q>K9_UmzlgRq6HJmIvw1JbK2;4uG&()h;s74 z$Iy&#^bkAIVdb8#b6#JK?|;1(IP`0I&k3Yu=O}^hHGHzXLm{C6bKgC8wc4VP7?l>G=TKeD|%Iqme3w08q( z95eS25|)&-PrWsLASM06>2!_AAV+Pi3oCI{Hp6ug*=i9HxEwy%nnBM)JX4Th6uG9g z+up+Ww0Y7F;NYMd&Z~Qm(YNfU&c2b$$c0Gkma*K|&WA3y_?-dtaIg009*em5Fm6Y8 zmhUXGnFEJ)!*`Nx*9Kt#m+8q*^;q^V`+;%c>~P~6u3(}`{M7%D18Zrk=umNJZ8t*cHzFK=1i8`EHQ&Utgk22u-4`swL2DfUbevoMe%`m;+Eq!;c&t}VoS7!hP$p;EB3GD>E>PRc zVkXaPYejH8c5?LIA2AlGpu;=!Vr$|qw#F$(9uDKd5zK(OufSZ6?Qin~<=6u%Dey*8 zerdFq$STHp`G^Mg0B0-g$?+;rJi5Be%S~X*SVjvLQr(x2?C_6)^9n-!vovT}Hvs$d zM{JdUp(h7%W@63G7h1f9&(|RR<`GT{MO%gBpf?AHtJdPSSmb)KkeS)?^^x0n(H;g5 zgF}AgSxvxvZQRT(d?6Bf=4{{~gB`mo>;BE}u&{ymnDH-ry`WTIoAKQoLpIBFkp5j{d#2V{d zNN|LitsTob`95sNhAR#vy0T$c9-Q>^hzqdw@N7WlIP&rvP^w*1`XiF~#`(y@Ek|VF z@*^+7J8JS})jq_(CZ3l2dYlHJ+*q@0^zisy1iukdxThY!iN{&H5dL-jbzwG5cc{y{ADN1b_%S0dsq|8;b=FiMI8_w-0Vt?Y5U<{ z9tD$j<#fF%>#B-7wrl?`>T&zWYjGqYOVw0&YgORuitJ=Y|3QrVqaz_%m*hm)6mx08R{37YN-OIWA=j5xhh)?bs zypE0N&p9>l624Yd*Be{mn2Lna5%XN6g}T4Z8D1w$js6gVlVB#}^uAbRe{g^^%Z2Ti zwl6qfGv}o9fy~XzN8ZgJDe;Aq=Tl$2PPM=t_?Msgu>$`0AUdKY>ZnWLkpnQR8}54- z>l?Us#vmrq?cu4Gm?m8zuj~mtMZs)+4TU{Un31G*u=twdZH(XOOydUvk z_{Pz30c|ab!sz?yCU^OB4ecGNB-|CvvkAbd1}ZL@iyiCV)ygtx=IZtP=p7{Q5lQqt zpNoWWPV8V+1RO^KNLbTCY!chomxS|Oh8+MTC3a}tGW>BBeto^KB?xBnPG{i2#9wer z%mv_LU$WI{m*sQt_Z^$qF!}>ttvG4Vhs9S@x1q4Qbq|BFU3RE_?MG-@blj%5;l6?W zZ7~(s1NJ0vo9+f9p>i#Qi*Pa{hs8o1i|VvuJN(!k=dExii*>G+Nlt6C!SUT4T4!4B zJU!McH{z;YIpd0?2!EFL*+gc2GYgwQ!ZrY1Z^pII&j!yDe1igg?SCMqPqGu~$R5Ty zpLDD*7n||>L;@S<$G9B8g#8$&t>cD(_kcfZ$REYIyeA6XhnCc~EuSDJHi_lN5zJk|LYkm>ot@J?7&~`C=R$g$M2jlb(M&GISxYUmGiHwK`0l3uT zJY~@qz8-E158I+M5+oQk?-)r%bF|0zT&qLm3yTvN$fYwa4BeKe=_6NyDsC6yQoC_! z9%sY#a7i321G$noCqIr+itXDexT|fRTb!|N&mAq?nq$zw)M8UI?{Wecn?N7jL&DuD zx`xky!QZgYGVIGc=Le+vad3NBxM(Uao`+3g;|?s3It5qkcOOw*g8cz7;?%jdMIZxr zt3~g$6CbmcYj`NySxio7F3xx4XIzQvb1B&0;?|$YK+s|&iFe6i8-g$9-3~$G>A0-- za4G{yW#jC&jV7`xn3hTL)XHB9xD;wjZw!t>?C*MVbJJq@J^9H4?CHsEm!p>nv2@X^9gjEFwl{LBB?A~A`=%+8aPpp{ZWri<=|2{ z(+8GkeCb1yqQb3Y0^N$_TCX8(z|EV5xP$0)Dz`-?V-nUINpue=d=GfhhXt?U|C~;z z7qrzC4ub{Tt@O8hP_ZAjRRqLU^gX%nc(G$N=32@BQFNwpNo@ZgADCfr&0X9IbICna zR5Y~_TyPE7tjusLG&L(L_lrP6?wWbctT3&t%+#!`yxmb;D7DnA%&c&!)U34Cy2bC$ z|H-^~zyoIH9KNsfIp_O+D?Vlh+zVsi6o#>Ce}**caO19+$TVE&t?}8MA%{!n*8Fqj z)s?PM%JueNU58soGh44b)W;W@%)F_%63Q1MY% z`9DWmN7B-U9%YMvC*L@LV3SpF+pUMQgwG$nANpzV_y}>-?$;~U)Qq&m>cPHcxjiJ@ zkrAv1Mm|OP{8O>^7Om8vf`-4^{X_r8@~5x|0of?RrIq(*jJ(ZI!m(6vgpy}D!sm_m zaEVd4Dl5!-Wz5w-Kqd+DgmG*qjQLs&O^C}_o;jyKd#(<7{$O-MA5%Ykq3}N-WSMfu z?Tjb!iZ`+8n9EUF+dtK}scNbJOh6TraU<&0sAd2rn}ktYi+fg#taE##mpg3hhDl@K z#4gVcx4u#f;{C0R%OqhAkYu&vdBf7sVUSI`Q&tE`ZBz#pOz5*U#K5 zi-#r8vxpeaavb}}jAt6o+-5R(IERsnM@Rv0&+wLH7$ z&>fMNN<$FPxSx%g3A%cKfl)h+Jl7w_*ZuRO_|e^m&prOdS$`bLWsH7zZy*HTynG*< z;QruG(E^Y<`7yDG#wJY2q{?mM?n&%g>WCWP~2?Ucc+a+LuUTb(7bSUZK zhT0n`Y>eW|e-Fb8YX1!VPi6EU>4zVRxX$Qjx~Yo;YjA1HuS-v3&oY19c!}M|{0(^Y z$*;9Y``&w-d(p4X<>2yEK1F2>?Pyrj)P3%rN2e{qo96D%?ol##Jp8#?&O~0Rj>7Uh zwtcq$&E{H%lvlkcL*E6Ram$rLx>fJ|LmIqKdK~O84k0JiwQm!7C+Ry{U1?8zY+4f0 z#F}c&oZZm84$c$*N;ErPs&RA8giF&GCf?w7mcC-eXQJOaIQRSN%3UAQTDL=Amuyes zK53X`9t+U<49IJs7;hcq-_E935!h8*0&GxzG zO5;y|(K9h~$ezei`(|$WyNdeZ^}yL(|NHaz9=c(;QOTB}Rj7na_noC&o`|$jrcAM9 z@S)-ti^rW}v*Mbsix-XLUECWRl-*tDW>IbhdE zEb4Sv|65ez1fU!z+P%M$3PtB6+%nx?;`d7WkzH4M%>cQ^jmU36d4~k3}uUthGc>UH@n=$SCoAEAkFO+GDZ8^0i)H{vw2&Falty4sxtc4PC- zm*1)c4LiPN(8`YeS)EmK`W|KU@M~n&Y?<5BR0*{9dT7#}Iu{)C z73M$1EbO3-a5bb!t<{F(G4jD;kpzFf)?8BWaIhQ{g{XIL)-2tXA`A?Fg;3moC&gv2 za$AWpq}i1RrwFQrt0=IW%R>q0zQ$$V(!-76yA z1-&<}SRyj?erLFu!d{b}2I!w70>9*7uVR%QH#kpl?obh%xTs;6-PuCHh+U{SSCguL5 zt!tEixh4VlBzFDjwT$Ce#a=iHTZN}*A)q?&IBvI^8UpF5#u-zN8=PoA3II4e7hHXtK|s&LJE`HItgwG~4Z{OT^EmkRL9 zi%1pF4W1H*(Vzh?yCj&F}AG@lQ*r&5}cpw zu*1E-VIfFWS!XxsQ|-1Yf3f2Q*c$&;DEO1$UHe{XE%q&yA78Xx)oKmV9d+q)j(W(w zF#}z!E&gS0?3r(ddm{S^kN@4-m^l#hO1lhOeU&^Mu~*F7V7DR{*zBRsA@sT{1WN_* z(g~HkzFwkoH{KgsuTrdnTK9|euZJ=fk{#4Hz1fZxe2hzu<6a=9%L%CS`RDS=jXi!6 z0M4FI>~%`wWs(> zJ?UNKn@vyu4mgo{dbM{0#EUoyH)XMio>!(Ql7QwIm6Jfz=AYZ~w52E4juNd5q!t2i z0b7|Y$5!m`|$>!}=PwjT?np~br`HoRJWj)g?W%%r^Fgc)C z|5ESfNdwnaLzRQy3fE>`R2z1`rp^O;vo_VsQC$~JzVuy>^i3G{D+vx?EcVlN^ssbF z>M7w)c$(t#kLCS(eAc+&YxL+50o5!vS;a<{7GK5t8=X6QESk0+-Bw2Xdg2;~ezs(R zi0-+$z3qOX?jDClixxD@5>*=bU$kv4T{`T zWXh}C>GL+r>4EKqh`D6vfxLdlCV>>P`bIKmuwrw3oprXY z=4KYqS2230Adq0K{>6&-om?@$MG^gqmj)UtPqU8d^^7U+T4k=8PNVOb9OE-Q*UNhx z^I)zYtrbG+zQ-)UMWO%wm-Aqm zl7jOm7n6c_C!hRl0vS3Nzxp71pcQi+g)^o|6m6=qdc#pZzc_L}>Q*hd5F5YXrHz>8}Qq`tN?|^p`BW z@@ke6=BTPT%3pOn z_;^dyRlVF4wvMdr_i%%=OV0B}q}?U@&~wY>grK4S<}?je^lvx$Xhh~m-dq}R>~Vwx z|Jt&4-3^YPbvx#<>p_i89}BJ?3+?N6vl`^>e(n1X{_UY8WOnG$Joe1Ic`41>v&~GN zSMbrqZ0ke+@^?Bs=YvL63G`PF?`RywM?|^5m**YH%RyZ87*L)NmLH;cQFvKI$ZrA) zAfR*z|9CQ8mEw7dNWcrV>p)9$|46gd*m3sRspC{Yac9U?r8c|y!Mf;^ zn!94|z1`d5D7O5pc9wUg`l99S3)wwwhIWqgmK*+)Ui_2k-v0b-)85v$_u#Gf5QB2f zwB2;JQb(kx=Ooz#j{6*WULtNs{~1E2FeX<){G@Ew0w8F0>%0a44l zsET(zVMxuGrx^uhNjento%86B*9gDj3f}|fd8(sSd-)aiJX$2ro5IFfd1>pTa#$YP zb646jd#oVn3CQza)?Yr>OjCg#tv6FPETS^ozreb)pqW{6YrG}I40fN*0`FycCFPUV z?3+Ch^Q}29fAzF)7`nP)4ji7g3J`C67kQ1b3{ehhh(dWVLo~37mzmY&AvkxZL6kAI zrh4Iw(c^15AZ814?b`!hz7cdynneqkhdhjX>CL^lj9yQMm^X#X5#vHac@-~k$EI+3 zLR^*vmr3M#W{85wQ1MWgmrA~u%KfM6sIXp~D#MFz>Abbko7D@|`Efl|>|G9kzB3B* z*NqmP8&;lQew%#?1QK7{H-8ORx-H(%YE6%cga{=Q-&Qtf{-0D}j9IkPmUFa0-_- zg3E;&9*vM+CqEOx;otBx#SEo?#EO0NBayvpk|BbaUfcoav3QCsUd3a6@DN{BjC&mB zHFl8vteGMTabJASi}oN<%8g%HkXD{sU=O+s&D^UVf}EPjkMEL^oCoK~kbITYZ(_>A zk-(b{qhLdg`3=363Xqo&x_n@B&t!PzjUsVid(Qa)tbX^#4DnCU>5f$r9tv<1)mIOd&s0fXgb! z1suX1{S8xFp}bChHYHfY0OcdbDGK>HEJ!Ce9N+6II7r5wq6qAvH}AQgwAK`=t+$~5 z>aQ!NIi03e-R5rB`?!I8e_oW5l@kJ$7}@$az!!gCG}(JUD#5Ys(omcOPiC4%>)Z@% zHT8afBCu0798P%%d07&ERN#nbWQQLk;Ijw{YI@}Iif4zjde)D=~ zA-`qFZv@J^0p$vL138e-2;WCI;nT{`VuksfhQ{^t2j|8E{s{!cfMX@}ew1VTssI1ONsk&QuE`l3rrYm^9yx$m5bp3f^?z4ow13@ah ztRbF<=UJ~Nt;a9M_H;c=yg|N_uzfi0Y3qNtVD_Wk=R3vzP|Q`N`0?b%VS3*D&O8MA zUSkws?&Qfb6orm_*K;UNr{G@lHM@AeFci4V<6eDn_vq_ojiW&mkC&Hre1G}azmpf# z1l{X}{G0gv^Aklk_<|d_YymEV%}3`!IRw<+&I0g^EQ$$}OU20^cUEVCVg@9;r5tvC zrWl*tNzZIWihAh-;bH10o_p663=2L;@jwhmH2A=loiO=m1P*5kdW#aX%e;~bw6FveQt(5Os zz|Y9QWz%u#GAMwsV7x?2yx}9yLl#@5es-P^3L%p z{9{+c0tz?ra%*tea1gC2<~Q2x=L;zK#juZfyNe&s{w+!NM_3r%>vMX9yf zIG5oq`=#Rpo1ex7jrim?LqRn>|BM&Dt$auCxg#0;!z_LVj5`G5=xiuS%vNc_?nU@= zN1<#M?l4l2N#Tb+#QK=#XA|G#WE6Pr<_8|;7uE5rTlm%3=jw+>#{1~Gl$TjTe#Kti z&a@Dx`CZTp=&vlKEx5P!?&OTY?m}>Az7Kg|JVcKg&y6G>Jq5kJfxJ`NM1y%=O}K1= zt?cSAzV+Vt*#S!jhh|7TwZS9OQ*EddGU@dc@*G>BjGH{S^SmJ8yR3VU@=m;9NFdi& zul;LYyI**5H|Vuo?hCMhcNoSUj>P#y;0|Z7(j)n@(WKIfO%d>X*if>#Kzg`oDos4M zSHMp$$5x&x$fhi$N6rTvqA{rs-~waC2e zJF>;BN2UC9CO^G3EgeZyd=_8$5GzYsvq}7eELO4rmzst<)QLS5$=}D|vm!t2Vc`yr z6dY#bWN$GjmmhfML-p=AS*`Pg)BJ39Z%$1CuIkD76GZNt)D?;1Lh(?JaB_&-A+S#p zKkl%7xbQ$R@MBksS7g{t&EB7RycX|(N7+2OnV)|ZPaoSv6UsK9p+jCbo)q*BW(8zE zS@b>{;KLqwlur4m%=?Q60PVEQC5`Hal5dO1Wn1Esevr?YvA zK76_WIsoH_9u}l`7933OhMffJ+l#pYG=G*u&>}&+C2)!&IlN zeKejyK&cb*vzu_0K`+0Qj8+Wtr-OLD2*poucfT<&thjf=tyk>7XDofliqFWULnr&; zq9I1{pQo%tyuO_GJ{ghJIb3!V@5rpBw{#>wk`2|RKxs%+#Ytaw>OV}Kbigh214FI{^eh>|ML8n(|v2cZW&1PUHzIW!KO4}Q&$U8 z%y0+A1$z-}im*UcfZLmfJ1D^(Wb!qcIBh;}PbB}$qi<11_$A7}20wfY|2V$oCN>Mf zsRMkU){&4BoJb~Ao_{C^WR%j#W4zI_sRKIq7X2FeUIdhyZH>~4;BnsW31C3ph>Q$~4OQZKuy`r0!{&4GlULGz3W@UC_Gn;U@2;Uq5E(gKJtvS5* z9e?+((DcJRf98xI@xBVXH`L%r!qWp40lcB`>}LsKb-NQYkg$()@jf-KeH}OxAD$oZ zb+bdSHtQ5vF5}tyZwUe;mptJ$M$SEdz!M};{L*zNl>+gZ)N<#*w_U| zAaC_T4~Crhs&l`+bnDeg$JFPYhb*62i`-I|h7Kj{Nj9J)mY+F!^mVQ;ew!ua@O0F~zI8KhH^^aCW_7=QeEIb0?B=|48S8h3 zc;@#U+v2;e$2atZYq+m*#cI!>Jt5sbfIQZ<98fTt4sx7cvKj&%o@+b~+-cMs+T%D^ z75dO+Umr$}{AN5nXp{8q{FBn?+&6utE+3*oOB@!N_8d9mDD^dtUyv`Qsb9M6*SLM@ z)GBlPHDq7r{xyIqHY5my^w=v4{oD7pp5L9|cARl+d)2LQ^EIwLqX!?kt$lu+exS^= zQrYBWdit>qLX}Fq=^5VoVYlDSDEj^HPOah(@w8#`L?^eTVq(I-2S2g; z=3(`+amSX}A0x95rD+rMp^wNVa|dDfqGGn*X1VT@J5ql|9j`MgS+RcH`J$7kGZYR8KLDCjWwd(J_j7Tw0>Ejth%4J#ZJzoG(%p_r9AyJ zK3KueZS$XR*E=o;@zy#p%{W=k=r6fsUDl>v2FI3W|~n^gjR2tncy<-xsSe=Y#-Gvwh40a{cD#!_!rGo z4Lzf!>y7-(ADAp{xbNHZASr@Yes$@1mA@wqt4Ghr2BdL7nKVenwOc;qHb+B$mSD-o z+7?!z<2;RYUr!V`-V7exS0&L6`&r=B)uybGOw%P%>TJc`O8b*%^=xMP9dEWNA7UBl zxhCP>+VF=nW8y;GzMgUW*xi^ta>;JFiC>-eMW7N8x6ZC}$YCt_{MT|@zp$Quqn4Pm zuf#du%>i3Z=dEg&K2I}Pm>+gsijiY5&l#Pd^qCuXpG=%0f=`hG*RO45`&es?bx+d= zfQYh;&e@EmQ@jW3>+PC6IeY!~>zc$_gx1YBZm5$S`zl+NZHbK4CS`P^D9fld#nw^` zu8EBaYegp#W(mC{tU_tMVjO`>=!N^8Vt@~sk zu}8fqPtY>&VkMwOu1K3#>IXtrDTv4rgy z^iGgi$1OPZ2In=IU;fanCpv=~?XuKeiVs|Gu;myOY!g%Ud#K~i)1$s@h$lRk&e3+s z@Ic1`O87HMx^Me{kox__8Y)IQ_bL5yrTL2SlpBOzJU{$OLh%8JwoN+Pi6zTO(n@tF z&Y%n&5+f)J92efucct~+*ZTbP96Jx5I zlDnAex@!7k{!!H#Nx5WjZ$;aErM_e@&~I>}V(bm@*mx^hgV8aQ8H&EAH5eHZP|c`wAlkS3cCKuiX8NYS8;M!xKMv|W5~Gxm z3Z-0z7+Sep;QrNvlhSImc0Tfm+gNZ+`eC_sCP_nXBQa~zRb15;Sr3etz|D9!ZbRgQNnx>R?o(9jIf*=&)l*#+fp6QABQ%W$3cxqF<|? zIl?Bp6G3&l5HgoxuFQlo<`hweHqFA{306vNZg|@2{j4-2Z2C~VDEfB9z#AURc*o|% z>!)9+Is91QnE}(Jei>`3}w&>Sc#Iuc_;H4=B~v zDbYUn=#15PJ1*w0Ida8FZ=Q}zJMm(*`|j?w-~ALFo9j#R6{gk(?SC-VSafWG+V%C@ zV2hdTKz#Vf4A!EvTj2nkJK;X7bBEn;S39csMV_l;&MS;BUV}gyLV!>Mqx70!)Yq1BK1n{VipA?f=J4qEw;r$BcEb`*0R*bjH+2C>?-9D9!+_}RxSANsYQmevWn(9vd5 zRJSQEejZj1;Fi6lRb2ucq*FAR$;TlFbm-dUW?bUdD54CFrgbW$Noe49&{fEdVu6(3 zRNhkIhH@x`$63%cY!*f@o}^liaFpi}B?+R?g;-O-0cX&v3$}r2_LAqqH&pu}L~Koa zV7}ds2r3w#J*Uc*SK;P(Z6CY@D9F6rQEYi8fFdGj2K?O?_?`(Us<1H#fU9BK*8un? z7|Q~FB><1lD;$j(+?qziC(|4Rp^kX(O-*JI6bmm2QxHqb@I&!ksm6V4KO9fXtw|!c-|4 zrn(436d}!Zie{X4-;KppofbJL9&>2slIdJWhD;bwb(%+Sq;E|pdNDdrs@`kJ6P{VT zjkcD+k~gsOJZwFJ-rUn;FYDu(;wVVaXPiN?E$!1NK(M3PbpQ`e#(XveNq{IjaJ!eO zNS*|e>kyPC0EPkUlo3dbDA3s$V*n*)lbT>f1jcn3<5>Wn31E51&gYn;f9MWT+_&Le z$8vyqNrVUZvylYHH^w#>L{0%TH&>7{MRO=-pHJhuG>KfoAY<33&doceE1EG3NpK#x zQMSw5Niz{rm3!HaU80J3m|G9Z?vYFZeDMrG$rVBJI?epoW@QRr1+uF9xfL&9JxE@BSs1Pjxr8!wX4xl|@#V&aD zK3fq%Y+PxRGT8{e2*mcXw0GixV{F|ttC->JmMT)kkA9vQ^?mP?{ z4~d{KnrkuO)EfKPtJD$hu{A0-(KfRS|agXK@56fqO&U2$i z#NEb`AVmy1cycK!btI{T>plfi2pZ1i-1%a$!?C(XtSbYO9fmwHH6VqI%|2t_~P ztcEz2^8l;RH1R3b+Erwo9%W-Csw#}JU!vM{!I(6*f*Dt# zy#D^}tqMeLqer}sBN&bW73Qd+CNLm_+q2gxjQ|+r6;!N?N<%WbVa0SAo0w~#gWx*Y z7&E}3lfE+&bYgLx5xQ#_mn?wEymx{yk+az%g=}!YnC==c8oL2Hr9XCLvo{*RPP>uq zZ!vG;X=KV;7baM2rCg>s;ec#+DxPxCkJ`Yang~T*JT|HZc8WA{VsmYx${m@YH1v#! zLVmv~USto?I@75KoO=}8K!-Y-3;D5A9XG0iX57`|C^RaaY}!CKE$cB-Yk4I*>93x8 zq2eLOsFDG#wI>3fT8Xm*7 zsHRaQYMWSG9D}Vm;%~y^Y@kz*ZUe;;vZvtZ2uMYCbgqMtdoByOkYF*oNOM^w8jC?2 zdYEfEmmC)1G<3od&vnWHDN9r`USzY{6B>ZtqKXMPe?@hDy_s3edsXxKu^y{l^g=(! zswQ=J3)O1winXV?%@o>RLf!k8W0x^)qmpc=pNvUgP-rq0xin{A+HGeBid97C@8 zQON-17^lYqi=693E>X0ND@=#+KDRE=Noe7ij4*WBf!jem{`}Y_ZjNb-MUu!#19V!Z z%gO3xIpSQ!)jU8omX5!`7w^L-zlmvyCzE%&=m*IsgDwJ^!!glDz|@5e8ZU{A*|hdC z+OK@;HJ1U>0>?%GZWPeo{Nnv@zUi&I{=1n0vk@wkw!31iXW@*^Vr7d}2dA>u#%dgG zl^kPV_tx5sYu5@4KL4n_9zgd3_7j|s-DrCfmsUO9V?ooiq>&)59Sqv1g@0&=G3m)b z7>tgD6&diirwAq)1|ktTo=o2kVD)3M@c>?51smWmSH;Ga;71GCSgZD!w9h|-x#WM& zIW09hmxG(qXc@a{vJ)UKwh2(qQzSRC!$Oa{ed+{GgDpjk zFdRk@CAMhic2H4qk6iNkO*}3sgJs+yqOiHR3a}xbCP$#zHm5m>7c+GaRkOwf6K{JMmWAW(2dkg4I8P ziA0ogU?rKi3_?&cl|367{*x{%4e}XmlnR330Zzr-hp`7w#$usIrMr_rZzg#rM0Azt5^*fKkg+L0As2|v)e#i z1|mZtx+vb?2++tp@MJegsX{iUi=2@I4(TFFarv%5g(xABG3eVQ+w06-Z4+c*eIr2%_AvgEmmU3 zf7W+&`K@$O_p|O%t*5B=OYiTYkJvMs71){fo$UQPVC9a~_cFWo;u!^irqD#T74IKB zN*g>KLs9{8@jt4A*h*2zkwGAYe?o3N#%RsAVS{fb_7*$RKvP@_wh4(mq`Nf@#Md49 z{ihK}I&d$Io9mZ_C*Rn_5?xLN(dCF6owZ}L$T^2AtGka+%8G)>K8@xamWHN_ZbX7Z zwQQ-}$ZI^EMUEiU(vQ-dw%NoNvjUu9ng69;J@P=Vygbz zw0Q6P!rM)558p2owpbyYzt?opUvTVQe~aF)P4jon2!@pr>U$A->0OWL)`gEspGX~J z_0Qif_lMXnkx{&yzzuArx=E}oytlElNVq7c7#_TCL{^-gi@CQ+Hyn5(kSpfq-{dM}z?3R*^$ILY3|(qya#KC_b!JX@ z1DIvDr}Pv`aczL7o|ZC?pI{$(ixs@(mOv5OViXB^2go|4aYsZ z>UlGL9Vz*WmQiiz&e5C?^6xCi8vTx2?Y}c_KEAoZr@}P+PE}&)#Vz&TC$hrA!mph7 zJEnW+@_187Tl!F?!{KDBt+8>#2TUxho42*G?jJ~S4TUZj?`_<_2Q6ec;op@7+&r^?x>?fr4sP3s@g#df> zj}`wU9^EIFi!n&$s16V~H_i9xzv>*lP?s7YEYMZg*Tq)vI)Hxr_s-t7_)1^bOP*$o z3lD+^3^JE0E?@R@exngupr4=->iHAbd~3p`$oKZdxdiKN+fSa?ifrz!ueSW=Qru>F zkoA_dBbv#^>M@;@H%2aQ@7LB&_ANL$SSe?!v){~K)>vPB%#e*nPY64dtppMdHppJW zegm`n0i}Qun5&UwB;+aIe_nD&t!vs8^z)y;pqJ`L>gTD^8TERv{Mab0T8r%-J@pH= z-MpmQF9oNQ?B-2nXw&>&kWiq5)je=e8q=?ncsTol79rwIKlI4e%tJrzT>fqyR-?{E zo`zY-JT0};*|2fnQ*#GGY;R(V!NFeh3;HQR6Q-vQhNyJwCfcyyp4^$f;-$^R-iz-K zGF$0Y+fw;;beeDYbkrg&$^)YrdPnWNM)A&3l;8HrO3Uhw@sRgcTUnzX36V)BEw7Pd zzE=kBNbWX7$)|Om*Xn29Kf3W=O=65rLQR`hO#(*_ONbSCnCisEHssV}33m-F z?!Wa^rMCQUoUF+ zNsZoPx9rrzmdo{$k^hb!I@s>N>~?T++r`?{@k`hOMc%Os)w{Ar&ubUvwDne=b&GnB^&dj{D0G&kQD#i;9Q4~aCT!l_l1PT2FtTO{w%*4-X&kzgb8O!;a8nb$q z^lmw_M(F{z$l$TLH|1-b@}YRH-mBKq{UOVoxUXpKdn$x4c_GJyvIC|suFshq8UH7I zC|2_l+}Ga`TexkWn46sGZ|V76Yx~Gd?!_tv%c!=($PSLyt@1(3)z9(<_+_n*)^7BA z26!*hcVls4ze0L<@s7E3`8@!ZR8Z03@=}h&en143({9K|Ng!LrBcJNX^rY%ZW-bVrn&d)qilOlH{c;#1@Rq7osEX7CiB zFU3T|`TGQ*?v2hVlH)BvfyE}6kYLn3utWm}y-d@(>D_JUgx@nztNMU#Wm~a&laMgC z?5$9mU!0~W(o<+(n0(+-dZ?p8|Mi6Trk?#kR3d^IoX3#X-Y;Z*jm@f4k>5Zl@V%OP z!@M@VFRCD3KCGCk(Y{Q$&+s*AYYf0qRQxR^lk!`eW;7Ywk6J}^6SjA)x4s1wS>K%d z7e9C2Mi3JkjkYiTcdqB;zZtvjYP1v+Jg?g0M*x%yg2FOo(0aHVt2l!0F)&It89|N& zEeEUf8g$o9dK-olPb=13hP*#`%a?a^p5)FF`pvu@sFM8D3?q<00dUf%iKS^d3dj0` z^KpfX`P$=DoO~u0W08@sAcLV{Nx%}EhFa4C=vuG~aIR@+EqH)1ZHCo%AeQVS&@fi8 zcUPya^1d)A^)*32k?b$o7Z#`YVwvqwJiV^aB}Dt~JjOO_<+w14qkdv;@u=<6lTVk{ zYewCFVD_X^E3DU6x&WGWeuZu8$!c>dG=a6cngGCPyAZ%UXF~$ zGM1daQe^ZWm2g+UGtR4Q^^4aO^*y~@uq}UU3qJ9L>8U=m7lq*M4r;Yow3nsS@Y!l# zcuQovqj?)tw6%2xtH?r>qW7C@Cl+jsMGsl)FI`{~b+mj#y~hO87tv`KKzXq#>T(pI z%yz_NMRcR?9p`Mk7!ho^jJ56YP};}h>cu;vJp9uxKe_Y^>ZWw=QEo*s8;PgwM&Psr zHmd)G@T@jIpRp4Lbty)pE=?HBZiX~pN6b7$l+aOK{)w*-tNgQW0+ugsh|yo|cdD!Jh+B4f)>SjgFdIGQFA+~1 zdVMB5AU`(g6h?E}9%J2Wrx0;DS?l%VyEhW_2Rm;@zGzE-UXWs*5jhW|l>|sk{Qja_ zy;jBnKrw8jR!IW@yBKC@3n7ZdW`a0G`8KJ%51Qs^ISV~7Q7Yi+ zt->U|awRMbpOSveVq&r^`sIQ~&|0gG3xR*_w5?3V_#yw8UY=>G*8^JhpXL)@#TZl< z>0h1(x=^|{Yz(`;O-$F0ZM^IfGojo65mt#^{3?GC@0ugef(YCi#Utw1ah<1Pg29%5uR zYZVy9LpA(b2Iv^jldHRg)sD~CVhYjgiRj&IbUg8&hr3V7v!yc4pd;|Vo(1llG`W;K z2Ug{ehan~73K-)Cg1fPP^i|s0M#5A*ApjAmA<#`jFbdGA?e;33K6$U3$(~U&v(mV{ z9y&Ja<2|C8#IU(%flg*u>0ZNzHm}60^o31NZujVGvDSOW(PAB&G%G_T13EGF)x9Yv z3E*%+BX2;60c0hiYh{hMT;!4XA$GN4ao z66OoWJQEIuAYH`@icZ48jw_%Lr5nWtuWA@6kcens32nK`-`n!c%=`n=$FcxbB z(q*O`;=7t2{uPlizmOP+R{XA*c*+hf$wx zf!!gJNw z&}r_|FWrYJ_jve9L=a5tg&@+DnFRfoe9XkOegG3}ih%-{1a}0J=dq>bqc-B<-CL>7 z=}~WaXQioOF=mI|F%qZ$2=gYSf9^nwRao`qiWi+9CL=xc5-*{om6M8Jv?B90=^D1t z_1#(Bt!eoN@06I)DD88*0Sb35CWu1;t}m~E0m{ihB}VZhS{^>#{HDO>=rBp5D|n=} zc@O$@84x0}@4a#gF9CSn%0E_Qzl0FWd|-t@zfu4fqCSGs-c1~PTL8**)X|@~J^sNq z60o>i`DDIMEefRqED}K-2Bga%E<`dhlNedYKY`JvA0{*?%qJ9k=tt}^XfgzwP>>Zu zSd`OYOX~^a0z#pQngxnrUaYQ`?%{jFTsLfGZHINmsK=G7)JwK2c42+(fqgBuFWTEQ z!}7I$f5rxkK*3d>3w+JP`Pw=8kw;LkqGQCo`fkKy?cVX%A(AatOrU(wE`bR$gbv|M zVUEprcR<(gJY;iTPtXm;vW$|hC~Xt+C^RQIrn3!l_kbPda)69&hzS5ty0q^O!N3(e;`UrB3UyVz(I2e z;`2WEFW4zyqKVpl^_XZt+Xc~yLiFy~6CO;L5oyLlhM4gfy?fL8O))wVY<+J4Z0}yp zDk9|7Lj*j*IL2H2S&jNvo6729N8JP!Y_R4^blRs2qd5y|xq3+NQ*E8Nbj^6V zJiTMu1ZS;uloqdETP@|UQ_|%v5D|hRvBGh1`x=fTf_dvrmf|mC@q8UfX4j2&iiwh0>h`Q~D zy0H?dxjW_ZG!*5TI5e-vt1sD*uV$8<^@hM&h+LVO(Y>MFCmF-mt5(FxMVNfedH3LN zY-Wp@#?~Fvnv0ipPc$07a}UoAfwA}I zC5i|nJyRciCm$L@t$rc`Ls{%CU>D2XaDofOguQGw!NTYPL?MW>%M8v-Dare(vf?_Lv6c9USEl9*AD2}4tN>?jxBxz=t1&;Y7#3Csyap*5wD3KHPT*0F%m z)HuhP@Mvox__6h8EKH>eWt9btW`i&hRAGWkx{qe&!S>9DrG~DXnP%V0bjTG{G0LIA zP&*3N{W_HM#cT_uW_rqZ>!Jj81i= zfT&Yx0SD454n(EI4Hzwq5>(U?(%|S2b#xg63=m_4f}ozE9uFRs^X=QU>)QX%-sgGl z_x{}x#E>bv04V9;ZA!J(}GDMsT&1XQR+2Rj3MW%#>)#jcA-drFgzgH?r@ib)L#Y>1MqC=svug|LDED*a#h)j z@wp!FmGFre&#sfMJ_#zL^WHuh44II@$u(PwI1#7_x@L$0{Q-WtU0mbo`v!C0gCM9R*`&`mHj+vcr-HP6m_Hlre}#`^XBcrcZ`^Ix7=d!` znw{jzTE2w_Q{lmM;q5^5;r?0G{|`Ix*jZIk+O}sk@4+Fy%#(cC-}bUQ+$A|LC;1CY zautOIvQ zE>Ph*DDLMCw`VInV5qR1WuzzC>NgV3zYt&kA~}${)0}l_!?1b7K}YJtP?D10X2Fl7 zf*)gV{z+=O^y*x4*W(mc^`1qsYt?`DeFCeV>jn%2w;Yw4&Jglw5F(X8bsj#6Mh_4< zgXsW%w?5UysCpOyg}KXG(u0m?#lAlp&-XHbVZ~QRy5f%jps<2mB;I8v2$F`^-K)+b zuRu*O65G{jw4 zRF04`t0qH~M5uOHNgDkTR&j(a1p!5<5R1ad>Vp<4L~-1_Gf-Wnh*4xePcdo&~~%30+8WJz~@8@QDh( zow0U2&)#@a+d;-pKku45dLn+f$Y?ar;gPWh4Vr6S=qQ0R6OP;M&EAxM!P;XOg{WJDRQ=+#bSeR=SdP94W9=hVG`oXFbiuRbiEy;E+CK2=zi>ZaQ|^7SV9 zkyV-E`L}(q-kx8u3V###njy0pYvDpq(_aqumj4a zWLT^j$quHS%!WX;8GO)0fvpZjO8bz~;P7Pf5KO6t3*vY*3LUolG>w5C=dkS23LL(M z(TL(4#8{tLooe|uE)@GHrSxRJ`EExOtVthTLez9EZp99vJObd1xZ73JdUr*pd^O7a z19o0T7TP!Fyts23ePKR$?nQ%kau1xlC7CS!L^&>cKry|g@-g8J}Jgh4Xd+i1C-H&i}VLv=^%#~;fxT9WK=w_HnJ z!Cs^fEAUAS=b*5pvgk~GD)6gc&#_ZF% zu|S3?Qd)3Fo9wRCP?i)|MpUg9gQWCALiN1vhsSKS;S-YUb-8jiQq9EtWo)LU+StaP zcJ5OMT!?VKhk%dl?I3I>oo+P(lggqShw%D@U6~>X0v&vC1Q$8M7P7R?NPRY)z&fem z-rxdC3aPp{F3coL$XWG(fAa7!B|aUr7k&eYP>%&NI>Va*5z<%02>?c-0iyb8FjE&` zODLs~)Q^-~wI4LfJ0cUzVZ$D2Gc5aK+NJU$Wk0x#S&R){36FO$S>uhFatp6W>91%R z&BHNXg4`4OQ0eA*reSiB*&$k$gp%XqYPT)z9q9~K`s>wNlvCSv$sAqFQw}(^+WT(V zV1(84!9$JF<-BU~Noai053+bBJ=h~`LPcD-#R75QLY44S)INA~{{ViR}=9Cogfmr6v zzX!tK_*XvlWsKiOY~_pnx~7yWFR5B|!|t*^5BLvD71luVaA9OnhC3mrK;(J}uPXd& zGJK7=9}ZzNq9_h<(_V%}za1SFz=sOkVjk|L2{$%dmn1>GT=xm(Ft#YUDEvi-YoM z@hgh6#0=9ayHxRdAvH&IHcnFM3S3QuAKwj}`LEf?Jt$K~cvw2%kEGt1M-glg1=&omenu_dGX%rs`SgqRDnU zeE~4d)l^v$A8t;N0pS8hs309en$Iv5Hq;R~!wM*2H~ND?90~@g6?V`IG)pG&ar{JC z%R!@*IB_g_7^*zq0He}UCH9y>HMAKY$pnZf{W=8h_n?1ne+q#o$jTvb;f4a-^ZK&T`uRWBG&d~F#ilr+x@>1EAX3LVfC z`3Cp{@(6<3gaw`cCIK+mg=_>5(ZH^B8K^?myT6^!q{>u`Kuc;s<6zz%X>B^hAYx1i z0B|I+VNH{ha+tiCR4GEW$gu4A?kc1t3uaS-hnoOc50AWPqH zG8FgBPH=EL$~uZePF~qwC_m2pplBS%7@m(UI##i{yN>oc>@St&d)EI3N?q8P{A-;9 z;X`^D&G_)e#r|*I*$VX{*bPf?;ueVUK|--Ya;y^ocOV=PAI-w}ta9Z%bR&SHM4ZAi zvdF7>XE_Nn?hKs^mxz~rBqf*?h;t#P23+Su0?+~eH*}X!fM?9Ujr;EZ5H0{rDF<7z zE&%Zou2vfxZb*TbY7amHQ?UjlnRi6I4hySC!#*P7&ZT2ki6|}l?jZtxlZxXJ zM4uAyy3~D9FvvXIY#x5Hf{(H^*Qut;=L_4Bi{cF;qL(Cf{v#c72s`xULP%L@h~>P! zUPMSiEPC4L@P%)p&u0z`mJ<9j(yPltn}iBgYU1yV#OWBqLffHc@36b$z_v;f+%svu zUB4?F94>`+v!U&5s09zJ#07Rt_*ii>s5uqF2OvwO;0GcOMTQ!3aq^6q$7U)h4rplx zdNLpeoIp1iB$6R6O9xlai#rX0ntV`G0A`KE5s6S?=Qx@UnG$x}5cUZr5Hn`bNfu@b z(9|TEyd`79RPn-@>@WpuNW`bxLpA~2Cc zh4h1kFU|cr4jO3tz8jI(QBONAarVZYG<&Z@JG9i#-S+w;@-tcJaTScf@o>nP(oXu} z%DT{9Z9j8pR)+FQkW-1~CsP`(tdRD@`YOkMBU}TKySLU$^&M^er)Pya4*c0M- z5nJD_t}HmVn*~VHu`|mM0~Vm)fqlfr`gUQpDM3HZL6$hUrvmH>9W%tiy{4aj&&Mrt z@Y7`coiNA@6~g0S2l<%P_n4Hmi{HAJ*WUPaM&;N+6%K)-O4Q;kmg*1f61L5>6*K^p6RY=r2WQwo;NC0-ybGRHVX%0K7 zhF_w9x&q8B9W$(nU1j5*Q1Bxx>md1yW~mBD$a|1LDy z!3=tPLa9@=dUd7%9t!QUNV0WH5~r{*I-nUD(@DZ~u%RYGXh05!0?F-U%p3s+ryEGJ zb{o^65@d0b)(K5Y#N`o)qAC-XGtF(1CVPRZ=mh?8aJ6YUWFb`^Ai)cl5yXNN^^4s$`?@U6kDp&v)64 zgH{^iLv)BdZ3nPSAd!b4T7sh!RN)@RD$$@uY-|@7JIRA|32t6yKnw-A-8}3t1^56~y`j42 zWi^D@dMFDz5DUc;Kx;ClorEzbv>sZ=ihaZmkT4I!@6NNJ(2LMs0k%)ZNvVx+Eu;d< zk=iH*$~VE?^orhdMnY!l$=^p61VkY_YkwXXmhd#>gVKakvy<3yg1D~+Sc}B;?a(25 zls)f+*C-dF^9wh~hwupa$2|ILF609n|Cxq+&&SWvaL*{XS1fRa1-Th>^=aJ61&?xW zWnXFy&epSi%*m-EPD_r7AMnW_4qGec;-Vak@b7c2^ zk@Pe7$_Hm3TIpU-_#T_Q2#C|5aaVgDmNCP!pe}w;3;`6%jG-jxQzF)yg0W@`|4gVg z89EE#4QWtH$hqNBkjFX)r2)IeRP4sBFvJrw0$T*nAN>s?LkFyc3rh!!;GV1hfTRV8 zI|I9$3^k%*4XKz(4)(DCGC_kr;X|~kZYDfjApq^8;&+Bf*i|Zik%C_%;q{mH4g(M# z1+r@eYbbC(dd#trg?=fi_%s+qTc^UDrX-o7&=S*2>Wl7J2 zrDx{JatTd^l{@SSz4ET7vJ)F&vk?;L)Nu5TfkP&4n9o~EmT#1+{ab>5m`}PfH5;d1 z8(|VkxX0Ji#VEqtH9cW73BT5Jc`+ULDG3VHbh7RM;(#g%3MIF83b3K-&ZgX?!y;Ki zQ$+ckjW$1a(IQfx3d&Y`fV7)+4p3clprq)qAwnGI$1oNXK>ApKIpus88^a|) zJLr%|OASdH_6hN#1{=D}#Xs)Bf1)sCi*Tocu^McM{|wkqX}n8HoN2QU7?yX!=+^Sb zr7tN29M9L@S*>(<@nCDQO!>^>{_d+~iutw?vjsz4UV6<29=g%Pik=w+y?>SdgbCyryPcIC{L2AA#FOxQ=A zvt$=F)`AXC+M0QLl;;9kUj8}!+e3NbPxs;($~|L$|11N^uD51vD2_z4Ci_({T$g{; zvSf!b3iv@yoNNI#B`=9~O3)a9)Q_+2=9noKrk9WHBSWotAdd~1bi%)*Kvu~3 zP;dO>{dn^oY%d#AM1U#^uyO$8UGS^gH<)Ke@ePETsADtl9w>A)e%WP^&t4Yw*^G{V zSJnjP2kzKq>QDS=O*5_c9rn|`bT+<@F&W;09!)IY+sS(N*y3f%_;7ob!{V?;=6ZGJ!E7PBaqo zgsi10z?v)L7U;MQ;J+mjq>u&90?;RP3^R3nV$i2vAX*3^G`e4rKOgmMUph)^cgQ?% z$stShaHXzPR7t}z=z&t*_?#8(%aZ%gjQC7FdzgR6G2pvp?8&i$ddd~?(Aj6s`F9S< z`S%s`4<55KYpl|q@@VwfXY|D*GRjjouf@MFr)%oDu9CUxNY0&&MqSUQur7%38SwG) zy5D-#rilT-EmY_0Rlso^YRByK{DfW*JspNs<+G)xozp4EkQ>;SoToyK13^G)OW*Cg8?&!WFQP!ik zG3Tc^k|=M#4ZGryD7R7%kJmbC;LW2>b)F%WXuXzRKa9TT7^J<4c--iKl-i=berw-G z|AEx|+dH#O3?y7AbXKBqRUmMY2%%;2((DxFg9-2onF~v>vVaPP(1~1M30HLC7HVCO>YkyN%fuzTm-6zn3oSh+ z;+L&`1#eCBi>iC0edo60&}4OiyI8iy70XnV##x!pk3+F2;}~^zYSqVjl%ZRwrbPIo z?E2f~u`eZMFHX%!DJFi}(Bq_wZ0e~5*cG+3zD6Hxz5i)QZ)#w>X!@Y`^Vgr|NIQrK zu8Sh!SL|I=Ii9|eb@;aXVYs-21QS=TLp_AwZOI2jw24%Ra0*hHin1;rye7FjLM21t zbUif#iY9XbObC^c0V$7M%J5I`)5r{uY6IbN1Q%{<0Bz7oCMf2MFR}s=BOE9X8m@M=wzboV=A+rRfG=1r8^fn_~Xv_SQW9f9c~<->~DQ9 z8vR^dYG++#MS8XO7N4bV@iX&7j_O?$43_0Sqj{{l3imj9Xh2{ zlvsyW0vn`4vPV7R!qu6RRq^MnuwQ?OGy2F4@X9`=GW+4St43t$re3>gd4dLKWEt+Y z@%Ep23jo$R2{DqrU2dHw59$+-(gv?YD>75p9|5O#{=QZNLkmet{VSjmc@P^ln5sx# zk$J*qnuJi(L<0W>(BXTufA z8E098dGJqH;8q+bJar2VcXpFU?q~z188bN%c~He(+5Oh4D(*B+stjL1G`tX$Do%k4 zEo}^w_#?TE$Y;0Y8Y(RB|9lxK=4kiEjk)IDDW-C3eV4)%$~{8WQnU@(rfr>_MG?z6 zy3SKGuw#-VW*1JwLsd89+>Y8?_(Y%op}9kY8C-~yVk+mk1RW{&@Boi6t@2!p8`ej@ zr|xh0^q!TxBtFhnXSl0&)+jGx@LW|)DV&>hIh+1%-M(zij4pg_r;`YrfSXbKL$T%H zh&WHz-&9LZOFIg?F%G^jDTA7F$R<&h(6Dugw4o&&uS>>@y7OT}5itFb(p@pXQ)P;X z2=xhJs=_=}serqaiEyU^FrjQ3aZ^eD=eK@zK>7{3#+E~?nd(SB#BuBQc$aCSq_lTjYT#s}ei|*jOvm!+|CPFeFiO(ELKPn-c;KGKs@jm@Nm*d5=*KNu&C<;3z z)v=E3vAez!sJ?Q%-w_BltB>%~Tp9T2L@c(BV7gs91zoE$>W>cQmUTgD^_OB2a*N1N zO#(DON(a(n$1oYG0MNE13$u9k5noq2exy!rG9E;yZ$T7Sm!)_(51cpw`j54P;;xbr zOCPc9IJTNNpOa~=sp1~EtqL{f0+yy63q{UPoi!MX`)<8fS+&@4T5;0MdtTMpi$lV@ zhMb8lmjC9cMfn+iU;2B=m=#8|`u^52`*g8qIk^+p(~|ZSdW@xADd|2XseNQ;B)0VR zg`e=uiuu3|aet-P+^#=Adhq{R3Q}`F@=>BixDTs$%4UsDUd^1v*>}%;&RIyXpk++e zTzn?w&V^Y460ng9D4LrAl|};Sk|l_|soLeFTo@@%1**78jI>y%V+4sW*u_vq>~3qr zS+Rosju7#u<-q)I+DHFQ^8Qxs(>kp!y-jtyRKR7$kld_3wW0ar%E9f-sMCHIuRCUu zGM28u!U-`D3-CyrC#mOHJu8pgF6tomG`4K!D`C7B<++V$h_JAXZF!uS!$x8{%3+C% zEu%IjbTyOoYM38~(YD^>!vm!U82Xbn@>$I6U%B`Bwtn+!y~G`pf`;As*Yj#rT0cc8 zKR*S$sAi0?8H&42hKIBhYZ4 z3C68iMmT_wodAW>BOe-!M#v1Hz+x@+TwOAgvfwU0nt|nTIW{Pp#rSoN={s@Lhp!b8 zlTDU%3z-4E zcNOBnJ96-#d3Fp?D@;t=@tkMIu|&+0)A!HAgu#4)y{R-7YikK^D4PH?jvgMdfRM6+cj!kt{~IX5vDp@;YA+JW_SN*d9##;{m8q((ctz~fpUoCw~I}?(>kO%IeLXWjnJ~B^+uyA%cV9k?x zuv$Iz>e=d&0Z#*1?s zsU7|NdiufXEIE(I)%BkicFDNN>$WlExEhXabT|b_8NM4j0m{W^$g=3MJeU_3c7hJ` zWr+k%6r{T6vQIH1Sq`E_2sDc!;scoH8jF4+sVyS?M`s4nVpB&8%Vdv9tpPNUGva;DuvWhzG?531o3c%L>_Fin;y|Xx2J$!y( z>Fd+c13pVrxB9u33ao^#A=xK783#UQ#o5z|G~8G2JxSK-eXRhzQ36jyJhgS^Z=Skg?+T4mm!LdM~rMM$B$ zJd$`=PQE%8E<=F@37FyWFq(_|tt6(;JkymAGt0~Ly!0lVzQc$l*(=DZ-)D+>(3r)9 z(c_;3M*3_xdN+srjXo;gytJgqH_b`-n9YvxI)a3CN9+p@b)90gaa@kigXWS8M^`*h zw`HAb_AEZLo&EaQuf_@1dGnB(9@5a5X*63j&9XHRb8hE}5(`gcQO9k1*L>PeZX;blYB@um#q{%G zHdU1dikDJz;GRC5NWp&3(sbAO3?!SOYd5IKaB5;P2|*`!Nt<^zIo+ZXX1)hc#ynPN zdiZ&d@VGgi2NVL|3tpSTLi_F^LMld&+O$Vh-Pxf9cN|=qL%(`yWN_^DK`Aj~>M!e< zy`#7IVv;ojGG=O@LbUf*w3u1j8ElP(y|!(q)SI8W29)N4(ZWyzB~s98mX%K?PCcgz z1GcWJ$K8^RfK#N`lVHl;9H#e#SfKVB??_nttBAk|L?A~bFbnQg&fGr{5l9!2sK@9V zVNf?^)QpV5kMG5kDpDhiYWAR)oU}AgRZ!tQI$eP~dfZzCMfK2jgX@Q4^NsWyXKsBG zeZGXeW_jZ9r>p_Y+Qp(kQn2gp7N_n|yL4gO89m%4y8cguwz>7-pdc51x6oRbF9@Rlq;aaVZ6^Ca6H-5K!*R61TDm;MzUPV{UaVqQvi@}=qd3-$;4 zFppkIw@XZy8iUEvi(tfFbM$N9c)tS9NAZ*QVjt8k-zmJ9_-b}WWzjU}&G&sDLlmo; zQQhmuP&mKfdYyEf_D73Y^`e>(-l*h#cELODIoQP7 zw7weNAo%jiSlqAoR?iExA3yqT`Pfs=CVk8@_10<{rZs2q6f^&|t2zI$@6$e?6L3Dg zOhNrF!N2{1s81Fw>g%`*pBLxj>BACn@d?GL-e+C2-L_@^VT(Qc5wHs<7L2=hdwYic z#pq(g$lZf5Z+=BsSo`VJ!n?xAGM}0cv92HPpX6RonU(ZKRq7ibN^X9(5PJR#vNqz? zEmL%N7e;5rq2tFFb4ZaeY4ztF*eKcVCv(lG+}Wb9nyxwYPc7Cuahg7O{Bzu@(6ytp zR6n71Kl?bat*CQip6QLuEu3Wr@b||OGQ6A7zQm9B{35&S-5tKQ_uMyVlFgMzbz>3D zT{dB{|GNCAJvu8kTGm;o^tXQC{ST9U%hk>XS9~@?ZayZ8vOZSC$cJXHuTC-=%e?X? zKeTFveP{x7EO$yR;=SrS#-3;xV&24jHEX1%|BGf`XUe@kl=te`DbxEO8PpsV?A|9u ztOTmtP7A$jcY2x$7>4bBCfg9WeTO5f&R;@{zaT0xV4eici4?dC751lhP(PA>@^p`4 zbk9)ZM~DCPc2BW*a$z*rMX#(`P4hy6)#Ba1rNhPQMD41MP%*9*Sq$x*S-0c&6kbN- z;=MU98a2<~{N8=}a`cNMtg7A@(iY+tUxf8BYnQ%6Yd-v&W0@-mWFl%^rimD8W`m79 zcHqLG(@neI7v@I#Py3eV4aZ}iNZ115uppjcLw(N2B&HurtD_f!Kfkd*muBDrf$zdhaW8&IJL{$O^3TGv>P7@5M(&i^+%+JY~ zUe+*UO6V3y>sN@`+}>qz)!MMmRioKRsZCkGUDl#s&b~*%@1eqxyF{N#J@+sBF~+RNlLt!k`a07 zY9#A=WFb4Dq_i+EpUF&PWQWD(Swy57CM9UGqLu6DN&aGV5i|7EB6UpzwOyjLz3CdKuPYvJ zm9ibgSOHFfYQ)hR_0C!+ye2g=-QaS!tSKF77ny-%rzs}4& zUwr*$;nnvKYoGu6^8KIfe>b;(yxJB_|5&^KRZ#cseb0}%JAaRs|J9QA_3q`ZN%~(a zY4e+BUacQrUUlWa-?O}Au=Jkz{G<5Hn&`@!=*I=sFLRPxQ-rO1Vp|RP@1<&6rJ5fb zY(6(Q2!{N&IA^xliJ$W0Hj)EACOL01jn)&?XA|X?nBw13MgNXb{uCkp-H*8GA^Fu_ z>CGOwPbSh|bY#9Ls(zH&y}3*GoeF7AZr3A)cW>WrY;KB0{zmQq|DhCJIPAeRq=c^j z1gCO1lc45S;nG$$nk#D(^?IVMdR*up$x(D|ubC{?KGx_z*?wobjC69U!nLFJ@eRv! z8?Prj>Ym;vr=gYHI_qbuU5a%BraBwu>L}H2H{H4#pEvn*M7^2nYI=E>I-H|)pu2gY zBVw*GV7j|yv4^%Yb@M<^>zjM=-!|S%_uPH=kPgKtyZ3UIhO;E}0w49Zt&FqO4%~9@ zYkxmoZgT4FqrQ%{r)-B@<%9j5ALlB6{d73^s(dqjEKBbAwzJIU%uww6>z63=azU6= zpZg80=Wkr*io$Ii^tWlt>?;e0qDk}n-lEPP$^2p^tGGF}vP0cpf72%7uR;GN?_KV{ zCUIh)1G~OONNTqUn9{J z*N%&z-GD(T&Xll}4)Kgo2^)R(6~23nLa>915O_jq6IM`=z6y)43LRVh8jvf-6LzwL z*o5jt_;Yb$k&Wh$SLC}1b-6|o!gz`+PU58H#Ldydw}~&!KB|{(N|^-1#M5P004Raw ztO!V})t%-Njt%bS%Bs1a9+Py?ET`t6WQx*v8r~Y5MOJ5|dAjlIMZ_G17Dma6N@w}L z*D6?8Unk^|-b1eVwBg-kKdk=fZ(}TpD_Oio+PUQlz7I^WHOQEUc^f=(HlwS;3%M{E^+XNF-1^MG~gIxYfVw7N6E_<9t1!$KgN@ z^gk@eOdE1XiZXIVISXM>{i&%toFVyFf88BK_ls4&lsd&pOp#VwB()9&WA%p9(OA8a zfgmGTBu6~6bJm`E_KK0UV66XPv;6^BxFuOA*0*H4z_L4M-E=?K-fQh|d1lm5BTgVk zLgQFi?0}er33k|dJdyJd;@$aujw4;HOxoWg-uC><5af|Aci`UNFPb{-?O>8TyZuUv z2ZY7+r+W;@Kz0chvs=PZ0Dxy@8ZPb>LbfZA@|@&pH$4d+gRL52OE8CJbE>}FGvB{s z+0XcId0MaO-&oV<`}gBc-Tw9D$La%E!IK;753gqYJ2%Rek7@KPt~g)MzpALK|N6p} zOvT1$!oUtZAGA}=a-oeYM%3*=C_&U!=}t*HSv6(2y;KL64|#~J&SUA;x2{Bx zfoa`1?V<^2n%1qU$D3n@|M7(!p<8ctt@yNFYs4=%{nq*0hA9lRR}fzIx>`olzu&E_ zTE0*zs$vg~&v8z4J~_ooyZxB=KDRkxGoWGJuZMQQ)|R(~zhLR8`iT#`dkl)6vwVyC zi|o+x#tstCqW>islj+#Z!S7t4I4MRH?y?LqOp3CE%FohtxNX5w7bxjUUP1Oq?Pajh z$4OV2p5d7%8nA+?=zojAcs%>-vWlelpWiaM$9}6yMI=}EMr5>F6uEi)m+Le_>S^@( z-f*b(r{cOxxHamKvv>WuH!~?)oW-t9nF8C}hC^ZZzTMHwZKlBVzfdwIZha=;IccJw z>E@mzyo`F=B}}3BunmQauNrXp`wK6}vKfMJ>K)cwW}!`MhVU0DOhx57B--|fR1S-a z@+@>ZYJ5&A&^AodyAo~7S-$k$hN*X`aQF2)TbCQNV7pS5(0`be%RuKzJ)Ugto&ktd zJ&mdN*6Qh*e6&>Ej$rgXC8qPwpBb4}*XyUgkJh{-6cL9vrst+c$kn5pX%eSi>OR?j zFf2?=bWK7-SuzHBL=z$k<)q;XE+RTK?iM%NzWtgXKGjjmDs4c9>D61!y<1{rG_qCD zbuOca-d0vwjY3Ve5I~YNH-s=V{m2xm#!dyfcq^Id-(SF$Gi1JnjFS>o29}p5PmCE2nb& z94;-S6(}>*mKlrKSdwb4cTlCT(`|%8>I9digMZPVS*;G%#F1~|PWsH2OtETi{(ghG zEaPtWTC!Z@^Ntek?De??__x|lX6;J8?~%&Jp_qmUrV@4Q**;s(h8D6gR)B_HG4>Ya zOhoCv9Y=UrLC#2tzd=Bh}i@S(eY2r~CK&PZ1H{jLFdPKrqRQ> z0g)%MJNn5W`OHS~^n)yc@>kb9@Ay7W9j&gZ`B%>Tz>sLl>*>KSH*}%PGDW7j%--c| z=&07^hLKB7x{{162co?glV6X<#ULe@yYUI@s|VMJN3F{R_ym_OlDZ4`#SiV7-M&0(J9)~U@BM{>ofeE7Y z^4O~@322X!g=zkiuR5)^(ffQZ-mhoJ>U~c@AM3Th{a*3hzz;6skr?fX$Emtx@6vGZ z@5Q1j?n(jDIhk?6v6~-L=F@bxS?8PAI&LOuvkjYV!jArZ{9J3ViILzJ z;5uAI#x2C9e;esqwmBBZ-? zDPh5^yxe)bq-FX7nsKT~ZD=)vkYaY?!QAemo8njbebu}BFR3!jja>?-v)1<-{&HAdurD|FRtzA zg|2y9ZTgH|nD3eNpYED_{q4feeb-*2n+SLC>r);2G|1_1{P$z0b}6T~68V z3Txnot(2g@dLo5&Xu2gxCMB|RKax&EGN`cy2;>E7Z1Fha92FU!7Ic9Y%Oo(EB&3#i z68nW~>j&Sxq4o_Q67623CJ+)Et|pm|owU8+@w^1Fw+_+9J2$EkGV5#-`Xc!{BuiMSc>XgVLkpqx)(otdjUpCmv|G7tOy6Md=fpg{c6haZ=d2uN?~O9!r= z_q-bJw2rvDdCJv{GDrE-^@q6bdtihxnq&3|qx) z{2hvPJYSufailcbu@`ZP7Md(TgiRbC=RR=782kU)ixli}U6KSCd+@Jd|n?t^fG&YEM%AE0KQq-S#Cq53%Ku{`b0d zEfBG0NfYLg3<`8&GSFomVL!iL9wuD*$0vYGK%V^P>VGQ*nIz;zS7d2-RvHPJr;W^+ zh?H^7j$>s>TBVBqjF*jI?2y-6T-*aW>)*!v>j3?+~#MNELN_turX> zx&5@{SgVs-VaYti{Va4155c7b4092K0(32at@r^XF5Jq~zAd4P{PyuyIuZOc8M&R{ zn?^{y)R&bCBsBUUn0((%qVEo!y%+i_EBaMgJhw>aA77jEg{@b!>!lNe<}Tgwy)K-U zy@g|a;rS`#8rW!k&V6~0 zdn=x3F&}GJ6#}(fc2fZn(`uJr&r|et)92V@Q@-nPN$7S0HezyLI~jF25#7#1JRqZ! z1vl@gX4Uc#`7Bo1&w{c$Ss)rk`xlu(LW;5N6`f+w>auB5WeNRRIw8p43CMH2TX^0r zwg~c!ZlM9vz4Zq}{bg$YI46zh*{GA}pIsdI0bKxKt9uX=*Yft~R5AFO>2$QS74t}Z zjl}|@gcRMt+sXUp5q(k7w@drVs04go3*K@)Ktk5cdgJ z&mGYpCS%6wS5Ic1u*pFWa4{Xcs{@4E{We&ZprlrC^OQ4kK^Iv7pi+J!(TteZi*%_|}zzpY`I+_oYfqEiPs;d=Y__0an{9gS8u3ORkX1m+>Drm)_y z8X_}|Q(Q|%sVrs`Qfnl9LMO8-oZ>5rxEPuivWVV124FAoYQS?c6qEdw@~#>Zwta_! z-VQ|{jzU+HQFDIeJA%O9o#$I=9mNDxI;H#6uWo@nsubQ+51?Kob(K)ibza2xJ)afZSwh3M!FMUzQGpCedo9C*ta&YU;?yTc^;eJVe#z zVC7=}{Zptf7w;9)QQdN=Vou*tZBz{z^PdUQPX|*?$!OllQ`XOWy?#%k{yYQ7d*ph% zn2M^VHl~tMvjl~DK5}Xi(?P?!{gTFL=y^C`>v@tQ;ms53g9^9Rs@ z`ocv=6%kRTBvfebLl(cgkPn1zB5R4LZ#LKxGWr^TDyE=zRP~Wx+`4Jj6Q?)J;x~W` zky-yP)V6CSanx_aQS1uM#BBD#G(mq7zoWyqrutM(J$sNz?7wf*tc)GHzlbO#VhZT! z5>j&^rK5<1syTpaATT6&YK<}-Fz0Q?R@~-PU*7gpB^Tm|8g2z^1q+Y#k{n^){xL#c1sNfRYOA+(NN_A zWVQhL<2SMlhWZDKD$_u90f!S$qpp#rzYdI@!j2bGy4NwNFWE>uH><3n478q!zgA~t znVNW`ZYwG>FAMo|`|>3kx`g%U_q~VrkME!}sJE_CXIl=S8VAM-iBD@O=u3h-SE(IU zxnmu~Dn>?4gsX^<3nx>&m+rj;>F)hU{&Nk@hzXo^* z^v}n3Z5d-bh@Gtz?0ph?l7#MHV{3RAQ+I3`7jvKRpoWaDqN2)Ks50`?)49kL|M48c zcm@fT$3hm9fJ`nj$RBl^ges=-PT8VTuqa~#6wQ|NqXL;`GlL`E9+9}6kPw?NSyppD z>r42pcK#XN#d~WC&n@(B+~Fc0kdckA`%n4LUgFQ2Cv~uh9c{#gyY3?mN=Tu5ZZAZ z_?dmLsivA1nO5zlRi$#Krc_#{q)j~2o;K5hB%G;frjizg5T*r5G7*Y!rqU)%P8U-obYhPMth*+wjABCb3QqK`SR*<4q2V$KNmX zoMMu4?mVj$KU>~PDCZE$m_3I$gc2UU6viuX2iJw#}EWJCR?C7orI$46ZVRa}CFOHCDraDq!{GsnA|Q~CgM z#(E;*$*X52WZzP9KFerJ@|`W~N&T|9@k8W0!=xow@+gxu0KZLmI9|`7oL~^4yM)u_ zgc1l}a0g$1Muus@7wNo1gI_Ew<)`!UtmK(Nz{dc3T>$b_QRk!^KLna5OO1H`55aBA5aEkfB=yh+|X+kwXocHe;gdZ?p zl13TCqu{O5I|P#e!g+x3cpI^S`Jm_W%VXm0roIb3+Xs(8&yF*0@tKe7Ao6|2$78&Q z31}daCFXzL+5^6aN-53Dtk` zityvQdpG9Si{md{IoH|s){IoK!X+H&T&NtzMLg_Hb$-0mdH*VhaQ5-*8&{s40RF3` zE`D$(U6YWX@SasI{+fIAx;2t`|1M!9^%~~mQfu>7jaM)5eqXOSKB(sW1gwUX3T{`9|G_wfpY` z4;&fsE-SHg`p~b$_b64?&6$M}wd^7WrPyEx)!=Tn{+owpi9zRr&ie-*F&H><&b!(= zJi{=V*(f>Uby&~v=JBIV;I(BWU};VxwugOvzI@3Vq*Q+fh*Ag+IY|fR~F69D7V_XFCFQ z24a=H!z$60JD9C(T9D-c+Qh%D5_9C4wTWr-CQn2;?E#x#R2jYu4_}aM|NZW|k7s&` zyRX9uHqF=gP{R>#*9R*G9n*JD8uWP?4G2!gW}CdZ`JqJV{*geTWBiE#w~o?#aeAg} zgS^+ATdMo!X^N%)EPlTBL|j#%$%({cETLxXv3Hmgf%SwqjX=o>?5SjOm7Nwxv%=KP z)0V#|^{_sXREcZ3npBzQJjFhBb}*~Qs@2@_%f*e%aJHF;a{6oq+lX)aue))_Wo2)- z%GoQ<5A2d?n|%nI9&K_XSyge!7PgiC4hYO9-$JBeWkb7p6~prF%O2&^Znbk}*8H5C zH#m*HrWX%*{7N!cU=hys4qJbjRc7UE^*ZvI z-#>6(C2qY*ripL0+o*D6Uk1Cv=Y{JRCAMjlpdw`?PtdH{_cTnI!>BMa@qYEu*I&`` z7uz<_m4u;LuJ?AX{9l7coJvq+9hT_(?_@D$jw>x2WKBk2~SWJt%L3FQ{jGdU5j(16|^0 z?QXw%<6f)tBb75AGn!W3w1$&6JuHuH)H^<1U|m>C_TQnX@!KR~xG~VS_VUQSC-d9w zn$r)T+y7Ye_WiAgU+mD=BD`mBMi-hzetFL- zoe-?_3yYpvO)DMavh@ur>K;Y9Ic8WF-y>p*C!qUzpRRJ(+(i;OYzs{>Ll=70pt6IL zZ`|>uevSRg$l8?HPhP8fgliVAcSk6rX@Bw_X1wb0IT${?=5*sod`s)?&FnnoQ3nk- zouHDS?}Feb!@`Tf9u$k+Bd0%iKL1wSddB(;G5CD3(66bsDIic^Go(bQ{nl%vQ%;!* zFyv|1GIG}=8)>!}^IA{7hchuTrsDYoR$qMtAN9#ph0;}Tq;RV{C3kuaW+wJG4MFG# z?f`3-wCPoB9*6J=j|J3 z3CNe5GG}K>-Z}9pBVo~w%T2=e!2OF{5FS7bldEJ_&Z+h)qbw`ugH?;ppI``YTwn%~7 zt@!|q@aP+%j2>{;s-0y&73>`@FSa%QuW~^_6lS*^7p+t>F-gJYS3PU?JhpBN{V4lc zQF8Y5iL;Vd*5DWA8t}W#IIn>j&~!K%v{ZRPH;R0Kb4;0htm207*mG&q4PT*!xp)E{ zoI3N=KP6xD4x@k}e+R_0&H8kEc{V%g7B@UJ)ts#njx0NIkuzkCHS1&Yww!Ac2VT+4 z_lt17lhD_92VBZpJVXKo+jA?zn~6?PVOYtGVBJf40zoLcCPehv-CYVgfh zB3pM~YkShWMp8>5fB3wsvo2(-eQ`r+;5)nH^`r6j`jaM6%WI$p&*SG=mAPHJG>7AK z%dBeqjvx(Fp0{Jy)bR<8yZ2lwGTUL7;rr_Hr-`hyoNso2FvTgn7>&+(_X^4JMx(=e zflnnz4~TF3^@N~m5)62CuYYx-*Xjr2b}wC+pidmM?0z)6xW>`;BPA_mLUTH?Z{6M2 zskGc~t#fL)bq<$zB#ES0|pdDDv8#*G&!tWx#@Us(!#?}pQey?D( zX#Z&u$(N#nuG&4+Jih3Cp>~QCG*M-*Sz{S$yR zO*D>a$=`x?TqZ;$Rpo2V8jH?*tQ<}&ch_FvZdB@IWo$m1Gd3fqOZ1Ms7ZWaPnQ}L- ze=(K!(0W=$L3LwNUv1GqMpgIN%U;Qn3#-0#9kqSzqvUIC6s=pWThARoF=C9KqAd!&F{zr{WR)3IPT# zQ{JID?RM#ui`iY6ItJdc+T_8~%d%H9Mp~9pZkycAmQ*&Z5!p3+^&v6ASCh*2jef5l zX;(a@qH<>4zw2s?IPm@y?XQCH4oTd9?E&G+9G>mZ3A7Ib6ANK?W_RwO5s zQE@z(G@UNuWqa<-#_i$ZvK_h%max0CaXZ60(zrNvs-0)QqdMIxBUZp+SdBK_vrJ*T z=;2C~y8R@2_htlk73*KTyZHHC5l}Bo<<_RHIM~hWi;}8^l;612MPay!QQHjKqS^dc zH&)?;u>Y%J@&q<5@|NSM+fL@qLuk>h+g_RT1<$9@JUxdLy@IGjp@;Rw(Qm?r+d|Ht z_C$v}c24pWyB{((usGqo;J}Ord?Is&@m|NmI#J#aMbr_6L8u@Uv3O1Df?MmKl(_tP zF5DT0OAM3SMs)nr_J3#- zF2Dr8mHW*8-?vk$z0|&KOobn87-~Eo8=N#DNkjJ!G_XFWOVh$U)#Qgx!zE>#KmUzo zy$Oztsip10B{*z(oKqE~vHB3nqx6sCZja#j*|s1XoZp9subfpQm!6(dE&3Lw;Y(vF zI}g?w48AGxiFWSI;Q3@{<9^6>D5(gVG4cR}lbfoo4vUg^iT1)T_BsUEBqDZ8pj}L4 zj@a{StY=bI0FNgM_t+Zm>$p0y11fQum|@9%*a-%>%yz7jphzuNaKqOraNocN^5k+i z*20;6unwDMejP5jv-y-X2<@3BxDy!Xsn!i%j`U1*X#MiXD-VOqP85ckoR5_`uRLy5 zjOXBXGRkWqQSgJtK^MDbwo8M7h}{~l&=da8eT~pN-dj|q2@Y6stT2<=Yvd=&;)Gm? z#AP#(dkaPS4#?dgUp*U#

`XFMjF_JEhSgh%7sp;L# zeb$1;sq^kEm)tpq!VScFR^Jv%W3a#Rnz0^dm9A}4NFMV16RdQn-|2o^9D6Ig>&fPC z!Vl&hA(dNo%&*I%X&>gP)2;yi-^sVl*nmdoEd|)C71-@O?5=ri^29xcufxb6>}s@E zvn?*2{vsn08*41uD1ABkamzhoNNAjJo3Ai|iP$=`jW=-7RmMhHUVY8T`EC=Mi#O>K$qP<>70|(>*I)WC)H{U*f zsVX9;T(rL&C$ER(h;g)P+!sHbHWRrQk6dT;IAvwk=Ir6OJF)`y;Bn3?E-lS5yD2zx z3y&n;qXb6(h`uO+DoPy|5Sp9M1ztZq+m`QQH>%k=NfHTJhe7*Zsg2z{%4em)XA;72ymn#Agk8ccXD41n#(LFLI?^RU7uY^^+Jibe z@l&=E?H}P>?A$5#U=~-H<$%iq^JY9mDJ`NLMxH*1+%Ll&2typ8Bh%E7dfc};4hehv zaR-*)t7gBowanKyMlyIaX&=Xpg)wXQm{26PRs_?J4+zZQv%g-?rHtT=fHLxQ@sjfz z>rZO+-+9?HPoogAzY(_||6w&1X+DR`0g(G)+<|`FJ~%Ij`g-LDKL?+8<%VdVM8qna z{&enzdzna&iBxC4#w3V74F#oTxg0zoOy-W4#|V>nt+y5iN0S`kg4j19xT;M!{Lh4+ zc3ZCq?pVH=JQ_3313C;tae7|3vIpFVomlH77ZQZZ)m zr&Wz$OyCZzRPO;o5&O##`}#$W&v51vkyawY^@>P?nzs+erJWYBZi<>8zOYbzvR91T zoyceM5SV`!^~5ul+cu?fL|MziJ=HKT(K(&Ye|G7`(Qku6|4QwicHl#C`W#&H^>NF~ z5lJO6RU4MdRpgn>uNsqk4e+5E%h+suJ`ta<`mb;YK3|vmxIyJzlWLeBRkVvL@~`>t z5?WMx&*!aCM63taz!RJDzp0n1(@M_FZCO|`d1n?+cq0^P;FZ@LFIV;MVN@fus`(n? zJ@hby2A98o0!J5%R3~t{KptaQWZI6?!e{@l7pFvX+{`S($hZ5J=>!DGK|#iKl$L-6qK$3a^+8zua!$HCnidUrrUbnf(1i~BE7 zeGwdsu5*XOwOsRfdsxl3`8J6Us0Z`UsRxW|1~mS}2K0OW+|`-R3)#I3w>NA&Zp*l# zt4Qpu(W)L)v}sN^ULLE2pMGSdm&Ir7k#`aUT8(^WKjP07gvPK)Q-;$33hCB)&BJfq zdq^6~f(26El|dIR^CL3oYMG~NuENKcw-Y|s-`T78@#(d7Jq6^PC7w7jaQ3uw&bR41 zsGn))Z}Z-F-O0y2+Sa-AHLs2FHt*HCY`Z&u|AebV%BKJmtu|ec4)$!bEnJFaw1#NgO)bT^hxGml<|l+a$s_HW>l16eap<@>iRJ|8|} z>3COD;rmo_+2i_+r9a`Qks<11M6QG zas+<1e3i0b&R+x7kj1tb)sWA_Y*{G(DebZISLYiF0dCq+Z09#6`QbJXQtJJkR?a%g z1#iYx>D|t<>?fshx%_K~*KHqoq7Yng@tVJ*wX4ar^Y{L1r8W-sG5*#MZ8OO!QN@l% zC*n?;Xr}Jan;}~dF`mp>-Tiy4M@8KnM$jWltUT$_ymVAngd9nr7&%eyPO+2kFm>I~ zOzkFuXqLMoE3&ps!JLuquCbhZyv+U6oB9CiHw~*E>YwxrirznmudUtyq;qa&l2jjW{AwKkTq*VAl7iCPY{El_ zhn??y9bUE%BZ#g;Go?{qXHl2S?frV|*ZHQNd*tw@p|W)ShkhFs=SL0or7Jd%ohyf= zwWm9n-IVnu5hsmH_n>PnU>djD9odA*;RXrcV< zOFycNGzHm|xdb0GWGl^-Fp&=bMX8Dl?FKCLoITqz&7RrRE-U%%JMI_f@@sZ;<$5+g zUBUK2RlR~uFM}MQRKhOrqUNW@pp|qf<9_SbMHx46^yZeT9jC&6Jazt1lPR#dtY5j< z-TJ_FU-i|$`d?Di^sfml0(cS_Lu8gi1Wl-duNJ1QD5OWvGgf-(++}e$d7X?Yq&O|i zbQ4W^(ym<_&`}=L^*kk8Ew|V&-LAg{>rAOZGxcTUKeI89_c01$?a0d=!@HdS)GH@b zu*TnkVp6VQo*L9`=+c4n;{}k0`l-VBHG_#;TA- zh?V52_Jb%;!Y7<$*nS`325tblD0gGZ|GTqtLBBNDz;yv(M*njtd1*%<38|uZcam+& zhNMmtfq8lo6oy^3@i}Mg<`y-Uj%A|(Hr-fxbq+2rjjx(nwN?UZc5%>qBvQ&Y zHo^sNE!8rA5>m8xBktPh+S=grt6sx%F7bI9d$Vj-S;bjbzkX;nmj?km+F>|s-YkK5AdrY2cL8PCc%R$K%zjf+&_ zO`+^0EcyLJD)!6J28*n*98Nz2Y6@QE_)dSzd!++C(3UMuT&2ZpH@6kc8nMJ1U6!Yi zEjMJ1uJcFd`t8+1zo1f<0PoEozKm5g+8$ZmvvK>W+S1T-2#Q1dsKXEyOM@Hn4(%*A z(={Rc=k>R&ES3|U=QeBXk;v;vFNyC3jc(aYeZs38>`sSzCLGk>)lfvY+Wkdn<0V7V z#IVK?S7_bLr$qDIG>nG%3RO{L4KY%+36#T*5r<kgg=DbuzgLi2BAe?t0U;ZQh@7!!|wuD3}2l}{Ho)=NF*Qhc5 znu43(Akn&4{Ih@C>sPtgeQ@e@6X*`<6W)QMt$9yMvcT$11KhfT7)sa+^o-h$6)}W1 zqE6dZ>r#>mQQBQF*1EiwtiA|fyX0u);3y*VZkKwqB;PEU)fY6JuG$V2Xaw`I>pA{J zH%>m2$3T%C_yn>Hp$Ib2BqoRrk^q!u2yF$P)W;lu^Yz$IS1U+r@g`7^yQqJwqWR4$ zw!yo-i~6KbOgB;qM?jXv==@zZ;5Dm@-rLE=|7c&GJ84t)H6*w47uC&a!n#aLuEkZW zE>W70V3{?ujoW(qsD)yMi+|upU%8?Hne?=@tv=jx-pFA-N1&^XSaoT=$mR&OB(oFK zwLR~8^R)y1(PI%5)kdgggeSCZ&{crr-8Ez!tbKJY#pd%0jJd(UFgeoan=DB&`HOTTkFNyvi>t zY43AszV*WSyztvfN$!Df)vH$um%j|Yo56l<=bLQfA@?rE?1l3hFXOz%o~A)3MsYfTL;pQ>7igH&VJHozZe{ zNBnwcCCJhKq%lul%juRxXY};8*@zr51}&F9eb8rx0@Ipsl=V1SAbS!O%e* z#KOgbq*#EM$dU`LQxC)BDjlWbSFZTdzgeN5TX9cIYGjMg`@#pDhhZw6PwWgOGy<1k z(1j{><*{9$Bc#|z^E-z1U21(0C*!IA)E4kRO5N#MBc%EKgLK4TBXo2YP++jA<*$#* z_ro&yid24Zc6TTzXnk8gSpxqVfW~Bi)50cebN=y#v#HCgjhuX~7Thcv5EG{nn!$i( z146q|s#P_OY(Z!@v*aJGwwLramWBXvwScdZ%~yr1ukB)4M(|bH{E{tFFdZSE=)V4? zr=mB1O@`_cM`O^7V8_9qmPLIUvJ=PVp^5Tk>4B2#AD~u%VFYb7?9&=vLFl-L}x?JCs=mzE8x|mtZx$l zF$=)uf`}Su6wPXsY;>GMQ6&(uA0pED#5RD0XU)IsX20luIEHdv+UNoxC=>3~Avvtj z9kGZ~VnB*DGyB*SrDf0+2EE^OQ&&RB6CxiBBIzaQLY6vq7Lg}K_-rU^BHTqAp^%H% zKt>o|hab@llqK%Y_-X1YmU0hz*RXq>^J^d4r0WoP@C08`253p7^2_HGte3{!#yS6X z2O#6#;UoOvXSFQtYCVaSp=py8d1KnNWm>CTYIaNhB?}!1&>i@yzKA@3K3z8bGF7Tj zey(IyBI_L({|hFYg8&%>m~ti)tR4=~SJ(hhD^1lOR{U9mPfV$YN)B`DrLFy7r9q6Xc zg7ODPnIUy*Ly@#={YTvIb;1;y^mKye7OW!R4?`I90E}Y+9&75@8rfUX; z$VuAJ^ZSU+cM%7=q(Qy%v0$pbe8IGdwdRIY&OxUave01=rd>+cPF$PDdihH)G)Sr% z##i9+^S-LA(B=V+6zOdx5RgM5X>uey^p7V*2!jwjh#&x{^35-Wu;Kw2R|P08gOo;y z*bMLLhn~pWXc}QsBk*%sK1Kx89^h#|_~YeP&wfB@$lX;8elCJY6DS0G$J@C0*hc|9 z1Hfv{2A7iH#)W*MHb`3NcA11Md%WiwL3zZ%OTb79Uttzf)UKt<&QP*KTsv1gPoTs) zeE1EZL`RdTeCPJF)K18$-(9XIdD{vopb;vzECpwlibK9*HEO4A{>PN2^J?yEO5ZmY zPiqXnH94bq>7?Ff1@UtW?xh=b|32-~^x|rj^EKoy`D`g|Sng5g^L18?Rka)A_lxPy zQpGV-f>17*1%X^S*ca&Y0udm9=Ryc$NPY}-YKK0Hs90A(#8 zr5wc4P7sId%dP^e2S(n$G**BCs(8>v0;mrHgic_CHpnUjNMrfLAuzoarZfZYu|^3< z>AhQxWXOjS45*0n8){*I2IF&eHzXox&1C6wcZEcRax?5Q2Hg4zD6*vkFCis|%_hW(1dt11mq_yrA*|#{bZLet_|M1U5!A6cV(!cx1dHGWQK)mI z;W{KO^yDZ^m%xg-XvKL*jUE3#GJ>=Ko zqcsaEmt2LN={D7^=LYOr1|Lx!tZPXBK zfL@)tqS1d@CB;xac7(fc1s{Q3LTcAfW+PX8;7> zPxx3qRvSV%r#GObdOjN|ONvA>II9PK#;zrm1H=Z1tWDX_EXRU>8SR1blPIdQ4^_US zaK0PQfT=w&VK{&|4C#N(rTQ@hxB4c`%c@~Kt6 zDehd#d{?72*8z=~T_^qx3LX(|1Kmm$SJczF8AOt3UNc zg!D`aLW7O?CqSw&57UDAuXk`u(t+#PG(1^xDhc0-R~%ovcM=iQA%HaO zP7!b)?=7ZP1Eg7$jw(ne>yl$3OfEni+CgSO-zEXqNP%)^pdvIVf1%(3xid}#4nsx< zaV`>=Ab~rDkWza-X#)CKbT#Ojl)eC}fKnA_gtBwDlPxMOw>Mz>^@0IUE4(|P%y?FM zIs9MiOU0=s<46>0tEPj)+CId#l^9sl0ioTF(9SBsbiUW@%U$m1R~V3KwxYUCjb%h6=s%PlmW%8fss6^!$JPc8K^ytg^X;8_8Bb6NhdA_5+bXf8LAXvN9fRdVH?N4U|LuN=mwBw8nAu!zl%bqP```uUz&lP?3XtJ`YnE0EL< zDLQOaV17_A;43bI%CoRzbG~CX;k<$a|M5vCHQ$Pgvcl(U*6^D=C1{jZxDDgd$?NDR z7bZ?hS2PRjG&=bjV|hgvQc-LW$2?bbTdLKNYJNki?uAe*L=YnQ*aI@Kh)a<>2Weni z9)L;#rlO%j`xs;je>Mq@i{Yp4ok3KC?iNJ(vpvc?kJpBfjh7TkKtlDkRVIFvTqrf_ zo$KswqWIIX(lhs8?WUA~uFWvgU=IHW*kC&jwg;$AfI|R_$X-jDuwQ>rnzLyR&jZ|A z&nt5Hv_$^jBy?ORg7OC_83kwtM$w%vG&G4IRNgDKa%dKUX@A6k|u4FI<1EA%`n;6&)pzP zQIM`Gf~WVk{AvJIp84fmP>W;H0DVPCfLa5n9*a;M2KLsxQTPL&TgZ2vopaIFdHhTS zwu8B^LGmzNZ4siE|EFn%P?C5UUj1+EY-P&Ot(0ITs}#NGFEg(6ea-*(tKh-c+&ojs zOC;DSy^d9=S;u?P7Wf3{5=103?xxSg4prOvpD*8Gvr-^)W6Yz5A_^XHoOISm5Z^|dYgEFfE3`0mDYsyhXv~2$5PCo;YR5j z`R-NkpZC33$bw_$KYu)>2I@Z`9soVZ@Ljr|rNyop^TV~QLqV(JoMQn!cRqp|*|rSS zyVlX! z1_N~l8x;(_N6+mWZ`QaL|G)Azp?7QcX1;w~yYaZ|>70xh>289`jYHK|(f3OT>nrED zH4*94+PRrj|D5k{XW+n0?BSCU$mef!GL!vQv;@gRi3}v+zkTlY_T-u_Lh<>DC}L?- zVO{YN->$A=GbUaP9kmaGNs7+$Ie?18GJ|j7?=V$N^^&;>l&>Y}(QmW=gW`_!!Ng;RGzXO~xW=r%}60 ztV6=20)i#T7bqz+VYE^hUe7~IJgke$4O(;~nr1M&AjKLB}uOz+xn_~=bhivV7=HDpUuttG0u&tvmb(DDAxVU zZpGM(**v1j%499k99m`oM_rjyd<7SnfhN03c94|4=JVE=TPG?BP+=v~#?|roXp_}c z4uGZy_wx^#CxSlmE?wA7K=Ut8Uai#5U=`@>E97HLwp8nq4lH?3<*kAlh@#a)T$E@H z+W|!4X%12>X3meBZzV2gk(h0gTAZ4%INDk(Z&})9W((5`HLP3mhF3#esc4m&TJ)KH z);iGzW)m8D1!`%qE?Ijp+pTELZcbgWVTpt2L_&$p`Ee;>ZRB|L(j`NBR2~8A9G!=_ z!N^}R3XO5ee+33mZ09%69E(ibVV@;O?Ae#vja9}REhn!dlyNw2x5&`aF$=QqHZ8 z5}5^wqmq@4Qy*|NN(Q4*79kTClK$&!`X8xvXFrQ*J0wF{(jh=)7)fMH02GaZim_&4 zZK;ich$(c8IFFLWG~Tm|kG7M%P-}rOItvWE^CF)b44P;z%Wxa$NJ=afttkO@Y=*l? zM-;g+kc?w~8fkle+XxOm)wJ9ku=kl=|xWWI6=c00fTAlCx8>tepqVAX+ zM;0ulL~w)}!-t9f#`){|csDb(rP>E={8y}N=z&FpgY=H<5bccC_WK1J51qL7STdWB zeRL6_aL#O1%MksRP45Mlu_O8K$I36K-f5*Im#@-HiW1s8u*go;T`D@X{#V{nf?(JU zH>V1rs^l^;Z~&<={QvnO#8w$VxWV*QF9J#9?jZ3;dc73Q$2b-G5E7xhg%Pft`uO2~ z+YS9tpE!((gf&neWUSExdYPO=xE_EJHqE+ZCs>No8%C%YFpz38h|v5TiHUrQofCAa z_cMfR6J;bPUZ`pt4>`)MC8@ta?3nC8t>Q*uL-AcZ3MA+DFSz5smg6Yxj57Ti`CF{9 zkW$6y*JktAc{4?qRtoETiY$+JJiIu6ZM>eeEm-MLgzrqwv{+~>sAzcHrF!7Z_p*__ z&u*Wn%-IhVZ{u z8dfx;ab6ICBgxmg%)ncV$MC)!qz0#m6xv^{7{nMk*HqcJ2(ZLJAk9D_6AnEMl}BuxO2muGn@6Ly3&4(QK!$fAY@q za!QoIR)#3pn*HL!2(a3gp68s)LD3VNFz)@ZdNv1TGJL%KuA|7gX38|y_W0xdD}9-@ zE7yA$n3n1f{)?u+i=jrAKWq4X(Zf>hPU6v57s4@)JKNO00)!r%UQ(jFg>qe=Vd8A0 z6f;fB;#m?t0u@?LFqX)JF!*H@Y66y8FLth_hm+QNmgG~QJk2Fw^R5>Y_%IO3C>NVa z+K}p53?!Ncq8P?}tS=RyOaK_8FbJ80mMH$YiQRV}Je9F1u;wt38q9p0e3GkBB}3~n zp?nnpi7)dYX|qA(RUW3IrW$+B;-hK~oWJ}Lig97aQJaRlbmsL}gK!shyO^)lQ;&(f zgCHg@7OaV>B?LlU%13yDgvNS@`++TIqh7IN=BIDB8(*|+&tDCTx;hPcI_0&8Yd5F09^d52V<3a zfECS`xvy&4 z9&XtK5XrXDjp`7RPT1gw`PL8PWm9=)A|lt?7k2TEN(2dTx5FbY)@Hj-=0_EUVPwU) zW!@Jdv2bkocY4-{N9fWz>dS^#*E{ykGN>zdApnvp2Ir<{(9fUR>ZWn?RnCCKDlSW{ z;V#nSUU|}Xq8LpVqpbx98U%pc`<>j1kg`iYP;7G_5CnT3;C4d{OcscVhW6iLm_S_2 z4H>uL9m)+tEgPa?pfE*@3Q57L7`dvb=&xNa_8T{LZwY>vh)tSi~^z4T%;y< z>m&WlNwHeZ3PX3ao{|zp0H{DMclUXQTLVD2YiUSlHX*tFSO86gfxBD;TTHT-soez8 zS3%UMKgtcm+CW6S z5+aR@wFHqo2F^#;rw1Id7JqYv<-bE}g0uTSG23CZ6Iq?bNNxvzw1A}GLnN1y2?2y% zxgzlA4#=m`3~j%ihfr^fRS+V z2g)df3?@d1lShQ5a=!b9rTV{`AC+E%6jLRnoYAdQrzVr#j=exwsphgy0w3h7`NBcM zN&xW;gi;;=?8OK&XzBu^(cB{n;;+5{8M#x#9r!_&0cuoykkISL)LBpQzaewc#)c?Y z@V*}19L?_}L(9494j|$#L(6O}K;x391qe$pB@9LxKnN!Y0YfNf8L9_|s8NdY zk!`bvHEiS^#)>4{OK8s_Vs!iK!qox9E!hf@waxoq;IJHFnopeXZzQ;odNT~O@Ceclt!+MDB~2W->vYZ z&MAXxt{-)crU^&Hlp~{rlQ4li%#wjC+k>V7UkIT9pyq=B2fz>pP(F;4J|Kx{@;%5L z6~x76i{lnbF+E)Lvb5#u`TYt;uAvL}eHe)N5p0GG9Zf-xTA;W{G6#0WZ~{XI`VA9e<63iQ1X(9D;NtOnI5GZScA3z{JXR}$G9{z=! zj;9zs%fk3FFu8D-+#e?I9A&#%XTTaE3K}P+|1EPI2W*{ykKqiZTc!-Bo&2oP&q}Xt zv(ke8&b4KwDJvL>b*JIErEW^k6Urp~`vrqg4RM}cqnv^Cs)J4-85MLU0%ichjX-H1 zpqFXBXXPWw7w);i^>llXe*p3cVBkFEg(@-5R=lyjhd63!c#Me-5~JO~#W@2sQOpeg z2;jv4L?Y8ccV#%60U>-1kVfB7PVfNC4T))9eb5bME7rUZkl53t9tPP}?%vx;>IGh0 z1%6!R+Crak;ZQ_CB1Q34=gs}%r<;rDJHiVvL-&cmv zY#Dd4)r|tn8-wJ&xi4%m2_>sshy&u;ugiD6@_~_Zwt~Vr5*ymfmXX*<^j*lv8YF{V zr1LUl7eMY2|Hy*n(d)7VnBo~=e(L6DfL2Xnoiq?#EXH$t@Un!}L2#qNOrEbL;Zf9< zBYcM=#$2mVN9^vb-b>-*w5WTRobG%!)U{vJ`o!pqeyJ&>l&QkA2sZ}FVku;E56bxH%HGjZd7&v{Ed)4=Q9s_GEg5JZn0-}Dq4!}78U_!X7wnIV=q!Gg) z?G|INR&7h;Iv754D4xl%S(mv^{qV_aYL5UTl^fv(6w#`~SbyM|LdmV~OO9jZV{GmqcaS&H!BxT0dGm9iL7f8`VJ6u9xVPumM zn=O8M3kcu0BJ^y6iEMxbLjC7c++w}2jWc|cWUD*4C|{7A1H~9&OpIc&IUpuitiuGi zd&@`%WcE`y^8U5NdFsvss8x>;MaAF#`G=kvGx7Hko`QVnm;A|ZFSQps-IR8_#r z$9MB}$Y(PnI2A<4b1^*9=8)@K;w}TeGUBl1>mUOJ9Y8XFoSgt85;(z&Sf0iEjCv#Jk4UnJA#9*5Kt~E)0JyoZ>3y#Cv}5hAE3)x zHW_;q zAqpQ4;ge+Bkp6pi10)A!BINF1`b>jidg=PfxrwEf5?50t4f`zJk>6?$>v}I`>EHM} z`aOkY@$OVHcDl>w z#`zxG6zr%ssrlzOnm9pTFw%j*`~`#>M7#kaG+~r7qXZ`g*fO*)m*ge`>eg&n&&AjN zVEO=i={W>PuK89cv?m#TgZqP9M!F2!SQ$OI3X=O}+TV0nN6WioAo3vOE2+`(0Wi5B z#yLfMv#`ctbXJb+5N+;!h|rXjbv`&{MEc>JHW5x#^Dk(*{J1}B)3fkV%~R=8|JPgn zPZ_GizbLml8YUq^6;O-;0sEDPe~2J?nr%h`4_#pZpbV)7knb`Qdts^9?8abmocV&^ za&3;|A8;;<3@~kZ#6i4`B{Mf z|50?EaY?m*{{RBYcH$2AHe5+L!aXZA_bA+^4IG)76^MJHW?5R{%*+fm4M&DEa}=4H znH8?oCe7QH|A&V+yy3+;=fibfzw@0cT_;zrpbNKdtJsWc`7-2sfmU)!X)~mc{Ol0{ z$i4EHs%X;k+jPct9buP9byY&7W6q3P6edNl%`d2W5L} zLD~d21M_j`ByUUmAFo;Rco#@eomTyLziu~PL^I00%GCmloXSklgYE&KTMSq-0P(Ta5~l-SPeb;wL3@CBIXYlV?%GXN znX2rN5=;-p7TS}vUTx9aSx~t*Y&c)x zPmXEBc!gnbPr8Iz^w7|r_nP31NNEyXDxAtJkFi$B6Lu@CXqsBlhdi>cb zoT7RAckw|cOwQQn8Xyrd?5dzb-Cs>pE6MItjvBlm>EI;e<+_xq0#)3r(cUzK3NFSpOJRa#Qd{2D+&^$$9%+hR*uf`!@LIn;oC6 z5Ti;|OcX@@tCTBoZ`jI)gKz{92P_U`gF&ghOVH#%NghZpoi-qMt0;j7-w}z+K<_N1 z58B%162N=OGyDN~&=zX|0L!pJ;t*>N09Q&S01!ef(HV}`<&5Cf45`70kW7xZ6R0vhJ=CnNouwsLum#u2Tf>-prV<*q&wk*}#ALlSGOH z_SXfmByAiWfGj?ugZ$>#1`ac1$`^d$!VuozXONSH~<5dSmA8UWb}%fWCBj$lYa z3@5^+5$0sNgg=ePgV@D${2@DzlA+>oO&l2CuY$u%C{k*+L15KLioJw#GF{XKFRlZ_ zBb2FG@`UuKBX9yGY(%a(B@8Ni+s|L6C16tMfc5>$W6JLlV=$2pY@rxBEWKuMkJA>p z1h$=J=Zpb6hk3l+ugSnjJtjW;$dp7tjNJxg%8$QmKFmGd`#HmPa<5eXt#ac717Q`u zK9ajR-n|h}8D7tN|Cyq09|A*+TvOp!`1r;T;$Ww>ECUcTC*vV=8hTBjaAiIK@x8dj zfcqp1J3$haI5MCKh-95A7iflHbRi&yK0Gt`4S2p&kcDvsz{>OXFa%Kt7orA&iv$Gj zeCW!^ zhsLh=q@TLE$`9y1fA=_d^nCJ$-H5zI-(o{~nfS^Mg8It-l+psy%%G!Vm{{R;EV)6JRTY3b z)eup;2zE$gwzkUm50F2c0jM=KLuOUWcn67m#F|3hsi_CL;Vlvl;J`+efEdL=T3k6G z19eUWqY?)oZDjDaWTt314B*M`VgbaE8i-ciAZ(c3eDK)1Z@@;zD~`ZGl~$AO&9TEp z(jjL7JLImh0qHJ6iTW^E+`K6RcAN^?@m+ubmu1{N+Lo!sUQw8$j^foE_k?XMhqigt zxg1=tDU;DC{GhJkmLK-8tp7`BZ!YUVr(W=&(w=xrQwr>qusS&Wb*K7G zr?d;2bS(%$2Nt^%f+S4?2wK)p#!@_$&V&C|2XONOQ5QBDeu(}ALLkG)TY%^dx<%^l zPN2?SA4DSDCYPMR7>Vgn455kd{N z9eD>~ckNGh0k^zolB^Pb2(oSFeDq{A$513`Ar`myvS$VW4}#JhSrI8z`t?FE4InTleQPGZ^| z(H_PJ5wG$nhWm?Q&Acq|Q67RIf8%VbixSK;QO{{5?p1-elUTAtwG?s zabU+-GL|T_1ofV=N7DQtx0wMTaS6&T~~HvhTyKjJSba`+Dw-dP(X z`a=x;063K=W=PH=`tVREB^&>w3&(#=k)g0yK*E&C0I`qW25-?}7*9M}Sy)NnQYUQ* z8PfEnVezIi(+9$3Ob9<7Nj``-Cxdq$1&L)!F$3=lKq%@()a+(P^Dd8jekwQM(2sVu zTM~Os=T~5cn_s>CjBCq^F1aIpEgQU2lRXM4_Fp|{k?3QkSy+IHC-Xqu zyd@tWuDxsu;edYqI?|%DLjD{PCMV8-x>o0)qp49UxEiQv_mMnAq+~^_k-aOyavJ%V zWRgbR;dB;L)!Zf5A-!muqfytJ=>2f>icf>qQj=?9;+_lnu6R2yh*wkMvo{0Q7~RA2 zb%EP}w3CzJ{@vee9;&;A@HRkmb>y;?ceYXm|#plm7d@fa}vyZ=)e5v=XIgQ%=Uff^kI zhmgTL1kjUUupe+zo-BfoV7_G7VU~Wej%AjV3K%uO*a3iCzX$c9Km*vIO9zc0?P60bR5!3wKFTHKEv+ZVIbPEn=bipMDkeQTAxhU} zk6OZZ2Qx;+#d-2SSlV3|qPKO0^I6J3?A-HMY1Y{#IB}rkYSh&MXU`4vKJ@zkq;mj0MzjyOarjKIQrQnhNl25O&x?ou#KOfclBXE8#9}K1fLb zy<`Us$H7xppaXKE$uSW~(*eCMnMOL`gmFE*i3I&>JPW(jg$7)eia zOms*<=G|A_7P%`0EM?PY3JI*&dKiIUwul8lLjxyZO)(R8|Ho(xD)QP%Rp0 zBn;$72vBB$^{Ez$L}h;#eV;fOEriN*fJibl8VB)Q& z%!5-g@>&T5^_{TY>2Id%z;0Ger;(4>t)6MfCXh>K@v@FCRo#Fb0+KuMOyDNMIx*swTWBAR{DiU-8dU`Ob%C<+Km2k)eTRVknyEQleU?5hqt zJ%A?&pwU_dl98Sg?CW*QARRxjBH83#0!R(VKJ5$cZ}e2AON> z39!RNSQrIr!-foPL`L%5R+B%U+scDET$Dn5LLfpjDW0rITGR zp&|RKB9?-XaeR2N^K>k|QXP;!a-^*xG|0pSY_7K(^y^evj1Z8di;fm}0tF<^2XN$V zQ2#H`0hU-y5C}yVi5Fo~d~gsC7ERZ*g@EPC^N}=@6BQR!2>5V?f)5JdP#m}}e zjy2;LIE)#rx{BFSPKZMLji^u(5jLYv=n}#%ONSht^Ipz4W4h5`Sfd;F0S4l`X5Zg83HIrlnO$F4G$(w1#0UOdfc|BZSe=mR7#3Ajhx+YjD_Ej0;AZVI1O0oSJ06NSQG~u4Zx;i+1@-z z00)E(JHM9)_RWS^2q3#zmqy(o_5k)P4dN&S8}TqYL@^7tn4B7PwpPrYBc|3y+X0T5 z4!WnDcu!1%TX!@2V_BAEY3qYa_mFvKUb|oUV%l2eR*Lc3Jf?y)Zb~gz%v|h9=;bda$^Aag+08g7O5+h;M4l(zdbry z*|Umu>k9*oyZ21S9Mnrhx}_idaz*`uIB4$|SF_3biz!27sGC*DjYQGNOX&F@5!CuV zR+P$#RZ3FUlT@0W8U2ENhrX1^ti(Bm_{XU@wB)M8M@k1<D_$q)8^g&OI8=;L6fN5^3nQeyE(7Yp#yeP zI9^gkvJE7-QI-OFV+dM8otNb$zce(#0iYP%`LD7)p)z=s`msV<9g?;JrNK z0Fs(|Vx66h^n68(Lw>eOj`YIsiA<#dby?>QgHKUhlE zT>uW_frqC>=Z)9#n%23i(o5dni?3dNGBuv%vV~5$<@T>QKLJv`=jt+rNdi4?5ZU-9LL21x1z(Se^ zx|FYV3j|XlLXD#fZ?%JNg9G<-U^G57k_w9lV9{idjZh4ZgV|7E3OtA*0lF6l3m1w- z@x^wN#Vm7xP<%1r=G{sM~H;tjI2RTPHr9@jy?GJoJ*a z+(?6Q)m!S8n%7|x>GFM-9geZ`i@od3_IwDp`eN^_UWS~^dDHT!Rhj^b6IlK4_U3?@ zV9|2wTK01pexeNh`O6O+)S+Rl!BQ-F2{a*?GXu3fKBsC7>UINZv;xu8C)xGQ#SN&1NvCSorPNE`JYh8~Q0uCbHof8E z)Ar7^WK&mJqeOF#bV9J*@y+Ic->gffBIC@Rp*IqEIaV6w+XvqljhO&*#S12J-)D1kG%C)w@*~M_sv4No0>?N@~a*jiazfuLYe|G?zDt7|C!tt3PRY zAfmVZ_}XcU`RAO7fs0r5TPg!?ZHJv)0vjA{nZ0A1B=M{{o<^+h6!hhp*=1a@>Fw0DH#m7d+dfl5nm{4#Q?tmFkWr_kieNY>B1Tml2iOf}f*^#W zt$ZqvDIu#Z7@tig(*cOMxI9m-5SSK25D8>91H4nE3BMt=?2&=pE{n=>!+mQ+)-Mp_%#<%{S9(zdXFx z)Ld}u+Uws>cWPB_%jmb>sjr=AZBDUkckkGinkEj?XQK35XAsYbx01UXl96BBm z-=jK6Z|F?3N5`d(?E&vEIMz9LsK6)#p~?EhnBBS{u$)%q=7CpOLq)sS!R+D#n;ZxP z;)&k~hhQ=y0I?4!A%U@zBoARi?YV3S)|dxCup$f=VnWnq(~Y|3sRagd!a;B!PErY0g+Jki(RgAqO1B<i?e2%0qpd=F598aDrrbLk4QU<*TDSEZIeNW?)7J?*jH54IJ#H@T zetmm%#^6#HEtxBCaeF}v{U4uybl>jJErn4d!j^I~TV&Bk&|LJHec%@eS+)oZrql1j zWo7iKSVqVj@|mwMvWnB7{F)WWC#ot!WI-R#=*q3r9M+grD})Ykm;0^-fN=Jzd1 zCx1PZzg?Z~9@cTU`9qk=Bl8K*)&JBd?+|J{k(cf-WJa`;3~p&*CaL{q?b~}26!z_@ zIx_L1^SoTeR3}UkmzMELoY=#-u5mDk)M(;@KF~YU(2{)>=IMe`7VM*mglyp09MBG; zL!B{)zB87vcSr6lbS9dCbfv2Qdod`_jfSFVR77MGps<~ton_4f)WnCB#sv^&8<-Cr{aXL}G&HsI&!wPw^}_3uT6in3`QYm0wgFA-$zTbX@eCVA zTFr~vsc|@J=2Ag$_09v=0}o$6x6+Sj(YBDPEPBj>Fb=$XVzRyUCs19Bd}VgE(KL=I zGt(0N0FDE^)YIuAQBzf*+p+j?Ay@%HQN(%+ETsi>s443fHh_wv(#d$+H7JV6_ERA{ zD9!=dmK+cY&jGMRA|NAb4ou*wDP5#zDho0s_L0F-=Lo|ZIJ;|(bUR5Ok&&|!lzdS0 zdYJXMy6X8X;vvo0{(QXl=H&*RCgy9Up{?GWCCQp|zu>-wk(X9~-3mikz`}|7m7$sk zA_JNyLx|CrOp7+d2+*=fd5z1{UND_F-lWC}yZ$kbp=rh4Kq&2^TiBjx3u~rKJSnef zUo*_gw-C@zU}lfk*Hm1Jqeo=ODTNKfys+E2A*iZw_LF7~7&XQNj|xC9XacaZ?htek zFnFFy^H;~dsUcn}VZ=5> zIMTpqx){=(GAK1e?FpR$6U|Mt_kQ)J%zVn#!9SDw{0=Oa8>i(8wUT%KC@;51UxpfX z`QrmF7~jcrI;r*%UqtG15imBLwLPYbj<-nAG$Suzyd0WGBN;e zwqF5(vwC>Y*N{PY>Hzo|MhHx8><%k`*1SCccC&Jn4m* zPAC{tVW2%p_C=d^C3svI^c^)EImdwo4=bUEAY{ekex_>Vpi!jbTUD0)#i1r zS<=Fhl(g}~R~uk4)gMkMvnpT~oY4o8yyEd}ZQ$zce>-C6bl|9l`Jc5y$_=#(M5w_a z$dz|XibIDgIx(OukbfBM^KAl!5NN^%KsY}IRU8cENJSZlL1ZTdbGYSZh#WNodxct{ zL#UCU;Rd%QL+F`lV-ShbtcPz4`57hkMbIdDh-}B1o*SzfhJ%#E?s9b*gIV#q)Vrp| zG`J?$btEEmxBQ6}n~U#_j_3!4VFtm!toA<6IwOfb?wi_PVDe@x|M;-#=*-vbC*k+Z z;+sbf&`QhOcpyyL&sMDwgG0|33u9zmPbiOGf|>h}(Yn&wDUXHO0T^VIu zJ^?tq34n`q;6tL~Vi&%PRBRzLn8*-+U)_bI5HsZnc2Gxo2AZ7XYS4V*B>rXo#qG(n zTeTaJwT!k<)`HFFC5w_yImpV_;n=9cDd?GVKB=Rweg)lyBV7B1I=9)rkWvY2JRfNs zK5Wx(b<=IkT)ixaa$}E$?&uRi7MhZ!2dcjTdK#1KpxhjYv@m>+IS?r`q$3Pyz#do_IDdsyL%P{d zw#N1~JsfJ!+@spZw$5p@Ry<<4WKuWVbGunyQ&-aFW!@zV>3iCbq|7I_^SB(1;u^bE zH#0>yv!N!GQTsI&)S$Hk^OKOYS3+i={qAKCNN#YyC9dCcquZ>h8Q}_98QcAwy?a4W zw90L+DaFhSi=0l=#lSr^R>bK5z=XKB?s8EJ81fefk^GuL6bFbR9Xg**Br;cnA(nIq zB9?>XWteiZOzGeeJ22{K#+fEL4HjG@6#~Bt-9=-l$1;>e;~|NmCYpEyAU0-&(+a5b zjQkoQZ)n2wTv$_vn$fG}e3cn%=Ci9UTkxjXt09xua$aQ3)<}iYG~Q+)!?;zlgePp?H9jt)|8z9}0C=aM@3S)>j7HQdhk+f3~HmxClyy&1hQ$rDoHVC!gB zbV>TbuPeYMhRiL6q5TDPS5U*9d@XPQ`VIH;Dn;=#@4CGt1nJr!E@;M#m9WErPh=V5 z79B~0V5K4Y0T9fXtoRl~hXYl{WoXhN+B9Y`6#|`c)Q|@U#faS**1#_ZS z_57w7nYv;rO9Qh(jXzg8ygdFNI9rH3{jE}D``7l=ap!-oLlRAmyWAio zoGrqYndAr=r4N2)pet(3=V>KY16kYuQvlLG?A-qqEzTj-E%PtnNRU8g6ZDmkfQpiyaSYSv7; znY$pWnN-Oc(3tM2eD+dZ-R_=wyh_`aL>{Q@w4G|0Ja-LDVt7BPmub2qo*hI(Nd(-1 zlQ`RncOXMW5QvQ9MA5(p4_-Q8PTc*%wHSf(td8}Zqto|A-0@lH{?ybwQHVAYv)!Z= z+5ak<)$OsX1F#$0B5y4{WD{c%a&Z@K*h2RKlEYBsK}9^MDUGST0ov#Jh?^v-TnP{6 zK`YZ4O0f)ec}5wBj(U}Kp3c;_FHbw2&+gl=73?&hk9ZL@G8XT?kzkoMSa4GM-aWCx z?k3V4QnOFqW`5y`(oIzT-`klQ*=6=NM1w-|yQVDZg3Sb}^&sbPE_7{c0<-TfA{SDJ z7@MKp`Jeqxi}}HF4<^)?Ng^@XrF0VYaxh72bL?`WrdOTmmEn3|-}t1x8{uCd$7xA( zZi5ch>h%7H7Lh4j@8 zGTG~rl^F&TVJ)R;dHx!GPohJ7xHzAXrv36VW#tH1N+Er@074?)F$3;wzoR&On_jiz zU_JU5hnmgVXi<_*`Y|!<#GJ=9+#G5J< zoi4K7cfL<$T97kFx>-TG5Z82w@)-OPF++m~T1xglO=BRp=*h7RQ!?YA?5L$gU#3(0 zNncZqJj>LB8oQhK-}vxYcOt*jyd$Ez;J&y`_q_T~v1@iw^UN=K&kR(J^rg4)KE~M= z2M8}z!Ud}RPKDq1Kz7~qF()xGuWkl$Nsn{OtF8c(PIo4uJKf{yX7i}4Wp^(9C_?1! z7`PHBv@e!1Y7R0&&;3KgeFMYxpjUGN6tOewC|$Hb0@}d;ZO|>`cW4Dvo064Du}q!V z3`3tNhPpS!BFh)$s)KJr4M^}C_7(?_S?``j;gHJH)`O* z8|M62YnAx*#}#@c*Sq2Yau=ix?d%|%Gt#po=sBYc&;Q+DWrYUHZttsx_J88O>b2&0 z{*hkY0`$cp_0L?8mDeTQ9)7-At3w0tqB51K5Y4RN5E9rj6{3x+4dG;+BxZ!gi^6&s z$)vfeE%?A)bqmSMCi@Q0q*-So5XB3J|C<^~wb5I&C-vQz|ND0!D8OvjM8Wo7e~4D= z)U#_3L+^9P>i&~0*JI501BIL2$iheC$HWv$$5oqLUx)|nE~{IdoTpx%rtUUTsaJ9M z96&@6mpr=)8-FXvzU60mHiR^wt17}4f4I!e?rv+pK10JwjfVW`ehTR*520l^Md~Q= zvPPbAHF+RQQne;e!u7AJcIw;8qabl=o(0$5eC&QzkNTBud(}4G2s7=bcCOQ6hLpim z`NDVjxkoCI-=7%nUSvLV?(kGi@3p?DZ+=nUp(yg#5-)K%+daLVDU+(LBToh2Ywl|?DYZzS(xhp>!w#8d} z5pc0q4R^3evwBNaTN@J0>L?mwY3+kAnP)^eexBs=X{j*H>*Wb& zqj+oNNv3L-xqN!p?ZT&(v(l9ha-ZA2J@C|Epm@pjt-$?fwbZQ1hV!9T!R2>T!gmW_ z3U(wX}PndhR)l*c?MZJ%;(l#$pJEQJy*M=48gNs5aBJU8U{$NpYm+f=b z^`M^1Z&0kXzv9$f}sD=4bPyln+#nXdWIAl^U+Q>Sk zuTMAI?&CplN||6e?&;UK4?mqWRzEpje8Rn}etg$pa}!iD4jALF_BWP)03RK8zW%{% zX^ec75_R#Yu= z;*No}E4f7;a5bV^%3xNKyn4b~eX>kD_UHEW^|98M@lMOex@KmTH^288OX^NCk+-*U zJ{eP}ADaGz8mrdhk10o#f=RPVPfQQaEQ1S*%i@)5Yy@r{spxpUr_XFv3WNAAh|15T zCF+PU{)y}LV0w`_%WTtJ#XR7{%GL>AIbn&hu(>C?;tb?_qSxf@hU@BHk0Oh%4TY_6 zHzwyl7uC(_2Ng#8nUG>{OyArLrZJN_Ss|pHWF@yotkEbJbcOWa&jm~F%jZ2PS zm>6$OQ3+d(yGpDN%4jBDI)N$Hyd1O4{XPJN6qH&%DlB+bBnY6)QtoEm?ccY2nJ%OD z<|6%rskyzGIp64tsM>Hwc+5Ti!cgmpi6*Gd7(+iJHl|ZrI~A-=EiNj61QRkWj$|ZJ z!6X_3F8J;hTDU&ms#b*%sU_(Ep!Q1)iUs}$7y_bCENC3a5q+Z+#Bo~UGOChF1Vw^| zx{jfV)=m|Ig%sWbp=6Ix+K^ao;$Ag#dwomNE?Y;Ele4{tKgsieyRX03p`b%y(TC#W!cH7Lo|H^WPfyHF z4LE-x=yb(VX6Ct^tlXmF{0kRSF4tvLRFqw5jw# z!?a5Cq@uks=bZwRtPUpV1v3l+i+6-&${jo><;s+D%GTObEKjO1)VZjm(Ws!ql{UX6 zZF57_qh8kQrncWL)4-ZN9#{4|--zFJhq80j!{D)v(~I4{GrPhb8^k_V3Vg2U`AXI4 ziK0ipoZ|yM%K>%$L2aEWCCwL#<}V1Ow??FOMg5NoN*|=XEmnD8ek;k9nkbX?hC`RpA-TPln>RQo`q2^v`DWSDxgD zr-aYrrosW+_iYD1b0WXip8Ccv{%|?}TSu+%-j$!Dm%qE86F#aIo$ts`1Y5Hi=TPS z_qTI48mc~(RDU{ss8;n&bF_ecP*863hUvX{E`IGq#QTWgk0GAxUJmaa?LJuh zt-Hj(rO?-%uCDpFzl$FD5dQpK+{ahm?-#7sUumzskzQMso!!uxTu~f-CEvfPcki|G z?G?qVe0=pg<&rhotoQO~o=Kft$3(rC3V9>xwTW?9#F}lWTD>>4eZR--(=M%#B$-bd zN*|@E>+!oLU(7_ZoNbwBc``nRftN*0r>%n z&Qz$vbDHAwQ}~JVJ4OoiMoSFabB$^**cM-OJn{SY@3-sgvjcYG+ra-MlwCRO0j9XL ze#jW7W+(@z;a=_9Ry$H4Zx**W)>ikhgy4{`?ABiYs9g78bI7CihKWnWi1BK-j>f4f zQqsG{M;$kwTqiRTD(-iip4PdR>xYitz4`10rOy4TduQ|Pt$>cWSL2pU(emmXY4<}q_eKvZF(+oxMM%*-SCIGny5F%x^Xkd znVsiXJ{88n&`V&iQr!mPmXLpw%A=mc&E|Sd1rp9*3zR96n?Y~a2DMRq3O+8H+=^qk z6OO)EdHO%IoqNx&`51aX`t>Ta`N<|@00b!-nIY&Vg3DpX za3?zqrI`xYixZLs47e7Dz|11fS=rs9412{BTd*%%lRcm%K}twF3%1m zCNiFh@DO?(?atMQN=L1o--aT8=ke`I-C(TMvX0GN`4T-)`G&|Q4lP97A43E#y1#7- z)~n^1=8O0Lkb8UeTN|vw?tVo^zP@yG2BJFR-Q5Vc_HMWXs;*D~f}799Mu@8qQ=^R< z7VYzmZqZre2DiD(?gpGn?*iRBtZ9T^OL2I7*?Tl*BhS%pT zw|w2kLVI_kfnOxfO>M&_jW zwvpK5G#-d0C)jWJrro<1{yUAr6UkZx#p0iHSreUIbdTc_DvM=Eajm`~h5?60us1+z zcp?n$pyPE024IFlxBr1dZVWiySa5It*b|O4SS*guZ+v~u1A)YL6(W)N!;_#^P}9vu ztJVHmL+k&-OZ2a8m}B zll_7({U*!qO>6_>Ik6))yRrt-KSb>KEfj^+2{Ea69d-~L)%Jd8fMwsUKz{2kS}k~y zup*=NUoI4xGUgz6mzT3`L;^|F!fnn59NVEb|Imo`rC5>y;NK$;OHAkV2iIdmx;aq8 z$0rMdc!R-Rr03SdS;*u(1AKtltM0z7{NTH_a-D)egYX*tfYm25w>PG48SC5vqkol8_w|-7dF3(>q4yfl~3)dE#vm8S)-^WDO_gx z%~d$YB4`|2E0tNl3OBaSA3qadu%mGp?tVfN5|YZlpm@}vLG4r8~vYuIh zd57u`impsj*hrcnL-ig}-zzj>D%r&R+)SpE(d&Ct3Hcs)4%f+W%nh0Nu2$|YYs5Ik zs~~`%(Zb1fG9KI9ANnCfwvi3pi5boJmi0_@dReDy&$v;)DM8P8I(5rAf%oUE$;pGVjeYfs z+1YBbz3F-qKa?)B{}gHVVf-a|v(Y_r_$^Abyb=P*R>b3Zk@`K!Uf8s)+HQv*(Z+%; zHp~V=bmcI5IJ6ToFciOpM_W2={L93%d zfa=a02B6;~G90q+a!aGrv(8f4PC(;k+yEk!{!X=x-eSNSANCv^Qu(T@Y_qIZGWB}s z|C29lKGb-JvK#c!3Z~>IW5v{;id}KmTsq z{|Mu45dBj1vsX}~Aho&O_cCt1R*5$Zuq!xJpH$rE+MyRNxe?^}c(Ri!Yt-+Be8bC7 zZHrZ;Mw+$w71qjD?n*xM><=OoH($EXPuu3`(-8l$A(c-=IDC>3ml|+U_0IjAa;Luw z>6P5FnjZq2WzaHvc}VpRI>Gi6!{H2_(`jJ7`RRK?oa%utn$`A~eJ3_1qm3nZ41~Th zC>%c~D%Kjmx8Y>4Y!Vinsh}Ki&Bbt(^oCrrTe*L0)Hr=Rg6T7v;U&_SsUO zx@C3cUEiDx-ZA2Qm}J$Dw3CxhO5Lz?5qI_0;H^2glTKIG4Si?j*tiy!RAGBh{R~j! z{PHTHEI?G>a_g;9tbaV3zSuE3wV$sxd%kj_4R$o zN3(%@!)r%$1Y4i;n`5x;zHSrkpy+UU*}D19C0P5zCW)2vPCWVPx5Y5Tydg@enesn$>CEYqG^9Go&d)p+5wCJcjT;0KrMi* zp)r!oU7|YoQD>=yp^TTqCt3kaa7xM>4tAX$_xQ${w^Ym;1@i=c_9qVWnT*}@1M`&* z{z5gf{SULmVlMHSHXBKLjaK>>-7Pi4hju0V$|Zm0hr9)jw!@D8W_!2G`3yvd*g<{5 z{E@HUhB)CdKi82lmdE7?fLXgD$-yHl;%6P>z3^*njBH zE2sTO4?Q4YBm?t%DTZx=Q;mYX+q3w8-*=zRq&~FYM#f|v0x6uxhl`#9Qsg%l^;O@0 zeg?)l^NEJ}C`f;Ns>pRLLdYxh;9@-~I0 z<%9)F_zeFHtAPeR%s%@vCd79R8MF)gQ~X2&>C!g>@*5ke{)h#YzmeV|qPqDpbWwd#K-sW& zKKo&Qxtz`|DP;8+b$Jl+GSbgj9(i9xYRe+eR+h9;F-K;RhWs<1D46>(7)QOVy|I{8 zK68y4xW+G37gnr_>}CN)c9unJ+iWcV6!t9)zS z_hS3mr>@H9aTHMCaU@Sz>Ax!)8-Pjq5B*wL){D#dDU-&q+YM(r@3^t=i%fx$>xp(D zI`Idx4VTe@Lp9P;9=tfSLc>f2iY~f(m57tae<_&Jbta5|=4~M6=FjR+Ks?*gom*b1Dt*+N8qZ9u*jpwH=G&due#Au_&E5v!4iHw5I( zi*ZwrswYp^ukg?-Lgp$hY+qcUi6cgZj9CY;E@>D?MCJq{bIBj$9vj#bbIrNC+TXq8 zwR8CTSj4Piy2!Hmlh6FdP7$S^?^w8jRfsOoL0)f4U8XmQFWmW`0&=h1LJRkFkh*6^kW|?8sDfLdx^)Bw1g?G%i6nh~7EM#4?-(-HG7TJ=ne+R-HW2#*) zyDh=7WYPs%AaVsjp#qy&3eoDDm)fcOmj&q37k4BUO8&h==jEPw!)p1rrzvlO8!?Br zHE8}`}H$U2Ij z_*=%A(fw`thpPcpy(qAQhgjyEuV)``5u#ggsMk2uODblAUcW)BpWU87&)!1M^UyDG zsGx$*&+N`IM5p+8r+Zq9IuWxc789P=C8u?74e+_Ijh%#L-p{Ex@%zjw@eWj+qZ!1x zFF=<_ptfO{OTW8w3)<8lwVm2TU;2H$Mjx{Xlor23BW_;m#T{bBRQ7V}&INXZ)9)m5 zS;t+XQJd&Ra(i0$y+n0H8>i>UeNEqq}0FU-QPEfUgw}+veA0h$OWS44~T7HVHVk#argePNp#raomJw6d-%e2 ze!r6&CM>ObO<>pKbaW`7&}+VH9hV1Pzm)azPGmH9yEJfs$IpFj(4%I^15cv={qAU| zWN5OK~jsR*UYRA=|3K;&F7RVsoVR_~VzkJOT=%^hobRM}bvu`rDX(+%1*g ztZc*PEd6%1zsDQIQJ6yX0=>QbZ%;zhc6WsaasZeplav2PJz_S2sHP-*T4mT9BH2Q} zK?1Uhg{~rt9x%e@RUcb8)WJdzQqc2s^mFpabm7zn4HH>7HBUw@Qcx`fESrj6#G#k| z4o8NJ@U0)OTF=fX7J9^A@O^p4N%6@89W3<^^Y|+!wfE5ptyJZOI}z!R3k`aE1^4}q zj=UmFXHB7XgXdookT&uBS1j}py9OL`+G;%a;-g2p$o7@LmBqT4T7&4u)NxF(=myw} zFQ;!CPPg;?8-){T4Yi#ihF{c&RmTu)N` z=RV9P9kak+e8FE_*d|Q907i#-h}QsONH{ysLBBdS;;a1H2Q_l=sMiJ^^S-d_ zl~Gl~>6Y=sbsUMYK2bO|O2HUaEu3(8ETOO;K@LHUd!h$Lck*%dIT`(egFaY{-XyPm zpkrR}F`Fz5jDsHHx7ScaSAu>nob*Epo=x6gKRdN?b?t38`U4+xFccU&9Vj4R$+}tF zNuijvGxeSN)4aZ(KPpR$$f?KG(g@ zEOeF%YMzLmYH2CoKdtPs{3M>6rPPeRjqc+wFVN6KlxI`cDBASG5P78q_44+-k|Xm` z4STbNjH;%*S2(mZa1YwfjBa$7BEOzn#6`=krJ`J9!1m@lPmc`*ecv^P~6avpU;P7MjAJsExe zBJ|D%jYrWxUeAs0e@1Vb<-GkC_IATs4a2>ydxtyYvfg#msW(SQ%}t)-9YzkBj%=EG z_;_?YEOc!0*~h_mLyzld@BL?5QT5J2^~=h+n5oM*Jyq&QY&1}K4Eoso992%xdm5gN zDgLbC|XA9$- zHU4^gp0>$!_yc|Tt>A^e>*+-M&bPyFalcHmfBb20OXY{rj;~QiIq#o68=r(H6>HTW zqaP>VkB5X#)@`HS?516x7vkpc^>V1Tf6|`tKNzf6o;yiP8~J-eJ}$1g6kS9kc{ShS zynn=_*7E%zI{Qi;ZY;DQSWL{s^yEl=whcA zwUy@0@vF+K_DRfuV`aC6v;A4y zaL@7cm2Ep7T{t%GAG)QTf3h{<98uTk%E>1!G^69r6Lw+kA)u{WR!n>5qmHB0JetuT z{1+9tSC(O?uAEee4!v*M&c3qag-g?Uw_-;4r90k-CUZK-DUWhUl#uLzgXt=1xDkkn;g@v-tHwtzXVm|DO9@ z5vP{2r#64Yxn*q`>s);>rCe|QmMe1aeS-~dcFoc9hYefbzo|~}_n|Oi+^6T63CJO7 zXJ_`iRQ9=+|F4nlnEuP=m)OYlMmu^9SJ=zz4h^2pbR%0WCF?_GhL;nR_o~ z2h{GN&>sSOCLHC}$u(z*?oTHU6<>MVYN+b3-dmTICRdJR2N-FLaMRrXx}p{C>HVk8 z+3E`EwKrBLWlaCdOqtdjW@57%C*uaPNnaYmKLw^qW zZm71oVc~4zJXb_>dv;*`TV__#B`NdG*YghbYyRM#@%*e|qIvSmr7Fvl8U1+z<|&8H ziprMiv#D00t!J&O(~2Hsjy;Hr8GV{wrka#6lN$C#pHFB$`;M6zRok~N*}TTT{CaaWLHA~1h7)JxYlGvKKmL^NcZyJHQ7d@K(4ER%#o+5W zo{OPn|E>QH{86>IvVa5BE6xHw2jAGo5wZGs=WkOr_0A%WfO^_2izB)y*bHH@>xMZogt3#KrI$rOo_<4X(^Y$S#$cF1g~blU`=VtWGGL z?p^sNEURxrcHN=xW91R+Mw+)*Ki1rEe#XOXqDxwp%GiOVSyg2fo^LX258Y|FIZS4j zx^j7WjoXg@{!^1Dyt{J3yh>g7?(CMMs=+-DyE7WL*18j&N~SL)b5`zrQ0h-S-Cpwh z&V`UMCF0STV6}%X4;fD5V3mOSLhA z6UAArcbS)(D|xa@zNaP{T~E9lI#gIs#;8`z4R+Fdb!pT$-|rqCMx>m=c3R@n+jY?c zK`xDMR5|0d;fBlpd2J8m85rQRzOc_pe&uF51b8MT9*)RQ2 z&F?#bZJgu)8|QSIVPBKf?eh_r7FEKfJ(#?ClCO&ustm`{LPr?D373}&i1a0ygaaw`Pk(gtC*P*Whj05l9|wT znmIZuVaMm#dFv;^4gDv7L_)!rAEfUnm8APF)2ZZ1)@O4?80{gKN>teg4$S%zjyeuT z9RHh9iV%;>&AeauzFPl)RPRDUPlB=x=pKi-CZ>A*3AYQomR_EAsf!4ELOoW}{*+bc z{@ABe_m0ix@0yOS5q%l)x7UqF4WIi_P7P%h=v)pw;n;MvJIUo#-r0S9POZ8Iw$}Kf zJ8i_w;}LhqD~~ZB!@qkR{I0Tz^}D_A#`3;nc5WqM*30GlRX8wJtDvQ%xl9^o^M(iT4nNZaHN4K;M zxL!efKXK!?_|L%`BF{Ju?P6nXRHLGWtdV^miEPsI_7ptgt@V+&b$2i zD8$Eb)pCEA3h-Qg-3C`T=iMj%HF}-ve@Zj~_zzcTS%g8ae68O>jJuD>$#y;+Rqpo5 zw;%P>eq}b8s@k6Sd^toff7~v2cRamr^;k08^QaipGO69|?_87Mm%&Lge3JSi|G(_wm?pfDV*0i7g@ZRT zl-!9xMQIKxtSpOxoPYEU3fJKkx^BW#Wu z5cluMfkz)YI}dzV{l{l!N8gEU(t2`Qhtx38-ruEn-=E@#S*{r`AV$3z_t)a*!+9H| z^>fGmx?*+VeN01NIrUrGh10Hv(Ip?9dJGK=ox@wc4qB|ROEnNW{Sx#$r^6;mAM%?+2zKZ^ATut{|L#SjnnRa`_r7+ zPTIKAdm`wY&7SEMSJrOFv_SjsWM&vonw&(;4?5RCK~s6xhbb$P7}j~8dXkqc zuI5R4L8q8~lG*YTt~(w7HM04mnw2bbnmu_=bggkd-ZR2oeW=qWczP~w@Jcs*Yc2F;|{3CsK>|-3hGw` zaU?#7)MrT%klSOH^OaM&wt!Fxv(E$i7;Iin>2m4xvNf>#r7#$HQf5w(gW{ybu8g(PFBF$jUw zC@=M zmUs#Jl0qPFxJTz-$*Fm9+RTmG>%q0R2V>Vjfr!0hy5qn1R$*uOS4gMr7&Vb$o$siT zk_-JCyw1Bu`^;sp0MxZT`+W56fQ(l85er{V_PU=N`u*kJe~d}KKE3VVrJXWy@B5{7 zX)Yyc0?7ovpiF3bv#ZzAEGRET%FqoW;rybwt+*s#BSZHIP#G7-&}CM`+QDpx(%wxPUg6|~3$OK;!kUia^_)q(8ODS(%O z7)sdEuG}p7XZeu7{8~!svdC-BSsU#C@H}&Oe(k@P?gcJ&d2Z3Z2@^3+$A%?|MO1eZ zOX7=kPVRQCo|im;RzGxkaA?;+2%URk5!y&Cc=B2Dq*qaEAqj#Zd3S_2N5XW4Fe!=? z8+sWM_PRBAZD5$!tk|eHczqk_154Hl248GYNmxUJ=N1(WpI65&zqZCWa7&hbdSys* zb1!?fsir;t`hIq=vh0+!mbPPvofu(BGx#~*G2ce_xav{Etg$W=pLLRC<(zrgWhW`y!dQDVDr87{0%*g;d?somtR_+ z)!R9}<{E2#O;Bf8zVWrf4a66!^%C}${ud{2{`A4ZjGnF2$#8dKdL=PT7BRivI6g|^ zpYH0raD%lxNbif}v26tJ^+ZpgR#E-~?OsXMA`~KrLRe7w`3P_R)7VE3)^Q~3`f+w$ zICmD-pB%aEgLvz(cpKrd7lL@v@f3!{299xGz@LelOdY=*+CoShUyfU&}&+<^-4p;7%kbA<+TeZ)H zLjPWJ^XEX}UB722jUrIbbe41zDmm4PCI@b=y*}9zCwX$4J32UV#E2R>KQZ)EO)F&W zNc5fPD8FF%(Jf0z6+HSN2z3fPy%-$*kDjj?zS|+nwdL<@(^= zs3$jS`aHHvNZ!(*-}-8vU7fq*nxK0nyai69dew?0ljV~CEUx(lhQWecw`~v-)^IZ3cZus4`?P#mg7MLZ9!(9MZjL}D;aw7Ki|F7kD75JkvCL$iWLNkxVo=W_h3Gwrv2@bP(R+nhnMC?_Gw;0~EZEc^| zf(oA$7n8ggnA99gW5;qp4r2ly~!aG<7e+uBpso|uLX}^ zWWA{Mk*qoGlbjAsj|cnmB|q+j{kItH#}Dyq3%#Ex4Q*j3pOhw|kkQuijGbt|6!iL;1FtnJ*IdSS3BC&qta*hd!sVt3;2TVCmi zC8_Sj^?{v90^*8U--McW*E@GJdmry>edv1OYU;5__s2SCuKNQGuPO5}pVCG|f^q=KPatTyV4Sv`O1?E2p`w|uQabnz-t3#cR z*5!t@Nw{55RQ&X~Yl=s|cx{{5v-I`qevw_jcr`{il8INd@g56e6SsKxiD}PK@hY}> z8GujzC|;$Uj_Z7$@_5tfg4E2B5yu7mbb0DBLUN!S3MOvhEke8X@Ls3K|H+rwpT2so zpzrw)ants}wA2^1&#%h!le>yLTe@#g`beWgw_KmWvr2{E@}LYv$gGqERF;*c2KVfh zK97?m3na>U9_2-Zu?4ig5_-J&CiL-a_~~Z-?F#Kh$@(rxb<`mxm@eV6wy$lTZOBv3s;jF7&QUklp|q28?N8)>s=~I4VA>+;SNY2 z92uS+dK0SvwpO-E4glN3S#!bcj7_Q2Tn6M4i|3Lg&Zuaj?!(&3lw$|PYuVz7D`NLH z@#;3b=LC*%MYJpz;Eal0XFsh0VqV3lUdC_FG~e^mX#&4)LF_0;IF)^VEW8uFCn#(% zZfLC|ELCGe2lm9hcYUv1?p+uSaoLh}Z0KLBk*3g*xtzbYez*}BD3LeLOcg~3)BU{| z_!V?~emSJa0rgN<{5PTJ0&kBewBqNDMhi$e6e`cjuKyt}jJfgTSuAa3XatZE5_{)J z{2gvH6yd+~Vbkzq4GF9i*$VLXmDn5+t(w5O$If~7%ZGG9f<7~-W|A|eS&;Rr*{VUc7@c~9;zon)% zM!HL5$eI$j|9x({^4Bk_i=Vwp7qDd}v!F95H<&Az9JP_a%_2JKnjcSy0X#6?LMlVL z%r(-%bHr;&@j^UEN{c@JTl7O$sMaF-XkT{te>wU;mHNd4Jk@+~GZygoRV>3OBSLPM zNNq{9N+5O?;8(Wc9Qb&9L~J)9a#ilbCfAx~v0MKqw`M%nJ(m0*nDPYwvQON6aBteW zj~N>iXTIQ_7~*A?VjomQB#E(AI&~y5==ZUm26!Upo5uFR)RbUrKmYWwNd6DJFFe-1 zY`@n8p8X}-`hWi>yNxbT- z>VBZ|Lmrvjm@fVU@(x^E^&_`*+rZ$$!u@zZ?TZlhZUmDcCluuL0~|oS62P%#BHRA| zZ!($~7P;l(?b&(@__FSiBX73; zG;o%9Z7@x8{r;VRwqMg0#g1nXwKgtXn)WUJ#XlP%mL>lBiILM^#Wgp!dI2QALi(4v z@)cUAe5EAA&B^34b8oS)Nme82o|-`t-8GVk52^DiV%nQmlBO>S3rIHA9iydMWq766ZxqXSXPW=#eNfvzbCEsP7<|HM`@2Q!s8gOkzg>$umUcS)n8VfvRr0Gs zofU@F`8&mZ>KOBO3b`72I#}0j=WJWXZL8wrPV_h95zAMU=&#xSrn3Fz@_XfL#2?15 z?pD)GUR(NUbYJ(uq2qS@W-4};AJnY!NnkETRLH^`M1|&#p3hfknY$mv%6=}(sP9CF zLVowG;&gsoC+%n9M$Q~D9Y6bJmK)Vvy3A`oQ1x+n;HWA0h`Gk4!t4k2L}Ja41Slg` zhm}Y7*u2B9dal2Lo^{JUR8RBH7h;F7Vq!KA3 zFON-^gM`<9PC<;E)+cq#h7OI(mKVEhlx5^AAE=pW(-Ql=E8Qs(y7gkFQRsA;_Mp|g%^NqZ)CUM$-;>L@i5^wL<1IefwScE+_`J6PqsR< zDWXl$mPCd@ET2m>WU+*o1twYrPza~KSDU*?C(w8FCP)qVxmvx(ncbieA0yv#(9rA3 zbisA6u4!Kr|Bm`bJPhL3Xm^%bvomB;Kze@maxr3X82^2H<|T&tmx2+*cG#`|NZpA?=(hI1PorXKvFD- z%WCu1V}9%M=%}Y<(&J3tD2c0vxEiY~@TR7(8ZD37IrW=u+7*AhYVEw4#Wk)*=2zAw zAD;48O_on($m26ptiQrifI2k9%5V)oBc~+cxmIlj-7DP;x14m_jBX~?s+5xtFfjAi zD0CmaOW(%EAD_5f#Q9RsE96K7KLpLqpem6r5;R&GpDq6}y)x^+>lRjfTq(>(7PLW* z66@$Vwo5&kF^i}*pc3mv*w?#Kq+5bW*p2lh-%>vPajBG*qfk$+66>3`c@w)8G~ zqsc715oNFTjB7+lQNMUR_Kupfi{k+a09mmeW!pC4bSqJbrL*K!BM_a>p=AvpX3m)DRd_n>uHt%f{(xU3u)3k0I z)GVsGeNS-S50jSD6NpdN24o_mCs@FP{`XPXd?MXhf4RxE+Ubw0zJ`9*=>id5z=D=B zK$F^1kxnB*_TqaJ>=r;Py9AthS&ME>p~Qm9#pYj+E}9~7nJ?SQ75L~m@CoD&OaM=7 z7UAfnAeao}NP(!D9Uxp4Td%%&=|oaRN2s~i8x7pO*5t|#H4^ammAu%^1{WxdZ7Fv zU53=#z(Pvcf=KsA$Mx_DL`{xDpEbB=Lpxd8GFbA}G=b!=tw+Hm-#Xx|6;G#=Wd5duw$gPo~dp7XKS@o zfK07OsHxt(;&X51^!?e(K{*R?bjxi2KH~t*ofsady3Gq-k`t`hw~yTsh-~=al!%UJ zO)W?<&a0M`-|%K|x7WzbS*s`0?<|i4m6O&(H=U`h1{O;_m@c9tFl3Rt zM2Vq`b-I+0O?nTdaukPuSFvM5U}og8QpnG?{SOQUDo!p$vpY~t$E|Y94K0V|Wq_L?~tZ%bLE&jyOJX|4E>#7Vf0MYs4d={4xV=M{Xlgo`JF}DdFa6Hma+~T_t`y`g^}o0XgOU-^5@~S zE0vI4EJzIl@Y<~a;aLG!$3Z30$Oi~(OT9I7S&uB+PLLu?-wj~t-{S@eBJWa`o<0Um zAR%wafkwC*IY^I1@cN|NmuuP@Yy**2j0UU!F=ZwBPurfTymh8uSq^rkTxZ;MpTCZe zPf(rD&{8-M1`{`pQ{d;pV=mzbxBDAHBE#I0tph^(v^w3f&%hmgew51-0?)q)8J?qh zLtOnO%v!;{u9^|DekhjJC^RLT%mC3cPLCO+nLmEqup8{E1&u3&dIBLUU!h6$w#@DM zIorFUsON2gskU4H>;qW62q0lfBX$kB6;N-3vCn)biYc%t$!6q*O`068P7Xj~b17`@ z{x5L7rEq`yiKrV-=yXuKk!xTKYFP*|gE#~mRP+`;hJ$1cDVU0#aot3Q91)J2DY0tyjn5lgpp%2ltNT7D?Xv6sv`)Q!* zC9d5jAprtFUDPZQ)tQ>oS(*kDV2Y=3={HmdQ0TeCdI%GbD(=lD8oL}S!xr%52BTzQ zya3eK?KA2HkM}P#nQwU8TWPvTFdbLuSAfPO^x6p25cjF8+yWE4toAIXxI$Uqf`$s8;Uf20Xhn@=0Q53Fl<$5lDy3!oW?Gxp^IeM zVx!;z*YSqJD3_~0q|lr}jk4pzx?Wi}KixI3JYBnhJu%)}4AjoO`qB!kcffEDlGS3B z-Gh*O5poym?F3TUin`TYH3_WK4eX1UVLAx4TTcW~xVpX5+KUL?Lb&^DF@Xx>=;#*{ z#{CF{D2bemf}ima$OR?DA&@U{hS0S7s|9Df&~>{|e}(|TFchcIlQgv45bC4c4J9vA z+k{{y_<2a(v|E9j^~3cFdm)_ZVyVd}moxxQKILj&1z%??@Epw~K(T@+ns7uxV*s;n zolrGnpk;3PY^i1xXwVOuK;Gs6$doIX^9s#wBbGpDw4^X&>zni{3~HWh40DZ_VB@&M zlrE6o@4GWpBpIT3O0Ck%n#iSqm-n>Sj_J%kR4+JAy%$~AZK^)hRA**E?ncSRjWUi< zO#Nh@-0jP+{plOZ5+@EXUa>NkeYQqYn zRz=|fE^7g(tQDGBh$yPl6?WcV0InfNlw9_@Qvfm%p=OZ~n>?CPB1^jW8mBpx`&rL1 zptk-+PkUYFwI;pz>Ek0-$79Uq2kOZEZ`6M@RsL;A&Or!8z`pjgn9aV%2K2WQYLAB2 zADW7>7ivyr>?6QmED-`5AjHAoRGeBILS&;*2+-h$V425L!N{ULtUsEWnhuV0ku9yU z`!_3aMJu3mu=IuOn)T~#$y~}F;aCs2Tdu(WxPyK-#kK|sJ#se+WPLJ8fVX$4nDBGi(DpKG{u*tYT$O&3uZ)^J&pkm<+V<=Z9Z zaR3DLFi044RbkksFcK&X#uWxL@QZGMIeLyot$+La+)Zg6yIDkvI^lKYMP?8D{-$Zx zjyZkGyxt{r-DndvcB--ot-A_PuzT!+}e?k+`!M z!+QS+S97~?GS%F83JdIK^f_p$1Nw%87%lo?jIJ$Lqs#h*<7Mkj(m@>#I(d^zszlXP zo-xe5rGM*< zv%5M#Q&gzBq+rHzNo5!w{4lE<3wxnhQcw?2Xev=A!}dn7=%@01nvOC{d^B_oY8D0m-a+oynf{d}5i;%w>5cQB84Le2kNU`<|ptFF` z^M%^!GurIUTD}TXD;O7rE;^!<=@$t(GTjhGZrLx8FMP%k?&{Vv$`*z_yJO@65G>H| zS3wBjE;+z1N7n0eY#=IUd}oS5<0!LNVbc6ge~JqgJ;(E4lP<3Fn_qP2XN^0!TFv0q zZsD1==;=flL|{Gk2RvH^6Qe-#U7^7esx443`xVA*pnf25Z3x_&C)DbG6#or0?hxvs z!fNA9hQ6>KV8uY2HR%^LX93MA)PRb!q~lb%-d5;t&wHOkir=u|6YPF~Or6QRvg1RH zBh?~X9cVmp({y{-6vbkZgb7Ew(Ct}pwf~}TxC@2D)tpCkBsEiZLOPur_$<;tm}`2b z^)d@x{PZI8K{mt#@t){XFtT^|q-eWh%lA@~bT0Kj1AQ17a)hC_Gpf{gh1(TfkaGW5 zI_FE{c;q4dkUjWhp%E*@G*_YaSZFX0P7iNPisj;JE{=x11!EN^{la#(x=~!F(L4~X za`ZPqhw(!KUV{naM?Z5GeEo8danxz^*#f;>XXuU|gL6ugz1!n2#8PsBp68Z+c<=6F zE1S{X)^a!QA3NX}v#ehny)@@Dd+PLiU^2U7?hc~f4=@j+#Kkx2Q&_60^#80DAci-nS$!pOqzu&LN;>0JD@ma=j-k`Ud+Ol|DE}< z3;cBz8hNWmFHU$lP8f!l>hW6gUVxnMqejUJ6M+J^V1w%iPuFuzij-Qp9!c&9W`T&b z0@SE5UI1zWAcF(oeczj)3T*4q85d^c`^)|(T&Ap3t5q0x8&vt77xED!aS2$=u%vF} z8pMLS`P}QoH#9kyHXqPNPbh!a74k)_Won#L-!nhA`$J@VSyDZWbAdNZQ(9k;S`jRs zQI~e8FF7ozzLKY|t9PSyj$DnUkJ|kCenU_zr?tU;m6op%us{GR5Nr$M7d{cPQMDX| zIP^W&$wn_Z6AD2VS0jeqHMu9&8!7MX?^&oXS%Gnv^mDk7?#R8fLL<5|`VVk_%Vgvq z!l*yFV^==tBYd6ibf`;Rr+1XutkB{E#@PxS3%I=vxfTJCmT0fCg?jXOgJ$6kyI=9y z3TC%3ap*)*C7u2wkJ$z$d&e)sGU`86B}O5LYrP-6QAjaXVB0n9PYT}DW5IIt%(@;@ zoN5huVi-XJhPfMy;?=8gebgXp?9*Sl}8S@_!Y*W(xJT_|@l z{`qxupZy=F>T8Uz81&fY<3bP|M$R$@@O(hNb7j=NRef2WCyl=7H>=Y!gpFr~`o`za zu0xCv0n|Z%bWq(O_m6zM4iv@34i3iSvf(W5HaoWYMJ@#z&~HR^c|vIZ31|-#{B4G7 z(_^?JI=)<8-3@pSykMxHUgjF`K)qP*@3z~t`en=+5Y7R|tcq(Lc0X>#7|$gqo#U=$ zPviQ6=^X2vd9+<6KB&$*MvC|+c|fO$*T7S4xLTI7{=~|JzKYf5si7xr0tR>mHhMM{ zr-F+M9Yus9eZNh*+Y>7M4(o9eTT2y*cPKg*vc6KY<-|gL$HbxBcR0UI8YZ4yu@PSj z4jWkTN>eU1s_9tz9w(VOB?oFP4=9DTIM|VfsBguJE#>+gq#9X;l)|rj#11r5-%>fk z6|dSkKEds88a{4IZHYa^^TSD2ZJFfFY1gYm4pEaG?PDz5i8Xts1e<8w!?X9dnx-c_ z^c$|>@I)NNsIrF$>6x?L=`4iE+0)AI;@w%#T&ZEP7~7K)YGjsY)RAEta8K7YV|?5? z@%3TVN!N7!yyeCAZEN?D|G*)S=D$yaWJVV_56|h(@@0;$_jQn<--2>%rVp@T$RCZ}O_q<{pVjet&(Bx@{FyUgr6Ub6WfR zhbP;SeW_JwB<*o#v zOJTBmgi9CZ>ksNi#)>X}ljg2GxH6BCNCveT^Ee`u&Jq*Z?n?1pi&8rgfhlhoAvG(r zL5COp=QCY9P^LP`xErC!ida3QTjmqy&)l3ki)gMz6Af+-U6no>|Co+GEcBS^GFLOJ zMwKF}d%v8b*76X=k@LIE5gYjhT+vEYCOYV#nrg-$T6so>$~=lHUy^K#0#C`z$Iz8H zHh0|^Q!8eZRq-JoAAS4t)zNU(@A~zH++&f! zL6&SrU~DF#@n#}}XdS>%NOV$>gmXm+qp?YbF@l6Z17C;3$r|2R56ZDWcbOF!&rc?h z4U*po)k<>tP?fciQ;<*&(dB@;g&c>RM0G#r2%Fa0XOfj7{mC|>TQ_(0)^s0z<^p>a z%%^FU;`BLQvxdZ*bjTE#26-}-_Y6w+Ft<>E^-dz)Mh@Y7YrRGQT{Qc60dUI)NvZ4}qtP~^ zdue^#4nSgfjU`;uQBMgW;WToTYv2PCZOMXf5a$#5mGzOM#Zc^0DvD#$sd){I!lNoJ z@j(S@V?kGZ>(JK!bO*^V)jds(c_U(U071*0fgi1r`gZL{>{j+~)69h>#&*KxYm_p2 zA-%wb!1th3iZF`01mXjraV4t5X5A+LZG|IaQG><0u)4CChJWde?-me9zGgURU|6@5 zRWP|UN7711U9a-g7@NVh1!cD}p@7h?TcIAo$J2WdAuWe5BrE_Vk2ZjeOyh8jBdSyj z9%0~g8-;=u*R`e;jO_`lO+V~y@S{xXHV)#pD?y=~pPC!cqnQGW^&fM3R_Sta@g$L^ z>WR1rm?j=$^jdO`9txkyI$GlLE@G>8Tk)~*yk^)>J-7|m=2<{k!B(uenC8{i&##y{ z#r-~L5NueaggEjPvO6EpbT6>G+@Vd`#lKag9Q&Wg=-f(s?@H`O4POw1;N*0K%0~h1 zrD(`*w1e#eyHa>4E?ws8)|;U5ORf*zVid56nFjr5MOvQE2x=BA5F>)>CEsfr8ZIk_&eGZu=~{_ z=0bdC$6@C386qi1mS!|kdXNMpYG!iuOd14|mA+gxPo9vz`0ct(_MsslE#p zf4yQrTEq7qDH*l>{mZc`vOvVQr2}M7&{ew;r zAjxeLpYp&1r`5zezZ@Wv{YTjc>{KaNU3Ix}+eUp1d=J`N&rDM*p5e67HX;XB{BM5y zN==UMwvgDDI%Qpd9b7be=l{2X!dVU;Zg5d*$&iFIP-N`EUggCRW-HSl+&K8F$e>8s zW1p-2^Fq`;(K5*sB{_bCDUQyX{3XQ(eq~alQxv!F=zhP=^{ z^9XDf53KqhGE3mttimqpLNUV~9T3Sd?&z{v_|92+0mR}1)KWmZp$)Ndr>%|ZitB6? zNYb{JP|Rz6v}BxX=GkD=PWf%)mbT~4&{a)eHr}Lr6j;?;Pg&2yIsCd%pt8o*6UFl0 zrbA~IoBsN5TjQJ9=(T+4N|=H_oZqV!7}hwiyPz;0YQ6aqf>GdQfPGI|N@*w|5}la( zNO+?`sXdOENGDS;;W5*r5Cd>jKPsJO3e?4wO$osE2rODK(j z;FtilCD6@X6YnJNC_Rg_Lex;@qyvEUtC8)LWGfVQf`K|d7<>-LQBtlTvdZK|8#&(m zBhCv5o19s)0`LPQm-Mqh z1|OV)XYe-p*33(bnOnTg268r)pEJ{NNSc#}57Jx1YcoW7ES^uAE zY(qe-s*jFj%w~uvWe)p)xDDUXyIc<8-cF{#URAwohbs8kSe!NM!ng-Y9$}AaXum9tL>7LrJp8s zNrzluATb+gMk*^|qSi&q1?%s+h`L20JXEl^1yDCvsub^91F;Gd~6%h!x^!sQ}=FQMw@eCj_k+6Y29jUU;ag<$#L%hC~oIS1N|5MzL{RN(0@zA7mW{k8Ce zTF2Oj9elNSiP*18(`FHl3V=#viODy_D{+l1ym@eaga7x<_j!fc<`-b~?xPOZ;ejGP z*o9v-MnNWk*H!izvyAmv675q!6RUv(4bfcwy8r_O2Tu<~FB}ff7jgy zXn8ZybU|JOA*`-B%ldD zTr&L?c`q_I(-GW7KMro}q^1tmD({(Sq`FNW1ag^Ny z9j^cC4j6xh6 zrHli#ajd^Hb%vU<`m0hM(}}kz)oGx53qU)LYOJ~#EkXZ>@aaS$U3w6JD0HHC*SbUP z_02q@4j*760G&^koyGEp6kX*~$YDy}9Vf*K@DV%$*rxD_Lj^=5W;3Pm9 z1H`QeE)pRZv0N7T*F|!Yltp=`q^c0A1B;q^AH0d~9hXxYfs0oF5^Gh?3Wc`h-NTSy z4@Rtd@6u!w*dDf(W}U&eoz+b`ItF~x`qiXJQPf4)D<>wm+iYh=uA&o}d-k1rQXke< zFIUE%IblMuCA*+tOA)S7+1>yHHGK6Uc|ZIbyaYRUD`}5mjWfzg85uu%o8u%OaZAFx zAh=9hJVlOU!W1kwO5)#D?!+6z5igDtSE*S4U_p! z`3MA-_q`M}Sfp4+$qg91AU7(9d8Tlh7L02s;$%hPq?-7iKs-r_ zFJs}{fS3CGb~-%C$f9@xAju$>4TF2LKpR+d6|m3*pK?A-@%sMVidE#biM09h{k;N> zF=XX&7A0S)vFo#1i=3P{N$FM6o%qx~1Z;>>kGrHks$41IlMVpXa z+>H%MtD3Cy88!|3s-q)Lo_Q+s2|D+XdB9@ee9|AXP?-%})h3Yjnd|-)b z?gJc+u_ig7`451Dmj)<;BOMMf78FVenZA~C97_Y= zARqDoK&Q04Zx=R2XkwxUTr*$ksq5IR1iesP;yhWZBzH$RHS$S4?AqXxf-&R|E~V(o zdeS&+i0%M1cHkyr<$M4Ji#Il_5UvtrIkKZ&s$+(C$#Wav^+Se6M@rn zv3`6d&-#T?IC-?yh}xin7Jm1xOivK8TZIyVIB0zJWYl74hX9A; znz7>DF3*( zP-+ij+cjBU6VCr;Ic>X)_ zWt9zqmIqMsVL~rLZ$of>tggrj(kM!k-~Qi=+fR2Obm~`a2gR%>H}6gNveK&~U)Jl! zSm?RDK_}J(F4a{1=2T9nzSLT{6?$mYzHU^jmN2BY*KjBtuZP|nAqY^SuQKvTCyYmc zl4BQ%Fj+gUil`)$GRb!Gr~d}0>99Vl9uL!o-t-!xv<~3AIcp6h2VBr!!ltUqu!Z^_ zxwSwBJ5%=lwxBxEq09Fft`z+87cMv~y-xW;WQoTd>jXYUDj&RQQ6vRwo8WBhqR;c* z}-+I?o?u`*W3KuUk~p zJmlrAD6{GFyKRqqv#(x$-{RbQxH9qm$m!Uoe@{7y@byJqbvi8J3!w8X)cwZnK3OXJ~4UG8~z!!lrGsX{BNH>1)e={5YHg|8Nf6!F}K7 z>+yU(9d%r5OwwIjI(!ZMI<`uUcXm{9s{aL#WTJPpE}S(#{PbG-iI$nFc5vI0B2p$OGhBLzj5VK%Rk&P}5lxVN2VBORKm`0oUj`+CF$=7Gase6vvv7sW|$K ztQeYlA`N=e4x#Cyiz{CVo0HPEYZfbKG&`T$dHCMY_Q+<5b2|<{aM+M)o|Ur;BN&5JC{U__=+j8@PH~FpQp@2i_6#3u;zlV=Ph<_#@1s{)=n}}D& z;dn^V?STUF09-gF13N+>0j_&`ZDnMlgz#z^Z2|y0K@uQg_&q>A3~f%lrQ}4xy-QS8 z;qhdnl=$^# zKR@d^ew9CQ^HUScri>I-0$@M;SGY{SjSBOU=F=g}u%PjH6pn0*fMl|48_$@ULQtN* z1ON$v;}G%zzEXMe33aVB<={OVbeI^^iiQ+1lyr!SJO4$sBJHXvRKl4Z2EDM0K!S=n z3sn$gbNbeJtCvGBfV}PjT&!{MrG`k$)x9_D^2v09OWQXuB9)IeN9>ofYwn#^@#03@ zQuG^2a>QhpEYcJMwY~Ps1!VT-NjnG$aGC8hG?=7B_==RF`DU_ou}1VvME+`-XNG6v zpQ;Fht!r)?WW$a-jiUywjq+IF)9>xRf8K#LJmBH!~VLZpk^5+~K>SPT+NBk43@QUMsx)l6On z4GLx?#QNc?%{1iG6?tcGvxcf8iTmFgUQoEPRFTr69llmnOD5-IKei=J&92@7Ddu0MZnaBqNzDa z2SpMBaul8-flY_-G$aB@JY*LIiTRF(XkbNZ5DRh*5GjSQ)=pdk@6J0UVbBEpxZN30lE;B13jWbYrGsE54s&ulkgH z$9$83qX}&#zq5x-o!Ou)I0?JM%e%Tk0Ii3{v8@l;wo3wO&St1>Z-It*id2c%&d07V z<+i6aFvHg)r4;YSIo=tN(l)0pmL>+=+N;^J&9M-x?x9pGMPtJ@Bj+YxuE@UI*`8jo z$K!je#a`HXLNDTgj5y zHO6ZBHp9P%0>kU8%Qd50lU>}ZkOIj5cd~8>eI8)k%Bc?e3OB&hF>DfmlO+Jq#;Ap- zEE>d^CywKiP)f8L)%(|=S#yANf4zdXJI_^7#6N0N^%g)jMAowvUcqK!cL8FvNzjls z90XNmh*9DKGW+-t?PebOtT$b@glLo~&ELD~1yg!T%s2Q$k+k7J33Ei|PTshgi(S;`#*(hn{Ib>@^Aj1ve$dMffkq#7S)FC#E!)*bx zsZd`I6j5&vS;c)bJ8{8IWH4lkMUl|1e42Eg5Uy8;@_(Sqkb25RXyI-B9n$Pop9|o- zi8JEIK8z~@Ub(wIH(=s86X^^bQ=k2#@b@*_!F`a5r7{K*-$yps>LqW-{@F^_{^;Vk zxM}?;H~n_}yTY;gI7bU5#KGSaa~GaTJ2B2yAyZq&F9jKXSc}my*=uN?e0?-dQt)6g zjsCsbl1wwpB_T}kZyH9Qw)Y*7O69@9Hv*7rZ0Q74{ucY2G>zA$@CkqDGn~IKx<9 zoOu$d)$Q;&o$vE=PQ~LTM34*n`j&@rq%rC*31A4&7KITocUq3abvFS-4{5LU(PfzY zm5*~!TDzzM9wI{#U2JH8-?nimIFpfN%msK!5E&|5f(t+<%nwj)B?Kx>I_}bBnjB3P zCV)E#As#~bp+2||E#3~WcV;1pvha8+JnJJ?e!o*EvQH;4-(i1xJJ9k@!g=UfHZH1Q52*tf+9nKpjisyEI%|WMbuGD z<^!@+TRD=-lmp~&uIi{ZL|kC$M}v5C^>zER+yKNj0>YLGe{YINj73;Z!IQa2iV$&v zjIbf04w4avMg7(!R3;S}P6H265fNOtJrC|i3wEPzvk(=j>zl|yndd7pq5jN+%`y?l z-1r~Id;(*dNZTV)9eMlDNL~#Qw~$VplBGKmk1l$h=-sU+mpOS0%FBs`Rm#P2WOs05 z^IGFzWchD?TlokIfZ%#N+=Qr*vUMm>EfUl+0AkI8#F#=20HlX#W+Fh!;`VCt5dN%$ zEX|$254m|$3y(5XteU&9>kW%FYJg0SA9G5>TL)Rd5^#?SJ-2_X@o#4SQ5l8XqS zMechKe;(_%XExb077y|OZGTSx;cQ$S|}w?B$A8KpizNy^dfGNd4C{EJ(DgH0q{A=Dgg^8P z6RC7MRHzmaszCG*$e7Sh>bmDhzY?84Kae$`XTtkDR_WA)LsBL!Zp|m;IF?U z$XwVFHZ+ckqzGVfENCnR8H$6SqJhyYR3-&^kOl?_k;edJ96JZq2kVS(GHk?oou8uG8KVS0pm zhoUBIdzdN1TWg?x`M=ENn=P6=Na#n1tszv01U02Vy9}TY16qu5$UxHG|D6OBaZnYW z-d!gEBtbx`(#Jwb0Ama2H}wFC?j4J5Vtfjj2OJQ(#oeP!eYfqmEzWR73~A&0hg982 zP%;~F9cPRR)X6-`2>=ODwVH8?zCFJFWz1)u&2-A>!~ zGEx(npSwq@YvPy2XS0E8)zUT_k|Y07r$;g*_0D$g$ko_jY8UPAt331YmyEWQ?Dl)x zO?l8*h`cvl%Uh%8QJYg*RL|r$O^I3goqfb$On6PdbB%d{ksOq300m*tKn$$G;Gh}~ zY9|BLz}0`N1|o27YGkMe1(MZh2&IIBe84iEls$Jk$WA%7!t6M-N{kJR)j%a^5Yd`g zX)6SxPKDgsuuUJ}9-vjauuEM!;YMUbBl#-_D3C-N(p3OEDS!n~k--2m<^Sgc@K_#< zBt%`F3zDE9aXf+nzgA>-_NkHMT-o15(J=HL@Gq9ZOAp4$o{2u?b+0JbsQ}ZGFO3Yi z!HbqAc1UwjvZ3bEfncoDhGR$)i{f>a(hHru3O!|{;6#s|v=>cH6mkxSJABPLwcM=y z1QOlreM1o%Fan*>JNS=qFgjyci(3E#pf4Z8EeJ3INe4!TNQMAPEC@&*xm^g)D~Bi$ z5g>(BYnQ5~1>B*J%2SF~3=o+QAsTFW3PSCUmB({0h#MEKz=3ZW;GjbJqwz!!CqB%O z0(ZwD6R8Lf0t$mc(QqJxjfy5CPtcH0M%&kArM7%wJ6KX7QB6nZ9h-p0uOTvDhN!*& zv(}H$9P#t&%h$Ya9eT@k7Q8Bhaq5axp8aAcy=VLwVnFUVavZm3T$Mb2;GX>Ud!Z)# zWgkb&P1+9;j)X(lK5ujLH|8Lvr*3KxpwAOrE*l(_SA;s!&%sH z!`DL>K)4Da2PicZ9-Q?Ueu9FGh)3B1wItjYd_FMvAPy0MLrM{m{%qJ@Vl<~^j25Kv zrO~Q2AG0w(vun95{_u@MQQh??2P=j%-axxOIF1GhgKF0`&scRAo!97n8*}dd;0}^T z@ObyZhB>2$b14mSgOx0&tgzI>^Xk{Ux#{6{ubbt6X6;;nXpo^=)U2Jx=1)$9KgGa^ zw-#Prg(lKZ7@bgp2_fg50eQjg06V~&42g}zUsZO6@mwJckrRrhPI8y0Mal`_x>c%8 z`iOqI+lifUT^8My1a+qr$napHe29p=_9S;2kl}0ZUMvnwC?ku{MJL0A~6x!CDZP7qmkHDWpL_%<-iY)^f%|Op!vF@OveKS zUM>Ht3ru}3%kWC>doyg(y?q<%Jhzgb;batv?B%OfK7V;g7Dt4X99j%pD(v)O|Rlx)5=aiU=a1f`lv4 z#Hc6%j6_9v2O#b&!t2)HojOuJ@8qpKV3se&`m3Lf9F=iSyK%m)PCS-}Qy4_J=e7sj zpLlD1=*?n+FL~?zrpX`O?GM(*_JxtpqUDS!F1pm?fI%$qQ{GuTOybD{LCeqw5ACnP z6AJAyWtXU7rXe=lCXZ0p{}+IznV((rv!tXSdb-+(+XAg&R}H3jB&x!gaL zjSq)-@Bke#ggP6tQ*8M}t{Mi3K&w^T3txM%pfyEE4;<8kj}-aNNHl~h%U+y{2p~ZY z@>U`QFspUcY4$A|u9ig3*~bkw5kR%&V6qkDN!1X|+i!L(Z(9h9iE%trw@??cYk>8W zx`!@3p?WVQyX(E$?pU`*eaO$TQ_P>a)JbaSFU#4b1 z{BU7wD91UAkg0Py2&zdfhm%|1MFUTjKIFfIh#1jgldK0P01s+mThiWVp}_fmn|rko z8FpdGgu*}fEL8xiNTWOP?x+jkUVL9hIiN&>sMCPXEr=U&+JI%C&U5e-!2S3i7UeI= z0w@~*d5n!prl2xds3T-#gb0}BRmlrK?qf;ahu(hLvAmMSYqb$TA4NIw562cp4?l>d}kIB@#sFkFw^u1$t|2+Jt|98U&P0Hihm zk0HQvD99WZ%!Vey6rdhNXaoTnNJB)CkwF4fMK02d2iqw)u$>Guqr6x-Zf(v>*X*51 zP?z}*;yA9QN+Mcx+`EO0RL*>8{j=cdFmotk>YmAzz)N!jf_mXC~NQ%KV zIcXbqx#G$O*<#*OagrCTl7A3H*&<>!D9?RlHgUy4Ld7z{`GRee@2%Q@4z1FD;SX%S zuRgpS`|9Q2Q=9AiOG|?KWarLcZuY}`( zk!Qwo(0cg^();C|1oRt(qUNRIw)FOf~ASpZpLfo>V|UH;j-t!h#Wl=BCS~cIC;E`#Iw}G z$t4ag=PT2$G!&u;yht(dWdQ?A@Lg)iQx2zTI7s+y=(pwun|-;qnK1C*qhJl!0u9LS z1e{j+@xB@DfNv*=4L`||!m%pG&Dka|yU-f@GBq>mWWCvu_=dQMNMg03_v$S>B?{M5 zpW~fr+OBw!v2m&4X$yTCVm)JcS!H9QVf1!sWPy! z5LUy1!cD1Z4Y`U`asyI1Plj1Wf}7f(*|(|x`i!ZPsMJ}mKCK~7o-N&BU#%ZS)cHo; z`TNL~0}0?b#WrC^BMc^cY#eIe2>LUNQVIjgP0pV|mb`;`5x|XkYGZCBCSFJQG)yY2 zJvfRU)*M5zeVJDNm1lVB*n-97`5zbVhhG{}>O3*%z_w*FuYXKrjxuqIs3T3?!Zdly-NhU{Y56&lpg7`bXy&UEG%7s7a< zSmahCVr!Ykrb}2G?>uzI7ODszQl4V37omD+v|>cEKx0%+Bq*xX(;YsivVs~s=-49% zUPZmdQ5N$xrx-Q1d(6vOnGV6<(resFZ=@ny;Ch017Xtv*-MB|T$uxq`Bri&WYRnLh z{+xXrm(kShcHG4vV6<$aabb~i;=d7vvTKc(FUz){P#aPe*52%el7pQ&<c5pw=?6YfT-W-epY zg<}NStA~~nPx{cS?Pj-48KkKTZPn-HYP>nl+C?gPQf!WP;3FnfNzF&DLk)PLq7y(O5w_CV&yjKE8 zNfTLqqz$oZ_kmN2zEtF1u}B<~2-ozc<`OMw zSiemkY>E$jUJ$^^Uaq!rOI`5l?rNXC%68h`ZX?TmOv5eXTpQm;qr(1eU9&|YUE01R z2CaAxHOCKKtGKPk^1t25%DP-JsLTaE8v$*m`vy`qQy_^t#)SHJU1r3)s;1iyDK074 zlNj>-Y`7i{g7ya-B?D(+I|v_G0)56hzZg*YFduf_DR?6Vd9XyaV#-ovt&ge#4)rde zG9&eM++_#lj@m)%3AvbLlC`1gIOr^7=n`$=2WfWTMI0Q{B@o+}X6t@h$Z*BwBXedR zh%X3Hrd17MQ35-~2@>7VG6F#q#1usGp=d>sd$>6v>)2bPQ2)39u|)#(f6oSgSHT(c zPane1>MT^h(bjnAemK+vI@E7cm#b{JMG#ZBvn#(gpbuT`d`;o2DxPN}dKzQgfdG?X zu|>zXzMrkcDbMBbwTLgz52M|2Q02$DFyhkrSbHLa!|w#B-=%^rSz6CZ*|71~MYl35 zc4te|(1YS`_6-82=*Pj2YukTx1zU^8E7(q&@BPP-3uyZ&f{`EzN8?`h?C-m zz5Sop=@mJEgCh=}yhzdvlMxaH7)Z||$S$%gDctQEEG zuCd-qd1ZgI`o9mJbZNa;c$3cE#D2nZxSUCZ-H^=#cNZIn2U1kiow<|WJ=1j`l%rj8 zF9n>HDgOPol2%WG>jpx$uoMyl#}oBuQ|M@Cl0sKMVGi~?>ENk7Z<0Ssq_ydMJ;T3O zt@m1I?%ud-_;C~zZr)HvcAl5HNTQw5?10Xz*|I&k49RPbCYexx@hQe3WQUk zi}~_mb~uYVI%bQ8u&9a<6H&VOeFA7aN=Ht=k$;i|^>DHee!I5l%(W|6t&Eyd?>}GT zjxm0Op1j@hbzr7Zs)90}#n;poQwbf;SjMEp204GRV*Y!lIvk#MhT4Xa z8i5Y_b3K)JpMuxw*ow7gLAyjGY}aV))mY(C%Xgk7_P@OBa+x(Fbqli9k+g`7Gn0F;i}E!40WQra4*nr<3epPhs07ocK?#*by+hyF~t7%z=tYGeyh z4rzN@@I!Vo?m%_J3}AqQoWH#~di;4){{4D?Fy~K07xKxPZO=siRm%by-?Zuv_ZimM z_$4X4iA;zZ^Z+w+8!V1qFs1Vb2P(Ez$n838_woj7_RIYS>4hshER^up#UW71e$ted zaAY`;3!M)SK~ltQ3oI<;^%^0HLYkoghk8!t-h`B(9Xrm$B)f64G-U1-R-XPPf_928 zgQe&XbPRz8qcOxdfNtPL*))33Ynm?Wtn3V3o(CZaA<6)BZ^000lP*6*-^bmeE8*ex z`b<;(93vu4Y!imrgsPJv@~rEWVoc7aoZsADePi^1X-y6u?Ue@pBO`$Hn)*-ubtgLT zb`6U7+@wOZbd%0C&B^kR&QWjf>Zg7g%|e_lAzUUmDT4d+9@^cgsAUHz&6bKgB(3XR zyxq`&$Y_$P8{EvHr}PcV3yWmx=-*!hzhvk#m*vxy|3Kte%}VDXzFu@iHp~`~ zxQG$`D7Z0+W)#;J{RxLBj>^>A8&w(VPwi#mCFx6&lUq-=!?eZ(zs*@`>~-wO+B`RW z9=EGYS9Fc=F>65%8~qE`h1;SNhtEU~+eIGl7<4rXJSQ3Vnq~u~%Mhew^y#Ut`m~M< z+Zls0)EPNbh|DHNhT_2Z3b08<_!$RSRK?=P)O`be)B+aNzPXst)wS7%v!q>fwk@2+ zC{g^jLI-0&{Ha; z8gV@FB6;NUbfT|S31#OuBlHclHBjEUqID*zu$oaALQA{ynd4s*wvasI`VzCzTH=DDdqHNO`+ zIP3#~Ckm#Sts@`vcRLi$KkbzxJExBHO5=+Xy)jRG%DHTtXc@YETE*OiltdjSeQ^+K ztmoO~p)CrEnUT8pbZeww!(n)SbRLjivb(0P2rS{~k2YzKpVIKobR~{#L?%RZl8|N~ zcy{xh`#I`Mw)O-#9tSgB0z_Jy`j8F#Lz#>K_hjDf^0n*V9PVZ_TN=I#!;5ltqUOU>){pl8U?>?SwF5yzBSj0M34%ud2n9l=0gzQ5=RH|8A zl;Hrovf<-7t~a5`(`_=BXCuKimZCZnDizWVituqo@@UN599EQ6F@oig*NmDi=_B~= z<8}|9&SLrHUMfHFr!yX^2X(3Z=Wsv5rn;B5{VQ#LmafZz{7a(S!`fVD>36=-+o|`| z3+T&yTU&j&WWghda0Gwqx>`M}RbMiHbM6@8v6CAv1#t_hQE<*VFz(~tD~6IcjB#5f zg+_baq-Mv)SI@*5T2rMogk%-JCc3BFgAHf-8vKGc=o`~9F;MjQ>z|O4w6?80Ir=4T zVBs41$%*G}oItTCY}KE@^aiZqtQ5>$&(Gt@bnuh1=S5}dPc9b(@s}|@OH1=qhB*`> zib{jH+Nt8}6^0=AA-b*QQ(I1s5(gqm%2S3*^k^_K0vgehNerBk4y=|si}9<&{QO$* zbs@OB`|`Htme0yKK#^R|vHI0j81&l7uc?3E+VwX>9{s z8ZG;JXb^>X1@so>vS846e~`cS1)KyY`WsC~AFGL0-CwiVMI@!Va>jve-|0p2`^;}y zSw0=0Yn#JVHvM8R&@X5*75R5M^iAXgJMe)JZK?7nKA^eB%CE-zTMR4M>UCUSu#)t` z){M{h(xM%Y#tvz^AAG{X$I0IuABYL!2g2m#U46f76~{Q)Tidm;4y!5eIIlCDEcXJ9 zk$>{KaIJISqt|VOBJQRKRr;YK0iv^0vhUh(Kmp_fzT9fI`arCzj##L3Aig?JIy|hJb`We}1JdPa@-|x5b zHaxqazsfw);J`~aaDyEgNgqi^jOFMY#3i9AX1e0gSXA}p9GXUleaOnEVVsov|Mn9H z#<&0d17`I%Ty^7coZq|Y2*!@@np31GKrZx*Ybc^uPsQBGS%2=hRVO`cDjl{xFX_ce zY0iDCo0{!23`gvl)sM~8<%aaNBAzxT7SG*rgnnl>A@$KA`B~k|KMr~SemzXnDoac(+jZDM*CA`H{3euSH`O3T z8I%%@s=kgW-zS@`Ja}em5;yOBgu(IXBr2jq)h1JjfbG8OzvWt<9S9Sbxpa+HWA zMuwF#x{Y!c%>+^>e&00>g8^mzNkxN2yyacI!(F`NOD((iDm&h4?^u=5`=qG;PDWu} z9>1{}#wJ&bBENC^z=~6p=R`o=K%Hgvr5ml-IYz11B@KJcad!Oxp+GIdV3wQh$`A1pJ$k!p`CwPt3FP(iK)|@u6ZL``L-AS zp{>;7HmP|d*{i$cTMU#+)zvca7THQc4A}#1%0c5wvG?(@?{NtmlKx*L96w0xe2X)_ zC#U#8Mt+r``^5;qZl$zlv2ESLdc)fDi>K{cfbVL81@RttXkUG98750dGp8gv?XI z;^PkzQ>IR)jU*hsOv&j;Dm+JJu#Pf{GUyC?QAvJ9<(Z00`K4EKYPzZ}Tsq&{)zZW5 z85|tsO^naY%`M)3eDB8k<2&ompS^s$@_GI9_y7Ix=jzWNPkwC73)e@#er^_i?*Gp3 z-WVzWc7^`+LA>yGz?W%<^{F2}ems7>)ZX6iqnQhC0sqh{&Rq6*4k%+7I>T+4%*ScD zo_FqTyjhIjk??$`x9Qdyf_;&SOJDPBrM^!`=xkrhd@b?N+09n>g%}+ZdZF=jHZ42_+tL*L&zViMq+rC)MW2Aree#6g(@UY%XHjlXIv2)$T7eh-8uZEklgkd8mF;B`T#g$Zt zkMks3weFd09$mS(nDzTn=uh0qI}N9@Pu>Yh$ypuQ+IHlBp}XI&e}>-)|5p}f@e=hU zea9=s3s+x#emr{c4EKe_uk$UhOKsj&X-(l?q}{)bv&Wgi z!Sy2Xl!A?1yldakxr|Q(T5ziLgr1bmdjF)Sb!h9PM5@ii%@-CQ{@72cP?%DV6_GUC z#@*C}vn{(nJ?IU|?)N%-$Zjpo-a$2)Q;t-M=Pcj87%|8E;Nti7k)G8T>L#Khe(SNWtJ9-~8`^xm9)B5h{t)~SSS#t&t&F%hp?S5I})*r!7Nm2b6*o0$9mrtws-syPR zwNKaeVaDhHEY^CxE5p$0HRljY^@M}bno0`!)GbxJ=cW>BpEDzo`ptC{?QIw9R?r3) zOQ3U>Et&Uv44T=&bJnf>hdfp7s!qgMC%doSR#*j!-}A;y42?ZA`finV&eT^L7@X^{ zcQshc{ZL4cOsQm6d6y}@T6k7w9W*v_C-J1j!pqC3&MH0XNwXK82J6XB;|-c=nu%>P zCkzb@HZtyc4zHD&-8pVo#c-NYZ_;qYyT82tP87n*natM{liqlr&uI11A9(N-@+o~|YK z43D-H{6$}5r~OTvTKkoCT(9v%M84k11&^yr@lVt86eG@?GWFIoD%ciF2VdR(fijyB zylqbY<1%ggFWu^GO;hR5*AcNMbFUlwPg%{`)JhjU`B*X{aeb}-N?C7E{q4@?=}T|i zy9xf*rNGYprfFVcN6x@*zU5i$KDpcz`rmGa5!dCyM!B`v?BBBLo7{Y}C0j`cfvB;Z zmB0IghGbg7GUhHTzkY35Oy^CGT4WtzP3MF97Utu{|9ux;ne#euD4A=orW-r;jV^h# z5!nCE{Y#)sI#96jqLl=pW?XqJAEm>Va5FH1u*V<-pnA8vN&^4< zf_#OKbjeh{hPse|IhGb_z4WP0V0d!dZii378JtJx|55U#YZ@e-;QRHOhtLOTkuvA_ zEu%g9nC)A=GOfZDIkyORZ`mDZTl8ZLFjmgqOla6g&5NUsNjJUHeEgcy>a88UM*PrZ zO52W^kN40zlXzBO%cp}%ZYdoeGm>F(Te}|<_Aa9+KgK1SKSUe&&YlOA~DBys0ACy)HYVaU$avf26wy<~$TFX!sB z&sFv(b-V8A-}$)x{7|c&<#?f2mEG`SOQ62lxStPM!E@qh_3oZgwWzZx7t%Eldmq+1 zkwXKHD2e47G|nu1YAu!_-k#Fk667EFvwSH>A4UMZ3T(wh3?*X9{WmY)21u1ui8fZ- zVqL3(rY5EjeNgotS>Eq>PqMgQTOH|Du(xjWl7V=){(dXxeSeN$BC4*Nz?8@b7G!Z} zHz&708*n2Xf#UjZJLuR!K<_wB+4KDEI>rqLDf?1n=Hw7nmlHfz_E)C4?=;b0(F^Tx ztn6qc-ZU6AD)Q0xkvUJixn=p6wvbw4Cvzdq&tR8E(G_HC^6}@dtS92lZo5d;UlbbX z`;Qj79?@*O@!Ub(ITR$-jq`F5Qv~@xcWngYlDJ39m~E?+eVdT`*y->3+g{AbGw>~j z@FY=MCTRAVKBa4tQ}{pL6RA|$-h#jVZHGQS^+=9vwcE1S&0O$FWHd^j=P-4u#N9ov z4a*MQ+|V|$E%XS~l+DK9^!GaV#w`juo9}o$#j2rjQ|?6P@HKZ z3kuz%G)FE3?i#zazTXG@-?N15k-eX?zWlp=_Er1ni4MWTvX%OY>+2V`Uz_-R^U}-f zt#tlu6*c%$YOMP94a@)#m-2FVKCED&wK=lC!fsgj_8n$imoVJ|8O2;>cb<7jul^*KC6GK zqOkDYa_wJfm$EU|&8;!?mD&rlzN)+Q`mukhMJv*e_uV}A-|q)W^%u^2E0^p+m|#+v zPlkk;fRT^C_jx%y{_L_V>e|DsR$&IxpQ4?5oJm46sK<3Iz$$iz#E%452QU=?qXik- z(=<8`)KdT}a^q!Ew`ne+{_Q-DOg)4_f)y!&drzJcpSGyp<)fu{#I*IuA-$;a$J9HI z4pflPq(C%jC@S`R5R$o}al{7)}`sDjD#P4~wRvB9^ZC?`{+0x%4o`&km0y%ZP4r-{$d zB`v{fV#HQcZMtqAipKKRxr(Y5&?GsOxlF&BJ=mRrRv&q@Mda0LZQlcJH={)rPU1+jp zDkTtIOJMrv9*T&vc`5JtR6a{~5RzAHPVcktM|qd_%j?q=DN zehAMYHF`keN`XJa%R1!;I#xC&J0Nr}`gAJ=V@EmmWhTmsQ(S`so2cjwEijjm9z&`{ zy`z`&N>5pV734q$B{GMfbW)IUichb1MpvUiIv=IBl&%mL$@mX}a0H=_Njduui#gg| zFn2|~ql{XV8_b4{STgP7isv2CF8;K$!W^r(lzl-djoe_1pvpuSbUm9{ON#1YmDbXj zXN46@ZJ`b1l-TdNQU5D*5$&fs=GC;+S{k~Gzq0|Tg~6S|hLsO&P40|M4*TYJ+U2Al zXaAWc{phnIe<3Bbo-f+cm|iEag2-Z!E1%DlX8%m6tVJOlG-dt zr?R^8$P5};E&!}`0ZR)q@B{W=R#BaK6@54B3i69vT`r9TUAXO(awENXCJxO>KVzhb zHg`emWS}jqj-KVCI~36m-X0|tpf`L{&yq2Tu_cpFFfIi-^FfuaGbwcfj3{)0QU{WK zLYHRq{=KttJLK5KM)xnFhZQk(f}SsFU#R@C4J%ye|)>-X7* z^f29Q^iHePIySSnu4Azs-Ob0$42jm$lF8a#33Vh|`LWl2607_RO_bB0!rXe(>p+{Sr5K#?0LeJHtj>D`P6y7uN+xI8<~S8!RV-X9!?{pofJUWD&qJ9(aZi zmI3HO7OI@)og+-BVD)@=xpc~EFlk=Y1kA-|Ad}JDvLES{t(2CN$FaXIUDN~B0>KJW zO1G%(B%_yDlwBzR&+sq{3gGpklE#mfGc!Hi0J>WURuV=Uf-BFEh7akXyUC%h*641k zV>hLdj>GhDTkI`|&k&h&x~XCL=u$z)%w{*$3^QS5RJdrq%0Jo4!!+?RUF4Q-Qdk`y z(?brc+YdLqPPRxSY!&CrCo!n*mbz!F`a}5H#3gE_>gio6LIvDf2N@|T4WJ-(XZY)+GtmBC9Dly z$_GDZjFj*&U)k4-D4t&ln7{9ijciDU+50yGlKXcboPKzH_#@`QZ%h{-ygLd$oyTl9 zlDspIDHdQ#cwi}jetYW1J1jbeJa|A0e? zXZZCwOd+XjY#wYnGUBW>dLt<2_Tk2}0&uMO#tTbyh*C*4kXj*%+YlR=u^cO5UH`_% zl=3IO0Fq6Dg~OW)Q9Ch-{+MqB%qjm{4+3v>@vdL)L`QXjU8Fl*0!(D+t;e4*#e7U` zrYPzgUBsS_JU2%D3|?hnk~1-dG)ylayegb5;ogGoowIeH*>C}mcFZsVZaImU_^Y+T zBK?dg*rA}d6>oR)BX(B636a5 z!(6XNfBMlrGPiJj>clK9D-yMZMuur6~ILx8%xaOeuin^1!PA7Pt<6Jr5SM!2%xm zQ5pO12=-SA=1&O*B7V1&HXZkSvXpqYS!FPf3^GH(ki$sm^O=)R=nQs6xqqO}A*Pen=@J<8{`1I{ zlIaT4oZCBa2F$IdmV5{pof4ZG`}64MRwicb(?Z}Hh66|*2*zJ&c=23HGGrU(?(Ubg z7tc6kY!gj%YAkee7edxB?EtnIczj&^@l`HZM!**Gz(Ve;Jnm8+8yuuzO1KaHhGI8M zmTcVTNF`vQQ1l!qBOwbYU=#_NDE36+X+lNT<;v%D+LKmIHFVXplpb31!0s++>0p7! z+}9URIl@N<3xfR8=a)ZY%6OQ+T{qj=SHfyvc5}fB0Vde}&7GsupU*w-VS|Bb=(gXZ zce>~Dv#_1~>-l>HLf-XfzZWsQ(s1uS>L%r&3BV-?$hK7t_STbg?j<+?Rvw zcLM~;K`Mqr6bw?ZTf@Z1SBa0ayTQNRUv(<+gv3NGv$8ATKP@>g{3OB$JQ4y z#T4u*_g6QwmXiODc6_?V;dey-dYSbZ(@Vi#7Gk2YW0xt|7`NdP!mBlvbNSc75bK2- zSnM@6hI{c=CqYt3!vq^ke!)p{c-R^1+u2EFfvS>`tq;EvCEcJdl#dkR=58Hv*Q!#d7)Yxil3|yFa8@d*oxm1F~ zcCx^Bfd8L37V`IzrwxDY9418t{lZ9?SX$C8#0X2CTW(>xS+854k0)IROG!;mBhOxk zJTDcP zkvbIEvtm~C-<+S;4G|qHq6F;d75D$JPk)~>mn zC{n!4(tb_o?})P1sSEirx?id#%GR*Pfd=Kt>abkc6-jlFB4W z!dZ7xNs)xGC_;R4^Pvwu`~J@F@z_7-u|Ia+JMVMOb-k|ZdOhtg-!d{haBKh{H&yYd za!>xzwJ{ep_3uZmu+-a-+TNqtn>pEYbe-O|o~vuke0y}uOH;b_Hb`Pi4y|iqmmGRS zJ7RInPj8Q}_RHRmpko`-E@__s+Ui9x$(#vP6Hf1nS!wAp`(x_r>SYVGtW9=Lx#x%M ze!F7%>G05G4c)BJ-QPXGaqQnOjoCTUqrb`N1>u;0L9SnRn!;XLv0kryx|%XoW#Hh^uE^sL^ps9-mLHAETr+k41VE)-*uaaMQ23WD%P#63OjguhW5)jwrJt$H2FK7wOe(w=A`AJbEKGyw|-=;Nq7{)ec_@X zmFReMVF(@bxFjn0=sCT$7Y^s^uS;@g9&*l6FTssELAw7e+MaS9j_lf(y;MI_f_{~deQRBF66}L6&`=HH{8e^JMF)^(5BaG`~FiW{fEL|V^)v6 zyB(HbvME5{Jw7|4f8lwwT4;G^)sCk<;Zd8v=p2)aP2ZGlgc_%dqa;l|k1y_Y66|tH zoHPt?-2dyql@kudmdIr-&DKLcTFONVhr8uJDk3Ad5mZQ|VA-#YGp);YQv@q_>82Pj zPVPIoFYJ+@-`o|#ihJPASN8Qf)T+_ifN%Q=i`9R|Djz`sib6@q=l z8tU4<*ZXde2938~DK;g);}`B3TSO`>UK=nF&_)8YLPTv3ZV5~%m)O)jhxo&q3-c&9 z*yIHFz(SgZiTtep((hLs{oV^qE}ixF?o?kr{CM)LzWbl*#rx_G?j6k0yMFSiT?WQB z+8{?SaQ3xfgq7FcfH(Rpp7z-FOFUJUv3i~&!_VK3EZ{z~fc&JsW`n|OXGUlADh@5T zOE;yi4S!p_J+J4x+$n%{E>L%>pSB>u>D~rl&9abt2OaipKk`rHM}F?8ez0FNMS99= z%W@<3s@O@RuJ>4je=CWEZF~*)>UiCqC!!aJzW2_%b-2Q<=c1qrcknNGp~*MZ(5^`T z!QHB}`PPKD-ZRw)7yK|YKmgfd;Xgs5S(K~A!+&EZ-;askp`To7XuzmGn4BG!*zr3t zVw1PZ5{K2Aqb8+T&jDyw%T)oiOJJhScm=1Aov>iTx|Gk(sO$>8RKGoaz&!c^2 zHu|^W6gxB9krQZ(L_PGxKCz(fWX5Lw+@s zEiCMDx^VrLjTcNA6=05#hhY8+uIj_^dgR@>N_fe>K$+0W!4iqrHd{QX$VHT$%DyFh8*y?lqf zyC3$i3>Vg99Gf5a_m)*_Bz_hw=rri%qFQYn`%U{uPrXB7AGPCc4lQ0zFi5--7(VmH z1Q{=2R~5;&C+c461Z0(4^=Ur+L;AUSmrjrZs2jK>Wj#=Ni;`u@eciqB*NEP|n4hY{ z6U5LT_a=i*pE%?5dP?8rz2czlvtn3%UU|%=A=#w-VvLHRclkNdJ49MU$#T#y%DPM2 zt9-b7F2rPR{#;k8M||v~uNCe82|q@xJD80KZm^0Ayem#>?4{-2c+&f|;vnWgoI#vH zXWM3{yluV>JAa0?6oQPR-3K?TAH^E9D-!L!^OIu#yw<;M-Rqou=pxnsyFSJ~-rl6@ z>~31}g3_@U_Tw^}Kd*hdejh*S&A#axw^FBIUb4wsQcc+_?yt3aJa=Y~XzR(TZ2W%)U729{`du2aI%f?wSmiqA zO(ux`_;l@j^0`0JbnTv>FaExRY_yJ>JideQru$>oi+w>+0sqa$F8IOMs!b2L`O)c` zOFJncY=`DXdYs8r{@`+MMxDd)QT2bNxg|5nz^CHir(*rvC?&O_r77`2avI~~zq!+E z4(`PZDkqao%kpC~UWd_4u4hbc)#&NW9F4nscgg0<#q}CCf13~dF7$J(5&b99d1KH6 z`#rh#a*M;UTLv%w*Y5PSdi0zucVMf2?|A;2k_+IQi$6e_^O=7~+y8f~?8n=yd;3a$ za8EAN=K1$))E&MQGh7f}XuK98#68rR$*JGO^}0~lw6U+?$(sCZYYRfQEuCdi*SxIg z4dFLV_SaMHsx?c4A03P$)y*4$QR4h{b@>}Tyi=+j$rh;9M3eC)VtsLe&ch?GoqdX) zUfdLGs_%0#yN;M8m(}za>?xFGOVl^TGp=G7j2re57s`^vfH>3h?{BShA8&sPlsN=; z#kUoRV2@T$Fuu%FQru*JR=_=Z=i7kd=I>>D%q>I`UbX=%@JscztW(}6$qTY>WfT>W z2b!bBQm16Uh4uvN`B%wTAVh0#ldz6O?9i3%?J%+Xt8jhyHEcQ&*5xDa)(`_tX)S zD+|PJMB7nfJn1HyRQ-*+gW9)igur5^;QI4|zdt%%-XK8dhFvqdPTwTDmkXND`b%!w zdQP}T8C;L;bN*vqOIKg@j0G&8E;0@&cZ!0RCp;wf2@bMz?0$b-R+r--653i{_4m5k z`b1>q{mA#`Bi~=m4(FdC%!%dC{`D7fWI~{&^%3!LXFkiQ^Pwt#)0?Hjko+vUk5`~; z{gER=yUtkr%DCAoj*Oe&8ROz&T-j?!}8g)?JBLNbw<7N(ffsEN3!NEb?XauxAjKHn{HMV z#I+S9Df;7KS$u#j2@aml2GRc;uUOfX>W`}D2_dr2L9*uA;P?>P)drb_C$k*(+vy^6 znQ*#%_3oaDW)W8=oN@Y1<*&khie{Kfs z@m*nSZnzhaeSW@NSlJ~UC+r=D?6qaXT{l<$Stg2Hy|=GOIN$SC$jBS99C_~8cy)#C zch~I7UJyBiR@kZ&`h>0Q4B9UDtkYx z?!P=W6h9YC=L~!b2U)NT$Ae?%G4DoUmswZ$?;eUh1DA2vx0-`uM9@oWv?&(IOIf50fR}^qxs=RiS9M?tb2+*~P3E(}iMMVwBMeF_3lJP|0Cy~_wr zj0EY(!_VQM-9{N5ieigpIMmCaO_~r8wR12yedFr%f1b7G$}G!dLOJ0wUK1M5Dvom9ncW+2X4Hl<0c3HrDCr@)voE%AsWM-Gxur z9Vj?g`!q=oo?aS}h-^$6hv~yG>g5C)JVOr?c7O@07qu^d1Ub-fA3kFbC$?d1Gi9vt zp>zMOd>6iY(c`GgAN?FQ$YKGhne_(Ao&mBwxac`Crn0jVB6#1DemHSQ)E8dVvSHrh zW_C!^t?8GS1H<-J-N`-LylKvROGCYJb6E1sEg^98-C(uQK(=SNabMQO%re=BXN06| z*|&j$#X4QXdu3a~R(`;1Yndh784MZtj()8a-V|B&Bi@$HlbSxU$H#6I}N3xF~# zqGpELqFym`fc;)jV+J;B6;UHW@(hreiGHgFSi@tsGZ7jJQ6eYs@A#51$XV&J)SGQ?tIMZ_OQ6=Y!BKVS?%|!`MSC6!HZ3? zA<-r^t=*>tvyX_sj-ZF2hFlf{-4oXpM0*;3tt&|4fE!h9);q?<5?Ojja7wMrwxPfx z?xM(96urdsmEH8%QNQseq30TiNla4!PT}=YuIzw{4Dq)@SoQ zc%#>^hAg?(_04nKf2ui6jeFy$j{Xt-;K8St%VNN$!MGhiHYIRn|6FqAd4h>5SPb8a zn+G_|g6v_9a9+Wlx#k!Z0lf+16|J%G5XD=TRQNEdZ~aO8glVnY;jWWwOE-oZ>!epc zO$=WdcWZsz4p6HSB$vVDxnxiR$NT^^%3wO@gGN9iqfbN^CQ{`9x+=rMx5*A4D3LGY zL!O<#|MoKN!RCa(1XXi94;Bo!-$;=qh6w+D?)vdkr)Vxzb4gfy-QCvho|)6H-i>-U z{fWJ7sftxR{Qjpswo*11cYc{Hc){W3 zoewxuB2&8_4Hk2gFSR_~GwvuFTvY+~M|s_@Jn%HCdtzM$aWnIwzMeFy^{J-nJxbHl zh5&E|j!ul#$OJ4+qKsuQ9kmf3hpA-%z3c-M$zjS9QPGsz2gmhBr8Yg>d@7=0l`K)7 zgAuJ@*`nkY;+{I$quT|W(IGmfR5JiJ5(1!s6ok?FsYrk{ z1B<}7pg5M)2U9YEH>CirP|6@l7b!k#Dd5?cpW`B;8m2$kF4>+i18X2JE;i=iRGZ?h z1F4^S_s*+amjli**j9C9+SI1&Q*ZV$JP-a8pP)*OSG-;v^PrVIurny?*S@(VL>vqE zCn;pWUm!~*lNf-TRQcOTIZUP-)eEF@#ddFmP2YVkS@_p=KaI3n%kob^!He&ZiFI2< zuO_xVX)HK->#1p@Op_#KMq=6AubMDygz^|+KzjxNA(({LCUyXnN`RF4fmjDq`o0=S zU}hbb)rK}z0~b(Ne}nB#Paf9(H>5ESFeS1?2}n@a<9UBa`?euI{e*Ig@kdi&|R zMv$eDZsr1(DD^QC!$PE3EQ7Utp9Tuzd0T8!WR~MtbQ$GSG7bXf7C1BK*DKV7 z9%6Rd$MrkE$H(p1p}VgC#mzORAB@P|UL^kcH*w;N@j_xM7vKe8aeWvzPpZ|1VT*IH z@GqmX9CYYUdmJFc0MT07bnGk1T1u(}h>EXiNr2=!1`LpHIfHut0H6GRei{N=|Awth z-c}Q&wmU#uppeyDYOE@=GjxjWuUeklN;7Ou7$`NpnPc}1!|e934m_V~<{N*ve21OQ z7Xw$ufQ!WjztC7P&*YS2T*aV4bG*@cch3l#k@M!!@9&FyMS&;WhI0tN6Y;)Iv7J9& z$Q6T?T#@}ot3~R!c81PL{h6V~ep`%|Bt7~(dCBeXm|MHj|2NW@^3&mEN7m1;pFaLv ztU_|W^zYSQ9J6%K+^lKSx`R>e61RtlO&Ok8s_T5%!iEdW4qyXQRXna)K32zy6P{TH zpx$d*wgHh`)0`rTBd4J*HkVJK>RJigAX8jE)qtBSpW_H*bh4K3rm^ZSklxQ@zZMQx zI?^@v7;V@+XHkF~K4I_PS6%B=WxO=&Pu<4#{dAVuv;WP93cvxK+!7}i&s^!;Q(}=r zdZfCl;X+hw^K1o6jSz4`jU)DG2XON0q>89a$rujPlq!36OGbO=c%^N~;>33EP zLlo+88AM2^5c-fcgF>(r-981h_0D}R2Ct3cvySW8`D0RaEaWiGNDT8qqxkDV)h};Y zXs+mIJ}Pl$Gb;xj@5Kv4a33rsfRk~D|E9gf-Q6=g7i2I`1q02#a=F8fmZ0q>;q^3U zokHOQZXe7cXvMRKOI*gXzvU8pY38ezXhlkNxrlYHQqar%HV7_s5`1!c5b(y#Ii=cC zBRc=q8}l2}C-!{a^tatk1FvGGpwu-$1@~x5P+L(pE>fDyaO_h(Wq9;4bJZ00Dfm8# zS%m<{7L_oiI8yW#2*0BS#YSp(OL8b-;~_ZO^;IECf^H-v#pwtEn%Hp_}-U zg|6+Poots!CH~zrqjjJrYI5ipHd}%aEs}RJv$fXWRSwH2QB^y0`%B84a?_BKhlVb5 ze3ve<9M<#&4&^zf4{LVQO{~KPy*UuGCA?=`|ES|rn{Oq~4}#?U>yLvTH7<4N&D3a{ zn<#X6bHKCdZ2Q-7b9ayDI;I8eqmyz}&qhqU-Z^)p1DQ3KxDaj8Y>0s3I0$!kY5F1n zgEambNg)L(5iBW4j>9Ypx`M+wmBER}FDYjclJQKDT6t`}qC?Yr5OusWYkxquDH zyJ#vo-h6bD7!ZKfM~ z;f=s?6A+c70E)i1J%tKDD2%K7m zQ?tsO{fx$#`KOi(j27&Hok}ruFcZNzEa_cL>6R*>Tr3z`O!5lR1{5}je~OU zRmclxPd&0Duah@y&8TB3^M>{bhi-RZnIpz|F)B%TC}#f*q5nyr}~`92r#*{ zF!`)@>op~#wb*mmvD9=_%E;8kYL+N+O{V}-0N|sES_hgVB85FSl^UhO>f1#S90L}{ zYX8O>wK-rch1&GfoCn$M7>0Zcj`47q;F`&g35e{}ddVT!{ufz(h)aSa4Xh7=i>(ow!T(P>i>Mn_|Bp-~E|yHvw$1ZH51h&~w&PO>l3bk(e*#z; z)Ze-LY5MGiuo);2r#}}()RLDFAx>6kZqfEb-yrah3uYa(7+boXee`w%W*`6oSH1;~ zul<^kfGs0fLHW40TAZuAi|G@hogy(OQbLL_X)wKh-}3SW;|Q^S8%+e6ANIIeQPKEN z%0#QyoJb|HGe-~aDKmP#f5~Xrd@1Q5uFJPh5K{oB+`{r8t2q)|0!MDRR+0-!-eHQdefyHb z{jgddQW?d+b(j@Q2xyXmzNSyS_W1GI4&lMfa@;ZwO!trvFjYc4ZDj&!?Az`{>snkB z?LBETGY8axF=in!U9pC~CnWCix5B#z$_)Sc_qX`NyZK(GU8<;Kr+^goAZ2U|j+xq} zk@rF)6^Ei#-&*sjWgGWj9Cz;luH8W5dH_Q6iWhW%RtxDA@(uE&`l%@1lh0PyVOSwD z4U|GERP!8`gp&FhMZBq~xAX!L4mia9$AZyACcyS+xbgA`fP_oX!k4IUVoc zmjL617>jL~-uoxPysB*>>+k_YauBrZ>FMdUlYId&Db++bm9LqK`x&0=24EP#VP|d$ z!*}8u415fNiJU+eUm!JmxwA_FE)$ux2k_`4-DQ|GfzU0ani3pi3UDjLxmR^9t<(K) zZER@=&a*PtE&5dBV~p(aGv@a*V{|DKFLjgP+){DlnsSX)fyQ@)(SXt7@ToHZZ4TOh z<Tp}^TMJwNJQSN9l2YnHe zq?*7*@Ret92<=`pvb}r|b!1#jf5nnxSQ7w>jdsn%b$Y>|i-0r;(L(_Lpj`R{LW+cz zRQ3@S5IzGTS_2PIgO^Mx!ZMFNH%ot;K73?pNb)UEQhTTAYr^=50n_KaQ;xM$$< zcf4knm}$bX|JxyO%j|NK*VxvWxruW%zC+YG7)@*54)ZnU0NPXy)f&UC(57)l7W;8L zZW*xWPw8h%S(zJHnd)Fxi;_{NVhy6CRzy2esoNpd^;NP`G1_%&aF&opn&HYd%7LPT zpHL(3Y+$7+gxCYAy8XDe(TpX4z^4E^6@v{|5-gNDna~+N0!|1CA<&ZWqp1N14&?%( zFzCE0de+el&T^JDFhrNS4o-kxz^_JRvlu3M;YfA>xejQ|hW}ZQP+Z_}V?f+oi}!`; z2I2Gx08%3w7O~9uF5VwVv#Q3e;X;Vsxjk?5J!^69k;Y@97YjY67w*e-E6Ls0l;jp} z={5_v&BLzZY1cM{AuMGhuNft$sB;kDBBuT^BlK4S9hHm@V~tvXk%=LtDYexd%2zuu z;w^lwxpQotM3hb|3g%-_xUY~;=OTLN<8*Z(PZX9F#Mcc_>e#`{Z4iv&33lQ*uifvQ z?y)Bl2n>R7nG1AB6Lo`>PHdQI1=0IfCxyb~LJdY|Ic{P-p&X!(zQq|ptSY_^P(#n| z($qn=8|YJOAzToQ;{sHnfKrGMCGZj`*SQS&=LK?E0$~jh$7~2Y1rF2!xDvqi4}dbo zFr|Xa_OE$`xo%~-p0w#b?e9D@yVTpvWQSgd#Z)q9lHBGlxCKpTrFX5~EMR^|BGS5C zvlBGBrR;7#G6QIQhh1HS>&MKv*f*52QicLh(_0`7j`WpOrHdwLvm03%ELMw@&EvBJ zFgoE<3=Jtqt$dbZyvz`>%m!};LaVt z(Eg4$C^d>c_4w$Ag)67szQ6lxUl*?->C!I%eXXJ;j>i2jA~$z26jGZnh{i0kDDB+% zWGv7D(B{j4IW_R232nK97;_NWf^T49t{=%~Wk^{PjCPyUNL9?nBdy?D9VUF80qDeI z^n;`a4gq)wIl}?Ager9ubr?j34ZC1-q#rsTTiIj=;S#_n||hB|qUI@T|~B1=f{<=19vD$klS)o5P>Gcx4{5~X$ z7qLl5s}`&~D|UMjDE_jD&+x~MFT(TSn;Vt7(VDo_eyvF9%>Fl6)OsYGuggvBT>_*^ zE~g8dd|p@)LYnZ_h(;=eTEdXSA$kcwfl>*TkWPm5tr^71=Cf)CNqrcj7A3}l_{(O| zEq8?60c*Q#Bft-|9UH((gqR88g)o^b$TEP=y%%E|kgW{}T?bwgFW|-JV%z`L$jn7W zw>8yW|CKs56b*P*rW?CV{}p=fua!&Is=NMDFZ`?hgHeuvsoKQU!8}#gxK4e*zo~zc z{;BbyEwc}y;IC5a)R0CW5Ieb%m@9v^Udn=`+7dns^=9f+vPm#IK&l-rrT-LT;-z}N zN}b5HWM=feasU^^X9e;9H;Q;9Nil=Z&qQKqdN%mJBcA{YzHhaAZsM(_5Sky8TQ12p zr^vMsei)_>i*+|)u!GyR+m!lZDK-FIiIN?l-0ELK-FblkA=E)cTWpn51(ECE6IGBC z4501P*q~!LFB~!GP^2-WJ&xcDlQ0TIbAHx!7UIEOXm}$l5}*&lWwnCPMLTjGcZ8jd zUX=1F{6o^?;DoV#f^Zgh?ED8Nz&Fl5<@(1-ip8)7rR+b=>o((fEwSSd>owHO5&(hi zdyzb=2=XB0^zs^u=ykKR}LQu8pOsc z^=qXI;sgvhR};eQTRup70{0BVG$wFsIXqJfp^EY^9zraH_>K_SE|)mkJ6w)nnK0Q7 zU4=dc z94j12!>vmZL@<=>Ac^h11Zl*4L}KpvHAu~CfnrfuRG0BYO_+YB(%JuN(RHO3!WDjm zwS1*ILZ!}xWa<;Qr;7ZsiF_srgSCM0ZDPIgM`Sx&O!&yHQiNauVaC6e!~l3M67K=r zn=r)pL7rw1EeJ|(0O&3l?WYKBej5&-W)Sp<#71tZV7f%C17WDyw0n{gnwOI91Cxgh z$P@BAXA#4bXs`&AIf93TuhJ?Y6+&p)L3EdwTEiIal1N5s?%nj<^GDFI=fee0gRmnW zo_#%5!PAf1H~;nfdiX(H#Ptu>Sd3dX&OP8i*OIPvW6eySeLrCX_UyHY7@RBKbKO@U z?%GiCnhnl>Nexofn3yDGOp25>5y&PYtUs1I<8!+4H+3b-?shL2NmL47D><2-Dh3 zt6TZnl8=V*S;c|}#a|yRJkr)8xX_C8Z0oY>{AK&|!e6nU>VLfY->-Q0Y=L_wj+c$r zW^ryAdlmQiMuU7e@iZeO^YZ_kpzp)V8h;Ia`{=gJD`v9&`qq*>vibP|UAOfo;&*GS zEmyJJQn0BRvCI2Q7KTxxCu0*6}Av)HIIU1>e5gk0$*0=Jj z?@E*fZ^a7{Li@2qT?ZZ{JcprZYnx2fIi6j0(mG=-(xxn-*uXJ5q(RXr^hP?Kr7`c#2tVO1T{o0nc9jTR52dQ zaFO(hiWfh#hCtnbNY#F~@Bn^3ft|zOe<7I3kzvBQj#gUiBXU&IG7w31z2s8EMC(Eh zm|#%34X=H|T1d2lXE0<=2^U*rmPRtGO6{|`TeT}~QSj)R750zAU%YfLsM-)yw!n$F`P98C!T=ZTRlidelYtfV*rC)BdyNOZBtV zNWhG}fZ;QjuM;D|$n+u=)x|~a3haId)o^Svb{OuWyOs*g_FD#E4^gl_gRxR@r4W|l zO{|qFuptD(u+Q_V_ZxzlBB@U7{Jp$^KPXA@vKb6pY}qL0cQKLsAQFIWL78y4C6UMj5b3Xan#Z&#N_KRN>h*P`Uw$G zLvLP=d7v{#m1+hX05cCG1lVh4B>}M~7jzcwSsSvt@%iVQtM(F4ZM)6CV7&9szPl&a zZ)+^|j7qS?wx{Lnf^a1LpisG;d(-m!>cl- zMM-q1k}|}Q1d~JN1BEq!R1;q=_RIsnJsKoiv=t%&J&8*|0Zy#m|&|=e(IK3 z?Yu%D#;9^wtqQyqQY{VTJ};1$5e{=;ykjyHAB4cR$Ry=(G)no>mJ)`AU@($X*jAA5 zAgMlVV&1QNUg1JCNX2|w1keLGQqAsada68Ezr}^)}tRAc7{iR@R#yOKXE%$f0Ta?4|K2^M0hMig{cZ{iAdNe@=1droGT!3Sc7 zvFuJLz|Cd2k`QTvQIvVwLNK1YJ`@|o&9@4u2G?4{Ni;#Ofv=LXQPOp^Rwd*5ni9b_ zAIB75U7HRiUd9&OH`Qr>D#H%V(OOO^5zWo z+NUjl35LH^;fx2a9BeeI=WVRMz-~V*-mM<2UM@O-B3H-jcC?8WnAM3G%ZGbiyD_XS znQz*kw)MK^?QE}XhQ!-bm5iaaVT;d3yaENZunNy9skxhv#Z+d@)p-BvhvcAS~*ea^6eYR29;gMekHKAL)4+l>#Wt2|4nvLX$A0Ng+j;Fs;Rch@e0DUS zwt6m(-8l?e;gJP)!+n<^^ys=4_DIz5ovxWq-DrcUJlLlAtXsElNbQO zF;lway)O>sBZ3yZNW6oj^RBfJ&*DMO9+DjGG6cjILS(EWH}9@+Nl>3stELQZ{zpYr zm2Gf`3lk5#a$Q^Ytzc)bbAbnw@A+P8eX4li-PTH6WY4PIdW-j8`dnT>`fk&yc^9K* zsTGF~{2>zqrKb;69v&dLlW+zTTGb96lN3>*RId|}g%CM)tLlmwO~~b1R}sZl7?sORMVgOg+I(Ev;a_EnDPyw`1Fz z-R@bDF^ppeyZ-IZk8X-T2YS%>%TS=$_98;5NwhipIjP{RxiLqbDi+Lm2t)L{=N>tT zrH^pKKKi8`S}TX#siMo_&^|nE)8W5M#)K0n*7>h&%-_(CM)T=tM;_{WXV} z2%~KYL=|G;VM74rvEh)41OZ|>-U`B^(pr_ubR~=rF2o+5#ARVI768EjMI}Q(v&-!QbGzob65cxBRlkN7=s){X?e(o}7g>4*gz1Y3%cFy#6SsKiDy^ zlG0`Hunb`r<{#+hXY^H%G^>^1Yrk``A4eiL6PiUN1fdR{qmL07FCp4n9~zcP&pigGsWoXpGoJ2&r5qL}jseu~AJCOEYB`LG;Lc_U5UTQDLu4aya5M)15%SyGD^UU2 zAsi0Y6$m$l|>{dp0D~U~$MxnN>*f&P% zvA;V?9cX`M=oKL2%VxLNw(Ry39*h~zm*lnNKOeArpo)tDwsNV zkp4_XsTE=_BjkD&MFCM;I6ud7#tpDUpom(dB0oes7wFU}IZAA%pMbzJA!9K18D4d8 z=suk-20#FO&1LL^$*SbOGR5(EGpv>HpBM<7ujz9FuuvZu0AM^+&Xv_bS`Z;Ck+>5g z#&dwv(A;4mxq`#`{@#25W9*mC`(Mb~nbco-97|DYTj`^=LEH`Ih{ey@8c8~742T*O zEi3KO`iZ;QJ<0lUk@(v0VXG<2N0U_Ed>#>QY*yJM!D@OpMD9SSWw=<(*;?d26l&}wUy zsaX*gHP!VN0*S!MmoV*WD8PA0IByG(;G`@N-&Q@}uRK%uEpWwGw!=!xfw&09mHp=* zFs}y`51Idl6NX}%yrN4!HET`Jgz1-~n%mMXADm^&IA3J)ZP5;_mn~k% zq|px>c4f+jZc~;ohh4&<-R7*n1>3xllRFW!Zm1UlKtD4183LrOp~OQMYE|(8Fh*@8 z$G9j!9S+82M&WRt-YP6-lu=V>DW?&7HzGaF+4W3C+O?Tpa_^DB6r}+szRv;5KXpGt zNGrD(H>zmQRD=v68HJH$w)zo-)RW{-Q)?2YY$-40gb*Qi|13TcG7W|CcB;H`5g98a z>&VeU87{M&DCCf1gv8Svz-amSVQ5ovk5Lv$=v*pX{)9)15UtT#IxMgZYZ9H((6o1) zR=LF9HT~_N7p1WNy?@}3!v}NEPLuo2ibgcaRPJ~_y z5nJRI-YfJCFRm~X-m8N#O$f-8Q%rkm^`?OIxM6feoKF- zqJ9+v+**3GJoFGuS3e|YDJV5C9WN)h$;m4ZP~%ku5|Aucp`~09S`1=QHWNUwfH4n; zK!uW+3Y_8ql7)pp%`h$%!kktDJ~c@mbwHJnXd6b93+wk;&82Y$t?OO=t{3b!U(5MY zqqTF@gHh1}$KQo1LuEWG`<;w2PTZkO(-CRx?n$Fw>6su#{O-aV-PIv?gw!^OHlFgn zQx22^dev#b+~TaG9I)0EXyH&#%c%?w))p3Dr~&KXOKock?jYwdL^-+Ks=^MzrvdY+LcBGH>Mz8m^DQR*;MJPc6``Lu0orCwKtAGml^$#1? z_YmP;gCJ?9Xu#b4!eypt=uP|+E!LRki}IqyKZ^cS)*w%(%Zk~xhHP&wcE6PHBbi{Q zN4uTr{R+^10ni%YHD}#uqmi_x<^xykcPr%f^>Tl&5=bA04ZkPtt9&99AbMO)Di%8+Fbfel!at?r~F1+4O5D7m?Tp95IoS-suoux#`DWD(9S_&|dr|$D;*;!Au zesDn!P-52@vY{y-~dGwXV zaon3Fop%Ickqu|&$Vn=EOis{B;J8?b_lEwTDwd|o-7Ysw6{;yUlfW1PNI2g^g_2#` zzR{dSr&%x!W+T;MLzu=#Sr!KZipN?!el;)`+A_}!Oh>pC^%!2x2kd1K^9o71&f!7d zS#}fV&eB$PA!MVwffoE5Jy+iz9+jK%X(#6|3IJc!r;1gSCOPP3hpiP7(sL;3Q;&m$ zKr3>v9m#$nKk`h~UCYUtM5yHm884^5UAH`6_peu+dnuaK^Bk}epk_K#zVC;h3jr@5 zS$l_cqJn<9C`Tl0f8Qu+BrjM8E~@PHzaq->LJTYUGlUm*ATAQ< z-1E1@9K=W=4I8Q+{B=^upFZ(Es|K&`ke8&?s4Sd)TQPVtne{$UZ z1!L@1gVU=tX$bFs7P{T2MN&6n(*py~YKSU`5zj%ZWW;$lN;g17RgTge15F{h9*%!@ z|9=y))G>$(swgTsy$rc@Lr5Q&%c_O7)0W_m>khYI`u=;AZV#YFMX3RZvB+mvGm}Xk zHC9d@hD-uI7VI9pYt7^OITJQxvv03eiGh7qfPV&nCgr$V7^kSF@8>+tISu{Ic{`wX9Vwy`#TT4)qv6Gd1q7o@)KKaN?IR;o&c6=_65a?1i@2rF%)y z$BM3M6fJOlpst@+e0sWWuU)eav~4bc&#lW)P0TqN$ruEXhzkheUIW^ zdbLX#-b){(nmqa#RCS1Y*^OrDr9Nv zyEZ<%mioMXFZHMW`sUB=>7VvH{QY?AtG+|OT~QSi+510=RrdVW8(XIb3H$y;I>zEChoYGPmf_TtN~jM+%;jiD04N!HgM>PgpF1lBzAmRiLYJ**`^!k1R6*+FCYva<;V z6%n3&9iZB;stP)Q*uc*RWSKc0+q#0i}y-)UU*;IE$Ct9HfI5#@3^rFFS)wB z#DEuEWpN`tp&xdOs1dH|^u?^Uz%18^ngMXyscmllfP;%>0e~sj5m0Q(ECe(sC$vM)q0kyjpt3%DjvIk zYRL`u*tq3!>5;$+-E~JJVv5df*#3COx^*JyV+#-eEN6yL4J1Y$FZeI)sW8VrV(3sB z!*yZRmWns@#1lKl48{BQzpYFqLxE41HbPePHPKi zQf9Cw&lK(Sv6ch6>&9U~Z=(y7PxnVg^0Q;=s(XMC#T9}U*K34elnPDaS)1TP1RZXw zvWI`KUAo+ddW*CCFYjAQU!90(Q&^|BR|T@T9qqY{bUatEVzE3Vlww<0*Q9M<2Vp^N zJ0X@})5cVi7VxyC?1fB}mB=nUk)spD#^5`HUI@FH6Yw{j>vYFOT~ED57mps%-7p(m zVe%I(J!-?wo^w6B&gBlRTXX)%kbCJNo2V0IHm=Tb+GpLJMgG6S)}KDU_6I$we0@Sx ztfazqD0!1kme^q2_)3p{60GcHiMX0-VrqJWCQd7vJ(;Ipzh9KA8)P@a$GJ!j<=63A z4&`C5?7z~(TAwQQGYUb$Jw~E7O&D0SusByQHFH}&1}h#R=&kkjgmeOZHS=}6W`y~y z)dnHU_pXkv767+zAT~5C$26Dve-vG5JXGKRpB=N@8T+mgvW2mRkfmg;QIw<_A#02^ zN;NZNr?FI$YHZmvwn(b6?~Evf8vD-B^3~?|pZ|SwpWG+socsEmbKal#0?m2pfre${ z!Ecr5j5ZXG%|pb5i^yQ4VH|rv2x(|_uQaHG!~)DYj93(S1J8#uSM-Pzoczn3^i{bs zAbND^@Z1LW zB8+E$uYb&jUAt*XWrz>bl~?B6iQq9!zUnEV^O$F zqKAOfS#u1T6R&EBhjVLa0z&u$+J>_NmqD@OpUtauV=Pc$esgRC=b1*F2MQ)h5#-Z> ztCD7s*(o$i4khl0d#iv>sb$?YCJx*}#poE$3VP9DV8i=-hvY5L2s%y3P#&R{$bwxx z2^D5`NQyAQP;*kOVk!rr%Ma!&FsDj2F;q>7&#*bTSe5Vm{L}mpXn#n0n3vL>)6FSH z&Evqgq|ogD<@9HE&~zTu+*e=EdhR;0Z1!^zF1yh4H4mqoepjaV?gKF18!hp;CngpM z!&^dD^>P(L4iO5YNiZi}3uAY(lYPpd*c>i?-`c`1?j&0T7i0x8jGM*iH_>3(T)3(p z1xaSLg^S=0{33&$yXR*m$xygq6c37~x7M^U?kN)#ovyOo(JCJ*m0LVQ&oM29ADV+C zh>FPIaHz+Nu`;D&E0K6Eg-Qok_fd7YTu-umtQ#U}*_+m^{l`$4d|DT|K` zZI7kQDrqgNWE~M2ebhS9tMzueUo&j!Q453DEiuaV%%WYm0D&j=sb(I$Ds{th6 zc0T1qgzO#(;Ke10KO~kx_VXwhTNRL~HSr#SoDW75C^BjftTseQrinrzk=jWFsTGX5 ztnvx;nLs}rP8A5Y=@G3oe>vr5fpqeP08#4ql$|{gS~yU2I16#8i6Rg|rvhz1XrFsI za4iZIeTYH>mzo#rsemEJnN-0E3Pgd#V<~9I3NF-xWcgV(*-WS;ul^mKut{&Ybmccl-RpO@YrC?ZF?xjt790J48h2WdK$Qh4d=}X(uD`RqRl~Sms{VR zCtC?es#BCrEYgB)py+T;yh0O${{+1i_?}9WW8u?R4z}935^4PIcsNRe3cJY$1^V5_y<}#$boAYA z3cbDgWbNFHpqch+qeF{(%@Y#`sS%TSp9Iw%s5CU^GGbHh@E30%hHa~Ek22b_D8wK^ zzrk>W0({xCmZcFBbQQtUm)Y8~5|r366$ThSK@&$4XetW?J|g|}{4@jp%hzHbWDIKO z&BQZ@REZhnvOLIBIsbjr;nqYbmKtfT-|GIO1~WW8}i98y8Wt3 zMZeKPqkmS7!Y6mF#fPq|O8;rA$_i}>9d>$Lo0(+VR^>Hmls=XQmXfY+P)w`AOl({= z`=jQ6Pq-n=pgsVbLi1%ZB$_pj$G)+~_!6OliJaK$>{;pKdzLcUAcRsSUcd_9CWU5$ zH1b-XD%e=gE*2g?J_te?Rbpkbd*HO~QB=$A;hRn5dy*m`)V`}L?NzAx2_si~zAwEH z@KttP3K9f>eZj)XI0}!h1hVO&He1`#3Z@hx%}-hdoQbj0zAXMDd z7)2sftcL+7__hLb3`~%S2fqa&z;nM%RAS!rEL`c^XaqdoY^|LXF(L|$k5n6V*=mnG z?V|IKi{;h@OvM70VdwlGoVz2a9MR};zvdj(!Xd(3Qnu^H13{_u5Pzz;-h?$@BUml* zyyv|$d|~G2kFzn^;xHpF+(-gp%Y>X@W8~>DGXAC;2ZUt6!pJv`I^a+a;(NU}_L18u zf_1J7ybF#vI|c`Hh-WAV9Lzy)#}C`#K>NJhcXSB+49S>?3k~5QZiw;OFreR*K-wVK zr;of8de9+n;WvdKQ8JHg4L(SM$>JdLTyP)jpb!yfi-($$LQL5Z6FT8D8){64O%s5S z{~{?=ak1ElFJa;vTz@_rv$_{9xTpZ+3mwNc%G*!cZ$4rD8Wj(X0^4*ucb8*%PC>Bm zR9j(XOQ!wp9sBoQv@jyy^{b-lIi{NYQIPQKXX|(eX2hwmD0^Lf4+bKDiHM-bE=*v) zn8SYGK!nnv7a5*B9;8hV!jB9JA;M~%KxgsyTyf;x9hf!_G(LjZ8i8M7!Cl!fM;6S3 z40j>HFOlgOB_GF;{R8JIP#ciEJvaUo5l$c(2Qk!p`JkFazS)DOYIMk8F+`6AQ^kXI z%%SQ;2!sn#r+@}H;3-z30Uj~{f~auN^1M6b8K@fDNrMf^zXqFUVUFWqzeX`2FVRgB zu-WdP*I_2xp1hbviL4>Ld1Yt6OS)2=Qqf`ee$PyZKQge}ET~)ZRYzc#uVk;U@-uK+ z$8kP(lY_rEaN-;7lZ2inL0_aEF+P%pNI>wy>BAVF5e!5G0cJ@_H;F`i?1qQ2vn}zk z<2XJv2NXu&3nfDhST{FXgZGyZGnrBoSC3ykcYrHz@KizdDjoiB2X=-5J5vwqg7BT& z=OTT}HMn^OLPB42(7DqxJwQO0hT*)>1lw&V@JPRXdj0b>IAV2Pf zo3b!~Fl?HOv1D9H*VaCN#N}(9nM<_z-&JjeZ=zL2I<<+^^6#XQdP=FA&Q;O;a(=Ok z4JlVL?N;kdSBd#waW}e}Xz+STY=^{w+(-K)DRj|QCI3g}VN$Bbe4h^?(%N#g`f~0k zAn0X}kF%qF$c4THz8TzOJQ*5DMx-5q!zr*ZCcHYt;sObGnT)t@4!TYvU*{kUaiFdd zI3&W5`4QeF>f=U-m-WKQEO?i;oDhVUzw29_UH_$4>!u?6f45f;dj zN=ujX=WY`ob={N*t!H~3MNi4?Oo(vT~p9Hu!MA%+bx};9JIuYGq)J@%8Bm_4i*SfbEiXtKnPy5#Eo=BMkEx> z(X$Z&Inq@IYU3F++yy4|r~C;r^My+x%mxP!Gw^{hy&c&i2P&Y)IZkF=-meX@q6pb@ zv{XQ_eFGfCkOWetU=DyF$B57YGDe<-9^lpnToePitEzn&eobaD7sN89@rR0mOT^pQbZ&@oK@w+>hH={4#UMArz7rHc+TJl zt`HppNzhpi#-A&7k#U^Fh3T^3GoN5!93K&hIQAEwQeb4v@}2-63BmK7XTpNnu#-5D z4vQxwhMBNoWq$6i99WmjC1VbZz=TGSeOLjo6XtPn1{98im~!ukurRCL`yh2Xm=||1 zM~A@JV0}E)z#Md3na{2S^BKomWEh8w$&h@okB1e`N^G#PEx+v+nIxMhJ$~SGO_6pY zJ?}sRcBIg9=0dsGWPOY8duV0DWy!w!W>Y24W9QG?cf68(5K;(CJA}|YB>QNkF}B+L zRpA7Ey-36|5B&SpczYf5g_G*T%JF9xMBpWQH&Ro*C8rFlF8-5CpF)H%$lq={eLj2* zZmD{i1;50G1(Pj9*$8{y6p#&^=m-ZkEXw4*0}jM07>4@C6o+N|Q? zcC*|#yF{7Mpc=D#=v2_(fWHAL7yfHdpP#-mo1&_lKQhSJ8O5&FrCj~5{O4%O^~YoN zMP-hcfYY1Qkb{jOwdUS!Wo>SaajS*NWw9M`pO)8B@Ap^D;9-9-xnC<0UpNvrD?3$aQK$PhgW)Q$m{eotHOlfj2M!dxMed@HR-XQjLC)U5DccN;PIF+(R znr2P(yzIc{jWqx_9}3wm+qDIF6^|{ywO@PdA!q%uu%_&-UjKi`zlL#hl=t%Ia&mnC z6?h48{6T{xCIYsP@n`DsT(nX9QkNL2`Z2P8IQ?THlO7<14}I`}W_8)eU}naN-Abs! ze~3qIvo?6X_d~GLJdzR}?!bC6xnW|C1AUl>s#0LbnUJGwgcAX54dO$yKo^NnfC$nj zLLdBqnz9oyoOuN{NXT47y`j#G3^O_UVF4v!$@VC$5j~&K@O;6{>+({`_mtoLO6S)b ze7D|1ntRShi0|LoAN{*e!Zt1YDW7}N;!lw~=4jcsK>k3rfK|AsJ+E1m&(X_Yk&t~Q zDUMFh$%xI^O2wda13-hns~*P-t)&(qF7B_M8U1w83}%q$cySP6OdhP3i=XJ*OeMkG|-5@x`LI5Ode zcs?@m0v{7*!v+npKnis5=qy-0tSAM)~Q4E=g0Q}+>YsXub#L$Aa5)>p?oqlm4A$b$zA{!_@j8C@6PK&t)(DjnF-k?!FMb6rU$h_+lv6INU`1rEUq+ z&-nRB-mgrlfk#@5j}+Vari-~+zDwEXY!}cugx9TXxqWzgx)y1O85FzJ|Ipy%XGLsQ zoIS7ZTI#ME@@e?=tpB01AjNW(rmKBxC&WU=YSbHp26klYLl@N4DpU8pJ`}&2 z$WJPb{9a&J8dg+Z_B3qhf_DG=4cKds02qd=echEy zma8pDRxMQ_ArKEqZ3#T;rBh;vgVbDYd)EbY_uW3@lilIJqf4xBu0PN&D}H%ZySy@! zW`DA3!ed88eSJ-cQ` zwP4u4i87cg4NtRHhsU;nT6#1_6&46rG3Tiy8jsR4F>B}!=clCTol8?lKN!E#l_;Ce zT7t>aiTM;wGMyxIy-hGdI;5i)kw?xHJqh#4o5VxCt+||7<%blg0KRFbOZuR-(A*P) zZb5B_(4I2em+GGN|3yrMM(NFz1s&a3tzX*%J`k}hnJ$Lm_NIXukPX7YnptK*xIew%#^crGtNSAEwh-o_| zeBDQHLg&QnSAh2DtMWEFCH>?fZ!@PaX(xR)8Ie zvI0Ky$bH0olrqQ?TMs^XFs9Jm%2&7#mL)_LD3;j^b=_$3t-JVLeLmtr{uSQCYexUd59wa<2^lVX2xpIak^q{m-M&*Kox29Er zq0$+r@V*POLDspyMB@R0N-N(r24a+Q4cMob$6k|qP|q$(2YLlWd_EAR;6fHz5jL?t zmUZ_On60P3mWj%={ghQ?-v>@mtYqj!IpqZ*#6`9x2*Qf{H73t*4x-_jT8)e9M%RQ+r2yj?ut-hw>#@G20_ zUA$#@mG79_cg@cct2ap>O5NSFi^tLuZ_{_Wydj>=!E{fV85_wzJX_vVmvv6ZIq?Xu z?A}aK>zuy)Sk+cgpL4qB1K56ex{reuY^*4r-yh`YH-VR(;f1>UF-2r^=&@(0X8@x_ zh;S-H-mo&l)z=0pG{;29ZrJf@sn87QY^YJ?bxep21jn)f!jnCv5AY{o%s5o(IFe*9 z8Bq@~{Zb1x^(q+bOuZ8=0%3{M&$c`Sr>Pj$^EVV zXt=cJP8?0CfSYn+@+hj~W&oS6aU$YyXzwMNawV}}i=LJlLdHEIqT9)(CGp?mn_=HD z!o`W&EBb4}bUXWB#a$I|YM$UMeRSlruK|6JV+*A2xfr(u0?eH(sdpf|%9pccU%>(X zOAN%Ze||tw?*8EO4(o)PUXPs6iAlj!R=jMW1s{aY%dj<1PyprgPqDk=>4Xg9}X0K<8yNq!3`&oe@hj2A$gTg}*63k4IMlC9r3c)$Dak!lUJ z@#2>4{q$Rk3L)NCy~mK}zI16; z*|Q1RXbI=IUPs7B?%L_?Yn4bnZiW6YPSw*KJv>0c<}js|Wb&*1DeYpf@KQ!B4uAj4 zrF~Eg9V#Zm0PJ|aJINGGV4SD)CvzX8FRAy*Eth=53c3s9AMj5LGw;U|Ti&sp)oI659#qyE zNA7u^u>YlTSuuIBoRQtEBQSb=&>}OmXoaAOlspPi$od}Lo|&OpK~TS4!k$bEkHBTv znr~wC32f=`z3m|4zqEfZe`kHYFjVmfSUZ2r@W^u`%*(~P5_{oR7aQifm_uQ#ra4&P zB2ii>kq8S4hi;w#(S#x?Fr#UZ^jH3F*sI${VZNWFKK#};DwoF?jhXkJmjH|Ir<0)v zH*}BxR8s4s{noMg>D{P3dt>o`HIFLEBGLY@3hf(WOezn@T+s+FJNZDzI_Z{Q6t4&6 zFtd}h^*~82#`g8L$+?h~Ed$xAk}sW`(~m-m!c{f<>g>O_Wg9E{90}Ot(>Uv?tREv4 z?rdVavT@WIcj=~#?#acGajuld<=mA^aBq*@1bw}h?N49FF;R3TwDOKM-$@b#*J8$} zsK|#2Awl=6U&o3|(Byi+Mm7*pI@HjWDhlH38i|KE(L;L<2lm8c$noS-gpV&m6-1Su zNLNaP8m}M(9W(?L%QFpAxl#${XUpPhTW;%`QUoLmdrXp5HDz}S6VB`x${3+u7&fi1 zs-&o9CQ0drQ=To2yj1l|l8;W=n5}!gSGP9zC~-YU+1;{2heRj?+N(T8p>ZL4G-5ueu4vNcS~HBoh_lX5`4!{A5 zgmz<_mcP64!5rl*`2=}JY*w$(WU9e5&M@KNt$Cvg|wno?g_t3Xn%UJOhI>5 zA|+O$n2RD$o6gQ>ULNb}{f7F8QcUW%e8+jpjOiLx=+96`ZTj)aInD4Ugo{#(lS;FOwiSFL9ZRYY8c3DhYpTRa;HcY!%XNEejVi z^7$1^&Ke#&TNa<2wDGwhLw)$zEwq^xpLnm%F8l`Zg_}cH?j4*_+5? zZl|7vHE0>{$=s2m88P1#3q#b6r4}VH#(&eS2ubM$zt*_k_Rc4QFEC zTe9&h2;&~G5((=2Ej|DTo^s!(29WaN2?_orM1Xl78J|FoLio5sjH3{St~4G1L_CWA zbC9-J|KyRaY`#d*!5V>;X`N}OWI3;<>`=qWqi;8AOsf=M;)`Sx4i3-SCUENBicDrc zrks|w&G@w-F_(GvtB3vcn>fJL*TBeyhijkn}?D>f=!4}G7k(Z;MD?SB29_$?zwaZTVCMJ4j*ML{*(G^ z{79$zC6&XsR1){gQFN=!fj2{=>bkSZ$)N+M$qSkH%a9LupN4Yz%(6^2^HL%fpP67R zZ@8j0O-m~{FC#9E)+;LfbV&G%Y~8dsxh?X%o7ve%kbQ6X8V=P5{X2c3;Q2se>X{0n z3*4otL<6vYC8Kpz<<^n=J@z;gHk~7*tP3Cur z^Z-(-7ZZUvOjDeI06Z(ug4lNYYqrJXj(&8uAz%J)M6oMUW9rDv0#rx)mG{pyS;zQZ-LaW->K?#A-gi!tjtOSlf8}VfULHrIe=qZU&Eaz$`1u><+ zxoN!RN1J>&SM{&p@`m6$#+i32rFZgW7c5X|1uemgD1V3kRhZ&ioAcCr{kbg5X71BR zHmb3ob5>zj!WeQ*c{!W5r&oXXrBpQi3{U7Hr2W;A?3+-109NZUOzlgoeKU}DY*n%E zQtnsQG;Y`R+3fTvTg$A&Dyx%S)JDY3wMTUvJH#zlTSMGcks+JoLU0*m3Gj6rIu5_j z7s3V=3?c$t(SFQ$n^b=Il(Mpt?8mEBnN6v8?Kq(^sFk!Y6COf@Uv+Y-O${@p2M(Y7 zqB>shJxmyRG_H`4PPJc_de>X%rqc1OmY^Cbk?=)w!u*Zq`rzrD+@!m#jHVdNwO^VV z4MLRP=#Or(1{bC~iIUy1Xmv}@%}VIv-Z0+@biP^w_@MgJ)uQqWPQ(J6&uY?$lx82` zko_-f871Eht2n2T+Gcwolp9YbQQc+FO@2g({d5ThQOTf$5FDS6%A!pAB$NTgFTD<( zEP3W`bjR*>*xxD{r@5)jO{SH67NlahNdYir*~^Pp`; z#Dl4U`7dwxtabMbX`i1NSgYRE_Nn79YO+a)DLSC`+wwhNAb#?)Q@Kt zLbwUmV#T$|UT>!rO(q{#>pcF@bHHqRV5F01+M$pwjUH4pZ66h-hg zqo`yFK3r-1f!hc_qH+L{c95MGBKW*nFNvFUF4SD0RYgm~;i~7Ir;~2h$z@-nH7>s5 zJ|(<%%ak_Sx+MD=Uz)rl=Qs4y07yORcx4jh+#2Q6AfrHy?rLHTYu=kbSXo&4ZuFC` z>SUH@rXm4egk6 zn2vG56Vgd*XJ&cB$y=%SKdl6F`BaTd0zf6WJ?dEWW3nMGG|~1tuZN~Xd*Y<=@!->T zgrJb5pupnOXPKtzo2y#>0$*pXr}L9d>rAhvF1=xze(`L*JEIYNE`|D`E%mXb zYcaGxi}rH?dCr$UW2+{m=4O2AUnrrvAXb+V+bm=3<}Z>>Dhl264KMF}p^*{Ng9yYW zbncBDD2?|gT>qk&aEl*8t*;&{c$cZdwf08eJf3h@LgCq~&6{QWO$>vqP?srBcOluh zM@5{cnNkWLjZ*F~m&Bvrl25c9>&#H{c-vcd?V6lIHe~dBrQvpdDT{@CL2o*8y|j^C zzK!2zsRVbb1b>grioX{;IDu)B6HrawUI1#Ywv>IowlmQx z*RYpyW9C_P-et}~Gx?3D>xYUes#0&f)ZD*q`gb$s$32w!B1-R-X+@OyHNK1pu#cJio(?Otf|n~`=QT}-z>He4sQaxa27@OVKm2huRqrY?&&q(7CLY$ z)+^Lj!vPv{T&XpfShcM}h|tbx)b!3449^T2doj2i(H9Rz@cHrVJV9yAG7jUlT37b- zo@g%iKTH-I`#vGS50d`{gJVJe104qO9$#=DD1rAzOCy9NaT0P8qAExUZ2`$+{PHGf zr6UsZ>e2@lRn;}swR8*(jgK6&G;_4Hwk4h>p0_=D@rZ?+n$Z~ry%P%R$0b#5u*y#8 zLvA<)FU)}mj8-sC*F*fsc@YZ_(PP&|jYAF{p(z{R7FE9|sFWpc@IcJynY2!s*g>Y~ zL8gjInVE5^`N?NGZchy^mzZ5_w7%G;AN*E}TCYTVu9)^hJu&|THQOpC;b=et!TX*x z`MzvqF5a(5>hc5W(+}}>bWuC1?1kG>#7IepKyh1NdAmR@*Xx9fF*+ARt$c%t?w4Fh zULXc@T~Y+qiIn8%oqOJ|((_J}XKYzSa-JV0HGoFDc{e7BmUJ)ueo{tW z!lRt*yys7fN(w8P70+JfW;UlMv1m6wrbP`z`+f?&x)gGDDbjNOmf_g-W7C(;Oq@B& zwy~W#dhCPd=?_YmC*(Z3q`jJD-CxQ$)=3_#mNb1Ut;Ld8=oD2PmD3#&JvktHVoJ<> zMO1s`fZD3C?2?$+cPZJ8L*lyxg&AX&IXjV^6JncZrB*Kr?|Lb(lZC&Bi~hVP^dsjW zH^+G6(b1KvBiycoyY)g_l{juQZoTi|@<+jyX_3Vxq47Dj{sp0)1)=5@@v5)F1?wX8 z4YfzBgo-u2vSIUAvkot2F4j!>v)0^4*Lh(Z&fA|Z?XYfg+iq-e5~sEv?9AkD*4J)z zzuKLy*xq`(zBBM+b?V2rjh(&!{`Kn)w)=Y~2L=XOTiaeY zHCNStu6VOkQo8ddce~{NW+ip4ENt#cfy5BfRTrr+m3(qoju)X2sjlSV zM+nIs|~#F$`Oq?yV~ser_I% zl(nlb9VxWQQoGbwUp87oEVO%S*HHek!nMwSrmvx5yqeUWENlO&aLu3-Pn;dSj|e~xazmx0%H z%fk$-6gkJ{`qfd!pI=sk%>_(SmFGzrG3&?`_a@<={Z9!KgegWee7)f}zFMPMcZrTCiT77`;R(%z5f%u_kMjaSS*0lnu$ddgpbhz6 zy5>8oe7^80FZl!MA&YZ)g#Q`Nn$s>S}ih#{aS7&+|STc z=usBowMh*~i~Om??LBlgS^aeQ&o_s1w}0>UYjdvV4rur6>7;dd#DLM_I76nInaq6F zT(?|U%zZPYyF!iDfUn1JGFlI{0D;ywm6&2D3Qz0w9k$xm9yMXy6Z>y>famV`eJ(|_ zMJC!yvx()mR`vrUGnyAThuF~UU1%d0^_f%-X!Xg&e$yJI{QIGo9g0*HZ#!H#Y&sS* zvNMfUA%F@!e@74RYmI~E?+H7C?#v2F9wjwF?Q!oq^e%l3yZ_qs{XdpYAJKEzv=^@s zq=OB+GqC(Teki4_spxUPrenM9*JB&Ke(LM7?=Oxq$$dx6(ro--v(c&Z*H`|u{^)>dBjk3xfEVancokavTxd<_-rW7?aE_yi(`Df0K9du&q*9gt1=hCE!p$Dn{+{2W=ci;z00xx9QIeY|Kimr+)n` z$mSaM7J=fm|GTGK@27m);neL!n`zp;TsG_w!2=*x^B>kD~# z_tO01{pM?y-Y|NI$~dS>7>~ggq4~?94(9LXYG5(-$--L27#J5-au5 zwM(z#1m>SpY~~1IT)Q;?wKqOi%FDh>hqc<}#Ttnl-FqnAP?i>a4M_jsYOTkSz+5|A zDABV|iEqPSYjw(3jd(+r-4LM_%_+ta<5nN}=e|fW$WOY5)0Nk6nry3e9L;18Ea+)I zPQ9HI@-V-i@0bYTe&eFTgR**gb(h>T5_1X5mb*l|rvIr1h$LENeQ0{2|FZSIuS10Ud*2eHtPl+Oah7D*aqFY=Noc=? zFv(pnYt!N#^tDnKsUSydz50w}O>*rL1HND6^79YH7!2OOE8byrOrs7^XZGCgI-nyjUhZegys zC`hf-yYxGn(bt+X(k5{07eBh4+ih-mCjI^8#gBcL8?5KwF5k26$j!(2MX5<08a<)S z@IV{+4}A~C)2l7bb!$ZdJig}I~d!x4JY^x{HV0KQSmzF{HQ)V?pe(o=4W zlaP3#<$gd%eeqsSS)#@757}*FovN=^Q#|(iqT_a76?ST<*rKLy!y0QpCU%`wPOj5; zE0h}Y<}>(2y`n!PEIm#RI{Jx<@g=oOjFYckdd*Dj z{Of_{WzJ(4>D>;*o%|NBZMS)e;-Ul-2@uw)TS4v{DZ%$-%l!zLVCOGijU*q(s|VhX z)fX>H1b(%~-kFHa{=U*MX#K|X!?Wyelcke~s~+~-gN|wcDcm3?va zhFE~X!JjDKR3pbhg5CjfjU4xwzO%ic@5@7-shC>rF#1MN%j8=xwK~tf?b09<+UDeq z!<5oivmgDQrEac`uRdnoO*m?^pME3pp{#m0U*L%pY%ccW_>04fCT0gZTub&|^vdld zKK{EJs&#vHf_UFP7i>6 z{jOe z48QA@4}{3s_@HrIkfd_tuIAQ9v5o9J*aaeCaD zbM1QY3b0DYOtE|dC(u{nK|AMt=eh|K@M~RM^qP6x;zP_N2h~JG)4Fa@XR-F*P^b$aV8IS1oP2^78ZcB)~QWA5YFK8Bl8B~enPsB{TirXLqu6#jkrjJ9XMkf;^o)CY} zI_?7r%_hZ=;uC*=*Yqqg|CxCAHP6?POXwnNa`}RB?dS{e5T9S@AK@V@FT%f^J2$6H z1q4C`_vjA|lQ!`gf{7W=C6Z-*snUDE9}4Y-IChhPE%}*Yr9>_IWF^=G+T|u5bji}4 zaC;^hDD)cpa0OWB02{=cPsLKZPsY7|9UgBGVT*V$v>5L{5k5&tyniy=4iU6T$IK>B zP%4pAZ0Ak$+XJL~>uo*>d-qrONr_ttfd2$Aam{;@i$*Ix>>(yNg-JAVHD8;fb7?;7 zkh|}>kA65ua9uAYPeAQ!EUlMl#XC`DA-+&q0)E` z7xe64bQ03vvpNwgvl6ny0^w|OcNw58!xL3M&Qvd5C|M1yo=7P;;+^~A$?MloY`d=a z5HZes*;cRf)=B7uJs>D5=Ig^JGb)h@IcfJF0mJ53X2rBSh)-P_(>D{ZbEER!tfoy7 zeb(r}4CgdX{84C<^c(7-H7I6Yy?)BPga?fW%eD{zH+8N+IP~2 z4Z8c;JbRMIQY55}HpNfjDwYxV2g#^!rI=xYS|q>3(^^yq;c$;Rx|@aW1ig%MK@Tz0 z2SAv?=3+mA`z!csUFKKbaPJI~%jE2mR1$&i8^9(Z>ERwo@Fo`1N5zX#OA={{-6=wT zWzULB1y@2g@EOKsxBhaO8LIx!&t(szE`5v$>ADeP+Y~=ZuGsTNPvL4ujS8nGfG@r1 z9o9a2oB3ojDrSWaEYpE4(ETCewN`@uv(iXdVTk0C$Wlq9yLrvcQA{h8!;;k%uEhug??jD_sDh(K(3HlGG8)qA6dq~27IH?ST8`WFF;9>8Au9MtUtx1Cl;ng z70oIADTO_GG~#$gZT*E}o*+i|7JZzEo?rv3>@?Y1F^%Q5nsNiye-`7%Ip`sh?>Z%-BBi=Fs^0E1rsuc&%>Xnn2YiqY3=$KZ_uoih8eAI*CBA!T zqm;;vSD0ZI=F1eOlZ6=~qAvYL-+c%urT{!G#0~ZLk?V~&o;1$lfq5LT^9Mc&0z2Ta zYXs~vE2Rfjx=jYOP^DWWK=HFx!7C6(x&Vo%!uqHT7pkNyqvTa}nkv@e#1+5SPaBgX z%HK4v5}T)&3RjtpGsNOmN@e$Q+c2|Yi;Z!6-1a&Nm}O(8t=|rEP=kcL_TT8et~=ka2*?e?hn(uzSzGT zBmi8WcT=1vQ0I!gjePo};|WpEjoLEPoR+%{(Ft371z zt#$PIhuxYcb+%KOO*ZDHI&ut!9ijt6OpJkj^9&AH!R4JoRbGyN*`C^B^`>|V?`_-C zJjKE^Po=r{VG4-o<)gqf5$*5|IiL6J-t3KTGRoH#W%1W%JpuJjy~7fHcX9wT!$mK! z(evx57hL4UeiVmR zE;B%i%OP8=rs5^Kn%n+OE%C?vDSa_&8QXMV3|YCvLC+ED8l`)8|BMVV0JHMZ6;8j! zX8(~H%nGhy2sAKF2IdaGTO$KgZ1j2~W{Xhyf`qI-+RptG@BE_H^?dDThgZa>-346a zTheII0P3bn%O^Vho{+Ya^D9bJHLi9`bnYv|>El)W2j%KYUl0r^WB zDJ6?UIs!|0V9^{{AOg6}o5x_NC^ml(D+kR$#_15@0F7si+R&HjKg-aT5i2*)Cgqj1`Hr(FoR5BkPM{$ z?dabZnAl!VYn!UvB6Va`wrAX^D?0k@0urNtbZnOA7DMTrb4M+1j6=I5uB1vs8}Gaz zp?SiIQa1Vp8(qRdSF^sB(%%hHkPRec1HPq`*vTNVQ)Q8<8k3o_lN=(JehHW(AQS%~ zOS$L<4u)qW_4~>D&dr|Gsz%gx>@o?9Bmqy+JvbFCgh*9(r4@9il$^V1kWQU$!pyTP zOF5YF8O#vw{cqG~D>Gn-1XOd`x1>M!wT%2#2MpZ@207??O8bWWOVw%KGV~1N+V52k z6g>g@V(KpT75{xR_%3fCpNO;wn(U;Y;F`!a4Yh^o&dY&Sv528t^{)Go7`DV^WElbZ zRR-wfeuZwK{yCyvP>{up31L})fdjDn9Qq~fED^g10`kd|FDb|pA}V!2;MbG)`Tu4Y z$c>Bi#zh=fWfx@ks^c#Ep$pc?QTiD$_FwX9T=kWsghZ-}3&3A}NQ zJmU$-=*WD^>LQM}B)}qRRr0{>4;-?Zi+momKbwa`iW~scswaTkYryr!1rip(B+Zj@ z)q>`9uCSKPn^ws4Iw_+?Zx+U$49tNBZVk31ZuS%nZIu#%dJaaSYWGjdZt7qogC$VP zZ2oI<-vaoUnm&>d!+wF^aM@f;KioU;2VKBzJ6rjFnlvl+4uiOatf!+o@hjC7=>{S) zI(YfExN8HRTS`Pr1Z|g6W)qKb8|lbu0_WE0%>p7a4}^S1*vaDvaOgX-2X<#Tycz-U z)C5a7r0fACj*D5n$Qz-6$gvT$98&uVHtRZ2w#Cjc1ekXK*{>LiOk;5xHOr(I|MuI_ z1HA`;g(*Bzs%ls5e_vk1 zlg9^|qYM`_=NoVSeWTHv9>^}_2oy5@(Jvz#%)9f++l_QC$Vq*i<^Dgk-0>XZtYth# z)+|oKY3_J3LSSi5iTP0LO11Gj%Li)@Z0HTdk%Aw6V&&%>>_#kI)OZo}PkkdHE?Z9; zL%+1#TT|_mYYP6sdQc(mZ}Hkk)5;Gb+ILokaco^%ceKk5>LcGDczC0d303 z>SwQS><+y>aRZof51(I4M;$rk+<0x~_^haMkaJT|DKSY{KgwN&SYQ`%>qL-q>FMVk z_fUMvJlJ-+BY$7*r+>Dt=dkaCGbYh8Dg*OPPj87CW;X>5e=pn5Hph+6`W!Xw zeY!00tq@%8W0iY@!-KX5>kq3};OdvVpI!R%bEDJn=GQ2h^Ht{?lVwl4*n5?KU%k>0 zex*-T`E+hz(C39R8AGy3)$ZwXnOnzI6Trne#+YpT7X_*!%;S^DysEy{q_#pH*(dhJ60;Wu598OMchqu??=4uVP|0}^inb)1Mi3)iu0-{QN@vs9I2LL|O*2s`cT zbSgN<$assm+NpXQj2U`df7Nl^VxyBx3cHr)6q6G0B!~d@7C9Z$VPEIw?}x~9^6iC- zk6f1IKV(=nzyI>o(d`c50xJ2nxA8asd~YK<z>#}a}X_=MYY-hv#qAW+_Ux?D1_`}NCRZ$SSOgZHbtgWic ziKKz+)=rQSwwD12M5HjE2wIy*AU<_ScR*Y6k}6y@G*cRGSKbu8&AWMA)p>CGlu@U& zisNNZ3;%ISmy@vd*E z`+jGQt*?aKE3!Ikn!M@9k>w>SIi?<0or_GUEV;95 z`PCm!(f8GosloK!rE{nTyP?jm9>EeBU^ApyE_6t{`^X*J?~bpC+)i%o|1os#VKMA~ z9G{t;-JQL(ZQE8$TTNG6l9fs-HM?!KU2Q2UVM`K1h!Z-_?4{b0R6+<_LP$c0!fb`) z7D95{5+~OaCw_69&TpP)pZ?hA*{Au=eCPZ9e%_zY=l#l@zL;GZCk$Ryncy3KZO=Tf z;8wo3X-Ix|Y{USpj1_l2wm59YdKhBhne!?KLI>7#DSFJDg)WTUCj%2Q*U&0wcdsZl zkFQ#1ZlRi3+OqCmP*8pJ`>u{_i|4~`rn`ct{m5Nh84$?7pMYNOeGo1B_wA0=S8nE* zPsuq`$d7yfV<>~3vr5mO?e7`*-#Krm%TYcK$Y#+}G6|@tb;k?LV>N z)f=J$))?!V)?H3dSs^av>BnbSJZg=8@F=>T7qufcZh*GEQ)QleO*HKj6rvo*P7}5( zm&wy6Q)hl{7ldCfoK~%;9u!_X@?cF`Omm-bSmrAYFwt6F;389g!v6E~*v{MMgw&+0 zVa@9sTt6)(fAZXEjD!ZryzETn$c788F}|wbxP1&tOe`AXs|SxJ;!b{FklDVb&`{pQ^u;p1gp*Kq4%|GtHm3`VEn&}owfs-Z8Fl$J%G1Tk4UqE`6*VHoEOK5;8t>{adl&8ak6V!+OZomk z(ncc80^)p?MQo!CuG9hHneAq;hGob62DTZ$Xw46fTtC{@WjFiz(c)_3?3m*|?#GIP z=k>4HwU;Podf#86`khkYGGTgCd`Y|WQNe_^xm4F`ZLN7@dw8quBSz2>b@(3cp)$WO zf;m-bVniskH4Hc!dQQgGw-~EsXNB*EdMsCNGF>;^9I@+srM<PwIyX|hh zamzk^E9pTR??hjXc>1*7sFd2OS5=+P^3!l!kLI^;ePkoAqIfm7gTeH@#!Id#lII;N z;`YgA3bSu-%1oVfgP%VmFm}hUoU~+#+e8sDXwp=6$oAz}`J}yX#yw`23~othvQpfG>Wp7#VB}ilwUsm0x?F$5xs+*Ckhi8Rd39Ts}KWKX_&|B!-?^VH!P9Ir( zxb2#IeE)ohv%Pi?ew;K}_MtebSz2(uX-Q4iG{&2^Wjz0q&m^O*C?c_z*SMcVLVYor zl$FL>n2(#wPvb9KmB$#q)G5kxMnn{3p5{FrE@h}9^BgjE{-AB~K2{W$H+Uwk7hWt@ z#l(-*ijQ#}Wh>(LTzl$ND;ad(lAkoAz%s&Oe^+YF+F^#x%T?xkfY(c2{49!Y`pIKQ z^9nw_KAzn>CGH<;-&J?#a7Dl_-f_jl4C>mg35OkG${rwfeM9Z<`A?rZwIS;=lRHHB zvUz9mkjcwuvTT0F-AdxDbGD6T#N=trQoo;Z@<^4%je99sJ9~h?L}<|so8^`}6clIA zFD9F-R~$dco!AgKt!TBf-Fok@RF_ppi_XPGxa~!$qPX^LKX53h;)6^i{6?C-KX++V ze>{;!0{iZ++Ms(Q7{x$%pZgYA~5;s@N5Mc?Oo{b)H^HhprI zfti?f(c*RE-&0+u{U(o3GbzJ69c@#KLK30BD!39Sv|P11UTs#H+v(1sZjGo1d6i?d zgI7<}9&MrU_A7jk-}@C3l`b_ua5R3{`GRM*a(raw`*XfAfi=uGmzUSmE#7{7pApo_ zaj)N-NZqX8_Z1_l>EAEPVyEB#am#Z3)&00%C44OW5!6~;xqSWg1)E8y69?g;F>Ux7 z$%R`Rf4{%=+&Ytsmzg^=e*f_2AA*C5OqM<6x1-G~ul4UZv0-j=+N~X3|2T?3M!4MJ z_CKfKkglN1>$If3o>|}3wmI;c`S9h}J~KCK<$eD0L{&sK#1PGxGaPWw`uOS*XwFE% zUH@}E|FoGkY>!lMl5;tU$`dhT+IV6+opKR*U4^MCZ}b!YrsWHZ`EM`6w$HV7#~UNL zP6L}~#z#^+*HY&?9*;4WTWxipamgl<(5}uLuZV2%;TKo3nS1OUJR(}OgI^DyxJ50W z7Bm{%5l~*5(nL*c%0HvYPg#4$WrgRYL)y8+LE+hO7*2MSYun5NLK8LKN|5ZWzVXoi z@(Q?PoitQqz$!{sgT?nBdee~^Wb(2je$4bS)e9Z-S%iJ$C!gOc<6$>a~$KtD+LA;*>qRryqZ^ZszfQ z;+WyiNacY)YAU0Q+S@HQ?@z$(vD|a(c3es=P4?RpxQrTErA;RCr#N0sQ8wB~cKkNP z30$^gaQW3ib;sP6e0f!VqR3yKc}702%%8>Y3e}RAsI|z}SR`t^bZ}rD99FNLm8T8O z#AKOp*z@4;{eUi2QzDbHbo^w*p=TDu+MMLfS%Q@2SQHGC#gf9dJ6iwjah^A}IpJtw5uppB^4?i2{1$MgD_nY|sJBd81Js@szMc?bf>6v?%S(C^$3|PRh)mE6{{> zX=vKc?Y*rPvWSWt?RdBjcB_KoxYwg!Yirk9EX=xC)uDH42#*_6FYXL^yOtVRGhNK? z&TNAhemvv%_u(ic{Qbnx@T%=mW8u5&Jfg?CZuL7w`G&qvo)D#P*R-2P3hwMB+LN+( zoQ^&As`>DIk!E{(l(pb=nh^-S5&SM0cGDS?vG4 z4~h}zC;3fy1a~-6BWh$3in>SP+0;(|ZkK=MVT2U*o{)1w8&a=*H*tn-#LN*{9DiRU z6d=02PCIspI&Du4`mAPRF_qBVx!pVHBTCt(Q_mkJfniP%OkSFOw3Yr1*$?Lz?1cKx|ZqRw~y9=W0UA z)MT5kStcCP64fmunKnuBD`o#a3yMUk^6Z&wPI#QCgXfCe{*2GxzKlxGRmZi!i@I9} z;d>`~;rA60sg>8uWHE=>;cE^}57TKEEvMSG2Th`eLwWG%s5~AH*JVxqP?0|$qs|r` zJ{KJMEgk-@rfz+6b)sKe?#`eWXP&f%AU>6sEGzO;%JP#CT9T0(w3F(k%lE`InrMwr zuBLdU#%DNDCIW-A<3oJogAeygdlI)rYo#sm!NVy5iCV4*9QQ7RLP)C-Ib56q^DlQj zKG)MxDgU=MAY9OCJn<9?@RsYe!nFK&T~H#L?~djttu$976_FPS z^2Bhk2n^}zl_e&Iis3uXuoQ#MuNY-wt-l;LQ-BW>U|%jAk)VCDKk8<);*KoVVu8jr z7wWuqbx!NcAODh;ZuW^I>M3Q=)Xf2D%<;fM_Vt*Oen|Ur@qYRJsLoL3-C15?`gZNV z>*7xFuP;ib?%wBrGb%b-+~(O-bEO+?ZPrHT=Kmf~`A%*mO^c?i$oDb^Cn>3)oM+Fi zqHZ!#`hS|8_vV>_>hYhuX5rYwMDcS^-{-+S&&>`PrGS>-hnsY1_}Lms{gBCBO0e&M zR160SQfG-$eG|2oxdRWqwX=L-_PL(qD~i6AFLs{m2^(v5&76NK3;yq)n!BU+;Y~q_ zN>XE1b!?Wuzw|2g%=BZ;-S>sj|LxEQwsl=Tq1_RZ5R#)ESV!J&I6*LDB31U2TTh>Y1Pka7C!HYem*0Y za{YJ8HV?RBu4zT%a>=rSo6mX2vybC*f+Wr99nug}V$rgx<$d-tDzvo&Qw z`1-go5ok765K;+SCW8L08AZ3X@}8I8UF5F*x@})n*8YskC(g>)%P(8s?r0snnYG|l z@9ih~D6udBz*3_(TDTJ8qcyJd`pTZgmPz`g5_%b zQB{E8O|b8hUYd56VofmVEsnw%s+DlHtVWHr?2}KK+82O>`Z8HD@bl|^w@O~j_ZVNx zTCyfYaF&aJ;oJ+dCGg4&t(P9wG;1yNxPO-1{7t|3uZ~%xpP?KI{ZVjnN@r30-|re> z_M1;@9xn7oZ@Vqc_fmoa{oPPs*e#Rxu0reCr}j{4=Q&c%l(@(rC_!B9OaUzD!KaU{k#g56Jm4iqGRp>FrcJo%$j9 zxhLtElufScplDca+yRp?N4IQky&qK|)?WEL!ZahP;@h8cj8c$Am2WtM&d)-~?rga6 zztMY!^+T-x&GD3{Oy~AYZ=wivDsHCApP)SS0nJ3ynps>eHb${Gg%A8s zLk`213kUQ80?{{}tAw=p>Ot4YzLzqi!AUUHVtw|F+13ZDtfV^m>)WEe?e>(UgwGDsG?JlhB4$ zsXeOH-eYfP>!E(-W11Iv<36iA8|EJ?J$TC}mGj?6s{Ph{!XhQ; zTQ=yeG1sXC0+sz3h?c4R##E?S?Vqhl3{&|JQvyaPLBr|hUF59$NnScOOgVarBEdl( zuHxxHY*=%2(RWtq&tp$gEcz%iZl`6UhPi-Z()2w{^dB=iDlk1iEb-4jrh;-MXsOeB zC#pJn6+07>IvbYUdbD&OO&7YAXD^M{DICK}1(X0LsdlT~hT&%9fy9Fw zV6W~Z&fYM!3s|QZzHdIfT{v^g=&xzQ`a)FT)L*F^xN-L&hSN;kI-mZH$~>36mz4j> ztqm?Q3YW((3n}0h^F7?OU1oLiQl4`}ecByI%gLgXsrPk8hp?MekL6neV!wtIJQwsw z_b6*ZZm`ybRmx{NU@LnAiaUp+_sMr99$T~6Akjrsbm!b0ynerH&QxT|@tk*N4mI9s z_pP(U?OpaO+ss%BiH$mRa+B~;_mqe?XDkXPEN`(dwDCDy8FXPZZkPL+=WFAO+KC<& zHAJhFu{>G;85iwIykR;XiVmoeHJu|AVa|w|4&79VtL@hQQY8x4j((xrZD2o8GdGU* z-Pp0$M5;p%nmyQq7SxxiZ40Wxb@uf(we8Fm4d6{?LFSWvAqDKj9tU0Bh|b!&>WOq6 z)#gd{hGICGD=8GTDdVaz0-9 z1rip;e?^>l78PX<+dOJ@wfO;k=tRjK&#hVuk2m(GuT9+iF~M@&oK@6XIjz=$rzis; z%P20)#j?5Zg+2(>up~qFblWKk!*bzfqx}S?8XgR*DE?Pfm^SOz7mBUBU?5DG_iJDk zs><4!IF4?vQ%G$KKGxi@)#h9XlN9QjAX=fw(;6@Kf{L#5%%B%&K_l79=}=#`)V{~e zkGmRvdcM$s1VJrWdL#8l$^i|0rdqPPttRwn{;>ZwX2|q`YkaaB=BDdh#qKW0y&{LM z8>~mWzB;UI{!+Ly(`ihp$O2d_k8X#}KK;wq)!&+T;bU#&)bpbb1w2WKQiibNv+);_ z-Y@?%#d-%crt7;Dbl#k1G|_Hjn^C$bPu~PGelwOkrTy0XPa*5KX0BAY-gtUKxt2W> zL9+=7S)ErlVXvg-_Y$4Gv!J$%=`6@Wj##*+AvtZ~m0>Z?O(QzGo70)XYRa1l<9T&2 zydBo<-hb_L6L#9acy0Nnc&*OXrmF7xL^V3Anm@C#);@*_;uxYl;mxH@oHCB%C) z6GjO7I-}v$Fjo@@zoomNAY(L}1fgLRQByFZx|wo!zn*HN>tKmr7Y2^mbMuUv_dsmZ ztn4F2(G7Q^a)WijeH=g6u@`@R<%^zqN$34^R9P$6>AW`{^)Ebg=W{%ONcw1AYCyIj z;Lx6#7h|YChthZzJ+3p-^`Hd~T07Y@+Pp&p|!MmO0_6$p346Ng7?M6|0z_5Y4$`$szT|>_q zF|acfbpO#Bj+nau{W&7#lo&Z!Q-`T%55&_NP3=kYwpd(f^^43v%NMYX*rmX%BSnwa zr7hLJp5WD=;deu_<6ngj=@&Aav{jbTy$D+VwbK1BB(f^r_3OaOW9Zs|sBZ3QI=|8w zsKbL((lrqG97X@4Q8=GXACfr%!%dB#9JT^d9<5;VOzlON}sw3!9~{gPVE*kn~T3fEwy=I*RZkw{YWvn59tgQFE5P`1l=D z{|n)B?D@OS?#Vsklj;Z4eT+1dO7wKr5a&*&4>F68m=D7=tLKQ|4dfy)1}@=vi46mSlo8F zme^+^<<_dI>^<~Q;2@~4`NX~hAED0}O5NtS!jVuc=1QuR6k;-rj$~6OH<6h4s&?}_ zz4~bs$eP-vQT1?(0!V;{g2J^IJl+@FW*-9>3-5U|tS%!R z=DWBc;+4u+vkT%?mMtA|8K8xiSyESFl(ByFieJ@x_9j$g+iSei-asMWGiU!k5Rsz> zgq^Ko2uZ$Pu7rkUtH3CX$;(o~B_kTr=GoNM_XRqxpMLk(w^Oun`#5uolle3oD6QYz z1kKp|Zm#>f|6R#ZLL(=p%B4#=?!{iT3-SOa%%J7kgl2y#y!po-@Q zlT;fhxXGSZk*&FyK=BGIxfxTM>nMC#Mt}Rgn7y>6$bFOd*14#&W%xzcedY_X1(~~B zxrvbZ;4iIH_7g_9PR-MEsqXRtW~^^J?1F2ohtVrvUZ@iOn!hMD!{W{5I+ZEjQ)s5d z9#TnaAO`~zH~gepl5W~}Cs7@92&#=3V)*D)_SD;_V(3}jEzR`fdl;OJBPCHz*Y@w} zOm@M$I?x#XJzkWOyHO4R`35*4U1&I7z^-ri?wC{I4bl=Y?Fi&wdK(&`i)*|Clb8 zfCv|dltzf;OsRF$DJeGDC#Vrkp-D3?|NF-q3i@3smevDi&T%1a6-`l&!bnV1`G(B|Ywf+jRslA?rvJ<2W zzXK`6<*E2hnEiO=Z90M3wHTZdKwf;}fW?i8NISD0aO|1iDp0>4vX$OyVF#YCnW z`2=u!txV+>UmgLbBZM$LVPKR%U_kSt8q_VKqC`lD0UAlAIvM!7gRHhLI38H=!?1{7 z{?E=TUiAL*GK|?!#f-1DZw8p|w{3;mR>d8=-2EMJI}L$^0<4{nGe-{EvD+6e5ZHF& zdxk-~I{dj!Xhv73Z59B=V=ST6zD{MOByo03M@(hXYk2R3OlZT{oxr#Q0kDVWGj+hK z2HcikWZeb|^@I%~WwjADZ4x$tmtv~HszU;;%3v?#oj;T?8oc3m@S_BS#RguwftNVI zpPOo)WiZc^SUx{+eWS!G)L@b)96OvkvZuQH&TjF2z*L`dsGMt)O@1&Sy{EM^xoqwLEIOflOw;k=V9?CgHn2)nUtX=KeB! zoH~3vjStz@;U5HeRTl8;n!&oV50)-rf0WqO5w;_$f+;sM5Ghj$fa$={Wfeagv~1u+ z%;GSGR*uywlNRjCex`NqBkTBhZo@cXA5~l1C$Y_>vD*N$kizQ<#>x@$mEea|Ra%B* zYSSVAK$kgVl-Z09D=(FKC|*4i{J7?cxeVtAN-VPsmOx$7T7!AjVUu6BTRvgDDBO%> z85{8g?}?^Eczn2%Ne{T?8xemwwRWJwh6mUsV|VQdsuG~3+J!CLO1{subo{{r94y0x zx-eE13Cq6jzKbA9-!_8VP6r6231h_9GOKV#+k%c^iG0ehxgS!x)LT8H7aH3EKW57$Xw40`w}z1`|QPlgcUww8{dlKB^Z>GyK1{i*rG~ zhoM7~QoStWB=6{_e8;;#@@R;_TZ#opD@x-VY< z8(}{OK4^*n8XJP1LabT%3gi;>oPPVc05Y`WM>)nd3Td5$iG;x<%A5v4W*xxD1{i3R zEdkD7hOsIE;aGn8^MnsgcU|7A$mxxK1p9s%XkD}EdLsQaM)av#TS~WnRWVW)Gu?06 zjj0+A6G(RQk}se|4jESgog{=X3bYZM+5I|fiY>8k2G?B1#?dZZ#Sa_5C}A|H4mCP6 zVS^BE_dQRT<~dq4giKDASXJ@_!_w_PGvB?Dn)?Ff((3(^n$Aaif;Oo#w@6CYN_J$Z zEbt7=bc0C_xbuiT$4Np8^JYCbX9(l}TES0zH1X>ZYX`g4gBbk_Zh}g(&kRxX2zutk z#P)YonTj3-(6t1Td5e~gjjq9MU}#1ykUAnsF2d+p81uQsZySjD&p}o-!5A_yj1pU6 z`Gp#CF7$iT+P$w&Jo;V2_(gt+GYQ}dTg_nKw0jN;o3Lf+f41^t%k>ytDBE{6_xMncRXHUnPRZ0d~2Tau8Zov zIfR67*}w0{awj-(8tge@J6V5*3BRA+MVL0d8%vr5U z8wUmCLtA`RdDEtvXx>TKR5#Fw9`-qmCXmoZ4jYCg%og_!@onh~)nY`A<{XON1=u&^ zv@y_Dhrc8JK7XnHd#Q>#qYw&jrezU`JIMB0&Tz*m#9>s}&Kkl^jjAXkn6MJFL!=Jl zos!%8>+L_L`%2$9C9GR9^xQ+aHaPq&$Ekp)#vUhtwXRb8_p{Fl@{_xilm5C_B95ZYzO6Ms-j?!RKm%$$bvbL-_wBXS| z^Qyd)HLSiGn+)=`d<7~Ay5iuMw**~=(W9`N1yk=NO=S%j7(#}fQ;}U6p7NuC0f5$v ziSyCsj7%Wst?I;aOqp>M9lK_mHPt-Y2CbWfirlQL3BJ<~#_cIKIXm9$d6jXe>~0b9 z@^Y8$b7+(A~vaFVi|429>x30Wsf z>R0kgtSxi|FUMd>${k4X#c}bzPin6Dn!rm3F8drSEk4rb`Odu3V@Gj@Wwp!2HEY@( z43?8rFNFpRBhFJw%u^)Gr4ozIBfRIUOma?}bg5Xt!Gv#EXv`uy@s2B>MC0T1-gjn7 z{O^edqzuS`BzIB?nx6RYXQYx?%|QO932~bC`2R@Ip%S210=CZ$dOy!+m$u#-Jh&+5 zI8heafi&4+kE~lT8=&1rch@c_o{?@&8zI@(t7$DPwp;=w;tUuPMyU$-K64>k8URTv z8{#}LB!Uon+hAPoW-DxW7y{|><9n>LvF*RQ7CA`BNj?ERU?!4SDh(FtAW|W*f`eyl zKD%CZ7V6t$o~3HrweHoqvu*E(EBsvFtpY7aU-%bVaniw^X)2yO0m-p;4}*!9s`2aO z_iu4F3HlT!o3sI(tex{75~fkFMmJ*f+m_Lyn(x|Ryj+}8GJr%)J(4gL$p&n>W-Mxn zuoL`7dXm;>JurAN6nhxyc*%H{P(Fy{Omd#*x#w31aht4u!qGO#j2|Em9v1dW6#D>r zbG_ql7&Q@N!)g{LfwKwkZiM>KaJ5fj`VpW9gxh6X*mOni?IeU*i>*IeJGM_ zW{J0`0f1Q)hTufRKNvm!6!_d=Gpah${r;T#IHN~MYg4d=YiTgJmL;9`=-Rih61zTd z6V#a6wVK&1noVyvEyKyta@p-Hw(9M3iQR5b&nYxi)~xG<$1v-T2<8k27!VQ7N|?Jmg2rd^WHD(Q$Tat49`S z-uEFhaM{cm$4aKJSu*Fmd7{fqR^SeoA8EClDZZGwNV5HZxvd@k6J!!>k;LkhaJ5G= zgGyA}607V8F7ZIN?jkkw7=>+sb>x+KIV_z?cc)bX*Ov$wNbb?v(ld;d^lfFcY)L|h zeiB2!ys|BS!IHy6Ee-!2Z>tFSRcEP+oX4WU60o{$G>Nz@FaRk2iXc*wFwSj>P*0){ ztq`Mxcn+EXsE`IPjtin-V8Kpxd-4<>c zT_xb5TZtJGk-hEw)$^@-npIz5t{(jSl_fYN|5Hr69cYI7^tGiwZvspPMP1BFkP3+G93qVdw3+!h8G1dvD)9>#0DM%hVZB8#`ptF7g z6Q&xtLiM}DyV>jSA9g;GajD2< zPv-lgBgb}Ss#)UV<>l9=HjUIW_H1b%R8cK+m99q*4A*Y8&K@2t7S+}d7EjErQqhH* z>Qiaf8G1(mI^t#2K%OmnfQ#t$2<$RK#;77B73O4G8*mD{iDK%fz$w(Ak0YAxypLON zm-5nEPL=xMm}>jXw=IidvgIzgG%$2JXnGyG7_2pmkgK-$%ES_yy~80rZibEUK)R@E zkP5@YU+ELJltB#6ma^BUTsEWj(1KGKiMWcsH+PUBYEevMHeP9m8cyBbn_4;{Q*WRN z9@jpgm@*0MmKhmYYMG^iTD4g>3~5c|Ml$?*uRCNqC6$a0XO^HqR|SxMnK)n zD4_DH)a>kQj(MoBVf*n@f!j=H6}zak0lB{iQ&?^zIAEf#QqE-hiPdU2WlJi|;viC* zUs}^**fs}g=lCCZG4Sqh+^FJ&yy-h+>PyCP+x^FlnTzuU3iSIOGuz)S5i%f2qdS!n z_C-#W;`WkBcZb`VQ#+miXUJK0>c#gzelp&&JQClBRB8p!}^mB z?jkipD-f$GXiw$Y{o7WW>I@yrw&)A1!2ym$Ea?r!3e5lseU=jCslgl@UZIP$3m48!vL4o7&z5F zg`aveIDs7<^q*+q%&Mc@Rf_QrW^xl9ZBb?Q*L3hCJkw5U{eI;s(< z2TY&7C@ozdKTk|F)uzIWtw#E-W{>3W_}yE@i0Oj_;|7N})Ba-JdA2~X*GQcdFu?km zETv2|;`(1stce{`{wgKa{W(TUC{rcnDyd&*9b-D+_q^}c5IGGBqa4d`wh)ax|+bw_O{MM1HF8TZo9>kQcG4%(^8gZ&;Jjj}d z$5})z)A;34-F>QfU`fYeO8rWNjsa$*AZI2rQq0GeaJ?`!D!?Lxj2+YdOD?38zUA2T z#4v{OJ!n0f;)ouhbFu-qUuZl%6SRvN*~3o9;YpZ;`O`?BCGUppMhqaY382fA(58(T zwK)f1rRXWa07!3^;Wonntfi<1-WxR&e!W|^p{!%k_~91OOkEf!cx$kA1OWwC>sMoX z(6;3@Xgi8B{4gnJLmBKONM*(o?Sk84+O&~&$=O5iHosaiN8HrKY8Mm~uw5@t8olL4 zUuU)z{+?gQd9B=*6&rnEMz2fM1JI=Fz})Pw`3H3%Yc2tjuuzLH`RABZ6>ln66{*Bkj?mN`bqc|^nTX#(#(mrM)l!n@IblI`Fch?`4LT(D@cbFKK`1Su!?md}T` zOl0kd%2cbM*mW7b|Il@?N5&r(ns(cBF`Odo(<5dhsc=@JitA9-r*^2J%@DQ!7Q0t# zmRQ4jm++TI8go(X!}u%3c?bTg;#TSd63WA(ZSe)YjX!=~*f`_$j*>)r+euGkhb^+6*dhnE`1wv{jrndj6Hh#?> zM|dsEI6uu~X(UW&_d}E}B@AYMWqySz68361cypM|djDPh8)q#ec$P=x0IN#WeQ5pG zf`RpkriVgiygL?atHth3zM}m{t_JEbI z8uY9J8&Uy^a0EXXyxFyOf*zUJr=cw*zzNwH&RsFjhIH?+#XPC*BVTNQ_cyJERb1fF(P^6}MQrFh%iGL>g@1#b zb)v_NL^NiGj-@TDz?NuYWc92o+=~GHx%?k_)A1j2_e342zu7` zFHsDd0!$OKYeV_ zxSrl!Myti?6r2XTn#))E1{BG~IKh#J>TYs|QBHQL zsU`JN3_*|3oA_~%3_bFa-4-*4u0>asU~mJ#XfSST#{|p2x*R@xWL3mQsE1fsJ84nf zhhnB^Yi&7{^|&}rDJTGU=|xSrtJToPOM2#Y&~wT zh5|Z0gkUgD3Dn_szvGZxiO>#p!ki5U1prVqgJ(sN=knkNu6OS$xM_bV@Aucv6= z^KQx}EE+;Vc4Q<>Kt9IrD9YfkhTI7xc?FV7Kp70U_{+;cMiWSi3NnsUct*;Hr7(mca6H1pfieOr!{}}}oTsOFcmtnthl}pqD1zgIQj(2u z=&I=+M*39!-n5$(UleH`f-L`H^k`;AxhtoFu-Z&$G|DcRa>pU>cvKd7&5I{hqjG7yMi>i`e}63PksxEoFxZ%pzx zCj5n)+P)#5C;0-emOFA}xZr~tLX4CgY)J+COCa9A_YwS3{VWuRnJ5S;k(ce@+F?4b z2NOR4#d>6}IBI0daPKbq20cZbc`}6)W?qP_RXV)uq;uM-^}*ahGb!_~&AzTb(R5uFL5{5=pN~jGgSp?u(3Z^jYtG-tX$){*xbH{a#60oun5* zik(ZZWJGTqH(U+%fm)ROA30YV$YhOPbX`C5g=oq2k`tNVfzgM1bEjss-C4TX2iQPR zN{#fCwHA9A-53WPB%=r21+6d7vs<{LDgbN3g%aVBROPrHyIAhW$vBBZU=f5^VZMV{od=# z6L+5t|K3Yq{aXO_+XiY`h=U%iU(TmwNzUWB6Yl%DmK{#nz;;^?G``!|>I8_C2#g~l z47k#{DK(S6+?3&=JPR4c52jGR8{rXvQjAi*{F47Fy9ER8K3Mvx5WvKR z530!W0fw7#PO3a}D?vYV6M!&y2%oMnZm%(;1WZQMdWHBLaOtt{(4g3n1#Z9)1uf(4 zp9O9N{cgeJ%m4e{?sO{`hk)ahV&#RLX1ytn(C$*C*C`vwB{m+()pN!bt7v(d#XrfL zWK4>|xv+t21Zbez_#PnclH!tAc|*^wVT)XKhv=}p>8+z2kxx}k63}E9Cu$pal-)M z=TcX4b=XNEPo^Gvj+#sJL23Lh&h-LM{1{yIcGocJ1ylAV5Ie60;4>$og=Z-|B~Su* zO~#x4HGxqh@O3%tgom1775Aq_Z92WvS`Rh;k8=GlC_DE;Kn90a!O1WNB4PEPJ{At5 z(*N{{#|dT$iYzp8x9H&rfGt_-wUxv4Q;y$OxWU40X3o--rXLM|dRdLgKPx^Aolrru{wLQd%FnXMGG;Ps@-9P?vA`1@WFankE$22f*BNCt_3n`8U=~Ku4_gC{L z#`b%ZGwxp7aOC)iY8Hm%DIpG;?uPH#3Q*RD&__S+JSykp{Y(nD9^znae*CtFF%* z&Xuy@p8B_bi~pS;dvUxm#P-EvYQU3XDEAq)@xM#y-%1WCSthlN;beL1V?o zrLLvq@Cuu?TRec}0g)}fv$_m`iSMV(KK+x4;gx_x8*;M{YzV}hl}UJsuC z>Vqzr^{^=r)rV#w8wjWrYuS_3z3+$jxfJ?v6W#JgKw!bq8{q+C`lE{pY6NbUh8KD( z&!wP@0)n0k%y$B!7ZFGuMoJ>I2e+8*Zx;MSoNsUHIUM6GP8R_0u6(k-y4&|bKF<*R z#s8mugS!dvag4IdqdfiOy&uhlb&=U+;y^+q@Ukf0^(h1cLl6-K=0GB#)Rmw&I-TKQ zG%u7kzUvyi1*3Qo)bBfy9L?`V#5{%`(&8Rm6x_Q95+6e>CxfJ*5O@^XR7UBKCVw9- zi#h7NYW|+n{l0k0iIcSCt@AZ{T8{DV0lvn5dGZKl#t^UdfEVX8N@GemY04S@sHvVt z_^T4C#~6BGvX;YW!rEjQwY`7IHT}KKH|}k$u^Jclyn1GQC$b8t3*NB&s4gw!b2E{C zVfJ66#TVy1h&>2Q4Sa20RP-!=|E%)aMd~3N49Gf2?l=IK+_3daU;-&I&e^Vqn0;X5 z6JV4AE(9o2+{0O9s?c+=e990;DP0rU*ogeKxwlgLn4_Z2tL+ z;Z@&LBP;xQ>+s}dr<84pm)Jh+5-X2Igo66_;pKCWDeDT3y?+!bIKB8p@hpFzDakGz z+pHhQ&#dUbxU{h7+VUA}E0AL8%PqqJBS_!GZ4%o9`5aK|bPTUU@`Zc|zK9VrmPxLs zRzeft8S7}Tg_@3#* z3a79_jsQys;way>6YYdO1h_GbW1lnB^Yp%kV~VaD9+;VIK8 z7k4sNW|nE#;WC`c3HYe!w1~yP5M+Tu5@MBB@-1#^yVo1u)QOt}QByDVRnCcZIiO1` zmfCx#P4#-``Ou@){Y`~fnLdzjmAq$(<=nJS^^e7i|25y0y!ef?<$O+CLPEr%I&ZdB zD!RvNVcN=R*di_)#~>&kBLEA;sN#e1il_AL1DK2&7KH({wx^PIhI74MWkVC5FSL>3 zMhSS_gp1LHWD1z-kHo6RAr{w=vWuRJ!c-`+%s>TE1x}k-MW{H!%qEaKD~AhFA2X(P z((FcocF=1CcQFYeX~?GX9%HbnU$3~(Zo}l*6w2v@1V9x0=U!UYfkP zWV+|IxJd6Ur}M26*B>4UV*a6eJU8?A!#m3}Pre~4792}YUl{-LTgbwc^os;V%R~t? zs?HSvO^^{4=UBK>!ZG(M3pQKRy-^J^bY*l~NxELba^}ZMSi+G|GQoqQeV`vg9%UFK z*mx&MDubYzIh#CyT7Mjo0JN+okQOXB4kC`jO&yt6){KBFCq``p&AdML0MF${MTeR1 zXhfJv@Tes0)Rs~ELSgQhQDe77&>Lo|>jJdag@T$cK8@gNIle>6U=!)k2*`_*HNpI) z3e~krW@}e(tJfFLl2(t4eYavSj1s;>S7RQ9 zQZ~vBrlgk0>jcQoVX`?eyPA{?BK^?zRa`M_hhhLYg3)T`j*HMSKvma|abc- z{h1=7grjGH zBHF2Z9b?Ey|WA6qi+StkNLt9JZ=cI z#o7q7jst`OJOJY>dHmCJCg>^leHk9di321FaAUDxYk)O6jNAZ!N#d8E2MVb&lH{<~ z0?)4Spz#hccDx*Ao<@@mrcllPGSE*mfC|AgDYidrky;oV`6dj%@{v4#Q=VVDf((}B zseav=)V$%bm+{G4w(@5)df$gV|A;zfuapy>)$}B9kE=wYyd1I57g4O+O4cObemg`l zSJC~uRg1D!@+;;oL#}7sl^}0#oQ62yhF$1b0RDP&u?mo$qerO+1o3(i)hrc2ri4MC z6KKGUIUYh`;z5Lq{2~YnNN*hQB8?)2lEA|b)SU*z;UJKxW-wMA1mZpf9*Ac}RZUXR zIhBdqAMw0l0-z}~iI3iL^P?mg*2uy(JC$_`ziSs2{>Tn&p?*8{B0W(SkVuuE3PQ(h z4asou$#yI}x!Tn3dE4}QhNVt#^o*-Q}mpFxKy<6wkrFjS%`5v=c%1mmEWq_EaXCOjOJ zK~7du4pKg~|H;X(RpG=;W2KSf*NTqJT#1R{9=&33#_q;*PVkk@!p@1l@8jXtirQKW zYm;?jp99=No)KKfKh-uq9M2LI2yRj3sLA2${6mZf5`rioEGtQC2>|ksw*g6`fzT|5 zpgRd9Ax#7cQ+6R&(zIWEaB@+=Jtaz##emUFFjhE!ALk#UBr*^7=(j zVKcP36m%NiR-V9ySrTkSlbB1IJj~v*&{j@tC)N7r3Q~hN#3+24X&Qi!o64lh%;Tx@ z9BYX6&jCa{7OW7a+>Pu3B^7d%zX#X#7-k5htr|Zs(OW!l>FW#+Y6&cyZYSyN?mf$Y zorejRuK9i?16NbQ{ADGFaPh+&Uo4SOvt$6hZ&l@1Rb31bc8pet^f*OAF#vsukv*f5 zDqyFkFOWbsMAi*}LIc4#Ad3%r9(P`V4v=H=^RWR)cJM`G-z5`c>TQ5E2k5{~1J1;n+Y@Q>Q?J2JuEB=A8-^a=Jg?H^EI zoXW0^MN*u_5ZZmAHbFI6?C7i_BqnTZO~es+-C)+?&i91L5YY|O>$|Tl1!5%rY@EEJ ze#7s=jboo7$4&J?n0m9*To!+_r;Pz37@<&%4#IOKRn4$&xoF1q%MB^}z$T!H zB)~Mo8)8ESf_V~r9B3;ZQ12!ujyHO-55D^iC`LDZ?gnvS^XNmDBSdhC3ebY7PGEw4 zDNu7fn8%G*yIqR`fDKtZY#3sIKdsB*Bjcc{Y(7OM=p3;ahXWZBli?yoK^u@0ykiy< z>dvi5Jt^$?rB%VxQuX8Vt z$I2?@ec4Eddx)2h->589`namUefdTMAyR5cM({mP8~{Lb@`RayA1`Qi9n@!&~*S5*Z>HMc98@?{J$||=|K5AfEfaKCKPZO01`vXUNA5gBgo!E#nWdWx5{5xH+PsW&kLG2sHoz<9Ht{8l;crH=5xGLcj@R@c9`& z9Wq}!7J8X;_cv^b&r+E8(Hx3GNSS&Un3|_GiWH zEnT{5td5tcvs<{quNrdk-RKCtqB-|&TblF&ICx1fWlay%D6R_0`v_A z(o_IYJf!Tk3X}u1B>^cdK%Oj(;SHIdr9vq{=nRmLrRji$$iD<`*Ev}cAQnXM$8qop zWphUy)QWNDFb6D+gC^ilAExkMWAM7qVLB{O3J2u+6?_p5mNySIVx9LPfv0~!d?--2 znG%5^XdR4?5~fEnQ|t~oL9MG%ix$%!NK+8urgywJF{j~i<*SgWbKv<&2ff4=Q;qAo zL9rIwX~*;t0zX10u9Zjo*0&_*EEc&EY>j1JVb8 zJ#a7_0DKkz_GA^SG4A7;{Q4w*^cjd35$w&3_923O$eI3FuL5O4U#08+Qhw%T{H7T&xR3DrnH#zVl|8;sHe6u6wf>FzsisFDw-Oh-oyS})+yFTnoD^$IW zYiC6-J`|SM#^0r)-UdK0Z%BdLg;`Q={GtOAD zc)%$5Z4G444Y=Q69s}T4n*ny1T0X9 ziLv8oiee#rOqMwXB2GDOO9t`+2go7kZSdfOlmJr(#GC}K`N6Nl0pi*G?i4761o9#C zB{Cov&|sYzzDyp8>j3I|4OHiVl(1l{nQm_iSZo_ABam=hp9!8jp$}BDo9c0F8n(8^ zErqAKS>8SHq$NKseBofOPU~IcQ?YL^KI`ork?pNL>o@9L-uJ9pB7l?U3gGs~BFaL` zJ*S*+v>(qG&5O*onfM~Wkn+e3@XbufvPx)yXa>!C9c);t9LvjcA=#+D9=7WK-4qy| z)RG6_r!>lwA$B~gHCgMcJy3xNa3ex2Dd76bB+Yf}d#0iC^d~}tU^h0%kPQ|l^6Q~N za*Qqyk{yl%b|k@?CqO#d{ON4I3&bjG{9sQ7*oT!*WI#?}6J6<0o6nGARL8y{dz=X0 z)ufu;Yl^oe2qr2qptHjtC1Z+@_q`|*%Pe#cu&hOwxGUtiUlsIN3>T$6O`8ny=tuL> z#KyKSO9-AFN6PUD%TX*;W?wtk3$XxaSH`z00soOm*Oz8>xiY~2q!{}#l5o0;>M}(A zrU8sieV`7|PI){ftSZ0;=D9-zaDa<3fPt3)QC`kMAvnwcs6z(S*+PVIKzp>|0f6zP zdehiWtO*C=7dxPf26}};h)jNMI#0UAr%Zv+W$$XBrGkh$?k0-(R)OzcmP0Ud0QgT|nNJ~!_i=9v`nKx>u`fdo3o0yQqcE|Xw9 zBKih{|02aMJ1EtMk&hmN_~UzO!qf*lYuvWBV*8Vkl&zh#f5V1u z3)Erw^@iHNSz_KU3kR<1S$U@wBg6Ur^zt=Yj_!$E9v=-G`>1l&K1O)9)n56l!)~6S z)9Xi&1ynn%P$g^(z*KKf*oUm&Cw-f^L1H^qLJmKGnFO^{5H2^7sv!ZvfFo=cPl=qW z0Tf|3!05cJCx|>9G6=P80#y>okg^iqZx8Ck0Ue^8xq${jIAAgh8cOE#!t!~MpdolZ zG43GWu`1YA7C-+l@D+xH3#RAF)Byea541=eK3_`@w z*ZQILc;kE+DF77s*@WB+Sq6)7G zfK#p(J`PMtl(d}6Jh^|p|BOZ#9t(lN<$VI&XIBUKVFK?@;_&5msdv%{zzjtaB~wrK z=eW`>v(+#PBo5p7m8?^+NyvnH)Cj7hIL%Z09t&Ht%S1pFvFtCbZ)Jt ztA1akX6oQpZ3^{Lq@oJnX4B3Uj785zxti}xO|>t^dYqM9!mq`2zdWtgj5DhTdm1nJ zy-<HAOZPR zZSbiA{AhrHVg`YA`1kz^HcUC1H2_dj9=8VFOY5Ql;Ch_;M5SmR>LU|PFVB|EqF3&d!mivB0d{JW7+-P1P7 zQ?A94WuonD!XJcbAXoUCsip9mw%Ks>uNPa(eo99rZEj8*8e56my)tyEzS_M_!e1=* z93{$~HVPb6e*yo*f+6PgLX*8LaRBFA$G=0!59WWqkHk_l?vNN2H0gMJ4ZnohcOU4o zsEl8@6tkl|O3j^-2$c?_B&uMFKh-H|5*eWJe{U>Ph2jgbR6b<}c0`1iumBRbcBR5V zVJ{O?`!Qk**M`#A2F4mdPR}1d%bs7|hZi#?mqj%qZ4S^iS3h zMUqNc&CqN0SryQ2Wv`}lS#{!k-ZB8yXJGZ6`55r|#XAWPufAq{NBUO{i zbYzG~Wt)}M(Hn_2c@ctb?M>E#rd@8Hb2j4Arov+f$Mg|_e&WJDi9zr-P`P9$-Q)|! z+B;S(p!A25bpNRR(0_rengH7xz zoJ%6&7}ZvWIm2g%8w}3kL6Dw+2WTHGP$UdAQOvxnXI6fDZ6IxdMJZimhMODY=Kiw` zZ(CqF8gZR1Zq|Y3YoDV}yY*VXtm090vjG`~>FzgYJ?mK>hcc*)bS$})<~V%h%t0=! z1jpx9h>Szy-T|M%f|3hxg=+9-_n@D!cI}@ZpDN;_D&Xm_hP81(kU!aGBWZ(@ZH7f0 z3%k`WJ!3NZEfve}OGr2!HYDvj4MY-HAfHrMnh}NHb}QXQ84Y|@y``z4Nafc=iy@9A z@|le%dJYOem)!sYUVUJ3CW#N9Gypx1x0PIE@o8tRAkLs^;?t}sWnX?8Ukl`9#Yp5DJC&XH{w_Rc0&RtyYkn<|wK3@WaAth+&_ElUZ6mtqXnx?F zi7z1(f4kNv6vnPGbqpCov=g8Hqq`vGpAeKFix>*~Tb{Y!Zhv%sUx*u|vbh=@enue3hA1J=O75fQ z3iy*L@K>O2vrkfyz4Jg9haraDPS;AyWk~FLlWX8aQRq+(T zEP|g?myJj(IZ1~{I9L+~4}{J@4GV(=#~TN8r%8M`VmVS<1*}v@1er8pff}%ZZRuZ0 zDjv>yFI+yw_hCIN69wHf8}w?<$`^sn-zS3mJR^K;Ke&CT9ZV}ng$l5K5L zBBuVX*^N0k8+t|Wzf_mNueOr2rQdw~ht%_%b9Tx#BF@IH+#*pF2K!0RZurQa?fVyT z?Tty%FU&3kR&`cSk82}}A^Y|SGEyLRtCMN!>WTbj#KD1wSfHj09^{U(6>pkJ*7Q_BBq-Cw$Ah6p>Ndy|L@*+1 zGZDd>g^HV9mMF$gt9@1J_fp=`TWQG7yt1mI`p@@y{)OQN-zG;o@UfwgC00C zBzh4B9&insDRg=;?RE7s>Dl;cbIqO05L2nP@;I}dYge+P%#s^_;vfE+FF6;fs2UG~ znX$eEfz-D24a$2}$VNZeAl?%13`RJ0S4<@@=bQ>9|^f z$9Cbx9x>9(4D7MQp2I+yXLTsZpVR@4Snr}<&25xtdQELGqSL&$NjRlPk#STX@uNt~ zM-!o^-o!tS0=1X-r&CnWwa6oiqph8}2k(7}rt*=gkGDD}>q~JQ{nVf0MYui*(X_`q zu*5n$k!yYb#oxL-1QeeVdLFKG)Ws6Gy)^#Y}c{mSHi)oqX#j)p;l^>JVf zCgtN55fc(botu=1AOMi)L}C)4A3)2|FH-wS6{R{D3-b|w6_2rV&D@4cav2o^*wzSS z^@=9LpyNd$YR|*?!FIR90@AE}tTO}EGl+Z8o3|CuJb@8v)ofX#YjM!k0_H;*q2^cC znYTVlhr+?XCSd%S129566PbtZ2Gb*`9Wz zP^ecJ_IzdJQTna_u+0gek#o6s)LD~Hq+rmxbQMa)Zvs`3Lc!L7G_W)?Ga=O$kUoQ| zww__j2JvD9??iy@DO3al#8X!DU26*eOpTV#U3b3q1<>&L^S#R8sZo~(ztzWHg4k66 zieYY1ZHoe5Rq^yiG=mA_NAj(ca2eYA?v5&T7Dr5qjNVbqAIuupgmaOhi_mfp3)HE` z;~|<2`yGL14Ifz9`Cq9Hg0-r3rC-dZ(wO=CKS38nYRSJRPdd8CJOLGeX)5S~@kG~8 zeYY|gjyqYMf5?+uic@i3@26NbSRqBmj2gDDEr158kP6QEzL;wS%`1V^u7VBNR9iEe zJ_B@Q9HdVG8=HZ3)xqjr8RA&rs7?20fm%_UnceZ?FSrse*iGOr@t9zZ&B3gzrR^`7 z)z`&t+6Z7Nmc3hHjnkyux}f4OU{qF?`Se!qor8@nSB-0Ojc>3YZ`2|EMZDU3s|X0y zjK9SbQ^PW!sa`8b$3uW;m69o&H+Fv6v6r0{5$~}9_L2}YKLjGR~2gGXr>r&R(y^|-822P zWc80ATp9!~3KX7!pA*j#R6d|&_n>nDG>E%3G!G4U;&80L9qNax|CMVuD_SUgm>R$k zG+-3QnEy2tTV^&Ms+x7sx6KX}EwAjD?pk<<&JQl>_)p{L>`$wQJ=nmIEF8;X>6)_2 zDk?mG?rY1Ukcew{iDI3lYr!873@yor^$rh$Wvcg)g3{*PoyJ1EKO}jl(7iJ$LJ9wx zm6?DmA>!(U!9~%MP9RvTt}QaJKO;Obhz#Z)k^vhNX*fDac#8sL&*_j{4K6E32;b8I zh(j*x;o_$b?7qxtKJZ{gbAhgDw~u^o)@lFCD^yN8Smf1l8nSA6d<>SNM=x3=Xf>=P z58#ZiAX1!u4T&4O5yZqp6)oJ{q<9O;p=tSKuynV()URL5LGyF`tX_WH0S-~7V;dD! zBL0bV0Eez+{?jJ8$wUbF1L>u|)%{N@jJ8*g)RmV0pxmkZTN8gM?R)~I<*eiL+og@{ z?5SmtJ{@QfZ-@abX@uGg9s)~XQm6?w^N~>184QG^eZgJfo1b31@__*|Xb_*Pherh4 z49)cGRs6Aa>K+f=N|i?vkjC5^VV$glp<;FJxeuP7Fl%ARA;H~(#}6IpeRFZe<++$| z@zX`)Iq9cjkWAw|msNO9kEL+_ggC4ZoHeu_$oUt@3G3#Z&DWlnh`tJXY%cWe)Vt_i znK?m;E65jvIToteXTnY8|9QQ>+*bad3SMRl)UqA&dx|=zL~9Q(v5cUpwNs5a)C{*A z0|KomsdVisRYg7b$W@23DEyTvkhp=+*mxf7(2DVJZd3HlyB^s3-w12Rw`E`4str*f zr(uuN!$*SLlJf#v!N+gsJqU?>?5N~t;&x)2^0xSBU@f>;5T4?qZSZLR?XKLdJ#m>v zXnFWQYzkfIt7eE^q4rCzqW`DAHJ1}Y+q_=OL{mpH{FN8g%=y^oJ8p#!m2k-v2Sb@G z7D)KBzit{0>r4}q`f^74B@T(64gh?3|CkRD)2H2A^JIQ6wr5b?OC z-FE60yCFGi>W6i9NT!sfCG+~Q`0ZU=nGHhq(Owd9xwW#m+1BNi9KqHoD`+w~)PvDw zgLBSW`Ig%g_=s@8m7a_fI?c^Ios$0uTRs#j^BAqRi!J#SfAFmRT7KVjjE!Qj+neD1 zk~>C^?08iaeUyL_tg0ly2e+ueb23`6d)wQf$Go~5?aqkN5j6b(-QxI(vM%b=YWpwIwe}LX|Gj5K_Zp&dlaDLlVQoQNI2#)dc zEs=IE3eLA`3=~{!tq5Y{WKbQbnhG&^kHaj&Z-Xv%0#{~`hb-A(X}CI!HpPrH|4g4E{y37N5?OV`U+;^s=p!c!gZH?M>mQG` z4*h3<{6iYxyS#zlxnahvoBo%(YDxj;p-n z+M=AfCLb`9j~%5RV^Y?*@Kt%yRX&9Dfpfa*w=XG|6hwwW^y1$MUnD z-(4J#dXb48%M{DNEs=v}?8wCe($ABZeFcvbWvb`3m&J}ESbo0uhr$nk44wJN-)_4v zefFuu9{(Gp`!q^?g;zg!an(0ds_oCKf$_7=3Yr@~rPY(qRG37_6ub``yue}X-~LWWerO$ZEZ~hWsQTf zD&`W(=I8?!f>=AaG*M6{1g;t)q~Xqaq9>Xvx_2{ zF(RthMOAN!m}d!FBrEFW;Ph+NG#OI5wL*uh#SVAMnmiU(85YA$sOk+G;yRAl4jl5G zwDFubc7CqzGbc@aF77ZbZvH~l@~w=`rZ{d(TyaqX`$<@4R}S+@Q}nZi$Y(dH4Ob<$ zmEp2A{*&Y3ogkf!Ai3o;BA-u*eYq_BHBWOhO>47Qd81MEQ#<;@6NT+p276Q1`<($C zRxD>Q@5@B--UI4RaoC4U(sqpN!UdN{7kv8y0;-P(HXQP3)OBZKefuO&4=P6YV=r}R zQSK|H*I<+GYG>RtOD=MZ&-RE-w~9!$I+>*JmaTcTK+3;FETRH)sZb{Nrb<*M<`fl6 zqKY5CD(-w)h;Ru*B+I*<*R(#TZ5OO`#7Eo0L&eld)zn7Q&{Wsd#Kgkf!qyybWou>c za@fg%;7UAt+|%7B!25WJlWXun?{k*N<1M{tgi}}DgHD}{j0!s!8-DH5`8ZlsV#1BI zjATmA6?$=a79)V#=5uX?bg?=5N>}pDj;w+TT5c}Au(+VCsVC`p-kzS3;nCTd z7xQCZ*>5-YHot!R`D^Xxx0m1F4|DdrzRo?^;oSYOo4)qx>O0PvHy>j=_UJ8~w)W3s zHTzw+wo7mA-MX<=dwGKq_BO|BDIxIHrJ(i8=RX8p*maBA3Gm$Tuzeq5wMbT3BFR3# zq}ZFL!Aw#u&eqPz(TmH{5A@fK!l{QU9X%swN7XoxaZsjGRiaTA{IhU<93p8n~*1B7iPegoybEf)DfH0p&!c&EapLb=j9DaMFs#sY@A zBbxgWQT;)(VMnFrqiNHQ&F$Ue)jK|YJMJ?d4nNz~d%ms26Fc<27kauSw7mZB-@mS| zF0qvpFfQOf0a*f*F+hWfY6grm%ZF0YN=~JOmWq)~jA6vmcuVEjEv#*ZtYd4{1g{FK zAz-4l`bhyUWU|z;t>$ToS`F5(iZSxt!HdFp+Py6-@#-DGtPkSmJdo_nR z$R;~=o_z&B_Nwz=cmAhW{JwW1s)?qbp4HkHDPG5UDb5QVyKBC8@RhpTl#u)6b@Z#) z52gOxyCNf+D=K?@9tr%9rSjFc_`L6W7fy;@ovuGp{rPFetA_s?t86B2Gy%Mcn$=4W zeXm#L*$ArUk`x71^IUS$)GP9+W%x#V1>iiw8i@8E~qXkrQlv@?SRCUn3>~kH# z8R|n`!GzoPd}s=Q@cWXI)+2$fl3a4b_o_sAbL%)ZUbU3~qA?4x1);N!YxrN~&u@@qFI^)e|e{-JWqpk$ZzuZo&1To0A4k(wi@UY$vH8(x z&;x9!Q7vfO6F0^Jd~r5>`tfs?VaTyk%7lH66iY?!4`@oIQ2Ca?=gE@>j>*x-R^e00 zX~Aa=(_Gxg^rFbm;q9XG6je{lXf&pRJ6nh zjlD^?0|RG?5W~WKxLW}A@?@lZzOugQ5p|oZ$!RHurL$Q!RqE2*9C9FPsDSzDm*O>t zB`B^!BCFt{Hpb3>a)Q`g~SL)G8gz5~)EWrARl2k|IiJzatdKVpUr+Z}u zi+)ibIl-w&7ydgUDr(=X$`fw)hXorXOk@U{ox^;LDP?(DH^#iWl_j$9E(`HR)gOqw zPWM=?Vih!zTfaiSAE9&vF(~WP@DxW^@-4OKRF~?YGDNGdi z&hx|lhGY$b-C4@w=gQ9PI(Xcmd*#Waqq=tn5NEV2>2p35gC;j*s}=aR{IHr4-*1H7 zo%~e!ueFAd9*Z`c&t-Adg-S77Sz(w}#wI zdoJ&41q0WqhsUbLOZw6eUjLPBmIY_OvR*dY=Xjv+e;rmHSEQ(SlS8D34bkj=Uek-l`4bS@vLEq!WQ#kxxnSj zUh&pTcPHZ6`pGQ|XVup*#ov+*8h*kZegP zM^h8u1hVf)nl3lrJg@zt6y=2(Whgq|(np+N+hEx28rtqdeV)ahfRCUje$=l5z~XuCCBR& za|Q-(hD6z7-msI6V=rW(XtbA#e5v|L`gWmTS7k=g7fb`sBFHnv)#J)3xWQTY^5Q(k zocoO!8L<@dWANb+to8iW3kY?|ADGecWXcxKf`Frf9xuL~dU++WnY6xInjm^w{PESS&`>eiH~3K#^S@!8oxf(YM)^#{ z&b_-H^IHn^PHwflWg#j6EW3#Ldm22=`TfXnHtxcT5IGgaFoFj@&T5 z-?9HZivC0T`Ha2seTAQq=;wTML~vVSgUh=X+CN4>*e#hLl_v3=joAUg`8 zbcE4K@M_=6537jnPvtklr% z?^lVNkq6!*hdH!m+%=W&$Pbkyg#|kvuPh+NyJp0gi<>ZtwLNW`V&?kP@VeE=&8cm-N>ZXB+@(P4AkhhKp z{z~QLb6>ulnl{Tx`;||pr{z3hA^B<%v~fgo7ebOhUBxqy#=d;kgivw{8TbACPX6up z7Xvr*$-0g)qnzya+RWCj9K{rurb~Hd2eW!j5S@3B9rMVyWZIBfYJW}agYQ>cw{rCf zytw7$<3;chG;N@!cm#je`hBufcR*1HCMsIDi=%#W0{%?ksB*Q(_*^h?Gq;J$b0E(| z9xOn5#v-an1&Kb$_;lnFCp8g9xtw-m5kQn5M#9x|K}7``X7O*xfp73;^Q^EdX0U(1 z!WQwcISMlWE7`K$rtA{(oCI$?pm@j))O7YCsCL3V=USxcDv(Q&Oo_ zX5;QMkzx!BVB-;=$18@2h*diLEd}0BL^PmL+vB%hac(SgQUT%jC_aq61?#*bI-t0~ zU;;^j(Sbe`?ik>&H!^0SFflbvWS;z|s!)027VR}ca5J9U`7p^&vRGm=vnwvf#3a@9 zCvpu?619N5CxsZs6~AR=j#>y6{lBO~EA{zCUTp?=Fk~7(KcszCl z>w$|;4%qb7k}hp_LXG($zVI5~@r@c5LJe%LU^lDslSfr@%h?f?I}L0XF9%N_LHJ+_ zoVXafhDVt%#%|Ez3z8@%5ivrBQyq|rKT}_`kv3W#o-&u8vyf@{+uvRyr`h$CE#&qh z@_ljHYe1SH1G(!LD8RTO?HG8y@IK9~j^DfNv>;_Wx$MYTsA*xnO=bz+KW3TZJc_Q@ zud6ikX({^M&;_8av5;0p%|@HZcE6Z+*trT^3327g{Ur) z5-|gQAFpKqKS#LI^N<2>&4jl&Bl=mDBP2wNIbxOEyNZLavD-%3f^M5l57F)JGHDyw zj`f*7cYoA-JnB6Wwa!AVaY@Kr5_07glA1w#gKJsBqoOoBZ>Iv{>Thj5xgkL8e8m6& z4#v|qZ@s}i2BwjL3z1_K_&lAt&dNNR+PcQ5d}-16kkPw3gS2t3hRU!+{ZYE}@a37V zB{b7Ut3BHS^^oIlycN<12xha9BSh2#K~!sDYl{YIm4s4nq`oJizF>t~DezT1>LFRH z;Y|kPd04g4Wqh*wtL;)JMh7W#q{GPnj;D}leCDftS3*EsX+JN@fq zpz`!z2XoCW`DjpBAM6KZ(H_)s;AH*UBeqW%z zO|!%3(!^Kn#MqgDK5Xj2Ar9V!6MBekRMSFjFxv-sr&1zJ8q~BLdOL$!pQ(IW*Xyi}sto8gB_KvsCa`z7gLkGf zwJuKxXAQP}%susYuv@!vl?=CO5OmV6>hZ$>+q6cPru0kU;Y%gMc=$u2&{w>WYt!&9 z8NP|{-KDp8;ovomgZtRgJrZgY_iU3qvQ8P zoUg(6@bGU$AtqqRQ3t+<7UD43FPBlz51}^68}kXMmw4nmxs4xKp^tyxba0lpShTh?HNtI#eMWryhhJTv&=&|J8D z-zHILm%OmfWb?_-y{Erl$0J?`z+LW+o8ElcX1?%zcW{k_S_5pYAbYM`p(dnJI*2zv z&|9JBgqSSBhX5g`w@+*>*V4D!FB+=6%S`|r&@J{I_XPYSfMT=eDZ`) z8y@}z4=0rged3_zP(phwl<)No?{ld6WzLYG1^8D9!Ht+er*SgD}KcPO6H(t_FTX^0?^=&Z#?vZ7Hm9xc0QLpMQ57|%qn?@t$ za>zPzP~h`zSfgo!hf;UtV(>NBlFUyyB2Bhmp0l=Gs`S4eJ6F~ zs62SPaJ)U>8|}}ry?~yJyKhHIygvm#O8CcxYQGlO_3jQGXxNC5(DpeOK2Yp+e(sR} zkB_egHJ;qj_Uj}qb4yM=GdP^^_j|v^Q{83rxSi+S9;Q0-JYqgTF7 z-Hh7IR?&%7UKxn_Wfj<8y1MjqC|Tmly2hD1C4|XwxrC+J@zVJB0<|U4n7lKk!D;&` zN)OiEoU5XzE;}5U2`fsKn+dp3EfF6U4sB-oB{tq;ovv!JmpR|wV&{F_P1|lXqA2-} zpLARDovTKb)oss0Z&yqB?hTCGxwfZ&^S}$v0{`9E&Hy#@OV1aOcf+HGb~`VsZbwNZ zlwpt7tg?d~oa62|bI+J>uZE79UCzlx-Hn*(wwK;#(bOx13W8Is8=Vvz@2;*UwwL+i zdidop&zGN)yE;BOUgIAj%-?V?Dlt~Y-}RK5eB64Xn*86s)@{w~@!#i5FPpe~-HW#@ zp7FZ=QFvx{c&1^qtSw;ws03zhu*LVxz2vzEr~IQ%jVniXI}os$P013|r;A3~d<*mV zC9ZyKf!@2;uzp4^;$`Bc;@BFuGf&ucvuB=MJ@@3My#MKiv2?ZXv#IR(xJ-}0*qIAD zuG^N;`IXT#w`)qn8xHc9go|a=&DcZ^MySMbLh_CmWeus7m3-KT9k?83{ZK{tPb9zc zJ51D=e8M?{T8TIgH~gDQ36mOICbSl_sR{B;X|Mhn<>%cVZ_{2a9=ahVap#IHFDF^l-~(E(eK+sU`FWhVJO8uh^gW#~ zE8Y)p{J2bgnjnADArTrZs=T6;TM`q>x00kT7d2g;(tB9kd~@iM;*|%ol^+)Lp5+{k zbEvuMVrX^w^m=!#_U%Q5 zRNHGG69>yqd`k?LXpg?ss59ed8RaWAa{6(?k8SEme%nOZVLR1Kh{P}7o(+V7pAAh) ztOA|9v@%3FMn=BlvTvgjuqeSD+^|)R{>_A=V0n09N+@ASHDSwEuG5i!RawEzwyM(j z1qo?kQzdNnN?C55fxIL^$rkDku`$c_wVd+kZ^l5whkfbPy#WP(j;rDA74#u5h$lp#i+iJ-xJ*siJ<;fVGo-cI2dR+VXPL|fo zA6Djb!cpcqC8tZ{J4+QQjNCL#fp zL#l-(;s2xPT>N56{|A1~nQPPBn`*kxOfxlIWOP%hoSAMTNhKM?P6@deMN8~Cr+dPSnR!0X<@0<#@AtP2>V08#lBvui zq{7L{aeYFNL0DBgL~;C!eIv-2&mBDmi>(P+oJkV>~v0!Wn3;2)n9VKT0i)b z!=KEV1g|IAx;lO8b1X7c{!HE{_83bOo#9^MyE&Y8a??@v@;(~R1-^TD?x$C`pN`z% ztEg79&evk{6Ebsmy~t`&MuGecpmc+MY5Vdpix2fo*YNs=1?)PD2jID^N$18lGU8nE z+P&`781(`fQ7l%^QzX?6IM@h6&~-k%;hbQn&Ld~Z2JNhxD74Xu{hvB$Ok#eJshM>1Lx=1|24E@ zl+gcGB?*0u2LEVq4k!8WciQ#+T9#DFe`P=!UUdbq0TgqdrN z!h(+sn}rJtUyS`G{CVp)7Z*xJ&}nbL64~%0tB`in*C>{HqO5qebi*M7Q4*82 zvfJvjZ=Hrk|G2<$98nCkrk&i_(Dd|MF*fI_#A%layfWDw5qxZETkoOX{=~MeGcMCf z59w{U-V9L=oB~K~@Nb!fs;@h2idNQ!RH_H_DK)9yerx}9re&mBKAyd=H5X3WbIIaQ zPqOrS#IKSOiyPnmZAp5+BvE_3?6kr&VC7c#U}Me8`hyD3@DP&3#O{c0`*E$um3$XZ zp)NXSH@6lql589%MaO;RM(c@^G_9G+RBN7EPLzaeSrs|Dt6o>Lh~%>kC*9^ey0W0H zGc4NbHx-AczRVn7cPMl9&vW!1K7V9Yu5oh7)`eCaWX)WN-Ua(N4?XSv>~1!JjvYSV z8nADsoyUo`%M@Fi0ZlXU428gTTB5W*yRKC#IO2{#zcqI*?Y!Fm690U^GKqSva&N(d zj~!n|ydRyxsH;L2&&MPx=#Pijob{M>df?Em5J?W|q6u`#L7giuJ#mIy*?}I-m?#c< zy%*zBiLT20tg*Irae;en`PqHVA6FUe-|nirHcWBT%)JxPL^;fzycxQuv&fCT?}z)o zGk0MtE%^RRgF5zJK$eC{rTcH(^lH^zKfk;&S5pu&aK!CO5x4!af2GYHeW1IvW`~ z5C*E!F?l}UvyG3nZ z)acqN^OzUa9v;1|L$(KwZm*L{;W?-FW8W?KO>^9`qn*bt%Q)b#y>6HP+KP$OTXyP; zq{XBFsK%-u+ak7mOz>M0AYb3!y|=pGwz4v5tj~R{TmLJj8tmt^K%N@NLxp*md9?E9Zc+Nb{?>fE=s_HYtixtLcgj^3%_xTQ5@z4Zk^0ZNJ>fC`eGDY5o733c^JH0+ z^Keo9zha53+kc>FDO-SE+TSk6x51e>5#hv+B1)iFX@z*`w{Gss~{K1wQRDkY_ElaXq#m z56&)iD%=Gv8|z*kqpuC?eDJpiEn?t0Qc!-iQ)TE^PIP+!5$p?)XD6nTLY~Syo&r-3 zHzw+XgfdjX2CbEM26E*ux)<1d2ZwyIk&U2u5Mtw)^&}?dL&6K%71=$b-EB)&&7WNt z>c0;AS_LgHCdDBK7sAr*qqiHvq8j!-F7bZwYnfkT47N68;el;)+%pn3uDA^xfGlTq z8(X5rq9Ny6C}$_+G8r6h{&4RV?DdfXRVVb!S#Dicu*azH__eq{oHTf~Ghj&@7Q0dD zAsAHdCW+cGk3P&p04)fKe^jRu2B6kzH2x9hN$ur*?{S*$Il6JNNjorNa$XrAW%J@# z{L$fI}IMEJ9%s^?-^ zvxls2`p1G&`rwtLd-r^}diU2Su~`Ei?4Ib>MCVQ@E+Squ4T?;-30!3@gBD(k9}q)A zD&|1Nl6sN_li;mupfw*-PKLw+m<{!T(WWQlz`&!Gt1&Ke$vI%*Y;kmhZ{O+FE$a-i z9@3x@yN6!ctux*(Ob)&qUxk^}TvamrjV+ zPTF03WC@Nv{%CbS4Rh0wIEy3hCiW=p1F!TvzakloB*~*@^v@?H|MTfZoNtdvnJnUC zo(9k)VRK-kv^dm400{(`>6g8e4VuX44%46$U;xV16+NI(`E+3b6bobKkMG!Cn|JV4 zk6kdvoxHXwq&J&5Ki=+w*US4eDr612wEe%dfaCYfov+*Zu5{sFNXo@(B`X_4bbr_V zvGPh!)v^m_+d^7S%oE^7=-vImpUX&DTlX%JDTHOD@_lXY(jhVR+OC3@yC3_0+Vm&# zs1l19yt}Ia^Hbs1psziUXCD+88gD-a8b5(nFlu6Z7(+mtLC{I57UnFb)~IQZQTW}E za13I+&UdN>h18{X7w*(eEVjFP(>VisvFe4hG&QfTt>o~{XBO@8=BW*336}ORUXDgc z44yHYSE_o`UT?79metzefxSP9xdOAqaRz7o5wRXx1Q#sR{7Uo1UK1ijFqV=(_}F(| z;ERrj%WJ$ZuDP6Exo;w7Z`BXJUOh#O_}CS99u0sFlc-g?!Ge!j;h?A%wC7`XohB3% zWcCgOjQ)Rxe@5-%P+2Xo8F4iHuAn^d(C!}TASQ_$d$@YcZeX6EBJlYJNS`RK>Ronkd|~no%thAi zaEF-PS+u*kD1Hnof7{}27!da@dQ?5ny$=iQ{UNWko0{FR!T+VQBj&o_;HH%?Y@_ZQ4vs70@ajH1+FP@gXbas6)mEyFt`(428*RQ&+kZ4qn(!@S>(WwSf-6 zQrmq)Hh~ zkeBSu$HcLf;-I5xp`1u8xkmQn;XuPGXhr}eO5Z3|-(1+1zjNBhjZIRrv5nU##oxgb zN#n7vhEMKMos8@$3sZU5tf%b@kJ`O{+)H(LV!0?wHQ$tBF<>@)&;kK1Ye6fi!9s;P z;HX17$Wx(Kdi2uDe;nITN9CwvCu+loxP}dAFSxBYxq^Y^`%l<>dL=OV;Mtq9*`W)J z^EsPCoTpz{^RK&1cckQo+;d4#1uFzICd3A4M&Bbg6Kj}{c>-?_`@Xl!?kPWp>E4t64-sEbEVoY?X(bfDh&{R4VyXg*R#T|C5abW)UzRL&nW7nVi++Cm7 z^R9LKU{UJ;A3a8Hjl6?AQb+|w~P9DA1dhO=^=jRPh| zP?7ZR(8k5DZ*LTldTp|?=V^ELXI-;KP+CRN3SUUsM~qL0PBl;#BIuK&?;Ydj86{ZO z_kln!Ed7PP(#LnK@Waik0cYOyD~I%dZy)fa_IOM}7RBhybb^0Io((&1rU2c-`uIKx zHTA6qMWH-oi=%XH_U|SO7HAc>!xBf?#<4B`USA7b{|h*-28=zXkg&1FW+13_XAf5j za=a!UFTZZ3xnz;?hiNXjAgCbjZFSwN0%L@!f$X4pM#X}8i5EiL)UPf7oF@X>N49|$ zQqVmS^6JZKgaGD>7jZlPt`lRzs1FuBSn<)9v;CF7ul_Ubc)#DftG}#V zwWKp~*M%jEiiwQk|L3J_S^`=E1nwj-dm5Wf%?lQQCT+%aFKF3}TB=b818S!M?fcNJ z<=Y%O!OOp)_Egjh0sRc<@5Vo=HHO_=9tCekt){{5LX&PYWQGO^jhj3&HGMc&Zgc9z z%3#do5q74cGnAMy@2@-0632Aq$?9BGRBNzpH9QRe?t}!oWXK&@bhVITVHKHu%x}Ed;KF*u_=yGEW9>O%SO6O zt$j96OlOWH?f-Yh{SB`culA?}Qj`G5J{~Nd%GIB^ap%|^_0`TV4^qnx4*q}_UwZ#) zKGkYY)@YmjL}9sY;MNvRB_Xz)y_r1TmYH`$=NR1hF}?md#hl~1J%BE1j9MsgnXZ;* zisx~Q#_s)Zs@+$)-^#0|dLdWWeXDNvkH#_9{UVMF9j%U^D`~H0u^p(yu#Ecu5tvT! z`5unET3;+(2Hz)&8`2fk7IDp03f2aPPW|!>OVFC5U}uu7X7z53_~9pzY*TIw9Pf1g zIfVO~_QSc(k!a8My8SnuHf2rrIbmv(^WC9N9%-L>H9pd2Q{Ajc`j$G59p9%Ph_wE# zwPFR;tu8Q`nbHC$GyFQ_T@-OQ+ic71F+7jCdqj`r&S_I0T^=%}{~?MFE`G85i(7jE zM{dtqiH2wm7)Mya4kvxNRP=COsPI`Adq%%OA0~ZKt=aST51?xPoVqxjxr{#yIibq) zJyxH}QcJ8uO**R}lW;hZ8$+!RD^c>nC%;DMNl#YHS|*REJn;RM^KXCb{C7s${+4#tgQx%?9+s_pVG6G#1x%5@2X}oRnhrBjN{sRcu|y+ zs>L{pJNy!=N#D;3>QHw#&Ygf2X7f9zdYn-BgTmr?aRZq? znJxdpJXHKXpA#@RLH~1;lV3584fUMWr-H_2m6OF#tnz`Hf~|~M>UV*YM-eiDCz`Q zznQ}$r@TTYn8yyY?G}h&#K}e!Z8wPGOaXm=r(twC}aL&Wn;x&i=Oi!gW3FF~er_>_zN7DtkN6_CjU2 zj>F6W1dmOi?~Nkn>e@Vqelv#X|a)!7#^QJ<2eN zf4DN7>L^3`!3t99w2r(0@ zF%ah(0BSUeaNOSLF8@A{owWxiRg^^U2~-|hsA|JF>D`n$adPVp4R=QP2sc-WaaI~i zVrp?>{Fi)Nm5gXjtT&rKsI71Qt-!|UPB_zPzbSTC8nliwTs`nR|oT6|(E2T|uc zi{vG}ff!?hy35`k1>tXUM!Aw;tNXEVj=H3H)ufRBi!WqboI+2PhFLCBVZ~Tqrpl z8>z~uG^h%H@&8rklu%9aj;};(n}LGOSz6tS$)p1J&IX#_2RrXB_oUtq%<{B=B(bV54p*jf z9wvq{p5nzO8U-VRl<)MlqHqpkQJ3DCXLCzHalWOcXUe+x2K}Xg7JvzC3p0Z&P?Kny z%_>H$9XY5u-vGRYh+^h_YUpG=U|$Kcktm)&!G5sxSA@56PL%4et$w+ zKnz8+M74oH^UW7-oho4_%cQ3iMN2=K-!*Go>&MMP%tICwfS3*VpKd2S`jcbHI9ea5uCC$O0+F;4x=x2un5jx7&vATZgrSorN2j6;f0!Srx9XQBNmnJsK5vm{w5i=SdkG% zFV>eZuEE6h_n}W&zY>JL>{~9A3i{-g22T~5_f%v8wYRKWRr9IkPIbPR8*dh^Y&di< zE<@}hH;Y#3&hlcrY;D2f(7|kmy)iPc$b9cfp*x4U20zFjVUuMhMk7IhkUyJ&l*wVv z@h^F6S38tg?@uD+b^_#3HQ_goO;BJhvwE9A>i??^$y5E&3^PD$Yz{Vje_CZ{v)@jb zuOTW7dE)DC|Ml7m4*EiL)jTxXj(7-K?3vZT( zl+3RPYQ59aEgsOUIC)NPv3+&kj{hnOecDni(gVU?>t$piGoFe0O$5GTlY1U(2Z;iJ zDAE`C6BQbpVq>=>TVE754RXs2d3Mv2irXVhicd3o?C@T;*yl%zNFRH9g&Nx1EVz6b zRrZZI_`Te^mdazhk<@yE?>ImSNA5DGM)SBW2I9Sx$M_-AYMxR9h${|h!iGx@WC$$| z2?*xi4F$1T!(?w6W)%#YIrJNd^VJFy6nSjfO_(HVrZr}>k6eusS%{JRh4bUz9LZb! z*NcBRw0L3ZJgJG{y<}44QopC+;7)FBbGX!9zSewgDq~&ef5WzwDZc9RuJGzSd%ZUB z5D3tcQWl#zs5l@IAgshmp3BJ{T1Oahf{!?NRJ2sqP)yq3t0eOg499%3 z(6t^gla-lI<7{O-6-TI@2z6qBUZ*zqT)@hGt{CRtY{qMj0)jU9|FzJQIAaiD_92;L z2(^RB)N_ts03G^)aryq5ZnW$tVW;cXHb;I;rIsF?#PuE&y$(els*Hg>B zifsMk2D=!yo*>h6KzbeC^CM{8DR+^sSe^nMU5dF4_Wf^$s9f3W?)gyMY`NS`_e=es zVx>;MSSL~IBo#WBWsvI{Owx!-G}`ZXOiuR(+exRQqo6}S2pmJ%2S5k<q@3^Ym+zqUlRpOMPEv+Ri*?duOe%dPp*O5p zQ2THbS@6@Xw5Kn6kM?4rCB0E8ZG=2EG1RI)IQu)pR#@d(Y%wf zBj*9bkdS*no|;cz@C9+IgP9uK8h*-X12X#nDt{$^2(M_zsR%%+g9qvm+cJf92hQFI z9{mwr^cFdoi<*Q#i+FPDW|NM$fZM{NZLGGw3NJP=>A{$FKSIyYP5o#RCSwv95-TB> zGVJYB@!ePAoiwsX947phCiYUDcEi4wtd$gF!g58zv$YAm$E86lq=QbjDi!Ig*0xS- zy3-Zi(c0F69{VK@)#&eiro#{HpaI49ILO8cF*W2I*g6v?8u9(S0MyBon5y8$W! z6L~PH5in~4x>OWH2~JF3MH>XnD-cQ|u;37G2Dq7(;qxvp_`3|Cv1wKFiaI~xYm%Z! z$wa&26I2}FUcX5jLoSv83=Pbf#J}rZu5*4M*+Y_A_}?6zG{Yp+i#NXt9vA|uPvh1@ zT3R2@wg;^}<(uLkad4Pc2Sj8jtcx|)849}!#JXATngdCKq0dVpX&L5Pp>rQf+qq_Z zZktX*hlEN4=m*p5|lN|(BbItkEo;nV#2TlBa*7npks zad~4B)c`*f_EP}`VOma~G(`dC(x$b8!)e{9y#X|zgd_A?DkAS|>vuK)e03?O&7Ro@ z(}Qj8a#4N;X4?tYZ41$(mfWpYckJh;c6^}xuYt?%tb+P8k(h12whGX>H_2Tx2K`Q=E{Uu2?`rv-a@#2<*V+-nq%k#l zE2l#N+reijeB5CS^~T8dV-l(g_TB!5?n$S$m1lI~L<9)9)lAI-NG)U5b@-)aFr^MK zZ(OroR(7oK4Kv5W-Vc|X7yu%dUQF}ne2vwWlK)MTK} z{YT7MrEozMm)fBFR&Pb;p$9J5{e92kSI&6k@=BVKYSJsYu2(EtrjRD8#En|VfIpnn zupkaXE@*On0*{cW2@6IW`3Z4SseB!P@|M~O<9I0UY}w3;}Gf*G*;yIQAF z`O0#@dLB$lKGFHf?C&9%mJ9G30a7ANlJ&D)qa zPVW;t9^EWMZer~4M*&8@JfCg1e;Mwi!p%xiJ5P*&;Kv(LX(LMSK$vxaDManl+*owE zrP&Qp3CPeR4AZ(gR`&4_z{YWEA`)^|Y|7@kWME%^kvFcvPOQjlZH(aq4aCaueW_jCJ011+)G;%8(A@*W@q#W0*g|FAGg8 z{KL}yfLUKT)z^_KIDKpaKU8<*?+uuB8=WLsxHa9WUW)s)fds(x~=#tNS5iGd?E84@I@<}a;Ai#G2-K+ zfZ-ED?MtU90p;%~trj5-$X}nwYa0QlEV%p`%uk~@W_gUQc)5n`Xr7kI*T9Rz75{63 zKfeD&p*w>a2(u9otKkPFT9YA#;0xJ|-8}N(|1(l*tC~!95iK8ee2&Y1jF{|Ja|dDj ze0;nNSwE_EoRHfMup1H}ar!|qf{Bk{KW;xB^OwCx3*^zJSop!$_4PToQ|^y!MQ#=6 zcb7kttW>zJ(YfR+&J^lgrsaeHKtgO2(J#2vrhdJ3{>KxbO%`NZt$nO*urWDm?Crob zoE(0a6plN#)jCejunRz(l40i|u&WTJbT;#garvW3nvohsQz8M@2@C|VFT)wT}v{o3o|k{+EZ^R{+M*6+>r0qvZ=*pb&dS1*|f42ei`tg9C!RCcbd{V zg;#B#H*Q+eU44JsHg^YdU~$&33XjD9CD^`liQY8uY>RQk_5O-fi3*eEW729Up`q25 zo$XA;1ir1dZSK#Q*|zx#X^z}=z`N+tUYmS5zZ-Pm!w?@%UW1r|+PYN*4uQmtxMKh; z(#U#8wbW7V#m^aBor~GBETdT>KHJ%C^|3FGIWR3BW^`YqmBEK)hZv1WU=^~h&aSKZ z=4N_P%AdHM5*ZCLb7Xs&1;B;n0*bv3Q~{c7h!B92bLEWcORQlq_dU$lgZ5YbPZxF4 z2N0|MJNZQlTC3})wEZ|+0r3>>TY}=N-nvX(by3Nl-39YD zALUe{L^|HS0-z{ivI-#fgL6avCI>4B_7K@#X9rK8-ExLhhW~EYzZrPpy9D9q<84~d zG1r*&z5q0BPL7>783WlRx5wsSXrTG}+nLn*%%P7ly9kYOA4j$VP{oXG*E9H}b9`t&n@8&K;P0{9tf=?Au!(&u#xW^TDM@(ppSftCLpiq!m#A zu43DauW?%-kr+N%1f7Xc{22B16D6eg)o=U?&^E)NMuS#Zz{}RdMEW)`2S%T33optc zv5qWISTRmt#AI+8p3>F3&(44S;GkR>L1S4Z=1+fcVIB+EvayA|%IHiwM)RRQP`+P7 zq?z)O%>lC-#O4lj;&KJ6QlJHNXWwsM2+Fu4d2*B6_4y^vg=9uSSk^#a=BffVKQh`>kP}Je2di~Rebw3pcC$BqYgzhG$~_)`EExSt z{DpUBPtm{M7hSE*Ty^7TVN^};^?QUeOR;>AQ}0(yhwH@2GF<{f>1OuD)r#X|q?6 z8HXtZD!mgI>PQSyK(bU%=_315n3)09uJ?-AIpUb&U!f>tEtdA(JOyLN!C<~kQ2NVO z)1_uret=FXq}b_H!X{pZvX3lFkm@Dp!>RIoUiY*DqI}CS9q*)bM>X zx$`t2otq`D2=2?tBTfd$UNVC>Qwhw#F{-l%<#>mjVjG;XN@1JD*O8o41GFTX8W!qi z8;bJ^OD6;Jn4weZmz9x@!!N61pxbHYi^hY??wzVH|N15|THDC`iTZYe8@|Z-?fz)# zA+i4%zt)b~F-he)$8p)`OQ;80X5GO-IVdA3+fjvx+G+r zlFgzSeAjcE_J^D5$GWci6>T}1ZkgSOo5gk`^i+*ywhS@3GX#)b1+bIWX1aF)EZYDh zU`JeXNTl&Oix2z7ouCmeaNakVQZ~!AGFAjx?Y&6$}Zd5pn>6Qerd~TPATQ z_erv>!a#7J2B_irn5DFYQbCk!SBJxC~rRnCx{`k8M485uAoR0h#Zk}aFgJjy#Z zC1?<3x=F*TMgU6X8-ZtXy_T^xF3+(zjhrIT(PL%#v~HZ}+?LljqDP&d3QfS+JV*O> zN@R|Ro5$&Q6W7+7Z>~BLcUv$Nmsy(FXv+I=>l4FahH0X-eCY6`I@pR=; zSCre*pOwVLt+fa(le-!N+5;d@j><-pPA>d}q_hhmf+h^`Y%6RZ0n2`@MHtm-6?S@L zxz#jg77Ii2WdZ^TK|qsB#awyMd`)zPof3wa!3b;CSPgOWZ+%sj9S}DM5qyIo8jP?D zGrH|RAlJyj2G({YnLH)%WFi1FOGB6#!J}CZ1r%RRsZB5ZyX6p0N#W=56J&W+X2V1m zDrDA|p|Pyh*8T|p;9xt8;y_YT#pAmnf2rC`Ic#>VXP$+&fXNPQH#46u1<0Mq&LAT@ zB4i?#Kx_`n{yQ$vUj-=H6#&IWmX|+-)LiPo$$&XDGk613=>e0yT+z@RIg2j<;=9{I z_>3ABzZrK--|EzC0#dVJ4rNk}5`8g(V@9|$G5%7Z8V7$XC-4I%DR0JyTj$JQ!f*S? z3n)XQd0TJI*dWWdqJz{`=}MV=vOw2lzIwZiYxfz!{djk{E8@Cb$zi37eQj=ideKt- z>doEx0tN3sW&OcRxjM@|UlLNAPHpmyn2c5`*oEmIw^pA}_)WY;HyDUp9_r2ZEh!3O zv2pHwXOQ4I4egR4P62AfKU@Ip%0MWu1t=4*SB=kmaG}N0NVbXtNX$2RW=gmX?S8 zhdIeE6@^x7ncFfZ9LHpD?G2i?jLripZ^(N6UhP>$pWHl^jRg!06Wuj^H@vqO`d44` z+Jz9EUgZ166^~eaeB5+R{^tU>b4djae8#ER=~(3W+Y4`lNwoj|i1q&cGw=d*x!|BJNK-M?c{qX_gTY^9Q@q&|4|P7AOJS;uh@!kFaY2)d2w>a z=1U`+j%uJE_#CR*;jdYdfjm==5^_1P8vFvsN*_8cxp;obxvBR!x zD=lXdA=siEV3;+jW-&G2rDjZn26_iGlfAgl40KaBs8q-JtYMb#>rP)szXdRH{A?~v zNxeZ_XE5K6kQ4~@!Fpo4fL{BCKB#7lX*kbdMu36i2$F+A3*xGqCPFYm7>Aj+ zqT3x&#&v{_Ynb7a%oY)S>rIaYgSjcE+lGs&wU!5WxjUdXLl`|K77$vYH?P- zzSNxeU|nE-vqfq_XT?IGW(yE~daDeEKImEgI1r#={TD~LDXgEr>xj-m0wDQK@I#~KFJgmRXK6!g$)+gmT+F$FA#r^HS z?4Ja8kOO_7Es_dn)qhrk)BFTYR#<1n1`B(`%dEdxVmL~m0jAaaO{=880I&xMzG{ZI zfn`t=yx{Ljfk&)2rK8|mcSKVn9!}L%51b3G{ma5k6B-0S0s}Kt?JN;MlK|_N4P(Ks z1UAh5tbxAb9Of_>1Vq{nvs_@~)=|?tDMH9!9TRhtFlJy585q6Dfs2sr{rt7Py5EO1 z#h=eo@=ekb4gH;gu|`7*hN(&eJxDM<2ve@z=ZqORK?qTxCBEpk2$dh>Zkx5B!`t@b zpVAaRe~I@WB~$JN{c+U(gml{Sd;Xu_-a0E=6xVmGU(buJ5^f6<{vl&S0?=Ln&~eF( zjX>QEux0Gjvb(J6SI{?r*?o(lcvH3+A=QZK%K&03oD6G7?rN@3uoWsU_ZJXc49q$u zWMUSF!XcB0*c}Jh0s^E5m@s=tz_it}nR0@=K%Ocl7?trG9@3{^!iSH{U%6>;6Y~YK zdc+9P18$fvQv zi>(h|IJHFBwXiW`QPR|(WtN+vyGK(OejYL_Fb;eFKEb6A-|C+5fAAX3>Ed~TJpKo? zCNHRL3W&LLhN!+SQZur=OZ;IL1hc*Y>_GwHtS{R|FcySVZpPQd8HhoNqy&Hty9XCC z2`|p!GMG7Os?QyV>i#A;QlQ5tA#a#~J%k3Cgm(zhR?e~4KqG4AH{?kGOo)BMqM9g% zDDy7-wjW{L23TVn=GNY}Uqt`JL{ioWibWt-EuidCQ%uh?#;vRA$!cm6K+e~Uh9VZ9 z1*~zH!A)n4s{0&Kf)ck73{z*`UV>iOU>&9sZd;VrrOG_PGY&`mb@O)m%L{Q-bGMHP zpEt3sgr5_XpT|m;zgg$&$K+)>^T=|bJA2H_00;mA8DR)ae~caqP)CC)41WXbg@NUX zLl8pPdQ&jDn(PUSQvl*K5ekip`vF(@M;M5JL%2v}Z*tzR{SAoypahKVSEXFo&J z2sq0?2*o)SCkezpKM78F{F2$QmiZbGzf}{GZYmW`scG}*TVE&K8Iv#8mk#iU?bzMfbkh-4Isp4>U2@Pxv2g;EVS%=yy1$~#wts{KC4Zq z`XioP?03+kT$<8W6OUvpuM`p1qKFRs^~Z<$RNBE07jf8 zQ!{)GYy*6KtPe`Z8J}Oxk3b*=E}X>4LxyWKoN%{myBJ`75Htq>u1)~7`8`1lv+ZHl zI|F13&$HtZs9KgM0+p7o^uX8M!&xo>G~`97J;fU8VtR94zqr*iiqqjpc#{bpF`l$W zO-ZUCr{au@JIu=faxy?xz}H`B7@;uTUe1^jb!jdVrq$F-IM?$GFZiF2)3f*gr~Thq4jeLGFazh>}NilcZcHrsfd?TOxi7E#i3xR4LNZSF} zj{{!~fQy<%HZ^Bym{U00m;p7N1U3ScsZyx_9uY2Ci3^y)ntK8BE`QJv!~lB?cE8dI z3T_hYHJ|`j%5XLW{{2k=-6-8QdIpNb8QuuXpL67ng-OxP>en#6Gz7E9^hpgNY{Iig zL?3+c&nNCZ=8ClZPilrh$o<-2Zncz0Bv=GF zTZW#n6iZJoO#E%B)+r}1Vdsg2L_)!`%MpwIslG7b6kKH>o{i+xqSh(qtMB6S#_*Y`i*OryH# zD-4YrejeA*zXELECYBysMIKF8VhRrb zTXn?m%7(}f+|8?n^Ime`u=8`<{>Mtw)Gi{a{fC#gg>UI*4|NP%;Zv-q4b?J44 z6{A)vU=rKtMoJX00sxBFYe1x720eK!(9HSX!Mc12gzC3D)PPV*z=~EvFGe2RB4^526ANM@%wTL_9qe_VzIGWe{#wVC? z`{j2m>$wkfJP%$~M}Bo+74=e)<)>udPsVGP<2?+Eq@1(;G)CuzWq+fqeG6<~u*t%E zCLJab=Xk?_{s{0*t^W&Ve?}PaAd3pL5)fjVy4FR*QffH+_K-SE4cO)cTO{ox0NHAo z9}E^gZ=i7vi!1=BF!KXDIQGtIk5VYK$xUuBt_apJs%do|nj>>7pUhUXjwP_i0mfGY zy<5Zd6wOhrp^pO0X7Rx_FbPPFteq8XGvDTWN#09OMqgO} zI{wg^@&?6f+CypliRgWz)s`C;pJ}>SKEAB9`t;c!Zr9kZv+_s^&$rrV|J2fRUVBRW z;hpo(y9+@&onxB;BLtYhB{n@YASVcvufF=OCh$ZM*+`_e-I!0Z@CYxi%uqvRyqy8* z0vM2?3>$&HKCCD#kBE#*R~?lGWSXMPLec6@}~bs6WKOI_fN5#!}FZJ$b~@8paWVO$#blpZS~#K%5*T$|+Z&H=_1o z3t>6Msv}-|Qec=xaX?fCtnH0wzwJAly?HwsM9c^3Vdu?}A#OLudiYxP&sd`Np z0~&_A?0h`Ey4fo|2cn!jI^RdSZqmFTw=HX~FL5rL9KPwgzxdV9(wWx>6ANFTPZKV9 z+iSjSLgL;dN^pI4cIMuBhjtB=C;S-kvP|x>ak7ejk8rzRQ7|aE;@gzDQhMJZdh4l%L!)=4opWe0vGUUS z{Ecdp*Ld<>La@UyN!g_A{-9R~;m|F-`(5!%-9L*Js(WmD-?6@+rfXowa6DNFL|Ac3 ze25~jC;+BhWm8Q$cjD$80F(j*^KU4NZKyI*1%&nL(^%&s}_Q-8! zxEdfz;Zvb%iaDl%GR9!iSH0F4+NULCr`u7+)P+H?VNq#wm(Ax2vstFn#tw+!kS-(7 z=|;(cZD>el1z{GCL)UV{s2e8>LUOgl9nGk@ax;JS2w0Z^3#39bZZ~e4_9!(*4}w$$>9Q~4 z@Hxw7?h1pq4Zk{`fy?RaA}FUKY+B5A8w>wsQI0H+$E*m9NoJ~1lj2Cfa%X}e|2zF7ED)MYAP>P#ugg(H|=Oc)znIEl7 zVYc7kl9+FI-S5vY7?1ml>tkDBY5%D?vmmwM`J>G)Swnv$R6h_^`7bGtMN1QTHCBr9 z0{84M@jcXa$}qtL-hUaR+i!UPUqk2Nmt_9H@#m58Jdgtrw;76i;xA%46;S$+1efqf}K5xdiDh<8CD35Q$$n>zCO@9+NcHquTww^K5ib z4h_ANGp?O1hNkDKMfSiL_Wh51UEx|3I&N+hXAqXBofrxoAdTrgVHJk9ag$af8OGj* z*!=oMBGG7f;nzri4UO*u`(FlSv>zAd_2GG!aVh}Jb6GN4PO zt}%(octCyaEHYeE*_Ygs_B4fmdZvK5$K{J&y!XP>t3L+5v^F&#(TZJ}KXB;C6UUEn zSu^#XDAQK+?2+-$8lS7Z{kgs`kA$|s*JhKe+Bl_k-{F)YnR)PCAK!LIoA@ewDvr+r zj0i1?Vuw~jswm4?p9)vVThtZ7HV~kJc7Yt6CNQ6bW&jFzvxDK4nA(pbE>&3u64?D9 zmNKFgOH#VsZ>nh~g;L`rD(zF$4L7pUxD3{Wo#rm(hf?$wDTh!=%Ga`fRj5B;sJ2TC z>W-2ST5yQ6@6jm2O@L3%;vyX=T>Wv1l2_X<^}WeHjiMJH@ zc^<6Xy}de8`-jHRa>4EsLA(hi+*hRb3tTCS+G%EAqL84}`6R%MLWO^7VRlMjK1)e) z?=PfgS;`LKa8R5Upv9)c6kvWF)K>=&$Ut3*wwB0Z_g+A8r9LizNK#N&3T5LUbt&z* z2s%!I3}kslN?Z1_!9y%4RqkSgL?=t&I1)Ne3MI(U`f`+$1aVM~vJoM6OHf`Clqm!0 z!@_K0C>Af)>k`9Sg*?G#PlfCCmOGJqnmJfRFF0ky>FYyd7|K!*fShd1PS zE%eC~^gao?fr{BJL08F9Zc?aHq~r)dNg~8mXM_tC?Fb-DSjZR|CKf;(01$Rk@I4+% z79DHkY^)Gq>RA|}crADSPGLI-W7TSFzPRH*5ivQUs6RaYh<|n8>)7vv0D~jdWIz9- z%Q*qBa!f5UemP*7VV=9wv8Mse=qh7`x>l9;31W3d6fJy{Utq$u%=g<$l;xQ)wS*`3 ztg3_aDR7_}wpI+E7QrwhD_?>ylVJ`}gRs#GG>a(}=oNCk)&r0(D?(cWzN-OLWzmP^ z`?3ZhRTiLz0}RAqCL4@k5_a*-|b?C5SOO zB*Z}xe1L?o0nkozRGbW@Q1=83YdZ;w3SgW`2$Bf0k}Ec|t&%BhRA*8q19N(f6Y%7_ zvH33S_dMI=LSmM7^~VGwlL9;Xry{NEc7~CA&&$=Wz0NVi=lq>#mp@rl0IPR~XIu@4 zE1SzTNv9+jV)o3kDc`-CbXh6T3=Mu4P~#q6wCNhQUsEdM-A4HeUNEnZmw z*9mr1lHl4ZfKP)tl*6Y#?bDHaAt(taC0^QWNCyWGzTzIiIpd|EcP5A;fsb39i&DTN zav)O#R^ZA`up$0c@TDpACfR#06`En9GdY;kmmvWKVJZSYxgi>n#?h|L7!qDwRcXs=H{IuI|no`-qDDzYUYWXPr+yZGD-eq;dPvLcG}TInI-b- zJj)lI&1WYEYo&g?4(F5LQU-?4z!Y-;0z*knDk^2eNCg?8LI_p_LXyyP3`je)4+6k6 z8F&H!(QNP-8_G!lPCiC&n5F4T;WUo3m2dQMDwHJv6*|(x80eWlR7I&jfqV6LK_-0v_F7OFwLyalFpxes)v0pvlIFX~*wBx*Yo}kN;4e?9r_ml+pEW zyU?jNBOD*`d5~Y#jRf?E@RkP*==yO2*yZC{I_AM<=qQpxJU-Y$uKn} z2PF_7{c&?8zAJM?W7C9WgPIN9I~B5XRv@=5g0WK9mhcil)i~% zZwmTA8Vj8!LLXqEE2QYCJuq7_;Wo(?>K&o3A|xlV#{nRZ3vlJ3nN+8iOHgRI!(1WyB(*%3aqXB4(g(nD z(ZyfK;owhB zPFftd`dmG{w|_(<=fyqj!W7YJSJUFc8LN$Ul&}XzNjDxs8fLUTR<6cNKW~@$hVQYq zP1rTD^1Ul{*mHJAt!wYuH9p{T`sRuBH4NO)+-?f54(4`<;q{2xx)^M!*vlpu@HYVv za!5^lRfhqQY5++al#7FRT!Q{1N1deH-J<}m09-B&J`TW+Hx=;J+ZhWUmM2hcpfn29 zC_yJuq0?fhNe)+$vWpaXT`9VRjSxsdh0t0i@Us)6ian4Dv5q2B%3>ihMNp~;ZT}uV zMZ!vBG4Zp~XgVSN8-d+Lqz>Pw?yB~rkLy59C+fyK-rd)7e$Xu@ywM+eH=N@OX4uu+ zg+82PaEX5}?A=Af{Lr7sUTTizRs}NcJ9u^8v^@}JOaTYqPyBSn6goMq9|MFW z&COOo(^_FSW!t0*$>9Xc`O{U)W7J&`#SA$M+?ytSse5c3YtyvOXT2ls7gfu94ANRuwgS1iUeRbOHuJuq>o~`Rjwr0RLT)S z5xgBOIBcrq4j6&~&gI4vHQ005+n8Jm|7rFI^*eWBwXVi;w3~E(if>>@{`KPzNo=KTon+fT%|5@an|Xn`hf)C;V%rMq_pQnc(HBh+Ha^Nu|PKZ*7?_z8Kt(gZVgkEk_Qe37`te zu5z4TksRX7VJ#LN{*}P_>)6UFW3LQm{)5h^9?JnR_AI4p01+$0hycVV6-UmF>3$IJq^K~U~zQ`+21pCc>o)EhlD3CNLNIY|N!v%v~RiMHrt5e`-u<@dAF zPB5Tyc7+bLMcM~ZYzi;tp^uZ$hd3`SC3SI9R6DSS-6_YkiR94&j1LDnqKu@m5Nb4# zj8obNU^tQ|Ez;M)u9yhCMjhw&HkxhlF0A2IBbASDJzH}AbYM#F%pG+fB0N|jK3LKJ zDK>z$y<*2(^NTf<=<19LJFTPu0T?$32M^BSoDrpfcDCb%&1{lc`S z(W4Z>-CDjxi_ai*q%IYT;HMXsp1ri!&jb!C(|@ayDpCLBSL;n?>2T%He(Cz=_i&C3 zDwCHd9fyDZW;POI;Cci7$2H8g$M-5(m_iw3B!_mA5HVEj);hVL2z6SDISXJ#GE6-K zR5*PN<={a8v*R~R0~_7i5I|hh*%OkX(IN5ZQ@`Ex^7Cd|fWgLo?uVioOh(IZ;|9m~ z?w@^Xk~IFI%vO5aE`6^5c*l5`+;3HR;?&&Nt(!H&whr&QmJ+%7z0>j6F(=>u6BOiA z)E#^xD`ywH@73RhSKxMPYRH3c^@mebq%b!f5Sjw@hk+MJ+%YAjHn3btrj{u?|D$e! zCvDE1Titkh?}NfkI8x&B7c;@x!2M6UQhW+48tf8n*#i$viKn-;QMgLA{Mk;M4tE{< zgoH^vfkMxb<3?#@=Tnr>(X6*jldv}bazaun(K5W7-j{HDg=l#p_UGR}w>^2k{YuK? z3rWupf9Q$qW{#xY#ztC3t@X(k3#L;azZgExZ0T9|l=3txAEBl?bmTzqIP0CmlXuz& zt zeAUQ@cjCXbB6DtwFN{?2CVGK}%r<2cDq}%l%;X^h10<{*B~TezyTK`!p`^0!ftkVs zG|EM&I=H#FB{S|gzmFbMEB=RVEbvkNln*G|&Ph}~zD>$h9sjJ`-4;4mjBML%faCGD zIDmeow!!uZrCZ%~Mum8I-`aET7wN^7No^<;1?!sN<7rLDk+jz-t$o8j|(=F9U%8pY=ACrp%OAUm}eWr-M zd$)jh0lm)Q76m=C{@eSU!;=w0;WPMVUr$)zvp&~9^3;v-%N35}*WU>9AK=i%2vsf; z9VEnkv~4mT{)7wyZhq7zB|i2w?RI+f&0Uwr4gXItmhU3cTf+Ge5|IKg?UZvWo6(+# zyv;6i)XGh|DI9!=b=7#a%S@n;@}}Pev;rDy*;j>mNxnp6cy`~fwx+&qgKaj|gM7kE z2AEg8CNQpPKjZ%4YB;53r8oT2%)QXxC-OeCcxr!IPC5U3gJADGl%Y(&9rNSPq{CI; z{dBvvzgDILt-`j4+f{kI#@5=RrY(aW7>qeyVEXD5xOju*snYJQ&swevqp#DLGUaS1 zrnewm74I#oLE?jALlbd6#8(yEZt6|dnIM0i#Nq9o{<>9uIIeA#AJH&T5M-KE9ObQK zkKF97nmwMs@u-(^^`;f}xTHYSUBm?`q@_yd<*wJtF2>Ii%bkrrjaK@*%g*8bz272* zVZ$~BrAD4p#>FO^ezd*Vys#_-HwPY-DXDA?;SuWX>UmciL%UV%YPD4F%Xr7Xd)Y`# zYwl4hpLr(j9yI>Aa>3E+o7G?6Sy>?-Oy3`}^=TIh{GKqAq+iE<_pHsG z|9tuChEPm2u^#_-eV7cVGe6K;(3ph_vK%zVlWe>R)r<$TiPsu?b(Ac3_(;yXMe3sg zGq;fZ*@NaI9NLv45Gv*wD39oQJ1yeT!MHb~!eW27R($5Ff*O9|Y%(_|lo#`^v}$0S zDG7x5=zP?$0O3E*f@4U2TK7y^={zN3?CN-Fi5%8YZb6>pa09d-S_WGyowziFylczF zd~eDl`j5VdkM3{#qy5tn-F4fO+h*&=Jqr^X44dz)7&%N{2}+2~4zIuG~O8JNFbDu@11 zG-9Q}zGPU&x%H+GU*0ulG*2pW6Vj9`>UeqvG@rnu-o(@9S{CkLzAeWa?Mo@pJSA3? zShV_R%Et^P91w_W6|RjUO_IY)f{U#gov?E9=nVE{cUUWStnTBClj$2S{V2CPIr-8-l?ex2qBx+9H?|OAH$kbXeFF56RU87PO@03%?}L4e_N-@ zM!zx#TG4^k1LNkb08CV{5vZ)dr}SEh9oAcM?D_nrjjBkJdUqz5$hR7Gq=xL&sX-j4 zJYXNYUF@gaiZ5dG$c5qOVP7SLb{C@m<0-x#bCgh-tZ$qkf#^#j^=8?q@&N~)ZCzf! z$Q-qWipLsewE!j*h1e}E@)PaBhidr!cY#^*bYLs-_{O+xe-a+@C$0rOB$tQaeRNLM z@)J+2h`jB|= zgyU?B&QxXgx?a9RL zvh#NFm$XlHKzBCze<#+YKUxi*F#XP-2u+__7e&x{^ypEa z;0*t0LxtiJeuh3oyJ5msF9w|EY_JL#5r*gwbeD)8H>-RievRGRCEf0u?%);~$#n)h zVrmas_rWjWJjpMeUXtl!tAJS$w@>k$^jQ$3J*k!&=wrNvJmdpok#sLRvP(Jbp6S=CX}HeHV+^VN&$dItLRXpY;vc z^zBW>0Xj1pn{7H2xV`Q9^nslX9yjST_8s32^zHiXyw>-@!}prg+w`uUS+F;`MC@d1 zD3RLr-*|rLI(H~Ca(a3;NShdVn##LX@=aGs^Fzu;m&%^Pn5N*(<-d0 zxTx+Ecug~~4Q1??ioxldb_%YZT31f-yXshzP6AQ{m-?()!A_Ru8~U0!EmI1V)kf=<*5mdbu)uA zZSQN*OFjd}dE=`m?OS?}VR|YSiAl9QAS8X{E3UPRl|L|N8rqAjOZzMS(ZBch8GLG` zY2(#4@s8lQT;~PQu+!lm6QeMUOB+a-^5p5JCJcsU(a;o1f${*0zm@cp7&DirN$*E( z(r*PQ0BAS8P9x}7vW2V0?p9yJOOXQ?4kBEK!X0ckst-tpxM1nBVVSi>^P&8*%y%BN z&n5T9t{?8L`O^Yr5~eODU5;XVI_Q+C8LPXitEkRiAXs0%ix{Y)p@IcS=|0^snMtsl zi63Rn+1IV5i?*>NS%XP2rZ99jQTh63 z`OGxU7eG4AA%goi_$MPFHbAW-`s2()=5YQ3u1_FB2gWmsxeRudty{s?V$ik=(_oIe zh(HCqDFtc+8r4YPhQ(t9VKxKXiz7du!j77&+_0h!?a-#p_l?%M(uW;hG*p{g8Bd7T z+3ahseOOIcI=Asvb)Q6AXg|PdG^iPDuIi_{uar$XUd|)%QV`YQ!Htjg`Z~oH4L>$? zVEX>cR_O@i1rIp-%GI9u{)?zys^QCr~8)=Pif8Zs#-9| zot3{SS>GGr4W=Spi;-JpNCt3@&N5=)Hixew5914L-10K;>x12pm(+PZF<#zd$c{@E zv#Z$p5niprF)A+&YV%E>_N^SWd0RDJ_G#Rs`jYK#hxgpF{~4<6@HF<~cDrTU7AXy^ z+h1ceHtZ5oc2RceuU6OmbwR(g27()PKD)QipIc9TR@1{eJ5Sd8;$Z%w1{qAL4Js~Y za{Ou1o5>lYsdUp9jo!c`Vb}K214!{DFkn*%&x_@}!l*IKOWK5|5XfVX8;bE|;M z6eHIc^9PJi+c3-+fl4+5H?}S-c^~Bx0Ax6GD5w?bQ(WS6j<@!FQuSN?lvRCTiL&dB zx^r~;WzQADZ|Z)TnavND4XWt0>Q4~2^!n54VJ2|<^!|dWcSYk=$4U#G;uzEufh1}{ zSVAGMMu2o~lK1a)s*r0BgG zvnzh?-{7NrF{fdvi)3?8o`cKaUPEH0=}FMW|eeA^GJ>;l708e=Q0a`cUmw#yODGQ&hD=JfU?6QhXTg|JMx;F@JCTz0?6>szig z^_Zg?35|X@WK4I(N%n(g&>5U0rL^6B_qE;PtD4OMP4p^Q{;S;Dx?*v)d^=v`wVLnM zTVYpH&j4<@8yC=zPKU|zw7ak*>GW1sxv7!R_9!mPlHd*>=Hxel`(@3MxcrN+>&Qrn>BZs@4SpH=7;hZ+JnO`67cEwL{5lQj&4pdptMu8rU7NHGo z7G73;PS&Ufx?y8rN-|#wNtCJ@MjDXrMkAI+uv>NNTMImL^WxBikLWWY9 z4M8DbdLEw)~vtH z+}z!vyXWg11}B%fu4}i(?k^{V&1Z$Fn>b#S-UG5?cL>kDFxEj|348l2)F#_DcX#*G zE02FS79qQMz9T9kW#XBFi;veosIxB!2~_n4&b9D1>|QDFb*c#dVtLL_H#Ibdh7$$X zxzzUFT$;OlU}0pvafLX0eZXMFhMV2fRpmE!wlY`qv{!ju(QfC}@ee^%*kos-(d6KL z-A-+3iaN?Z;oikSBBPcrDYwDgiwF^tE8a2=<=6a4t6#$Ij4^p!-B()R^GvaKj~w>3 zPc@hjugl$`{?zI6RCL&KwQccC&BZ`ucyGB+(9ZaOp(j`CUoGi`$yKO7S*tf*EK&4c zlt;bk8e9q-Og34w+U7}Ly}ZeotU@H;M%pU=86)~z z=kly2W77We=cQZzYT|9KeZIl*qEAyv+PhZRbZ#}2?2zfGY7_fru%^E0k5^$96Ne&m zLL`oxA9!0#G?40GG~72Nl96KR_LASx$5EBi5IW))Ey^S1`&Zy@iVf` zI>GU`%Y#mppSfDHn0$AjJx)nu{!&cL#ne|tKC1k6eW`kV5$@uSy60XAtXsOKnA zm%L``hQ)OEwQfdz)`ce}k89~=Rk^##U!sx2uA%L&e(P&Aeks57{_C!WI`+hUHT@@I zdtO@UQrzul13O>L+RQv+-F#kL|4Kv6|3~7|+y*hG;@2myaLbEdx|3)?<=4~(eX?F~ zv{%l*t#Q@7?^3T2mxOuencIu=^x~2Yedo7M^6p}VHj=zK?a_{14NrS}^zJo;Eytw2 z8;1XVo*H#7((Ty~#hm00mct%%*VpH4d)J+r@f7yoi;zPbbtC=a)UEWEp7H*&vUhN; zx%teudnKrhm?P7CZ!jFFj`uCtyc7BSQ_UIlOwh-@)a-pB7j~lCRfHoJ3m(ZUq~7q} zn8FKJT3cKKz9f{?^WTt{jQ$G?e$?dhx4X)hk_XLxCUc_lstY?Vq=8%Obf_s>_@KP4 jIANU1=wn31D~*>OqH9lAH#a?VxDUKO`>}}w03QDb6ty_0 literal 0 HcmV?d00001 diff --git a/grid_map_sdf/include/grid_map_sdf/DistanceDerivatives.hpp b/grid_map_sdf/include/grid_map_sdf/DistanceDerivatives.hpp new file mode 100644 index 000000000..20fe2d166 --- /dev/null +++ b/grid_map_sdf/include/grid_map_sdf/DistanceDerivatives.hpp @@ -0,0 +1,62 @@ +/* + * DistanceDerivatives.h + * + * Created on: Aug 10, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#pragma once + +#include + +namespace grid_map { +namespace signed_distance_field { + +/** + * Takes the columnwise central difference of a matrix. Uses single sided difference at the boundaries. + * diff = (col(i+1) - col(i-1)) / (2 * resolution) + * + * @param data [in] : data to take the difference of. + * @param centralDifference [out] : matrix to store the result in. + * @param resolution [in] : scaling of the distance between two columns. + */ +inline void columnwiseCentralDifference(const Matrix& data, Matrix& centralDifference, float resolution) { + assert(data.cols() >= 2); // Minimum size to take finite differences. + + const Eigen::Index m{data.cols()}; + const float resInv{1.0F / resolution}; + const float doubleResInv{1.0F / (2.0F * resolution)}; + + // First column + centralDifference.col(0) = resInv * (data.col(1) - data.col(0)); + + // All the middle columns + for (Eigen::Index i = 1; i + 1 < m; ++i) { + centralDifference.col(i) = doubleResInv * (data.col(i + 1) - data.col(i - 1)); + } + + // Last column + centralDifference.col(m - 1) = resInv * (data.col(m - 1) - data.col(m - 2)); +} + +/** + * Takes the finite difference between layers + * result = (data_{k+1} - data{k}) / resolution + */ +inline void layerFiniteDifference(const Matrix& data_k, const Matrix& data_kp1, Matrix& result, float resolution) { + const float resInv{1.0F / resolution}; + result = resInv * (data_kp1 - data_k); +} + +/** + * Takes the central difference between layers + * result = (data_{k+1} - data{k-1}) / (2.0 * resolution) + */ +inline void layerCentralDifference(const Matrix& data_km1, const Matrix& data_kp1, Matrix& result, float resolution) { + const float doubleResInv{1.0F / (2.0F * resolution)}; + result = doubleResInv * (data_kp1 - data_km1); +} + +} // namespace signed_distance_field +} // namespace grid_map \ No newline at end of file diff --git a/grid_map_sdf/include/grid_map_sdf/Gridmap3dLookup.hpp b/grid_map_sdf/include/grid_map_sdf/Gridmap3dLookup.hpp new file mode 100644 index 000000000..1ef1f5427 --- /dev/null +++ b/grid_map_sdf/include/grid_map_sdf/Gridmap3dLookup.hpp @@ -0,0 +1,105 @@ +/* + * Gridmap3dLookup.h + * + * Created on: Aug 13, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#pragma once + +#include + +namespace grid_map { +namespace signed_distance_field { + +/** + * Stores 3 dimensional grid information and provides methods to convert between position - 3d Index - linear index. + * + * As with the 2D GridMap, the X-Y position is opposite to the row-col-index: (X,Y) is highest at (0,0) and lowest at (n, m). + * The z-position is increasing with the layer-index. + */ +struct Gridmap3dLookup { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + /// size_t in 3 dimensions + struct size_t_3d { + size_t x{0}; + size_t y{0}; + size_t z{0}; + + size_t_3d() = default; + size_t_3d(size_t x, size_t y, size_t z) : x(x), y(y), z(z) {} + }; + + //! 3D size of the grid + size_t_3d gridsize_{0, 0, 0}; + + //! Origin position of the grid + Position3 gridOrigin_{0.0, 0.0, 0.0}; + + //! Maximum index per dimension stored as double + Position3 gridMaxIndexAsDouble_{0.0, 0.0, 0.0}; + + //! Grid resolution + double resolution_{1.0}; + + /** Default constructor: creates an empty grid */ + Gridmap3dLookup() = default; + + /** + * Constructor + * @param gridsize : x, y, z size of the grid + * @param gridOrigin : position at x=y=z=0 + * @param resolution : (>0.0) size of 1 voxel + */ + Gridmap3dLookup(const size_t_3d& gridsize, const Position3& gridOrigin, double resolution) + : gridsize_(gridsize), + gridOrigin_(gridOrigin), + gridMaxIndexAsDouble_(static_cast(gridsize_.x - 1), static_cast(gridsize_.y - 1), + static_cast(gridsize_.z - 1)), + resolution_(resolution) { + assert(resolution_ > 0.0); + assert(gridsize_.x > 0); + assert(gridsize_.y > 0); + assert(gridsize_.z > 0); + }; + + /** Returns the 3d index of the grid node closest to the query position */ + size_t_3d nearestNode(const Position3& position) const noexcept { + const double resInv{1.0 / resolution_}; + Position3 subpixelVector{(gridOrigin_.x() - position.x()) * resInv, (gridOrigin_.y() - position.y()) * resInv, + (position.z() - gridOrigin_.z()) * resInv}; + return {getNearestPositiveInteger(subpixelVector.x(), gridMaxIndexAsDouble_.x()), + getNearestPositiveInteger(subpixelVector.y(), gridMaxIndexAsDouble_.y()), + getNearestPositiveInteger(subpixelVector.z(), gridMaxIndexAsDouble_.z())}; + } + + /** Returns the 3d node position from a 3d index */ + Position3 nodePosition(const size_t_3d& index) const noexcept { + assert(index.x < gridsize_.x); + assert(index.y < gridsize_.y); + assert(index.z < gridsize_.z); + return {gridOrigin_.x() - index.x * resolution_, gridOrigin_.y() - index.y * resolution_, gridOrigin_.z() + index.z * resolution_}; + } + + /** Returns the linear node index from a 3d node index */ + size_t linearIndex(const size_t_3d& index) const noexcept { + assert(index.x < gridsize_.x); + assert(index.y < gridsize_.y); + assert(index.z < gridsize_.z); + return (index.z * gridsize_.y + index.y) * gridsize_.x + index.x; + } + + /** Linear size */ + size_t linearSize() const noexcept { return gridsize_.x * gridsize_.y * gridsize_.z; } + + /** rounds subindex value and clamps it to [0, max] */ + static size_t getNearestPositiveInteger(double val, double max) noexcept { + // Comparing bounds as double prevents underflow/overflow of size_t + return static_cast(std::max(0.0, std::min(std::round(val), max))); + } +}; + +} // namespace signed_distance_field +} // namespace grid_map \ No newline at end of file diff --git a/grid_map_sdf/include/grid_map_sdf/PixelBorderDistance.hpp b/grid_map_sdf/include/grid_map_sdf/PixelBorderDistance.hpp new file mode 100644 index 000000000..5cd2baebf --- /dev/null +++ b/grid_map_sdf/include/grid_map_sdf/PixelBorderDistance.hpp @@ -0,0 +1,104 @@ +/* + * PixelBorderDistance.h + * + * Created on: Aug 7, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#pragma once + +#include +#include +#include + +namespace grid_map { +namespace signed_distance_field { + +/** + * Returns distance between the center of a pixel and the border of an other pixel. + * Returns zero if the center is inside the other pixel. + * Pixels are assumed to have size 1.0F + * @param i : location of pixel 1 + * @param j : location of pixel 2 + * @return : absolute distance between center of pixel 1 and the border of pixel 2 + */ +inline float pixelBorderDistance(float i, float j) { + return std::max(std::abs(i - j) - 0.5F, 0.0F); +} + +/** + * Returns square pixelBorderDistance, adding offset f. + */ +inline float squarePixelBorderDistance(float i, float j, float f) { + const float d{pixelBorderDistance(i, j)}; + return d * d + f; +} + +namespace internal { + +/** + * Return equidistancepoint between origin and pixel p (with p > 0) with offset fp + */ +inline float intersectionPointRightSideOfOrigin(float p, float fp) { + /* + * There are 5 different solutions + * In decreasing order: + * sol 1 in [p^2, inf] + * sol 2 in [bound, p^2] + * sol 3 in [-bound, bound] + * sol 4 in [-p^2, -bound] + * sol 5 in [-inf, -p^2] + */ + const float pSquared{p * p}; + if (fp > pSquared) { + return (pSquared + p + fp) / (2.0F * p); // sol 1 + } else if (fp < -pSquared) { + return (pSquared - p + fp) / (2.0F * p); // sol 5 + } else { + const float bound{pSquared - 2.0F * p + 1.0F}; // Always positive because (p > 0) + if (fp > bound) { + return 0.5F + std::sqrt(fp); // sol 2 + } else if (fp < -bound) { + return p - 0.5F - std::sqrt(-fp); // sol 4 + } else { + return (pSquared - p + fp) / (2.0F * p - 2.0F); // sol 3 + } + } +} + +/** + * Return equidistancepoint between origin and pixel p with offset fp + */ +inline float intersectionOffsetFromOrigin(float p, float fp) { + if (p > 0.0F) { + return intersectionPointRightSideOfOrigin(p, fp); + } else { + // call with negative p and flip the result + return -intersectionPointRightSideOfOrigin(-p, fp); + } +} + +} // namespace internal + +/** + * Return the point s in pixel space that is equally far from p and q (taking into account offsets fp, and fq) + * It is the solution to the following equation: + * squarePixelBorderDistance(s, q, fq) == squarePixelBorderDistance(s, p, fp) + */ +inline float equidistancePoint(float q, float fq, float p, float fp) { + assert(q == p || + std::abs(q - p) >= 1.0F); // Check that q and p are proper pixel locations: either the same pixel or non-overlapping pixels + assert((q == p) ? fp == fq : true); // Check when q and p are equal, the offsets are also equal + + if (fp == fq) { // quite common case when both pixels are of the same class (occupied / free) + return 0.5F * (p + q); + } else { + float df{fp - fq}; + float dr{p - q}; + return internal::intersectionOffsetFromOrigin(dr, df) + q; + } +} + +} // namespace signed_distance_field +} // namespace grid_map \ No newline at end of file diff --git a/grid_map_sdf/include/grid_map_sdf/SignedDistance2d.hpp b/grid_map_sdf/include/grid_map_sdf/SignedDistance2d.hpp new file mode 100644 index 000000000..1646d0bbb --- /dev/null +++ b/grid_map_sdf/include/grid_map_sdf/SignedDistance2d.hpp @@ -0,0 +1,59 @@ +/* + * SignedDistance2d.h + * + * Created on: Jul 10, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#pragma once + +#include + +#include + +#include "Utils.hpp" + +namespace grid_map { +namespace signed_distance_field { + +/** + * Computes the signed distance field at a specified height for a given elevation map. + * + * @param elevationMap : elevation data. + * @param height : height to generate the signed distance at. + * @param resolution : resolution of the elevation map. (The true distance [m] between cells in world frame) + * @param minHeight : the lowest height contained in elevationMap + * @param maxHeight : the maximum height contained in elevationMap + * @return The signed distance field at the query height. + */ +Matrix signedDistanceAtHeight(const Matrix& elevationMap, float height, float resolution, float minHeight, float maxHeight); + +/** + * Same as above, but returns the sdf in transposed form. + * Also takes temporary variables from outside to prevent memory allocation. + * + * @param elevationMap : elevation data. + * @param sdfTranspose : [output] resulting sdf in transposed form (automatically allocated if of wrong size) + * @param tmp : temporary of size elevationMap (automatically allocated if of wrong size) + * @param tmpTranspose : temporary of size elevationMap transpose (automatically allocated if of wrong size) + * @param height : height to generate the signed distance at. + * @param resolution : resolution of the elevation map. (The true distance [m] between cells in world frame) + * @param minHeight : the lowest height contained in elevationMap + * @param maxHeight : the maximum height contained in elevationMap + */ +void signedDistanceAtHeightTranspose(const Matrix& elevationMap, Matrix& sdfTranspose, Matrix& tmp, Matrix& tmpTranspose, float height, + float resolution, float minHeight, float maxHeight); + +/** + * Gets the 2D signed distance from an occupancy grid. + * Returns +INF if there are no obstacles, and -INF if there are only obstacles + * + * @param occupancyGrid : occupancy grid with true = obstacle, false = free space + * @param resolution : resolution of the grid. + * @return signed distance for each point in the grid to the occupancy border. + */ +Matrix signedDistanceFromOccupancy(const Eigen::Matrix& occupancyGrid, float resolution); + +} // namespace signed_distance_field +} // namespace grid_map \ No newline at end of file diff --git a/grid_map_sdf/include/grid_map_sdf/SignedDistanceField.hpp b/grid_map_sdf/include/grid_map_sdf/SignedDistanceField.hpp index f1105da55..cfcd8ef81 100644 --- a/grid_map_sdf/include/grid_map_sdf/SignedDistanceField.hpp +++ b/grid_map_sdf/include/grid_map_sdf/SignedDistanceField.hpp @@ -1,45 +1,141 @@ /* - * SignedDistanceField.hpp + * SignedDistanceField.h * - * Created on: Aug 16, 2017 - * Authors: Takahiro Miki, Peter Fankhauser - * Institute: ETH Zurich, ANYbotics + * Created on: Jul 10, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich */ #pragma once -#include +#include -#include -#include +#include -#include -#include +#include +#include + +#include "Gridmap3dLookup.hpp" namespace grid_map { -class SignedDistanceField -{ +/** + * This class creates a dense 3D signed distance field grid for a given elevation map. + * The 3D grid uses the same resolution as the 2D map. i.e. all voxels are of size (resolution x resolution x resolution). + * The size of the 3D grid is the same as the map in XY direction. The size in Z direction is specified in the constructor. + * + * During the creation of the class all values and derivatives are pre-computed in one go. This makes repeated lookups very cheap. + * Querying a point outside of the constructed grid will result in linear extrapolation. + * + * The distance value and derivatives (dx,dy,dz) per voxel are stored next to each other in memory to support fast lookup during + * interpolation, where we need all 4 values simultaneously. The entire dense grid is stored as a flat vector, with the indexing outsourced + * to the Gridmap3dLookup class. + */ +class SignedDistanceField { public: - SignedDistanceField(); - virtual ~SignedDistanceField(); + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + using Derivative3 = Eigen::Vector3d; + + /** + * Create a signed distance field and its derivative for an elevation layer in the grid map. + * + * @param gridMap : Input map to create the SDF for. + * @param elevationLayer : Name of the elevation layer. + * @param minHeight : Desired starting height of the 3D SDF grid. + * @param maxHeight : Desired ending height of the 3D SDF grid. (Will be rounded up to match the resolution) + */ + SignedDistanceField(const GridMap& gridMap, const std::string& elevationLayer, double minHeight, double maxHeight); + + /** + * Get the signed distance value at a 3D position. + * @param position : 3D position in the frame of the gridmap. + * @return signed distance to the elevation surface. + */ + double value(const Position3& position) const noexcept; + + /** + * Get the signed distance derivative at a 3D position. + * @param position : 3D position in the frame of the gridmap. + * @return derivative of the signed distance field. + */ + Derivative3 derivative(const Position3& position) const noexcept; + + /** + * Get both the signed distance value and derivative at a 3D position. + * @param position : 3D position in the frame of the gridmap. + * @return {value, derivative} of the signed distance field. + */ + std::pair valueAndDerivative(const Position3& position) const noexcept; + + size_t size() const noexcept; - void calculateSignedDistanceField(const GridMap& gridMap, const std::string& layer, const double heightClearance); - double getDistanceAt(const Position3& position) const; - Vector3 getDistanceGradientAt(const Position3& position) const; - double getInterpolatedDistanceAt(const Position3& position) const; - void convertToPointCloud(pcl::PointCloud& points) const; + const std::string& getFrameId() const noexcept; + + Time getTime() const noexcept; + + /** + * Calls a function on each point in the signed distance field. The points are processed in the order they are stored in memory. + * @param func : function taking the node position, signed distance value, and signed distance derivative. + * @param decimation : specifies how many points are returned. 1: all points, 2: every second point, etc. + */ + void filterPoints(std::function func, size_t decimation = 1) const; private: - Matrix getPlanarSignedDistanceField(Eigen::Matrix& data) const; - - double resolution_; - Size size_; - Position position_; - std::vector data_; - float zIndexStartHeight_; - float maxDistance_; - const float lowestHeight_; + /** + * Implementation of the signed distance field computation in this class. + * @param elevation + */ + void computeSignedDistance(const Matrix& elevation); + + /** + * Simultaneously compute the signed distance and derivative in x direction at a given height + * @param elevation [in] : elevation data + * @param currentLayer [out] : signed distance values + * @param dxTranspose [out] : derivative in x direction (the matrix is transposed) + * @param sdfTranspose [tmp] : temporary variable to reuse between calls (allocated on first use) + * @param tmp [tmp] : temporary variable (allocated on first use) + * @param tmpTranspose [tmp] : temporary variable (allocated on first use) + * @param height [in] : height the signed distance is created for. + * @param resolution [in] : resolution of the map. + * @param minHeight [in] : smallest height value in the elevation data. + * @param maxHeight [in] : largest height value in the elevation data. + */ + void computeLayerSdfandDeltaX(const Matrix& elevation, Matrix& currentLayer, Matrix& dxTranspose, Matrix& sdfTranspose, Matrix& tmp, + Matrix& tmpTranspose, float height, float resolution, float minHeight, float maxHeight) const; + + /** + * Add the computed signed distance values and derivatives at a particular height to the grid. + * Adds the layer to the back of data_ + * @param signedDistance : signed distance values. + * @param dxTranspose : x components of the derivative (matrix is transposed). + * @param dy : y components of the derivative. + * @param dz : z components of the derivative. + */ + void emplacebackLayerData(const Matrix& signedDistance, const Matrix& dxTranspose, const Matrix& dy, const Matrix& dz); + + //! Data structure to store together {signed distance value, derivative}. + using node_data_t = std::array; + + /** Helper function to extract the sdf value */ + static double distance(const node_data_t& nodeData) noexcept { return nodeData[0]; } + + /** Helper function to extract the sdf value as float */ + static float distanceFloat(const node_data_t& nodeData) noexcept { return nodeData[0]; } + + /** Helper function to extract the sdf derivative */ + static Derivative3 derivative(const node_data_t& nodeData) noexcept { return {nodeData[1], nodeData[2], nodeData[3]}; } + + //! Object encoding the 3D grid. + signed_distance_field::Gridmap3dLookup gridmap3DLookup_; + + //! Object encoding the signed distance value and derivative in the grid. + std::vector data_; + + //! Frame id of the grid map. + std::string frameId_; + + //! Timestamp of the grid map (nanoseconds). + Time timestamp_; }; -} /* namespace */ +} // namespace grid_map \ No newline at end of file diff --git a/grid_map_sdf/include/grid_map_sdf/Utils.hpp b/grid_map_sdf/include/grid_map_sdf/Utils.hpp new file mode 100644 index 000000000..32d03c452 --- /dev/null +++ b/grid_map_sdf/include/grid_map_sdf/Utils.hpp @@ -0,0 +1,21 @@ +/* + * Utils.h + * + * Created on: Jul 10, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#pragma once + +namespace grid_map { +namespace signed_distance_field { + +// Check existence of inf +static_assert(std::numeric_limits::has_infinity, "float does not support infinity"); + +//! Distance value that is considered infinite. +constexpr float INF = std::numeric_limits::infinity(); + +} // namespace signed_distance_field +} // namespace grid_map \ No newline at end of file diff --git a/grid_map_sdf/include/grid_map_sdf/distance_transform/COPYING b/grid_map_sdf/include/grid_map_sdf/distance_transform/COPYING deleted file mode 100755 index d511905c1..000000000 --- a/grid_map_sdf/include/grid_map_sdf/distance_transform/COPYING +++ /dev/null @@ -1,339 +0,0 @@ - GNU GENERAL PUBLIC LICENSE - Version 2, June 1991 - - Copyright (C) 1989, 1991 Free Software Foundation, Inc., - 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - Everyone is permitted to copy and distribute verbatim copies - of this license document, but changing it is not allowed. - - Preamble - - The licenses for most software are designed to take away your -freedom to share and change it. By contrast, the GNU General Public -License is intended to guarantee your freedom to share and change free -software--to make sure the software is free for all its users. This -General Public License applies to most of the Free Software -Foundation's software and to any other program whose authors commit to -using it. (Some other Free Software Foundation software is covered by -the GNU Lesser General Public License instead.) You can apply it to -your programs, too. - - When we speak of free software, we are referring to freedom, not -price. Our General Public Licenses are designed to make sure that you -have the freedom to distribute copies of free software (and charge for -this service if you wish), that you receive source code or can get it -if you want it, that you can change the software or use pieces of it -in new free programs; and that you know you can do these things. - - To protect your rights, we need to make restrictions that forbid -anyone to deny you these rights or to ask you to surrender the rights. -These restrictions translate to certain responsibilities for you if you -distribute copies of the software, or if you modify it. - - For example, if you distribute copies of such a program, whether -gratis or for a fee, you must give the recipients all the rights that -you have. You must make sure that they, too, receive or can get the -source code. And you must show them these terms so they know their -rights. - - We protect your rights with two steps: (1) copyright the software, and -(2) offer you this license which gives you legal permission to copy, -distribute and/or modify the software. - - Also, for each author's protection and ours, we want to make certain -that everyone understands that there is no warranty for this free -software. If the software is modified by someone else and passed on, we -want its recipients to know that what they have is not the original, so -that any problems introduced by others will not reflect on the original -authors' reputations. - - Finally, any free program is threatened constantly by software -patents. We wish to avoid the danger that redistributors of a free -program will individually obtain patent licenses, in effect making the -program proprietary. To prevent this, we have made it clear that any -patent must be licensed for everyone's free use or not licensed at all. - - The precise terms and conditions for copying, distribution and -modification follow. - - GNU GENERAL PUBLIC LICENSE - TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION - - 0. This License applies to any program or other work which contains -a notice placed by the copyright holder saying it may be distributed -under the terms of this General Public License. The "Program", below, -refers to any such program or work, and a "work based on the Program" -means either the Program or any derivative work under copyright law: -that is to say, a work containing the Program or a portion of it, -either verbatim or with modifications and/or translated into another -language. (Hereinafter, translation is included without limitation in -the term "modification".) Each licensee is addressed as "you". - -Activities other than copying, distribution and modification are not -covered by this License; they are outside its scope. The act of -running the Program is not restricted, and the output from the Program -is covered only if its contents constitute a work based on the -Program (independent of having been made by running the Program). -Whether that is true depends on what the Program does. - - 1. You may copy and distribute verbatim copies of the Program's -source code as you receive it, in any medium, provided that you -conspicuously and appropriately publish on each copy an appropriate -copyright notice and disclaimer of warranty; keep intact all the -notices that refer to this License and to the absence of any warranty; -and give any other recipients of the Program a copy of this License -along with the Program. - -You may charge a fee for the physical act of transferring a copy, and -you may at your option offer warranty protection in exchange for a fee. - - 2. You may modify your copy or copies of the Program or any portion -of it, thus forming a work based on the Program, and copy and -distribute such modifications or work under the terms of Section 1 -above, provided that you also meet all of these conditions: - - a) You must cause the modified files to carry prominent notices - stating that you changed the files and the date of any change. - - b) You must cause any work that you distribute or publish, that in - whole or in part contains or is derived from the Program or any - part thereof, to be licensed as a whole at no charge to all third - parties under the terms of this License. - - c) If the modified program normally reads commands interactively - when run, you must cause it, when started running for such - interactive use in the most ordinary way, to print or display an - announcement including an appropriate copyright notice and a - notice that there is no warranty (or else, saying that you provide - a warranty) and that users may redistribute the program under - these conditions, and telling the user how to view a copy of this - License. (Exception: if the Program itself is interactive but - does not normally print such an announcement, your work based on - the Program is not required to print an announcement.) - -These requirements apply to the modified work as a whole. If -identifiable sections of that work are not derived from the Program, -and can be reasonably considered independent and separate works in -themselves, then this License, and its terms, do not apply to those -sections when you distribute them as separate works. But when you -distribute the same sections as part of a whole which is a work based -on the Program, the distribution of the whole must be on the terms of -this License, whose permissions for other licensees extend to the -entire whole, and thus to each and every part regardless of who wrote it. - -Thus, it is not the intent of this section to claim rights or contest -your rights to work written entirely by you; rather, the intent is to -exercise the right to control the distribution of derivative or -collective works based on the Program. - -In addition, mere aggregation of another work not based on the Program -with the Program (or with a work based on the Program) on a volume of -a storage or distribution medium does not bring the other work under -the scope of this License. - - 3. You may copy and distribute the Program (or a work based on it, -under Section 2) in object code or executable form under the terms of -Sections 1 and 2 above provided that you also do one of the following: - - a) Accompany it with the complete corresponding machine-readable - source code, which must be distributed under the terms of Sections - 1 and 2 above on a medium customarily used for software interchange; or, - - b) Accompany it with a written offer, valid for at least three - years, to give any third party, for a charge no more than your - cost of physically performing source distribution, a complete - machine-readable copy of the corresponding source code, to be - distributed under the terms of Sections 1 and 2 above on a medium - customarily used for software interchange; or, - - c) Accompany it with the information you received as to the offer - to distribute corresponding source code. (This alternative is - allowed only for noncommercial distribution and only if you - received the program in object code or executable form with such - an offer, in accord with Subsection b above.) - -The source code for a work means the preferred form of the work for -making modifications to it. For an executable work, complete source -code means all the source code for all modules it contains, plus any -associated interface definition files, plus the scripts used to -control compilation and installation of the executable. However, as a -special exception, the source code distributed need not include -anything that is normally distributed (in either source or binary -form) with the major components (compiler, kernel, and so on) of the -operating system on which the executable runs, unless that component -itself accompanies the executable. - -If distribution of executable or object code is made by offering -access to copy from a designated place, then offering equivalent -access to copy the source code from the same place counts as -distribution of the source code, even though third parties are not -compelled to copy the source along with the object code. - - 4. You may not copy, modify, sublicense, or distribute the Program -except as expressly provided under this License. Any attempt -otherwise to copy, modify, sublicense or distribute the Program is -void, and will automatically terminate your rights under this License. -However, parties who have received copies, or rights, from you under -this License will not have their licenses terminated so long as such -parties remain in full compliance. - - 5. You are not required to accept this License, since you have not -signed it. However, nothing else grants you permission to modify or -distribute the Program or its derivative works. These actions are -prohibited by law if you do not accept this License. Therefore, by -modifying or distributing the Program (or any work based on the -Program), you indicate your acceptance of this License to do so, and -all its terms and conditions for copying, distributing or modifying -the Program or works based on it. - - 6. Each time you redistribute the Program (or any work based on the -Program), the recipient automatically receives a license from the -original licensor to copy, distribute or modify the Program subject to -these terms and conditions. You may not impose any further -restrictions on the recipients' exercise of the rights granted herein. -You are not responsible for enforcing compliance by third parties to -this License. - - 7. If, as a consequence of a court judgment or allegation of patent -infringement or for any other reason (not limited to patent issues), -conditions are imposed on you (whether by court order, agreement or -otherwise) that contradict the conditions of this License, they do not -excuse you from the conditions of this License. If you cannot -distribute so as to satisfy simultaneously your obligations under this -License and any other pertinent obligations, then as a consequence you -may not distribute the Program at all. For example, if a patent -license would not permit royalty-free redistribution of the Program by -all those who receive copies directly or indirectly through you, then -the only way you could satisfy both it and this License would be to -refrain entirely from distribution of the Program. - -If any portion of this section is held invalid or unenforceable under -any particular circumstance, the balance of the section is intended to -apply and the section as a whole is intended to apply in other -circumstances. - -It is not the purpose of this section to induce you to infringe any -patents or other property right claims or to contest validity of any -such claims; this section has the sole purpose of protecting the -integrity of the free software distribution system, which is -implemented by public license practices. Many people have made -generous contributions to the wide range of software distributed -through that system in reliance on consistent application of that -system; it is up to the author/donor to decide if he or she is willing -to distribute software through any other system and a licensee cannot -impose that choice. - -This section is intended to make thoroughly clear what is believed to -be a consequence of the rest of this License. - - 8. If the distribution and/or use of the Program is restricted in -certain countries either by patents or by copyrighted interfaces, the -original copyright holder who places the Program under this License -may add an explicit geographical distribution limitation excluding -those countries, so that distribution is permitted only in or among -countries not thus excluded. In such case, this License incorporates -the limitation as if written in the body of this License. - - 9. The Free Software Foundation may publish revised and/or new versions -of the General Public License from time to time. Such new versions will -be similar in spirit to the present version, but may differ in detail to -address new problems or concerns. - -Each version is given a distinguishing version number. If the Program -specifies a version number of this License which applies to it and "any -later version", you have the option of following the terms and conditions -either of that version or of any later version published by the Free -Software Foundation. If the Program does not specify a version number of -this License, you may choose any version ever published by the Free Software -Foundation. - - 10. If you wish to incorporate parts of the Program into other free -programs whose distribution conditions are different, write to the author -to ask for permission. For software which is copyrighted by the Free -Software Foundation, write to the Free Software Foundation; we sometimes -make exceptions for this. Our decision will be guided by the two goals -of preserving the free status of all derivatives of our free software and -of promoting the sharing and reuse of software generally. - - NO WARRANTY - - 11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY -FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN -OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES -PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED -OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF -MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS -TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE -PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, -REPAIR OR CORRECTION. - - 12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING -WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR -REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, -INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING -OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED -TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY -YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER -PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE -POSSIBILITY OF SUCH DAMAGES. - - END OF TERMS AND CONDITIONS - - How to Apply These Terms to Your New Programs - - If you develop a new program, and you want it to be of the greatest -possible use to the public, the best way to achieve this is to make it -free software which everyone can redistribute and change under these terms. - - To do so, attach the following notices to the program. It is safest -to attach them to the start of each source file to most effectively -convey the exclusion of warranty; and each file should have at least -the "copyright" line and a pointer to where the full notice is found. - - - Copyright (C) - - This program is free software; you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation; either version 2 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License along - with this program; if not, write to the Free Software Foundation, Inc., - 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. - -Also add information on how to contact you by electronic and paper mail. - -If the program is interactive, make it output a short notice like this -when it starts in an interactive mode: - - Gnomovision version 69, Copyright (C) year name of author - Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'. - This is free software, and you are welcome to redistribute it - under certain conditions; type `show c' for details. - -The hypothetical commands `show w' and `show c' should show the appropriate -parts of the General Public License. Of course, the commands you use may -be called something other than `show w' and `show c'; they could even be -mouse-clicks or menu items--whatever suits your program. - -You should also get your employer (if you work as a programmer) or your -school, if any, to sign a "copyright disclaimer" for the program, if -necessary. Here is a sample; alter the names: - - Yoyodyne, Inc., hereby disclaims all copyright interest in the program - `Gnomovision' (which makes passes at compilers) written by James Hacker. - - , 1 April 1989 - Ty Coon, President of Vice - -This General Public License does not permit incorporating your program into -proprietary programs. If your program is a subroutine library, you may -consider it more useful to permit linking proprietary applications with the -library. If this is what you want to do, use the GNU Lesser General -Public License instead of this License. diff --git a/grid_map_sdf/include/grid_map_sdf/distance_transform/dt.h b/grid_map_sdf/include/grid_map_sdf/distance_transform/dt.h deleted file mode 100755 index 7a00eab49..000000000 --- a/grid_map_sdf/include/grid_map_sdf/distance_transform/dt.h +++ /dev/null @@ -1,117 +0,0 @@ -/* -Copyright (C) 2006 Pedro Felzenszwalb - -This program is free software; you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation; either version 2 of the License, or -(at your option) any later version. - -This program is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with this program; if not, write to the Free Software -Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -/* distance transform */ - -#pragma once - -#include - -#include "image.h" -#include "imconv.h" - -namespace distance_transform -{ - const double INF = 1E20; - - /* dt of 1d function using squared distance */ - static float *dt(float *f, int n) { - float *d = new float[n]; - int *v = new int[n]; - float *z = new float[n+1]; - int k = 0; - v[0] = 0; - z[0] = -INF; - z[1] = +INF; - for (int q = 1; q <= n-1; q++) { - float s = ((f[q]+square(q))-(f[v[k]]+square(v[k])))/(2*q-2*v[k]); - while (s <= z[k]) { - k--; - s = ((f[q]+square(q))-(f[v[k]]+square(v[k])))/(2*q-2*v[k]); - } - k++; - v[k] = q; - z[k] = s; - z[k+1] = +INF; - } - - k = 0; - for (int q = 0; q <= n-1; q++) { - while (z[k+1] < q) - k++; - d[q] = square(q-v[k]) + f[v[k]]; - } - - delete [] v; - delete [] z; - return d; - } - - /* dt of 2d function using squared distance */ - static void dt(image *im) { - int width = im->width(); - int height = im->height(); - float *f = new float[std::max(width,height)]; - - // transform along columns - for (int x = 0; x < width; x++) { - for (int y = 0; y < height; y++) { - f[y] = imRef(im, x, y); - } - float *d = dt(f, height); - for (int y = 0; y < height; y++) { - imRef(im, x, y) = d[y]; - } - delete [] d; - } - - // transform along rows - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - f[x] = imRef(im, x, y); - } - float *d = dt(f, width); - for (int x = 0; x < width; x++) { - imRef(im, x, y) = d[x]; - } - delete [] d; - } - - delete [] f; - } - - /* dt of binary image using squared distance */ - static image *dt(image *im, uchar on = 1) { - int width = im->width(); - int height = im->height(); - - image *out = new image(width, height, false); - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - if (imRef(im, x, y) == on) - imRef(out, x, y) = 0; - else - imRef(out, x, y) = INF; - } - } - - dt(out); - return out; - } - -} // namespace diff --git a/grid_map_sdf/include/grid_map_sdf/distance_transform/image.h b/grid_map_sdf/include/grid_map_sdf/distance_transform/image.h deleted file mode 100755 index 47cada090..000000000 --- a/grid_map_sdf/include/grid_map_sdf/distance_transform/image.h +++ /dev/null @@ -1,101 +0,0 @@ -/* -Copyright (C) 2006 Pedro Felzenszwalb - -This program is free software; you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation; either version 2 of the License, or -(at your option) any later version. - -This program is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with this program; if not, write to the Free Software -Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -/* a simple image class */ - -#pragma once - -#include - -namespace distance_transform -{ - - template - class image { - public: - /* create an image */ - image(const int width, const int height, const bool init = true); - - /* delete an image */ - ~image(); - - /* init an image */ - void init(const T &val); - - /* copy an image */ - image *copy() const; - - /* get the width of an image. */ - int width() const { return w; } - - /* get the height of an image. */ - int height() const { return h; } - - /* image data. */ - T *data; - - /* row pointers. */ - T **access; - - private: - int w, h; - }; - - /* use imRef to access image data. */ -#define imRef(im, x, y) (im->access[y][x]) - - /* use imPtr to get pointer to image data. */ -#define imPtr(im, x, y) &(im->access[y][x]) - - template - image::image(const int width, const int height, const bool init) { - w = width; - h = height; - data = new T[w * h]; // allocate space for image data - access = new T*[h]; // allocate space for row pointers - - // initialize row pointers - for (int i = 0; i < h; i++) - access[i] = data + (i * w); - - if (init) - memset(data, 0, w * h * sizeof(T)); - } - - template - image::~image() { - delete [] data; - delete [] access; - } - - template - void image::init(const T &val) { - T *ptr = imPtr(this, 0, 0); - T *end = imPtr(this, w-1, h-1); - while (ptr <= end) - *ptr++ = val; - } - - template - image *image::copy() const { - image *im = new image(w, h, false); - memcpy(im->data, data, w * h * sizeof(T)); - return im; - } - -} // namespace diff --git a/grid_map_sdf/include/grid_map_sdf/distance_transform/imconv.h b/grid_map_sdf/include/grid_map_sdf/distance_transform/imconv.h deleted file mode 100755 index b4f27ff36..000000000 --- a/grid_map_sdf/include/grid_map_sdf/distance_transform/imconv.h +++ /dev/null @@ -1,179 +0,0 @@ -/* -Copyright (C) 2006 Pedro Felzenszwalb - -This program is free software; you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation; either version 2 of the License, or -(at your option) any later version. - -This program is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with this program; if not, write to the Free Software -Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -/* image conversion */ - -#pragma once - -#include - -#include "image.h" -#include "imutil.h" -#include "misc.h" - -namespace distance_transform -{ - const double RED_WEIGHT = 0.299; - const double GREEN_WEIGHT = 0.584; - const double BLUE_WEIGHT = 0.114; - - static image *imageRGBtoGRAY(image *input) { - int width = input->width(); - int height = input->height(); - image *output = new image(width, height, false); - - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - imRef(output, x, y) = (uchar) - (imRef(input, x, y).r * RED_WEIGHT + - imRef(input, x, y).g * GREEN_WEIGHT + - imRef(input, x, y).b * BLUE_WEIGHT); - } - } - return output; - } - - static image *imageGRAYtoRGB(image *input) { - int width = input->width(); - int height = input->height(); - image *output = new image(width, height, false); - - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - imRef(output, x, y).r = imRef(input, x, y); - imRef(output, x, y).g = imRef(input, x, y); - imRef(output, x, y).b = imRef(input, x, y); - } - } - return output; - } - - static image *imageUCHARtoFLOAT(image *input) { - int width = input->width(); - int height = input->height(); - image *output = new image(width, height, false); - - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - imRef(output, x, y) = imRef(input, x, y); - } - } - return output; - } - - static image *imageINTtoFLOAT(image *input) { - int width = input->width(); - int height = input->height(); - image *output = new image(width, height, false); - - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - imRef(output, x, y) = imRef(input, x, y); - } - } - return output; - } - - static image *imageFLOATtoUCHAR(image *input, - float min, float max) { - int width = input->width(); - int height = input->height(); - image *output = new image(width, height, false); - - if (max == min) - return output; - - float scale = UCHAR_MAX / (max - min); - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - uchar val = (uchar)((imRef(input, x, y) - min) * scale); - imRef(output, x, y) = bound(val, (uchar)0, (uchar)UCHAR_MAX); - } - } - return output; - } - - static image *imageFLOATtoUCHAR(image *input) { - float min, max; - min_max(input, &min, &max); - return imageFLOATtoUCHAR(input, min, max); - } - - static image *imageUCHARtoLONG(image *input) { - int width = input->width(); - int height = input->height(); - image *output = new image(width, height, false); - - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - imRef(output, x, y) = imRef(input, x, y); - } - } - return output; - } - - static image *imageLONGtoUCHAR(image *input, long min, long max) { - int width = input->width(); - int height = input->height(); - image *output = new image(width, height, false); - - if (max == min) - return output; - - float scale = UCHAR_MAX / (float)(max - min); - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - uchar val = (uchar)((imRef(input, x, y) - min) * scale); - imRef(output, x, y) = bound(val, (uchar)0, (uchar)UCHAR_MAX); - } - } - return output; - } - - static image *imageLONGtoUCHAR(image *input) { - long min, max; - min_max(input, &min, &max); - return imageLONGtoUCHAR(input, min, max); - } - - static image *imageSHORTtoUCHAR(image *input, - short min, short max) { - int width = input->width(); - int height = input->height(); - image *output = new image(width, height, false); - - if (max == min) - return output; - - float scale = UCHAR_MAX / (float)(max - min); - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - uchar val = (uchar)((imRef(input, x, y) - min) * scale); - imRef(output, x, y) = bound(val, (uchar)0, (uchar)UCHAR_MAX); - } - } - return output; - } - - static image *imageSHORTtoUCHAR(image *input) { - short min, max; - min_max(input, &min, &max); - return imageSHORTtoUCHAR(input, min, max); - } - -} // namespace diff --git a/grid_map_sdf/include/grid_map_sdf/distance_transform/imutil.h b/grid_map_sdf/include/grid_map_sdf/distance_transform/imutil.h deleted file mode 100755 index ad09d1f8e..000000000 --- a/grid_map_sdf/include/grid_map_sdf/distance_transform/imutil.h +++ /dev/null @@ -1,67 +0,0 @@ -/* -Copyright (C) 2006 Pedro Felzenszwalb - -This program is free software; you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation; either version 2 of the License, or -(at your option) any later version. - -This program is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with this program; if not, write to the Free Software -Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -/* some image utilities */ - -#pragma once - -#include "image.h" -#include "misc.h" - -namespace distance_transform -{ - - /* compute minimum and maximum value in an image */ - template - void min_max(image *im, T *ret_min, T *ret_max) { - int width = im->width(); - int height = im->height(); - - T min = imRef(im, 0, 0); - T max = imRef(im, 0, 0); - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - T val = imRef(im, x, y); - if (min > val) - min = val; - if (max < val) - max = val; - } - } - - *ret_min = min; - *ret_max = max; - } - - /* threshold image */ - template - image *threshold(image *src, int t) { - int width = src->width(); - int height = src->height(); - image *dst = new image(width, height); - - for (int y = 0; y < height; y++) { - for (int x = 0; x < width; x++) { - imRef(dst, x, y) = (imRef(src, x, y) >= t); - } - } - - return dst; - } - -} // namespace diff --git a/grid_map_sdf/include/grid_map_sdf/distance_transform/misc.h b/grid_map_sdf/include/grid_map_sdf/distance_transform/misc.h deleted file mode 100755 index a9514d1f4..000000000 --- a/grid_map_sdf/include/grid_map_sdf/distance_transform/misc.h +++ /dev/null @@ -1,62 +0,0 @@ -/* -Copyright (C) 2006 Pedro Felzenszwalb - -This program is free software; you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation; either version 2 of the License, or -(at your option) any later version. - -This program is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with this program; if not, write to the Free Software -Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -/* random stuff */ - -#pragma once - -#include - -namespace distance_transform -{ - typedef unsigned char uchar; - - typedef struct { uchar r, g, b; } rgb; - - inline bool operator==(const rgb &a, const rgb &b) { - return ((a.r == b.r) && (a.g == b.g) && (a.b == b.b)); - } - - template - inline T abs(const T &x) { return (x > 0 ? x : -x); }; - - template - inline int sign(const T &x) { return (x >= 0 ? 1 : -1); }; - - template - inline T square(const T &x) { return x*x; }; - - template - inline T bound(const T &x, const T &min, const T &max) { - return (x < min ? min : (x > max ? max : x)); - } - - template - inline bool check_bound(const T &x, const T&min, const T &max) { - return ((x < min) || (x > max)); - } - - inline int vlib_round(float x) { return (int)(x + 0.5F); } - - inline int vlib_round(double x) { return (int)(x + 0.5); } - - inline double gaussian(double val, double sigma) { - return exp(-square(val/sigma)/2)/(sqrt(2*M_PI)*sigma); - } - -} // namespace diff --git a/grid_map_sdf/include/grid_map_sdf/distance_transform/pnmfile.h b/grid_map_sdf/include/grid_map_sdf/distance_transform/pnmfile.h deleted file mode 100755 index 282843284..000000000 --- a/grid_map_sdf/include/grid_map_sdf/distance_transform/pnmfile.h +++ /dev/null @@ -1,214 +0,0 @@ -/* -Copyright (C) 2006 Pedro Felzenszwalb - -This program is free software; you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation; either version 2 of the License, or -(at your option) any later version. - -This program is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with this program; if not, write to the Free Software -Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -/* basic image I/O */ - -#pragma once - -#include -#include -#include -#include - -#include "image.h" -#include "misc.h" - -namespace distance_transform -{ - - const short BUF_SIZE = 256; - - class pnm_error { }; - - static void read_packed(unsigned char *data, int size, std::ifstream &f) { - unsigned char c = 0; - - int bitshift = -1; - for (int pos = 0; pos < size; pos++) { - if (bitshift == -1) { - c = f.get(); - bitshift = 7; - } - data[pos] = (c >> bitshift) & 1; - bitshift--; - } - } - - static void write_packed(unsigned char *data, int size, std::ofstream &f) { - unsigned char c = 0; - - int bitshift = 7; - for (int pos = 0; pos < size; pos++) { - c = c | (data[pos] << bitshift); - bitshift--; - if ((bitshift == -1) || (pos == size-1)) { - f.put(c); - bitshift = 7; - c = 0; - } - } - } - - /* read PNM field, skipping comments */ - static void pnm_read(std::ifstream &file, char *buf) { - char doc[BUF_SIZE]; - char c; - - file >> c; - while (c == '#') { - file.getline(doc, BUF_SIZE); - file >> c; - } - file.putback(c); - - file.width(BUF_SIZE); - file >> buf; - file.ignore(); - } - - static image *loadPBM(const char *name) { - char buf[BUF_SIZE]; - - /* read header */ - std::ifstream file(name, std::ios::in | std::ios::binary); - pnm_read(file, buf); - if (strncmp(buf, "P4", 2)) - throw pnm_error(); - - pnm_read(file, buf); - int width = atoi(buf); - pnm_read(file, buf); - int height = atoi(buf); - - /* read data */ - image *im = new image(width, height); - for (int i = 0; i < height; i++) - read_packed(imPtr(im, 0, i), width, file); - - return im; - } - - static void savePBM(image *im, const char *name) { - int width = im->width(); - int height = im->height(); - std::ofstream file(name, std::ios::out | std::ios::binary); - - file << "P4\n" << width << " " << height << "\n"; - for (int i = 0; i < height; i++) - write_packed(imPtr(im, 0, i), width, file); - } - - static image *loadPGM(const char *name) { - char buf[BUF_SIZE]; - - /* read header */ - std::ifstream file(name, std::ios::in | std::ios::binary); - pnm_read(file, buf); - if (strncmp(buf, "P5", 2)) - throw pnm_error(); - - pnm_read(file, buf); - int width = atoi(buf); - pnm_read(file, buf); - int height = atoi(buf); - - pnm_read(file, buf); - if (atoi(buf) > UCHAR_MAX) - throw pnm_error(); - - /* read data */ - image *im = new image(width, height); - file.read((char *)imPtr(im, 0, 0), width * height * sizeof(uchar)); - - return im; - } - - static void savePGM(image *im, const char *name) { - int width = im->width(); - int height = im->height(); - std::ofstream file(name, std::ios::out | std::ios::binary); - - file << "P5\n" << width << " " << height << "\n" << UCHAR_MAX << "\n"; - file.write((char *)imPtr(im, 0, 0), width * height * sizeof(uchar)); - } - - static image *loadPPM(const char *name) { - char buf[BUF_SIZE], doc[BUF_SIZE]; - - /* read header */ - std::ifstream file(name, std::ios::in | std::ios::binary); - pnm_read(file, buf); - if (strncmp(buf, "P6", 2)) - throw pnm_error(); - - pnm_read(file, buf); - int width = atoi(buf); - pnm_read(file, buf); - int height = atoi(buf); - - pnm_read(file, buf); - if (atoi(buf) > UCHAR_MAX) - throw pnm_error(); - - /* read data */ - image *im = new image(width, height); - file.read((char *)imPtr(im, 0, 0), width * height * sizeof(rgb)); - - return im; - } - - static void savePPM(image *im, const char *name) { - int width = im->width(); - int height = im->height(); - std::ofstream file(name, std::ios::out | std::ios::binary); - - file << "P6\n" << width << " " << height << "\n" << UCHAR_MAX << "\n"; - file.write((char *)imPtr(im, 0, 0), width * height * sizeof(rgb)); - } - - template - void load_image(image **im, const char *name) { - char buf[BUF_SIZE]; - - /* read header */ - std::ifstream file(name, std::ios::in | std::ios::binary); - pnm_read(file, buf); - if (strncmp(buf, "VLIB", 9)) - throw pnm_error(); - - pnm_read(file, buf); - int width = atoi(buf); - pnm_read(file, buf); - int height = atoi(buf); - - /* read data */ - *im = new image(width, height); - file.read((char *)imPtr((*im), 0, 0), width * height * sizeof(T)); - } - - template - void save_image(image *im, const char *name) { - int width = im->width(); - int height = im->height(); - std::ofstream file(name, std::ios::out | std::ios::binary); - - file << "VLIB\n" << width << " " << height << "\n"; - file.write((char *)imPtr(im, 0, 0), width * height * sizeof(T)); - } - -} // namespace diff --git a/grid_map_sdf/package.xml b/grid_map_sdf/package.xml index 778413346..16be082ba 100644 --- a/grid_map_sdf/package.xml +++ b/grid_map_sdf/package.xml @@ -1,7 +1,7 @@ grid_map_sdf - 1.6.4 + 1.7.5 Generates signed distance fields from grid maps. Maximilian Wulf Yoshua Nava @@ -13,7 +13,6 @@ catkin grid_map_core - pcl_ros gtest diff --git a/grid_map_sdf/src/SignedDistance2d.cpp b/grid_map_sdf/src/SignedDistance2d.cpp new file mode 100644 index 000000000..c3ee519f5 --- /dev/null +++ b/grid_map_sdf/src/SignedDistance2d.cpp @@ -0,0 +1,290 @@ +/* +* SignedDistance2d.cpp +* +* Created on: Jul 10, 2020 +* Author: Ruben Grandia +* Institute: ETH Zurich +*/ + +#include "grid_map_sdf/SignedDistance2d.hpp" + +#include "grid_map_sdf/PixelBorderDistance.hpp" + +namespace grid_map { +namespace signed_distance_field { + +namespace internal { +struct DistanceLowerBound { + float v; // origin of bounding function + float f; // functional offset at the origin + float z_lhs; // lhs of interval where this bound holds + float z_rhs; // rhs of interval where this lower bound holds +}; + +/** +* 1D Euclidean Distance Transform based on: http://cs.brown.edu/people/pfelzens/dt/ +* Adapted to work on Eigen objects directly +* Optimized computation of s. +* Some optimization to not keep track of bounds that lie fully outside the grid. +*/ +std::vector::iterator fillLowerBounds(const Eigen::Ref& squareDistance1d, + std::vector& lowerBounds, Eigen::Index start) { + const auto n = squareDistance1d.size(); + const auto nFloat = static_cast(n); + const auto startFloat = static_cast(start); + + // Initialize + auto rhsBoundIt = lowerBounds.begin(); + *rhsBoundIt = DistanceLowerBound{startFloat, squareDistance1d[start], -INF, INF}; + auto firstBoundIt = lowerBounds.begin(); + + // Compute bounds to the right of minimum + float qFloat = rhsBoundIt->v + 1.0F; + for (Eigen::Index q = start + 1; q < n; ++q) { + // Storing this by value gives better performance (removed indirection?) + const float fq = squareDistance1d[q]; + + float s = equidistancePoint(qFloat, fq, rhsBoundIt->v, rhsBoundIt->f); + if (s < nFloat) { // Can ignore the lower bound derived from this point if it is only active outsize of [start, n] + // Search backwards in bounds until s is within [z_lhs, z_rhs] + while (s < rhsBoundIt->z_lhs) { + --rhsBoundIt; + s = equidistancePoint(qFloat, fq, rhsBoundIt->v, rhsBoundIt->f); + } + if (s > startFloat) { // Intersection is within [start, n]. Adjust current lowerbound and insert the new one after + rhsBoundIt->z_rhs = s; // Update the bound that comes before + ++rhsBoundIt; // insert new bound after. + *rhsBoundIt = DistanceLowerBound{qFloat, fq, s, INF}; // Valid from s till infinity + } else { // Intersection is outside [0, n]. This means that the new bound dominates all previous bounds + *rhsBoundIt = DistanceLowerBound{qFloat, fq, -INF, INF}; + firstBoundIt = rhsBoundIt; // No need to keep other bounds, so update the first bound iterator to this one. + } + } + + // Increment to follow loop counter as float + qFloat += 1.0F; + } + + return firstBoundIt; +} + +void extractSquareDistances(Eigen::Ref squareDistance1d, std::vector::const_iterator lowerBoundIt, + Eigen::Index start) { + const auto n = squareDistance1d.size(); + + // Store active bound by value to remove indirection + auto lastz = lowerBoundIt->z_rhs; + + auto qFloat = static_cast(start); + for (Eigen::Index q = start; q < n; ++q) { + if (squareDistance1d[q] > 0.0F) { // Observe that if squareDistance1d[q] == 0.0, this is already the minimum and it will stay 0.0 + // Find the new active lower bound if q no longer belongs to current interval + if (qFloat > lastz) { + do { + ++lowerBoundIt; + } while (lowerBoundIt->z_rhs < qFloat); + lastz = lowerBoundIt->z_rhs; + } + + squareDistance1d[q] = squarePixelBorderDistance(qFloat, lowerBoundIt->v, lowerBoundIt->f); + } + + qFloat += 1.0F; + } +} + +/** +* Same as extractSquareDistances, but takes the sqrt as a final step. +* Because several cells will have a value of 0.0 (obstacle / free space label), we can skip the sqrt computation for those. +*/ +void extractDistances(Eigen::Ref squareDistance1d, + std::vector::const_iterator lowerBoundIt, Eigen::Index start) { + const auto n = squareDistance1d.size(); + + // Store active bound by value to remove indirection + auto lastz = lowerBoundIt->z_rhs; + + auto qFloat = static_cast(start); + for (Eigen::Index q = start; q < n; ++q) { + if (squareDistance1d[q] > 0.0F) { // Observe that if squareDistance1d[q] == 0.0, this is already the minimum and it will stay 0.0 + // Find the new active lower bound if q no longer belongs to current interval + if (qFloat > lastz) { + do { + ++lowerBoundIt; + } while (lowerBoundIt->z_rhs < qFloat); + lastz = lowerBoundIt->z_rhs; + } + + squareDistance1d[q] = std::sqrt(squarePixelBorderDistance(qFloat, lowerBoundIt->v, lowerBoundIt->f)); + } + + qFloat += 1.0F; + } +} + +/** +* Find the location of the last zero value from the front +*/ +Eigen::Index lastZeroFromFront(const Eigen::Ref& squareDistance1d) { + const auto n = squareDistance1d.size(); + + for (Eigen::Index q = 0; q < n; ++q) { + if (squareDistance1d[q] > 0.0F) { + if (q > 0) { + return q - 1; + } else { + return 0; + } + } + } + return n; +} + +inline void squaredDistanceTransform_1d_inplace(Eigen::Ref squareDistance1d, + std::vector& lowerBounds) { + auto start = lastZeroFromFront(squareDistance1d); + + // Only need to process line if there are nonzero elements. Also the first zeros stay untouched. + if (start < squareDistance1d.size()) { + auto startIt = fillLowerBounds(squareDistance1d, lowerBounds, start); + extractSquareDistances(squareDistance1d, startIt, start); + } +} + +/** +* Same as above, but takes sqrt as final step (within the same loop) +* @param squareDistance1d : input as squared distance, output is the distance after sqrt. +* @param lowerBounds : work vector +*/ +inline void distanceTransform_1d_inplace(Eigen::Ref squareDistance1d, std::vector& lowerBounds) { + auto start = lastZeroFromFront(squareDistance1d); + + // Only need to process line if there are nonzero elements. Also the first zeros stay untouched. + if (start < squareDistance1d.size()) { + auto startIt = fillLowerBounds(squareDistance1d, lowerBounds, start); + extractDistances(squareDistance1d, startIt, start); + } +} + +void computePixelDistance2dTranspose(Matrix& input, Matrix& distanceTranspose) { + const auto n = input.rows(); + const auto m = input.cols(); + + // Allocate a buffer big enough for processing both rowise and columnwise + std::vector lowerBounds(std::max(n, m)); + + // Process columns + for (Eigen::Index i = 0; i < m; ++i) { + squaredDistanceTransform_1d_inplace(input.col(i), lowerBounds); + } + + // Process rows (= columns after transpose). + distanceTranspose = input.transpose(); + for (Eigen::Index i = 0; i < n; ++i) { + // Fuses square distance algorithm and taking sqrt. + distanceTransform_1d_inplace(distanceTranspose.col(i), lowerBounds); + } +} + +// Initialize with square distance in height direction in pixel units if above the surface +void initializeObstacleDistance(const Matrix& elevationMap, Matrix& result, float height, float resolution) { + /* Vectorized implementation of: + * if (height > elevation) { + * const auto diff = (height - elevation) / resolution; + * return diff * diff; + * } else { + * return 0.0F; + * } + */ + result = ((1.0F / resolution) * (height - elevationMap.array()).cwiseMax(0.0F)).square(); +} + +// Initialize with square distance in height direction in pixel units if below the surface +void initializeObstacleFreeDistance(const Matrix& elevationMap, Matrix& result, float height, float resolution) { + /* Vectorized implementation of: + * if (height < elevation) { + * const auto diff = (height - elevation) / resolution; + * return diff * diff; + * } else { + * return 0.0F; + * } + */ + result = ((1.0F / resolution) * (height - elevationMap.array()).cwiseMin(0.0F)).square(); +} + +void pixelDistanceToFreeSpaceTranspose(const Matrix& elevationMap, Matrix& sdfObstacleFree, Matrix& tmp, float height, float resolution) { + internal::initializeObstacleFreeDistance(elevationMap, tmp, height, resolution); + internal::computePixelDistance2dTranspose(tmp, sdfObstacleFree); +} + +void pixelDistanceToObstacleTranspose(const Matrix& elevationMap, Matrix& sdfObstacleTranspose, Matrix& tmp, float height, + float resolution) { + internal::initializeObstacleDistance(elevationMap, tmp, height, resolution); + internal::computePixelDistance2dTranspose(tmp, sdfObstacleTranspose); +} + +Matrix signedDistanceFromOccupancyTranspose(const Eigen::Matrix& occupancyGrid, float resolution) { + // Compute pixel distance to obstacles + Matrix sdfObstacle; + Matrix init = occupancyGrid.unaryExpr([=](bool val) { return (val) ? 0.0F : INF; }); + internal::computePixelDistance2dTranspose(init, sdfObstacle); + + // Compute pixel distance to obstacle free space + Matrix sdfObstacleFree; + init = occupancyGrid.unaryExpr([=](bool val) { return (val) ? INF : 0.0F; }); + internal::computePixelDistance2dTranspose(init, sdfObstacleFree); + + return resolution * (sdfObstacle - sdfObstacleFree); +} + +} // namespace internal + +void signedDistanceAtHeightTranspose(const Matrix& elevationMap, Matrix& sdfTranspose, Matrix& tmp, Matrix& tmpTranspose, float height, + float resolution, float minHeight, float maxHeight) { + const bool allPixelsAreObstacles = height < minHeight; + const bool allPixelsAreFreeSpace = height > maxHeight; + + if (allPixelsAreObstacles) { + internal::pixelDistanceToFreeSpaceTranspose(elevationMap, sdfTranspose, tmp, height, resolution); + + sdfTranspose *= -resolution; + } else if (allPixelsAreFreeSpace) { + internal::pixelDistanceToObstacleTranspose(elevationMap, sdfTranspose, tmp, height, resolution); + + sdfTranspose *= resolution; + } else { // This layer contains a mix of obstacles and free space + internal::pixelDistanceToObstacleTranspose(elevationMap, sdfTranspose, tmp, height, resolution); + internal::pixelDistanceToFreeSpaceTranspose(elevationMap, tmpTranspose, tmp, height, resolution); + + sdfTranspose = resolution * (sdfTranspose - tmpTranspose); + } +} + +Matrix signedDistanceAtHeight(const Matrix& elevationMap, float height, float resolution, float minHeight, float maxHeight) { + Matrix sdfTranspose; + Matrix tmp; + Matrix tmpTranspose; + + signedDistanceAtHeightTranspose(elevationMap, sdfTranspose, tmp, tmpTranspose, height, resolution, minHeight, maxHeight); + return sdfTranspose.transpose(); +} + +Matrix signedDistanceFromOccupancy(const Eigen::Matrix& occupancyGrid, float resolution) { + auto obstacleCount = occupancyGrid.count(); + bool hasObstacles = obstacleCount > 0; + if (hasObstacles) { + bool hasFreeSpace = obstacleCount < occupancyGrid.size(); + if (hasFreeSpace) { + return internal::signedDistanceFromOccupancyTranspose(occupancyGrid, resolution).transpose(); + } else { + // Only obstacles -> distance is minus infinity everywhere + return Matrix::Constant(occupancyGrid.rows(), occupancyGrid.cols(), -INF); + } + } else { + // No obstacles -> planar distance is infinite + return Matrix::Constant(occupancyGrid.rows(), occupancyGrid.cols(), INF); + } +} + +} // namespace signed_distance_field +} // namespace grid_map \ No newline at end of file diff --git a/grid_map_sdf/src/SignedDistanceField.cpp b/grid_map_sdf/src/SignedDistanceField.cpp index 163dc3a2b..16ecd3906 100644 --- a/grid_map_sdf/src/SignedDistanceField.cpp +++ b/grid_map_sdf/src/SignedDistanceField.cpp @@ -1,184 +1,198 @@ /* - * SignedDistanceField.hpp + * SignedDistanceField.cpp * - * Created on: Aug 16, 2017 - * Authors: Takahiro Miki, Peter Fankhauser - * Institute: ETH Zurich, ANYbotics + * Created on: Jul 10, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich */ -#include -#include +#include "grid_map_sdf/SignedDistanceField.hpp" -#include +#include -#include - -using namespace distance_transform; +#include "grid_map_sdf/DistanceDerivatives.hpp" +#include "grid_map_sdf/SignedDistance2d.hpp" namespace grid_map { -SignedDistanceField::SignedDistanceField() - : maxDistance_(std::numeric_limits::max()), - zIndexStartHeight_(0.0), - resolution_(0.0), - lowestHeight_(-1e5) // We need some precision. -{ -} +// Import from the signed_distance_field namespace +using signed_distance_field::columnwiseCentralDifference; +using signed_distance_field::Gridmap3dLookup; +using signed_distance_field::layerCentralDifference; +using signed_distance_field::layerFiniteDifference; +using signed_distance_field::signedDistanceAtHeightTranspose; + +SignedDistanceField::SignedDistanceField(const GridMap& gridMap, const std::string& elevationLayer, double minHeight, double maxHeight) + : frameId_(gridMap.getFrameId()), timestamp_(gridMap.getTimestamp()) { + assert(maxHeight >= minHeight); + + // Determine origin of the 3D grid + Position mapOriginXY; + gridMap.getPosition(Eigen::Vector2i(0, 0), mapOriginXY); + Position3 gridOrigin(mapOriginXY.x(), mapOriginXY.y(), minHeight); + + // Round up the Z-discretization. We need a minimum of two layers to enable finite difference in Z direction + const auto numZLayers = static_cast(std::max(std::ceil((maxHeight - minHeight) / gridMap.getResolution()), 2.0)); + const size_t numXrows = gridMap.getSize().x(); + const size_t numYrows = gridMap.getSize().y(); + Gridmap3dLookup::size_t_3d gridsize = {numXrows, numYrows, numZLayers}; + + // Initialize 3D lookup + gridmap3DLookup_ = Gridmap3dLookup(gridsize, gridOrigin, gridMap.getResolution()); + + // Allocate the internal data structure + data_.reserve(gridmap3DLookup_.linearSize()); + + // Check for NaN + const auto& elevationData = gridMap.get(elevationLayer); + if (elevationData.hasNaN()) { + std::cerr + << "[grid_map_sdf::SignedDistanceField] elevation data contains NaN. The generated SDF will be invalid! Apply inpainting first" + << std::endl; + } -SignedDistanceField::~SignedDistanceField() -{ + // Compute the SDF + computeSignedDistance(elevationData); } -void SignedDistanceField::calculateSignedDistanceField(const GridMap& gridMap, const std::string& layer, - const double heightClearance) -{ - data_.clear(); - resolution_ = gridMap.getResolution(); - position_ = gridMap.getPosition(); - size_ = gridMap.getSize(); - Matrix map = gridMap.get(layer); // Copy! - - float minHeight = map.minCoeffOfFinites(); - if (!std::isfinite(minHeight)) minHeight = lowestHeight_; - float maxHeight = map.maxCoeffOfFinites(); - if (!std::isfinite(maxHeight)) maxHeight = lowestHeight_; - - const float valueForEmptyCells = lowestHeight_; // maxHeight, minHeight (TODO Make this an option). - for (size_t i = 0; i < map.size(); ++i) { - if (std::isnan(map(i))) map(i) = valueForEmptyCells; - } +double SignedDistanceField::value(const Position3& position) const noexcept { + const auto nodeIndex = gridmap3DLookup_.nearestNode(position); + const auto nodePosition = gridmap3DLookup_.nodePosition(nodeIndex); + const auto nodeData = data_[gridmap3DLookup_.linearIndex(nodeIndex)]; + const auto jacobian = derivative(nodeData); + return distance(nodeData) + jacobian.dot(position - nodePosition); +} - // Height range of the signed distance field is higher than the max height. - maxHeight += heightClearance; - - Matrix sdfElevationAbove = Matrix::Ones(map.rows(), map.cols()) * maxDistance_; - Matrix sdfLayer = Matrix::Zero(map.rows(), map.cols()); - std::vector sdf; - zIndexStartHeight_ = minHeight; - - // Calculate signed distance field from bottom. - for (float h = minHeight; h < maxHeight; h += resolution_) { - Eigen::Matrix obstacleFreeField = map.array() < h; - Eigen::Matrix obstacleField = obstacleFreeField.array() < 1; - Matrix sdfObstacle = getPlanarSignedDistanceField(obstacleField); - Matrix sdfObstacleFree = getPlanarSignedDistanceField(obstacleFreeField); - Matrix sdf2d; - // If 2d sdfObstacleFree calculation failed, neglect this SDF - // to avoid extreme small distances (-INF). - if ((sdfObstacleFree.array() >= INF).any()) sdf2d = sdfObstacle; - else sdf2d = sdfObstacle - sdfObstacleFree; - sdf2d *= resolution_; - for (size_t i = 0; i < sdfElevationAbove.size(); ++i) { - if(sdfElevationAbove(i) == maxDistance_ && map(i) <= h) sdfElevationAbove(i) = h - map(i); - else if(sdfElevationAbove(i) != maxDistance_ && map(i) <= h) sdfElevationAbove(i) = sdfLayer(i) + resolution_; - if (sdf2d(i) == 0) sdfLayer(i) = h - map(i); - else if (sdf2d(i) < 0) sdfLayer(i) = -std::min(fabs(sdf2d(i)), fabs(map(i) - h)); - else sdfLayer(i) = std::min(sdf2d(i), sdfElevationAbove(i)); - } - data_.push_back(sdfLayer); - } +SignedDistanceField::Derivative3 SignedDistanceField::derivative(const Position3& position) const noexcept { + const auto nodeIndex = gridmap3DLookup_.nearestNode(position); + const auto nodeData = data_[gridmap3DLookup_.linearIndex(nodeIndex)]; + return derivative(nodeData); } -grid_map::Matrix SignedDistanceField::getPlanarSignedDistanceField(Eigen::Matrix& data) const -{ - image *input = new image(data.rows(), data.cols(), true); +std::pair SignedDistanceField::valueAndDerivative(const Position3& position) const noexcept { + const auto nodeIndex = gridmap3DLookup_.nearestNode(position); + const auto nodePosition = gridmap3DLookup_.nodePosition(nodeIndex); + const auto nodeData = data_[gridmap3DLookup_.linearIndex(nodeIndex)]; + const auto jacobian = derivative(nodeData); + return {distance(nodeData) + jacobian.dot(position - nodePosition), jacobian}; +} - for (int y = 0; y < input->height(); y++) { - for (int x = 0; x < input->width(); x++) { - imRef(input, x, y) = data(x, y); - } +void SignedDistanceField::computeSignedDistance(const Matrix& elevation) { + const auto gridOriginZ = static_cast(gridmap3DLookup_.gridOrigin_.z()); + const auto resolution = static_cast(gridmap3DLookup_.resolution_); + const auto minHeight = elevation.minCoeff(); + const auto maxHeight = elevation.maxCoeff(); + + /* + * General strategy to reduce the amount of transposing: + * - SDF at a height is in transposed form after computing it. + * - Take the finite difference in dx, now that this data is continuous in memory. + * - Transpose the SDF + * - Take other finite differences. Now dy is efficient. + * - When writing to the 3D structure, keep in mind that dx is still transposed. + */ + + // Memory needed to compute the SDF at a layer + Matrix tmp; // allocated on first use + Matrix tmpTranspose; // allocated on first use + Matrix sdfTranspose; // allocated on first use + + // Memory needed to keep a buffer of layers. We need 3 due to the central difference + Matrix currentLayer; // allocated on first use + Matrix nextLayer; // allocated on first use + Matrix previousLayer; // allocated on first use + + // Memory needed to compute finite differences + Matrix dxTranspose = Matrix::Zero(elevation.cols(), elevation.rows()); + Matrix dxNextTranspose = Matrix::Zero(elevation.cols(), elevation.rows()); + Matrix dy = Matrix::Zero(elevation.rows(), elevation.cols()); + Matrix dz = Matrix::Zero(elevation.rows(), elevation.cols()); + + // Compute SDF of first layer + computeLayerSdfandDeltaX(elevation, currentLayer, dxTranspose, sdfTranspose, tmp, tmpTranspose, gridOriginZ, resolution, minHeight, + maxHeight); + + // Compute SDF of second layer + computeLayerSdfandDeltaX(elevation, nextLayer, dxNextTranspose, sdfTranspose, tmp, tmpTranspose, gridOriginZ + resolution, resolution, + minHeight, maxHeight); + + // First layer: forward difference in z + layerFiniteDifference(currentLayer, nextLayer, dz, resolution); // dz / layer = +resolution + columnwiseCentralDifference(currentLayer, dy, -resolution); // dy / dcol = -resolution + + emplacebackLayerData(currentLayer, dxTranspose, dy, dz); + + // Middle layers: central difference in z + for (size_t layerZ = 1; layerZ + 1 < gridmap3DLookup_.gridsize_.z; ++layerZ) { + // Circulate layer buffers + previousLayer.swap(currentLayer); + currentLayer.swap(nextLayer); + dxTranspose.swap(dxNextTranspose); + + // Compute SDF of next layer + computeLayerSdfandDeltaX(elevation, nextLayer, dxNextTranspose, sdfTranspose, tmp, tmpTranspose, + gridOriginZ + (layerZ + 1) * resolution, resolution, minHeight, maxHeight); + + // Compute other finite differences + layerCentralDifference(previousLayer, nextLayer, dz, resolution); + columnwiseCentralDifference(currentLayer, dy, -resolution); + + // Add the data to the 3D structure + emplacebackLayerData(currentLayer, dxTranspose, dy, dz); } - // Compute dt. - image *out = dt(input); + // Circulate layer buffers one last time + previousLayer.swap(currentLayer); + currentLayer.swap(nextLayer); + dxTranspose.swap(dxNextTranspose); - Matrix result(data.rows(), data.cols()); + // Last layer: backward difference in z + layerFiniteDifference(previousLayer, currentLayer, dz, resolution); + columnwiseCentralDifference(currentLayer, dy, -resolution); + + // Add the data to the 3D structure + emplacebackLayerData(currentLayer, dxTranspose, dy, dz); +} +void SignedDistanceField::computeLayerSdfandDeltaX(const Matrix& elevation, Matrix& currentLayer, Matrix& dxTranspose, Matrix& sdfTranspose, + Matrix& tmp, Matrix& tmpTranspose, float height, float resolution, float minHeight, + float maxHeight) const { + // Compute SDF + dx of layer: compute sdfTranspose -> take dxTranspose -> transpose to get sdf + signedDistanceAtHeightTranspose(elevation, sdfTranspose, tmp, tmpTranspose, height, resolution, minHeight, maxHeight); + columnwiseCentralDifference(sdfTranspose, dxTranspose, -resolution); // dx / drow = -resolution + currentLayer = sdfTranspose.transpose(); +} - // Take square roots. - for (int y = 0; y < out->height(); y++) { - for (int x = 0; x < out->width(); x++) { - result(x, y) = sqrt(imRef(out, x, y)); +void SignedDistanceField::emplacebackLayerData(const Matrix& signedDistance, const Matrix& dxTranspose, const Matrix& dy, + const Matrix& dz) { + for (size_t colY = 0; colY < gridmap3DLookup_.gridsize_.y; ++colY) { + for (size_t rowX = 0; rowX < gridmap3DLookup_.gridsize_.x; ++rowX) { + data_.emplace_back(node_data_t{signedDistance(rowX, colY), dxTranspose(colY, rowX), dy(rowX, colY), dz(rowX, colY)}); } } - return result; } -double SignedDistanceField::getDistanceAt(const Position3& position) const -{ - double xCenter = size_.x() / 2.0; - double yCenter = size_.y() / 2.0; - int i = std::round(xCenter - (position.x() - position_.x()) / resolution_); - int j = std::round(yCenter - (position.y() - position_.y()) / resolution_); - int k = std::round((position.z() - zIndexStartHeight_) / resolution_); - i = std::max(i, 0); - i = std::min(i, size_.x() - 1); - j = std::max(j, 0); - j = std::min(j, size_.y() - 1); - k = std::max(k, 0); - k = std::min(k, (int)data_.size() - 1); - return data_[k](i, j); +size_t SignedDistanceField::size() const noexcept { + return gridmap3DLookup_.linearSize(); } -double SignedDistanceField::getInterpolatedDistanceAt(const Position3& position) const -{ - double xCenter = size_.x() / 2.0; - double yCenter = size_.y() / 2.0; - int i = std::round(xCenter - (position.x() - position_.x()) / resolution_); - int j = std::round(yCenter - (position.y() - position_.y()) / resolution_); - int k = std::round((position.z() - zIndexStartHeight_) / resolution_); - i = std::max(i, 0); - i = std::min(i, size_.x() - 1); - j = std::max(j, 0); - j = std::min(j, size_.y() - 1); - k = std::max(k, 0); - k = std::min(k, (int)data_.size() - 1); - Vector3 gradient = getDistanceGradientAt(position); - double xp = position_.x() + ((size_.x() - i) - xCenter) * resolution_; - double yp = position_.y() + ((size_.y() - j) - yCenter) * resolution_; - double zp = zIndexStartHeight_ + k * resolution_; - Vector3 error = position - Vector3(xp, yp, zp); - return data_[k](i, j) + gradient.dot(error); +const std::string& SignedDistanceField::getFrameId() const noexcept { + return frameId_; } -Vector3 SignedDistanceField::getDistanceGradientAt(const Position3& position) const -{ - double xCenter = size_.x() / 2.0; - double yCenter = size_.y() / 2.0; - int i = std::round(xCenter - (position.x() - position_.x()) / resolution_); - int j = std::round(yCenter - (position.y() - position_.y()) / resolution_); - int k = std::round((position.z() - zIndexStartHeight_) / resolution_); - i = std::max(i, 1); - i = std::min(i, size_.x() - 2); - j = std::max(j, 1); - j = std::min(j, size_.y() - 2); - k = std::max(k, 1); - k = std::min(k, (int)data_.size() - 2); - double dx = (data_[k](i - 1, j) - data_[k](i + 1, j)) / (2 * resolution_); - double dy = (data_[k](i, j - 1) - data_[k](i, j + 1)) / (2 * resolution_); - double dz = (data_[k + 1](i, j) - data_[k - 1](i, j)) / (2 * resolution_); - return Vector3(dx, dy, dz); +Time SignedDistanceField::getTime() const noexcept { + return timestamp_; } -void SignedDistanceField::convertToPointCloud(pcl::PointCloud& points) const -{ - double xCenter = size_.x() / 2.0; - double yCenter = size_.y() / 2.0; - for (int z = 0; z < data_.size(); z++){ - for (int y = 0; y < size_.y(); y++) { - for (int x = 0; x < size_.x(); x++) { - double xp = position_.x() + ((size_.x() - x) - xCenter) * resolution_; - double yp = position_.y() + ((size_.y() - y) - yCenter) * resolution_; - double zp = zIndexStartHeight_ + z * resolution_; - pcl::PointXYZI p; - p.x = xp; - p.y = yp; - p.z = zp; - p.intensity = data_[z](x, y); - points.push_back(p); +void SignedDistanceField::filterPoints(std::function func, size_t decimation) const { + for (size_t layerZ = 0; layerZ < gridmap3DLookup_.gridsize_.z; layerZ += decimation) { + for (size_t colY = 0; colY < gridmap3DLookup_.gridsize_.y; colY += decimation) { + for (size_t rowX = 0; rowX < gridmap3DLookup_.gridsize_.x; rowX += decimation) { + const Gridmap3dLookup::size_t_3d index3d = {rowX, colY, layerZ}; + const auto index = gridmap3DLookup_.linearIndex(index3d); + func(gridmap3DLookup_.nodePosition(index3d), distanceFloat(data_[index]), derivative(data_[index])); } } } - return; } -} /* namespace */ +} // namespace grid_map diff --git a/grid_map_sdf/test/SignedDistanceFieldTest.cpp b/grid_map_sdf/test/SignedDistanceFieldTest.cpp deleted file mode 100644 index c66adbcc0..000000000 --- a/grid_map_sdf/test/SignedDistanceFieldTest.cpp +++ /dev/null @@ -1,305 +0,0 @@ -/* - * SignedDistanceFieldTest.cpp - * - * Created on: Aug 25, 2017 - * Author: Takahiro Miki, Peter Fankhauser - * Institute: ETH Zurich, ANYbotics - */ - -#include "grid_map_core/GridMap.hpp" -#include "grid_map_sdf/SignedDistanceField.hpp" - -#include -#include - -using namespace std; -using namespace grid_map; - -TEST(SignedDistanceField, EmptyMap) -{ - GridMap map({"layer"}); - map.setGeometry(Length(1.0, 2.0), 0.1, Position(0.0, 0.0)); - - SignedDistanceField sdf; - sdf.calculateSignedDistanceField(map, "layer", 1.0); - Position3 position(0.0, 0.0, 0.0); - - EXPECT_NO_THROW(sdf.getDistanceAt(position)); - EXPECT_NO_THROW(sdf.getInterpolatedDistanceAt(position)); - EXPECT_NO_THROW(sdf.getDistanceGradientAt(position)); -} - -TEST(SignedDistanceField, GetDistanceFlat) -{ - GridMap map({"layer"}); - map.setGeometry(Length(1.0, 2.0), 0.1, Position(0.1, 0.2)); - map["layer"].setConstant(1.0); - map.at("layer", Index(0,0)) = -1.0; - - SignedDistanceField sdf; - sdf.calculateSignedDistanceField(map, "layer", 2.5); - Position pos; - map.getPosition(Index(9, 9), pos); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.0)), -1.0, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.1)), -0.9, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.2)), -0.8, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.3)), -0.7, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.4)), -0.6, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.5)), -0.5, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.6)), -0.4, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.7)), -0.3, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.8)), -0.2, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.9)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.0)), 0.0, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.1)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.2)), 0.2, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.3)), 0.3, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.4)), 0.4, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.5)), 0.5, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.6)), 0.6, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.7)), 0.7, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), 0.8, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.9)), 0.9, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.0)), 1.0, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.1)), 1.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.2)), 1.2, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.3)), 1.3, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.4)), 1.4, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.5)), 1.5, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 10.0)), 2.5, 0.0001); -} - - -TEST(SignedDistanceField, GetDistance) -{ - GridMap map({"layer"}); - map.setGeometry(Length(1.0, 2.0), 0.1, Position(0.15, 0.25)); - map["layer"].setConstant(1.0); - - map.at("layer", Index(3,4)) = 2.0; - map.at("layer", Index(3,5)) = 2.0; - map.at("layer", Index(3,6)) = 2.0; - map.at("layer", Index(4,4)) = 2.0; - map.at("layer", Index(4,5)) = 2.0; - map.at("layer", Index(4,6)) = 2.0; - map.at("layer", Index(5,4)) = 2.0; - map.at("layer", Index(5,5)) = 2.0; - map.at("layer", Index(5,6)) = 2.0; - map.at("layer", Index(6,4)) = 2.0; - map.at("layer", Index(6,5)) = 2.0; - map.at("layer", Index(6,6)) = 2.0; - map.at("layer", Index(7,4)) = 2.0; - map.at("layer", Index(7,5)) = 2.0; - map.at("layer", Index(7,6)) = 2.0; - - SignedDistanceField sdf; - sdf.calculateSignedDistanceField(map, "layer", 1.5); - Position pos; - - map.getPosition(Index(5, 5), pos); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.0)), -1.0, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.5)), -1.0, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.0)), -1.0, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.1)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.2)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.3)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.4)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.5)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.6)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.7)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.0)), 0.0, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.1)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.2)), 0.2, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.3)), 0.3, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.4)), 0.4, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.5)), 0.5, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 10.0)), 1.5, 0.0001); - - map.getPosition(Index(5, 2), pos); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.0)), 0.0, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 0.5)), 0.0, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.0)), 0.0, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.1)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.2)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.3)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.4)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.5)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.6)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.7)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 1.9)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.0)), 0.2, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.1)), 0.3, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.2)), 0.4, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.3)), 0.5, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.4)), 0.6, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 2.5)), 0.7, 0.0001); - EXPECT_NEAR(sdf.getDistanceAt(Vector3(pos.x(), pos.y(), 10.0)), 1.7, 0.0001); -} - -TEST(SignedDistanceField, GetDistanceGradient) -{ - GridMap map({"layer"}); - map.setGeometry(Length(1.0, 2.0), 0.1, Position(0.15, 0.25)); - map["layer"].setConstant(1.0); - - map.at("layer", Index(3,4)) = 2.0; - map.at("layer", Index(3,5)) = 2.0; - map.at("layer", Index(3,6)) = 2.0; - map.at("layer", Index(4,4)) = 2.0; - map.at("layer", Index(4,5)) = 2.0; - map.at("layer", Index(4,6)) = 2.0; - map.at("layer", Index(5,4)) = 2.0; - map.at("layer", Index(5,5)) = 2.0; - map.at("layer", Index(5,6)) = 2.0; - map.at("layer", Index(6,4)) = 2.0; - map.at("layer", Index(6,5)) = 2.0; - map.at("layer", Index(6,6)) = 2.0; - map.at("layer", Index(7,4)) = 2.0; - map.at("layer", Index(7,5)) = 2.0; - map.at("layer", Index(7,6)) = 2.0; - - SignedDistanceField sdf; - sdf.calculateSignedDistanceField(map, "layer", 1.5); - Position pos; - Vector3 gradient; - - map.getPosition(Index(5, 6), pos); - gradient = sdf.getDistanceGradientAt(Vector3(pos.x(), pos.y(), 0.0)); - EXPECT_NEAR(gradient.x(), 0.0, 0.0001); - EXPECT_NEAR(gradient.y(), -1, 0.0001); - EXPECT_NEAR(gradient.z(), 0.5, 0.0001); - gradient = sdf.getDistanceGradientAt(Vector3(pos.x(), pos.y(), 1.0)); - EXPECT_NEAR(gradient.x(), 0.0, 0.0001); - EXPECT_NEAR(gradient.y(), -1, 0.0001); - EXPECT_NEAR(gradient.z(), 0.5, 0.0001); - gradient = sdf.getDistanceGradientAt(Vector3(pos.x(), pos.y(), 2.0)); - EXPECT_NEAR(gradient.x(), 0.0, 0.0001); - EXPECT_NEAR(gradient.y(), -1.5, 0.0001); - EXPECT_NEAR(gradient.z(), 1, 0.0001); - gradient = sdf.getDistanceGradientAt(Vector3(pos.x(), pos.y(), 2.2)); - EXPECT_NEAR(gradient.x(), 0.0, 0.0001); - EXPECT_NEAR(gradient.y(), -1.5, 0.0001); - EXPECT_NEAR(gradient.z(), 1.0, 0.0001); - gradient = sdf.getDistanceGradientAt(Vector3(pos.x(), pos.y(), 10.0)); - EXPECT_NEAR(gradient.x(), 0.0, 0.0001); - EXPECT_NEAR(gradient.y(), -1.5, 0.0001); - EXPECT_NEAR(gradient.z(), 1.0, 0.0001); - map.getPosition(Index(2, 2), pos); - gradient = sdf.getDistanceGradientAt(Vector3(pos.x(), pos.y(), 1.0)); - EXPECT_NEAR(gradient.x(), 0.0, 0.0001); - EXPECT_NEAR(gradient.y(), 1, 0.0001); - EXPECT_NEAR(gradient.z(), 0.5, 0.0001); - gradient = sdf.getDistanceGradientAt(Vector3(pos.x(), pos.y(), 2.0)); - EXPECT_NEAR(gradient.x(), 0.207107, 0.0001); - EXPECT_NEAR(gradient.y(), 1.5, 0.0001); - EXPECT_NEAR(gradient.z(), 1, 0.0001); - gradient = sdf.getDistanceGradientAt(Vector3(pos.x(), pos.y(), 2.2)); - EXPECT_NEAR(gradient.x(), 0.207107, 0.0001); - EXPECT_NEAR(gradient.y(), 1.5, 0.0001); - EXPECT_NEAR(gradient.z(), 1, 0.0001); - map.getPosition(Index(12, 22), pos); - gradient = sdf.getDistanceGradientAt(Vector3(pos.x(), pos.y(), 1.0)); - EXPECT_NEAR(gradient.x(), 0.0, 0.0001); - EXPECT_NEAR(gradient.y(), 1.0, 0.0001); - EXPECT_NEAR(gradient.z(), 0.5, 0.0001); -} - -TEST(SignedDistanceField, GetInterpolatedDistance) -{ - GridMap map({"layer"}); - map.setGeometry(Length(1.0, 2.0), 0.1, Position(0.15, 0.25)); - map["layer"].setConstant(1.0); - - map.at("layer", Index(3,3)) = 2.0; - map.at("layer", Index(3,4)) = 2.0; - map.at("layer", Index(3,5)) = 2.0; - map.at("layer", Index(3,6)) = 2.0; - map.at("layer", Index(3,7)) = 2.0; - map.at("layer", Index(4,3)) = 2.0; - map.at("layer", Index(4,4)) = 2.0; - map.at("layer", Index(4,5)) = 2.0; - map.at("layer", Index(4,6)) = 2.0; - map.at("layer", Index(4,7)) = 2.0; - map.at("layer", Index(5,3)) = 2.0; - map.at("layer", Index(5,4)) = 2.0; - map.at("layer", Index(5,5)) = 2.0; - map.at("layer", Index(5,6)) = 2.0; - map.at("layer", Index(5,7)) = 2.0; - map.at("layer", Index(6,3)) = 2.0; - map.at("layer", Index(6,4)) = 2.0; - map.at("layer", Index(6,5)) = 2.0; - map.at("layer", Index(6,6)) = 2.0; - map.at("layer", Index(6,7)) = 2.0; - map.at("layer", Index(7,3)) = 2.0; - map.at("layer", Index(7,4)) = 2.0; - map.at("layer", Index(7,5)) = 2.0; - map.at("layer", Index(7,6)) = 2.0; - map.at("layer", Index(7,7)) = 2.0; - - SignedDistanceField sdf; - sdf.calculateSignedDistanceField(map, "layer", 1.5); - Position pos; - - map.getPosition(Index(5, 5), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 0.0)), -5.05, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 0.5)), -3.05, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.0)), -1.05, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.1)), -0.25, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.2)), -0.25, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.3)), -0.25, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.4)), -0.25, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.5)), -0.25, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.6)), -0.25, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.7)), -0.25, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), -0.25, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.9)), -0.1, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.0)), 0.0, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.1)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.2)), 0.2, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.3)), 0.3, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.4)), 0.4, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.5)), 0.5, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 10.0)), 8, 0.0001); - - map.getPosition(Index(5, 10), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 0.0)), -1.0, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 0.5)), -0.5, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.0)), 0.0, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.1)), 0.1, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.2)), 0.2, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.3)), 0.3, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.5)), 0.35, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.7)), 0.35, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.9)), 0.35, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.0)), 0.45, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.1)), 0.55, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.2)), 0.65, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.3)), 0.75, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.4)), 0.85, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 2.5)), 0.95, 0.0001); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 10.0)), 8.45, 0.0001); - - map.getPosition(Index(5, 0), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), 0.25, 0.0001); - map.getPosition(Index(5, 1), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), 0.175, 0.0001); - map.getPosition(Index(5, 2), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), -0.025, 0.0001); - map.getPosition(Index(5, 3), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), -0.2, 0.0001); - map.getPosition(Index(5, 4), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), -0.225, 0.0001); - map.getPosition(Index(5, 5), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), -0.25, 0.0001); - map.getPosition(Index(5, 6), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), -0.175, 0.0001); - map.getPosition(Index(5, 7), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), 0.025, 0.0001); - map.getPosition(Index(5, 8), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), 0.15, 0.0001); - map.getPosition(Index(5, 9), pos); - EXPECT_NEAR(sdf.getInterpolatedDistanceAt(Vector3(pos.x(), pos.y(), 1.8)), 0.25, 0.0001); -} diff --git a/grid_map_sdf/test/include/naiveSignedDistance.hpp b/grid_map_sdf/test/include/naiveSignedDistance.hpp new file mode 100644 index 000000000..c3957a0b2 --- /dev/null +++ b/grid_map_sdf/test/include/naiveSignedDistance.hpp @@ -0,0 +1,116 @@ +/* + * naiveSignedDistance.h + * + * Created on: Aug 10, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#pragma once + +namespace grid_map { +namespace signed_distance_field { + +inline Eigen::Matrix occupancyAtHeight(const Matrix& elevationMap, float height) { + Eigen::Matrix occupancy = elevationMap.unaryExpr([=](float val) { return val > height; }); + return occupancy; +} + +inline bool isEqualSdf(const Matrix& sdf0, const Matrix& sdf1, float tol) { + if (sdf0.cols() != sdf1.cols() || sdf0.rows() != sdf1.rows()) { + return false; + } + + for (Eigen::Index col = 0; col < sdf0.cols(); ++col) { + for (Eigen::Index row = 0; row < sdf0.rows(); ++row) { + if (sdf0(row, col) == sdf1(row, col) || std::abs(sdf0(row, col) - sdf1(row, col)) < tol) { + continue; + } else { + return false; + } + } + } + return true; +} + +// N^2 naive implementation, for testing purposes +inline Matrix naiveSignedDistanceAtHeight(const Matrix& elevationMap, float height, float resolution) { + Matrix signedDistance(elevationMap.rows(), elevationMap.cols()); + + // For each point + for (Eigen::Index col = 0; col < elevationMap.cols(); ++col) { + for (Eigen::Index row = 0; row < elevationMap.rows(); ++row) { + if (elevationMap(row, col) >= height) { // point in the SDF is below surface + signedDistance(row, col) = -INF; + // find closest open space over all other points + for (Eigen::Index j = 0; j < elevationMap.cols(); ++j) { + for (Eigen::Index i = 0; i < elevationMap.rows(); ++i) { + // Compute distance to free cube at location (i, j) + const float dx{resolution * pixelBorderDistance(i, row)}; + const float dy{resolution * pixelBorderDistance(j, col)}; + const float dz{std::max(elevationMap(i, j) - height, 0.0F)}; + const float currentSignedDistance{-std::sqrt(dx * dx + dy * dy + dz * dz)}; + signedDistance(row, col) = std::max(signedDistance(row, col), currentSignedDistance); + } + } + } else { // point in the SDF is above surface + signedDistance(row, col) = INF; + // find closest object over all other points + for (Eigen::Index j = 0; j < elevationMap.cols(); ++j) { + for (Eigen::Index i = 0; i < elevationMap.rows(); ++i) { + // Compute distance to occupied cube at location (i, j) + const float dx{resolution * pixelBorderDistance(i, row)}; + const float dy{resolution * pixelBorderDistance(j, col)}; + const float dz{std::max(height - elevationMap(i, j), 0.0F)}; + const float currentSignedDistance{std::sqrt(dx * dx + dy * dy + dz * dz)}; + signedDistance(row, col) = std::min(signedDistance(row, col), currentSignedDistance); + } + } + } + } + } + + return signedDistance; +} + +inline Matrix naiveSignedDistanceFromOccupancy(const Eigen::Matrix& occupancyGrid, float resolution) { + Matrix signedDistance(occupancyGrid.rows(), occupancyGrid.cols()); + + // For each point + for (Eigen::Index col = 0; col < occupancyGrid.cols(); ++col) { + for (Eigen::Index row = 0; row < occupancyGrid.rows(); ++row) { + if (occupancyGrid(row, col)) { // This point is an obstable + signedDistance(row, col) = -INF; + // find closest open space over all other points + for (Eigen::Index j = 0; j < occupancyGrid.cols(); ++j) { + for (Eigen::Index i = 0; i < occupancyGrid.rows(); ++i) { + if (!occupancyGrid(i, j)) { + const float dx{resolution * pixelBorderDistance(i, row)}; + const float dy{resolution * pixelBorderDistance(j, col)}; + const float currentSignedDistance{-std::sqrt(dx * dx + dy * dy)}; + signedDistance(row, col) = std::max(signedDistance(row, col), currentSignedDistance); + } + } + } + } else { // This point is in free space + signedDistance(row, col) = INF; + // find closest object over all other points + for (Eigen::Index j = 0; j < occupancyGrid.cols(); ++j) { + for (Eigen::Index i = 0; i < occupancyGrid.rows(); ++i) { + if (occupancyGrid(i, j)) { + const float dx{resolution * pixelBorderDistance(i, row)}; + const float dy{resolution * pixelBorderDistance(j, col)}; + const float currentSignedDistance{std::sqrt(dx * dx + dy * dy)}; + signedDistance(row, col) = std::min(signedDistance(row, col), currentSignedDistance); + } + } + } + } + } + } + + return signedDistance; +} + +} // namespace signed_distance_field +} // namespace grid_map \ No newline at end of file diff --git a/grid_map_sdf/test/test3dLookup.cpp b/grid_map_sdf/test/test3dLookup.cpp new file mode 100644 index 000000000..254a6cbd5 --- /dev/null +++ b/grid_map_sdf/test/test3dLookup.cpp @@ -0,0 +1,59 @@ +/* + * test3dLookup.cpp + * + * Created on: Aug 18, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#include + +#include "grid_map_sdf/Gridmap3dLookup.hpp" + +using namespace grid_map; +using namespace signed_distance_field; +using size_t_3d = Gridmap3dLookup::size_t_3d; + +TEST(testGridmap3dLookup, nearestNode) { + const size_t_3d gridsize{8, 9, 10}; + const Position3 gridOrigin{-0.1, -0.2, -0.4}; + const double resolution = 0.1; + + Gridmap3dLookup gridmap3DLookup(gridsize, gridOrigin, resolution); + + // Retrieve origin + const size_t_3d originNode = gridmap3DLookup.nearestNode(gridOrigin); + ASSERT_EQ(originNode.x, 0); + ASSERT_EQ(originNode.y, 0); + ASSERT_EQ(originNode.z, 0); + + // test underflow + const size_t_3d originNodeProjected = gridmap3DLookup.nearestNode(gridOrigin + Position3{1e20, 1e20, -1e20}); + ASSERT_EQ(originNodeProjected.x, 0); + ASSERT_EQ(originNodeProjected.y, 0); + ASSERT_EQ(originNodeProjected.z, 0); + + // test overflow + const size_t_3d maxNodeProjected = gridmap3DLookup.nearestNode(gridOrigin + Position3{-1e20, -1e20, +1e20}); + ASSERT_EQ(maxNodeProjected.x, gridsize.x - 1); + ASSERT_EQ(maxNodeProjected.y, gridsize.y - 1); + ASSERT_EQ(maxNodeProjected.z, gridsize.z - 1); + + // Nearest neighbour + const size_t_3d nodeIndex{3, 4, 5}; + const Position3 nodePosition = gridmap3DLookup.nodePosition(nodeIndex); + const size_t_3d closestNodeIndex = gridmap3DLookup.nearestNode(nodePosition + 0.49 * Position3::Constant(resolution)); + ASSERT_EQ(closestNodeIndex.x, nodeIndex.x); + ASSERT_EQ(closestNodeIndex.y, nodeIndex.y); + ASSERT_EQ(closestNodeIndex.z, nodeIndex.z); +} + +TEST(testGridmap3dLookup, linearIndex) { + const size_t_3d gridsize{8, 9, 10}; + const Position3 gridOrigin{-0.1, -0.2, -0.4}; + const double resolution = 0.1; + + Gridmap3dLookup gridmap3DLookup(gridsize, gridOrigin, resolution); + ASSERT_EQ(gridmap3DLookup.linearIndex({0, 0, 0}), 0); + ASSERT_EQ(gridmap3DLookup.linearIndex({gridsize.x - 1, gridsize.y - 1, gridsize.z - 1}), gridmap3DLookup.linearSize() - 1); +} \ No newline at end of file diff --git a/grid_map_sdf/test/testDerivatives.cpp b/grid_map_sdf/test/testDerivatives.cpp new file mode 100644 index 000000000..5fa890412 --- /dev/null +++ b/grid_map_sdf/test/testDerivatives.cpp @@ -0,0 +1,31 @@ +/* + * testDerivatives.cpp + * + * Created on: Aug 10, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#include + +#include "grid_map_sdf/DistanceDerivatives.hpp" + +using namespace grid_map; +using namespace signed_distance_field; + +TEST(testDerivatives, columnwise) { + Matrix data(2, 3); + data << 1.0, 2.0, 4.0, 2.0, 4.0, 6.0; + + float resolution{0.1F}; + float doubleResolution{2.0F * resolution}; + + Matrix manualDifference(2, 3); + manualDifference << 1.0 / resolution, 3.0 / doubleResolution, 2.0 / resolution, 2.0 / resolution, 4.0 / doubleResolution, + 2.0 / resolution; + + Matrix computedDifference = Matrix::Zero(data.rows(), data.cols()); + columnwiseCentralDifference(data, computedDifference, resolution); + + ASSERT_TRUE(manualDifference.isApprox(computedDifference)); +} diff --git a/grid_map_sdf/test/testPixelBorderDistance.cpp b/grid_map_sdf/test/testPixelBorderDistance.cpp new file mode 100644 index 000000000..38b1a441c --- /dev/null +++ b/grid_map_sdf/test/testPixelBorderDistance.cpp @@ -0,0 +1,76 @@ +/* + * testPixelBorderDistance.cpp + * + * Created on: Aug 7, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#include + +#include "grid_map_sdf/PixelBorderDistance.hpp" +#include "grid_map_sdf/Utils.hpp" + +using namespace grid_map; +using namespace signed_distance_field; + +TEST(testPixelBorderDistance, distanceFunction) { + // Basic properties of the distance function + ASSERT_TRUE(pixelBorderDistance(0, 0) == 0.0F); + ASSERT_FLOAT_EQ(pixelBorderDistance(0, 1), 0.5); + ASSERT_FLOAT_EQ(pixelBorderDistance(0, 2), 1.5); + ASSERT_TRUE(pixelBorderDistance(0, 1) == pixelBorderDistance(1, 0)); + ASSERT_TRUE(pixelBorderDistance(-10, 42) == pixelBorderDistance(42, -10)); +} + +TEST(testPixelBorderDistance, equidistantPoint) { + int pixelRange = 10; + float offsetRange = 20.0; + float offsetStep = 0.25; + float tol = 1e-4; + + for (int p = -pixelRange; p < pixelRange; ++p) { + for (float fp = -offsetRange; fp < offsetRange; fp += offsetStep) { + for (int q = -pixelRange; q < pixelRange; ++q) { + for (float fq = -offsetRange; fq < offsetRange; fq += offsetStep) { + // Fix that offset is the same if pixels are the same + if (p == q) { + fp = fq; + } + // Check symmetry of the equidistant point computation + float s0 = equidistancePoint(q, fq, p, fp); + float s1 = equidistancePoint(p, fp, q, fq); + ASSERT_LT(std::abs(s0 - s1), tol); + + // Check that the distance from s0 to p and q is indeed equal + float dp = squarePixelBorderDistance(s0, p, fp); + float dq = squarePixelBorderDistance(s0, q, fq); + ASSERT_LT(std::abs(dp - dq), tol) << "p: " << p << ", q: " << q << ", fp: " << fp << ", fq: " << fq; + } + } + } + } +} + +TEST(testPixelBorderDistance, equidistantPointInfCases) { + const float pixelTestDistance{1e6}; // Pick a very high pixel index + // With one of the cells at +INF, the intersection will always be +- INF on the side of that cell + // Here the intersection is at the left = -INF + EXPECT_FLOAT_EQ(equidistancePoint(-pixelTestDistance, INF, pixelTestDistance, std::numeric_limits::max()), -INF); + EXPECT_FLOAT_EQ(equidistancePoint(-pixelTestDistance, INF, pixelTestDistance, 0.0F), -INF); + EXPECT_FLOAT_EQ(equidistancePoint(-pixelTestDistance, INF, pixelTestDistance, std::numeric_limits::lowest()), -INF); + EXPECT_FLOAT_EQ(equidistancePoint(-pixelTestDistance, INF, pixelTestDistance, -INF), -INF); + // Here the intersection is at the right = +INF + EXPECT_FLOAT_EQ(equidistancePoint(-pixelTestDistance, std::numeric_limits::max(), pixelTestDistance, INF), INF); + EXPECT_FLOAT_EQ(equidistancePoint(-pixelTestDistance, 0.0F, pixelTestDistance, INF), INF); + EXPECT_FLOAT_EQ(equidistancePoint(-pixelTestDistance, std::numeric_limits::lowest(), pixelTestDistance, INF), INF); + EXPECT_FLOAT_EQ(equidistancePoint(-pixelTestDistance, -INF, pixelTestDistance, INF), INF); + // Except when both are infinite, then the intersection is in the middle + EXPECT_FLOAT_EQ(equidistancePoint(-pixelTestDistance, INF, pixelTestDistance, INF), 0.0F); + EXPECT_FLOAT_EQ( + equidistancePoint(-pixelTestDistance, std::numeric_limits::max(), pixelTestDistance, std::numeric_limits::max()), 0.0F); + EXPECT_FLOAT_EQ( + equidistancePoint(-pixelTestDistance, std::numeric_limits::lowest(), pixelTestDistance, std::numeric_limits::lowest()), + 0.0F); + EXPECT_FLOAT_EQ(equidistancePoint(-pixelTestDistance, -INF, pixelTestDistance, -INF), 0.0F); +} diff --git a/grid_map_sdf/test/testSignedDistance2d.cpp b/grid_map_sdf/test/testSignedDistance2d.cpp new file mode 100644 index 000000000..621f96c17 --- /dev/null +++ b/grid_map_sdf/test/testSignedDistance2d.cpp @@ -0,0 +1,112 @@ +/* + * testSignedDistance2d.cpp + * + * Created on: Jul 10, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#include + +#include "grid_map_sdf/PixelBorderDistance.hpp" +#include "grid_map_sdf/SignedDistance2d.hpp" + +#include "naiveSignedDistance.hpp" + +using namespace grid_map; +using namespace signed_distance_field; + +TEST(testSignedDistance2d, signedDistance2d_noObstacles) { + const int n = 3; + const int m = 4; + const float resolution = 0.1; + const Matrix map = Matrix::Ones(n, m); + + const auto occupancy = occupancyAtHeight(map, 2.0); + const auto signedDistance = signedDistanceFromOccupancy(occupancy, resolution); + + ASSERT_TRUE((signedDistance.array() == INF).all()); +} + +TEST(testSignedDistance2d, signedDistance2d_allObstacles) { + const int n = 3; + const int m = 4; + const float resolution = 0.1; + const Matrix map = Matrix::Ones(n, m); + + const auto occupancy = occupancyAtHeight(map, 0.0); + const auto signedDistance = signedDistanceFromOccupancy(occupancy, resolution); + + ASSERT_TRUE((signedDistance.array() == -INF).all()); +} + +TEST(testSignedDistance2d, signedDistance2d_mixed) { + const int n = 2; + const int m = 3; + const float resolution = 1.0; + Matrix map(n, m); + map << 0.0, 1.0, 1.0, 0.0, 0.0, 1.0; + const auto occupancy = occupancyAtHeight(map, 0.5); + + const auto naiveSignedDistance = naiveSignedDistanceFromOccupancy(occupancy, resolution); + const auto signedDistance = signedDistanceFromOccupancy(occupancy, resolution); + ASSERT_TRUE(isEqualSdf(signedDistance, naiveSignedDistance, 1e-4)); +} + +TEST(testSignedDistance2d, signedDistance2d_oneObstacle) { + const int n = 20; + const int m = 30; + const float resolution = 0.1; + Matrix map = Matrix::Zero(n, m); + map(n / 2, m / 2) = 1.0; + const auto occupancy = occupancyAtHeight(map, 0.5); + + const auto naiveSignedDistance = naiveSignedDistanceFromOccupancy(occupancy, resolution); + const auto signedDistance = signedDistanceFromOccupancy(occupancy, resolution); + ASSERT_TRUE(isEqualSdf(signedDistance, naiveSignedDistance, 1e-4)); +} + +TEST(testSignedDistance2d, signedDistance2d_oneFreeSpace) { + const int n = 20; + const int m = 30; + const float resolution = 0.1; + Matrix map = Matrix::Ones(n, m); + map(n / 2, m / 2) = 0.0; + + const auto occupancy = occupancyAtHeight(map, 0.5); + + const auto naiveSignedDistance = naiveSignedDistanceFromOccupancy(occupancy, resolution); + const auto signedDistance = signedDistanceFromOccupancy(occupancy, resolution); + ASSERT_TRUE(isEqualSdf(signedDistance, naiveSignedDistance, 1e-4)); +} + +TEST(testSignedDistance2d, signedDistance2d_debugcase) { + const int n = 3; + const int m = 3; + const float resolution = 1.0; + Matrix map(n, m); + map << 1.0, 1.0, 1.0, 0.0, 1.0, 1.0, 1.0, 1.0, 0.0; + + const auto occupancy = occupancyAtHeight(map, 0.5); + + const auto naiveSignedDistance = naiveSignedDistanceFromOccupancy(occupancy, resolution); + const auto signedDistance = signedDistanceFromOccupancy(occupancy, resolution); + ASSERT_TRUE(isEqualSdf(signedDistance, naiveSignedDistance, 1e-4)); +} + +TEST(testSignedDistance2d, signedDistance2d_random) { + const int n = 20; + const int m = 30; + const float resolution = 1.0; + Matrix map = Matrix::Random(n, m); // random [-1.0, 1.0] + + // Check at different heights, resulting in different levels of sparsity. + float heightStep = 0.1; + for (float height = -1.0 - heightStep; height < 1.0 + heightStep; height += heightStep) { + const auto occupancy = occupancyAtHeight(map, height); + + const auto naiveSignedDistance = naiveSignedDistanceFromOccupancy(occupancy, resolution); + const auto signedDistance = signedDistanceFromOccupancy(occupancy, resolution); + ASSERT_TRUE(isEqualSdf(signedDistance, naiveSignedDistance, 1e-4)) << "height: " << height; + } +} \ No newline at end of file diff --git a/grid_map_sdf/test/testSignedDistance3d.cpp b/grid_map_sdf/test/testSignedDistance3d.cpp new file mode 100644 index 000000000..49219e890 --- /dev/null +++ b/grid_map_sdf/test/testSignedDistance3d.cpp @@ -0,0 +1,193 @@ +/* + * testSignedDistance3d.cpp + * + * Created on: Aug 10, 2020 + * Author: Ruben Grandia + * Institute: ETH Zurich + */ + +#include + +#include "grid_map_sdf/PixelBorderDistance.hpp" +#include "grid_map_sdf/SignedDistance2d.hpp" +#include "grid_map_sdf/SignedDistanceField.hpp" + +#include "naiveSignedDistance.hpp" + +using namespace grid_map; +using namespace signed_distance_field; + +TEST(testSignedDistance3d, flatTerrain) { + const int n = 3; + const int m = 4; + const float resolution = 0.1; + const float terrainHeight = 0.5; + const Matrix map = Matrix::Constant(n, m, terrainHeight); + const float minHeight = map.minCoeff(); + const float maxHeight = map.maxCoeff(); + + const float testHeightAboveTerrain = 3.0; + const auto naiveSignedDistanceAbove = naiveSignedDistanceAtHeight(map, testHeightAboveTerrain, resolution); + const auto signedDistanceAbove = signedDistanceAtHeight(map, testHeightAboveTerrain, resolution, minHeight, maxHeight); + ASSERT_TRUE(isEqualSdf(signedDistanceAbove, naiveSignedDistanceAbove, 1e-4)); + + const float testHeightBelowTerrain = -3.0; + const auto naiveSignedDistanceBelow = naiveSignedDistanceAtHeight(map, testHeightBelowTerrain, resolution); + const auto signedDistanceBelow = signedDistanceAtHeight(map, testHeightBelowTerrain, resolution, minHeight, maxHeight); + ASSERT_TRUE(isEqualSdf(signedDistanceBelow, naiveSignedDistanceBelow, 1e-4)); +} + +TEST(testSignedDistance3d, randomTerrain) { + const int n = 20; + const int m = 30; + const float resolution = 0.1; + Matrix map = Matrix::Random(n, m); // random [-1.0, 1.0] + const float minHeight = map.minCoeff(); + const float maxHeight = map.maxCoeff(); + + // Check at different heights, resulting in different levels of sparsity. + float heightStep = 0.1; + for (float height = -1.0 - heightStep; height < 1.0 + heightStep; height += heightStep) { + const auto naiveSignedDistance = naiveSignedDistanceAtHeight(map, height, resolution); + const auto signedDistance = signedDistanceAtHeight(map, height, resolution, minHeight, maxHeight); + + ASSERT_TRUE(isEqualSdf(signedDistance, naiveSignedDistance, 1e-4)) << "height: " << height; + } +} + +TEST(testSignedDistance3d, randomTerrainInterpolation) { + const int n = 20; + const int m = 30; + const float resolution = 0.1; + GridMap map; + map.setGeometry({n * resolution, m * resolution}, resolution); + map.add("elevation"); + map.get("elevation").setRandom(); // random [-1.0, 1.0] + const Matrix mapData = map.get("elevation"); + const float minHeight = mapData.minCoeff(); + const float maxHeight = mapData.maxCoeff(); + + SignedDistanceField sdf(map, "elevation", minHeight, maxHeight); + + // Check at different heights/ + for (float height = minHeight; height < maxHeight; height += resolution) { + const auto naiveSignedDistance = naiveSignedDistanceAtHeight(mapData, height, resolution); + + for (int i = 0; i < mapData.rows(); ++i) { + for (int j = 0; j < mapData.rows(); ++j) { + Position position2d; + map.getPosition({i, j}, position2d); + + const auto sdfValue = sdf.value({position2d.x(), position2d.y(), height}); + const auto sdfCheck = naiveSignedDistance(i, j); + ASSERT_LT(std::abs(sdfValue - sdfCheck), 1e-4); + } + } + } +} + +TEST(testSignedDistance3d, randomTerrainDerivative) { + const int n = 10; + const int m = 20; + const float resolution = 0.1; + GridMap map; + map.setGeometry({n * resolution, m * resolution}, resolution); + map.add("elevation"); + map.get("elevation").setRandom(); // random [-1.0, 1.0] + const Matrix mapData = map.get("elevation"); + const float minHeight = mapData.minCoeff(); + const float maxHeight = mapData.maxCoeff(); + + SignedDistanceField sdf(map, "elevation", minHeight, maxHeight); + + // Check at different heights/ + int numLayers = (maxHeight - minHeight) / resolution; + for (int k = 0; k <= numLayers; ++k) { + const float height = minHeight + k * resolution; + const auto naiveSignedDistance = naiveSignedDistanceAtHeight(mapData, height, resolution); + const auto naiveSignedDistanceNext = naiveSignedDistanceAtHeight(mapData, height + resolution, resolution); + const auto naiveSignedDistancePrevious = naiveSignedDistanceAtHeight(mapData, height - resolution, resolution); + + for (int i = 0; i < mapData.rows(); ++i) { + for (int j = 0; j < mapData.rows(); ++j) { + Position position2d; + map.getPosition({i, j}, position2d); + const auto sdfderivative = sdf.valueAndDerivative(Position3{position2d.x(), position2d.y(), height}); + const auto sdfCheck = naiveSignedDistance(i, j); + ASSERT_LT(std::abs(sdfderivative.first - sdfCheck), 1e-4); + + // Check finite difference + float dx = 0.0; + if (i > 0) { + if (i + 1 < mapData.rows()) { + dx = (naiveSignedDistance(i + 1, j) - naiveSignedDistance(i - 1, j)) / (-2.0 * resolution); + } else { + dx = (naiveSignedDistance(i, j) - naiveSignedDistance(i - 1, j)) / (-resolution); + } + } else { + dx = (naiveSignedDistance(i + 1, j) - naiveSignedDistance(i, j)) / (-resolution); + } + ASSERT_LT(std::abs(dx - sdfderivative.second.x()), 1e-4); + + float dy = 0.0; + if (j > 0) { + if (j + 1 < mapData.cols()) { + dy = (naiveSignedDistance(i, j + 1) - naiveSignedDistance(i, j - 1)) / (-2.0 * resolution); + } else { + dy = (naiveSignedDistance(i, j) - naiveSignedDistance(i, j - 1)) / (-resolution); + } + } else { + dy = (naiveSignedDistance(i, j + 1) - naiveSignedDistance(i, j)) / (-resolution); + } + ASSERT_LT(std::abs(dy - sdfderivative.second.y()), 1e-4); + + float dz = 0.0; + if (k > 0) { + if (k < numLayers) { + dz = (naiveSignedDistanceNext(i, j) - naiveSignedDistancePrevious(i, j)) / (2.0 * resolution); + } else { + dz = (naiveSignedDistance(i, j) - naiveSignedDistancePrevious(i, j)) / (resolution); + } + } else { + dz = (naiveSignedDistanceNext(i, j) - naiveSignedDistance(i, j)) / (resolution); + } + ASSERT_LT(std::abs(dz - sdfderivative.second.z()), 1e-4); + } + } + } +} + +TEST(testSignedDistance3d, extrapolation) { + const int n = 20; + const int m = 30; + const float resolution = 0.1; + const float h = 0.5; + GridMap map; + map.setGeometry({n * resolution, m * resolution}, resolution); + map.add("elevation"); + map.get("elevation").setConstant(h); // random [-1.0, 1.0] + const Matrix mapData = map.get("elevation"); + const float minHeight = h - resolution; + const float maxHeight = h + resolution; + + SignedDistanceField sdf(map, "elevation", minHeight, maxHeight); + + // Check at different heights/ + for (float height = h - 1.0; height < h + 1.0; height += resolution) { + const auto naiveSignedDistance = naiveSignedDistanceAtHeight(mapData, height, resolution); + + for (int i = 0; i < mapData.rows(); ++i) { + for (int j = 0; j < mapData.rows(); ++j) { + Position position2d; + map.getPosition({i, j}, position2d); + + const auto sdfValueAndDerivative = sdf.valueAndDerivative({position2d.x(), position2d.y(), height}); + const auto sdfCheck = naiveSignedDistance(i, j); + ASSERT_LT(std::abs(sdfValueAndDerivative.first - sdfCheck), 1e-4); + + // Constant terrain, derivative should be up everywhere + ASSERT_LT((sdfValueAndDerivative.second - SignedDistanceField::Derivative3::UnitZ()).norm(), 1e-4); + } + } + } +} \ No newline at end of file