From 99662d6d47a5be42494772b856751e24a3d84fec Mon Sep 17 00:00:00 2001 From: duongtd Date: Wed, 14 Jan 2026 15:04:54 +0700 Subject: [PATCH] first commit --- .gitignore | 4 + CHANGELOG.rst | 124 ++ CMakeLists.txt | 187 +++ cmake/grid_map_core-extras.cmake | 17 + doc/grid_map_conventions.pdf | Bin 0 -> 39725 bytes doc/grid_map_conventions.png | Bin 0 -> 71905 bytes doc/grid_map_layers.pdf | Bin 0 -> 64245 bytes doc/grid_map_layers.png | Bin 0 -> 69502 bytes doc/interpolationGaussWorld.gif | Bin 0 -> 363743 bytes doc/interpolationSineWorld.gif | Bin 0 -> 520702 bytes doc/iterators/circle_iterator.gif | Bin 0 -> 38534 bytes doc/iterators/circle_iterator_preview.gif | Bin 0 -> 20228 bytes doc/iterators/ellipse_iterator.gif | Bin 0 -> 30436 bytes doc/iterators/ellipse_iterator_preview.gif | Bin 0 -> 12485 bytes doc/iterators/grid_map_iterator.gif | Bin 0 -> 77741 bytes doc/iterators/grid_map_iterator_preview.gif | Bin 0 -> 20068 bytes doc/iterators/line_iterator.gif | Bin 0 -> 38873 bytes doc/iterators/line_iterator_preview.gif | Bin 0 -> 10436 bytes doc/iterators/polygon_iterator.gif | Bin 0 -> 88369 bytes doc/iterators/polygon_iterator_preview.gif | Bin 0 -> 20229 bytes doc/iterators/spiral_iterator.gif | Bin 0 -> 44166 bytes doc/iterators/spiral_iterator_preview.gif | Bin 0 -> 15920 bytes doc/iterators/submap_iterator.gif | Bin 0 -> 27314 bytes doc/iterators/submap_iterator_preview.gif | Bin 0 -> 10235 bytes doc/move_method.gif | Bin 0 -> 57693 bytes doc/setposition_method.gif | Bin 0 -> 256424 bytes include/grid_map_core/BufferRegion.hpp | 63 + include/grid_map_core/CubicInterpolation.hpp | 345 ++++++ include/grid_map_core/GridMap.hpp | 589 ++++++++++ include/grid_map_core/GridMapMath.hpp | 344 ++++++ include/grid_map_core/Polygon.hpp | 249 ++++ include/grid_map_core/SubmapGeometry.hpp | 73 ++ include/grid_map_core/TypeDefs.hpp | 47 + .../eigen_plugins/DenseBasePlugin.hpp | 32 + .../grid_map_core/eigen_plugins/Functors.hpp | 28 + .../eigen_plugins/FunctorsPlugin.hpp | 59 + include/grid_map_core/grid_map_core.hpp | 18 + include/grid_map_core/gtest_eigen.hpp | 165 +++ .../iterators/CircleIterator.hpp | 101 ++ .../iterators/EllipseIterator.hpp | 110 ++ .../iterators/GridMapIterator.hpp | 105 ++ .../grid_map_core/iterators/LineIterator.hpp | 126 ++ .../iterators/PolygonIterator.hpp | 91 ++ .../iterators/SlidingWindowIterator.hpp | 95 ++ .../iterators/SpiralIterator.hpp | 109 ++ .../iterators/SubmapIterator.hpp | 119 ++ include/grid_map_core/iterators/iterators.hpp | 18 + include/grid_map_core/utils/testing.hpp | 37 + package.xml | 17 + src/BufferRegion.cpp | 56 + src/CubicInterpolation.cpp | 436 +++++++ src/GridMap.cpp | 891 ++++++++++++++ src/GridMapMath.cpp | 600 ++++++++++ src/Polygon.cpp | 352 ++++++ src/SubmapGeometry.cpp | 59 + src/iterators/CircleIterator.cpp | 88 ++ src/iterators/EllipseIterator.cpp | 100 ++ src/iterators/GridMapIterator.cpp | 75 ++ src/iterators/LineIterator.cpp | 138 +++ src/iterators/PolygonIterator.cpp | 88 ++ src/iterators/SlidingWindowIterator.cpp | 117 ++ src/iterators/SpiralIterator.cpp | 110 ++ src/iterators/SubmapIterator.cpp | 84 ++ test/CubicConvolutionInterpolationTest.cpp | 130 +++ test/CubicInterpolationTest.cpp | 126 ++ test/EigenPluginsTest.cpp | 115 ++ test/EllipseIteratorTest.cpp | 55 + test/GridMapIteratorTest.cpp | 59 + test/GridMapMathTest.cpp | 1039 +++++++++++++++++ test/GridMapTest.cpp | 496 ++++++++ test/LineIteratorTest.cpp | 178 +++ test/PolygonIteratorTest.cpp | 196 ++++ test/PolygonTest.cpp | 268 +++++ test/SlidingWindowIteratorTest.cpp | 153 +++ test/SpiralIteratorTest.cpp | 36 + test/SubmapIteratorTest.cpp | 267 +++++ test/test_grid_map_core.cpp | 18 + test/test_helpers.cpp | 232 ++++ test/test_helpers.hpp | 96 ++ 79 files changed, 9930 insertions(+) create mode 100644 .gitignore create mode 100644 CHANGELOG.rst create mode 100644 CMakeLists.txt create mode 100644 cmake/grid_map_core-extras.cmake create mode 100644 doc/grid_map_conventions.pdf create mode 100644 doc/grid_map_conventions.png create mode 100644 doc/grid_map_layers.pdf create mode 100644 doc/grid_map_layers.png create mode 100644 doc/interpolationGaussWorld.gif create mode 100644 doc/interpolationSineWorld.gif create mode 100644 doc/iterators/circle_iterator.gif create mode 100644 doc/iterators/circle_iterator_preview.gif create mode 100644 doc/iterators/ellipse_iterator.gif create mode 100644 doc/iterators/ellipse_iterator_preview.gif create mode 100644 doc/iterators/grid_map_iterator.gif create mode 100644 doc/iterators/grid_map_iterator_preview.gif create mode 100644 doc/iterators/line_iterator.gif create mode 100644 doc/iterators/line_iterator_preview.gif create mode 100644 doc/iterators/polygon_iterator.gif create mode 100644 doc/iterators/polygon_iterator_preview.gif create mode 100644 doc/iterators/spiral_iterator.gif create mode 100644 doc/iterators/spiral_iterator_preview.gif create mode 100644 doc/iterators/submap_iterator.gif create mode 100644 doc/iterators/submap_iterator_preview.gif create mode 100644 doc/move_method.gif create mode 100644 doc/setposition_method.gif create mode 100644 include/grid_map_core/BufferRegion.hpp create mode 100644 include/grid_map_core/CubicInterpolation.hpp create mode 100644 include/grid_map_core/GridMap.hpp create mode 100644 include/grid_map_core/GridMapMath.hpp create mode 100644 include/grid_map_core/Polygon.hpp create mode 100644 include/grid_map_core/SubmapGeometry.hpp create mode 100644 include/grid_map_core/TypeDefs.hpp create mode 100644 include/grid_map_core/eigen_plugins/DenseBasePlugin.hpp create mode 100644 include/grid_map_core/eigen_plugins/Functors.hpp create mode 100644 include/grid_map_core/eigen_plugins/FunctorsPlugin.hpp create mode 100644 include/grid_map_core/grid_map_core.hpp create mode 100644 include/grid_map_core/gtest_eigen.hpp create mode 100644 include/grid_map_core/iterators/CircleIterator.hpp create mode 100644 include/grid_map_core/iterators/EllipseIterator.hpp create mode 100644 include/grid_map_core/iterators/GridMapIterator.hpp create mode 100644 include/grid_map_core/iterators/LineIterator.hpp create mode 100644 include/grid_map_core/iterators/PolygonIterator.hpp create mode 100644 include/grid_map_core/iterators/SlidingWindowIterator.hpp create mode 100644 include/grid_map_core/iterators/SpiralIterator.hpp create mode 100644 include/grid_map_core/iterators/SubmapIterator.hpp create mode 100644 include/grid_map_core/iterators/iterators.hpp create mode 100644 include/grid_map_core/utils/testing.hpp create mode 100644 package.xml create mode 100644 src/BufferRegion.cpp create mode 100644 src/CubicInterpolation.cpp create mode 100644 src/GridMap.cpp create mode 100644 src/GridMapMath.cpp create mode 100644 src/Polygon.cpp create mode 100644 src/SubmapGeometry.cpp create mode 100644 src/iterators/CircleIterator.cpp create mode 100644 src/iterators/EllipseIterator.cpp create mode 100644 src/iterators/GridMapIterator.cpp create mode 100644 src/iterators/LineIterator.cpp create mode 100644 src/iterators/PolygonIterator.cpp create mode 100644 src/iterators/SlidingWindowIterator.cpp create mode 100644 src/iterators/SpiralIterator.cpp create mode 100644 src/iterators/SubmapIterator.cpp create mode 100644 test/CubicConvolutionInterpolationTest.cpp create mode 100644 test/CubicInterpolationTest.cpp create mode 100644 test/EigenPluginsTest.cpp create mode 100644 test/EllipseIteratorTest.cpp create mode 100644 test/GridMapIteratorTest.cpp create mode 100644 test/GridMapMathTest.cpp create mode 100644 test/GridMapTest.cpp create mode 100644 test/LineIteratorTest.cpp create mode 100644 test/PolygonIteratorTest.cpp create mode 100644 test/PolygonTest.cpp create mode 100644 test/SlidingWindowIteratorTest.cpp create mode 100644 test/SpiralIteratorTest.cpp create mode 100644 test/SubmapIteratorTest.cpp create mode 100644 test/test_grid_map_core.cpp create mode 100644 test/test_helpers.cpp create mode 100644 test/test_helpers.hpp diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..64c5965 --- /dev/null +++ b/.gitignore @@ -0,0 +1,4 @@ +# Bỏ qua thư mục build/ +build/ + +CODE_REVIEW.md \ No newline at end of file diff --git a/CHANGELOG.rst b/CHANGELOG.rst new file mode 100644 index 0000000..7a4acae --- /dev/null +++ b/CHANGELOG.rst @@ -0,0 +1,124 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package grid_map_core +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.7.0 (2022-03-17) +------------------ + +1.6.4 (2020-12-04) +------------------ + +1.6.2 (2019-10-14) +------------------ +* Implements a grid map transformation from one map frame to another map frame given the transform between the frames. + Authors: + Co-authored-by: fabianje +* Contributors: fabianje + +1.6.1 (2019-02-27) +------------------ +* Updated host changes. +* Updated author e-mail address. +* Contributors: Peter Fankhauser, Péter Fankhauser + +1.6.0 (2017-11-24) +------------------ +* Added new sliding window iterator. +* Added new `thickenLine()`, triangulation, and bounding box method to polygon. +* Added unit tests for LineIterator with using move function. +* Fixed cpp-check warnings and errors. +* Fixed line iterator for moved maps (`#119 `_). +* Fixed error in SpiralIterator when center is outside the map (`#114 `_). +* Contributors: Péter Fankhauser, 2scholz, Remo Diethelm, Takahiro Miki, Tanja Baumann + +1.5.2 (2017-07-25) +------------------ + +1.5.1 (2017-07-25) +------------------ + +1.5.0 (2017-07-18) +------------------ +* Added new function for polygon triangulation. +* Added Eigen macro for bit-alignment (`#88 `_). +* Added default copy constructor and assign operator methods after the rule of five. +* Fixing return value in `getQuadrant` member function. +* Fixing buffer handling bug for circular and ellipse iterators. +* Capture case when both circles are the same in `convexHullOfTwoCircles`. +* Fixing build error on ROS Kinetic. +* Contributors: Peter Fankhauser, Sascha, Thomas Emter, Martin Wermelinger + +1.4.2 (2017-01-24) +------------------ +* Added linear interpolation method for data access. +* Increased efficiency for linear interpolation method. +* Addressing C++ compiler warnings. +* Contributors: Dominic Jud, Peter Fankhauser, Horatiu George Todoran + +1.4.1 (2016-10-23) +------------------ +* Improved line iterator with start and end positions. +* Added method to retrieve submap size for iterators. +* Improved transformation of images to color grid map layers. +* Fixing issues with order of include with Eigen (`#67 `_). +* Contributors: Peter Fankhauser, Dominic Jud + +1.4.0 (2016-08-22) +------------------ +* Added convenience function to convert a grid map to form with circular buffer at (0,0). +* Contributors: Peter Fankhauser + +1.3.3 (2016-05-10) +------------------ +* Release for ROS Kinetic. +* Contributors: Peter Fankhauser + +1.3.2 (2016-05-10) +------------------ + +1.3.1 (2016-05-10) +------------------ +* Cleanup up Eigen types as preparation for ROS Kinetic release. +* Contributors: Peter Fankhauser + +1.3.0 (2016-04-26) +------------------ +* Made the `isInside` checks `const`. +* Fixes polygon iterator bug when using moved maps. +* Added unit test for polygon iterator on a moved map. +* Added comment about size of the returning submap. +* Reduced test build warning. +* Contributors: Peter Fankhauser, Martin Wermelinger, Marcus Liebhardt + +1.2.0 (2016-03-03) +------------------ +* Improved efficiency for the Grid Map iterator (speed increase of 10x for large maps) (`#45 `_). +* New iterator_benchmark demo to exemplify the usage of the iterators and their computational performance (`#45 `_). +* Added new method to set the position of a grid map (`#42 `_). +* Added new move_demo to illustrate the difference between the `move` and `setPosition` method. +* Fixed behavior of checkIfPositionWithinMap() in edge cases (`#41 `_). +* Updated documentation for spiral and ellipse iterator, and iterator performance. +* const correctness for grid's getSubmap. +* Cleanup of arguments and return types. +* Contributors: Péter Fankhauser, Christos Zalidis, Daniel Stonier + +1.1.3 (2016-01-11) +------------------ + +1.1.2 (2016-01-11) +------------------ +* Should fix errors on build server regarding Eigen3 and visualization_msgs dependencies. + +1.1.1 (2016-01-11) +------------------ +* Changes to CMakeLists.txt to enable compatibility with Ubuntu Saucy. + +1.1.0 (2016-01-08) +------------------- +* added installation instructions in CMakeLists +* new ellipse iterator tool +* general improvements and bugfixes + +1.0.0 (2015-11-20) +------------------- +* release for Springer ROS Book Chapter diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..238f7ba --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,187 @@ +cmake_minimum_required(VERSION 3.0.2) +project(grid_map_core VERSION 1.0.0 LANGUAGES CXX) + +# ======================================================== +# Detect Catkin or Standalone +# ======================================================== +if(DEFINED CATKIN_DEVEL_PREFIX OR DEFINED CATKIN_TOPLEVEL) + set(BUILDING_WITH_CATKIN TRUE) + message(STATUS "Building grid_map_core with Catkin") +else() + set(BUILDING_WITH_CATKIN FALSE) + message(STATUS "Building grid_map_core with Standalone CMake") +endif() + +# ======================================================== +# C++ Standard +# ======================================================== +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD_REQUIRED ON) +set(CMAKE_CXX_EXTENSIONS OFF) + +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + +# ======================================================== +# Compiler warnings +# ======================================================== +add_compile_options(-Wall -Wextra -Wpedantic) + +# ======================================================== +# Eigen +# ======================================================== +find_package(Eigen3 QUIET) +if(NOT EIGEN3_FOUND) + find_package(PkgConfig REQUIRED) + pkg_check_modules(EIGEN3 REQUIRED eigen3) + set(EIGEN3_INCLUDE_DIR ${EIGEN3_INCLUDE_DIRS}) +endif() + +# ======================================================== +# Extras +# ======================================================== +include(cmake/${PROJECT_NAME}-extras.cmake) + +# ======================================================== +# Dependencies +# ======================================================== +if(BUILDING_WITH_CATKIN) + + find_package(catkin REQUIRED) + + catkin_package( + INCLUDE_DIRS + include + ${EIGEN3_INCLUDE_DIR} + LIBRARIES + ${PROJECT_NAME} + CATKIN_DEPENDS + DEPENDS + CFG_EXTRAS + ${PROJECT_NAME}-extras.cmake + ) + + include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} + ) + +else() + + # Standalone build settings + set(CMAKE_POSITION_INDEPENDENT_CODE ON) + + # RPATH (quan trọng cho plugin / shared lib) + set(CMAKE_BUILD_RPATH_USE_ORIGIN TRUE) + set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) + set(CMAKE_BUILD_RPATH "${CMAKE_BINARY_DIR}") + +endif() + +# ======================================================== +# Library +# ======================================================== +add_library(${PROJECT_NAME} SHARED + src/GridMap.cpp + src/GridMapMath.cpp + src/SubmapGeometry.cpp + src/BufferRegion.cpp + src/Polygon.cpp + src/CubicInterpolation.cpp + src/iterators/GridMapIterator.cpp + src/iterators/SubmapIterator.cpp + src/iterators/CircleIterator.cpp + src/iterators/EllipseIterator.cpp + src/iterators/SpiralIterator.cpp + src/iterators/PolygonIterator.cpp + src/iterators/LineIterator.cpp + src/iterators/SlidingWindowIterator.cpp +) + +# ======================================================== +# Includes +# ======================================================== +target_include_directories(${PROJECT_NAME} + PUBLIC + $ + $ + ${EIGEN3_INCLUDE_DIR} +) + +# ======================================================== +# Link libraries +# ======================================================== +if(BUILDING_WITH_CATKIN) + + add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ) + + target_link_libraries(${PROJECT_NAME} + PUBLIC ${catkin_LIBRARIES} + ) + +else() + + set_target_properties(${PROJECT_NAME} PROPERTIES + LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR} + BUILD_RPATH "${CMAKE_BINARY_DIR}" + INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib" + ) + +endif() + +# ======================================================== +# Install +# ======================================================== +if(BUILDING_WITH_CATKIN) + + install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + + install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.hpp" + ) + + install(DIRECTORY doc + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + ) + +else() + + install(TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME}-targets + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + ) + + install(EXPORT ${PROJECT_NAME}-targets + FILE ${PROJECT_NAME}-targets.cmake + NAMESPACE ${PROJECT_NAME}:: + DESTINATION lib/cmake/${PROJECT_NAME} + ) + + install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION include + FILES_MATCHING PATTERN "*.hpp" + ) + + install(DIRECTORY doc + DESTINATION share/${PROJECT_NAME} + ) + + message(STATUS "=================================") + message(STATUS "Project: ${PROJECT_NAME}") + message(STATUS "Version: ${PROJECT_VERSION}") + message(STATUS "C++ Standard: ${CMAKE_CXX_STANDARD}") + message(STATUS "Library: ${PROJECT_NAME}") + message(STATUS "Eigen include: ${EIGEN3_INCLUDE_DIR}") + message(STATUS "=================================") + +endif() diff --git a/cmake/grid_map_core-extras.cmake b/cmake/grid_map_core-extras.cmake new file mode 100644 index 0000000..e63eae4 --- /dev/null +++ b/cmake/grid_map_core-extras.cmake @@ -0,0 +1,17 @@ +set(EIGEN_FUNCTORS_PLUGIN_PATH "grid_map_core/eigen_plugins/FunctorsPlugin.hpp") +if (EIGEN_FUNCTORS_PLUGIN) + if (NOT EIGEN_FUNCTORS_PLUGIN STREQUAL EIGEN_FUNCTORS_PLUGIN_PATH) + MESSAGE(FATAL_ERROR "EIGEN_FUNCTORS_PLUGIN already defined!") + endif () +else (EIGEN_FUNCTORS_PLUGIN) + add_definitions(-DEIGEN_FUNCTORS_PLUGIN=\"${EIGEN_FUNCTORS_PLUGIN_PATH}\") +endif (EIGEN_FUNCTORS_PLUGIN) + +set(EIGEN_DENSEBASE_PLUGIN_PATH "grid_map_core/eigen_plugins/DenseBasePlugin.hpp") +if (EIGEN_DENSEBASE_PLUGIN) + if (NOT EIGEN_DENSEBASE_PLUGIN STREQUAL EIGEN_DENSEBASE_PLUGIN_PATH) + MESSAGE(FATAL_ERROR "EIGEN_DENSEBASE_PLUGIN already defined!") + endif () +else (EIGEN_DENSEBASE_PLUGIN) + add_definitions(-DEIGEN_DENSEBASE_PLUGIN=\"${EIGEN_DENSEBASE_PLUGIN_PATH}\") +endif (EIGEN_DENSEBASE_PLUGIN) \ No newline at end of file diff --git a/doc/grid_map_conventions.pdf b/doc/grid_map_conventions.pdf new file mode 100644 index 0000000000000000000000000000000000000000..405588f3d34073c660cdd803049f8e2a75de816d GIT binary patch literal 39725 zcmbrm1ymi&wl0i&Ah-s1S-1svcXxMpC%6-wg==sR5Zv9}gL{DB67+}cowLuo_x$6& zao<>j)xD~#t7=xySzYt{=7daMSd@+tzzj#$yL+*FRCJj$+1n4tLdZa9XJ`q>%}q!z zZDMQYY);7fTBJxwFKS`!Y~uKOv^H=y5jHWhGd3aQ<%M%{b~G`tfpZ6~NE>qeE{YOz z>K=h&vh;;6pgyY=xg}wg8kEv2l7prZ| z`?sT->1oQ#b5l=E4wVKZOJ`}PzS={3QNd(viDJ#0T$iexH;mZpQ1b_rCis_2*nH8A zBlRiN9!R`CWxr0T2ho`L-Y|83GJR2Of>n$ zDpG*s5oR`@H-%_P9=;HlXpJoLEKzNRQM#Zkb&h^4xFsBHs_(%L0cN2pM%rrdAXU&e z%zIV0#Ncl2!4aKZO^b9CQIy4_@iku~JAuQ^HsCb=%Ce@KJ*Yd*ylABd|Ts(WsaFlh0bk#!8&8tS`44Y~vlQpiqLAv#*yg%lKb{HdQzkl}` z!(SSFLNSY~K0@S-A{)PENXC_|RG6}f{=CskRv)cWqF{rlshJ&Z1Ict&KSgw!7aUAE<(&Ljeg&&(Drn|(AM??L7A##%AD3K_sCjuCptpX2EDzkbUz(ePS1LthSKTLW)~fNB*`v8$ z5OCg4;y1sEGEeCIOh)4`Cl-@ZU;1l2+m*04`_VWckB0_wr^-8gWK#)-SVd_+lS948 z;Fq(l#Bma5YjfkT!zV5$47e(JG;@cBZ8Q)uSM%_?NVWsWUMm% zGwEpQA&>lXs_{r7k&ATrb)%i!a#Z_!$MT~t&)5i2$TV3WxL>w5`fB&}WWji&O-TWm z1m{7MQg9eJAwgHQf#J3T1G3ur7)Wx^KVx3N?ejPSC~-0_&pbMLg7*SD+tfjBdxiat zeu^Z`2@BY-iKBfZT&A3r|o3SBfooDmr>r26DLgys9`a`T=K({1mj;?U>$rr|*><3mF>7ng_# zrv1&$Ggj?~jEk~`(5e{3J*x9?W1+5H)VT{RnKb+-Gw6wS@7e8yV*fll_HFy2`barnZ?R=&_3;Bs;TWHvtxFo*WT^{S01D!XcN9=gRT7Bh zX$@P~$xczr2>agi#RRns1(Ywo2&DG=b+!g91bm=@+c*k;iYpDt=i6~~Y1KEbr z4=YvM`+_p;WW5rdsXX@y_t%?j5w$${PzpGd*#^ns5Lf}<(A{q}63xA^s4ZW3TJG%) z*4EZQx964!Fx|34a@B_%PhAkytQoko%Z*IYywJ+Bwq#EZdodGiC@P{%Z|}n>&o9)E zAJXafcq>+e**GnAOV_P&J+_mAQjBI)HjKLJ2SPN=0u9>^;bXd}yD!C}wuqMJq}^o7 zR}4weZDyc%d60d=D8?kJov7*&+xW7*G;^|C)z8|2JjaGO6_pddzm&IAPVc8e1TtSJ z{Uq-MVkD>EQAf9m9S5*OM}}xE%ny*OuG}-vB#PErsTm~|#jzNV&tlSpy9bq|-*PN! z_9IbYYi>SxmUs~0u3y6h;d~Q|usa>Eq$dyHvMHSN{WWWPRv<7Nf+pTWtToQKh!1`3 z?kMD%&nc=z*ARp{k&tZK95=eptipY=yd|kr+OGr>>! zpxI>&2yE1L(h;B^HQ;2kN z%;Xbwr%tF_#AA}Gjx_RlU)}8(mQV0IdFxJ$hhU#s1+p39SDn$af6K)jTV`bP4#JM% zk`PA$R}NK_(64w|`?+CzU$r4-s&|j@el8A`{4+lzR!O$8QVz|P6GuvSic-H=<(NY` zxQtuO+#+*RF949=jN9O3b1J;0O#&=2Hckhaz!zoq01I6au)eK37VG;2= zn-hGFOK_$5H_?Z2IQ24z1IZV{x8??afir^a75v;viRYUPLAEGnI#?@&*%Lndadt~( zK2ee@P8BSZ4F0uRG&-j?r;sO@Z@z?#xJh1$uwK$8dpaAHEPQkPF$!V}QD?P%*2&z{ z6<)=PqBW~8$B-vtN#$Gcvi9=Ru0nJHM*6!&HcJa{5k6sOijw*Uf>}bhYn)x-mz-YX z8rEdF5E_)x+g^NhgKB>hMz+z)%NZga^HO*FR86*i)6c;(qgMXMt8D1shD3NmQA-WI z@_aafGetW@jEvsj_7xPtWFphbr!M@z+hgE-=5oPDK{HpJORkPNaZ{RLHFrbxPG6T1 zKg!oKhk;LwkW>oYPok8BxoW7^F#mkiY#~>h9`*1J-ph2Oc3X<6E8rw4TasgRAbbMC zGRXQX4An)FFEQWRWcZGhq2R4LAGR-4H7d#+qFaT0pMd!k`2do&AU0vj;FMvS9E8hb zs5wkpEtm3XY31f;45XeQuCJfh8xfQTxFl|s7@XHPDJ#XY!y-r^X7_Q2<=RCUFTyL$ z&(EzQ9hNPWPa!?#C%_l*W<~mn}ft z-bd7xvrqpxR0Ho)2CvP0)u&B4i<}}X6j7X32w-D>tP>HJ(0bM`g+mPgbqI^C5TQg( zhCcvNvMe1b;$M=OqeD8?Jtn11!mh8EXm-a!om3)yW+_=riE~&K|5C_E6jfAY61)xr z%L74VqjX)zN=ClqUn0E&)!;J4aFU&FH%G5j>FLSv#Y9s~r%C60OzeV_y7014JB-VN z{z+WyM{dfGe$L@WFVTV0wHMGtjJ-=Z6Ig>E#W~et$cf*g6w3|K$`YnmF0HI2xHa5wiVNAY^Cj{CeGq@Xe8U^%`VMj4ccV z?c52q7+wolI2j0;*%)--ULA+O`+2+XkHaDFXlJBk;!LRZ+L^E@A-%GRyE7rZgw1Qm zf`1={{ys_&>JZWk*;(5;D%l$tnGnADD?(0;gzRtK!o8j{5i-8@sQBumy!tG!qxxM% zS(%xT@$a!KE3*?a{;vPplQJVABjfM-ujj0UjDI^l%F1kTjDLyt){eTIp{0q@UrkBa zFcNb7>ER!F-irRn^S1-V`FFd&XYo%H^hz#<&c923%STABW?}s5Y_TyA(uU`K zoSj~;3fbA%+u6R>h2!|2-MP6Wg~~t%1c>#gnCX~^wX+K2InAc7HFD50?;J^!6r!LV zj?W86*WSD@JKN{(c&GWn!LyHst}wO+argMO`J;RK+EMwzeNpe{h!zVKG0TjR0{f05 z7rD9Ol9zyA&6WyShT8p~MllL{j#t#jZ%p1tg1586k4!vEtc_~k1kK_@FVWFD_i9lOVMttKn$=-Qfp(^xjmi{V4K>+a;mru`{ygybrF|PxOWYjA zK2%4`hZ`yZJYK}^TxHNgV@hD>L&T<;-nIsTv&njlEx{&K9~~&QLZUAL7`Ibx0+wXN z?U8*x&ZqL!TP^BHs;%L5y>2x`9Jk5S5bJ%2ffKE?GMz-@w1sUtPOgaSkhSZcJ{pu= zu{<@0?rgO)y2w}7$;l+6Br%bxnKxVHdLBd<4Kv;MN|8%MjV3_hQY6jPv93m}0ldhE z^6C_8V*CIfTbiZOt=o@f#vkMzYdkLv#znE$=_7eS;*qRK`tPgLoB6z16dNxHh>VOS3&g*f(l4Qi#}`&kd-6W!8*t^C zudxFpMr6a$Jgze7gfbbcz=56Ty^}>HYo6o|V8Z_OV!X9aYXHeWFn~15@Py?8cx=UX`AM6vTLj>g}g;Z zj%2BYq_wbIoI|vxR-9s)#$j<8#%O^V#$;>_k_TK|bBK717N{jS2+Phkt2LY|JKjBx zZZq{V2`r2r?AJEbb4%Jp(>BxdV9e>vDSUNc3d-+gmHA8=!)M~X#m8QOyO_)5x_+ciD z6`T5l_(Q04`S2IPJ*@rZ?knMs9GtF(^0n7dV3R|duEngq^*B{{WqxHJ z4L^f&DksGKcYXY=Xm85L!t&4C^6g#oUlfw*@Arx9>&uc};0-*peO<;0|5h+XvDa7H z|AeV!Cc7ysEn$RCw6V8Mq7W03UEz4b5>9i8qeCc!OZdryg#?ki3PXybAycUuD|dp5 zg%TTypuqx2rz0hnY0wP?(un>76#bWnh(DeSiR_T`^ zBTZtD%x0Lo^u$#i!e<6dzbdn^g0-lM1|(6OH*j^IsiH>-fG(PdtO34=U&6 z#}iosQCS-6*2m@aZ5SXoq?+j;YTJ`kKfL#%b<`%icEcSZoVTeXKOa=N3NiWoNhHvjO+&EEnh;OsqmoJ;UCuCQ##>Ctq(s`@edTGhZB@I`}TEx0cblPbT*f!T+73PSE?QSdL8b0!XX@6oGmNLBNBQJ_@ zzX!jEP=VsRV%u5u(v;>*O}RE@w|C2)JFBB3nKD(ML5MJAWH0CWTD0kSFd zh(1X^7d|$EDRl97Df#DDtLBPs)^+m)ONgZ9B^ibprWuAC25zzTDUh|s`^Pt+$d&LP zR!@@^5a9^U6nIQG*2&a;TsB!|_#npq;1mvR?x7iYJ2SP`n5 zLH~|f5xXENA*v-R=8|QvX<~a~g{{g$_obC8=@+#vwRaM6l4%lXQcS6|irpOATxO|F zsoX4sCAp=6<&x#Y9H1wo*xM~X*lgT*f=UU zK$d=1>@?f7p|st!eU^bbb4~bq2+dv1{d!%7q|~3I%BEzsk({{|l_y1XQ@meR%Xlh` zifh%)@?~qsQFY=0TI>Q1+6_u>f^t&y>hyY53a7ce3fUFeUpmA(v_1`YP7*HbM+&5O z73W6eb{J$CxXDMTC8OW>tuAxybI-kSY!#(Jo?~(qC2A(HUJu(wx6+@5qgjR{}h?YQuN&`~e zrtU}eea~`lnw5@`&p?Rfwo&bP;p$#}MG4)yYsZNXSDH@sDn^TJ%ft=h4e)+ zMm)zjfH5FS&)q(ER%In=Tl46CRAwQ1-?i7KcXg3x>8bI721yDjPAqaDu_$35X98X~ z3|OTWr&iSve`|PZd0NE#kvE(-nisX*wY|)T{?6bD?8)_h^>X2C|9;^?4uS)s9QFY2 z3xp_yDl{)V6D$g(3q(&BXje-B0sXWdsrD=enBb$3YcMw~D}oOCy%QFImZhBh*rQR! z-Phd>g3eGxSg5x}JZ5luP%JVULkh!9bV#gEWKK**#7hJyA_Y{Z)u`POjna%FEabr; zz(w~Wb#*MconDm+-9Fxe+x`h))=sWHUUsbCEg6}pjMeMXaG=J=CHS!Z{v{l>yJT0o z@=CACZ5Lu8p(XSoe!rh)Kl)tf&g3x;0vPl)Xi6B^s}pV{Q7M5gu?;3CP`}~wRqw)o zrz9~pF`tULWU6G$BB<`JZbp#IAflQ^hna_>jlPE^pFya3*kbOd3ThtzRGc)WlZI(a z%I9b4Yw;-3bh1DV_*%=aYi435*~1E>$a_~iX*;$fABHZ69(-9%S>0UB+FhSR9=lk7 zS|L^h&sS=%G|9T@bTw~Yw;#pW5ZZ_@osEc&M4RBQ+eWO-D�sx9gkNp6>MvHVGn$}iWt^kR3r>+f0wj#FV$iBxPt!wzG{aPKp2|8&jxG8vW+i-<( z`@VYEe5sylsG++wS-GK8u{(N^chS(IcHFLNpyi;CWD#Q=Q^!>NwN0|hQf#j1$Cn@e zI5BB^Z9lvkPBNDVRu($eZ9dI_MuYc3^Wvl7wSF4BmA9%8u<0}SzFFQgag_I?xx?&} z-Y4M`@$C<)+@)SLf-;$NAckF9%Sbu8Mc4%Mwl)PQ>xgFAH|6b>Te(k2&XZQ0< zCN6j+)csFDyVr~Ecb-F^wWlfQ5+q%|QBRI1^CzR@?K}!NIqIxZzKW;0y9LvdwyWcu z1^tQIFteDDMj`r_q+eBXJ&+S66EvcAqCdnc#3rJCMXh?)T=kueL;+{EgFC36zuhKH zm1X<7J+zq_4)vZ{O&z83Nv;*QbKcM2*z6l0?98}XoE8>Etd+I%-S|J{J{VmM#2p^X z-N_|oNAtOP!#-ZPliQf?t=|S+KK%FX>hEpn+t!qcjgje(1N8M$|=hdu4z*vbFHo;Fxz-EKu0jW^s*@e2kYp}JUTL|>JPl2#KgPDMYI zL_)!dBu2sEA~osGNA~a%T4fx{_IeXp!`eVNaEZ?@1P95mTo%hB$Ps_OC`j; z4tkM@$WI_uHd|Z`DU^D(ukS}V*E#pO_H|c;dGsvm)38;-lFKSHCrFbLiZBwhWFn?( zXQjYr%MNAf;zq_$0A1*}<42nxB49>N;(k8M-jH;7Mt+|PCzk89MgQP~eTSehI&1Y! z3atbB;m)D~>iZ?$*$f*5SQ!}5Cj-TOYJh@AmWU7b^Ca~VdId}?6nE>QDSd;19yr!u z!lsHXZZolITx~_Xf#bv`eT+i`;|mfX-R0_7Cs6$%qoB#C5h;9)=0>?aoNuB23hzv+ zTCb`}!r&9+UCjNoH<&wt!c|GUkMr8Tn4Vq*+8Wdvq}P;v5xmTUr3<4M9#+lNHQ7MtvFVTO%y}3WQfgMVl_dhpm1!CZ@J~#sT)HuXR5mS1-H8Mvh|R9K*drK{ z{ZohJpDIi}&5)NDAzQLAmt(V6r;nYXusjy|T0he7LE)|F%qkjw%kLCB5Edqp#h^2s zE0N^-BA>;S*xM$`#!bdF7!=$yV!%i&H;rPw>cJVaJrET26|;>lPoaQopvt~us79Sn zX$ka^z_9k10oM%mOEvpq`Z0`D*T*hINH|BEkLc7hK9tv&t#U5P7$0TjFCO`QD8m%S zmril+$6}sC(yFCsu1Mr28CkSWPzj+?&0W~1d5f&9_>K{|hoM^T#!uRN zBnf#J-yrYkbkpW!>2uz5iEXi7G3M+#mt_z(S0SknwGYh`r4NM<{gZTrvqm%V6RA#8 zdmI3gv*olcn{3gmO3wgwHA2UH&MKRgLP>VmYX@^T@v-&sD>rU6T9Y1rLeWm!*)iIGEEXg(s7$DZe&xQPGG`2pmF$E8%9@Ksw%Cbg7qG5WYU=v3q>DeL7&*AWOHk5>yFGPZ4V^=d?2v)&@SS- zieU3oOE~nUo9jr`T&oz>=j8o$2hMWHnXLC7b6zC$b#vR+e!ln)RGiYs>h*^Yhf-Us z&J9!Uezz(U6vA8t>^Lu#>^NL{#4i|ACYO8~AP(;TVcB|HY2KD7Muvaf?B9^?e_OZS z)+t58f2~`8ZhV7;|3R*u{{OJ(H%Qgx6+dMpq?fWVc6tS$|8DOsy5$cT{_kNif3+!O z;A~)RXZ9B??(_!_S2b~Tvaquyq-O-M{M-G%;pDe*|1+lFkn}$wu<|Ro`&Ywni}7C< zWXCZR~ zM?&UT>_OV#?;otMKYqi^Z&I?dGW_|2`?vEyW&f+=zXSWf$MQ$!zmagJzai`Y3HQ*6 zm$B?&cprSr8=QPdte%Wo1ZqS{1xkM}G=tBd++UKL9DGdc{m>pK1E<5?Rg}t(W09Ek zV}IEtL43VOAHWj+&53Q2<9h(n)MUMrL}Ad$Xr1DB=C&INxJwg!iXT=Bh z{Zyldm&TzX`0l54>TsDY5n~I7C~g4u(@(_|?69fIN!7D?-y?6TnknK$kG_2ibDL=m zKBC`tx*?rJ##@?>$EJpz&${N_baYFx1QLPQkoL&RRerv4YZ~BLhg_((vj+udpkd6J7cVS>;)PbXy zc(ox5BLQ18Ym-+SrWbHBdSf!!Szh(@t*5sibWE)5uO@0>|A!S}enniBoK0+0-|mn$ zF)+5UHG^Yhe>GqAzpK2lO!NY-W`8j%Z@Nt{W8nU8zuxTVRRv9$2$}vcIRBFSKkzq9 zeshM`}+&5p!c;Bj^z)J6m5URtN5QEriUH2k|V})aH|IngIaDNjF6==$A%Hb`U4UsD^}3VRI?QD~gC6W<0fSDrH__;Rw>SA{QMWho=s@?QOiE19FZmRtAP>Ei z+aM3M6t^G`t(1iBRF{i+EHW!U6j45Zaj>= zSO(}|PQua1?pDH4UxORi8LB9)l>Oi(no)cMSNIvCD5(@z12h9y*vkwCuAn8rD4RhR z`X07H7RDZxK^EE`tid<9%SHyRpe5ST{BCO$(|m>)m|B69&|nYolA~-F2`|4Gc8F8bqTy-L#mdsSHxV8pNZ920!1M#xcMLYY>id8|=X` zi=`}ekD?Wdq^ty6pzNs{n8GmYq*!!+CmvNcD1>3wND(!_2`a%Xlugkzuna1}FpXzG z4NfJLPGVq(SE7niN=XmGrjQP1*zHb)QzDkGVG!y5PC2S>APUbcnF40u7&L^@Pb8hp zklKxaN-mU=+l_#1TFr3Sjeyb*kWOO&50*ghCzqClZjmrSiu*}?J?*F{0P|T{Gh&h{ zXstUA1^2UzKISChKxPqgZ^I#@$CUT+ zH5PDbFY!!ePJ>zGmhmq0aY<;3f8|G=%xMkYaq1k`35%zYxJ1s1IU}{e|IXb=P|zf< zQHGyBo1gljV5#vLPkTKoUnOljg=|%}Hb0$ZX{teTX-X-fNLgCew%lC2vZ`3BvZ7d` ztg>3gOhqbTnp{;lhL1zn691*o-9p<@L_`&mP7Y8uNSz-#d|-O5lcuexkfE(Sr7dhD z;_O6Z1NagOXQ4#of;Jtn^BB>(^F1PC=NK+jt9fpBS8tL^23XiMorj!N7~+K}5&c1z z7t-zos44Fg>Z~=;Ndzh0KIWn$?XNZ6c;73!UE&Y#B62MjRxIe%=-%k;)YQHE^{Bbm zoV~4gmmPrF^f9}S@m*#>w&Sm$kpb=J{#_CPf#WZ~kq7Oy?F#_VO?$J) zKDVJMW9I?`$llc2wF?1UXlm`>RRIh%wRZ1f0rRzW_Z)*pq_m%hcNu^}+K7&vox36c zdi$jb69S+tz*bG2jrxTf*rt7Bzcf}57#S(Wg&8~o0B|*N512p$Pqe=|cqET7YiI3U zpaChGxVv`gwZA!fWQVOSn6Lpgv`rl?HXXTuD~&8p7F&)qKy2+or_}yk41iLT^d?iP6bTRtaIO8L zan`Y9Q*q1$1sJYPZeOzH$P7H!rf%ZUAwoY`O>d0aR_rRskirHk0?4!@n$R4Y;zrZ~ z?Dp6_CM-Y&ZMdeW9mP(vY$<%8Hh@$6YZFJKu>*D&S;B}tpr=uLf-G=EUd^6vnLTJk zA8@D*W_GIm;>1rEgg6y-D z9)Jm`4q((Suk>@yz#l6>0#X7wk>VB{!go-*$TFm`fbsw$?SLlrMhFMk9hA<#(Z1|R z0!%#sFW`l-v78+f6_Xwy3V;H50zLvX0XP5@%;8`TPkG87@a8Ubdu(m64*$rF*Kpzt z=nlW^F1Zan4tQS(vrY?pxJQs@&}YPU=yiX)F7^$pGxR$YXMg(6{SD?bsyhg8gl8yT zFoFQ2&W8=2j_CupF0Kt5dz4nlH3&OD)D4$29Cvg)=qf*>4N7-xJWzW7j)0!d^D`nm zqyX>@ku$JGq#J+P4XBC0HhrYUcOU)W>mKGsY4kA{VY9%wI$hVd4s0gPx|laC&d}UZ zxIv%6z6A_)VN_#tL*YZFcZzN#tA5nNh2-25nd@C8n&< zSNKXM&#|9U!9*5lI+9$RG0Z4QbBP%G!z+biP%(9p$w_sjytg+w86$0x$;wn}L^}R1 z`z7z?m&zkEtMEd@RaPiyYWNg??`Uc*ikV;~c^9FI&zP`nascMY_xMFw2Gooto_Ht% z04YBx(RCfPJ3o6P0>FR0Q{;@M5oA12uXAF9!X7aLk}rUHgM|aq7vu%x6ZCrEX=lR* z?iuSHoHuN9C+3FJ8TK8THyAI}CvXCPq%P@pitNLW>pl3uW0O%1A zUa%Q5ea1#`S}^$9B?r(H=)C|=eYO->&CZh?*za(reuw%vjgZoiN}a}&FgW}?#o+Zh zP|AT4`ot+9rJZ9rC>&if`gp}4yE$lyeunZ8wh%^L<_vIXet5C(@Cf0J0}Kek5g>&+ z^K+ zC>r#d6+gjx!T6eCO~f^1a6!!}bxvlZtsfj}1HenxEE{V5J ztm+|WAdjrl@8=z^rCJKMUeSDytMf&+b^_fRlzZOyM=Kj2{fyO<|!}tI|u< z4dp~qUxkVLhJu<6!-oO3IVpPXb z->k+p#C{HhaZ9tsiVcc>O)e+7CE5eMAT%Us#_0&>j!5L|x4S2}L=8bZZ7 zHydP&Vvcz*8+H8}cuaf}wqCloB(c`h0oWn}p09k5*}>Zj4~LqD8BLb{h|wYno|<=~ zi0*l!$`r|x+o3t@xk1BS7h7)=w+tOQ$7}S|qg5Y7dvxNTWJwUFYeZ*y;)7MM&)P=d z)3rQu^o+^+`8M=`EO}U~TQR$r^QE#wSW6_!Y{)h5J?0@{%aHB`w`M!4jT=!N^s~j) zWbFaTJjn!+h(Og@tJm!J@)zOd%1;t52|mVr9{#OiNjv13_Q#Z4h_NJX2FcqX7p*}l zz##?4s8(6ooB=*Rui#cu+4zPbF3UTT3o=e2K-|QT8&;?sBl&u)-O%k0v?JU(UwrKj zUXveVb3jdVK+;G*6*dX_XI8w>so}d9jiFD5Nl)u?8ZT8v;`LW9hlULU_AZz`_Z@l( zR0f}Za7Ly|A87Yt?n}U=GTBNq#>t zcrSrUp}fl7KCPjktE#D}?YzB++aHCm!ts@mkDi@kC61NY>8|>SIRp_q!&XW{_6GsM zg4*Y3#9D}yC!aPMUC}_@qPYzX0F@q~_#5^4Tm+jgfL7Ynpa}|@bwOB}MpYR7kvGQB zWPgtE(2euM;L=@a24dEX11klqR%pWJki@+AQfbCuLWS+e_FmYIk8+iD)I}Y*yl;O56LXH(F|v7TG9Q`L#O2Q=q~nCnR+l#Ng~1kMuY)FpFx zEJ|9E==2&$l`DU-Om-Ci0-;u&s2b;ZePxNwlTN>{cH3?y2dkuMRWT%irE&eC$b382 zR)yt!uHHo{WuB#O$itlIK0c8PT?{`ezp#P%az)8zP){jZRN7=!eoNWfvDPro$=!|w zEVy@9j?SsH=xouuFTO1HNAp@OnilVPAKH+e5qJ;v;BdTDMrQBYrN{%Jm2qe$0&!9~ zzN9z+ij22oOk=%RSWRr+$d^qsGmbGLA7xdIiVK%|iE_x4Y!hA^kscw(6Jz-%^gA(g zS_Rftlxh)LNr`cOFpL!_qT{$dX$m?I(pTg$Y+ILUapJF=)NPz84?3JM=39>N4oql8 zdl;hq`i^B)FS(L&t)RsrhOL?ubkw;IW|?;`&nu1d-)w7PXc; zs)~B=^BS1tAxUt@1?NL{NMY9^jPr?eGcD0@`xwduBPwK@1S%65L-G1#**MCp=FUGT zk=LH$&QATzB-`zPKflUVoAJ!-=FOpo4F8eyl~JXKWbSNEf0H0yEZo>CT>)QdzQ2<8 z7DK#Tofiw+=dn0VMF9NHQYTxx_x_nR`gi+FqO?*lC??P`zVq%<=hLHJn;({Z=Nr=3et{3 zpSS4ttM6zrvir8LY1at%DOrN@oW3u{E|;2EE2h}VqDas%vW{B+kaAFUlap&=-V@$A z9L6dSrDj+waVOg%&xyp1_9nre3&Ss|o1d%pjD;(A`bH}@r(#GH1{PM6zl z8SEO54bwsKLq8OFan^c--?V0lGWplYS5a{^DolgXh8K($JyM(9U5T_zv~n`~ONs@y4hmh# z*pAp>Y`WLuAq}kx4K0lQa*c}ey`2!*$6!|7cNGU?ey@2lcC(bvX_d!3plyL)6v_ea zRs6de^F8G$DC|^8`-XbPNviZF{9m_l*-N3g`1saw8874=n1-49YbaIwk@2nc>23u& zthR<%dE`be7cVfYc1TlKu@`$u<1$kgzkEH3K^`6pACl%T9Zvau0e|MUs$ls^Ad z#iT&}(jlK{S#%3R8W@PJkFhv4f?K|sgVPM0B%+notOzNm*9tymDB)cBi|t$ zeE**3CudM^tiJaJe7D}hFBCpQ0ZI@ml#m7C$2hIfj<%Wi^p8&&?BknNkav&QtXZa~ z`FfJ=)8-a!&XO~7wGx-9-xONpyj0yXZR>w}=m6WrJJ2Z1VV~FJjzT9s<0PWXK*g8J z63@J=H2$Q={-JKgnoSf7ags%w1xC*i>m0Ib)nHz-9Vvb6sfS(ofMDAAVS9?&((TiU zXPVU4X1*g|@X#55>~Ax(Hx>&II(trH;7ry!^c^d#3`tPE5XI_`q)UXiwM7L;l5xhI zt6B46c@{)nw7hI0k_0S*)Au^q6%MXe1s3xeL&3|QPbXH;-x878+s;~wBz zzC(yYyuO5wo)^)*7sd48)Y9_$#d!Fz6LIVtqoa|gZ5~tJ0F?gu+=ai8PR}rj6VjoZ zICzo8oYsSbRI_!8F>s8Cc$0UhBI59?|H^4b?ZdNf32&7WO?W{~4f1@vK6?_LZnEDx zaYO>ZTuNg8u>9w(oLO!-Dj2h@(&dBBDgNOwKM8bU|JBTq2RPKq$zkBuu6i4hPf!Re zJqJI@z`aCQGH*PO&DndIjBi&eJ(y1^Cz{`SOY8^FOAB*M8bKG90gLhZiC%2JHn!xj>QM*Oab48fdBhTLX zL)Mzgx5ThpeP%>aIkks~RnM;i9LG1!w)84v_~@#Qro|=&3k<)nCrH5w;%z7j4uV<) z-&s>ds0perh3c(!9i>$NT14d{cu^^Hudwo?pRSE+h_!-k|2e*w>c)$GrgGlME#~UH zKu$-~ej~ZRyWl6J7nkY87dx$h)$$IrTvxNHbsups2j{yx2vqjf732>YIekcHpEou@ zrzqylYcQa$c(4_YAF^UL1F)Y)JyXZNz?LUWd|>>vT;R%7fAEg6+>+!AQCD7v#_of7 zNLPyNfl1(AIjM`;$zs|L?FXX|OA2kq>lsm_8Y_iztILTsVn$;X6GJH}?EDmD{RP3? z7hk#t)~%w+TJ?Wz{%UA#EaWy@b1G<(=^K*h8*3`R;ewgUn62oMj3i#7fB(sw=!0xs z-RkDP$hn-|LH>2KJ|*KOyJ+ap7K0WX-A-#EOxvRdv1V+@a`xb0_0p)$58^P17}zk_ ze#S7FNUK8bwvAtYzQU+g-qK=bq6K}B&;tb`*QJG)CrK0w6*F-gcm4_s1%1%a14TNR ztPH$Z4g4m}!QO-p786Ct=*^><6LCNmG6nfkU*t8*2CBk&cQ`giMCWfTrTvyjJ{|+7QJBb330tsC9Q|C3~u~F>wW+f-fqnt-j(2157yM*M?cDg}T?$#FMC!IMb zQLFBxKykk5Tgcf0@R?>L)2~Cbe2?rehQIP;b%MQ5YJ7InWR;6RS5ztiY{z7U8Nrn+ zg?8BqWV1>3JyG9r(?$D9zccW}P+gCDTFfne=R%@ObHQrfnfwY{M!v{|s}_}IA5&Vq zfFYN^hw{UO$idh=v}(xGc}54I#7)kus!=_~zDAL^qJ6Biqe9ftQx?_^t3NV2AB_Fz zNcb^yfwi6Bz90Xi`&s=QD@0H=WKk1~>C(@Vk_4!q-w$}8q)ueb;%Qh;`nwoC@+B1& z?P{vlh_O#SO*B3a4JZ|~9HkDK1WR%4W74Ik;B!|SH&T2@@qC}}hWF5{aMDxfN@dSy zBW8!gXfmcNfI-!1PAWjg3#>ss+w37$x()b*NLZ#3CV)>Ha(ZW~v+Fc26LW+vqfx`{ zDD6?2$2rGYaX)7?vKNGe4P0vT8%u3d-+yqJb5@*}h&La|8f=gAkvYib`2bqjb;0}S z2U)8Vaaxt@!;<#oBbF#zT+eDt@A4C`!Q57Uc{cr0b6Dv? z<~x(y;xew(DM5w~Cn+sQeodX@^E*ZshBj`lf*8FV6DfCLT~%Yl4$wFZuP)&Mzk3Jl z_Pyw2!bt1LC}~M?n8-oOPP&Bn@~mu@0hb|l)WZ|g?=)_lg3?fdjI--lrVKAXj4tSi zfkJectZgePPeIN1Ydk0^2E2|xcl}EothXcNko3#!VO9{q?o7)#d5=FIW8QkS=WlWy zN@a~E@6E1=-Tiv7wF7$p%uhC+=z8FuzOr~Woy`R?%J8!bZ5!e``8u_F*_IzeE2Wx> zq8B|sFk(FEl^THnbhgJQbU9Ek6v85(du7_L#Y#%2*Y7M= zK%vAW|FS%*FdzTnn$KKTr)m3Veq^ZBv=Pp#i^eqxYf*EN^)fM!pJ&#&b%N|xL%u!A zoCIxr9rT2gUC2X=g<%W6k#ic)#}9qpNbj)y#fY9cdT(H_bshS3d8nyM?Gicr0V7M` z`AqvKsa}F`63(OuSc!>jgdAkNw3c^wqhH_EGV)ONB_LL^B9!s%K<4$xl|P5cShCl= zLu*0NB!~Oy^D`dBh&h3TIG)*PcT+la#sHZr)sYsdcQ};_xsfr}U@;%{T!&^QKQ!(L zDgOCxi8Wf?{y2~(!zDEY$zg^=&9P*Zv=wbE(&}`z!NKBY_RAXL_H(t{(KC=i1|~{2 zB1}A@zlT7rS(qdD1!o2;84VT9SOyMBjg|B96Kwu|Jhw`k=Bfm@S7@_$G|J80DtQkA z6XGqG^Y;g_Nf%O(^odw`6n$8PB;U(L=#v zvTI!4PZN(NTzmV*<11V-C3!Q>pEk1Nb&|6doVWdc+9;Ed-4$_2p3qWO=)PEa$xNYU zWggKBW?vnD9;^4nf#R&)$>2h&ioiz}VP70!HgZbF@0aW14 z$7R8>BY3jN{JeE|-i&Be0qmC{Sw0V>$9I^87X9vI5i+*svNMyvD7J`Ec7$n$6gK7U zw9Be_%(<7Ng`exwV0mNXwXr=SHH##RmR)D>)-5%WEPmd|Wago3XggCuCo^NE`Tj}o zpxRODKd{Ar@^RRi+5VOP@HM*j_38*Zvt_ z6GaIbnHZU0lQ91?htJ9W%Krbu;WM(o=4Aeh!)Iq?`NQEez6P=UVetuHiS~by_^hv~ znZJ2{@z=!6f9LaA*qGt|;q#f8-WvFa&}aTD>E@r%o!{-Hx#NG z6D|k1I+sW&^SN%yh&+KQurafT0T7=_$4D%R2x5VwW|2!&2$4?_yccog_Bf=KeOXI7 zlG4*Ldu24*t62#?Br_hbRj4n;+AF!0dKvE2Ddox|4l+ zoyGr;ws(xKY|YxgD;3+eZQFLmwq3Dp+g8Q4ZB^__Dz=S(s!pHo(@%FlPmgzuH)Chr zbFJ*X*V=2}`EXxz{;oMa)P*0Q-BSH_;%a5dCLMB}jjEEYTu=YVy0R@ycJt_3UlWe0 z^4QuOApZhY&f8GF$$HY)>}YV<`sQ_oGI$j)iCJc9_t+Vl{Zd$5si_p)?~HbOP&lFF z$)nZ%5aJXav6mQC#RW&40v0Jm10Smyd;yQIEP$qW-S0!cD0fw+x!bhKy}xwNV}|lJ zSiDB=_3i99>vsRUjPZWaL)ccboW@0t(-!-da|2LlicbHlPI%RU#c|V&n3BL3Lk&+* z$r&py32+YD+*wHuaZEE3nQ_MAVaaAjfhRG2*#>Bv5Fsf&c-JdPiyrXtn>gXx&;=z* z_|VpnK(AQUlvuG7)TNo@eqpepVpyfn-KE~}gbgYcv(pxe)Q~m5-QJeEbtQq>TCNrr z`P}S2pTgXOusqU&-IB0rdPjYJ@-dC8h4IlOE@B-`^%69WITTjqrcv&%f#WpgTh7+_ z>gd$LPHknoS8xmT7mgQTMK*~wy+5BIOqG{?U`LSgy)3sL1a=37zAYGMk_#nC=cPD4Rk) zPY)@5-A9Cw;3+|yN9Ox%@hNnKqQedh$=FvO-VwI zmn){yv-^AhU{WY@MIsC$EvL47db>s&Etke~NaWmE-R_E3t6G~ZE-{YFm!G)&H>tz2 zbV(yz4)5pT_L_VSXnKhuoocMZy@bI`{FZQSl@&1%o~ad(6}{;}$Oa28BMGb>6kggd zb&njzXb)6Et6JsXe14E$4YH)s5EQTtToTmlZOg3^h2{bWXX1@;i^-0NZS+rg^DU)* z0b_E)6Tu<^M-Le18;xNeu8XM>>;!$J-$B`74ta%Y4?{*S|8}D&j_`Wc&M3B$6l-?vV_-3QQ6Vy);(TrdVff~-GlcfJ0y4Lf#E2jz zOAAt0i&l$u_3}%p^*R7Lv*72@KRJTbccjgL3vl4S*kI^$0WP{}s8!ko+>#PeNchR; z@l^3Hs+^z_m(~yEDy=Y<#|%Xfyi{@Opu>OltQg-%Ueu(nt+S}^GtqC9k+t>q_RB&L zDl@!QUw?DJLohiluDgJJq>yz#GxcbtK9~NddRGF;N z0;_@9ezFTuwYRIxMKPC)`l&-MSo_n>=N!~et)C8n6OFaUn-;Zff{#yaJFqL8`fl%9 ze}!6(9gwuOx==KH1NeOWCXT2=`%PHnqN%=JjJHkcGRN;wwxSDVCoR>Y0Nf^db+ZbD2wZ2b&Nu zGwFAef_VI~ar`wFZ4>GirX10cW=nxQ5DCeN@;uN*O1X; zMz`eO8GKxm8!{?E8MOe$GQ#Mab5|-fNQGXa-xhr;l{dK_{Q&c4M6f)^^=DOWII#8T0$jKXSW)alNF%TlWVVnPI;vdIoYv#?RQ zyF}M~;8%yUwx=m*iYC`lF!Qz3&dc1yin}%3gLELM;`XbsjlaNVnH_3mN7&CgEH|Yu zKwRcUJHct#7Z(8`^|~UYV21%vd`0+JS)caC9C1c{G(cdDETutUcR65Dn?Ee1z~5%$6;Ey?A*&!`|qA4zEC67<(16sOIsA;n?8 z6?-}$#CC{}ydQkdv#tq6mZjBF98{6;C-oSwc{7%b-af_Pj76g=9E|E@f+h2+u8xvGP0c9A7zZmm`+Yz))^rof0nxd9Bq8tFRYxQAAlBzyonCsTkHMRB4 zlD!Y>j5g9N_d91na>20`83!L-qM} zSLNmq!jkk0Y#x~EXA}#n(C!>CRRjP@0$p*SJu~3eBnfIT`FM#dB-n2mXma5ir^&?x z{Fga*^U(lS1u6pH(twN{*L!w`!j=z7b`3A5>*di_u?FZZ9fDqGG)23sz3rE#k-~)C zH7irtYDXd%%gabpkH>M>Xa@>1vuAiD=L}#UPjU^by!T<5PEH}~`~7KDa;^5Evk2H= z(Re9WhAUQ&f;ngxlz5xBK%LiNtsi=ze}$|sKa^i}eR1=$dtjYlN;?3II!=6X+031= zDYYqpk6b`~oO7a_Ke=4*;C|Ww_z_u(vh0Prs3inRkw=n{_UUpBQD(uZ$i*-SJU-pP zFIHlv@y>4w6F%5y2|sCcVP?e!mL)YUeH}jAS#_hQi%Ip=x}yJk_mF>dm9sS<309S3 zKsn#Ay67;(ukrV$lwb}d;Cma`q3}8my#^Z|HFW*X>**5yc*N zwh~t1$=Fo&F%vi^R!Kw3gP^E>mb%yXTbAR=Se&s?_f8M3gC-?b5yW4ve$0$tFq#A- zzH*+MYZhz*EO=e*KB--lEGIuu@m|Ky zzowWRB=6}0vkJk+oFv7Bq5XKI8xM#(ObR}1?S48;g~$S6xuES0N$Pizd4Jf)dXJ&J zyY|}(mK{M|Lxli|&mY*>yLxzjvC0GpkAI3V z;V;x~$R^l*Yl3`_6Y@&=qz>A>g#I-Ki)3injsbE>rUdrlok6Z)sEcs;WNo`7u&?BB z{b zA(?eD`}d`0y*MS}f^i->hN0@=U{c20n_&~19=Yl>D%{Q}D-JW-4ewbo8VTYfbqtK@ zv%>4Dbuk9X!m>d;>z}m(^E!k3+v3|I--fGHzQ^Y-JEsZkPZCiS9vwN90<&M!Cg4^g zzuHPtU$yEdtelz4BLgGxv6d4fku_-4Rp#=QG#Ib*0mOwmLIO{7AHzT-tR$4Xlkwej zyZL-}I8)^$@$KkOT1Y2?4^S&V;@ z4vb8H$0L8wrGK5K|Cnum%)US9hyO4;|0eV7L+kpl2nYzqKi#eV{1^Rw;Lp$g=ZyUuxAVvD2LZvrO7~wVCiCg8 zx{C81LsKnvQ$(q$RE**zV^TEnfkcLcl=!LT0nFg|DFI?6a4fLkp!Mk~w!gX*zS;3ZXP+kCd8@CT(DjVNi=B<$`R zB9?iyI}6%^w@;8%>#@L*_TziN$7ofXVz)7UPENtbKDKSdEaqtpFy_K zs(#*%Zvy9kItot;xN^mO@>gvh=05(p`m{yc1R7YyND`HaWE#Os z=_5Rr+-VY|m4K2e5f{*#IE*p=C1CLr;eh-jWI;A zU^dX#rKE`FpQ(y{*RB5eoPX0u5A3 z`K^0l;`c}27sLLk&B%vo9y98}qxglBNyUoZwNqg(MpULb}}fKB)z$u{l+ zdJAaFqE{t=7JLX?2abo-L*yah0({G$mu`!&mlqrtfd}u!|AJ@hJm4Pe9AN{zxrhk% zstY~}euJc4*d_h~WXrMFBA^RFoA@R00%D77YbqcaTolZk0E?tu$R+mT^A_BeYp;EP z3HTIT773Ryo0vDEvHcEBieL(M$Q6N|G9CkBig*ftii|0q6yY4=5m-Y& znh!QBrndAqf``wIUx}0vD8LlJcLT@+7zD_31LUO02#^p+5Fx-G1Gofe@Pp|>W2A=( z3=v2W7(SL_Oac@=k|}&K;N(ECJEfYXT6 zKc@|1&NFjEN_RwaUqfEu-GEj=xuH%2L2`NdVEJJM+;i6DK4E~JODX4o<~-+a3U>K> zL9T>5k~9uoOH0XUCX~-7f+804&ll{B3OHGN+6l-28cB=E zs3z1?=>-IDrKWjHIz~+1v2Tex_N){G{cP{jLCa&q;8!0CrilX-D+9C_@-*07$yP$X zfJ<4UO6)|Y{4-h$n=;Lttg*b6XK_SWR$it)pDhRrA-rC=GU_C9E-ki`lL35cbGS*A z%I zUJct;@VQkjf-^c5)eBL;R)85gn>^ixX&=5B#`d5C&y{UaN~DvD2pTI1oCvEX6dlbM zq2cnH)%^gVW!5@v)~~${sgS->@L@hx6Pn4P0S&3Sur!NCl^ShPk;E@uB=6qbPw(qL zw)n4()OAl+93Q%8kCey&Ps1Ckl|2+I5h?v4@WICj8I$PyB&6-CuWxi%emn^{v9FGJ z_2C!|xggPQQ9iIVMy_|?)eJ53-%+>+M_!q3biclg)|tOW=X0Ri)3H41U9{_Nng*R+ z|8Vb->9ALeO+5_4>d{R}kJv{&=yFM}vx*O2lC!3|kon99aEmY_=NEen6q-h1>N!6Abmr>XoNb#VO~X@hFdVSfv2!Q zYC9aoj{#My!uGi5hp(NfHa}JBsH<z3dYroVSi4)D@!J6xyZk!N0y~Dyy8=7T zg60QLSbZK+kZ}W`0|xH(CJhHVN;?9ev-}1EgaesJk_enGm{xf>t#|uQWJ`@E>tWSQ z#?3dEPoPzgwC-f@;4y;=qx9dZdi;95&imYO@!v9qHdOR=B&B$SUGundsD1EsMWYGKJ^}OK66tN5MP7`#X0k+RIkk$ZcyRpzHCU=*i3E zC(YRtvf9~y>%yg=T|q7+Y))Kl*1F9apWuoJE?b1bnbKP8>)?uHy)5C1M(xR;eT2#a z#6|tt8lmzHr*e(Itcwta!{i|b*(*fgD2nBM!l zBBN4Tp#84GLTL7}zt{r^QxF zCM3to>W9J9xRtee2BZ7JIQlGR(fs24f}+YJ1!Yl^EIB1LISs{lYC>jW)=?&2G0~97 zs?~yR__86>funk4znXHU=D9OviI;FX1uK(bc=K9hz}YOqOBkm3tx1ynTAns*?IhWu z;7FlK;*Grcri-|>eRAE^36*o^i89Rm=o$aU%v#X#vH7l36GOT7lyX%=i8&D#d^9NY znq$qF#X7`&+i}8Ec=G+?qeWfagU^5_;UX2iiAfDW9dI&=Ci&sj5kQu9&pae~N2Mj7 z{-EtlMc(Ct<2{-5gq33hO?0uAv;niZMp&l^{Wq%?6*4r&)ia!7jH526=|Pl7#y+>5 ztg}fL;n_%u*R)sig^?JG#0bgF$UuN(GPSQ(nQ`O>x{Ui#&fUnFizIE&U504w zTrcn(0DHy{7bn$Y+epg$h$M zg)%wwOa!fby7z54YT{xT#~Pudr$B@LPr@2s?N_yx>7MSo4Vx^S0n*1;2H229p)=yt z7dIE`6vgk_+^Tt!TURx41{Pti8^)|8R|1m_)8j5#TKhm@6fN|uO%ib^Bg{TbQfJml zT9{6IHNh{?neUBuD!?Fp(1B07lKnNpo2&-HaH*LfE?B8qRTxi7eq6K!S9U z&Me{VhbQA~PemH#W9ej>#a-wZDym7G)7yotlWT%Jq^)|{dlyQ*O&W){xdm>WOcTdB z2}K@>f4b&U0$1T#Nq80=DQ+n+^GHWVi(*cWX7MDQp0SQHYCH)~ef`G2H+bi3a#J$f z)|4zHGbmFrL{7fwJZ7EV*4gE5TkkCY?lZO6)jHYL4&|PsleIBR+f<*}7kgB+dD5!r zfIVV-m3m!TS7&>n2s`|8vjEA`b8`rXG zX}6jeW{bl)`eLH!Zuj-gsirOk(5s)f(zeBqJWkVhk;gMdKPg#}5~W4GKqc%(LSix8 z!C$k&7Btun#18NF*$C^4s*Tn7z-kSXrT(F$_Wh58gLalF{6*U~(C1vlBU1&b)MoI5 zc1Ahtv>4ox*@TUOb$zUIKvgCb0615CN7`e_l-3Q#jz$I5nK{F(e zF{4pmB#17;qb8z!z>AeD$0%H*dh!sD8L|uC2z*k|>Igx}ScNP;)Xc0s$+k{EEdb4aNCz0hfT6{#Tn+?=R1t@2GzWU};{i4mR#Lt9=f*{So3KK; z5x&B`#mXqYaZVoOeVNEuPUVYDqO@>|4=7~u@zEbOKlGCS=0up5s4TnDpFBRY>N#&oIUmxgZj`;1S6&P%s4oREKukoNz%#!?~!zIBJgD zhr$(b_I*$A&4M@qKG+|L|H45<=K}P$0@5Xtw+^<4k-qA)Q4{S=-A+cY6EJ_kR**Dw3{1UQrTR8J;T1>a;upZPxCF zcDCwHE7a9{9W!?dGuQ6b7It;D^DLFvBWF7wKaEuEp5=&Ep7rZC>X!$imBklUQyT^b z>u1Cjn7}s&pF}Ye9f3Y3^91*(AtoXbqSt$iOE3_SQkdvhqonwn z{v8(dy!GaLB6s1wvg{A%WLa!i(fzB*^K&!R^$Z)9rYXqD>9y@_)HV2YPG}q*rYGOM z1e)l?+DxX!bu%+?%j|>@?o3kj&qV=q!LD4AnAj_b@XIktfl3#;+6j{iRv&nK1|U2a z#gEzf(lY&>1KW?vxWnNYspeC>JG7z*@N8*rD9}fs%?5!qIM&LqEFw|HH_QV>(ch!$~Z>1 z!%@pS3{U;^J6~T`lXr(mJoF?(z{4|DN%oa@i)AU&yYx0r-i#EWQOYh=RqN-`eo|i< zN{x&RlV^8nQ_Vu^mZ>zrTYerh;DuJBhSlCGk_186quEEhj|&H>O%+q%T?}5M{+&QKVLDbR zC(DT3O;ArhmaR+w1mBCH>kd?L8m6yyjK%2t;e~efp@q6qLt=3Ua-eePEd;FsWWEQ6)hz zN>#7sgXQZ9XEwW&ivyyJ1>pgw6HF@DNVW6I%vtR@J1Z5hpACW*Urb1`an*LmE3;H< zS{Z7X?MHjlz*!3)Yky)q-BoqnO*c~1#p*a;F?e}w1gU+UVt;{`6tZ4Lp>Hb8$2CRw zI5$SOR2#n6)01H#Qv=L`qW%%?;09yXfT++VW(oltlq%vGyJJ;DEnu>2`-Yh-y;b*) z8aRJj#p)t}7{)%)a8Z;C#!A7aGRBk^n-!5t>A~n#hgUJ%W%|9fXJchW8W6R--NbPj z{EQ}xr{-EeoQbefyi!e_wFmvZnV6whuEX(tPkQRqvV7Skx~jc{YK!4TFEeNY!pXd2 zg^neWdFy=V4JXa0vM|RprmI$ik(ovxw+ol`r?J+CF?3W%T_B?dYFEUpeBL5(GF) z*qD_vIPj5lGhOvvn4DtW2*k~n9OMn;)g3&+C&~9Wm*khW>W5b17`3vQb!w`+n;cEY zi~udd2uP7!uOSE!6%5*46;w8slGfvTUkS6IDUVx6fBvj3cGD5R8AM}fRj;$C#X>Sa z+Fd@Z;58qM3avKjUtP0fv5sqRSVx|v;cX(T=xmdsq0Pd|o=(bUC?w-uXv?cAI+*y`cs!fSWIcoFu*ltgFWPe97Wf?JMn*iEob5hrFZOZCm6LvO%JKfE zR|1<8uU9~7;a4uYLH!wF5|VzR!2#kyBGdRd14P-@w2B8zV4Y^Aw zd1$TNEq=suCQSw-ZCN~fj-k=yAoYAY#H9!hv-gEtxZiY0bST<`73Eanxr%w2=Cc%!M*M)OInljnQW!Ab8SbR$xi2n-Q_*{-Ny~c(Pm8gP z=!n_bVg}rho#pW3g%{xDI#C3D*oY-dM#``U3i_ht$$BjJgZ+YECr9XlkJEIs>&Pz+MiNWKX zekv?Zm2_^8P|~owoSvjnW;Y+*X+7?jmu)zjY_Ow3R&4~iZ|OyFMz2fc!xZ#y)tG~~;6p#jI82-!S-AA2KukL9{@S68rex%Sj@E$0W56n`nl+`j6DK{^r65m~vL?WF z65w`AA~Sn`)7p3q#HIIZNb%>({umZl2JqEtZW~h_7yGT+CCc6z-YyfzVo= zVUQYM^ZT+SY*BVONDExB?FykYt7nn)NY@onSe;bX4Wb#<2nUXwgHp#ILY-3yWJLnh zFqcg;4Caa-&x+J-LpHpsldVAe1sk8zbYF9~Q|eTzRB+=?^qrBy*DX+oShGT5RCJU! z>gp&tAHbWkcUJw6(@~Oi5)2weWHL4vM|jt#8kBlGpZ&@A>qURUPO-Ov7*od(s$xw?rt0%RpP8_ zB5I1z&H45Oc))&PN_;j0jlHVSam3>=OhM!}v`BXgdE&b#S|R8;BQ#oJAh$T>OmgXB zs&pLJVga-HPK!vscrY$>9U4(&`gOH!9X?KSP|u94=Viodv*ElQ>tY(Tdicn zgxL^x{*Rw1Fxyp{o?fa$4wd$Z!QK8LoYClK#?P(Zs7nk@*l@M>^t-`tsHc4dIFW;W zEu<6>xg=+}xIj9)>He(O5zf(_I%1lWQqm~EbdRg)m!TBpM+fQ zw(N(@1fZttw7IcDqQA%km7Z{G!tn<1+y7#9kQJ-rhbaQ?q{%Pidm8!TkM>R&@xI7R zH|-~2_i4yhc3k?UE=MvRC1M|Ulhlgmr7iZfYMNG*&C8^BUXmMzX@M=j!A{-Nc%l?? zu~L1xgQd-FUg9M>?ETZ(xa)5>#eZ%*#Q3N494kE=^PdUG-&O8^CLsUo8UX!`_dj5P{}vzkaL4^?xxfcL@E6C3!o z|7ZMr{15N+PtW=1SNv^{f%(^Y{@DI{HZvnD#4mi{WBiQ~{2G6yn}6X0zs~wmEdTqJ zzectXGsxdp_UmuIk%M1I0rN*<`Zt8|fhPQlS((}Jm_NF${EC^_{_iXLx6kqPqZS^WPne|~52|B69;r19CA>G7zU*gn$WzcC0pR@VQR z$Y*E%ASnKVL44Go{2haU_zMQX{#Od(BeVXemEm6~h>yGfkCgsL>yf{h8vcSH{y=5^ za5ZH7!?5r#5X7I%&M!B|zvc9qe%;-_KoD$9O#ekne?r~eQe)roy>skd5Q)4~_{+}j zt|XCgSi!?|c$}p~Q8`vu5_|twEjS?wHd3U zs#Yq0Y>pPLr205obvdj783++tE8Z!t866dT!)8lzfe|aE9}A$!@kQ42y89IOCVSWQ z1JBbHAg-2yu~T5l(n%_0F%A7=e#bak*ZH_$vfwED`{$@EciPOhX?E{addKZG&*-(X zjAO)RO&uLhM`d=C^DR~NA)l|4L$(p+I?XTDUn?JBv3OlK2N*MtTXBE3du`42W!~3e zvcax;dY+JGd!J}!ewYTO_GcM` zG)~S*#Z6t{=c6-{?jBY+v{w>7tdGs1^pCirw^}a6+uP?0qZ; zDN&kA+c4l_`sO_8ZmuyNg2*+H;{TSkL|@&Q32uzQG)~ptYuTKky`mqqJDAM=?!Sk! z>FQB7_<1p>;%FxnK13o|;CkO8{RJlj%nXW1*tXQcR8Ij}tGNuHSr9Wfa-a?~H*or? zq%QsFn@4|OL!>cF{Rj-}agYfBz2dx+`MYlWv~5Rqn2VUrvO<FJS7x)r~(@?eiMb7%qhm>q(p$edAL1`n->Sx7ZaUNKfSrL?oMlS)`|4bR0on zbZ*y$W6=F`FbWLu=Fk9TVXAz55M)PD+I4Y6^CNB2JT?ZB8vUr|1C5^;obqto@$&v~ zSWVS6d31t*=YAsl=;amqo(u<{6ey}B`z?4*)|?@&nEAc(wf+t|Qz?1w)qkV>JulbT zrTc)P60<2{lNCCpw1_sP(;_NI9T{zZ6S))6=3oh9p0!|y>IhcMMmVYyW>mW`vb2fb zyaOZ|-lVxl&S4Mp8?qWMG)CFPq)!kClaw@|IoGFyEdXe?xrruGd(HY#r*zYwQ}ta# zkb!sXTg#_YU{jXSkeeXtFz0JioiI$P%VLl^5hXdX=xKB@Fe?YO)aWF}tKDo4atYWI ziJ8F3!qe@nfmlo z!rEHe#vc2{oV-6t193<0$&7z2&t&+bvN<<+%k6`2iLT0Q@tP@9wOrft!*zlqAup9_ zSVFN-`VHokfTp<(N3rgC@Ua0dpoRNN6~YWenzFM z@()lF3z}Psq&9Bxh2#aw^8SpVjKA?|5E26<(jSFidfIiGFh|xW3*Z&`0OJ6c-?OaR z2iuhNdZmJzav{ZDd40aA?#~UdwFGE)y zax|(_4ITlH4kU=gqcKrBwaKXMW2zH#!!MAyfSEgo)W9 zS-hNNP$?G)Gbs<5NEiH&v zF?6v;M+-7Pow~?7gvpi4DP5jA#p+aMtYpt;%^9M|f+eFQlkz^2(qeJ8Kfd7hX2oc1 zrtVPmM@AtJbHfp}1q<~cRM$Lll>4-dq1N-QNsCUm5orMQE75j7r1zS9z|sl|J@yV$ zlSJEGGW zWdq2ME63aj3@0y=O~(MOv*DiFYEXf;u>T+mb)Iv3WRf^!9KGrApqT!o%-R9K4Sisi z6KDoO6(-d@kQZ|*>K6!+{plJivs}Q88x58Wpw#Cm2gDTnhE5EYJAWDv3>Q2m79X9Z znGO)q&}R{9ff2nC)&a=@=0*e0wNlo{6@#d}k&ae49%by-A+3`qE!@1&w%l|pK`hKb zDHqhHLZ-CT@MaaOQlRt08X+SJzh6*^3_?UjGeWYA*o@>S=IBJo_wjF=el!fK4MqLEC(Lq5knR#I-ENzL3UmEOI836= zo*rX($UzqVP|(gg2fl=_y9SdSXYMpg6q3~oR}Q{9(gHZxa4GXdQWl?iUkR49CAGk_ zoB;(T%~C8el<_&cUW8=!(A=XNC0znqcIdR1a<$Oa*_JO`lS_*xTU%mCVQnreYMxTB zrk)l>jVxHO(3PD9Uht(0UJ${(0GKG%(D6mNW&07H+)F47H+EaJ;NkD#z%?M7mm(K0 zMHVjd)MkatN9;#Kuo4*+X?!qf*>Er#ve-)mCDOEg(Cj-dKm3hMiDH^Ou`peXa!2cB z3L|Z4$M@#u@-X+u&3e2EPCeHAdAhiikmZ6YvqIV~DWm)Bt)u1dpY_q!m- ziPg~AkH*U8A0G3CAojh6sD7!$Wr1|4)%^rU?#wq`afp#_7;nw2)$>SiVMx({3H2h5 z&WJu_Jzj6q*9#k{vU1++@8l^VGXCa3)qppIxGV$gf#&PqreWHW=+p-=pOM*2fXTs! zRhI`d6_L*lxp`kFW`pCOnZ_Oh%HBWy@~v6q0HF6%DG9*Zx}BFA75VL~IKKS0_wt)c z4>Dy~uKt?mPKa4&LOBTt+k5j5s!eVk%Sqt?-P<$spA5K|6eMeBE{8S{uHH@@8Co_G zq({Z1q*Dus(Cz4_WVk4A=*?V90)cW2{tyy!$xp z(>g)K5iTWftJsu3o30N))fTdJ6Yr-c)|vG2&*qF^G0{@t>{i@;wxOQy!%1}OQs-v1 z*A*`@Qrig1M6?X^tO)e5Owvh_)vvcxj-3(ApFI9LZv5#4$|I3~ z+!(G7z26dqKK*wnQR|H}RF-4o%b{fsLSLo`0DnF?{8d<&707)$y-YFNGe)ZMf}h#} zoS_Pk7m9M`fldxXxG>4|juo(VTG&!Et^@siF4lUpe|2olQ^orHGK`e&GB(s>mUu}Y zQQU;&>?fswz8m?~!ERGrV)Xz@CYp>QQ5iIN^t-M%g%XBUg$Z{@9C(qiT1C(@)d4uF|j1n9@P%SEZEy448CDf>=>15>_AiJDiChwNck%OlS=?Z zHSxC95@cxW=&XC8rpLnBDHOT0?iqQ^t|6W7tBBFJW8f|;Q;=Sy80xIQLJbUMgk=iF z52*Bbl#T_oju(yNwJ0bRy7LBprrLC`{o~Ll8CG>NKF@KA{HQ#7Usn>k4!x^5uA@Fv z^|R_9ppe7iV>MB<`psgJTAVn9JaeH#*1bf@cvLfm&YAi1@IsDX?3@a9s6+tell2OD z5F^@dC^uqLUG$8m-S!Ux!TF~xyTABcLP9U{orkPV}&Xayl9a>%!oM1h*+N-3E`vfO%`#G`QIKy#4TPfMi&a$ z2^@}c1R2ijZuVAX^%(S>yg#S0G=uC1ksVIMr~c?p)MawuqFcX+3616k%}D~ zZKGtzgBwFLawY}^+Vkngf=dDXY|p0)12zue`>_oF%fYYb)<-v=#j!H+5ce2_9joU) z3`|_?kO~97Fj056W>(aq2@a7gau()Bn^cqLI9#5kL)+N+?=e(_o=FYBPWA&XA5Krt znNGupt!DP=C0FM`M4!tB?~i@)Dyd1h7n+Ug(OkQJoayKTe62BONkhd}C0Pcf32xG{ z_z+o7r0O?Gl(ruwruU%2vvQOy9ES8nPfD+RF4%X-9PFD^P>+0vbvUp}R+{NeuCSFd zw0Y+?&7{dFY$|7BC2aFSSUJe=QDy*jJE9tX5ZwWPTkD%uQNe(g#G{-Xz}61m%gAv( zYbm@_AvBBD6F0&-*tb6j*jWM8=?eY6o68}M*=4BBsO{X=IT{v;g1)2_<0-3tU+UDP ze+*AbBmmp5S3E*8#9uCkRiPxg>lfeE(k2s)dkNroiYXDfN4laT6nPgJK~NUwbpyDE zIV}q+2VYczpny&6{sRH2$NeM@;{C+q!D3<)HH+hsVF!ELyX}=Gs|mlQJ!=11&2I4; zL=A+mQ8KDlS^}XYWQ{~4Nv9h1r1wOJi3ak%q7o99`|{<|af@qXUT6qP;L@#9`nhQ5 z-l}~zK%Eb>dbBsdLFK0>QaQ&Xbr1|FZYhM3Grv-jgWchLRkr)p2;}Btn>()i&F7{@ z@4FR?wbuoePCxfsPWELLnmZu6xV*>dsM^Ro)@r+%)eGD2KK6@zCgEz5oOmEa&Y0TX z&>Lqbnkid~j1J5O`@IpFkc>_=<4Y}cA3JO79|J%bX|?^O0)Ihi(R#xT~ z1%sS#`V-)n(M?`Mdf*8EIQ|dUr)=ab4i;QY#OL`mPG*j(=Wlp1J-Q?mV=u@{qds2A z9;HMK%%7Uwr)nd(P2@Lp?Jv7*baoX^pIr^DtwVKEW9-WFHWd_Mf2O;!Bf6Id(i)A$ zUxlQ(7M;ITYQBAc*|u!gII8V~1OtAMemNrmvuf|4Hzh%+ zq|{-G=Wt%nQqZ-D8S_sehPlb(g{KP#XA(*Wi_D4+k80n9Jh z=itX#m6Yhquc=w9nrM{=6lBYM*~&1^?ukKBVoBd;Nd$coiw$a+)g0 zLsOnMn=~gNy;p=?J`Rh4d`m_T#3Ka@Kv;Oj)nNje>qIGZ)l6_+Koa^H64KI^#~f*s zhH2^?1{?;fyyhlrGN(XdP^J}``h$0{rN)+0SfN(mCl7GvcqKk{?RPpi`p(F_9~fJ2 zeAvI7wd`lvpLx=vqw`=CGduW6l^&m*vk5%yzaitKb4Eu3opde-nmFIbK0jx^84>(E zeSYqowYpzl4D~368Q@fn_HLSK#P;L67xToK$`gDg96IfMR^zIB0^!WGyQg~Ec#HZu z`E&#Gi5=XQ9WrJ@y`n;sQ< z2b(m`nk@N^?zC{=aQEv}S(KFt8tfvQYo9qnS;BN$by{ye#3_xs=tX#KpMs)<{EGA{ zzSh22;}=4!e1?^bxCD8_0jjh-f|WzE&|Ljio5Wmd#k#L6M1fmjyj(K5d_PU6f`aV) z3=yo|M|62TSu{T@_SChR5*o>?KOjgL@G{S${+Jh8pUR1!6SZ=H#oD@*G6gO1silv9 zw%D?Re`-k?d8MKl^kRv@g|yv_=05Y0@%ie&i@917R2PW0b%|wJnIWKRRdKejPvw(k zl}*#Ln}`T?(f~zc=|gGREyR?jTL6S`)~3vEiN6!eiDFx|;$xE7XI6$Kp|dqjY^HbR0md;~E|vx#6#z%Y&u#99MSp}sBz z%J5=eEb2kMn}q#GT2;Lue%36lSO3)KO!@r(3cK>CCayiKDIl8#Wf5E;T4PXICYebx z10m4^VkjW1f~b(NiU{FhkVp#}P%MiYQ7|GRBA}>5Km?yJnxFzw6+~>YfD~jATGY4z zzOwa3t9=PQ=iM{^%y)j1d++bg%(?f@m+u>K)HP06qQl?eS-0%?W!5fyM07-2l6@|{ zMR?|N_NBhXX*->Zg<-cr8eS>s-t4NOJQTC~_77qwJ z&FUkT>z!wcw_hu0n#b-HB_E<4zGPq}%2;n9YEJfm4EJxT(6G!li-Bg7Zl?EP z@%tBtMmv_aKV@0paVW`cJ8>>C-oV{{PNRL4A;r6`pcu&u*z0>CRqufqFOgT`=(VG^0ZpI1wxiPLJ zeaDo9XL(tnVG~oYj1kUn%|y(B_Q@)=W@zV?-K9#GQF7H zesV#hmS@+2F~QeU96_08PJsPwnZ_6#Qxbjek%9lRgP9-hJ|Zq5n@8exN*!`)lXZ<{ zJ6SlNyE0!#qXM&s-F7$BV}y3Y$r*Yfc1_GKlO(U2-xDu{Gdth(-g$iFh&PilFd0&j z&Bfhl$=uDTF%~n6neErk2KYTW_3i2V0Z|JhtDLV}YWcoyn4d@7;C5y4H!jvU0xCj(>S_e3}klsxEko1$z=~hxJc0Gnza#ejci-y-j#kh#@zN z*Y_bqZRFQhE3#gwrJFqcgR?R6l<{lV)DerNe|M+%?_mN|@&q z`*?-N>c-8)7{Ji(*AItdB+V=wthNdxN*t*vWxW#ATkC;P@~krW;je18gDa-$UKaH< z;H1XaS3&n=fx2My-y(Qllj{6t>XHon?>EhRR#^ysq!yk4`Y?n-Q@qL>; zr0wYWHN?)=4>FJWezL=p#tyjjrRi-r`uxv(3rAZ(ub@CM8Sp?zC_?jxAR;)vL@Gr6K2PC1V!0u4!J)DE zk9C6Cv_otthX+hI9XY&EJo1;ef*UvFf6xD(4)S9|!vKu{0n&?K3Z6=#02zQV{3i@X zDKs#PR1|#lUl;_FAkcAT48;`Y%E}l7DM%K|7!08^u7$}EAipTb(G=E*Dj19?%tMvq z5HfWJhN37K1En}Jh9Y3cK?(bGri_tE)PL#+=)H0rgh5n5sZf+Jc_GmdRJAQIg$l?r z%5e}vp3y!C`G@==m|_j1R0l+(Dkw857)_xiqKu&^SQ@Bc7zC;21p?xfs{Md4m^5SD zFd8tMRQ^2$$waj+AO}>{I!H8Bq0^}-f9DD%0p^G@268_m&tx(@6CIGwyNl zyeZ^MKevS!%K_e;u^+v1y(1F9GY!NnytrH*5Jmk&S#gdI;{w0lkMtF1N8n{k4+;q( zk%PjpFdB)9U^FTTCDX8ADh1yl6A0_vowWZ1 DG1QT> literal 0 HcmV?d00001 diff --git a/doc/grid_map_conventions.png b/doc/grid_map_conventions.png new file mode 100644 index 0000000000000000000000000000000000000000..d75537693ff069ae55a62858e8331e5155fa1861 GIT binary patch literal 71905 zcmaHS1yEeg_9qTOLvSa!ySuwfaA$Ca;BFzfyK8WFcXxMpcXyV2@4f$SZSC8sshXay zKIfi$&#(LF4OWm7M}WnK1pxs;kdzQn0s#Tb0099#fC2lQ$(R~e`24|g5LI_jwlQ&V zHn0PL2pZcM0th9o4NL(_00U!J+aUlC2naZdxr(}jx~vSBk&QK-!QVA>F4jLksX;(^ z_+5S)7+C@w2n_+I=0IMeil`o1BV~o23z_F%dr> zA&(2!Cj)DMg8`w7wH45w%Y~QdAHH0lO4Hg*6)Ryt-{ zBL+rBLN+!!Miy2!HbxpkCI&_(dWO$08!aOX7b_bV6FcF*KSZBbvoki~QW6pS_q9I% z@e-LiIQ-L3`rq2gP?_%(io{^5>?=Agjp{(rxf2p2dXGe;DOuFoXR&Pn4-8zp~K%~U!_2f zey1P_Dky@YL5e_%2#N}dLZCu?3t>3|75YM&O%ew}86~uwr#o@i_GWTH_XbA!JHgcp z)A?aP|7`XBAU!!f@%Ijg0O42GsJwz87yS48(R^tkVyX7@xIlO3qdht^b$G6$*jz9- zEq+t%W&;?A9C)T;FovuV;Zq({`KvV4ztC_;Z2NMpi_ZfEf0y+=^9Xr>d#El4%eqs+0?HmWs$5*^)2wS}L)lvpZD+wbcrBRUH?B{HITlwyhh#vAF5pRRms?M#- zOS~_J;K-WS_#4d+@(iIHIu&b7oSbWVsb$;TD4siJ9#|3icn4%Nr}IRY?solJ?!`&> zFI(LsGx&-sm{BAy&XyC`?3G?hb-dpx&)xv ze#;?3(uERm*oySVoFQ-9(*`Vd96nD4{lPddUc$$73kb(KvYhe~-Odj3t{^c64~*~> zo4{NdtG7U~;wL<|q+*4b2zfc-->&Uz17ERE7jHm)yIM#lig<}Kzi2&6Yk6r{Q=2=j z*AX9uIoX4ljkoM6kALV~x*4ctQ%xc|6EW`1d&G@Nb>58ng3{uilMo=#ioXfdizDzl zkpP9q^N`9(9PGzQ?!b{zH3jOkaYO67`{Dtj?hcNR3&R?Se^$=)u9ODI%im;FNUq{K%;+llXEr!K`BJBk^3Bqckr9jgjOxR+TIIdt&*$ zqk6KvVG-!Yj-50K z7EViY0K}%CgvQZ6JoSXZ;VNXdZg1EAN@Z@~uQ9b3TJ>i+5L<@37}$ZkNVU{!M$4^k z$@bo#l!|J3O0NBW=DI{Q&GSOLAu$;Mi#8t~uXX zw{bGW@odQcPTOhRrJ1dd+|C1B^WRBCKeaTiz`SXBXjODHPkQJ#mp0#E@o2eCrGb8J zeNNEUBQ<^IzWGA=b{74_at4!~4i^lB&VcWjrk7H!BY6%KdE|7bb(LF(oLG;DJ0T>_~(anhk98Vh@P@%@hWVDp2F;-OT+aS^BZT5~MNykD_s(u&4^IMu){x zH9+s9`2zLza@dbZIV;lZog+%iF@~D*9SNj6QTB!{vmW2m%o^?|kup3;IWe6AysCYI zBSFB2nQjoEa?K`1jBW#MaKaO0M&orN&S`%{cZSbbC*-YR=0t%yS>fdX`Z8G9bb|pT z;O?4H=fDZ>1nT-oMcO(HjwyT>{Gps7Ow0y^u3h9?HZWK5qI|=)XpjEeU8z%H_&9V=h|FOJe&*ma&kO=<#E^bzn(URMg*D`k7wmdCP?$ zHsb;3)JU0ElIzOOJilG2)BiQ%(xMD*BezL}sy5^u)UU5P8w?u{d;XnnPp#oF~>fOQQzeXHYTgamRRX&bV_Lh-rPa_ZJ5f+<1io+-(X9$nl^1O(k)YP}U$=ZgUQwaGb$e{A*)o#uJ-0Wl<@fq9N{cVgQ=N4M z{xW!sKFI<0@O;#8oT6Uht!MkMBq0TWG7K2)ms39|m*cuj7!iT|K@2Zq5jsC7fa(m{ zAlj~(uDEzCya`b+@h_Hc(}?2Ntv3O7u5Qp5Vi*>*aWeI z#>kFfFL-EHgLp4)(`I*!<1M7C@1kR~!HZ;6CYybs)7Z6_E@i|Ed~>qt z!R+QDc)nX3ONqG2uhkROMpSP;xIA?tJW`@H+Fb2g!M~_W=H&F~M4xeW**)VAOh`Rr z?I7}a>1e?*345c+9r?ChyODCJ6C3>Wz9~HP;mKlg8`h583)m>)j(BI20SUnbtSnY> zl`Xz@47xJ6e3QNtFVo?6ANmGb3d#kqU>+r)&PqGkJ+w-F%QUIPSXky{lE6%4~82Oc@3sVg}8rkQJtmxW7U=O~L!?>jP)zkCu; zM+mThGtjV$r)wH9Ylh1t#^p69=gCpds-a)Ma+4BdQeb(Ot86qH+i&+#8|DVWT~)vT zvU^fJdd1N^Y4b7M<2K!uzEG1@HX5XuEh%>3%0T}QTR6KNX}&g!4|$W)(%df?a39Vx z)l_0v_F=E7%-ds4Xv^=~^*)_;xtXK}<7fWNc#`|nB;xPQY^a{a4xxkU#I+_PM@ndc zbwyfBeB4RjuOdiJ1%|4bw>#{qy7_6pL4ZxY3TVv}uH&LISqES;PgB&(d>evM=Sks> zRZ!5VVw1HXWG*Vx!RpPwrq>eoouS^? zQ8PaI(y8lyWcA8Yk+cI%_3+|g$9e^0m_N7*-j=_S`fZoamchAISug$RWOv=`G(y3H zm$qFu?CF{mutlnLT-2Ulw#~XMT2K-Ga^Eqv)ye zGG2(ZYna)XI8uG?KqYsB24At57BI~jbi=rjpQ?-R)VyzU{)1SM@aq^d3t^-S@uV5i z3D{_g@o#@~-*-c#!VnG5YTqXTfIaMG3wRow@W!-G~>1=_i1x zDFIMheO^%%*JMo)Ou_rylqK>d#$TX~(OO%v2=uePAd@R)!~3^F&Z$5T{YfnX#|o@} zqpEdXg0mKctuI*KtROVX1p4xp{P%dCdDY6$u`y(J(6LP2Z&{m@Vff8&;Tr?~duPMP zyHch-D0~M4@2B(mh1DX3~3cH!&PGD!uLV_k4L~Pto==lFnP$Fk>?LEG>QMhk4F&vI*1*Ntd15f7lV@g zf|e8~Nb*n@SZR$TEmIM`6vB#3R#7}jF_9fR7EtN>J3Xum1kHqHAil*7TbxD-uSFG` zv}fjm>il`hF*mhtei+9rnZ36It?Q&VT-Z8jylX~@1)V~|7+fKhZXTilq;0qm%tz`duGcQ^G%B8%sZcySz9W;1=~BlWDQTn1|iW>jC; zOlbNB*&JfZYQ{zd39q7FF@q(u3%Sfs02(EQf?u(Iph(PJ~T-9u2lF=80o z>N9cara&@K>WWEl2!^gwz#sS1CMkEDMSltWV}~lfH?C6z*4N;plnnBOY$=As>>AA| zO59t@LKEpI2@R?FhuvEd4$r`~tjIZ&IV1@NP6w^Elde(zp$fV31&3(m?#s;I9``7Q z!^1!`P*_mKZ6?Q)P|9tw|5==XX|85MU0*EGnan&e)5zG*6Aa|RQT`T=wdXL8)Waz+ zITavGhU4&{nx!XuHg~uUpOtRim&C6s;S9PgPKsGs@fckUtEv_Psv{Q0k>*xtMxI@7 z)^}|fYY__JE5IT@sm;AD>(iTksc*@KX>{XgnrVhqP&}VO5v&SYU$A+?*8B7E53Y+M zP60~-QpXDPPjTB#HTZ&97PZjZJTU4-kEnjPJD)pFz`&2T2a^F0u`XydhkNL=PVK^1DzeV8&*H zmJd!KQQv*UQa?#C&wpArhmo?jSZ~&x!7MD+95ughzRwZcuslV>HcxOi#!$}V%2aZ3 z@;f3k9<|$?OSZ=`R$XQIN#Hn7mK83^s|l1c>YC1!i9S!Be-Mlu2(p!khb35VoHtETpz!Rr zREn$DUV9e*i^~myKS_RPhKdWc++!c9$JJ?Gs0C`-Yg?)cz@+ z&ku@7T3!;B5+@laoPzWI^~q9WI-la$e&~C*;h!u}*H8QCq8iUz4_=`*;BrKl8JOTl z_ZlF2OCQW`dxr2@lNDe}cA^(EAhNB$W9=bWaG*PT5G5?qgy35Y@@Zpr=g3)TK|orD zp%Ee|F+tGF6q6M(KqoI6U$@v+>BNxz?x4cme4&!6|89x$^9#=d_Rd;Ki0I$3?Te*qI1l43F=d{Y`Yr z>~h7#pyVHJIF$xs;vFq`SJSKlPLZiQ@MvdsV$;aW9I9_fqNiNx3ca=${O0?k=L`$S z(9tg<;QfyqD=pXhS7`_%e(GZt!CQa*5f@ujd>GPf2|C(tq4nQMfhLCQ?)AHl1X7oAH9H z#=PM9cq#r?IZ^s=DL z0aSmMlQYafS=9Nvb;r}9cJjzJt!L1QNG6Dhuvgk(e zT|?13X9z~mk(Zp;&-?%no#p=iq*{^_53(pF*AvO6E&G;-aAa=#gy7eI((32zbu@i( z<*l&Xk$yS=v1wFhY^XW>KtUN7PP@HHFnVfzny z`S*JF`LB#&x=8CFN2W?G8uN zcj;>xXvrg&XDFR1yurtsM+E~gTJ>j)W-m)&=v{C<8Th`wN!@`_*ioQj zc}$C6sZZ>r>w05+^gn*Ef-exO#TYTWmcRS@v87Q1r%q4^wquH*x0uRGD-{XWK~l-x zQQ{?69juW@9c`WN(@O=CP8`ek!_y#3_g`BCeti1wE_Iy@GT90g@lua!0HLxUC&QB` zcTgw_BjNqW_*Rl6-y%b3ht70$?z&Gh#} zy#p99dGIT=-M;Tp=>pq(I{KwL>A=FUm<`SmI)Q@b=0#5+A>~h5CLdX?iTdXdN%8Be zoD2_`qen3^N#KbEFdr$z3l??Q;ZPavck^27>+5?{^|*J6ovm9pWZp||(v1x)POgJo zUt8;HEDJKbJEOk7%ng)J9CkK89JIvF_X3leZkHSnRu9ZDG3$1@zt-Ewc|Og-9T)-K zpEnoU3D}>IQAc{U{oJ2S9r!>9yc!A~it(Qm(j|=`Fap-UVjJ(e7liU#v5d@-3IRABj#c+;wwJ(HUTw=qgem7)J`}1x5(7-1_xa z_XbYJGPkHwt_K4FyiLsUd3V$Iq4|j54I9StX60xjClmE=#CH`FB|(y$oV>KO^z`(k z0G92<#l=-`wN&l-axat}Wt5}clK! z(Z!vF27P2`sHhkdsRj38Ar8ML@DW9NS@5vB#yemIY%1f(?9;FO83sBMoqO-H8PO3pjM?J*hNo`-kV)WWPgz%n8=o37K*sO!hBBjLL??7>R$jTU?| z6XnuA5&%4clQ)BH-aXthmS<|RFR4i@umvi`;SDaI!wPFBh`lU<3v!uW)*YZ45+ zsfgf+t$N$%v9%&r>R7{(y&Pz`PbF>xs$H%O<>e=k_#U&KP&vuT58mHiG&D36x(${* zJw3C--?j5=k!|>n3Km|`>a51-WoyRHQlYS;K79IDcfIqh;wN~oK6{*`06Y9>k?`Sa&bXh_JfU%$AV zPJ_s1k^hFY5ZkQzSy`L2Mam9bo})>O5fKrELK!Ii0~&7P&QM5mBGzcR)2s1QT-<-W zNS4jeeO)ALE#`(lfjdU6W@57c`S`7^tp~z!0v*~iHl>2u&Z~X^&T7(Ju0k-6wuEj- zA{h781s8$a8%e}=PbE}!3pv+4PKm2?a|hB~ch_r>9eer+67mju@4^nY8ff23@IGzc zPjnjf%Y8H|Ztj=SWaf;F3~*>f5x>hjv4W@P-#mfCtJ^wncc3)l&l=zMS9LjNre2Tv zi)2mT?R-RaRCL|^;fyD{RLhS9^O8 z)uaurt3_$k{=n5vw${l1I(Xt=HI?g|T zV)D3L!Y$(6*ZsJ+50rXmjLRHuxv$sSE!A?+G~hEWth1E=`cl{cSFdNXe2hk~f(Nc| z!4E_r$YT}Da6I07**n@(ywULXzfL2`yU0}dvI66c#Bv93oOgjwy;p|;JQq<5-G%!z z2iSR3rNoUOWaW!7|7|ndRWlaO`=pO|J1^n7^ad4Hp}mv}r; zZ@Fmxx^2%Yn3p@H26dx$Yto#AKf?S1*ABlwR@uOldBc=F&HU^1gh@#jYu>-Xsnm0q zWq_b%(v|71gHw#qcw*ltM!eWcIVf!aJE<4mo2#?-L!^Y+dg&yeLo{L^3cTkTla!^% z7FK5Pr>00UbNBm%AdMMBCS_^Eo}4Y36^_k^7LpOZ#*$i%iALhTp-MREXHA-%9QwF9JRG4o+_YG?0l1og{WkYf z+#-cLj41{x20OQsesnSJGhDFE@Y2k*+*q@^XhJ(c3i~HoYI}hc$kpboMW&PAk({SG zDG5m6%~Ny7Udn2dP~Qq@6i-^5Cky%l?|+O50+wbb7R;t2ZG8dHk(ZQ1lP{U=1pXVf zoY|5mb2((^@9*zs1x;MpQ&xP0p+z)zXtAp%!YFFso#l_K>RE)*2q3zgNvhH9C|-+ay5aZifM8E1yO-WNwtkDwiO_ivMh`*;-0-ISw> z_}8iOsNNRYLDS-mKS-8JI(neXcMDEzA-Ue-MdGKzQBKth05SW0aka(y+*l=SDsoN@ z4lp>xb>>{QtYM4SD8buDcZ;V9E%S^CjgRNql#%Ts3iCH z7Y1wHmUf{4;mnsBk5larNMQn$-Z-?B1mmb z3`d_)u{zZUm2bXEOY`crCB){Nc?mdGuMS<{oaDLTM(M_s!1Q|nID#_}<%J;t$-!R; z85ehT7QpHGTpJiDuFOBbXZQ4Ub6{Yr&z>WRGCVlwGtFl?Uz%Uuu(+t6r0{9pQ;4ox zoG3x1SovYJ027QbwE`K2~b|0q?TQkl>;9oN=cL$BIWDehYL z#iy9k$OZ!HJ=AM-A3Ug*|Gol7To80<)n!u*;MRl?R$IqlXzlZZk{=vUwx`DvFt@#D+v`9BvSQt`gh-9RF~4WG~E-cMylHmWP~g zpF&?IvpmE$k8T*PRSgBcrlCJL57JOjo=h*9P$pfYet-cSrcYWJik1A)L1IP?Gl6Q; zLG2DAV528ySeyVHuJ@+jl8N8VB64G?@J*c#=FGVoeQWoxwi&vV1*Nsc; zzSK3jshMacF3MK!JHV02rEv!YKIJi=C+r6azZ}-T8$8Yf_K&{&IU8RIe0R1lwbB@W#`81!5^$ z8!N@Z(`JP75&TfK+^sThSYiLM_KzShqt7l7gWcU-4lb_hB`Xy)`b`a9HwZn4A3YTv zti=n*7pPlu<)hBvPw6;}+y|?=kLgH5q7t3}1Ve29)#1s6E0fOIT!0t)0q~ zY?xwR6K(h3!fKG%_h^Zf=eN%NKs4_&*knF=q1TakEGftEVBAnXjq9VTZQ2|v?#g48 z=UsT!@^U#}oKDL_llLcyGF81hu6R0e1Ax7|WC-T`P;nr_hE#S+h1+LwMS$=)yh}f7 zWKUODw~#8ML{(=-kK5@g&P6^Cy1j+oMwI=BUw*6P{EtL~1NmU*;-L$9;|33>&F2R) zU3vDKi34`SJ~dvatEgQ#BtZ{7vG7h2j-v7{ydsPC%t_^$ zFdAfkm>*JRdLRXeiY>Zl5qA2LPp-UnO1W17j>#IJ%^6L!5n-Zr1mLL?N~{Q|X9^z5 z=1AR`o-u&55O^$Jh|)<$(^ETUq=akKR}UW6p9Bxdqp3{d$V0Qq`+C5scA|h48hU5Q zyLoLsp70_a7u{VjjoPeDDz`O5wdUNd_SSAx{OK_hKUe>Q5;r4Vkf7IAR+*)for<-b zAYL$zbc(e5*>3vj%Um${#u$SBgi^VZsDW|8`poAk{R)E*9b2Dd_w91|GJ>iW!fp@)iQE9h2`$r2f8TBBJa7cgMP zVVo_dUM`&XTa1uXGo$H|9F~(6?nf9@!0+QQoYj}4@O0~OPpp~ke%)3C{QhB;^4nC& zhfLf=3H7>?5Qo0%xq+qUEcH5Y-N`FQsqjP--Dr#Z%6o+0i`h&DP z8J#(D+VpD&LV!+Nd21FF_%9c5E1zFN01YH<%Mg#5@;ikEKQ24Z>iB5GojxmJe*SIr z*@dxIcWOft!i((NScp&8J`G8GsfM$-EK+63*MZ#@;&QBkW5vtSpXZJJ8p&U~}e%fC z&uzziuiQQaG4=_FeYatrR2jaRC;%mDL@^sXmW~-);YM6qg|uC1$Gplq2-G5UdW~~P z#B)|dYF0!VWSN-=9AD zlrgmRrb2#tAzbZ;_3TW=`SRUkuE4xT%9iA8Ec(}tmN(bipvNi4X`4J$t%b*6zju1R zOCxX$QR*?I&zj>-%0Fx`Q|n{qi0B5T_q*|wIJlO2CdDk7sAmK3a;sR;tn($t1-z4| ztMhkS+Oo#RM^`FnzAtSx{w7g<381Mh!zN z%jFQXsB22PAhW;>nu}@zgfS_7 zg{ZQclpNPswS)U^e^3YgiqNomzOP34s@ivs%#j#Dwd|pw6~(Df9osPMH#6ysv8k?x zrY?SkF{!QsjmaJAB8|zWscBt3UPIgUl_V~DdQv%Hu?u}Dz&Sc1nzaW%4mprUh-z2P zJcbzkHaSEIz1xFkftOVC8?Pvnby>WsP`>2J>z2qkagP3Ve3`_MEAMVK-qc0^j_DXj zvUmgu24)&4(azjoQrxJM$)BcLyAQcc%v<*hPxIvq@(pENwkKyG5~VUKX5779;KQX` zQ_l-5jNaWcd7jv(77@j+5FWqocCflnDacO+Z?I=RpBNsfzCnh=E)D(;>wAdEXtg`= zB16^LcwX@pO(c@XV0`K5An6r!a(bixu;$)ybcLA+Y0Idwad&9mIJ}!_W}f-uz3Sz( zhV>CHysA4N9uyu<8ZA*_PCb3(AbX}*Ntsgnv$Hkw7yR#2hU9=2clL~Nq?4QO4gS)G z4ySFYZ4|?xb&0%)6JpF>$R;warHLUX^0MhTNQZsen|O~@3kp=r20j0e!q9$? z*g-j9tGT`Zxy-`1s4mZ}dm=dM+YN_{M&yNPOENT>>1Em3SdN&*!r1#m0K$iYWC8{k zmP*7>7f`W1JI2|yb07H+r9&*4HxtCmP4)GqEa&UNc9+glgP~>rGo4d~(jT&$HDw99 z3QvkxJ3Pcv?$!#s%u{M20Tyy8{0)#!eyc)$xB_qnA!R;?n!JwA{cvio{dg(m9_?5>{BV&2TJcTwaB z;bQJ*DJ=dMv(*6U$4oeJx9eM!1xf79? ziq}r>amg2EgQ$Eh<)>!ndMxBDl2%8RPYz7*_j&Ai8gi&V@k?%NkLulDWZ9fd4wm|k zhf980irG`c)%NRvCxO7FP<8GMUxVpK&Y0g1E<(-*!W6C_^Gib$#Kp5TB`o5pNd25= z_%_@d@o^6#S9%7b$3HyhgsW@k6S|aPGF|$wwTxh66cpxpDdq}9+k)_W4XDyz$iriZGUp6^Z-wA)n+37PYy1Rgv-aoUceETB3+;9YHb6Gs@M9TZys+iSWYfB=O4d;*cETwRa!#PJ;UsU&O>?DjC>o7h%5q`+R8A}=agIuA% z*7Ut47Yv&+8bXdoZoduhXu$@j<)2-Li@JXKB{8r+cFoElXD-_j>>*h zSF1KgZ+py>g${?e&&A)9MT&EKMWkaX({Pj1F9ASwB%M)pz{py0lQWzNJtI-`O#cnw zPEG5#sAU|2Do2?MmSmz2Kloaw6I$U$1QI*}R%RdP&NRrIEcPYK+3C}~HuoA5gU_J% z0DojWe;3>5X3}Ch`tEW0;Cb`|-3Akh8})z4hKFXx2!tL+2$4>8x8W|QJ(ih%j z=i0S@;?gLYQy~Z}O&t}89TQc!U(KCG_lxebUW$Qp)Opxl?%#;yF@T`M-vt7y=yK@R zDE+qPY#eg`Q6?i61DOcilyKjqqjZA`C6l|#7kx!!+&?xzV&(XkXLwRsE z=fPVvub_S$G0yPIxr%-$E3&G6nL(mq9DBT!dCSlsnv z>|FsBhAiG9DD_+`zI6k&R_laQR_zs_53~;?g`+!Zj(T?@P(!@#_BNSHxGhw?Py*SB zn`z9D7>VWKRbizgv8W}npA8brP*@CS_aI9VnnKcU^OR7HIM)otCDo!s%w_=#EN_? z$2zeDrc#5iI91hbmdOnnW9cfhQqwd$Bq~>4MEKvBsWz;9$>4-w5bDVN-JNiTN=XiP z5cD;o9JiY7W;Xz#1&G1JY)p&-*0kXDW?&O@&xsy%wo#*cvhwkosF@R;PY~8xWOsOu z;Ellgt=pdN{jF1<-9pA$&Kw9VKa>Re<`{6Zm7Jd~)tXE=-h^eboNrvPd}I8mz%# z=V0>wA{Z@T?H_wBa6Clksl(}eMZYX2T+d*S1;ICZ|TR#4B)JuA4Gc;9J5}{dM=(qpMmA!t!5-XuXC`(Ua zZhek%xXZb%?YAU~E_17>Sni`qZj>XPNH;Vz^l8d}HAn2+WsEZ{MB*{b$s6>yK3bw!4#oU1x=yXUR`c##kcl8AH3HXq4-6`&xko>2g_nwUqWn(+;&_ELBeffV#`b1HsIZWqp59fB z)Z1f(dIM18kBw(rs>4l_c#sLN=C9%`SHs-NB`de5=bv`w{j@!u4=)^ie?c;hv9}yB zdOqUyPMX887;j|V{QE0H!o6CqB=O${q%p9tGj{9x4LFIQQ)Heo@K(t$-_33IWwCu- zAO%MbKfABmvS*IC(h=vt|J`}}H+e3L__q|Nix?an{MnfP>FHb6X*!_%t0Hc0cL?}t){h@SbzkHg_ZYx(Ygczl%dVz@81yEW%&5C*a~9d zV&Jij9#3}4v#NUx--3I6us(u$h}1M5e#quUrTNoP#nUL7kxI4A!B}%TfF>gDP{x_5 zxDgL&ij?7+KYWXYg@wh={8;`>S5&S8R~r>8+?Rb`f_55Z$b=)2KbwwwOZ-1823NJ# zbFlcc08%Hvp5223VMk|2$1-;w1Zj3==GdMs82|2r)DMfpJGVTgp`EKkhv%CyZ`Rkh zH-olhn;HAjj=OSrCp~7xXp6;s+J`-qNXFH#c&nE@0q$G1>UgS(R*tZ`DRA(u6+$F!k>+a?Ba|0 zv~!*w9*x?-STcxkbAO?!&)u9)r}(-3{rrSe*{oAo(9AIQcXvM(va-C)W-e6u5S5m; znkSw3uWTvB$^nWrlw+m*AXQ@=7464hym%_-Bpz`zTjo%lWjJpur04ST`Un+gDowyK z5OHR1%tQiXrKIS3gi;AAo+aB9t{&k*!UG5-O>FdAS%#`}jtPd7gg1CNUrQ~gLBi)5 z92q&8D^XKc!)Dn?Z3g{B6m*KEIAIE;;zOV51**T3{qeyVyPoaVlnMM#KeD&_8V!X4 zG%ll6BXg_jMjM~C$@<>|7Q_+GH=6+tj#M$`^aT>enx&Pqmo`@IN@bbT4S8^Z7AzXg zZ=Mh~4|aTxH6W@?V7{e)8wj>L!(48`8G#Ug+-eD9C66HUlwVr9P81eIVMkuMR31u- zlrXEEakM0hBBaO=PWAN&r!v9Yt3bPky=%<1r_f*EMCw(VQc^tnH{E92Eb#tjzdSKlgqgdELQH3f=0r~L6*>qRll znlc2K#uoK6a{>3~GnXK*Z7~7it$dh@F6`69KdR#_;a$Qelmr2lWJ@-xm*$fjBDRIHGs2Ah=`^tCIR_ zEJ^xgNnhMMzBU;torcGjmw$QU1BjE}xE89RH0fvU4r}7-^MywF6%0VieHpc88V3at@zATYQS&MGY8b@_2Nv&wbErgU{7%Q z|9;_d#<(IsJt(XZHB;E`1`(IZz|dJdMo=xC`Y(i_zgn{vCD6kOkn?d7^VpPI$e$+Gw$M~8{vAFv1FLpU*>qzaAzeZJt~b}_0a9{n&%92j>vb)$!3gr z7DD*P3o|3nBbUcd?`*BX*D|fV)9u5pZnho%uqco{d1({Kmfx?`-9F#Xv@#wBU6Dm` z$79!|$?nYFoK)Btx$F*w4fF@QSsOrIZqEV@(s7}XeW`;bJ0g?9)hp1lbRn7T&S+mDzuuh5~4Tidg6L)bbL08}$q)QWteh;M?s)(LMzTT>FcfA7x_0j0fN*k(bGB-Q(&6K3lI{gG^HB{>`A)n(q#RC;{o2KKy8st)J5+Slh5 z;@9m2+JVbjVo-)lB*pjw_2RHmWnXF#tALGyL>2O_yYRrD9yf$^S)8fev-qjV%O&k2 zHidM+SErMrJ*bLvCkrQu-y9I}h7A32C zK^oucwY!v+U_amJv^`_Md|s&4Yxc`U%eL%VE_uvbOC_Si*=F-KVs4kNJg-0^57_rb zfcLna$fVx`Ui$*H(}VQ1JG>%q55Yjjb14MEnGo6IkprE-gH5O-bw=V$NRHcJqJ2r| zqrMP*ZDNP)Xs+!(QRT2_}s5}#xx((S8zx`(p*bPuXcI3A&T~^nIrMn1`~Sh zV@j^8mwjb#ozvFhj?E`>W14p7+ueBXhyTUZJBG*A{?Wn{t4SK$wyh?O+1R!l+jf&Q zwrw>|8r!xxvH4D)|M~Eqv%k!BO)`7mT=)8EZ8p`bBXLVcu6+BgE>N}}6MZY$wHSO1 zN;zwkcxw{P(y;>*%-|JcEIPdDDtG1t56Ig@IFd(LkocV`2pd7WjaUC zHdQ4-q_y_PDgc^)V?C6$_u~`Z`PlC7LU7Ie_%!JE-*8vWH9vmgJ z2C5O2?KgnQbTFW2n-J=Bp9bS5um6`G-rupM3krwoJ^aiSrdn8WyOZgTw{kC+xJek| z0$d^EolgCAs3EcU(qDI`(q7c>@w-sB#e#0li*SZ+?2aMmgIz?}2d6Y7G z!A-piu;V~NIgu2+i6@t^_Ce{EHAFZ z-SU>q<~v-fIMRi$8U-DkA9vgY#F zJgmNqJikUc`7@HIu-tS!8jLtv-LRte&y}cQIhU;>r$e8?I~1ets>Jr7@4YPd9h$YP zal@A-VK#I5)USd8VMk}#oNVR)9Kbr~! zGsfz77Z1SX*lVQ5e7HInH zMTVFV@ZwXqX#c>>vVCU0JXYYM?aI*K8@m7+YT@m&jZLz}F+^0vtIe#a%D6Sa_`CrZ zz5c6pk<@)Z(iIyx%6BS&*n&V%IL7>qb5OO`YcZ55_-EiR7D1Y{Yyg)gZJ}Wc->CfdK?0BWKOJ0U5|w2_I{H58&Sbl+56KX_eJw z{4xcH3iC^bC% zhmfUUXcqpJ0JZh;>KU)~K&|b)!MLIjtw_;&F(77+SM!U#T~6x{Pa&K-8}spdy7(y1 zuE*mtA;;GXW(GO;*D2%;Nd*P|j?yhs0}AiW$V*HYcemT5SLX4iwSLKt_FQjv;@ddi zAVUSy>u(=bw~&g8T#h_hhK&*;=jue=@kvSU-YdsabZY2InoTj<0%v;E=mFm@od0-x*K=Ew( zii2x9E-jq$-%I#JFb^OTX28+bsJOC-ph25%Ge(wY{^kaN&N{Lbu(F|$s!ALd`X_}< zrg(m9jG^j{v>h>Pb}s62r@t$i8g+R(aBa1$Y0zp>XcuRBE%kGX@c&oHo(WCA;pFbh z_surNff;meAqTdkgFnk}I5;=sZMWHabu5`3?q7iwvv__b^mv`hn||U*YYv8W{O-Ff zbiUkQ+XL&)>T)t>94d!TV|QX$XBw?6pNO~==vzj=tScN-^fqnq8w^t$dh@Y; z$`5MCYz6z#Ut1}X&jwi|@(L;>Dc#7m*!lY>nI=#O;;D~0+-^k5=Y85NzlM$-71m~e zV19aTqG?+xQ6nIS9JJR)2bmv%GVVo+ zNNQnjT-y!ZDYQ){&|yRM{E6Bz?{9=35h8h^3YLs5l|d6X>5T`Y!HDp!m<0}yob#tB zN^g{z{i;Pu3}%s5k1aylyr^W|gV!|-@xMzxDwkyq+r)d=f?f*pBOV?w($pyMxvO!| z1^a4_K zsy#k(`Jq!|VCgWy>AAi0HXbk4( z$0v)c10sZ5h~fS;}3TD*gZ3$&@LNu5dV^h_kE@GBoSEK6>Cy>;>$?B!y$_GnXMit<%I)~WD`1OcyC+Chtx&Ub`jR|K8r z`}yZmIVZm8$VwOHZq_f1vQfA598LZMq@%JGOEsG+!CKjJB42O&ut1OWJQQ!>7=60a zhM;TJS+Z90rr1p}%@HN7Ah-@Bi7&-(AB{7lr{a1XH6FQ}ls`yu4rC;XlhboL&atmS zE%8MYx|p!F5fQKAZl{*Bdsi1X{rdq~pm-rHrKRa8e)0Wic11UD9DAP!=ftusa>uv% zTZR`|5#Uc3FH^2wo3j+9m#{LviT|Umc?y%7#0CxHmbF?H*XHQ&?-}(Kak={1N)aMk zn?ZDH7EGH=9;8jOvY2IGxMss;p*^o{u~lFMCnmC8gk<2D%EuNbgrkUDp`f9bR~rD& z7|Rxz&2kzw*0$zk5c8X?BOY9kJl?Ui>S&u<;Z|VfcQ|!$hwuh*xOV z=F4kt*q+k(H#T_B;(aVb%EV+JRD=S$TG!1HSlNFjx_T3w++U9h#&Vn+WGPwaGTUII zpUE9O0N3C{NV&QHFt+BG&ia0MN*vXw-&cK}k(Margd&e}+OD!&c8(m}+#XH!?Wz!n z`g~OCb!wH&Rq3?WmuZXG*i?!Z`;yP%w`%^dMfUh+Lk<(DbsY-Lt5`Nq^;}=dN0F9r z8bs@AbDCO>RHX}PlE8B4d)=fGA*-!ROki6YC1P{JiPQ)4XxCN`Dz_kJVzR&5?geEt zUtC;NfbwwbO{6xu!7mSE@VE?+c9ELiTG+-B3aqx+$B7bvq;IZodY66Y%w9Xg1%oB7 z*pXGXm~>Vh5*iq+9qm)TJ3Naet%KEC>~C(qZM(W&m+exCrB`phDe4kTZqiJ~t7AVN zx;W`@+Flk>ffhR#kzklu=hctOvO7{Q1SA(DCM*EEc*hFER)9bjC^6Zhvc0wS{%k3( zZzuO5)ctu87o;YZ&-3#^9wkMJkYL|HznM5(isb$Q6S}3v>la1$)i*~fZ3hNTo9`uG zfF@fB_L|q*J;g{C)<*~95gtDr`DBF8%@UPyw3#YB?NF@*RK*8_OvsKKvo{oHzt(J<2w$j_ zALCW2s@hhlc6>|T-wlqVR_@g`Vn`K-9t`CCM59_Dama|`r`;I<%MScVE&WXmueR~0AJY&bEFq~ zw+rDAv1+7h$^2%hM-yt;`4-a0yQ)ZS0z)VuDCfzht0wryxL~kEIEKwGtsoT86MASi z72M`~qvo40$$_){meYCbUvuKU_vH0BOwh{3<#j1+6#SJ;EgYj=tKv6qm8we9ajr#0 zRdQ^1zJ;}mMa(KBNYM{9VmP~gD67@$eX5l!oL;z^bm|dpsrAxh>UHxr(`j?-wd05Y zIDo-{i-v|~zy4?E;DE!R2LK;pwDQJYt`I8~HF9Sw_?R-cFhq#-RhmuaqKBSGiB2`DBZN1=4|lB{k;ci_np(PO3r0a^Ik zP2Q|)H=y2}VsTJ;D)H&?A(ql)@^Wo-4-{8bO~N!d1X2q^r=VH&@v zW5j}ag18^<(RS*(;8Yl-Qa;qgGY(-Vrig)nD{lj1V`Wv<`}13u{h7++Lao-wiNdcL zw5T*D;5lLxC|`IXHtDjZt# zmNg6ReJ?2C)DLjm#bGyH$WG`?=@>0UFV49TOkpmiK0grh-=Cm;&QusHblOOpFU-UH z_tAV#Tl2>cj{MH;tC20_&2VUZ7yIyHcAAh6zQ|(%{ait_8uPg6jy~mTl4etyFWkh*08zk*3r&*i__F= zDrED=wgl%##|o!E5sFBXcF!QI0%Ws=L~4t;5a*Vh>Sn>=U2GvA3pSmplpO>*yYItL zGMAtp$82?tVp$&&mJ82JsARX&rOAoL>Sbe3+R}wz-7|p-GaVQxvWdRdt{EzeBO6wx z3cL?8)T%c`HyKrh@lx(x&dP`4${|w`BIj)3?QKHV{$+~Z-`plwKQa%3QlGfMti>Q7 zgJS<2@+Mqv;ZN*Kk}s#avf1K9$%YlKtEC@oX_Q5Zm9|(XuF3(=cy<)?zTX{)6NSF`34-)bS|@NRuSwD*djk2^q! zHP!veEXe}{N1M{a8C0tl^EA~|A1!TaSEN+Hg#=&canczKDq8@NKM!~JFZkTQq5ucC4m45r>`&eL>_(VH35edzW{0m%mzL#N`0@hdqnTRY zrCg!wtevA$-DlKtBO5Iq*hw})h%;(8pDnS^tPnco)5lzvwf-xM33$Td5f%7+Ch$`ii~LAhezW}dS&TG9o2Ck03Q1!_vCHkY z0SdD&QJB~v8;kB#m6BnE!A$kOWVLBHbnunF+MH$6Dx3MFK^q}1E-nVfy>nY^N*m!* zl*wLoH{B5s#aKzArQqkqb8jly$C2&8<;forA?lp7)xnriajBTIQTFHeVBEQ$S~E0< z{mPp@f>!A~&n1lO3@!oU$ ziiTcNQWB{XqZw!>1OF z<d% zEthO%HF7i;#c?e7f;A3Q`Iu5e54&Oc>KferZ;Y5?Awb*WOMQX9K zYaSf*>Fo?${?2~t(Q?nXxBtCBv(XHV#1*z-1uL{L=?2Ks6v4akY~`b_yw=vFq8;?S z3`?;wGrxi6a%#It%zD`rawe-wp$bjE{x#+9hd!7K8@MbdMSizBGO?2Oc%7!-+%EdMO9U6oSIecYh4=<)b7zb?j(!7ViDig^DTS6eF}L;)3YtXmh8ugv3Pc zWf|hH*#_!Cof=87X>CJ%+GJGL$^oBO{j89Iu~K6Elu|Y7aFxG$u!#B=d%z05&J#A1 z%l2_-Rh2NTe4nm8?jfh>7E#vKPRgYFa%(zdI%>0Q!sIphtl|(Jh7lqvIbIcW+{1uj z6&Z3GPHd;7$B-ro`%oL%%5dFOvQ|r@&RQhk&EuH#@u2(sYqEpS4P)8WjlS#)O^)2P zgUMiF3aP%$;^)H{>_p7t|6nq(s#zJnEs_e9x1b780U39V(Fj(o*k2T%ZGtsmPzQJ5eUmTOL-?W!4AiBtaYd1D|SA>&W$A84X?*494co0;%yg?gN#`i z{iSXA+mYts$9hm>3(+`5yvN}fr(*aa$jdgwpOG!#)ol9`<2KOW{|A)B|NPu^6DE+x zK59}Asy=H4Di|9L^6O;rHSjIFT8>z*QSWdy zHn*w%@rRezYApnGLtfFl%QojNy8w)$ATpneXp&@3Tr)%oi6OtwcdYgUQZh0Y7yI@` zsfVXO9L8p8#nnD!>KFz4ewh6l{Gy+>(QnP7PRrz(fv;meb0>4}`$Xm^m;2=x#PefE z!Xd$dy7074=`z4{qrH)}(UJGG2@2As6ZzsLmjdJ~V}${jXcVeggQVP`;^)7@q6B&rxyMUH!@is2CXL!Xl=@6USq9pn{h zRfxWlas+WBJeF`cn7Y`Kuoqo;v&_y!H=s17;h(A3!>UnAbXV8;%g31H>Z28E3VL^k zUCQaE*;GK@UrhK@(0p56n=7K&!&++GWLwL}F*Nc&7%#;O*xxf)#x^QyO$nQF5hYQF;RT)Qzs%V!Ht| z$G2_YSd|wT<+GOB#4x1Bm-|%j3Dt$ouKPZY?kr`T;k&f#T2$nJB%iCX%77pF4V4bH z999o$arvQb<(-F~HcNc7+p#c=4Y@+w08fY0Sd?fhySG{+SghuOJR|cnXOrNN*ubIE zqBwOi796uVAVdKVGoO_~)m(lwbATx25_(ygzOC3=PHqBZy{~UP} zlod%YlnmWpNahgt>-*d}`Z52BlBVKXQHT?zXzqGh7bPVpO`Ja+p6D~-EWr&vbQ4gG z4If&?F7;&6y(uEF^w=x$Hvmy6J7-a)Dr7J&&-7o?T5sfz~9w#z_`LW zmv`@2jP-uhA`&gNJra=kBHfeKVyoaOhXJ@GteyVw&@_oZS`q2Ti~cRtELZI@U^W3= zrlxR^fu>{04EkN`q${^~w^1Wma5#+40hdkYQrayyPF`;wH%z-`BY8@V+UGz8i*Mh~}mt>Bpx8qciko3{UL*^YjFseq2+W3OWS~er;5f z>)(BM_V7#9DiGk|Z*Ff{6bR7nYipU^tC0K~A(-$W11Zm@h?<9%s&Wq5POEr)(iy_( zjGFy?Sl2pixz2%ZFz)_f0f!nwi`7m?lbETe(vLF(+-W{ceY@W=8~Tb$i2IbXjWmcIEvAszb(YlQEf1?4u3m z%gEXaZ{B%hCGWjEVCg$Q0?9d?7aR(qBpNxC!J$PjHkgx*o4?1&_b#1hIT&yXa2r5kW$s@m~pf$rDG!WAUG7Gvh@qnZs2@%4Sg`jMH`X zl(p&9mAU24t3Vg0qM~Bng4Kz0TVi4&NJZMI*NG67B+2D~nzJI-8gL->Z*2l&W&|L8F@NPv00f3&wX~Mi= z)<^qI6ebGD7;WZ)672@NBJrxjpJz2|^k8dX6LTXWW|sy;#|L*NVNR_&vNKIuRq`c$ z9X}gN$-L`4P>Zk8S!wuxrH@Bl#Tj+^u78^l^I2mPsMK}igc?2eI=@~#DX4`c-lb0J zPol`38Tkp754N50?Xhycy^p=nJ*j_2T;BQ4D)vHx<3!xjT6H)d{w^B$i<;FBT0^;* zX6i{AiG~AJSlODLfAq4myY%cp2rNutuaB#$p;D;Y<3$1htvbTM6{l-;0lW}gxM~!F z;epsU=$%CYD!&CEkt!{Te9aljL8{3Gi^9;3`-MXV5* zKyQ6Ps5T!%Fo6odSgnHyTIF|$nf$q}VkPFn5tNGy*9;8;HP9Poz*-^~qRSoAA`Rdy zxsDO3s*lRpaTW03Q*r-8Sa-}0w)sIvvooi!VuA|ASETi7~FQH>SG$ZhK1S zI~tG6`%MsZNLT5;-H&Ls{tXDy(s)J$03ekY0X=>L@njMpr7itpwq4e6aBJS2zFN^; z5PJ27n)Vg3ocyo?1GxWdG1{Q>k?RG%O&+udZc>NY1;FAL4B!d`^zN>eFC~uSROW}3 zLRJy|7}9bnX?%LGH>XTT`u)B3^~MFTRR*U#IO`JsyAfCPS^p$PLSr!!WP2RB2e;-U zyuJupUke_>Qur@{=`Lw>3FFUBRn>7*S19Udp8?ON+4Du zg60=mN+8T+$=Yoirw%Wsp*z!7AS+69fRvYrr>1<}*TjccDZ>%on`2jT8;Up8fXU%bljvy2im!8iAQIar}mZF zm2tRt3$3bvG1Cq<&YsNqlsR6~s`XrTht~B)JYWP+s$hoxT1QXwV9ETuL*I52+#qth za2XT`sXR7^+6e|PqNpI4-+poL@oX_F*4v25u~Y;_rsrH zHH}TIcm0+R%BU6+pa&wF!I=VHYV?>2ncOI{GqDCwa_P~e&^+}mg!q@*T-$OL3rd-7 zh+mq)ZvO*7026Ng{`2eAr(Y)5$I#18yB!{g@Pkm#ea7;j!=*j7(pKHhk;#mU=>pYb{jcLJ%-s2M z-4_IlyZO~rU(=D3!T)2Vda$KB!JM*0Z{Zrs29o&ypn!?lTTs7bE`VSa<{U*L+epgb z-(lj973ll^VrpXIPXGW|IOXDjK0xF3Z&Uz)s}69)8_?$zW}2i%h0+oNF^jwF;&ceo z{{|gwWJ6%=C?*T>`w}I#&^h!V*#Dl*{+mniud~lc^O(KpGRZ^`%LTYXE#iM|;8#^u zHDaj*EM9yiX>@r$-;6bY>k0hE)#j=&vH;Y#6Vxm1Zy9iVSYM+oM~JoG`~!4E(HIud zX?3JvU_d;dp6tPLiIJj*{tnn~g23$m@622#M*S#a6)Gz4SE%9w&K&(#IeNwI5d}<} zF~1d0i3=3yw(6e~&Wyy!^_J8Hi0OjHJ~xKMGiLpdgUJR~HwqqCY-yr*`eS|!Uaufv zI(az3+Xa-1o$fqhc(XZikOJ z=@a!r_W^9-oeTagQCGoCo zU09>h$obvh61%5&2th@-O;R7wAOU(CU-Yah_vGgvPXnQ+->n9e}R8%4d8zi zP>#xT(=BA&QA&-Ohq6j(92rS|W~^ESTZXewazQQ_ll$9Jd6d1qf}L;VcZg!gCO`Nx z+J6)MbZOAuO&CClc)D=C--{!_KRmj7yET;=Hr@XIhAYNlMzQFfP_15TLHAPI2UYme zULJYi#W?K8t(Jyj$To%;>G03o0c;EPJv2eo)ybpKg+kZ-!9wpi7!4&{4@IGHlwE@I z&7A7P9uIwmZDy>bP(C?QP_>UsLd+Zuf;;}#fhT)r+!(|zBkV7s$pr#F#K}_I_6DJX{vv35P9HQ)t&b1y`1`XxrkQlh4hY}_trcW2_`_!eO>j$^nK&*Fs{^v1W?JYzf#-j}4_$$YNu>)3YWXd+yG1Wx& z)(VaQ(7sCb+uPor9_=HdYkwh0t=87oMt}@l{G6xa=BNaZ&&mRxoQ#;T=FGA(TuRH! z56W_x4FBS6g=aViwfJv`tG@mgXUDPJMVsS6WJ^oSv%GuY*;;zf`nt}z1*rQreGL|@ zUmH@hvUKqT<1i$O$5#buoA2h{_e$Pst}mE&@nqVSij8Zv8T0RrFlN$`1Wx|-C<$hg0XEBl zdFyzwmga9$!vtr*`7J_ZRY`>(Ia)jSk9A4O(&-|#lcFa{x6?>TJ!~u+c>hKr44beI zSc3M{;|ebhJURUBupbLMm&v)|Km%L=fRN&}Wz)=+v)gnF&8qWgCreqtU5>Ed(Xb|C zbbL%*Z$fEll~PEO7_eZeNFGdkm%GO@4Gtx(JYZvN^kIyH^W%WjxF#nj4Z>W- zw^wD@4#S>ZH!_0!+8Y|Y!pRIz0x;WmaWB+3GY$1rD(UC_S-`GV*T8)i4_Bgg>teP? zDmFcQ=C=t+su%B)JL}6ypX=5}twn;+Kc%-DBy~G+6hCCmQ!Vm0=IV?kSaAq@9>ja& zeAM$tw)8cZp*}HR>_&x+hM%Nrkj|Y9O`L#!p-*#vA2(J$&&KvsrIR{Lc23vYc+jvf z4CMcEmNbyfcY7 zSE{u$7jyfOkF@x?kwK60De` zo7~i06tkH^su3q`zsIhMgE;>6cv#0~$bWMW+%pbWz+v%P0a|Xu%~|Y<_j`rVUa)k&ppTp*v2f;(k&kAkL^yFMe^+t6CivEkoEKf1q(=O# zZ9K|lAcekH{X>-TADQV2I(y--jjv$DK-*x>%hlfQ$;>}*V>J>^*OxO+U4&Q*0{nlw z3`M{1s)`8)b@@Van4+wIiqr~O}?OK;&>l($CeY%Nf@tT;kpaHX+YU>+(zOxcV%Y*w>B}*N=)9Y!~ zG~qr4P zk96;b$#bK;`>bx=2BkAZ!{NL3ak;61r(>j|S`dCs9m?Hq-}HX`1*UxH!-(*5XdvsE zH16&&1+&M?wU8s0lTgupHvHlJ^>Z#8Jzc4_W!mC$7+)xpi!g7?u?eKUY>`tm%qhF{ zu9nmGV9tC23kPMCaD8rAq z8#sb*aqDnWaDNkvNf>d1sd-cN&;hFy^{0KX44d7alF0h9tJWx4D=vq~i8FcHZrVAa zYQ;3kI6cYV5WWSy8TSx94f5?qL#%D;dp;M78Ua_$hZ{B7@;lPe-HptJ>a7E9K6o}N z4MOc<$0~j_zuU+Oe)ogRL&;{gg97;~3JfS}D+{sn029Tun~J%=trDglurt5gWJHV~ zo5STR5p)GWYdS!szZ$CQOrx_cat%fo0;fQhj%wtKDfo26){>@YyX}R%*Usm z`R(1+96$Xc4q5H_I;{V`!>$7B?Rjy4E8|p3;tHW@1*?({>r9L`2pYvgHUS~-FSsVm z1sI5T3fbuMVW*hj3Dz@x9Q03DXQ04;?!GdZhBGyl3sYkqni$h zwo%(LRG>ex^B2&;Hd{q98%XrzPbwR~EPuz1yY$aH~`&+4`zWu!b* zD#iwxic23`Jwz=h%L%C{bc0aUAO>5b&~T%;xY3*Gq9Mc@V8WRAab+!yXp3 zCv4TvT>x;=MmK`YskQCAw-O>hkgEUg`sB(=kyWsUd_Y#u1P)OPTB4uOn7IX06rV!hlqw_l?;X5OWjY-}r(EKH^kL=ea89&@AP;?XWPU7Kh5E zQIyz*zpqPq;|kNv75}z$Rkw6apg|~b@ATLv1nnh-#~-d~%;*ffNp)_k#5LOz5+!p( zVskL6bTy`Q#?mfFZ&+g`D21B_v+R zS<3~&Zra9bMiW#go={QE`N(`aKe~@%>&i8{jsoApjFWIsI2+b;u|eUO9PlF)wwe5h zc>G3(OY0q%C=N?>^eHfb^sJyzIs;KdKLb91#g+GG_?V_eQn_h5T>xIHxx zm8bX&TxjyhFj{<%`v0{eZXsVmEJQ(eML$FK^U}wDbknnUqUsGAz~FGU$e{6DwbAo` zGew=n3%D<|ogs#t`(TQ$hPb4aXdqvK5Qd$MLe$|g9we?LyI?A`yZ6Orr?wtaRA3{T ziF)_z`8S?`nC`NIj35=-q-Q)S3iel(WlxfqGTqf!Y7VJMMCSfYTx0{3_ z&UBrDOX#cn@w#`WIIUVKNOp1ASDK16ug8t~=qLrAj(XR53zysF38f19iTILVsZ{E_ zf!4h|{fN-srqoq%^Ka7RF?~c_qBTor&b+NUc6oP~VFu=fN@e{)t+qfC6steuJ>AJVG7g`OC`-$~wTa&&Qe3R^_*Doa{~l zo1kgAjuc=Uov?S=D!rJtjdcTN~@{{?#M_;c2?F0 zK>|LHEpWl1Zo1kbDxgbMRg=-DQZQJxRa!=d2nVfVf`67WW^Y~rrlO(w-P8aT9}EG&fk7lvtypXcYoc`=rY3(%%Pj`;O0(CF;slxU=%5ec0O6_wVxOx2S{Faps< zjGXC9vdzEU_T@-#4ki8an}+GjVpi?W&IZcb7*p5t)i#&WmW42N#C)KH-R0C4&@NZ& zh5{$7uUD|$6*y{CN3WH8ba-gQ=p`u`egN<6Gz`){As`?S5D;LXRZQI-92f`*32|uE z8OuU}jvE36P4QTa`V))9nP<}Z!1xGIBZ9Nyi*kN{4?}{2f$?&8*I+~#*B^5B0cFo8 z3u28odv{R`cDavF2skf$jh_okT)=4hIDDL$VY-;M)-K7J9v;xun3dTjTicyPFDu+O z7R3fdn1KjW3B^;)dE(*_yj6KDgH~L!9l?%z&4^-|+r^?N*mQn%M&2yL+DtG1AZV~7 zCd{3-9YuIEeZ;Zh z(b0N{(5$R1Q&yZ1@B=5lKI=P&DrO-Th8F2c(;FRdJ}4n0MfHRfDumYz_+rprUqcU7 znBO0OjacEKf<-uzw+c}P`H?txpiinlF5lkZ8xIrV_B@a;>12tTDO!qU;_7j#nbti} z?stX!WVjVvKb^~okh3vzRSy`a*x2XAWpK2-EN*9k0aD#9^`?z|7L9q*4QJ3?dYra&qF~=kJt&*QDhC7>x2unrb>QG$M zg|02775O4v#*ZQMxLH0hmnXgZXV(jyJH1)KtwWAYdcxk%Rp$lIzth;>2Sl2hYBKn6 z9=98+3*Q`+sm1pFe-hQmb_651c^y-P78h&%yEPpc6e2|Kemz* zEO^eBPQK$?Xt4XJK97vGj!;O`(_p!k%zS@aw&IL?EtB2)u?4qrPF*ZG>lpD-BZP)v4QGOPmiIlVkH7*lkmYE%Dk^+S zJ(t_575lYQ7^Ro355M0MCv4B@YDVJ3!>d|p@ZR-6x1>n8Pf};qiH9lJvUYS7Kg)O3>%aavrOEW4!Zj zm1X&XErP8M)fXBp(sUad=-KRxt)v%&=3FcRDcp04aLJZRD@Qre;b!XRys1vGd2;UF zCIuo#4?4T8Vhz3u?~Cl1Q{og_zRDlveiw~RTzi-A*~*p}EH}b@FPcXJHj$6tmI4+F z6hD5HoIzH!N%T`Mp;YCLV1Q^Ig6IlgbsmG1neI>>();%8%|b(Z#HJvo3k8j|>vmhL zpa!o|B;WT0)UDSeQrQx(l?pb5D_9OeJr-pM9Sigo9$E33H3EzVUP+*NdfACybnkl&*fP6iwl!NDF(dn*LO&0-)(%gTz8C>3)|tK zp2MFO^HFX)Eu$0AFJm;3+)Et9w2->ENO^aMB>B#X@Yr>AeiU95Nd^h$wXoWX$35g_usfb5ZMNdx=b^mAOMyR@P_ zmmJP%U3Vq5dao&qc!{O-*xYLk(D@VjV)7<-`~+9BPkS4!!9>HSqy%keRsRp7P|oZ~ zR&=zu$hT64Hl_Wq7TQ}yl*i<77|Wl{6_lQ=F@xnw{8f`A(Xn43glh&;WY`uUbVBcV z4D=H+vL5CZRx{6O*S*Ysg9#NxxnsdR26ijE-&Fw#|-h zCmo}bj@7Yk+qP}nPNw>KXV%QD_5I4PN}cIV$uxG`}D_24#Dn!a-&6& zZVr~Eu3ckuI(39!@OY}@Bb{`OB8=iu^}lorN@ae;AUDJeb#R0Y42FKGD_)EIr5J2x zAqpnRaY%{xhS36T;OK&c)5rMT<<5w0RmW^!a!EpnS|;kST!=J~KjYIrnl8Ybjtt_o?09fE~me|wb-AlpE$Po20_^XC#Q8%3panPX^Oi;VC-q!ChL={M+BW4htKto~U*73+&&fD|4#7XJR!s&+nk@ zzSt)D&9*{2mHEVnuf~XEWiZR;_RwW>D@PnyAQ6558%TCP-TT;Zrtp1q4v&orpG(?{5$?UFv zxUJ_{&3(D35Y%g>fvc}=Wkk!D=SNrg+MnqPlpLVzgIStIl;F619=E$Le>iCoLcs@J zS(nUwh_R&7epyrWHd?hn1^;`7S$#nBUuaVLG9sxmgL?o=CeuLqQ!yms^L08sWigw5j9bD)srng(sMJc!!C}W}5e9On{ zo}c(W73iT+FKUQq;|ScNK3bf~xYv$}&70EoiFo|l946jFyocHjBaQj2b=)j7_u>&z zjX2pQWg%>_C@|$PEO6~D9@fozJs)}Yo>2UrIVtm2&6POA?nKdT1u{&BZMrlw9W0B} z+z=lu{y0Gj-bxmHQ1n@r$6$V$IoQd+aP;*uJQLA&=_^8CYXM@8^XGKN$fFWt8C~QT zxhZQo>#~Eu!lIFni-I+(Py3kOg+J3lwAWSJ={LKd#w9Ur=7k8 z__U4JojIW99wLD+VyFA}Cd-c!etSz4g^cB$VXZNc%`idHk;Qe8a@_E7GRV zFyJq@)7Q0?I-+IT2b{1>*c}ADI_0&ABX!{EHrZ4^=yeU8`IP8{qdT5^*})NLg+%h@ zZtjqDO|PX3*8t+lZ@3>n>1ZcBMh0)}qz<@5>V7FhbEzhdcju_n$B45&+Fp%cG|SLo zmLj0BMXt@;*rLxLEEgKos1%UJS8&4Lg}LU%Zu4cYLE6ZKPTR79dC_PpuV=5N2VN4G zV{&f0?)wnX>>nTg@dSW^YBxTQ@D=-B#)y^(g1@RYLsc3k~;Qh&!5)oG0*Nn+yl>HsQqa3>oyk_e*TmhUi=|+ z+eAKUoSUI^{-IxxWXjXKDxZ)jseQ(*r5c3bSU1h%Uag-b{NW1}6TgUYc8DzWhvW1I zoPBN^6Y%N+v7kj^`q(-b{AQ4$OlxmCLg3o4RaS9h11c9vkxNSyOjU5gwM2-p?vxh( zOEmd|&`!m3H&kffa0t56+*+9y(Xdb7XHznGeGd#~=+)`asP76WN(1M%1v5fEi_Fx^ za^+9Xmnr8DUz&8Q^g3#5YqyCk%t-03K00oyWG;QHR)^1?HUmoa6xUc~X_!P=%=tLg z*%MjCb9KCwH2HHf!R%N5b*PK&zUE?>quwo?r3F*Pll_1nJVX2xi{0W~vDA?$RPT^@WOv#?YAz;Bu zmDJy_bmfyU)=ukPyd3+x6i=-}vx9U7P0wY;v*DX@FX@2dkCoo~KbPM%ZIzLJLL zvZ64-Ho7{p@l5^dn)*4Rr=^vam^c7LaJB22K5duI9)O~<3ziMdy-cY<{a+jVat)f# z&$lZa2rdqe_LswS8+G8Jcx*T+QSWHeSK9B_!;lMB`T=}}UVp{MMIy<>9H$36s)E~6 zi!^2^C^Er4-PxYh8aZlSJDm5nHy7>PcR$)(Om|0)=AG@%GIkgM?rk9=B3g4^k4%(A z{V?aC^&k%U?6SuoKWY4j{6X+MwB%<7?Vr$>u)p~M5sF2ftHrqI(*sR+tM&|bFJX@O z7x)4npd^EGp-fLZ1>0Kf+`)g0qN!ZL&;5~j;LvJR;Qii%D%VfnPQ9*OJhCO!}O5gV9i%BJTB*AAUXLTU44xBKcYI?-2<%;ovp2H zmhbCH1UfZMT&oO8x$43doVd~Td3m~p;gXfy0Cfeoqu0Dw^aAlhA`fj(CS&)vb>@HI zocC&SCdR~!I{NzP1VyPMd}OUUMh$N}NBts&fN7<*QN!h(K(Pd<%X8b!W_bOEb78AW zxkks?ZIj-h8(QygEX+t3}vrCn%p z4+CYs)ec*2=idryxnMnC!fDrKNaLMG5$C@5b@ai zDYKMp-S#&wHc=^t9bAhd-v&9C5+SuAWWINGp@hr00&>nJfOZ8gr+H0^QUh3#`C&`> zW^y_Zygr+Z$8;{Uuho2QzK%ZaMjd?3^PLK`BHUf5KiggJ*kE1z12-Ni35iSuY&f*N z^De{X;`}Rz{SiDIXR-#zeh2^N$K!m(xMTI~SSWN(#hBR>;^PxSWvH=qpY1;Mi}U_P z+HiWWsA|h7Y)~ReKb9h!G#JddRtLm?cs5`Rzv~K3EB#thMITAr8;=p2+hir+;ka04 z^PN!)<(DBbsMCgILQkK~64dU;#XSQ)xYe0sMReot-a&2Qf z>chjjuV~_|`VwC1=SWT+Obb^a==ejez>NR}S>9GE;Sk@NC>iy`+5k>B(f;ljOwbdVZqVlLrYgOQAsR-DCJHn+5O`Yjf;c z=FN@AS*s7LRx2yuaKTxA_q@d@sfmw<-tDg$M4y81Me$Rrqh% z-3YOCF16B$!_+_nkdO4YI6ddx%tva5P9$uK(M}#%;(ns8O8Y}aouBy;)ohP_Ecxj( zyN(eo9og{J-7Z{K#hlOn>}M^j{xvm{pgW{2h6E2G+;RQ?V?P18YU%N=BB>1hR2TI; zNKQYSO{`ifyX)H%G;&dY_PZ20be967_r*5tJO%wlxhYNk?t95*b%dy3^`N3L zaA#_d+)6G{V9C_to09|N#I+R|en;b8Y%NiPE!dPGj*As66_J4yRH__ZjBj)Ag~$50 zh+drf&r*BaQ$YF&YuEwyGU@nMjfL*g8SL1-33pnaoc5=|GgUz8K-(O5Tn<0pbn))6 zVR`C`+hvm(q|St=lZ-mO+1Y{i)K2O}$H11{^)%tU_K=#xAZ>ZL90f9i;ToX)hN`+n5!{U`or04U*O2gS1RtNTz z4Xq@a?;q3h>W0-`aXUEf_P&RtN ztxFx~Tl@6?3G7f?WgR6rbD}k zZS0;|s^kZg7wd#%i2*MfTyBWrf&-cSfj^T?lKgV<3I4(+K`=nV|Cn~y^)FEN(v_zE za9fk5t7Or-iSSH=dOly6-R<}bsUt0i=dhG4}{{SW4<-)SxAbT>}FgJHWDhkW~U%1*GA3Tqq`z64qPS%k!QE%jyI_W|QeR&Ds0mIc<%&^5k9y?8UH8 zdO78YePfYc5-9TM`~8$5na)5FCPOw;y#HW_ z>C9xI(ldB!7KW|55=aCDR=z@o!Fk4*SCbDe6>u{f&kxM=7iAbBiK~!zO%O|Oa=cHs5UtWEi0Ib(o7&b;M2jh&XZJqUuj@DFVh zcNyKP;Z&g-^M{?8S+V^<=}gBt5KY$G=&=2mF{+;pSV$9LX>BtKj264y|2_7N2aGCF z#-<)t#{}uhr}6yT*59<+!)Z6^5F;t15KGMI9s(e7o>owC{P{*2-y5*e$l$sbSXCk_ z6ofsc^>aM-e3aE0p$@oiEnP)uylm~_@L4bWA(@N7N+6k_4Z_|&lAyL>Tn zojZE~su!4F!UCUC-*rG^iXi$x{{4CTo#+yex20l4g#^XW*H1@hJsxYnChBi$s-}j< z^15OOhS|7Hdy@m5Rs}{If?O8g$31_8sg(hLVQuZK64H?|?dfYb`!w|f1UWYqTst_B zwuf-sDo~|iV15eV0*dA_|B$_4T$fWPl?wa#0b$L})+o2c2vjuCk4%Nrq4{jpr5aEV zYW27y3pDJZ;xEKH>}4b+9e8hW2wL>Bp_|4vN^(7K$4`~8inF;+lqhc_PFXj~GO9_D zA!EnN38uk6^RD57_{HTUoBPo9w~vq(XYXOGWw+{UB5QWd(7>z>@;fvcHg2>aajX_c z#t?5T*-rx(XliQea;g^%ab7h#R#sM~)bW9V14=(jt4U05Olcmbn2usF^+UL)z}zq{8GF}McnCfL3p@TRD)-}!OTZ> zM6*Z@l74zPgKyBrj~4UQZxa)3TKh&focR!7ppRJS=mWp%vTAv3!w$WStG~bB`3yL@b_B#lfCF|IXlUM_FGuqB)*=LZi(R(Xd~qh(_FL(j zMF-I?DP7Sgo*Eh{1@y?STq(z%|1g}$`g)dfCNwlOlM|g5d=nc&_G)EB(ffTk;jJUmf?P-U@e_tyC>w z$@nD$TBd|L7bx(F9e(sk#NW&KR;I*D+7nkScDe9Mz;A1D|6IW`%5_)bmFGhmmFdsVQ-0 z#dNpC3K2a4x`&V+#9GiU=#hUhx01}#3ISGG9fFGK*Je+KI~|OUD=?#EE3r2ttUrIC zs8U;K0v0lTaQ#DxWYlfdX06)~R)&mvCyya=x7~SqPW5roe2-9zQJU>1^ZBfy?6hI< zNDkln__Cmt>B$pDCDqW#^_>}4T_%lbPNnd=h4_miH)V#pe7@WYaP7`=?yJFv;DHH# z+DOi6vo-i6qRGpvZC!4hu}F8?I?qZkI#IAT54Bip$yLG-7+ z)%f2kxysDdy9J^igZLw)nU+7DsAoQYe?@gA14Hbk<)!6P3Ts$SxE$^YD+xHDfmDz5 zZEV(W9gKxP%~)^m;3kDipugpn&mUhLh;P>04Kl_TL?#`~Gc8>ImFX*Fw3@P;xr~QPWWrMp?s4cBq z{-P2zQn?JV22nx*%Wu|z#$X8&8t;bCCOEr;$K~ISBZI-QIv6s-uROYhkl8}%3iokrY|z58>NEh60Tms6!QeHc$jsf2A5(iWccMsN-^qL| zj>3&RrRK6l(BsVJm)V_TrI%2}6HmKS>5#EbNnC&0fu?y6M4O(1$3M0Jwre*v9Ys+- zhKt?6cx_06^e)~gmz&?1g~NwWPUCbMq(%fXf9OY6l;-C z-u+1W_65@`-+Nlqks^IBr9_tl@LUJ(D8zlfUycy&1^-x{fQt7}Ss|aHTg|O6zS>Jc z63Yfh>M0_hckG6!*jDF!*I`!dgjHu!Mj$o5{YikUSqtz0S_fp`&m`5o_05zu4Ys%3 z^pjUTIo5*3^B^6BzNI{E3R864=IvF&@o8*7>_2!Ni-Q8ciPTgQvqt`c9d6J^nSS2R zOSVvdZ|Q=^ZKj*2 zbG&x{ikZAAKU(>M5}t5tXe;kJVe!(&qXpj$z=NQ@D4 zDiR8l?{79b-1(V1noA&u(b4%YCg?@2Ymom<#hm)!8I3?lrIL*FFU&z(N3v>1U?b!Xwyndl{xOaaLbL& z+hMfg|Jue2P_6e(+LIL-ZW{QwL@8I0Rb#8%^30*{#yflcukN{D(J8f(S-7vRJKMH+ ze|w(4uxg_&YL4sH?S@hx(!VpD_I0%J?@l#aFmyh>U84VuRJC;0U;WNWGtLDc1bLl09>A0@%!xE_!(XL-+XajA3kc;bo$~U>3>ydMcc4+!29bxOk_rcJ0M|vCH`8J z*;IB>1RaFvwz7jOUcBsiNM{agTU<_Bi|W!~%oAolt)wmygvD^WvL7|`+lFgP!?dg| z5US(3E;nQ>PEQiCS@F9F)J?t{>yIRRAVJOf^)+tDE&7(*Buw6>^XjN0&YgFEd62c4 z6*}Ge$(G9B(T0|zzk!WVv5<#7&RD#Z8XY*LQXz$Y`o@@Zg9KvH1mbPRjy5C2&IuMA zB;gsT5-QIxUP!E)N`*w!3i&G!{4=sBLqdnEAQ^b0JXBJ@6zonNA=MfQ4Yis@&9&DJ z(YGP_m0iU)UA{qU@2Y>p2n{+H(f{i=aTB10^MCj9jBI^mgQ@aXCFY4?M^chYA-RDh zC7TeMyV(V>fscbJ%81;L87sy9$HN%H;MZ7lcGa=Z!SwZ8IrYIbA>oXk^KQSvW8Z*E z*YyGINf~Xg=e7dHNmrffk-DI5HtQ=jD7k& zPJ)+*=L7cQHzkFxBve%(sMSPj42CK-YLZb8He)-O`NSH zTJRJU^e5B14u+6W_S@Mzer7c{H#cqk%M|cWp!$f~CI!#~3~r!Ixc?yi^6_=pM4Zr~ z3dud-C(lP6RV%`Jt&=-~)v!~V;|H9FU%T&@`NXWC8Frd*=yPekBMWcmtkq=FA4O_9 z>!*vA*%`FNk>myxG#Q_D-QJ@+Rg$z+--avLyDezC$P(kUI6z5(C~Z7{c(Mty zL`Is@gF@pH`+oT(Vcn-Suc@I4 zbw^G?Z&uJL()f06 zht(R@oh3L|^G%19q*D0P2?4n2&-&(;7A$OR--9iF{4RTMa&D)|+AsX}k^PGFgPwe% zxoX25&}y%qc{wtd&Hw?|(8pGp*tDPM)DDFqCiR-!xoQgJA3tB$mXZW@37noU>zbRN zs+#y??n-tv+l21^=<4NZa=DS)i<}hzzDBAGM{GNDe7lwfby6R0YOhc z9-Gvo&aCy1v=eHuEJ4#7i`bQ4OASuoG}F*<{B0JJxR(@o_GA>J6i!COc%0p5)H~Dez^`Ed1~XyrOE_2SAoeD z-nk7sI5wSnR3BwPC7m^kN!2$?GanYI7y-4nqh6OEX0Vq$)Xy5mSy4xEH@{j*QRu+@ zqlQ4K0!nnV5Cfjssu>P(^>!BKrQCW$q?0cP^1v*RgQkisHh0F zG#56B)sOn@iYhi6D@mD|uT{!7CjS&GI1v9?&_m*IO$SSgnFS9I6>F-?wmKY9Z_{tX z5V{kC$kUif$RoaZDI~Op)^nk^Ls!iJ^+(l8LcF2P>B~Ol&v#MO{HGC4s4{T;`Jtv57rl#c##v-ols3>ysWI7!pKI-wg8Qt6pd@+ zolZ3LTHx>f2rVRtxJS<&)JH2Qh}%D)kl=}yxrLFsI^~2j;Z&LX4$-syzik6X@5u{` zizP@o}IDo*W|im3LK^>E4EU+S)fe z9X2O7&BkEQe|PV%JWVfcYqH>sn!z;`oNmFr*>ZVr*)3Hxodh$7H1zCD zn=5zZ5cXhbq+~++J3VCXk6Klc+A*2XLi?ACXUzv2s_3*I)-qt}MbP@r>rHJTvhG2f zGyo0gV@^L&VIs*}Dt^rQdMWJxzF3MVa8x17LL9Sf$5~$V969g`=h0}ys>(c1VR}VO zS)3^h5z|5fiO@jT&yVm>uV)do7y6Q)8$Eh!3GPF#V?SKw~D+Pjv8)LC6*Q!AIF22FfAip{Z25=*JJ$Q z!p1Y3E&N5dELm+2=_aXc&zsP6)xfa^4fV~>$d0$Hh||d^ zF&N}Hn+qT?`xy@$X6|@7K0cOOn_DOVrA4xqw0i8`yD{TjZ0fG|r z^jA(=7g}}TcVPSk{Jt`T$ftTbS%eJ0!9NB@^-7%*;2eWoJ|>;c^Scyl3G>--U@wvM zWYk$V+gybaYbYi*cB`#EP|ybM-gg^wo>1_t=}VY4<&Ngm12Rj1z23$8)S$Qg1{0cO zdbMbW!X%Cqjv|PVJ|ZSB1wSqRviV-cNkyt8W`J-+h-s{o)euA%?>mGk@xoX|5+rStAHc?}1$nEvF(P z+hH1JG=2!a;KnLR4k-c9H)fzbSopH z-Q(qI?#RAL1t2FD002~0+6Ib=5F+pH?gE83yhH|{9WB8v? z_lgiKboH<~aidF0Ecy;e$;qJ(3w%YJTKP<0&}sN^cIsrohagn_K4Qcdq__zY&Ia5) zR1@GMlV$hA(Ck?6c3*;F`9Q3xVX*HV~O-8+STyEx(Vh zz_l(N`qB2dJ3&5DEPxCQA<+F(y-4lcrTC$pZi-)>HrNyEt{>9_68E}4k@bJDEPM+P znCCZPa(IZkTqIiu6cKdE9nq$ri;1D0{r7Q*U9TZC1!*hh$@dL*WhaRAqsQNiJXEL< zyKq1=uJ2)0fjK!jv9U8qS+Y-Ti$h7kJOUG->A|<7%lEqZpG#*yQe=Ec7EuuZ=LD+! zk!gE+r~;<_;~wGl^nWIvyKUlGeal_$0x?Nyb6>5l`$}m4?+eZO6K-YZlEt6@&>D}V ze%V2pNUfOa&DNWcvX7+3qOwmi)NjJJuIC*wo)T(k_=Fl15!0a@mx_y?MOj5mfW^o- z;{EMa2xwJ<9Cn3(i^y(jf7W&64#6vv*>a;4AP_aWf0ytPtO~bAi3FFkK8UY%Kh`2r zVO4DtiNU>xO##$s+AO49^>TOCi+`ShL;Q8#U?-Cf#s!Bfv?j^qMM zj)E;8V%5%LI#!Hio?CFhUHIDtc0r~SBRZ#F!8_hVfIllsG#liQy4S>-=YrQmFl`+V zS5rL@I2DL>coFzBzNz=R@2R1LKT)#Q@9ILg$o*{9m0Ea;gmjcKXZn z8)YQpSrW*{jnL>jOH=p_Sb|K>6kE=0#nI1+qq->Uh7(>-t*gU)q(KNOa^d&O!5!4} zK#*%+hePC=zTr=R#eq`-j_>L7i#9z8ByGEx3mU(BIX*`YKkd%&$UNfD^dj7qy3j3) zHR#gp6yjhdM1Q8clbH{*tD?giZp3s0&1XXx3ls~cVH&5UfU*{uF+JlVcs5D?*1KaL z#tw^g-@OiQOMUw9gIgS^?mu}bW2|O+7p(4)$vd#eFn|t^5V=GnK%T+y@UumoUAHN| z22*x=-N1ZB&d_ha&TyCAD1R*G5O?<|zCXPtuuX5CO}mINhkbDEb>J>q@EI*+lKE0v zSM2kucH^(-sV$RBYZJ~ShnjzD?8m3^X6&wTbpnF1>^&Q&3QTIA zSN<|?E-AAn(ll2E>@jSi$AC&`b=linp~_EW^Ipw>{;1VG+hGS_?_^be4a`|MYN!p| zt0uyyalPDL^=OEQd$Z|Cm0g?jJe?!=MH?UTLCW-YaN^TyJ!LWOc^0CPgaWc=wldd- z``r3~^X^}#$Kl|;H4g9l0=X9H;bT)6I1GBP_pY}Z@B#;nAhN{VYxM;9QxGfK$sSE? zIjN1Q*vjKlTrKu8++65~XA$WA^z8Yn2m}Sf75L4uMV+s76$CCC=moWc!4|H!DfjNqGW%vUGZ#t?$j5rXiF0r{A{W4 zA^ubL<+x?yyNy2ji+%1ucWit z>}^1T1_2bwAcmaz77XNTECOl0)7HxQl9e1pZy#M%y%A_{4BekBP@(pmCH zgBJK518O^6W%UJETq6zBpH9)FBMJWX-Z8uG3~?KN8_2^j^g^8LGn4+QCBlfI|6`J_3X&tO6qm)lwUV)-qSAL)vM znfe!>gua(0m-n2fY#h}M2FH2&Nq)_tEUv-L{fT*%tUdRYD`6zO^1Aut$8Wcf_`ctW zwpu)c*=8~T({w;SUI6fB`oX)lhNsO#NLgloJ_dpSm2I|%)<;dF$eiMUB{2YN^@NxbqXj%&v9MlM zV|;-m51Zvvc6<~toY1!1P{f<3logn)L1YLaSHXO{U)>ybJ6bhln(?N(R4OSR^TH0> z!i!W{+F~8M01Sl4`U$@pL&((-7IWgot6;s66K|PKQsKH^_Wv@$vATOen#=SkmJ9UG zJ5d%)ktx~ANU|XFU(&nP}J+% zSZ1wMmXcvDypS7z9%a!yd>sm!zmz2wc9wyRd4tF-U(}j`NCqVHc`xcgJ&Z!*wt~}i z7N`vo=r$P`eKl(6kQlj`N&{VW{w?#zPu|1N0`QHrblFW@M`D)O&?$N{(@n%XdR{5n zXwJ6&H+7J~iLsl$ZtnGdFH!tw+}sP?kQ*_I-?Cd$_02sf zcqO9!MmZ;*@AXW;r6)*pMkL%{Zu{wHx*-PjP{vTY%X9Dn_uChzo4Jr@=e4pMncFoS z-hpraS(6h@k%TPs6t?E!WvOa|^7kzRSMVAQcY;iFDDZQYB zSIW6}IX&YgWLON_R25dyYX@%X7>~!?gW!jSXT1x`Y_wf-t3fcg0v=9(WhhV7>^-ZZ zR%snF8Cw@TY3^^pt&yN=_zMuF}iv<18)!2 z8G|b>wDu#mHz%HokrEK-PGK}gK|#@=Q4179!@{COgWXtP$L10TGS1Z0)S{!K5wIf# z2%+KN0#{}hY?k$W?d|P#bp8Ux>x7fF-Q76?1k9Hzb%n*9cY42JVkV0Luor}PcqDY% zzg)Sw^JF`DSH_>fTj}*XfdTD!rOr(FXkd2MaUzZN^Yaq{J>Xdqc+!VBZVm@6`ShiX z9Dkr+(B%9fhZ5P4;@1n-pin~&XTiQOE@ukXP$5xOO5v)HX*?*E8w}m&-SFe-aTzry zpGd##b?W32&Z~m6^{BR#{Lxh$(e7uh81c;DhKu*3K}ds;>=Z?RQKxa(5}1)A1b1|F zD1|R7R;BUbT}&W2AAX{9*&YPjbUik*9ekQ|&cml488ELd<04-4ozbYNYLd0E}<=>90FPOAOD z5}5jTy*7o#cPMt3_Bg{joR@ZorPLG9da(q?Di^t$yi>&B$UuhgRoY#tKPQ_#eKO~g zS$Cy9W?`Zx(*7&$1B!!c_|CR#1uyVq3qP^E4_6}zsO&__V7#6tt;gRDnM7>P8O_FS z%vtvrb2xb?!iufCEI))Mpuhs2T>;uuC-Pf*i$(afyzhjR8Cy-PP>C@As)3seB@0-y zi6Sk`M5zJ=iqqq-Iipw!lGQ0-eRTS}LR!g+7d>*|+JEZEPma*#hA@8Q+TB}DPENRA zX(V=N?|XRv6ipTq-dhXy?1=0aY!o1(2+8e$gq(cIYm_>pHxOtxkac>L(x*J@5;oq7 zU>q6j$QNKPH01NEe1LOTg{;BBf}>Z)fi3x0=%c?d(5)-Fo#(tG{%omg&b(gUs{hPA zIjOt5yR|+)OENcvUcnRSJ@d+>KL>=6J7q+G=IGC0HSKc>`Z+uHSBb(gAcZam_#WMB zSX5Z_aVNFVi9GY3TH#i09L5bS+JWC@r2=%8P_iLY;zB9-t+*%a8q3ve8Wz0dKN)u=xd_vmrfLlg6c+AUqCfPv@I1}Zb%ruSNzq-{8T8rTnHT#df-{hI8%kEBY;8WbJN0+A?A#$fUfS?5Z!hG;`hBu}0S;Jj0e1>a_+h!<#t1vz-DJ|}(T#Td-ZH4m({h~ZCe3-uhOGSt zEySk!z+d8mAEiE8JMG#if)<31;DZ61GQ}l!nTNFDs%l}AaoM9N&s&r$Qo%#ykZwKr z&cZ`41<~|*&v$v%ffjvH>m{R(;oq4twC z>4mL$o!`0Lq$R#La*RBMh@f0+Q5Gm-Ak1tX%gl~$%1G-x>&h&xH67so$e#m1qFMAR zzdTRkpBG$?+olnn+S<6NwVlyiXRBjZCxzFiRV0D05CJOFwHPs)idI1cM$tb$#9&Nz z!GU9EkRHbb*o94vsC5L|bDw9-9~;Y&X~q@|L`i%sGiG!yX7X%3auc|k41>X!>#ivg zs0Kz!Zn>81!SRWM_+J7bE_lC=Fxd|U&I_0aX4{q*t?uJs9QqwDPAb9$ngrg3>L&hj zi9161%VDTmvbRLiPWl%iXGcW;%N*aW;hn7l|B(lR(J3SdfP(Dg+yGn*6H zZ}Fi+pK6Qt0i^3j_tL5*T>+=I^n5DO0fHtv&HhYa=Gh{cJyr%@s% z&BzQjJx}Dsb7q_zDH|zR-g>Sgxuf@`LFxL;Z|F7Si3IhB4~Ux@%-w0Ba}NY`^Rw{B z6@XM_DXx-U<-HO1uV`+L({cx*GLsbf?|@>~vj;$RQ6&q-I>f1po7PX_KN0Ba`p|y- z@f`;fZ#^CbwGn2*tKU7|LzAU+rOI7Xi7{{@hE5df$+$payW;$*FTA&9s`HEa;PrI@ zpMO%DZ-v3a9=vLyCYbzwL}bOf>-j!>2kK83TU8Ha+LO-dn0-*- z0ewf06n6q-9u_oCsuoFSkYQ4wNOP3jQ0Ml%N1$f)b`j*4O4(EAQ(*8hOSWL<@k%%> zk~kneOMJW_RC5J3)Vd-NZ5@c(Q%!zv+5%&QfVbQ7%F2kzFjEQC59iS&ecmR#$m=aX zc1{4lSv~dluZkG)(gP~c1p1cR>>pLa3M7M=JLg!FI;Vtzy%jAHHkeNO%YRy=7WUw` zdHu^W!YUcVRo|-am>+tqC_OxrQB)6^!q9Ht-gn_G!2LNSh%(&RmJo}T2NY6n_V7jo zh&S!UBpPyA=6>#*7dFnY5Z&&+h|kT7P#&rzP_3&+fs>7w0BR^$d#HY9T_a(l1bdub zZg4~kV7sd)z^SA)z@gy?d+4_8f5-bV5oMn(f#=N1J^}H?g{tfV2c@-Q@{DA~87s~9 zZMNT=boxsnP^GGF0gP<~dcpd?n=!PdA?efYOBTcLg9eEV z@J>tqV~9lH0F^>zN0X^t$QXlM;t-zkcp7l#ql>JN-I_{RvMhqy+BzF(hh~N*A&(~D zM8Myo!=Gccod5kJ1uI8XexOtZV8gqti@Bzw8j=V0u;&&xgspj4T@uOi6MP`J_IiBQ z#jZah-9kW6QGVg?DR&KI=Yc+rQc%Cp&QP1t)R1Zn^T9{~;|`pO8ywmsEfya4u^b&8 z$Dfku`Qz4tz)44P^BF5zH=aG8p}hMrsY^ldPy#rVb7wrNPMVTov`adO46d2uVl6*O z3woJo`J7bFRE9CcQ9nw~k(w2jvxsO`LYeRp!WCAwmr4xsKPF^DaOSc&=_-HMUuryn zoB3gU`%;!RYWdDpC%yT!_fel$7Qv-+CBHKgMX+pRTJwos2J8ST215tD^vz=wF$w5I zgYY_>APUPG8)lZkJQPk={sl0_z@!Gnm(ShZvEjP72VYhF&Ji&7Y=b6DrWmHm!Ihyf zs}x(}YfQ-$E|mjjNwXgpYhULYq6(P{6UH<;W*#OI4#OQTFu;=1=xUvK!8+5|H?13Q z4I3;$t7!E*G&vUP`TED*)k=oLbFKLT_(%;Mke+2KZY!Z8a!O(aRyvi{H-xASQ?<%w z;Xu;3E*MylgUQ5ynTG&ViHHm%KHH1(nV>0NgolFK*<53MIMDyYC0~= zsavq$;Mf>^zP7r7;&#!4VcyI$JsjflIr?&8d4^YlvtbcTcpLaJdwr z{1&>sc60HJe@X*s@{hxu#hPAEWTCI9N+b-kHJXg%cO3_=~qBEQC3B`=2U6%#ukkoEwy<_C-R` zZ+;`Zn@##c+Y@`FNVb;rmgrWN!Wnztc2d{JWUSx~l_QufF=3r)Z>}4X=Z%t#|FP^w zz%^Nx=(?g}xL!~PYB(e6|7)&rYx_IiM3?|2CQJn7?s%C02h?vv`M2#ywT`!_vyFU~ zEA(5V<9XNTIY`mE~NXe~(e#s%_iV>e; z^_+iZV*bwgSA`vOSk?sAo)0fNta~qhmY{68j(6`pc8P6;KF6}_AfB~5&z^s%p*q19 z^L5datMJleUk;1q0PWT6)%s$l?~`MA?ogR`t0p2(9C&j`362?}`NLR;5QsZ@NF&yn z*G8#_s4k}Xi_?YY_;Usn{Ji|q6z+DZ+i?NYN5IxADhP@7qy85|l~7t;rENM-VVhI( zj#osAXD(c1sOw_7D+-R*6#S(X2y@#mBZwqJLxn8Q6lt#xkLK*Wga1^pwZKRxvzZL} zohD{PwSbsBE;3!LS(Z*G0S;kvyZ!Bs#LioLV7XJLhTft$*q>%#J9wa5SlM~uUrA^V zazL_;DRbQZ3s|J78y(ug(PHE!e@Es|tfw|o2XI0cW)8>jw|b5_xU7E%d9()5x>t9a zF+9^M;rn^o`L{m52-$n}PkJ>#0#jkE0`(eDdyUuP=fy{tx7@vK2>iA<5-P+Ewgbd# zSV_svHq*YEeYYX+Z25D^24dG2fBtTQr-i1NPp9)r;#~q{7T*u%*svI3($k_KDFcsHW|=dLVt0mFkHw*A}ND&z5sEryJZw-N?M7^^)YDlL?5EdLXv z!6R1q>oUhiZ98?Y8qx+R)@mEO#K-GzRGLvFy{a2IP1nLsPG z;K|H73FRDXN-rjn0)*FtbRFrM*|-xt>B9o8ObvWmB`Mp6B9# zI_zm_5u-Ud7HjM8&$og~Espo2a5FHPKyZ&gwEk{xho9=?L)#t=8z6{$SKU$o^q8Js zUtj-Q?EN$l=@Yu*cdC7z0$~|-2xcv~`;_yiIn9rQvvG2^uVTqidPrKJEgmn_Aeq%Q6~7ro}3EZMnJ@YqMji@9%mzcee}CliRW0>rRr{=5(VmvgzLh zjp}{;Lyzy9Jrd$scd2i_@sw&H<3Mx5*LQAGvh4nPn?neH_2HEcQX0oXC0UtNh4889 zs~;eRS9-iC&#r0r3|&h8cJx)y{})}~99>8B@0*5g*w|?7G`4M{v28bOY}<`(^Q5tD zqp|JeO@H^U`_{W_y?=6Y=FFKnGkdQ+-~HJiK+oD?mJ3JQq;Y%i5P4b;_tupMQtN`O zAyG_oXr%?jq~O7fGAy3IrVyH?ct{~2LH#aok2+mR?-xHJxLG)hP%C!|copnf(IM<8 z6DL#6)G0B8y-`ZlRPf05q$5JZ%1>A078f?8uDHYzA=v)?Ek9<$>+^E|57~hv?X8BjQv`bVSJqK$6)A#-uPb_G7{pDM%VTt#;n_>XIv)U z4G|O0$-5Kf1%#5mhZDu)>wL(UizIOn^Vle}UC2?0?VoNrIV<*O#7oUJJdL-q zi-R=j8r|j5bXeseqD?KfvIjf2J%uE*aQ3{D?~K8e(<|7b$x>;ro#0hhK{?&;zN)Ua z4Rp`p>4WE>N;Ta#UtIFF6V>|xjeLg>TK-wnB(rkW%RbLxS5QWmmiQ$0@=6aqFO40IjxZnm3oaE0g__~(XW9d`HRMf;Go!`rv6B@sm zZA_f-S%Ejdt*lDK1dTvm?fNN~OG6hG2<2*okvOKJ>o%%|K8Y&v1eFSx56q`yIr_KuR8Rbwx%ICjq#{$&f2kqERQo`iOJjMgR5_A&wh1 zh7AIbu|gyzBGMmAWdwrZY1Mk!bOAOB5DqVyK%Rq*ICgl?Jek{;;uhHUesC*ijlrgI zeS4$~zD%)PfMm!Gtt*4s`;8*Z*E-e)4cg7~#r9Smbm^QQnwp079&c}P5=20N zXeVSzLn3w6EJvn?-gef|mVH^rui{$1Z)~s;TItuC9#HPsU_Y3U!N#abh-a`=MdkCo z!&!VZbsMzXoT(TXs*|;qDdC|5fCwJ>WN5&TjV%K~r|XJ~0u6R{W@c=BoaT=6(mnIy zJ7$;+@@t3jeh5{FX3+^h0RZs}BTOyk#igB3qwB&o>k&5dnfK0BW#gYJrV;tbSbSg; z{XjZrTL`}$FRll))>9gb>HF>oWl9YTJg>A1fNeS~9GtR}Qr}K|>&sNdfjx)9ZZ07O z1;ybfOaAxOrQP_+12YqoD|eoy4@z8mYI&dBzkBTu)riJ$1+`RAXBla)v5ks=0r}8p zx}>-Hts3)>$A|UD&CZ`6Yndq%IeZNWh#|uL{s4yypRMT47wO~!zhHLhF~4|@1}!`< zkGLdD;ixgE2IjlfLIsddv7~Qd<8ej-Nqv%H-LFqU0z{Po^q_lw{ki-5dk+r}LUI9a zJNlrIJH;gy!(6~gg~v^gIrl84>^!u3?G^cpG=*Cu<6adfL0sk^J+={5F*$`Pr9D-Z-X-X&PSN%EEoDE={fq z&~XfY)`l=?7krXpYBA=TSO@&&!$ka7DzcKRz3-9E93QDtMh(OTOI7%M zUNt=7Zh_AMf>&b<*f9r|zTKav&4y@CaHC{7`#sD3aSOBgKM>L+`$X&wfQh_8E$ab+ z);6o}3+si8U`COPDAd39XH}q{Wi}yZ8{Y=fSohJX`^p}4=iEE6+YxbzM*DE(z7Q~3 zgmji+(^la>m5#o`8P1GMv!1t9B%Xu5xl1IzafaJmjiVK)og%=)Z=_^sBAnUPLQ}pn zAt?0Z`dAfTTaXc2vZ;8uGc-)(!ob17RVE=7zRfD_=>J)NjnMjuS#o|O)*u2>>Pzth zLfh^`-*ga>;QCBf-7i&3G^xG_|3LI+*SvGA(S>qW zT5z_Uh~KZbeSK@xEkpxRgbMjpMh*(E&x{=m5vJ?JFs-v)%XL9@mGhqT&2pp1=9^ZF zi;Lp?#WCei;-Xh)0^}&k@-EG6dlj5jh(6zPD3X+?`?vr=`+Ze1yhZ`% zt?2P*It!V6ayrRqLZWjT+)cq`yvS6iNRvr8d^T;RhSN|&@9tk7PS-Gz?6q*t^)$n> z;l)_Bu`~jB-rxH-1sCp8g)+zwMUM_Yh*o05_arUiG3^STrt;{EN0JPIf!fYdzf7uM zFYj0JQBdJ7#LpfCi|zu>#RMJ9_Ft{@aotj=c*82WBM-o7t}Jyr!LC%X7AHmDcVxV> zJ%;Q;>fi!_0&~dngJrI|=Vr01N}q$>X;#m$)aPqDh`D(z>h|UP`aY-slbaNVuMc*A z4q*_!46f;4IkF}jDM+c|07?s#gq3D0;d;C}amCA7c0mNOv+;3RyBu`(kq$^$f zLl~Q4rBbx}iyRt{3O>pkxh@^wB^jqICf3jVD`{T1Fz%TsZ?unB8rdx?XPJ}TC^dOT z0{zDPa`0IGzKrM5h7xWjr^Dn+lx=AwR*mfwLT|h z%1$1`WIHYQw+kY_wTOJaeLBt*imKXeYc#QQ&QD9$JX0MUGCjAAC_Enae)nyDR9J+v zekR8}(|ig)xDbe@J2T48N@!o&fp>@fRObD;k3EtA6|=)BJPElyW;1uIy%xB`5-a>r zd8afzw`Mv`WN@6$_h{t2*7`A z#7LI)35`n^A9@OVkw9Fl7%CG>Owi%D2nDL^o4Sd^rG8iSVRWs~BH}Dse#0xXz`?G@ z?^}o-+GWJ;+{rU7jH#hHUkqi=O=^d(m;Gf}acZe1?+kYb?-0Z4{?Pp^>4YH^*bS#IA6AlUh8$>h2~Nrc{MGWi%o@Tp)^M%q6S}TKx1x z5%8RK5EB!_zbNBmn14!zNp>g7n}!bwLzKpsg-N;;=LQtlLp{b%=zk&!V6 zTUsYiPEvAsa(G)DGma33?-deWxdDe>~Vu3`)bQF$`&mcs|)xT!Sy%Wq})-05B^5 z*cyg3G~y11Gi@)wJ6xi#h_1X%W_|mfr4bR!@U+D)GegZ=wg2VNas2E-8GTk}D9Eml zk!*71YJQ+3@w8Rb(BuRS!{(>(+q@>TzdSJu1QCbyr;0BwlK=!B8EHJzZP$#6roWy5 z1a{4u>lw1Whm1^rHMV#JMjIwi(;|mi%(0=F!FQM4r@t~Af09TL zy57TG`l2&*E7wcr_D$ch}NKXocRIax>;C-p9&+UOMgr$b>l&ISdmyye* zy{A-clp?Qdg~BG4*!%Lz%Hw5CUvw-5KIf^;%D6+I&Cmfsr|+~t?{w7jc{$+)syPb2 zZKjq?i!SXqhrBL4Wnps1Yfq4WgxIN$ESeKT#LL~ROXTkOB>CATwP%XX9hVlJegck% z(bu!Q`YbLNL(BW4%KQy4p@5g;c^dONs|WbESG9I%BtR%%Q&R)bH6FdZD+O`8mWrwX z!=ReO=liqODNr>-YiW6B=NsnI91uy?n0o_WE?y`a=jmpNa-A}{v`67Fx$NtFS5nk8 zpx3%i%0(Z>U57^foV8qZyNpxpcK~kY&242$wpX^L3co=2N8gri$5kV*a7iXu|zgR=Z*`_uz_9JeU;e%5FXDf8>#-DWG^d5{3 zCFcTZp<8TMD?5{F`s{Nb9TjCC^dqS4rPGaSj_OI0RmAMbP zWC^uv>YCQh1;>{quy3kk2{kj?50Qw(fo`SOaIzSw*>eKuij|q&lzp&Lh7^Z5i z3e+VBO46mzuSfyxJrfp@yuQFJk>7@8l3LtN;c;e23?wl#o+J3XTF%q_D;Q-A(Zc1b&X8;B<|8-Tc+$&({9Dc{qlURlk4F0vGD3DhfHk!&3~6L)r0rC=ASfIAoalu7NB zLRMC(7d>N@pAsOPjQ>jKrI1L~^Ju>p8&`&?Xje!V>aV2v?)GTmy=0zY3vi4935Jax zi*Z!U%g&pD6T43AaMw=aZF9RvBqeVb@5Wm->Fpg+7rq6%{SLiTQNw&cCVD9(q!6ao zz_CFi-O97JVu$#lCBNxm4Yprn zdn?C68}pC%?uDPt=k0N^!K;F}$t~7a;gmsf@6<@xwevT7_5q|&A+kzli7+UZ+?8)} z?5((q0_sEbrs3xm0hBp?>bWf~8ts9EJDwp@-`+aiL$iXqJ~nW_TwJqFoQV_X7NG+S zAHPQ`L2l67_bvMty+OCe=9!#Ys!JQOKV5qyE}YIPw4v2dII+NTQ|PmSz@q6NEppO= z8y@cmijL7IrnrqRZ!P+i{GR_3F@!?riW=2h`O0rIm3Df4Ab6%eLK*S^!BjwswZbq7 zP}6_a%W1Q=_kSc{Tv+4;nHXLyunDJRE&0-SFZ=VkCpTSewik$6J95=3Ja6`+qzb7)ir>ILO|fu6?l2DzA9~sS~mmJ)iAJ6FN z5z1B2ct>Y-b9<0#9~me_Pvn=CVGt+`p_G>vznKCRN9wuerCfkuQV>s82AaBrl1KLx zRt#W}7bM-c&d#EwaQ`)32^cU@(8*3uhmAo+K>@Ia?Ck8QD1?ANQ%%`ZJj5t8AI2*j zSQI93o6WoT=IZ<+CNl6#ep(b0PrE&_WS>4V=10vG-mJ-xk&!>mXN~S@{`jHO5n3r4 zvTsWKueGq4(qzgH0o@TKxS*aMp`}*{B7S7#G3iWK{t9RmC6L0jcUMsd54x2*j~Ec4 zWQi>|d$sib$?)M8M%~z}%-)kE_BlUK1_TsbTwFDq7ItFb66?U&$x)_V9oS$K2ADJ4|8TaeRyZ3 zKMZeoM_V{MI|Jr%+l&>>HHdnxj!@_f;F8=z!p{NTzP9bxa*_BqdiZp_1Jawi%S{#+ zor#20)vc|q^4UB9(i0XDF*`qhHd81Kkkd}j&Zy8vQsiYsL?F}WU!ByB7RG6-&oYH5 zka@j7I$vm?X2DxM?xi`qia(6$ZIykb6+eY*7sTd8nA zoQaB;LGAbRr)$cD;rRIYk+EB#cL}2w14e=X)S$M_d<3#k{)k5n@yTGjqp={Q zYU;{h^IrT>e#^2Bs1Ex3MS%|CeN-al3-|pn5rRhCcFEUh;(ja8?I(@tJ@LZR~ zf`Wp~W)rkdwLmOqT^%eU;`t_szYOAE!xMgulSoWYPmhmR($*f+|Bi=`Pe(@w8Y$rh zS5#(zjL~DNEbdI|x>y*MwD{Sc0&i4r?$XN0#g#sJ03@2XcaWgDlsx!;ys=Yj0Lr1h zm;e!CNqPAYHV+>kzBmaMR@NZbu|<3raUx3-k&EQ0G3UW*j(Oj6P{?9r9b0+l0C3Uq z5(Uxt+{tbL)h@6tJ2TVT$S6SS&g_CUk66I#Lg0pskMDgViyL6LGU#^vlGV*%v(aZ> zEK{W^I0?P*cO9>+dgl!i==Pl8yxe+P)qMNcFVatwbf=x&+y-~AR#f+p|1n8%Ac2TL zj0iFuG@M`iyo>;1Gc8a&OGCG!`49^Q{wZdVhLUnZ@gIZS7TYP?&(1 z4sBFx%KLR%>vm?!$27?6#r?rbC*S}PpR2)EXBi@4`1a<8nU(de0dfegZpX<1qe<*^ zq>ji3GlzolyLrXSUNesZhVkD$$wX&f2q(5LswlvHul}V}8VJpzqW$=#uo=*{7JBgG zVi)Ijz(J0DkLWiv|Al~x=9vd=9xd=9{3BeO9$+8VH~}>^!XBPj?ir;$2cDCY6A1~4 zd6pIX@MHAhTq!D!ih#}Q!tYozxg^+&&O#l~ zKbg)}WXVult5OZiL}N~+v$0wHmP;XJre|UkwplF8CoA>~mmKiL%#aQKp^!q5I2i%R zY|^H%($LJ9?2VBUaDdWjja!_7BF-;<#rZbYm46^QTfr^Y<$dc~UN>sNWoFe?q!L4jQEy`0;kIk5_Z-rKY*=hf((=k>11r)9uu(rB zt3E@UZ0mD-{H{lLPX4Rg`bZrzF{O?M3EGm@SX1nkeg$2~cSQ1eye;dv8;gxk#5H4x zUr5JtbKr&(io%e_7BL(d5n^J0jZ06ZP>i*hu(c^_3fWI)`o=;m15k`9_~9Zv$w=6a zr+;=OP+$JduVEK84l%74=eBZ$flbiMLJW_XQ2u&{0F7`lHGd1Urq$|Gm^FVj&|hxq znr_GEt=?UT{4pL9f??D%>0)@yrhwSj3g+BN+A?4LP5p^9uF?KnL*a@V4Dp42 zGh3-$Wj6g$w}aU+U?Lx(Fy=tQNn(I0g9}bN%*viPpl`O zAqxWP=kM?n2I;vsZc^St)Zy(m^QMb~lT3=ZgX4=qF3Gm#5Btq-X-3q>UPyiD{+E7_Oc@_aj( zDr`4#IQJIcds`1mxT=WQ3=jdk#unj?1Mf4Yjdz^irJb+NA23pcut5tWqPP@1&h1Qi zuHSsP*`3(bEtCwvcxfZ<=)_;7_^X@!8vwYVUDAejMi3f2($M2$r)6i6PjosQ#fY`1tJDUArnj zYmebt>4`wNZHcgM?`V)Mq4apU^C#lcYNDfIkH5bqE^CiikWmztOu#;} zdLj!Zif~2_6L%_l$(IqdDiA^8d(NW=iNk$|4d^U)k#sMBNZtNPA&3b>nva3BD{LJDk zV@Fg}RE2teW@ZK`TCH5g#l(ct#BCVC6+s&5$GQNcYX7-j7cRy&W7W+#M~x6a@Nm33 zwF>oP>AP(mg7D?v;PISVh2r+q_!$OM3$Md7?e+R%PGS3}QzbBrh8c!7PlRKSt^lX& zaQX$2y>j1}mLQBht<+VO8teY*Jkpv@xAS!pdnMH41chDxT>p%$RqmyzxJH|?w4XTg z7Qn2*Eku+J))WQD5G>%}6APV@RPg zBHb!Kqo0HEVgX;9e?Wb2tyZR{$fTu>EP9TvJ+a;KTf=wt8Uhv zsCNhK1Da2qPm{qz!hGKP#NXKI9{3639lO{M{^=o=3HDZbFSUHZgBzE9d7CG{w`=87 zJXhVSG#i6&Ec>KaOrluHT*KM}d6vKfm~Yt)`~!U#LA<>$sfTFZ4UO)Sa^SW4ZO1En&HTxBsIu zU$lq1Md-S7FsKdk+IimNbTF()_CSrwYfsl5N#c9z>HQ@-nv#-10j$4UG~7N@8MSKDO865?dZZS0Z4FBucEfKC3s#lIXU$&q77@~EhAf_0wmJF}m==I&~h!Clf0L%&21<2GkpcdNds;j^CEKU>!&i@vahBqhR^oGM% z!zVujvF58^bg_Al76vB1_AB$0WoW3AUHAQ!Uczh8RamT@(mw4JJVk`N*;iTa#WL65 zDx$+-DPzQcZ^||-hIey%%?hBJddo@6Vli3_EXo=aG|%j+{}B{o7ViI2TGKMdCT|Ho z&p|KK!K?>7(rjR(b9FoyJsGe1F%LMZUSesG#fF zJl0wy7hcwlUWVgtc6d)Jq&8pg+^43MywlaxFk5H4t_;-seB(%6#vy8^-Qlb96gc-7 zf^KNPrM1K|Iq3jbT_5(CR{HOm0Mb;X0C-!QA>QW?n64u-8W-sdiXrPSl0L7TNqmb| z`n{Z8Y>dA{sJ!9_iwlqK^zGr0XsKSa`M0NfJr%)61_MDeF6{BItT0To)lW4K58W6| zx+L%Ls*?%5^c$hSabaFE0_e(vk>;>7sK9;+`|n7R93d{3L^t&{a-eH^m180l@Yg^i zEablE`@A~ zk~itPZ0rFiM^M)@2xAl=L^$Yme$|3A47s2;e7VBSM$o=g3_7l1yWT^=Bu+J5T-^A$ z<9ASG&dp@F!0kOtqmKu_3@Xs!ZW%YNr;$u-S}vOxbvE~K z?V)Y*n1pu{AB?n~d)^Z`zqcU|M_7)X-U>vSD&5H8CKWyV3Pmb#>boi_De-Z>xr`y7 z3Up7ZSL@EJKeEQ=<>sE;_l6+ha>1s$*&IBcG*3hJ94}|zt389xK1)iCzj;o7HO-<} zC>+$^><3>|N?;+O0rTO?s6~g8N8Pe(oz}o?Q!C4{bZ$Uye{}uCV?MLl@b@4yCzRKm za8JeI=YHlb@1>Hs`1oJ)N)_g3F7rT65*=KqVj|m}v6J*qo`zNwIte_dW~?)cNI-8k zA~}m{OBVa%8Ig2TP=ubdjA5)7m?JAwYjI^^p#f8vAx$CM<aU;+bu0#ErjIVXoG|Lb?c>mtSf5~R1+#CdEjic{i z+1)TM4DI|HK`|g!A9Uf1l`b#TKh7|t2Muw#>YG|+v=p5MnmX8&jT@!_H2YyBD^_r+ z1Ev9i+|xaqv?GZe_ZCURluO|7CaNNk<`W-7P|~^-!CBmBZ!B|m-od6=9Xvg!#os}o zl>O%EHN!u~0{H_3!N{$qL6tw8Aev6vI=;HwtiA<8x%favqVF>3(u>%L>7Q)&Ehs6s zQsNaeyv#GDEisG(d29X8p%$MNCY4yxFfpwT{>iU|+Cjlu#3UrS$eUFY ze}b)i|C`Mbe&mcf3afn6PxWJ}<9q>4dA&l!I{f{SZAEc8@5L+YJKi0T(Mn#rtYHVnGLOg>swetqKXZK}vE=RwLjT0!6w@Y}OiF`1T&FOi{p3}J$boMasWQoi$ z?p#lPv8YUR%wEfYKMbt{B*YeJYzJ0UF=5X?G`b6-I>YpAR%#^Iw7bqy`+f zSGmF5L6Z#G13hwomBz@IJUaVTU}({{+T3f~eWc+ouk)oEd!)5Z))6%>;JfBMz$$MV z8X6)a;R#~INl^f}hnAKWnD8I-g-1UQPpc(K?Xuq?p5}K`c6GageNX1<(xk$GLx-*S zWYFO&lfmlK69kIPMTw52+#H_IZ6|vsp=Ob+fdfH$J74hr{b54S|qoY6j=MiI6 z2u3M>4fBU$vCK0JLtuS3l8(e-wTxs8BfnCetzg8UMLvZ>%U@C;rTz_0O{u!YQPq8S zJ#oIS_?Hrc_V1I=HDkMH{cP&`CeP&9#BYj%ES;@~yHXMeJmnZ|9c3}9`y#IM$PU1ytOOmJJ@O=yq6&J#mrG7K83aM8kHT&h_G1toA*4hm3m8YwPx> z)uKrq`ZSt(W=_@2#%0KQEr*S}T8vm#R2#jbwEBMdXlrXbJKq8|(`EV4;-cGDx1Ua% z^B;1!LoTqn($mEQ4I_6ytx>(~bf@yAg$3>NJgvz(GdoAe>lps`rD{EXyj1{($j{5O zSAQw}o^5+i!7g(&H}iAKUk9~l^5N#Dx2?;1xlS|!1DF@ypDsHAK(?x_`3moD#DwtI zHs?J9>Z2g)Cd+UaF7ANu?c$BBY41sLX#p6waKe;Sj8vy7kEmjHS%E!3=tLta zQofwd8Ko6kv^cM)<198(QTA~bz<9(DWHbaWu`CYGW8>asz3AcY+A`2SzNWxwEJkFo zZq_r_m>5~7+)}GKu6?A_*1ot&xjk3v;A0NtUka~hfF6{waK7%d>fBA5T{zmlv3SVf zsdaq=KUyX$FQ%hX8uaFy63+U$r-XQYJd+s}xaX}Kg_8?c3uBlG4VCOWJ!QRA3_Ecbe_5(HwXMw;Zr!>2s`VBH<1Eb!+?EaNMD*byGgKl*DY+1tdOmY=- z9`g0%BuYNpo-VCV^-;pq(k0Tu(g#;v7T0<6C*%?nW2B-e-Z+Jt-ZG;_a_7IKHtBqp zck_3I3_fwxYF!4tj-9#;08;(cJBOeO!Mw6&3W zFSw##DpJv2eqg;C-HDxW!9MHn?+3zGcwLU?YK;ajl_iU3Vc@Z9eBPe7wzkwNHGg!7 zb|0MT;-ygQu$F44@Lj^^N`{Iw}% z&_rxMF#2)M4({i?)oFCTa{4!C2twQsnRA_kX0h@C=)HjmU;Q+w`2hw%C6qapi~4-Z zxOq1!@S0!p90F6RQ?Bv)ic@D`c_zPk#{9lAvdf!{a8U!F6Ii9q>9Sl`iP}lxkH9>d zlJ0=0<=dM2ym7j%gNagn@oxV*b-5o(dm%UHD4mS zi>Gz(6qs?;^~b%xs47zta1BmJV|9Q8+Qzj|-@%Ha)^Dne1P_){2S2BRZ!j|~j_q^Q z;r=WyNHvQdLVVIfLLw#O&1Uq3hX-%iZz37;_Y&)8pkf z0Q9rlZFFqMw>TZh>FVl!yuabL(E_nRn_f5LJwb3Ms2onpH3yOAfA4k^8Ya*3F`4`q ziEhuldv``$A9e?0{(T#05nyF+S1N*@p1y^*y{&D5Pj;U8<>4ZS(`g@|=Q@1o4}I-f z^}gEa-{|x-D(8*sJ7q@eC+Kt_<>XiQyEG!?X?TFKc|2sz^K!HwyyLb#!$h+9LeQgb z+^Bqmtb}?4dh~+ZCrj#Wt|i)Z=KJ`G6W&jHER3*R!u>tMZnUiQ!HjCaOe*yI(C&gy zs~92E&u|b#Wz(Q<;d~|!;z5@`(`l0Ej_|En+Ji?jLv81`%2nY)ZhL~oc&ki#Q z7pM38_A6Bu$>P_PcPz~xi&w(wVuovGpW-6ew+7WnQMP?^@)K-cVH4f&mQXH~@B)5i zK1MRAVXGOfLiw-|U5=-b57;s}iXBRrGgd3C9MSI<%US&i!ug4)Q58Tw;YkY0a&P7s z+sswt&dH^d=t^Iu<^fy-&$842*6zPz%q}Wx zQqu~ozcz-UQUJIrpWXwUxp|w*$vxga&L#QI%tiZGmcLlf22bF2J-8Ql;w5f-o3&AV zzaWtbEe=G)#dEk^j)9y4Ua6Au}@#*pE z;rhDAE(}PO_6FSkFJV576lTr7mD8=~@@2z?e5?P!Q<{9X<#ciq;g#irL5Tnvl5{UU zu-p3D)-L+)4n!S~mVtpyfn7qpH-q78CA6Br)oObVVG_2@9d`EeUQm%fQprh3bTj$x z^nLLPe>rJk=QkdT1)cyvM_N3ePUH7|2kO(oDBNZs-0S`=%83vf=Up ztef{m&2SBV{4gyle+g@Ap*VIDyJPudJ(`Xm$%S*QYQIF2TuMeYJ*s_2HjV?v zNKxj1lC<7qoOdzil9UPqZ5EDl(RH4vtJ%WJ5v7jDk73HXr*iI-yZ7NF!`$#)B7M~^ z;^c3A^^JRTji&Bz!r^R!4|A}waHBES|96*M^nl9v)Zu2orkfrJ7w-) zuVj+JFR!zfyG@bPy>!qquE&&lI^G}T$YEmZJV*b@89!R=a}+!#L;>4)C6`q#tbDS} zsJYG`JFfqm5qt2op%~ZZFudR4A9xXiY*tSG1Y*NaT7T|dd6=73e~XcxL<%l#AUd10 zY~-U-IY>TQw#La3WSlZ5XliiO;?%OJsWteCx*34oM~1`6<}mCj5_C*qU9dfqfy~DB zF26VvfZIKv)m}V8sp|8Lv~KK5!}L6Cm-X)BDGCXfi5f2Y*!Pt~Ew6QNmsn0-_b@>kJsZ1u1!`Tfp z89%P*Trzi|+i1y>#Vx|w8CPvkit}e8Wt4EDh2O%&T?tjQEn7YT`bA6y_wqXC_R$4}AWSo@jnA~{PsI@V$^iv^6j{SRwHS~P5xD3)+?=oRN zM{0S-g`DS}uSMG*{n^%lx1_`!M~C5-_?&5z9ULU<^Gkoe>!|f~cX@)f-X4nBJESjj zDFp=uqbUqA*v!ynJM-)o0e(j^a_spE&Qx0YGn!tP;vkH}r{J_l{Ada?42i$cgULE8 zEgf=;?8UR{M;3pX(hs+zsT3VnuLKuE=k@CX8u)Q%#*`{fc#z(4^gMbvuX2cmG4%w^ zn%<8&g%&-ZR|47RFQVh#6G*rfPO-2k&C6$Xy40Ryz@Z*BVKlyBM@^J=Ak!v~Fy))# zvPj?y9(yPwm50%{d0&l0=GEyjbLzE~H6yplVdI#8_*H(R&?7^Sov?w~5aQ=mCH)3D zsa5lKq)_K#>O3H3_1i6_m0wW3#&BezAX4fJKOPeZ>ecTD}RmJ#BCm(|u_vo=Mo(>paD z{Y$M%5sJS;$r5(FCXA3E`MFZUz~0rM*=g4uC0y)c!+&-pYPP@7aJe9nbhzuLCoJVl zmd!@Ik$OpYS?Nv<=(P7_O6q$vgv07Mg{DY;>?jnjoF1}xLD><#S{9VZs|tO60(ZOc zEVV}%Lz9!yORVr|Wd;hBtE*A`a>3S^dwYE(4N}J2)ykNmHlEbu3tQ(}r5Mr{tLRXX zij_0&;Zen&-~z9A3*YCXv9LpDk4y>mRkKoIob`wRw6ewfR!-HzvJM@DD%*>qBGoGd z7EL;_{|wW>eUX%Uf4Uh#-TdNhgQFN_{5pJ5u8-!H(}< zdVkzFH89hB5e=d}8ynw?n3b!^ zg_0c(2l{pKGrwGb!&p&A;cukOW=5;P+Q@`kPyg}HVW!Ev;mQi~X`UvLuY6B<3Lmyq zx4J;Cau08G$fnCOl`rAwcP}zl4vT|`3VKAC)ChvcnHjpX8&bD_yhur>VB@q$L)jkv z`~}QTG=V((esIy~E6#GU%`O$_bYLubz{MnG8aQ@t+l ziYAG2zfOwvD0|D(^$Oy)_ze2ZK*M!@?*bI2ULnxd) zYPcOcMq!db);y~4_UCHw4p&?w|SPh_gG zve%g#7;mq5;eB%v(jr%)?poDpInVo>V=c?a=^Z0Hpb<~Lfu(i*feVdV0sx((ryWPGfrErZ6UKvvE^A<<+OL0&9AO+bD<)FM>)FmnIWc zd~IVaqPKEIl9J?ZP;0ozSoSL z;)-5w%}=Ri9?p($>EkJNTZ*rCMDi;ytH+&-k-OSEk06j9;gf=DWl%>rxvVicbKz}R zwR}FKO@!-MmSsA+uk#;I8%opUcP(f-q>6j9Uw=rtv{0p4*hdtwzcrMd#oWROxp#eP zGB7JdCVt~T8YwHCdiAuI?;p7lDf1>S*ik4}VKU1Jf64#T(Q!B<62zBr>hCqRNFN)c zn${y095^@vsg!I3dCDL;`Aa*mE8R}_K`i%;0>JMipAf=l39kkf&u4-O;zk%o zzAE{lMdQQ=Tan`kVw+-mwa$&k3}Q^1QTDYlin*2bQI9kvh*BDFFo8miINeVP_}!*m zlY-o+1xJ;qk((P>ENwi-=DBl{QVnZLWlH6~6{1Il=%UiHl;gs;lRUacZs`+ZL(wMb z`b3BLY{V``e-{YpQO)RjdtNkm5hJA%b#4_j=Zy>)joy&%G`F#>)29ExC6#zLJB&LEqs~`4wB>JWyLljOcmu z*{^fBXfeqW!I^75{3+3{n<(YvYto3m@`>|tS(0W@cF*1nbr4HQl1C*0c4+F!$rp7R zm%tik^V2q6`~mBF4QE$xT_&;>6$Bj79qP}Z_xM}%Jl`^$WqD?O&cLQpD_mg%&_KOr5rmiUPoi8@=lHANM_#&F z$Yu3^^wg*uU*A$4#kb?uY4VtMcZ3}lCOP4@uDUL>qwgeNkaS!qKlF52J_=n z^eNOxQ4Oy+!|Kh@La-cst{$&)JTYb0BX1inwORm=Iwsfm#WS|~7)S{{-e#YGAVBzi z1tyCFL}w+#1dpC?hOB?^e{3ACEaqBe<+fyEf5S7k2Ll5W2pC0C`2_p}L}^0&djXq4 z1QQ@5MUhlgM4kh-5CK;&At5W<>3W9q-|zqJ_1}9-aQ}M)W=B%Pu0TRTOzhup$ZC!P z(5R#enMg?Tb4MKyCh)nr+k**m2223QUtL?T9tzBmC5Z~y95@v$d&(GA(#cszaJax`tR@m z+6Y#F|DUbEhwjSmuaEy!NCE<2Do|ix444|`7+|_c0H*W|V2r;BfF1wqNdLaHA)(I! zobvxYD6suka4;aZA_MjXZfF#Yy!_M$JZt?T*_(U7^6X*S>)1 zVN3LWGUvG$`cuu5I!fDzFc_Hvqh?&@4sIkIdN3BSOC9bhiJ{fK)n#s>+v~rt8_^8> zQEl=BH1AjEOCC3%#$%&!@xf%}YDpZKW#wS!TitllpPXMz@X|Q%2O;~VM}OY`Nz12@ zUBN+4qn(>aR#En%v3yCaO(^pInGdf?_pg%((0xy(i%r=gOF#Wl4*FnKx8W&z`PNs; zYAaVR9XE*4V9cs=#i30YSb@zz^-cEt0(o#0i-GO{o?J**OHP}EYjUux%HMqwfNEb! zK7S*J01nFn?_2`@8<|)xYR!d+i*vAT-cxum=2*BT6y1&Zp8s@Va`!lz)y(lMqxqP9 zFTo(YfL}w)`L26I_&_-^8b2iJys#x+0GDNm?S4|Nzq*-!Zy-h9V-%JYek+u^>!rOS4N@*SL+>@m+4v( zzh@w~-=h>-EihgNOuum*R^h+h9Et{B$9%k|xW1M=;E(>F0J;uE@gpQm_~fWPe_#4H z8##9BJ#@nG?skN;y{;0O!B#kj4BUI5`^`-o;)?jr0VBT{);ekD?>iI4)~z~)OdjX& zKn!XqQ3*6s0BArA0MIDN`J+2F9E8xq%$Y^MD~8TY&v~>0H2MI6;>-y?p87nEyCw53Tt7Ea!I1NA|Zoxe`_*> z1fQp5owZbIQ|T%qS$yV60gJL#CD2 zC(g{gd85gLZ|^@99sqy_0HhsgWYVs=JdcpNn;P<}{MG_O&(32ZBy`Jb>2;$dr*6fU z7bcZz<5%N@NvE@np)b$tg-_>T1vSV|VrANpV$^Mm_f|<>o-mNSQJ?fH{&L9BS-rWkX?YGa2-mbZx0NV6O=NtSDPxAmdnTDOW=;s_>Np|5UKmASIN0CaMuW9kqr<2oJ`z%QCOc6l}oiTu$8If zlKUIc`B;@qo`{dm!if^8gR}!c0|R62K%;_+WLb&WzLXvQ`I{w6maN#g{}jG@=}sa3 zNrKR)BYcgXWcPQl9j?@9v#%eUAj zIc`4g9~`)uQJ)f3#cS*2UgQD4xeG#526P}#1kJtizieou003j{0Pu_`O7anMDa(71 zO|2Q+D2t)Xj-L)YZ|FBjK}>-CWyjd|F+Cj5IhtrE}Ek$ML0Z;eJpCVlUc zJp-XFL%SmMsCDn&N;aE^kdLy7fQ~aJLg@Xb75Qe^T1?7@Q%kAYI1;ar%7v$KIQY!s z2d`vRcsH$hH#m5=CN9^jL{)HcG|$N+x<}^ehwzmx0D!au!1JI-e0OXdHW|5j^DyI; zyyF{wm)Y=Z2+w4Bp!E6sv*ylrC#H90UWu;ya|2D{b`1Jy77G1-wc-}?+cKO;y5+cU zzpWgi2xkn|D8W`x(n%uh+fDDzII%CevnD#t5zLR z72#1?lct(dJU{t9V)J1dI{>_WfI}W=Wbgz2w*YPVpv5=)?qp@%KK{LH$edMDZcPH^ zIP6nmq`CjXh;x_EM||x$^5#h$DatL_iKgX z9`LHC?qF40sp;)6#%~+bbIJhkRm9bhC1*BGB6Q^F5#kUqb-KBws3IMMFSZEe#q-Yi5QWcfOv*y&=e-$Qf z-J9NH>KGqVt7K8Ltw$uCm7WjeH+23=_W9e5>3zoV?fbPCqfA_?r?L2a&I^>9h(twW z+0`!+nXE*E=yv>PsDj*0J=`L~)fcAL(|upGBgpBy4~x^L+Cf7F0I=Etpx#ZJV`Ebf zCDY`D&kjSsT-df@l=Gv*LuPD5VTXD&u&&E4?OC_;_vLZuyFYu^Sqv*1n-?xM5s6j3 z4$_3_Sp7AiyCH00000AngDE0002IsenTs0N!x)53*F!ic?)irb_;@;#R6| z=2v|Grk5)#p8@~?(hdM`8EUyEHB+8j-1bFT}-b{A~T(bsfKPNHa8 zocK_o$-8DKEM0n8{K<9I%gB!AzzOl%SV_9MxcMp4wXwqTv;Y7AX$OF}3*EU>qLr7+ z9#zp^<*E~+&rg*Wzp@mK#&bDG_>t8T8$>&9f z6_g1fc3$Qw?XKNzM{&^KF(v6>x&r`6I{>^H=${lS6Eo#^@>N+v_2Uw=KHSDY?`a{N;E?9L{zALB2;I~O-gBxg_cdRFnRmwNQg^M3RU@Xy;7q3_klb~SV<3+ zng=pj^AlKKDA|jS#*9!|3S2GpaazhoX`n*cT;VkaVteg?IZZ=qe&&Nt0 z)gi$85{b67B8)*M(F&F3M1`{NauDt`1Xo!_hB5SgE>8FBD+*{#0Pyw#-?amc1+^+7 zN_@P^qOg=tM>_S=$iF)xOEz7R(cSpl`!Zuslth~KZ}0h%y`;SUF-~AzQ{=LzBiYuM z%TTI*jFIJ43e?8eZh0GqB408kwu&8|;l}?WM`kfa|yEc9-K~0XjK3JRyzQ^KBSqYSl4+T{NF~}PO>B1*Ij%Co!R=U z7YRx3>1(rXsC57bX>();imAN=1xx$#0?5T(0(`Ak_O<>ZkX!QtHx?rKTWCO3icxgA zj-1&Y2#riiQAm;Q$~8jQ1O4o_1Y3EMO8k2_cAY8ucH)N-+18)WHg!+(9;vYU`Z`dm zXNY3Y@e%XxrvMV;Vnlxyv+$EdI+$KoQlt(xO7`m8b-aR&g9 zb^v&-$RvamHF06tu$fIrtJlev$yKUOhzKd9NmS<^YM4wyCPfN^vkSYO8^@Edcy0|cETtUTRBxcXHp3YhxWZlz;>w}PvhMy=3jZjaDy92|@f#HUbio0W!Od&o=?i2Osun2_vN%j&pdpQ1FGq-5bDeNnaDC$?2hvnyxSA*} z8q$$fx%=YCsX^N5GzVx;007bs0I!`VIm9Prwl1syE@BE;J=<`c$m?ZfJD)Y&{@rRC zX#9Z8U`gPfa?V?hL|sMx&1moDVY8bW*ph+e-_@1d*PT&kifUbT?>Ei6DMg=A(<5pq zQ6g(+dgbhBC8`UV+U8!|mRz$BpT-XLkS08qZBpU*nS`8dxTCs(V`X>hUyJs zbp}FBph*D$NIL+$UUa0;8sz$7CY3HxUAk-N(T3~FWDj+etSi#4KU$RH$+Xq!6Y@}4 zh^=vg7>hKHx1JT}JD`Uu=JY;Xqf&B974wg29I-{N*1LAFncb#_NGd03$yO*S@BK< zDv{An^{H5zzGVll_2aV3MTp_WZBfx}ptU|_5r zXe2OrL}M09G&gcpu@6-TZ_B1fm&y^vH^4T`4r`?TpLAu^Lv^;I+#62w@4;<~kW8f7 zm#(^0sI5FFO)SygmuPX|TOu63mPpElVI4OHC-vL-fHOmAmHD=H$2U-E68#vMpyA;ewzH zZ^NqW66n;NW-Te(ZQ`gYku2gHF)2UX>r@FHSxm<^+R0f+`=SE~TM^Y&t`Qiz&DwR3u{N&=#Z)+(Y zf;|cARaCN>?9TEnN1{FlMlGh%GcK0C-yghdj_oI;jlOSUr5U_yNz5U!;>F zq_-)bzlM!tn!xf`+7vFgzE45TkyLu3cyw!|k}8znoYZ+BT>@eBqh3|^FMWm-iPdQy z74MHJ_8jWi$GD5Utn8~8g`CIP*v&##s_42zvGYdRm3&+k)FpkasyW{2BZI7>PL$0$ zCi^SI^y$3hfe7omXD3_GbpUv)p{-c40%`$x`=K^>rwinInNt5mg?QHVfVS3)dT?HY zQ<=r|ccdswbt08srbA8bnIHDD{jlkCk6Tl{J?TZchSsgw&c^rlmNRPd`lrX%z=FE12vor#YC literal 0 HcmV?d00001 diff --git a/doc/grid_map_layers.pdf b/doc/grid_map_layers.pdf new file mode 100644 index 0000000000000000000000000000000000000000..bfc4830b6a0b2429dccc18981ce9317c2beff4d1 GIT binary patch literal 64245 zcmb@t1#}!svMnlRwpg;%VrFJ$X0VuQYvAWmfEnojbCl$rMG!>6qwQ;K&AkT>LmJyUd>&7=mL3Faqq2tl)Tg0SvOH zcIGY?05)KgGJrwc(#FNq3HWYf=wd2rYHV*}3gG95b9QkuHME8E03FQGvd14r9bVs6 zalz+FK(Ls*J;(ha_=GM3@w9O#lus!GRS{el$eG9AU74GkL*%Ye8V?|?c{e+&tE=() zq3tI4e!+)ve4O1o>GL-yMvkGctP~p2$o02NI$3*{--MZJCu-TDe9jbmRWp>Z_h?H) z2R#UAtH%$$vwUtFJ*{(Ju7@%Nx>cxr>YSO0qCi?@g>I!%$6fm^h9vXIcsXQ}b8_lE zjdS@Q_r`um7@OO7#ay0H!6(LFO~Dg$5_yyiSYKLEtQOCF zs^b-Hi)o;QiHh_kDBYO#*ICum>wLXW!}_{|Dfb#yD&WUTSZYT5ia2agWz1`cI%%kHT>O+;A|BcR3uG1H_BZ9)lHRz#2*WOf%Tmj<*6~{cz zZJR8*K-J}M(ipAh@iIg6t*v3!I`Gb;cG93ou#;!x4F)=ihUYoX&ZMjn1cV=CYdqby zEZ?!EYG=I_!rRI|JGoZ%Y+5vQyGy^GXX(sT+&Lm$gfA7v2)fLK z`O)dTy@gh{>LuE;a+!&Hl!$j(?}M!NO<*M#@4fI~F3vT|RwbVCwq&Vz>H0 z1{tSET0XDScvGY{(KwNLkW(ym8jYo$CInYf#9)*9x2Q}uKpHlEoqfMfU6+Ao96bCC zVmlXRzN9p<21dX7e0_x>O35;BWQkG>-U23TOud|!jUwHavW_w+l34&YS%Gy1pZw8~ zb9(RNl2_lVm?Ng5h>3wQxhjXoM+)*lHWtNpu4(e7P5xTEK2ZwEv+V7=<12qCIsrjz ztowm>aI*U=J%QOA3;h5$Avst#rEHit{>_}jAp)>Ehc#+F+l>Jcj`Tv{@1n!uBUAhP z-rhej`pqJeO-)VbFe(hBrFRtZ$X90Hfwy7BLg?}2x7Qng20Mk1!&v*e3;ffC>IgTi zi1m9O0XyCMHXUb>_O=Lzq=%;->8wg7w$IygK4pv1`=+9_vb1^-y1kEwf*|HTxu`mX z05i~??B)zV8_~1R=Wy5H2iQZMTgS7HR zG8%d4rXcZXufo#~rUvOG^q~W$E_S9@7|6TWl!lOel*F?Ro^m8Cd%;zc`!Y9EN>ns3w@ZO%4RArNwjZ0MVz5o+U)vV z0*2P3KLUAC#)1~5>)$?*B>kjsBms8N#HX~cvQ0?s3;WHvv8zJ>_O3X%{&2M2eN91C zkAm8dimvAB!IKzKktT|Q-kwun__NQaM*_VanT0NuovcZk%d#TVu8^zXFFs&Lei_}Q zU{vOWsyhl2Uwov{^E7roGq1OE%q`pB&EEnhV&%6)kH{&wSms_2lu8&(g2eqwtqfbA;821i0x_;n)S__0s z58==tddVBPJ!;+N>1Mozzx025XS)O;1^AX(GU*bcw&CUtRa5B~-z?`+u#e zxRRTI?QlY2A*SsF&7-)Pn1<@Sa<)X^pQ8lRnuHA8!A0bRlMN#!Z#A6>=+6#Jw>2Uf zj^Q#v3#L@F@J@zZYRPq~`iyU7>jL_$Q=vI<+?O_G=5*Gi_%&Nylbgp@EnPgBnr4Wn zdZ*1!DXFwT%o$nXBR=&JVG6w~3>TGfri&$^qkaIJDUR&Pmuo2VK;xd~ zC^=W947y5ii^W!3lQgF=RMO@(MvcjzfEPAfYL${J@0U#_Wl|SJ)DyOI)55F(iPA|E zoEINC?aEzy-`?D*#U}wGF{aFHRTlk;M{2&3R1Q=!C%;(TuECGArh8Y?>k`~X&rZww zQRyf={&4rD2Ci!<`W@MT34s~<`<)xyTT-Ib*~cB1)uNjt-ax$${4$m!q&k<@8(Lz1 zONg+#d}eOq>GzlYcJ3S5{J96k5i3N}Q`y_2S%Ew8?{_%5bzYx#p086{{mu{PkB7l$ zK&KjaM4gd|m{%!73-=#e84|x9jp3S&3&0w6YbD zHqJ#0OhP~Z+ndiidb;{q?)GuoFX%j65LdOQ4&L|Tp+(Z=qM_RU2();9_5`}C{H1(j zw<~#HEgpMyd{{n1BVF7e*l$Ix+i}8pMGg3T*8qi729U(fm*tiTU?>xy;5BXEWr!_e5G^-Kcb+%gV5eXTRwVy15?=8DK zDL=o0qZY8d!kOBc{8oa%v!4R;r)vE9&dkQf_4Del^Zz9-RXrU{0St zmcN9ivZ=GZtCO**Gl2cC1`&HZ7vObgz)x`sRHAaGCYFZ6_8x$DjKBsqMm7Kw3x_To zP>lW_=jZ4Ch*(7@dt((-7r;B-+S=KMJ>9Ppe8!1QxSWuWi{Fo=1$NT|2~#qh6=62OZr9RIi|4xIC^ zc2!jt01MNvb_P{dP5{fVhk^s1GXq%ux*71C3Bb(trwJqQ|IA4KDJc<)m4O2jLJ+-me(w%yO!4fz;2UI!NgxOjYG>%Oc|G2O z116@dSY20J!$dP5QLC7In?u78%^(D)FmYVeFwYRIU$8N9{u69Wzk&q7 z@Lz$=G``)gpAkXK-G49#J{ePrue?>aj!b2z&mjRsS$pO9Rl;=(Os+tTJD(o;Bm|t? zgd7W!9DPiY2$RwwNWnx%af3{GA*6T!9~TAVqSU~haR0?DIeaW=7QBL!e{;rQ1#CWI zBwYgEaUWkSd%Bx8+7Pr~DVEC|@z{)B^cwUFNYn?m`j4p?dY+BnB=_03>`6=?FCY0g zpVxW>5U(B`35F)CPn(18zsXHaAuM~!;|!s{d1aldL}dsnC|pNjwCq~SStbfq|WxPMQ{SE#9KV0>{yaMiTbOB_WzYzK>LVh#lFM9Yh@E?cyO|$LFlA{HwL7i<6w^V}`n{Qb1=kJF75C|G=gR1Nu%D`M5_ zd*Was7Y1f^OtnmuJ1rWO7oHB=G3O*wKL%Z&sJHRcyjJFqruulpw4|7@V$h}L_jJd! z-SvaDQ9op0ysi7LTrQ=ooJvVE(;Q@OxduJ;G0_(Jo&0vI8~kKa_1O8{6?D@(^8J4U z^`G4oCKk4TK>cT7{JFaP4eI|q(0@_+-*5xk`4@5iw{ZJE@$+x@_^$w068{CRPY^-u z_7cOLj?EQ(7kgzIe@%hg-PR!6_I8oTk8Ai;@+3Y#Y@ zp3zl%HgEwl>8XeFuMqz-`cEL3I5_@5%=`!Te-H8Bb;HkP@E3AF*LW2RLla9o^S{TFNpvLYzKDxOGf-t0RJTSzxly$BK~i=!M_jR-)iN*;smCOK(-e|Sb4_ChQIPj zJSoV^DtX6Zii7|SYrs*v`sD9gwMsT6jD{v=*@yZDjw=tFsXY;bM6)O=xpyo54HSfY zm87^LRzrGEUl@coPaUj3=D1ny<*HN9wdv?S;yQUIhA0}E;fW*jczejZSwGqkJEqcH z=R~9O_#uPNFlo%Xgp%M=wvK~L6HyfHdb_@ zpqHOA012C))|{)pe(g@UJv^}!edK~ea|>V8Ym|CYD>AJhT!Zw35c@fWdJp}$B2$o4&)qq1hp zt_q56XCTCsvY`ikhgoe@feII!-FYz?F-lZ1*)(dN>#Y}kcZtOp-c+!N20n{L_#>jr+ev-Os1~WAMKr{hxFFFADf`m;aTX{7yywP{uC>&ipfh zv3D|Y2If1g%v|)0j9e@Lc1~t`R>q$+^SgnLor|8GgNcg?4mb-@ds{tG|KuZo*zOlA{Xa~PiItI_gNYrO9dXffak8>< z0sgeW(XrAqax$|31uau!0$g;*nn1*G_^Fh zZ~<^|0CPoPHtOVH|MP1QxWAH*e+P=3p|dpr7!ALcWMNAeXGK#d5qnz)d%K^hE+^2U z|EkA-CSd>gKIJ&)ojtxpV(2r)^HH$wIz-<(aTKX0=175l~wPfIX$;j^|~G^pRF-1{x2^N0Os9T_wh^K zjq!GT_tVq-?j-Ve!)04`cvg6yNJtpBXOg>S0e`-Xv)3|(SEd(dZ|3`(AEztf;Va>J zSEDZ`edh{!aR@3M}0{GW6%I z*~h$Udb8j}3)mgyT6v#eo-TiFezzUjrG|5iHGmDT*fRHZD3yTer2n$X`{(2}Z9&UH zU+1Qo9(%Kr8dv>ajyHloAAUU6_kW$tf&I$$1Yu+oWemdvLikMFec(?=rll)&oMjfc zQrpAJr%0SX#Fq&91I9XObco^g;pRv6BvKiJo`M)cShXkydDiy6fe$S!c62G8_iXQp zON%!%eh$KoysDXVTw>Pa!+}kWH}fK2;h1EEBRhVlKR%5s{8wQ*L(75R%I3f9NAOL`& zg*y{tm%3JO-fuYvlZ{`8v%H532_G<&V(sWHhU`NgHwXMi4De1o+FQ7#KTc>;^bdi7Qj2$Dl&G$ zOi21lL5wkpwAOXEzJIf+3L$=5(cXA;UuT)Czk_jnRAw27izvCfx0vkU`;My!udx|7>svf3tbtu#fzZ{u@M?Y{%dEnpbM)Pnvy5$=v(4rXxGDz8Dz68Nj15<~LL@WnE zo}LY&j*pBEw}{FrWF`+qk_@N&X@)n{9?K%PPIi_z&*z9&96X&M9dB#~++E}#F;rd# z{kf|+6+0n4h972Q5gN4N^bA3EWB@dw*K`aKy*`o@^&*hk_m0NTm?rJutROj>=1i+g zdU;Bh)E%tOB}Z6$fQIyat~3JZj{#4Y1YgjJ1h&cgDc!ELNjQyDn(pMLy8bOY)m?(VT>KtAH@jCq<*ebJ^|aTOFjoM{OE+S6O9Tla8~^+)avWd9(?@MO3$l?4Dw9l$TN64Rmf4g*2E(dtOd(6LZjl?&vEhKi+g87qwKB|EEur(k^ZENYb2V+mk1mT^}|u1jA#85qF;*-k
x&QtrVPa`Nmr(l0Pj0-wR%bch{9{NV_>O^OgG zl`M0WRRMUE+4mN8DS0vy6D?++JY#oRCo5PLMw>q6?UEo5wflE?dO4WVof}ZoDLLuD z>fN*RSKCQ`?v-k2R4C@ugdr1ys}+IKNDza#|5(-NI?|4P%q?>Zi^=TNv3S6Uo%^`s!_i82PM_a>te&hXRFtc@ZsSU3cxVh5)e>K8VOE>bAMI7a12V{LgsS%GQsTK-I2}Jlafzd@_w?TCE z+J*1T}<*S#FLU<38Z9!d8UzRawUt<&}lS<0E3SPQGT$^OBHR8n0AiWVk!c@ba~2%9wB`AElMMT(>q36tode zxk^|8-TNY2UM5*$blss(5UMrxEygJ|fwgSF=ddF2`#a3IM!YiQ$qp^b*i}!D6|Dx4 z8dw-?Xe(t0iG*XX~g+Zl~J ze`B5Gfjy&n*_&@1xSr-2;+(XKbXhb0UdP*OgoVg`qV$B=0%$V?Yhd0FIl`vAp!KFj zOl{&MlU{hd*rnE@1VO{H$@^LxVABGE6^3Lbfn_3K6{7H3K_YHRBEDeu>p`+ck6dto_#3<`F~W0scLM6ejleN6RRnCma;w zZa*;%b6S5UiF2%aBy-a)Tw}S>HgaUijB}v#Mz_OM4P+mgNR83xMSRUD+u&{dGCwNp z+j0DAim55asLDW&U8NsTxFNDYGF-vKNQhB5SBDCY)kZY(}E zym(XU=_iz}e=&D&VrUj!PcAxxy*tBD`xVWfzda>PID7esd~2Iphl~*UcvXLrlhA2aLnAO?y*;myajI8wP2T`Q_5f9B>^Q)QqwQ zqWnclW`ggp;Ghz-TiFcVy3{huCT3*jOFi|_VCojpyf$!({+x@D-c6ts_6<9{5EzoC<+|Ct7A|cE<>3Sybo~v9S1da#@xH$s_0?f6S6V8$jKl z#ippL_f>JLORFbBNYvR_%lc@Wk&mMI;J$w7O}&I-5as|%ZNBHs)m>enj0f)OX0fT% zUOAh>{c-)O-`8kNKs#t)%!~0ZGs|GZsx31&XBifFU9~26 zJ>>-^nGIX?D=Wo(d7WSNRAinE=+1+8Ws3EUYJx5sMGs=9+@cIBru1yl7QbT6L(he$ zV*jYWk3fk>W~F12Js;pN+Sez=HZVqs-r~ALo(c@!6h7HqYR4b0|D;vvc_HE?v-8@p zQ*mo5!!~(;&nwe>R-1HU8?a^g%!0eupG0u=jFx5@DO;uY>tG#OXtt8IO;W9YLmPasuq4qy$3bWji(0g@jW)NaO);_?(G@ zH7c{LY81a)Ncj8cXSvdpouxQib3i2U3BNAvOxVNW#1JdB(P79lLEf&dbq&K~j8njW zX&CSy#NHL7Q~E*!@m~EIjfAEcauP*eT%)f8+}1oO@IVMnC)db^WmAFehhtYx33Luc zLylP>JRPF~&#O(q=p#NE?k2m+|BBYzV0D~Ard^n;+P2k^T3!*7u8OlHF~q9F z^Ipj8hylFq(RzrpHV+~I3>31d@{2@?OCuD(!7-(nt~`*K=0i}dTd~&0drU^7;$V!3 zo+XPBus1U?GVj!1ATSFxJ@_Xq*_j(dCR$iTBsjYtj^x zWm|?JG$rFfz{cq^q!yMd{2{vCL>aOlxcC0W(sGbn3ni&wTZn#cuTg_{NXrscC2f|$ zQAx&RpN!!1YRV?a=X#r@C)Pn`$slmY_{GV3=^}g8>1NZJYmgX9fh<~9F9+LUJBqb@ z$kYV5_U22}Rz9JE@#9iBiT4G;_bGh%P-w=B!DcmX0jdwzy5kTN+E7fk6{+ZvgNXM0 zy_$)%wEJl-NAbE78WDs-^;fEn}XhRZK%YoDe_iHD%_M$*#CS|zl8JfI!ZeFFbEz{a?qpP8gi|BFBf{_9+L@cZ~Q*eZ#q2R7!+7jmZ z;B6I`z!o5q_*>dqx=Cn{PbKXi6I!FRl~NcLn2h?aoIP2)hL?j9>9Ns&MN8q-(UKw6 ziinY*XS8^_a@e81u`Qf1sso?ItFa6o(6Fr4<^%CxUZ8bgpmk9560D5c&0=hk@ox&| zjzHSa?n^E*nVpKOla9dEpOj{rPwvpZl)TipR3d_P@%tj>R_z|7P5=`AAu>r!qy$ zd?TVDm@wOwHNEMFGg`8)%jBIhp^O}UpPupv=t< z9BV$Kg#*?#f#w`A$aZKA!W%w(p`(F__g+yV8Ka8V78-&ah6Uwtmhlz~!V^bskfzfU zlroCpGH*-RIMved-BrCrrXBOU_ip^`IpJ5)!Vd6}mu*qcJ1{{?imYPzj!H3I{lU33 z5i3T)+@MGg#{lz6WKlj-Y!ZwFjbK@aH#2y3xWDp+y{7M5MeNn*CiYDFnJIuR+iueF zWP2TOzo944QI-8E+n0;04x8s5L(q_piHP{~;R+0*qYcJ_b*K&N{LW0CxufdfBFm^n z*dyEf7^^%6aFeDWi81L(i`Z@~lRMz=vw*>^W45@Y3iDoo{^<4pq zxCb$DTZj*@AAarX#rZ5PbtIoTtxZ3>Y)_bNI~FD*pJX#_*L#^+7%097O#SPUoaKym zW(Tw3m#vRT$(tVmL_rZ4+FN{i^F(Jt%Vr-Rhs&8!QeL`^0=cajYiYSWA<>uYh-n}thE=6KNSDKvE83-L=PG! zh@7pTrQxnkTraHqP9}sPdT^iYZAf-GjF^%rUrSKAhe{{$^(-0%nM|E%#e*IgSReOJ z6{z;6@WWMa4=7Ax*NoYha#=-q8;o=uv%KDLf_U4}8J|0fz70sd&l+!we=cs;S_W!$ zg71bPt)ZK~LLxzsDT4Cs7N$}{=i(WDa@aFZnaeN8&>~}~AftxDY8c=V3^pyl&;l8x zneG=63enTsQ+fWFt{OO3;mZCM!L4Bh8=qN6+6 z%b6l38o6qZN21o1I58P^lsGJtsU!uY9zBmi%tn$J15~mt3qRZ z>LT5&1Sw*Jt?WS^vHMZ#Ej6ix4Z%yPoyGzAr%3WE@nEJDUjfQgf~5T(IKAPKHJCIs3tZ7g>)VC(4XIiLcyr0 zN1;Z>g8j46J}Nx6NRVJFK#{3W2Mg=0o`kUBKT47Mh!T+57Z9gr%b;TReAdCWak zYO=5lRO)Z3>FNq0?!oF4>=uU6=V`0S@xRiQ`@`!^sZ+KCvanMOx zG8`Cl4TJzb2do031hfH7vEi8e6X^Mc?}?FP-6>D!KMMDFD?kn zv~rxkRC(+7UMjE2f86ogLFA{=X2=?s*R?Dgrv4PCH;6oZGqOmTXK?w7NAQJ+kfm@z zb^zl1B3gHB%FSDH>eGX&ZzR5gErwW5^H^!|3>7Ba;zH>y!jB!@m;s2&)>S`nLAmXu zqWUpg1uMK%z|M%e-ZP(@*C;-wKMi!5UtHw%4r-p=D4h~8j<#<=Rofu zchdO+_i7Ky=pexxod*Wc4@ieLm^b?;P@@3w+zqk?6y3_>JBI~=cd|@^0hPxvueAcC zc4G#T=l=MzSXX%s{H<|s7P`_#R3@za*HR&6k)>(PW0D`F&n8>c>5_!*h77d71}+CL|?V!I|sBkaU;@C6eAneI<%XRLCfB%a*Qsa zP0!bu4z}Wh-Q#gvIjHjjE3F8kX)23=av$+1C_Z1s{c2 z3ggd);99Gf;aYD&!m<+~W>S*}Ao{Jfna+Hkl%nFL8v_h#O6Tpt9ISI`wYkeYFUorK zuZk>km$*3zVHKii!I7!5veIMIxW!6vDrZrAK01xyGFg%CS1;*y9P8Kws$GGQqog9+ zP{iv-uI5$I2ExLeCU&M`*T*^4SVWQ+ww10`D_vVz#~#d=3d_vJgHD5YMjI<9>*EZF zD*N136hbp@=0m%!i6h&+5w{8w5)))>BEmj@58MGAm6_M*P}QyQq*e$t(6sy9RBEk0 z#$A^(3PpKum7;%j*W+rXS-u&RXR+dm$%w0niY;xXQ$m&rZFB(h^lhJZa$l){+Q2Bk zTCv3C2ZnZGsUVTAFJib)L8<6$26e{UJnC9k^NmunHM8RNDSJrq$*N$MGEcCJG+<(F zYWm6Z^Z9q}+|g8C)&de%1)ds55&86Gv6hAjID}f7u-mYxn-N74@fcDCG;WigL#xOk zoJHX@aB=$hCDAEf9DxIvMQGw=5AJ7G0Y2`{_|%gLQ!&n&kyb(MU|zrTjJ-F1cX;~ zHHyoe+ERI23e6w=yRKbh5-SWxQ_|91g;nOs$S3nntAQN%W$4 z5_lU^J-+jgnZrbj$*4}gPNA`t7)E2v5F^RSbZnn>2Ip0yZj-YrJT>jiGVVMV#z8o#L^NzS$5i7kx@V$<2j@lD4626TFi`SDGpcUh7$f2QQG63Da z(k9+Yq^;J_XiP1af=V`+xRQAaw0n)K)8Be4x=8XkDr1prB`tiJoyEYxs*p)^eOY{Z zo3KnGcT3l-8q8+EO{)qYmNlPQhTnDhx>!Kv6P>xs%o>2(3qgyH&1)M|1G||$1pA|4 z28|C9m*N4Ap70s10FK;VOhzXywPjl>1ro{ojdkQ{F`1Rtd?^`!-C5`La0Tp8YvwMp zuE3(HlNrXLld?^R+W2t9ot`D`f$unCW-aTPtImi$cl6jW7qMkT&n7re4q}q ziS5l3gg~?t?cAo!(#|jCArr1Ze&QzEN8Jf4=y&+;oj&|QRJi%NYq!OJo$JDwU)V>j zN-+Yo$HGRn*24{_z#`HMBJN&}E+NpbUVH0iv%xYFnQw>S=2?R(5@Hf)&vwIPzue9p zDnp(7>g+tf+-P}IQP{*x7{Q6@@vi#B*!LeaF)WA-=&f>5-BF`^z{)5GzGd$2LtHna z^k3x_8W`C~3Z-{CQg5iq3KT z8O^+5;8f~4Gxe?p{2*c7Hz!di-?L5+xT`(Ay0?38^i+GYTLDv;S0+N@%2l{R8x*`u zEV9c2Hf8G=V!p$G`U$m$-fT)Td4!XUaT~5j%-z9lSU-iZl8CG%@h+17Mu-U4OP3Tb zJauFoi~IXFJ&GXeVu?K@yl5xX+?Dp0iCoc(H{E%T{B%!ewvMiGc6Xjn(j^%)QDR#c zcKM;+=UWrFWQmjK? z?;FIVxcfkbF(K)u!iE^n)2KS`^OMR~Sna-8_?GXX+J#m4pMxz0bNBKteIF!x`Chkz zQd=AymMtT-pEHW18#OXhJxt52DR?#Efud!BHv>*2#$bK&QaN)sA#*vqO(hT?2E`&? zDI)?Dw`Zl@18YaL!R$^$({KRBG(R}G2PFrs01*y#I}FP?k#mc%MD_?oX956$i-~wu zrYTfLW*GPtn#o3h%h=_uM1qT#o3CFD?Wh0WG z(fo_`x5TuKWH9YMZ!WtMv_MuSf0xdrkUKl6&^xXjYFh-ey}fXSRiiC|J%)isf1%Ev zw*7V{w9yCsb~}}7gDCq02`DEiQZW}X6mAP^8QDQ7$uk->u2J=Qy=(UXFjyTZY@7Y< zX%)*zcP(?Rf~I->kJuDCFWyb@I_qvv5h5TVdFs_`I|I%{#!-+WGyp2tf~sR)mO)`R z!7;Q}kx5^yBOyWX_*ytl7VN$kyvrxX*3b8}dP*Q)Rlb|ugU1&I$=0XLikN@`fCDzZ zR`_;{B5KVnl9jNupR(D0Z9{{$jO1yJz2pLJp6iDz_Sj?cTT@(AvO|6raUXJfy(vDAatcfbfQbX>XL-L4B?XeNqNz>sZX!4=@E!<;?1+<)1kiy1WZ`-Fqx>T4wT+OB zw3ispty7(l1T8EaPJJs@H{R3;HjJkctep7ezR@GM0%I*9y;3&wC~673VG{^*FqXMI zhA{+24#c-IzOAHs!IVUw=j+yI-tMoYlJ@#fW30KE?lPdeuY35XlI{5vrK(^?1c>$LxS6>3YiFNK z=CxaU*T_LX_~c8QrW1vH=ZyV&cu6Wt^B87H|Iv!(#EmIR6nGaK{FliW zskJffn~*sI=p{PZZgq%=V4HC|oA{<9mzUDy%`F3+xFXZC*-oOx-Lk~hKBN*OH~1{c zFGrY7$>hKf$egcSOiXOf8esb8DD_L|89qN!2L~^wk$fva=nBFJ*5yO(NPCXVL5e$? z9hH#v=|(b=cB$R0ujBA=+c5~B`zU9u^ft)X??EH_F#?%qT)QR$IoRHet3{Qfx4Aa2 zH?j?(E07PKpmK0SW{H=x+?VQbd4EGKh|inYgXaUZ$hZpF`6#hjj*p#T@LZ}sQ+uc> z6}KbhyReu`dd%DDP9ZBY;;yJcUzbxw>aBK7Wc7~7h5`3lBF@{?8Hn{kq~OU8TDcyg z3EI+5U1v9>bx7c5y{{H!Z#-Y^z6X2#tRCu>O=>F17)e}IM$XL^xxOdSMe}UmgG$sA zQHyDsXeF|C#&~ZF_Aq|bpj_JL>wy2 z*deOx&6jB3LQz$f$uq0_tRiQ}|>>-}|e!D4Ln1U_tEW>9o0 zGZ1^f)|Rj;HP;lnq^}M>+=hYxvF^f^wZZq+Vp@~{nvdiWnNRvt%D+b1uK@ZPRO~GO zsMP*dME$owWBKjv|52c^u(ACk(m1&O!$|ups@Q%P(fvKD{UWwyE)RcllsZE&h3)!@rS55{udmKq4oHl_@3az z9x6=`TqNXI2M-U<^>5#nAGS|dt@+o#=XXDY&)>0l!KnS!6ZrezFodRS)~8m(%`=C~ z>u&zcQ@fX%>tPOPh1Xg>@8^T*=>;eTxXXSyq!-|?pW#%&MQ~j@E*r_Kx8J;3^2jC% zRL})O#H=y;nBlJzbiYH+9$WHyx=F4ccMMI7|JLs5YU}(kr+T;jkm4~e4vBq@*Wat- z5~KS5WT=`)A-2h!VzN8Kzx(F)G&hhyaQIZfhQROf?)p$7KvocX4Mw1V5RZPitV(zL z{-hcrQGCyUC?1psDIB!@#n<``-s|p%@owK+o32K;i>ELCPmc(i9_`I9H}f`rXICcX z&&Lz9MaPXrtBpy|IMp0HhZGDPeoMOGB5NnM_@@H*KQ{I!c@+G7?-2pc9mq{SRMp#) z`WrDJUmPtMOzkYJY$U{KZZ*2LC&D343LrB3H;{bZcq3>scGkF3$M&SwS{yx;rRf`P zqXTa$;MaIV{uF-Pn3PjS@n}8VUVs1ca6Yj-dZLoQZDMab@py9N5oe#53qxrp!7~(p z#&nZM@OEs6f$$YZoi{I#wA!6uGh@T)Y4;{t-?8C>YfYvF|5UymKVTRjd0KE0^RDXy znnlgjFzTXi6v@l!bx{OKjp9)3lomtK7A$sJJC17J7lM)*MJLqPCZ$rqy-6-ROuA*sJ4M8NTnI2yw%MZ$M=Rn^zK zb=32(`&*@wRCV0kka3W7LlzppSl!GnX!x(+KX4Q*q@9)gaQa9tdA;!f^a9`MCC5At z`amdn>@b9Z5k`SDkAW>lsgKBb18DvQ&g*{60_nXJg0vt=572dy)du90XK7<=Gfb^p(c4I$a}Tw~xyN zPB-7%Jax2}%5;J>66E;^z|7!%tvUz4)c`vsBEXT}i;x&ZB_`@&=}!$=7z zm-TOxNEF9)0HgERy=x+)?hiO5rONHII{}`M&bpCX)F#lfv-DM4@;+-N7M@ zlROAq+AGHau7RTTp;NXyN)4Y#50ms6{%$$%3=eeLjm<9ywsSwwSW#e-5b`Be5J?a} zV1+^8E=ElabI(wlByU#Nf&CCnFDE3Bd@H3*(gEKqv-VCnb%X2_4qBuOMR5T}xeGA} zT>&--z1k9`_;wO%=xuePpa_&F{3!(ihav9kZh#IX8KWTY3(P0;tpo@tE|3+4xSNI4 zNQpLsdnkh-gWeXRsG@hxVk_??KU%D|ed7PfN!QkuSfar-QP;1Sk4oWoIzH^sh{Qc} z3j-pBO{E}0*q^saab*#!$Vq7~qKL`CV8N_@Hx1Gs4;}|4M2!uL{uW}N`Ul?dN#)O{ zN9uoK9w2!@K96|mzsM2cHEWLA95HzA3i3b@77SxotLH(*r2C+XZh-fFHOHGMI48Wp zC57P{SRLoi^KFCQSLijwPul?9KKB5_TOsOF^u2&U)Hf@r#r8Zw z$-Vl|TR0F@;KL-rS5?ciWzPB^A|)tILqwVBA{~V~m2^$`%e4pFxp871h`kWl@rwN%JLHFGJswx&r<%y{JowqKH(`OYPiJL7ioKgWexw=mkSD+OPzd&Rnrz}>NrRl=PlyumL= zAy>J~`D8_lmxI1$poE}Q)7ki2z)x82x zfRv?NzliypVgZ{^rcnDtN$R}owkGj@TMPbc+n-`dCdNE?<#-eGI^KI^zm*ajY$_O< zu_Y2gjoWhr6Lv|!Pix`;kE@??_{=2fd1yBo`9mM#i8Cs@URKdwy^(s&mrSowJGnXIt zlkV+G`UUZ)OC@O)8u?SsTY@~2UpMwsoAfQI(gC5e5HM`w0=BE_N26<8>0Wk+4g%%& zrc`y$SwsYoGhUma}VXyPSy|+Niw8G9DH>LIj16D>#qQ{4_p}ud|1Ob zsRxW@jeuiD3?m|ML9Z{O##v;l#ondWXb^myV^(XxD9$MP5K7AI-(6U@9*W?lby+f| zbfRVrN6#SJCD_#_kK5`Ht34DCA_ zU~%+GAPc%GDO*Giy80|wJ7d^Fd=9fwFA0XYo92zr#+07VBu7)Z#&o>ZMakilwmQ zLB1fi?5d7Z?DGMqjuQKg!+QXq=2s&jEON<}AOmB>8ITk;BoX>07r!BrjJ5`Qv^WMW z^ua@JugYubEv954f>Kq;re0m~gD}S8z+lyh&M-LEW;Th;g={s;G#9DmlG`bKOKp7o zQ+Iu^0_4t7=SeU)jt}egHfsCY3xO0A2ObjfpTS{Ww^}+-QHvL7N{<~v_G_p4r~>$+ z0H!C%!BifD(W47N28~erXhM}oO3%8j-d)~U7D)YMk;C>zF%p>8%90W9S|)WWi3!*^ z2?~CQ^3FsIL9Eo_3v+z%hT9j!D8@!LMOSojK=s@QrnDd|o1rYDN1Mi+ zKkn;+iw8sI3QwZ#U#;TCeZh$n<9(5lZA98aO}8B&QC5SuI)LDcZ$OP~7k1*f%3M~` z75Ib+{>I8K69J+5hx!-k@Ns4N;cK-@QE2#u_?bX%e!&eQ$^3kgPx^wWny786l4u?l zt0?Z%y+v)6ij0;YC!N^lrxWJHtxv&(aKFGdAt?JGR0}<*;U&%Yyl;}Z6J}ZM7=}|p zK)`aJD^C@+pmlK&uPT(NeL=sv&Hf+z|X_lMVtb zJx;sk%7)xUZ{zf4y#8tWhjL`qHDORpw7E`dz!=v&i0ytpNeZaVX-Nh*~mdE}hz?6uF@Yf+8tu|dXxl@>2Mgz4fA(7NJCL&mILRm7uD+@9PQ zIObI7_sP?W=WzlY9tK?)QPfWuC#sWfT5_-lYfE=3YlSk~IMNpMIs zsJooj;BB!`T4KPa968h0^b#H5c8|Z;v`^ujs}Xvazg}zdHjU}4$?zO%-018nNU>*1@d%xdNYF63@v1c@ zJR3n2#B>ls4Pw_&mJa40|lbLmG6yS)&c`p7gwnQ zrRu+aEv1dS>e%SJvDO8$$kAT(s)}q4Fa*=Y1Q&ZMU`s-r(2=N`q(#m0LN?a3oNzYy z5;}F2d-Le4gZlG(~G!m<>&|* z;u`49Er44W*>hX@dt$f>n++0`>JajgT;pXZK#Qm;97TWpF+ut>*vbgJn2dle;e677 z2y0{GtXB^8Ygt9q*54KG829Q)4I~hSr!N3SEa*`_rDJ^M37zOTpG(Aw(g10AN+^X2 zOD=-$jn=TMsFwdCuPztg5RqfFtHn9mKn0I@x7J#5G()mzKe!(WJK9PS8o@Pkn2cZr zLo&1?Cp%tZnY9dF%qQ4BRe&E03se+!fqGYg3K<=YVWh?Z2*iFIRUA5a;5MPkUd57* z8Acf73yBCptZ=8PU;2J~dKJfaA3PB<5Y0?gdv-6uwdAN+A-R6W#(Ww*W^ zIgyr`Ym#Kh4qaUTh||_(+H|>2{b5U`$_3XWB;AN%yn12rLD;U#{HIUZlHJK7ecY^! zO_Oi1E=lH%uHUEY%77Hi2cNUp(A$`25;n#4If z`lbm*^O#f?B0u~>>^Hq}ae2QPe=yN@R6;-0AxK6F2P}agM=XQLVZw%Tr?rAO_;ifW z;mCOUJ%wNA6-U33qX84U4Bte73XKEd{Du1NbJE1qS(O=u%A%w<4aHDm_cQ8FWA%Ib zddj0|eCGrb97L&zwb>8?RD)SM_8Ak1v1o+WSXz3XlD-xCj%=B@F{>rSPq9+tOmUV5 z-7l@K9Rv=Eos8K%FzNq98>EkyEPMv~DKx6_3%z;`?Nf!W@P-2>lg(^fI=>yVTZI6ZI-Y6BnNd*VJ zo(0DBQ2rg{0N`{XzR(N;f9A2CG6oa~A3%D;)E&o}P#+6amyRIJLN(XX3m^0jg1U?r zw;r0^jE$*R{A`{nheEl`a+zH{08O=a`apVt{8J9dp_^9H7GxQu&#YyCZP>_mCu86b zGn_=tB&#f}f6Y0_H=Eve4NGOAl$_oW@?8Z)n-?MuW1b+7fM5mLHAL1LpyIu_6ss-! zD%1}J)0Z_rSWj*pVUT8e;BUn`iX+tJ!siW4^1*W^cUy*Y7eR^6-ov5TSVnC-70-=DQ%Y(%9 zhHnS|dE8*J_V@&m*4s{8BNY~&FO@F0NIxOM{pEqM>QaV81hyLi$jvw?f?0mJpGCQ( z-Cz?w{{@30H43NJ;)Hsv+{rd3%y3WtB`XIOm+6Hs;hyX(7ZG5&+K#|0cQ|>NgDSKA z6^@%IPCTZ_oB&psg(h)sJqGZ6NOuE_gY3)tKJa=KsC$E^M3H5aWbj6=!N2x|j<4#+ zxsl`Nds}bG5jb9mH~dkWv#t%uz)gdEp@UIkpfxZxo@49;^>YYh?(?C*JPV`o+sbfE zq3QBXFhF$3MhP(PYyD$$o4+m|t?$%C;b=4@V7P`#D;*#M=9^!lQ2qX5ZijOrE13c+k^qiuT{S6IHd1w1D$# zI(>+l6u(i$6vmv0cp^tW86c4c2%+SZKpXl^tj`^jgzJnHQIR8s(g*%VfAudzzdBc?(ieNq9J!`m{mh(}2!k z-(roTyfR@pC%WBQdgFs5wC-K@=TocQSZ&`vizx~M>1X&B}uvlgf@@<_36C>yFLLomCuI(BB}59(C=zHYn^o`O7WauE>#3hwwD zSKW}|daHMw=x~-BwR3KNh+I?~v2BP}yzjVhhjAOTCLUDW6OxqAhr(1a_s$(f9mU<*5Vy{3R|N z*?PV|5)Vq9h0MOk0*Du23&t6tLwAY8`+-+`bhX)wAC}I|O6CT?>7@F=&=#dz=AVYmBozCcNJfzS zH1%w3=dhEA9sLyL+7aTrrG@{7TdWlosPc`6N#=#vC^UvfXb5TtcZGC6rUYEK*UGF{ z&Nw9|ph*hK5KNu~CP-R5#hFg?_kNw#(~z=lKy?9xJ@;ASwZTg;WI53nQoz`AzU4R9hiYVyXNkr%rVyv?n94sm$@8&`9S{Ywyb)PPjDzj z>s7Pj+Ix8Zd2RpQSdnP?$~=a1+n_OUW9khlcr9B|oPzrl)K1MjNu^bV@46u1uyF)= zNe$x-cloR0Ik{&8KfrN70^XBQ2fdU4odWC_#SPzCLjfOJ$k7>jQAHsDs9-^!&7x7= z@t$$6f*B-5SgAIZFPL7l&*FGu_0;?;umws z(Oe%N1AAd~kC)0rdyQDD#V)ZB_&fHDJt&}cN5}=|>56?AfqUJN(SC#j3Vu6c;0;u1&C zM1HL8)TNHgUA*v44)%@;v&^=oRpZL>2<>=)I$45-KBeEo%q4B&?W>*C*J%2KouX18 zp-DH}FV7HQSw9Gc4MI_vWM@T+VH5y zT)FK`qPxT?*MMI`hxYfgWADsh--u7u!M^#@nfcfNyps>BqbBt2gV7Pgi0C}x=`ckK zE{a3k0$8<1mO($>6AN&hT%-L=@yes3ph#T5isjs98}%AriLOdAHb{Dr28(wqDS@|M z*@N!onDSY)0rDPzfyx&Ge^x;&i)b@`0Gr;9Yv@3> z-85k}xlp;fO;2l*->&go?k?f`4QVGP?XgWO;f7*b)0k86ul_%h2d-j}P#5YLApl4O zrz8TIVzUu$A3xEUdxv@1_10Rc${RJMNhBik6;e>UU2K z@;Gc4jd^U+JsA96o+D?5l!Hu^M4zOP7XoO73_$M{$5JyW@uPwLDm3Rw2pl0rTfr@{ zuj**+*&#(Y|CB>K#>91ODPQsUn%^=ucw6 zWesvB&3KtCCtZ{*yB6~4@VAF7V(*2Y8}}-qQTAAly%4Yo(Ahd6`+6yFG9aH0X7p3qu> zMC1Z|H2w)S8Vc;h>^TaZHSTKI?XUASo}6ob;HfIgcYsCc`y7qH3s_!P?RkhSeuW^y z?+&k>Z>kTJM&f9@dOLFgKe(`5;+mBQNMnT-qSp|33QUlr!O^Vv$an23DG3_4;$320 z`xW7;P0k^l!dzLQTN{Q9ecp%&er|~mG0;oo{1xVedfac|=AcSQ{gpWj!&=ZCSq2aV z!y0$RM}9I$Rr_eGAL~1&7?Fw_7c0rE*#m_joaWOkQ3)HPJ(rinT%poR|Dd6ro7_i7 z$t*#=PE7n@@>(h>EWfEml1417G+IurLXO_se&3YVyZ~^CcA6@*Yb5*oVDR`PdELS@`5VxxrSC=FK2Gh40h&XHPK;{7*{9=C# z{SME7Z?oKk-`C=B)jJ$CjXtM|l+_~J7j7qDtjp3(osuS0pjzqQD7uRrC&;lC0!T8# z^zG-iWcX}(J2=zYn;qEuEhZgX)6W<(ELFbyeaB0pXEw~$F~|S29!in!q`tBDQfmK2 zD}jhSfHG#<%fpul{)kvB&;d%Z3|a*R0|fZICx9Pmc;1Oqh6ko1DFpDwpQmMTs4d4c zg{U@c^%cy~Zp?O|-N=WdJBRi@6ua%3pOitq{_uRFeib^<%GL6V##kr?d8L~`%~{LT zatM~;E21H|W&~anZe>M-gP#xxVA>As_@w%d{<5{5B_g@Sz9*ohkeLkuxZ^uhwgeLq zG>$5BasDJGXy!cl3TQNp19>wzC0baecmsR9i}!YGOSHb@Ujg-(SkDyN+X&HOQ-lVO zZJL2xP4ziKn>!W4#5!0hNW3GW2$7MIzHZ)_Ga1fcZnZ7(z7>`Sh&KrobBB-k>U!kQ zl|>CuE-gSqzvS-CAnT$VQuI;<@18xP3drO^&uCKpg_&_I(FdMGxQb_p>MEK$$U7nL zU>EqG)ni~`c0m|U+q{jH2!cU9AJB;Ukb5%#ni-gSF0U~&tOoA7rHb0lv<^x%5OROA zUV^igItfAJ$j%NXZO@btNsGh@qtX6iF*|(lPA>JU>*ZOJfIot*KmRr8kw;glH4bAB zMr8(xxcAq3{R%)HxZ)Q9c0m9c61axH@=j>5mU?f$KyIK;<6VN7CJGhK%}5OSUgBoO zBi>(?AI>fOfjuY7o|es+9!Lp2l?LX>(I&XLuK~7C+Q$V#m`Du^#9U_8UklZLW1(Y& zDx(tDA9c)~9AqJYym=Os;gZEcX|aROaOOPU*|Wb_I@fII8?)-}w1qhN{bQdYwu9IW zxZ3~X+e({;Q7H;mL!BMRBF@CiN3ab2mk!15&5)+!`xi5#Qd}=_+|CVN@nZY&h{0eO zEXa6=%ath?Wiww&4+}fGc}{N+5CnGV1C};k8%H!KtVcku1<4>+vVO`@>H$eNhl15I z^EWrdl@Y~kMjvZtS+e7n)F-c-Y4Np}YQS}d*!TbI7EI>*3AuT9Cim}*oWGeie{FvKUv#|JHzUb`0}FE1yrBnKHbjE;RE44gX@pN+Z}Y^~n%K6EH3 zrxsU+OjTYmtnkP)S1GzYO^&KS zBl?U0!{Q(0@sncVJ_}|B$4b@K1utZA85tQm>x(fi6-Oth@?+)Szvt!_l*6?Q0F^;32$9JE{EX~O(r+04f4=0;7I z3pw7Dwx35yjpN>_Y{t@#pCMBhARoBDotzpP%hdZrV6ZG6LzjaTFj6u4e2D`T{9LWQnvVa}YKcpXPmfQu+sQ@^e!N(2uo&&gri{Q@FV-|m z2jVB3=6YmL(lcgzQ}d0jGk|k&ezIAwPzk2*gg_wVx1QQXKWn~_<#j&Pa#P*BfQ-)W zobXQkyj|IQYj$9npU&hc_C&~sj)sAO;qiL?XR;hqj&P$r)$?I@ zMJf1+(psn9sy9M{N#Uc-rR?}TKam{UWYlmuAbZzayY;5q9g*PkO=#!=*M)%RSJvm@ zMsPHEV0O31%j?5h^H1Gwub11_n(e({m!G%U{J(4|8EE$2w}uffSGx3#`_{7!0B~V& zS8Bv7!$F{Y{ikfZSnRl1k8gyKQCWYU>`g8&-jEP;G(^-5V2T+@8XFy8$`NdK+I_(Ec7>w7`GLNlmeaq*)Wu<85J1C)qZ%*Yy)RvD zqV5O?Xb2`^(}2F+nmt}@LY$|Q_VK|kj=nt?q3f%8OThWt3Z!DJ#Lv_oOAU=v>Diu- zBOB`?rg>J4Wk1c1Vf5By?|EwnVmS+;^cy8(z{-KaMR{_FtSsTyPGjEkxgSitE!z@J z)aV-)gY^G~W~`7;&{u2T)kaoL8sp;tXi+J;KHl{Ek_C|q5>RmWhf&gbrPbV0>TS^s zbfvG*zNrdt4%bwJ*GvxrA9$9?7v!+X6})4_d~sdK zT`^VDVUuIWGgH!pwW5oi>__UyAPy=FIn*y4V$_E(+%m3wS7*F>gTL*no#hvEM1Zzh zt+8pXi6%rCz-EVDMB$*kV1NyhNLG4=)-d8~FIs+54)C0(jKTq7o7PM6JT&g*E1-?m zuW8f^wg{cnbji76jM6{KO;R&~L;WrPs*T6^e9rAaYy8yo5E@Q=)qn2LRF7dwsQIO1 z^P|h$SD$Ux3v03l%1RTA)6obNGYU+up$9^zYzsjV1)JU)#GHB;-!=Wa9 z9k_;(#CiVXn;1gaISR`0(S^xRV*`27_U|ALMWSnaCB^>JHOPB=Nc~M$61-lA9uNjt zwC3X^i1AfYCw#u35GJ}d6bV;|l$6#QiHxQe6Wdw(f{`26lW=8bqb7P*8p{L#UVPSm zoID;lCM%fuVEmWx6-4(UR=9X2_pTA2uHYJEC(eug-VIGvx->o;+h}Jmo5qNT0vs%w z@dnpa^}1hbW=nh_`gbK7ySb=i6O6w^Oh}nmPyJ=6)F_UOb-3Jl$j$q2pGW&ix!Lb3 ztn+l$?R~cUe2MxY;BYB95e=Pj#+myQ0mLueke0CE?hUrW?sC{ivV=0St1SjQ5zD!; z`gCX9nm8vGmN39kjC5=B3TwUKOciwZjv|q&#z7Lu_`~1^jbbV%N>2j2wPueADJ6V6 z#B?~nzN_J!orMhQifNP$!eW__Ow|O0^)M1A4obfr6O6IX$>Pfv)x($dlhA(eSz6ne z9qJoE!Z0JD(NkMshGmd|TT9fk!x{>Wkddm!%HsF3%BNl?5O#5+FO# z__{dVmoL^dI6Z!?Sz+i%6C{Z*p-dOX^WtkYN1U=mj4u^c z@nq)Y78>dqT*%B>Ox2IhPB-Od9yF?Pb5JYou>$*gn!fOOjTjmdmf7n1 z@OvZJ%$Ja_&_R2ub1X;IjxS#%NI`p5ltudcTv&McrJ0!u6KnI`z4c=0(soKIk|zgw zuR+9C`ABF5j+UYHTdE;e^}M3daO5x}C&f7t&>7C}8hhJ2a}=yOa(kpQI$Cw`$|q%O z!5V9YUn)a8IjqmZ2sgrL~x$1JlruY0EYfU1c zHWQ7tDLys$?H)bBQ{=mRPLxERh(xrkuy!Ukw}09|i~?%$w5H$C)b~f;U%rRZAxR&% zh*$yU#+T2DS-}$TYsq_rHDj(;bI3y!AE3f|x>Rm(H9t8cWWwqZJESK?6Ou;)%vY*- z^-@L}lKdPmW=UAA5ngR!fN6 z_BZR%)H{@^HtJ&s5B-LIBqx5|b^=Jg^;eNymLNbxMhPlBGe zhf|6Sm8r1jtc_-*8)oFO>qyA@Zh}=*QEWX!Qh#pvB+M(XYcYH+p70cVp6~AVyw`VI zgP4xN5|NRDnTezPIB!ss2>sY9uBYoPu^gP3IKY_5djlLgVX7+==h;tm1^U>l<&$wv z+6T;djxKH8|M=WEZcd`KM(t$)t#2&&cw>>pT=%ta#`DJKQc$~E^z#Ay3g$_^W5|ZU zEa#>}iG5G=Sz8M+wLl&=e+=~)PsVuQ^KevC!rAFp^eNk%s4*n{ zWraVb41%_&Qlfk}aGL5Fo*QquI!)lp{OpNeXFx+mo70RD5|8_Mxm?26C{FY#MiO3! zIJM-LW{Ony3*^mY{+v7PmhaRm4)f*ZGjA`eSlokQJM;+LH(JEb1W$bpcJb5zC0h7eBe9H>&X9PG9ux(t{kyONUN zt#KJXWTQgF#b0dpW0scY#r`=%B4x1EgS=Nf8J11R?=Yrzx?h)5L;|;`(IMGJNU=Ap zGB;e4D7w5v@}0E#dd=6x zQ(|$b#~C_}my;6Ky5tp4Tm*PJ)FoVkqhNzTJmghLJzXqbiO~Sfl@A$N!LEW&4Nl@c#;-{kQI<|F-~bGD$G*uLh(S;js5l zHcnfLL6%2Q<=VQKVNyf#u}EHLnRFtVjE&^s{Xd5n%Su+fN!`iuM-R(!R-PRhw5P8V zwNDQAf-1#msEgn-lZ-0gpdPqc&;=E{nMyDmPff+jAd+P$Ceo9LAtp*m7~X0**{0{L z+nQuI+185qiVf|_Q;W#zp}9FnX-zCS0hvZ2u^C2a{uxH(?9GzL+}w)@cueM~r8sb_ zj@BEsoGSYs{q`>NjWY49OuslDtf?1Qw20@d=YCI?wwFeX@)p+V$zl!Cl;d= zn|RbP4ik*RqP80&hcK#B3VmqpBDXhKU{rkQIhc#P?y@f%8TYz-E3=$ucuMTB-1wHJ zwwXGzB+K9CF}cBCil~N4Z`EjXm6mN8Cf^P;2LKKbo(#g#w)v)cOFh z^3df};gfmEJ{$W3%&8n7`|mUI?}_%;jAUi~PlfisJ8Aw~$>2-n_iwG<|J8*2?_E6q zZ)fC1rjwSkI_|Kjya^=GRcO(8%4V}zWtmNESTv!7)ns#5b(~Kro5|(n zs=F|>IQ}P%$$TLv>#J!E_hrGcTE3{jFt(3f6=P%u4(8@k_GaFGnY6;mya3&fR=rI~ zMJ`)x5|sN1@4Nl(eRoo2RK%*w{=y3l2P(=HCHY3T%h~I}@>iw7Y7ME&^>X2+|JCVg zxlO&Fi>)kyL8Y%(Cs=4mq@u;3AhBAj)7ifW7{Bcamz~~mYWMm<(}j@7>v8Tu^NHZ= z`F67Xt2WT#{q{OI4|uwIcX-%6F`VV*sMfC4`<*cB@9tv0RABsM6s2`5J%>D#UeQg$7d@-qeOS*TGrv(Mq;^W$lib{oUnd z=whH?-?VzOq6xd(S38QXjUa*2mqaf+i(28Xq zY*yg;eveJpMslXOJLmE(w>u{hH2<1D=USQ_K&+1Wy&$)eUc{Vd&W*HyPOa8tUKYH- zw}n4N^od_%eBlx`Q~v-d@0ud#dW6rfFBB@!cZGzypi-)i1IxUSSn|&1c&kV$`VT3E zw6OSER18KjoOvm9**WLfOr3%nkZ7QvN1SRf#X#Fw%x{9chT7ZMBI)4<0svRBUmqJ9 z%-L>9jqC3a81=IvzXk~?bKDgw8Tz?76y=pW5Mfj_3Q(Azj0*Y#C?PPxPgl7}=s2)& zmH5z#s#@j+jT8zvMArSkdB4PMZxzxc#g!fnn&^MT*xC+>--(Lj_K;o_n0y`4NCQDJ++;q|twiz^foWc!deLps=vG?kILDj;g~aUr1m_nu7X%91X4RccPdEk|Yna z_?jF_^hqSEu~5-NOV11~3@Qs|U_}c^0p~VVrL2FEL4o!mN;I}#Lj#z~BM*54Rv;vi zAPxld9Fwq{3puo6gb=rWB~oc#C@*Upf-=F%Kt7|SVGO%vZ&)Kv*j&O%tWGp)W+0VE zN(vDvH5uE=7Akfq?CGw`51)oIwhrVuA;!6+Dj@}&@P?zX(BXR&K>Si6TqYMxIy1B) zm6v8}Iu`cf>~v*O>^HkFuFCH@MZs17;W5Oe<~oNKmtqE1^Ja&c_5$8)^p z^`&;P1AB7(bC?udT%3{$CQEH>aqcinbGSLhl#JH70YkU2{839-xXC;uO7UpI)lR36 zvB3J`2m-V@rk?4w{Eqt0#!_mW`rSHle;jvWcjUPudj*_e){)b)7}tdYtdn1Kl4b!y zihXUKpwu+8+$5wJlNpQ+rtaR^WrbmC*hh=W^~y0$zM?ofn9Bo(y!?gYhOj8qlmzoi zxbQmZ$=E+&wmMv28E+mR!iy0uROU}6tPNv(C71k%cO z?_j(^NrmYiu@j*7_6!X3^4Tj=IE-DZon<=K@vNm4?U-um@e2jlQc!~%Y&?U7cI{>* zyOM^8WxNE17OM-%tBV&tUQ@rR@wT{};VdXT0z}1Vvv_}rY;F69>7Zv`(B2-!?&4c& z3#1X(RRt!>=$j$xTbNTx;tqb}+)(*8+|bU+4wyI;gtB6)W2Qms8SBl9Xf6da zWTA2)Jj@EFl_UWMnQKhzYgw7%ma+VMwzaLatCCc!Ygy+?Ds7xaagtI)XhN=Y42gCq z9O3X*FwsLRx$TKokvMK|Dl~vy{PXbeL-??az+bm}{x@G#5r2c}`u8@>#(P zMoVhLtzyu<3oE3KzUeJSa@JVhwJ|P(M`OH^% zD1;RGk4R{Rr3!}Ak_ci`DnSj$`04UFJlIYsjn+Fqmd5c_wdbOKTEJaA8+DN-7HRPE z`gjOn^Sv z@z{8nJf*IxOgw)Gfc8WC1aN`vb%YQg%N*ks3K6`kpmn)t^$E!1D zztjtLmeYqu(;1Au{c(mU z&0yuRIw>5 zb%Q^NBT+GQvzy_%jKqdgn_C1chhhkN2=z>ak&5*KD zq{7~o$nTO$pyp!*g@lx$($_3wjlIY09C;^EVytTrPdKb$sirI52@~}>bit~5F(^NP z%^6uC6w-v;w||mGCNV#}IS#2Ynn@Sc5gEcMsiROCInPKZI}K?jy@-%iA(=aJ#sf5v zM9lH#W{&eSsOX#yl--jg2^{urMe#Ckta7meDW?t5cE!^(iN_M$N_yI`%o!U8C<*Km z#7N=cugfqBODXa)e#{4%l)q|(eho9&+)R%kT2^QJcY7eBNkU>7o*;UD$#~Kdh;<}!J~GBu#VSW4zxONxmE zCVZt)xtwO-{(4Z@RcNG=(SF(Qj@IF1Mh+C$LNLFF%FhvojAXnO@1K9ij%0lqgV7zW z!t47@L=Z@9HbHPoPBocphXzwIj_?(H`~6!q=I!Z}Wg@rCglTe+=J1YdLeydVf7>Ln zsMDB+0|wBEWmKDulK9jE*;oUG=Ar_ldCViDzGSMi8Fhc|ufLoo^*%)FQi*q%z!x3=4@T&0BzKJSz^o zFc@M%mrW?e#Z z(G{Q|-J#@L?1um37c;`d6Hrp}yY&#x#ugsNv1sW0xjRl24(NN80YQS1sI(ow^k*ub z*8WcD9+#TGjgU5)5G(Wt)+pBfevH^xi1iFiVJGgI?QE%1r&fNqrC>sq#{@Z36cBi` z2cO8(fdtcjkMrGX;F|cu%_u%zmiZz(ki7vZaM5z zKkoh!@8@_A>f*0ZO6Szm4=k$NTqJLq`zpEo`O#f;9__u55Kf&mK zpwE9NiPSvi{9TK)QK9r+)|eXRfdroTMK{_R7C`d|C`*T!uBg9Q%TKP+%$ zzid|-1g*X-ZN3~azl=2hW5HVy@MVtrKRDFSkSu$aB^$Sv<3*{%Wbg|=;DD=JPPg7?*_+e1v7qORrWFJYp-NM&rLrLU%Y|!yN zv7g}-CKfE4q|mw{-=4p^(bn(quIJgoK*~XqJu^^TXNM_yWr_Krqh_ej&?})jAb2{K zO&FT>bwRO4;&)VRaN9^sV(Tm8^zEm27^3Z(nLZKe)1B_mwf)uJG74J_TM$DxX&#lk zLiv{(@A0msYILhxCG@?)pQB&rJV0Ct74A#pJRLWW0J^%BXqyn5;O?`w#jrAO7EVm= zcv!Ww59DVlBc$J#oJ>*b3ow1IRG%A`4Uc0>MwHCA^|yN^J`NdV zM`&}-#U96y9GX3$@UAp*Geurq25-;8T#d=zm^*ib!1}e!-@(Oj2!Xezy`X5&l-~n5 z77-zp#h^1-ES2Ogkk4XH80ZvZ=OJev2?*>T*JmP;n?teM_{AB$HyjXAhuKM&r%=c} zTy5JuTC2vdv;zE2Xi$I7i2K!;T*I-Pehwwo%hihj4r6c4g-$*1N%e5oA?Kuw!6hqy z`!3)~6{0Y;a)t9c8T}_HtwxIGo>XpziBY~fi z((&EyE^;H>dYHY&W~iy}dAYil?%i4ugj>%oEGc*F+PM$fl@y;>3wWL!{_N+r`pl~0 zYHfbu>5K0SDMc^;2;an9>&{HspS(Y%HYK_xmTM(+WZH>cvGm}a?N^=I?1?V_oT(n zS{VmPVXj7KI?og}MW7FV;!zp7xVEinrO8KFb~Cx`R7LM$ z9MfkewY?y=5b`9-oqw~Bq5oK^F01|q?J?HEti1>bMxSIwpFW^scWLSD3(qI(@+XNp z7TkR65_R5yv%b_63I6QkK2tT*EJ5|WKziuLSq-|D^*Ch73x|AY>)buc7vG17RpP4I zdc!}F+TCz$o^|zkQkkX{;U?t3`K;o=;npSj#F#a{<5vf=bNwHJ-aqXSnHc|7f&1H2 z`LCe&<;yG~EG(q&U~EM6cbrlr(*9?V`;yA}H|s98f4C6;|AVjMSUqB(AHbTEZb2_Jcopa2SI5pXdygC*!&B>ACU z1rgDMjR;HVt4g-J&9skU^{tho=A{+WE6=4iAo+Jcus%mMU?0|8HMGmKUM&>V@qs50 zEF@qAHQ=5d6B97Nvk1t-dna#dYKizz{o^IQk5T&?ZMQsy!|zY;SP~9lG6*0T(M5J1 zFAB^9kOZarL2Twvu(A8ZZ_GhV%ow@Qc@-pk1JzcK#fLQQqbbQ0`?)ykQ`jA>SrP5> zn`z`b`4M2bS}Ek)ruiO_#+}L%X+Q^0RP*!C8PY(EXsNmrM-;hMq0FLa*q5QVAV5$F z1DqZ92;ncBW?4Y4MW*{A z)jyL&fyvdaQ_W&8D)BBZ)PEnEy>zc^5qK$m@Q%2>soYSUPiF~6WT|giomVh)VgNmo zX{6)VcO|L-HCRIk9PCucT@eA@f&(>dX50}3S?R7ztWJ<`83;y@X&Knr-@+DX!PjjD zOxBOx7D5Z`M-RL$ESwKO04AtciV=9z*Br|48VNm5uq+0n05MhQHxjM})GuK{`R{0; zgTkRPNO1x$GZZCQ)c$3;!t%WLq>eakP}=^lIgm3%tPmf-o&m@yAoKe0%Ro&&D>dAB zP=LPiZ4p=W3`oqLwH?V83_gVBKFl55YarS{-M)Azfe|RsSur&z+#3<07&S6rWMa!$ zk^+!Y(X<$Z0^HU}@mRZkP>A4M{S+*WA?&?i^@tqiTR-gw>wThW9=-IQP5a$uHzh{Q=mWL9L#NH|bO zP#*!veXI(;C321=K}f#_v<$x0MlB0=NZ?V(#-m9Dkzp#5eM@cdRhFFG z4v zDdH*V$pDCFNxn zH@(JQZLag#@h$O%+J@RAktES15jZirOj_mVBHChRnRS`m0;2_mg}%j##oHo%dE|8Q zv`f}>rY`H}{(JCgONp9K9xoV6#@U zl8ca>6oVRrZneTyE}uenWp+U~pj*>>tY?O3RWDpHy|*McEVo-fOFw_dkhCnee3m+2 zBmc{x$FRvR?1pbolcFXxQzA|xa#TiXd0|souWh6CnYSs;>HLv}v18J7phMvPg7JG*E zQ$-txjg_TzTh84Vp4@5LH5(Z1vhCB42#+Lh6mLwByuq%)od{3Mj?Pr=0iKJx~4Iw8r`KVpAWH^)60Tv=Qd^KtQo z@Hd#m08xKmyr>kOgd)4iz32+JVw~#(VQTs{{q^s_ATU`#omg3uk-{OvjXpSOp zw4aUNW5JRG>H=m(k_WUy4JE21&?WXj zk?V)m&}g&pQg$-*v*t4jw~d)EUaFwx3CzYyQ#q)cw5LSej?A3-}(&potX1xclep`DhrNh-`-V{%T22|wYfbrJv%RgJ|ce;v}Yyh zo_m>}G+tSEp4irZBzxy=uQPY(BPm9z=a+;(~@lyk63Gxqs@c^PYHae#}Ca zBI@u@xPAXH`!GD;%cF#mqs}Vhul!hiUNR}|yg$!b(wnXiF^vvt5oY*Ie5sb}2cIsT zrV(opI|Wn%rXyY=Hr#6O2d~E?lIQmVyTAQudPoheO9k{lfJxk@6+$`zh zeEt1sePndJKks6GRa6|dS>DC}==+iTW_UjwdvY%KESH!a$?xI;{eJ68VQq4_^%QXT z_CF-Gf2E;+<*&@_Ow9kxSO0e8{kNp{KMZsKGpYUCK=+?;|DR-tfB3}y(`EN>K>sDf z`VW4&lD@UAmGNIPk4oll#$VRFOf2kd|MJHD%Ax<^-K(f?WBS+of4%(Y{V((0f47?b zFF?Mq*PO&p0SKt)EjwQnc2zh@#2rmkorJjX3MDg#|I7D-YPHO}QQ-{8+oI5GG5S?i z>Y)(hRLK)8rQGGANM|uTt+dolRn7uMuYzFFAEz|8?T5?%VeT!X;>@3iz*Q@s+u@B{;Z75$jrd{x8qs<_dSW*{Y;mu>}=@dZV!Z7-a9y({Bg5C-Jd^R z6qi?$R288Wv9omqRv31q7q+uD1`Z(bKv5G%BL@q6Cp!liw%-Xy?Nn?njO>g}h=2l_ zU-u$z;o#^bVs79-1iU<>tihifz!K7b6f^!=7n%*Ii1_ml=5Nn`w*l?yFXZUgdH;v8 zvj3Te^q;Is=hL`tAQMv1g---uVJMV{$PfszN(sq_!x-tOH~Ng93JmFX@Z6rFGguQm zl6xCljm9f$jhxdYL7Xm%*$`v#xSdrA^34=zXjAOZi$x^7OscG?c3^rDpcT` zm0AhKdv|?#+c~o@H3=rrx16?k8pSuef3j2{?fT(7jk3W%-yCO#ce^=hz5NzdIk9|2 zHP5c6CHTZ{+tFE8@~wnVRKDqWXtcp)_vkk#<{A z9W+6xWC^dg!b+-uZ3HMO4f{S6D1)YmCP?8ffFXF$=9(Dq8)E8FV(_OZB$ffKbyqda ziy9Yhw-(9OIrWYo;b}UnbVrb3vmrSD+m?Uz<*#Xk<6rSCzee|WpZ{SW|33bI*n_-* z4bX=Ei@jJIm^l&w6V3iSP#9?bFk1Ai9PC8&04{bS4kjidE_N>9hd>Hw&K5>Owr0S| z1!y5cjz&N8IdcGO#{*%&KQ`zAY`~J&A_n$<7Qkj_;e=sSb~3S1{dt6}iGi_&tr-zB z2k?`m{^u^Nz-urHxtRS?J^QDHG0GXZ{cY>#O#zL^1OUVS$H(q(_V#yJ^Uui!OvKE@!p;hOYyU8*&8NBxruVN6nq~5-t4FWF(+z^Q?iyf1SvP?O1$8;t5QT$) zrk#_(%Rn(t_aTK}Nu$*##}`j~sM^R?nAzMIk+ccs9*U*}xkG#hu`8jlup(G+Uj!UeEU;>-`lGthpVRgR|IL z6>GM?>QumnKA|G-qga}}mgBlK4Nn9Xi>%)KVr{_4DVBN%347J?=!omltwH z-P%gmFYBM89k!P<9iK`v+d;S|PBm5}_Er&?8h?~`411iLjlF$|#FX%6%^Jn1jiQT? z8ta46Kq}O=5ZE8R3bq*61*m)I3b_i;tI;iIyEHxVX;lvKw(p(O#-PXikabm_qw<13 z^w%{ndh&X9?2v8!rhX-wc1}@WG%SriU9U1@Vjaxd=k<};S&)DV3SO8eTk#Nos4KTX zX6p&;z9T4}wEZnx(x&^$CkK}@C+3-K$pRra-M0#eGd@s8!kTZviKFVc>T(w_6B*#< z#ZT*H3Sc)or11MFIBf!EDP-FTj}Q*Y>)(gf;l?fT=OeQX#uD5mO^7fa6J;Vc9=Wm)=aabt?$zn`^bGa*S}&kc2)`;Z>^NU|$I%zW>d482U8u>;JIg;7;s zHH)@98E<)3wpQj<)U5XSxJv8Qe!ka{8J9gtKnEwiMn3Ab!sBj5DKIxImm!wXEkCZ* zILUFm6WEdDr4-t_)>xH6d*2&@!0kXT&t-)n4{^$+xc8Gi;^w_ zJ3{{QJZ?eKEJ*s4Dys%{Z+dO!&A{=eg$ugM%bphg_{=?c8CVg7uLOx0NU6|r#I3Lc z4{sTBnB!9*jlgm;-$@jcyFsx9S@!S>qZ=?7Amqd`rM(lPqKrp2MV5vp4>A-+&WUAW ziC6px(gF=0!U^RfOhFtNOCZhIJ8KifDojHh94lLm z5(gC?WbqcZTb2nK1?nn@Q<$z>GK^Rh6)uP>ATyiP92zG;bn|UtfCLn3(1#x89*&^A zpibmyq*v+t)Jya&rY)Hs%%Dl=EMx@aS79ttFX?-hE!3XDAOU245--Vnzf1nD_E?)r zzOf&YZb_F2TQ)sfK^)L_NV=5I{+BpgcR^~3i5M5kmy zP^52z?R}{#2x>ZFE@^uhq3=+9gqlL_Ikp&jGJ<%Z8c}`Zo1!jRdJuXlg0fJ2gqwox zS+*#8VxT!tY>BiLnxgILw{Uu5giGL)N9KddpjM#OP%4SE<(I^*Fr$+ShAVyjcC!|g$~yn5V&9H9?_;xKcPqJnCnaiPG1YN1Y` zUxJ*2SfH(-t)R@1Lm$*1q%1s}&cpzt@y$Ot2t3GC7}bEkTgIG> z73o;SwC(F9w=jJ-DnO-MU8I;|jPyP7KFU544RkFudXR%KwgE;?{5xSFzJUw_%>r#J z3__g66c{TpM81op{g#qAjR>_6^$Qe2Kt`<85K%s=^*Ck-==c?7XRsY|<&coT{9v?B1!QDa@&ZDYGf!L&hnr@6_MT4p9${ z4i%;(rb4G6r=F%frwDUgb6m3S zPM@+db1<_Hat^Z1ayEn~1r7))T%H?({qNKMy$%I1f7avkmn@Sc7Bn6kZe*2&fFH3~0cGJyXM(tknb2vE?0~0JsT< z@ELiAh)WU5CG~t#R4{949kNnjlubgJIXhaJwUg@<&~g0~)oH_H{F#?MZSAB+qg>K( zyDhVBTSL;pl&HppxQ2{0Jp8U9-=#>pg1Q?mynu>2k2+Of+Bf3xH7B0Sc|F&dA(NFJ z`-N&jv8<1dLZ;JXDmTjCyNDcBz&CH*T1x(!TULxBMygjQG)i2}x>-f^0R_-nS=j$PH!Wzzuc#>`JLZk}zrm^M^}YB}E5$2aj$o-|K=K z_1IT=+QloTPRsl}J^^0?PMR;qIfmwZDqC9UX04KZHW?8>W|2@Ww3D8oSt6=UjamV`6OFl54hh9 zu!gd{h+Bz$d%GamP3~hTe#8*G{II!H7t)*u(bv}p(^a=%)h+QLomVL<)}bxah}iHkQ_aYOQm5xXwt( zl1cKD>aBBzs;P_Cnd$m?h^^2p7`Ul$Z3iiArOR8k2wtr7Ijy-EToXKb?tWA(lBS7zSs)%10d%kGbIc9={ieA-p(B z`TXb+-ad9)tF|O`OY_9H@Pv5k{EToWcZ=bf*513`|LEJrZ|rNBRoz)VxpZ(UQ1_M{EUIp?%*z3TKB3h$cF9kdW&DO zs?Wk6>ch@$BwdMoA-A0|x5X4&F|S(i71JU%phlDxy^xrZkT;^Zl+j#Eu27iWaF9`v z(Wmp(BW9E-`)-zsFs~iT%~|xiU~2}@hbFh?k6{+CJl4Ao@=TfSc4Y27%H0Jv zx+eEUeq8qH{@Ad}-+OjH8oC#qyV8O?_<=LdYk_>8FsY8&QJD^vs}tX$ZD-8f(h10` z%uI1&Kk6S^^y++tH=U!j`b=_9Uq86ge)^B5q(Q;Q$Zi8piyTp4>1QH4;+*eS%)=bh26CtLBrN@h+F2litLFC3kzZg*Ijp~MQ1tDY}m>a$E zW1J>c_ttu=C#u)Di#Vq}!l)A%=!m8wAG-X}_ir_ohJ?w!H zWJ4bf4MVz>9)bouaFgnB1rtauTUcfV10TUp0lB75r4+-ImJmgj(Hw{)Vb*!8Sn1E} zO*CTI+UNF|`X=*sMY+zo>pAAy-Fxk2Z#^GF_8`WPYK-ykv8zC^6()_Da3vyOwl+}v z$W$Yl>K+n=oAspPPpFoevQf=;j$JyJgUX|%4cmJH+CNvs_lVc^V_4u}z>-2xJ;tp( zx2jw0W_;2>SeZ~_j|A`IM6=?<=%432)vHmefwZBm7Et4UZlLQ&6}$)i(#c4qD#cFi zezEz%%>ZOxHF-s9U3nt80cDSs^Eplq6{!q7us2e)vP?KwYFb&b+*~K2chbgs1YRNK zJ5uw-_rQPwjg6oIqSOVBuV1R0=NARAczCm%vZNbQ)jc_obW zdZEFd<%_6_!O~C9E@G5XYLej~LiCYFzmn~5GQ`HZW-n(;CKp+vlqGM!Q!ndfyc-6= z_8gi$#*8F2tf;)`anbOKey8T?kmTf5BzjXDvnaQZ=Joc9cHPTau|KtR@4@oHt>!5I zc)!GQuv$oWiJvZ$PQhgekCR^=yS=R0Y{hz%F8w{Dt<={QQXW}^3ws4lK$DkS-wyV< z9b9Efb z&oePJVRnGC|0nCY2Ujlpnle=>^( zUn+`GG2HFo?x$LW_Kd1tjMZU0RdmScsle-o-Vw$@7-`C{-gq7x09(SLsJS68BE<`L zy06u(jspK;PtcMr--(hD!vT`v2=crS3vQ5E1$TQJ_JN6TqM0*syd4BDs03kard%{H z^l+G9b4z6b2F2~9TD2Oz0a9X=4 zHDz0+eVmO@qDIzmgyt%d@M64hjTOm?@9D(XY4b`s4!dB?HSBn9xpeZG4cGLKdcBLC zZ%QI+H@{N!haor1L+u%Zi9)K3 z8`9mc2Xw7D3e70UIW~1fz8Sp-eWB!d9m7y9KzVUmtoa+yM!^V=4%e|eU{3s8W z)3A4*N_9%hVRD3e?{@)fc$h`=8@VOU7Is@V<)+X5smzWA7Gp{p_qj(E%)0mcOIk*S zS4Cq9!A6h+5s^(?qvbTrx^a2Nau!nVU&~YC=#ml=jiqr6GWeBg(p2cfzp&q^rxZGP zmCU8gwza4V;CTu;>WIrJc$@TVxRx_;8BUDVXgact?~iGhu~DKDipKb4*Lpj)EIf}B zAAO3b^jJhnIyPN4J1AIvx7uR)>{3SCYdm7#&9!DNKiREU_H}t^Fm(|qXih_~wd$+# z_Ik~*un^~>!*)$=W)Ywx_dFHXBBQ7O`ki;ul;N`sz+Ag>?6hIGH>HAQknfS4u7Kh! zz9zK>XADQ6Lz4zMKzPjiRB%`qIeeQWjq=)eR_uc!5iO;zBQIHjWqILA-pI(Pm{;6b zab!{)N=2Aa@Ibb!8;{2U!}?Mxhu!r#Y-o9ZBrVT{-puo%#fhDkj>CP+alu|mMO1;= z0=!&R`X^q;VFsZ#0!ru zCW9S2YiY?CBN0Vd!(Fq>NNU1Es4Qda5zx+NOTx~*UGq+K0Fi_uxg$(;IE{pY1Zm%Q z>m%2-sP}tSLy87Lcd;4h*};!_BQ+XGZ|G;u2h?`ywa+x{Crh|=y7yQ(f*^5m*rUpI z9L;{DlddXG^X6IQDQdu9}C(l(xD}?#oT;tSR}PXJnRkrGJOLM5MxL zFwd1anH%`xUXK1l;oH_OUF63Ce1#ou)qBjJfFngCx@uyi&kGbyu~%%Ve9k3cb$cgl&cQ!sq7i_omn^ zS~Rq<7QO0mwBrSZH7K)K9Qb`g%#k=BqA#5M+kKl!3-_(ler-GmGamy#T>rUU!;_miEMPkUVJnOqJk{pEE|zQf;} z_sFRy=IJ|flwtFta*PTb&5Fj8Gb|hn2c(w!thuy|tWGBAN=9#;%@Wx+b<-nx7zt_l z19b$;_~I<#uUkdJHKto1bnYQbd3_ow6R@Kmz*&~R4{BHJ8)c3y%+XmnMAnZlg|L-( z8&sw9-kQQz(ee6ORql4Fm#7!_{SYGk&@jGz+-u7|O1Ufjx$FbICUrmbot4pN)H9XJ zr1~1_aEr|J7evbnaPow&9e(@;)lRmzEwcrX+6k2w_})8Ko#PhK+9$WW8ldzf?GFQ2 zctC&P#ogMHYJv%PIgMs;;KT83WVm}6{@J<7Vr zZA*5KMeiak&YzPejx{jUT4*7a^TSP~TS_#v=Ew8L&6^FK+O0mlT>7-P`+PV!ofvJE zA))Kn;mPyxmJ6xUmv{AUK=XaL*0MB$Lj`NeIdSAYk1x!TfZ$FlQRTd|*T= zi)ei|S>sLQW^08UE18B)WQsO-uy%s$n6aKt%)6?Arl*UujB;b$(0yOP_%R{Oxv!b! z41dFlyIPITxJSTo@HE|{-GeKwcI3+#`hIyn-Sw`{v%{K+3T@@Nivr&EexBD#-`9%K z(g~W6Qq^PX+;jZ`E4}sgsI7OhvOjc*m=Wws@h(JWFunNF2FejxGU{Tt#3UKAZB&1pu*=&Vvdon$1WaE*>Gu8gLBb2v!)dS-I%c%3?On!B+b4k8!D z5OjAt7Arp4^Ng-gC-2HSQp877A+%w6VQ2WoO>N-tLtkXUefY~NA2X6l?ZIIi-|-}R zx(0=B&s44GKwD%ID}BXem7eQe_Y zPd?;-oIuini<1M$JaGKv4*xT4!UYT<{u^z= z3?xzhMVr8IFasHjKWGy!AT9HoHvy_3|3#ayF$0N~pSwsBasDJ@eiJCbu;srID8No) zgZXubzZeuEAP@Z0LjJ~}{0Ge>`=6T0-wX;H8{q!~fzq#TW34rh?K64PxN}eX8jZiQ zxTsfy&l7ER&>Ox}_aPNY^U=hzG2do6q)?fM=8$`e^}U5A`8T6#LMIv`n`JWn<>a2M zZ5)gDh5;2|CB6+(RLcT|7Tbe9XsjS|cj=xs9A{Xi6#3-dj_Z!+TnGFY*Bu9Z7iSNY zowdRgEs`{)>71=z(Yu5;IOC9%4C#o}-nZPElRF3U88&xSs3oXH6TH_=Gm8)5V}V8Kc>Psl3TS*ijmNf+6xqCN_ z9GRGTsgt>_4tmClS`rTMEAn#BaQ&3Fx%0zr3pY)pTlJTPp^ya&-xt&_HV6ut3ZWLKPEB#QrdRIYOL=!usIEr>GO||~pxx0l$#)-!T+FJN5s*uu?#k;x1 zs>#Pbaj@DtoqWNuaW$qBKaI3L$M!FyKBxZlI966(3g3g0n|!=&#v37Ic9Es50hWke zO8gS&73>-&3K;^WlDRR6lDTA{5=I!FxHFMYCn`k9Tqrxf@1$$BsLqZ+`?XOwZ-(M; zeMI6@34@eI!4xgeNZLb{aGA8Y3cU5?O1`rNxnNg%f%jsfhcNnp_uhJ9xp?vQPB7T| zIe}Ctn=ZY;GoQL6g|s8~+52K1@xeX$HD|G$UI4VODwH|QyD$5ngcDz_;C@uaBUm{OcHW^5tQIC922Uh948+Vf#6#9qckwY~DO z=n-5___}!C@vL`Q%}LYvkeB(^|I+icG7mj-_EX50p=P9ZboV0)GEaC^l}0AZb_gVG z7HcFFoBHVI`@@vjPBXwIn6n2!|>KP`m@Gn)|Ycw%|y(S z$N)%pv~QfdprW0uc{zl_?#Lu`Y!-0(!qq!CwzRfUxG!4`3;B4r&z?lEFg;%VDz-%fc@5lDgpAW}l-h|6M& zh&?txf(qG#HR9Y3UGiC9DnXzbQz2jnp9bLtr3ZLnlB{?@kC=p2&jskf#9{2UBp2Eu z9OPcwUH#y&rd*>jO2HVyx+9E~3;P7sBX8Jv z4u>GBXfU6@LLOLM_`cVBx%+DCEYN#kb7^Yd45V}4TRCQ8Gb|(>%-f@pb!o6S`6^jI ziB^qkf-H#<`O!$)bDH1Obv?P8~-=I5};m%7UE1eby$ zf;5=7MF>gqye9m`8(bO5VN2!H4u$Fl5-dD36LZ@meSP1wt#6igZ{HcPqv&D5Vm3!f zucj$pEK$qZaad5TkWk9*ByxioK%sO%Z<#rYG^Af9>vJ8y8^YUFgsM_w6l4%$5YY|R z4sL_A(2}pls}l8Ut}a7v#i^lP93PwI_&upVvzOA;Gc>sJdB z#Ip!l-rKAg6o~UxPN;>-Po2Dk49Ah#n#$qA7S~XBzPw;Z;()WP|0x>iOZ}QiBP=y zLsKvSr3l9!&u_mk2q6?<)2upTDs?LL%Vm2oi4M=>mN$PhAuM*o7I*J1lwOyS;CqCS z*0X2Dnju8E01`hiW#cNFS26p37{g*DS3=GyWqOLyaQ*=wB2EcJHQ1<>FeExchQ-NR z8-L-RvuI4;&xBWIMLl2VAKeUJ-AbGs_!UF>RQ!CPYq}f(#im%tg2->g;7{=q6Q6`h z72bU`-rUfQg-E8i^DI$CjjpO>SbGHxW^HI{Eou#pN&u&!o!sWl|DqnQGM{R{veuD>HKXq51)KaalxcO zsv`;m!HrR4PhGjY9gfPFPJ-m1Nb+YA+{kxqIO;mtsz>^qyy}d3^TF`nZb%PUepV1MSz&;mWEvmSwuly z<17J;O0;Z35>3uKlM-I%d=x`r7lZsxUt{7louQk%1B@>_gP0JIn9(sYS?ZD$nDSlB zpl40WC?Q>0knRsr6egPlh<8|^6JS>0_Cs1e6!V(^u(h!~f(lq8hL0a&JkiD5^!ru} z`e5f_e?I$f529Z+dM1=qqp=9+?-wBPc(7nDs|*kQU3Pcf4SU+xnwMZx*>#==4$KTf z(_L$CE8LS3%0DT2Sa}S9PyzCImWmWcN?e)o6~@=HG868zgtwQ-mypjt5d4r0>D_6^ zO!nkShChSipyD)P4aTC0>3Ki?DRWW{5qvNCb!DhB_eU%fSJaP012j?mOS5~!0H67u zmHT!2xew9}h~3Y4-(%CM9W=N=9XD}JVo?0Kn3BOZxGppP%R|Zqf!pT|EU7wqNyP8N z@S>(Q-dbo^+f+BBA>RTjl)0$-acxD9Dp9ww(KKML&s)KRm%rYQxa*3X$@decL?ap( z3HuLkWs{;c@<8@7AcGsHUCCe_=YU14nL)-Sj>rBpGV-zmC zGHSWvU-m- z-dJ?AZGJ~e+9-Lw7DM=_x|gr zaXr$K$B>XuD(;6z7rVw@3@vYUm7e9Et%e3VLEf#p3c#d$bv2u0zqse`=|MxhGXvYV zs;<^qOVba7Ze9*LUjO^=T*~E8fLn0ax7|WUS5Sr} zhqhEx%+Eo_ZmWv{qk{YaN}z%rEMF4adXJ|2p$SWGQ}Oo&S<``7YNZ%Wg<|3P5Tjq--LfeAhR5&`+mli}W=XSiYk#guh99STzi8pyYT>{8ssYLL zKnxv{$KB)bNmD>{_ddvYWNKo{b@%)`Q*Pz z9D!aw5E=LbRKCG%uBZx^3wmb=rGJIkvgoo_gGO3b}MRUSFWXu}%^fCqtXH z?qujo_~~7F>Rtrutn$*V${YDH`R-^{HLDZ((y@u%Lfm$E(QyVtrv^>!6q zwv5M3wd&#em8`kddy%D*dY(e9NvA%{4DFSKZp=fi<7^tK%lj+t(0sDYq%E?J5jBY; zk3}9|W{usp!){NGrkt}0$WDQbwHR;$nOP{FRfJoD8u!@ToK5fD6aPUMO3xTiCIGl$k%+~5}9UYv$GjLT2Pgrh67XaiJ`{29(3h| z?D{I;?=^Mw#gD+;fEA~Wl7u)%Ln|s|rt9;Pq_!2n0fd*j3VHCGTw=zoI}Pq48bV)v z69j=cLOah)0XQEb1&-OwLwbI^)o0dSWHB48@4^lFRc&NadVJCOI)ia_D@GoYO4#YG z&G~#1GC02e*_l0GNzp2KU>0NEHQmMbcr&VUZeKwR`&36Q!63Gg1?LSa-q#yZ^Bywu z153_2VB(SB}oc)bI6w zd!l%)nA%91dprHV*XUm}(a+h5nThLPaV;!=#}xlkr2oSjt)V6-^iJbnp$vaa+kegX zFdTn~zZw5po;m(hdjGfO83=^_wLJfaD2Bfy!oSY-Kd0G0;q-r+Sao72rTdtW1}@wq zxGF;nEEXb!p@v3;5z7p3K$eX)LD``#JPucQhAU~^?uj~6ysoRb8yG8Up-b-$okO9; zPh|W0s}xD$I5h?>K?aVU3Q%Sp3Dw2+ZM9G)DscHEhu@SUexakbt@dR1>1xIEjD*N@ zMm_C_)(LmAg4*EBlj%xP(znldIN)!)Wf4{>e_D9AUTC9G*-4nCC72yPq^Ku8v%ZPq z5mn=g3K(vVEBb7BIM(^zkr@t{-KRKVY+IX`h9a1V3_0Q>WDgw!0bqUhv*_2NkMP9d z*8}moohptiUYRT09#NmzsX6Fm_O~i}S5g8I-IsC+KVy4&{RgA?jjjXO{uQP0YxI8i z?_W0Y*ZBT@J^$aP@IM0-h=2hKK?_J4{{_zkuH6`=t0 zKOz+V4zT~fMJNz){7-!SSHti3{d@WTANV>mGceV`Kd;~8sqS8=Dk~vbDP%ep&;>KX z{e{scHSi`0DyfxdG{Q;dpeilO#uf!8sIj>uSjLKI-SFSV#1vB?=H8=4Y%;)5HIV?z zhMdCC$b4Hf%Oubh?7VyNe(ex|Yu|5~1hAM*q)1sTw}gMDp-Mj<7S$OYNSceiI(CC= z`C{#m5jAR)MfpWkW#J>i83s9Yi@%~SrkJnY(5q=!t;pF%P^fZrIC7 zRAc1i`LP<9SVPQA6|xES+~bqDa}Z6-kw!Z?ad)6GfFogP%ZfH9$v$7l&#H=TcwJHo zEI=`b7w-q>gFP{9FCH=rcqZ<>06bIlQe(@HT$aIg4%rKb>;UjSZxzEy7<1C~5@Y)$ zZc$?U#BXK82@GAf!$BI~%ZJ#R+>3|208T#}RKe+uR!f9b8Q&{~FdE-$hfEsZzYkdh zoW^aTV)G{&6v6QrFER8=0KBMr*|GU!x4f~}KX2(^uYcOI!CsHslEZEosTK?2FkYe) z`3#q4yhPP|0%)V?g}~NL$WesIf~y+3`~t@~T&)}83~)0sj}=NXsDNV}x@?29GIo;> zF*8x8?_~k-()TI@%Hy`Aurp%~3gBps-DE=~Ox#36LQT{edI8u3aRw!Dh$EMNa5BbC zdLd87>U6y%*cc<#f)FuqcSB4HA?eaSaL$0a5hleDOKgfECf$$^fR71V7}x_t@5p=2v1v?-V{^1a0NBzdRG)IxLlgn4 zbiHx_v|%PCh(Suaj=14Q;V?y;T@Rlv8TJ>axg2aCN9pW5_WHN`M2q2LIBD?tuArUq>~_IZ9xw@lg7uJZHdHZ6MZ|I<+@E8P4rVFsa~d=4 zODRg}n&r{QKD8`9eTB%D<6+*UbGWDSW~Iv1b(oyWujfjp5aLP&{ z)U*!qsdxp{5+xIgcwEvAe4{BAllFxxv*`#~+}*g#fL2BPqUal!7zy`sMFiH8gcD&c zW4n#)1;cxUn+4}J53{@n)r&poul)17?b{=6&sF{fZY!?B;c(O-iCNCk&WX+gp6*I* z3S8rlfj2xS91GM7QVUh>^=tM&VxCAXpq3|;qn8hA z#MBU&@b!2k*QeKiyg{;}J`q{~D-o_lr6nIy?U$g(^ z+;rSvt-s~7Go%%JSteVgGmjO86@(S{3Ht);!utiZ1>*%WRs6CT_uX zmxHSE)5fr+vwd{tv!XiTR%Nh)vSOkQWeZCfA2Brf0#H9HXH5)D7{M88No4bz&zg^! zPnsX})S#}c;yA%kWmHvAMZ7TSoi5-h!&P%JDX4C#K3z9&tEC+-C$l>djjuFyz7-F5 zy^t@DE=MRAT~MKmawezsH@R*&4qn^QP^(_{tVk(tOGh8H9JCybFzK&eu4XV2tJSQ{ zRj*K2Rh3aCqYVI}d;rWMc(dRdVGZJPeO08<9zd-uT|zu=Kh zjWkdj(z?Vix!vHc-&6&NZ-Q0%C3VZ_^Ql9&WfSMJ>Oxupt9*lB@~WdU^S*N3YgFU# zf@MM|_^WK{ZAx9fRfksf8|*gPRJ??`EV;(3M~1#aY%Gq}LrC-w?NYiVa(hDuau@j2 zWmpYG2Y1)U_~s7Oil?AZ$D60V(8gPfjhvm$MZKJwpMso%ZJ>_C)aK)HSa{@QWq4)G zIzc<*vi63ihJ}ikf1&fjZspf%k=g;h6rEY6uX9QoXw4)JHu)AdyM>a@%DWPuJW1uE zhy0Je7A{7`c+urkMV2s8FJj^iP0ovi#LOkQdl>pJaeos(6uNeDh{igyd>0>l4k0#9 zHK(<=AGP@{9UQjU+oN*5qic_?Li;QKT1MGoR_P3wLT`Cllf1-5 zNyo+ppZw)oZ$!X1%-1X^`EhywrJBfD9sd2?yqt7t-~C~tlaHAqo6;il^)E+@ErfL=G_=37pLX#c!TC{8#8|Ez9>O$mFX z=QkaYkX^2uT9@!kh`0Xjn^x73Uf>;X_53Eg%{G;*aZf?B{9?N0tHG=x3H=ef*)Kud z2-_gn!7uz8yR|lfUa>WZo!@viv^6Mh_sJ$(HAou_jz3}>s4fJf|BXKWWdKBWVEwQ0 z1)Bv>>TtSSv>{b)PDsS>_#eQT@+}cPm>Hv5y<@xmLkBC3FIT>PM5kp zEEZU4m-#zr8bK~9u!8KjXn~5GruL{*prrn|Om@Mm*0L3{`06GEKAcLLK9f;kl4^F3&OIyl{VJ%HQ0_(-PutV`^c zUeefk*rUfvbf8Q=9~YW9Gg~JEt>~fuVr79)k&kJ?(k?L=PgKzEutx6rQjtp@of`%! z@mvdP2AV-n`3(6iCdBMdG+N|uK1*y{JC=j-I?_e`gYL(H|HMB1YwjCx6$oy~=n@2& zPZCTDMO1Sywk36AHRTPbUCz!JA}~JBc5v2I`}$};waQYBejnb0VNS~hnS~8xJJIgv zA#{SJiZ@O>rAnci!+7zm3AxU!u_Eqi&e@;PrA93`J0Xr2d0K$b=Zh6LgI#lB@*Qw2 zu7WX=OsnA;Aw-khUTRlQde^-3MM zA0IUR>%9Xq^HtQZ=D*`Dq@29!)P`gh)zA4oQbzGJ&M-W$DEM#(Zj9p>>@+F##8VaE zpC?)+djlXl(|FfV>=R= z$!XU#t(#y4V;!N41vlvuJavBL&P3#r$xWydt>X{&ezok_tsmi^oWYqHmN_x!YnQFs z9MS8m_f+(Ne!w1^s!b+kCS}YP8!WfqNcy;L_-eeeEKvV=sIn|rHGSe1=QS5b*6_ua z)W(J(k^pzw4AyczzwyxK(XYW^KtRkRbiD|_?lV98NY*TeQ;__u?jy)aHKdh;Uq?~k zcNTo%7e#LI!6USVL%M}yx=igFd6)9{TD-mC>J=S71Qfn)xQ)DCw9>s?Ggy{<^M8Ee z^1Xa;W#;`MBfD7Y<_m+@tE?po`_jKuCH8JH+kVtyR1v1}doGhq`lG>S{I?HNu4p)D zHXU^K5w`hCB!k)C6gf8DvpNK=?9tH;P2%#OKISa$Az-JoQ1Q^Rkn)Xx;=Wu4d3m}y zn|(^vrPete&fq4~EzrRx#9bR%29WU5v668P8M1Hva2VFmbg7ZMcvqgrW6s6pqPQUa zPSHU~tj1PE<+k73DQ&6htsLf!Q?}V2IUoM&?1zpb!+Q8^kXvJ|MAO+u6HE3i0Lf%< z87#xiB$ z4YtCzBt0lA3WbhX-!TU)Q`57nF@?D z`Z{ok#WLQ=M#kZOexp%R$5|rQtg5TDJ0nNFG;B2T&29gPlw1Y1i7LNVohX@>nlNHT0tA+`zW$W&Q z@}Za*Q%kUmE>d=1v6CtwDMOaDEz^hTRbkN^tgY+5gP2zz3u&X#rt){~D{V`<^lGGf zhB-}tc*jI;x~p%7)oQxiN4~kwuKUA4@`D!$RtSNEkE|(N&$kQaEBDvMoDaZIl8J`$ zh%s0Qw`n0oCWs}kx=w;3n*CgN08$&gn4C7x;1FmWUJ9(mtAjWhWe4M+@{+ ztzN!etaFq|(*0%ija5)NuXX)$munp*H^uOkr*u0j`IdVSl}UL3hDv#fB7t%IB&H*S z1p!@}O(qh3V;AW}IU8ZDwVPKpKnNcqY3u@Z9#z4TeVx4i6lL7B-o#Vd%l}bHA+UF= zWSFM%IMl2w51!%99J~@lU2-QU3)?k~(;01#raAcN*0}8|pTm5ltqmd+P^BMKHZ5(O zrgr$P^gg?Qb8XEYeOWt-y{#6vzO)!UAvaPEt?$z}MJVRSK{oEN<0#cyMT7WJFBoj+ zRcL3Jge_Nd@eGw)Wks`n?oh>p0oWKdYxI3WyB>`OhZ=U4Rh3M`Mz=4;@C(R#5tZg( zQfl@7_ij|h!32dW`6pYNEyW7xHznGHWXFN^PC6EO`VL-hBHz%g+&=fb?B{a!M``ua z*m|=~@58=@(ScssMrcL7c|P|u3Us#Wk1iD;<-J83q_zc<#(OZ=9w`qo~3+_Dc)RB(&XQ+NKYD&Oa@!GSZA-;D!sB=fC=s?vp($ zw6i(qzs}jAI`@RStWo2v&@#mgwi$qVJjIJv@#&#jrfr~DR_`hw8(b;WoUi|Yesw-c zb?Xl67gK+g(Ky0G&swe2ao`P^P&FMTdpSrQS=tR+sIVEfS;1*&d|@=9Q~uI9^xpET z5Hi|M6qKU(NXv~u_s$W7w4934?ZtXTf3|A!{yOs<4L6PWOYcVB%DwXq`YX0p+OyaQ z&OG4kJ{(n9{K@R874JKyZC^Q+DPHYH@St`lKkq#Rj_))xGe|dnRrs-qO8nJG!>-oC zc-hj-ZkEN@E!RvQuJcXCB0Iu%4UL=jZwUYqyxILKRxx$eo%7b7GR*+*5y$9vweDt9 zoU`&?D5kP5Bd>ghP0;Nqnjp$So%L~h8`*fbYU{X8H|;?ej1+6{qZKIo_*S>r06QWJ z`T%MH?w-rWjGV+x(Ej&=B`Zpe^$|+;wC5PExl%0TZ%i)s%9hItmelv}Kga8U?r2~DPO{VgOsM2+^M?fb4eNsoLi)FMAHb^vCH+sY{}G+Ozb*iWzEc(o3f)1T?;y|tS7|Bx2*8?cD95Ua3jf%@pvADWTklk_k;0-)B|#_MDc}U<%eFBG7JXWt7#f-%;&$QqdMdRx(P5o<+*IMnJq?KRU z7=I_%?mbtnMI~R9l^{y>O3ycfd8N}~nJYslfssi`f8h$<^>7C%AWngg-~o3am%R{O zS)pf$MxUD0s$^4Rl&Y0dbIh=ij50*Qty)bg*RjZO!>~qeNVcra?;D#GJ8uoPPXHm< zLBqXrVndkLg#6k`QU!iN<6DguYdRC znuU;nEaG!oA@Xx4h2WaJ?Ts(eAEh_t(M!f@p6n4?U8qQ=Tp zm#!YKa+y?!y^ahHM{A3h&}tG%+_gw zU~c=hMTc^StcE0*r13ei?rWsDm!l)m>D$QYjKf}!84yJxJsUZhCV(xN+lWW z(MJBkr%et#60*gBr&%U%3ZR;|R3np=cqSdM8aQ)~mx)6^oJ5)Jf^<9w{jf5r{JptK zfp%6+0iAxAiPA(K0rJ!o_u(s9tAJU_g`vhQpzP!#eed`T;&3{fR&y%Mf@z|+3^Kmr zt0NF#UMD%89ak5XlzMKpB8~TfWnNui8$y6rGUY){$+3jl$2CY_uh@5~x2ndt<{pQg zqpusnMNGlTR;(ro;uUvQ-(^@uUVIlA;{SP@QXjVvJH+=Y5GLnjde_d>hU%91vEz7O!KaZyc{nIHB(eyyz)#g-AA)#};<7!j2n<9cf{O z(tY9?O+NY5`dcz1_!$r5VI?5|oQ^$U;N{Aj-U^;)dZH?TF?l6W^A7c1k&K4>)J3wn z=%uwN*L3Jpz$xDtE>EHXY7C5Im=M;V!*o&$_BtVC3=Ei}nAUv#Las08i5cL)E`{rcd=fJ?I*6`04hKCA`bHtuYR6Zy`}V z+BLOY-Fu=f8_(2)pS&z}Xz#=(7G!WCOwZ%L$~Wm3!rFWvMsb>H9sOAP);DT3s)tDd z3+CezqyHcw9%})4)UasbB9!t#=v;$|A=hX#^O)Vmz&4ZtmEXX-%TF{(CAf>pvPEe9 z;yCWo<}1734zCx5tT4s0blpxVomjX=FKUdgqC{Q_$&b`;WDUR6RZLa9l4sx$b)`kj z{^!Y)_@1YACnzaf!cw=I^CJTr$TExGlAnRCF+(|1g0xZD#Fl;SWqzfV44(no;jk}5 z)b^DsFiWWpXWUUblQi4aZc|;9tH|7~A{*;SDzy^a z5nt|h%N+Lqvh3}Y`epvy=NIbO*^eQsO*&slnqoss7%$m}YzFoTa5iNg;9peAu!n_{ z$!$0nwuUx_XPndVOep3;qHI)#9T_=GZ94G}f|fWUk1`WPqL5{s&Fhq|t_RO8YMb#p zj6Iu+co?d8pkp-nPDK^vY7@P$z%UyjgK||hGi>J7Gto>gfw32=VI`y-+Ce{0KQAoW z%`%cBkLM+CFbGlPt%yM)7$ZXS+0d(|?%9x)%t%G1Y9CA;7Rg}hi?%v)FKA+?6 zhdMH(;-=m++Nqn7>bpKRx!peb>g2?@eYr1cDtSS@wBby~iJZ~1EKbZDC%$+6Gk#jd5>UA4NZ)mU z-HGJ9?do0n4@}?``8e%jHINzb=|BZ3%NSpA2aTh@%jB{%uB_fDtXnoaTti1H{8}c~ zqsyafJmLk*ck$RER@$#so%fLagU#d@Gq}%6g+|R^Y2b|6>|RI@l`S7}WFHXn>mhrj zSoOl6F3a+0&Wp^~)lzr*Lv-C!)^(qsGwpCwtJTi>{Q7BZ%Q25F0jf&1=RvK*gjRa* z`NQ7xLB#i+lLR)PGv!Et*gS?nU9E=55BoZI%jeP=EnAur4}*@!-2WQ1ujr{>nivIyQG- zeoX-9PSse`M>3?fSw4G@rzzC=IUzgDbfgzo!>d5CW??v1oaqOINI0)bDSHo(hiOVDon^=tL5}ufGpV!BD}+0EWn3d|j&{3gPF{B1{IS6p z8P31A;X_zQh1xBAt)E|ySSQLhRU^79PS%iPl{*F{LRW5qfX(C8nrF%3G9`VkkK)95 zk4UKH)bRB(YByax$ew47H= zjHPEj4Y6E+SdtOncTT5n%uq1j@E5`IAoSR~{LOm$b6y@?1LN=bk#`ODuF0}h@VbuA zxMrtUdg$_uHj(^wk`N6Tm^{E-beN9)go@qt?uUTAmT54vBV(oD>x2g7! zHQMwU~(AbFG&whltzBRQ~tnm{*9!kb<*&diSj>6dO!E^e`Gvr zz&Z85knx}}A_(VK99k&g;`>|3quy}^hGKTyd;cyr?bNWp4}aS5vrRvpdH?^W|K-#B zQ&9a&U_$N$LM6KM?)daVQIP*!VEPw6z5kKG1OXtuf4q8usHVRKChENc6X0-69OFM; zy*q?oL-H5u2>lm+?zg~%2Arb*J!m*JP~Xg$wYA&dWkhD4ym48uj_uVsb`SygO}PE; z8&dfo^@mo+?Bu9KXr<_a`3UhGxrT6&a*x9&>|iIP)1lw*Ebu*sJLh_WgviU@=t8YG zDNeyrA~8)U2fNinANhoXM%+e@m|B$eDplUN^|fL;9oru+UlXP%?^jtg%Uo> zZyt$>->wJ@X?@c*A$Y9H#dGZKd;e8JKyF}2oA)N6_Os`Z|5rMJk=bWU^lv6c4woGc z6&hjFIN+z%oGZ`RvY6@F!N{0e~_e;0LnoWF=HcBwb zNqv))FOI$c@>4clV#L_|BXNl=G5-ip<;sTZPPyuX$8yS$!s0n?_s<~ILdu2=m{inO zUm!!v4PJb7NH|GuyoH-!p-07hak{`Esv$B~oLiz4eOUFgLYmm03l9L1v2=-ibXs{!*6Jzxb1mhk$tj^PRPuco93BZqznglc*z}Os*|X=4dral* zr6w1Sg2VuwJ8@-4ujT}c^~u`BpU>%iW}kdrGezG69y)?DI;8TfjDlJHj88=djE?3a zIWv```ps7H8sUw2L#62G2a|j;Mk)=Y68+e33(J=buUizCU~bgfq+EUa9N1qN8K?|PElS!YGb$0JPCAesd|yj$V`*LecSLA_BJO4h+I$#m+UN{43qJA`-hRrHvD}Zt3U*ZgpwF?m{xgX?t){_x@ z#PYLzX}rR+r+a95Yr70XN2to6w8!u&LaimiT%jKn$$2Zg>Pwf^UWvG>gf5R}SX0zL zhr6ED{z7BMY{KA8;LqtSHV(yVq-7{J)Trk3*s_JH8QiyXGd8kT0w^#y~Sj6#&Cob zGLy>aL*z$F`CLelC(q>6Z#~XA>_$UNeOF@IUp(~~K~p^Rj12j3za(fKyL3`y>Y&?bM_QH?&)bHGn#cQ zsYxfz7&LO`{7vKO;fkqC4N}S7BzI`ji>P6<8Hscqre*U-T*eko^eh!T4NJGH00U zl^+s58)OHy3#n+^UaHWVeWno@)7I2>ju2{euuX?nka<#Jak+1^i$L_5v&;~1`;Vg* zQ3M6=b3#8@+JpL$kR7n@Rg+1t|h2LW@*2yk-Flx>95pl>E(XSwo}nr)&(OCg=DE#B4w8v$RP3G$}Rbzy_mus8hZxiI#HVb%Fduu2fbHe-4}m z^yDLtjDSc2T^D8Aq8e>P)frd)zTEo72&w#x$aeF>-7!&69oth8NL&5pS+;K)qQatyxyn9SXIUjq zb<2ELTQD2UDVO=)T6{J+W2is-%baPDo{V%| zS5O}@Ah-@#&j@S+pwDH1KRDRH!xHcA3)WXv2NE*4yH)TwOLri7geo!j=1!Ra@q~-b z->?7d0=@A#Tfig%G#&E$03yI30sjnJ@J|{F28ROsLgE2-{)+~Ip@^vUT{OU8K=jhv zMFTE~p?G%FU_kl%XmUhl{cb)agc!_!4-N4TdfCX|_y+5yZ(-0Ur$lh^5$jR-yZ*UlDU%gNyYG2=A z2svVA$ldj#AVBhpy|n%9gTv$iuamuea6nAlO#|lSJ{lY)M@(f&JpQb=ovYn6pnXK+ z=+1wBtxFghhS*yNK-)KmU}y|r3fuc#3=qRor!v{z2TU)@~*tgDs zb-8bxf#=4)`vI4O0hA*_hU@9~49A;jQdyJ*1t+t)V) z0=AzISPFaV0EV8Z7TH}M8V27xpMggXpsm=)2WTkv(vbV^2axmxz4u-sA^%VZ2EFfj z0PyXr1E^s?AE3F|J1)Ruh?pN`SKp8*1Y+;p0M;}S1hAVAgWNa&kQg)&IBqu|3TWQm zzM)_+AYR#CK42mJp}FHN0qZZGnus~r$y)_X2w6iH7k4lcSTRIXucouD%TA^$;%8ML zOdS>uv&G;r2pk4!X=?*P*g&kTq1F%^D>;~r6;#d&rbzwoS$>+}-Q0nn?wub@;3p9+ MM=dO@rl(H*fBD!hyZ`_I literal 0 HcmV?d00001 diff --git a/doc/grid_map_layers.png b/doc/grid_map_layers.png new file mode 100644 index 0000000000000000000000000000000000000000..ef56e52287b3ec9d04f231a14f60b2f5fad37727 GIT binary patch literal 69502 zcmaI7by! z@t!YNu4HFtX7W-Ffo+d6905Nk%Qwxd@_9j*qY8EEu-p(Tyf&c(4%_j|QH*G})eltgVR+GPNSiS6> zpuGVAK@l$}6Ej;2Hwse=t4|I>RA=qoR1}}gg{ZW+6xkJ>BrL2y$@;ihsQV~snEBY6 z@tISJ2vZ1p@k0l&w{SC|@UpjaaOL+BqWWiCe(3ez+iX-6|1@#46{7l|NogypP)Ins zSWs}WzGpFG=is2==4R#K7^Y=X+L17b`XnK0dy`W4wFE0&T(K>h0iW;>F_NO8xH$ zk`}IJE}xv-J~=v2{2kH6)Y08dhzdH>|5<{)(|?C`aQ)9VK{t%e%fyL|gO&a7lKyR| zsQCZi)ZYHTtzF&JEdK9&|JQ+CHN2fH*wids9o=2bpoFue{`)8=ehC)~6E{Z}4M#`2 ze|J&E+R@F?)!NaCLPDLJf?m-~xZiP0NQ+Bya7b~AvGeipzLRF>W|xxS7IeC&_x zXKUqrHf=iAU^kL(Vc)!Kki3wyN)twt2uDvtiA68)MYL#2joyCgaWkz8(c+KXBYk+E zEqQn{$eIG{j@GW|3sxb`j$v)`tyDU#PBWhE_v+noPwD)}HENyomc+34`XoBS{8m?a zXTP4T_Fl)!=y6d(m>Y&Kc9Kp`PIPJ)1m3^r;wYM%$4rRl&6}90VXgkigc%QQ;qtjS zJyH};Cx5u1y}iAm;hhi{mxut5kdQmL9yKQ?2ht^1!AuWVS~wgUCE8uq;%V+Sd*b2l z>4_N^t6lvuT$~cK@b55os>3>PI_BQuBZGqx3r7~-zywb_JHG%Ax{OJtHz=iQ(bg0N zV?0DeE2Q!9H#ZvmC%5-c0k5YMtiJhR-f$pB(1N?WJ9P;)tb~L^%gP^@>)YESH-2v~ zizF#LLaJe^u@s5qk)5rrtyoXX!S_NOd|b}wrc_x2G%!zaP5_ZPE}NY3`T1#+CfyV6 zoH+-?TQ)vrDl#KIJw5!NEp0>?k*N0}JA!!M?>}E^wXMOjwp4BG+BiDaR#YT8218ds zB>|oO{hYjT!EJ4|VyrSN^Dh`?f_5)w3k&%5AsR96jQ;*umcjUVjGQ$L>mG+DBE_%2 z_ce-)G1<~V5coheeR?b;I9M2wsL7VYOWJK@+D-UVahtT!U5|v=_^X@irWS#kuDwG` zv+sTh=Kn5goATVtZ(d;g+6RE85SyT^tbBHSZ0uBkILV6e0NoJ#6MOq0WIOKmam)Ip z*~5~gFvfm(+}0XL3tC*X2f%w~7I^U@eeTF?+)S!tFMqS`gEv}e=;%KXR-d0IY8^(j`H%e+q}S3s;J@5cHQC?)?7I-D214ra0-6r0QxX z-j4eE`sOyGn4h>*S;4ZHP70pNlLtRk@o_x6$B-$czlx4h#h_tB7oOfvi;FTIuG9N%-mF0@!{;?u%V?%=j4Vvr+Us*^>Y*qe7txI`irk}YDW}}C>E17Cs7#2QyC4A zyq9UK)=fMN{!X~ngBLR&Cm5*^>*c$XQ_q>vEm&B0xA1Wt>tD^ySQ;1d-pG zJ$j*`8%s-K1Au&Day6%&gJp)9prL&izA*e`8W;)y5RO8I#jx%yNA_FIH+GDjHZ?2Qs5s z>8wIoa-0N{^okT^;%;wm@reO@C0&IA%##G>+t02iV@ zfS5@GP-K??h@2~H`}gpS^r~mW7|}~HnpzNTtHNiYBk6#m2eKzye$->5M1}_U%u8nm z0ZR!9;4fBxh$R94xV4$1e1VD>mKape8~_76KYjY-VL5-4m7kwY)Xw`+jwNitvV9!v zw79Z->;YviUkQoOI%Nvc$vDD*&&RYyf*_~&tz6fJwy>2y9wWH2I_61~P<8qA8OoU^W8#yso)=q-tE>8iHbwO#({pn$L8AI0 zi_6QO^J{-o(>&;6NunLdFf>G_n1#TE=Qa+&%veS1%3=`w`8-ThZsQ&*E{3#MI8!Wl zuyB95BejGr6~gT$8f5e(nv%#hd^MaR5WqNGqdX#txNJrCnY@a1w~J>t!AAd3AD` zY946daVmHad+20KM5bUCOXgr3DZ~KxBOI!pKKCsd=5;T;nR90aVgg<_As|JVo zZO&$dP+p@lU&*Wd#Yw7?hz5iVq)*;Hk^(aky$yqZ6AzR25&F{70tZCrD1Lj}5@SFS zje}A?@y7){A+~k(n}|gB7(9V^{^frJnSpKE+Ref8BQvqr+qZ88XDrIYmwoK5JX<6N z;4EX{pHO&dV*iW?nC2OxZBUw8f*vWl34XC;&5$+5SZ|FkZIbfQ52!6jMB* za%l^6J)x+M+uJd0atTy@a3}`A`?N2Z`XMN^G|6tjLy0xqcoq$qUdK33#W2M}P&}T8e%+Ezgp|>-s zmZDe^vtgkcA+@43G8)L;xT>VcI2s3i1AziWRNoY3vC!g`cjwZ|L49=5au6}Wk)mx9 zjL0Q!oT@6@ExEBcCjy2<2sQy#v1oj3Jizn-UqEd6#N%J$?p81q89TYy*f>~PI(T?I zZ7n`M`7tz2S- zp-k9)IYbbK=`l*u2%(nmY=y&0#k;7|F>%H!FD@9a*%W)DkF<&H!dzD;UKg!}EH+q= zh^Q1FM@ZnHt!sEuefs5h6uuZ?u_y)xIyxq1y@S#TX@3c|qN3u38SOuMY9KW!9ddGiqyG+*VRJ!}3OnYfXiLLB zoQOR;0TD4VrtYrMv-l9>H6m6hWAH7DFQC;>RNwGQ&YZ$`*ZcGMAR7S>OoO&&~nD1ZW_5kgzV+e!`q7AsHzt0Txf6M;l4r zzuJBbN0|cG(7@nlXT0D{{`t9cFi~%fLmwg+$Ih& z!O|ro`1d%D8me~}5Ch0EBWhtCHEPM_gjTOlMdI%+t+Q5_D8|_9?!0DcZp%azQ~z8M zBG!X`Zr$NVeH@VCYHmLJhq2iz@n7>801t|jw6wHxt}UsE{^0ndCj7eXVdC^uDYB%q zGjA99*h9C0%~|OHLp~2@cdjao0kj}KD=vt6_g?qH6Kl4x7#8IWdzw@&zreE*@rMxF zD2G%++0X4c8?LlBDvTOSCfe-%%7wuow5N@j5Ye0^nPWX#OARn@T% z-0vVstC$E=2R&2IvH+MfU5HmP99hmD-FcMY@up@-L2C=}hvAE{LW(Sg@J(k>Sxz#Q z*PDFN9wYb;;fgTCP{;$0La;Ka9&NFrEQw%&<>ncXUbHo_dn|Ps{GCDOH{2dg2*SqU zVc)8tk}5KM15_f-uSj6gSkrClTAKbbL4UminG|CR?bV~Ky=tKs_rZCfvKY zoZcf&PR^i@<;vG9Y|xqY(H4Se&Aie?-S|nZ!yWF9HN;V9`rwg6U{ZrR%kTBE*IL!f zuzSLvgf~zqBGTRfTIHFTN^ysmvzG&`Uhk`FTz;$t5w`jIT0o8YU!O94j3!CectJc# zmlql{N6(6P*%Yc(0pPU1eY{(m?;S8^r-ecTrVmc79JuwQs#QqxxA4c{61jbrMM8)6?;s zWH*5f7ULQ9Nn1+M7Qt17TA${pcQ5a)`1$xj{CwmuWLFGsBC^4fKSx>fzZE7>d~9b3 zSL!ObxIb8_voK+JE#yqXKv8K9Wy>I85G@N4%Fn%hzOrEWAi5Ew{2n3;)JTr4mMoPh zg55*&S{z6K?Wsa`7Ijg=*%Tm!C?ev8!5a&eKH5R4xI|QBGQZ>c@gdg>&jEv$ko$D} zEXkH)*a=*`vHn%Q19;*hc?yFjv}B6qHre5u_@$|Sa56A`^v3UkP{j9(^v{l= ztvvetxK)XYN3lk+0QnHrDH!!Sy-xMWP-L6UPZhceWO;|!rMbwJ-xFK5sa*oXXq(a` zwD^rZf|ca0G5z1iiFlZAO-f{<$%{z#gq?q3Q~SKbc!bc$)bGk`O;wZ%ui0vW;GdhG zKt&tg?JWL7=$%*aWDP4@ZB%s$3`fu88Yy=m4eoH!bW%|fWrlCz#?r>j47ECi#b0kt znP_Qc$v|5_GcT(XvS@}z=p~c`HeC>B>=iHHIXFH(JU%`+w84jp(F;V@;j2bZL+DCj zUCyL$Nl_&J0fV<%j#61klzyMC2$)I&tuXpmCP)e-+K(zcFBwY}ZISS$zo?CpDMc%q zKI{P7d78SQWitsbU9~cpZZ3h+M`o0hCgnp{NGRjE-H_V8LFI3bJxt{8@-RfIFyqay zQ$|di(J7M!D)fyF4Gnvj)yym`%*=LS++iRTb1SR2E18ug+YiJwk@z>w&F?MxhyRI< z_(I@-!CMi-hGzqJi(5}XcNR&}M7Eu41Xw`GL`{uD;<{ngoX=M{{#Y)t;^~8%8;>Qk zp3xiyI+XCqY;C2iS8e8WSsGR$mfRdTu2^a6IpDKoy))k_Nvm9Ua~~ zEGAivt*nGXHCNa7rRGYl-4a}kFc?A6xY3fMy4;zv?2s9A)}@7;tH7N|ce5sGU69w5SrM zKv2|%vNDVZ-j$^=)?9GNsVC1K%cFCHqUu-(7{M4%!&X4pfh zT$EY7TtBnspF-luCAvz*!jE707(zwHLMo}pT|1ob(o%{cei?q;?S#>G5&cKDwy5&* zM^(ap2>1KbcJ;BbXqaed{4noY*C58De*=gpiZKQxg08f*G(yZ0ke5(?J*t`Q3s+I9 zuJ!kun_JJVQv|A}x^MR-eIh#EPdE?6F1e)~oiv2gzALB;~a{&&2v zy59LP0B+pX_e(xqS;n6V8KTg5$#4>3sk`O4y?vT}-e2>u>lAG#Wogx6$o7<( zPw-a{rRy%Pt*o$cvmPHDH?Excbv~85`xp*e6=Hwkgf#&|ncyZPfGkZ{yYlVRju=|f zW1W&R0?{gC4LeO5k~ZWe+RN{)zU0uYrKrewJ2@3A#T$v_7SU$v1eQdA*B5^OiWkA< z?F<(cg@gkX{2~%gIX42#?)bG?LMGsoD7MqUFT{Dda-^SCVVlX341FfEeWTMN2H`5q z&Wd-qL=GC`Woo09VV)4LB_!!!eH|S`UEsHFb`eaGBwz(zFG)J^Ixa4hnz~;iROv6C zaC~@JSyxi=H>?FONZojN?BnnK<1!I4_*~2^O6W#r;5_1jKDGG)tRaZrS_@<(?;V#QN6~1 zG|~F+>d|mmXz9qJrJ>y8Aq;S%0Op`Siq%|71}RST1CYLpi^Gd|f{#VUQDok$7r2Hk z0{qf4ll5q!?Thege*qhbu(B?wN+N8oh8g~~_%miKCPtQJryY-*Fb*2GOq&DAXH4G( zU-q|RQ9q)*IWX(Pv7Nj$PV@-eLikCn<_fdsVC6;n?93pK^4T^Js3k~QN zNwNIII3m61(BkW54!83D>SpX8VTJ7Ad)@8t?OFbH4|jG3u6A%$Q7^?|GIVSYISqt_ zI)#J`3=Bx~^5Sni#$S{MtQDr;r)6t2n93a9Cv->&66ce!P}dL&%)SH0Q`*Kvq%E2+ zx@5BPYZSaKYewQN&#c7B#GW*1SWGhpO#Z9o{H`=`p-p5&9$i2wWsdwTCE^6>4DECiZ+9rr60qLg zpeq*)#rGtr`(Z;vS@EekgRcK^_p!jpERdak^*CZGU!nZ-m~ChPjZ#!yT@B@0vQJR1 zEvbsRsj7~+M(4);M#hJXQs{k&$maEt?{}Sdu2?-CpZfrzh3Aa`XO;q|BeHu^>#cRt zrx+`{02#*K7K))DCZq#u?YF`Rk$^GUau5c-)Dy3q2GPDuGzn}#n8ub++eb;qp@XC# zM(oDqR`TB{YnTCH_cSxSoO?MKN-e12DXZ9A}K2=GF{gZj#)P zhXxDc8cLtokrII)^^2xtK-n=@{;9Jj-~~d0YnauLKs;d|TvBm?MItQqMD~CifKT>W zGhc)q398EhM1EsqG4k@R@89QuFK~x@r%jsY!d6b)_{S~3+oeGLi@sX5&$Ht7Ddz)s z1INd9&@i}g!SnX!>gw8^pCoT>jXMWjp+CtcH?m=LI^csEur)W~xQphzXDC~D$?mqX**W9EK+7vBa(Jw@BKXSwy2$ zIxsEy&K&)brBX2_DW-&&m+TfFE|pAdOWzlf3JsH|goxE2ms1}#-3(qnFXAPxg2+S# z^vL*Cpu~+v47q$S9!uXCN;^RU8EReOs-#hZ$PZ;GI+HuT$ZCv!PR0qh&V)F(Qq|aq zEkp%|7x)(U#Qf&(tKY{IX(1*icK%&FV9G%P7l!IL3##{q|`=ZZK@h^f*mX&V^i z<>bIlZR!~q=;D5&aY7aV=70IVaq1Mrx8*T)qJ8@8h%5`3H zzu&toW#0?z4w@5hn(tCshH{p&8pTd2DCnu7;rI|1`k?f3x8pZB$y47oN`KS9SWcW% z7lI1J_cgar(dSlc8yM3%ouBAc;UhJ+#%ML-DS^hj;dzKszXoo*l*c{@L)(#HjR1_y3cdaoXM$4;R z#`#?w2X>Nt9jT_~E-1l8eDa!D=87zJ{f_SiYR3mn<$ zay44>AD2pb(qu}q5&56D5aU2^^p%9=b^>UOQanZ8Op(Qd*17I@{ivhm?&9JrL2-id zY7EN~KSzs&M&hOO2M{`oe zd1vUv_f74R5;c6mI-fmV$orAhq?;vBkWA)+n%s3p>Ru}0N^45&om`{5N%(NnXuY^z z!nB~{Q7?H(^-yUMTt3vWpWnqVuztAE5iT8&U~&i@x1 zoB9u1l@PvV>X|>soY~XF(KVwV7KTjV8$rY)T+aZ#vjF`U* zmO}^)*80;p_~n>h^CL2A7~`Mo2eS?dmC&zbBs%O0~hvA0)h$#FNrYq5u0akiVl zru)pnJE*|6tf=oF#DTXb?tCO77*SgiN^8G}Z%T|LU1Zk^VgnQM?knr5FDDVq%A2TCn&>%sinz1r0x>vys?Ol~Z?BjQ@UIU#c`5|~x7 zH-SLJm&uB;+s70wZ^_(#TCAKP27Tj!zvp$r9}B;bCEV(0i|g zR2r~7d}R<-DSBC(T3VnE*594U74JV+8Aglp96ZXpQF=e6k`7#2*f={rv-%XVZg>|R zGc}s6wPScbpE#L*>F_P}elmybof9Z!)R)vN*jd@)yA-k?e;G}%vMy<30wBR%mi99? zE#rszp$x7PW2%wb)JjSAaPrcI4b`oJI~0sOM4YwAh%%^>5T#nT4@xDnHsoPm#i~o3 zwYL6N=`6DIQC@RvA5^JPqzy1a=PXj)V&V-WuvYpQk&h&7jnTt5@*`O;s-V2tMMW;+ z)y5A#QaXoD)Pg7073!Qm#ckuq%XLv-=#BzO)nK~~!Z}03zK(7*jWQx_{&eo>PcJ2h8^6z z`LzWO8sSnthY@;m-rSahRWo9aU9! z`ju?Tso5G)is%Tij=S}2z$K#wPXfsckEbxkVBii5`>U9gvqp5wg?Y%N25sFnsDP2- z^9;QS4sboAAWsf1bhM4U4XaX8=7Ldm5O~S+Rs(t4E+CbjxOZrY_tVH(dfxig8zpV* zl3aB1C7k7LG1$t1gybE(g3ofP5ezZ-wD*jr0kRrY9>X6rK1)$SF+%yvOL1b_9cIE*fi~_(TC~@_?t%9u0_1omWo{p|A z7BV{27cCN%6%W>6Nc-6S{71Qa{txr1ibb zS-^WQ@vy5M1J6mL>*I-nfETvzmif~zu%=_6)X;#?>s>f`xSl{w+jfglpgrPhMY!Yh zif2y#WxADHRLVr)Ygu=i@6wUs6zBQVgKb2h@ayl2K;H-A7X`0zMB(ezvWe#g13ojXY&ew~dG28@?mx(hQP|WUtE^U3WcfJVYcs-51we zyR4x|PRLf+RA0)vF0XybAAZ{DPH+1Rq8i>8Glh?^`JY>*XLO$O*lCNzKRsQ(-e_;c zWaX<)3K>0(dJg(ObP*d~Eo%wmU_{0HpP$Yh8S-^p{0w|3J3udZnIV?gXxpzr90G+j z?;oxNUcOmq$@5^@4n`ykT0Ct#s__k(jDXf~%+HK$pZi$S4Gw+O`Y6Yc2(?9>tXgbH z#u52sQ2~`4=9xiKmtoSmpgO^8v=MOfjWE_~p+q01S_%ngg>~Q5D!E*+pe!vTN1|Nn zSjvo~(Lm(AhO4oQPlqUsCh(Dyr75t9CuHwn5z`U7udab?9;jdEVUHqtaS$d$I_e8j$#qS_+Y$QQA=jc4!;7}-W+ z3+dgwxVZS;*Vp&dF|@67X|VirPYr)KJ|3KeeH%pVS)SZ3nh&K>*FMJc*l8%fXUG2d zefPs^3uH}T{X9NG*>8(g>`q?!L8zv)mhr0gF6NcBu+)auZWY%xnI3JFv++?Iq386p_vUqWM(B5AZVeyyw~R&iicWOc!_kX?J|G>zzL` zmE>vrjMtDs->_|fCnRZdU5I+sWpWFa?GGa=Hml#=1Cz*|I+*LsE5RZCkM}k{Xyd@w z`||qs^`|n*S!X_J$AzZUK9k{NCKE%lMUWBfqB_a#Y8chZ`%SRj105Cnhjeu6|G9I+{Y!GRm;@U~ z#TO96;QKKmKE4P!>-axoY5?>H$cC0_e3Gtg4QUr@Ey(+uS$UWal_4z|;2f4#jJO=+ zU#CG!v~E^T6C8~zTJl(Q#)MpWJ_x19UlroIh~GYlbXD)})G|&`6-g#JCz~ z3L4%eizCDT-u1x5z?{a=deDD_@7mEZ@qbiY(G^E*g@g~Uxr)OJvFy)791~-c>)f7jeM%4uwL$NcywPsu~H!U zm+_AR5|xEE9(j>6X%0{0LvV+)2+xjJR~OCj6M=l&=d8abu;JD8YMWM02Gj9UvXFxi zbcH883xqtz$pVNZ!Q)tb;_MPweuaeMDW7A=?&(nsusM)v+9k;!qW zE}CX>Va$9~kON9J1S{bBrRIWDT#=l91kc%&3h`QVFd_|DLCL+{YqCS_;zh0@z80@R z%4@w^w~}DdUCit(B3z)n6`(@5G??TAIl)SRs+a4)yh7a`+V}MzKj5cH;tV=? zxj4jdWm85t-|;hkC0sNetNEKx_V$Y^j79Dv@3=!b7pjICTv$88y1dE$nglDnp|1u3 z;U}gwM+K{Q9|f*1$9KDRTq(A6f{k7ll=qRLMHw$70jz76E#xoU1mjTL`ZJ~ z4|Qdb5f<_vhdS>N_pHdDmiLFqo+ku^53NR+#9Fr|y0L`smM0UQ&$&4yO6CJJ2QmJLtLr+U91t*PcAbqHyLZW~-K|N8yh{B`n7^Qw`q;1CiNQn0NBd7_mABomgo>oQ!InE+3*VE& zoVN4Gy_T-ePG2vKCQ;CauU1_=yCI{#gTfAa{xKAOr&9aylmt5XaC*N*h9)Wv)mEX} zOJr=h7S9qM{B{54$O*3IW!UB*-Z9`$&h7KqW5AiCHra0A%WXKOQHjvFY5>(YYhKjg z{ely&xs^xaNnbMBmZZ_mYb9kxMej19m1sD)Z??i4fx>qZer~}0R#XnBa8sYef zi3Uok-8MQ_)PY7A)~Fr;ZYbF=tiqr)xc8s2G0D(W5#Rjmby59_iz!T>UGa`q9)C+S zq#ctkO)L6pD9FyjA{=Oq_H+1LBPEcZUQXJE(wa&Y*-UXj)9Fp@@HA@ji}BU|{(eP> zL^$9VJ&ErG1xyM#t(&9QwkYi^Vpe8r0{$P&Va#Ib%FQVQrWKd^hk4Pt^01IxWR++P z1OUt}H0RBkclC%qozU{E_6Lgi009eYYvWa6&!gqsJD2xZC%t*e6L5&8C;LQRzWPZw6v_OthCZItgI}1roJRIYZdLOP_LpQ z$wx#))GN+R^%T}5g$ESQNni@i(tJLCNkGJ|92LdiKcBrl#rH;}H8J=TcLuUt_qZKB zd#1F6e`4AWfh-qc?0r*B7?c)k-F6RrUBWMRG<xgp`3583_bT0<{i)@4Q{In3XG5gDQ=@FK%FZBm#!0 z;9<^wv?51DwjK%f7rYs=1A%Bq`uq6VGbCYocOxvun-aOO$Wa6yf=>UO6uW zH?!21$b^zx7UJuzj6TC$cKLHHvJpf!lcn4!M=eV z5Jfe-YeeK;6sA{`5oS|->!skukLuT4Rwmxiy6%5vr2EF*=+Vl zn!Oc@46^g^@QiWS1Sc@P`6Ws}SLv62jt6e)>?Ad1uSdl(qvR!tZ$LoV!xTJ5Uzu*g>48n|Tyd3;Evwcly$zREN z{#9j&8nk)6pp8tWo&P$q5_WXfy0v!uG^AJ1%=0)>cM*1sfK4SxENL(e1fs53yEX+bhf zc-Cm;qx(g);cInoobkb15g()(G%WP1tJ`20n>Nt&V8oo-T?u2Ey$a^B56R`s z&p6uBRrKcQ)0xF$=5>}H&9h%ZY-y|jQ1rpXIP#{(#m-FyitA>7p`VCs4i*KN`6$p` zB1iu&$It{miLsZCIw=+t`&CNe@&k^pynaB-%o`gA9(}3QAdKhbTT{fIiE>vVQ)Hwn zOV684qO?Q`tdUW-p#?HSQ z@Dr|$d?LD9wn5Ck7HK^iUlH+9_xBO#Dw*QqBEgz9PnjNwm$SgdDM~x+TJ`p5rWQDq zR?QmDaD3PGK)Au=x5L9KVoNkp`K{cEzZ1Q@4MV)=J;83u+0~snew~afv^vN1r-_Z7 zUGj-W7B)3(>97zUzVrh9$~T0_>JJ+#wHk9YzuUoa2U|WgL~N`SVeBDMvIc7gr@_JN zFHm%3y(XWm&j0NalJ=s}lXOKul+3-L$eUxZ|5FvsACw{EU!S2V`^*WoXXiOs!+H%` zr#T3Yg2*9S;O+uevM?lsUz#NPlhH@(R7kO3;RnWG88Lr$T8TF#Boes17loae@s)4m z)!@_W%!5og0s-$JswzB;j-+NUkOwn7FhyFqc~4c?AM#&RSi~iE5Bue7Z}0s@A-cRJ zG~eObKD(22_zwgWnn;Q*kDl*g%9`8SIs^oGo0xbwIQaPZm;`iD2){5keP$8I5;;Cw1qwt}2~Nnk58hJw}?j*2fWElq^!%F&PuM@6DDFXCPOOm0XH>AF6CuyT04 zlP|dID|Y;jDUlc;cR1+6Q z-)l4L-b}p0taxJS-`+GbrIMfD_C4o1vbf9Gj)g!Ey=T(e=WUFYS)TswC!JH6mYI{& zvm@BhEiBLSN@IS8xoB>Fs4M#*q2Qj(B}uN&4I37-F|}#>IY)sptn7e!dP>Vt&D#<- zHxV!PeBuqMp$<>bH-+{0)8f1rF!X*On?rJX83ppN{-R{$5mtk=Nu?X8W3+;!;BMRi z5@pThz4GJEszOjaUtY?-hTI_G`zJW&a)`23PYMM-cuJ})O(xnBI8pjLVS6MxSC%5p zg(j@CPFGn#Lor{QPuUC~=dbc`R(#`7m@jzw;XS;o{s~R=aXc2<52^u(o_br^2n;S{`t&}a32SFl7T}-&)hM8H znEU)J1R#8PfY!I+=}a30kEARLJVjUiiJ!gA=cypz&p?=hBVzwLBrp2y10|_0SS<~M zt2b>;un)>`6(nhT3)3607a_ zqjc#d!i=b+AhxWVV$Qvj>f1*_(fXN2nI@>jLh9-%+xSC0mh6x4mKGx4BC{;4XSH>S zexixFYUNDZ%`TK{S`}exlZm3Cc2&<^N3mg{+tJaF170W3-m)-PSI;*$L+iF>R*Nd3 zwcE>Qx#22+xQ}n_a3&ce7iMumXgoSk-#;RkXsRHz7;UwShE&mg<++jCbRDze$#c4e zBcWA^uH6*flxKt)-ZmM{sti*Im_^Yj=7hb|vP))BMGnlLW<|J~I_E_=rMPC14xr}> zANUi-NLo@Rbq&NB+`m+eCJBKaD1qX*#_Y0>Jbi%|RAlgW@7M(eIe8CEPcR+>n`XuB z6o5RZ3Xb#YAI#?mw<#e2Gm(Y2B^Sog^9u`Bf`$>u9qTa(Ld|UrD7=6wgnPeWdu*NI z7J^2M_WJ(iSqCnH9Ct3RN(~=RfhHVzs~)oiwi?u!BVGGyF}(%t+UYr4G+o8KuQ!V( z^XrBV0(nbHXFasd>V$WQ*_q7zdO2c7wW?LA(L1L%H%h$8`jEHWeR@m!!UW4mkvv0e z`U9!3-}OtVmFkW35{8YKuKC{<#hPdlu9gsXP~5*k3Ut;2B31SnQzrM+@Y2tHf5uDz zur3q~zY;iugo9#2=mhxyFQcAL`~t6t)S;VzJo1y(;4yrYs2=>Ssa_b34nR_>{Dcy1 z2y;0|KYLUSqBZyh8y*46o1lyRqFoH?dQuBt$aI~gn%N8U5lbM0t$eQ3H%7FWkT74&J(stU= zTq&XWq%J1VW%$C(_+22>*9gk>Q14Q482pr{QU3+~k8yx)lwJb@uT8TI?0MackD%|lTj$;{|%d~7sY0(rx56wV> z5W5H{s9zkY^=aU~kEL2s!xb5^k7-ACxwHhuao)rU#DlDAUNfIt7+PCviKqpT@{lSA$`!^7;U2! zj1lh8z>666dko%6y~Wq2201~+CJkCU)7}huCp)k@G^eUfuC3S*srIn4WeGPs*h)y3 zoJq6!Ryw?XSEl0OOGsO55!znD3m(+NfmWc zd`G-r9fs=o>kVFrZ=C(LJ+0Evt@T~!%n!YMtAI`&ebN>(|20ex2k-npPa1b-!q<<6 z(=IjQH_kkl(X|6)q}DIuRu3&?!>doZ^BYakEY9Nf0^K6tbT)qpy=#z0CrHC+qHOUQ9_)qY)O&z$JJ{Y1 zttME!~5KaguU`71Nrj6 zvL#`tH+M7XyY5sQ5NGx1T>kYCH58ih$lrwWOccZIGufyk{vye@KT$9+tG!Un8J1yV z5A<~M^DGLXk{}eNd*Jc|Au?isPRb$idkNksmRJPR?#T}9ZCH2W$F7q%)jawR2(DcR zwy&;3+^bJKTDY%4Sm43^rY=9Or<*^^-FMYro(T5pDGvfHQ{~azlhd^ z6Ig2-#)OTkQjA;5`^vOWo0}%(YDex7+6*HJq+xvqbz~_Z#1c(!$z?eo{5)4a&~n-( zqbtxE6fX)2?L`iT1w3L5^`k0a2HgUO5CVNxR@M;^H@x@r*t~jCr!;%Az>QcAeUF>s zJzz=;kP||AScTmHCxx}dQ~_8GXd01jA=4Lw0`Jme4PR7xN>$q15k{NnW`N22l_2Vq5Sx87pS=3PTYA|GmQkKEJc1HU8aCg4R4`a1y^I6-z66 z!}OCa70*mrbMH_>()X?uUjsgTw2g+n#12Z3bGI1}keHD|}WU&vJ9Y zqSl@)S+!N_T=VoOjG9*8Q9{2qU9Zh4z))eedhaOt`^tar>}a*`zv7aUP~^l8uk1|hw?ld+*Vdd@3qQyS3Nc`9ti6Qg+plVR<(sTiDwSF( zzOT%w3d!BwU^EVaJB#eW{}nDJY_SA@DF^O7%PiMB1nfbLa`~w5lSYOxFpvA*<+FG^h6b2STV{oR%rh1h| zX*6mbolU#DIZ$jnv6D$V$ApvB zo~iXLb%Df{b>L30Pf=PFi1qnTfky;)4%Q#N3j~p%Fhon>yum@v%*+f84T1Y%9c?!@ z;7B+j_$^|(!E5a5)85_=r-Dm^&*SRt&9&eBx6ON`pRfDOZyEIa<$#ynYJQ1H!Jqs)kM8tbrMCy-U)`#C#TD9$$T07@ z5T7tMysUZmOB1=9p4QmTp@Bjue&=`7=WjH<+j06B;c+W8z@rY9(d+e!OAtL{7cZ`^ ztUx#*Mh429*qNjtHf2mlJ(`*egibgpf)%&Of$eq;3E)-1LlB_ zV4DX_OVFMayh_-oh_Av>04+(IpWIT@LQ}~qO^HhIE5BfmD3G{@ke8EtL~M1;UyE;b z%zu3<1fcSg1`kv&IbJRSF1oh5I=8SeKRfGz2w{3U9NrWzrxw=M)OPpwj*JxdIvN}t zd_qwRCfP<_likpSj8hbMeIl;Dd(F#=pEq{fh^q|8J{sheE*kl}-;U(@tvd;Z_P8~>qi`>UI+&v}kvAeZ~e&l5jP3(vYn|16!btx{t-(Z2+b zwB{Pq<<`GebIWz&Bkj=t_Tg)5mF_E=+~T*s^STnO)S|gjNI$ri6&$K3(fun@3&ouk zCnhGQr>4=+h~>iqCJE|wb$y+!JzdtW4hvg!&}P!8A#TV6VqoDjlN|WLthhKqVBRig ztgUNqHo*HVk|`9xpv1OQu|$f+^vQH6vW;g}DHVDQ=m9#gn7$4hAtchf@f2VSaOas= za-W>2R5WNAyl89DgZI^IwKX+I7;0^8E&Ma@_snG!Nao;+pkX->xtszif*8@$*Qiz5 zTsD!~B|resCzlsDgHS8sfEImym(_@T$qKC+boI5)ZZrHVDgd$g*0!G&CSq%W*ph#1 zE1m|Q@bjPj{Lx=LLKMi(uFiqML9q#BFMtLJUdyL3_PZWYH5z>w?Y7X>)pZaHfp4rU zTuy=HTP{+|9q^0bGT~R`B|z9ZJUk4F;W`VL4R8tg6RL{uz(?S0{00!Xy)XK(Qco}0 zMuGQ*5I`?1ED*NfLBpYq1S*eGOG`^nPtQRrm2RWJV~Z6)()-(xN-9T{7Y!cTkihMB z6HJkOR?=XbD3B;?Yip$x$O?=Eq!upB&CSovO-@ZM!XS$oK6OoPKD)Slq78zHVz@Pg{4Vt+`nTmW-8*1rZPIu^%E7$g=eb z@EHVS+f$fczv zz8xViJb$xvl=}Mmj;)eLqp^rW={LSZqR;1phfFBf+7jN8w0`2dOJTE(YOqC_LTJf8 zUi`X-_4Re!>j=L-jAuHT46`lJ0t@0^M+Z?0hlYn;18!%(^GQc7JPU#QJ~}!o6A_LK z5mF6mqX@fO>XqvK;$OxWedB-b>{k<*S?A`L!X_GLElWYQln;#L9 zA|}4ktPpkuks4n3$xQkuR8hFR#=Uo$v(5*%70N859h_Znfr3idOXXAWXr1<%;o&?U z@gB@H?sYWdof#h=pPQN4Uwo_rPmNxuwnk~t*BbN?kTp1a>@H`g$<%DNm~Cd0rjCVx zVqQQ{s`d&6w#Y3nR?@|qf;yjr@Ip}LSp`C=%!v&SL~xJ;(4b6+;9}4*_bF&IK zbay8nOGgu_*mg3WOhva-IT4!Fh>H<)b+x;DS%{~1_gLVv5!>F$X4AXbM0!`R(-?Gh z8i;8?pW<-rQy5OhnPr8H{d9t)kkP2qHq_N-b^*|&cXpXd!3Z3Vm9<#O3(lc~G2v(M=q zaJwPG>+I}2Mz5PvdKy3ha2xaU^AILFolb}s$t>bV*f6yqbcPqjI?jHN1Pp=!F~FoX z8jYveq=AEXN=Zz=x3`BXt*)*DVkrA5lgR|gsimdmEL5VPzoVmruNR<7Fi>Sb1yEpc za1d0&^7d(MxkM@v+QZ%?b8~YOEy||&d zEX8D`R(ti;SIgTt9T_61a)oU1#ihTEPcnQkaNhW*gEi~poA0`K8KFSUAVuMq6D;45 zQx*N+ZaDGxKT2;lY2Wjl2Hc7(;A3UTW}D_&^+K&d^K_RMGp%Af5+pZBbwX59xXezf z+;&BN;Y>R{6(SiyZ&9BGy!`gJzg-O%0cr;F)Gy8%#uFQ86-L9CciGpwXzE zuFm1XZg*d2e}6|`Uq@qOeJYjmt*(cH;dOt&za9cJlFhRF($J{0+pQL}$=nM6TAGap z#vEYKBCp7^mj0~JAc%>&hiY*oZ6C?qSk(AS{@z~q@Nlo#o}s6^ySa+;Fi%f|(f5ceR$$J6oA2-M2k%w7P_VQ? zFNW;6h7df^#>NJ}db8}_5GP^&SF`?*vIuZwI2;Ct4GvF2GC0W|suKOFOhYvYTFXkC zb-`=e_yCW=HH4IAI2D)7k}C@fb7E5hzyv(CFfXEhzz6kpHMUlRUawOKS(tFat?h6m z1rIbMw66Of{QmcGNrKgC9XWSyU~s_cbi@Au1N}M|7vRpyT!bS-guMeYyvBM~Tv%RB zem#`^s!wuI;r@rCzfA3Ze+!-~}nvA3-bT>`_XliFuzm#d(ULy zkFG(f%KeIlEov$L}T1rq$|FMs(gvFsL10SzCzU2GXopGkg?_)EisHO`rf9xO=09y1L1p{uRpL8S!DpGvV?~G}$fsHcPW!rzue>zaEbHgR#|6bag$pyuOu6W&Lam>cIEE``!Jd zqq^Ve8a+1(_QJ`wR(3X>*{0aCJT)MKqNSlA(hr3?mJgt`ztB5cKeC)0-`M%8pcpYI z$7A{2rN^W&zPvNe3J~hoJ-dnAw!u~-EW@K)d$YOtkk>T8i(E9e_ec^84Lkp`l>f>L z8?Jd)^J~5zziTW1!6>oW zR{BD@++spl*5)(t01Nr8y+SmSt4}D?IdMh*!Q%Nv!Y`=b*?A^;3gm*Z4Ut(BW0oYC znwXgOc(COQPc3ZF>xSK3Lqk1IcbB`*(bwCqsnba8FGC3X&EmlKG6I^|t3V-^_~DN= zN~P6qvD&Q)F&6-DWimVKYr#+`914V1R{b9DTt;k|2q(9<*;-qg;h11(GZ@@Ri%9}- z2By~L_ICRfR}Pt)n_F6%H5zpRISe^mGA#m_9ELQ7z1*H4u8+s%*KiE{U98b!<$~b{ zlSbQOEHDP7n77!=n@xAPHk*eW%6Ps0A0U ztt~o|LXLx7N8&WpYry?$N-2=3%x)|tr9c9RQ7IM4H2f)@Ev{uyHRx)a8nqqfCQL#c zHT?iz!qsJle?+A0A zg?I>tIueOYPEJDfkIi>yMWO0`dwV;-|6%2bAJ-7#>IQ^36kCHY3fSfeX z384KCiCQQj9AMf0p#2Y}c1o=Vm0DU__-4`sH~<(eE-vzG8K~O<@-52lgju?ACBc+x z77^g`xn|D4@)SrAo&w3QPym(SW-ZRovn0Xn?9|j0C|{%&a=ktcjoMCIQ-`&w&0?^d z8SACOdLIJ8?H0fg%}?8Z2k^9y?UEW_4@MW)HrF?{clWX|PXLAF_c3UbLGN_-TP!U% z|Hf@@x4Wmir$$rzly!J&bw@|XQ*0&YnaZJw!9psPQ)<+8m;7t)2ls~mIiY;h3tMi| z3aVNu-UsKLsZ;G^hU^3PYYNbwk z9(G-Lc5CXC6cp^YR&0H}xni+4m)}#dPwnjHHSDy7Oioc(5g*`+$L4|NPhE8;&jwhc zAO7G6Km6ejJ(JU56?j4)6%h@_#+SeNSvOpN&gJYhn~eu0lLac^ix44S$P2}WvIYE$ zm`7k>LF952M9fe?w+tp>b8`!D!1{W~Gd;Vux<=_%rBap46}4(Ln;>enw3?clSvxqT zLMd_=SfM~f1lha@2H1Mpy(~K^+pZ*or0SyD7vCAc~m=t;S|-1V0TvRi^<6#M(0`_Xi|*d12y&eVjn6 z)Xr{F%n*d*sYpC|>Es;qv97Mx-rNYVpkC}4aqL|y52-!vX4f}jzCdi*zqPy`32tm> zu&TmsgsoDm`dzMPJ^R_jlt2yZD?W4}UNY&+$!oXk`I-O>7_tf0e91BnOGx z84IUZv#$n`;G#!rFL>0I6vr#9&^}&(+vaCy=N1;$R#$@oCh*{h(@D&;VsNik*;^aC z+SuOcZ7fO9RHr%pwfmq_a5KKRwgqs(w;u6_Sz`;8h-;~H8fewo)j4wR9BY>(E_`@` z^n8=$i3t(P*az%>_y;d*z5Z~hjd()PXw}0Fh4qb`AN-}Q@hi`%Ki2fme&e3ayVJ_w ze^Ki*8&7Wxwv+$!8;OYq?LWU*-*Psi{J;YbfF-)_y6Z5vIXyi+D{g`^J;@}M#9RWi z7Z@>X>S{&?dqzh3ySwcJ&aQr^qoHEM!EdjVBH@KtOs%3 znyyi2vs$cnv(;j;+03ox7OWxeL~;Y-1|cuzqzgF_B8aOZ*kAG@`+@x@o!N;-;*r?)R%|=Eos7nk$Wf@R zsWCLx8$?=zURSRZyC^1DRU)-rEKg*1MdjgZ!ZEmh5?3nLGNu@_ZVVw6r2QY2`;D9q zf)0DxTq1p`;{tVqW&})Zw@|D&)PZA8W-iqxwv(CkZgC5PVs{6|fnX&D?a3&Rpb{fs zrgw@oOmUMcR7oi)GCNtY?2%~N7uw#~+#VPj{Eb^~0pIw|d+*)a+=4N;w%G;;2KxH@ z8KI%C4?x4IZ}*2Nfl~Ak$795d{TK)zU_zq$HH0S`w99)eZf$L$O1PB~I79l?Xf#q4 z;ItZIURFT#`xnH91aot9(^FHctE)&Y6Os?K%korQVBQt8k9VD~w<82ZmFyH>e%5}4P? z@d>t&(K|CSKDNBLgm$F1MvX~*cx|_tMuvOc?k=~h%jtBqx0y@r8aU^Tjm>~R=wA_@@1aR{fo7rZw*z8t#VYgXy4O;QOGf*KGBMRJn5a)z~G27QxSy$HJI-D>R-q<7x zqz%MkYK4ETMq@LxuyBf8ZVy2Nd^jr>8WciqcQ>~ciEeCehBqRco6+!AG$|qvl@h|u z2BSgWWY9G?HZS15qH#eRjQF@5Pa3I|ajt4|w9Ho@XAQM%hgg>5yE0x8*6qxuX7 zTpg6J-$&PnBe|`>Z7oYkn|32B9GueU(ay>lzeF#qdB^zpJy= z*r?als+0vVd7l+&z;jPVxn8;PMn$0$=$!u;lx3+*bu}D0)u@MS};rNYk z6jf@}H?+1GO)X8P7K72yY|z(>R-Ub)U{}cj2*~Ed;sslPnP==tBsQ?+m_<$U1?=X) z)^Li|3ZbwaPsNhpSyQnD+j1IQY_TvQu9!f7UoS3tj3+JyhkjZ;^G`@S;qR4(BnzHNvfe19s+;>(7@#3_D8)0WQ#q) z*hB&}3=d6G>=T;U#};^o;(QYiE=#$sI$e|xY{vZn7hqDYN0$82WIBr`NF^w;M1gd< zMn*;eF}U2$&h9RY=!2X$z@{rF6>ho1mP0Ff&QZ?uB;Onv7k`c-P>JSTpPPE zF*!ApNvBIM1cue^>Kz_-15Bx{Rf!&740FJaDj2;o$4HKF=`34msS z{aBG(WJP9kSvWNukrfG%gj-v>NJ~ z>b1IhO=f2=vYp;er4y-3F@1v=iWziT2+OpZ8l_m7C_WBl_q0SLp*Z~RuvSr6eJJJ< z_`nV`y<%cRBpE>1m*3wATc=|xH9>SJrVtK_h5;X}?b>z=wYHjIy((SJgc0-DEY^%C zccSrBU~@aZor%UXiNsDc2D%g}kivdxrdCti-`_tlG=!T?^!D`B>vYuGOd$xTYc+6V z2y9Y>-4RN~Y&JU_4!hlc3_7}EU+qKn2b8d~v@|2OG4@VRd%a#H<{iVbEC+H%P}EBr^r9^H^#(o=TxsSl39zcM|E{L~>^{l8PnL zN`)HJDp;EU^x)|19KGU7H$x0Azzx)D^YIV29(w4Z8*aFP@7yJe3=w|Ca@N~8VJkh{ z&T)Eja(r^43xTjx{`F8W5M->$K#(YqR-4&kZMB+Bt!9(O+@h&f z=d(gy$ckY%t0Ul=Nw%s|q(id5u|h<4XJ>bFGq$-EW&a|v%}8l~EY5m5F$&~PF@MXJH8OIdXz2A~7f1!J1W{bdyD0b3 z0}mZQ#bjzHdWr4GZvdesIs#a8RXLZ>YUD_P-2XW4dx_Jh_m9J6zE!bl_K%(RgnUHLR%_xv|t9x+J+27yO%l5VG=;$~J z@erFpm-a}&h6I$lpbiauWr5#D0oM>7TazNSaDIMnc6NS#etKeJb!|;TEmSIm*5(F> zy@{c!|z3wS(hUSHlPd)K^1SS65|Hp-59LGF30pQ~^GU zC#s4@r!kJ423u7^o(U(r>armS@w3b{>{Yd`qrv{YjJgB$sf*SaJzZ75QmyW4-5_r zjf}AFUaaXy|Kme}l(`5pMEG@t2&EDZho>ec#O)rvQ{&@{i;KkuEH&!FJ_XWhGo2gm z9T@0#Ivp-&r`=|XL}DyGu+MgkY_Z;sDwP^Sf1BN6w_CwaFt%f3JryDp0-36UXj_=w zRfxriVp;-wGhpkwWYWJD3EO%32IjE#-;^>z7dv2~LmE~Q{AJ91gkzwJ{QMBq`( zNr>^1B45~LJ5;5ki6m?5#LWFA3MA_S$;>ee78&1AsZtc!D$eB2P81_2wpaE3PSy%B zZ?Rt|ZaBfBhKdwOO_S{km8Qv%TWZ#3u`t1JuD#88YCD+>r_w$ks9q&jeh$a|p_or> z&#-)n0tq9pA_`{nTue`6wqcXF4rn`r^yGNsC1{;Qj zVHqTY)dB`$4J{^t02!t=%!Dn5VJmjb7MTzuTY)fvV5DV+=^Zqjb1*$e_jGr4Wo6}^ zS$V~Mx`)Rd;d<}?-6JC_v###yqk76aJ1a6WBGMz`kNf0jllOZLO0KQiZS6b34g584f()WYrE-CF<%Ha2&6 z??^2ikE@6Y!k17B?*cf^qdl7mi%I{Ge5d_JP{P68X{r>-y|%K%T_}*0se_dUfDUdK z4j3~gydB7P9Gck~U})PN&4VOdN%BjA%Z+11kc61rerrE8u8E0jIJ!tCFdq%iD)<+y!5kr zr%6i(nLi|@1lB6*k{#Z`umjw{&~b&nStyosxk5IbJw8t5a(N0$009I;0iJi}a|KFj zlVm9p0RRyQhXbKt!0$s!TECA94TPJ3DX7`+m<)vn*p@&msy^W;^hmL@XVQs@K9yy# zjI2l*6mQvem=3%}7q>{r-l|4j)9YHJRj;?~`mGCsH0m-CQ=Wmw^~E9Jg}BXQ^R7;dI;OmCkdoNAOb#sP>+$EF*%mAUO|S1 zR}U@_855$ef^`B!3>?o>suOM<9F`BTHiLVh3+@Xa$>U7v@F=x&E4#aw-rPB?lnt_+ zSYlLd&2z;Q@#*Qw4}JKf^9xA;4G+br8g1JmwA zFc#AR(*9l!r!;e@#6YSSx~9`kL^KwLjXsmfQng3;yYYA|9t#J8{z%9l3J2Y8H&I)F z@YE$}gGJVYNell3AecP{1sS>~Dl&BG)mWLpGDDZ*0)iQc9R_+uYjP+ugl&a8Sq>ZaXUy{P>VhjE0qw zs1K0AR4gD0t~W$rs^70Q&S(VZ<_`hBIT0cZ)Wjhqt5iq){?x?Jp#i$?&*1}mjoJJQ zItC0YQ#Tr9hz7Ajxn_B=K@b-`?nblKwSV+`C7&dEWl>cmuPOqFAtfYu3=-{8Yt4b5 z0hZx-mq|P$VEvCvrBNo&$mM-0j`#B>%N#;+_dF98fCga$yOuYm#yu=U!tYbz@&08bwWrgsuV zFe~MbX03WhDD-g6mipytA5y?hpOs`zego!v-~2|yYXH}Whlkr_XafGfe(n0D6v*i* zN`ai3PmU+&CStMR{X8;b6CSmyj(YKg+>lOXa@issiS!5khyW7Ncq|f)MS?*;LrM^^ zixi6GY&w_C=2K~uenM#=(j@_`5RXP8v0x+=3WkF|pUlvbfJuu7w69=EJ23Y0X~mkmb{ASMayZAB)DnM1dXukZFHzIkQzx_ z(ey6XE|0}q7okA9vD#`95o&e_BbcV+e0Rn!&Re@YfD)ZJRMmzIAUtv?G5vjQ{lwiq zwL9ErQ3Mh%%{b>7G3a5-vIQEHyHX(UU9xW2@;etiDOB|E;vwpkD)qyRag?cKvZV$o z;1dNN_RI)7nOt04oF--yfS4sodOeG_(P$hV9PAJ#!S*Hum~Co^d``8{$;G3AiMVe( zs>H*JB754sGg+#EkoJH&K)dz)YZ5GKwmOs(N?#@8KIRWmK!VtgP#FWmXtjnkzlU@+ z5bbeRL5>+>Te5u{kq>+_7;210I5c%+#SWTQxK`<{1OZvGur^dl^1|{)?hOwg4*&_I z-*5DZ|!0MM7!UjSt9phX2zFCf@}+y<{<9e8_| z&=Ht=qlH7!g*@y4nQS4O$x~@pS&>n`B_57MqJ73u){NcVlg;hJ8*6(fsXRW=&~^lu zC#R-XuCC7Gu`oBEOe7MI8x7yH5TW)(G=6H|I7bZr*q}+{&475#<}l7 zh;Ye%*KDE>HDZR%&70Vps2S9d{u~AJ%JS?AmKgvvOw3G=3{xQ6t#%GVI{<=AHg$?- zG7Umk^avgR1W0pCppH{C9(F-CFw8h7*$=UdCPEI#Y_KkLd)+J&CvyN7GN>edMu9~B zV>A>&Tg#wTW-y5gB<*(gd$87nq0SKHIk{bF(4c)OJO@ufNJ8aWdfm9@cmi-|}LlAOerwN~uEgg-M zmT-18(*3Pr`4=Uj2ASMI=tdOfs&h_owBye7{p6OkDX!Zf<2(iO-h>HyN)!;(hEIuj zQg{afQ+M^GsOa_6Ts4)|PO@k=ktXAbqfV8pDX6_c>n|hJz0U~j*ocQZGE#`};qMRs*m2<(H(bB-lfJvzIkua>{kiI9(*K9k z2oc`@Z0KK&a(0r`ceEP6{+G4Mp(`KaQ7V=2Q|k3T(rcwqC=huDl!4s1xv{siO+T3s z`KS{EgY(eh#CX)F3Y??wV7l19=N#ckXaul8B8q}eiKySN-k~vZ$)qJ~wJPje+rs#i z7>OMd!$_ZI0XO7wg;W~3kTwMpGm>aD2;j`9)iN2_o-D2dJc2*qi-dxqpbsswgML{O zSi)%NQz_~GK$xLNek5a<2ni6ScDuGJ18G`V_Sbzhq@Y!SW}~ASb)3MoJJ16Pq$+u2 z$t`(YBods
fbNk)?@w?IbwU@dkT_N1NYGTemg6j^1jwKYJq$y&2*4AI>w1rjUU zf*YQf9VyRFiKMU?CRM>LcwT#x9!?-zM0={^Z1p5lIZi>`xkLqWdU_fissJ&}&5ezW z0IuBG+uKKK;l}>H6$#5=a8@LH zcThc5_yasCG?)yFykLf8`fvfWe2$j?c?WTzckpmy>=IykzzN@sW}D0t!BNd4&Mwil zt#}nc=jb9E2?xS{y;3Wb%Gpc~K6LhIG#d&BU;_xpLh)Dx5`;j|M_Lv5ai>J30oEBL z43y7gRgV!WSku>JJF0ALA8u|RZEYW{UEke1IHhbTmy@Su1_niG4a-e3P& z;ona9|8}PS6MxgX-43eV_}8D)Vs8vYI6ORrr1l-=hSKeJF`wJs-rL!|abpdR0R?j4 zFa#g!#l@-BrRka3akwx)H}3b}8z-Ifw6vEeg$@qe(~|g9nKl*Dnww~~nyHh__3Ilq z);4N-?UK!x)w4iMv(?gS&C`78G*@ofh7RXGfspw67b6%iy*npvt4+K)?s9Ti|()BjiC0`Yc{# zDSs9IagyQzL+Hv@0l~@ejML%7K#eqJo|FI>LL#8FW{&0QeMrNA;mHg`@AM>hV|{Dw z#wIn7z3t$6=hE{0)vH(L=BKd}!H^jh0`uX|5Ea)x{S?3tJqriWXUy7dllxkJ<+AqW zzxmb|pZnU2FKymQ^HbB!Ue% zrI|`)s^uyz(MO_@x#V;LU8*9Xa8TE3rzhB%NM~{fw~jV8wi(hIk3_|cDJL|X>S7OKMQ*XJ#%Ugp`4j!z1~e@Fr{g7jN)^T z@MwG>s8^!G%N*zo3}Fb5d^`dp06c50JIw1)YdbF@Hsqxh=0*; zU{RXFXw;8&0$KEl0)X6_fy!W2Vw$?PcSIM6D0+N~L^uSpUxhqha&SBa3JyAafRPy+ z3Z$(75AB4ok97pZ0~}!{Vx7S%_8^$R(a=JvoX?l?`9eCK&t$SjjduF@7!ryju^8II zRWu!2f$-VP=B{760bimdqPp5h6t=;5B8p-vE(dGZ4$nXVb6=RC)9LK(pY9!;?ra~e zukT!2+bfrJT4Cbtxm=giH8VGZ?o))`xV*aJ^?GTeVQy~jF+_NKKm-RHWSA7=_{b>x zm6M)Bb^id@{!*#6-DDO=gioo?503FdtMz|;x%OhZeyu6J-?}~12@AiR=>6WS?ap@X z)hFC{WEi;IAA27OFyr2z8o&41EIi>O0geBO_dR~=AO4{z%KJa`;rD;&ED{_Y9Z?G8 z*5=mQ_3NqAQ%!Gt>zivYzHoCuft;F*udd83%ug=NjV0%&VzJ<*djxD(x?US%JK_dJ zSx&0Y8&AaE{p3~jq=-j@;h>$;k!`1M`UAf4$x&NC+ALMHOe#a=8TR&%UVQP|fC3qd zh9gmwXF$IRRe~g{ONJ`3#(>Pn9_>Gn$^p7d8Ah#CEEh}Fe6dn0RZ10|5-JG(=&_17WLLbx4HqlYPw z>0)oq#zKR_{1}=;X2CVi&`(?{H=l+ALIS7b%cFWDlG>CC(Oj z>=UXVebQ}mN*ZYcQ30g^F~Tc*#$piY1yvI9**Q6rv<+y+5C8f7UXJBV95Qea4W&j| zYg9F(tm(T)nP!t(bvpunH5l-PgFg5~ghD|D!Xz>d9i&Ksu)u*61UR{X{}H00rq}bi zVm6=8=SqOE3;6(e0a9^*Wn8ILkvx<_?X|6q z-RHml9ojAoh63=hMYR=los9+pzM+M5#^JTQoR#gJ!_BS3t)0UgYdc#zClpK#w-o?= ztgfyuEG!@qVSZt1dg}3HNJD`xs8LCn;Yvl*Vk|8wc4#)nUmw(U;Wkd0}ABwm6_!$)3Y;U!I0|V8C}y(iIfxV z9k^UBNJmD;5>LP9-3j!r3{$C`;Ymv>(qO6XaI7^!U@0<~!H_=?@L##IK(q2rw+nC~ zP2?jp>HLc?zDkMlmI`Df7>z|DA%8FwgiJPDrYK? zqQ@)IY!z)SA=#@p+GNZf=iMRKY}qrJRAD+1^wI%$?g5+hPM!;@GJIXEMnFW&0HR43 z>91t*OrVLB8Mxu}SBLbRJWX;+p1~=3Md3kt13bqE6! zL2$e9RWdAUVby3_r-U?B!S9tO;z0lekose`%@TbgGEwM2jOZX(3hVu3R={C$$TL92 zA_6&lf$$hdHH_faT&vwKm9;{pf^MsY((c}ImrfAKQaBQdMF`0kqI@(6m>c=LxpF?2 zPiGNBQ+}dH5Teo0^wjwK-~TiM@sX&TYJCzkK-&+478opSI0xD(LMT9v<>dwXI&?do zY_5ny&Y4{LH2sZ#{5Ji#(a$vn4L+X_*73nfc6;;I`ug6hH})E&u|h_&8CoQeWNChW z;mVaOSjz-Vu&{7H12Up0KKtymZ~uwMK0s>t3=Zc=-ELP9q&Hn$=gs(gtjH2eU&h5T z)|SYaYhTU(_Q~b-(x%5j_-tmGOx*OjM?P4>ihK)oliogu$KzRj;wpUEnL**j@4WcU z=fAOjnfE;3zgn-7Rs43_6hMO6pmK2@X~uNLKkO3#cs$T}^AP62Ob8a@yWQWEsFHTzC58#6U z4_}NeU_%pV2yexTktu2EqIOA{&&kDtYCuNn+yj{nLdXls4(Gi-`=Z+oUlG5(u@Wf) zIHi20mMiPol6D#N;p4=|OBLLn*Xn=BS+I$@ZT_&wn2-#F;md#aV%MAaDrL(CoDZDU zrKbdMT-dJySdj!5EN@&+WF~+msDQRtSd5UCL=l-fKpjJ=i}Syv4&yeR6u@*=OG$jYUVsVyJRWxj`&z z^8-xU6W|yJrRh4XD~V>BdG3=q+(2-;T=vJ!Iy6nc_Uh)fmv7$KJorz4{c<{81PsTK z;>KXa5uVxD`1s1|3IKv6ae5dT9epit9LM?n{QUA-2dq4H{3s?WnHS^c5z5^iw zcVQFanyo)ae8B#fpNM?Y-}&5sEPdge84Zi4)$WompJP&XJS5k>x9s@(*T4SA4Lv^e zqtR&W?d@%EZEtUF-dMl6{_1tThTA3C@T@6z*!Yw{*duv4N3T;ibWLl+-5TAU-Sojh z_OHJD0=YfAv^2G{FqvGKN+u`fXUF^j^idx^1|crY6Rw z#B&ZRj1T#7)o5r&(`X>c;2>Sh5z!=BaH%9`1>8WT?^qid^oCv0wQ z+P6(som)vWlA{@c1a-k0Z>o{;eIHPlH2jj;{Ccx-tI|pVgAtL`%;bu>Y(AGS!S{h60j%)R(O9$9K@LGC2P^;9{vlk3 zv_6i*$*~CfszlsQ7d4hAy#gwoYJIX;d*Xl@Tzdy%0RWV}-Q&%j!=3HJ>+AdLHxGJU zIvd4NdJo_OMV4k}XP*AP_s$a&hq<}Ahhpie>-y(E|M|E7(4#p2fiS}@GK{L4&pr2# z*0t(ekY~O%sjcZ`g0KlP=8YTGbg}u>^JaBot@$S}^tAofO8_uc&$}LsR?_*x7fN4@ zs=vR`{cpe2_{1jyi<{+N$vS`Uht;viS^S&%7Mtej$q713ZEbIEZoc~JtEb1uRPY27 zpg!&Jo3c0HkB@s}BWgJAi^N6sc8%3et69yZ^jxZ%OII={S|JO8cKycw=FM9S^A$R2 zsd%N;m6_$G8EQ5$H4$UAWwh!`9Tr%*=YN@P2tYy%osmS{aZ6ba$T{^Bh9RK+8z zs*nVWv63Vc)s4{LDxJ#`vx(ikLu!W&e-|68(O?8EErWr8&*>D&h-SZIcG;e25@#x8 zF_7W`JZP76AFMHnUQgF*1r5^8ZrveQGS@d=KC&`+S@0=RA`-$7qM$C5X^m3!9VCTo zw>rAfs2G4Gu#J5yQy$dPi9Cbt)By1r#cr&vymzVoBm6kv&!KUpEgnD=euf9=>`b>mavDpj+TDh3ZtdN;=+Jz*+CzT)_U!}HIxA+b9Gn)*L zDtlr91!5k613Csw`t>Bz5?z8?vt8BESFEh*>0))~FioG1;*|qFCFt{o0$zW>=Tl^> zPT+7_Y(p$7n2>6l*mU4oOPz=aA3K;%mrx6HrCbL7J10m0t8;WD_T*Emu)O1ms6e=T z^z%Y%3Dv3&D;(|uaCvv<;M>o?cqUnvh$Tki$V@~6fuE2e&PoMCpxpilcRIHYGuyjI zTbs8wHul!m4+;gO6*~xd!IoQg%_e7;0P{c$zn52%IGnh!cxCB(+lf*6*k`|yqZjx8 zpVjC7aSbkf@_#w{`77@{h`>tl8RM*_6A5k7mOrY00s4<5^AMyx|>6bcYrQ8#1jz-Te4!#w~%*@O?oJRYKDj7$o*JURgZ z8B&{!n4^M1B6ekEDNg*XBe4+ATW2*8X@Cn3+HfU6LGXAcrpMuHFg9E&RkBpjDV^Ov zIKGVn3F%ij9EgO2s#kG4IHV?^HdNQBH;ct;zEFakE|)Ln3l%ErFuw2+p4CS~!bkeFwNIO6u zR3KE0=%{&x&sXq}GC!>!usAr19D+uTP(bt{|3k0rNrY4Y1b__S)k5__N-QL~K9Lqe z5dzEQ2#e{Q;B`b|M7M}Q4tN*JTCH5w3#DqQTv^}Vr+h=F(@A8(0?|kiElVN+wAm5H zy3^78*Z)`b4bnw;%Wa(Ah-X9un>V+JjMDY%*9-YPO%VG-OEW}4dYz75NNc%FHJ2)9j;h&ox6@+ITlF|NCZI~NU8`P?&nL~zj89FC#ffVrWJ0nm zG3Uh?2FcK{j?=KGrAa3+ZEa~f#80&u;6CtoA*#V1oy+Cn`^gF5k=%d+8IIsC4{2s5 zm#4;+knx3rfp9p8CRG7{qbF?KYJKPluOhO&F8p1h*U;~pUDRsmQiG}LCA0DwMK=gKn|uK6;Y5qt}dyKH*8)cEy53Mqg^;; z|JubE?o?`OG&?$}H0VZiP!GU#!XsANp|Di#H0#6jhsv2j_Ct1{7!(YeL;#z@5p7sV z%7ePvJ+wJE=YNPW2>lO5>VF6e0<&Wr`e&@1o}mH+RG1Xi21uVBUrv_D5}Bx1>^Pf0 zbYScy*O;ht>~Pd;tzxN^FIV&VB0$Mvp+W~|RG$~Hf-H);0(K3kF}ffMu~>9uBnn47 z9uCJsF5bmhOafXeptegEn}D_KG|&1bwgDS!a}EZJ{tST`hCzlDvIn=0H#YWm4^ow~ zQLfZAy+uhxw^0ih78b8uS(=|;q@GN#Q+xaMEV)O=#wqn5o*DUBWF$QExzykPSp2QY zao^IQ<>FM=?fpH2EK$Y9dTxtJxYGK+_ZQjUV;sNy&%#f6?($i8P|QK_0Y2J2@IkNr zm6w|3R(qde-XP(EFMa7tk2)72pU(ptKqdUG?Q7Sr?eFjREk!(zb`2m}c@)JLA6J4= zm*nN$0_$+r>w2frY<8IR;bAGC7Zp`h6pti}lES-Rubo}L+ie=PhEb~|c(f6Ae!FYtQe;qJb+bvsV@-lf-OdVmx-KnE9hVl%dPyn*G|L<$3lL;vnQ{l1ty-we9o9GgI33SOLhE+YwY{HUyB#jEI&S28{ zOj_#4A~>0}WX-2kYW0)BIPoNTGuH<}n0HKWmK8*LoFu%2W<@jz}4xPb;^2yWz& z?l@`r+B_}cH5EzWog)H2aG}C5v_#)*)>T)!(df|`Lae>Y9%127yClwdU5J)*`zO|$TnBmvn2lAy|x*DJbQyn~Jy;QXPbX-q{5 zu@AuE!~uQQ5TZzrfFYBRwqQLM`N|(}5&;{o$a$RPp$Teg6r3Jj*c@HAB?O{KDig1@a<}8Q=!f zw0BaHnYG$&YHW?N4X4>uI%DY8G*>hpNzPl$hIl;c@wnkNEEI~^o5D>Cwo#)Fq z{Ob!(2jYv_)6JK9zDOt#h8$6rNJRkY3uLu+AsY9{Km?9e0s!a|yNF&J6G8Z?*JgWG zodLG&a-~`>>!nJiRIZe?dYh<^IapJ6w^dIkF1Mm;&tWzMcfZjzJ))pB+?k4_*{x^u z+N};xBZMUIUQtv;K@kWc(ajGcP0#lG=FSru2m$^Q+;C_ALo|R0dZo!&fFJ<(M!L5& z;^f($Zd)OopCPnt6y!TwBXSfd4WR*(;v2i^j^f!^r7`a~e<%qdpFBMh!udn5#5=JS z&}sGHHZ{~KGAerGI8&ru20?K9kv-t``IJyV^~w?tKn6B5;)P615P3ig9JU^iO<+n4r?i&M;YU6E}zd?f&>5}|4kiMhvKq3;4q4s$^8sU+?O1)Qag94W>c2q6g-#gjZIojF2b$xyR zrcEux8CsiK==b|qR#p}k7n7uGFgrW@P^g99%g5dy{i_dr26;%Ie(vCZTv6Y`GkI(V z{bn5B{N^_ymt0+4eS4lBtbvo`lb!7?^j{#r_}_+fNX|*s*<)Skc{OJXbvclE6dX>S7ztt#^#fg)06RwDv*^* zHI+gsr%Wnyno7eaPBmcyp}+`i$s@72tqDUW#i<=OL&nZb!bLzn0YmT>+^yAYrcQHT zf1$uJjaq3Zo6XUA3SxvEjYUGCNH`h|27>{&lkZ!d1gpY8(SpP5SG8I?moF5`gMe{F_6l?gn2jbu)Q?;L#1gBr3*TGqfxc_2j~3{ zEr#I5`NK=4lNj4Zf%;2n!=ejT8v@}18R)<^#QA`S^Mge3*Q~d?x?$+V^`KgB*6Twy z8InhpMTJNmh?1Kq2oYrsqC-Gjj#vkELv~=KC)_}XR&P|wI=uMB3ZSuSjR+3HDft3w zBp3*V{Gm`V5(#(}g%lRZ!(j&j0yR%u5x91zo6i^W*%G|(SrjfD2oiXrQJkhh!;yF- z5s$dsHWim;2I_?LUFOK(CG8QEO639HkWz8!;tYj@BZ>H6ar*u0@XOw5cWxbJwssD; zw+=Tp_O7oV6bZGE6jUr~As|Em0auon=NAZyO+idmeb}x!*wdFOs($D<*bM0>L7d{pG)JJgt zX|{S^$)y=>Cl62Glm$nv(dQ_?&EYK8TqT2R_dT_?v(|K)Bp(%AILoIH&;YTSPWlnQ zsAhL~{*bf@e4 zoJ#aRBqBvPanm=61~Fk7QWQWy0qdX~Lk{JN7~*<>OaWqZY;vpR0jH;e|Lfo!&z&E_lR3aO%UVN@{+V*I8f1D59*OTAAh zEFg@(vq9d0P=Q_AIdeQ>Y}2DoyFCyrN}Z-*MNx7Ljt)#`hz`Pn zw)_~GVTVTML7@YZhMLW$p<@q%))I)*v|UTU1_VHXR;^}e)n>z>y$Rmsq&x=Es|vE> z5k!`IXe~O(#Q~`_Nf)D5Eo-?{qgv|JYi&bs*R_7HYZqo2DjUb~j=7nUt4}0XuFTCR zCuV0x6-B!HQ?`q_*5{5^dj}k`e$V{#&#%Rz%CjGwBKx{YZpKhwOF$A3=Qq~3uf1|( zYip<1yTtNQ5V)}*!*^4&(YD*k>Wyxp(uoCK9;YK;>AbRCT}{SBb+XzGRXQQY8R@c^ zkJf6nU;DLRgFo^we!%z9_k>UrGl~uadaaWwwkP7^r4RM4q#E(N06OgDrE1%kuX6p% zHWCyC3VBCDDgdit>886+S`tuYHan(=X9q(H_nJRs==@>V>=&xFR8h;8wEku11gA6- z@r^=uuZpOp2rn&0R0l(K2S^;|cn9sy;{^v{zH*#pY=CD^g^4&KY3L%qXK7WyL2Cko z`9rck;g_fB?D`G#I-+BTw?7MxUs#xV;$15XOLIIyz$|OY7NWiur2t!$30v5BsO>fE zf5_a`%vV{L=C=8YCv?-a=~O8(3WXjArpFNB?Q(qK3txCM>592rZf6UR&8@AqSFi8w?NJ=S@jQz45N@07 zRfA*G!Niy^KI#j{q(B%K0~w!#7-`h1bxp%|Kuv3tTp4yNKnsH66(mK#c7W(~disNy zX9p|_9jKq%FmC8|It`kal`(t(%*b__s4!{ z#qamfaS5YQ&!+QK+@5$+WGTau`dr5nsEzMc{B5C0ffESb2}Z)c2^O3qtS;a z(d{yV$I)!{dyKPX28@nWZMikW)M{LY(MwkOjd~|3lNl1B3Yzw%zFwazlf< zPYsPk;{2gc@+h(-xm~qpr)Jd4wYpXt$WQS;ujogYBgKbCN3vURvs9~qj2i$< zAiV*T;}8w>S(8`=!O0+gu?!BVp(52VVwrBQlP_qwTp^z;!21I4PNR-1mI@NYW05Gl zeX(%0s>82v1UH?f;^I!HGX}pxt%4Yef5*d$B%9}<0CV5|hp;eDPIKGaN1I!>;A?Gd zcR(#1RxO;EoLpX6O(y3OqtU0HeqSPycn5FA)W+#ipesIx2#>1>59z4a>-%WRytB2r zxxRMe#?AGbPEF4^lA986;B-aCCZm(Hq1dP|F&2s@oF2jKQ&K$f48WE)V_G6UrZv7t zE_6EGMzyR%goeI377J@q9 z0Bf#6RxV{Y-n$6V>%oHqR=_d?ME6>ao)V=%N)XrKl+IHid%a#80SaL@=l~0}9vvv) zIXDwZ_PS+KpO6*Deaxm>6v%u=&!@}T6D@NB4@+a$z-SJlMlw0Ex;&jsPR=LC7v{zT zLEl{lB&q6A_i31NjfrQ*^ovRp-M0g z)9m(9IiS|88t71^8I7|ULeg~b5;Z3opaa@$T9YGiU#-#q+Z&DlY|-PFiP?aOG(*(f z>h+Blk{sz!V)fkoA*vR_`A};EL4Pm+s9xbY7w06SibTqQ)CMf4L;?{^`ct)9%K{+Cm$2iL&6kQLIu{!V22hp| zEl0!Acm#!pNVCB5WVYuI;YF*}>gh~2bDGU$;JpJ>k?oQt?NzCs)I!pw3Lv#`VPSr8A(@L7ppupJNd~|#!IzAN}8JGQG>QIQZwm#m9SOfG> z=a0m*9+3j>nq-Ea>h|@Ct0BX7A-eRbJu)_a`z+JIf;?o1x?ZVZgl;q_fdIn4%Pn*O z4%itvr1hfgB}D?6Pzyz>81v9ymTs$sH3maBG!4Rkt6rxk;1&d@N9?v5&AL_Kb&H}s zNg=x>+2s*l=j^3jlRye&HJ{c{1@c(SUrvEsUYcH6CMu9~$c<7@y7C6i8PnAp2#9lhYqk+#)X}V&?pPiVnlGcHmE`ftq9OH;2^1 z`Gxs~@fr@&$j||rSdENYjh0V%m(wjuon~{mj3Ihe z51}%=<}${;>l~)37jwnq0~C$UrEBF}yJ3+nAZ}3xA4FAAbca-Nd_4B#dp{z{-j94B zF)|YKcs%#)N(?@~wx^}VX((44FJDUoIFLox>QZEGCg8%N2xjI)^1!TCbkxWr;*!TF zsZy~_AIR&KAgDCzP5NVEB#x}QNFWpphJ!w*+sRmymUN!7Py8rh#dHbVlHh|bth6?5 z7{H1mE?Ka&`V5tOG_6{dU7W(Dg#UN@tya5QYgB5Ds)3n3Ei?2P2dpNC+3xl%5du{f zeF~`)ND=@%r<2YGas&`yL!fUGH3P!BCEC6?ihy+;o+ojdAwq`)Dd7AeM+Xs2YJTLP zbvKSUBmv;-Ws5}|G02rt5TrACtMVZu#-&XGIKq+8=vV^K0K99lco;yZ?LqEfsrV3W ziCFpr)`TG?NZ4q=ydMq$9PqJPTi<#4yEoT2_V)H6O(^I_i_{~KSxEr_Tz0x#@pwEr zKmYD0pZws5Ka@-+A5#m5k4IyoVd(gopZS@OfBfU0{`9BcsuOr@Klo-Gxm=D?n(v*A zb~*)0zD3?y9(qT+_z+xyo5H&|H|W8Q@e38&Yp*RgDX0tq!jm^ecKfJM}BR3K!60RjLF z0XG|rP?mF<0U1J+@stFK)D=YOwNW4kvJKeF7?y4Dc*6^^aoH;f0;)OHG`(D?9&c8P z5jnnWbhEbF*W^6v#VSPSC#&!TQ>b^ebyA zQFJ}?zR8*C0LM87la^#q(X5s#fDEX$1Vp}asX_rqFocHJ?N)ox6whVzRtkZgc|H;e z0-7=Hqu1{;CKY4o5u|`sC?eTJG@a0hf}s|d#DQY4&hQS5$=GWQD+={av(o5R>L_SP z&8X<}QUo{Wk~|JxYc#0jqGmLRS0_3YusrW`$%5NMrwmAG03`<;IBdYu`T>Jt0}iBv zSQJDjks;#AxFWeg8V8heK==;S^2mhHn=2G^xqJ>Cj{qhV=qaHfK_UjwBb~|7Rze|P zM5{~!!Qp!>&Zs_>+Jcc51o9^=4gt&9HXpXM;k|%?MJ?Pp+S)q2abx$!#sM`%9@M2! zS&8Q$zwEItvsH)X$B@Z|qvPYF!^6M%>%VsVHaj*xe)Wl~#4dSZZa$evBpyo5?9n}7 zK^`9;w_2@7<%IwEkN^0)-~H}e2oWAv5#EgBE_B6QHoJqP21qWvaeZxXZ;y7eojl(q zLb{N91>>>l#jE3UixYDTV^hi4*aQ)3wIUOlnj;rUFo10rwts*N=vSCZWmBiMT8*Um zTr7dfPAD1!>=2BE+-?uaLCqco2z@I*gg}R$0a@4w^QC;gR4ULSfm`tS{6WR`wWBjZdXL1Nka%9-vI(HWZpDai5wWL&zdcH8X+WnYrJ*KOGb&h3&UFU1^` z?Rcj&4xWyV+6?K0*SR<|@dy9w?>9&{1f>kAGc?0Q!|KXPa%pjLHaW2{H$FZdyOaW% z%4%PGeqXP(-@Q8Wu9Y}|1JpKdHS_6w3aO6pg`7ugN>dV0d~YO*`ELxh7TivkCD@Ec z*!4^b?JiM-Cz~J0`bx5dH^)iKa3~xI1pM$<5F*$T4JZwb8qq}Pq1)|~_1HyqNb+QG zS(}|!yI9rAC9MpYv#OOUHQI4^I-Nc*N)f2C1h1STy8sV7_wB;Rp9+RlzS}d=X+mpi zhEdVsLY*`<7?;Z#@F@YG*ROg*0oCvG!ZkGFJ4kbZalpsOL9%Ph{E#7%iHrpi(EJDx zFlt!AO3xKC*+Mp(8x|yp!|Q{_2H}x-#N~2P+zO9?GlZD}dVpmtQ_zNC`FP=Ln~1~{ zal$u@h=`ld%^zNh3n;Y^(7@)_t*!0D>(_UWPcoz%a>i~!?FWBIjgNc7ac?B9hU0?Q zH&jS#>xE1OR#Yxk$(>Zwsb0r|6!7QhBe*@DrKP2nm1Qb~JUu(>^?JXjw&F*Nu6T5G zG%+y&DA2G6z8*t_cjhthXrRuA7|62`Fsw?=TA;(Nkf#Sk?>)T}nyg90CqLD55MQ zERY_iMuJU&thFHI*K22g6e*C3Bzqz9!`sv_j5;Am(q;-dB{&(1auBI-PS=Be0>_zR zgK=d{380yl%V>pEC6m%J$Cpwd=jO(rSe~AnpF#>`a?u~I8ls+y+LZOrHMhJyZZC=d?& zQO?@0I#AM>r(Fa}*QivgIfTB246OHTVIW8VxCdtqhy)?LN`N~EZ{S=wKR179OA*i) zP^;?jfG9kWMr5ALRc7cr-Ad{p@Fd{^x%lE*u^nLVoZVBD`adMx*hSzyJF${^b|H`Vap= z_xcO(10(wb&wk=ZKlrg9np(JW-^-o34LX?iAUKi_NQ2)&hZF4Evgk=zx_RxDSFgQ% za(H;@!$zX9C!TyNxxAuyy;jh-nh*8_1St{IO{PzZ$p`{S5rU+XCUFt4fdkwd^GmEe zn_a?*=vjU0UXSqjAm6RmOSyD0eX3U~m!1-2_Myb6FC2Ee#X$#RFdN=S78t`^n6!Ld zsIJx2O2uO4v{o)(dIPs01mh#VaMUe|_gT8Q^bpNG; zexHn-K|)pNb}eG8Y4&WE0tR4C__ye*%;>y z#eA_bH4;}))I1Il;UVrq@HzuZ(DT`9Ayqy(EN4%;%?3RO6kwoUtUNz6GyB97SLc#* z3kxWy91I5ENn0@_Y1gh@TUl9A6y@!Iwm*7o}Pjh*eCx>Z}oVKd6G6C`PN`CU^B%i}Z2_{4O4VoH*g`-KRDH`8wG zx0=mN>NG=&2ieopbn2u*IPHQU#70J<$eT|@V{r%1pB^1%NN*yOKBbKS-pR)jqlwWG z*hEncE*x<=d5q~cgRxH?gt|RC0|5YlwZTJ|wr5HGphszvgz1LAYPTwtie4#c_`RxY zW!lK#olaybcp+t1;DUo?u+pGw*qhMxZpU&Ugk)V-eI7y`@W?XHJNp;b^to5*KJ=X+ zY%~pn^b2(OTTMeBB4Apw4RjuojD6BcPOZ~w({_nSD3GMHfc*vjL8izersiQfN9^qz zF*T{8gPnDvR}H7sYd3n$Mz7oIHfv_n_`y$n+#d*h>5I=D9_-Wp4po6%U7nerpPHY? z-b6eRzMu9p1qW6vv;&|?{-gIct=^9{%xIEXm^@+KZ*A3>CI3j3- z932epa2>o60HF%SYA#ni*gxFZ*rm?e7fwl7URj)(nZy~wP>>2BF+>%NvIPcmOvC;K zXL=0GeQ6S8v!(5w!!6V#IJmyHyMK_fR397;i(*WQ1RmMPc|_hLIz`2e{V7Gnc@ay4 z-0_eSdL-f)gtcRXo8a%$jsY+Tk$ms-IU;mLQ_8EYB}2%q5dE zGc$Lh(>`uAJlq4|vm{CIYP(#n4}IuEfAJT8@fad}FCIrnN7Pbzb7OODZEawV;DE>n z+ayWd0VT{VUY(p<7)>sWPbWjs_?*lLTpd>SypDP%41{RA>$S`UvzW3j|Yg1~}! zBH{H1EID90FJ~u2BH?A>0kQYjU&){N!mO0hs28SqCHuUGa56jk+leUjpJxjkJ}rXdPWOc!k- z$UeoA)1Nr5hY`3IBf(4%^MfK#K|X%@zS_ z5Mu;Uq_Pc{IznBt^Ac1+=?HL2!xTu$khnVqk~8}gOuod(Wkzf_ECS|5ld6F{6a)_^ z*`Rr|mtZOmv%ghr=F%B7o5;e~Nyp9$2S(U#H@~njxw^4_ z5=80fP$(1*NgfyA1Tv_LtiN8bgCsoiXY<9{XaDSlpZ?J&M-qOxhP7-FkU(H!^S~sP z8;4%ibNNy(kL<#Wf&{U6G)lhv{oX>coXzAjq+OCqXDVf4J%FE!NIVgZ#}O)r<6+gS zoVP+|hP4at^tr3oo4b1_TRXS5HV@a=_byTk@#(wW-blh98ATdFB(8*FyvuU^Xaj5~ zJR1s6VIfeM>lOhgAk_w&Ym(v;g!@!XvUxUGwJ;2=OAtTHIpEpe z%P+rd7{*)D19}V*-d+bJrkk4^+dDg38=E&bHg2x1QL+LV;jTWJVepiI{*Z)!4c}V5PNBuXND+{R7BG0_5l8alTpn2 zw2%Ml+EKAmy~uV%{^n(;1i)g1DYJ~3W_)e-+^*3!^eUl1>bZ0&eXN(VwhH7~hdUfr zmzU?3m!{^D6Z5lU6BF@Ex1MghlgSm*r&ub-@97Lx^~Z)nJUW7|LTDifUv8I+Ju?%s z!)YHS9D1m4Y}SwhnX^DcCO4o!%8G;@MbQu%6F^2E@Nqmq23()ny!P+^!&iR(pMPjH z5wI+k9cHuHK|qkhegRSoGw?Xn&rpONpZFOf*#g!hZ;@0iHG;wXp;Z)NQQIJ$&I95> z8Z6Bg1^46_uYkQ}cQ47UD$R8UAGyurJ8;T86 z3-1}@n?&S;E?4;8CFCJ^6>y>2FEEWTSfb(Hny*%{eH-6(cKJ%H+ zBoc|Io_gv}|MXA4@r`eM-~%6c3=tk57hrFxynbVCduyAHJRBU{YLjh|=XffFi0`7) z1$$6pd}?BTY2oUVSDtv%t3H5#=*1;KO$cpK7m6ULjDZzqTFplKG0ZyK$9GVwfgpt*ttDVn z!JQ0&KgptGr$sGfEmXt~ zq@$UK!fBv;eS@e{mh;(*r}XR-Gw}V|i4LbkN(J&g*^Y3}1XFe~-BTuT8$P(~1bRlP zfS#6x3~ce0%yF}JDFt$Lb$NDdH0t+Bf}4Z01wc43t_+2P7&S4^jt#s4Zxd;-Pywkr z*sjnljmaz`IufM&R6)q>b^FwZFrCe2Q#mq2NST!u1rlPsEUPznOHZwiwis zz^nRt3|Fsras_P%wF{3fQVSsf`=VpMXhH!@5RS{i2cs6=Be3E4j7|q|>eb4?(1bt) zlk#d2-=GYM&ut@7o_|%QpjHKd%y4d78e(j z^GU!B6O$8f9|~lv)jBvh7#|;h3&n`;^LX;fC+FwqUwY}KAN;`|{Oo5x`%Ay{OTYP> zzxfyMEn=^vl}R`%qiQZ3W0h2=O(XM-OmXBH-xRwicWC*~GMr)Je) z=zbu=ZL~-8tU!MT7pmnl4pp8Wr|2wQCQUQ)Krjf&S0Eg&mP#kbN0oA!1YI_YmE3qB z7>ZyeIu5(JHRwPlIw|4N7IVb--z5VO*rV?CC?T?IQ6#AlB-Mw;5qyT)R5MHiM=2`= z9B4J9FX+}tq~MVy%-x&K2H=LqnF^%nf$Jp+QY#dYc4Pgv$J$i>hXD~ffT0Lwf!J8< z!v+u{iakr6W~<*a{`0GoFKr$lWJ*o}PDgRWDai_81-B^Ni2@lht1{CBe9&SaECA44 zvxc<2<7zfluN2#c)^6yu%s>LG#ddYMxzUmELULktHTj+=my+`n7u(MlbezsLCQR#9 zWCuT*RMUXK1#(~0s$5aT*=c7|x$Ui;S6*4C6BD=ZQ!FzzJ$3boE0dFB;c$R)P~S<* zhS33MKCnh+sguK*Me=$7L*|~QN1b+O|5j>abN{86H*T!&@9muq+@c32Uhq)7AiE^R zC96s>s>Vi@Kv0&wScrPq;gB@NYIKgKPSz5=-VISsQqar8&^m-*L}@V|%84Pp3FpJ% z4Gi8aoavw$0@mbE%v1-&P%Guyb-k@uTTPvz+ATzolb9UZ2??(3=tk54}8>WwauFw)Yd@LWI2aK0<$0z-zEjqFY0MIkY~8Nr{%x^qKOVzILSFMfUqmW7L#B&e)!CK zfYCP$!61{L!?Toxm8nqSYAVk_`_^!mAfsm)wZ`6K>xWYUL_lmZ?&e7WkK8i!Y9XT? zZD_?pIiEK!Gr}Gpi>@xuEG$eXlj95XlZklfE+y;RI1K~oXy*K+WwX`Frt?{%F^ncv znJg8D_6VL>ETX8P?_4iF^WM>Rqnb(QA*UZ0VJG6TXd;>*ZH{2bPoEIQ>1l{ZRMH6ZusE*Dkp_t?k!a8hF4j{1s8)$x0 zwCAzAS8hRkpz{7OO?B9R1eUjGJ*+~TV#9`Ka4)OFMT!mZ2o~S=+`VL2;de$bw~IG8 z=*O95@szAC1}t(oC7oJ7@J=TZfV?Vvd_=ETmK2`no9(uiKdod=OSx1jeOykTFxD6j zM~9*q94GOvuC6XFEzU1srQyw_Kt3uE;d7t++>ihGj{`Dz=9y;zB3!+C^{0O7rwWBa zAP{&A5gs3}_c%H_+95uVo0~|1JUu?XNP&z_OeGgqCz6XJbMsTv$v`YYtHwoKKXAbx2wt4Dq%uwpOI(>5p0q?`9<7=>K1m~DIE6n^ zEavG(L(31L7!n#{kvL>!sPE9X+<*WjR4U~{E>p;53%Oh&o2l4Sh^o)$LuNxj^#>I| z2BL%n$6l|GYQufI2!T40DB?sNCkR~VS#s27rwxg8#Xv14&Cs-F-RPfDAW@_lHhV!) zJRWJF0?C@x$r>vcE!(7OU;yC}MGxs0(C)8GxEl@|HA`K_kzvoZs3`?<(1#wTK*l10 z@0*R~>So@Qg!2^0fw{I#dDEIkeK^+~1PQkw-YZ0P^g@=JO+bQJ&7QO_qd?9tOs!r4 z#4xciH!+tSzq=7Og)D^vni^1xsbSNBa3q9UL-82W2;x!I=Y<86%~k%*zy18L{NfKz zjE5=GMQJ0XGGx=INFC6swCUg^zKBtBcO3GR<$Ih-z24l}J>J?r+}=K1ySaDs<{hbp zz9?!EsNuLb9J^-&h?b;4eM5N>HVDX1g^(?h*q z+J_(_4757IpzvRho(=I8BHazRZQtQANx#D)XTpBf)T=czE`g&HT7~L5QwpS8lzE;b zTc_T)vnbrYi8>@@klnv{GjI0BnL?gX^}E&s1|g(fH?Brq-EQx1U);2OjIdFnuui@; zd`dO}lLi1dtJkI{J$wN2&JBppEIw4uSXP` z@SYJoaW*R?+e64$c2aoaVL_%#h*Sk?RC1K4#Gzm%T43<-OP(lPv#itMuv{?--4uW2 z;CkJ5DRZ1XJ)^F{pY90sw{aiK)cc*hioJ&}=gKuqcp^3SBW6 z4F2rT{_OAk&hJo&@VmeJyH~DUdCz;^^M`-cREbj9M{GqVR=_GUoVoznW7>N=zRbJ>(N@RyL zCi)aRP~>2f9_ZE7RRAS>@Y$oh6M7MueN<)EG!5WFxl|=nqcn?h@Eon*(rnBZiol-k z7A5#{a=7ErNlW%Vlo)82;gAXU?n8D7&Q|SIf_(dxR6Un3)yik51TWKot>*H0yrD3e zHlZ%I{@S=%eBw+ z-uuk9Y?j){9DJIwW=w&BK*;5A4-SrX^$raWO*tICU?dTZWyx+UsfApDP^LC0 z3}&^lT4|}3YIH}DS~xqk04O0A1!vTtpS)f)W%77@0ze69kSf(;lIf91ct^>7bmluo zXq&}CCJ9M`NH7rcxM=p$!NK8jHAb^StrklaV!4z9X40$z7fKIYHWzD1;g(Y#hg5mk zIK>3>Klz8pB`u>o`~Zssn1MFX#`@TxfQ21jxv&FvJQA{x4UP2mj1BZSMh1dDcPXKP z)vHP>kR2Tzt*x!iEzM2M%^z6>@^evW=!c35trTR zLYM$6H@M4Pno5PqTxBv_ur8okZP25OkKgBaPEWa^(-M>(2n7<8%ymYKMGqqQMxEX$ zmWe51Ac!$T*=>RrW*~adzXZIfhUj%D@rw$hEDrUCn93;Q(bgc6IzdXq^a;1%-ObUYMrJI4Ea!+tOROkr=tIvgFWp~;E`otlY5 zl}@Momw^cP+;h*5fBfTkJkICy%MfAn=FKZstU&0Yy}g}*2uys+K`4-e&}cc(+tV{2 z1+sqOqWad3n);@ire;(1g4q;E^tJc6TxgCbI!+GzH0fL8^LZfHV5u@$023I^X0b#< zIxP#hvw(D3mi#8@l|%*zZcbuo=>~ZQdm0nm2nA9PE<;A0&ZySud3+u?5*O)y$Re>X z#(fgmY$g!!2f@M5?f3fvUN5;6qKlnesX{9!xk4$ED`ZL)3+;q7Xp&!;!cgwC#D9V; z1Oh#AY$TD4gyRQOAjPusRsH}`5eyb79%YG0*&~G)cBBa+9*^X4Z3SIc1-Oj8 zq*f#1aVCn&!$}OF(SlMWUb)VqKuRl=bEIYIoGRFHd|}Zve0s{3Z%;&y5sKWZ~6Y}1vUE0ox5EA z!GST`5ReJFx(CO`U2{?kRmLj0!J^QcWm1qE_aA0csYHnaS&8;a6i6cV0UQ@tyC29=l_aB~qZAE^ zIFrQ^mHsBcoRvxB7!x48CYK9%d=}9}0yAwE2iEN9+g;>xImA#Ko!g0UBpMD!!of%o z8=iC!#MMsA#!dUJqOl z!dPmZ%j4?w2GDo~*0b4AWkF!2Y@}UoWR1n5j*+2>VcX;=`s{lrhWc~(l&%z|RVtKi z9c|EQi7Akcjg50+(9eYc^SS4qi&h-3z4jWqU4{q<=}D#1U;gr!x7>0I0}+_`%*E8? z)F9L)25q+ft}al4M6)jD9Px66EU|Ae)zq148`LHXU#ut;Siwlt=k?Gnkvgpz06~?> zY&MuJ8m+c`)jrTzU!2)#NmZIuVR_sQDngPT&uSb~q5060(-PviNlLIqL={7Q5(R3saF2wp?_X?^@?ONF$jjpW4(Q2z4NFR zD)kmjEd*@f zi*UY5ECaNM&ek$5vD^|#s4614oIq8PSWH6-Fo`AUe_SQND}PKT!0J>i7N5(;Wdd9f zz?*{UG)(=RIKsj~Unm#|_^eA+J73wt-Muj+%B;z{u{PFy`;n zVdig*G)1vn{jox94a2~^3WeY}Zf7dyS-}K7?+ji+x=!?EM<^F&c;ONlejTU*aa4}{ zIcz5ZPFmaH%;*yV=Ec=lnNh{W>K2k@;P z$=H&{nA?xGxL}X*CSrz*X)nBP{v8zpg6*LsQ479=)Y+r8Y3jMfkL6%3HE zMN>@yFu1ax#o-(49?w|}x>*meX0Db;k<r(U>)@t(#+zc=N`SA{6BNCSa@k}fA&$B|2>k0A@5yliB1m?hYIVN9AXPb zhDap>W=PBmO&go*ad#(vDKVJX;;D?F6z5^N>Ql@QV1z=|52nchsTrcjQwin}821Xa z7*KS656#`k4d=?G)BTJ$r;*2!PoHN$W>wB<8?|iGn};Sj#l#yP-ZBeaoGGb(2X#2= z^1glzgiIbh8mBADgwyZ(%+)c zPKIM~T)2iisl)w>eTY#Aj1qMn5CPhG!PGPI^-&XW=51Zwir^z)N!z-Ad}T}pFrd2( z5x<3-!RN3Xjl)x;99cw%jK8&k*f~QrYPAL&QxS5nwxWZX=SteP4RhI_G7bhtZ4QRS!!UaiW_lWDI z7S&#la5U?7!TC}BC-E(~T?L_I(ezP^_5^4x+2FAvJ`!wh z2GoD4j701$uia1#;;;Q2u>tV%X+;uLz`*W6W&L36w^55(>f>Z)wUB2y>=y|tRg%x& z+bQ~C9J+w~Tle1Ge!XlE!E6Q$AiYX@N)x_p2p!;Mx;~yIYr< zCG$B|uymA}o+ltnAtjc#Al&JJBF};7;Fd_hbWE;F%gm4m@W&Js6>0{x!SeInc_kpgiaW^@X-MW% zzZwl0zy#|KT&<p{*toE(X5+1}qq-j@q96$|%HgMF8vLh2v$5Q>oi3-Ir>^r?R{fh;2G<6(oxIaPgSK>E_gGrlG z^!uk}5fNebNIx0G5wC}MjC)PjgW~|aZvEopqa%=wjmhn*&i|~9H>hm{ZU9D?R$m|rv5G-|#)1YTxu*u8M9pU%*aEFG5F;ymx zLX$*yrl!3*W4OL-Uq25t;~)%!`8MH>1~0XT6H_Y-k~aHUv=Y~-v3eJyGEO~dSfH?v z6oo|`MKn|}GMm|KP10OcPf#*=UjJDUPtNt6i%3Z@S-p6{u0^n!JA^mFo^|W-IlyiI z;fIJ{yigPq^U+O}hD{1dtYM7?{Q^pjOy7PXlb$?XR)mb?m6Yb0q2SM-W3UOMQuj2v z%v%x-;>MieaX8UH+(bx~*`7;&^PJ-QOJ5pR&Wkua&dWUb41-#jzc-idU@j6aLn1{G zz^L0cB&t9|JLN~2IH@KdNF&@HOrKC%doX!33wtJOHO56O^O<*$??gN;9&-eqtz$XjkF^-Z2YdA`BpGq4*5p!}H8b zULQt>WFeRol7voy=8s}XV$;S$fl{p5ve`d;GW3t!1E@t^HjybNJ?1H-nSaQ##YQ& zMX<^VL%T&$E6hlO+ZdBYocmUU(V~G=p$rLX@DVaQGve5vY!I5;_imo{X+^VE>*;AY z3e&C?jN($0U}c&9M4}|6sRBQ_V$#Hqz^WGjf5>Tc+Y=%NmqE1J=RH1e-)Ngod)IYqQV_p*vJXz zDOKW(VbiINURChxr6V0aec?_Hkm9^)FUAsw&W2zjr1p=5ks^M*?g#?%t-i&XhzJp8 z@f;L>gnAA^Ftr3_8CJWmo?&jiJAZozAbSb`rzBGf+r<2-eOO1AG?uPZ23@G&M`#H^ z@=z?wl5`RWFQZPBUr4e)U>w6HtfBwi*`RKfBQ++}P(DQII&qb)?%Skw1&R85tF+%2ZWV4W8~Wd4lOcWlWF?4u%a5 zZhdzU5+x$1P$;wm@#aQby)_hgw_8tVvlXJQ1f@MdF!G6)or8I_jl^IM-ss8_x{sUX zS3atVOsiCld+De&YpO7qOhcGSwgwO$3mn*s-Pk1r=L(-ORgXrdS}KWGjusa*oFPY7 z8VQuik`%&=F5NPT97D6XVVnIEPXuF{WG;9TPk5sdn}`F2or@$+@cl?kpBAT_tR72? zmsP1`$1FKuT>i7mvl(mt_yH#bO)FnPXIa5XV#l)qyQn7fzu+Cy==P15{b1l`xdL0n zF5TTJmNKH^mfBy*b_`ITrK!+@sVP{p!1LKE-~cFPdC+hCt5CcOdVLa=llHAwPT_EsDW06rfBHdgex`Cb$doyq%W#T?k64o{dpYzeX-||k zWrdTmD0eB5!OGJ)WCS^gM|cXfMZh_BZ4DNnRFa(KQIphiXbMgMJWlMEd~WV`{j*Px z9G$GDXgwS>UEk061Amlgk{hQlP@r%%LMZw^XrI1eB^Uzi&-~&FLw!(vu&iVS&V`uO z3DU9?g`*anG>*`;G;jwcv)pXtkzw)<)QK_HoX6ZRftZ4+(}bSF7}7$1U)j}UV82Ix zAtxa&AiN-=%q44$EzW=6Xn3!k==Y65qC|oV8jdDtX>Iw^z{rJ?D0gRLSaI@g`RS#) zh47ce#rng+rWmiN_@>rVdq;lobNU!H`}In!DPVbXNtUdtv&;LSMEp-nXV_xg%YnP1 zxu%0}Q(@Z&J$>%Nxs!1rbEaxI;Pj_$4MNR23V&~GK;WF{IZQcp zg5Qmn8bCRXQSCd-4}@fm@|{Nhp|LDT1A9~Ot_Z_)vlm!^*7q}(K7GMTewmzP7FAwE z*grq@Sthf6UJupZpYC9cXcFb{6)Fv>;FB3?RcU~lWL{M8!nh;UdU;eNGN>;=cz6xq z-ZTPcV|BPp zX20nKAy$Oqerm1U?vE_oDD25Ijnp5t{EmH7%2*M~FFUi==u~K2_c37@^~+yK(f?fN z>ELhwPO7r(-JTqc*&ujxGamn{>oXl4gmyh78RN=B1v7YC(=) zRZiovXN`Bt0OwZ0FNTGZw`4#l*yW!;)dH2uHT&FY0-$`V%8+iMl$ih?F zGX^GLn=g#DMVF`-ON>cz4p8VFJ~NjdLQvf8WHVo|Z|3miYEXdB^c9{ zFV{xXnHFL{1B3&FSSno^&u_bYzNz+|UO)dj;>&6afw@Rmu_3)5GQ)GCpjCj+V()t> z`?;W25ak+Igyfqo0ICtMBUk##PAy+hi6Ab;P27Kwj7XnAok(;?9C-(0LNoB=U+^8J zqE&FiidAq1TA*(g4c8=s822AMIc8D*@Ebs43=Q5WF;?N3MZ{;V0(Tu8Sh1S~B>2Xk zW|?u*W#TY#+sQ>ju?R;oUKIMI><9x3X*UV=A5<`KeI(f9UrmLN$oF*aD1%@b5(%h@ zSu)NT1fc^69vjr?anOL0RBHdwUbxyB0@(0OJ#e}ahN5DS25v%pptDga%9b62&d_~# zkkFx8X3izI7Eaw0bxX7=p|CQPWS$%rNzrIdozy<4wAI<^H!T_(SI`cSU?tjTFSG$T zSu<_F;Zgv}m48fmkrk`|f#~@;IQa!Q*&zw!-zI;bWt|*pmU$5OIZ(5srL?m0cvllO z{%h&>1{*6B3Jm#U9L-0!-^Lz6Cjx*zfK|{-w8NLF1c4ku zk>*4YR1*llqqZ_&LRi{W^+H3s(M53~K>pmP-MK z6V-T@3N6AQH28CS=2(FuqpMFLDz~Q=6(ESMQlaDSS8418w@DF4Au-X=LC%auAZ97$q9y!l+hyfEkRA*^|9?; z@s|oi>2So!QbUIbics_}?K*o)a_a_^&Q{$cu(zkk(THNgWev-Z$U^r*anWZTkPrFdyoDWWH_MO744B?nK1JEH)KHW z_UlC#rtdZQSZYsw=FqxDADaYZ2RkVnf{casg7lE|zl|>@emFjs_>0ul+tuam{ivaY>b?O{Z4ly*oM+R0>>&B!0V>m)!I-3+TOLMkl9qm&q%nBC z1b>-w%Lcu&s!8?KCnO0pfEj4v%%$X5Nr-m835PhLla5NeQVRjM+0ajzH1s(nQjgXa z2K)19Q45!TQn(a!x(IQ$YPnn~kM0B4FlVmwFT#FQd zt63y~m@b?jO0QiN$X)bm|9bl7YCgFO{@hDN?i;rdaGv4lU;Wh7G;ZLqT)+L-t`1^w z$0dpvf=sYg(XS41O!3Q}JQz#~`3gztmBz2HG8PtS!f0 z!UlI2dD^g1ER4*fD|@bI7!z)-2?37V9^Qtm6bpuPrE3&y81*JnvtrytLy44IbMXEOABfk2X4wtxhWFMN? zJbm>T$fpnl=OTxRWe58`RgSS=3pSjz4WZp=s*xuPtYOJJS9K^D94KD>X@ON~$o!!p zvGVKca=pXaBA;lqe#EzN%f?XDReb`kg^tSh6zt~J- zn9?-k{kjga!ojg!4r3qoqV$pYk-$8kn=!GsV^xR_M8D?Y*X@*@z5U(mTQWp*$B$Er zOXS;wbiKH=w6r5$0R2{5RVB%H=jB_9fe0x?nC{@BO9s+lXp4xff0DXY17xofG`j|% z?7>tQmVFZ)rHldnbPzqMX?-Wc|qSmrf-j-_xlf)PVZmE|1g~0Qu~N6Erpt;sU=#VYTC;imnjo8*r*ov;g9c9c~Ftyfs`Z} z=$A`&sfxI1%Uu42m}JC%=WLK<)E`aN2FO>L$j}gi4Ly-m718EriaWgk@}eY2UWQADx&FjAZKWR za$p3!UU>MYLOJ?~0wS9`St*SwZpIp!VsNFae(n??@sHedK#?12{RcGOX5=ppREh3{ zk;D6-I%vVf9Q+_S!D3{VKlfHyV$sG-EYq~g*mV&pZ1PhRh2PT%VfiTBYKCub_KH%@{EHTYI}ORi(y}xB|i$mAd6a- z{pAMp5#Pu4@GTg@O4hEkMpDOL&d)ddj=!#dJNn&bn|!=1Z993QAO>OJ;^HC+7HoDT zWswO=&xCiI_QSxD44GYTzCZB6(Ve+>i36UrjQ^`j@z=uEfJS6S5S-`Wq97_Zz8(Mt zFwjC>`+gD~Rfrii3y%?95fBC31$7)`K4-GfhXQV-iiN210 zY-CKA#W2m${ecY)>mBaSW(D+D;HMR{K_eA0C zUSL&5gek-_l}wu?jwqFfsXIEnh-V(c*#qc{LY+p()QM(@FfwV2`VpDmc5gKSq15#j zG;~pVmzikD+ma1hQ8NK@wNN7FnK{#k4WLG-Y$A#s7?J47Vp61zl2j}s0Rb}62g!kd zQW)qI^<6gfTc|I-(09QBSxZujcSz^Q=ybvT6k? z6cqSq_yaAfcypIgUeRUQicr(L95Hd0v!gSRgAvkOxQ?Ba`R-xS*UPzBHTt_{^Z0e| z%WjA{XCKehp{npTFobl5l>hKI5(m~1yQpX!EAYrAqyY9S@7YSzVF<3ue}xGppBL=t z;regfLFla;8^+m_GLYIL0{u)gEIo5IIJKvzvaqz+VQe-nj#e^qZzeSI+Q?u>LiP2} z_`&Y_3+T-b|7gn9io*|r^FQ`xfhlBl@j?xCzklAP2ofPw>${N zN~IE80h;O<8DM(>*?t&7ykz^H1hel}^GJG#y@9DL5q$@6onN{4Zo_=O6-lvwhY&q~ zEp%*}aXK{Uar$?Nny{9g00ilZpPyIuOn7s-0Y#x?1RR1eBcBMs)O`jp|N8#|_3Drg z3F)hv5gBn%est$mf)jf#YCU~0^kKut8(Ldinp-j_w2?ljGBon`270_kT29%4_KNTiOHVZJ9!m+1tk<*pK`!D{GB=u(Ct_w={e6qmaO_ z3}*5IV#2@n@o)O0pgK~a6eWD{$iDrgs=DWO{W8zx4@0VfAX(fSKNjb5xA)`B3>I{> zRg*xff{`m&8dKzMW@LAh9V-x-F7C^6c{w5iqDN2f_vxND)>l0J#q`+v$Xn*ldJ-0% z`}1f!l59IjZIM*}&Ir|6JaZcg&4U?* z51^+)tk#&#fLem*Z*IdDM|t^LAs;{s4 zQ)n2N=w_eJ-g|oTYV!mb5?U5R(QC*T(4k1?ZSRMsVp*(BnCB>}EKVs-a@Rg6daV*i zcHQ{C7d|7cF_)L4aOCIcVxf2*D@~Edc$)pt zjUu!dyYaCRPGwL?6;4D`{>ZG)|E%pK-Dt*}i`EJ6!h;zF_-W6X754 zB@X=qi%y1-ST!KRjRr3oSX5~Gv&1UaI8LJ`kn+r}B!O{Rm?FIbXD2>QxeC+pNT*=b zh+Sn!B-UPq8}HiNNHiUl8OsQ+q2CkVHkCLXO+2B`Oy&uy5ks1Dm2gan3^^1Fi^g5{ z==)gMiJqZ`YOqQWw4|PV zZxW{O>G~-%=D-CnXfz2HKh;n$i?u@CBz&M)cNz)Hn>=IM<>&4?G2G95LleR*2bxF z<(7#cgOv|m#BMyI=70g*m?TfDVu#rdJ!Z1_;T=8r#xp^qRvDU|Fqp~|?a>3nVjo|lM7BSH zDVix6Y*^=`E-o;6L2sC)oS|^9l#-J{!Li5?>c*3@Nl%)ffz|YOxj-)R6wx&vnna74 z1OqX6J3uU=TQHf(>FQayMJ3+KRit%$<|Gy;63!aKG=If)arZkS#M8vfd%d>tl`u;r zLO2oH{&#>rJr>H?q2>cmg%aAtihqQ09p*V+SGoY1`_i3jdrBZwC-niTWMjV>K_qSM z@mOVIp!`pL{=ZB3eP(7&m7(OhnqLtRWq!_ZxrQ zle$u`wt3#bAe#j3U-QrR5ZhD9NG(BJtcgvV$andt^*P_JBI7Q#T25|PP!(xC3!6iL za?dUZ0})@&^fxqFgHTy;50t!=(@-OsiNtD(j?3128zai-51W0*PCiVu<;~t?Vlt8h5 za+15H(jw3sddnDAp~DRf;5)j0`bANOzsePC z3w5gD#b^Hhjp2~+m4cOG`A6Sy`1rGw&pddf$1#H+QGC$Bk;#ZeMtN2Gg2y$tscUSww;UJ7`YoHGP(G7TQe$Uw(5#hz#%d4xi z6IpG`^!uj)s&=1Ak`9eyq;iPd$Bs0s`h*0IQYR9)X~ZqBF@Yp4r; zFkzmQ8*)Mt#3}wdYSWeD-Zsb~AR1>S(b%F<`p1gXlG8}rfkhuN*p)j73E`8z25u8_ z5Zcv8C^Ze13vHW1AFAF5hiXnWihxf(fkTn$dl6`EoLc<{#5pS@1fs@?4=cu2BZ&wL zaxJG!*Du&p8WCuqQ7%g!-8WUIN{;R?m1Ko0hpn3bE`InA%w&1{WQaz%jQ6voVHdju z-7_FlZ+S963VJ&rwh%@FN1O}J1x{JWbhyYlA29~2(0w;UW{!(ESh7-lH9SbdMc0vC z-`1|+4z@djE>sdyd&M!Z(8+Yt7lv4A;)Lk)^VnyT5tES~5udNC8WJ<1C;l+>vokmy zcxX*KuwrWEGld{*hTk9YEnA3qv_2)DpC@@4JKq?eZR{9MrfQc}1wr3j_{mx!MWpuAKvj(DA8CVP#*tg^FvN!)rkjZuzkmCLWUa8Rn%`ucjL_{P+_4k-} zt{$aHW7R!B?nzILNt@Br7!tg`yZNpb!7H=yD6>F-6{u4Ghp$9a-FWM!&1x{gT-rnO z0#7U=F3mO{3^gkrUV|Gkl5tV?n7N8o1a{vfJi(+JZl1PjP6W^e{|JvE z)izV6Sf{E(n8IC|Rh}?y7NvwZ5Vcd9y`zX!dVrY*16eNtaCYzc>svgoYm^~|&>QRZ zvsZHD-b4TCs6ByVsdQ)f%(jcr`rI@6CfxZPD8hR&3tBJ=NoV z9q&H6aK|AQfA!bhtYV@ZuzI10i`;i%tq;*O%3wHurgM zZe4BN{oq<9YTIU3&X&Bs?HhJxdIVVL`tnBHWX7(gUDj%bj4IO&&TYz4eW{~sS4`_f z_|qRKOe{@$%i|<6snh#2C}XHi1-Sp%$=xN#4^8pqy0JU|@pu(477#|$mUIT>(j47L zav;i#fYpd}_C!_tAkL4%iKY?1EClq=t9Ud@HEPxV%riplw-Gud6GQWKEcSOe>ds+n z+>lkPOoO8+iD+^ENHbEvmX4}n8OFgtH`dFXZlmLDDlC-BSRG^mP}D0|97K z1t8TULGa@UR$O(QP+hp&mmknkq)NH;#Z$p>MG4LZOf3^ zSQTStg!dUcx|eAz9F31z2uo5#U_<;I8cwC~-ff3C?{X}`K8<_;9dGPL!R)b?tr}TM z^*l&ER9%_^Vy;OT_&!a5dX|(-tDTi0uw^~E(;%k|jRbc@=_J3(sYI;`=4cwg0-pg$X2|p~*Hx_-;>^0I!}Ur>iVdX09pF}t zVaLoMPu+&8B%k=gBaSMY6Vs4hgS`tTQq#Km5}6>2&v^{uKWZ)J&}^y*y}!RFj~1-a zQDXu2-XVnPKQYMMwJhAAnv@b4dKirdWA;dVx%9X*a@--)b%g$39!T`N)~M^@a?}5Q zL6U5wiCwrGHDc64)Xb!OnJ=zQ}FOW8L{8{3*mt-Fu`cG&fp# zLHkMDbPTk%kuYK}TcuXg1ppjC5L9_!2Cij;n{r~Kh8?&%4s6DHNKs-$)7YB)rNgUvl7{u1|X zA8h2Oa+z?tu$S_11O)E~Ps4oBgG z@*DJic6C`#=XHy=RoB%y7W9hga1O9$pCS$IgdIF|EKUj zSjA!{YH^FdchgowwP`_1l$#Gh52{%_ptCa{9|(oq=q8G>H@+ys&2Y!O`;+-qLLG=< z`Tt!rz0lQjKL{dW?L4B69_HNSJzc89go8;p@q4C%(*dWuLTr+{JT7aitEE8ZqEdw6 zgB+kwD$Btl>qfY{yG`1FK$wpDrdnViw~jVt&{^8}em5&&2I5Xm$DFb4%t&(eiV`Ud zF*89WP@^X)VI%xTWuTDVOVCx{%s|mG5~fm(@t!Vu!*rH7R=-B2P-mM{jD!Z2Dok&* zZMQUB^<{Pm-;3*;8o(ju%#ii;_T}Gl?7(SQKiD0XnyMMUFU65J3ySzkT5?ve@AnSu zaFUifwj2}(U;UUBEV+OhB734{ym1!TDT1ea(}r?zeju{{UBV#Un!@(0wY9Y(Dgh11 zrn0sc@>Jz_)vr72pH8=F&Y!p?ruWhaT^Ni0?^Njxr?D86m6g?Yo>V>4A>1u38GE1q zN8f`$86H2f#_az#+nAY|L2$jS#eR~qb(pM7-(2J7;^yY&+?*8Ihm{(@E=!*j3sljj z!^1n?66VPqha5kLA+(H=ZuuUOg6njzOwghdZi&Dsu2iU3t5APbt&k|koc!X8ZO7eL z(fFemaq<#Fm=E>|;I~4?Dr?Ptf-aK_2DT^QF!W*cP9NTP`p(#G-SCrJ&PnECj1y%` zw9lCGR?d?|5s>naeqb%h>V;p30V9SkZ%wzMJ-1oA2IIfL0Bmj8lg=U(Dkly#B+|`o zU7bqm?CcBJ_y}9-Te`a)s65H3&?aVO(|)EiwM=?)(o4L#ou_dqkJ%x2`MIZ4|P6pysr;^7X}fJI6T zF*iJD{#c4EIp4?^-g3J9xA51aGI$^B|2}p;Ye(nj5JumluJeTPn7I;&v)bw)wQA_T zVyRH-GKFr)N;rTBqV<9Ryy>>d5#(mCJczLcoaT7HvSTlo2nPXjs9e~uS)^6NrI~ss zb!AOOhv1gZhA%ZjW^r#Zc4$<(MaX=~^4Jd4NBBc|OGs$y8SSQ=M?=Vjx|>IL@UX^? z9d5}P-$?6QA-d8}v!TG>87cS`pZ2g4kY0V0KLsZjSU}VSOCmg+?5kK`N;MYdS@_@X zG_wu#vwtc>0)dHe(W=mXxm)sTTX*L3Frnwj{{O=+FM&Ne)1t4;Sz0=^h60BOb8~a2 zi#0;$&2xf6LWgUnAka}w+XiR$)0Q3yA%TO?vq}~hx~HxLT%){wYmVI2Zhs@D-{M~{I54H`~INmA@Ms z(39auI*Lt(tkx=LyC|QO+%Y=_Ba3RcL#%KwJ$(uPw_CDezeh%v>P$ZN+5A`7bxnk_ zBJ&{$WVi9hFq@yVO4h)|dY8w=+RED6FQ4Zd)$z}HA#=wxcydKBUmyxf`5&QX64q6= zAOo${WkcA4!cwI`rJ>yfQYXQJzIdKcIU_0R~Ah`W1xDHl)6o@x8 zb;@YHzqWj9#hs4yz*kceLF{?)g0FwiU2#xK6lys2#jyq=kl_To^L}}YhWq;1JK2u% z3e1SvpSr7p=La|wan~UQ)lcnV8{e7bW;C>ohSg9rO@ko4aO}=^nn-LtPt@@v1`vOO zvtEcZ5F}PZ2x8y+YLi@L>+!=|gI0TDGBV-kz2tP}FE?MjZ9-s>Bg6a*OiWB19Uc2H z-4`-o#^_ERqbAcB=E)*s%x-^BSE|)k)fxn(Jpni)paO@{SQ9DJT;zs}Ta7MxbDg4q zwJ$S6P+oJtC@>pjTm{ZF&5Ml>wdg1&%XYNru%kot_&+#;_1o)<&A-~&aXpdfLHJN2 zTPj?o35>F|-*C9H0y46)-Nu(WPf*HMjy=y-{A4|l5dBwz$P zY6wY;{6%~WXn$!?mr1IR4CLn)byAK~jlozBM;Hlvk@0#=*G5&}`z}Bb0Q=3{e0N~V zeaFqBMW6V;zxY2oUG#W#-(|JUv97X`BYX1uPVn*ZF)C}jcxjfvEo5{vIw`M3(+XtH z`_p&sKnCq9%ksP^zfq$CaTO&ru*`Dn#oM}jxCqYG3dZPLGc}{@sjQBOMlYI?85o%>Dw{`JN_KTc!BETU9dIk@p-Oq^K@Kr z?#S@v#3|?3Xj)_z4vVpZ5M$SMB;Z56o4U7`;2r;#ly5n%O7Vw}uaKn0vKY)?tojuM z0zsmeWZ_j1Dr*LnBNj?1@3%D~G=ypX-57{(_wLc>rgN|F6pMYaVH_sIFk5bl+Mz5y81%^6t$9-{Vz#Z6A8 zgNU~}zLd{#eCEQtjgMdM}A`HQufLJ&)gbD>Kqu^1NtsY%j^v zf-YKT6MY_f5iz!zghUtL`$hqp@b1grn>{ASbJZw2AyuQ>RMeX0hCktA*XHpK7joru z-j5gSz5cyp7Wyr=`1#Y}mrm4y6cPY&8k`!#j>euIKbfAdkR4%7uP!b&hvZ6V$=_t? zwX2d<1>oP<9pQ0DxQk$o;%g~4j>j|8+}~euF1!uMvhd6E%CE#e{z6%{v?3xKXsjaF(*R3_yVk$A~_Rc?1KC+$f z@b#@*zI9tXu&Xs}-YOWEa``wAsq2Lo5qbex2#?`9{JkNoyNGtXE?>G>wY>1TGB}U) z^V1rij>_)Y79d|nIar(_d9-5y2Y6V4?6`Ta#^<(>Hnf=@9aLvrYTTW6qIa7c+C|}Mm7sq=u>7KU%II-q z{K~Sc9j~@n?e|dnkNo42TiU3X$K`{#Q6Rq}u-M1V@wzN*Hg=fO-2S%b_hFtlD;Y+9 zK=7oMclQS5>+hGq2ycR9c+$}X+SCD_!ab1vet-9C(f5UT<&eb69MF6Xid3bAF)(R* zw?SL4NOCIQ6}Z`A>HYP-xJR&l-g;x@;WzR!hlub-Sj*}s)%`vt+p~c#FhCbYQuOid z>Cil#rIOw!R_uB!@^to=e7?>I@84~v!bqN`<3`xSR=N|<(~Rc_PwVT4%Ws3w*%NZH zZ$<>ac1vLQ$L5#Q>--$-jyGt<^cddP#g@`M{I*Y!S6XRRpBYW&A^+h)_8u%|_&z~y zL5f@&IZcNDL2BY=2y*@A*|EFL@Xyeeq!s()zQ<8R8badAB(8hF3Qn@V%wcs1-Na*{ zpv^T7kKPihr`(rQ(p>GfhR+PPxes$@zmu*%ja?9}{Citfl}0j^ZFLFvtsgwidr0nT z{XEmnc8N53J2VRM;X8@K3gvs9R6=BZm)9edn_V7` zjHy*?%y=jc>z((3h!mbr+u;!Q_~u#odk~}$P)^VQuI_cOJAe#Y43lD&KC z@IQ?&8lRZD_ta(khFmB#wOM@b=!57GkLkR*-by2EZbtf7=Jg5KK;(NO(|p~X-Ycjq z<4G#~*uZCH=qLG>-simOT)6u1c>NC63^OXU5GM3{l5vgTd)OU6xZA}n7JKt_%n^ns zzkc)v7vN0qV%z%nV#b!t+|vDu8j+29&(oZVwKMj`q-5>hD1(q@@1wo|-&5`|Dtc2Z_x3`@_Z~ba3xgmyofdMha(} zvyimIrTf1hUz8*3gjRyxpWZI>RKJI1_2xwx=HQNnnDWI4Sd&#**&tH{4sp|5(R^n6sH9!R8X< zmYdakHM#`0Z~9XAn+8S;tP{UB$xG-LJ^XyG@h8oq{+xw%CGBgUc~E2m<3IMp=A2dX zny&5`ZG)A&MqRLA1qeMIQG6d+df#-SQ;LM=)Uey14sO$!X547Ff-bgD6&FqxNR^9& z-!4DiYn=SsU`2`&ohwp2y5n!`4E(-Ree+6UZa*V?Fxf1!Qu~g|dZ-gM%UZ>wrezQJ zaB1Q-HAje3%CnvN;p=>EJW^Z!{;Usp>Tl(jc3zzv*tz5Oiu%aG-!zFqz&HO4M%te? z?v+C(q;GFGs!CUJTnoFU9;@YRJBw|EgO-z4I~In3Uw*6paFRvO;eS;c%#!g_W=j@e zT{T&C;a|Rgg?K{e+*V54*4@JzJ7=lrEyCHLFZ<+~up;3M8M&8m?S_6XgGpDZB&ib% zA}RY}YIMe}njmBvHwk+9AS+=zM#uWMJEWJ>D10U&XiB<_rSs(MDAvnb3B>=1*E`ZTp|3Q5coM zvKOa_aeLY|^)OjvFrLnj!_7F=*0T#t--0Yw;8AexFgKm2N+Q(s_-)`KAW!x zf6-H}t8X2qQpX@F!QQv+!01twjgISDvDi#ne3sra_@kw4kvJ2#ErQ~s2h_cC8$JPl zt|i=9oQJFbmXSJreC7OMYz$&8kgZZ~-k=8^{e}z&6Fuzma$K&ftIMSzs>FVsiPDOe z2HW*JNGltgC3i`zhjjf-G|L0_Q(XZ=>!6Yc2g2GBt9JawL0dtzv~X%+@52LPp7?F; z(^*!qy-IO%{m(|_9bos7_jn9bTko!SQDe7{q~@~DTmhbX4aLe?+-+dj|!gYaTc)NX%I zhTDE!{fqr<9e!ct^}asO)^i;l#iBHBVyI%&c`(qmplY(Bwf3)?$5CyuTrf6_mhxdJ zUZhnDF@6O1zu=rceW+LpA@3vEp*#DJo+07an#)$DRYTQx=6>ilJ%*bbJx&^zHnYN=X& zQ@tzf+I*RcMD(x@-E1p7ul~DW&$#c4ih|2i!yN{wt{hq=btk>w_NKfD9+04~U%DLr zf&E=1&HMflTH|?9Qurdp;|(wROu}}dsK)=_Dxs2YGkw@g?Ro&h+*4^ChjKhbah#C* zICC|ZR9)A8kb`*jX193pcFGvCQq0v_e2$V*{$70AVJFD;s_>Zr{>ytXVct`JzX|3- zy2-{zxPRB(>mgeQ{zaY}#N?|sKzK7pb>c#@?YXr4Mr>pG05b#)!YhpVEJKdz50u-n z;*ZSd4abL?Rop>AjL) zx@De>IWy(#M6vLGgcFTDN@ZFnfDpmZYE(&ipZ?EsrPWf6=&RU<*ZJf6r#9F4r<$;8 zhG{{@n_Th-*~dc$h4=2#HL=>)EtX$h<2~2=uPOo&C*s5Aue(q}CmmYg?a)8N8j53% z#?3ofIwyQ@Y_+TJ)Y3I)YMSfNlmDlvYmbI{`{GJhxry6FqZ+2GBI*9f`#txDNX4RG zgkexpiV?Y8u^ZRnw`u)zI=d5+s zK6~x8KWp#LK6_^^XRi>nzG&l9*rf5q^9(O%oc_^_FOKUZX|C@|G#8%dzA-qfAlcI? zhel2cB_0DU&$abdWNm=Y;bm(UFI+;eB^!Vg=uB|Bhekf)QMdu2hxoqh@J$)W7GQiv z8bFor8pL!Mf?mf}RyoCpMHdI;U@9Xe5(4PwIf@f7ZOO0-{yqTz^^`jAwfW^e&XnzV1|y%RK@%z~ zpRjDwyARS@7{4c*dg4unsE0bUp0!RDXgi-iiJ3TeEK}BssR-Q|!29V8O4<5k>}o%j!9D>Il&55s zkL`v3Vd*#ET4Eom%lEAV(ic>KFaif;{CYRWf4F>$i@%1blOiV8 zyh8?T=TYTb#BWgAHmkl3!FV6PbRT`hE+AUpzCoAz|AU>Z$UmEVwjnF$VBwNlh=$f{ zUDahy1e4jWRT(6j`#7#K9gM1r1zHP{G_Mzr;PpyU#L~TI)~5ft5a`q4r0~Z&Y-Dsb zvqraxciuW+zWDVO_H3AX*y3$%*MhBwL=(Y-xAkEFf1qh~(_Cl=xi4t1;*91M2wu;m zWFBgGbwIaRen&t+4F2G`6P%}~Ov9JD9LLwYpppZk;~LFM$e||tH&OR95o=RgY)mYX z{xuwZ?mgOY*nf%(wo|_1xOPBY5B7y0X@>MixSv&`PHpHO5Au z*Omf*JA~fimh{#dH$sG;FMfrv;;h5oi0GQd*C-v@)uy7=s#iwZEOIGn|; zcSY||(bpI5*0DyF*T`70Vh$YHO3?q(Zi^#f=>sCSY^O#~QiZp>w6WO`YCcqZ;u?>p zVm3Ph>C-%Vh9sy*OqZgsXMU2##7_2?}yOuJ5(L;7l~LcKU?X?ZTcwgvYp&XQ4}09a?+iV6T$e(A}z z5*-6$@4C1r6NOQ$N5VHnz<82m4K9?EWJlV%ULKl8F>RE_wP`spDPk+E$J`jILp9$|sa(Fs4kwvz zrb=cpK+~Fme8)_e!6>fiJ9PyV7uj*=0@h{DD7fOpUoXUkN#5Xf|}wcgnh{!@(fyoM#C9|@LUE

ox=$CCJuh+oLuv^%F97>SCWk)4!CSlCc4SIP2%d$G`A z9ECA*7->~DPbG^OxR`ti>XR3|aiK=D&=aAjBcZob&2tOd3Y53qYo;yWaq%!pvMx2c zfjnYqRyUu0)RTPgec!)}evBIqLVJfT9e_9;? zK9QZJIf>Ti&3aKPhbH1mHbN9s7n&tHQ4mL{-0|1oNNWFCJYHXq zBq3L%s)Y2>oVvp4qWGF?QirD5X$L2Ce=r7Pb;HoWyw5x-wOc}ag z(_-Ul?~8BHC|~sp+}ReRj5JVoR0iwM1_SED;iY|7(_f?d8AFuttcZxMpoVEn&*AC# zZ}*6;!}UTe#>^nj`Oe;jKkGI?h%J|BMb<}!@RRsYKuI>s_X7iPa<4#U8&5!K1H4FaP^%M1Xj!Hn?9uZ9vV(4|2`xydC8n) za*~r#R8|lYwp@jqgnRl2fIuJ|Ts$^*4s~PEW=>!c6L>-Z&M<))4&a6ZxMpVlr3EB= z0)^I~TP7LboM##QN3w8Me=b|Rc<$K;UZRGh+EDLT(zg^ic z+_YxZ)Gsv6whamEwW4A`P01K3^~klg$cZ(aMR_c+lLOrADoD)EJSn4)mcJ&bbXvKNSvsg$T3?5UnDjj&XtJ0ijVqa0Se= z00*}Z2X}#hd`t{F1`!>@!QH{Zy&)pM5W_tKWN&bUPlSZ`Ou(@a=!5}y5d>bC@vcFP z$AIVsAb1F3d;!GX0Kq4GrW*m?Gj(9W9avBS9q9wdiolCL@T@|7Z4Vs#0>`$%i!bnO zfqk#Q`UohF0)``i(h6X(f~&Cr*p30#>wwb+V7~x-+5mi(!9HVv+&-YX52&33vKN5P zK47vB=$r$_7wCG&fchOE_XeoG0kU_%hkL;IKmQjnc|*~=BTzd7toH%ueZcx0a6U(O zIt0A-0sjNw(*+Q4f#!b-Sl zLJY7}2h4v3j?;nTNZ=&{cq#&38-a^)V0i>M8UdbHfa@dRmq) zTS-TsNdWyfchVrhP=)PS!peK9u6)r=)Vx# ze+K-YCIB)Fct9ajs?F~WL&jq<8L9ozABjz?lCAXX=U@ymuj9tZuY%zOD%of<<+{Sr zWTp@0CZlylr1Bdq{2|iRT@fX3zU*sOvf6^=1a5+RB}`r z%NHvQ>K!-78Y`A-Ec&C#RhueT>+R>uO~;$6)|=h;$8uDgt2f(y@6I;In`^eaAz(BL zwU*l5{;znfW)m&H_Jkh{=c%8PgKjn1=<-gq2A7|E|&X?BvBjzN)g~Q>$ zrfR6SH(loDV}v#-N<-nmh^Y8lQkIXG`yH2rsdJ~7F-0~xurGWSQi7c>n$ z0U?=$qT?#A1;Fds|FHRUKc5AM&XPeHh9dHu?|!Om2Z1XzE!~SwTID5+qKjtQ@R~g& z+KA-I%}DTIdpxnSK)j8l4L!x7`snpWZIByLaRAgRD?V=}Q?Ul@Dv5SbfH?VU*( zg^fFm75*X3!Pe-_XhJdA1?$@j<5Vk#L$_0Xa%Z6qW{(RT{>(lDsU~ zN!iIyvxg{icZEJBtIwEe&&QE}brnGc+1^H}P}e%;(?auj!Tqcsdo5)pl}%$Q-(gN; zOw2{bGAp~KP*RJ8ijGH-1&KZS#PhF_xMlf8H1R495?0?%&+BJ~;91;Jw90eCU?ik8 z`70D>J72UESg%@`NSK_fThe^@{S?-h_m!78doAgS(8aHuk-B!m z6U8Q_9`5?M^o*|g7S$bII$jUp>+=~k9`9vwb&sC?aUVvcGrAd}V@)akA*9!SUGUG0 z`D5c;qyFs#UkD;80x_B~ds{GOnM=DN>5S&2-1J7)*b8aCXCLHetVIt6*vD>G=Uwb4 zI8m#r`=thoHuiDs@^$M)YdmL;B_xaN?Wqj^O^bXkCshh>n`Lp1+UK)MK3I`*R_Q_M z%NWMqj5iS``;wF~dsW+n3{g4(As0phaEHs&G*g(?HQiIl zEEIlkr2%ICX++(ptG^-OHZ!=}X2}O>EdPkm%|B_1H1I}RQpfA&kFd1-7ZhyUQq?T? zJw*uGcWep#3}A`4RQmaIP0*j+oVPZ{Zrz;gh|%6{)L#)D7lWFfFiB_1H(dAJ<6f>{ zfq@^m4q!GUCJ2;mf%0?ylPpeJsRz8A6mI&6{M3ak9NL5#?B|GV2Ep}Lx-WT1C@q5= zZ8toB+Dqsv7;rjQ&wQ8qY{y{Ev-qLVXJHp24L$ zMI4|Hq}N(f@!!9E#OGxugX^mS;Drj97MWDEqn*=d(9wM%z!#)zsdzjgIxgW+DWf@0 zzfxIpCh_MiJB7P!KW=OU|7!q6$pQ{*rdU8bQt4w8mR~Ro-hwucX-rZBHwTbcO=SY0 zJ{$lXUZNEI9{r@wA*Q*t@hjDz&{ z+020d;xABOnbkWK!_n`0EDmu}(nW1rNY;dk$3M@p-u&4-6uLV~B%z{~I$Z6XE+YB2MQ=-fjZNw_Jqxu?7;gXS_J2-;Uc;EsE!8 z{v%kwqq))L)89YaD8n@k;Hg^8H^-gra_`0u1kPc-0VDs+bQ;j?3#0z3LS`MF2Xk&% z-9!GEJ?o`bNpDu`BsqO-%OwKg`8p(?iX0I3KaYsqC}LIrStn<^FVNJu_E3y9h+KQ< zhUHMEK{q!3&0&sOe@n-o{y?luZv7K>?N6GXBFj{3n+^>K_nOl_+Y=qvaY)tQ}pwXAqTeE zR}Ce?7#mmt&ov@LEI#TEmX`A`%bvx&zv3n@uU4#&EwMEv&>fN~hkIQ)8k$||nqy&>GysvTot(aZ`2Y;^iI9>;aHTJ`YmQUSFK1~%} zortdc9T;ukY=-EPJ_u9OPNCP_E$qTK1v93ftpF%Xs+ey}r<3W-jH8=orBxv4@ zN&>ly>cl!0lmylpz5>}Ww}9x?&J)QQ=z&ju7~%=lOx`13>1_6nY`5v1JC@&DnX6qU z^FR8DW{I-`$)HUGN&r+Fg7Pb9aybaG9!o0GO^zyfM?W~%Rz0W5`uejU-QcI*|hJLQcQh@kyCB*rZ6QPO>z){6aE$gh=MauO@K^US#?8EVVys{C$ z=6Q$r9EN|)fL5*mq)IV0zPR63upEdv7<^+|Gq9EoA`z5$&*)qayu<1dp&`Z2;_hL6 zzQOeht{An^-iUFPrBDp2xOoHIDIx%lI|e@KUDHX(WO_{7N+2y0He6yz>XNg}|+1DL&ie-z20GC&F3Afl%nb z8^CywnLG@AlX7g;4>E#N8C?T2;vvZPe2>7jQo>COa7&zk!2FFy`Wtu`b&4pU@g&e= zfx_&HtE)R%(JV|ThZW9=z)*83j+3(3t<|S7ADe3;%o3|*1At_<%<||WX z91s=r$uCI%G=_d2OM%O^=p^!ZSVLeX(t60jGBXK7DmdsQ(y1&>0VR%7IP(!XoeCNS zrwy-8oT}oR-r7RSSQ~=?O{Ja3Liw7}_iVh|6fnwQFIeUr8Wk?)9vq?+@l815b|g)~ zAtJ3cWmzBFOBvfuDAjkA?9KgK=W`rSYofnm@IhpfQb~CIYNUWt><(dUta6Gxj5)Jy z6oBsmW(+brS8+0!vC~%q;Y$5eRuT@&u;dd%G<*}slzINtCJrKJO+^LQE4y~ug$F9d zsxzc)kR&)8<|B}1Dhub5;l#lAV!;ywUiRs%QR#n)vk^zrX_KjQRv;bvey^F%l2rBr zU&BR&qF;_8n+;P~UgLKh@`;P{$$L}&`sM;u5SGzg9c4;B7D%BX_alintkvg4F!q!w zX_O)7g4pBYKBF}=D@iyXgNl>u49C*}n}La^|1`6W`iHm*cd&34$!hjb`!MSAq$uU+ z0%C7!(oBWX;^fsFw>IFtND-NK5rT99oL|BHY%ZJ!*7YgLEee1#$_gVT4dxY!&haj` zM6st>b7(*I#9>TxS_ROr3pHPh-B@zH{Bd|3vENEdH2X^OEz?c?A#Ysay7r}2hB?8{ ziSgw=$3zu!M8WC)b{kP;Ek+4pZDmN7B?!H7oXkIjRDK{rOJ23g5&N?RnJTi2-OiAT zIT&+Z1*$BMOI7_VlKsk(4a-tUi>CT22xiN2&;H|W5gtoo8+XizqdlqSeXE;P zbOswz@t#lcE|K@jSd|-UE_)jQmdb2Lt%m=vG55c*VMm)*Bw*f6Du;-exfG^!HeQ_iBwaU#wjDiAjC%855nP+iI8943t!Hn z{D^~}8GKBZB?6RHS!j9jPG#Jv(o=5W}o8W%MU~D&*~43 zt9MJlYb*`0*CaTL6dTntdeKHk)@me=Y}bk+)FdoLp*%X;UoRqIcEVW~#A)A->myW} zcb9AAL>nj#n~K)~Fjt9#C{FQHL)(dW#c{xtJdfKiA&1Wp=z z&lC0kwE8dx7dbV-L|TfB8zh_CNRrwYKa>Wm7R$lX!^K3yhW@l#pMjr5>I&OCiUV3O z+#BZ5I?M6v>+5t7^ z{;fallyA*XB4HPz-4DiKuvovuOh;Hi8|wzZM>T+v2sW}C02Z+xx!~10hE!wS__@0I z#=G8E_ENJ2(>o8MbPO_I3>K?`WwSrSj-7^(7O>Pi1{^1bP_iKc6TQ5wgL)k!w|_?5 zvIm1I`-0I2($&Cxz(^>%R)q&x^#bh7*8jt#KgOhw_v;`nTOSHrAHCS9hDmT_z$m)Z zxP?hm!vp~C8O;gQnBX4kxfqb>NtAR4N53^cW=)_oO>CWaaxo3Ghz+EhfHO_T(RZRd zV>SNt3`CMmNL&wTZcHEs){L2S3)oKykc}Ffj5kjJ1d#FH8^hAhZCaU=Cj(gOY-6f# zU?=B(ev^Kh$`OOWF&^Zphpgf4>={Y-zLvNCePd8?<>-aU^dp)27xamIHF!a-ZYi#r zN#`-az`+v}aAn7AE&9|98*EyZZ5qb~9%?eX@M*T7a{5QdEE&esrsxb=<wajR@P#kUu?!rtbVc*tk1seoU?*u zI!++9fGfUWISDAZuePVGhG2xf%K-~=!MlmAAmz-QT2EytNQ)v(WEn=bgOgMX8) z*Hx*==CAUSFKWWXC&*1#3jadKC98|Rk`3k{pME-N(bnGqcCxa{TBXwWkD<<#$v zukWrDa&I=kn43S|7Wkd#`qegj**DiOH<4kJ*i)PSF3Sg18w6czS0?az+WRIt^c2;r zn_}=CIbZ|VwTalB4bweYilg<-1D@)G?}5AaW}svCLqZ*Tq2Lky>RCZxkw)WK!U8^z zeben?6UGeN=@ma{5!)r0Iv{Wdv0oh!U;lItmVN(qKOg;A&3Qr?vd+)8avgUV(|L?V zafH>i@-Z095xim7wI)!z7G?%2iU&J&ogiCNxpi%kUx8(6H(NSSX|`tNFptc-&Kq3M z4lwrBUC#(0;OMC{hLj;8jrBy=Js;S@wfZp&Y$$hYb^Y?xGIyCf_sA}OnMmtI00Mrt zxG=GXchlIZkvQh3f}bPb>u@;;o;sI}iRw z++hCBlQWt(H45yVAYdO_4a>Fg>51Iz`gFlywCQT7d7&c6rRs(6?ci z6*(tZ39=(ozmFu~TdJ;F#7}88u94i%k$&F@V_&Fgfa#{M`{Ns!H6{L1!B4B-|E(S( z%mdeJ98fC>Do=Ie>V~#ATLdD#MY&k`H9i=!?5f9+trg0*Rf0@7?gL@baf*Od$f#yCJ%Y2 zaJj{fdkS~GC4_*Cr=J>=sfDhd-Xu<&#Sdg=t`<2Sv_rtsT<6c1cS#{n;ak_~2``0K zRC1IzvOO<3RriFHuf!o>1;{$Z^z(Yvb3MgVTmlF!;mIfAjmY(-HbH6x276$WJk6!t z(-wcs$9h8gcN69Is=NLA=n5jjgjJZn)ZNTYN^(D1{E_c|X$S^~NuGvp!+P9a@Bckg z{eJ8Z0SjF}+jGER<{-fGhYSK55sSr1vs<1-1O~ap7h>%_xo84*vw;lleT8^(@nCq8 z_XkSf=+$%OGT$Gnq_NB2^76=yBxcCiV)pvUDq-dd2CiL~;VEh5Ne9C{Fdrad76^u} z)JlW0KDq*-YljXX#xUHMy`pCP#g!-pCaBbTKf_I~>;; zki;NQI>4k;BI%}8)x*!-J7CC;{AJ_w596^^cJrZZ!#mrloWVX=ryri(37L`)$3yF~ zVtla{bj`Q?F2X5aCZ9&nd4^>PiqLA-!?k+nzBd?0shDf>auoE}c`Q)kuGO?tC~%L< zleT?(^$VEDTYN>~_eOLO+S_C!73S{vW_Ki|IV|usBP%98CWH}_dg=Go;W^*C6q*a> zKCjR*DR7BVWyk&4IBHnUSwXD~8s`94|0}+yM%#@2H)Y0i_Y-EMfA7)88m|Tl)R}v| zRk1pe&_XBRQ1}P970G=LehsH)zhfVHOQF%0ThKT^=4bQ8F`a5i@7|Wy2QVO?9wu-R?u@Hmh9Nh~xDNsV(;5f!MX%$O_9gWSa zC5=R%G86Qyd{X(xF|=BZ&!xw5vdg;-ZSJ})>{1=UGNw**o46n;pUnZjLFHQQNh+>0BRKUbl7a3 z@YqZE6}fHEdk2~6IgQOIkM&Mg>CgT&BA#mUipWX^n}ESuuGhC_e3N|Zxo*1hx->F>EOCkPlFUV(7Lums>jL1( z)UeSbcd7<(;b95W-x1<{Iu4_Dd{e;d_b~hxDa3CB&M+Xf$5F2q$==O)^KR>j3TVzw zt+Av0l5s&(#E>sH=J2wQI_#^@wuJ!lAZ9|oA@+e{i5-D^d2>PS0e@4?|h zax@BGD3@_F;0fL9ua)zWz~^RXTY9xw;yAW~vMWnQaJ5)l(ULMfJ+*7i3|%;^2H~Gb z_hv>!i&r^45L$oyi&d1ZRCa+-QAuMk3Wkn8Xd_CqeWXGl>6F!`g2SXTMQDD2AbjQc z{DXEAPO6!G4#W9#olMlI*;6m)ZM-D$$~#B36S{w<&cU@LgnJjqlAxvOh{16q41{OU z{!OAM(nSHXLQk9Y<6OF>6#@P}jIch7{WdAFAs+#$cqH_};xh*~9P-_M1NW7>`cmMx zzZqUF1fe~M&jHkI;fzwAUGLNC>3VNpM}`l}lKrOt*oYmL)dV3s+ZLTed1Rl2GiTXs z*Tbw&;>)Vos=qi<1;(S$5GbIp6iaG_E^J99juC1s{B-uBMl|q~HL@*>IEJSZ#`@Y( zeKQ+L$#uHSC9Ij&q@%@PwJs4O%$2cP8M>C$gD?-Cd~Ug$khUt z&HU7W1f_3NuSS{4)cQ*uwiZ#*8G>NbdjF`8$B^d0k0Aa!NN3{Ng5lCxPLssFd>(v!Bv^*>^4mr0m3^;8@RPmDQwHs zE+5k__{s}KuQ8f}f##mOlSOl}FtWu=9n(Bd!`&0Zvq^#h%MPK3D<1X@wU1l8fo`9y z*Rr2?lijtE8MyFV6%zSO{H(60dD2M;;(f{-k8r%ScK+P5CP_4TmKxf(1V%J(m(Q8Zxvi z!9PUWNt!8*ZB^N3*kefVj)BA`1*Y*$NNaSyZA(j3yjxvr)XiPyP%YYHheeiy z8?XZ3EGUQ<^m~{xJlONc8~s(|p)Y@2a1VTu*&V=cc5|YjA1S)wFoDVnXQ>)b?3Z*^m%Hwih<3lu+0x z)e~uP$<&}M$6HD>6ZwPUj^m^-jfu?fG28cDPCMq8Al!C3Fb=#W zslg7oo*()9#w(fgJl`<;`9g0a5Pqy{ejwyPqPelkW!-r14>ak`K(G8ftlB3Mjq`V4 z-r6=R=ITcG%O2rKXS|j8XNfe(^N4;I&>#Yt<*x&W%D&^Y4$Zu%r$L}=Z}9s`zSA+e z4x*xs!i)kbziYuQXlj*h(Wd1n_(b0++U8n7uPfR(I@TF2+W3M7CDM@w(@N~$3GJPe zf(Cj)7m?umYU{Z!rV6^>IOG}QB`9yq8LaK7g{|lf!q9pY+%VBOUU6LGPV88iIEbck zg;xYEL;T%X=WA9s7e3eayZ$|^Y7#z)y}NEQYuQBBx{Mo<;di3v?Sl2|xs9tLD0HGI zY@%pnQA&8B#Mqs)`%ED+Ri+0DDSrpMSq_)Pc73Z-B*1s0(j+r#~WDhYh`7Xb8sq+ zUF;+8hPUr?B4sWad2$okoZ%F|>Z z)-<`^MpGz-QrKh78ui~(`}$M6Eo-NYm^f~Gp0=pM=Fg&4D_*=22nTFJPH=p{PDk2) z0|HBK)4CV>_eXATeJB#2r)nNL4Q++nXqz4_nTHlm7LZ)d_t$;MLdqB+pMjDq<$tS1 z!h;Ok^5QXzNiy+ucGEyV$|(Tf#e?ZeNT{d;19S~aol-zw ztyPeCLua^o{CIgTaTFmeqR0pRl?VOb)cVNtA!?qA>qes(VgtCMQ2*>sE*_D!Eb;wS znVxmI;`M=;uwINE@$GumcZEYv_oNXzWySCl)3{aBvmjI1K0mY^uL%{y3lS9Oi7L9$ zOi>h{0pT<Il}v?SZcH;!y_*e0 zGBVWDFiCTpJ(NO1gRf{jp;RZUIDDXjvH+@P(;(*xP1%WLIFQe3=Rt>nTEdiX|5QxK z3>CDGHmY&x@=mJ94&}p-Exak4%E+!9j4yW#89++WpZfT=!nVcVjUH;~3bWYqIIW z3)TCEAuX}dNBmi-JtX8Aekv*%8CjV@c&({0HF7RR@@LSugASJYNKj*yDZ1oFG-xtb z1MgWIx1f)sa&$klK4A=kTMM9UiqCfpv}{0_CSeeC@@e!Ih5L&cwg*Y?ce5PyG{N~J zs4DVx^@G)_ihmFKt9dn&=rq0^jI9kIVSBzKerlIZIVnZkv0!XS!uit6YkF2kGv!jYd4^eS3pa+Cy9yq0tCYht5qU7;#gnVeheXrN8m0ky zx^HCt6MCe7b+iwc_AZQ*-IlV3(F%NKpcDN?Fhe90FA z!VS~ujqCo-SRXE9GJ$5;L4n97uoiw(SqBN-SWSC&4djufzbV??i%UOr*GLZEBb6hS zR((h_(H+2eUm*?!y?#jfsaw!4*?J%@L%u#~W0pyq>BNmsgSH4x*x;KiKb%Ik(i=P%jucL=FaO8;lX6#7v;XL&Z^cvxXqv6m`RSHOsnAA&eOSUqFwD!D_}7 zM05qo>fGfgO!j}xCd(K>Duv?N%u``*Utg}@EJCR{rf4`eqajh~awa5N+oteygO?Tw z;!rKIT;E1>)5S%>cTjYpU5+gXLHv6zvq|(GYn6yC9tw*ST`K{GLyoeNMbk}Eh+Z4P zw%*keCGj5VHI(M6D}Dt@W@^Wj&4k4LBbvbmy1ls^1Gj0>1|~9;D7O-?dRuA8S{2g@ z|LOq!8UhD9&@uy&avVBi;w3u(R7wUE!FuFMYhOF}#jmWya}UKi_9Q3{L#VA&b+&DJ z7j0#&ys%Zss)Xwrh$k}yJD6Xg5xJ8_OGi;% ziS^|m-D=~PH!_JdQxf&#{eyikiana*Lzaq24|*;1;A70hJ%0&n;+cuf^*wAZ+wBjw zAqtiRO$Vw|2b_p1UkP_SFgDRs?4t$FUauo#;`3vs%$CHDOE~rt&Fm=cfo~iin;UIt zwN5)_PNf3(EHt28JW#xmV@!MAnW9srE+MS^0~Ood0MlJAv)ycl6DEQkUe^->DTis% zv#x6U03ej~#MboOw#3X%TtefU!o^LT4P~N@;m}#Uki)&aLn@v1U>qnV9F!KZ2iCR4 zdWOL8Fzp=>FPjim)Y8svoAfn~PVt8h!p)$VUoV|twB1dYXv&-75!25pnr>58URO(o z3=W1@`(7O8Nh7AI6w9Vxp!iDA8U=lGh2=kgk7Go4&$kYsSEpZWT|%#17i@RiUF}m~ z`|AR3Q?-$O){Y`uF4_pEH{mwrgr_$-Hip%1x9o0FJCPfvuJrN86A`W%!Me}H!OV?xen7z6CJzM+8ENX~a7oW`R_6S|~ zf-hniwpn;XiG4xDBNy~($H%U&z!SvZYy-=}3C+gc#_XKw0l?C_Ty%A@Fx{nagB{Ut z1FK!Ot9sKI>7Iuxy~t-ry=hjPOIG-bcEbwJgmxagh@r_4luk1ciO`)dgEh&qGb5rc zNytaUk^|xHWe2lK#DAk2@lN8~cSs4gN1r`cizk^G@Aqp@V)V|a^)@A3FZOJmha>J^ zgD>6@fBI35)ENOKNc7-(+BpjPxuTA|Dh$oyeH_n zmT7+2Jwc*HzUbBS(p};w2)W4VtF2fx4O ztqS&X1dz!^2%|aFCg>^I4h;_7S!nCQG<{#m?t%;J)5qhdkS7oo^0QDClAX_^UC1LW z9;6=Psug)RDE^Qa{~VM4+^Ftp;CAFE|Kv$zjG}mJDCn0m>@Uw9N|tCvH3G%zetITz zP-^~7+5%F}^D-<3?JmViZG=5CXx>5*t)dt`y%b&I z6KwNcnH=#L>gF9Lcz0a`sqtYYmRebuMVL zxk-q^q`)W$UMY-J#8HgvM0Qv@j31q_L;JsB+#hwBvw6(9A05jjW_zzxXN{Ve$=Gk7 z^fPQSmtXc6J#PMJs!%P9=d$&l|2&`7Rx;=8QQ&H$&FAjw@{i#4PT!{|)^7zvH|>7V zYx1w|?$QJBNV4hGD#FBEKOC_(AaOIrs_kG;gbj)`MVzQ4FNfoRvM;q0*?rbV>50estgTFZ&a4 zFldIC!~CQLi7k;#n}2+S_h^|mOwdi6O-~H}@)4Cb#~v5`;a0Zgl@+|_I6V?PSV~L^?4|E`x?ve*YB!K;yK9vs&)l)& zpg^B1Wb8)|wf?3pa&?azNcQ~YgX6EI79%ZBjzyiE$~jw{#IV;_*4kcF(F+5$rSNpq ziOJ9DpT5Ye5Mz9C@cn@yNZe~<_{aG*l$Ur=YgU0f@e5ouT@;!u65E=NPF$rYWG&!V z@zI**{Ss1z>X}OqR9a^CN3oMShKUOF1ja0DMTxvFJt9uI*-j)FR7VvKj32(1>UxDQE8GVb-8EOd9O+Ci5}xbUUA9vXW@gY#WY>= zdoF)SXadXIxbW>LYj=m+izX5$bEYG7b>h!INdUZ(x+j;w!OykhQ6Aa+6=4@~^@G}@ zXCissMFHhL8qT>8fhc9pZ!4oYNQUP^mpji;)WWFT%qzRG9s7_b;5+>}i_)H83{F56TE7pEp(R4>4{fqc0RHgxn6X`DA4-bkm-^G=D+l@s#`;9QrZ_%w| z(S`SdW6ho@O;C~1{@4rS)ZjSV)6jdS!I-E_;NzoZ;4M?OBw<97w*WS953_}3+@W43 zRAdF>|fPTb8q3Kk8XMBdX;EC)VC1o{z^*9&iiXr2*QLM z1y8{jp#Ah4RexXqeTi;PLc}m#lOYxkdki|e;oI3E?k+1ZVoYwBnM(dzKr+ZQ#APr8 zXJ|Bla27Mc?u1Bi7j$9O?4>yt(aQ2s;5{Sj7hT@0QMK@5s_!XTNBp!bvr%xv+~R@n zm_7kxXK{BaCFnBPQ-)QDh`UB6WfqcWplKh>0%A4`5W5|-Z0zg=!rMJJA!)Y z$xTA z@ApKZCc4>Z3yv%?26D;OpC}*PdqsIg(Jhg|l|da;M#A(XcdZr(Od}4cQY|AN>-5Y9 zV-M)u>Sj9qElOWTHTgisE1S1X&95iJ@?pm5pW0?qzIEp6#URhol-9GX8I^JCz0TDr z%+u62j3Ai08{rSkH2l%YLq;LhCu)2Qs_EQzenI_Cu&@Mv{bAw?K3{*C^ZEI9UFgB{ zUEzQW(gJfucfe6BH>nEsDpWOQlrSn^O+yVs7|LK2ANDb|%1ASLUA3cj88vDfitZmf zs6Dv;o=3QQ8eDH!3OixmeywX6%;@0649x#vxpgv9J<#yrU*`H z2z7ktpUt_(Z(P!SHHFP5wSZio#m2E3dXhKCfbN>h2UA9hUr6~h;|+TSS{xF*-(6N@ z5xsB=1kx@PXQMO@`+oJv2xWbH-JSYXmqKj**C`rwxjH{p*?vHS;#)7Kf7cc@>qBrO z(;sVw*RG2Y@)^qeYI(%>scn9QRVK>@U4sTUy$2JXxm-KQO3eH)b-=(O>7Vnoy$J2- z8Z7QdutvM8)?{juSEpy{s;taYoj$@N9vzYvpzsu7h`{vhWW;}Y>hK}JMFQ;s>ywrU zxvD_n)}uXC+hw@oM3{Jx%ZJ+xLlY@16=6U5hh2_(>-S5ZlJ~)&)Kx39TL#R5Dsq;d zIFXN~`0IhQ**1~}rkCNoVivIH4d9wpS0J}-{d1RZ3n=i$LsYP+S8IsNtZK)y1=3a@ zYbWl5vhA0p7ZDPu-(d^k&ueR19^XLG?iX8_J}4<2coYuoJwyM;*KwkNlqMb<25q(! zMJl@T1|x{=d@2_~-Z=N=m7qYkf@C95Comd_pYPBf3q-7iN7whNE_@dx9Uo$YIdZt2 zn^~3Qml7>KWE2G5ciwGkhQqn`eb410^=%*4*8IGSli*nGC~s`2ufS!7;c2NwRG%Kt zphkW+WAfWGeW&WOmgLm?X*V!aZjjRdsUWmeR*clfu6k$I@h- zo6neV`!#(Dfw5r}6G{p^Uz5;nAlU~T^nNSG76(Mct;Mg&&GN93yh_me*iX*C?Ppzi zc#$tN%0Hi03UA{>JI-`DN`vdpvK<|3!uI8~i7tk>w);^WyJ_%6||OHehSiSs}?x zntV6uu7B8(jqpt?^2KP+c?Z$6C;Sj;jo_V*K}PuLbP<0)OI1EeuB9=4v_~a%sipDI zUkcbEr4m#sQtnGrY(EuzC_e;_8Y06e)z8BOMzdZL>YZxpnv*7rgN2|+ zg;KTYq)q+2yFnL`816xhioG6ih>P#Igz}S`Iqf4ZdGy<$xk7LLJi*G}B2u!WZ4_)& ziP$h9EijWw7#3`YH?hCXkKC3ye>rZW=oD#^m^M(Fda^W!uG$n<07~I%MViRjY8MM< z#3dv4M{UgqY)5g!7W-c_e+tF#%dPaI)RMeoP#d6+-94nl?4w432Vw46V4FzE-fs)7 z>@gzCaNN@JJ@;|Khv5#*smc>cH!XlA_Kp@)Xy0R^3dy4J(eh)?(^Zr6f2ZL0-hKAa z=NL71P|h?6w-zg-6izEt-m>yY1W+ubaIyhRbO5u~5WQ~};W-y$%R>Aosf4GjfJHyk z35~$XPd@m5RccFB5}Q#_!IAL6d(VAtks|N1=>X-uNssMGT^o6g!eG9vV8|ZP<9HMs zO%ge^a&Dnvxdp~U7#a>heJ=>_k93v`5GQ%;%k@2Vx$}c|Q;I=mYQ6NKwa7d8Y7=!`OtcduZDniI#U&mn1%o5~FL|o9 zmn0uQ3c;yl>FV{o)I-Ce;)}mIMs@VYp+IS8J|jE%ye@=nu0ZUFu6)tDoW7U;npOZF zj>#a5@l6I7(Mn8yo>PX3mcmM=PhZ`##M^W`z+qR;bGtU^*hgWf6p~QCn*uM8B3rj$ zOKr*Blj}Tmyu}@b@>RiP!Ed$zX4+_sGPB6QxtCyp?0#t=SQ`;T-AKOw#h?|gF7s8R_Zaj*oJ zvXV%wwd)oFSh53;>`NZN!D|f0!GPi-}!oM#^k{Wn<3bV8L-rWfI2toX>Z_ z{F#J=M&bvLKV625WwOmN*mGP*<>0icOb?g9Cx^o4@_X?8xc4a*%F>5X>EdO1eYh^h z*@v>4x)q6MCgTVI#X#!anEAUQ8yF+bvAKXFl*Yb36oOC*$8bw6y|lxV$hlV zq0ZiQQYyp$1YIm2HHB4n3|BDM(dT_Zd9E44tzw1uL4{1dyj&rrgZ@!Cfwc^S*xeY&1e^2`n|Y3lOZcJ-k#$nsS-EA@WuJRC4vicKNRC< zXdF#1gNx;5zY!rT3idg2ZBZYl6pjU;MkqbdOI3haVqQ*H$l@Tjw}X=ZA1+Hq-@YP+ z{_Zv%6e9}wx}N6HictX=jm{XmU@<}aTqWTUYsHyMMRh5+!a;W5iCFlE7`f|1mGS5* z(>e{+Xm81!LiGp!s@n2{K0-$vWQTr2s2j^E8DZ(MhI1%O*|8CXQRSoCb_WIpj4|R z`;FkUF&=AK$8=g58?VhZ?%cEAxegU`l^tWoYol5^!4A9cx9_Pf!f;lr+m7^^bszMu z87{-bze+vY)*!&X^dQ~aExxb%5$e`w(u2TM8XA9fOk=qM^ zQ`(yrKH6z~ucqYn`ZLeYzay8a@23ubUH{WHc#mO!(auX5ol%|qFoC<;{m6Rw!iw=D zAHnSg!;|F9%Sq!w&{ z=U3A`hZ;Qv*Ldsz;$~9pPd0;7bt*sIQCUG0cUFz>!MJp?2QQf;mZ!01#~ZH87lfW{ zr_~V*p4ASPF61{~VV61zMX-@%n3DN~iaAOt@PVFgG&YU9f``?Jd^3J8@3l~vaHhlBpu;zB%PyFw~xEiFwv~vwuiMg|zd8o|Wn9aGe`-Stv44Vbx_G7K&T>b}8K(D_E z#5Y@xzz4rI4w&&vey=>{wkzMXk=rJq&HyKb0yTsJAS~xK5ce?{_;LGLNWRoFH)29M zHv&qh^F^01T&ZJk9)?r(Bzvg-8gkOAqylMf&+}~-`3wYt$67-YBmo}=12Pcza1S+M zvj8w$`AadTBj%QKA6z%WQ@1w5QFp3z11{ihDVQReJcT!jw?M6Nmb<}hFu)RFpLhPc z2{i!@^?~#AJjla51QwtRy0Z_;jhldce=!M|Kufpekb-deDrlsGt)znhpo06L!a!e# z0#FVDrw_M*2ln%|Td8BYQz|0a#nLEpd)=FZRf!9= zF%WezFkdk&-|{iv@)373AVab*`?FvCuoMbD)Z#SccnO$5e21}Hp8zV)w!*qJ25>un zAGwc~GYP=JATTF3Tq-pX0x}!}GVn8Cr+6~ts=L2?sY~aP(YtgOA-y+Wr>1%m(+u2h zsR}fGB-2`2IhZpDL)E8MTJd_-XWdYr8}qF@@*y7q9)mf|!#m74#-}}>xc<^OgaRM> zLJWYh34F0?S3Aj@aXMEmOR_WRetUnnyluijfX95bX2UZeLqHzGffHaMns`|$cZ2t@ zL0aBGwiME@R4@~?=6~tWM*W97FxI~mF*w8Ma~5aCxv>YfFz7sSOMEgM13SzEJ>-Mh z*S??R1MwZ^9)^NA#DK?-z}#o=$7A~{yJYt&tOfWt*oJ$!i?MAIYYcEhD4?x12tqb| zLpdM=G6Vz8FT=6RxuzDSa%*Y-BIHN26vI0o^u;c}Z|VNREfX@Pg;q0X83Qm_{jVoO zGdKe>aF&Y?H9!Otm`vb6WXhHuGdGW3K79`%MwB>_VnvG=F=o`b{*hxxj~_vX6giS) zNs}j0rc}9-WlN6v#t|aqhi1)ZFiMmlQDVdh6Fo_s5Q^bM5u+z?U?_s)0|*izoIWM- zH0p<`S3_7O@gd0|Lf5E)%9gF%F=W4x5hNHa88KnPhz%=dY#0l>EL^xKHh1q{y?f=# z?W?TVFu^X2AM)e1hm32}r5Eyq@^UD?>l%)(~t7IR@^_bo#%rk8*I;l9I&F-92yl_}7^Vg6Dq zvc?)i0R_7rtPC;)?Ru-Tx10$rL(tw52$^O~ORYfEURx#@*koI0o_FvW&czpDj8VoJ zX{^!4mG;qRpM3BMWe`t*wC0*?ghXXXP+BPAr=6zK$)_S@D59t$OgO3t44}G7OYyYa z3aci4u?8DLx`}3;b*3>3nPW^$YoO3J3oI}f5TwgL!Tj5cFk%WcFc`V$+)ptEC3|o( zyzauQF3d6`rWp){Nk%izn)#5m)>dl`Q}}{8CYTi6dB?UJNiEgXQ&CM-RZ@2xM;uf- z0R=#!kTc0?fc-l;N{aWz;P!!OI?lu(3qxtgNojobjx~ z*ed-@7-R}!%Qb;aR5PJv%Gs8l7FVs<;)^lPSmRXp>1P~Q1p$&8Y-F94NFX}_B$Pl} z7~xl6T_!;Wp`@&?s4BVhvb$!Vm9|T0N2muJciLH}oua=j=PYpDEGSN54zv@`cIkyT zUS^!Ly0VW1tbt1upoou!ayP=HTc|7n! zAVFFYLI`1m4?>v18@{=1XPRk#`4(ZbTKfgG(13v}uKN(ov#>qoh1cq2wC+Sue8nW6xU4!eD@swK6eVPNNh{AvowPnMg497v1U-wEGoWER z+PMRFW+}%n5@Nm%CF3&yDvV)XxEEq{OlV;V|Rn#0Tj41x$F zcr!H2^9Zv^=G}0I%wXRBCm$Lwb`>UjcOhH945LcSus}n{fXnwPB|h-Etr=>HPu{4w zCSUpz8Pezm7Wt7QWX_bPHMQw&5a%jxU_%gL0fidh_)`Ni4oJ2V1Ske!jar3*8lK>W z3^CpnVk?sAavCU$k7Up`=cB-P|-|KpyHX1lV%Eh z1%nSrM@d4l>dpS7R0L)nGM=o{pjcTK&lSAG8)#jJIntWDw^A{)oB|EP-m+1>@@b)4 zW8QhU#*Dza<}^6ulb-BT(F$cRPOR+EW-w&Sg8?I?B~8dN(BT?e_A((W-7H#s$&PM- zqaF9K-)SKnVF`Z`apE{da^kq0A<@d3o@iX;LblCXX_#`i#YPJ5Sb`2rRY@Z_rwkm( zM=HH@gQ?RXAvt)#v5KGs)Ro3M)anj)u$3GqgsWM08JpmFilD&*O}q$$HNUo38R}Su zdbQ@zW4O0KU0ak!RjJruaC8`B28J!gx3;BC79GuKGl4e?F#^lRt+FYLH@fjsaNt9x z6ZZ3;0seh4`{838wK|0-k`RbDhT>Kpc63qwFe~IVE)XFT(oe4e2vo?*8NiLIudW*E z6PO@_SP{Wi;Yrr$vMyR-T>(0(yACtCgP+JSM_i9lWk7-YT*$rU8yTgTotq z4)nX>9d8-&XdK+wtx{0|2s3(O5Pmr0tgK-qI4bq0V)3vb-Zu0#=7L z)nRR224H9S7`y|>?eK*;rU7{)le_8R`bDQaJtO6mnw*~w0;x!-#yVsU3}r+k;K;FtI6BY)ajrkOS3Rx_OmJ%c4#qQD z_5Zm2J#K$`7OnTw;O9Buirh{}u7Kgp%H=cKEA*Hru+%H`j?Ky*(B?uAsV0o8XQbVlJ5p_Q0r1F z5X#SThQu2DKuA2y4+0?x0716W2>WU!IT}X~lmHlrAsDdcEtcUKh(wK|AqF}i#ndk+ z^v?Zc%mPkLTA~H41TO>b&+tBOtUm4oT7Z2>h#aKh7aZxWd`acZ;#2H~px7eI5JDZQ zEcCAI*p?w4M9&cG3d@*>hv=oEqV2xkWRlq8L)c^)kZ!1c4ClXec@71pZ)PW@hFZt>a3ftNy@| z)j|OA(C{h4ss!l48=?Un(Gl{_f)wE@_TB?w(qbNIPQ4ybAMp_%_0ctsjo3~D133if zfKH$Uf|4*#1T9fbIx#kW0Ua6=8T!fGpboCys`nu8FxR2#+5sHCAqMjd6}#acVoD?_ zvoh!B>q6#MUTf^sNK7>BR)`P@h$_TnrR=~W8onhMc!-5UgolCwZJ6g5)+iKSU5r$j6q94yC%S1Va!VcIjI>ksL_S{vqEg*Z65RX5-czsrRa`>hdfa zst(V}1nVp_Km}A|_@Umo!L`mv5DJLHlIq@iQC6C&?b3({&u9?Rgf&8GhT^8nqEIzM zX&It{a-88d?WhaGNhn%i27I$OO~5G+PdGU)|729-s`3}M5*;Hit{n0#+#?uviFc~( z0kd=T^07$cAs=my5OE0T!ZQ*JGBiv|Hc0T>&a(v1ffLW6J#&Zm=+iI_v!3`f&l;0I z^)nhcvIYk;A{U**jc#~#Y)bKX`zye_B8=aC3vmz>C)VVSM8c41=Zw;;n zP)*#?Zt?~KT~!~^vPjjEJB9Shd@YF%=DQFE9zBYR)H4&+ffLIiONq5u&ml(}aw6vt z@=TRk7wiSCZoxh)_$X#gt@T=mqr!kt7y$@!fRadvL{>-!C?97Cp${g31R7AIc?haN zm;p{kgj{xrHICsKfWbDkFdDtk8hJA*g`ysc;B}f(1Tw$^X4LRJ^;3~EtY%<2(~2IN zb3Wtht#A!KTH{qkPc08I9gdV^k2C_6bS;1myv9c$vh5e#Q8xOrEZ!4K*?|)|ksZiw z6uq)p@9CcK%p2Hk-SV^QrePyR3tRq$c4%ATe(>QQ3T-*80T4i;jl=}0U~463GW$OB z!$1LYP$8+Z;TL8oH3WiBvaBr}3T$&yHJPU!Z4+N3RSRK&;;ium>LJw5@Hi0`@irA< zHSS;!uLaIAySDUOezYCKk`U4IEVpx3(?K0P_8ukBY23zcCW$Y%?HE3=1Ru$fVD?I< zfg&f;FwX(jmuw8peMk}b->X$ zzmXeP&EvYa1e_r&f9!T{r~b$$7Ri3}I*+svk@QI8!DH(;9qhL|t22qtELSOaS9xjN zU^WwN4X&=#FB@_&?^7E3ulLRbyM7F<{1Y0gfg`0=-Mm2wy5SqZA!uXwgF*Nr_Cd9> z0TlGDgdJzL)`)kNYJaf7afHzmJ^@HJjAR_Gr+mSCuqFyS2{lp!G|VeBk~b$;AZ;TR zH|^+cQFKL5pafVa12SOMc5Dqlz&KUS@TxffcnlrV>M;G!|KiG#;tKPQfqpesEz5y^ z<3S$S_KfM}6sYqmC;N^Z(3&9oXS8=`ixN@^;KITg;RrW02~s zZf6;@8(cSpCHaH%{y`jk1JxVP4nhA!dZ|%aunXbVbzSA|a z<}`p9HgAZBV2*j2p@?r2m(wo>+Exaxu~Mz$J2t=@qqtMUN(={&4acfr!*>MeA*~|T zIq8rbnoh0`_hUO&jqw*Ajuam7*JBgn0h#P9JgV}9;bg-FRfm;W(E;+>+18{1kk0{- z*EjO6%OY{sB6W7b98+iYv+Anhkt2DM3Hn-7tI#|w8TNIMJ+<3HeY~5p|Jx}fZ|~6m#xu(wDF09lPVAI zQ#}=mLG?KPouM1l>Yn--E!YaKfj@_H~1T>!GjBWuhTTO zkd_-pnOvtS5Nr|OVDh$jn8rn;Fn|GG|(T7W;Knj8xUO;;7 z2w!=*1$eU_-tW2c4-LU8VY9-DS({Tu;HRU(92uCcAn&aJSFY-pe$#=Q*SL+(0Um-I z9*8@eKQ=A%uva@p$x`lrL9qlQFH6%QOUe3k1Nn~w8J~Kuy0TJR5E(1Mfj>DCgXy}i zzajn_?0TU2dc9}ypp$?V7+O|>q!*uww?ILfpy}U8Mrp$pC2>VajYeZ{v1y;IDQmUEyw~0HryBWugJ08jbA5nyyov!IPtD1FhHjn`T(P6BijveBe zfr0F-e@rXWDqB)~JMt#FjZ=McAJynbsu*Uo{BxjDGEnT>m!9F&@=dz{BD zFQuy4TdKJ$jocj2VRHvFo}q5aMb{l5m~^dt#b-Me{gZ>ce8KR#8@{|6r~$9X;UmfX z+KrFUC`X&NecN#n2ty1TVr7jqj2iqP3H(4b{S7ED8VJ?slxyXTG;BGx7NQ&q^&;io zAzV;Z^IdUBYnq{mKbz5400vTErX}4dO*?MUa0Ad#@Rr#EiWwXaR*Iu51s0jMA#aeS z0TgxA)R$Vie>)v~34f(Jsdg$No4}{)h%E^%NYRt-m>1A@WIZxSm9S-S%89Htr`-fGq3fwg%$;en~WS=JTT@`T*2;tJ;d zuQ2s^fw4<;&zf)8foRaAyR~J-b(ZS<^UE2t8a5c(zd;+mVcNAJ8^&QWo4)w}OpIJb z!``S9xKA^uX%L$KB-Mx-xR0UP-BxgGIb?;QDGfQUko#y0#GFa~NUVXHS0huNtl#Hj zvx`k@0I?Yc9`8Zhmpfd;mDpu^!Z|pT6v(1^^9D_t zw`tPMO`B$p+^=8f%E3!l?%cJAE7cV8ebLrs8OUW{xJbCHTsY7;5`Kl z$OKb4IGI=uPZ$0qVL29&gAqAMvEzEM<#~`R|rdn#(1gD#Avt0wqHK@D>3jQ^)U1R4oH!bs=bjlFTiIk|<{(o(Q)QSAKMZli5>HHV#gUB}3O1iu zGiN8D#5u@mY!dpKYJ+MvND_dE_Hm-daePfDXC^8$HXjc{nr%4u=84T`-sTB3$fy$x zPM~_qOs7dRgUoiph)OA`%{U{T4C93d{zD4t!BCGg@U_66dl_ty!F(bBd+U7&0od!= zw2C0muL9M_0S73kV2+RtUUX4K7CkEuIpxd*(%|XLPgD1unyhab6h!kKZa zv4-f(kou7XD1LNiTqoIV<4sTMEOU%H!Zf!jW(4DCok~V_D0M()Ozl+QQB@0I05-6# zCq1q@0Sr1ItFx6LSGW>Te+)GKg0lf@gCjg!2Ru+WyPfVK(};$HFk%j5tYaqg09;Gr zaX6JgP97}55VmTvEt*^?hULJB;~8R6 zQthGim>~qAK!hbMS#7`rD5zV4 z7^D>!_RS*Zn8`~-#^fLFQP8Iowf|b(F40 z(U``McoeT_fTb$}I}0?#5|$&4g&Jba#_p(bMuQH58`j8%HQM+_J4$q-6s@S1B3iLG z?&BWfV5lE@6AD0q#x}UA)0|+|GWqoh5QOlA5(4R&)pQ0FWPFWr0`XDOZ00oxwT&h_ z<2|>4BO>yYMsiB297+*Gl>!_U)Uq=)Snh9u;Q3BfwH873q{o&p;AIIiFoI!$H9u`T zCa`v8pRj@uA!S2h3ORs`X=KHo(s)oimtIi(KAQAh7bsIlEVBT zj^J5zwzRFSZS%5^e&B;2!rRAW#1Rf|Y{oc(!0DYfLyeMcMi5E>#F}=>G4&DhjC#To z`BW39Yw!tY=F=`JXwxUoaEyJ_&}=(eC@-6oV}JW&#&QfODpBq4l=D@GI+kOqS&C;> zxr|^1>mdVK$tnaJJm#*3IX8lo0B&Jja0utK;AD0H1s?E#3hV|9hfri97^%uUKAhJL zeIy;^@KE5si8yQ?&Lu-^7B!jjAdIZ5v5wu*j*``*8dLU1_Vh;Tz=0%aK%*?(KnrNQ zC|ZHF{`O!_LRdoyipGV?_O?{6vXzm?k9rKl8TG(u#3nNi(tN@XNU#QK5d|BS;WRZp zgOhRKca1=xA~b{gZkueQna#itr-^bI^{$bGB(zC0=HnA;fpd**JQ1GLXva@b1Po*# zLpn`626ikBOXb+Nl=cttkWsM7lANXta|ZAI7US<3SD_CYxK)D#=U&E0PV(<3b_9+%$qBA#%tQvg>l9 zJZoI9%}OI0?r4XPfiyaKfx{QjNHSQU0m{*SL!YA625Ph6iQkcQJD>vkM)LalFL<5SWE!cOB01RxnjDANGqPoE(lZU)7f z=#A!1r12hbhVz@@SR*u`kWC=-Eicj4RVX&;U;p^$UiZQhfj(dFeM=?FPro2N&NxBS zW#F}@ujhgg9-({=Lf`=X3L&!s;euNY>k@3B1a7@>3RN(TZVc%n?vyOCL%gBJodh03 z8PQ5e47g{_10H)1$~mmf6nCmiUEhx4L?Qw&bF)wy;LxnRcr35Y1_^d%0WG`*hIwc> zi5k1pH#Rt5rzA}2PU7f?mk*Bm)T@3l33tXYprZ_8NT(hU+Xp_z!3sghrZfJZ8Pu6J zUenL;Y&0>O^JZ#8i12x0&YtNLXgHHx&d`*SN!Y1(&5Vjc_`XiO5rmqkL0Nga&>}-Q zhKZH~3aST!#X@=FEbU}^O$^ieh?P$06> zU>(3~6vhEF&_au+73#!y&!$&&H!XDc5i&6k?64uk#ttylIqd{l7QtBbqIi9ib5Z12 z^7IfA@p$G2gY94>Ng`Ta(QZK2Zk*Q{2jftl&}2ZkJA@Eht7n8qXoS9H7rM1@#Xt;$zIW}&WWnMcnI{0)iq9t#Y z7Y#yogVo?94W%&80EA}tJ3crF;t+92sE+GcWpu$0_+SjiAPmI748i~%#2|YtkPOPu z4C#0!wwDh9iF>=pd#^D*o)AB)aWZrAK7yhdpwTAq;~9E5{%3c_CekMwf`A0eM?H%o z8iTMVW;9c(!5VpnCYpf_+n{zZSdG_~9Lb>$FxfxsbqwEfUo~NLF zz_1?mZ~`k}iXX6l3W#eFMi5{{D*`rl2v{H()M^&SYY4&tEMQMULJ`7N73oB5gtJZG zWD+YO4`YupfCirZwIq)3+0dONST#cN4Dn-n?elts0^91DJ&2Sn~9HZ^p9DH4SsMY z!@(!ZS2ARDCMh=?ZUQql(zV?Of!V;jLSGaly}-(xdLpa)36C&Q&0 zi-MZ;b0*sWO*?`*>rf%*z!LVQ9FaJaGntd?)i@xrKvZLiS><$LWG_GBP9zwNA=VPsq>Fkt59aV;@6v%4;UGno zbM)jRb9p*F;tsx0FXko{IL28rsG;YDp}qiGX3-5o_6;I>BwK+yoaa#3;Ca*lXsqQZ z*f5!vX`?qPJnvW!vL~9a#|-$0kNdcp)DaBMK$?zWd-vcP$#sW_Him(~NQg3AzA+k_ zgpzpDCgX!zbVeGEBq(Sm8nNjzZRk_45hwnmVMc@CGB9&6{q`}~(0HliAYU02De^6* zv_HvV6E;~mHPI41A)c1#HTLIUU;}mVkpldulwY-V!E%aRH(&%-AP^>C{bzR0bYUvs z0xi@Pm!&S7#YE{;Y}ParxQJJK2aIpW4(axw@sx7_dKE$P5NhXm(C83Tu~|9x5RoTW zn}s^jfQ=)XWP}M?*a!`hL{QeSq6&pGX#zYr3a!x!F*;fg#SjeAv5(3Sn$R(i+L{d8 z+L^%sajd6=xRr$rwVI&tJG^%d)DQ}B*c%G-GKj)Ru+b+nV-0|S8-8SFa-NB$c)mng8fh~D;IBy3JMtiixCKcu&4XdgyQItA%*)R7}mv;#c<>pwM2*b)G0U=B8fvIi6aXV zEb*P&bQ0$QWEO5BmswtwmDav52#juaxDw?604CBfd z{4fsmz{5{*4{wx(;s6_*cP6QcP@-p3qR|PC0w@Tj!~x40!GRjWu^HYoW^m|{#aFL5 zlRk6?C{nr_w((v5CubZBYZ_$e8Ykli_tQGbjDDLFEF0>N1ig^ z0WjbJDc}J)D_~%ifK%CE_?e%D%zu*nvpY@6z)%e+`cH9c%0??8s=A=W)=v2wFY+`m z#=n&?Hz^(IZ_L3Dv`@rzBVN>xC@uFD~+zy{b7Nga+MTR6yA~2js2(RG>X0pzD zcnzE&4$n;2b!A)xZwt;0>qc zqOyT+#^Iu(p+3c&DCUzU!XdoBJBRd)K5odmNHEao1BR+`C#Lay!qLw&)fuvZu=R=? zF8+fvNYESj)~@8kBts_D?(iTN!o23U(SCXodJGRBNQsrm+}sN`q6P!r`;(oR0-~6d z9WcK2A$B;6K^uUS2uQvd)Up`>1DLwgJN*klRu)@fz^43Ro&0wBd$enbt5RWJ4U9U# z);jqT7UrhF_|kZF8K(fsBe^`wxx5Z_X}?@?d1Kvf7>s#dq;HOS*)|0zsPGBgFlBbl z;U}DB^`I$HnAbn5Dc8ZHf4x*h+O7E5Ws`vq^gud|R<_abb}11d;D9E@{JC`k+q{D& z?^8a4FlQErkRg*OHZv!rn;HFzGpH~ddFDNg6dL8DkccwIuHhMVh_E3!oONhM{vX9j z*f6|kamn`r4qsUj>>xPDa1Ly~rz^n{B5@9ny%Ncd4%chaCSB5iJZcdHK@yax2p9u} zY|~$5$Pm_lNa?bzW{NBQvsiiFK%0$R(Rln~p++0ZAofl}TS?j9}va9tXFLp_nt@cJGW>9F)o$x1R7_fSf1mm^38#lW*w;Hptaj*^k?}FBEXo%MT z^iOgcpqg_bf>RS1!Xa}`ccAPJz<9kpX|j19L4-BwS(UuP&#f6M0duAU#iazkm`hAucju4tJt&;zbDF_he|IFeft{Tntlh=5Zz0 z8fTaqv|Ac0V^fZ_8Jz$Kg2pJUQLh8AqFj+W>S7U1A@M!I z67WFybe`Ny5sXY>4#F@sB;DLp)8~N(GHHD2TA0wz5j;sgCrl%-&M%5K14_&nOKHaur=$^prm9pww=P z2@u=94a`POo3?BTtqsD~(9<& z(&bB-F=fuAS<~iCoH<|O`z24E0Aaz15lg0wMKET{geeP_j3_atN0kvx#*EprU(=+y zbGL4ql3(!Tm5Z0|9JzR6&%ui)uiGF$)*6Cx=!u#qPyX1pZ5xF58YpXm{0suz$yz6D z*5Z1y1`5=*Yk&k{^OQu8AZw621$yY|6Xb`2I{6WF?K9|Wlu19n7Pk{-Ki3#%mYpQY zHfrCh<^Bc^T(@q~yseYA&fG6@zs{X22k%@uc<|=2n`h1(Ja*=$yPMa{nRjQ-UW9+q z!kPK<=Ub#dk-`HE4=FOdPtl=7h72X_>o4JX|Ww}yzxavZ(=lY z#df6W(Z?Kf{4GWZY4i=8YP!*_8r=jsXq#uY{?Ue-g!1YH6i+&lO_gg@$>bD2PU!>* zJvaj7ntVdiX-ziUbn{I(hM8l0 zT!*V))R9M?w!~tqt#c+7YaT)fAq*R88lpy!KnS6Rnr*U~@*2cs>%=m;Qu`~AB(4c0 zGsgV7=*q@e#jBG+Bm)H%#%6`=*lPsyB#_dq$qXA*{7B-W%pUWE5NN77NZW6osb-sQ zCJZi`b;`|-o#n_m$DDPeyN;dgs+(sWc)Ql3KJVWPXu`oOvcS zr<_UCN(Z{=*2;8JX$Bz#GrJP%bP#Hui858ZoV_d%(*9};n`9dsT5vcaZV!UVO#t*L?ndXQ(HI6*`C^1_1x7FN634ED*r@;A8kd{$W_5VvAW! z7#d?zwvse75}E8#B63HGc1ELkqE(S>4!Bb^y3Mnm(>KnTdB z%q2}qPD==7ij^5uoI(|jnIS4vfeMR!A`_qx(?$Y;39yMxZ9^nt5si36B%TBq(trmt zm;nr7I3*axNJ=t-!IVJ}#cztTiZax}jAWF99nDc(Ipz_MdB7tb?1)EMDAh)Jz{4EX zum&|eg}H3(crM=NGw52 z%M-BkgtcCU1XXFHTmBsL)?SSFt!k`HIMFE1G^{fXc2Ey{E_hRAo`>NXMi!WvMulgDsOv2U>huj%ie5FwYo7l$OTOJ?8Nlm;sG7 z2$2NC+=^Jy{<=~|Uf7w8Kn5F+d5s?caTuwA4kDF&$PGau8re|Q8lLb2A(SV|Y7jz7 z$ur)Bctjzcl}j4d$&NYB<-P2zV;;B+nYp}Uj9uc(7%W(iGgx5R^6<-l?K@BjV4xrT zNHahKB3K8K=~?@v;F=}4n8mn>f^HB(H`+j&36HcRow=h&Cc`NsDmS1kw7cBq;H54H&6=Il(J!$hOi1UpU~Pwc_^4bWWo=bpa_>T0f;2%0TrO5 z2shGnQuxMKzVk&JKVlgVbqGTk0ua=n3iVQ(GDC}3Sw>Zop^lc8qo+ju1zFm%xai2^ zadFK46g;Z&4887gkE!|=ZTDyp(#XX$TSH8*fM+c~pe|W{fTWg&)fv=4gsXocjh41H znMy`fHr`4CHJFr*fk5dQ-7?qd!5e1!F!V_|fwgoXrVjfCXRa7L@H|*hg{b0kX zsbV6k;7F)5@oH;?l)kg3b**jvl6}C#7fOK26>BQsyCuaceG|4amT?sXd-03N=xP2u zGS!w!odb^Wmy}N5W%U=;U8xhE zz+oVmr6t+S&NHAmQPZ|#`wZRK4XO3Jm>LOJz8Mq_AyhL_c4%t-eaFO2dD!NYhTJ!jsk9Wvzx=%&0dXX z!awsUgui_!aZ_2&fhY+$2bEc+0~(x$$E--gF*K%?WY7*X4L6*gi@8VKiHUAPhFt^1 zDI@|49fn$?JOukEP|>v=>VXybxOLs_es}uvgC5HH#WH{aj2RSTDupWcvHp+Ej4vV^ z@n2L2FvKEZ=4`4QYk6Zl$S9A+t;HNklborZp{m`SiV&a2O($t*Ei6T}lCzT}A;L;J z(V#*wpLmF4HW>(fqvA0f0R?9u(n!a2%EzeumbbXI#|s^II6{&}jaWG%Xb{IZgFS36 zM`V2`m&+Yo?xn{eiyq3lz&v6;!3$P!er)O|&G0d8H02jfGw-iq?Tf+r@2qp37o!_K z&c<%~Y;XkHks5KQ4MMb_0Xo}yryNn4oB5dq{0#_lr$aL|pc4p$%MFBJsJUtg%Fr$^ z@sdsW1M*UZKXAKGz^GH`y-&ahs*#~C0fbBlg--|s+5;)PyFnbx{z0|jhjD-gU|X9bK#2O_z>M{hG5{bE(4Fr!WYUKzwu)qGmEqN zxu1q%rkPvCWumk8DS`9Dziyf=7vMQlNtJBK#U;rW;_8{2sUW30C{Y?XpbM@e2@)c4 zKyT2X+rl)BK|tj(2q~EoD)EHtIx$O%h)=+TOxT2P95q$`sG1u(LGm&y8pI(RLOb1) zp&1khe$YXAoJV?G6MUdFX_$w3CACK*+IA zkf>8o0?)u58ViJih_2y-hTNzilK}^J00+NvndVzQouQC*_=R$Ll))N~rtAtyESGms z2TzPF?|6YwG=>+rtdVnu_P{1HQ!QmmCi;=4)9S4HfS>p?MGv6GTI?oY;27E}zTNN^ zf3lEYe5VRxlB+|&q(P_!<6zS~?^-B_b=sgTRI<8HDSat791! zRRG6Pc(qJWg;dakO~8bz0h6}_gsq{7P7p8dLbXtn!Ep=|S*u6dtWDcQiF-%_Xvjxj zz^`KvfMjqYJwZHVbHbcjhG0N2<1|kELIz2h6lBnp1*0&ZQlqf&DS3bfKk6|RLX}Xu z4OH2NPOwSLOdZ?UB+$5she$(JNUu{kmQLyf8#9d02({YS1Xb_^E@72H*cOga0v|gr zhU1wB;w_>K$^kU8EXz1a%nVu(=}=>CQ&Ii4hlt_w3h3Q0Z)*`R|mI6fOVr71>^ z87LH~v>%-`Uzi!bETIT7IHSo8Dw#~&pp3+z&n~HmR5&khOa;))1U-40J=5N}`pC zFbyujy|q%ucJu^c!8f?zFjC@}MI+E=yb%%snvV$)X>i01dOmNM25;~Xujr6+NmhD! zlyj(1j{`*(7zPdPN`E=Iu{=dq{+u(;S|$Rizp+fY81Mk}gUfCz2L0nU41*(5 zQ@~Gf6gx2egWi*xiIUG#(1?kU2;9RxSDVv2O<9$-yM4$9e0YZ|lZLNIhXw-%WC(`C zb3&^?NaaLS#9LH#z%QYlhhJE*v>+U3`-LoQR5sE_N^yrWRF!Vi9E9jU+VYfYC`4+o zx75)UBw!2|qboqDy~aqfm8?Tml}{dm2pYRFNz#mL=rM8P7zzoJq!bR``j}|YEp)n& zb>Nw2l^(B%P<9xO#)?Y*cA(ZS`;N=nP_Gm}XILNeJHKU;7;HLAS#%%!SOIjUznQB! zQ~aNGT~}i$1{csyc!iQOG@c|7C2d&Da{9|}I2tF>IzN)v*_EdXD!}G?r=v4ipxcd6 zDhPzo22aZd!+;jkI0ds~-c9%f5fr;q_@PYz(@#hRi_L^TIE7S*s2yTn9?}{>z&$_^ zO*2h}QlPt)U0?P+seQl)dYA@vYM^2bi@y_wn>Ew}dqU@ILPY)FKSeOhiwAY-Dd!*u z=tzqQlQ4O(HZ;OiZxE&a%Ld7bk}BO)Pr##8frdi-hGuj`=lffp2@)Xj8FFc-NL0m#Z1eBqaJML%p>CjZe~mBS{RYf&p^9~hOaD1}lW1v+hCQ66Qp35kAy-*-@_N9l?u6ANVcJLfc1gj~-5 zMbvT#S^*Z|vWQMKS`MF50(HSoeT*>bhz3>h)NV_H{zIB?=@!k2uD42pPv{kvM8i59 zmS|x;i2k6cXn6>!5e=ABTgW&yuB}7dp-hCZD?*@D{rod&rF3b z9aH@D#!>hLv1?@JeKkMWgi@&3K;Y@`JwZ}~!Oa9yOhDg5z6T*9Wv$+7Hc^v)7>8BP zvVA6w>$F06_|pJDFr4~dpmk254caz}2j?t@$9sL%gqFDiJ6HS6QP6`?2sP&Qk}=KiaSXxe9n(-7g+B;{9>Tp>qX=*$!BNlz zPxfR!*n@lEY6`FLn%IYZ;0JuThgTw(uFwj7EDN$&oJK`3U|2lkL{vO!LZEH_BNmTq zxqh4lmdGrGRPM=+zurG;^uKRlo_>ukZ&4LOSWnZC3_tjc)nk>_Ktt9rD;et&QeiQA zW69R2B-$&lPB<&eG!?r7mn2h0mpN?=Qtb^g5xi~2;_499-qUuN4kkJy><}NteXNih z27~^-$pQu$*cX&DZiX%x_DNAwbnfO}fftzWTV&VL{RM=GF1^Ye3)WO0i$+xHqv6Y( z{*#hZA-(3YEx+_vN_XApg5%qDn)sG6j;e@L_yeB|orPOdZ3D)M0UJ5C(Y1}y4WmOA z%z?xxMM}Vdlt_mn!bXf9-AIdoNQsK5ba#n>N=b)$T`W1`^~<0R|%0JA=T z*&M(mIGAAzXR{+k-cXC>;!EW&`URBWf3%r(lt7%kwAoG{GYlDk2{{Y#VTEtihR1&z z9v>Lh;;<};I%GONF5z(cCV5N4ZU4zsZS*AiPv~BSK}4&mMN}-LxTZ`vCQ?2ght> zd6`^HxTYBtcspD0zYXlZ*AMC!m@hN#gKuW*|Em9Kdod;b?yOCHif4#7G=7foSp?y~ z+;nr2aC5UWaJ|cT{nzKsZvPK`cPGyti4CN#nNXIJdCGJGRtWBwO3VeS>>oJPTh#kO z8|+INnw}FwH|!g1OLUn3d=FcccdXSp{rjDR)KJvqP~lvnuxx8}8?7)f#9^;sTZ1lG zs7qZoj{7rHW7Qm~vfdr^VIWf}O7&e&QbJpgnsDt$#0u(St_^OpT{h&wwD>- zk~EC!eb?^7F}(iub%p8O+qXX}Tr!PoYR=8F+Und|?n{7Lp+85nW}#mJi5|L(@jF(ApDn+`<3BU4 z@-Wc6f|14gpW4EB^}n5KYK^}4U3bzc!I8or_r zaLOOA_Gc-zY}RI*K}xXM=bY2sER|=ZjQl|uPDW!`95<%3PU^J64{PJcFp2S9^y0Uc z4&bn*SO+V}tnYV{j+FNz9rKQu&wr8QZtZlrR1P|~YNalJ!QRR{H&s@1I5G9I(c$TW zyxM=&DfQUrKg=C$*$V8fntZ(+Wb5k|1Y~ReR?}o_@+lyvj00PX%MF`5MUS3tmo~S) z__o&kIOH^p5Ag+j>DXYQOKVo`TYh0yC(=1GtCOz1C#?QjeyhaqR2k~*H=4h~2z=H$ z95zGisW6-kgnt{EG1~i)EF3&^8^?oy-n|Y+&!V=t@KcC?GQ!s5SvVu#xJJ2GD?EQH z5&fp?hJ^fQOiP-aMWg0@3z8cL5Yp806e7QRX1h@cjbP5~_<`BS+u>Jc9oN3eA zX|qwjvY$L5_KL*QY5+W|!ERB`2vORoSbWevzE2b=NRu?X30ah{B{ODHkTvo(#49x( zH9#pM9Ki``DzxJ?`S-7A@5vzaTJP!5J~T^bv1KRI@O`jecIRtT_Hcc=wo46p_b+$2 z!BnhZ+_NSO!TD!yPV>v4&gU=6^j}Z!l-=rnetp$oF?>+%15l)kZYE$X9S__R(>6Ly z%@>~HiyK>wH1Nzc&A;JUIfjog$&qx3#+rQpjh7|O!~T$2K=H&`g|(fO|9p4gn+M6d zz5Q4}d~Fh&0f}3oYoM%N*;|Q>@Z8wqI!K~P>JUm{9D3mZ0mW966%)Tb zs~p0^nga@Cy9S!x$9z=EXp>MFssR$5wxdSNWK;tDCS5qQrOe0J(RB%8k@-8C^)b`l z6CuWveLKZjIaA&#-*|`!;+odZ;9Phlh= z8@NKxEY`aH*?+Ry4vj1w7 z+~0d9t7?|0&(dD&@Vih=O~4wJfCnKC^V0DA-VqkI6NgS$(w6@t+ZHncEUl~amzlBQ zC70fzG;(_EQahAlS2;hw>QFR^|EQF{3?OURf-a9iib~%p-!NQ%8yid&eRt+bvmlFv z*5U4)5^tvJ)f!(nxa53zW`?%?{wU-Ld&!y-e`n8Av5gbiXV1)U^v=X6OPy2RLXP;b zl90BKecweY`#d85o`7t8;fR^c5AEWS0of>i}t_7n1wkO{oC>=-}(@0WI7W?pJ zh3-!tY`Nnau+3?9|3Tn3U$K+hu1+8_2_0&JzCDXQKB zpwRoRXZSYT^h+ff1?OQyE6ejT@iUGSqkw(G9sSvEi%N|1LDqO(Wbw4vzFk~#~wpLCB21b?^EGd~5 zU#beYGUg-waS>k?lEaLd6|WrOF`B|mMOW2|4^{bzG^6WlhklE^zK zit}nt=0L%Pw$?l}V!}aoG{w@3<)g;@kd$2lz!E@_Rp*~@`EA-{cbWyOqq~*)MKz7J z{tkD-)FTPDX~T>{FM*O}t>xyR2xHb;QfGban7%DP&k?G`SYzdN(ZMOcmm?*6X;wyY zw!9k#dzzy}!$8&A>F_q{@w0@Y2T^%5gW~KJKT1d9H@5EI0AyV=Zydv?Y4yR7av)$B z-$#k)KI^ki;~gHGn)jS(-{Ai$BzRb~S8S(P0v!vmh!A8D6q6P-OOYxL!!jfe8$$2 z7jnQ1XPop;Wn!oF(+YW3T<-GT#V;Iyk`%ivoPK1@X$+vsAqq=b9Iwhha0uG*)@G!Kh zRy6^GugHV&vs7$sk@h*>6ihL88yvX1fdwY61M!YO`9{qW)1GI_k*RX!fN^6p%grH6 z5H!_`7urna2I{{duJ!8UY^KG2n0;7Ev=U5m$`1UH3y{qc zrfSmer^?_o0XR)MPTOO7v|p~&T)6EHlO3eP0MZg0(rx#7HH%y= zF4eNoL>rc`yIOpTQQE~}ocANVZa7bE>d{zrpB2C4W+AbY)U2rbuGs`$PxXRH-VXMz zz}>*-m;GqKHH}L_L#(NN)aQ*AIyr;ThB|%NrA^~m14eAVp(T|XjYAt{>vEF_eb+7; zy}|X)Ukqd=#bKjGz_zbA6i*zn^C@JA4*}nN|G(FR0IxS z4e;8&OT?S_dzs$S->j~F;Y)0oG8Z8HS5EcnVB!J{&WCSP&BqJG@8_@9%dgP5@R=!W z0@rR&r#$gm3ZIq_D%Qx5(t=aHRQEJdd-_Zz86^OD67HPqhvuc25BZHfUws|BfoZd+ zGrui|1IFBz&AUebC$J#vOIg(C%=5mg7-+U@X%Wi{3M6-9rxG6R5Q!Ouphn^s-ssJlIl#X8f~TpZR>gdNG=jc z#1Ukp&#J!by%cy3L>|jVr{-3f7QQl_W{CZG8Lt6$RR>ZvQLLK6K4(@q9pxGAp~F(^ z3~jxg$G2IACWMPNoQmQFh_L=Z;N#eE#2h%Udy`c>$*S9Y7<@HNLyYXyR_!8MC z7E=-n0jiL~oQYB%3B!S%#w_khIQzgN znf#aXd?+Knsov6rcF7Bo5Y5`5yd8?_4?Xe2!lZHR6X&0#yFl!1xWmESgPp|6BZ)Lc zpvy>>+N9(>ql5Ueun>4H z>#nn}+?3(IasIsC+fn$Xurhtp#)=evd3frL#jnNd*L?SYFx%Xrk_cwwfjq}7<@!}REy z7og7Ev>JE24+VBkZ+Jp+Q#>`@w`@>K2xU&rqaV31H53acap#x zGQun}cr+5m0@E8nWHdo+u=AKg`I20uGK8#Bp!&0hf@&zg2VylGi??Nr@FWM!=P^uoyu*yC@I$t;5G26~p)dYapKq6?a)xG#W_5o>-S!^4x9blkHf1%*x zs9Yu;=T_3OEY2irF@q?%&HND?EOXI!sOjZ=q41F7^I|O8b;Ds$tvql+K64?y#g#Yg z#Z9CJAFBp{b<%DgrXTjEt0pC>SW7L~eFoUCFsRA&+3Q!JX5TLjbmBaPWzp*mu^g~C zbD-5D90r%n__%$&^8-d9A7{05JL3A0GTgh}AFh1WR=GrWxZpAn?x|5_~h!04LQ>2eE2;qVEmsvivUOy%$U1^zk*kc{d&|;AWYD9E|$8$Y% zi*DDedZHc3s#Zy2K8+kqE!P@RPy|!dELm;-H}K0L+pGb1uhM3d@lOhE(gOeO&s}8X3p>B(#F{v|!LT0vq{exMvq{cz#SLUcdBGKpTR(ns6y;Nmy;@Sc)v}xv3 zuX|C|DA)x8hYrz)-Eb!=vf%ox)4$%MyVWf9RVp*jIT~UP|#f*rP!9vT+)9B;h16&%(Iyd<=3%=0kW9JN3y#!QhIjcHZ zX^xH~Xilmp5#irYQ_7pa8lVJaO^Pv#TwmuR^kYTP@ZTZt}xP_S;J|E3PTVSg*N4&3U8CuTxodPbqh>ERqH7LzUvD zuo}lwFSwQleBM>eiuN0|2xP%2yv^e`Q;;8?e7A9wZ+BDity`*!)oSOp_9p29$V3R+ zCiYG%*J-dF3rrk)N9g?2Y23aP-gXf!1JvmF@Ml5WP>}P4aPbj{K3r$LAWQCAu2xPN{NKmaQ_^;oG__*y%Qx)waV z?Zl!EJCJ;UG`9OGy0X6^-g0k-nemxpopdnyuQ}Ppz?l`GWAio_IH5yx?hbsn$s;D) za&Byb%5XwQD8uT4Lejj_I{YZJw3+xP!7D8FokEJ&x`+uK-jjmLJ`H$3`(pDO0~C$# zC6;ez$&&eQ+Y5|pPo~+AV&?f<_?7v0wr?ce(me`FK3DeFxffcRQ*pCkb8|<4L zyhA?;E;ia0I}~7R_Olf&OIN-Abo$vp?76q+wT99aXmCi^cqj4mK|YdDPjr-(QJ6>J z3gjg;@#8tQxO{nY#V(EsN!$YjMzM=#S8q`#YqdZ%&ygh*%E{!a_{|>}+YX&BMv2FS zew-}Pjbe!34nJIcc;zW0PU24F=k@2(LT{E9;SC@*?`gs#KdcRFXHq@k^Hpu%S8@Lt z$lACYcbDVcIt*P;Xb`>7Htz!t%ys zWBxJUQeEFW&r(Of-rRJf#;(ADF^A(LF>#Sq9IcrF;0rpKBo&j6@__L{f`Zwkjlp3e z@n%=dUfIo#w?1On1sv_=clLJn>hDbmxymr*iN@kgbSRCD4zD31b7cR}gwy8`<0W~% zJ)nA+YdmPFlwp0egc7tqhpApJz{r-6<5RVZYvL%$3V|&1rwReULv4Ef3}=UNVBOJ> za<_rGjK$NIsl-RNI*7o@UWj2Jv{z?5x7`+95(%|DJChdh)15~Z*b!_KVdKip>qU#qOSGuB!FPI*oRJo+MBV;8)sSTfXMC%->}Z z)n7A#mgu;8=zsOEYxn0#l3{CCrdWK|mmk5p}D9>=0Bn zqk(sV6ZWLaNCqtPz(}URl<_Py&qfD?pSXF!{3DdKGJ(&Q<)7?m_51Cl?E0LSb-46V z_jzI8L|}nXjmg#fN^a%OOqKx2a5o5hY4$YQr7H4_SFa@@*cUQ%*23i~oX0@*A|3{Q z^@8MYXqkf0jz%``TtxEaN-wJh$D>qiLs@5If2;zAvK#l3QhanON@_jC3!rU(@2bfC zPp@}8SYv#b&+=DkWWN2EqR95pi}RCeN!OvWFj-F9wsbz=zdV85h}0z*lJgGT3Bk>r zI!CmGRDv?4nF`h39&dSk@xLM?+Rd>bJOFO`{YG-?ob4aaove|+#qH;W%V1<)7Yq0f zrMEH*Vrcs|cP0qh$3M8GW&4F*(UbKj5ZS!r(vsilqe~6KT@O`&>0joy4H|L~O%<$Z zVib<}1&!?JV4C<@|J!*my4IIGE#a+Yn`VjX7OM9Rn2%0wH|iI-kT@**MmQ0Z2tXyN z4@3R^(p?Ji^_J&I&5|>G;S@|&z1__6zFv|na}KBPPc^s21;Dl4niSi)Y`(Fhoqb4d zHwK<4%9@b9&Th*SS(k-7qLVa{+XmUOC{%tLkwD4GSu;iIDN(+#}(Qq$sRu_9%K8VUP2NoM^~#8e3AThCz*kY3D^Y^)+^;?N)jAG%M!#w z=z591Mv9`#z$yNGCeIgzE#ixOi`{#erk=s^F!- zz#YZ6G`{-=MTv&fH$;D?lH&IeNClRg7+~qBLE0W~&7&P5cUUcSJcpodmnr^HZwEF# z-}$hgDzR`z{R9?jH>E%@@ImyR<itKBU;Qj@I)We0^Rx(a37M3p8q>&j7$4Ph^No&%WU#3h|+4B0q@ID;5?uK{~ zxE~?Zyawvf?!m6cylj^C`NfB;P{$`Vl3InfFFoY1ix~40p15f9%*%LIe43wt8`x?F z3~50dfs4qpx^p8CD5SXSmek=)23*O`Qtia0N@xI*&y8&E>M9&^>UgpH+Ze zr|6sW_>LBjWz&zHrwLHdzZpl|enk1Q`Kn;Pi+YKGi#X9#b61M$#%Si%_n}3v|LXr0 zPNDy5>A-*~H!Gx(v5ox?{C^yJ&o(LD`@`gk)m&k9;wZt zO0Xfn&&-rN0#3EFomnqld&&Ik(LC|-=jdeZzb6-eCf`tCP2fa;bM;$+S(hsQ%5Bxv zjYl>oT_w_TJxI+QCNOsOu-`b80M&UUr`a|2H~#l+;Cfl-XPd8w(%LKiSz1SzpB~DO ze)fOYL;PtMi8OzSk57H*46T(ktPW}~d9D~Rfs$$R+WTtJ0rf!Ft}U{2+SOfAs#dQp zpOwF*{0IS@s;E~^DPY*=ZESNK1+4Jh+g$Iqo_}_m1$&QV@bPa=xT>GTE7wIk%O0j6 zkyIa9exZ7N0QeM0Tz#!A&2z}9WwemfGr~{utz$~2>?T1>Y6ncO?+SYUj~&d3Bxp~; zImb2|JZ4zbz^qaJQYQ&w>mHy=>t*V)|kbK_w80u`hiegzfhd4WRSUU zG9i60L1N9bxpm~Qj+s!0!7J#O(8^I@2U;t)_UHsrUuxkYW9+*8f64=Wu z?!yK1dT8wKS1~{VZzemDFh(bY+?qO-zf5W!fJHz`PFG^+5*w7s^OU8fkF)9CpHCX3 z^uD28g(=1-PbQL+eS7`!T{MYp`J>)`aXWl-G95VC;-A%;HWld0 zSoM@Ju$k;*&OVV3s0lu92@dS*mt_qg0ot=Q9~gTbrcm(RL)5sJw0 z*eo6k=X(mj`Xo)6j+sM1OZ=W&*Ps$dpSPL+!|3=`I*tnB_+5EX*h@yf!K#dcT#v00 z??D&^wF)bks;S6lWXY%{G-;uj z2PfcC|JoWp%`>dN&idT5n?w(5N)RQTh{U!UQK#S^q{k`|AP+L~-pGw$u(SYvva7{x ztzXT{5zXyAhE>uO`- zMR?7C(xZVdrkIV6{;v)Qk$U`BmeE_Acvaa4)fS$*cnq}8&hziK`LVK*-?VUZIXWV>V$R$r67I={PqPSYFuv%d7uzU{ta%?-+lz|bL8RcWa+?`Rs zlwa4`I)rY=^T{f>lqOmLExRCtYJWjG0vMR)b$k;r0JpjAILVX-q|kxqzk}C^b!Upi{anA1@WM2 z9q@}wCx|@{(XH;|MuB-k7scFIwOQuCV1)g8h&I|%+w#Ei^l`8~YX~3M;L6V$CiYrR z1kZ@)$GGLN3vXCXJ;UO7eO_%TRVH*(j*Wc-_Oqs}yAYtgL7{UD>*J~Bpf`thyNA)i z5?;Gm4H(QSBC`?5Q8L5+@c2er@_`RNy^Eb8O2Tta6Wle>xEF}=mZ+<&Duug23M|z` zqw3G+Srl)xZ9yVm_g5{MC$30VU3|6MkPH;qbpM3Kt>L3uc)mF!z?C@u?-;otBk87x zxw7dEu^&lse~JA9pW5e_se6vB2Yt znTLVz?zuS0{Yl18LA@~TTJ(`98)J{jP?71PH2TXh_pkUc%oRFE$;dB^xDH1|L6dRn z7(yyH>8+?mr&K*n~ zqsfFW*#Pw}StZ!{iz;>wm#nN7tHda`Ai(jyNKyja=H_3toAy~c)&h$f)W>U0JR*hF z;x)`yNr;qnB`D`Kl)<$1a!e4myDQo|EB}!1KKF6(GacI7QQ`TM_bfOV)0cQ+qi*bV zzE+JL=Rs~Tv%_nr#_7Ivs&nIKwJmXGeuu$KGykD4Y~mk^#UivIMvf0{2CosHh=2Fq zh0IXo<-@qDlMIUJlWQ$EpD(R=e|zZprfS(f*URZ4dHo`p`RaR@ z7{jq6hDUUIhb1N#8Xv-h)TaAGE_ZRaH zMk@;ePc{oR-#^xE%}LWg(2+uLs{Xx|WWdAp&#ielr>S=EwV%z*vgq7D!E7VCFKp8z z7P)Wdd9lz3e?+?j8k!AplyBZtRRkybxaH2qs6M-tbsIqU!G8G@(Stwm$?t#=Rh!*G zp;c}d7nECl`GqSB1;05b4fP3a)`tdan8(^#7DMejV>7!?3UB1z*6MPvW%fDwr{n$nR~Dn zn7CS{Q-k+yRCwRb)V(cVBuXNyTAc2g5VNiP!W>EY{L^XQC*ZQi!%RPo(kPv0J)r|7 zk=;G<35f{^Xp#Awd)Z0pNckm%NMglW2hXdD%gJ|{!L1nUGnl|0;O-vayw1b7H>6yb zXra^3XM*{F4uFEsp>E7iey{`u^k~*OX`#fKq@tRt<8`M!(ib-ejsF5Ew+C6H#0>p+ z;TQ<&Ab9pH^PUzYJTHA3&eL5iX0`!F`Zi#xq1sIjJVI!u5s3T2sG8(Xr?k`IS}SA! zw$V6rY%EO7hh6j)rpU@Yvfk6>-?U~+{Kxj6{&D@&C!LRnHk$p5CLDevy@w9FlCx%b zKL?A5S5=Fhh~m@?$B&&4^8_}!Q|4kVy#bWBd2Dx05Ma)hvJa7(ia6M}Dm%0OGCo

iPvE_4BoM$F9{td3l`G$KTl@(8IfY^gemH%Ni4IHNgh_Cb$rgI)pQUaf>x-5agcm z;oU9FGItdmQU~Y!r30DJ;DaLu@v&kY?ipLgJY$=iG0^`JR0jwX;H)YNr_XjxU#2wg zpk#v7uY?w@O2((x`oFd$|LiI`y-`}SH==UGUpZ0rn?Zl7DCZF?-~36svw zv(Ej=3g$3I`Lmzf)A65uMl35%z6=yed{>RTdUAcfkp~;GY|~&}!c=Xy3<5(;-&iNG zpe}%`Oq1$!&EaL_ZAaOM9xQODhcwMJ*^u!9A~Fw!Ohx3o9uN_9Q-~SL$B2?F;+@ZI zChAvQjTH4R&S4kz?H#Lu`DFMKP}$+YaYR0xB~^rOWH%y>EYv`X$miM;L}fVNdZMz9 zZHb5!SS}HfujfTWB^@&-6=s=sY)Stj$!CsDl;-xiy|*$}`lb&I&EnH$W-t8sc(c-0C9; z>RQM&ao>__)@q+ya~351E<`zBoyJFmy|wbrdU|)m9CWg3?-Vq0n|mBAh&@?yeLRIgII|<7kHVz+Le|{J|q?-i+7BEH1dz3 zp}azYUMTNxet!-dAGH2CYI*wQk1^&RRix&kaVY=|I(6WwHs!bQg}lN`XQEYA0E!Q} zt-dSb7c9H7bQfB_`x_n?Rzh^ zugSLQpxc9Drw6inBN&bldizjPNrr(Ej$oXH6W=Gb8}ut6qbb!{s+<=k#)M~Qm(J54 zBWbPpU{OWuel$rK2&;;pjjJ3%V}|6Q_ct%S(L7DDYD5NtA(xmwI;NTtw*y_*NX3*y zAiM;@NwBlsJl@k4txq6?;~;qs;nID-efj9Zx%9#xH6!&~Avc1>cZi&$psJ?gn+2(d=MYn&?ZfCEaK_7#33-m8eOC^vv@|;lDZ# zX^qyKV2uvVuAj$84OF*ll>3taz=Ui75$|w~3R)R~JQFov4KJvq`~hQv>|4e5GfD*Hp(; zftfPyQJ#32%g!K+T?Ah-v60b|!y`k!eoglyw|25_X5N%Ex&c${@6cJgys@V{ezJ9o zB43Uyyr}n)hzxb|89u1X(3|zV8e+PF4_D_GnKmUvErsCK-h(rC+C7D;b9kzMa|qlI zc4jPYLbYp#HT-^>m)_9~;XH%+z?$IcUfakti?MpTkmgX-lK{mq3?R5`uOCGYs!J1pzoPC3q>;!lD4{Jp4ynD>LFy* zPj9(m{|Qp(a{m03h`sAujb~8th>VLyM$$XcV+Wnr0XzyzBvHuUzL9`)*8TUbSvf#8 zM{Dq~e+-^3%bB(vWj0owYN}kMS692ZqJqb1Qpx6Mm_Eqt@_OdY4bzTWqC78tgWJB44Wo;E96SBcrNiOqlQR31gFFgAOuBpx03$^saa54 zrvb++FBm`DvKLLhVBVpOCg9nnLE1eS`P$e0iZ14rjz>mz|1Nh;KNmN&9}KVJv> zdGT>A9}HYj=499T>&BWd#B;;8rcD^yO=9cfNRa_W79qHOfiELWIkY(g$+xUR?1ff& zKA??`O?mhGc+Cn$&+8UuPq?ijHMXj?KK5($+wvaKc`aa6B$fB=spe>o=nP3y_ZeOv zrRlWs6fjbr~N@PG*sry&SS zvP+c(<+cF};Gn$tsJ@R*H9wrNn$Gl}PV@p~G}K(B0~N9AjMnrIyN;4yK$aF+WG}Lj zgW0Tt*<6F!lJ#P;YISiG>6ZnUx>u6#|BUKN(%qr+wHKw9K1+Qy!uQI-rP|7Ap<*VFnRS& zX$&2wj0V0n1-{t?#l?F#=5b!L6=v*Ve5*ml>MH*mfm$of+$x)z3+;HsxTeIRqvfvSc21(t9>v@#g6PCs z?}_^qEMI~FuB!tnRmy&K=pYpEoW~W%bmdPq=Y4ffHz&^G6G6p>kneWMUcl>8LbBfR zKwFQ1qKK>5P-zv2Zf*h6j)_eM>!+}-n+-FM?9{8zN3}=LsJ^tMF*YkES~fIBc|qs- zvW~x=dANK^1XQ|bBsE^7nDW-(-#NaWc*9Q(LFVmuG8g2hNACXfk;`12r`^kHK2o80 zoPThTzW{l6`$_sTs8W7od1gwLZOrMPV)2Vz|uU9WNCfbB|1UKb~W5op~373Ev9OM+s7m;ES;Wk(R95oRL`2 z_J#U6VQ_>~L=>@r4!qMB|K_1n)-uuKx38X^F3zjAK|2MN%bvqzuJKJ*y`wg}5S4p{ zJv4^>Tsh8gGo?`v07=CbB^TL=9nLZ=dJiL<6Kaum;6iOLX;q4@?;Pi_b}`wx!N)+Z zvq)*(`%d~mgUP8Y$9&+6BEY9AfW-+Hlo_|+W1Z(^)kWify8<~L;_qb1__zZ7C~K2h zQu=Et=&Z{IAPD?-0rX~*BLNI#XXiY?3dZjy5f77Q9}4@QmO}`fGx{LK20(JWZ47e- z^kXoxD_^O*<|i>ZqKHGqADFZo($iB>-~l9>g0vbgl#oIJdunS;83hB@C{NxmzqzS`0Nlhd^dxZVP z$mIy*{TxFWD;A-)p)0C5E|e&n$AfH(li2DxfT4mR7;MNtUat+ZQaqgQcp#EDiFbwA zNTw*o&~_DwYju4AlEUu7>1@`aN7eOj7SOj7bs@+5yUhWt`q-?`>&C@(fh86X5|PnV zY5am;b|QN|K<}C0Rb#P+>$e-uL8dp3I8aR>UUWEXt;R034cNVAmmCbpy#&f{tH}=rx-dec)Vn!K zJ_*KddN4g#E8+)=0*#A7qH}9Ks&e;VnDs{vmb)T*s8zPLXe_CAS6>ExB zG63;i%Km+ppRNw#j|O<^ThwY>q%PKe=ek;+h*ZTQ%Rfe6vh%0cTI8kBuFSDrjIS$x zQ+Q*u!wpW$)2%OqvDFE5NmF#oVbbn??EdP`%_&`yfBVax@$IxhS7pEto&`N0g|5-T zeNPQRTO#ihOXda@w8ZZo07}1`HNGcx4+>{Ah@`z5xLZ;U`$E0WAoYtdym-cQ1qjl> z|H!vsDfzKXc5yE zYO@gJdF~w|=aSH!l?Y)yAleq{>Z161lk1CuW^=Wu!kC#j^}fKv%j#EoUwb^(I0(BC zr8yHKF`UqAD%9Km$$@+(vdryk`rY?zwS@$ zsZ({KQS>@hT>7{IV?wURJRC|f3FxoWwkUUCcbO;(wP*A{>f?hO&HnfskR-zUQVR_1 zH)Q8Gtc$*rNip0-D=2O$2=p7NBJLWmxOFTT>tRYa+wKes!!{laWH!OF7cLJ`MA(wi z6W=l_!N3E#%H!&|suK?1t>Lc=B(G}HQK%po=`|~YE!|WB=bM7wWI-WOd8E-_2hYo2 z06ov_UPff6djNmRgGwgt8Vpp;wJscOf#@{}wGiWDrbnt*$kJ3%pKk7~jpd3!bv01l z<)<&+i-x~aYBdL3wv(ae{tY{bPaJD|WPc?B+g^c)we@crC>sL;JL$5d@<^;$BhYm%u~+4P;nwFI2*T48Vni zzV~8Bpb&2!^IDGgdYC#+)gSxtbv@x|{%7W?fN16@{s*?-AgX!swz*EMCmHCx1G3pPv<{!Vu4BhZIze?Xop7p*W!9J$&ya5YTnPvtp34kcV8b9M6 zR&g9d1dHPV>oH48Pk>4B08QB?o);XyouaY@brG5=Q_5GhkDPQ_%p>hnS|d7ElQT;9l{jy2Y30;V9h3AKoi%pFaXaPGnW;T!?7`A zrxLMLT!sKUMHTWSJZoY!^ZNqNoQU~-E@XKja=SnkSYQ<#H%AH_us2furv(Y*_9+~@ z(D~@Z`DB`FXWx|XK%FP&_=P3f%;87ak!UaD>duFwgi-LsFGX_Qal&iT#I8EezB=Uf zIR-VshIQmEN62bIa5(86GF~}bRrT`A^NDa@6Yc)xF6T!eq8r` zy|3r%`ReKHvR6s@e&fIU-%o>1oOV5xvtOPV5aPo!+PYbqk1WnZMTheQ;(6SoYnpCz zn`hM|6h;7}cx$QB!#w<7EsDaLPIa(E~@_O5E)@^?Ft+f9*sX`A5{|3!w1OlP@Q z7rK{ESf%|De7Yy}EPCtq7T9QAIQDVszVGc$wpdQ<>23B6DA^8r?|*`NF3`eC;LDlo zcQ~k4GBbZ6GaFxc|MU2Br%&yl(KGHO>J(dTt|R?GF+}P{w{*V0%#2!L^9kBjLA%^OAl zbcbCTXA9Y$77sw)7^4!cbXYzXS!Y#ipFWd&5mIYE>XHHWvx%CT$%=e#0QIZ*j zgng!9o>n%}h*&L_U1V;@Ac0bN(u;I1PL)zj>e!o7S{En6dip<)&ZFHYb>1{yS1xLH z>d7*?R!ce2=G$y$eHNWARp(a&tW`eM3Vj?lowr$1=Xl%?B`9ZB>b&bclz#F|f{e=^ zZ8Tr?!ceKp&$ZkC1|09tH!pP_D+FTH{t4}$3SN2^eE-;qiU_QHVw(DJ;{53kAEJKf z2?@KMTIshwr_4UCpjv2hKl{ol^8B~pB|gXMht>}s&QJjEKT*S({g)Pal6kK;&$14f zO(6cchA6ak;bBr^WR%kWHj4Nnb8S(x-ZHF?plC(AL*SLVV8ekPyHE_$ z9@m+sCCIPqB-Qqals+Jse-}JJpVbIHo+21wEQK zcI!#382@lwVIT3O_L0Y}mG``I?CHiBKi$_yzTcz+-QKPj1(lCnEBf9bTTNKzqvUZ)eR+Vj5e7z0>kwo6*l#%kBE9#J;?V%Daj63IYY;TN; zhMf%K;Jvmt^3RNCLSyjQB^$Z{%9RQ07z>@ep0(R)8_H2ORN7lh>4#AbMU@Om0$Vhw zmC_&?Z*gkncHUXTt$lW$H3{>#mINuHWl{u-G(^putZ9R$*f(7BT48{+dZkdn*lV3U zqECxXF~5_u`r;>~%YQ|V1M<3GA5Pyt8accN+^N%9UC{!F{0Sr2PDE(Bt-V1Ze6290*~p~%&?PvmXy7otKq z2YHkAa1GrKjP;Ew?UTW@>bU7?o_;<=3EVgq90LX_t^EX{7KIJ(90JFMtAOSC^fW@`RS+=p#uwWP7rAa$e$HHfDrcLvmYk~ zd0ECGlw#NjW1dh56FDNwLrJz^v_tFhrtqfSv<%gHX^Gf`tSCec;<~+LoP44|UJcIJ zD_JIUHMgRhCLG#p0;^n=(b&qa(F?W-2}R~^Y-kE;xo@8M;#peZ`snez__dP}C1$!U zG3h~)BskA55YdzkO7@SFFYzC))yWyRuA%#bH|5hDbP*;FtwGvvxZX70OsWLeIz_V_ zJtj`sdfC;MyNC)nJ&snnU`WgvIC=GMzSopYAIx~(P zaNH9AMASwHDPy4&DO6w#l)!JQqD~BMBFWlxk%h&pz?sXg z(2b-d+;`67PjD7OCI)C~GaQsQ_Ts>~Kc~R+8;MK>%CW(wL4tJfBpION@HYJhG&$Fd z{%vK>u2$jwW}c(>OU#pj3`dEdC)da`>UeXJ=fO7DHaN;c(x3EP=*q~y&o#Hjcyj8R zmC2P`r`PrP=}PxR<6w)pVco}@-RdBTfg%T%RTVoN+- z0P*C)6?7)Yj?GvbG}30UystyfxRnv_;}}yRm>^*?7#iP*|5{;97HC_)3FJS;0!;Uu4Y^}RKGJ-ttU$p4zl4Z%d=KI ztsE;95T&WPLJjg!b;t-PC%k}#CdL^xnd#*iYAk|388mAm5nXm#+d)3yPBBvP+ZWol z!;0p-Ubf*!R43cKN6<8;Ek@9xqG!tmAH^4Z7YVJjZ{8wGRSn1puyhS2KHbWKFWB;5 zePBUFim1Dikf`>mV%i4j7LLeVKGgkdrX*fZjhBmZhFN}MCtN9+LoFvbWQ3vAPBsA1 z6%(xUs#lXAZHM@lJsx;9#u~BqE|w|EGZKn)`0rY)j5}89ln|la=OjJUoze0w{d&*~ zv3WeVZl5-oddS(k%zhykZmwft#4pwuUL(t9BvWdUVo`9%c-mf$#X0pX?2?JBq&{?D zqOtn9)`hczO+4%}g3zIr#F>*#@mPOCg`i`qQ$hZ2i>I5aI}XsfwD62>!MgiDWrn*& zRNrI1ETs)(iv5&${?)j!m#1DvOk8g%ymffVw<%fZM%^D)19Cgo_TMsZ{HS!=bcntb zmsXJ5PuO;vi*L<{u!4E@!6qZ2;lbvLb`Ea7wW^A3WFd23E=S4qLF_T7u=C<}#=0Dr zezSj+@RXFPCg|C{#txVPFi|Fkk9>rJBxU8_@0L&=+S(-rUZec9stIVSwGf3NdlSLg zm82liaE1m{q2g*uV7NT2O(N%G+P(nxJ!Robw0T8TaPS9@dnae7#EhcP*CC`pHjGZU zLhKi}%{!pSv;Ob(YuYUW9R6Dh|CxT7ku5}wepZy&!Q(81- z{1LL9lzO2zS(O|WkF!!9EuJ~vgqx-m|6|c_H_}xY-74WP)xdZ@ht#IwwwRfUjIWA! ziVJ?R3L0^8T5b8q_-C9Ue~;w7>K#xiUmF*eAYL<^(lvauhj+e@AhTEbH7R4`up=KK zRXHoUQrIz@h4^&HBV>`zxRg%VKrF%2=Z{0ek?BE;m0RG-ZJfadgXc`QRFKjshFhL8 zUFz2ckPsqLZpZD2i}zE>>e)k@l8c{SGXWKWbIHks;%b36FG_H|FV3oHD*?4PTFD_@ z6>!})LU#154tq2gXx^8l9|~;cB%HUaG2&~s8;(;QpvdluE`&D2U7iklCA$B7p!x=K z_8sJANTQFc@j|<4m`39AUVJ3@*?6|;`R$x@jV&8nx$D&r19o_>E$dy$N=V=wy11y; zhE+A8T!Io6r30>`U{&{MetL~;QSJzqu*nBVPqxkqDir80X8ng0W&+=Rf_ zw_9EH8U3C4^^Er08m!d)$^RWqPK5KUw~@BUkFWGKp!|itGKA%b&GBy}XK@(?Q9@+{ z8LcI37QB&XHZp;`49o2(6elGavpF?QrWc0_5taDPkO2-#N%+HzOZfY5SlRJZWhw_S zVJcR2^uEz-r*?m5A$S5`1#YqGVx3Nr-vRZ%0FgBK%~XI&(SQN@USSN-zP;7Tr-qON zRKib~a%m{x?=cRuIxtxdhjI9wI25k%PP^n)D!^HO4AB7b9BuY^rMh5ed~-SHMi$S@ zcY_WNrePrp&kC=jEw@3wiP4#tT1}E1E7sQG0MdF3A z`Mn#-jfG^6>kBuZ4&NddK@Jcb9FI@-3lll21cavRPp89XGDL6p=WAAN;Ur795DnF+ zHtEi0>CPC8RAWbm7T0JGLHP|Z(|4=r4MwE2C!r3=ed`k6njPQ~Q9gT_>kFq!6YI6f zA^4t=A-Pbz^|x$d9C@HozIC_N{QmQMi(Q0%$DSJbCqNdNni7Gu%qfgBoB{^rSeFCS ztsuPC?`q(`GU6@L9BbS|{kJyLCXqyebZ0xGsU!z*bJ~t^5}7+?itEpmwz2=2{HI`3 zpy<8$E_R@PoTVIFfc)R46K7bP3jDnabsoc@`=-B4xuy{@_Vp-RO`PPb+QJLPatd+3&u+*`FU8tT zGZFB=3BsR+=?4fn?4#y=;b~<=LnM~INqrOEzXdx<<5^R3wp(=d-LHX;}m3!=1N?xwIFZK^R}dyo_wZv>DJhd?uQiy zb&fN+db{!J4Kg0khw8hzlY&r-LAAN+rpwZ(+&`-CSL@50dL~;vDL2IeTUqkwy(X9;N=&9=Gk%h$U*Mzb9ytK`?lwOc zJnyTEPo15Q|78A8beQI%5iv$r@O0mFv-L_&c}`7v(j*Q(>Weir{2v4k*0CfhaeWqV zI2Kmk+L&C=|LpSc-tBH)|K)@qPX~~tjR)+q#;>Nwi&pe`<3oP$h%8KU>n|cMdl7+L z)Z$9tS4E&oS&F42v&5pH@S+~Osw=mi9D0t{ImBD}`=ssUscO0C(Bi&g#G9tU?m~v2 zNxg}^@&GsS4dXfg_^~5KPX3JcgdKy4B{SrENX|{wiUUI$f zyw%|O*(a!X-8F$5L=9s;JJTe;$R(42I{Yx-{%KhHPLg?%1>wBBiF^||%agH_8t3#f z@^K2tQX*B%ol~bTd;p-_2f*Ui*b2@7KX<3O2ku*W_`9Qum%jlzdA?d^IMGChTQ}%e zOqb3RPMq6R=K-YLSW50_5{IlM-sw(sBF7nb^SUN%50~GY0Q08T2#W%QVxMLR>l%D_ zegON!*h%-eKieT!oUy4<_?R_9Zx}(RrE6$Uc@(S*){d)g6A69UO2l|u|IxG5cbSWE zwJXYm)hBw$5(};+;hq;FBg@+(pt8c5e&tsRy06Y<+c!=e*XA{ev)qJ7mYoUhd%wjo z(E?f58%BPUYIE5oi#5MuygjQivn(! z`zpg~B~)!qJMm-aGoLN?;M1O#k5fXaJ(5=r6Re)r$P&1>rMF@=pi?HuZ=F16{M{%K z?=lZFYbmSRk1f{pMBShI7!pr}*zqTB`E=qYTg;r=6P$b%E_K!cl;M3uGn#7Bd}>MG zo3etGRGfVMOW*g$KM1(6()wLW&z6T~+Lk)ILqJ3=wz4qa$)DSj*=6Vtbk6V{@%yQF zGwrry;^lDcR&cry_XU)WR%X{@ggt?O(qxtdRWam6iGMG9ge``^=)?f}M zNpqXpI#gS7IDNn@x&#I~9y(vWY*ELyGYz@QzjAuqp44M#5AO0byVhkM+hv5eEbIHu zwFSdGxES{4%V%~1kRAD*Yi~_UQyswEs2bTT6{_nQ_aB%K`w-}Aa7XR zIGjb?NPK_T5H$JgMmX=~({(owRW&e>chV21BLd#tcc6vVrkhzSKlAQQPq4&dXLq=N zhgio+n$eTcL}zr!6CQ;fzV|N06wqZmk>aNi?sd+5)1$0@?F}6&!$Xza$R{DdwT2D} zwM5gtTV0yF?xa`<@E-(hzoTPA=n92^wmTIM4i&Md)?Vv=#TEi)%W!w-5{W*xDyLFb zeQn%+sB_G|D_LA7`X`^j*jp~zp1Sy_?uy`K^hab>`huQ8<*SY#Cxwcegv;EdD#9+* z&1lWSI@vQ4owAKT8(_#O@KZ;w3rKJDhG!ie9GCHw2ao4A@*fR|dn9+DeIgSKi&4pS zMy)w?8R@JDelQ%21e(L|eIo$BpbZVQVp)I7EAjS*8S;jIK&g-)IvV%H=QZM11q3c9 zllZdE;`joW6B_6bP~9uY-|;8cbIwMMUHa-D{88xg&xZHWA%r&yh=4M`Yny5@4i0g1 zmu~UieC{2v?CsxHC>hH3*YG>OShA(kpX=s9&K-;5`ARFLg1VrWT(4SbEW7%alL{S8 z_zYutGys<-zRb00_l5gMyu`GYC zae$bdA@LbQOJ<@>a^UH!^*=CkO#6EK=D-8&e3R>=&~IA@%E!_Fm&B*%(y0%ECv$=< z&j$y;eK^S%eAY63Njvy;W5Cz@s&BOe-+X^IUROYU81#CFhkbn3e0b$8&!t=F|GqQ2 z-gE^&d176n8@SjO(SO5wO4p&$q0->N<{ZYc!66@}Yaw>ox(c1`oku=S?B^)ig{~## zP|dT!MI#`PXqb6CKjA_KQ_yB>aU7pQ>Kv2Rp8t=u`~770e_H;5RTQy7!6Gd-ZMcSF zvTjsVpgB7S#U_i&r}Xk9DaLY`CE+X%JC^CQN8ZAxzc;;@_AIG4?-4?xhwsrMXj#`Tu* zKdp7G64sO9^E9p$MMvRJiMmW@E`F>#UCRR7Fz1w_RRWdF-`xkO4qc-Y1Id>Jq9yzncu{n-D8Y?F4EGBeg>bv`@2?1ul(P^7@Qtpk}g;N z{vgdenVaXkN3`A9h4ZVfzZN``Df-2_3pMk#L5;wiQMr<|eshedc@%muEsGeWkSD0< zfSNS5AAT7>ECq^~GmS}VwZrcv$&bHI8J3+gy()HXL-Uk!*z0j9sQhU9TyDj|=MxvC zRL0L$v}DVK^2vAm?t$PxjaMxp0#4rqG@g-jR})~5eO3~dyX0@^82{O@K8?D(k)Evh zM@z_PmLXrAs_QhYn`u;4_RHYnO`o-oW)i=JR;(<{l623rB{nFZ(qeNIu#7edY4n5l zPW|KT0EwBZEN$0AbK|9;e6b%ynUW11qwUcF)UkQ zi3I(*CE1aL7{Xjq{de&8?iu#)3-PwTx8A=#=ZZB+e>&$IJ;x#G+s3J(Ad{v22A}o_ z8he8HE?$eSzf6O676!Z2Mf1lA>U9uc)aZWC1?r%plf1OX8#8Ei(&Dv`$}`w{-~y`W2_Kh597{gSy(pPgQa5{3NU**>?}0f$yVSk&&46fLd^+2-xQ-2RY) z9I`=H$0ORB5Z|IGlN5>-;5J7wPyy1OXo#;$3D7Wsv1vM9SpBR&nXIp z2in+1+Vh`Hc^KE5~WWou(B?XJvh);0~ha|K^ zOtM`NQru*4d_YOhav#BI6QVT`#?Kj_aXYB-I)EQl)y9kX?v;jpg@s0icVrf=h`#+= zCHd>_OS@nUMamB~To{^vHYSaD<0C9@zWr8eNRp21NU7BT_o( z)zAkv#OoI2?`mx|ee4Z%O2yAzYOE~z!28^21H#BZbd${?CY$TTSIM$9l1v08qT*gu z|M=r%{n1p2AHA+!CMu+NltoaOn$!C0s_D+tJu?whrzO(c?rCsME$sbg7}ClOB)s1Y^R=Jy`8VK7 z?Pr@C`A!QiYzEQN%9=TSUYz-jD5 ziRBxBTg}#90*ZSHz8b*zt-?}!l0_z(NyW=~i6jkV*etga(is`=UAN|Vo(8)4e#9eg zc*0>v2-G8Bk5LI)iP-vga+lvAcUMd=oVq*)KY|d0f=n#Vckp0@68M>wRPi>>*+LQlJy8Z) z;%NT-`o8ryQ-?(Txfq+VxkxQi)W5IPIH|*qrP8j|HJWTS$TqT0G5CL*{>)sFtvd;x zm8_SFPYp;4b-l@Ffc;{3{N)i6w{*jLO@a#N-+myiAw*4YWXig}L@W>-`>B3q@2? z?AetihoskKgs6j}FO}a`-9P%qIml41=pEcwitWC6W531EjAs7tt9m6uYWMvQc1PP2 zvy*Yp*Npjo)Nx?ftOuU(-F38{`BPpz7s9yW3gl>+{7VMJgI<;)!=Jn0|WTwUy68r@dbhCJL`2f1%{V5M#`2k%r1E_s`Jf8R=pCd~T ztD)l-@0t7rp(;8orXSNa6jVch;V>~5EG$Qr?hJ4j1vp)yN=7>nWpUY|!-ChN1#jR9 zi*||fd8~y7mytPs+d@w98DM#@qeRTKMILA6KYNX$iO8em+qCI&hL_aR>rk1O#ez;~ z8Xb;`u~aSac9dAF9sj^r1<&AbDd~e_`U@U+M>B_0-@ zCc*xIr_{}PS$`ql@w}{?l@!P!{E#Z_n=j809JMl!pt18ETo6!kV#Fb7$p{b;CQ?3V zu4zPE*&dmV5O7WucV}2E~7(${DJji*Af$ie3Lis%L!WX&spg;)$K0Vi~ICwn_Ef$ zeF#V#4lbBAN|$90DG4sfZV##TP>$OQyBy!5B<1E!7k`e6o#oFxj>GG|7LF1HhEGpC z{#Ft>eV*VS_;U_{S zYHg%^?WGinFvT(Z$mLx581D^&-5=Dk5V&71j9w!OP)6~^a&Q@io49!|`2hc-q=_H@a}*;Ak`4n>uKvmp(_rZw z_ywnso{m(UQmEh7AP{jD-*z$xhPK)fV&8%|uRS}>elufy7E_5yO3MZIXC2Thr!ogPg zaZ{c_&5h<334h-MJo!+jSC*uuZUw}cNj04hLk)34>S6)b}k{bjgszU zWKfZ311Mf7wHW+L?f2BnFe_n@ukhxYWaUZdNutd*XX_fNIm>6VaN^-N%A+#QwjtgN zi18+7#^jp0Q8Rme%yq$<_66k+Kt~ak^L!y)bakZ|94ZDEXObB*OuOB{q!hpbRcq<4 znTK@T0Qux*_UC4aCdy1^latOy{7RUmkHoqM!&J%11RdSK>cJ zA8@>~a(Vq|d_yo(u^ZjG_rcaUn(OJlX`8sae;m&h?zgb(M7W#D9pcb4$%LmHslL5m zFSD&teKo0kMP@VlN=h~TN;r4;QG+b1awj-QtCUIJ1|EL7_bvJ$302Wo6MNz#f_cJuqCj`jBkwh zb9kLc(A21I`~MgKIGhmFJ*3$CLlG>|2Oy$r070JgE0S`a?kb5$%Tgsk3I4oLuZ>U4X z#1hBB^H?$|+jIo(91FXh18T7YJ-pQCZ|QBA01S?e>9us1G_y(0+CEV3@8aobHbVho>Vq%HTgO2aL6m5S8HUrF zlfnvchdZ+4zD>TvAM>mgBt8iWB>%5lHfPz@d%d{jHZ*0ErE`(puLLCWvxYEmPV9pp zA;EN|?HvF9PhG#&OS@N*T}aiK<8hbE_cVN z>z5CcTb`c;nrp;F?5^M5Epa?QfZ|Qzz9y|-oG33zA3|}LZgc+SV5o_|`jWQ(!$Vv7 zw3VLxwqhYssSBVospWG@@7%i=PZpQ82VUt?f2bvbLHRuS(Qv(JddzY>AYH&?dntue z&?eoitu_I4or3L2c+l9-!fs=H`YUFBVNT@BZp4HUq)VKg6ZOvFT~w}_zHJ*28Jo%v zCBM9v|K{4FRnczBiG;R(DKUC2NvwMmbwXwzR6IqS&SW=Mx|y;h^bgACay<|L1-Byf zAz><|oQkd&)OD@+O814|D6Kz8Km-HDk;%jY>u+Pbg4nDOU z5Bb5ZGd$>_vTpvlm~wou2?q2mCacTMCkK2IKwvigygOBzlZB1+O#{!U$x3zj7 zw}6{lWL@)pzk}KnWSZB<-M9U;hxVY{)sxf zy-YNEDmV%@ztNwG3fn{0JW>X<%0lzeW8dUT?J#ZXk?0boAb@gosn2u$Qd?8=6dqwZ zUG5lCiXdKLNwU`7mCkZ|dphXtcyZ~PnHNym7X^r*>;0H_9|Fe`E`N=|NIMq3Yo-e2 z%X$Lxc3BC=C9m~Q;KdPm3?gKqDsd~t>3Y-XHo@jY&2W@e(eDBE-!tl!>#w~3lfuOq zx)a1?WO#UUqte=dPbw>9Vl*gnH^0RV@F%NljBsoYK0*=Vq}Lxth=Hx4amk0G1!g@x;u$!XL+!OkS8oS9B`?#LUkMb4gBE^AMA_sK;)!pLm&`Tgl zM)#iLl)QrFf4YLz)%THGnE2^`p~r{~+$P5{digE89jh9cLmZx6Ei_rOj9d-iou5Hr zn|Gb%pK~7)WF7usLx?X2_2*vvHtH>v3n#*(iF!?TdRd-)S`)YJO?(wIgwQ;xZyaI* zxe#D0zEE0T8sy&5eYqNHA<)Q6=r!icFU&>26q^<3neoGJL)D{jaQ;)ld*l@>dS^^z zDaTFOH58P>`^MT)cyMfFE#>ohJ0tE(7D3V$g>j^)JM|8kt!T-uu<43!FR5qY5g-4k z=f6ZuK@|51%KI^p?wiV}a$H#KaZuXl^Z1)E*G2EYbv>{pe5?n6LeDMF+L+F43qZAF zaMbXYahP}c;G-x3Xnj1KZD`#Ax}x_5@y?Gf2cB1C*vpbs;mH18NB?Cu96)N(v3OQZJ{3$9@r?x+C zQ>4PW(7tx5=Hl5I`@4GSRmB#Qa!&t#ZHk>P2y*GXI9=!Xq#*eGqbn;z`KRw)e&6+P zAYu=g0;@!oF=R^Z5Q_=tA3?{9|XO5C^U0J>b&0Z#FQKGO;Vg; zTh3AW2k4*MXy?dozr3_>K8vm`+%L7z<H;85FVyqAbC(u`1Vsxysqs8#tW98Cdqfx%fX9n!m7S0?r}xsC*V zd-V$mTAkcp=5GV!Ee+(eo0gV-x``f?q`Ye%I9V-aH+X{%-7N`ZHmnz2d^TNI99$Py zSFHSeWUu66;|NdI8JiJOCf@irN!+o2j0SZy*00UAGR7!~8b`Zc7Wsi_N$%IjFemavuN5(zu`^3;NzO5vPhS_g0R14aw z;KxxdsC<^p$)p-93S`7CmX34XIl^NM(?RVhiF5|(4B@}#l@ru@88>zZ=e5n7sR3|bSx zNBdmM&9t@q?221;pye2xZHdbyeRr#YP|%zXIbN@)HP^^krN2JyZN%gEWX7_q?C zm2Wja%I;K+KlRp((0=K*g36ZGGN))Eo?A^r?o*o}%}}%O?(U$-TsIG!2A7u%cm#d3VJ23@Si~?Dr0X~U ziFc{}W$4Nz1~m~kG-84*o>jDGTKVQX4iG42F6iAsdr#uMf8rg$G-^@q*ynd2Vs z3j1$tnBK@Od4~q!q({chjgMjI>;+QMZCU%*3!jLD$TciuE06Gubg)sWb1+SfF zR9b1T0{wjw&IaU)*sdhn6;i~@rnolkPo)?o^{3$9#3I@Lyr#+!dq^HGPJTzykVx?g zAGj|19ofz^JgNH(|m{|0vXe{D|A9{rT#EMp1sAg6A@bt(?m zM$gz}fhwo^%FNt0i2r7&kYgN}+`>FLqoJVq8J&I|Z<42@m7QcplMe}r1+Q?p=`dER z--UKOgkxor)iBkP2O9;J^r75mgd`Qa0BOU2sCy3)d~%K6V)eMevo%#IRw3MAZ-ZQN z#c&eE>Jyl}bC#;)m82{I;Ll+Eh{@q!^8@CkV4R}4F|bvSR>RBtc)b${m7;Y*qn@PLn+BwwTuGCoEWsC&dw z6r}Mx#^eFdS%slFTct{|dS^*2yiOy5)u#Nk=jyq~=lS8qVW)^d;UP24Cx%^%`tely z^*?L%2LNs*<+_2t;PwTrri(@_WYZ6hydiBFr!$%X+q2(uE7)s+f!ETKqsBZFwCkoz zisLDBzkccz=dlE{l~4g9J>;ul@-oxWv@EsF>g!$A(o}$pupv^{i)ERSHUU)(s%es*kc(3{t$7!jBL6!B>mk1tU38IAOlhE zKN#o)NQKgYw#XDEb`yp#D0Gb|KKcb1T|iRc*CfXg6tMBLxhwl&!v|3B_+(m*d?w64 z{?)~XR49qT-9QxobnOAB*Ec-v?b4*|)hn0m0ZLJDQ_Rsl=p`>C##V~k$>Rm@(Hp<& zDCc-g7Cgf?8VUWa1kcGX537~mk$pF13HtI{lJ!nmBO^c%E7R#486hRT;5?>_{N>;n zZ6p@$Ul?ex3vw8vHWWt}Y_X~Q3mWmRD|(yZo&C@TLj{qj@b}1H)UpFDqzGQB%NAv4 zZGrm)PQ(w$BMDtUq1Kn4m8jf3bGpL9JbgB7po_TM`MbSrCGF_IuN6J+GI5SG@VRAH z{GY5u0X8DWMFX(v!Iz*ZBmb4(4=ii~E)QWozU&1gfFX5-<^0fcEErX{ZNU{k&$bZ< zAi&#+SmtM!FrWX|#I+2bVqc`us(*MS8ZeX$f)a5YgHzvwQ)LnS9QXI45^w*qG%ofu zE;q~Am!DN>Zij9e+lkiT0C5l zYO0}lW2C!|)tNqGqhF!MmAY-3Fa6Wbcf^aN5S1X4ihF?~Refw&D>!dZCfPilo%HiD zgTD?h`-me7Wz~Po7CeLtzDtgjQ7P|R29+<%u^61Zkn(4EIdLM2%^_R~+zKaq+w*xl z74(55EHd|Of#b};IG)e4mAi$e2CjnZq!{iuQ#GH|CP|9lpQU2_)x<40Z7g2I8^%}@ z2{Jn|eAh!2BXU%}d&M#l8q65YBZek^l^?{?0Is^@x#Az&comL{wTbGE4p>8Y#D`H{ zy%QoF1n?+Od~Tp=t?j;9Wul)6c8=#=xAM!5PsvH2t`}DuM1T4x!77Hc!2B`JNW@-u zoqt-wZDHT%g=k}MVh~Ijvbymx13$axW6T%|DDCScW<2*pc657!bTnnJ`GSmX#7xr! zL+Q^v$JJd~;!!J7vJKLP7#SxZ40=)G>ZOo2Ysi^OZVo4^u?g(a_6@ADT9cg%PbAna}p3 z*{IReGttIwRqf&20*!b9m2G>}L?2Sv;c#~asc~kL0vF2Ryq_p%t57z?%fNjP$2P61 z*w5g>c#YKk;dLWourr5(ErU7eA-o=D(^U9L_wr?vPUK{mu$Ytowj>YOkR<}~8;%S$ zbe<9-G7(h-!8=ZoR4OQGeVb=D-K#Sb;6k1Qq<^wKz?^{JjiU#P*}jt3%(- zq2Bks8tN7h3r)If6C+~AkG@Y7&5DNDv$G6>6qT@EgAPq12$tcP2{FSjGw>5(*t4>w z4+IuKFDu!6oCYB+XWjad5!`_s6k{dL4%{n+nR@Nt)gZ%Ng$V`-OcR-p?s8or=0%%O zJ7N8tFz0LJNZZ3D!tcY~sz&FfYRm8aJ4iuWf<`H~^fX?$R3W(t=1qVT4A|vPC~${j+_?GN170zSPadiXH#y&;1J=P}k2pZyN?`lg1_z~tu{e)E zm8PaQXkJ*k3=L@_%M-<e6$F|@8Fg0iBJgzQ{>O2O?#8U(#KUmcRX&~}c~yg4f}O%7|~XLX47I+s_mT2aQ9B@#90;h_sB)~IXMg8VERgdhsh6I~31 zkO@#V9UL?7lny_(&J@$%TsStc-KXX~)0EIc0Qbk!L~${*@pTUoS}+q$=I&h z<+@C|e zDUh9X#jaTO9w#WbKxa$B{^3{S<^6!9a|7Xn+TY|MU*`gFKQvzzoZ&kNfV@^Hz|a0- z7n~`L7E^3Dl6?TR&Nk^r$c#$nz(;bcG9|8xIi!nNhUr3!YbbH*rU|>I8)mw<35#)8 zD19q`>QpV6G3OptY8zC0Qj-LbW}l6h^nZYRj?~;Vg*(d}Ujs zKT10CkMQB5yRpxSalu0)bV&6n2oM$)FSBG zAV6)qVp-85-IjWnZK|mdjMf(RSecA|L#+3KI15uFy+yVrpYgAVa4K7yjth42IKyks z{h9l@49x)B&7yK`e!fsBU(}Xv4`^AIzfmma_?us&lYeo(Q)kw;bx5$vQ%HD|c!baH zj*(V*{m98qH()w6ee!TA{B4!pIeixFai(R0rDRO78UL3nI*)SOmL!7nmn?2-8&*FS z^z(4wvo@|XsQheVJ$k?8Csswu70QWf9Vz~#o_BIZKk}2I00N@(&FBF``<~~yE(X#% zKEhIg#oq0BeZ73?K%jAf6EU^Yn0OYI5%Dk|6)jacs)r|81I@p&@xADos=gwrhr%!H zM9X7EL!Jzlg91%Q?|AySri5)H69l+9OBKw-yR^K7QpWqc-XBC7L}#NKtCtj5SCi z+^IK#2(p}`=!z3z&Z8WVd6P7v>Rh+kT%KR0@NOIWo3$?yEt?&lCmASvZC2vG=o7q6 z1v(J+N&qKgchi)4CgZ@c9r^L60xG`qgM33JLnH(L%i?Q8g@KHUxRdFcggG!&Td~0G zrgkHzwBBkwZ6uV9{u8(s5;uMAU$;cSPiY>hzcvf*#q1d$R?bl1j*H*98fU85J8BI( z@yCX8>ds7&{3sg|?Ap4SJI--?MlsM(;CAF64!Q3gCz{~A_67PSD{$)M#iErd-7dvj zT`%fU$XYul#{qt7Z|t7@H>O{TkLbHoJ4b422PiLPuM~&%s%~%B^3Oi~6Xs8H;;AvD zTQ}6R&g-_tNDm>(Do@W>K8bO4^2livQ*&;}>GP66U&zCn6*Y?KJdA#=)_cGaHYCjK z1;zr6isjmzu&dOXwgtV;gy`C_XI~=4#8Ka0i1B_9GkOJ@TeTA($>P5! z-n}BlT(hrz+}J!`P>izRc@tK@t7%NgxG5f5T?vb}l(1wsUHf|0(PA3JNWhH3BWocT3f zzT8j_h9Le|+WB8;`T7WJ0|P&41+U;JZ#xwU08h&+pqTKW8L}s5+yxVGc%gz)NJ(-z z$Zx#{@@d=vyHc#)1)bv&%K!-YY>k&_5U#e0X_@RAo1jmEerB8QsAQjgAs-yrx^iMq0uMi5Ygi3NY&rK#n zy+pIvR@KWQb}+@X-xouWMx#lYg+oF4g%E8wG`MqC_GjiA-@v!B6hu2e>FA@#^}#cj z+i%8Ssqgzgiq8F?>HmM@%*HmSot(wyILDk%Iczh`dFFh~IYc>CDiyP_IW_0AoKHze z5-M}Zv2sd8eGr9Ibfkm#*Y}s_AMkqKZqL`_c0I1^ew`Dvg)ZQr9KXQ+{P&+9S9|y5X-~(&2JeEVNT>{1_R7P5o)0 z+{-glSwU}$-|ie9N2og9R^6@%8P8P<7*5>(Ju;D}ar!Y0!o@x1e&4b3sMS@4J5%&Q z;QQW!k3S-d)e`@Nj%&$hxT$)!#IMDs@`))i=gMA=k7Qk;f7;U ze&0w}rb>PoS8Q5ofGShV5#YENBmk)%7j#n-QZ|Q-EK7xB2_~s z9dpVAFfOZJm~1H?TI^&gMk$7avUD3bYqQ+Z7cG$PJ~@jld)5&?7)jA_k`wb~#cVj6 zO9|IG`v8?TguD!XZjGJzn zC)V-n3F<xzp=dMCHW%+KeLZ=mmB^pb@T-CWc z=72M~3U<6&Jfq-h@8S9qL5SD~Aw!sFg+0#{{BZR>eQlrSwbgrD-D5Y~`?Fu7XEG?j zg`5l$@+7|;$vMMUo*H}xWtS=zjP4YZ&6FDihZY>+{zix9xoC-ZX4+{nha`$DZIrr? z_956?2k))VRm{I)Dz+r9r=gQLW|`vt{H>m;Ws57tnKp41t#;pZxlM~!6(#I@#--H?5L(jpO$tzi zq}3Ey8lwexEyW}um>FR`Bw6tgVvIqS6U*scwszqR5$Sj_=4pYsjHkSq17G+dJp7_l zy>pHJ8nLh{ZXdOEn)-R9@N5h7Wp}V2=!%eoi*7@J7qKlB_4sbbQ}`trjDSk(?zp|d zORRMEai@3hGd%%AFSwqw;)C%y_cOIw)khUq=9HRJ{C4{B5W}u4-KC}nM=@;?-^Z0Y z8@_&2DBIJVz^cEI-o^H(#@{vzURS^s(lG+1n<@A#tRcpdWKZ;bz$+7u;05R@v z(Xl$VCRlsujB+&?Rv)TeyCe!YrKg#Ou|-JC*@YYEKyiswH=Z5hc^_RpG6z9cWE+SM zEWGFJBNy4y!>#|6Em%7qlO5k$d*WlU;E$ z(Lq6LpQ)M6FO-CxjwW|NvX1;ILM4Aw+PrEYJ*?V6m-#4QvihSSCYkc;fmn3{6^3@yv>8K@-mN@MckJl3cp^K~G# zgaCU&3spG2$mkrCd6CS1gIfIFXY^9Z@v%SMppwm>png|;dOFoaNXEpq{`|Gd_P0N9 zn$X~K}8jB8__})dQNYHUuUUC zqFLqRLw#B}E0X$?_1 zm2H}xWjb!Sk(8e*efFR_gu2O4Y{f8Eg6)MW$pqO)9$IE-3`D|dd2+sq2ZzR=tD3S7 zH|n;Ti&Pb4f}La(+?Xcl070iDfSNQMq%f8M?%z58=EU{jjR@hKo3npq!JEKk*3qNSM0Dl5 zw5JZ8!Jvs}VzMq;*^$SC(AP0(g5f4SYD!m->zUkFbozsHr&g?ei0`JNWrt>BExYmw z@iFl|MkN6ZbD3Gz>#JXehz_Mw!1INv8?CT?~w^(xC5uW=|ilZSd0_yk^- z{b-|#mq!D2o8}x~dX@VutF`mQn=q|PlG*0m=*IWdyk-pxWv>M+)ilVZT>Nx3AED)Z zw4>9EZRwS-LEYdInwuP3y5lGsS`$cU=eItg%uf*dXU&(3`SSj1dLj#&RxymP zc?1Ih6hTAFMMRXGJO!|J(8wH?|AmTqw&@dSFzI4V5@~*F>-+IYJixO-`B&TSh@ac) zE5i(B!%(+#t*pbf!09B0%AY8B#=%sB_0SepMkGiQX+O3u!f-y|gvlJ8^$*t@cjnd8 zA9Et3DW~+fqSRnXq)$pc$u}$4uKeo%a_z*I7_AnIJNN$I)XRwTI*S^;FY5XHM(K+# z=N{!;5eN)>wAYCM8jY+upKU?BcW>e^*wmwfQo{={@j8iydZ#= zlV2$m_9hSeb2vbvgd3Mj@uc^rOGY(s+`&X_%@(f^sJ zO2^?%W55hFaq&mOGb@yL@|?rv!He@SVio*Q(Hn z>aB)~#CT9IXffrjZ;`d`=!27B&^8%?!>X%~8#DUGGS+4U*I|+FLFheAJ!LNGsw5ya z2}t=SogbgsA{y9MV=0m2t&#&NtFpMIalGS;fnsE!0z;Y~8o}oZh$rSWrD`z$E9NQI zgfQCA83b}`QVqT>$o@HFU?^h?ij#LB$bF(42GNZOfl0&~hT|Hj=^g5I9m^G+?1xTv z^9S*HfZoi@L$L~8FjgQTR8j}j_f0-RgIjLv9C^SWJH|gcq$uQei~}&;txXimanda| zQxLMb<_|4*(K=zt&%4H}q^JC|4!dPe{)kKwiy=wpKu;t?YN}LDUNBQ;t0)So{!B5e zjfU#yMAR0%n%xoF6(j_eE#aqzHMY=Qpy zkP?y{Jqc|V!39pf0KEb;ocH{)#={@$wX`SgICSMuQ!lwdLRmy58Fy782l~1w|F|Z+c~3%~YLj@+ zrkt&R877mHs(S7|Pa;ecjJmmEVf#%)mb_>1N%&^}uq|uNulSvxtBl=vzFqk@!!Z{j z;syH$wX8c_$;dI5*DBDv6Mr{I!Hb$4TBE?pV+474O6&tr25USRN0mx59(U$Pc9>TA zn|P+^&Aq26I6;qUlEl+-i2Y>#Uv)73U;Hoj_@PeZ>`wky;{d*p)I?X^TebO;p6JdqmQnq-P4$+r_f6S7JXIUPYI#9N@qA zwCtYE?Y<(xR$Tc{_Ss|{xH^QS8^?d0rBh)c8MUF+eIH&n5NqAcb0z88xKUk1Ezd}S zzVpwc>m>i{nf~IaxbW9DAvP>4O8VfATwwBkc<-VWyM%#o*2@<07>wXKUU_skS zb(Ae@5k$SY0`lP?Pa_(ku8E*Ls3WB!)!_)sLX}<_gjO=5&jJc{0W)A~{=Y7qR$#jS zypS3lLJB<9{LP+2(Xd{d+b${14t+9Y4H$pr(hj1S8m_(;3-VaC=WEIFj5$?y6ldg) zxcrO&;mZ#R_!Cxi+}wI!yw2&e3U34iP+EK7F4Lgr=aK?hm$>^&Ydq)5Z@8s%98D?6 zL{S{t>2uN!$9 zdV)CH-3#?JTT#~~gTm8sm810V>#~q{MLf^tW&2S#yIr_H8J@p~x)sinHHb}W9J)z2 zvJ>&LYaTL!^9u18CG&VOeo@j6<HixK+LU_LUE-Jc(5q ztbsh}EKp+y-=E3X$mxoDhp@j4yYBdW;714M9)28REf-05Cj*KX$LOL3MWa-Ed&;1#yk?V_!A?|5ud%3%ajM{jRY z=D0=N?UYriV=&{Lv_7ZWMCwNGPYmfvYS4}H=AX5#ZyGHou0YfJA?*ot!FwfAgPJ4v zc|PciZ!d{uprPeGVpj*+x{0zk_a4zx3_>)BsYAXC^%{S;kNj4JH0Cl{%}Bdf8z?@H z)8NrFK;C4Zfc9%MRTjE(*ROPkc%QynW{=uB{>C7OB!8J6Zl`E!xxev9it!7UbPrsm ze|AV?1|gw!y($0cYU%NuM8S2)gW`;m zsl}{+CmtULOk9GCRF9=zBmKAE(ij@~EhmU?ec|;P?~-=JqKKqaK&cY`73IB{2(mKs zs!u}wWZBQAorjvHzPI!T4UDv8AL!g*!~yfzHzw2;_vA!Ri&>(=`aBG(s#FXswC#lYdq2J4v{`&c8pa=fHE{=A)TD zoAzA!!s%@%WsFMwfNDm2Dz5sX`^D5F-}FLMyqXV{6;3(tOaUc`s|WeCUot9ANS}{h zRuC^a<@wJ(=Ut;Mhb;q*3h+&Z<p8f27RNIMvtDDwIl4^5WN|L&_(BLV~I^8%4 z(KY3kJswhY*7$E8ze-4DcTKGluKLiOq9C5QDpqJJK zX$wu7V!WIBR>+M9_zeN&b5rcxYgQI$r~g+M4OMz6u+8$K&;RNKts!y{2S%cG@-FNr z?$21Lu``Ln59FG-tvEm*P8-{xGD>$JO0YooC#KV_C;nbUWD=~2(rdA3=Xz| z%nz!@w>m@r3(@{3D@n8uL>T@F2L*93+{kG@?EOpFr@NG*8>d3wPbItjv!~z|a<=N3 zEi#we3$cFAxvR*cgD`X@Sfdx-4uV!%J}lqaeEor^+-s)FAYI5;>!zz@@*Andy4#a% zNyj*n+B=?_KLbr4-@E_s{oiOo`X|R4SL<=jnGCu2ig^&5B*}>#c>J|2bk5I{?-ueT zBCz{Bna6DLcAkx+?K^czK+=HzlOJKQyh-u$%3Kc6)4!Gavz2;O+pqyqGD|dbe|cmW zWYunXs9d!GJk^_L&(|C+I1ZftcjyD>c3TC8vPA->FPfO9c_a&YPFMYJ_{`G$^RU#@ zBKq8vDsFZh6!wBP~5jDY_5@b!%exSDUfPIGL% zZIQfhOZicMV6JV6c`Ee8YvjnZ6gEx3sRr20swJ?nhSYUZL$x_s+0|y)O0dDDMbEAFJ!rsN$Pe3rh3OqJ-Ke{c8jRu8_)7}EW|`TJI1EWR4B0ujQ> zUFAB&2VO)fbhOkQjnjxPn(sC`gg{Z?@n)B1t?e0e<(WES=Fg1);5Ec8i%e1Z*tYPi zl@_)tCt|)gWs2!gq^dRN-rAwG!#5_aWdEDGrloe*027xw`QLvnt2G(PT}^|$YF&GQ zkfW3Riv+e>YZCzjmCZjkZ*~`tK@|+9qInhhyqGw^ZBjHIDD8q}gG=_POogYcz)acS zVVh6gJZ7A%VtSN9@+cbc`g{uN7>#N@oJY*9T4YmzZZ*x8_Bqv6NzM{j*)?rg>&AWX_H^XV|)AN~1Z$$(+KJrHiQo#lYky=j~B{d_ZS znP1yZ?&&jSmKkd`CC37_lp^Rv@|4RVeqDX{P_}V7CC7NUR?higBBAclw-sBiEUou_ zC$qGBOl6-a_{dz4J!vQNhX{h(O+$H9=BLwz*FHyM+)BV)pVeBXy)zWRcH_hXyD9Gx z<-O;77AK#E5wbMfJc9To&(G&bxDha&D0`A-E}Wul9V=*_pmhX9V5RZICJTib+OkSV zwWa?OszhzBb$VS;84DjcXWbM@p2%3kr&+PTWk;ul^k|PrYt2M5f z_w*0uNKM_teZe)(ki4sQ2(cYjkokW)bLPT12qoK~SmM00UzE&lo`DQWzV8v4i~naa zp5M)%WG?)bE?X?;@#hp1SWF8pXcxV{I+LfyiWz z?C4$qBkqxkonfSiG|L5|v(2V7_c_RP4yE044TR@B=&;fAI#0kqKHpROCJNnt# zUuzpeW6=op%pEz*8uj&j!?DE9S>PSb;^Y^tP958cx|AV*Tgrv5Ad1EF%nqgj-7%gM zHg5KNga7K#^s&t*q5RsFViNn*Czn9$d=||i5g4> zBdvn&vtB*#$y87W3OCM^r?NC{^H|KIL1!DMc+v-n# zZQbgb{K{dVl1U7(K@|kCBFU8HtR9u1+B9Se<1zUH@q*$txN!vyq6|FN|9_+robR2D z+FBcbIaA#eVXj>s6Iu&Wq++F8N8hQIPK6jmHABkii%M;KfN}%HiagIsjWxFL2y-85 z<+Hk&bVy?ZYPBBFEMW~xvyZbAvJyStsk^k+4E7$l^*nWL^N~zb{F?+dt9z<@6;D0u z7sRi3odCO3!0X4&tG%2YVlaI8Olnzv^e&KKr)+GY_*H{xtuc6p>2X4-Nt-!IIHSZ2 zlhajlVvzFj&`+HH3$x_Zwrf#m%k%G$9!~2+{njF(>rp9gB@eot#>_iAU5{l)j2F}y z<8b_hC7i;z99<;9(+iF?ZfkHWWa9bl63VmWMxh~{fha2qFjNK4{HC=Ht4kS{ow_IW z6HTzmNKhbX!=Yz`2^UZ2rvHj>G}N(|G0q4MzDEC**0`cT0^fh@Lcuqt9I-DyFO&LO zUL>i7(Wy))ph|WQYZLs=BlVLDiND$z3^zrX`c&yB(weGU_`y+&!j*7olxUN3rNE6beH3-B;`g3G6@Gj zAIs=+yUC}l2*J(@Glo%y_OzGO;Ikb+TVDNC?CyFbnB=ie|1WbE?FSpPl**S;B^UK} zph898{`Z#0RHaf}e#W=|I%$vS-a9 zYNjEubf=FQWv-0dDp58T1@p~@vu=a14<0oN_lmXC?!=6 zHQh_5b65yS#}<{N_p9|K1Squ)X-rCD#Kc6+aN*@a*y*?2gf!c`#YjqS1F*}I@!ivwH$BiqtcF}&Qc0lG5}R}S0B!u zRbBMy6jXC9w4>>O*aw>uGU3?w2|t|Z+gj(zf_JMo@6*sUtf(UpuuqH0I1S(y8CX$~ zI2RSasdnQ~HJhvbq7d*b$2)l!FaYLV%Ii%yzkN2L)i=QD+wsM;wS)qY8PBSN{!3bP z*+@R7(hf^$@s4d7MCDYQFXVMI84J(TOz!3mij|&@cZdbL_U!(#@c|ZMzwa!! zW?}j~z1{xzWckhe(CePt6pNIgC(9nn`T<@6eEboBjfE2rFQql+RA2QX!*Y&ZH*;3q z#-!+Iq|7my!~w~bz1;SLo=HQ*Tjb4eH3~#y!Y^lE_=J)(}(y&Fe%mjxqZ{>*CI{nm~&^LyN`iuM_3QJ-6C(s9M;;Z%KgP zW2JdoDSydKe@sF3JtL5~kUEL$Y(PhZ4bXgGQ0;qjyLn*<=ZULVwZg`kHhbyIyhxL1 z<)&y8{lim>JTV-{L{I(!k_?70d~HeDWp(%}Mr`2-2P$VnH9cGG5=;zj z1jwSV^PbRuakrFi>yvP_z-=ahLH#~mx|FM?wMx|n7dpy-^Za1| zL-~*1aH!Y=H4kd|?Y5I!EWU6s4UO&*dqVf83I^z%WWlytSPz*6;1cRVO8td+s-{PZ zZBNdhWw^6{xk7i_Hqs*yuoPC0FL6=&a=m3?$#;ArkVjbGxJ+MSaM73U4S5vOHi$Xr+gV zL9MiuWtU1CNI)lsrX`E2kOYv)r{31&Qt}u)(y6Lz!gFaI$U%*me{vrCVi+$2Z`o@C zZK`R;{s_e&;Tk~tQINEimpCK{BQ%)xzPdI#Ag?J}YL(G=ej?p*63o5Q%bY{Y>>x4!4ImCH(CWKraDiF`Y&_!wBoY!k>EX*(Wu&bK5O;QLuGOAU=Q)59)~c2 z0C|x^fKq~F;xOEK4DPm-a;Bp&;_%4q8!p9)L+|dII6##!8v`^g2Fh52oT^B&hPltJ z5lT5)@3bqF@@U=?xn`@C1Wzf`WJ6@l?=7b7N%FC zCZ>rVxkAgGju^S;5ARp(XG`fIoCYAY%(`C(_kT2%zRDF0mo##0sk@6Zi?GU8nDg7kbjuu#8xc~L%txDJG*3Q(&H*vt^dpic2(2X7yu z1g9#}N&VYQb%}?xS|K zJ5$nBETro)3?L@C8*dgbX||cm5Ljc;ux7F4j4yl*adBm9>1KPXR`dkMRi6ichTskc zYO_q*oTlJ+f5BHWxW5TPt(Sq-TO(F-H6;+x>k2oh&>NcmFucGu+Fn zFxeEDI{=>RNlRShv3lg)Z?AL1BddQ;bOy-Rua$W=!5imKWQS!qZUO(dW!rI3-9gT_ zV_9t13a?yr2u~|NpGrroVKLGfv;i$)%0LNLKC!S zq_!4+(q^JGz{w%t>Qin1!JpCYTqepgYvmsjvg^Zol28uBD%aU+*P2HIXDGB4%#oCy zBy!`hktLh^W{GCpBgx2EY^*X+$x&Rx1HjtWS^?R_hmXz^gspz7T4+o(Bn{}`sVAmX zc{aJQtkM+XO@pI?SM~Rs1nE4lxwe|>TK85PC&&r^8C-TX67*;2i5tu}#ph<@eBF^j=pLy1 zC%S@V4|F)Fcpe}(vxLTCUYRgx*aNelvA|gh@XJ2Zq$lg+_%x3M-56atiE+v@Un;E2 zGh!oY6VIH{Qk#&x72}QNtF6miCu)hvXG?`OF>J0+_|<(`IkrGUU)=$Y0Cy17CL7UH zZLkI{LY7EKgF-g&#NDgnN2gx5%Il)rcbbG(XMsS;!o%v#5B#IOIYQB` zAqobpQ8w4u_~=-3@Gk_87)zncoHb%0D7U^7L^4q>@Nick_J?mf9i2L#GlK5Qeu zzTD&)Y z)AYmymV;Y(dGk8Z(al@7Z#A%&o6~Ljc#}27PMyujfjqjl#Eau9ZY#}j5T(s(^vj3? z9l`XN0iM372;uYl&sNi7rXvh2hv&EENz2aot(H4pSq_YqJGj6G=vk9-GJSCT6W&>7 z2^hTn>Rl$FTGVpdw=)ofdDG@Lx%_!|JZ$r}9EuBI49l^>8ehf-MkidC(bz<>q{Q~i9GF~U^^ggx8wH*t7qrnn|C07 z=s$Kzmu`(K?C?2BG*J34gF=c0Qja1x?ghzx!ga$tZ^Om{$mY7dH_irsrHB5>Zo(PDyc*W$deBa1s8CJIM5oKcs=c!n(62Bk>=7=Y!s=Cus~+c|wLS!A z7gt>z-ZiuG6TrV!E2e&^XC3|TA1quK{X^C2xRCn`?b}1^g&&Ed!3FicKabP)A=mnI zY{%pPD|P*!1z%okmW37G)lacnW!kg@!6Vq&0O79w2SG9J*Rnna&M^OHijW&47k|t9 zWOxR%FGWG;A@~vbYPpwer1tQNDu(T>xV&gTfu>ccI3U9^X1dBScM9?4)*mO}Gu4;- z&5X*r6rE<~LhF~ek65yx#kVF-O+d-N6l{v?(d~wa*Ua525&fK66AGwtHLo#3O84HP zoUlN1lygQ(Ux$YAO*|d{uBFDo&ZO*@@refjw&=3dx>SCIZS;C&+ji*(j=<8Wl zsxIk*ncdHHa6KxHtnhi8S(I$L!BKL-Y5UD=NXglHruujRFPxjX~WYZkc+Ud_J*Q8aPK5%aE}k0F`n}Oq{BS z$|%rU&Ik)?TUtkgH#pVUC@I%lJ2x*hdY8S;=h6MRP)~d$Re$Cfby{k<|8)3Do)oT8 z>+rDF=IEu8NuvhbtRBi#a7rXStISWkDPvhr$_gD$bE^EjV4d8kYG6~+eRGQV`l#Y& z(@b4-?U_1;;4kY8>4gR)>Zs$f&B0V)JlZm>T&kGWG%EedM;45x`n-c=R{F=;D>f}A@GDouQ)DwWsR%GjqvqI1 ziMtY*rAPzL+L-<(d)61Y2bRX$OR)}*g zfOm?f7i;RIP2MuomCN#LCa~h!lnI66^1_L#Ck5*g3RkwO#m_dADGUtRKu;`$d?X2A z2ImSPlx3J|E?}9kXeSHHEA?I@2nU@Ry0FAGAVtI>-f4v5Vs9bjZV)x2;%WofK7^MP$qrUBeeR0wK!$K;;GM>-4P2BdzZCy z*6vBe^xjDJuM+um`=5*OtLWG<9K++{v}^`O#wnO~LT3Cz-HMy{1xACy#Q9SHK}=ox zd@3Zol-O&XR{DKGBBShY^>}PaUF?KHN%?wbJn9%baj8+0U?X#7dX)5>8QoJ6W~kCx zfy+m=l!zT0M160h+fi;Q)NQ#-OPgmL!&v!cx<{o15DBZ8G@W9G%n_P9Fo33hrgLRd z>RfC(BJv*JC55s~1W7@rp$0Qq?2ib}t#tdSR2 z(E9>!bpg{qRbstcwRwKM+l{r?H%;Fi96-=jyGu;;rJoGwI@RU6{jH`h=7e;Ab2mg< z>?|Nmxt`;>^h9x!o=tdSFku37wRndSI4>P&LQFe$+{$G~-(&>ctcbbo*YZ>7eCv1h zoEb~6u>6R2ox}J~!ruS7hHX7W`{qP&_M10O!mB#65vVir7GBSHgk2K`?^N@Rc=ZPY zdY-<78rRhe6;)04Zpjqo70bzf-Qj(t1rSZN03Zqth*0>EFdd7|)GEx$v=F|>Ggha8 z;4Y=TXyxi>aGo=3h{;k&9liB(H58RdwpTi8Ct85cAW7h1g<|9bGa@)v+UU7r;kPtL zj%>ISQtYJD(oCyfk-$EMj}DUj$KktkWqa~8K)ZOb4q-~b_qe}4XH}GeWZ^g)CwcvoL`ddI*zjwg^UZx>BHHovq&v^J9h$W?&a&OE;mkjJlkw;U4? zts1MCy0Zgl?(t5%;PVk*#cf`ZMcu)y)~@W=e|BY@uWfdYTF6Jb?vc(f-d5mX~%Q3Om2#d@I^Xv67WLyXA z%+;4=-da{eH6E)HJQ6)8mCKk%Z#=#tqYzPwU_~3pvFxtvTfhi>OuD}O9MTprl5IKO z=h(Atb?kdIO)#ALA3(on@ZYDML>;*WfHg-+LPd;IfDO5c05iUlr%dKl!u_)}SW@HH ztJtX~?FU%A+29%w9x|aOI%>0e0uJPAOyWN$^I@3OV$Fo>ebKF@(R(s3vJ}4>J025Kuo(Pso9g|>bvw1ED?&Sc6Pp&ieQc{MfeO=XT~rDYsYGHZ{(Hk zxLA!djI=KG?bK`>k&|h7{vRWCCk76&4b`vN5Uu0Emy^jtD5T(uKyW|$sg;4M~NY| z2P<^L`f8tUH+3}tX`8Lpa(c|%XvVi3wDB4b#&<}(TGYxk@zjd-U!|Gt}u}GFCh^6V$It3PI`#7LF_u^Q4uF>Yw&RMt~wC6rlcgFBMbVV zVK48R%F*{VSmK1pQ`oFv9w_C`9zkTRef?4h?Tv%M`0tgMG*~CEdKhk4erll7#D52# zr$iHzifzBprmvlnY$t~5WZ8%ka@L)O_tUpJ*0Ms!FRNN4SX8Ge+GaY{lc^y;1|*dW zo6b)%zn{s`fSLu1g{tRj&$Q<;K2<4xGH;k(`0xAX?JJSb>S6D$Q)FMwtd?Zm5#yik z6aH?p$Ju$qhR*aMR@=qLoJV>Iq_!SzI<>c^r}e6a6~%d((8Nh~A$igXs9p5-S^+iT z{>{>S#W$E&B}oILZQfsgzv{bwp?Y=h?x}sq$jb%f1qujjy2gW(TN6yKiaKu-ldfR; z1H269zj(wkPVK8<~>9a`C^Y}boyfsSD}7AncI(h?m|A9TYG3l z(v|-LdH?%Y;C^rdR~N~d%%juO^;?h!>c~6r4@mK`wem%|8(WBuaX!tm@T{VvT3xPH zlw0>?nC>HgJ5}`#jL3FL5{#*`L_9&2yQhH7KQn!xN|ZC8LJO-Lu35@sDI>vCOIz#+ z4MEsHc33_)JSJ`C!rU8TDT;GYdN(ybQEbYeD&0Tj7IlKz0~g=KqwmbTWDuk_@GJRz zQ<9@@@X_kacGv1EuJ4My+_RH_KYO_~DuDsZ!+eYQ(PlKsiY*J;9^;xy?V;&`1IlJTK^S#RiG#@jY_*~cDTzyG=H+)?oHt^&o z7lvaHi-ANOCU@k#X6=owgUggKZ{Or2rON@)1~2d9N6#1YP59e|+dZ?8B>V`LeimhE z5pOeq0uClxq6T;$HBI#SR2}-T5yLijT5taO;b`lEPqnuo_|hFENB+ZEP-txSk6Y}2 z(xOSp5(Au~M7nu^tuA!YUT&3`oZQ1eN%ahZ?o-A0=32Ha{_f3<-?4#wqFb&^%GM=| z`=tKxB?cQmZNynVff3~*p9V?-`RHhQ)j=5-!u)hvbbQ^&aqfIpXa<|e_p~?|t|X>! z50+C~Ltl3iQhL2iE}hz2Q?Tcks&{=+Zt3nh8yf`>${~efc;ffc5~@m0J7rzp;PkP# zUzi@P%o^3dKu}oBj$N_;pT}58GyhcN(ptzM)*p`UpNjb_ccytTt&8v2uvjr)_}Rsw z=8%!MLMs0Y{xVEz+!u(T&u&h8DO_AX4G8s5hnQs!b?Un3e6Ni2b<5o)g)=EF^cu7Q z{5was0W&krhY~(4BhBDjHOTpv5BL=<7|dbUl)%sGVDbNdDb27fDcS7vE6eY)+Rtrp z1wgB!N#eLb{n#|_bs<;wCKe?_X=jkN|RsA{IV*wMlTfN8T>l~j^z?KSo%_>w;H8 z!mm>^s-|8KKT~v>^}I84Z7OYZ&k+KzL-2O<0w-p5Z?94))gIJuc8{PaGi&Q7N>6) z2acPrrWm-?U|&L_=zeIdbgR;1tvo$m(JL7l7%}9rx!*INiBpW__I*uA)KQ95`ZcKsuuuV7z zofZv`Zb?+h8d=)XEXZ!V>0BeSE_TI|TRS}rUazKPCf%ofAw3Z!_bC6x_=sR1i;eFs z7el?fLSMBw4tNz*1#iI2TZ$SDsFshn9Ad4id!B~3lAJxKayL`ItzbMJua#-ezIB1q zyQW|*)V0gAj5_LbIcnGjdz@HV*D+O9MOq>9EYDj#=X(=oXD{P16-KNciJpt8qSD(I zXwLsQVzNy%hn5U>cZUIOPG=u zO0S6zRZ=CKR0bZ%OtF?Z9|Al*k>rk#XPeDe?EBKL<(P1#o2}C)%HS z2^|^5+Q1&=r`55zGkl!KT^Pa+qi=u!1dAlcwv&5y_F0!N9D|pz=7Aq~VI_@aKlM~* z$ftKbqwSVR$q{5Czg))E`*`vou%n8@e8Fn#U)0v$k{KJCYpVf_n&g*NUG_AFm|ns9 zO`Yd05J1)zxDsfsD2FfWkId3R>Z~!dRjn2I0Q&8N`Fp!ODSHYn%vHwhC#N~36{+<^ zuMeKtWn0)-L3tF)co6-O zg>e~V$)6bYM>?0>&b>A#f1(MYG|>%Gel{<(>_6icg;>NFDjM>TkH#mHb`>zy(*Aih z35*e&u&Evu(JWW=Kuvj0fY4{2EAyjaF4a;^8ec@yKDB1P^u-1ruN&TEO=`?~1OOIB zrdW?XKW?~v2zf5oX+5r7#`}j|AtzDUkBCnOa9tf#UWo+veLMA0JixC|ks~gWOm5OnRJ(6{Vg*XNCkj{_1FGJpS+A8?l%?a>s4k zK-Th3|INF;?=BQwE;8`Hw-;R;ry{5rdUI!ofs~I?q3n8UhXgA|vY%6;A8*w1uFH;& zH=Gn#WEqGz8b0o5GvzcXq$3lOFQt}Wy54n3x%M>ff>|Y7TDDFM*OIB0DrWpNbl?o+ zF?rCK8%&6mYx*o}PL(4KTF!cYm0NG*Zq0@a8 zZ~sEj{m)~aazZX24_xx8*BPk^OEHWk1r91>I&EYl`MQtQg5=BEgK=7ohKQQO6j}fs zt*}g<&Gz#ec>3%YH=zF0vrdeA)P^K zhg`d>cS|ju%S7*F%CQZcH_z@1M2&yhN2Py*ReyDHs|{1@+1Xz4q`flM3Mx*Y3b-JK zix973dy&`~)|_G*7q)&|h;%u&h2fE5oPT$JT_5_NtsT2H(517B=)~s($a-fh@!_`2 zXVJWv6RdrSVNN4AQP+fbPb_S^z!&~|q%5(!Gs2vw{F!6E{AH%s5jiVzI-l$+8;ok= z6vrvMzikqL{-fj$9IeT#y;527%ZV1(8V!NiihO=pxY@q2x#$`spZb_H^-gi_^RWU@TA+ZCCcc~AA7##iRxmzApOUCV?oJU1Npe_(+@)6?dr zTA8vjSBHLORPbI?3Tk-#LMXDO)rH;g`n`emZcg7ssEdlK8|n3k_C-j}C(~ZB zyKN05ii2A8@`)7@61R73W!us|w)FH6dQ|U=v@e=Y@V0WG`VQv69X28d9pd1p8MXMy zM=*1*+l|wU;L;zmJs|sfMemI>LoS12o|&U^P0{oIQ94I2YTLQ@RxaGXpn6(b%0o9T z$et8;z&1-;H`}IR?QY#H zZ);;HQ_c^)Dv;%~#oB#akzbRu#lATvaJ;t0(ioRM?xmwS5sTc{G%8Y`r0Y>Sotntj5kt-b=kFbC3LiON2K&6OCGHxJH1Q35J>LR=M)<|1=4zFwFPQR z1a4iS9UjIc-cDu@B@D328i~Vef}QLKR;cOxD`lLBQ?W0ExW6c?hPTha;SbOGt6g%6 zVz|6d*O`b-YW?4V@%O2-KPY1_9P6iV5k7Dd8ysJ`gv`c4=bG)BwVKzzDdyo^ueema z?otwJV3csw8|g;OH5q3TnS*sULQQr}(Cfd6aMmqc3%LR?&sX?y z$qVhy2y$id#omkj^UnAR@`bPOw#Cu7S4I|(QiWU;@e6;ezHW3Ww>0{WZqEG@KIii= zZhPVWRgv?4kFFm6{P9O5+Mk{B@2$D6?)XvTZRZE3kKBavrOg1Gu0P_TFBNf#lq_X> zGm2zq^bfmHwhAHX>d&N-Birk#i;V)5t2bLnN5&VuC1|=Jm(A zTGe`5mz=|qUZg%SM?xFbnir{i72_IaiKiZ`YnQKk$mT@0(uJqCjvlTr1*Gk}9ndel zFBBf0cG$X~8_^R~`7zuV0pK(c)e2neb4PIYY3+s^^=T~@uBU4QfP?Ahp0f--JGX*h zwStIVWZUdgk7yHsu<*RQPng}?CRwna5Sy|)O zXg%#5)DYWIOu<43L);{>*r6=!WYR_!R$P{iM{cfsmb^Jx{{?C$ZANG2&MVIt<){)w zhSgr13=$F3)FmRH`RT-pdRi`vBqQF|EM5k084I%1b1*c^vjY4&Ra$fi$u%~X5jNNa ziQgE8sf{e8#=>%yZOUAIn3!v^F=XCk1=#lQpOPEZ#W@s=>%A(|^l| z&e7iA)re+_%IBuol%K>FH+ESremvv0zXKlVI3Y*SgG^vT&;msgOdwxit#+J$lbR zPO{!>e-aKG;cv${>YRH@VGHb$=jDYFC6WQzq_3x!Z`I1?*>5RxK^-JHj6NN1B3%K@f6>!#OOEiOr3c*mQdMdoX8az z_g+ZBUPVo}0UEU!mkm8gl5q?m_gh;I>mH3FsSSY{%5+ING{l4f0JDe;muw)jEm*j1 zD{>GdTzs-tg&CsgojFl-Gt1nZg9)Aa4E)(Ro4kA5sU-Pck0p=>6o!fgG>is`PkVr^Eh(uO2i+eP?XxmCWt{9;(%_ zA4V1z4$EHFMn0u4V#9g-PW4%6jK^AoT8H zwHS80i0W&oQB4u#yf~N`H=GdXKJgw?-8Yu1XbQQKG{80P#vv>CNlP(wAhdDi{_ZIV z>$Jbh7qJU0dT45>epNXBxr43rZ%+JKcrh|A0VOBUf;aMv6UpV^xTj~~A2`MrQ@Wp^ z%pARP1vw-9Mma&nw*MOQYSql5*Sy4DeSHg#*d%Z$sP*^@2ajpwY;MRPX?1VwfssT> zP-KpXDV_$;qXgVDkC2`El4=o&H71!y2x||6)tSQSV$^=lIA1v{t|D_g54he#TcFyV zw$0Dn{4bql>5+GO=Fh2QJ+R%bhk>Vtao>ozkNZquG{Aa*0K5eSu|6hXAU&Sc*Hs#boG_bqzo z$&27}39yy5SraM=lEQuUlCw3^!oK5zbv%b#opvFX1iMF691AXq^9x`gz4WZ4mJ_MnijrmD}ehK*W=dIUCG+&A)RdC9v2? zFS5eak0o0;98>c`TUOh5CH+FI+M^d!OM^*4K&hj)B(l1o`nBJa()w{goY{Ys_j2dF zY^+n#yuPZ{a(``sq``?A8&S37HSCblY&)U@7*+)G5Ixelx+>q}er zit!4F>dOx0i5K!a(r{!WCth^pZP)J<{}yz9_!}zJr9rBrxu4(XhOxD`*#nsqx90?h zs%QHx%x~R~KU};1$6I`jCH}#!N_|S2cggu=%_ds{)W#LVZ?=z;Mg|L;wAIGtE13Bs zRUkZ?g_6HZiIPd{?VDYPT57se7hJ>l^Y1jDx9c0Qc+{p^ntuhn4qJnjK{@JI_Y8%1 zGw%)vm+PD);tdljGr=3SvIg$Sg0pgWvVWub{>n@QGvXW`xY#RJjTx&uIgf>OVML1s z6I~pFCzg-8d)WPIGGhSQ**EALr-rL9gCxJ}j*}BabnF~n_U@NV0LtQVes*R|R#AuHzEt<~J$nI>>-vgAAZ zw7QI&$qrg~tQ*PGzbpAA5_~gY2MI*q0@9@BUrFODB$NhwR^ri@My<$-m+5ugg5O*# zhx6qys=8=}eXsq5b5rSPm0ftwMaJy*E*&21^G>{mZmhQIM*6gQGf1%1Dx>gC^U z!X8pe-WXd)zE-63A=Io9e;V%U^ZlX@AmGD%OcZ#Q7FkLwE|!6+?$DHW)YZuvaMl}2 zzHqXHxj+I8o5Xj7(#EBE8tx6Id4jAbaMX$TYP@$CnX5Sl(io$AX#^5IpxVwJ}jTUTlmt~774-Sufa&E{yB9Gf5yHJcAz3#$fO z5>0wgI(-Q`wj3>eTZzT3ts5qR+{syOfmyV;&pltsk%L)1yxOxdD~FRXUU!%mn+DEP zUB{@>Kb6mxfY6M!nf1ycvsvKdZz!=ZqLMH}5>~!z$V*qG?O3f&zTP}RMTc-gEdf!b z<6+t3Js&?kVYbPyL9HmCil`ou;Z$_7@!Jz(v8v}|QH(fAOQY%3emg@ zb>%~HtRg7qkjx>s4-S(PS%=- zJYeOze&Ib0o$c%aFC>Q#U)p-+ohm^a{{$xxvxb2g>Q)+REnnMz%{+SzCa0n4_P%;Of-Dc_2Z_M++an=XraVu#dl5E zw#l{og5sFzhkypT>^|wdWT|&hd*K>KYNCwP`m#j(;=F`nW93qZ{L;W0VrmW1A%9fw zAy-*>$;ax>KEZh-+caw4^k?N=QD)qWW`L2%nhN$y9>x6|ginfE(T`-+JZ7)*h?9iR zX&jcvaj5YjYoQr#+VHP6i|1Ao)hs9*7JuDeLL>3^)^I-x}+o8RRI_W=aHBVMqVpF@BuU#)tMKG_|psV4601S3gtvX=b{gY$OBxil#3|RVUXuGe?Kyn(z~VMUuOtSX-={m|`L7v2s>(2W zx@$mJv$9s&EDcLRRnVKjm3P#pbX0b_HhM5H- z`{V8p&O}AzijVXo00gK)H;P&rs%;3?C$J=>+Uax~{VbP6qWRRfHI80oE2mthvYmJs z#i?)GY5NF1@cQhKr%Gr(uQH`IstwnCq6meF+*np3Zcs5peN9=i@my7*qKOg4R+S>+|fElIXFGzPwB~FXwuQsZ& z7Gxf0k>OdW)UC#sQh}RM5c8Wc#$ni9SKtH3DR^lmKn>_F72tPN3FuoHb`7nR4(NCz zDyKU6P#$HZ@LF+c=z9e3uZTX=cPrj8Q)|&}Yti_M{|;rNw2E@#`8*yIC=?n>cym_5 z#Dwel(h3TI`%i6p8 z%>Pp(_qEY-;KSzgAt|i`gSu;Pn1K#HUI{2`{vnzt&R#CQ5QnQQFC69#nwZOiPhFQ_ z4Mtvtw^@BrYP>AUqyGdKiu3I7udzoNVw7l+X?`!V&)sT`#jv;|$cJ1{D$x!#y{fBG zYy{rnWR)oo8ERb&1!*LXiT2+y-f5$xjY`={IA2Ca7rs)U8`r-06vYt>ef;t})oMwX zRsMDIQ4iW#$Fb>A@B1V7sIu#GC3a{R#k}*OF~u^{ssip)Up2m3XfW`a>Z;}>k3Yv! z1Cs87GYeU-p5c^Mzl=>5h2n=DY2b1an32a^b3()&vS`!>ToNMHT- zL@v~%!7!R@fX^ocI+6O~{gv;`(Wh?*zKxB(y{+dk#;M2+aXjh!Pf~O#=YH8SK@{gM zZCmMRc)emd-SxW1V^vH|(fJFX3jSA*tja#GaU3tnbi=@i{m`JJlZhL+X{!fXBOaIh zM}-3aZK(^F!PWL-_{j0M>}JUiJ2`Im}Zqsnc*6*jarxh_-8&VBG5-y~sO`YC!j zQTAPp#0cjlos&A}O-9qJa`Rgb(s5Rh2T|>YGXLs&OIqGsIk)uO@N!GV;&kfKN`w5E zY3(p)(;vdpKe7EUqskm>)n{rxaBTh>8kGzB#Oz8N~TfHLxUsix|zy zLYQ0yZu%V49`rZx;i~2cE~!YnI|fqd7VA3l&qZ3JD5jllpUXq7p{vC26{+|ItR!oX z(!aC`(I4CE;|={m|7qK$*k-NBC~o@2WBFcRL8Em1gsJ;n_c@F3%%Jf5DqZr=jhQ`D zClXJ-r&barh~;IC{RDYq(yUeq;=*rMN_-6;eJ#!EW^UL!U9J8x5WPb0(1)Xx|BmPG zB5Q4{Os>54=hZQ2t?W8}@cC1bRDa|o zoX57#>aFhTA&Ck_QSkDW!v0^XA2PGbQ)pcYDY7W5dXte!p=}JQ9%s;^0G4Zf7<_!R zBXXg;d8yNPuF>^ncgy=nLF*IuFFb1f@Fe_4@un8<=?uTp`G)Tz3*TfZb(H%PxeZN? zqYSMb_o36?P>VEj)~q=hi7`(3Zd==&gp}3KJ7VY%Yi}04@v831_ehv5QhoG#Ogd-F z{Ii;Eq4H7(dn&)QO*2yFIlYHp-k}@&2q0})a#{`by0yN=Bl7uU%MGj-*LUZO z;!6Mi)(PHfE9$&6C3^nm{`>yBm(E9g-tew-4ZH60A3bK#@s??9h&pIQ5E@A+358n< zav&_D-QyF4^<`WIC*s@V&qy+}>l1{%>Vp%6d<)%8guJV>OoV)hXk#R9q#lE`?h|B} z&?|1|L}up3f+RB(29o@0KYnb7FVg9Wcy4XyqiQ+I3DO*2!?ep~($O;$rVDI6e?Bv;-ypJ#cR1)7U0 z$8UmdHEwR!UBLPY+t|v1*T7~$DL1V2BWoIW8=Jd#cbnQqb_MjCT&hx9Qf_}=)ToQj z9luwOQkgG#B+!%skJ^X@`&OEFEcxYNJ&L67=h?sWOEw=MNj)4dObDP(Zns=tUE6vu z^nB?}eCVtSZ0!bfT3bd`z_v~PtjH%c=~C?0-%pogkEbqjKHuTdy&Sds>>}sc|CR`* zBHIyf&)$0PDkC<`!slQbc}qc%Q#2$A%}MtRuUMwr)6o)$%K@uOPo3+dmv2bqJFE%G zG{WMA)lITSQvJG)-=+GHSgVARa$)0`EEcd=rio67q*R`5hnH+IHuq*>>~{M&maisz z!mwf68fsL9YG>p(oV1&v8jssyaz%ajrK@7R){@1HisrAN?sVGDk z|9tU0_<5C?pJ;I?h(#Qv)5RjLgw(e5zDuD?)F?D0VPD5dD~ea5f^Uk|I=Y&P_5w0b{%kV+jPeX7q6Vs9>2ut*GEPG{P7>jz}9rsVV zATPG)m8!nalID7U+T(8TDW^J`Gh&wyELlc>h<}YX#RpR|Mdk-lU(*QOl1-NLB^Btu_S#OP^vy3 zMD;R3M3dr)$9+=fC5C*3l;Opp+LQ<016MCi5(}wl6O&)7$TF58nW>HQnc>w4bwUcW zMW@3q{%ZCSr#k~oC_rkPr=SPL;Dk?bU0 z0Nh&HNYdk-ItgV4&m$3i$g#k4N|NS|vxBnlMiQ&CgH_z*y<8C(S}#B(Jy%v zNX4wkwpBX(L{zIMnD0(fO&%k?*-PevL-cc+h_c>RbDH@*6{8;-jBs_Cc0beFw~U#- zu5Djm@Ur@bYM9+A@~}~0_|1&M`o<>qvvoOOr>g9Ps9et9>?R_}uZyWJpy{TG>aBVid;~(1B$6xkQm}-1erY|~4`wbN*@O+E zZEjo+*3>(DFqS5=J~rwpf8mqP`(IN{ky7#}aEQxVcDVB^5Gv&%OyP2oL?Z|&PVV1+ zOO}U42H778wkKY*kZ?*R4V?yvO9uYrFnI?4`FJ{>=|a6+0j_^O5L$~k8?L?THCGYH z&DukuaggvwhnZnd2gSZir}6#^6=a_~&lR(lczG>(@x=sUfF>JYaDDpQSv*Ig%9y+N zAnVKxfcaoP>=T#5XKas+CKa&>OtA z3WFJ>Nq}Rt#Y};0NsY=|=_x)$F*j$S)9YV5ym~AyPzHUZw}*z!BK^DVJD&%!7R+Dq z1)O0n-nNM)}s#0iiyuQ;a8G`7;;A6TMY_7z&cZ zjF7)fc!)WG%wm(ZGkL2pirarP8JE{eG}BF!f{18rJE*Nw0I_I*vE!;7R`RPxW~+S6 zcS&2f$c3rm& zYjTl7i8?v9h-x*s-GOX5ikEr3;!t25Dp(jREa>=Wny*9|bdyap5+zvPC4b7K7Ofx} z_YobEuxwUm@(QTd+IT6)qre10atlk10XAeQ670a4C`>o&t&U)JFNTZu5WD3xaB`U4 zGMs(ATJ&ce8at>2$+vdjXLo1e{7Jw1AqyphR7TGSY#594sBwVZ>fp4fRtEjr6+(gzQm!+d*63fveAUbzCjRAsxQrRiP`scI8kd<2eW z(ee&4@$8fjr!x5k9^szNlgj3#DJF<2+YqxDU`Z9wP6i&l9_+t$dhU=_>qlP6N8Z^d z<>VmldYgHgkR%dKt8>!d_Cff2Vz&!3cEiuFK|vj%G~Y`3lmo#~qYDiyoUWc1>iam$ z_cWzGP=^oZW_)$KJ4;xn6Be>>mtQqM#U}e z3fjpb+#SUc#Gw3TMFH6_zgZPK@w$}rNtq?@QWqnl3&qtHloK}1aa19;5iB;w5dn@9 z=lyB*Uohv*^2=5z&L9+r)1s^?lK@OEj2Yu_d5#zv^ zt3?|yJvhwg)bTWR^199Z72$hm$YmSN5sXQ5Zbi~v4Zn zD`HraOCvc#&5^4E%GK3&=?^S|%@)O%t9)KIAXK>=Hm~v)%?Xp@6#6MDIDBnxCX%U+ zq`tQ|lBm2U$)BvquTE*RA?B!;3wl_3N~$dog}T)(fZ!xNIJ;c3`KO1ldyry2)E=N& zh=+QFNNveTbGKJ@ghK9a$|O>69M*Z|2sxCkX^Cq2B&y2M_;RN#_o!mwd^q zXKny=N8luK8@Q|-mc{Cs)NV@-0)<7^W%q&TzZ6ngZn&ZNGeZF zA)87*U5Dn94@@dYwJMj2)rF4SXF0(JINQs!9s!ajmn1bcicLH!A^%2TWcJQzWn_b! zyoFC;H~<;jb>p^L(T`6TjjZ{v!$FynKDF!imyF3OXn0f}kLzyH#CbBMJv~fSE(jnX zeec;ju6uui_)cm6ZdJi6hn%e!OyjI!@Cy0NSYX6T+-pbY@#L^c;ENu1hMiG8;VMVi zBNvh{ye+0Pv>yi!ir+S#SGg9sI;PwrpJ&8 zX94)>FXIj8oA3j{WNQcU3W(XtMe|0;s#knKl9w^ ziKHFImhc(0Uv>ZH#Vo-cx;D^YoSoSac82O$`10bt24{JWzZ!!+gpCOtY((QQqvsbTslWYAq=ter+(7hQ z1y1WK;nh}-x0)QEdcm;;jhoUvz|I!~f?IEWmVHe{Icp?uJE+|%6#ew1VD>bc1`PXL zQzgMqvqffiI{IkB*?fyC;*hbYPoGCOvUKN(=~w=9d&02RO0SR)5cXosj0YWpnc>dU zhtuExOw-7WJWWZG8;Hu>?|M1xVpeY?I8F~sq?^~XU%VGz)cBC6q`_^4!~OiE)jn`F z_|dH<iQID$zq7gppLPqm1Spz6G9E{L5>48h zM2k_IM-OsWrOyg4ckNamGPuxNY-GTz{F#OgTM(qFa9Hv#%U~OMx z&pOGc!<>dSb@ydwE^=eZ-wCixr^QRKvub4NgG!X zLD}buN#3}GXbVE46G4S{alw4O9n#e1&-Gv*B7OoXmLV_?OZCNauJodTBI!NR`6qY5$ht|5<0VamYhqBAW7|GnOLc|h-`JJ_^Zy?pq z+|8uw+|2ee-;JSp!K=NtHC)@@?1O3h+;wXoD?T1til0B}gCrlBq`|!6wm3h@z|JsP zJ+EeKZT(j_P6ek>jB_>XtKFPglbx?*9(CLKWuw^1*uAV2CG+#QPX5pv1Pn~e_wMOT z-nonFSD1XAK{@^|R+o}67}o!;^~*0aE{TBk|79$01g>u=E#CW7IwhKOjl{WiDWXV* zYgjW!AoMby2L8Ej_CRdZSTUNl`+}N9J_#vGk(&hd_+1+D!B44rH`!%oU=F6*#r-A@@a3eKu z#oafGaA!ERSpG^$6Ty?iqR2F}l9){YYkg$sQ-4OaixVPgn!(M~t^|UqXl#|-u%3K)_`}%U5Ww7z< zr)~HH3J;#?|Bx4O1gZtJIf-`GQQ<(t*Q^bX<>W%@!3-+(yCB=7Y%3by3 z)%lv_`OxgyI}5Fq7(^h~hmyaQ-HOl0zG$q4a1ExaFpM%N8uK^|k7}(N22Ly=`sZ6S8d?O*CNbuL4 zE8?=JrBc6|0-s*Lx}1@^T!o*k1jo*3wHu#ZWz$-XE4>c* zu=l{>60Es>&@HcK!H&=QVY~fV=ZEvp!ud5HIKPMH@h-WJK1@HqP5q*PD}`ck0p9ER z$pPt@OFaScMt8W^s(%hZ&h_k9a)pdjFg!aGJ+0hCs0v#a_MJQ(P8JP*@YL`Kw*kfS z5?(xwVsACeqN?|MFwF;$XV{P|gjViiJa@!PRhX>LHcPd11OO@je1h*;MyB2I^NWt{vV z_7IJ{2FYEB*VqJq37%g`y@Jbg@q?4*Pu#;8R>kbAsns7@8mF2ARcqf(dilFI_Tzk1 zst{-0FY)UPDSx+p9%(ER#?PhW>*J6s%G2g^kTSElYoBjzAv*FsZ`E9$dl|ykZCNC; zSl{9JBKeK%{lpTv@KwkLjaO*4?E<#CKkDo6k78KZ^Fu+yXhsmXJPM$MU*wkzmm zBtnX{=-%D?f@ZPIQ{=s5L&6o4EUwg%oMO9ydE1v|LLpQNeZd-ugvg9xLkBD=+osZn z!Spc=eO2~af(PKshFMls3L36%BXL(c)RSVIJ8Nz!s3TvIq9!l9> z^)6x|ntf*^_1aZh+BL8Bog7M+0lnR3(zeh8>vUppEO%UGibz99-iy^P$aJUY#`JgG zxTF8AK|%r?DFO9{C8W(7ly0lkhHZoL~v+sU74Bt|Rx&8Q)(|mBLrKy{5g9v-==5TTWOe zz7|tHea?I0s&rxu9X)1~w4e0}x|&1(P)~wbR1XkN4|dE6qGf)l#a#jPcr4z3Cd+|o z%U>#34p#uG-uF&=^so6-Dt@c)>^OqcrIIATX2dzGzcs+h zlAxX~;MePPHWz;GI(G7_8LE{V8})6aKvz;M52JH^cblQjd!3h&nq@2^Vbp7v-jkIs z^x>1QO7GaRoI~~aODT8LamO(whtQ{d;lE-r4NsArN_czZ)xC=l^Hk-Y^X}+TFyEBmuE8DU< zXcUJcOcL^a^{v8D2mLJ6kUUM10n8*vZYjjq3le2c2kt{T4C&GxFdhC^9ap{fedOR> zH`v-S1a3powK3CM#(MtL0;h`q9EQWyU?53u5CY0(Ofmyx8>D$Xb)`8-pP-D(%N3>d zW0TF!sI(C&5`3vKd@=0ZAT`EnUqa;s^+ejlSV&3EwQV5&OkxAsn78%G`+27o3TH0_L4@1j z+mE8ZG#(1^26a5VXEUeU7U>hImL6@r+n;)>kZNoP(u78H!vmVsy z0ok!>47!E?T8>%x0W=%0d3Sj9xzXXZv{+28&^^3Ot+MgD>oiTE(M=%GD3BV??Y}X^ z!>PH*`oFFfm$v=CDfJRQjj4WY3KSR8>&Fu+Wj~g8dY#tYpGo|$s(&M0qv6}r<0qrn z9eJol{K5YN{~CMl7%q1caZlp>62ytbduBdnaq!YFSQ0ad`1@%8oT=~9<{vp=;pjid zA1XgC|JXejO+u&mdw3wPG>(bmvo4*3oy8EZB(qG?ErSZ*trgya)6Fnl2ty^_rK0>* z2G|2#5P_#qy1+=_88rGTH2X982_LW@3hck#mq-E8)s`MxK^bh{;qP|&I2#1%+NXHk zxnIA*zj`GM`bCTwK+m;v?kUn<_mZ)A48aegwkE69p*cC%Bee}ssHdGn>233NH&u(g zkyRtNyY;iXHyW4B(sfAs9iR^8wN?2wWht4y{HsfV`?)pC`#dXc0PHet(uVgOzWGaM zsXUt+c3Tw-m5z)BL@J#6yR~;K=xRUCMD0kJLNk3m)PD8Tg%tYcCxDFv)1J5D`KF`>60<4sh>FkI;&XL!5!?lY_*`_};{aX^LzLrm4S@ zGLi@s-{gv8ji);gbQ!=Rc&(=zoeU~u!VM3#X*HBw!*D@%V;oS0E(#t{x_;#R?+0@0Se^+#c(P%ls0p<&Ft|&S5k@g0Mcz~EaVC4 z&7Z1Qt0fn=<3~yD49WY$g6%_Ymd-J0eIWg4k$jh#M|Yd1bSFi7%i{`>HK)D*`|7W4 zvISO{zou4|#n!je-zksDVJDnAATBy=yNem5#SROi^ebVt>>uQ8uFTv0&EN55KUR~C zQSmg{c&#SmzpUVko6^aIeuJdpW^IIc<$35YdO^DozoE=VuMk&A)|rN0GlU7(0sZP> zAJY4c&rSQJ{Y2J=mPgU%sRzP2+aNm!#T-2C(hr3ALUPe|zcEhN`^Sv$+5>T8g<4+- z`ye14Gj{7fmHnmeD`%Rl8*Qlz^DYge7+>cT~CK)@N}PcY+!dt z;(o22hP%nXRl+~Ts;~PYjXc{f^fL9M!lPWt9@+%~I@{2vmjWv&)n!zvOc2dPl+09E z1QZR^J~!2D;F|A|<5aP6p{$+z2jocE+8BbtlyL12mB&WMV3VF?V>kM*DucOR>&zat zY-NOW2PjzhTqZ+tVyO1aLDHQ@hU+yUhIA zDu;T?AIp^kWE=pB#{f+n;B^iL@+3DX2l*ykWdSj`aw;2CxZbLI<`nb@-l=6Al9zIy zU-hv1@~W2d&$PKY(e?qZ^Wj_z;qniBr9PdP`ZSpDUnKCq{dB1|o_9S={a2}Cr0V(1 zRJ!VRfdx?QL^2b*Nc{e%Ij5-^v&i=Q_Y+(ZoqB4)QrJ&^)n*DlP;1a=H3L65sAv)r zQeAqVISu9IH@SKYBq{5BWglMuh@e)`5FOR|ujcaaGKysDxp6;fX{0bbn$ zD8`6(ZqI%|%W)&vx)>hsc?L2a7e365>!s$|IFH4<;8o_=^PUw><#0DK z{&F?+a(O1l=`cKsPXO_8`X$_K_q%XAPk0oLdF01v70WaQCf*8boFN^QaZj#bJ4Rt& zTbvw}Qzu%M|Aag>5of&uHfTVYlvk47=u{SOy<@k8nYhJWwWDGUHtYBT?V`;6%++^L zzSVM$DX0Nz1o)JL+c*pVvIxDpa+$*i@gXs|@S#ABqUtX;Jk~oY`1Bi{6ew6lDBklW zo2b5Km!EXKSFN$KG)lc&ESHX1i6iwbN48v)DWttxpeZPeVq0jEci!scSKYOH-Wf!~ zk@CGF*#5^g`1S+0S%~M0q%>I0;)lF=7mB2+w5LkG&0tdA(u_(DH&5N~sy=L5U*99g z?e;HTqCSqe`zP{Gs8Z64O~o}!vW1QWCQniPJaa%!VW_vE^e6AZZSkoAg*(C0KZ`bs z>Lo5a1FcusiuZHOpz&7u?^qru*-ksL%s;fLf5_Tge8vv!F$pBNCG!x3c<-0H-pS%H ziH8jc@qyX7g|fMMw>nL(b`5gcGX%2*!B3?SbH9OlD4jPU{yA;fvw02fO$F2M*kozs zsO3p_=ci)Cdq$)WD z{Au;OsWxDh440{yhQ(>HXM(`G%BAhT70Dd>*;n<~*3TNvCw~yGVwCh))OGY5AGWG{|}# zjYsJSun*| z2T*VT$Q`?2@6&EA0Hl3W@A9O+Ih#5)^$AzVriq;!gK|$hsKA`L`Ha52K5+eC`rKmv zm-u{}`7jk1vvJKMu6d#RFX~mk1T<~kyrd_PaZUTRVmWQ8O@L6EUYwV&;6_vX$Fpa{ zOK1pG#j>d<0e`mb+yxizZx>85bu{%3l8q_!7jY6fa-o_<2EP~i363)v`j?tV&XGF}L*v>7Rs8=Tc)xo>;%r}ZGGrGo^WAR$HGV%1$$cr2J% zo@Cw!l%0JL>MA}oH(E4y?tpNy5MFldKvx}GUVM5{CMX!|eMO;%HZJx7Go{-`k(-Jt z+4!;NUMfC~UAu|@Rk-ejg8l>PS&wUet*sSd&3ZhRi2^FVGj2i6so&9LcXT=ptAzFK63 zRpNh~)i$_dXZpMPwUT|f;-6{z&cm{Kod=oap!;kKUGX?E8!_VCy2OR0H-$B*hFRsJFopq++xU%v@gZw&(`AdjdeF30P}YNi!;emOJU|hckYeE#=f`8%v5$ z5skB>;1FZab7WqXz6UblVIp!Uh)rDmwdaOKZNpO%XqfwL(;Qv_O^9{P^M z?x@d&H;Y$wvKBb*Fi!AQYSn_ixVLf?R%n=@dq#ZcgN>T^wT&Jhxzy z#0)HfspC~o5u@h7rHXT}%v2I1oE})(`oXG}@&v!Y>>A**7RA&Wotuq0a_fz!gXT+h+4JM?pXMH1|EJG9`TgII zZ{PkI#IQnes91L4a1;$JH}*eVjryaBkcMc$m~`XGYGQC%^eMl2FS^4FRi%ClA{UE| z9V6t5b|s<{Lj;srXg*{rMk0pT}ps zU$5uWgv%L+Va1XS=zl`&)M{*2%-t5<(oAqex+TtTqW&p&OzcOfjADMK7`WZG?qXw& zWf5a%$-s7{u)0WM9oT#bQHGpVMSyAE^q~l}K<1{>v{3ik!wsRLF*UGY&!PC&yU+71 zjm3GY^1*B9ZbW=FX;ZP$^bk)*~5#?AtxfUF3aGa$}q}|h{|dK2Cc6f zf7DM$Xtg!Y#<}i&)ck0334S#d(`cO1a$3&)DmHL8ZKQEFe2Tv??4}?z$H`RXI?%f_ zC6F}Qmo9Yk5Ie;JV;NvJfGMsp88Bl#2n26f>Ob@u7!1yUhEQ{ZnU}0XoF6Rl$qcWYfrR3$4q>xkqRZW;PxCZJg;@E z-rVjL#woxZ$Yq%8&KTVx;*qz6*MIsMHXp(dH70H@G`hxGgpAQj$&Q_S(83{rdzO@;f(wn+^$6=F+T36z96#j=$M+YRD$Y% zkYH7x?60}3!9tb=Ei3hMy?KAoTO(!(R6c+#{c^NHs5o46Iq1HAbh_{;#1hXsK4ox} zB%BEf0bx`~3OR@*m}U5@0x_%?%MoSXplhA5#*TNYIC&f3lR8|i@RZ@s5tv|1C{!t$ z7W3^+DSL}5QXatgeWdbPA#~4IkIPquB#LMpG#5Ne&Nh}$!>WT6P2R zi(LHYF=)OD%WjJL zrNb@f(w1=WG=W$-ow>6|5aLr|!=-{3e|X|x%s^mDg6=Y==qxuxECnQ&D#y`z-B zUK-om5eAQPHzKbvq3@@KZ0Y}27~2uuMs5iZXer4+VJTN~yO%b~WRxTEPdd6Yr0tH^ z9IGEo`D!rMHfuP0-0>-mi&P>!Yk@nwb&ux*PviZ~pZXEkcdWHqOcTUUsMM@*s@_W{!M9b!Wg)1iF@r73bng|=l1RE)+79km$#){ zYepK}eoeyu7UX7U>8Y~RPhniPCCMbiCd!%I)CY?u9~!nrrQ|b$Vwvgc12J`ck)ClT zD~Y9V=nNFn8y*&{B?bB3I8#^7VeH4R8rcbgwH8$8iJ}H6IV_#0Rno9|347$w59jq; z|0}qQ8W-;Xq+9IQE-SrKoe!0M65UB+jJ-_aRYG+pbF?isB0hv@T=Cyx{lthy^F12+ z&GjA2LxLnwNxbj@p%6q`1jYd>3uShN-KLfP3TG`mF%|#tBYrmQ7i2Q5kXYE9=vxM{ zdAY9JszT4U`?AftqEA7k#;Pmip7Ql?5?u42sYOr;Kjt`}tq=!$ zNUx#F!z{F7+;AR1*_ha$HeY-5-;q_E_V3HF6vIkzqM{m0ofa#!r!}oTHch|9LeD{1 zHWww+W?*~ov0lG&nVt@jDPKmPwR2nWk6#Vgjb`aH(3N#;6^?$d$-K}rK*hC?;5w)K z)CTl`2`{gf8L_&bvgxK3lGlVMP(p?Vt`nts2^`52zCwvYZ4;O)4s=&) z)d+RKv0(?38TtO1i6lJ&Z zXDPQ;Fa~8Z2D{C!>eJJNtOcJ^1G<@QlNB!dgK@UDIm19*W-pE|hYToi`yKseu5axO z;rakJ=0wAVbP_XqQtwi{KIt+`5s4sevuFYPBjR)U~#A)ssZ4dJACc)*nPvRdjsJFBPeT=iOy=6e$~mzD#*XO84P zXAe}&UaZ3`{dEV~7C(#OTG{5Ip{(`hcUi5r*yX5wyn@LG7--JDpIrd5?~k)4kJLJ4 z)cwtc=@>VLB|{?xP(omGmT4n`o1_WnKrxrIBNTamokfd}M{Fn`T}~67M8El&SO0LHe;W3bj)X|7A-k}9f0sU#(ARCFwhr^IWu-&+7peg2wwAGI|m?L*@8N-5#!iU1T8*dzAv5O`>>JUmT1ml)AP+6 zA{3N3^c&=v9iN=}FZ+DlagDgI-aUroOu}_v4FtbD$kYL3UJ8?i`}30xNS(SUCU0Gq zEcdj3)h}a`r(8$GSQnm(A&UCPW}65muFH#_2A&BEz>#U-AxZg+__3$}l)C&8lVbhZ zPeuUv4&DOBy>&nUtM`*j_Q55yByPGHdo3_~;Q?Fq0VBWRoz10x@l_??-Wn9TD9yi- zzLi{B%8M#Z2*ws>&ra~}r|zJ+AJklj#Ycyftr(c9*IUVnPY`$E+dbvj;OyL#X~`ad)0!@zo{C!oz`hA|Bo)Kp@AY;V zlSs!#n~$dcq8rw}vV;NHbgX@vjNf7sgND{eyQszHjDrgkk)nx986*uQZ?WSl%~-cC zg*4MrZa#rY;#tk`<|tOT^4v z z^aNU!$ymDrtrg}ZE-0(MP^z9)_QzC%<~u=A1=id4wxYnn`fswf+3Gggk1tSC3s#!# zD4r>c8RIRN%LRS(*jkbHI6Z_i5p&J02BPj{;f`NNW5Nb8b$49Ohd431l09wAtx z0hBMOTr2H+fVLLy;APaUDEI0`9ah`n#G4!LpOxmQ-GL1631!vGAg?*_K{5o0qZ;S2 zm*jAol8e(yc;W2Nj#w#)q(aA|UcNPVmI9Z)Wt{R%h6PV}D~y~)O~9EOM=6ZzkVMXUp!_n~gjCr-?Z~EuxK-I>yhh+@t@IU;9G$lTe6gCF$~r z4R@N58jnW#+oXvm41}9bc0!*p`{==gkq_T&rnYi~Ih5etU&f9R4qHXHJl+2ySmQ_V zL8n{`fVhTc$=3*;V;N75TehgVzIr@xL*OQ*|1v?OIto^$cdR@oKvWAI?EO}8iIO~? zE-}3&Y4JmjCxa_~M1I4fKG?4$!QChjm0Ku4PM?*^hOmVJd^QzP{7*i%WvI>@^IGQw z=Tag)=YNOrd&ce<*W(TgNgjvdOSb9B3LCvtB=PjohnfoBK7AKEqpx%rk->MwT}k0Q znZL-{j^Qy=i0~ZVzaz{;=t(&0H-d!GBMcamNEM!#=ldMioeWC~rgxGVc7@UhX3Yk5 z_YX}e#a%NLIlu+gmWJ6t+i{?7wv_$0^hB`jn9LaIbZh5y%j>OW#kNAJt3?HZ%8PzA z9gLN97{YhTXCx?nT__2!WqA8Y*@Wsp9M$Z(WZZ+UEsZ=5Q)ZZ%S%6BA82r~asUWe> zx`&cVd~M-ua(x1)35T8xx&NyY@Akm^04uH zuJ}$mXOAZlS3`x+xRGcP|}lScNW(TaCD<7#x$zkxs2wx1tg9g!`ks zwt2+QjKpPsJ%8()+CQq0>4_qKP>J*;?pT$UMzxrO8z@erw7`!|4|4ts+5dH4=;Bfo zk<1AVe&g81GI4p3pJRyo<;}8svfT+4%GGVma(=y~0Q~6Lbk`mQ$LNg2Mpqt+T$a;iL`%sWa8e_eLA{nd@P--dUNQx^&29XwCq;Ol*vzi`z5x`q2FN0 zAvA8uVy1!h4igw{F?LHDJC`$Sl7v$6r+#BR;*E&%{!HIet;_M3UTCef;r*BUvWdYf zXZNQCk$+o)?Y|p?X`nJE#zz3*N|L6`b&Y#yR((k;E9pXpC-dIBG&qf&;zpXMWpWsZ z=Li7rWWn5_yBG54PIthym-pWMRA%}ckvo7F3)$K{?d*}WT+7)rUJ zv{x`Z0!;(JOj8-=ysH0G`Hu$=Z}-Q2uPfa zbMin2Ep>PC%Ct8mZSww_pMCf8n zKu7Ot7HAApEFoN%V77G}CXgyhOIeu7PvN?2QtiJ zmv9>jY$n#vagv{z-*I^Av)Ewsyg2CgvwJ%e zMd~GYou5BAJ6wHUa_`QoIKU6CMq?YKW((y%OfNoo$C^OFvsL%0uthr-d1EHbc$(R` zkeegl8q`z!<}pucsyis3Uo;oNvLWdAh9B+JNz!LS`QvA)<5R0z~{bm4C*wg(BJi|yQ1Ws2=LraI}m=4J0?yDJ+OyCo|FIo={6P7R8J;p4Ojk zGhP&8M7Eb1=hYRjj5XC?`ewkRrzlNlWv3;VXXO`7t>zTh$0Yc0a@d1HQ}U%?fzIJ9 z%3PBY3uMyPT1SD^elF}4s9x#p<}R7O7gR)>)p}y}h3IcB>5CSP3pVzHP6B#8QIP!ZuAW~y?ieG^78J$O)WCv zV0_Ibj>TLz3Ci81=RgIuK=`wGTIeKyp0ZG9&ilO3GlnvqGsN)!jtI zm)Ym*O_X;mlw?VCq&EwT4EBpP%JGtQ>v|2ub(h4XWMwmE>gpuxn;I{-li&?KUn~m@ zB{|X_D`BM9_Y1IQ4hKcAx#A}~oH!gop2EJFdNB1YR%$qB59TaFQ)%++lx4hab z{K>K$3MZLifOyTOjuWPTjMF!k>wm{bX8BbOwrC zCAJc+Xa)vO)GEJL-1k3gb;iqRz7lx!Fr+3EzU319#0UxkOI(8 zAwCkB^!#OO?2`jn--6k=ICq&CYiOO1I2T#lh6PygV_@Z$4_||YWF!xpkm}u-Z%gs1 z?<8BGMe)3L#fcNUss_x?*s95%6~nr8ckU}t!S7Rok>CW5$cp@k zJS@ymVb1n#1W_$olXsq4ecl2633cQr8VhtVwQ!7`~(s{7wJy#$C;n^t2%^i}dtFmD1dNNWjKk=2n zNbP13KO|RXPJq3kt}aUth8nQ6&E1t%60aA}Ah`Uz=z667zdRyK?`H#9HDqkvZcJ{V zsfU6U;ZXz0Vm}jBX;?$0FG*s`$-T9j-jmjx?Tvk0Q+P|PtGO&hH?h5fL}hbfwL@hT zXcbIi-O?e`%ujdQqUlP)y}i<|XX^GlZWWPXZptITyM&wjDLWP8kH>gIwMTn)62h;& z(6>SnzFrIAogOs(L1rygf1E-|U}8oVND#XZ!nK^vBQHJ+s}I^~IMc{*sJex_m?puA zr|Ge=4bTGgm~}?ly5(oUQ#)}N?*UJUX_jzpz2b=8My(3PYBVs(QE+`1s4T*QQ4OYo0P$tPB0 zWJkq1hI{Ov28MNrGWH`7PV5J$JG{2k33o@M1*^^_@kTz3|5{?L&oRq{*Mqye(Fe>F zTfF`n`&MXW6){7qOj*us*L@}OqjYo$7Oxdj7Jlo_XQj@K7|3ZPM`=CoO#d0Q?bgHj7~y`it5qI^5( zH_KO!Cy;*yBv1Nz?Qfc!5A)U^dw?@v7S!HMhV-ZgZMdaZd4z3h*hvHr@(V;A1SFZ) zrHCo$cB(_{hxDR3k#wOKxN%GDjE{jEM2g%+NmTvy z^GO0v;46v{I8JRPSGgbqdx0@4D$NpKGh#?RCm~$))Y?Q>~YvwjQ(VM&6t=~7^X@2SjMy2>Yc9H!N9Lv!9bd&3` zZwgJCI`>rk#_*hgi_yoOrG^*JBq}kZBlPYRqijox)UZ+zt@9}*+e+|wF?@E#MMM8q zaJS$TL=38d*Aq&m0%I<6-~~+M6a77f3T9qn6-~9Bc~xQcH#Md1%~0|ABHw>trOtbt zyX-Cy2~jr)ku8W;(rSm(un?l!)k}MK5rE7LK><2aA z-ojSDqVYG3vwFVl1}}Z&ReHAdXiges=ZytZ=T_`_07-* zc{7!%1c5s;jVzn>gW^sjwEqe84!e+Vu0ItrRBpj@Ffpf;3sN$JXwTN%JbF{}ND*bj zC_9M%kWv{j2j=y^A2ob2D-4E=W?24)aEmLOFcEpeR?}vK^ zcWTVJ&c?6KY%B7P(A{N#FzqnMTeykVWQn_B;QSb+26$KyynmNh$oPNNGLZVtM_Xgw z--OIBs(n1aM)y7Ok=cTa<8f=R4(>sY7)U`H# zW3slaSMH48(h%*qkZQSTw^8#+`Ld_QYED4Bv9G9SV}C=S2x=3$R}w6$w=cd+GWfV< zxcFr*U6Mgv%@dC@e}di@Fsp-@ecRs>LtfP1@lB)ar^vKVq%jCwji7XkKV`lYgNEx3 zFt}X~>cMke$2r|t%I-n(WI2lRyneZH+t$D?ho{KC6O6vzK9&F`iXBD;L6~L2#%9`v zbq##>o|OjJzf+1)h@Y{AnnBn=q1Zc)(suyi#%M?itUzovnQU!K|F@E@;tytO^jH)( zQ$LPpwe{5^H)u0GDkX@e(&e0ONR&o-ol_WIJGH!@8U7IA z(R6&%VAsq>XPn`cj+(#Mk1tC>YDP|BV6wxdC4v3Cbwa$9w`u86JRb(y;S2@ns_vqGYe~}Z zC;YZQxdvFSR#SY6dLp8QfwGdXpU9usAIKZnT#JN>d@^nxbfDuqj5_;;6BE7_v31 zR+kZ^g>Gp}qTe)RrI^(E0%NJE%M_fcw~R`4HHBtsJD5|a{={Z)pL{~4yJkW3R10;V5RZ$G)Aul1S9p^1OdI(Qpa zD$WFjO*%a_)~IS`JrCQJG5evxc)czvK#EWFECs0VTZ~gMOdy<%>zs$;vjGBAn+ z@4KsvboyXh4=V*Ptbei6%A%qYFpjXQklSlTd|i~4l<>CQ8V>r-4g$O~Dc)>Q1IbWa zL2v!eO3hDU+wRe#dD_NcroFG9GBk?YzRwEZ)&93)@}!nw?8xQAw%qvi@Qgvl7)C(D z3}q}Uj13|GRFZV_LXDvdXso0}u8s~PPDjJcyF=vMq<_&o2w@gYn9%u!<5z}!*H!U@ z!^%z!m361h68=JN#KdRix*o#L)y{-8RTN*je0b&m^d~eq38BTD!TSKdYX5hi<6h z!#??>@ol#XNj}JOOu3)sbOX896TmP_>+tK?p2|qzMq?yTexx82H!QA2fzsGkGzUo9 zX87vsVJoT-K_c=(?~9iv{49hi83^&trc^(_^~uw}HqvQZwU^Sz;q---esk|o^C)?Q zGH1mQ87mm$S0l1*0=T~z*(R8p$&G{n5*S?q47mugVK#Y&JF&YDEW0H!BOU(faD}a0 zXpV`G!3}7O!W?`m0HyNH%sqVcX?~Y0?Ut$9ey{Z27ikY+*5vDpJ@}m4!m0V~*~KXH zIHc%PSj6-w4w{(WVAs5&B=m6`On03A{K3OB8+_54z99{$aeC_eP2YZf;YFoLrkWC6x`DC?* zq@ao<>676hL}%*R4K3x23-42JlFX z%=mg(vFbt=PQu5ZDw_#7E*^&4J%PL&F22T+d_C{%%~U@WOx+4g3@^|a=h!k1({<70z6y5v7-T;QwF@g;TRIwxF2k6R@t*ne=4VbcY0R6lwm<% zfbmHx2UL3{OzY^Wj2EcQ6`jghq1|-=^QqC7mJj>ZTMX`fsG36`7)7g40cH;zVW(Tf zm%1_*|J)LzPgH}}A)vn~AoeG}qdN~{gO8)k-D7fpS8qdSw?F%9tlGS|HKChlt82bn z2ix7R-QAA??ZKLG;^5KPY6=K@4fMR42P>#xh=G!;tD)#ZkXyFpc{P;RO|VlT@ZzS% z`{%R@?X-jOu9k^5re|x%BrvFQTElkR>i&c3AylZ7_`?<{+kt%EG7Rq-6EVKhcc{qf&)F&6! zujJMD1TrG|Em~vl_NvhF={X6TjBJ>DO|2 z3wKxy#NlW!r=OpzAYLFWQxua#BMnj`Us?pmwUXD;#HQp(wb&@Gv zju(LdKz0RebJbR2w)&bqrw?|aj=C-STIa%XH_LD=WY_g28l%cTt>qz)K1{|xGL^s3 zQP^NqEK7Ae7vbShW~Suif${S^?ty%h^)-lqm=ce=bZFaN&=yyNdxlS15Y5!H?~l$O ztRtN^3sR}f3Rf>=nDe`J2e-MGTE2OwNeeBNCE-U(>L0DqSGm%%W`RREw`Dis9F-$u zcNU%B({?(O3RTCfvVTXo$23Qt2?v~BO`m;tJHLAM-v<;o#V#Ylrd%fIf64nR&DOPY z&BphQi^NkB1n$lh9$6uE$}d%jJ>*ZhLdJ!x9Qnyh3%mt_w`}F8VD)v^mU~QTcQT|% zOamv~9O7jRlXM=mRvkpWE~<4NUaML5&aqYtJx2FBDz@@C4&EJEst|o&z66^Fk`zJ%P9P%^s|Lc zgLXM(klN29ShZDxCI7kynxCA{t%ng#vrcpsxQ>ouc#F`KFk#xI{d^((aRSWTUZo2K zGg7U&7SdbS7_it!*aKO#Ic!pFu~@H3E8BIfQC4`TE{)_+;Q`Cd&f|PL`v;XkA?fgO zV2Kk3xxRX*?|Ajyoz7u_HHokVdn2Ae$v$@OyF$OlU^NbBK$x37^Mr4$gJA=#^j6=v zr=P8D3RchsXIRz#GyHu}A3tTvz4$}#RF2%NBu3n>)QoR!juynPF5k@9ufF(8!6Ow~ zj1XURd|kdV;-bD0f;fvgPZN()p~~Qm%1#{cX`Mr3dOf7S9VXJ=iB%PQE%9VZkDbSw=PkQO)(e1PnJK|9rM#fj!GYb! zmYTE7Ekdaac1vLqIMs-&;pFhk#TwpwW#CTzI`{GyNT|O)?{mG<$E?tKwePc`Z?t~M z&m$R~6+R;4Bn$Dp<$-bws07a?y!ij>yYHaThy*lm{=OSpIMerq;yb4B7|^@SW4E0r zKJTNb)8;$u8=o3XI}6}#;?sjz0-bF3o?$ZdPhmCo)bv>ig@pa@B@+mc#+YRcL8dn+sr_7V5QBx!?^s z`~C*YG>L=&hI>#cmdtTe^b0W!Rlh zO>z^G*aaFm-n4<`edLx$!$r%4by`JHk`T83VCvNiGo=@J6x_Q&PN7GDZxp+7(UCqb z=}*RGIwivw;OCkxM>|pRr=z0ZV0qe?0G7?r^aTZC?yY`*X1wTv&;m6-)#6w{sy*sY zU@xL$gi1Fbk%ToK6Ar6_~=+F)rBEbW*XKUn{IFf66J^QuILIlpy zC2HFI;oHo@^G%I2<~}^?{Bm(T&_A?%^VnPIBtbL#G(o#@8y#aT%uEKIAfURG;uT7{ z|IMO=Y1Qzibnw>p%KZS}*P{Y=4e;oN4hLhrP+wWF4jfz$;T31b4q4Q)pUjc-9oFmI z#rxTnR&-f21if4g2S)BMnn<_N)kxc3&WH?{-0X`#a0$d_CM*iD?zP+i!VXiHx;oO@ zJeIwrl^W9lzz4kl<70+JpyWgs70o4Yz%9ccMcXfyTer8^Jjqx!_}~F2FrmfYURCK( z?OJ&imZ2>3@EO63@D@uTGRg)40<1ZlV=i zSK2%7Kgo2CxkzFmq@%ga7r{E8YqZ%0%#mndhIwU)Z^Q15E;FLy760eQg$Rq}%OEY3)#(C~c7TP)LSB6M2U$u=^{ok7rnE-Jquzi8YCrd)SB{lLf*uyp6! zQU|QTqWIs&YnKblffp;3eO(B4H*Yt>gxo}`yG3P%^xOAaGtJMY0&P#|W((C88N`eX zcBdEOspYG6Rn~*L3m(%QdsNf#cxE| z7aDY2Sl`m9))WN=`ML_R5)#o;bY5K)JzRqP4nXQ}bBRzg^#^z9^v_Z+Mi~BDn$S$^ z6?YTXFwZVao;#M4;@UfV3Cr&!e0SWN##l?TQ|Ly=D5w`K+T^tN30{4<#N2;ldHex- zIGWj4L`i_6u|Wt2f&0Lf_Tk#tUF(MZP|fBeBmPPYwD@0{T{^!4J935tRLZ7-`mvm8S4xaeLEI<;wf14Vwew%#3m3(io zvc(Oy#kVOuzE%0@sS2C5YYI;W=I)UzaKR+T3KjA=U%%aa2GiI>=vA`Aaw(r?9VLs) z{HTz(A`C37XaBHnY{h7)H-C%@a#Fy@QCB})n~XlbUq&g|cp$5B;76B>mwCx78e!72mKn_RA`zO5p1y_ ztuTjGmkiehQ16zV`YlZw@4L-spsBs!3;7-550 zwW54Sp`w4TuZK12UYslPMeyycONrS36v*R#2@xg}iD#9W?b$LA8U^Z*_8Xjjl<+Yx zDG8`lE|u#n30^%J!oLi}gi-s)(_9TlaWo}x`P%Fu_flgtf{5{bU?!I4 zfkkYgumjv%x9S4o1+Xj&RXwJ$Dye-Cs~aJitS8!_8ib$?TTtzx@K4T*_+x}i!mWU*$pvaTNit`N~NAh~*Ml#`5;F%~XJO2gD?a8IRYe@ zo!Wm#@6JJ$`@*T46Y`tguDKer<`xc@4JOPJ_cF0*O%qvV9&XCbdfnS>QY@+e(~CH# zp`~1odn$uV{|)IR18@I*kX>m-le5SUP>DSBjbvO_Gj?+_twATMD6i(5zR}D7W~=@~ zg~1A#>w_=$Tj$w7V|w!oY>iY1MA=deBtqQ6d=3}6ZhB;E^#H3R7kl@grFSVPyR83WJ)EA z`bMX}@(liBmCKmQddUVn1+Bk|7589V7l!>ZEp8(s`<{#%jw#+;CWk0kROA!cP=H*pR5!Dz z&|yvo@5_ojL$Cf$3y4ox1=s0{*X<3{Bp~=6TLjg+EA)vdRG#u831*N*F&+T)ZbS5c z7ZSE?l65+e=wX_yPEbZCh+Yot)I#t>xEca{$Hu-@B1K zvyr|b+LfPf$tXYAC=&rm8_4rg14ri)T*TWh*7LG*sRcqfn@8F=CX)xqO`Jnh`It-* z|5Nt8Mq$+hVz_-|)7xtI;RnZ)Sq;-!U02!Lgqm2)bnKF0=gE)}S5pfk z^kJvj|Ec8^h;S6@0w;GZZlt8sKDU4TAms0;h37V8*{1*G>r3(&wF3K&*y)bfS}lZV zDPHT^T6s!in4#6ujgTK{tAE|*{qt?%C4@zn`ooYAs;@pfX zeOo57rAz~f$~nBm)&Iaj)H+_4cSIQpQ(EErz>ysOGU2E0|9qaj^DV?+3SJ%wg9nLw zgueZBqU$isK?dj$541X!oOch<_Lds2M=uj=&sn)y|Gcyb9KV&?UvnCYUT!t5WnQNS z8H(VWC?FprU%52Uxa>uDe2$J>$UB`*x@ZQGNHlf1pg9rA$udye^L%JUsmRe|&WgL} zF{dFysXs;5om_v0!RNJCxNv(lVspWGfQ<8PoD3bACD$i4NteCYQ-*GDw7BJk#Zmdj zYxet>z?>th+qpnn8Q|?|;It($S;Z;356&%+9;Ni!zmwWKa{LwDtldEr6##OK!f*ZP zf&w7@Es*MJKK8soE@qJ7Bu%Ccq&*!mxsf!lJgAvY1=53LbP{;P9zUQ0mQJ@f>poxe z=j=NiG<==U_e0i$iG-M~F8WlBr6s8yQ0s&BWwVAjXgtgTqs3#?or*M}AR0JTR<`Vn z%4(m*fUqkQ(pCp}d!boFmeW3XF}&732CXjY&WTz{GjUCjXPXskU$Qx1e2fq;P4B+s z4?3;k>t-9+{y7_nVp6#c?pVw4-iU4|+s|bM4^KHZ6d@ktOF^sLBZE!qgSFPPMV#;L zZ%rZaM@!!bQE@BH%szF=u7jlrhsG_SZE2#lXzw2+g$OGWLiQcK5_ZlTNC3 zC*UNBDhIPAOoU&EI_V3)B=_z?@ZF3VAJ)#KK57*(g8BIX!(!|SwvE-f6^Rf-W!oqw zMJh2qvuA|bNNTKMQLZc4%;Td}hYT33X%Jv}!>oj=wJ2xmY`XkXZG zX~w~V<4G3qw#C@i3)qtiN%3cCH7!7E3;7@I2e-F0_D*d$&q4#oH6ITf-fn>WoBQ}Z zYyv6^F%Bj)z1ZLtgOKYsv@16{r!r{GR>Egv{=@ftmYgzf3NLWj#TYK;{lyu{bVx{( zn!VK=s`pjTFtTv+6OP~6wz@AYr->2&-rf#*v6@ZHU);9})-kIVph1n<>WrCI?|0LA z(xBBTR)GH18mDsy&vL#NubNdvRK2U6T z#!Loiy3qSE{cXZ1b^ONLebLVS%eVVePa2Pfsb9~S3{#0O?N232;?8G2z5v=Yy#|Eq z)I3OdUGSCb%~`%4?>`B?y!J!4Homzw<~b!M<{izsR7epQh}fC;W-E{STV5q?hNd$Z z6_i)DkfBBP1^Jym-Z7JtbQp<2Usxi5Vxyd5KREqmsF51IPEuv8%gw58Kdpz~71q5i z4U~32{T}cYr`_>f&Fu6YEe#kV(x!1HnE2ChcE);}LtGAMr14BVABaM$8w^qJA^Lf~ z|BiblTAI(>9A9^1#1@2utWId2=hd}TA5Q&JXz5;wSj{lWp1boU`h0pBtvR{6x!e+? zWZ5}bh@tM)+!ZP1TqxoivJy=R`DPxMlXXlK{tNtgLWLTlGBDnrxffK%`yE`4}Q z6r@(|-Bk+vr8`e77QdF(E*fS5quWmxpL{V2T(r{R*!nPI*&+Eu;H zGSR>g;T?`-qntWj!4x`91@D=S?W6?PGl$m@fs|Ne&U7<`C zNwYo~KmE!1HdXWOx@37M9i}LFyFcMZL$j5#`Q{j2{z9mz!k(Z~s+SUADrwd2xvrNI z$SP^$Zt14yWn3ib*kg*zzxUBOCi3UEgZJ;g-x*E-G9sPUPTj`vEH}M3*Umhq@`TMB zoYv0|UR;gUpNAT+ell&bY+kDUVl84*ss+?ry($p5u9ojI8y9&aq=mms-+h{9T~FRB zg3|lceeN4Z6`}LQJJPMiu$BlV-H3W{X_`+RTFgqemgA8(v2Y-L(F9ZIZW{}Dp4{fp zv{n-%M>ql(ATS6;o11NkcjYS<)Bp*LKxejgk00(Vf^K*>eXG6{mcG0QvaHC4M3QnJyS zPG&TS_7HkxP$&pgHe@dq!fe+G-Gz#o=vu;VK`|ipv`+Os$ng^TM#iK5QBbx5k^N@v z8NuR+wvgm1AktNAPuVKo;!1>wblU5Uh!I>pwEs&D(Wk420tLnE$H+`G%{RXt&w$&S z)&yR5bc())h_n#yS(z)xd~EUEpac>k0{IgVnBYk{M`RUU)lnO=Ibhf|KF67W2ely~rtnSbNy}x^ZVH)ZoJy#DLl@i;=e&)Gem0iaE+yKpWjzG8 zvRavfYOnjgCk9b)zWO791daad`rd6r=k?YclgCSzz)m|Td9I7bumSw+1_l1 z%PG#lup;aszV^*>Id)bxz3mB5!_v@ujjRL9Rj ze{vP1dFjDOIL*vzUf)wR1bQw%pqF)4@J@=_o!HP)PPhhFzRt~thCUNSk@ffW6TlTu zdra|ljwmKWNim(Yr3zGQB|3?mpNB#9n_3!@&>iP_g!1P1=i1!8ZGEAmrnR_|o1~?R z4yjnN-Gx@~m$Z#83v#%R2xWbiM@Yv$VF}|DazuC|$+`leqTXaY7dJ+mDW#=1s|h@; zE2f*syj()(w}fQ%?~FQb4XP=>Gi(`SLY>GX^dZ}Isf9ERt&4t-aPw^{>LKCQI9LxI99P- z1y5?6`u0&fad@M;7Mft5i)XV5N~Lj-;UK z<){YUK9vnIXc@Kr;Qld~SQ9azoP!H-IM-fOPr%A`nxA$YYc1CUV zNUdHKKFeZ~Qs^@xKiExUCFo{lSMIhr&l^(te8bw1nUJhoF#6=QKBvYKPa9tV-)IOy z&lYw-z^StOl#`XLdsjs(C}LZ1@cRUQ)0sQ5N903FHMATg&@y4`8fkuSWmXednZ;lJ z{$5*X)=N=%qG8ZOD6XZDu|QDkUA43!u);GP>6c5jzFY2FX-E&Xla%gcU3-xFy2xx*`y|W1 zgPxR$Pa$=|2jbS%r@p+GFTkH2++4>R`>{SRr^83|K0hC=VcNmlkuzC4wEG-6I1)a| zclb_OuRIzSmjB#OjwCaTu*9_xrX6-t#0uv^R(I zaz&%TSDo@bPyI0L=tOD<2fNQqqy{fJo(ac2M-YGbRS{#oJyH1+acHYiyT@Fy#RY|j zIh)tj+R|=HrKc2Ov}$iTt*zY9xLhFTuSf{GCO8_JhD<|Nuyr_GbUGTaVzLyWHpcz6 zMpOG)$kujnRCl^bVq75PwJs2?Zd)FEJ>`0Ot)gId$b;G6YE+*aZ0cvh*-PqCN>@(y zOvG4QgG0>5|$_w z&RfBt2x|`0K#(dQLMjKM>Vi;|gs6CYtDgc11T-c^3LY7^gxWW77#3Pt(s@GKN^OKO;k^Ptog> zAO^O+H>EdR{L5uMOsjm)T{RpOAs}jOjZofnnL4nzI>mby5ia|zmoS|#;9A|FH~aeT%|WEoDtH>*6cg4&d;*MaD}pC)F?Ax_Ff zG}xLY{QBCAilAUE`y})tEEq-tS${Bnii0%pAs;85o$ph-!Vq>6V%$h zj}9LrokJmXs4x#)8;(dTI7h)o-y2XZl+KL825!R2>nN_k5+v%Q|B6N#e-<& zf@D{yE9q;w`D*1M5Dw;(a@Q)i@?o0yT8AWLKIgK7ci&mN=(vL!r0QDY>Nx&8)HSL! z@^P;BVSj>*)yp162+#3X>o7`<0FKh%|NtFexR8nYv1w& z>%#(Nl!NuJgJy=n-`d6;473y*#w5Mu-Sr1)ATyH2TB_`bV4U$Is0MD(%P_Ant)0n~ zi%cVqhZDd^n#;p%ehaOk5i>* z&61CA%b_+7_Y_D9H$ir(l*1ToWSKfpX>oX5=08P&_$Tz#n^0R68J?j`eNZF3wi>yr zP!m2O6(+HNtp+<*tLsO|bRp}P5&Ea2r>hX=O`Vg-KBzE4K@@UwHofL4PamzN0+&~X z5+}9kw?8~NUs*Zw!V&HYlBO2x`isY#9_Xtd+<>J~1$Ts6F%)w;RMB^dTuBco-l05gni73%nJ!*d`oVrzC>p{tY5e z8;TR^3YQP866A_ISK#CRezZgwS|$*f(|euR8p3Hx?Po5vX{@*x)jHmJg$O*>Q@T;N z%vQH#MQ_N7F0scFvEjt4savGa$MD@u3a2a*)#lXz3B(83{kGP|F}tZ>%&c9LR)2}_ z*T*#p5!#SHS)NX9-4d@FMd;Jm9H#z&5~ag%wjKoqVK`bfyFuzmq`r$W^={Bn+uHGH zr~6SS7_D+*+UH59y1GVG-x5=RuuS2S5k`T3k4Fx6@bGvA8YJ5KbiPZaF4sP-3JA=k zn^u<94%7%E1fM4s1klr_DmUUGe!p!%`I@6Onm06;ks4kSwG_d6By%%f=C$+R73Xxo z3)8QR5%HA^EuOD0JWSb&#x@O}vUt99H2@2U?h>ts`Wpu&Pk|JA-({T~B(;QUpHge% z5A$<>hbNIPFSS;Tsxe_GKAEWEbgZ!RTe~+1u6ezqqm8LiVo#k|E`t-zpcx#Pqpr-X zs%SO|5UIv}>I2YwaxQ&2eQnteE!dHKNwa}G{n-6}tAtf@*=WbE5Q@bB!lL8WsT_LQ zE^GZ$L?!+kS)dKc_i9Go79K){QW`9mcwitN9~+9E1imE307a0s&E^P^C|V ztocnU>`V{)R=D!*d)tIztA)9Cp+kw*Bil|7yU@;?nxwutFxirN#FOvORdS&R3iBk0 z#nb)(gW%@5R6FNA*~)13@4YsZR^c5Robi-*3OgDk2&S$D4m&H?PQ%1P8%1s<=~&Zz zTI?6GgD;jQ5!yAI6CWQak6i5u=ah}-*mGma?dl>3pS+}8ZVACucVYbX+s=RO9U)>F zXG=Zj4a32xE(t1va%I{gNpa3x_1Sw>UWlUYq$E2+4hdF61sM)$_{V~>ttuCEpYl$D zYF9tfO}hT#_rgUTiD)ytHNGA^0Skzn>Bb>$G} z+%fP6VQ_~vbU`h^%Di5r&rErE(VB=X8{Cti!(fO#bKF-5h!vu{~SDC58zR-nsT9P7O@?yfOKgn`_RJvc_TR-0W z@pbR38T7wDjwHq~FDLRn5je1mO(Cnj0AbYe9FH${ED@I)6XJ}|(o4UNnu-6bRi=@G zKJ6Cbq$tw(%KAaIA1}Kz>F)fZO+Ng4sn5Md<5;OX+hmsXR}dkm2m5rM;-k@hnFq&g zk!H4BG^Z!$e3{`7tMO%_>}JPI&D?(l5zsP6BAtL%N_Oof$6`spTN^_Pc5Pb&4Dmz< z^6YqY`pW~x(&U2w6I%cA_dA$LXWb2$JIot%?T#e9u%4*+BDg=1B@;wMe{Nx}oe2?> zyd#-s(=Pr_B1F3oZ{CJC4g#G&)l*TY|IczO-fb>hz5U7!#7x8>ll|bdMb6_Ve(`(Z zhxKHYU)!#Kg>+4!<7FB&(52EG-1l;7sk!7n>fJS;ZCOv3ik*7ta9)v4p<=kTp7yk> zQBDB%^OT%Gd;#N4DI(9Aa5)mcC%I-tJRT!3i}^&AC-2Rfo^q-{yQdYp67y7*ye;!o zIMc3Q4vUTp8|O!hY^CJKNc=`+LP<(lW4|DYoW3;edF)J>~8)2s{)QvzZ zmAX6bu7K!puzaW=^IJlbl8p)i3N zk8OMN)n?w09-8usx}H{I>CEeZv|z>}TxGU^ARQ;2#Q0`E)S<% zWZI;%VbLm`CosB7m(paB{nwOf2`(t?b>`46m*bzr#KZ4_zO}>3r5*^}+~uwGADwsq z9OtEit}&)fo=|?#=*s40UJ3DUKN!r&$=Sos8RTF1(f`ysqh=u5ifkxzPrwXq6l~8Z zvCdH@3mM6PN4ZamW<<@5h*mk6)s2g6JK0OG-d_*HN`UXUvZ-OarRgq31H7DDV$vxEw=jtk%=VrW~Ma!<#-(C&bN(xQNZ3}~C zT#=|;zm|jIeBO)A(gaLZsG~QLa+;O9n+CkFIIHcX?Qk@4#5$N_#F+%s>8_)lDZBk& zy>z49g2%Vd(VXS_?d=zf)*snrwl>o|5e^o;gzii6Z#r*8r3Y{s1923-X&~|@eLL^Z zW+yYHDsTj}O>(&hbRYf$^TD&e5SRdrFJ)m$a6B_8_{R)!Xu@M5Y=&hZT2{7U4NOtc z2E}eU`vwO9#v2Ik5bz(s4Lm+epm9*>;~N(bkBp3rnVZ$r)QnnA?jJvZf`ZPpfqyQ* zj16YF1{rZVxy27GoLL;cX#f+2iFJeZ^acR-p8_{esZap>4Ipw0@Sy-;=CN9f4M2$k zHzELvoonKS_AH=$0~p-^+WWw}8^G-ZaG3#Pm01F_TELAmfHDGZi~y7}FzW*BzXNXU zfg3LX^;vNAwcV^mK?(L*Eby-yn9YTR-2m|?K*=>wcLHS1g6HNiPN#s$zrdeUU}N>g zK(`e(P7}c2M2}x$3N!$^O@LDihFKyQG7JGDp8`t&6%wCtm=~A@*pPq-65tyKfwn=Q zBTVc^4Eq4pJ_vLM0^L6XdxQkg-2;?YY{0$9tMnu0c9j$ zjC`uU2)r8xoMr)=6~Ji~u$cqgSAoxqpwAYKMfHe*pb$z-$}PKLX5- za1HkX^)ukrJ)nLMygCE)&j7PCK<^$fy~i^>e`>e~*lYt%+knj>;B<)peh={227Gn^ z_angPh~UdUU~>jIodGuYfYUwTaR&IF0Uq~&?*qY?b1JXjTpxbve;EG;%>Dr8LV^8c zU_TVNO$Kg?0aO!!Dh6(vfZJgJISA}80;nP2W)ZkS0kWh&5&@vQ+=UI5I*0;n+H zCJaEO05>VXObvi40d7hFRP$r>i_Lr>6bU3FftX>S2np0p0YOJV*dCCK0s_wg#61xC z07RYx@ee@y1CV@96?O)cpnxV6P<#tC-O}Wq^L{&glkppvngLLQz|A0lLIO9)r?)-8 zAPQJS0fRTd;tlo67Jx$ie`@ zb$N8A;PL0jK?4`KbjsB^-9b2HoMuDSxxJwzOsW~mHF^D!RDuqxLpAw>-=MD|=u~P8 zhU3}w%FKpq3rCartVc3b>WaqGMcsd|4%Zb=X2XK;=vC`Wrt_8KIn77vOJ|F<^Hnod z8_MR(jq4oNMjFZ&e^~ZL(5p38EY;c1mYI(>R<1O;Y>#BBHC3&(d7b@U8*Tcr@e>Zl zf2Q7C{i`>OjLTxIxn_GXmPsv3y`^?{G)2&HeXON!e=_G)g53)`r8y zYU|M~jkd<)m1g(D_3^f*KO0>^_zarur_%lp5nOLHy|QI|#`4uR+Wr9N2gtg? zmwz^=(I=)ZU9jsjRL3(B7wFTU=cn6RYfY2u0eAPPKk<`4|C_$JqK;+oLsQsqYCTjh zX35;qqc(#?mY!O=-3sCS3Z^RZSoNb@7PJh3hOq1UfnDq~{ht?=SSenldI2EHD)#Lt zVuO7vl0VZW+c7vxOz=n?-=XbT@tFOsNUYGeo2c5hbpSBN=MkK6Iys>es5UEq4v6hnk0pJ|kOEV|E9%RhM=}MB z+o{nM;v2W3>Kg^Tk878c+EOb@@w^Y~XL#Z8meWAP_rO)9nsYNwyS+vG{fC!-A}^oQ zerRjCbUd{_&-HoHiGh!I&`lz!_(mrCH&=E2(+v}sK04ZcvnEPG-}1I!7K?v}!*cPf zE4iDT%JXF{Bma%Tr>~g4U^KP!fi8#C&nA6un1Bgx>m#>OJfPC!4aDOe9K=iOeBLVk z!nwih0Ro4&F*9@kbG$OX7swBUz`tp3Esv_s-xR^0$5z-wSN_69Aph)2`&x85?lhP;;LXa*lpdO-AI^(`xkSSHrHv}pzGxvJ?_VHJ&&0vU zP-TMQ?6HBK3DW5hStnDHpwmWX6H=yCnl1uo(LP>Qc-U_>xJ;GuK+N1eLgRjm?B|do z-;AaEZ+t`QeXlsb6c?-({4JVHq#}*vbTnRdH`Rf%azsXz^P5?w+xsvXnX2iyHyIWn zO6Z{6v!cMI(#i9=CgqEkxNqJz`7}&lU~0UW@f6)V{?}NN-*RSN3*sV*oGua&P-i(3RU{PfULg1yCuPiONVxb$4MdU? zk(EnM=1ejoBJSoM(_TpPad>Fs;yWt{fJ?H-0bf8s+9f)HP4uvIG6(|A1_(^uF)?h)Y5RMs5@9ffJHgHj!5?xOCB-XGk z22oAIkK)G_0KV|fW@*o3tL`I=qOZXXmngKo!_$@NBpO8d6@f;c6}3^bT_cuINdWJ| z(86ZSLLJxNa(PvJpor3@0Apxbc9;bjSpSl#T)5(lDxKu##HGL|Gk}o2d~^%XvueNH z354WS-f4x@6O%f>(I_`r!lJCybLNc{cbNHoIh55XjHB%7D0gXh+11@&K{#|XpxgSH z<fOkyCGS-I=)XU(D#y4%B7NwK#CPzIZF8h#eL1WP>V=d?!!*~FbzK)sF4pR! ze`hw^h&#)rE?V_FUsCjzDICiRamV85^;L{FXa`e_nj`q00#bKT#jOpS9s;yjI|W{Syr!&rh2}~ zRM92MvD)@RhjQ$#W_Vos`$<(I=JCivciHu*MStVlnUv0YE8Npb!L#11IF_2Qvv!6c z5UlpW@?&CR24yoroPDLayzVmp zNjL=-zsNUOTb!OK{n=K)O0(t`l%p!n&(4oEG^?+5$BJ29uj{^ zYPFt_t2g+qb7l`Tz&}b)ceK&6#@AON3@=f&AgoSXxxv<5f06dKqphkG#4`=nN*TB;Vmrpi2W1pn$#O5)4Wm^_t@UEY^gZ>6T(Gu}kpd zi_+FANufUyN}=eJpW5kk7}Fw0@$Z6@^xsht8FL??%x^^9+}tmfnj%^>=6dhD%l)}+ zrQ(y=LQSSu)hz5N+t26K^Yu?cdKr!5L~gqx?fQ{?B7l479gJ7{&loYniaFEU=AIP( zLJ)l#_D9@B&;KIOM`9O0q+R)$Kgr0eFP%^ZxB9OZr1nAWK&X_{265ZFxME}ui0{S< zB?#_W>D)Bl^B$u`|9RK%_!IjjPSXiT&)r?tLrb!ZR0-zyzwNqxb9NzDz#ihA&BB5p z`JsOkCa>eN&wu}!y#q^ax`D!cezEy&H<9dqCc%t#A4>2C3{4DpH$85^$0GNvOxY?We0glSk`G zGXvl*>Elh&#~a0uhe@B=Y!NBb#IkTDo*}>LWG^rdeD%t9^XVskV^Vx}OCtL(-S7Oh z7yOkLg5B8!-|u^<8k5}T=$186ISYWL_=16E%XPL;K-u2)vFrvJCKK&a7~E0F}1p}r+1jo=Mq1VS7;8>6I>E5 z3_wasNWFp$ChQHwg1PdmErAreyhAZ z|3$pYkwJZskwTq;!Vyi3@B7iXr0vY8ae+?Jxm@{-HA$XW}n z@ycXX%b>qY-`|! zj=Qe%A@NFnhr*7CiaON_D{*j)cOLl&SURU*a)ke(y0m?yEXKRgp{%IUp*-ZaYF4~- za|A45nZIqq`OsB()>;~JTY5rMv1U?GAYT1RHD3^#euekKgQn^puN>uFf>NypJC;?b z=BJsI;^On~(o|gzSJ&g!NaFo?B2l}lTAHSse~?;pDv;amfUas<}z|+TiNQ{!m@v=~E9It@+}UB@x>wf7j%w_QSLMapk>2xi}I6>pbxr zqG;>m9Scd?_sODwh0sm;|o;?tUY*LJ&Ho8DT{O51=qtV20A|1M{_2O#&6b@e{&MQ!a8 zu??4_9nvH%KP5U4k)7kWKOd7%<>_53Z55kkrG+b9X20vcME)dJZz5>xB2@o@G6g9q zb!W^F_pj9b8U49M+d^B>^~a}IgrGjTyfn+Fn%jv}HWvJ1wNv80lSs1XR;{^grCF4& zcWfDufVRtIu*kZAMXP__-?iM|b#|=ueQN7wmIQ03_lvfHaU}XZda^{Jeez@7vTDuN zW4%w+x-{B5nA?Anu6D9mmfDZ8HPj8D<&Wx2)Z1LlhQ@yPhY$<~(G8)vz!S@ZoKLz$ zVI6#CLs+X_()a^zbb}E`1IA{<;G;%~)1g@I=l9S)CxTuH?jZ}O!Sd1W52GXHZ5`lt za7jDZQg_5tjziXIR6KU%gTz4KQKuKdAffiqk0bDsTF=k1Au)L8McJsYZog>tz$>%i zEbh@I$-xo2?o7$i4^f?g_hS;;Ac;-unRZsR<+zl@u+-hy675g~-RLj%o(PG_zxShA zqXS}=6LuLBR&osY)f4dasNKYU`^^n`w>+!Wm|VL2XeHXf5P{r2CWquIFV)L5eLOvO=)v)N2Q#w2@m zKUN1=WC{??(czO~Y0v}BJ5Al*kG-s%8L1fgK`?VnJ1to`by_jjuQs9D0e;~(r>rrn z<~+R^HFJD4o5DRWRXO#ueSTbW_E9)nAF}XP1B5j`4bK?)aNIe1+woB%TT%HLY@V#wdDrC#X9r()Ao5n z?fG=`cHxeh2J|<4?AX7AC}&XZwk~Bu*y1_f&sbY)$=rGsvr=rnK^Tj4jp0j}A-)IpnST*8@_}H_R)eLtRW&wW ztS|jOMz%yR3PmrIbPinlZOTgTo^)(R`iEZxuuA+QW`Z4DnC~X}Z$8ld=Be7s=j|&d z-13)R3)I{IqcK=uN1W}yC#;m-sgnsnL7y}aFU(O+nzM#c`x#j~j%J63yvL6+WNSpf z3_t9$KtX?^j|%>x&|QNfe=*qBPgX1r=U0(O&Qpbci$$4W4*!jHi{rok8wNx>{k$Ln z%afHSkdp$kJLuubvz?@>KdR3CVwQ`dnyBFQ<5#?Yilufo(SJg-HW^?i5E+_@0HCZ2 z{p21BV(L0Mk_KgGZslkFo%`@ep4tsrpG?v`bjmtAw%B0Y+++M<+VILqe43bX^C)5c z-$nHK><83&<^j#*wBVa%;>lC7A7>XG|Cpg5f*h30Mr=bo@LQ7%4FxG`f$)AF|FhU7 z>AV!F1`~Jgi4mX7^Ikbk{MFS05nAqVYl0Xy_sljff=SQu`1YUiU$VcsWUD&gdUj&a zx%ZLb#NaE6;J-gpL_6UOhq$~Tu;m(p`1?<=ARp1S2`>$_m?#cOxou)nwKRXcN4SjhZs)w2=1KFSy!ST zFNVHu`ThCJ1iK`L_P76}QomMIaVHyeeTe^X&H_7#B0hGK-kr?8c6f2+D{~{EbtCcS zcJT#>;Xk15=Y!ARi#Hzfg5AUbBa=K1>2v8=D*ix7_!E4U)#jT2r%nl>ihWdnf5}JC zOY!Q9Zh^ariD^z}lXZ7hlX%QK5!8Bn>S@Bx>wT$u`7J^$I z#Y~e6hlNV>pCRK-*@QIpK^cZ?fBtSGIyg9OXww*bu!!k3Au%K#LkRPYm}-;LfDYt* z<(t7Q^Se(cLU$Z|>iHp7a{{n1Q5n8pvT@JivG5f=o5=SY|g#td%FnMDNvghCR;-ctbVi5WjFv{;kF)~Ue^=%TTWrG87`WNu;|Sn+(e%){LA;hTNTAf-U1f|*J}#|;n^tHd+a8^ zlWv>Ud$+XPe))P1^rN@I;O)7zu@^HxVJqG?N_lI|wdTuHy=zn1u-HA9j?2{mz4YRr z{&#Ki=A+L*O^i1`Z(HCO70GY)Hxw2;?DSq_Br%h&zW~gu9nz`C@RgEXk^qqd|FKQi z!^tO)4cGLB%3D22q#`3d`G~knmn8(flKN_F8OC*FwuQuI1@rQRC|T1H4I(J;0^t}v zv_{0V!ki@b#QqlLa0qjCCCkEe%xAOVjanhO#HF0CdKIB~ESCL}EEA4y@2$rPQp#}@ zwAE{@8DyD}(qK-f=%lg4F`JjkjH)>xqEl>{m@p;Xq*@QzO$>(2W`X}YxN(BUpp-R6 zut%qp?_;;?&FzEIFU2`S-qS5sk)S_uX*?%L8YlBiuATvL z0Tf)8l8AnSx28@^tY5>JelZed2-j`muZUJrUShk}^#PRFB^ub!KdD!J#p~DnaGFy% z;=fe}5|h$oKhe$jS37$z$u1jGGY1WO+jAMuw5)lW87-VfC5teIZz}9Ui}o5XPM4(&r^=}qyc>N3v(46PX$gB0xubCL8B5R`%-@3ZO;hM&v9LAhMcZi%KjvoWXG|LHF|DEN?5D{t0i9~ZpbZq=^-XBbao zz=iRYb~4!ENe!n^8RoMogC5l`3=h9$w_S;iF6z+_i$HnX|+1C%zn@b(peUzVf85~{kOGE!r=2}Gt5m(Yk*OwUtAM&lO6_VKJ+;aB1X$I^0M?EUr+lS zmf_eszanLz4)qFSWu=b$KKE#^Rj&& zmk$c|viRJ$=Jbv9zpk}`lkPXK+ny4irmdQJy1sqzRWLSj?ZDol48fbhIbgz z&kEj7OIpTVQa2hH){L`|pTfVxS#d#d{^TWj4Ei9M2FFYr{tH*_?dd#{3Z+ z)Y)9B6c6al{J3Re)K#5%6Y(h4O5_1eun%o7JpMJA-Aj8yz29B?ZRQ)1Ivk|D->`Ky zarKc5?Yk4~342RTveH9r+zVzsDiM)9u@G6si23GwvKBScID6Acsdf1#Jm&GUZl3KX zed!^5p@b1{v152*vvG$W?s4-BGv&GP`K;ly^BD>z2?t}nrzuJu)2eN&Z18?VKzbU`{C*Rl*3N9Lb(*Np>w11#NG z*Bo_L?>yX+=|w^)3Tta?^Y(eU2W}Bn?U);tIPB$}{9X#2wE~cqLZ)scnFK@<_Gc7M zWm$*SC)-X_bJo_r(e~omDaJDx`CqjN|1b=^Yssrua_#B0?e21us#1q?Qo*wgS8nKz zE4(glCs~XFDMELkEnXHn!W>+w}>IayRFNx~@@n4rT#txm$G z^RP$eHok|F`MIuIJ8y=Rg*6-pCeExb_h&R2U#M3}KF^;7*mP{eA?Tc+X_wp%rON3A zpG$((Tl?@O*xIX(!D5H19lh4w6x-6o^-ZqZT?P37Aqo&bmyQeQGwWmXPYF=9>0LkU zr^l(tJHsZ<>7VfVxtIrhbMK$pE}PyKW*2Ht)$5iZXzME%Syq$Bvjnv2TL@sh=HyDc zzeDMB>V)-s8`OG#;>oddwR#W1O$uHqNW$cWstEOJBv#9GcH}V5E0)lX3WhfPer7dV z=Zfiva59`hSDPW0Eo@KuL1Ug9x^s!x`pOVS4SMYWr)}M-J0rITp;$TcnSCmaf`eo3ed%7YM4JGSeY**> z>Q2z84zo%zbD!^+Qv8vUt$wTHy*x9yD&Z!Oz5ecv~4fy!- zOdhH;>x<9%{=_ZmZ-k6=jls!cHI{`YJAYwE#4BfxsjRlEG_PRLBUSTGLkR%Yu~lVp zq0ZO$a&76Vr4XrYfsrEet^m3zLbbjZ`ik2#6IhkK1UU*O2n}*15Db|(>zlIwi%svM zbu~5|?lFnc6;y}#G;tmJ{*1YJjY0!4mj_#tr+aoAIC*biXQ=3 zP)%fg3%Pwr%Geas#nZ1q&w%{kitpr5p9Xz1n)PvQDPS1Ukdd(?NqSG2No)9(TI&l* zjd$@a;Cjt@-$r_2k#9#se<~D^W}|o=GlVHx%nf?}jBwJkDWVRQ)yKm;342sjz+)$J z!LxtpMqbNnddp9YpO4Ak%jc_)s~G476%0P37!hTekTVY;Qw|XCnAJ|C1la@9$Fo;v zz4R#<2Ew}8NNlW4{b+(2a`WjVb-CjTC4L3iF?W-+@y({fK`{>ejMApCRXa5sC1}(KM4Cc`x!VyLq7!c6Wr+hfrR4PO7xIof|{ z*7 z@}}{A`F?CNx)9x)^kB-9XqCdFxz)aTmpOkwzcJEpMrIk1oA`?_CfY4(a=Oq$y3m52 z$`>&DU_oiOhD$g`)-cJ*`-^4WC`Y^ISYNB( z?5P(9)sPu~($2|Hr~sBZc>U2&b`2{<{o^jSFErE;^(aUaLTQgN>bEdgx!U2pwx#jN zveo>fw{_!ZM%3|EL)sd$ zw?H2o(3%+Ti(_keiqHoznJfdyyfB`UynEiLD@U>Ds}LY5y~W*c#Zt6o!aY&ZZj04r zOU`4#jh51(P{aslv2v9T5cS6(gZA36qUNiyF^~(_V;J-k0YX^I2=o$lwOvw9mhUFE zn|81^6d@xT7!!g;<`v+Aw#a9BpPH%XX7Kit^t338#a7?Q;P~#{Jm99Vm8fY`BlQl? zb`6(z1^eahQ%ej=9GU-kP7i{FAm!pk}I#_ zYGQmJFmtgBuxnP%S9F4R2MByX(XJZ~F1!V0?a|uX9i z*2^{U7Jva3fPrJE2cmZHDxZnJX@G{tfehzz9oX{6mga_D)g8crsBVevzJ_bC22=h<-$lmZ0xF+fWWmV7wPymHcNb^vz zhFAXtS4RRr5QJ$Uacl?%OfQCzmhrRxUi~#^A|CV#7V_3L)Yryoik;B@cI_+u>q%$b z)vesr73a%+0m6O(VlV+>DAG@9%?D1mX9 z^+90qe9w1m_=M4xb&dXNPZ$JTcLre?hJ+95pziZiZs9owboZWEwI=dreec%Z`i!Ss zB&S?KS7q>x;Abssvxek^Ck7Z8hGDS4mWO+u_(~k0`w1uW?4|osZ}$qf?qKMHtp)|I z_5^FlcWaP!Y`}&QH*rr;@lWW3BQSw)F9u>LhF@3spZ?wfR{^vp=l)3-@QAN=u}$6@ zui%Nz017sCN&o9XPiv89a?DluM`i((XMtld27itF+z(DtEddEf_ur@R3`h5*&hS&m z0T~bk#`grEzlJ_Y@i#vLBY1pkz=lwmhEH&YL4byXKZav4ZYX#1KF3@YVBYVg`XpCf z_eNTNzIs6?a@EZMiD!R)?)5ma_GphBL_~LH*=KO zQKCT~KccKz3-w7*pKRBx`4L1^kf1?+1_?Sk=m;@l$BGdv{#NV-Sg!>j6e{%EWh-}uTDO5!xJX;JY>O0Q$G%|kq8N*;ER?Yr*6d!r zekV6`?(F$9=+L4^lP+!gbi{r;cD9T;GiJ`%G+mbXNyt;EL7qHC^)vMo@S}vLLd89; zPq4_xh(%@&11t;}W?Q&uaiV(JwuIT%MJv~B+_)!F&{c6_#R<27-4^D4*u{0T*A*{r z3?nk+W66vSLl+MjJ_eySAb|xMcp!oaD!3ql`=s;|ORdS|+JrmF)YDHpG!V=xp+Ggr zCsH+46j9TJVhuLfpoq;h(+D#RF~%%MOmxw;@Z4hl)Wvrgec7>;C)Qk(jfzUCXw4@c_8~|peN5xWiP&HXqgGoL6CDdMFgDh7PM-B% zknpufSdef9iPm5)a93DiWtpYwbkv0vR+TW&nAI^^DkF?A?65`bjpSOk<58M68#>6;GGRzE9 zjx@q>2~R#9lRP)wb=!USnEM3LCQA{j%yLT+w)R@IEj1vFQQ;DW3U0aK_KArp5`~Qk zFPg2TyIs9NjM$F75H_YKfTbzd(eHc)`dBB-ZZLI>eGcn$CS|3vHOB<&!cwl-fev;Aj~;PL z9t0yO!3h>`9|T~)4sP%~>2a_GE|cC$niZi5l|WA=FaaOB;fxfaf>1^=!XQEsiWG&y z6XEKE0hO_z%axBtRf1JxSWurFNy&9wd!45iLpsv&4=kelpV++SwJJ3XcQL9JG1j$= zWthMn>nMjjbOn!h;>1!-_|f?up~~WeP;Qe|G*}%uP6-$ z$7s%sj-e%iAR`&)NQSPsG!HPsV;=laBQA5P%Uy1UANe51HSj=yJgMw?8Vp?FILJYl z@kCi9uvRcykqs1`C}%BlO5$?X2Vs~18T`po`P_BBhRI8PHL|4Ga1_Z)g{5=}lcK9; zR~^x<(`)m3&T}3kug7>rR?At=H<@9Kv{kGev(%M5;GwH|Jdl?TeJDgDx{zOXV-=ua zMGQXhfj1h{n8zf6^!gS!n$fHQ$uhxknj#241m_cdIKpqHQ59+&K^Vzs<NJESYl}9O<8=N=E+VC9m4Rt2VG2G#(3-$2<}&k9z1sZoYjmgd-fLHK_s>K{-Mn29PXbB3FaY z%&P});6dr7%&rX}1Rtbwl%V*55P%W{5?bVpPcXJ(Xk!KlETxy%FN2RTl` zv#E3<7#`55UE};bV}>}6BF-z#N~qBfm|zg101lu~ks_KNL9yJJMl~*W4zB8ST?1{` z(IREVV~mn30=&;u_h|xBw)Z)n1LCW^l1_fwt{6$PbWev7&YcQG83Im*IgpX%T(ONE z^8Rp#tsQ9QUGuuvB;m(BSYc63fP%Q6I06ImBhohz$xrAO*&4 z8bPz0?ZG+6`PnPKvt5%V^9^<4Db`SIx2K_vY&gRigOG-~&EZuXFJq_V-6>X8{jPs< z#eC=+Tc%4%wtMokvX>5cm6FDEacYIt>s}Yazq-X(BSRkYSVzRyG4V2HyzOq^{`H#1 zu?lkBV;p>F#2)~03RM)PP@f2fMpG{5mOoS4cO7vFJ`m>*h=2i@=o2=?-G>=FLmS)} zgfozUD`Y5q(XZsHx?zNL%*jZcrJDBXCo*_MciYn=1EXbQ~vq z?CJQuIUbI7vqzlmZ$Ccr*}9MAg9=S#LKEFWin#=FjbLCPPbnXP;s<}% zjcTxj9ffWQ8NdMWrAQmpAQv_IKn-dT0tvw=z&U<@?(h;__ld;ZWR#cf$;x?|l0PMl zyiJPwT-{VT%mSW|q&3~D9mD?-gSsWsfKiMVEkind)s~%|t$ESJ;Y0HNm7oba)S8e( zChVOiOrIy@0pH0Ga9qPDTmwrXfriBy%8dZC4PLW#6w7&7;=x%1P=hrP0yga2{4F6h zIKwxzjkztu!nM*cgqN%B5CvLbyHKEvsM^4l&sBLv=AaM2aowgxht^HX7)FYz;a=t- z9lPkqcySf~-Bc7doW;O{+POnJtb;q~+6e}tAX1RW{Q)R&0w{pOwgAFz5XIv7$>dA} z5->pEi9pJU00{`5_$Ak}jerPf)Bqd-Wxy zsZuzdQaBM1R%K4Wp%3n0)xgaP!Nmx9QCaEjRNAl$j=37cEu8*2paWO|ofo;ot@&YE z4I(yXBk}OVIB0?&oB|*O0x0Z8$uR|@T*ILlMN=Tbo_QiB?w}|B;3jTj;(g)=Ai*Gj z$RM~_6AnTXM#C4OLzW30=PlYzq0PFH7rUfemSAD&xr?e9Lok}!RY?lhRmy73UJub8 zK;7a_*~-x^q!tmKSCJioO(P$=!yg)-HnyZog3La2<0*gwDzwn{T*Ec!jEbCNx0t{K z1Re=kBFgEYC1&DZ8Ks=vzzF0CCVl_|m_X!ZgZu3xArOKy0Hid;S~{46Ii!Qa4c!5; z%PRe!d99LvfuSwpV&;tD>6w=mNt$H23uXA11@gz09R8g^ITq1%o)m5+G&Y<-2Iuo{3F!@0RA z??@pB{$4s5SUPZtcjjn2h(mair;q+ZkP*X?+HN2S! z*e89GKxf7rXu{**DIVkP*#iW_{1vFUIfFNRgXW#pb^acN66862S8leNKXt;btH3;Xn9#+R*~NSQOwa916R!{(Q%&GbtPA(13Ek^I>cso7UqujD3D$% zrg}ySb^}gs3!`|*C$x}}V#A5JP*r$>Z!iD`Xy%l1W(a%$eTqP=4&?`A=`*1W_%U7s zm;fnqgH@7gG;G;C7#MA$16M-mqDdkC@9|DDvRW+aP(o4$t0|`rQJJ2So+>HQc-g7J z{U*YRWZE366fT^?aiy$5YFPt$pOr3})s6rok z!XNdKkp@js3;+hqrwD+6td4-IGAum4BYs|D3D_s&VSov=f19$*5Xu}aW!x20~G;pjmBp9U5=CS@>S9M;(c^>b{ zDTTTk;|f%q>ZUQ|kPg+QbLNyPO-9UOprKOCFo52na@8w!?pNiXto@!aT&J-@V=XaI z0ko?(ctbmc!|+fo?bdEW*ef}7gCG&bV;%}17=<;|Bp?LuG+cuW9jQyL6uKM%-HHGP zfBFN7Y|dtZ)lxZ_RWLL#IE2FkLoEf*@sHx}&7g~K9Dxl9 zm*k`fda4L2=VZYIjP?b*`p0}KFyCTN1<+B%dK zJUps_k*u+HW#^eg&@LJso`W)=a^lXZ;^rleadCh>n!4o}GDb0YvFtMDCg@J5!g*x} zI;f)(tAWYp{w$S4Fa(3sIb zXft*mLMv**sZDr=vHLFWLgsH?X0dMK^3PJJ%5D)exGA}QWx19tjXJ2{B13}30|>4| z-@-8jL&Gyb12oiw1W&U}za6k)EH(p5Hk?bJ*igw8at(>1k^;)j&5$S1kV~PoBZuM^9l_GF+qjhcVAXErrqF;;7Ri zXgF}J)6VWpSGL>PD?Z$eKYEBCY>Oc)sgj}sp!hL1xKyG%Cbv|@ijZ*ddIBdDKn0ZT z1uQZKBy7UA@NFk7^`b3jf&dLqX~kl|05Cu}`12EvudXbV5f5u910RGcDza`gLU)z2 zdY-Z(95N`wchPUr?Q(8@YtdaH|E+TWjVoWa=|_X~Ga|8KCzvP8!^gTV9DhSIv$QwJ zaZFpbe*4xwblg3VL#c);eDaLBWRoFR(@DmpZ1DIY7jJ}Bq)UhlDT z!uc$CC1cuTH}9R>cZ2cax>75ZYcp;U>7Hw`rY?IcwpoGE$GRp2zh*ShH{afO)b6*J zOIX}}qbHEuh@c2Hk!q8&lpst)Y7;n7{P80OjR$kEAE+PQvU4LpufpniBfql?CoHVS zun5qt_Lgn19)UD`!|>Ufiyy5KJ8EqGUZf*y`l7c-yAru3xx#HUkq7qA@}HXu*pR2} zSIQ_8C!G4Wb;&-re>mzVAFU^US;WQCIzTWSziv2y!|P_b9Dlj5E1yBEN&YuxAMi$JV;GBBLy>w<)|RR@kem@LH3oG11zdm#d^?{%uk$7>hkG~+ zzcZ||us++lF!*yjc#$41R6?P3S)Xw^bmfezss6QfrpuO&E4ksuwJU9rV<8+XBktjP z-d8e%&~e~bvh`Ln+*a1;FcWKnwYS8r!#Z@QGJ^w_$8JAI1DF50$w!ofxI!NQLblA% z)*^VHgsluo4$n~LIUhx8XGT zLiGxlEeoXLc8+xzt#N`WkfWO~c1k?((Wo%AsX=??IaFangV)(x{pE@I0`W7D;K@HeE-l|Lp$nok z#S9s#ZWKzsLf*}xYB~E1iokhrd~Ia%2D$)>M)!}Y0~_d+k4DI>Ib zr?2`#e8qqNY|1#&3bcX=bQrNi@CSc8NJATwe7iPq1N$>HM1!S5zWpPQLHIX0=$x4! zdkiHzKnR+K3YE1`)~ullwJ@O|KM(zQ0yKyrLTlJ8hN39`NKhzG)&}-*F!BM0k{B*r zz72UaWS+#yeX6{_NW$C_pO~-7Rxny3MdG)&NTry;F+n&oSSFhTvV7Ho!mo8pb zc-pgjxc&0Dy3;lMpZ0xg=ieELwQR=t{aYuB$~$Cf>t zc5U0Yap%^(n|E*DzkvrAKAd>)efY?=BIHm|Mo$b0hWaF3(5H^rJYmEZ{gZV+eFT9I z#gSvEf!NR|3{~*EAS4WeGO)lCrAn16W&Vtr6DIzM2Rmu1>7@r8kU*GkzF8+hrQ|7x zGN&3t44nxHyGk*^;z8!Dva~`bovSwF5G}gs@`|iwP&`MNvdm$tFTKzLt1J<<`inwz zkWnnL9UGGe9(fv+Cn?F?DKeUGpb00OZYTA=9F{Dv?*1CKM6}8}Ypk8&@le(>SwBlPC9=FUW|>mw9DtO3O! zeiQOz5KmA!!eNF{K`$Fd|vv8_e_cVI}4_xrU z2`}7m-^RRWnm+vSs5)!hTnM9!{z5sz4ZfzusxY*!3acy+zp5%NU$vQ0W@amTI1Oq?hJaqUVWB{%zWzEZWSjfE^#ks4ss zrt z2NI}J!puo$V00RfAM#|7i-=4*5n-Ia7V^P}rNoaq|@ z`SuKOY-1b;q~!iXAsSJMPEhm9R%lm?4fpA2#*Bzz2% zY?_EQT9^zM%B39In1)9V<*$tK3lv6R00bED(_vD|QVv+zG3SFs;i>G1Jb}-oPzJ@G z)h$7*YF_hzM87OL#xdQTr(nzmzZ@w|7~Ev18p~G|tkvi*4$eerfQ6+7II2O8eNdFKjdko}4VO4!pK547M_vuD-_qD zA<4c29&BtD8`oG*cR1?__uQ!u%y8{F1Yj4du_JSw>yC9iagC8(V-G)#)KGC}Dcq^d zQYa}dQ~sISvImq3B`5Cz7~nPN@*VS>X%3NX_r>-!()cZ0nR&ywQ1C%BROm3 zG{8h9p7FG!VuS$|d&IbBCu;VgvQ;<6Xo33vlc7WVK>_WMrSjaAz!3}n> zl^}SJaSQ@H7a65`7#AKt00K`7Imjxp;|D^V(jln0ZJMm13Xp_iry!9=U1S=Uxo|U+ z+1R8=b$ShF0Mm9l^Kqq&dQ_rT3Yqg+i85KT65Tl<0#JlT-Bh)XDY}C)O~LO|=Fv?o z*Yj-inBIG*f~zpcV~iP6qtnK0wrNRa%zPyC`y2y5EMqyZLJF6V#6`Cv1@64cjkSeMGp>z20UH)pwWi&kX5)r8Ua-E_*@y5*x+^>f;PMM_|o#3aoO5H#GdJ2hAc9!YTvYy+5>*Xb>*xc&uyH6)2!qGA zvmMcG?qlH!vFAiSst_l&+?*5L0m49fw38w(cl_vE-E2yI>sQ};QvERw;_f`g8V_{S z)0=Eo3?Atj*R#V9LQf$+@xc|D$b?Jy2(mYnKf@W#47M88AOtnCf%pDF41y5O;5*>) zpMU*pX&-|BglS956Bx&%^duqB17H#bJ8sHf{Nx}6!C~6O6I9_L?gWPf@J@0lJT!vE zHYXS~1Vx5{S;pd7#48@!;dO3l4@}^>Uhj5n?gfJlcZ6=aEM-!RYd&rdnwV?=kl;xE z3d-_KNF*aN@<}q%?%iZ1ZR`lk-~pVxtefCRFrMNna71aeDZS=t3gM?m=&LD+=Dv*3 z&in~T>a9qEVI893uYQk7kRX5v2$KeZ8Uz7{oBlZ{s+~VGu-NJs5`K zRPP~F0V47Po|;My2FNG=OQA;#<~NPjQ$`P+9)i1MdgA;G1@^J z<^&0{0ToPO0vMplARq!NAOa+S*LLsbD&^*K&H{dI=Z0-19AMZA1ezeg1eQd)$c6lt zhswy%NA4+`@QX6K$?WQ>zPj%U%^}NZ1&q*5zMjy1w27nF#j9?lBp#Xp>0$6euVG#m+ z%mrUi26-;Hc!$U&g_t6M*Me$ql;mfq$SA1H9D~G<{v;!x9E85O54-jVek4TBw$RJu zVGGIbeT?Sp@+tYW#d(0FTbd^+;--qok8b>m&paa>%;g*IW`GI^9Grn0>ampuVH&2v zrp6&3_R$~paxeQ1AjzRjFd|K!!w-z$6HaP9Jj^f$CL%a)JGujh7NAfC?Z1Wq@saqoW&fRMJz@zoC-sJoZ$#4Oy+ux*LLz1cXB6V5%z3RXNKyBcy7pi zY?y)x0tz7R!a+gM?<>U*9`;Kf-o`;1#6cY6Te7T=n2-q{gR8QU-Mq}6%ubtP<@@vr zo47JE_9-cj0x5uoT>gq&28v1eMoQRnfT*GV8qkCg(1b4MuMh4rFZnV*^^?KIq)d=N z6Edf?)Z+m`W@IRHlvDvv{?lI+VmuaN;vQmz+Qd3Y4JG}BE-%7P5CRa6Ku(ZA7~p6t zqUKjTWZe*B9l&8ZOrSSm(*;{n7G=^lhb|azP8Xrc0!}6-dyUD2;Yiq#9o>$)kn@_3 z!ac<`8%i89wG2&|qp|EJc=$^RG2&eE1$?;p54u6z~Jnbz(js!{c4PC&2 zGYDvrs(~8@p|<8T8|rZo>~BBmv`!g|OeRMakRVZV%X1ip@jyXO66FvZMGyc1b9U(> zRDpA_ArB4$cKX0yD8~{%VF5`C^)UY88wvm`z+xHDL2Bgatq|idBEw;1?zvi&C2!|; zUQz;JQ5IvbMv2Z+giaTKtwm`rN|fXWr6CyhY%GDKpO{DdjIw^pK^n4h&Zcu5v&`(8 zLd&M|DWK;tw&kw6GOHp3e~@zsk76kQ>j$B1pz0wc6S4sbbcIv5=3~K$Q*#7Irh=>L=NnES11MkuY-a*mv&mla6=!i4D*z^G z6z6b`=TJsfM*;#eKyUVjN&cb%8t5(f_{pEfPoJ#oTiB*M_sQ(ajtPn8N65@6;;WCg zQaRJ^x~z>z^vh_et1QW~D1P#8q~yTd5*oPS83aupok1H20X?W84hKOsN6Z<4AfH2{4q{Fe0u`=dhX%n25F%j-)xt3E*4X4R zEi6qIf=w956L|%U&Vi1kMJvj|Dn6w9y2(e7;RHHhBqks>S+aInk|lLUW?ywSWzjZ; z$;W~bCV8#b7=ReTfk^;M%8CL^hw>=ohrgW1NRRYsv&eb8lFs5`YMDZ4n$$VDiU@HkSCPNdZr8)}} z31MJ3N+A>e4+Bl94+4R7AdaPGs8U&sPDYGzbO;*=0UGuP+`32@D5R{qXhO`P2^#~u z=0O^SL56{80$kP=S(3?a*mhL)HE+&Ef2}}#tw4&G=7LHZnnZp1jGCs4pDsfg<0e>_ zV!xW=ZMxXHAmg60Odk5_ispfe#Sg1|MEth(pOko2ROPSuhcpJtCz}Ksj^KR>$iTee z2_WawY3@iE=<6}q zf%X1m7?*380&w^>ZTN;~kyT?+W?%4RZkVVkfB}%;ots3ke$f2F#aHxRBZ*7|8Z4o1_{P$_)|gjR|3)D zer*aHNT(zzFQFMau@ze%B5WMmqff9w6bjGqSj@sS6jJS2%m?mtEhS6#{PMP zl}Ln-x}G^f0PFlb<1@ZtCay#c>AeY53aXd1oI`FtV zr~w*!Fc`3FdLSgM&`qA|>RFL>7&4#(cH03c0LX)T0*HH;Rke6+*CmsDCxbCId97tx zaVXGbz^KX?j|2^)%!*fDo!7Z_pJ9U%yx#GWix;Uo`H>{#2XCBe*h~D_opZT ztY=oG-RZ4))4H0*Pdwiyppa860ZNIfs@i6rSNJKR?ODrcMusj=X;O!nRUNJ6AR&Sqstnp0@d z0oYN11Av;yiG8?-du5}Y`eXCyhuX6)eP#CZY2ox67H+70{`?OVHr4BLJ47S3U~iQyo6 z16M5=#%JK1Roe!R+Oukes3FltNSiilpRx@Kg-wtjY&2_Py9R2UzMVXK`uqtrsL-KA ziyA$OG^x_1Oq)7=3N@$h*8zN}P}^22uz+owS_MG5+Z_LDVhp8R<7^a&L< zwt_ra6YIy1HB~o5dFtaw&^2tHP<`@S7}Z)(q5OpE(t7cU;{dGpYrnZ|uW8^A^p$!f((P4m9Wvp}}th z-AQw|jz9tm)Q&s?tz)1&>yt2h+1mRg%)JkSZ2*9NB9w!T-dl3*<9A-RTws?U{+@+ zG6@n2D2Ih2mt}T62H9C{dB$gBYc(dw{xm#J^GQk0j1&xetx1DSIk-vl8a%-Hh8r@t z@dgh%n#x0)Jo2z(!U-8L&_M?p%-R8Tw%Q6FblFW10R`3hy4`l(RTlvRxGr}b1MgJ> z&PB~m)DAS!NTX0g4)HgTG!W+ZAcg`GH#hQ2V+-?6CXbHxEjqu0iY&6wL0nQ@BpN4h=6n zh7Ywf(L)Nkm;6NiHp?tHgkZD{HyDjZ%{D4&@*CBUI?5!2e=^LVtd2VP^s|$fMP(mf8Ams|akG|?MG$Y=3}GO3v&gK)PJIxB zo3JsBJ{*BhG_i&t`cVF~G|5CRg&Epg0Cg9f@QE#Fs-PeMai&jr;w6tEL5b_kL?Di?&81XmgfQP2&1`ke^;{+>M!FgnbMGAC4If`2xbfg0T zUukYwzM8;z#F#niXikfr%K$Q}!4Yso<5|uNMtrVSFVx{~cm|nPfcRsdb_BzA3UbJ~ z&eflT7&1frDai675{(aCD|v3KNPM8twrWhoS>eD4z^FkDZcxJ+qSVGVrolaJU}J~Y zfRtViV?j^g1Qd_~1=2LZihOKke!T3ZFMkP4r_`fl!$?NSQpSvBoZ}oS>j#zum=vvi zg&aCOj94CnLH;nQX)fT4$?cA%`rK zJ`Jf>x~>(i;H@JX1B%x0+z||dM1!I0I!N#s60d4S<2@012t_D>q9nw>vau3v^ubZthzyUiaYFQI;uL*21t^Y?2fzU08u@@`Fb|8^#47e<^($F2 zmNATE{-*34$yjDOmWhum88#^V$VX<$F%GiOM3tX#h7MKf5<=9>8Z4pfOS0h@y?~-e zkg1H+W_y@xfW|OyQAJ*WW*AVMuxP3nj5Qc@7&iSyCYHHj({Pjxg-wG+D*7Qb?5H4V zsLCDi5JqsM;kVb6LpbQ@=x^v&8{w3rqpCv230#GO&c({4v69tu6nCrVJSTFIn~vnF zGo3Ihr#TtWz^l@uQ)qM&s3r2oAfa_fg#-hVS+$+E00}RLB;-L7TIxbzht-8dgkBtq zMkJR9A8#N}teuPxib#aXk+2mb2rZ4I;A+Zg2m&S8V3?T1LK(I|rf7xn#3@n%h(LV) z1`rurtdpM%h8oe$#y~$Y zjU8qKgK>7$oE*g_IETVfg0jq9vgQX=2pUbGA&e&g5f?of!4Fc)nsEKHG`q|N6oRfG zU_Pi9zv#&iN5EmH)3%LJ`mkRc<`g^F!O^%)RJ>61&3ZdJUXHHUz3`Q92RJZalAg3y z6R6eZp0l~@e38Fp)Xsf-P108tzyyE*n80ZK3}{%yZO9w3yclxTgcQ|Xd(6)yv2DoW zwXWI>Nl1L|B_Gm3#6v&@QBP5Hn$i@E&7_=>!d5a+ZPbiMY_f)+2_r*6(31W!!Ue@C z-jWwhjH9qpZn(oA4&{B=gBinsY%!6czsPo(8JA6m$30FDdeoyH1ZdekTv3m4jAK&H zXgT%_wq`ctNF_&b6kVx7h=JPZQE*NZk8XmBYaBtzit%8e|6D;g4T3U_ri;=9jS5xx zg)$!mj3;#bnX4CSEQEmTAX>f+(`+Oh1;CHCQ0>qKrAk$Do2aV1E4Ok)@zm^a?+Q{t zxD9MT1Gt{=;b!HWSUCsSwxZk`b0wYV&`PAQGQknHF%lV@Xd;z_7KpSOj`(CK#0;qq zK`!J-K6W)6()cQekXJ8?#3w}SZWeo>#~!x9(b)kDH8;573~jWW&HfA<1U2SD=b+sT zG@dZRl0BimQ}`7SnmDu(G_gL2OMm**hu=Q%Aqpf@3I9BNdOrRLhO(eEvzKyZc@t;8dJa2S<=3TsjsgfT*l zfeLydOV=Q25(q*?a}CGU7HxqFpnz#qQx|{X31=}^ZWbw|5q5C&EEuv5(4Z}H2vIK!p<>OGZWDn? zFD7Fi5=THJV;~_g)CCQoazl68 zb!ze;48!nV@1=JrP=rM&D;z*8N?2bEKvGi394GbuMYm#+N~k!DCsHP00?S z1ymw3M_@HpVE7>jF=7y*5YpmQ1W_MR1&8o*M-^d{76B2J6k~L#U=kE1@tq0t$6CfHW};l16DkH#JgO7=Cpp=o1KlKrzj?SGwehUkR3BX%rGy0K>p# z$#j;>lnfZRWyr9K%ODKqAeXHe59WXlnSu;WbeHZYf5Gq`(4dE=Q4OI4N?pfh1?77_ zhe~e7J&+PU594p^R2LI8jWF>S;BR-eDzd5*Z@L)08W+|3Yu1$lBOq(5?x7Y zdjZ2N3bha~=pP2cQLBO=bjJ>_MntG43`G7UH?p%1!_WdM@Lnje0vv!G30Z_BRbLF* zkclIO%V8||^&Fa`9Lupq%z0}WZ~|2b4S~oJ0TV|&1r8cP5l7G-6d`S2)jY`44(u^j z!oxf&IaU_2N%vWKWz~~y)03!yA}IKu&)^I$@)0Y-W(boo0|i$O1S$OFXMzR_I3Z}r zrwW=73V}dr8Hx(ccRqbUBw`7oAsUusxn&i%49gIH%oKi=MSja*4(GsqbD4hSV3(pI zD!ma8?AID5HdWEqFC;OT22+^Su#7E-O0CqG1QjOH2sT;sCyF5m=9HPlHwZ?sTMzh% zP^V5r6ABWD7(W6RbukS(v?B@%O8%lmO3>3R@uE};f-V90ir4oGF}j+D%u67 z?r;LbNkxQXMHw)J3TZe=sDuSn^lQyQU*|!D8)*W;U>YMq4Hz*gq2nx( zCn9uclTigp?XWM}X!cbXpX_gq54lHVl zUS?U!B%|qP8|m5`u0|a4Ck=KaZ6qQZBtaU)I7+MOe>PWVKerh?QW%jrHCuBNf8iMA zG*~zxL$ai$bke1CA{RgN{ut&YfYP;?YvV)jVPYH-df%`hP?aBNr!DJ%YQ&*kFgQeT zN<{0>0w=%%#7Q_n$N)g7kb|lLd#7tR>yQztI33^sx)vP;rk#4HcPqdE94VjzBbed& zQzTNJsIhLT_nvL2U|!WBnRlP4VYTjY5uG$5@bO|L;x<5a5gfs^A(;{XIVlBGJuN3N z+>jD*#f;I2L4aaGesL#RqY7_v3S1*3dlhx(qdw-Nq3RO|HtinxiZSY)Y8Cwijf z>SfE&eOzV^%iwWy*^0Jdm$A4vzp-AzAPn+nV%PN^8$n74bD*eOBRf|kkTOuA@Gy!| zGjVZTG2sW!YG@$-B!S?lTY*tecal%)6oOgDG}90mXaN(0@O7gx2%*+;Ehn~_CrAdd zgA9Up0irECSh71vn|aE1DGLKHZ~}O@0w-XcC!m}NNrXvQs2FKq$QGT6Q!87@`dpK71!S)c65AtN~w6(P1^8*StX4skSN&Q?9p zu(qVMt8JDI&M=6ESTlbX6FTDuO9Kd6sS1I`e0>E@ngGM9APA>0HG-=OfB-^Xskl4L z!|%ft_ArafGz_bF4#SWRlB-OY)qR$GS(a-KuUMDyfDW-y8>QlEa|2#T@Hwx81Y3nk zX=R|*U`qbpgSraZuM9J1paDLBVSsmWHf-^LH-QbOa0EvXfs8mcMOI{y$QGr^K$Vd} z1L`O}RuW&g4M%_k@ux{3B19M_Ap(*h=VF_z5g@1rkSDtiFwg?SnF3UV0zml5f;y@B zduxLlE6(Y@4Vj%?goH@g0Yn&tDByz{k*TNq!2ujF3I;?F0Y}wvU0e87p+msK%(do8 z5g0K?oTNzz)q4JmBGv;AN5CwD2}L@O+>U2&WJvfvX8YB7p&*34m}4I^4ti%+DNiedREVmYc*!+{DWyxi5O6t@v?y znf?y30mV~H#lQg@I4BRu03q+XFI(lyBXN5MHA)|?yfvcDaTX@Q*AgpqT#xY<7YG^1 zS2Q$S8Q^q2TvI}Y0Vt7CG<~27Xpv`ra3cj(BWqTF9sx&0nN{}DNZ2wVZhEo@f@+vN zI~;}#Fu(%ul>#d8$yoi#RkQ&zJE%#hkT>g`f2V7Ihefa)gjVE(0)PaBInAEr5vAcn zokR#D!l}=algZ3H$IP|sMz+rKLt6{M6)d*VW5NH4B7?vzD)M;MV=&wkUD%LwbM{Ku zU<7}5yHnE#c@T6P8g%AD6Q?gI4XObRM<6d1%)tX1(re}nzK0`@q82Za zT!8_OY2tuXBXt>=w_Fp6x}}*}M=__#G^J@6pb^qE;u38(n58?C8Jl58l^@@d-;K1V z*1J1!S`Oj6vMF%YAoa39NQCP9)wpJa3z@UImb0@`ghGp)cgFw>zykl$tDsaGAVJil z<_!wwp9{tw9@#dpCz8tCFIy|XzD#4xB0AB-wB)(i2o#-rJX4SV$FZ5w#x|oFX|tIT za=+AE<}$Zou8EXe?m|@P^1){A%>9xux7-qvbQ5#Q{Z2@7t5hnfglgZP-@oVY_c`bN zc)ecl=j&oQ=m8W^Jes=jL|4F%`w689Al|Id&+Is3_WsPohsGhlu!*DKiaU?m8EmtB zp&AdNEx_xuP48?cMaoa7a@Fc5fFTnqflZf^Z+-MDXxf};ZfSZpX@_vS%_9RLXqhuY zTvMQy(}rl}7Gvx^6?znk#AhYm7H20KZ|op(>AQr8d4T&ODq(UnL;6YzZ&*Nu1RyU$ z?TlXaY8{;I#hf`_-ULf@g#8Z-6Z#&1WC!z9|X$i1644} zdemVL{vK!P7H6Jm8M?g62|I+3l%GdDH1}U@Fr1C-(Tx5pKq27Ew*~I91gp9Phpzc> zn*>Wd!nPY5@0N1~t7z}4%g5cmZi^To?PMVDCT^;xOh}tOey@^hmiGFST!C-XEr)Z$ z-PV%U_{qn~ft^K|W2wNYZS0x7XHN>C)sB8uSrPYseiiYS$iOz%{gbc~Am%cs$#Une z+F51K$BNXViYem$lf*vM+c?x!9(6?Qpwp`g7>0s*YmXI>f%>5^)xy{b4?e~6K_$%R zJJgbXLHqvX6|f*9KBc5`WaUviD>=oqnzZWFyQ@FI*Ax47N8J5nt4z`tV|TFQ*o4KA zISbM|>G206TFPDD4r8z*iF%HE1~W4M4aihtt0u+HC`<}K9!Tg^d8f1xQsP8M1;#(o z^-EM154cT2*D;GFD%+KM+k*E6qsxVw%Y=$N-W90`{cb)B3;iqnLge@MyDJt2?|+9k zxZFDK*W2+XMdMW8s|%6~ncCgqfdlTs;MQN&89;EB^F$Z)e`=Q3J3ll$l~|g#49q@y z1sgdQbM&Ui4TMhKUS{L|i$?7bn_Cc=8Hs%`^I^K2yjT-Z*&ZVK&~K?et`aro_4Mj$ zDLDsp?~V4gxB5?lK8$S)UY(rdKk@j|8|{Fva~9rmnfxu{CtW+tvt$55VhXWME^!?H zNvISpSY-$sAaGZz+~x~UUXN45nIbeaMus2Y)ytx-Q@#vn`9TK}_5E{2k3v>57?nD3 z*M~Una+lt9&?Onuut+)P^q=1+wJ*hry>f?SEcS*lq%KGFhq!6^Ew+X9T*b2=1k;;u z4$TR;5p8caxgSXwH9zjuaxr46%3`+8p^hh9CQp7g)TV^%k0@2xJ#Jq@Ewa2Am|1cC zpvv~{`8NkwwiX_Sepr6<=i2saU#8rJ<-gHCKentJ6R0kyd_Im;S6;Z#c_ZS(r_b6) z?|14(PN)h<`%K6S+=*IAmg@$-i@Pfo9hee!=Q35nq9(M0EQ9io-#;N4D2+=kCf82( zOBjKQn6Ti(%;#-7P_Pe8`>Vr22ayD2k&Z@>eKC%aKYcJX5--1)A?-0m3~%=lkca!n z-R>=>f#5!E!LE2t7eLOh7uikZH&ywG{d4k|9ie75aJLWPQ_AU|nU}DKh_2SDiS1&)Px4?U4F~;M=YB z?2-Ep@A$Tg0_)?LEiVoh8_<4#T}M=0#8Ojb5~(*wW?Iotf~}Zs5PZn{dvpi4yzxsjts<0>Rk<-s`rImvcda2 z2yUEwALVTvr-~#WrfF}_7xVMOXpVyb?X@J)-Nb{m1?D`+xuOfWl7yIrOiV9zY^ZAcjA`i}Xq53rCg!3?V0Ar!ciD z=>a40N9h8m^qn)Z(y7v4Spq{6p1~iM$k~ko6umW>knDb2(Co7Aq4&I#|fi4@aYS($Gh+c^6&Y70g8gLY6UU z<`cVFp;fA~{()xHO-2?Hw2q&m^{aYJJfi;UwLLG0q=B#KR4U5arB@;=^Z9h|saym| zz%1X}mp>l0sPxVA1iSi(*PlE$j3t$aK*|>wRt5|XrhXo-V8a%&iHg^HvYx`b!m1k>((_VGLY=CKW5zBl1r()@MB!j`=OIca_) z=6?uq*&i2}A=qdl9_c8|;25)IbIgn-71FK@Y{=ptOG=b|hlY~Y!RDJzn!d@;5?KD| zv4OK%zPXw~U?W&<7Za28Ua&${-rVSf{ls6E0M5OV0+{S&F|?|VJ!}(kJ7Tx(oQz7j zK|jf8Niu!53eEJ{kU$9v6p#4Scofwh0$RFamNU9_7W+WxV&5Yi}0|Q7E^r*YWM0P zwQC54-om7OhQIlD>Q7xJhHYB*iGI9X6Xyt2N7io|BfUkzxEYGrqNR=Wtp~|pisEm7 zLA=tohD+@fdEKm}y_Mco5n7!Sc~tFULZHNDUZb3OGF^S?%7X_YH!!)SKN*QCGVPfE z{Z!ZgPJF4xu%qqg0u0}N5s3l-GowcU$9}|`4N|m3qE`wSKMajb-oT+bj+(e-e>0T< z^Q1`$Ngns4RBigfay)5mLcJ7w?f8xI>N;yt7sfYKuNSgUqH~XA{26jz3=kE_+)I2Lr zJw;H;U+9M~$|xF!4oaB8#G#s%tbkf#bfvC!Yx8#v-@3J!Qd$DRLo{i%Dqghk{HxHy zAGdd-4@AB!0_4TBgzO7bZwzF;l}__u*rBlJhvS;Agxm}|_W^z3wS!V-)LR(EpzP=o8TsJdQsH~&+@UJj0!9)O*xyK zE9>&yYPhA9QY?P-W6~+3sYG6EwLU62hSn-hEcKyU25|~WQ}P)#lLA2-Tc)zb7n5wN zv-~tP*U;gg)F&u~X|>SxNaN|^rPZv^Mx1T`=Ig=>EcsH>zCB5B=1|bgJ$Zd$h`1+c zzww0cZne1&?!zz4BI`4 z4V?WhCEYkFHZE~ zyIwchvFRw7*51y0HX*1Ntg(cL`tY3Sln0@79^X;v67R|-K4>UUdJG~78MjDPn@d?1 zJvQLYMXuziKE>f-c@+<^y)IdaQAzwkPnbDioj>SIjylZl$s|^6WZ;;qP^l<3)pk<$ z5{;{oVAysp5KfDK~qukN_LONMo=(O!5{D7s8R zir+@3$-2CZquz9qan#a-e`uJbK{eL=TQ=VF{}{UPummzD@kWOLejXM8lejvMiDZFx zjI_Wptc1Ad=^yX%%M+nPsGz6q!4b7^uUhTLEG>j~)&McRIq#82UUN~=xWZHN3igDB zymXOxZCo+_iL~!vDOMLj+pKdiOn?It3_H?&;l)yRh@-mT^J@BSDA^WXNXiii$NyMT zkfd6m0-qJ-?`cupz)Bw)(^Ch;r)UV>5G7u3m3wNa@}m``fns^S|&Ox6Y~g#ar;U{P+&J>D@fwgZVRSV#4K=0)=4B9lIt| zoo8noIQBYshun;d8!c|*GY<)J;jqMT54c?+$Y6!;p%d@V!v?eEc8r+c6o@QUVj}ir zf(3?$tmSiCAfYHx56FH!d@?!~CK%nDVmk58P;*cSun2(aJue9y<#_WW1o>b z1)qsU+v*VN;Kh!$&>2>n^WVC_ZfR>Bf@MQ-P?Y%NrEZv@EZ1$}NNC|9L%`sPPXF%* zNp;yBp|G5*Njhofl~*$1_Tu>{O7g^fXW$+zGPS!nf`_Qg`d4w7# zhijNp9KA0DvOSwL&IV2GH5ThiPc1;uM(U(L4IZ9J@1LdJ$7NkPk$>AWX=1*5IUxO9 z3A3ylWav_NS3Vod3ncOhpZ!_$evk0$Y=#}?_+AkwT&>B}aBv^_EIaLJPFq>j<1!MF zKg!eg!{v;Z>OHp=X#hRi=dQ%ceMS%rXtaXmjbeIuNL-7BMS->U5hnCcg^*Kv^r>=T zPN8vHVgPRPw-M+n5Bq>KB=$v1CPK6boSf!x8=}jlNd8c7W{)N4#M^pwo^WkDaar~I zNa^vj*@ouOI30o$O!atc`s;1r>)1Yr@-~beVy>%tQYHUpa8j~=p5&3V*~z3cEnxrV zk<>7ShirxPE@GNXq95_TXDr1F)Ad5v8ajd`ycPsOqzpgyzuI~X!spIQl~}bj$XW5; zL8*(XfOs+T*^3o@y`aEm=EwwOs-d;+YR{Mm0{3Dx1Xn9(46ZQ zZPFV6bm8XSa{vy+1gj`z;2Y;l?#4H`DtwO_Di3tx`JzC07zk0H3}9;oh{Ea}PnrPl z*O|Z=Y9@$;`z*WK8)6ax9<`TFOI$UV$O0#iQ*j59qE9+fYp2Z+KzOA?N5H0Cd{Vxw z1$0Y3+cM|r7CFIilRoz(T^`CfGsCzZBrdm*FQ1h!A7_PHczLu0d};H@8C}H}Nh8n7 zkErDt4Cd;j6D6^3$(~?CZx%%_nm3T@cxM6^+>4z1scU#PPLwERppYvsD#QtQ6`QcG ze2(kv79BfigxP^X55^|I(!m&DuX)l78z4_zPKA9F>AZp7_3uj(oi%$SY57G z=M#|Mo})3(O7}jMVBp`!{Uvb}w*pnr(9F6~@cuH1+dCdDkuY$A|9?^me^e7F^Ys4d zrT+yVE@Y%|#PPldW$Ihbv+nM0Jpxigpy?@4OG`&%c4deIEan(2bG6*0t3aK%9enkC5^Hc5$PmT^|H?(9QI}4TY z%s%rhebdv_kOvsjEo}fhYwPm%v;4U@W3+8-v6QY-cI#N;N>y`I#UD5gtLe>CT`b?$H%5K_XwB@}|p%}=#1@OBL*b(vf=Bf*(S z-mGVDWJYQE#ob(HTe&010dD@!(RTmk?bXHy&%531;S5Keka?__r;~zwUr?bvk(WV> zt(Y%=8faM%i0F|Iwk3{?+Z7)74FQ^NFTIo`jXYf14+g&fv^1{7KWe(ZJ_IbBSqiEz z)ALWb;o*L&Y5gjvDNtgJOb0FANnUQaANT`fU~>Los2t!a;JG&;%*Vhg9oK$kBwm1=0ASW70-g*v#T3Y7nTC@LZZa{z=^YhqG5*dcKRxuq!(iLE150= zo-QC?ZmfqmtKW;bs5dEy3gac5cFgVyM5<)cbY9m-t=_*(dgB0SK7`C)sPF}GY1U(+3d>h;gEgk(gdOZ zUCp_h1@dXnUYdHVeqHOIrjuNN{Xc9+E|M&hNR}#dl%xPPit_(7680HO-RjCYJ_)+* z-sQrd{#zjFY%ynyveFNY(j6vW^KE7fEJzd-^!e_7%1QJ5`+EmH{==W5V9eb`+LD!B z4qPiI{QUof9zUq*4O7W!Wv8ADOm((P^|I@HdjsAfm0cg6EzQecGE_R>Rl0ekcq_by z%Xx0)F20aF@(BA8F4hC0yMW0*5F@Q(3*o+fu#26w;2N3Al_0jiNAeZ0p|3e;GOb_t zn7ZtVE)%ha9NY&)|7cB!b)e_lMu5@`fxSN`5)uED5G)k(J@}&))BO&1OHRwn&l~_w^JGi z0k)HR%KN?N#;O^LzRIMP07@*$(xa(BnctMgDC|F%*MDxLn(^{>SMb4K&srYjwmiB5!bi=xtx1q!O8&fuuOeUe zue$D<*`2XYeVEQ`mJ(r5T2A)tYg9JzC7d~sHo$r5aB!r{EkDWNSepGj6Z#Q7{vS-GL_-s)m&*<7J0q0jL<#qbAZJEhA z;jFthQ6gU9f1hY2$V}3|VI*z$0vhy|Zr`tbcFT+;h{#^fPpY-8*&9sj&`Ol`-*dgi z9er`FIdKC^)8YGZXJCFl|LfTcv9vymS$XTbhIcHTRAA)}^@jff_EcC3j->}Tgfze8 zXa&x61ia24m3S09Tdxav8RDiHHrs9o_+U>MEmGn>kG?J*;@1)Sj>T*3OWjlv?@j3@ z*5sP1il1b4`oo<9kJKyIKj|noGIc&G-&wl-MAP)l(UW7GC|&?a)ywoO#Ep9 z1dAz9+{55G?$kfWYm05cjFylRCiM10P72(O{x`sz7(_??4_duH{V=H3&>aT`=PDRf z@z+e{e$1^S)!AnanFP+%P%9})u5Esk1j`!Bbk4N7EzUC6GVfGIBH}wG1%0-)*L+f1 zum7%tm&qVPnldPc)y`P5ue2U8)AWjzw`;g@u-ub*@<0852fN?a$M64V@INm1e*jc@ zEC8{$tiR7v7sjT0=2#OMio37m${AB;Tp}H|He&WVHUg+Kx!Go;GG$KhJ++hTAbk2q z7u`$uM=rot_j@A>cY3>vK1TX(t}b$Fduu?3^nK(3E@KBNC~{h>6_90DE zGfp4ISTpinZ~d^=c*~e}P+5&~7*$`Y-5Ajt)1gDP6Mj|CYaoQy%!uVKNFlk(03$T9 z*ncgN5X==s?X?>;MjCufxn05@*AD ztgWQSfa%(5dZHOcdSCERwQyCOqgy{JBG*2UoagKqcqbw6?AeDjXJQ?oP9g zD$QNaZap4BX)0#4%A=l)SyOJ(@grWi`3p>Ue;2K!*^Bc&g$Um!%-o*pfLyJI`hCs9 zT~B%9{ECF@@v4CAM1?x3zh;=KLXM#P?JA?!!8KbgFNwLE?dI}*H~o5La>IfLucoiC zlLkjj?}BkTNx>HKF)jt}SC!Q(+;J0GiOW$1RC_`E7co@Zgt4f5+oTyzNyA_x?8hMH z7LA^+l`qB|)nwmT8^p{6|C_WJBmEeGe=!lw(3ouekxt@o#-(TfXzcLHQf%66UphGi z)=s?+82p`ba~wCGZuMkcD}Tr1W5(Low#ul}Z%NCt8hQzW=~l~Ck@lK&9d&apJHJZk zQ}o$?1)8sTyxaalPeBe+bpXK*fEpNuqihC0_8VCWB#kx7gAV(W^owg+f$WFQ-C{RMAD# zUId4xn_q%p)pba%gNtz68;6o!GgHn|U7p6{Wgmwc2(mvcsxcfvK5Q8!P(4%Zw%G6i zL74#!N^;H@GJMLDG0>jB)^b>Rb=;CU^qTbX=BJ~(K|(tsXnPF)5t*QWJ?c@ zo`oAulKXnIUz=m+zt1zM@#&XfFSSx6et;?WcO^0SCs|S$4@~UfP4|o3l>8h^IbB7T z<<+Q@nqv7Zzn`ppyt-)`1F(O+20yH^!%-sWlBec9EgfVmER#-G=QZVaybO`Q{C1mi zdH|U*_^#KOXqUr$GMm-MGffuzY2w#RrqWg{#A35&s?KZIEsB|7*Ahql)$i>`D z{*P{NdGinkzpMM?`{KKKDk}^gKu+)jsNMf7md!g_(j~75+iV(p$>&?>?MCmKkkjXe z1ABrusu(T(7FJJ`4I*Kz70!&@!Mo%adt{h-xd*@M6}Tf$g~(lSx}13gln!Sg>j!{x z=W~+p7ITKVpK{Y}Do9toQ7k!d&FV4+`qtt}+uL#xXEl$f>mBbwi| zS}pJO<6lhTJ&6|R&xW#TRKZ8xSotu;?5aSexC zm^J+k(D$zWhU%l0*`eANitIaqw)^a?*{UkaEutz*on8%A>GX7Su(UT- z5-Q1!^{JFu{W4SSZvS?Uw;Hb*(Eh;bT;3cOI@XS}Ivf8^8#0m;7K@V_j}mJvenslh z@wQ?3w_vmY;A!xhD3q+GW~+)$m=uNq&O*QVYCnr7s*ARXg5`^csI;GKky4eN3tHLf zIP=kxnN9OrmR@M4$$eH)&>-nU!1zfl;MlN^fLcB__s4gIo1bnUnh^)NdstJKqk5_T zRD{-!7Ixj5%oeh*e<*%LWE~|eP3itnk)C~urTVqF-&}J|!+=D=A&MQ^;{vulV3MWwQW67_iN%yoXRW(PTLg zH8*?&Ym_DCOMjQh$#j#S=LFLw=@WWdVAZ$9iwz5AFkmT~&)6XBn#MF9DQCz#dO1Qy zbp4)t&dWb&8;|42DnnHF?6r*evuU~yzxzi9eu`c+|6sXcA?ml$Te@6WrTZy# zd*{0l2Qd4>&~_=e`kAeLmFbbj1c!5ueO&7$M_4M4D+(e7VB8TIEQ(brq{C4Zfb|?D zY&1QAPbl0{z!{`fZj^p@K*$M}DJG#7KskPcqUHp|Y}t^d?m#_{=RNPgwB0YWLMHIM zbhb+j*WkE3UWi=DldhdDk>GpXG9sbMk?@3zOL&eu8X@%KWoBlJi`!iXMw>8!w+}g(1t!K#kJB}Dl2=BY zR~*m3hkC6nfs>oT*^0>ucd{EzEp%yvc{<4_8l*?3$@YM;r0ST; z_-A=YP5)cV&nuj2)VH2wVd{#Rv13Rv(${IM5?yluc8UL@i6rIOQC3}ibvdlYaY8`z zHBgnQaIWXYxpa(U@00zdC)Ozhh?1xj|PWuSPw=HE;#C6`(ed z9`r9A!IZ@ygl0Mn3W1H1ayWbZ=2pwBb2&JfdDfu$#=2F;dp||hh;*IebwK^P9kGOrHSLw<=MBHx+!agW z;3&tC4jm$7?1U;0QhnQD&xbW5HGVPI>Np7$8ps@jimJH^sX!N0A6J+-_kIEcjiQVy zxF*v4p4a1(rm~YL@zNv?)`X13$9sGMIP(Rtgz9c7reE;r4au09 z3j=iaF}{%L4J#(6f%M~CS&U6`V_z}mkj==>#(7Go0A=dfQ~C8tx$}$oH^u8JHtW6i zilf;|{BD{XjPS=Mny@JiogSU;VJ{tXqf%jS+N*%Z44Q6lP~_`q-H}Rvj37qn;Tj@b%QlmF)LoTw zz^SU9E>&X#Sz}!V0Oz}qZYhpz?E>f=|D(h2sFTop$MiHJmE1DU-JgEYZ%P6JJQ?v9 zMzA#|pvZsxl&)NGD=UGaA8ON$TL>L-!} zE-$5F4egNDS%ns6Hdp;^vWen%;K`q=j!JXVm)%qJtCO>d8Qg{LQ`n>2qO#SvGO>$T zLtcpvjt4YgAf=J@6`&v4Be&P><3iVJWOySuX8zz`5XtbH1Bz@YVR6w_*(RsNJU?Uk z-9s>`QMS(13!`k&C}@l+9Y}VpSer-Z|8?G&u~&+-C7!@VeuvUbzwIJ{p^AcJn^aIOPS;AN{zGeluyuv zSJEnC)B83-l(!s`CSXO^{qF1%pl zt|GuG#<&`)#2~#=hX9EAR2I!uut(!DthOO!p!uPV zyZp$b|M|05&ycfVzJ(_jp-<{$7GjuOQ-4kte5fkwjFHJ(hc_!de`B(BH z91{_<5ZS0>=kFE4nYD*g%AxT6JCNW`-QU;e>nZh5ZvBQe=R-*wssC?5J(1YUsg;Sv z%1ngrmDZNqRrB5cp(~d^*cr@Z3>{m0ZC-2nB1_PwtyI8oFez$rs$xoE5P-=yhM2AC zA6Yx%C!hCoD|aGn5$s#Ag!T)VQ`8$f+bLwzY(ko?vrJ={`CC3#L3{rl7K)}2OE_Hv zHr>Qexi?kCUiKgN;Sd@%dRAzJD!juiMPVy05Cb{n-LV8kKE)pIRPmAa90;}n0258j zo&k%`+2~-%DY(L5K-jPPkFemW@aVU+zAu zFPB3A!!Jjf#cbrk%_s3)RM){{2Xp?iQk=d(^*k+E+x+Yq$0jC z^be;NE5-Mw$X~;l_l*P}P2cF~?p0(5C$r*5n5eeYce)PCD=a&u-Y|^n*aP>swffn+ zal=?;FaI7t{nKP|gI)4e&9bX&GX8P(3SMbV<=%xk=NzK&X^5{!VDjme=@)s>dyZpT zPlWEo1E?h?wcNd$O-E+%kgq?B3D-GO;qj_`#YVcMAUL>8`lnlghSBgD|Cv&J}KdO>%5%DZ~*wNp$ zIWgSHC4kP)zU&?Ci$y}eCK$7qaDMFc(1nQgH1UlY=e!JYjQ(Iq(bQU-eUpPs)Hmlf zqWw%iLTSPNw3M$6#H|SBXH{$YwQi{8W`;beor{) zK|~fX@>_910~(b^9U`WAJ?09#&ubp)F%~jBzPtA1srQ!@UT~qkO^>HMls0mVCXiEZ*MpZI14Ug9N#6;Ayl+XcQ(f%;Szsl{>;F{*GUx!zV8O zkG||*aSmthP4)0eWYsPT!dvYSfo1V(TJhn#+UJj-3VwQ@Z50#r_L%y~2W8#&ixY?= zGw!toF>hY~i%kP)lK{Wka_aq)%o#)QZMPzbr03)T z@{4R_PDd5rRqD)7a=sfN_%70-0PHp|)m>tA{noTeb$Sl7>RcMOGUEHsC%=*vs5#$e zyq1PEtRHFg{3VB|K&p0W&pR8w89=77$K({-D};gM5|AoX;>f+*5q2>C=WY-CUt0zb z6gwJgQ0>#ojY;!mj>DI>&{BroUujgegRQp*hAwW+nF-zhF_aSi{;!_TpB;cNm+=N z$K=`X6=gQIfW!iUgNM1zwn2jAbUW{dhaOe(iN_*WiUjUNj;Q(-T`X+bDe=s<^F{fl z*}Wh3X?J{I=-s8kEc8yYm_~WeP}N7(-a0-g^qNzQ7*&1Y=sO%ysQW=G;_%E~!ZV)z zO_bZnYhO-pEF$Kb--iRm3^cyuVb*BAY7s*oUjAGILtTEPI9C$?u3JQRkZx?REOoKQ z)N%okX-{M`;FN8T-fRm(3q$@nELkY)@U;9yiVo;6?v%F78w6m(Ei?rdSo$rvhH-5b-czf&Lzuy;b)JrgK zhjg&NwS^#?n8mpI@1QmR(rAKIKzTCZQRoc^<{6bNck@xuav8PmE6pz%(%D~ zJMHr5>ZOKzT8m+HrdARbB%l{MLl==scyt)(J*X`rNQTr1_K5^JK7L=EMzZU35cm_u z>f_f{mCd6PHTrU?=ic<@nyTrZ7Iiq!|AzzqvBEIs7RdCfh&2JiRVirC5?4`cK6154 zjlhA)i+^pCOvw=BdrJH2P?11s6ifAP$;GLbYzd!23*R3Kx^JbZ7fp`4+juQ1=J0Dy zQXkmNrOH32UYtk1DO74{L=;6#SqR*@951nvWGX06!UlsZ%wa)>!%wNKuGjy`{L zMI|)%aV!V>0M+1!v*MGvXM-xPWVtCV7>ksL?Kr8JLg2v&JxH>%NWib8_65~`nlnO8 zX3{`$5q-pMpaRquIUF0Xkk2z+p>%n)S|KEk(JBnTXWn%}B|7=cQ^a@hEglF1i(Ca; zxNvU8fdt2NrmoxLG-jm^YvsV8F@He12Y06C*u)+*Drs8yS`<}hxG3Z0tv%xal$ox% zqRbUTajEpjxYM6eB2l%6goryY{XW`_$IL}Eq+ z6kQ=cT&$?ct!8pkfYew*g&=5fo>wHY7bpGHtzV@ENK}RP*p^EkQ#bl8t38-OjXHI# z*izuGPK!rm&Fkq8S_Kdvs*UA$RIUa~r7C#ygTMK3|Djkb$T6)FITD_f&g#O@M(nbS zqF|}*iDo&uUowLmoaE;RMNMhkwKJ3?qo%@Eq=^YxBn3QjK>>9SYq%zFwA-O>ze73dUcE*=!zW~Q=Z{obugTMsP`cHH9ogcjXoxn{*!m@^f2%7O z;vJP7;dIJOtrjmUS7eN)V-Rlp(}@q!B4Q-h^Oyq|h8CS7dJ`}!Z?l?3`Wq+u-{zw9 zZu3JuR9t4YOD`eVUQ|zmt152JjM%80}>NGj_uOXjA4WhC%hI;tw#pGdoawK62Ui9yt4xYywlG zmt8Qz=)AeHPLvtmgs*yv{z$N($~8ZhKgw z-qLqX57Y@^=^pfx_d#wb^5E^7^g-1`gcZO#jza_Yv3E4DKYK)H;!Xj8}|Mey)e~o)@ zL<5?Iz1$;9#e?oaYWx>_B$h__ryEBG6s0bKeR|imx^U>uO0Ci+t#btJ>`$j-0i|^n(S~rILI)we6d3rsI^PBG(Jr6(&Q#5*$V4KEirM3nb4z~Pm=-={; zp@wJeA2PN-WvF$7IldF~pIO_f&*zf~KGne+R?Cn~#CDJWDudKx-g8T;7nKx2K!T{RLu;Ki%1dpl2RqNenKKVv3ft`%}#f?{sy{IR6 zu?RaVA!lw1OPeAWt?^1%kx>)au|0rf3ARnx%RoB83?mb`OA*__%s6&~&G}%xbtT(2 zAzeEY^MaiyHgb6ojABa_d2tb+1dl-vspxCBq&*=_o>ioId8e$A6zCpS})Yl{z+?! zE`+VoJ6~z!i5s}ph;H?id=ds@Fbrg5?U%ozn=+qq8bX~DS`~amwwjE0FxxgJ&c1xk z8>1ErR?8lI+y4Ah@6!>>gTf2)Qy%dx1I%EO*PAh#p>k@pp_M_ri9ron@D5lP=1}Aq zft2$@hTNOu;(khvR71NJ5C7Qr-shPs};5)H*E>**~JrGm2XB4{6EcU_v z8i{CqI;qjjr_}u4&PgG2$U14{_-D~x2yDI7L!Zq9J@^h$QHF9>AQK*(132%$ES^4| zb#OBTu`SaV>$YnfM-fJFMNSB1LtW#JpT9(2cRDZjvw9vNc)mx{qjIZ1P_NCLc*WPZ zu$k0lO!818m2U~$Ih^Gw;}!*isxNpLhknNEM-Z3lP^Mg{HKcgnQ>P|psq&VzfNNDiO{*45wU?GE z0ujm%3zsq@z)p72wvql8)Mkcl0Xwh4npVQF7{a1!SM{p`at;78S2wWjp|^d2&~(h3 zaxGaKnbuPqvb`^tDXYz6iSVDXXAXi~V5{ys@h5!Jlzs{*m3JvpELIGR`8jzTNM-0o_+PGfk7d7zLmjNp_Twi!Zw75mKST=Uxc<|NlmzR_JI z^8DR`7&Dj#VOMjmN5b+lg)S^#hD{}cyaVYCUWi1nxHi)gtwPa>1bB^WOI3J!gl@}T z?7usMlOhu2ANcEGYCeE@wK5o*Q_A53=02lfF~au%=1eFLJ5>3k#VjjGC>;5dNAOZU zfg=awAHOW`=^V@<@Puz4&_oWl2`Ep0YZo|rmEgsvoZc0z5RzHGi{r*VTigUo$=L7U z20Mlli`OkSR&!V4u9>JFW3eAbzC;#$p5sO?cm%u(vs>5$svF2rJ4|SqL9Y&GY$NZg zIz=Q6W2N8oo=)+-7t7d3@M-gtaf)7!_2W2c{2QJ0i4u(|Gf9AYR0c;{xEInE6Dm>QdFl9pr<8wgs?1MMj~>r>VRRGm zzcQ8oCev=v14+L9p0BmN8-)bCv%SJ`TQXNauW65F7z*{oZ7o5}tQyP_iHif9VZwe2 z_jx5tRb_TCFsWWs1*_Ki8sjJSgw5gam*NRXUINL*kA8I-&HI+MD_5M8X~mX&JBaY{ z+UBuryla|j2yL|gQ9&5z*^?;8)@9>V%kY=E&Z2prkeV;G)I3w?mbJw4(lr2L zk5Eol&wNlCa=T4ERgI1A!Ksq#3~y?fSwDn;gsqDv@-ma^#4^owUq?oZTA zxKsxZ$pw5KMMPCt{r&>K>IBGIQ>c-l8Cv8Nn zZa=?j5hz;ZFw*7s&`K!|KH~QRy;>jAcloflWv1p*S19^Nxpu?dlg6uHLn~(gtE8q% zsjhaLRV-2>Cpa9cdEq{?s3TP_C*p5!Nb<*!9BfTa12W=+D!(a;<*B(4mo_+mxW<6> z>lTG%3=Y=qvgOQxSOv{uCZO>p~!wQlha=;i$5@;0t>k0!WWg!6p40DxZuneOPOIfN<%52IQeq&t(Ve~!haT=s&YO7Q60rHen0-R&&3x%Y zgND&J*Cy2i@YQ-e@vs5R0?ao)@U znJpqO#&NX7kb34XrS$@2S-vaf#4w8h4Ml@kB0*4f`tNiVEYQ}UBKc&QcJ{+~47nl^U z4Cofw;}FX8IfLSKzYRbja3~#3z8YN$o0(Rnlr^9&I9UK5P_!vl4y-W7CA|}n%CPCz zjP;qUD%25w!FUu@=L;`{Q?3|0rflZxN+Z*StIc0XX_Li^+!O*b@yQ{BrjdpAx2EgK z)mG(J_nT&$UGIggj^1yczw0%S{%^@%Mn7Wwh+1{|yr^?-t-{HOfBfcZ#9IG{_&LGS z)#%BJc>ed0)(7VkmOq%ue7X4`;xmszr`qAKwpaI(KEE>g1X=Rzxis%k?W}QACw!)z zLa+@ly^p&E1oxys3K8VFOpcFSsz-nG*AF8`2ZBW#Z8L0C*%%utgNi3ShRSHK|vBel5bpO5ClWC|c()IjSZr|NCoRE3UERH%M)w9_9l0BAOBa zB+QIH*9)CgWaqfy6nj9>_*<`zknzr7zPIrfOEkye1N|szGe#$E7(6e#_gwpZalTLb zSdG3w`g8Ss0Ub74R6$#-J!U-TRNXX6`)$n|WU5@hqoDD2>l;C%DbpkO>4J^#TjjRo z4X~|hkPnS{ytVpR}mH?sHZMoKiB)De(z^lt+>ZB)mOt~ zCPB|de`3vS!S^*#XTe9noGZ(Bvf~2WFV#%c*8j@U37|7Y!utYeets0Q(|z@v8{&Sx zu~z)Vc*MOWy(P3UL^s}s>!$8}44_UqG4q#)>h;asUHK9}eEPGineAm4veqb83e~Ro zTXI?SdXhrAD@sS<%J!j(+@%z@aT@Zfs}Je2Va^FK>Q!TE`ITCmR13N4?MhG8$TPRo zRGaAStvcsS^3NH4>KMp2eoGHuHklA;zS|HMVllD@>-V?Te-sT&S+7^p7*YNX<564YFQ1S zefn4U6hkFFGb$?n>JeV7NPth(%jF_OMv%EA)CkfS)G-Y8IcWL>4K??1BI(+;4 z_Tk^3U;q1$35t*zs z;~*c=SWWKfJ>PUQ&H7WA<)n+Z2}4Gb-XbxqL9|~0XlJYP=uch zk-AKRbwPh^5mnnKUyW;3`xPrlUY_<~j^nC?E%ONUo2jW!cyhdKK)GKSc{(R?ilLt4 zQkA`jDT#Obq?;O1Lh)%vh1d>7Tk$VqrNdA$OmGGaDG zwoBC~D(F%OlI#gl47^s^jDjJgi}j|v?^VHHG`M~dhIbD7ADfdZM&Ll%*ApX-_wA&3 z?bQ~apD{bT7BkOltAFQV#27s%Rwe1c>Bha@TB+G4^G?qO2%ek-O@e3X9u^a1dgHWK3Pr;b|dLT9#o`=BS49ukp9`)w&B0e(omAou_S6?aTj4VV4 zJv~iq7sg__%N-7Yb+x|h*O}U}#dDRdXDozI-J{E?YGGHv={FfPIvP>Qqb;Bav9#pE z4w2%tR<58gt$WN<@>e_n`g-McaI z1nsOy74Ir<2~bGgv19SiGp{Zk$I$|YrmQ9qUAe8{HU#NK@(Tnr0TQY{o9an}&l+>4 zPo$-ZxAd~)1DDELH6V0V85Om#>-nA#G1~AW2&l?m9%aJMg zJZyBZbfaT|(%{sRQeiK#$R4)X{vmutANW=95Se!7A3Z+Al(37knaFsQj@F=zSZrjR zRg3WE|5qwl_j$3xW{sp)09OfLv^O*?hI%N&!(&xif@ZY-8f95NJFHY`EeEsVUpxMZ`i zvydHdO?*l6wPV`Dsl_{QcRSC1{S6|p%f}fJFD1j3?)|}ri%y;fs_gfs9c9x&{DjD- zQ8JQ)`i=N+#TLoz03@WmB|;jd%W%gYj#!nxxj)AE@jm!PRbQhssY=%&buF?+z?Ssw zTMScE{a;p~Oy7e%eltwzF~*C;{#0N5ki1yuZ@|e>xr*m5^VjUkq9McUbYX+w}VN=?hP6yq?Cl z>;PkRyswIDsR$OSZq16mtvz}gXUIFER-D}3cnU%yQA9scd`M`Mj9=@80P+)WaSEEh zrJT!^NE}4`*N=!@mp~q9xKG2?VkAq}C1NR%n8~O=-y{?FE?is}ApXQJM*vq$LHs&| zg#<#EAEc4YF_O$Tzh>PO!FSlibSmA^s)>+6Dx7{{ahgiyi_SA!@&=wm>ugZuHWGO+ zE4p0scS&KU7>ROUa*?}yUnh*to8x7^>~D0%3l!r8x-=_0O_8fvyL7gY@0yqH;u;oE^Q04FSl5_-W%&e|(ov4}7lh^iWxr{6}Ly{c? zq2C~%b|6zb0)3_sry@w@4w&)-+|cV^5y960HB2DKjSquol7W+EeATVQJC3sMB=C>59W2=K%V!mhbFuhCZDiC@!fcDFJl75SU^|Jua$?ZO%2S3!Md17&d!l2p;rk& z?mbCNwD>YYA|lc+rqAbqcA=bd;m^0@+Ab2>4K&sJ#{=7PPjcgLwTTl_#m7w{Jl`*X zME&ELnofC;_*R1RJFru}ClO}Y)azO1#dm#2KH-K;`jCuU11OzkIN`!K1#|VUQQq9m z44|455H3-!a%V1zJoJJj1wrB?APrDZITxsm#WzrJX}pNl+KL3a32-3awf@v?tto-mNc61<+@;Xj(GV6wi(Sk2 z6r&V8rDa(_OnOh8pzuxfrCtfRoU&Fkdl8hpV`R<=Bjg$jArm$(i`?|d`ToQHP$|Nb znSHQt@--&gIfDDgPrJRJCd+9idluY#?DKyfa934{puBVbJuqHL66Q%h6UrjjGv^0i6PED9Pef_@q&ZN%FC5y2B zj60P{D-*{Jc_a(#O1>m`oOMJNCktLLam${m5B5dxMhME%iZy5sUyH6uVJjIsk{`;z(fL~Ig7jz`}9HQT%$#BJquo*KdJd{jN5dYwN|y6wpVdTMgJ zK+A7^GI@^y{(EQgG3a*7vdFKRv;6yKRvgttl)NWHpnPp=p*u#?P4RbFEvxR2hNXS} zAOt1dG@6ivV;zv1K5@8;#-(+M;7L>UXa^mMBw6-x*)0m@#KovdJh1f6GBkhDOB0kY z)q-rDPEd4C^6%QpPvqcp;sp)fPztS5qB7!s)QQ zD{CG)f(j9s+=*TW6l14aE2fUA`dBmPayj8rV2mbsf+&yC;S2kA6{Jo0pi0V`O!s_) zKC94B6zf(|XLYUz>GbD*5gaA!gLeO!2bFEEY-+Wo$y95~w%=2J-KLZDqcLI1h-`XJ;H_xKH{kbs!g4qf zUM2g3JrTfg_Co%3t6pH0T8}f6+mqG2XTjcfVebX98?R>n+-E-?wf}V>B37yD6Co_D zr1B&W)@Q);MFAY@1)JLA}X z=&kiERlejT_bS)r4Mi@P)E?~u?sha^A|A%8KQy9f_M!ibC!5xWVa_d47b; zYdx!P&Z8*8d1~ivWz~566S#!S`aY0nu5<;i@inZ>Ut2x(kCn8n2^#u)0jHdwdRjyM z#F#~d2F=e@UMz3MNJ3pjLlS(nfnupKhkp_j38ckShaNpyTGPCy8TQm^siz<#%3AmI zzIBs<4M#h;BN!Mn@t{C+c+Ow>99Aw}6KKxj)&A~s)gQ#Ed3kB`rJOP5Sj(0;ZHRQd-qn!~Yi*(It%=7x)}IlO`?sz`_g7W4e`^XSKe706L+mnEYlhTe}1eeMg`K70&@`+5bAqt)`Z$CN;Gwe ztSG2p;N+}G(*zB?1y9P{a5@@@w+f!TLK_^^4TxaPZqjkAlvej5PmfPU zrH{rt$gyAvOo~LF+1^^Z_~M46)*@ajSkv+r*R@p|#^<6M+Jg{wYv>DKx9Q@xg;+4Shb%il6!U(+Up-ML28FPa_XQv}sn$L74bE@r`yO%qHA?41l-q*C-5c86 z2hIK2-_x817E(URJs zY|}*TluWd??_4YTf&Hx~@xQ*T<{LP^x2rITKLkoqx5!myS#oBj)DI4IwwJy%ffHEx2PR)qh$uu z?|z=^R9Nito=!(EW5aIMxrx#>s2Fl3Sr%9OaY=<-kBtO~k@A%suG@qghKEennN^GH zF5L^vt1>UbP)bcKbC85W0c7bOsY}izneT%E%<|Va(lGLaqyo4W{V}yh9_1J$fd1gy zdBLKj%%}>#DQwb2Zm|H$JnP=|eX$#r6S$a-ZcVw18!Eg57xf-Nv2a~PEB0&rgxyM#Np~MCDZ@r z(vFzQiru9J3C@|~%^_Xws?v{p7tNdR_FM_o2&_PE zw%lF%Ca!+2?#i%6cUOC})RQmi&1!O-)dA4J_R0sx!&_CtN)O4cl73L!ZBAEhr^B5A zQ8JcdCT52nd6Q$Ty-tTY+93V&ZLAinb5+C^ll0ACZS-6#cw0@LWsLO31H5YErtlj9 zm2oD9k8cr^Q!!tcT&^HexQt>IgBVn(q3Y zJYso6JR|yd-$@76?0%KLeCYA4Jc@(LG<&d~Ti+M;u5!7*$3h_ToZuT=B;lgr3Uolk zy5MSsmXJ#jc^_q~!pHQt& zNBt7lWmOj4C!f=JgBsN7M-d(rj7hFd3=5xgZHcB3q}@x*?}N0mpud@nTlxSIcoHOZ zYfRLh$c+J3rjN4#-qmids)$ZrhfPi^QMI80!vNsI%rG>wmvG)H0Q|!Sf8t7l`~Q&1z|bA&dIGE@E}G9+IRbU-qNoT7YSk7j~OrO32r z`3=+1v>4zBjFNUpWG2arJoh3e8&a#pos|E=d3CV{j6eaJ)XN@zm-fgzVI4!qt{Wir z+r0_rORO6|UMV^Qs+$-;c04I60* z9E0+9oS+c*EYT9v+k?GbY357&e_;+^;00D+qH}eBj^V*x zq-F&k>MN+xdY5!DTp+cI4OrtE5J9?;j`8;qj_oCcOHG29l>QS>w19#9yP&TzsRI6p zfiGLJJXahxZNo$I@mMpAuqfI-Pjv=%r}yy|xarEIZyOBC?fY5y;#H;y2zNVGWlwRF zGI{|-e08I4BUe?x!frrxZpSV+f!?Xw<^)3|g0Sx5S^4_*=(rH-vCE5NX9Gq}nkeGk zGJR@pktvR|h2nqCd^#Q&`;of6T-e%~0Y&YlJMDjSZXqj3qicAOOI8rnD>Z3)P#xlA zZkD~K@KYKn`8^(I78-(r)^nUzwewCl@$(UC)Et_@zc93d_laC30~KPdW#%6r+C|$f zLk!g>WiSW;-<1R!I!37u4~GOL)`VMW#LdMW1jwy1iSU^gT^>-vK1p?WWG+<1SUPv@ zg53I6sWUH~_H{HOMVr+}l^=h9O7h#26pS~SE>!@#&GNZqQJ@czy%*;NzEL{-`G#hi<*Fd^g;+(IHoKW}v!M7I6hTOUDblM3?bgF9$ z$8k}li5)yuCHh&o7~0+9H!|Kv(bBe+ga7R&lp>w+zF9S>YbWS+n3Hx zN!`e<1L*m6{tVMh7w&oa@4R<^IBuoZV`WQ2Xm{?Rj4(d;?+4k+&XTFuFOzeJgO789 zc@8;l1~QS|4MkzlBOxS^j8J!S%}bUnx7q+^Ez>inljhln@UisPT+x=LrdHjcC;!~K zu?Ae(U7!=O@*9*2^#)NjC@2Yzp+S3YIcnA1%U5C2YSnt=h&}L|G*&)Mg+xOZw5gM6 z=m{;QGJvWVKruo78edXM7enD;e@0MuYu-fq?nQIX27Vx5+q3}`xkgCW0gJAdtHdI%VK&JNSd(dYJFU*pzK#c zB_tBTgh2!S$pcF#k-XB*>{W9*q#a4MIu7~M1o&BpBdyFJZC!@)YouNv5b-5}ZU7J* ziONaC6_2vZ=nW2!UA#awPb0UK*W zk5$L$*aCRX3izMwR5rnZhmV6K+BWzfHpq0TBOgzscOZb_2gp;O?saU8g%6}yqJi~3 zRVQ0hdZeB!e@r5G@w{lroP{g`a!%d7}UYeAdE8R*v zFa8796ZNY5M-da_JJH3$?cmz~4pPJ^7UD<6;)GN#1DP`+7C&$D1}{A5$vp*2d+O{i zEpBk?p5-x4FmDhjg_a@H#3~Ed2Rs?%`D+EY_k!DS0X0VHRw%P9BePjf+s#eL3{{XX zUo1DKUKtL^jXMOW!7Eh4Dy|)AnRn$9y|g~2$syO|TcnpA&LnO4fj z3R6kO-Y+@Cr+T`+w$21hP^~ayO|~^u&kf0SZ(3vi7u?v?PCIkxRRX;jGp15IrTT(5 za;G%L?cT!)z9)ajqP5hT5o+9i*0+P2L%he@zGWQK&BP~-k5#K#7pR58fzJ+rp=-^L z+j(wtsyh{9ZO4vQHQgA&?LZb$;Z(L}b6GP*R2R9dI7*yrfUlq>ZVE#6Zc-*px`BJ? z87lfy1lW(z>1+UgjdTd~8^$b@ud0Z?Ub*GO34SfiRjk?xPNLP7WNA*B+y0^3Pw0iN z*W5kaMYG$+|HbemhRWUhS4Z)?;ax88yThEdJ{ohs z_fn*#=Ea+eEFU=redGG?2tCs@c@bAUxAR;j7--x&A4${vHj(Ytr%;3!i?!-g*5p!Z z0AV#pH!1xZT?SS6L=~xR)kYLm5l`7 zk$!GCH2pjl_43n`Ly_`vQt~N8vMCFml@E7dWGzf2neW&zGo&UA~S z75J0%Kh#^f^-Ii%Zi7eDuC(1U!pJ?U5dTym_QJIyACMSfC^iPjJ$>j^Ro#Q9EN15Q zGh7+f9RMAKSaz#?Hkm62!v$zBC&0N}o9X2}BG$za^RB#%M2V0&xMHKax9f5h zEHzoRu9cJrn;G(aRk%;-1ZtCxYzH)?xf8{YCo~7IrC4r0>NoBf^vn#1%3KG)`bSy8FeCa>Wbgt#8VSJZYN6%8rHg#C>`9w!)yBK*ORu{Ns+%;uQNWoi`|n zLw&&E#OYU`Ej|e_*G}IJn6-FYcqjH?)m!z|rHo@h&Mt>TfXgf0-lT^@cUvnJ8d6SO z$UJH4YtKUc*KcEMdK>t!ZdNjR-UG-Km7Mwuc_oehz%kC8Ih)C@kNb_m=epu41y!P6 z%&Y>L?FuBUK(ULaIsu^d;xrlnDy#+B6*&p9TUo1e#n?5uOa&1Nh9eH$<<95~yoP&KA5iLO(CkB>U zcE=tQmvw$j5d=`!f0dn|r{tS9f=vMfj~*rSbHBLRZ2n!?`XXu&3%7^TpOfAk4IwD# znN;t`RKKijN7?LqS$6x7F)IaQ4E=TSeT%Ny!;|JyYhxvgQs{tXTMT)2HEkCCXI?pB z6RGP|zbBi$Ci}`yr9_H`E!LR&m}SWV_P+pfNJH!=e9r$Z`a@FUS`qrRo%2(*mZHj} zgyhCih3{#d2`uCd4tlod{vc}Fjx#aWrzJOf3(fWDbSG;yW-{HrIFpWhll&`b0RPx{ zq0Wv#O)FqK(-jDsHLGwmplTGupeZu|>%t>KcR*?++Geh+5()Ns-7=xGo7cHPjrm?# z0H$)ZuZU>i9d9d%TZ?@HKytv~gaTIc$Y&%*^}xWYn?@&9G&^o(avb5KE7%EHN^Lec zpT4Ild7@oin>cP=tghb!j6xjpI=7bEvbmg1KNJq{2)LxjkyHb_?hyo@n{s(PP(?lX zhP=1hDKo|M2UXP%d@jEv6&@ild?ek3-!YfAvEEKHx)kyZ$Q|01g46;`lHhjm;*+N8 zw)$DqTCJI%^qsbgsX8mnPg$8|)mALYcL|@$66u%;suqRo210M;Vk5G!{_=(YHRkDa(p)OF-h9k^X?s6I_UsJ1{@%V@A0ly7Asq86=Jj(K zG$cEyb7u{}`#wWXfO)f5r2><$G2S6TNhCmNnHMn;1E_OV#o#rL za*e%!D^K>-dl%AW`!iDJjIrZ;_QPt#S%`iPH zAtLiOC{$|FL6BG_XjUcWqB8aF`z>_nNxs7G+NPo>T)r!FOck^%|1JD&_%!rH&Sn8y zav3M|;2!WWYZ2%`+IHk9R-PMpWZE?%JU4P@J6d1qKZLZyl{*g~T)jXz@!thuiIFhC z?o|oS2S2A)=d!o|mZd*nFNx)-b$(7lQn-8DvES}XalPQ0Aq~y4fMFGM6O7~!_?2x8 zPAlPZE|Kfci1I;OemNKB3)m2F3}16$q^cTll;sMU4-C0W+pB!9G7%s0J}~^2>+5;B z-SucVfsxb-D9~W2>|l~H70jkv3U3(sA%3~7*`?l6McyT=#q`#S&PCV9lVG~rYx<)s zIRB}GAA#57*{Kn&$Dhy-MlN`44IcbLRE1kNcP*t@8ZVD=F@mQ%+^YA3$$E*E?QR1_ zkei3PN4dNz{0|i>CbYu%^h2I4DOIPY-$7G@A7IK3We%lFSk-Ac#|&}Z5NeZft$8|3 zcZv|4S8JIsfb35qy+jhpNBU2+rASS^9|D(#;t@gX`V0m+-K(>a)C!%d!70=Ulxq4+ zu^``pwk5ju6M5xVd0wnwFOQ^HzKPB%#e@!{1z74fP+p8sEqY)AB`rTh8ASAO(d`r>DOVgAla*yZh&-8(HFongz50&g8# zJ%UvyUq3PVzHNKq{?=?ZalSL$y%U#oQdk7W2WvRVva2-|V@%gkubOwSbOhPIa5$`1 z*K+U+a;W{ADrjbi4G@s@5Bfnr8&u}aBL#METcf!}^qGlUVG_B;9Wcltn5#{$8QsCF zk|^#7(prZ(s#gw)AwrNqaTk_;vbY1ajSh86AXUOJcCJG(7n}8UF_$3H5R8h6^`2;d}9&{hYex8#=((OnF( z$}%lY`Pis84Mjm4=s{c`O_LHnTGY<@`MpqXz;33Qzp4a`>Nas4Mp==Xg7Tip*E4Te zTHlQ5Kcj@rYJY{QEx=paWo~)1<8k0*5;6u>m0C=~?H+}w{LOe^o=uhJQshByXV;k8 zHgoqN7|CDq+>b(Mct9by%M-_Tf7TiQGF%ayBYT~SOriQ%DqIc2r&}=>(_dg${E{RC zCk#ZFf?laxxa&_6r^iR?@4u5ee;4v>Jh&I4EN#^ELR~u4;4Z=4sHRY_^un5{Lb=W? zc_2%t0D^sCMr#0ASvD5j7?F?2Yv)zDX)4`fo3TaVQ}`k4L_#uTzQNF;K+FxeJ=IN7 z!rQoOEy*!L7@aKUzO|m}NNN~@IeA8Iq#Zv-IatFSI&*eqxnwpBZ5%6Y;9kRb1{owH z_Zxr`j_6$UmaSp;kmwQd;0$-epI%tgScyv@L3WPw1NW9LE1lq-T-zxPbOgdJ?9 zd|B^`@wXARr^er37ztrcf(upIje^PAkYQGcAt;&)yrDW=cTJnAw_syV+6Q=lB@;!w z2@KsG0*p@&5igOhS^?TfBP9fF@G3j(sx{UQg2wPgD&|`0#svVOjNBr{=qiwcz>tV= z+@JzfxXuCw;5(x_xQN2>STemKu98V!bBaZ6t^SaN#Zgzmx*JJ9_%#As#~_Utd1R%w zz@f!?0x!utowxmy<(?zRh@#ZJ;*CQXGtH)6|2|~Q^u1&`ryHA;qCGcg|uYsAJ8m%l~DYF69S8?@QDP33ZRoa zf~pulur%RQZ9v6V-876Tz|=3n+w<=?y0YdvSl~)tUV|66Dv6VDDi6=po;jg`<}}yz z@fXJ^14o^ZMNSR=>V;%()djY>!4?0^rU{gHNG0A1lbb^GOICO7JMVemna`X7VtzE| z{}Lg5?5*O_s8r*-n=yD_DUp%7juXxvOtL>3!TEefLTgCeL)y8#jg54%zcF$rzc;>& z|90>M543%3J-&?^pqheaQq3ZS zOV~tJViY9doUhaJ){KmiGeqr)7WNvX#cfV>!S}<;UV84m!X~hO(Sl>c3d41 z9b7UmIA7@KPq&39BuOndgw~8cfHGKs>nN2GW95C`8((lfjIht>(GgH9q*f$9hNyT( zIZcb<4GKK$b|^GdQPeSJ3s5;^C0b2u9u+dqyO3xi4dmxOK8aBsH7jZ745~i??nES1 zAIogwK&w(2cnhm{7ZlJ|Di{?@55#KzbHv#PT^a(R3;@h#3wPTXz~@U_RhV!Co0+O> z8EYl0WHQ0rFQ;MWq{KO0CeyC|zSl4QL^I`hT#oIJNU3YBTgvT`CQ$ooWbKg<5ALIy z#=d)X!IH#y@$)ewrmAuQ1gyJF5tdB_idAqB5k!El?KY<(XMwv?N2eTjDc(Jn1+)hV zSVl+cOFJq=k=#^zk@Qjok3O@rM6I8Ktxn_d*D{gP6MwJY z8k`z#su6PRV_4Sh%G;57q8*zN0YRml&-6ezh|7q(_G&jn^)@ok@ph-N%82`%-sJ64 z3{#|fVgwDtflV;UN#-U%_oq?fde&fwy$?X5(~EoS43cQxPfqsQME0g#?RiwwFLH;> zjf}Z`<3Y!lhxuNo+3_dL*N5=p?kY&CoDTo9&nrm_pUxaJ9Xaxris;RwSjYxWwL4sa z#i+=)NO+<9rZP zgjWe?u!2>@De}5Fk;~LOg9^R$Wqbs4k+AcU(p{i;zmH$j)n{F3HAP$tTX`0|G5=b0 zvr|qf$cp^!qhK|5PPGl9emfsnET^~Z5L6CZYh%{}*BisB3evY83+Pvf29KqfPn#Oq zVXZE-7bF_C4}I7>!Q=5!S47Wm?ZAAiTDV-nv|g(0sjq*-WTRX2f#@8^ka91VIys^$ zWNVVH@~yW*vH5~f*wO$RQ|VX*rzPbj>{Fjq9XGheSzxt<&pWIkpAZ0lu=x08KZQ)R zzDPJ1Y2ARA=(0YqvGQNh)|s+Pi&G+=>{K$R*a0brN_r5m5VG|&IwnJoW2pUeqQYm+x1ak^VF11-PQEonxdty)>}z?r{n!fxWDb$CnuNd> z5aEfx1@IX1%L7-gOk3c7v8&KwS+ge*=beeLAxzF%5xkNRF}!*QoaQXN{H9QAS-)=( zex?@B{>*8di{Dd(@;!OhMgiDv((U1i;j%pUw4_lsw57^b9w{eYPLN_bzgO>=I}!J> z*Q^hSdP>A?l=Q8+c|3LHJcB^Fytq+@WJj!;9V(X$xnNg7;fwl;9tw!!cF&62AY^?I z*9p+siwT6uM@wfDZAKV8Q3tcZrd&;vXCk|JyeBI{ifx+W&7*cURL-U77!M4~WbL$A z)t99+f{F6me2Blfs%13GGFt0D&LQ%dt20Eq;(PkYwTB~#N3GS z_cDmS;G4?`h6g!~e<<0db=)DWM9vtX5I4r_OcU0h!myvsYtWKPXx3t5U$Dc^{B4yE zaz-l4AmeD;IrO(jD?yg#e>I7Eq(gK0f?_|<(b_#fdsI2&7w2?lj-P9~-AOtEOE=%i z(KSv%Z~!n^Sygz3(%!g^l(k$CjSsMVmE}FZ0JGKXS8^XiliiRUVm!OguEE9l{-rKy z&i2%BKCJ0;gOZ-?m=*4fiGunHWXk%GJ_QRU1)6;>BR7=GeV^KF^sRC~ZXNn)dS(&k zZWrdM%1Bja0jB*@>p`!F!;-`zGyQ{ypFQ$X`~5s}=ebUe+^4p88ddHeTdK|u<@!5u zVd--I5zaOKDYt`1)4VfxlksNM+BVjpM|moHh`2CGjWaFTU*vUuFy)ije6ecoF1-VEYTM z@^AZ;XW)7=iHIFO%qH$`nX`P*TmHQMkUl5h&BVbYv1o8s%15F>H_}I6pexJ|wmJ7H z0Se0;TW(Q-1t~j(g?%AYffU1l@xCl!jdc-gVh zND&V?C=5Dq(j?~wFqJMAR9)IujixU+Dyf+7*jpyhS_=j}YI)l`=H`bixZG~poo*;D zc;P_obNHYLsjY@~+&EHV{EkfIED8jKkhCo4)gWjMC!FZS)H?h9B`4ge9<@`4Z%m%t z%q*zCsN$ErwJhe!PWihW>DG5ugHfSa0re7^ zFnA&sFbtd_{`C@crZdff7=2sS?a^thf&`$S|BB~KO@Ayr(b^|#5DVZk8?!B-*+Yx> z!Q2XP?t2h!UK7CexYvsvc1}TQt~EH=)?4VVnLCvIAye$kMG-^oAa`RnRG=wNgX9ih z$#=bJ@U5jlv+A{X{!*(Tk6Ge?Ccrife;4dVvNsMfxQDxMME2gq zMfXWGe3d9W|7e`Oj^$hrO1$Xb_m6^OcrxCUxjZ;ciq#f0Lw1@MA^g4=QLCi}J_1b=y(%Gjs*Updu8ng=k> z95=LJBP^6$+=H1ZO^G&G4rk0mO5+s)xp?OQeJ*U*=xGybJzV~)I~Ss+K-55Zx(8g= zWeFG=1p9=8+{u-*;zy_7uZ<)hJccOff%_CWMHjO6i*7JMf@`Gtf0N76-Yyc)*>O)k z>G`_+=?VSs5>AwZ^|z(Ir~4L+NXjW7r5iJz3d^! z?W2MC0~}1RV3!ki=PyDPi-i2a$?vF(1N!g890Cp#`Xvtgo)rS`>Yi2YKn#)J0Cb1j z!U2k#iSujpIo0#=AhQ8gvyPAAo0fPOE92%F2dQee4>H?=m3A&JU*jSj)-{4eHBqu^ zBP_tSxYtcXK-fyn8yXuDBiQ-~#OO}o_h~@#<&gD30RC7G4E6?-Qq+`O6%Ea zwTA)PA^>f@bR`b^D>XDFPelX=O@1w1)D~+l(UqtmbW(;cD!4BAz&=g5{|9~J_g+Jm z|3K<)`cWGt|2HmwpJE2GzAGRZdwa&2hiTcH7XN^*GDsW}zw|9cqreuATzjT(hHE#& zEj7wshng3^b&)L4di2~HA@v;64Jm{sLX8vS6xs4RRrkvkBx01^b$sM3Vu9MAs5C*T zAP-M#@R<#NMN0ths)e0qN(k86te|MO@1-(*?yWmdAWkY!V?Q9~TtH~bmPzOPbo0PW zo)05cY;@|!CsN3mq=5Lj!+;p)sUVxv-WI>S_*9ui!M{fDvW|9^B(hiQ8HEc}*{{Rfx7 z6NeY&1LV&M>G=(MIuR{E{VLB3g;@s54B+rx*x7p8OsAJB@vN$AOZrWK9F}S83KiG6 zEBqXJO<#a&#J#C;7(pfVLzy@y-jrp*Ny%0>H$^#4m*pb;A6;&o6=T;<{U6sv*%0qZ|KobngF5 zzyAZC+1Tc^6Xp=x40CLbNoXhM)6B@JvN_~bp_Iv7-D`+8ni3qJKoK;fLm?-roKmn5fUiY!UeVew*WDp@PaG5c5F zddU4#DZ6!&S9f4fx7djZ9hTfv#Wy{ddAM1$_vOc>V0A*&yI?!YMLZ^Zq_- zO0j#mum~L7BA24cJxJ?^^W?q;2|W3yI$d&~q~1(pM`vzw**N~z%Rs93=wquCpmRKZ zOB26)>BjFXyQ`OIJ3MGRcmec2Z_2k9`k(|_U!s%c-=&~5>}d=+VDOj%niwl%f2Q}C zf-=_c%sSexZslQe>lQK2s<+Ggo~z!~h_3UgGk))5=~__dR)X;} ztZjfxsD*e}pqtZlnN`@3AeE^%F3@LJ)n=_Py)P$44TLL%>B$!oBPZ?HoZ$%-Q;(5~ zg^tpk5|dzI0Q+8@Yp`D2<)xSSAEp&IBfIxG7CCton}umPp0vy=#JgQ^`UEXDd`$PN zYJtj^m~7#vbL0chtt&2EJviUzN4xwx(CTsPrcauj?B~Fk_*XZZst*47erU@9@c7l+ z3XQIXy1dwXGC>#K-GA2dYwhb8%9_>4ik@B?<22i)uK!gV8=KMdt+6hNv26CyaZENg zYYiWROWer16y(+PXw0R+uP}zGamVOlwn6I_Drnd&qUOk6n&dzsx*>}>knMk|gQk_s zR2s>8W0I!O^^=-oSSx6Q88=6fsK)h-c$jXj$S2D{$e==vT5V#DO(&8KFA=AS%sg|E zO>$l$O*(711(?B~+{f zR2LmbT`2aAYa27RjkUXMYD=L~bkTlf%A1Ohf8m5DzM3nql^8Zsx`MphFP4;;ng42T zI;y0$puf*OrzyFK4tk8c>YX5%RVilG3TPvv+jqN+GQu*ghTt{1`r~JS3Jqo5Zbp_Z z>p59^6M}o$q!iW%)9cqlIaj(`W_|i@E+^*9cQp#`wch+IcPZEM33dhU3Jc6Fv|q*O z7TGhQyw@MS60C|>9OUve4t0v_)em~SPPaV7d@iH@j5T<$>v>d1`j2Up-_*;iYZb8<*q%)R^;8A_8UZXvMQq6${9l9ReG{l|IMifxI# zwIV8Doaw_aTC@su@$#c?$z;9B(S9Ydz5TM@PVEo({rS}M<<*}rza|c7Qt-M-EY|L< z8Fh-e#W`Qr#P$5gX)Rxiael2|m&{pzi4Zso$VQOk2p*|e6@$?sU1qWg>Oug|;K`#* z&u-`ApTyIfgckbc7(cE)KV@JJR;Vp$Oyz}V4s4}$(urh>an!1tKai%<$8d!Blcj^o zQqr&gjWvlZ9|-Jj1M5!kVXgr=2xaT@(_Ok`GF94tnvsr1)@_|Yd0I{j!gb98RB55| zU$<}NZ*tq!XXZzy$IGs6g_^7$Fv8*v)l|&H4{8jSdme0-x;nk&qw%6~#Ja;rGp07z z;*n?s+hGQA23c8gD!i`?@ zOeqD=5<$NMqAdZ=dN}o^6yWK8@`pRD-gy=ld zCP|=PKNryQW7=O^akqBzvo-$${-Yo&7<|)W@o(&1OGu%@ZjTz~Y*~8cob%KKFT3z5 z*01R|01_KAh^mTGzKB6y`coGzY;fUko&;wX#8d6q>%z9&H+_zkL%R9V1tpOK5E_fq zSVHDqJB9=wqyR(aZRMfW0;*YKsv*l@!uL?4a$kzBkvDNK=6lEBtLwH^>BZPA{Y`>EgURA{a)W-CgCU2M!q2C3z9S}!s9Mu#XE)p`M6t)J+$ z;VfI%)wgWaY33%Ed=rDysA^ zam!|^F9tw%wmxO3JuDls@{e*Dl7hw6eyNe*OI-Iq-^^ehT&bBQ8symj&N}xUhkkhB zF_p~bIkZ_SMJ^6GulFGY@OyTZv(m0A{aVIsXb>r@04L$e#=flO6cC4C;z?_nOHu~L zr!huiZV5@AZA7!V*b6vPs(+IYrLG=9KAYAt4abE7wyuDmnajNwlcwAza*Q=@salq$ zK0H8_-bX9LRObFlCE%b)C!hMI6Eij1pJ+#zr5#hn37wG>AIJJAc^BTuTPJ$lN4&sX zkhqqr7h8orl5fh>(UgkW^;sI97nis51Q(YAaMS`V*fCyQ6IPCMPRo0xc>P&NLi4ELVRr@%_EZ30j%!8AtaNA+jdq z>lrO^hLR%XN`?(cEkxDSYV{p^`6R5Dd0eL5QYtB!yf=8Ig8#Os}26>%;H0jASX4!=d=>*ky z9JWv^XUIK8$VipLCEvqHle$K2i|KRx zSFMXCGx*D$P!ry~>06FdeIG2IZdy-yj>HDq0!hnrX9eH1_n z3Xrm>mp%DvXvlwJ?ju9lG+HZCE#uGZXvI#p0 zIy?tETpMbVXu)0?*|+k>@OJd>CxDR1hYlE8obi_A_Tv?Li@7mS$mp+i<4Xv2Ob5yn z8|mm$Jq?eVXqoqr3F7bkPruW{Y#>sz-KlVLn!5a${nZ5&B-Pgz++KBPye-VX9(Cdv zKY3!v{aU)m1L{43CCdWL1ss{`vag zmZbO4q8`!1{%9Ll`59h3Wl+wVU9L1kbRz=k`ev#5?(k7k8n z6VH(XmSw-+M$)d&@at~IDIIBOFDa->|6s=i#5~n~A}wY=a8PjuNlM2)y06DG1YkDw z(b5RT1(%W~l0zO(MafWtHIAEJUji>}05_F?>4v`LIDdExi;A8)#yZe|b!rn$*NSux zf6Y)a+0p*Nbp5i)+`xAAdil|mChkD-Y@VKB3z{i$AFWNEt~I^)*{faZXXbW?z)R7* zTnl(~d+0$8vW{jG#eUG|H)KrGAy&$tM>Y13X3Ddg)3GXePv(MqPQxzCes|L*oj$@n z4~bn%iT&-j_I3t(@om24ms|<`1|qVNj7jT?krRgwThF5c4wTbtp@OUh+r)@xIc3!8 zh?4hmefOvpfJD7RQfB&2LV#1-J(a1&?fV2v{;vI|Mf%BjSAEL=CPpAH(t_9z?7sIw z?Bv}KHVZBLm3{;M#mjkIp`fUn{Yv?vyVmuUoW_+tb}Er6o@+SmIqST~0V6ltSl3#; z%?4{hVx{8T!rD(K>~Qen+}fY|wQs|{SWNn|oIFP#nZ??je=KQo9`~}YIXwmZj}zv1BrCGZ1YWD+d-b@{XFzNd zIsUj)aSEAy<@QlRU-vvYH_F-TtI4&23!h;j1e_V3@;_3e+sMRqTX_$?Cj9qzW6iG* zx$-5)TDBD)gc~>SO!oL`NBb$HX}|LeRQ>Cf+g&V{*cX^Rr?QA1O+Iz~ zd~$w9fGxfV-k3^AB5hu;y=dMw5I#Wp6sCXejq08Z>Yn4^*!ND>tQ#>bIibiAWSZbn z%-_|$Sp+jcOZ1RJOaSf7G8-a3f_R z2t9~4x|yfckPYw@zai(Sd$lC-BxFD<3~c(aqqaVAt~uG%M|`p^KCh?u($%{@^#0nB zFDO`ava?T z2_i}rM*{VE**#@OM7$KTVu=)bU~Lr4!Meu8YY>-7=}SPIjMZcjq> z=GAZZ1?0cGG8qO}zB-UU71%hWhZes)4TLFfe=zd~3SyYrK7f(^50{E)e&OW|^~m$0 zTXZ4csO{F=Jvl|^M0sa9P18g}edn){PMG^v&w+-W1H1j-JsK4SXXBBglpe#KFM}kA zwy3}jfUYLdTsY+pd{h_zX51@od-dwM<#?~oR*!}vtvikWE6JLlhb~?GJBEnR9&(0b z7Q3Eo9tgKv@N5pNlJ@&Biuvf~_Ca#MOX3`Ncvw;2^*V9P?S{)eK!TE%@&i9$a?8_L zUIkKbOAM8YC>X!br4pk^u#f`=)bicfw-;P`hTh32q!2Ej4g6XLP<;;Eh)f7LFhxH7 zqb^LHo&+l6@2Oz!NqH8*{Y zHLp?faP&2Q?d1tmcL!VE?%CFblSpJjsu3ZD9w#=@=axaj$>)kW89L^R?!Zf7QO$$$ zUsH(Z-OC~n@*0RRAmYKu{T6=F*c+(-k76BWW`K`!QaBVtr-sJI# zrHh&toOtmvccl)x9#OOde{yPF;sn-klBUT9_(Bdom69NEl@%h@E#k1WucEi58cIYzA@dSr=Qo}wS3+e>jdpY?m;EFqm6%DtdiB>%NW>5A0FuILN8APwD-x8RlSG-h)izDqSH8 z@Gx{-2_%d(|3-d3;?lL|tQRmE-)bYq!a1(!&d*qtU$IU|p3{cO`BUc)b1eSr&9PP( z0(@C)A-9$}@9Y=dyQ7n;e~2qwkbdYcPJKZ8T>Lw^^4-V!`?VbKS*N#~>g!e_R_Yn@ zo0>|e+~PEKhyEL4ou724{b6-ur@^KPa_CLKu2InEs^oyagJC!2+jdZ2aE-bsCiJlx)-gKOi*yH-6`a|Bg^SQk+NQnC%qv*F;%`pm0Wmvxd6#&ppOiMS!nb&3_bltL7KSo=|%t-8VoFWXn4tUqwHMvCF zmKZAQGa6Xmpi5A=A)}dmg8JB5*|4nnZ}K{5rJ|Wp)pDZuyFsy4?9-MrE2ZAm({&yf zY|p@~nrE6=mx69(TU~l`IpoUQSpLdf7vn7B*2e316(Sujb@SUA@00qqsQs$O3yz{Lo#hc{&863k{gHAwG$Ye@X~T?PYiH;Cm$oz8x+L%+oo_Mp2WMu2*H$V*0Gp z2@E?9L$}m8YK&S}%o*3KDHGn+s}u;cx5@y_GW`b8`W~-{Hwg-c74WV{R#lo(FheKy zYgy~rD4o~(P7x@W;TAo7eqYt!BsaDRxCzD<#cxWW$V%Q2K|jB4tHD&egwxf(5L%W| zbS|7bt5^SVVNwfYfUeLzi7|(2m9T((t-@R>eRMQ$K?CIhxXVNO7pv}5p)$6%-h)p2 zII5Y0!!akH~_`sn}lwK zO_htX*z}&_j0~e&M~l4A@VNK&tCon65DpuaO>|9iJbdf>tDM8Pf3LWEh1fmg-N$m8 zbW3xdf+R@qSrLbKeS7&ES8eOfuG%a&&3zMW7x%aA&MvG&!ZAFY)0r_^Y%GC{58*Ax zDvB`c|IdoP#qnLJPG~`k6j;r>CH2A~_J(z*no|vXLuJ6=x~6I%;k@GvE5I47y2oS3 z%hS)qb9Ojuy%b zG16)xhK${un|$}0_qo3q84KQm%};~;#Im%}hPn*7$a~!5UUeXR=#{t^^MF7w6a&Lq*nx78C)?;c#3@LG$zoE+4P@!H zr0h@`gR*k~uq)CT3GX3pPfYL$B<(1kd_&A0F`j0_i!gDi_+YI-q>Cv%`z}2Ty=NSx zZ@D!cbs4L?@N-Z*@_d$weLWg|Q$cN8x8$FAN-l}%c{3H64( zMm$t@sN+*py?s7>03v!x2462L`K15m{?Pmerk@%2^}{?qjX4Q6^hlMP>GzKBW*Bwz zaS9wp8YWa48sM~uO%LU*A(Q_oBT;dI=%cG$e`adFy0RB30&(tR9L+&?^?A2qo zXZa>C9rZ{;y11=pWZQSSgh>@HMFNMa%LtsbZ4(9nvjF*j?9HTxd5~|-u;Ys+--}K0 z`dBTE?x@s9l}mOFbgGkg$RQ_0Y3Tetb*{SgcMoLKQW$!fps6>h;;`s5fW*L>b&aK% z*>h$ElpvoCN7xxHaI`Akmg${(zvxvv^-xhw^{&g;CWbDM6e^xF09$;F~;#<}{BMC@Rt zyk)vkh2g)(S;W9%mUrhHlwsmj$OGX(`376}WJ1on=Ag3v5kebbfu826iab_pmb9l z7iCV4bU2+6I1)QotlSOY-5*Bz=Jd-2l>;=#-&p}njH=(z*4WCd#cwCiq+q9O)3#@6 z??#+Nu71e;AgMzLB3yO8@P$rzOBjkduZh=WEHy89 z9SVN%O?1J2oAbT|+&Ye~E8k-0$GmJ#f8F#P?;3pNAMJCBHag zO_KQ`*N z$3g5Tp`rC^@z!fPe81>ZP8g~LR)5X2@saG8Ekvbkm%ll#+=q3M0uAke6!$^;rc)Hl zb{ynJ9Oe1?#BXYF1ZS?TgSd44J|F%2{zp5%g_nkdze#IT1+MSUYq3P&K*k}r_>fhb zgEP_vZgAqC16nT&UGLUeeN8BMGG*DHYIzeO6T505JrMgqb>EitlE3OLPv^*)+0_BI z1R%y0xX7EYb&=+jk4dl&Y1k=|Ni!VMl>sA0;T@TT(^F>nsYJn6v@3O22MYHY?X5Z# zvyW;LjMR;J!hOB5PYt)fDHKt$umfKs`|p_E@DBCu((X38GIOIms%nI})7e!Y`wt0W zsgf`+EXa#NEJ#e>i(xLL@v{@tbxJ^Aox!dot52!+hL1J-5i%Z=8sLayv2At>!x8lh z-pQMj*gO$A%n6DBA)+JIV&Cd2kEm*zW2i!pDuHnKfQRjx&XFX)AS;!Bj?}`2or&Md z9mG3lL$jM3D=v*~U9BNp23q=&sYD+gwtzfKP6($^;jeL8TX-?TBg+@rfbzV|LBBeSXTW^2K$G)t|x1G zTuYiOblnhxSI>jF+;e}OMNEA3M|30KDireY}G^>9RC|1N~Y>r`kAza}8HpPqtCl%thu2R?1u-Apm5H+jZ+TF)GwC6KruJyZx!JYYSz6XR( zFriZq&pmH77qQq-xF#Dood_-!Qh@k|Nm+hBYJ}w(DL$F@PWIqJG8^YerBJPrFfIw* z?y9nahrCWvYB6Z8Ihp;7thoQNsY9v?7XVQ_aG|hykN7n*QVL@5%p`RZ-;i?Y{S4;G zBF3F+@ZLW|}ryF1C53}`MK>Irja#6xTxWtv!<$GpkD*C-ht@r(t?j$pz0 zHvv|MmtDRlSS_suZ?LUjnN?d}JNHGsnu#U;-3eZUo!fIHM8afVBwU#dbN!L&;-lws z)>1zPV439WEF?E%h}6MS4D>TB;!kc_A>w|3)8=>En;W`5Otv=L#30MIay4fgo6>c+ z#%I7?V0OH)-%QmUrXrLL7J79bz;Q87_K@1`wrOucYDhey`>0+eBG19^bf$>YFlBMv z@(k^@HKY#YYZ3A}&>G>$%u5Wf<~V3Rt_yEE>bF`t1h#%U$nYg^`<2F^PF}vf#(}DX zZ|eo!8EA=So`$l;r`(`h0{xpubqgMQrqxLjHuVThFpSuaQnEmmOGCthZacP0nRI~Z zVtK0z`cY_;-2${a+rPHC=fVyDCAis>Nm5ZM%je65Pc@5^t3rxXpRB>jXVGKJwBNuR_F;kZ_Qe z54$oH6pTckBOhmVxbFuZ!IrCSV!!Sq>PxO4(LHqoa&1p8R$mQ^GFbu%lXv0N3Tt7V zkp2!VUT!amaIfG67m4xXJ$Fqjw zYfu43Z0g7cDgQXCqSrJ5K`%I<5RIViNWDO3>jl<&e}4jL$SVU<$VoF8EV9@*mvNIK5eo+{!sV{NT#Um z@S?hayd$%jpojvAv3_ zy^?l4XC6+?1bM>R;TUjnC?uWS;M2zm6Xo4WwS1-#v3D?k!{*`Mlf!&&*K-}P=lr(s zA@=o5tw;SJ*U-B5Z+SFYoZl}{lJ5?m)te{V^bRoLl74c=Gjj6$RGvW~_PXtR^u2Q_ zAnmox)Xg@i3l^1ZO%Pm*rp%0@WqT=0P1a&OXF;U{g1RJ+;-)B+{~0Se_$-K`_%t4L z2oZ1}WXp~8`!K!Juu#>az1L&_=W2!V4X3zEpctf=nw zJ|GNN)vo;LIrkw}Tl$0xXcT;OKtsmGH)ei9S^+A*3v`EzjaqC|#29aO%A#ZR|L?2OHR-I^MuZN8DTAa-n&>pCP#* zM`srisun22DOvtERmUazkrJKlYuyw?^mYpUN+3Ex3g$dXJ-d41xGwE=pVImJ%XwbP ze@Kcclg*S)B$u=&Nxa99YHP(tG0_mGKDZt|8(z_!^)s7%3lzKt!4V_34o2A@tj25%E`FeFoKR;q` zQYhu5=Hk^OooH=PtE+<>OEgztmwCFD4c~>7v^}o|>qlO`EE}OuC4pS>L+EWYRIIBI zRO-5Fu$pN<%QlR#(DoM`eErMNBmS#Jk_@aV&(T<8XN_!wltr@0X%ICuY8!bcw~+K> zpQ_||x2;5|MaT_8nxIsyo`JPz-q#6K8EZLcD^n>?C)`<~XmwxHWftZlQK~?;~ zsZR+>-`B$W0kCIl7QMa&!PR_}N;fLjS?rI3uw2?UHS4 zX1k?qv_9oN{0cK%5Bij5e#Pb5?GM4=r!~WS`VOvW6s(K$C&atkO3weY@NH(v__T@E zJ)NP!WU-^gje(Xr1k}X$rlL!yt{%^`X`j-xniKZ<9w5BV!$kdY)Rcq?QY!7}%wX!c z<*4V)T_qM7_*Q-w;JXeys`f0mP8b-?V%2+S?%cb{$}*qS@-+J2-)C3#A2sIGI~}x* zYAYOcO2#soLoP~M_L=zig)>L<%5Ym#Oz798EP)=l1%eQU!=4i8LI@5|$SEbb78464 z-(e~SzO@0a(?jEXEkep5Sybh`GIP!lITi0TEp{&0AY5dPF{g>itBmQIC`1hp0XD@C zpC~e5R+0cVh={{B~gPi(w@eC5D@ul}9-x%?y5oJ;UN z%y`-+wtXdQL-cD!(5;`b+V5L?vwYy_O%?#UWJO>~Efx6MWI;P~lD9VCnJ`0sW5tGO z2qvk!(rOxDoZHlLk_)}l4GEJo<#uxAj2gQKvW+{sx!DG7 zeT&&fGfauAVO!ZE%%oE!ftj?8n#-B?%y94NHvh!Co7`^Xcv?<{9D#ODax8MpuU1lB zO*#bBY~x1AIt*XlhL^W|V55_3IZdSbm{qAuBVDnDEFn=bl{)OKm<1YkhWoS&T~&^> zn7O-|L9Q~9zncmldc1F=Df<31cx+FK9TGZzXAlZ}VCxW_Z0jxEsD0$Pa_2*@If4?~ z6}nVw?{6Ma!}7Ns+axea9j*v&5iZS=xbbDNY`*q7gxi0w2-Px0tRffjdW{RlI$yAbfz!{%WNCyOvU)ZuQ>4A9Cko~g(gHJR2ICef7aX}OkO zdupc4R_@pc|L9DiH(ZdHYLU4oR?bzv4r#QxD;TSDL*zw)oZS4gi+s4qCUqbUozU-8 znUi>m2ywDGQfL=0r>noy)zDmAXm6LVldChVZ7R%SO%CxMFM?jvnJ8Ya1bu=rL^LiE z_}GCAl0%1j(oZm3arh9U=I734I1NL?X^Gp3p`VGByPhif>bBZ32K?%}UG-E7VZOBzGy?B9 z;U#5pXIS29hcttmzx8K40faln2XW8VWZRuyJb0!rUAx{ITg!fpa%NO$*M5ioOJ0N| ze&r>tCs>EPWuCvW6tVrz)q+Ei43zWF`}&N8ye7Z9JI*fW8B!Oj=Rj2JCZD|j_6=qY zrczPE>SJxzh1uE3q|BVYlFUqVJj#y)Nlyj=5Jw>H6fP$mkQ)l}Rkk*aOY$cV?!_EC z|2(1JHDna{1z1{Y5bu3DM8Z`m2Iwz|o8+RIsLEGEb*9E*kNxmXU`6KvA4}+A5BHAg zi}mnY;{Yi}$n3y}me6zyv>}WK%e`5}v~?LnAyuSbvdxvVh;gtKLzr^52R+LHpdzC2mTIn*a^BN6`Jy4n zz`!6;kqOrc@G?J-%f=JgnZq7bUp}0Mu8->d1+CxC?{LGQRb+5vfA(KA@bh3}O7&P3HwSJZD~fu7yNiG5&#LV6 zpK%B5dMJs zYY|I1)_iAi?Rf&PQ~nGy2n}(*O-fR zn9_3_DG<8;cg<2Wm9-lsQ%t_j{mxX6AJ+@WiPD8Z}UrhQPq*Flc=m6+lFs%&OB1Sxfl zUKBdtp!x!LL)|vWS_-P4cww{*M7?ei9H?!4)Z(e-eI;2pf%fMQ9&aIB%D|fE!Lvo3 ziv(vlw`@c|GtJU_G8nzo=X~Pdzr!iAmG*zIcYA}OngOpqsXN}7JDmUQ^XuOF>-o9R zn3la_k1buZDShDp0f@L`+Jz`$(8D%Eg0|$6Fuo|D#`0!5U7VWqGn^Y%EjpjR;9f_m zpg!!GJfgo>Y~o%vu&TLf*!C%!Qu90vbz!=eZ%V#$*SFwzLA68pij`Q7_N4urZyFC#0sfE7l8z7(t30HF48$+|M zX9-{Tn`soq$7qN%8QyTbZHuc5B&&sERe|~sJ?3KBfn-B5x_V|=XMNUXg#j8ms%sER z?yA6%cPT_IZd6N!2BrVKXz*J{{>#((p@tL{SgHYSt(sIq?7L@ZaR!L4!lvtEzTXSS zq^TS0WqBxb%$%oaXf2eX6I_s3tY#@|!B)!+=OvuO4jZ^2Xk8K+bk8l%ZmR^IZzxjv z)F02Ytx}t?-2i^A6o|4c&4PoZrShe3s(ZI-#LgD9NU6WWz!SSOKErLc3|78yg?!_yU9VFa&a-ufjXvoy8Pl8)4*^PnCgbqJ(2TLt>(Wq!=Njls6saz#5RMfL_n2QhUw6j_Qaei}`+2)$@2=y7zFCXz2w z3AuVP_$kTl$!OT76qXpO%AoLEAtmT0I`B8LxN5_fS{Aiueg z=}F?|&%#mEtl~guDZI^&gp1Y5DjlX{o7Fs|JoqP)%<5D8 z0OxO++E(Ytc`sb@jWxI^3ZGWr#lC>D1m1jh2QUR1@Bx$K)xlFH9!yuMqVk}>xpwoV ze27FT`f^ew=tw7sCdyTL?=aA~YfxSO6gAD#23>ySBISL92?n{D4i#EZ+x2|py2^kp zFNEnULK`Rwk0~-o0N*{c?Fa$tFLOI{dz+7N^K1vR+=@)eH2fpt$G~2*!Y$ooQB}=A zPd5yu9riTzzXaSDHM*W6tu9zmVQ% zu+{lgc7%)iwI)Fgtqv6P`!GWCX9c$lYSd?=4UqO22l(X7{o*sOtj2pl^Bl0{=tWzac&D3~!oL z$%+#HIOTKx{r!tJ5RGp}TBmb`e{Q&Ca(zE&AM3#Ep|z-|_B`x>@w2!@4P-AFNp2tD zCJGJ8frj%%>9#qUb5++Xwe%T9J*>ed-@zVG$7N}Ae50+!=_=B;BGZ5>;|1Y=h#F-h zZNr(t`-_9Sjf=}I(3)A8$3Dg80n(F((!)a}D*;HvvHB~u&GY?@&tK6}K;?-UOkQeR zQq#}~O<(MC*=JJvuz@2NpfK_b{$P`2c?AhoPQ-N?=8;pxkNd1WAv`;gpn#z=DKeQ` zgoeh6vP34K1bt`>sL<6b@$U`iGM-m^%~08c@yZ&aK>y!+hfkL#+=#r}gK5r!w$atG z1Thas#J2!DGs-mgm~rh%T*m!UA8c0O%e2QNV5~de!G&Mp1NJ2C0GPqajf6k3bbC)qmH5S_Fc&{)cUs68I4Nn81-iP?#_l?EmTQ zyWm`8yC|VDaP*NhEmrjEqsoPD*O{x=${R}^MtM^&HO{yjI*Po+1o;auUt;Ms2`VB|1WC)7Ds!^L=mu)|L>19 zd6G9EeyU;{=$RrW2SAHPLH@Nqe3J5(5xu&Wp2R6!p4pX?%9VRgvg$L}u}>2x8Q&Fd z+x4%=$VJ#`MbtAOn*7|>?$K+B<9rhLn*HOpg3}0}nIu4(ZYZbqF;Ty@_lk+H`O#i% zy3p_$n_SMtjkT0=49YLqH^_~#b|KbzQU4dw#tM1DtSNU(JPtx-JVlA_NwOM@=WMd9n>@a(te*k zH#U2-(7&@%;n|}*VNmyo-Cr$qCNXZtCS!Z$kF{&s&uT9Ffe0L)W4DN9pqve-c33giP!^=c?3&9Cp+SA`FZ`dWly81mf; zpdul2E81}&=|Nx4nbrWHqBk*R_h@Ta5F9XEP-dX{48ns_Zav24shp`q&w<3txsdUz ztFb1ufWrJW?cAL_onrJa*KH05xA76hl5N80QelR*RHLk%`RJf4L&6Mol+}serVs5c z_ve~Uar8EU`td+gfcx@$W@`lJy2s*-i& zX%4vtPYhb_G{X8awPRV*Cr(+s_tMPn$C_ekX0W4imk|`j8FNi3MS%+NjaM&t#a7`uyJTv$( z>y*HE{vEk2??N=(d&?*gD!3S(C#`lp!NP?_Qs;T(C%EVTI@s4VRS-LS9kB1fhufdm zS7du|l;o-%Tk`S+C%v^pW6v4zO@^T4Vz=KxH53fT^4y(80@{-{OU6PWA`h=)Qx3W1 zUIWSKleXKIgVShD9ZyroH>8AHUb6LP+w|8iN?ucU1fp=ET2@1i7BjY&{W#Y^(%X|4 zO;>@fUD2gg?pG9oNfGzjA6Hqqns=S)*k+w$H!~>xANTCZmU?Sxi>R&dL|5<)`U#yr zqO=tT=(>}4;Fk6li2KjLVpDCrjs!~jRh=(I1r9`vkL{H(NH)d)8bs*rJ!H2`HM~2H)x{%@zV-{5<2TMyk?yOSRlF~pnCE&0$kMeFKltg!AWpy=*f#;i)Za3 z*GlO({AfrOhj-9z+>f(C*lkEyHs&VOHk)Uomfo1je0E6~m`UkKEW$k)eFo{FW~nCK z@!hZBw+tFAw*g4;Ji5L8Caqb5&??uzEAYPVUr(FZHnoKnSxXvSP5Zlg(q(U^|4%tI z^vmgosu#{ifyv|wfVfVEw_U^*1TGeU-lq*bd-}Yr{7+(OT?Q`j#fO4<=-B)3!b|i% z32TZSB6ou{07)djc~m#DwmZB@GaboIG;4p3(hU{b`IzT1&D%j8XSE-79R+T;d9-~M zxcojo?Z?^k4(Ga-<|_Q}UCB${5x0plW&nu>wmJKSgoX1Z)5cbAH4`iP8CeD?ZOHVo zA`<%nk8(BAQ$0O)rtt(M+7s<6AQbjPz(_Th|6}Of|Cw(8IPNfPbJ}Ke4r7>^Gex0o zHfA|&&Zp#jCdY21az39;4k2^OIi!*fH**#u$4Z5eQ{70V(!O8+z~`sW<9b}z`~7-7 zpVT8saK=`F6j4svpt-IKCTBobaI7Jk(v(P9lvPQcfLRNxJ7-ni8etGkW(`)}n&kmP zN){F5(_Vd~pOkrpRpnY82!8Kkg=YPD(RRz?J&SW+R<(C58)(;)3pKmGsl0t0OUc2^ z`$6UPuTyAFsA%}d(=OBV;BKL%|JUK>t6IzZHx2&$`1dlpr+g7d6g3||Y~)QZ z7#8!c2;&ylDDO|nITv0)5?UtG_JyH76n|w1P>%B@2qP= zZH}`8&5vPLn!qh&R_$(FqajP@7WdYt4MY5KbZ$6=RovMmPK(qYHqOUct;r$JaFEjF zkzGjHV$oAF<^v|t)a(|`isG4kaJ1xL_;=9M$xZKju>#c~#n!&TT?d|UxihM~y8^(m zXj{oYKWBCQgwAuh3`=nE_T%>%mx@`ZQ7&hddN}m>{nchz&6b{m9n-aZ`;cx_P?fV=$x7u2TB<<=RY{E_RQ}t3!H^T|yS( zV3d%lYRxHwlV>6iCbVW<9!#G5H1WakIGd9adgj%&Nu>dh)lu-1Hwz>FkHcyrW$ZS> ziWPWS8a7r0Tj6%+=()NysZ6vcNKVQku@K2B*g~3SP_qlxjQHwTYqE07k@*N0$oUk6 z%~I*Tsv8t&9n8^;!6j_E;ICMj8R)+u;(IMjVf`{iAXU=ORX{=1CHB{*h|jftpY=Rv zz0Ye-OBuazCt$)*Rm^YyA%r8Upf)EJ*30$5%%LA3l6y+f64#PCBI13uyQy$*B71?j zcRqs~URAEUb|h1lY=tan^mhq|mCoVLC3>$oV;?>uiN%N`eYe z<(PX-4J&qaezE~Xh7-mr41O~>5nY8$vDBnJ)OSeLq`yg`#W7nRpBib5dqBM>^T3F| z8!D@sLkg++JR|u8#Sa`y&(W+>9=Q`F#2C0D-BDA1&z%b%rQ!pI&*|*;` zSMhgzx8aJh&;!$HCJe42S4R-CeoAr3^Z?&qPk^5*qbl{JiX1o+>|C{oNbx7n$z+aG zr!NpyrO2)A@>(V;kY4*}#Z+<|$m>W=+^wqy$hWG3tQ_PE8$<7@sjE`*?$py)0IAco zsY@P(Ng}GB>nHT^W`&omRgFY?9na^Q+Pb}l-HuN|`MHCy|8|Da`?!?d5_s*W-{`BgKSLM}(i=sHHs%ZMs*GO1ZZ8y1|FKiHJI-%NosA?Y1N zd8~W7V}>R4HkwOr*tb-04WGYj{qgrRtG*jLKqb##6b#!conuEsr)mFVVzR7o-eD)2 z4eLe&9~0OJ9r4DieBNZgWI&<%m0~fGr%qeNKy?6HSY~s! zHl$7|U*LvyHAgTB(K}-x?1!LU+ zmvrZzvrKUA*X3jfL{Bk_=yV1$ECQM{?D#nFgZZ5c<1=}6>M7RTQ^lsQnXucxxKO6s zyq7|YiY4uzd`e^&C`n4%yypMpbLJSR?Az-wBa>uj!q?jl1glj(`%|>T*QnXL#H!G4 z^Jigr;Mv2<|IR8+MTi5C?tV1=)fjG#Q~HQ|JTr606l0pb3Monk$Qp7ubsI2^Fi^A{ z`atKBHiw4pL6fr?L%7^&Q?S_oqqI(iNpY(8O=~%RMdJsEIlmMg)`cC18e^mG33Vlz zjoLo)0Z+p^e!$E$(?Pq@Jv3%Ge&?G=-uEcgyTCV{9${E33nMVcjGACP)jSXk*Rf@p ziFMw>VWHo3C66ohbUex5`e!%AopY&eoWeGaA zkcq`yz8;MbqPs~$MxZX&+1QG=e&Kw541GUA!JP#QfKkTtiPI(H%Czi^Pr3=50Am{_ zzZ33C{l!EZ`>896KO2)f;@&pFQwTaO`N*YvveWQ@Nlupp^IeW3fL#&?)N zsJc*T>C2$W?_HM)jLu#w`1Nk?&6q_^D>JW9eO!u$r0TsTR6mM&tUN04C`EHrSSBh} zu>xPA5t}ILK<7p_3R{;u85s-UQwe)ouv}tB^P>`2kwc9wPw*BByX(dTu(&XOWndeY zdTULbe8O%7h1n{rV}6n_UcJ?5EBc;((QD)8y^fE5RnKs2rf=6yu>iwoN`)=dx!ic` zny3H;1UIWr3qB}qE!HUBwv?|EbCP88m;=m{Q=x2aoD;vkq<)e5R~*Aha{Rj@xo$Hd zgbDNrD+hv=DfjehLLEiE@BMf@VDR2KO^jvlhh|5KB|Eg4R zTkVBTxBdf5^r-UCG(b?aYq~*^1~Skmtfa4eHXLEg(7+AOshv;HcKUna*$wMEHl@s9 z`wT9dw+kjtJ&6V7Wxa~FcnVR5uwK*B;GDUA>2*}%gED0vJ+eLPiL1kpgO@f9A8VB& zN4Ts*Z~bvrS&s#^E($4e-mAqfJ$m-K?u(Ad!w-bjNxpPVBhlpjkmP4q=4sLAZp`DZ zvW(qhMf}&(WfOq+bBOYEe&0@j+$fmveF*I$e%}me{6+K;4)~{nLkYk!j&!w;n|r+h zwRa%}tS2Ptr+XqVOK}xi=QHUksUrzYnmNCnE_EK@=o`o7C6+KB&&`QQS#zB1Tq?EG zz2tVfmu@1&L(&5(m~_43t0&aq3PQ+nYVbPuuos`qaewvS;oMnJZY;D{2R?)pYJ+C<3K$`%l=}N_eie68qhrDR^sP?!LJ&upfcy z*Ql}A3Ss{bHIA#ZuIZDgt1HUtBVQ;^_}1D_ij#ULNk9=f8W9Bfx@4qV6~!zOX_naV z@RQU!B}H`D<0P3j=Q%f*HM8n+vgej*K1t6J<-sgKFZURah1(nI+~$FL`DKR&~BWTu14c^#X4?Aq4}JK-S5RTy{*s7Pabh9o_Gx&vm?M9 zH`qpW{1PoN!Z2L66!P{ZZw?PJJjqG)u?_d&YI2H8y8Hwstr0-k>i>abB5{OoHihD? z!Y7sN`;mo;lMC?tlHCdz^cbjN)xRo}@x{QD9*-9yTd1tQ?!J*xg1sC5!~^T$gQbY5 z>AgFs1RegeDluCu$rjLh5BdScYx`e;v4M6o3O~BZ=3(VNE(5M-6ZR7~8 z_WbRaxu zvyBX~8`iyBSxmo}<$>xLCKL#K^NW25kQN@z;lG@kthsLFGvwfvQl~U+rey3oM^r+= z2}3UYZvv;z1pyFauUA7Ba&oH5TCT!1fG1c5=AGn*mr$J)OO)A{W0Z+NKF zroKI|VLg~xJDBWOK9865^1+_Hf^}+$bhOy)OYpAAxa|kpkqLmg^zUrhDHXu-0TkG> zoiLSM$c_D@Ljr8y;#Zr;yEjQHXCpd9nGirah0PZ8o1OXnN+9fVqVAb6m-(9$+>x!w#qW+G zb!O6W1m~ELBSuWkYEi)%2p5H>7>B=_$94F(O&E>0`LMbh zmq*Xe-fN@*ttCkB|fcyo4#V^kj!qp)FXdEQbvu0 zSznYSQ`Dws`_lMGfV{W9aj~6#fq)28b#2b%jm5KpnJpQ}Co1!h^ zFq;!+9fZhK)acg=FGOgMH;V!E#qvb?5{?>y2@{_uQaZcBh!%N5hD_+$1D?~xulfo{J91C!@??7HM0%lKC(T01z# zSv}0(nTbaO699y(&q6{X5gx1D@*--`@57}jVlXHzA-`*UWjHK7dwlQmPfe3B2NU$x zdSq*&%(Bt7y>M^mvsDG0n00(;=zDkDRR9iQTPvkcf&A-uA);aZh|sI&f$rTr$>~}^l7`|aGS)lNQW#(us&NB zSxrs&dYpT%>EpJ4Aw-lYo{V4Ks{htF`Weq5eCtCK&;?mNnAk)lC~@d745ln!dRje1 z-77UdSaO)l_kZ`9WG7bp7j4Uh{;*9;m3q%IoA+Z&PnN}7n~Aa7m6O-h)=VA0v@4@U z@$RIF5FC1NMJHc`9D*WCOZM9$BN8Rq72^;Z_VVg-{OR1-^qNGc=bBfwc|xPzbDWaU zD@lechu%doWw&T*yrVZl-?OTl7^kSp&Xr4d-x9N^NXWe9y__X=HRA6vb4n-y681*ajVsIU#}l8EqzeG-<5!e zZZ(D1?_Ya`m)!C@0v={Lzon-f$Lz2%$S&{5Xi zuWp@3amue7S8^jQbG}I351!jCIrAY%JKIjLSaA>X&B=B}Udtn_IEaiMWJ3kIg@2e- z9Ym>N`cOfAP}?DvUiZ!7n@0}^;leP-k*jfPm=k3S)`aj|9wCHD`ZdmLrN71>=!>oz z#k*za+NDXbC(4k^bfOPuQ{Y5H$9dFC+O!RKFhMSe!*z?4tg?Kbb=Oqi7YPtOos0bY z5NO1gCv-=MD*_)h^#D%ZsbQrnDp%V+Y z{hxnps@^tr%_|)~{HqMZt0eYgy+N;k_ZE6dbUd|EXL)$AMmwEn>tB?A3GIjXh>K|V z3wKG0KAD=r15DQ8cuOpkx$qVNVu7!_A-kdb^if|<^aZF|T0<)j5xR?m!+sg3K zmSg@0VA!+l4|lmAO-nAk5V5mP*bq0)zOqqZqSJ!>$)5OO*#6x8-G(SzxE)MNxa9lR z@TXzFd`*wZ)SKk~{g$ocQI zvp2$yJy{{4i7jD`juAQ?c^;O&^$K{UkWp(~{MN|y)sS&CpJRC)&rGdJakXS2DuYi9 zO&x4CE%MRk$IxVGs^wxz1StTtYjs9Hab@7&?a zmTYr;$V`wM*iXyO5@`+~fM*@63e-kff|r=Xhs8)Q*Tc?V8nTJQv>l1h)adsLh_z z|A%c3g~RD5{0FyO_*R?uO@Bt+kXr{-FY^cTY?DsqI3OY{e|NkRvM~f~ln3gwqu@Y; zUxPw;n||(M%bUcZJkk5xpM-2$JEzO3RI$%eH;>8+$1!csU@x%`mkVF2K0kr6Ce(){ zizYND^@Yq;51KlMk56Ig`G&Z$Pb6_$5D`J0m|YjdS>gTksgLBYGDw;QqjW1_#$ch9 zXv|z8WNJd?$`3h2Cjd zOjASeIImj8K2xo2{j@XV{=D%eR(DxfIoEqWb0Al5+2L$kz+}K#)sAiqN9+AZ9JLtr zxHH&AXWm*w69)1Q+oVJ%uf0dr_3&j4Sv_CVQl;-_WZFD|cql5Do~9gZeWGu}n1WIU^ke(@>i5&SFU^}40u zU;R;i-k;a=38J4~&YDvxaS%9r)&h!{-~j*_+WvMsu&|IiN*3Z~526X-V*wO=Im@jrF!#zRe-qMxKqIMT&l^nd5VY8QLl`&wxTp zeqyRXBMRzc7iu8}qtkGhj$6`~3`N`-4tM1#wk2&<@+I3$R6CjQyS6*ORb!B^rG~c& z@TpkYJq@wY`gA<4#j!iH$Ij`;YP2#o;N7d1*89&`JKr(=y$-S+Uu&(-UAOh)v+CF{ z9feahPm9!uuKZ-~g=IS6ES5kffoXb}jpJ zn%^#arJ@y0hMN9WrY5Oui}@}86pG3cM2Mw~opRaUod#+Lf8|J_Xh2gxihN+cx%fC6 zM(flg#i7L?5Z5Kd?Zb$ltz{zI+T}39&Zw4L1*relaqDNGy%Sp&H_pF zAb6H&ijt;#W7_F3`_|Hw(vQ>4-TJC!!^;6B0hn|`C;`#5WrWd&%YffZ(j)jFn05`B z_RBg(e^$#efElf^U+#F8ibp|?pO>5-R7uclo>tjTt2PYhhXg9avdDFrj~RqOMmjXU z6-o|F&ndXuQ6LSNLBW)i;0t}Jx?l0S=B~mI%I5ccL`DR|<7>z<#gbXzZW*_obUWZfyP34m_7L}4JFiY z{Ok9Pp;jZTronWB2B5wf!AmEI7~*@Wpt9W}po~p6hNF|G;TjJFzdT#ThJU1A+-2C3 z0!fmk-~Ap34BU(Hyh*?_@K{-Ag;R&@ z*L}EbiyT+fkLoqjY8Uj8_EeZuKl74lwslw7m^d-EgZD$7;_L~C%GV00$5P`n3Uq#k zbCv$PBFGmxmL;?zd(mHS_r`4ILhKt;9*=V`1wv?97d|}|eoW=9`hEny*}nn^bKKyy z0J0`Tj_)alh%{*Il-sw8_D+w%L&2?9grwDt36&MEGWY6^XT^V#wbR|}6cL;#ln)HO zwF()*528+4p?OP(v`oL`aJWF_8OnJ?gDw}u**Fthqbd~Jr8{dCmWd;OAy_=0nah@x zljZ5f3HH8m&eoYJ>9zAZfY5OrT<>cPd97PwlZ+}VW_zw*$$nEdjz1If&L zf?=aOe$G&1EE5(RkCe(x(lBTp{6|^LRU^anzw*%4MEC@g$k2n=qwr`ljmdh_lcwCv zr||ESsqyZO4($ED`kV8yw=aA&4f@%&C_qZLb86sHImODTOeJ3WJhG%g; zpDdN?nGSVkLdF=YQld0)#c-i)%LN;Zw`96m#XX;x(HczM=H0HDG=ChiEkyO=4u*)s z2kz_`ov>Zht_y}J-QUBQ5bzQ3{G7w#2?+7NAJG@g%!LqxPDZ=Ky-X&2cJ?>71YYK8 z13KtL$n>!Iv#k&|cIjjM?h65)2rAD%ROx+pM9mIvE1lzi@j(Kt!LdHGFBS}MtJTJ2 z^csxtIx+w%nF2Fr(B9@jF-R+?opZ9QsQ3~0)FwVcCSPiwc2ysrRhwcLTX~&Ktipd9 zlC?^6LrT%FKrc)Ln7j5b5`jyJixXME>8$V5YtPds1-AN@7P17Em7ol+=O6qlmz66& zj6D0=;?T|^^gmGb3mh-R6I2*4^l$~eOagsKfy*a>H|uR(a`=nf6qEa6;yifIj`L0R z2?uxbO|dDAZ(`%i8DIEDtMClpeT|cwjYLO7ZfF})(pU@K0>h=B!n>RwP(3t zfyi&v_uKR(Uy3-ao?NTVcC8Cy^5toc5IyRq_tuSAfELmcG2+=Mkgy6|g68p2jo_he zxkRIm{%$~%U`IlZ;b6#dW5G$-j;wM}2eOM#scWY}&@Mr;E}2ISCZ|>S;MiUA6y&$F zgJW~Yvk}8lY5r55O@*V83b|_?pU%fpz8WJ1s|UXBN_tou&G>C%Pn!KDozVcOQJJNUsnVQ z+m@Cxpn_pg$NSh9T{m`2;ttgX!-6qiL+?CGyIzr~mt zP=%n5a1m3%Oa$-EU$fFU4_?ym z19moP?7Nv{fHJ(IE(C&_3R)MJIutKV?i6_W`J{TM*`g3@CHG3mU^XJ`$Ep;VDl?cW z`6Wq`Gr@qP->@vRiJEr7E<#XvtvGzg>)MuVP}6PH1~j?0L{li*#-o&M&gaKbraG#P z9j~zqMk^#~-DZ}1^+LU);#OP`3$3sbo;DK%D%=F0CaR2YtE^{1GIB_Q2mFv35>!KAYefJo z44p3&aJl-tA?0Y(?S`G2is4nke%`pCHr2oPl$H_4&2FZkiFt7PuW1B2j)~yfd>>i^ zB5;+h=j?Z14)SbxUOXHK{Wf5jxk;apgXE7I^vGpd zM6kZf$O>U)X#sv>2=*aN0#s`C-0**pc$1z%8StPR->di!DDnr6R8Y2uZH?0VP0}&9 z->vQz%(Wr4m3Za#nj0%kmDL-@f*NmZjv!;N-Lm2ZcH*&)bCu(-qXlQa3txNgBB-+9 zp|Yl_tl5cqNy1di-l^6Ezzgwz z9zFCS*$bkEbQStNu}E0#BY5Z-tf2#r_JID5h!Q0r;cJ%vJJKoM_p|WFop>6oaE5I> z$PZbUVIMPpYZhUJ4_ZjiBX^mw1v>K!q0EoR3J3@EFbo{?S7$W05~I{)nvhhHxJnXX6|;?k zxIBEeUg#kXxHesUFMeKh{IWtO<)A(>GEuk<_aX8?-gPa~Ql$PS$WvV&jOo`ko`}ea z*P}yAC<#t2q0nr%N6gwZDDZV2j&P--pp=F6CblA7f3aayE<0pHq1DDcU z-tG}Sh(S_K=Xqa-v}?ilhy9zs`Gcbj+8G5$3i*7X>Wd6=2h!Gn5n@-I{-^Q6edH98 z9r1Pb>fNOpH7B_PJX|#2ApG>qi0Xip$b@J6erhE$%f#(rRO8|LR9QJw{^nK_kYmO;g&%tE z*A=eY*vIAAkJSRIZ`}S{;dixZdE;OBu@5RC3|p*;>y=-84A!_TqjEA83 z+G#PeiTYWP)u+E7xlx@-f_=&SHrU-e;qRJ!=FMmU+j^TJ5dw*w;PVe&7_iv|7sB)N zr!nwsHu9!jmpaw%Z?lO7)fnys;ZEQXxzt&hEWXEA+w!hAB2=20d)iwM%)wdf^aHyb z{iy8z#(x_7Y9E*oA7$)9wwspo7w_^M=bvy@z(!1Gj$wCi}w zr_I5ovb@Vtx0+W3o+$l{(G5-%m1NIK>f{< zg}(82-}9g&r!}`YCJ1|2^YkXyyK8EgiZwd|OG8842$bsqzaQ@k*|PmXy3$$=LN$VH z1{7@mvDt6q8;s|xiT`6EdyX=C4zmjJEBAe%ZV{LP4a)TL@D*w}{ksB?=LPgxbdXSv z;ateYr3yl6K#M5RcLF=XCyv7@Tj}KIZ`m1lXWLZPRj~(do9Qsp0Hf#a>FJ>0Sp zqBVDNWk{M`>l1>+e(~x-{rh)jFBrV~(f>-=-daaTP}eI$|Ik<+U;wDOIKp}1T4tJ0 z;DkxUkU+Gc7Z^2RnWFAvebZ{rszj%Bg>QW^W@Sim>T%;eHxOM$1DJiQXT+$5(0(TmlSz!;P+n#s8W>Y!$sH&*{iRVSt^|4f)9k0Pa-X_6Di{N_}D1?Ya=%6Wtc=dQI zk2|Y+HPs3gxrQF) z>7ufC>=0HDw=;FG-o7ve97`Jmo3^@J-F-0`)DzNR)+Gs(A$;!_-VtiHY$iB1OTXYELyj8UefY1e6n6K&n>GS*dpsrb+DPFS51MA1A(zX=Q= zBhcnIZ8q>+nCT{#4Oy=qoS$KXv2HlcpIQeLG|_7Jy;O!q3uQ0ehS)YAZ9z~51v2;q z7%4|o!<$(LGCG%y&~k1KVlYV=2zdt%PezUWOPES}OPu4H7pQc^tylMeV>qkgWyxpV zFiu5_f~jkStOlczsmcqHnfZooCR;--;!r_FH10)P_?ESQo1nKn(m^f=0I^%cI+`*We#N` zRLz*Bo#73)%C$U*v{ccM9QGkmZsYJ#R55&Q#Ua{;nT~Wzct}9nFY5bFlI46@pMk(7y&?EI1A5|SsENuFshDB zdPP#(X!=|g_hb9>-FWWu&!kVsP$12$IUGz|gm7h2t7L4~%*#t_#uQ@q3P3h>UR|TI zIog^Ox%w3b(DsVC2l@14r^rwqg2#%p|6H%Js9$wLOZ)flv0MoIo_~hm4qgQ*aHse* z2a)$Nizy9j|jJ>p``h zNzc7DV{!kGY@f97F%=P$hzY#NnTNB%B5y<{6i!lvvu>0CJkrfOiNdCCVM7R07vvz^ z291}#Vy9lPcsWud%vjX-Y5<=Ou*mb)cR5a z*zSz@UlUB(djFVoUFqnU`Mr~VQ|Zjx$3>QneOqHSW-w4@KBFVXoZt@jhtN0~9_EYS z?Ku?MAjaR^Xi<9ya<)3oYQ6N*u&MV4*RSM9inB*hFdpWvWsbgfD7Upvw-5QXQRJCW5&p>XUY$d&LVR^J-Krx05SdO@(HxhmzD*cIS6jVKXUP}ItnJ9}!9A>BKZ$6Rgf_SZSK~9o4Tw$4q^j#PRH)P> zr&Fzv2Dt`8(#Wjo3jO{m|$i=9gv7|vX{kq)kJ1; zaJ}b%0(&cEO+CMvmg%ztsX(S+b%#}9uL4k0%oJfCKxeI$&OtC^8gQc1aw#1k|J+dy zt{+Y=O@}F@JPQt^!Uh!^Q3@%Mo|3<&D-_O+jakGV7M(%zWW$&bO`1H+!s?vOS)pKy z?(i(y8_tHB=x%*&4?!C-F8RoNKm%%xZ+c%6Qqm?}qb`LHkjNB&y`QX(`VZvOSM0hU z!6lDIf+(fT@9pd9Ec-9K3(L2C%L*lpu;M_pF}wjey8WOx$i3zH%h&^!?qBZ<=lQReLq_1r{j z(C3-NSc_-_Y(5=qoh~TSuCA%QEMKlQF)z+~+tsB*u8A%-O3&>g>psQZ3q2H`*%00WYW{#xMmwxAHk zK^|Z*1>+;%mF|qnrQ{>XjvVU*K!S;UKSCl3m0q%*2@YQwkgYar^$>ZvG+dZ09hN*( zYZgPfJJ=Z6e3CR@c*tYz5GHu5ngYM)VRPxE5EjdpC980dPVQ-jjO?yDFUWBF7~<_U zwK>Hd$kM+XO@JcS1mT8wQA~V9(q*!0_&rat9b%;3n{v+I1nctH%1xagF#C|T`t~>b zTDKk@m_Iuydo|m-dzpmGiCtx7l*cJ4YQM}-i`axzMzt5k9rH_@=#0)Bq^IdSp!u!? ztg$c13B1muFTa($rMT2jq`thw2|qQKtv%mMEAR_O?L$DQ=5a{lmvQ^he=s!n6nIzU zxRn-zj$ot*s5YBQc%qCm{Az*-9<^l_zihi4YX#%kyb8Jh*qOU2nVjD?%9Vdzm!ZCn zym|yHk|NY6x@-$Ukifi?2C(GnfmC5cYw3vDrlx0z^iR?EpBLiJRz#Z9R4FMUWxwGK z-jv%7$Miizoo0iRaKTjSASCifv&kSI%!@i8I@e*QQ$3N|+nePIpGXl>SWRAPVGfKw z=veo;r}?U8!drKMRWY@$toIwd7%`{(;m^jm`5p}s71r3RxNAS39fXVcPkB%Oh~jU>>WwK zrvGO7yOT{_OVGtp#^y{V2gJbCbDLvT$ebE1*rqj<=2gaH?dF$J{kGB`jt3d9x5B`& zwoVH*sVp=$BF4{ev%UIW$uBQ_kLk2RXL?J@)$mx2mr@@AcfKwEQb+^7@VOF|lq8;* znI-V(5x>e0y};$Y`vRTuIw637J4vo3|E->v>B#$}_WQMc&1UNaNzt=^By|76Sfc1) zM+e}j&KGQ@`v>uL*7^5(8ff~?>ezHXcTXce?Q<^C$<;QUvW3SMcO*-R&b+kVPEf8z z4=Gd`W|~JYJh(Ck$l`R5G_NCMH@-{~Ga0LcB_K=$t^%DApX+tOrX60hyGtlp=)cSi znGjeyLAO0T2@NQ?5hwIPP$R!~m*t+AIP3W~aJeSO@o1L48PpGq& z?RAe1Zf_iS;c446UpO`tn66Gtk0uI}X(hc6K$GXdc5_I}e$bsh(A-F4p$C3In?lAU9VaTr(^l$idl= zZ)AKp|6Pbf{1GVa$e5unfY6AaI?kT%aX3*IsHNMUO?1qJ88=TGD|&#*`JnQyjBYQm zu?&LlccFG4kvR>_rbgwt0o%Rs z>IZ}|jV2OMLP((32G51?TZ6i&tDksAx6bKv+=`d8Ur-0WSC4QP&N(d~W}E6AcYtlb z3o(jpo75?##j>XTz^r}kN)E)-xeL}B7|VNzrXgT-JdX#1Cq*5QMCJ}ucfVpHGD(-d z)}PmQ&c!PKj_?C1ZHJ_+nKSwQE^}*u%2gb%7Y`AqI&h%+A|bj1&%?=v+hr!3k$D&V zE9ZZ4ckhGenhLsTfK(A`rlM*dPeENjZvQ)Od^H7@BKA5wC~qdlrxDL96svuliY(@` zS&{Pphsy<$cF@UXN|korkL@Ysc2DCDbfcdgGU`nOvI?lc_ z<<5_b&3c|LkKX|~C;-#u__Y^HEq>QgcVH)d;AS_p?~yEN(cAGYPqF`vl~Kl>L--vI zOiVuF@f?sc2$XOD8LJEP!WdefG8uN<6DaPUdTHkl=~Fl!Ck4BZjCI1fn1+gGuKE}B zyOh#sZ#a0qcB?T~xhM6gf3?+m*d#Kw3%|I#WOx_es77@pXQWA(ZAsLgZ{GD# z{TbDS$*WipbZ(CGW9|TMux%pGM zLm1p6a>^;UL(-_A402mDDaytkj2FUmM0KxjivIS!@G4UTau z+3n4_k$=ui7G?Mvl_+1gv=VB%RzkTZ9|n`pSU0)bC!fWM$`U#Uzv+5QM9P=BRz{h4*O^PYWy` ztrnD@50p^ioqv+t)mOR58cXh)wmjwxJo+S&pDDhYcsWen^1mURvR+F@>=}9(eq{hZ zMkuN|hdt-0G5lJ@CRCcxM^J^E`%FtK896`vM@H5Gn5Le$cRM|;TI<>Dg;eU*<|rEp zG$vLUK|O$541i*)!MAY6_%vJ2l6Z|Z(B{3{9&hPwI9vnI6k7o-z$;rX0$=PA6f6af?v3FZ1M+ZKI8xr>C7 zyEF?t74*$~`>*`0g$}kRs)ff6W%+ zw$8wwB^v^Y#8@!-%l}KnwZE14VclGNJ~~CD`2mjCwI!L-SWwkm=`6u}pZX}>zEbR2 z^k$(dyG_&g!~EPGHOr@x-EX@$*0IF>80{wW89R+VhSWC0>RV^xcc@WEN#b8dwSOpG zcGO6K8B!3c_56XB@Y`HhDCThyPu)h`rt*vOEx3t>l8mx(WBhsCKgOP%a1Q{mfea5B zFb>KfUmeOUO6C_lS9(6^d@70L2bG5R6t1j?U=K1{f(e!7f$1CS`8I*+* z+qOt>n}cne5%``A>3V#ZlZ$q3{Lsxuz&u^B5Qi|$MHm^aZ``CmCTBh~7i{KsZONxd zVep#$3M#>?R0%FGRdj_VE4gxhEcreaAdcmI4B>r91w4jK%1l_k zdt*j8664tN=7UsKO+z81agW${y5~T@0j4zCr_^zQ7$OW>rBwI&Lu#ML6 z#Ti*g68z~XBnSXi-!YD@M@4Cq$AR(}xpgP6kC?m-9|hW52!m(i>uyE}nwO8Be?H6E zBiO!=EK5P74`sc&JDVXoXztKD94STyVV`iJ2T**w5Am-ysK|{m*LjM~$0g@zMp4AIpS-%4mQrTJueE;5^P2u?^d+}Qh^Sy1qSlnbM#o^8I)*$IRS;r_F3JFt_Vtoh z6dKj}wR}hQ&wM<*>?86ggP=ia8~`~tgDLKS@~CC=g5s`Or0opwPIWG;XHZKe5L67| zf;Q6&I{bbrbNfO>XzE7)0I&b(jODq_Rd)lM7S_%837dyZWj_B(FDo=6{_4}Uo0(|a>ZFl z)IVnUnj>|v)-r(MwY%)GTxQb%7a72{elD7u5e;{JBGb&M&xpDYOc@QaS46sL#ATz) zZSf%Q%%OTV9cl3zs;#Z|51yX}!-|FH4P@`DG~aH&e%3_2q$<=a!BMx08ZKw=&A~ou z84e)aKF9X-sg)*hX_`Mp|6`r&j@P4z>$ptONf5cZS0%j0hKmK19k-!%Ds_KSs;|BT z@5z0t{dwSXNJE^p%0Q2IuCi~nv&)LU*B9qonOp=ntKbq*ahtWg)$SR505APZfuiN{ zQGmpo%6F!ZoU=ZitNQeKA3W3APw6SRgK3@@lUO_n=wvkSkS^CSB(rz=1nF<)Eewh3 z7ULTR?@_Ui)7KOpUK^6-3Ol~r#$%vHS61w4ef-(T3qnjvkCJ?(b?UEkW!J9raI#I% zwp}f2*k@F7gto6!PA=DrKcDHi1dpn_T{EB%P~qtgGa+pD_6MS7A*ilPx)d;(B7E+a zWC;TY%zGhM0{GbQ;mG2ZsmN3Ck_gbGI-^X+STXzt7wfb3*qIfFC!p@6OI@B9TxNj! zvj{^uVU9K)DrEJ??);RENZWF7@@}5Ijrjtx@neGe8Y*CscI8>c7s#F}$3{W=xj^}4 zOKmCMb;G51ro0d1zgCrhU3l^}wXIT1im9kC@p~>Ba1W;19;n9cVWq<9pZXX(XmsXj!mLiAEb+ z_-7eiX!|=j$ML(6fZIUQa>DT6g<3z23MaqG<6f z{&X;zE2$T{GFT>L(p)JUvb7u*@!6u%;lYQAX6rP&)^k@~hcZdKSQV$o%O9+icNdgh z0^Sc7BY4}LoVpH&W4|l3*+24pz7X@^VfsQ#0X&wt;k%=(+vK%M@CJ*#b#8UQ`^)o*YgtaGD_Q&Gh--SGNaEp*kQz$tky-iC zXukZVB5|4vv2(75c879inK%w_vZ)}myeXs|8;p6m#dG_5FuWR9y?6Hz04!FtscwJs z@Bb+}_kX7U_m49hGpAvWIczhtIW@-+waqZ+vyk&yBuYZ+&1}s1ETS@}oI~W0iaF$z zkVHw&NhKs7O8V~m2keLKc6;r0J+J5eaeoAyKOqvT@B|>dOOgdw!&UzL6Q$Kg+hWvQkhVGnJ@k2A$$a zCG$%FQnlc=hMh}HmcLXX^64wc`~C6q>XPPRVya@HvyY}i5^|Jhq9@)r^I>VKV&=<+ zZpD@}%)1~Jmqjo0LW`G*p{HHmcMm>tH5&vqIe6xbHC`~w@Ska)Ry=8_XR1G|pgV7s zttvKdM=Q_0+z_ATQz)WT)Kr)5@TRNw!ihE0&*w%oRdNr7c}nw#eISZddPbT`kOoIp z0h5l*P$+}SrK%5$b3n+Dl*&cKKHX1Fzq(>VNWW%PD9g?`cp%@-LZa%d-N9U?*}=H^ zdj4;RWz=&ytuH@TZ1Noj2{!sUkIshxgKhe48W59A;9n@IU%+v9;4Xlx&p6vgs%<0B z8rU*)Kh6TE9>hpScL!Bu8S4dCd9OVzu=!n<^$cx0g?et!X(w-hhpen+?NraOqzD#j z{sLyL_NekUKHGs@3@-sC6#Ej)4bhs0%B5>f;NJ0~olm+cJm(&E5+R}gm9vbpg@-=e z<#fHmsp{oH4{NSJHM;qHd(NCuc-z^hT zD21v0&p}0?3_O5!$WgP5{|2k+G?sNh(6ik81>(VjTH5r!kZ1r5*gZrcCS+Jg15V9_ zXTNIhQ$IN*1ip(#=-z&!DRVHHd>-fnrP13?ZdNjVYHVmXQR1>_w5@OgoQ9srOVM{u z35^LN%S}Id@fYhOl9to$vF zq;d&cl#qG~$gS)-#cu!PH^lWfv+!Adol15{xsfmbN zy=W>qBM#Cc5qJah2d>HpavO*a97;WCL*@&+w8B z1QD5{#io!EL{2n|?5E)t(3x&QuVA6&RHdK{Pyv0wc z?SF`OEV9k0yMEi-vDWIk>HCiWv8!Du_a*hG7b@Ew8n+xgUbWVL{J4B0r8ZG|kxjyz zKy%K#D57Q0iRO})>0Q_^^XyqJNGb_$xn&)gx-91^qe z6hl1nHZ6#M0nK0?txsMeAOCuQ)SjXjpn3II)vO8U>hKCv!muAL)>j|dYW>j}7FJbS zzIM5KlC?93iM*d5(cDkrRRJeG5GRc{sL>->upxdmDE94BkAo*-!GC&RzFdpJXR77g zcanP@d*YQ!QKrBaB+BFu%IIIAp~wy`>R%bbGnn)~of8Twk_(y}kHx z^FCE6xw?lG5(ZSzxXc=1QtH+FF4te0_pVOpY;a(}VktsxCYj^h5#=1jHvFSKsg zVraIajzKN;gePE*Pcl|=IS0liq(@^S_M5%lPrMdNuaT8E?xTPG<}JW)Dn5UZotkvH zytLHDOEJAjOTNoQB;E#;lTZC(Q{&SW&qn>v>acHXF_Z>=o1N5*KydLPiL2jjWc{== zrMutFb_`u_x_+zt*0)3{WA$aB)r#K3=0F1>zt_y_wr0zdmcPt#6T#SC@HGjuQ+a?K+wPox=lP6rA+mY28Mm5*N2a;BN6j)SAuc1^ zty(9h%`!M|!&CCqi`GU4V)wo|yw_~<=FNt4{6X&0Lp_Ak|M&HRoHAfSB_g=Py>10# zbvGHyxF!Iz_qvr{LPA|lzn>tE7{-HBPslY%Scjl-nM(J2+%N{OwC%a5XHic&K7QBN z6g>AkzCG2pq0*?k4b553ZR+_7<|tLtCz_CK8~6CXLL3G0Jo<&f1?FX%4p0J)NXluj z7TU}klw+oFM`P_8Pnyj^D3p<}O*XiK_?>TQXuUI8X& zy?U0H^oLNYp|;cxQQ6^+&Pq3G`myb^gsAqVnN#`tg^!B%9`#ljI>PO{MuX?oEl*s` z0()^jjOYy>%fn{TOT^gA?gHy}oy^fjuTx6kzAH{T{lZQ@N9uUOUN&3rtR$;`75HVd z>re10Bit#R?kS@&szq<&?lAC#s1P}N7q$GfzGLJuhQULa&MF*Ww-sewMJ8N#Vut=vnYDvHe%rDpESE&wdOK{1FjRU=;+ zFTc~T?$gJM{dvz~1m+Y&LmpN-vCDs{xYtovztmr8t_bjecghN@cb|mcvx}(g`OWij z>fTx2`sQYxGvdm_MI0C2lT_ZMSI(vHh7=AhS7^DNLF{l}wlz}SDJM?;!;&sPrl zdCg-yEhG|}J_QZ25ehxbDnw+Ti_b1$2Z@GCgfw#odeLsq^+o5uj9DPWd4XbE+x}+* z2U8Smh7(b#MSJ)nOJ}M@5S1p5`>DNAy0HqoJ`P=TiKMD@-REqtQFm1QggL55TRC~Q|PHAE%LKas_LaKa zM=4|7GNn6(%4}k)UI6*B^BR*Gde{f*(ExuW$FF&;X;9C-vFg*8O3Wsa`d(l_2$kKe zh_V2@uK19qOEVaz+Oq*u2u;WwIQNP`6Gwa9PvH3-4wP9jt1Svy+&8&Toz$0b`jefq z#TD!KYBtjH;!mw0x2)BxLY8bmD@^XeB#`{UvRaPjAKBI#3^v=zr3V4krm7XG{011j z28D{TX#^`Je#F$B@injLrsxU*F2}qevOK+{2vH+7$iw*j)sfO7U_&!8%~|c95mI^~ zvHr=P8gT$sraa)fM0S0nOwc+T%?zF{Zeg-yTjh>Mg%g&TpKJJ?l?3D`E+2 zt7luuZ`B_t1XX+lKbQk|6rV(A@V(`}XHyFGmC{*Audm~Mxl~s_SNaKCWsy*Mrc>!i zO1<4o#G)HiK0sp(y#C$r8qSea?)QAjs z7YWrJt^?d78>+;g|N5m0#U>_?>5t%%b*U8AR+qg98kSTD&ONBHv^h+SA(kcJn3iNvs~Y&oTC$ z6@a8GD@UIXGu35j;Z$oX%|~1dkCyLh_LL~#C(9y9e0_pa zie7`I_!C_}$Ns^bNf*0kRdWNQMUdqqMX{1j=iM}utM@wgTHs2f=8$t2n?cUQ)_7hL=Mf~V;m)T@KPo<1Q8Lbnz=7&>vi3H6&vy>} zFT2f1BP-HTq3S39_EN4&_nUbp$C{ShY%Vp&h66*VXbhjq2S3>A$>4oOIcG}Q!gdi( zB0A*psTK4yCVh_M#rcgkuNCs1x8dvGNvPX?{3KH%{eTK8Tca_)`PEi=E}zvY1GXMT z^2l;jeVEUGzg)k_&GSg8(jy|jv90v2x#+|WuR^#~$1f}B&lJc+3jeKH-ltXtxDD1oL!P8EmD?rWE=CBLv{lAKONOR_vAq zFA?{bDWj)ZE-GDE1}vENo;J^{|+tp!pGT!%2coxI2Y>W zR(tbo6_IWG1A?5|(lDVN&^ex`2=Z4|MW8mhlfb$24LR^bHcpmjM+k--Yx$Gxc@E zY2v4<4CzXUEQ)Fq()7*hR+f!$_PC9k;4cuAf?dRdb(04st=(?i+ z)s!{t5@Z)&<(20ek>4%7m1X#X=}noYy@~HrPZ@OTu3|WDFvfOA_|R-B24C*K!;C2H zOxz3qu;HQ{Bm8M}S#f+*WMUUmi;|YC_xlZ0cf)nceDHIQr@28#?bc5~?rfYMIGw~X zYme+onY2$w1NCemk!ct8kHw>(Ql6Q%oKZ2CdAP~TCEBGLEmJm3QMAeUWe+F?!|W91Pp@rH+A}!DmNl$BxzUtp~>yVL`O{4!m-KW=F?x`3y$#K9+r->h8HD&Hb4M#0+b^vs*TB+&f>v|8IFN zF_;ejpJd>N#4&@130_&Ki1OzfZkb0}0>QhV?P&T-S)a`qQm&Q~XAXQ{^xdlYR@Y}K zxAXN^?<-WW!q250CDS5+9=PSpgOoCUqvqN#z13!L{Aa$DuzK^Y@y+tPFLcW@_=NMn z<}A638U;nz{A?R-kdzS*@qgS~ZzDq538?>mpjNjYto!Jb?vFLA?O^>gW|n{-4!ZTy zJXPkwtzy2H8tA;s_syjn0=~9=*q3ZsBdDB)?gaSTgA+taVofu{qQ6kYKv*AeM8Y=O z#P8+r2G6s%!vqwVZLE$e@>v>+l%TR#oWqS5J0XTT5Lpgd}D!#a-q(8Yl zQ9(hK0S=#XR{>hwWm!T%RwF%;B_*@pD*j&dFn9V-T`@EFX3t}3 zvk~j)GT`V1HnWY3N+v=gF163qt*g!qD;CTu#*~~HoaWUzZsq8Xs03wCSFd(BtWem?9ES)~=4iFPn$52C8x` zS>|U||23=rn-e%sN6=W(rAfr_?C<|2|I4sDkefX_Ax}fHgMR72v6MC$F@f(~bc<@q z49WHy+X}lvjIH`WO^%FVEYwjkvL?Hd=r;b+_E$aAN`wI_VJ)t{$u z_Cj+{?D~4U*lCYvk-O9W=9gXFF1}gJ<@s9Re6c<3djak1+s58UK~u3JY1l@W>#%o( z-$_=sXQI$t*H;JlO7CCoVNs_WKkrPMhfbf&=_mw`yF z!=`;O^7__atkqq70@2a4pw6a-Si3jFl@I^TSa}Iw%kIxQ$F0~2Pvp}(gi{60bPzNV z*JwnN#HCI|vUKbrf{sYV_?-K=CO9k`6VJSl-u=Z+Mkn+<SGG2g=kYpmS@tP#jCKKyxi?1^h%%nBjfyIVw)+RUK8w~8y+HZ> z3!-{`-PF9QZ7EpXoB9m#S@|)3)>%5NTaYW@+HvK)mDT19NRV+IK@#z`VmUn>Q35qs9Vb!y;=8-k$UUlKq97-4)$V<2+kz2;$0ZbHmWUU zM*7N3i@1aB)YY+5?L9s`7uusiysFJG_F1PZ^Au6nEA1d&+%xcrsB)0t-C3oco?9YS zZr^o9ygGUSyxvjI31joA&vIs@!!Ytu{^8>h#Q|62IETbslBV_n0g!L)93-bI?09m#==->|+B|gh^~L#rfB*bD&!#YtWyJ=7D)zr) zI&5$sH3+~?O2doM2XGm?_(0g6D-}DS1quJoxX4-?%0m%3M16ozwm1hYU91#KTjO>D z_nQ_$mE~~=p4L3d_W+^l$<9j(;X4$mjqp0%$v(a?a;lxW7|)=Cm16w-8&AIou}6`E zD$O_^#?W+{+a^(r_LH`Bm?Zk-kWVbKV#TQ}y5QVfisF^*Q5CQ~m#)eNKV!wsFIAk& zp^KqVy!`%4Z?+b0uF}GHlqk~NE2-?}E#G%3CA0=#qC%(gc!N{OOem}A+neuFJP?Lr z=U&HsPP9FQgZtjnjq+FEXVr(1+P2VQ6`z17r4l`M?5U!)U|7tO*ew7Wd=TSvd-vqA zECoi6~OlMFQ5_B3Cf%MxO8IbXDO0{#wk)go@*So7Uu1GLr z#uA9AVO)|XJs}#-Jz|=)-ZtA4pk-F`HmELJ?_T(j0)D;%s!)+%HMxv?9G|MJS%o!V zP2)GlN*1Smc-+BODxOnDs$MxfCJCD9SH7HDkoonbX$BzbGCy{|ro6UyU_~UzH(h${ ziA~G=vO_oqV7=kh-N-%7%{U?k4{4%}6qn^2ikWiP&X_6{t-e}z(gxxZd^HdKPD4jDzYqz9WWS7GiU6hn|cT|j* z7(#jR{E-l~wl%5C;E*Ca@yRkxvDqYNmu4oc==WiPEb%lxlYK1lQD z6+LWd%(&c;wz#BS*yh$^>kM-fdp5`8`3;#Kva4Fwv{_KU!&JQ4n(DbQbVoO@N8|NF!{sogXx$P9n1??LHm`d~RgdFE3qA1-_S-BYD62!LnxGhz4%|S^w zSNuK6!~EWrF9<|5o=o(SFt;a%w`ntN4|h`K+$R*EWo!c{o<|`1xf-Sb`__;_uEab- zxNF$>oO<&16w8EQF0$2^m8Zo>#YYNzE|s{*^p2Q)E1(D!1_7f6+TU;Lyp9o<=to!; zIjXH~@H#^{E~Bs`$_rN94W<-WzALRXlA&S6#u1+wt@v7+<`4-HaX>x9c8u_yj+K~M zmI8@&u=T4*t=GgzTwiR-uS!><`M6h83g~wJI2*N#(x(iyKl4{TEE06LF73@L-yk^+ zG!iZLzIn}e0qb%b6o16s7zyxptnWWNA#Qd^H^Gd=Ot+9Gntwu#;C?q-q#C11f4J=Y zw9o0-Jy2z5#p%Jk(07~G$4hsdj}cuTw{M^6Igvg)?_O8#VdFHIu9BZVv9{Yf22JIGp?8r!fL5 zu{B;V>Yp89#md7vyftC`9^iXG$gAgdqqSuHmG88xgoeEYVZ-~(j|MX23q*1? zOW9o?!1~39;3*iYqfl1O0JPG?>5Aa(oA2J-$MUzThLsTA86uuXqb70(wM_6Y_J&@_ z&8+Ba&wt+k*E4hwA>gq2bVM`OT5<2hOIGr7iSQh!LeT5>9s3Io3N97zP5A(BdvIFea2X%7B3ix|9e%;je8u^<2j)Z`mw>P!oo^?7``orQK^y-MR3uwG@lGXSD~R1L zBc(~J0LkDK9p?-mgoa_v#rKUrRwX?HcH9TqNiKzW%FVStY$T;O z;zO5spJKa+yn_k0sK7;yc(UF828CbP3mriF&rO#RE|cFr3Qd9fu|Lujr;Ln>MH;`; z>D&KqE2VEN}b;0O$0FIhJ@tvuf{Z5o-y9`gg*k<%GTky~w z^u~5nsdwscj^w@J5xeYHe({-tDVa7SlI*vQAJkfj&6pJ__XYQmLhvGDz2)boIK_(C zh27>P{Jabhuk$cm&IST5YEnqjYZ+&XE_Sgi^fmfhLg1@$bfo>w;pDi(vF8lpXbn>f zUYPwCekQ8o%0ZJDsiZdmlz)BtW-ulqM{J!r@trbp#C+X2xTrH~ENvCl&gxH z3c?vyRyuuiEty3&3DAYqL@YrRMW9;pwMdQ8A`-&B6z0P%+vw~P_&$UbwTTy@Shaql@1tuHg=za!m&}+p;6V`CogBKn$XWye=DuMIpf)LtV^wmYciYYrXfM>!`=ye-0UK_ zz5?DfUPsd~74seMr3i~ORGACPV&Ez%SstIvj4_`GWvV5;M3$LE&w&-z63~8tXT09e zVwlivJN^w0uYj7Quo{hJj++f&jtt(LOXAqxF`sIaadI`@8Hy~eLRMDEvmROrfD9QZ z@4&p8p1@5=k!+Zp)@KJz4~6RZbG$Epn?54exnY&>R#yYD4bPmXrrJlRI+CqU%$74Q zWD7=rAy)k&#zf@1z&^WDXO2>8#rWLCZ6!s&fXdonP7V1rMzCAAMx(YaytU=D1=4Jw zg#7}atz)cRhIG+R>OHJbsD71*CVSjLp-4JH^_+QD)N~u33C$)rXNa7;ZL@u^04biZ z-!>f;?*vJjjhPV{ZnpO58)Np4v95KJpDQ*D)eY?=2${`8@A@8P6J@hkg)(1v?+l}x zbKBN=&o$Y{Z}nl93C3On#xr>)yd^5k&jnB(^GTQCx1-o70)c&MUnJqP<~u>G?Y&{< zsrD)Pt-%XH`IGHyRT861a33Tk-}E<;ERRIy-ieOLSNTR1^b&l9J<0r_!|&uZc*7q-L7f%p$0JK-lsc$DhZYTQ{ngHcDWWEXA+-LV{Wa@a;G>A4%$*9ox`vK2P zgr>p5+d^;d69eAT-ESr1ztPXCQjp&gWI`{$yTo{n`;epg^7cj`XJ$j#FjTl`;87c= zT$Qm1h7giDBE&Wwa14~SD3qyA-q7FQ%FKSDDPK zE2R|;G%^;0iERJz4Rjj2#HxwRx?3ZP>^t9e4*on+p>(*z{Oi!Zrr5U8S>2{Oiwhg zQm5i{z@vk((^N28w@mIiHNDQmesrnec}`)^F(EpROCG3nV8hg}6YkJYMkrqlR24A6 zCzu=$$y?U*&WD+!Jnx$l8sicyJ4fT$r$U85jC+>8Gb73~%ypfqo9=_o`sL+Rv1%1n zWLVBKWclk_lu5z6=nSlhyjj%sLC;<>r+p*RTL+Sn^uHrnf46%!HL2Fa@2$#KY-uT? zZhb;F>>-+S!Q^QXzl4_3fy=

9xYgq%kLvmnY(zeaWW8TvFdP2S5tVTnNV4xN_=X>VBI%Y5aBTy|K4t{6*iDIg zn?cr2UE`M)kHC?Sn5P#)kg9<(jecVC5Vs!M0_pQAIWunA^gSvG^IEW9@7-G$&H?lt zsYv5`y0I91>FfJZ*kop+e?oJ#ax=A0RG)o!eMr&^&S_UFNv7!2gq~nb14orR<5Z#s zFoe)7V8ZMZgAM)D0dO{^;sVDM^F;0Z|E@Lc_5Ux`S~ijwKJ1lW1%T&o9v=7oG!DS} z5tZk^=`h}Oq>Iau2;i8qKpEm=W9|a_fP|*y6?XIQ78-9I`e5nCh+Fq$N0!T`2-3(w zZ}`wDcFrp2hsG&WqI{oUPkj}uMcMq2Qhu#uW3o-|qAmZfF6+GTCPUH##+s8Xm0<}r zp_z8n4C&~vd|3+Y2gSCpMi~F;I`B-PYn>bpC?%O*((0c9l-cf>JH3ITbFm-jZa#j4BS969p4&?Yc z$L?@VhE^^WW(?<>xv$lyku@T6j1wgj5>@2IY+g}asvK$5A3;SrvdQ|l*2SrgC>v79 zcMF$o-l8tMRU>rJh{f8MT*XL$?!KXqwGQp(>bbZdqkegU1IeB$)q>;-&%b>^T~(ke zc_P(?OARQGEA6l#rX|5e4Ev^dO|D?ZL@mB5PZ#r9S~`oZTf*;14Y5lduleS`@*Xz5 z$7|f1H29)A_=NLE=|o2U9o4|AnHR40t4E$b6Z5@v3H)%8_Y7m8^rq>c#j{fT(9C(| zLBWis>_?`d%)SRX3J>IK2d(<-^yV}xel>sNH+5!5{~F4lv~RQF!4yBf>cDJ8Fhhcu z@3_45N8W$ys(s|g{9Qw=Z@owh?5@7)k&=%YTc~?6Og?jz#MPdj-3) z1-e*tL5#7+U9#3Qv{(3#cvZWjBd}{pSz+1C=Xk_uVPK{zPSt)g$F7qgDE?FJA*A#Q zr$&X<7WgDzQ6^Vtp^IVl6E?&7@`ztPWk7f{)``(~G4H213;@#?XzakaASkaVecRk$ zE2b2V=WpsYF|jQ3wb$?J`kL+AzIidCVut+P9j^tCkt zTMvtQhAzK$<_t3SY)r)29<%>_f~H>FM^sVYulfx>erIa$<>?DMQrOPHG?_i)nYLZO z+1T^HriDxwvC4B9z_2CN$C_j4zxN~7q@72dP;oY-@U#y2z(ku6XU3an_@JYjmof_+ z!zWoin^`BmyByEQ)n4pg^kApN;k=KQ3VPzlyYq=%L5)%0`eyI?$4Bw}RXr8_$2S}* zP=Fe18L+v8V|U=ZBh+@oQXD53C;jetAXL%8E*tV5PpfuYk(^pE{m!QhoFI!RJj=v& zybGEC@9DLE=4rgD8Gz$`hv$t~Ao+=RC1E$hX0dON))XM1hQH9#dR2Vf7nXojOogio zTuY%X!{p6!!`-S}dvH9Je@W`xEt4FyV|RYA{X=Vpae-dJCCB;;Edg)43qmeD^6X0zIWhmW zSc^}vsxrI2m9N--7f|)P{~)WDQN43_G^Jw(V^pz|Z>MRR!(v_c#bYJD*fP{;WTH!6 zfTg%5tFLOgbr2$^wmpsk%RnV}17ToqhKg&;JSi`}pp(=iDvZPjAh|PG4;H zng;~%h~0AQ40}8JpSjb2uK)g(RArvs#!xcPZkF})pIs@t%s(ISlbHFgm(38K=x`R3 zf@<>u^T-qJiRD=B4@_Q-&R*rm8k2`)lsZY0BRAhc4<%IOHSH^O7c+HYDA0Q#E}vy^ z0H+DJt0R&h+#0$xJ)*!!w;RRQHcXEyJzYsIIIqJF%6GsY`Knr4v4fi0$hKn&_GIrj z`IctEelT4zTdI&5w1gyJ%uA@WCdufoK~0C84Kox*ojEcToJp%1X#G`Wno?(xkEVR( z@J^b1DO-R0{6=^`-}@-JosLgIDeEFGl&4kCT~`umV(y_WO?URg+KpIW@J-m+-6vxp z{hiw%+wXW(o{iG=2u~?^?pmb6FYbD{dipI};7F7xhnT};h7Ieq&8@q}W|*m3y1Bx` z!>1RNl6Y<$kcMq46B|J5f1vPaG=NuA6mUwb>6${ng80a@C)q$Dj7$npa7eKjC@AaS zTKUo-bUJ1DzD_Vr3f;o%vX*12I=_}@d;jW#n>rG8W9nM$z*n7fW=bMf=_r5Ud&cwq z`L-FKzH2xGs5j7t1T_uj#mqPx+N$Av0ZXsXjZp@aTE+Qz6f2#5+T~sU!1!%f zn+*xTPs7@UEgo27u+yAJA4h<}=gjY*LXX17 zMtke2OQ5b5zpnLyF8f=n-$S{3`uVO%q#HWuE@V&goYuGOD0`>YL*%jee9tF!0#h}t zp;5H?&T|aBjY-uSjVF4WA_?bm4WYFx_L#RAyJ>uanfLu{siRgUT)wlcu>PY@!1H)_ za%Y{Cz2^P z*-%510eI3lHNn&Q4=+o-41%&^3)@1&Le8H-^XZrPqrwxVA(33{eU^^JUtdRr@239V zp%^?Z;*Wb$k@izL>?}PoGdf=D{*IT)m9JkweEtPz{)c)git91D9kk2oR5g0$%9~fp z+dG^fl^X49MI2pAOLwheF2TR+4a4g2AeHyF^E0-j z(~^N{9>Y-4PA@0noS)2#&ZRgx<@@`sW3@MMxVZ%#Y_CSK87KngWcpC3S)d8gWiu2@!u)BdMiY=3V% z|Dl1r#P5S0)3!KufznOXMS$9gn5r~Zpmulwt!|rYuv96Su=_~{laSp1Z8#>Why>%c zrRNz_cm>@OfhvZ5Dmrx<4rTOYvLUF&(VH6};TuZ4PCN_i!@GRr3tz;ixeoh;S+psf z_PegU<)(0USt?KfoIWM+@YSf1}gMFKGP}xo?m6o9{I1?c3K|O5DGn^Os$71}Ol%(N?8I;af|U=uRNr0wwZ{bm@n~ty%iLFMU?6RC$?8 zx+(N8gs$WwLDQ<)oRhI}K|80-k0eDSTC7?n#EyR1eeB@w{A3crb$kVqtRZy*|19!@ z;oVsNv-G=u@`b#=-giAa!za$&FA8zPD!C<$n3dIB>c&5rjc4a?78H@%^y=2zL5sG_ zSZzQ)4EUeC9o79ZmANu*F9Un1L#J{G#5VZ$54|$GsupRj63QZO_5&TYw_km3)zNEz zTdnOCX9<4VtIDh5T^u-&U)$14J7Y}c{(hVIRII>6lZ1c_CJIW}?6rX)LITI_)U1Fl zx}}Z}tTG%myipoXJ6*bL>pK5xx;%CFE>68paJmwcdpF@pkh2{z-uPzZ zJ{qBB2!wp1#d`Up=}7eEmduIC zIibT_8Ua0(JFGiE1~Tl|IF2i>Sc}ANdr7=09UcL0Mq4NBSDls%ody>*QKZ7c4%gKl z#Jn=ElJ(p2`=gnY{3I^7ha8?}e^0NnyE6AbV|t#KGQ+VkR!c1jNBqgpNY2~Yv#~x5 z0!=|plrY{;e%)oht1hDj)G1NR%A2|W#(rPw@xB&y6Lc-N(QseiUB9^~bU7At9o8|| z+BHdwgx*w^kP{Vey8Gdr=dSG5|E|qCOF`dT9{NV8V5TcSnL1wu2i znHFo@zx^rG@wOx%)Bu}MKqV?S1e^qqRb~jn7%Z`vz#*3`loeTT23m$MZ=WDw!#q&e z4f1ce06sxDeMx|lDtrPDY)!7F0E0vmgp8L>^uh}RD1vrPYG?*ja)_1i;Vlb@R!uZw z_CjZbHQXB2B7q+*!1*mc;{(25KEz(z+-P3#HF)wUISHc|1>$!cAD|Alx+;qW(e;AJ zL)mh0t~8x6cKqg#%Tb|t7;3hA_^1?ry|hfQ-V5Hk1IaCeV5SVE0LAYuA?sj1CqJ** zCGMG}gqbC1S#M_$NgxStlD=Uj&Jb2SEgIa4zO0_R?TuM65jlqyAv08>g>KJKVOPWeLyg7AGN*@w8;+l9$sod2EAz*mpomg(aKglNABCa^x3)ppX)2_Q8hxe z1uf1{M_c)t4o{2tL%!D>qTkf+9S6*%tLQI%InfjSN{5;|<*w???TR{pbZTm5n}hB? z8P?`E8(x{Hi(!^|Igh83M`d{%yP6RBQ4C~pUKAsAS2e*jk&B2@Dg z?fz5CJJ0VhK}ye5WMPHeO%frqL+?Uf&#b}X&;|Q1VW>x3i9p{SKLK$SQF1DOGR{Rh;e_PouO8GsJqkW&``O{Q0mJ#j<7Z3=1dN!1-X{6!K6%; z(}_XhJJYH!eE&4aU4bX-YAd)NCc-N)CpDYQiJ$yo6;hwez|YC;OY!N-)KDCWhneJ| zYy{~}f*h*aX_{470X6Eb>6sAugif*m7t4iY5NPzWm7=%6wl~mM!`MI4xW8OEx-}1z z*`rAiiT-K6P%dWQcUvcuoW2woPpUsC!y#VkvL`(Em|KXY3RXh6P= ztgRcWue;yjfkv_i8AUfq#QzrXYf-(6wN}yt!~uBYmE15 zC}4O;;d~^dEg2@{TFxTe(Lv1WJ$B>ZNT=X-rwWSf5JKRt;_Jn7i*z{W<)3-9S%UtG-JJ(mHZ4=y$l57+xr_7f-FapIFQY7d-PTA-ZCv2 zJ8k|gWf3jtM`OoJ46p~gt}@rTB?qx2`PR6>fsKgp0c-lw7u`9zp~4E*Sef)&?i&Bk z2SYd&L26nLnMKtTQ@fdj>13$7^jDp1;08 z@jo8QIw_qrY=J*CKy$qxYSPg$(edfK=2X+>(+KTqBsiJdJ;M|2Ri3orGnCgylxYwh zIz+~QLzT&U`yub~pd6A8kRZzgxeKM1h4TFZ9B*6?ZhPv)5DwqXLuFb}G<%|EZ$UC( zVYvUIcB-Pvt$5{vl+o*PelMWjHpgF4^p`vOVnyOO$W1Ogv{6X+E@V55`|gt4*+K3F zw(H|lQsy874T}dJ{w@uPr9cxIK@!4bInF?_nnZ&DqoFOV?)@53rz-fW@x>@* zLU*m(!u-~gG+li0YuwtPJ$IcA{%^c^KcT}-T z=W7#7&?ZTMYt3QbTrXvu0h7|U@Q*BBrtw44C)$Zym+V_@M(&3q#3?^eyFU)rk#P!( z;Ee`5M}e~5!u0Arzw15(*cZ~kvzbY zOb9ZS1Rps;1r$sMlX54I*hVPaLeHDhm~i`1(bZf0P|{ zKU!^gN@fW6*85L})XXA<_t;paTOMjbs5s7KA%3r^I*gHzXzMH01|Hsf4uo;=-XciL-O0Z!E9=+hRQPt81FT;j*E?O zht*d`1MxN%_SvqCn~Q%&TjCyev;MIHdyq{lW+^KRNK0)(zNI%=46Cq*f4(1Ya`L?* zm>I0Z8u3;jC(jZ;)-+;vGD`r`-wb~<6F2y8sa8sXjNj7BCfJcUaTlSGem zPUhCsYbJ#|V6^;T-79JA812@a0{5+xcy;G_69s>CzBR&9osoYF`Ksy?4FA3WVkm-5 zz+D=NDMF9)C!nmJIE=BOy4p3ypB148N8kVp&qOe*z;8Sva#HPLxJ4TKudoJRz0NCE zpIfZHM3f9hpI%QX=^ROMBRg(do;Q{{fTxw+r(aqPryNr9r$WVQAM4x0wrt-YM ztkIA}p|g$c1>Hd*jFcF!(8Y5u&)3bXpC$n;s1VpBlKcm5f#esn_Xhje1n$3#RS&Sr zj(}-51S_azIy?5_OBJe(&FL1UpDS2E|9nJ=$?5YWFatQnl`~ zW#@U#UVdqK*yOA0yK!h_w1J_B(|Pyd5Z8of?zeyHp7;BmATm5Amf@9mSGs2@@K!3x zLbI>M9$Ouc-jmE&YjrOSV%FO@*hHOvU2nUHOKe1fv~uwtxon^Fv+QU~Zt}oIlfcNJ z##v|oW}lk=sEiBY!}_;3Tgt3TtG9oDZ!_rbn%`Re8)otCKf}zF%!ksqFGQ6 zm*GC<88YSNnqV#UDUBw)Cx-0z=o@!gJRh6SIKs5ZZTC$wj=`kyp3;j0tCbI=z?58j z=xP;18B%9skHIJEmBTqG^F6s6kQuDi!;>}LsxQ{ER(Gwc00m}w=)z*1BPst&d6Tvk zW(BSem#nd7sdu;32FO#DrUi;3ijkX8n7ZFAOFV$GaMti7Fz7(}Ljf*-Ys(5lfxRJPN0adfZEO zj`pg|3gjJEJc`wgM)NxyDs5bD&O#*H1D~h5aDdFpoemEQ;snk=KR(+3`r$>^`4=at ze-3_CblJ(C)B>l4FlEO%5V&4#u9@OP)@~17U6ebDuFSTB*v5QIFu`VMmV;$(;)o+M zdA!~u4s@^UWQ1=vdx~T*UC_wI|DHEZBDArJD&pW5AuZ~NVbDZxd~7e3y7fve`Bd2C z@`qDT2ls}Q9>2BYIo%z^ZGO7&*B(y*%O7E`nip|Utjb6^NIU(^;feX_E{CBp-$z{m z{+H9FMaPsM&qTab?$wnrk+K+FHuebDK_rXaAiM)zf1|>}M_t)WjfCuN2p}>0vg=Ob z7t_U@#C@6(DKa##>BZYk&mkcVtrKP;jZf^_UK>;&3)0bbL09c%Sj+_&UUv+!S2V7? z$~d9cS`?XJV?v4CcF`ES%h*C3lP-_d7BP~~(H8>2a`690(pf-7@xE_=U>8_&mu{rH zTXN}!rKFSwDUpzphNWu-q(!b+8`@eJM%*>f{CeJ<3Jaf-= zf3A-sboOP2BebV^zmb-%&%CoJjC#t!R9Xm)MKXPUJX{)|{!fk!uR6R(Gn23A zIwugcT4Akp?7WWpCD`Stn@4E7w*6c@;V82JTPFCu&Q4)WfNP+o#{O{hQ^bo>* zvy2d)>O~*xkgXxISuLpt?fOb^Oz#HIC)En&DyP^$mrNWrigZ;`RfTrXX}?A5aANCa`<$l9RW#lNrNa`P2oL%BY;U>%&&|zrK|6#vvNuYI8 zG&j2-sE5$4+%CCktVj=6N3ady{3Ac@muQcBtE#TmR11I4Dt)uu4L#!^sm579=x7g2 z`V9Vjw`}g&8yqU72mMxnGW#bmxw1J+p}C=|NbKtz26lhU?awda|1hK4BnACoSkY2K z1b`K9Tu{$ZJ%;2I%xu?tFdM2cSLLK56_Cq}CtE2&a>!}od+L?LUeBnov$NofRz(sS zA_mR4pFcipj3LlPVN*$#BY9^yWHc>P=?iQbxa7x$5td7KmYjrHUlT;>lQIf??0VLE zwe;TJs1+#VR*s`F_WB*0Y69k*`74{OQXfj^-UFt1N6T1#y4njRn=oOG`(sU=DhKi` zpo`tsF3nierV>7kBR=$#=)pamZUKl1-uxM!>`}({2wzL{hXcddHj9#Y*p|x*EgM53^gHAA99^K9n?)RSqytrGCEjEgLv{kvgi${=btl{Glo2*w!Im!s z2l)fU-$i2%RBH&mUwyVg=Ew~2A5+F#Or4uk<&I5hIhb9NQF=e;oM;@;**(T_=XKEE zUEZdgbeOVtu^TZ5Yx_l6IKa00sfGGypQFYJ7l64kG%i1eS;hkeaf7J()@H`wjSG)4% z%_#qLrG1Bu1=&}9)zoQNO#G56v_7w=l5B=>vZw}yEzz-geWVMF$1s|OP9?1*-t{ki zKy0_J2B8iNn<;}C$?p*tVrHvDC8K8YQI194fqO`P&0%)R&A++egkR-aBsCRxAYBG) zxFOYV9QWNr4?=F3Nn8YMjIt*W8jR*iHX=|HSGG#zj*0Ji+o2`5U11Rk?jp*Kr7hoj zhH-ZJK%3JTBf#7y3;#&{tZW`Ej5@VRW?iBq_K#!L{6lh8?NVdnk0Z}R#7V+x;vd_sBr!0iH>Obkm(?_ws z%wA}t1ZQxHI9N9yZtmWHZn^AGgRcAS_eYBwFIN{o}h4WIvdV5%UIzeBc-dW-U#+y&j zBO@nvJ+|MZe3@<$P0e~t`Q928?fYX1=fE*fP zY^}8+cE2lNSISmZW8xn-#KjsQ=d-}qGx~+c=&Q^vyP?W-s-CIFT&&vQIALT&F`&)N zO13QnW@op1Dq$O>?xX~wd&R!cLLp&u^?LHv@pb|G)`fJ;>p_!hZPN|zACw2Hxw2`SO zGR&AArz#7v2Q!|tL&|w(ZO9(=cpQ(Yh2>nuwt1eWEi*w5f97d%rV=e?kJFNOS6$ei zXT>schS;uy)8OyZ5z}J2o~T&9Is7$zL<Q8|gu04}4cfOM`(v13+ zQS?}=2(0p!$^eF=GQ(R?89_J}@$N0OrjbCxo1b78zckKLsDj*^oFxy1|Akd4SXkgS zn?Sc8h3=LI#{xw63FVVFI>QpU?r>aJW;XjxK?ggk*_aSLFQI}`Axkfuyf$!P6E$2_ zSZxz*fX(p=LDOx=(PT?+9>o#HNjnH4I*Gv=x#je+?Rdj7VFyV8%};tDsiB{lp8-H6BHLeX(3RT8fYK3r@EFc=~>>duPe z5IiGE{1NYQ7XEw`UQ3LXIzpgyMmwcQiKi;~HS^Q$5)2*!0YRLx#<8=x+p_&S2R|=j zbD33m3Pil(#!0s~x90L5iR2#e7LK)}(Lw7!iQ;HParjHhrP{sR86`|14LGI{LH~Ku zx+!e7C)3Q#5#eL@i#kyMqrA-@c_om7wkgi|f(BhIqs3Cn-5I5BkyHAjg4-ezR&c2-zZpBRFrBgKVxz;CiW#H*Jg1u&l8hL>fURRhYjAJqTa6yl+!tIeMuieS8e!;C@t@2Pyt(_rW zV2^X0ky_jK)+V7~yt;s?33@$4P#j@dIfF-@gNL7~B}M(3*ho7U1}SE@3T9TSn1M8Z zh18W<(VlB3M+CF7zYs8jpy0T1a9oTE49A8P2N$j5Oe(?1BP5Mvq?Jnd%XC#nGaN~V z8aah(o8xT{)2P|H>~ke+wa9(+b@AntP5C5j@zy28-jwiy>lFeV^$Yg}ZlJ6R7)dSu zr5LA2%Ul_*aFijg)sOQd2W;05RmD|8RbWVjM7AtvDMfNZ*Om3N`C4z7kVtdvS;JwFn-ct0HjR6&FutKh( zQSwZgnenBI9Xgt^Pz>jo9D}PmgA4mwTFhHhS_A#OtVLEu?wSi1ZezY2V=l?W=c6nP zsHPbAr(jBt()pnjS1R4X{^o!MU#LX+PwvxGqsPW#x+xN+E5+hEXVD8=4<}cmKP;xP zL>-RB5QD|hVC$b^N8bok9h(%_YZ123AWa8^o8fxhBC&*GVxf36F(oOWW`ob(>^&BY z$X1@KbjH`2Ji2G#7yWK!+Ko6#1x0>ZIF4GXHDp1Xc-gAtqb2+=cF2o&$uXJ)1+d_c zl@w9Y+2I*hD@M|*bB<72d@ke*gUS~O1gu2yN4!dcRB1g?|#UcM|fTuL(PR@LGJ@|=!=K`5q6kJTth zXeX-~3qHs&Cw=~-Yeb@JV@@(HlNv{En5vyjO9}c)NH2x~N{y!$f%Ip#RYTCcY@|tk zLl1nT@lw;nU!)IOX?bKRe^!$Y4PZ!$D$z%^KIde#gdsvq?6grhr_uODZf(QvJq3%8 zxUd{*U{VA=TFb8Fb6VsDDDwX*9Kvl0C|*4{Jt_r@mFpN%bpK|_DuOh(u+BL{1k#n! zqPV~DaWKTKxW>k~8&teeyEz5+3g}WCBiqhvGmSM<*UVV%`9&}0*EA-k9A!x~-fA2l zK>3WX`&CuN#ODKu|LBH4$MbEJ59aW;_-mks{Z`E=^@K#_G^+<}a3@alR%0y%Q6kp0x&BTEkT!Vf=izjSOq&UvZ znl4yLFW-RgD;Z4?>``yK^J;BbkSCE9`gOJ*rON~SKyp5!5Bfp_e&1J3Vskk_h6 z{g{%p5|e>Curhq$co28!XzZZw^Sc=6P9uS|x37$$FWXzP3d;6&T>b@}-UwT5REJTi zaCQYif&GppbdsWRNPxsbIsOb1=cW9!laiE}3ULN@kohl}Rw73QN3KeoMuXA&wX0_% z^>vw9O!{c#KvL{1S3PJtq!Q`B>4LYz{#;WSre0iM;?5tss6` zJ=*zMBV~b9jpWg9J{h~L8aUjQ-l%8>ueXAr3`R~)QCJ3^C@s=f`=nH18(hEp;7>1* zTr?CL0qGlMeM%Z~#ENUHr0H@7HYS%C(-7KoP$uD#hm(2E9h*D{Hh|; z0P8!oTH`Td7V^J(t7r*>v&~li5pUjK1oaugD>eh|m z(0Dsyw(P7*R&oP0h20LZNgj+HUvnG#8Q+d;{`I8Gnw=S7vTlkQr3s)bnddE zU^tG<_y&0Yv6)ra&*mua@z_@|{%64`lL?jsGh#(kN7Z9?JVw|Dw|0gM4IVNVm8D{c z-|E_~uHHio-*<%mO!#RbaBhtTls5_P`=RRfd(HYsAEKa-St4s-uPbl}Mtt}~`z5m% z-ht2Y_}(~B&G~+m5eR9P%C`lZc2Q^)1jnB_hFd^jK^>;wD2cvO+9MX_IB<3Qw{-#D zcO~X`d46i?DzadnY0{0`7BL;4gTSv<##Z@~jDeRcW>NCrzlXA8CS9`#-xl5;LRgMk zQ_t{)9u>wBsJ`YOB5Tji+>{jY1uHW{Gw~rGeTS}I!;F*~+VSEez?w}~Q7V0Gt6Ldo zs2Ho9I6}5VWn4v?QHdPA7$~b)WK5TR zFQoFZ+Xl`Up(dmH-cv^Y`;k9#^q1E~9K$MF>?)4hpG8KlrQ|7fDk2C+84ffuT{Rp0 z{kats34kOJ%p1 z+tteCG0j?wdr8S{@=(S;M?ns&GOltioXgaptWwM~DksQH%-}IDkba^4cATPGS6@TG zEpv3C%CKB}%T;weokK3;Ojy*UdX7!?4S^Q#B{u=P7OJQ&L0NrjUEH-$4xfBvf}B&g zPFSl1iBHLA+{pjIXODnN090*aQSy-T6td}ZvECkPrslF%jefHOCSee&+6o~#!I?q} zHaWO&^bECSt!6f9RvYy*DPm#?%t*Mb*RH*H$KMJ)-&nixjlCPYm!pJyt=7wDt?dp~nlSNq@YIJmXCS}&I>Mby*{TBsMq?I+-rKvu5BJ6oErMWnR*MtOyI z7lkv*%=STIBA#_X;#|2@NPG%1_)zq*IgrR#0oNtqQ7&Lr9b;}j`N-QSAXpfl%&M|aq!v&S#bTibH3&Hvurl~T{~ zR`8(`6-$WgIE(;{f}4m$Wx|ID-O?1Vm~m?4Q7aA^GE%gAX=+#fHE*i9AEc)b08EPd zW}<{$m^zeY2c~t5i7Fuyc@SWxh!3HYgv6%cY>oYOjo3|mnJ9Y#o=nJW6HjtWvgqW~ zr>t!j4*9dqf~rS`;tWptCrPXp>}XK|0-X{7JIsn($2s5c%EG1et-oc`HSK<8e$Snj z?wRv#H54w5Ri=ZGo<;UlNRP9pnP@Jv|EIeVs{L7>syZ!Qjbgl=RE<9uNvih1Wqku; z<4F<_WlE+X6PZA$q=@qNG&X#aq~I6k=*Sr$;Hi@SooFKeZM$i_DkoW#?Zu>S8=Y^j zp*rn5blvb&#JcVhN4oUK9rl&ReXXr3%GWL>Ns_lNWslsdDGfTvh2(@y$Jr`!!fru5 zCPO>Ba_5*a-ui-oTRldl@f0DbnPNr_hgZ85spMU zY$4JOVgntG#)3JpfkXj?DH=lFOoY7%3q>vK?qo%Oim1KoopQXTSiYb7bOG#~P@u0$ z7s67bshl{LsTl>qj?lUFU-MlI4cO3IdCu^ztvf;1OJYm^TJCle?B0-~?F2p7)e^EU z(;a6^Q=+7)_onB2vum=K z1LKJ#Fh&eGSq9|t(12Txpm)v8Y<)Ji|J*lO^XgdXwbn$Y%Bt>O=FBt^iPL z??*CvL@LW}c53m$?J@;lOvicOZZYW>3tro*dDKh|a?)W{eSi_zdM4$w;691Bs!@BH zjzUH=+ffUZ6cY`qM&AzrIbx!pRCHmp2_!orCVG*nM!@>0PX(CWHB!o?N*6Q1e^E2S z?&|m|Wa>C`PxDoU@w=m^mC9!Jn-Q=b#;JQzJE9ram_(Hf~f9J{-yi`uA()|T=NP1L&ahf zTSrfgl}t+v|5YX@WxDX_6K~@@Qv^1)O{N})Ycc*3MHB!*K~+B*SL-;r8Nb0D&uxKm zJ)@iV|L}=i?^20dY<#e@aMARYMENt&v??!ZJ5!InMImrZMLFgAks47A!dVHq#v3W6 z#S9^P69F#UNEb#avk!$Ia3Oan5nLHdg16xuuZcxi@54{o_`sEbZ9UfteG$!g zXA5aYG8B(dao@q>-Rrz!OnwiZ8<8^Q&72LMSSCJD7b#?28(t^nq!k_x4yl`$@cpwN zGT(TTg>$e)n!IuZW5&w1er-Zzps7NEq>UAm!y-0ljIxozyi(8PZB|85zOAl8#gIoH zn{sqa@AVjg` z(XF-5z9ubl??zK{o+^>5o2ar8DJ5`Yj!41Vf~;T)eEBn@1_un)$hZCVPW_?d2}wjOI1TmlJ|u)6xs0Odu%lluAN+d4 zD`dkzNS-cd#90*Cd%8X_yg_I&2+uMx=}@-+z>gW_6Hf4RQV?ro#CXLE`8>L}#qoOY z4BjzK|J+TS_N2Wu5&rZAx3Wk!DfX<&jyjG<(lv|G8M}P_W--M~tLlGewpCbLk+wLA z$Z|sOMNRk?>3?@3nftMy;>Zn!gdrduQY#q~$~l_WfMW-(gN3kS;GKki4-ziSqrfan3kaJ(`~qVK!D=b4jVMu{0iCcBDu^d(!IS70Ko4mu zKljWIv{G6kjVK+bUMGrW2o{|2A9vMIFHN*6GhPV1CMIWq?@kp#G@R;^@E#u10*ZO4 z2ZW`Mvori1u_y)ZT0a(?9lqMf7S!mZ#L6OQB|?d8C>m~vMAA_- zzAsbhekk% zM#2)_f#z`CIn~)2_@o2ZU<@hfnrD37p(~@%%?5>=L!Vu8Rpw+=pj4>c!E)mS^)t~w zbHU29pu+({j0&7ku4<&m0;QG^RkTAN+mysS)zjON)X5E!4}8zP87=986K<;!SfG{n zYBaP1&s|eZPZ`Gm9z*2bEhw&LvYBNho_)BPa3Rg%x`UJxPTTkGGYQPTX0EDpLEe~y zX^p{bFp5TIlrNvuJNgIs3w@GXCgV;E-WL4;T{O$}hX>U}&s;Rus~D9Ut?r)5ycVkC zqQ;dP{Ehhp?T^iUb?gyD<$EGbJGWd_w%X_fl`C%X>{#WpG`}d4{LU7i}GTH`7LZOd8f(keVUcURlk2D0PmGS$uq02V^EDzFX=hK-K`9;39+ z1nI@W+%AMo@b{`!^m3cg!Kmqlk9s!+UwC)po}5M7yY~y%i3vHXg%(u8ZHIRbs6=im zU7BSh395=AeEyGX14Z~wc$EGMv)0pODisTAMysE*yw~gpUGO|ouI6Lo2D8n8nmaHuX^aja%*u&ho*!F03IxUrl3Z?xnx7+u@8D;v{XLU7B?T3eR*?<_I@ zFO&+I-?5#jo&(k}A9=}F@`NUC2~3i!YHY}83K_&R&{X>gNo%u`gbPPO?oum?6LR6? z7NL1iS)-kKq=X1gAp)USMP6>6c-N6=)JR}fl9sy)b*k_Di_Unhr4T#yAXU=~;Wjqv zed3`fcCbl;-&0fJN@q*~W<$g{lvbV;CCC9r$HGt+$`@cRd7`Y0lEf? z#?BnD68}4sEiXJ9NoSty9uwS;$3v8gn0^xbV##j;?|24D^cNpv08D_7>*0aL^u6`8 zyxE9!x?h2PZ+r`jBg|}wsy-?c9H=B3Ri&|ss{idTBzu*phz17>K#|YP~FJ@ zJr*7owJ6pxilL(utR+sQd%&h`k19f{h!!j#BNHRFF%PbPW|KI`5B4!rCr@|eH`E5= zJZH*`<4wcMQcazPosJp{kEwQ=ShUF!!`ag=#^^XC2tJJW`-`M?4HlM7f%MH|A}rPP z7A$r{ZLS6Kg3;*?vZjTX<0ZYgj9d(LaCew}U9>`*{uoHHdAUH0~ zR!?#i!IF2DifDXDr{XF_z?J%AJ;#&bO-AVX5%|Hy5y%>;# zfzKf8;Y3iAYmkXa+s1%~J0!-H#&|l^IWTp9%f%^FT+Qp=7GHc=KCGAsG(~rhuefQu zBcjIKDtxaeYa;vu(f{yb!WDh{921}FvfUBq3c+auffX>e3a8`fcjou+Sf2FaZ@OzgHbL32`hebA=0U|3rh{osH);)NTVTf0?Y;$7NiP3r2w9^EP5Y-&#jf)@;B266F+V%__3O&W1Mq@!HNV!IxgfBHvB zn|M!XkcGNx86+|G^xGyqKe|o_8Gqz zSM-A((A>QWt09#+vG$STcc&@443wsF?H0rwe;VidNfCkdWMbK42iOCQq>yx_6eGsz$S^}W39J11L=ePZjw z_0vZg!{|-}CP_~_WTAFHQNVWUi=+7CBiXQ-1;i+syZAGKiKvg3sE|(97n0vE{!HWf zRPDLu;6m7cVvpiJNBAljTsl{{7$Q71gkD`dd8K9G6vPnM)OYSW=J~Jil|GlF4-8MH zq4|Luvw!-^_@BM|){(LEs`1O;LL+f@Bsdq}e9apC;yB{u+JAT7;XN}T3EMok{%;^0 z0s&ZV!1!apKY$;27?!c8vEv@*1O$XsR8;H&LQkJP18G}dkOG$?z&tDVIRZHM0_JV- z#;gRPHPn!KJe++T+#6i#8vwYWA=)S8z5%3e0pWcBYhD<*;RbG{fqh}2d2G!a!2AY4 z>;uoQfq)y}JFg01E?GUI>!VL z%O*R((}(FX@bs9_7!9ai0J;}|>K&ka2bf#{PcHzIJK*UZp~-Iw#5v%&19%_Yc7j z!2rMU88jP@ZQF)m$;1FYSA{Hr`zMXz7gs-wx_!(S5moaD`ooyix>_FS@vso<6NAfx#YTro1)8pl z!>>fQF@@9J?LSA0PYnCymmk?I{+GdLL$cWBwv9`2=Ahr(_50(WSQV+F>#jdPH!Crx zvS&Asy@R*rYi)!~Jg-jLmnYvFysuCM|JVv>`10R>;i$X1tViBNch5H?A#JPDPTMT;L$(c1i;-zd0qG3z6uSbN!?YtSw_`} zAULudvvRXuNY{)wy&9BvjmU8x;n}xX*5Yx>e^wC$_w>Cw*nbkdF17sbnR+{C{@V2K z{gPw_(_)kmSptylukQxDO>wSqHM*yfsYb<;B)&%lJdylSQB{#={O-NF)IlYtXhn;+ zpyr#~k)9ISVNG2b9dB7qa*N!b~ z{`sUCUq%1cly61V6t|-*=nWl-7<6j7e?D<9=(_xt1Z(}3RV!4DKjZfEzu#9G5h(or z?w|crxP)f|gQ5{$9grQVv%xL>(X-(hH=a{0if)}>LwLKT!XxZLmRm#6=w$fBolnR~ zC&y^PVG9Wx(fJTxgRa*kIW_mimpswjh-ulK=AD@+J zbrYRqQz@SK6}%x9@c*Qhq1QMqv}q45Z{jPh_g}U@l9T%UNBrapvq4W);rC4y zD&RfqtJo>7`cx^qvCio2V z`RBiveZGa5o`<$a;LEFZD>ybeGg$5ZXJoVY641IYKP@5@jz9Ju+lN{K^4d#;u!|Xs z(p;&D)+>T_iWx-F_~}06ET;4T?}8-$6Daj0ikiI`V~K{-+@6VG?hv+EdL43P&R(%? z^DKmvsCE*}S%Q~cKlY4SKa0I^v^hf_CaYbQij(;zf@sH9xN?wx4i=|D!AhoP-j9RO zPxcy`jOvJ26Y@!m!8T!~&xR;+jr>Zpzd^w&s?_EDz0)kqwn=-(jKLE9Ek?pqvtzO9#t2GFG~bBR(SD)=hDk zTyH_GoXOH!FZWm|J0b=T&T}Fx?I>TkYC6j_C)%i1h_@Qi&~O8|6;GYT>Tjmpx0`b2 zi7HKV%JkeVjWden_QmRH^}M^pc>gwzVo#0h`ca|s4=_Vq@{|#U0k_ROjz}!2KL>io z_Pz<&5|!{?SG}D3i(-w0DW(0#!=ZD&g=+ z-Wi;T%W~y6yAsrH`YeaW#n+B#U9FWllYz@hdBZ{?53Tu(8k0&{y(;x4SGgh?KThR- zSLGBL)1=Q7`8wrjllUn8;C!S=FA#g>jYD_F@Oy3p$ zu3JoYS6rPid%LDmqrHdLfAe~=cB8eNLYPvI+(XS7gi=_=T`@J@LF83{@UoOhe10)`9L4?B+HnNbrhY0&A(1u)!Ck$ zSXkuG(DZ+8YiA@7p-_6W?Gd1DK;YDE|F0EI2cla(feQ;8h``)Z16VW>@_BAhESel(ml6(ug(IS2 z@K3lT{ZTAaw%F{>EEsby05*jRgV_TA?i&Dz*Y|&_Uwd09tBC9yfkP6rj&Ctoeklny z?+C_ot+;TUO| z>~f<0A~h)j7fEsV$Owf2qeM&*n7s1i@3`cVJ@aW!N$m-9mDW{m;HP&-{Xv9!J+i2L)Q`jT6 z+#VG{pMsOEw2;P?uaBIY^NF{gv!{(SdEiFG_$@+%Bcwn7BXtZGO0gFhT%5Dc`sL9; zxQHVz+?$7i6o#*5iv$IJD#!Suj93}l@$U7|C=h1)79PxiiqVPVZSsvv{ z{#W?1Im*KhbmK5AN+R|WlM#CGHR|akJD2}hO8&EmTJ|0C=bDSVtY8Sf z?UZwAl8?ZPcX}U{Y&Y1Zri1rv8LwV3_Pz?C|8uGxF8;K3W3aYab$f?0aDX_f&Y*C$x9m8`cLjRg!xkXZ}Lj>7S_YAt4Tbe z5Ywltpz53d_6DIHqVl_`5~t(et;k}c(+1LdUrtk;jk&LcX2~qTDbyRtkV6T zdd#oBg)QFmapSOm-|-^sVgrA~(fR%GBaIAMjeSj${hWo<)*%Yo$OThb^jDq<5`~5F zeY5BI6N;gZFs2R@nStYUkdXz1kO%tOR{D}$J0yy5&YQsq@c^rA=A6<jAH0;-66#a;)h$hTw-$tc_=`Si$AtzL~-Cj}p<;G&r zR%NsjcbMqrOVu1QFG+iDv@gD4U_dPL9v0^V3BQs8WaoU9q+nv^(Ga8Hr#aEAcu~)m zqAj>%Wf8F$)4*7wSyu>zltB8qjwa0puGm*~Z*_B+p{6(G7~3Bpb~_+QktWuHJB*bk zF^1d6v@(8w(WdzcXRp8KXrvwcFR>{dmV=R}rEC&oy}hSMM&Xh2G5L5EAE z*_x#A#YFt3G;EOsJ=~z2oG7?Pw1iQxOa!XZ1r<;kj-MNiZ;=Q&NP5Hr+FL|1uy{?m zU`RbXU=-ER4P0*sseus{kTx2N{N?VZ$@b?#DxQY;hG`=;toONRFc>Fe(t@;F*+2?{^(i&_qd?@R!{No$GpG_3F>AT?mFNa7^}=jNv4 z1;y)kW(Bn8=N_ayvdDgaK>8QuO%z~P-ez-0nUwIyhP{pccGL64h^gka+YM$DTF2?u z`NL0w_T8M;wKMz9pUccjX5hR=w4( zhT9h8-y%vZ-|KeOWb%SEEi=n4t5fLS>)w{W(JrH@0U6TPZc#{N5!7W(RM9TgD7aGE{h@A`>Bh35^R_f8uP#};%wN0ypXK{xnfkIr!@EO$ACa1qmHN(= zntJV8NPgY*>*}(uMpf5(=#fFmZPP#PrYy^be%|`SpoX;xOyir|kD{=TKiO*@%-T4D zKL%Jfkmr9CN@|k&`%wV^D;9wsGdG`>)t|UEa~w54Uj6X!5vcRG`9wQY9tA?WwIE(W z9~XhN^BZK3T6Mb{J7t>4gPSD?!3yw9v!qr96BYTqHKjwF|1UEaawkimBRn~$&;p>RP9Ch~}Y58nHAKUiiCUrK|K0Gwt z4BhP^^j%tid%s#WtKxUQtOYH1YyXJ=Jw|o*qCC`C|`SYZO@n5|H|FFZjSnAWIH5QLBs{1(CmJDcCd62NE+4|E!*!C z+%~h?cccC3N~h~P{a~f+fIH#9P6lY5zWpWrplscsOKr<<`oXc_HfVAi=(tPv7_@!_ zl12y@_cVVL^FeK+VW+xNM)Px-FPJHOj?wJT~BB-j7x$=@OGvR2)YE|gB@ zx=ug6ZkG-b_%U;fD`DpmVdn_pNN_Ip#@j-C=kHNULs?_PD?L4)i-|!sNJ1Y6fIH1(M!u z>?Bg@ehZRjp5O@S3ceftKGp3_-~Oa-G*frPbh7(N@@EdYVaEcH!Ru+E7O2qXB!}E2 zhsWofg0Yv~pTP{1_fLm6k|sV+4SkpdtsH}@xxWZ4KreNsBYUPz*SZ|1`iK8cAL-7V zu8o@VPs|;Iq-=W@h-Rg|`ibt9V;L}Wa*cERdXrC{j&R(K#Pd%!uk~V2_d796I8M!( zP7XB4Hpy5gBd6Kx=Vui+t0IeD{m4DNC}9tG2}7BxfcI zrdHnWtfam8+RCtK_iUt%aitHVHyt6rnmi3sOj%me`)?%#BnDd^OOd`WnwGW&?e#9@ z^iCHt&Yjc^u?Z~6F=I#3FUs{!XTMu%Vw@d*1`>yT*-DXHOB&pNx42xtJpJNJGUM2% zl%VKbO_@;d~quaBd+q=pYwmtCf z`~LcRA5-rZ?Fx70Q@1hZeY<*LAc@T#31(~wX0ZF`9|q(SEO3yi=Y|wwYo8HqL%gHF zH0!IsSuwq*>$y?jxkc%@#cGR=$H@F)#(u01(m&nWyGP4=PPP@Slcf$SDD2y;ADUaQ zF`aIuoNgrxVlT=ZhWJ96`@hSOtadYvF%|AMkf1?KtLvdh&Yus)Q;&vD4w5}V$s`;7 z`l6?#*fO8dRQg-{DaSX&tIXDGO?oHJf@?LH-Oi2OPNvhxaL{8fsD97M)d2ej=42eR zl){9r{4hOky|?@M@a*$pTHj#}25p*pIP_r$DTsZL_|tljokS3q#AK8DuNes~9s4K!}S2pud*Pkb1 zaFE`YKP3O{{M+~yo_aD|_$TN)x|ifMndDT|`udOH_4*uC??3cL*o}bApMUy44I9p7 zPp?!PenJ18)TLd=H|#K{KWRlosG?L_M^Wt3ZQNS&`Uw= zIEDL5dngO+p9FyYK%&hNy7hqGjDNqEP{bH0VgN%2T;eD(BBnZ)DD`+4>)pvbwc)mE zBBg-!P>$h_dMcxQ7?{>*S2LYMuTVADXiqy!;8`D%)|gW_mgqUMNTd|^Gfcv5<{JO9 z(tsYEMDp8$4Ns{A{El;h_G{%QI_6i2{d5E0bw51o4a1>-a%}$5X}VA?|B2(1SOoEp zG8R^z&vcR@*r7GT`wPAL@3G7C#A>GVrPP*;^UZ(RkEAdv#xhuZvZ(f9(G)5eer$dozvGU<0_P~(q~@OuG1dMC-SJTfbm~2D-Z_kHfcNxZ+Y<^$39+ZFqq+@5*tc~ z{Yzn>MfQQbcU3ac|E?}SvF4P({k(&t=@3s-WR$&GSInyGITlUgQ}VtMy1V}9C3pd5 zOO&=DQ+uel!b(qqRz)1G0Dhr-8V!XPHAs_uacnWvc*N-YDBN*ISOxc#RIn-38Vv{E zda8a_zjvc(8me`!^RCIWU9E1Uv#b5mw?sy12O44?mN0u3u%7ZrGT|vXF3bM|RzRu0 zGF7Xx;ySnyQHB^?Fuzt~lqO01_f&}?8)R7tm)I^3lS!F?_&$3QC*x((3X+A?7RHv4As?U6O5H!l@YZ}1P?ywG|p}t(9veEzXtnEoHJxoLn7Bz ztDb`ohWAFJyIeI?Z5fn1)_LvgxKOtV&KT=jH{hV_um>l+a0nmHc}<>y-B2+hHekE& zw+%&9S%Hz3H9-;XOZre752d_z7M86 z(L@{aT-Kxq4!BTH_imYEL!G}`{0|_n^)T!A=f8iMB;6UM7FVR54J$4Ea2E&uIAFE4 z`7U%zvW(|GG^g0mt7xB!-_hiUHJ2T0ZQ!$jc>Fg)5|$7o`@j$ZwWqiusqQTN$Q}4R zzya|w(03ZtAOznhKZY2sTOA8s+c*X8u(=N-&yetVhuoaZ)Atr1j*G~&j3w?^j)O?+GgpYB{(M^1LqaQl#A9;c|s z7#Q#@_SirLx`@d_+HhlPG@79fd6`%$D+H1&A})=1N%3`Hi%5jyCO!T+Ok&auc6y}Z z_GEyzviPHmfK%WMd-=TP84X$Rde`2v$+1exZ)n(@=GuCxz-VUD1Nm5DG1a-wUGZaQ zJD}Yt^JvPlxS#?XfE+ouNW!*!xUZKdjl$o0SyjC1j6qJ77PzPM*f~*( zJ}QMVfM+s^w1b@m!H;2i!9ySVE41Q5Tpnz zx>KHx=^j*s=SH>me8C( zbD>Se=LRMay^o&Nv5(~q9_2a3jEeFhWO>*NC}07If|auiz3B%7J6iGaQ?R>pa)bKXg!Dqo^dDFYwwU##q?EQ+Q96$jI z;B>ooP31mCyw8RDQlT_->VCmz-KLVWsSurEiz|R&{tIx}0!Je2gLS;)mf(y?vXgLc zE4%}VX4oGQ=&%E7tjbhEQ@M6Uag0mL)#uGuhJ+Nc2bM}=7b|eag52z88{mKl)Fa0{ zMsu1=5(FKP7rjF5ZF)J{*qQ939ubHDPC2Z~8GrT5H^r`qeK}v4mGi4zMYMInD&GP_ zRFw@-C5OlCfXk}c(w8R5KF&*CqDolK8(rpDB=vv|Y>(=B$ggJm5ofS-FSK0myP4R3kY@59ZV-gHJiJ?B3{0KQ1xu8n8h=g)Rk zNlfixi)TpFE!s7^|Ms?*5zJ?D*Ow^BM3C*K^bzFo6l6 zJK1c<{CCsZ>7!#5?j9#^((QitmE`^d0w^c5VyRB`vGX~VE6@49!_IP+gMH^=27HI9 zzF5km`~eR5ebX~PeB9n+2cQT2+<~C+<=^frFOWdx$;@}vuRid5P9>^4D|_xQ{Pqxi ze3)x|@183b&wNLBJ&3>l;>*C}M}Pa=V*vjh96i)v88ZY#%!Lsy!3C18g|XQaRQuF7fj_3h=+FLq7+AfZv-f4Aj6PtRo?)Klt;& zqieGcbh9?2r#dS+^h3EST>e4+%fW|>wAULueRDhy8@DVhH=oP39YnGX06H?`E()Z; z3oybrtSEnYJ0R#l4-CEfn?Iw|0St?Yk_$o#oIpJ5J7;r2+mGe1$q^dGemqI~lSY9g!LGP~KV-u{oJHSjL0Uw)_o~HOEJM|! zycUea9+X9i+elfA0DHs4Ak0K`bAgg%$`Sg3e!NC&1jr?vLp~fi7huSPJW8b8NIa{_ zTtq`%tFf}XH>zt#v~xC6>%aaBONZRMq6|qulz){6-;75Pl%f8&pQCvl3 zvqT4w0HicbhNQf+(>18ON&ah0ouoyKRLq9tyC6Kj!^A{31ipiGfD7Qny97;|>4zN9 zfv2QHy}U;LluS)gw91y~2MpLu!?et|L`y+DMzlLO9<<3a6hysKOouc|S^UPL+)Dj} z#md6~W(>{cB%Ftl0n_|})I>@6`%53tfmR%eez*V(kN{ZxJ&**?x1_+uG{&<#MxmTc z#iRhf>quSe$jY=g@C46f_I%Uw^;-}3pF_ll}&|INFa>939wHG&;WG8PW?ntN4bZ$vrgy) z&^heOqtiy2sD}&CfasgNqufe*jL!%?KeU`YAf-)@98a{IfD1)Tq}k z%*@Kf)HdC_Zw$l>6-1;Yv-pftI*m#F13n>~yb0h=3D5ux_|rgz)m<4>LIr}S?13)j zOI-C&I?PfXaMY3D2T0{k4R`=Ez0}OK%#Q@ZO|{HUy-c{YOqo>E;#^W4#l*s7RT0&I z2G9VCi`8$%6)XJ#ANT<*{m-XFR7B0vUDbge@B#chiHC84xlGViEz?X?()rBPW&Ryc zG>y-XEKUfRJ`W98kX+CpjJ|_xRagC0aCKM;@drXBS05nPajjMVL{xs z*v?iZ)9x%*fIU-a9aVbd(T~j6mStIi1z2Q7Sb?QH*wg?Az<@|K(1+z&3*kU_Ez~P5 zSLmczLe0{O{eg~+iF_`Rcnn|AkH*wR$jbFJ7~^#L3Z0<|p(Noj!X%vlNG&SG6qbfa4E zjLntx&?enV-~-7#Wl+Y&R%}gB!i3G7#Q>+(0QFp2@ z1ufI=3|tMMUmHDJUu)j{O%D`$+lr-Iq#a#Rq*X2r-EkekhV_U|(E#uLTl($J;*Ht0sCxK!M)kJjNkDU*aZbdC+%Q*WKfkgU*V8m);n>Xp+0ER-1>w!S(G3Ps zCOt@)d|yh9U*oJ?!5v}=kW{k80PnR=8!Z6^J5ernWV2Xd90=ozgaZTfK z%>m(4iGCmf*e!uLHrv_dPJ69g_+?0hHB zWwqb|76xNU7ULd>TTM1pN`6~0=7AYyiF>#J5}6pWF4`P`;V@3)ea-;{<_Lc<0Ul;&8(m;)4q5JeS_mFwj2>bT&gO>B zX8Y9Wa+YJw&432DVvq)D5~v58HtDNwV|vcp?4?*qUS=+JS2fmTHSTI0fLD>QGqg46 zc1Gw0mg921QSMaL23Xa~^I%k7)yYF@`8DS`-e}of*q&}@cGiFsK!FoDVXRi{uy~jt zQ0dSOW{MqV(T&?MhG~5E0hP|@95`!{Z~>_X>HfAxXhe2e!By4SJ?G<CT%2v{YWCjIzT)IXfnDBQt6uEiCJBDXfy`d%=#^yX^=dH=U1A2~N!D8iONo6L z0jV}P=#Sp*-8O;52JZNd2^h-k zdCuFF&Sy2g>}8g0eCB~1$bo=92~Z{h698!*M(7@H>!wc7h0X4##a!2pa8v$kzaG}6 z4%s+9TM{m46u5xhJ^>RTffVRv`8IL17H%H6fs_X08^Gr@K5j_{<9v>6;#TRJUWt9k zhg~*sgJ$O*K4?T1ZOqMF5f$(62I6wY{#k8};<#>Vy0+!?2JH22=TRQ)f-Z0oFYy!S z@{S<67f9(9*X+k0^UU@EFUIUIW@+f{WR~y;5?BEfFzmzT;qzYbkp1COj_`#Q;-)s< zz^!eC2JDBxp&&AxBV#sM!zb{rsSi)i!$U-SdF@`A=~At&-x|LJNrayhQz zoF!%1-StEM_6$ID`i0#_M*$K3H-Qx}VPeO3kQmJsPxg5Z=6s%K`~GifKXYoY>1&?| zei#8#k8?Snb5nPB^&V|3R_{`_W~aUNLnibpPWM*5?skv(L~rL^mTD3R@fA=36BvPf zXL*j;2OC)Nm}ho>uXcd9bQV{3YQKSZ-Ut*L0TobzI6r}*A9|5z=YwYFrxtQ5Z&eb; z^@U}1^`2(r{rHNv@`&&C3ovX_&+-u<0T%G>mY45-h3 zAaSv`{EFxY8-RHnFnj)Le|Ba+d$*r+0RA|8#Z#-xPjy6&l^5(@W>&QhtHx%ZQ#(EqhHB<_{hB? zrLEARV=7XZ;QqS8#EKIqOe7>o(4biq88i&kkl_Ns406}bt$Sf^3AcCAx-ICpAc=wq zQIHjTVg(5k4ZEgLA&p|q$dV^hu59@-=FFNmbME}nAB~(ic{UwtRA^G7NQd^sA=Czq zdm{Hu_2#XVHc^5`8A`#Tu|pMMO^7XA_ACm48T_`5TLP|Jwgd;BU9RB*_30&+pB;$S zFyXPpAwE>mg2iusp4YQ)@BTgf`10q+2c45fjv6<3-q7iKD1fNpU{q5))lh>!An}tA zIizeO$PuFCrp+tUjKIPQjkT}>hhrf`oIzrpRZwyy=H=W#+?f?!1`TYNmRT?wln{*w z4Mv;^{yBb?LWU_IGlF{b2{|N@MH+b|l1ZZE&w=^nz!OtF?FV2}|3&HAPd(*;gAhS# zv>-mEw9*PGt-MmoD5PXFN+H(#_}hjKfd!U_G#)f#iOs>K-HC6tr5su_Y8R+rClEAP zLOBxm)j|-V*Fp*-^aGiam0Ef!rkQHGDMt8tl>7A*rB3+0;N?XN zmZQy>*|bv1A+3xuh?v=AW6Uxtu+Tya<_Xs!Vul%tPziw%6d0Z{nnyO{gw#ePbk_{owj}Ne>+7T_O{?!XnU z-`p$((tyhMQmDcevQSgulh?dpQ#AO|00$!Y+~uGI8ytWt1o;ucAV85TZIDfCqUf5M zy4DI?bqzPwK*ll#$O2&rXG00>pbEspF}Q88c+jd5-%xM?5cQ5Y%G=`G76_Kyv5iGT{Q9WfyBOm;rR15Q{$35~p-EohW)x>zM#XG~wkfVnV;x+GqTc2$@FYqh!~xG16#~mwnh}I+WFth1 zH7sGF2N}mm!7=g?Fg*6Ln8rLNGD-4Bd5O<*>LcX&7ZctYW zQ4B&Ghd4qKj^T{i9fO_1LSO=0V1hWAa*c;s)L7o8$~129{#y<35MoUE6`2XAsW{~& zJJA_MXDFi{lX56lv#Qnay+C|3h!;gGD%Og6?mp-1C`KC@0{QvR6QdABOSQ2ZLGZ5? zoSfyf(J}jSN+&`0L*T!M3#`=z|{y@i1Pc ziB?(@(;xykh*2B?3CuW#Oyx)}0?sZO;vyDd&GX&DlAy3_ToeOO4A2p8g}P0(o$aQl z*@`h28O^}(F-A}TbGSpa+Pg21gDhmr?4zq80Kw2i@YMoWlyYLli3kP^TY1Gx1oZ%f znqGl~t_?y$XDS8Q%#@o$7z4vIm7`ym;bGq(a9C|7L3E|(kiv>LgexvF+Yp<(1SST? zAkJm&EJnKxGxwJmeg-qvArEW7L%u_PG^8U9lOl)U$g5>-fyY+^*p5{Ma zC4n1bQr*@hmaB-3bflmdfitKYYvx)k8HE0;H3AFg&RlY+F>vP42!NeH6*Oed$Aa^* zE?dPm7E9MPlQD-uiH!C_quR`HhdkK9Xwpi$+ur{6NA{sw5g^&Cn-<-YH~nc*Q<>AN z1%U`ca2v9T;7|m$L^_-E;bk1&eg>!DMt$08>8#a}~*{O>K$3_st z8N}v=b5sRQJ#zhWz1L$eGmK#kc4V6!^AIMuQ?7Dvi@VYwxb#;+5U&}4;I%{J^w2EI z>6xp$(jg!RIYr7V{-N{`4Wp!j2T_gB{+p_@I|e#$HZBj#*y1>SW9~4NF%DS~;t#o^ z^c0@U7$3a6(<30cpy<~Wc)S_Tfc{1^m@xv8lUyG1pvR9_uJ^s0w#XllxzAhs)trm& z(>Wj7rUxIm-SYlNyvr|l)v7$Rg z!eU6oARboO4>+vfz`69b9yIm-nu1ub_p|9++CP44Bt9fL$=9-qbVN+R-iGxfCs!> z;8~i?-5jR9R;3l*l10=A{#Kg&gw!LQnk7w=OTpD!`5QX?+jg{ov^ln=Xxj?VMhD(N5vi+QvzhR4qea)!^H?9o+pJGk}Al*`1=%0}5Fn7j|Ly z1dLP=zz2-s2e{mkEm@@jQXqxK2$CSpwbt{!03syJ5pa^ijEN|a(;#F6H82A+Od&MH z8t?s8nrYaE!Qa`H9S@E`o7E2e*$&kiArBH1?hTqD7NE^YRbM&bXR(*>9fRhPoI9|C zJ2)W9c_AvMqR;F@Kj1?-lma)5Kn8+989Lv)sbS2a;mg&4%(YhH9huL)fH9N_N*z(x z6dmUEN|~VpIs{_==cUtnq1g?}UkQnepsmyFAw$go;7yg6t-+t0ot>~KA=(w39Q~Er zO;x}-qvnB@HH>0A3?DqOgBGfyJ>Da_@WWKBlqi@&19Six#@lL@A>h4S8}?!vijR^3 zc?jEymz12Z(HPF7p`?Vcb`+rS-X6Bb~H&5oLNSSVGZN=_ZxsagEVWC0qKGB8)b zwU;0&!%qI*Z=QoXoP!lw12_!jD7wRZVJ3UFCryAM!5kwjjKY|tlsCKpKzcw2NM#v@ zz~8NwK&GY{Vj8?*<)!(j2*@E3?dGmD3`N@JnplHIW@IzQolf3ZtbJrif>PAEpEQ!B z4*t?*0re$^MJI^fjGFnCR6)@uvS0drRun=5g+2p~GQ$9f+&bi_JM5@6OrU%ID3H2@ zte8S6Ojsd!02aKkFYM`ZEX==XPLRuwhuGN-7q^<0x9%5cK zn8P__q&iIKM#dV3@}3iNqQ?y!I$6&-q7w^Hr%Yzz##!fxMxCERQ4>OAnmJ*Hx}6k4 z!ylf*nfj(VBmwcQLp$u~I)H;aY+;aIDyE7=KM>3|h)EOCN-3B^ArxtFJtYS`>6H4X ze~#hH5hN`#WLKKuK#rl5M(GHY0xW0^gHF;R_)jTNgE=t6IW*%lC}wc3AMXj={!Go3 zU#(Y%0;)QZOLI1-)Rj=4mZRF)+Hr2{!1Yyz3Y<>nB;3UyjiSS_0-rIo1Mz_aDV8EQ z=uD=@tGs3e!FU5xY7)Lin8f&xRnR9nxPX3+W|a141_C3i8tg#6+uxB}t9qqWihwc1 zf+-*ZC1u0HG*KQ}gRnk>=4E6voWs9WTMY){iwc|*dZaJC=?J_j6Y8G(H7B7F=Ad#b z6sgy;_LWR|VtZYvV#+9EYNVp3!(&dWJAi{Vtiz7d!+Opu(_-d6@IyIpQ`m$}>WrT# zbV3s72000WF*LxbnkK61Cu=pp7@j6+GVJq_TN$n`t$u*^H2@NHnZ#uN!!{7n*o?w7 zSi^WKDl;OQ`Za@ht{>pOWev(yI?*5$37i~dCpv;2;Z%=yX6uJuPq#9ww;E^q@fF~% zpKwA$-)bZ}sDnDhLp(5p#+qk560JMXLs2%Z>slr&;zKM@q&9&W);L(|aFhMyhN(WO zX$tJxjwWfc?ce?9e^%P?3T%|Z?R>5dMQ+133<4q`0`Q4vn$jqZ%4l%L%GuEF_^q*sz*2WX!NRD&sK zlf`PoHr&cJAVCtCX*}#L-x6!c?j)P$EO$l`;HHydMvlwPn1Y(O;>g7}TiHrVDUB*6d#Up%Bk&@$uaDxhL6 zajeM{?>(VR?cT@vunr$5&QdZao9y>~oLjmbn?_;C#-L6% zIJAQ`yu&GOu`TnRKHA2Z+D(Ar{PRbg4L1TtKp|`s8n`S5^ zzh$xtBFVaCAOd2wQ7AJ!!`_N+JeWf|2(39(0|28gIEcf$=G`qn^pH`6KJISnL<~z| z-VwZ2gqR;ny+XZ(sy3KHHjqODRDcI;zy>h0O6TV@=kddKaKP582y{RLOc?ZT!rGt5IeXj=1$oCkm@nDP+S+ zy;YhFLal_R1#Ex?{I2inrwEv)+kQX?gs@{PwgqdS@J?yKZoo;y0y$;FgdqY8-)L`= zbvnSXIy}R$Qs}X!_WaWD=JpLL$+flwrL{5cXIM&W};cx@kXD8uN2 z{~LmfYqim@jQSx@GGmydGBboVLC3>91RpyX141)2HGso6EVMW*EsHn$9>w)$qDdY? z2wIfW6$(shwx!zb^}N( zB1}U#U_)9mnmNovh#xZP26X;!du%zYU!B)EBX=$+bFTL;c(da(o9blX&agSx`I&<* zGoJY$dUeqDIU<+!h{MAGsC6uhLp6v)aVxi@ue%=gLpkIjrsr;MblDN`GQ^yk{ZMV{ zRMKrqOaYX11&sQUd%(bVz^VE!Gpl-gKX$;Tx&>4~1K{ngV}m$Q0~O0dI)wNIh%IcVNjqjEficv&+8 zI|yw6xPvuh`8S9|#UK4Qv^Bdo{o{aPIb=g2EEuocp&$G4?)uNI;O1@=9qK5IU-$L+ zA(1w)F-jkHz$3Y-oBn#N6THGZIm0jW*AhIfd%z)Z!!&e*u0N*Tl{KJ~F6kn&=!Wjz z%4mQyV?Q^8M)GX6K$Y_tcbQ5!fQHeFXhQLYVF*t(-}H3fIGQ4P2FiAJ+=PEK#T%_IQ(b z+M7DTANd=@G2B1)!TT=TGrtEkzzDzsmYcgb%Y!+{!#wypJir4gqcT`a@i_k`(Dw6% z7x=MKesFqcoO9l>mpRW;`$qmIG-!A;hOVAlFF>3-r|z6NbMX+)o5xO`Id;|xfD_m5 z+c$CGEPkW6{!d>=j~_vX6giS)Ns}j0rc}9-WlNVYVaAj>lV(kuH*x0FNittKS%?G) z8dR!Ot5({MYEw!|)F@GcS`i&oDBGx_+FrdCz!Qmrfl) zbmyL(J4WzXGjzs2qhkiG^s{HsV536^tr>0BuwNg8-K;im*tAOnFFkwqYjn?KA6F+^ zU}tsl1agj-ZeF~Dli{tiwhkOMiQ>Ld%Sf-^PV?u{r&qt8eS7!s;l~%rv8T5~QMtV~>y=Wr(q(5<)NddmY4 z3-jwP5jq&`FT6Go%)|{gu%Llzrg;n;a3qt59e5O?ZaRd_83;ONI7??B*U&Ky8rhCP zPBznITauaHcB@Ud-e#jRHr|jt?wn?jMDCp9J|n0zfuIX=I)yHq$1)wQNy3MhQopIgS3Y zMxJ?=g@+w;(t$QwgqV45IcCr~CLJV4OD@W6WqYl*+f<{HxFw-E<{a9hM6NX`(OK>p z&*FWi+B46oRZnpiaP`$#gPjX5xafil zSGiOatN~r^s=xyeH%OwIi>zsf9e3nehew5~gJ(L<2!d`Pb(k4bASXM+HaTY8RgE@g zj%hbZ;+oNo+}EH{o6IQXWp3<&&_sx!%*<(XYjY+uXB~Ii5$~~Y!Z8-%cK-I9*z(IU z&s_7(bE>!}a4kZDgR+rTZA_}4ta=Ze&JAEWK}dHw#aF+3Q@2&P`#;H14r&~{)a=%fiF@8ym1rTF_5mci)i(A}e zph-Zl@dzH{`_XgGAvQDJt6HI%*E7;_oG>}5UFull8L=fM*(@hH%Ng6e02dE*=uwa3 zn@6;$(=2#QMth5M2f@OV1P6A*SdkOQI3Af$g)Wq#nA->bJ`Qn+BbY)IrXW?zY^jYS z1f>v2_}C`5A_|Whf>M4cP|KI(svw9cD2u3pM6n+Mk)0Lzl|xZ^{Ou5n$wxgWM(t)C|lvSh(Kl;WN}w>$2!_UMT}4b8}yA_eT`KP!|s>A z{q=825LFJSu!1T4DTP)b)Uibg$cCBn3e7+`2-hKHwL~Ey$2>L&L{Os|*gy(OV=2+I zSZJmrXn+G80ILZ63|17tZ4!0*mSG}sXtni_19Ulo84c`4i)*Su7_uxkc`YGtwH7wV z_g(Pz&z#PgS8CWee-ZkB`V*Z{ePr#dc_iI~Ng; zo9~MaIESMge7f_w(VcFHAy%>EfW;_ym!PLal+c0@-BLDL6h9!LEQQdIEI%x}pdevp z`ymBsAxlDQ@TM74%9}A(sFVktinC{-DT*fm+XwtC0=k5iTY~j*B7(d_h=C%igSBD` zIN;UdNUAfngSBTF5Z7)}NSEEp{^f&ED;?D`23w&+Z1FZ*IZgIr9)s>&=_ps)e4NhK z+(f|1xK}bTmoLHy8SZX~o1o*Ev%0|^cCp8&C$A8MC=(PR33190NAT#WN(WL^t&C== zQ%Yu|5~@*&tPn>SgdYyE$%WSqZc2KFHL!7r52jS@qA;-oG9J8)&-SLno9(Gzh1-(% z(k($$OaqM34mwfM7*@<$zz|o!T;G#A_q2|*rh}$zTGdQJH_|}L<{Z!nN%sU{hQ7vU z4lXmDo<1_iLM*d2hAc!!P<>_l010g7bfSVA5aGlgU;$w(<1C=#g2w@8D|k8&L9X<(U3SxU}PHxM%7dLLnG}N2to_riqU*huU}qd~R(=#w^IR#vEvEd$?mA#DO~iYR$OLuioq$x&a!wq1>{t8m%$x5UU(I zh(h47WJ)Kp^sW>@Aqg<;LDudpO2JboL}!X3K~^VZXa>+Gq)`O#_i)4E<_0;8!5jo| z5Xz!t`U440OaUWc;~;MlDL@h>F!O|`r!LRNc4@_eM*$;3BH$}~0tTvrY-^J5_;B+O+_2#tzU~^CvMKpXlA0nyDhmnxKv8a}b*kbk=1m(&!6@QRLe4HI4(!9& z&p>R*ES|z;3UErG#5X1lOt6a?0x&5=CkYNgAQkWdARq!J0L2>70w#bFe`fMp?bAH& zReVMhBk>?Pa3VfXJAg7^bR=;YVi#@h_;!vaH4}WmEUTQ&nu70ZvhdSr~#Lv;!WX>b>$xxNx&^5C%Lt3>y#u&Y-ayg!3A<0Uw<5IFXZ~_@Nw3 zM}$~shnT`FEJZ=IA??C2mi7&VGAr(wg5aPc98u>LK*hjf$wF2}q<(L0{4hDnDsPbB z{v8h?D-NL=5YYi500IJ&FJa55_|m3YZRK`J)Epoa6*D1&XypnrBRtR(MXB45ShK23NauMziDFOvl~sR0SCXnUZl`QYLB4(Nd90o!i=?gydn zBQX>R$Lq`XXgZj|>7b=L&Vk6f==e+&*Mtl^mSyS~qBbA(uA;AMgey;|ff~YrzPf=& zw~iaIAvmvr8i}-6jrC!SlpI7!5G<;}It9b7Qa>7P0MYOZUB)Ucj3`Ftz~HbzLTFKJ zMp_L-5Rd@6zC~`tDPQ77AeaFgV#p|r0mTv#KNGP(ZE8

k%DM0~4}PHBcdir!5vS zPX*v2zTpGgAsMacQH^jiG;&9nMXLNr2)D@f;Neu=%Gahv9a5EFTF)|l@q0M3S(xQj z=K*VsFe4XM8R6?Yb~8Na3ktbTI1hmvwt;57?pSqpX8{HLItXJV}Y-oF!sk)rux{duZ(lGg7#2^8+s;Par59s(~7|ZW_4m8o0rA zq465XtqOUzc5T-@5XBp2W*eM#|1f1_Zb%e7p+VdaEm%h>#G)+LkHQ*+cVOxe{Ec;@ zm4sL!mPiOKNUEDugS$SXORB4EcF-8EK`XN1Y~@vLCtv~5cm4zOwJ#--5%<%k{xo1C zFCiNMFw++T1OORt1UE0z`C@I%P!@573_>OLQZbWj8rN&OrbmRZ*91r*pv8M`k`xWd zk8F(?vu1I!h}(`ad!p|fJkT)+i5ggUD2MZPw_!(xlN-n(ux>YoWmqN<3m?28DkkL! za7f}j!4oK@EQ)z4O2&szMJO)ClSttZx`KsvMow~XOwPn!m}8x+Z1(tw8cN|B&h`QV zQvxIa#R@Wi@ij1ECGrXqZd1%YGwx99IO7H~k3)|lCgL_1mSLAlS>EeaE7cloZZZ_2 zRXI|slCS1&&Vj9snkdy(3prLN)4fhFMrW0A_}mKKHU->s2BZ5uWw4j`J0)^Yj5m z06aw4lOGjFlJJVMMna*A7-_RIu%j{$=uHf$a8z$=gbaZW2lfIuU22f%+CV|0#R=sU4axQkT#9vZGQF z#~=;}lX;|o5|>AW3}P3;fI@NV^hrlR5oK$0!J%r~v}fBsSt9rfa_lQ+;cOay(>Ei^ zq_g1~t|34U0ftk%#Emu2$RQSx8$t?1W}rf6JV_}IAqjjKLJ-Vj)No~L`6^fmrvYy( z8pJ{>iS8`aP!-~ukd0WiR;^ArNUT95lu0U@9P_>zt9 zn0?teyxSVx(Ks(1Kmt;rkTe}P7qp6E?#^S4*04rd{JbFuILIt``ItpQk88+OwN)Km z^)T6=G`Q*pnjHX_+xFct`MH6>Ls#F7pn?@RiE|rjmMlP=EJlmejWg9*-Wn4tK@N;g z6@{3qRN1E@@W!$z{)Pg2HK}z_2x|SYED5AR+E2+_=XwPpWVB+M5zOqGf+om$M;|`A%5gk&0z#Iz?{)JogW~bzna|FcLC3M5%IL$?~|Sja$eycjURw|NSJhQ z)iJjtzT9hJBRi0TY%-K(dtfz-C}W=zy^;|JLJfj*gNz}t$6=wVy?SzS0M`S5Qr{{zM+<7F+fW3KrC zf}K2g?AW;zSdbk&dGg%3V>nMQJdt+FEHVB}&i{ zQmqJ+B6UdAp+SP{7WQjb(4fY2N0l<1x78pdqz1Plm5r3B%dIpIGREgvx=R2J`b?1HykC%>_@ZG-S!Fz6wga!=~Bxsm0!GQ$q5Fki^FrmAH?&Kqg ze*ob@ga{5IphurRzJmwz9XPmP%qBQ-Gxzh42@Xo@3<%CTC>``rMkzJqP)ZvW)DSxt zWyFv?)+of0JP%gb&^if5=wXBGywpxgFYRYdJJe7E4o={#cvCpy@PrLd-C!e>P=|EG zO*hwUlhi1Dc_!H*t(bz(TS_j;WRp%l31yU0PDy1|`}9*zEZb~jm^OTsHVP7^X_MGp zg7jtBD}adtRbPW;qYWuXAc5OwhKV+cAVzM+ieaCvCYm6vywX>mbT#%_DYa=s=>8yr zi1G@duaqK)G0!z;TyN?0#tf#-ZHgRk^Q6NL2^UOofpyzySDggtx%wS_-97N0d$htw zUU%-9H|u-$HDC-j;^-94P5ps`EV3>IIHE%*S>w)t1}6B>It*F^k~<$&h!D04uJfQn z3N09IgAO6P5;!fbGm}d$iL;J4^4_#lPT16V?=(nMbImo_OoPZFKW@1VH`xf54V%~C zDT*oiR0(m!5>HHV#TH+z)js?1Q;uw+9FgZBLJH=kCxSfo3ZRM!>7|#FwMLp>EQ?~u zYJzwvq-Bp%3aOWbLG?;&bg6lSAg?e=<|vG%Ny^cph~j8&yrlqlK#0F%4s!9#WBv?q z!U1QsroGKmwQm%q)4&B8XmCNQ4rpLstKN0zYJBm*Hy(N8;YuE^55S5aHP!G`(>EM+M{%rQWCoI?N?n2rQ6fB^|OU;-GJ0Ia^_{+(NC@IA9i z4+(EIHxs@pI}R8Dy<{XWo4~|${F#Y00+gcCsY`JV>Ci)a(M#xRaDQlt(;3O)H{P^J-u|MoJyJaKQ4d||~X z%69}KLCSkiW0ap11rP-Y$V+piZ93EGAaxv&K@DzauE@OGe406{ zyP9yC$UKz;8ek3B)nr8hieZbEbrN?4=p`#L$PL*gAa(vhE^_TqiHD4VM0|>?T+ece zhx+3Zkszy|@sbxfsv!;*(F-Rv$_ebaF^!>Mql??{;vo)k6r~KpDR7EjHd^7C+s5Ky z9WAbLkBeNb@S`8nh(r77Sl5+HD!mOjVO->(?LLHHRclqAv^&oLLp`|Mq^a@P+`een6Z9gN&+hd zSP@++gn$tot1iJ74+rLQArdwR3N-NH3S!_o8Dy0QHR!>&O%sH&QZY197`MHhxBCe1k7*HG2 zC@4Om-B5fqjcpu)8;3YpZp|nfPaI8qLGy%dq>|h?%X!Xk+($i9a13QYqZ!Ol20EVc z3}`&V82z}eTCij?SUgQ+IBP}165|&yWfC!-5tPdgVd*#x;t2e+&1zo3Qc;*pdWJv@ z5>iH()%Z_%jPi66Mwv2F2(=L3wT(6kkpxk@tbT&%1~rmkjEg8_RJptwGnfIv3wvZ# zqw5d^k&Kj64$z&T8T4;rc{)gfaiAWxIA}O*9u~EJ;7V(3p8Mo-y-dFhd&l z;Kx+Va;0*xDbj_3({4*+zA&wqQk(JQ(@JwPNII1=-ovk>kXi_(u1qzNR#R+{>ZM2> z!hibf68=hI2&(!FDYp$+5~fiNW2D3y@fgU3BNE}eZ%UV&n+HXBDGy_i00kkwHruj& z!D7laR&HD7-sS@<^l0aV4>++f8!!#n&FG5y5gb5ERJeEh7+#`u66Cd{`Eyf^r*HN2U5ribr@a`;$?{}glZglQI<=8 z`qWPgbDhx)KJS_4Fh|GD0S)M5)I+2{7YmkTvHaJRA{&%3QX0?unxaN}6h{E=U^wlU z^s$C}EG5&RJhOavq8b5cC#6weqQ)4Ek{Cx|8Y$ByJOw_Ua3@bA3W$IN`ce(RW(^Ag zK@71F!}2<7h0U8i(KsxG^YC!wQ8!4*gJlfhdTB zh!ysLKt@u zX?3ArZ6YMuKqu`x0M)3fCv>QEXH6B_0$m*VGVZ|5fUMd%XVQL#v1~041;$8gGY|jkpbD( zL8*dm#)KWNGI=t#9j~$-CpK57azSiE0u6u-h=2&KrFqvRFQ`>4v6+NV_%8YOE)aQG z?xK*g{(jz<~6tLw*1alPJkQAkG2z;@f zeNqaMQa(51KTiXmk>U;Ica!O^CsoLn+%3QC^a3z*QHHCJIQpmzq3=7-%y$pFO#gK}mCxc%Q?;490+;z(Eg`N)=ZU z7qB2EM-YD3Kd4vW=4W` zrvX%=_CF%G7lh)hX)>!kaxc_?1SnBi;Ia`P2oV$_5fagX5wR^8krM16cqA}*8c+gg zV>Xw0Z6l_R7lf~;@`H;fgWJJ2SGpZ>>-h?_( zq)k26V*nzirvqAsC9#1sn>B$iM@S>C=@b95P(yJIJJKUXF=k33Bz-|Ad#OfhA~FD` z8Jgh=& zS_pYaKd0d`k6|0+Q$C1M7f(T>rI2y7QzJ(xm??1(D)E5=abXJKIP>rj5(W|y@`2V6 zj+429C4d5FLyl*2j)rHi90ahOd2Ot6A5dBy*I^y#mH`bg0>-dV{{Esx-LMm1DkIFts`DRU7@R(~9}&5P`@y`blczuSyT}>6ud_{CcChwR4JFAV{*pUFQJ@9`BnQJ@ zcJUOCkw{3zQ%}>ktiZFLkcXaN2(&Q>Q!uk&+jzAU}!H8cJ~#4&}X>mlFc{tstTjLnILn(n}bD5FX(z zDKP>h(8Qu!0-`&*m8k*rY8@HSj)-TP800|{Kphy+0CR;w{->F3z$Cf_Pym^CBjJDu zIR>V}GEl|Ry9-NYEm9M$LuE0fBDj}?En-8cMW&l4$jJGnSCmD*x5hY9abDyj8ix&W z*bTFal4T}Qg;5)-VF-d^zCT45_0_kA01BQ!3amgp_-o3i{1(!n4p9rLQG0VV7nDDV zbASf5k;n|^kPgpa4(iYwxNIpFvM(w7m$7PFWA+p&YcLwD6u{GqfU$m*JQ($pG}`be zd4dGi15+o{mcJ8VjItT)!&0*`D59i*J%by7(h3SX2!vV+3gsh6kWHv1dmb`(146Ez zGY?BVx$!i_?$E^ISOO#?%jDb{#)O?PjW};Mfh5$4b%AI#ns3eIE%?WqkkRox{WIDCSS)0xIDXnqbw+SNC-`n)ByGhN08L7;0in&%Bz5$QZ3*EZYBE=4gGnaNh`H` zcAtTE4$p87fA(j@fy)N;DOQt>e#dVPc7d!3FoGH|{qoFj$P_^`qZ*t9t}s=p=E3=Q z8hSAZc8fo>reAULT~G6&5E*h1 z3jt5o61kAOWFw#gD$v@k9or?40sdZI#RYxPw|$OajIWzH#)oGe2R(xaT>@!yyFw8T zCo2?w(|ZXEyt64IEPb3YG@JWj-3}MsffKwR+gh>-JAV@nYK$*Fl7?WEP$_#`7>5YG zRX^tyJx>QD5pR z4OGjY#Ic{ej42u>Kt~J@XlxAC;M~=4fx#Ezl1`(60f5TvXm;@#n&e2|InEYJ7vCe; zvW7Boi#|5Ys3sFs-5x26bQibr8IMLr?wlhzfdt)(Lj_VUAwoI~qGZ^DAQEC^1LCpaSjwT?U6Nd$cPYea163C z0;V%^gn+ED^fE64<>xX|P^kqt#WD?td@uOoFS`4Yw!^X!TxLhG4N0)h5w#hP#6ORr z!jDl1u3!kCE^Fn}37y~veG3Y#@bo>)3aC&H0q*KoZ@-#q47Dt^Uk!c{E@-{34q|_* z=-?@#B0v!I9Dyg8Nw6;kz>mfq;w4EG;d>3*X-0v8D1bp1c+WCk!V3FCqD9?{PL(D| zg`#_CmTtyKhry^pMS*8j3Y9JhA^Al-5?c~?I8ewg_rww#F__Vk5l6Hw+M+q-Vhk#f z0xR(Etqt%55Bp&LUb@$2x(%<6Wp0iMjhUxQx+w7G`FPnm5?g->FdkhE&v`|?_i!M; zIyfPQI>FspCUI_D$Q(%xI^k=8s>rd`$Xgqokj^8ckjzP7MiP1%cv(Mc7HbG-zM|Z- zMO{AbYwGXs3ZUQ$P`?VWkR({o|MrUyItLKXnxSKc?wLAt=%5*V_ADVmW(^4*M5s<( zymRq1s+*TiBfNO*(#@M^&Yd}S)~X??h7H@amx#D+yN2ixw`<$7aT_&iTd6~%vXv^8 zO`En+gG7l!T8NY=L8J-^67{N;D5-*8Z6zhBP$5rSUqRI>id8F8uhMoEboEfHQQArg z6?$!Ew{8B@5V`zDjheW2?W}=Y=WbnL!|TAYbC-CXyuv9ByIU-;absgCQnXmH!o&&C zC{C0hT|z?!(-~B+R*gZ!Yu6ZLYmkjWg6j;lU!Tr!p+p80C`gbnQLWqYZsEGQ?1m^D zwrk77RSP%0`t#@5!hOT`jr%uo)WuN?Cr%uA>eR4_v;GY`d-v|AFJF!=d3E~qvB{iv z%|ExBa>}NzZCYuiltHv1rIc1)aY`(!(sJb$R#@@G6;b>kg%npj0mT(iI`N}JRwiTx z6ha6A1r>7o(dR`NW0Y}58f&!iMjUh0aYr6|^zla^gA{T|B8xN<$9?KK$0CH#X;LAE znEq+{VMZe^JBlYAb4Y>*9(Lqm2cE~)u_lQmjH#wS`^TL>c7}ZKyf~s#XLUqoFikFd1jhxw)tk9bFMj`jFy~8N+%0q=A4Aod8QzX zC|YvpXyDm$qc7nZsib+zteTx*jiJUGYra9^8${l$>85U`IV7i106e59J&79Sz(THK zv_Y{3xeC*&mhvQTR<4qd6l!vAqE6F$jwDm2Z9SL4nc}M9U^Xo7=?qdND5XI z!VqS`N>y4h2t!n8Q;XuCRlH&qiXG^QJMoWQj`KC?d1o--Xa``#L72d}BanshoFFL! zEYBSV9Kdo_>X0!45~!dv!~x9-f)ku&k%k1b6W(uf$C_;YE?WNCS`D*M5IkdzU<8nh z&Nk-MjmbHuK9+Nd^pvL^T3Ux1-U$a1%A+oIu}3-BVa~g{Q4MM&Cpp|;-l>jr2qbbt zn*YJmH3s1m#?3DqaA}48+;W649^nutGs}i5)gez10z|AJgdto;2tXKOMIbU@15p8p zPJ{>*pXkIXTogip22`K}C1^om)Q@wRV@X-Ul9dvYr7W?qN(XULMJ$4mbY#RF=>XF_ zbg08H!2>1oFcW0j;i`2Mz!+b{MiE~!C-~juPjq72{POgtw=rreWVDJ}q~erTOvO@t zyBJywv7t?g;&3PH;(?@sI6txNVKX@d^^WPCmX60ff&K|htORoy&<)ZsCq1cR$m$Mb zuwYm!kfaGD8JgHxQg#bOd$(->3#Ssu7s2b+vPWad9JsD9Anf+r=Z;@#=u= z84|2OG{?f^vPOeRWs&AIP*#m^a>Hc05_Vdov81sCKmry3cogoFNpwurob0rVVE73K z62+`pF#n6P*MZ3}?Q;$0aYH#sd}VabhKOzOBq$<&*rQ!0~JCpd~xo$KW~u~UUcs~}fE1rj7KYO^8!LtQVWvZPDd)L4m*BtU z=&ba4j=kut`gp&aV;Gl^CYU%mvY`n&d6+?PMVjKm0gOP#KtRV#BLr1I#|LUOK;WlP*aUo#K^x3RecVT!@dsll z0KTKO?2@~KNGMse5_M>`Sd%*$@;e@Mnk4jyG1)b&DHD=PiCa00liD{yR1f?!6;zQN zF3c0lTZ*H2n>w@`(&L|_8icg4kPJJ+LeLNjag;QYLr)k5F!D2^&<0UhH!d78=DCJy zppNa(FZfVIK0>ipS;Rkru|HCb!3d025u#%_24qNqWPm=-utd-Bj7kDB*&z;1EHaC0 zxFrh?QtUp`kew4Smhwvh7C44#a3WR$5YZ}|n_#B+GavpdMq^tZ=5W90C`>z>9Am4h zsgW$cEL;|aT%32VX=K>(EcxxCCnl%=Q?(G#=)8ng--v~=3QN(&KCm`8I&g+~xO zbiAie2$4^4L3sQGb!5R7yr)MfJAT|v-t5gFA%FsqyCg)ljNrk9yeKRwuk=bGz4M5t z(Fpb$i7<(;tBEg>dM`5>D|4_FJ`xOJGfHEcJXZobov4#haK)3vqNci(w&)uOyO?Tg zr>D9wQSdekxtKyrz0(r}Lud=4Fp9^aiDudlb-51k@Q!LQj}w!XZ?HG2bkIHGDt_ZP zV_*hl&kQENjI!KB(TFnfLxCydq|%5h>pM8;Q>7$Wzsiiv<7xi0 zI>I@Fai%%xk8l{kZm1mQSuExuvB^1~9n}eFx(n076QLM{0g;@d%Z9`8AE*!@vB)+F z5;T_?G#1>t*E~n$@`HJN1amxvPIyOke8(0v$8rP&*X*ZM@B=bc1zG4c-@H>i#nXNO zPHWHz9n=Vq2-LoVHN4vhLUqnSGNW0**kz)p7PmBUE9Y7iuQW0RsZj~=ZC za`~^Ipgn5blbm{mD^ifE03$&-f>$^K{NXmWxG>baFbfF_{HY37y%Z$KNx3jOR~$M0 zyN}CRk6qHQ@=(xrP!)QshORk2BI2q=bg^n6IIK(tYu(TeT>(k@$`uIFaQ*>}29T@Z zAU{*&#I{5h?VFuS`brWQ0Tw_8bKpXWNgJROgvfaqFSCngn!NR)kDBl-b9p5=xxM+D zrXTGOp@XI;-8`R2HbohQBj_g4JCqAcLv8Gkd;*b18^JTJG(Y$R5cGpnFjEi&*)vsz zQ$VgqP=!Z0$0LZ%eeysL^n(n1gcr02e9Tjw-C4EUhkfXWdSH`Bb((p=p+J?pi$KDm zVFratuOm#azXMct&>{4qT90Cf9-0StFcV5OiOXm)s05G7!UoBjJZ!*;%BzWNKm?$8 zJwHjk*E<6tw^gm$?v9SfH(lL#wzz42iwHQJiiH3dU)U{=#&gmhhMDkvF8& zFJW6szyOax+^Pv(73NchWXMn!*h;S4)?(?5Aj`zJv_4MS#1c3G-#Dezb)C{R0Tc)_ zZC!yBP$eXQqR4@!$ebK%08h9X%MHV;EB*8zhQMyg1LuxmTJ)k($4|wZU_* z!>i6*3#&z<3|8qH@aT?}paz_PjWa#_Zq@?7$xH@QXis+$cT|YuG)^>7(wn%42W_NtDYL z*h(K;fvyD0(e2jK1(y<4-PRRX&`4eD0~ffIBugBY5l8~Zu_>W=m~1$eR+_wnaV2SD zACqGk|4<@8b|vGL%;Q-`03o{hL4;A!Cf0gkEiw?$4$MTJ_Hg?|cQUhZXq%7=3BhG}qAW7wgo zi8Wi(D37=Zw*wO{c{{<&p)3K3F*ygTbuW*?PBs2XiNnAe<@2LM3`8)?MZVODoDjPC z@f5~Ei##c+RK><4a0M|cH?ZKJ3luj>L76msNicf7iy;aFamJtnkmKOL%UQgZD3A2; z3$dLy@c0@*{G&b!jBlvWt86}GV1drv&`N~99t$#K5#3`E(Qh?HxiaZW@>bATfrL{5 z7I5hlI0j=tgv^^MeD#lJw2M97<2^LF-)&5g^bcrK#>AB-qT`036zXfJ-ty!;1~Cd# zjT;Bqn^~oABj$;9vx~z#tvgdd>X$ z31v$gd<}3{bRs8ZkU;s0qreIVd5XgEHf_6*3t@%)<l0^ zoQ7mV1Zu#!X*f@vn1;%<8=?3~ipdzD7#z{#WDAoZKR5y!?lw;t5eu1+3*?v$F;%D_ zh0B~#1q8qXwVvy+m+|Neh1RbG4G)Lrqi^UVVYy0VScXpL++@J+j{fLvmECRyvbX&1 z>Pu->kKI&1xX$n~RZ0O?v52GB8}aP*IJ3Q=Tk35X1e?f-%F6~p zpb5DU3Kv$klaw4$@yRg$dOFU01wZJUl5vF!&tGr!gLmu$vQ~vi0PznuWfI?CM@R(} zuj@V-*$;ogvtG?q2!%c{_mQR9NAQDle}q1WgjulD94~l-zmcEChf**b$ZL}zhcB$1 zn!*;mEeR82Sm2C^wZ-<591^_i%w~})6OrmQYsfV+37yNBP(f;kBw$c*unt<{4>?o7 zq63NnS&Fxy3PETK8r~2PsYyZD_TZwBb|M)@`%IV&BMT`U1t|qV;FCd+CL}6SqD+px z&^=WDj9uZg4P$t89kqPKIR&_0Gj^>=xrOF7>Yj@6tVQhI3uwD3(YH zGPe3+wc4>H@RR;)ii>M%MrKT5U2mB9iOg##1;>=k5W|TCJe#Bt1fe6kxj=$+J36C~ z3r)rtpQ4)!y2b<&Klc~M1l$kn z5PyA?CHH>s_dalhw8n&d$m@e&{(>Lia;U|c=y4>l26kwZlW;s2XKrIlA- zX|=*uY2kI&T4}L$R$O%*iEJ%7&qIb zX&GbMa}$SbI=CJMcRv;t>ABkA^vp?41C2O+M2;^%Lws6t=DfE*D? zD%T}^$|Hb8@`=NJSlnJ8kT~K#mY)qMJ?rQ`~xW?|aAR!A%OiXzgT zg$U#cDTa8$rz;Lc{!ruuUlgcEpu7^2KN6%IA|-lWLnJzeiH=1=W!-Uv zChEg6NN6HD+|fiNIF<@Xl(0R3pcuz?=&)310z7@tL_UCK#3LdxiAr3e&iElTB&fuF z+}O}Gwt)mBFy$LibDNWzbfP5r=tSoDQ99sZjdRR{8C3(@jsB=+j;_h0YwV~RGn6zB zCE<~6>sS&vtVB0(w4)v3XvglB(i5P7Np_S0T)9Reictu{G@@8wAq3&MR|rBkesBnF z7*()~6v7XH3Y07E{! zf+kKF!xVGG@%Gt?1PC)T`E(X>eL7AgF^YRM=S~wI`~=U z5R%y&O$G^~0+?fuU_6mLsCGvd{m4dYZPAL5RHGV=NQ@(D656bRwk<+wNl;oxJK_c+ zKn609;;_b2e$ta~;Dl3~sv@N@)UAQWa*~F#*GM{Nh=a6ZbAa+gCk){SKa|oFsOUt& z3RX%`bYf3{ctxN(X*g1h0twj|L=sXLnQj~c8{EJK5^$2KF}cpSKnaKJP9-~R=!9wC z5EV9z!Hj1-*BQ=qhBT8=-KyZ~d&x*a^SZnKm9a3-SL2+XSiot$Z7#0`xx&gZMnElN z3=o0Y5Jh7!qYeBWW)S_uUoP1Nr}dSF6!CnGD6XX@QXJ+GhBC-VMDj|J=!O*_Ig}^- z0Ek1m0u_dE#V0zk(c`G%5ub>T9~^dy?u@6V9|Ni*FrkT&5rJbXeK98f@CQw_49Azi zgd)Ck2}rzjWhNXMe72JbNL=E_m)Jx(lKRvqLpjP){#jJ>fsb-HsuQgcg+H|=zs6o; z8prhNm5fxRCcy(9?C4sWjg)4yevw5sI?@+WWDPZ^nMo*8(jM=+q$yE}9dgqWAOWcq za8Ls&$Td|>emg0cTmwylP!nO`Wx3b z5$1e{xvzc)QHa%`MuCIaG67vf3RWyIB)Z{rNKlcGJ-Gr98U6%umh+rPc+d~+;SMB# zc%Mh~ArgOR@g;_=2pPXHh>-Y$ePD{?mA~|3-5EJhOBlox5?RH6kVQY7JmsGQJ?KK8 zkP|CZj&j6eFpoOPw@kO0N&X!|cGLJq5~?xCR;?pSMS2pEY=kx&r4@{HE)ra=<|8?} zv8?VOl9QN3rLY==GYa=xJJerxp9Cb*`gx6x`dpHnLJG})ni`IDV zvYP=7>QcA5$LI>KteGq2@k+euZ5Fr3g5GgAkKF17-&KwgJZCVY8U+-^eb+^p0jh>D z_!|aR^Z${1xUS9D(P=3V&DFP<(=1Y6InAS14?w2wRRSu7inF zY)mS6M+}t=%K;fC{#-&I{Md`JP{|<~3@O<1evXaJY-$j+}V%Z zQIQbI9hude{YYA+!yFxn8r_kR*wxw?2@qC^U1gnJ!A&4ZiQVyz-7EzX>>V#X8e>q( z(TGMQnGbAC68b%mAS_-XR1W84m?r=NA#{Qt9Kq(H0>y1mMF58@_<_T**1_qv>5{EX5fq6Epk{@GOIL5zkeC4>W<#?`g#~fd#hd z1$Qma^C-{$vv7s3bcM7@lQJ9wG%&+D;L{@sm^PFj{LI(A83vrt(mz4cYt)8mM;Kg2>3 zSQ@1rf?^ERWoQEuSjHeA!88;Nr{n~pHO-X(p%ETQS;dhxXw8vK%{t73HO#}B&Cwjy z$Q&h!9U2E z5p4e0pV;3;pw=D|g2a^)ID%GjY>-C`OeYk=G9~F~c#W1GPYdGEA2<5D&CL6AMrUc3B0rRfT#bpI(GTSpZ*W zDvz{)&t5>&RX_tY90PPAf+xt@ECHkW(0%P&_oYTP-WQy7-y|K*Na)L)c*5ae zl0qodKtRqb4Am%+mi-~jCp>~Ge1Zq5!pc0%b^t=lJPga(lu;eQ9|+Y-DS{#}f&x0i zk=Y|mT|zy^SSDzKdMW~WDgp+sqsx8gdy1UP8P#~YTtY(Re)4C30ti2l1N)W25&n!0 zq!d_U%o8HOPnvMU6@dv)d`JQG5jaqZm6$_2ILVL5gPB=F7lDzR%@tYMkvq(!l9Y{0 zJ_#4W1Jnp*l<-yEbs^kri8$oWPmD^KdpPkSxXy1`3H zWW$`;%Pf^2Y{b%QsEHxC#%vHyHjsiKOwuU4f-J?Cql|=`RHH)3;lT|D{zY&j!QkOW z?NEq~7!jZXIetvZ(9p=VSWR6*CM4j=LBe<9SRa6ACRku5WC9~34ekzF0(k!a{lhLxI;m7396*Uf{}sF_|xja|vjzRnGx4N_mV%Bz3~-lU37 z#Ex$1(xeQ+W-#MnOp@U_*yEHEZ74*B;UU3DUWa*ta|TC6WFBy2ga-9tsr89k`hlSo zM3Ama|6IeQk&9$NQKT6SOvFT*`W>%rN~bK%8=b>BpaV28Q}E#aqO*l zMJf*JUJ&Xk?nP*x;$95TEkea#9D^}rk{}Gw`OOJRl*YS_-)sC&XaFN@LDZHhkQ_3O zB{51zSXSr^j4DlzHAW6_90wo-$0In0#MH+pP{#>D2L`%al4&jm{=q?FDm?+D1ZDyy{3^39>m^WvvTA|^{wlWu>#ri2QT2fZF2W?dK@pv6@Cxsgtzb%w z-@QNzKdA(z9KsceWKbMhA4Q2ZgcbF2UG)ax9XUx6ngfY$sN2}2l4xjHrHwpbD8FVQ zJM0m@f=H_b79q6?Q(%KqD8(e|sHIHG`b_!ml`#N+nnGpiy{LLvY%u(l`bQtPrts|6+*BiCa) z0&B9KXSmkP@N#k|GgUs6MB&jJeX);LxzA+0g#PRl4N!c^Aj#+tYDu5nnV^YC*QMl< z7(-d1jrOj?keKM&=qnIrXrS$tm0XE6xC5c#Yy7rD7A1vJ>I9n-7p^^8hUgb(+~#Yz z2`d=HMM;=w^+u_o!V&leab(yX`ay>=E-CcKz1!(R|xTB zPSZ2tB2={PGn|8{7KDVMpCc_0(=pIR4g#a7MogmwE7(TQB3vsV+$uc~o~#mWu%%Z* z9B?dWh&5*_j2M0VP#<_43(aoJsArPF{uCpyt|JfujwQmi+Ss+WXCfrBB3Obw60#+% zE+tq3SQBz4Sb`-aD>A&>+Vu3B}hUEdh%ZLHPDnpA((>sNvdD~lpsul zWmt;REDbdj=ESn^hEj=1nxxw>1HV3rOnMR5r45Ok&DM31+8{HFnlIcW^V=92AlVHv z(JxT+gr{_aFHOp$nT}wXs=m0!PXl!(N!TBPLU9oAXc0$m`-XEq0&#dyClEr10YW*? zGXyD$zd&O)4K2&8;?oL;%Gg zZIA>vuaZTq62NHAXh~@X{YG+s6mwu4cZi23Ji-cf3?Q6bxUT24Dr=H4D-oowA_Fod zEP^7FwOS{_TK_>J|G^|!f{lB%BBSmf$T+h`0VE%CAD`#49&!}SLO=9%luJ3zOODwN`rNsGl#3)3BD@;VH2{kwy0!N{ialA9a zaJol9aECP~bN1mU;GzEJZH_0P(x)Qae;vW23_|yvNns4a6q(72-9>mWk1 z@d%F0DML5YVmiY^hhpw&Z8R-IEmG46m@V&pkFHRYv{@H4Jri{?=5sv*G(>HyYbtCZ z9F{VWLLIn(%`K!uk~SP18OO#|@+``F1W0^VIh$6g!7-b^rn-Y$psk!i^#8 zK{B%IDl4{%Zdxbu6l`_s`uMe40wqZNkB{zJM*$%(!dNrHk5hFZhif4JDkaz$A;<2r zdUYn`$CRu5$|p!vm4g-68vL+Jq~(@nxWuIl*RhGiI#ffUsc$=|Z95 z!g34ZMcg3-f8(Yn45x>fb9RD=odO5FGiUh*MX1{1Vd=LwM85bz|FnYGe}?_w&k>xV zqDPvUghPgS$~DZMIVdy@Gc+?5J7Y>0V{-mu>ZyEB(|TzaG6-=BOePaA1L_k`v@xb> zrrWkhZ2@eW6(`OldBQuHssc5bYuLs%ADo;l9F{&@MywJ?5JDjU$8e|uYJI|UT1>={ zV@`bx$CxL_2=c)ja>;|IC0uJ(do?3?^&c$4#jo`wY&?y7e~qto#^-pBPlCuZ!swdy z>UKP`{(3)ECu<@{fg&WrxB`SefddH^G%QouJv_sdZUBecR8Z~UbIhKhdj<_WG-t<}HFKuyJbGozmK{U34B7f+$>1lmk1SaV`p8(|w|^f#{N9t# znF5CoA%sH2 zSV83#%0Tf0mB>&L?G)8cIpvW@BJm>?O#s0}lT%By1CfvVW9++p>mb=0CsRk+xK zE2eI+;YK=ZquZvrzDx?K6$?Kc#FIiiA;dPyTv3HKKt6HB4?h3_EwfMJRppZ%JHz)8 zcTWLiUVk;imk>Zu@kBCKTtV?R-AHMrH$QyaEt_l(8D*4hG_LrsZdS_nnrg5y2A+7d zQ|BCXRDLGG@S0Huz4V-EZyEI1WADBBa!y9T`*=ns1)O!RIfY|tK5x8Z$U~4BbBsyC zkZ^1JP?T3#G55n#eA5lZs!yi_sqjVbf*jI7F$@*%xujZ_F z*1G?Gn5aQw8bl18i9ZwmAIBXV+Zfx7+}X@*?)yqIhBjo z9Z|V&LI|l`NjFlzPT!w@;q&-B-k;Co{eHfmuYndt$+_U1SexjUaF7o&Wo`uJ##s&{ z&@@2B@HHNDn(R++?Fxd~NsbNPxmc|5=?`!PySXBZpBwNR8UXdWO2uBXLC94Ipm`#xJs0z-he}Pi2asCVE6c++4-Efu%p~_4*MBy zv5041z{64_w8CcEqVSInU;J3BwEM{XOb2;OV!;^qZ=Is>sF$j;z$u14n!od;#4i*T z0>p*Tnvz?5G@EJ}ipIXA=bt9E$a*Fi5&gT;b2w`4#+>|Gp}4r2xkf0r8TW=T+H_Ve zH(|jUPrurmAvJ&*s>5BHT2YJ{l9jgc+q?=p9NHu8XYJ~nCyn4v{_=CkB=F5@P=1vC zZGLzEW06k+)1fS|mb+nZ!1wcFzhI_h*sL zBtcvb`;+g1ycIA-5Yi!A(8}YOa_e_DHyn?2_Mm>$1J^G4&m6^7atkTS_v>r5Ux63W z{qb|nAUzv2w93XbY=Z-!%};qBG->QUJnf4DlVN`YFSVe z30)s@|E|er@^oJ$q(lh340DgeSd~7K;et>95fKzxW;-sl=x8aO_gVBOJR7^;^6Ph2 z=+Po!o{mM_>!ap6#zSn{ceEO#?woXUl6C2_tpxd=mkR!AydjF!lW!4y*fo6T-3Cx{ zImyCc-djN1=$F{5;NvCxc>W;fyL8ga5aDc*5w!`6tRrpT+-pNN!#@hr3>|U~^gF+` z4`oezUJe6N5#O34!R4^%zc4(+8w5cqnU@8W(?W`1QOeTFYdiK;lzYjrekX+keBn5B;f zU`ojM6K7@bTCD93<*uK{Xu;EGe%M+%&bPB44OMSP8|w<%bY>6X&FM&0}M-e>-D z8oDh1G$%?aMZWLyliMhXtck{zx4sI{&`4za>dHQph#R?R2!eU=dvTzsnD;~IY%OeN zl_Nnok*Mu9=EWa8Xiw0=RHTx;y+bNwiG)yUg-<&tyr3fC*d`jwCB2z|i3PGJ(@0yB{I~J~RhS&d7e`-_B~9YV@ItG5h^Wc3=^M!n;`} z5VlF}UQRua84>g4Q%JKRK@)~;@l?@L;Jy@%K{%rjI6k3+k;^zdg2sUmWw-IaLnuw# z9FcAJ_Li+iy~xM;oT2DKx~!@b_e zIKRJxlehH@h1|CNpNRv~qUAUyG7R9Y+vJS|uqA9#Bt8ttRTI{~$d_){U}t@<9a+CB zr?BD~WqJO8e())BWIbICcAqFO{b1`d)St+qatk0J{-1nFIX4*nDeYzu@&oAEUmOv~ zT?t|f8TMmA{5Z4Qw6}YsTH%>84SS8YC|W-SPx-Je2pV2fgrgYFvAUs0YO8J zBy7B)C9?;oky~*e;W=bWK+Wab+ifgrq>-{vxr{Y+GA^Vp*3R;_xy6!3E~wfILSrFn z*ZJ4U@H!R(=AiN-@0;gm=<599`oWT+{E}Z?r;TNdd1(90P=Nv=hEyX-a!@~!uP%!| zX+qGo+JJd*!VwzIo)nd?q>_4+3oAvufh`W2QYuq@JcO2KZMqzVDzQwoUrf5B4*y=3 ze>`CFbmo5Ilm43s2)I@byZluSl(Sx0q0+@^0J9TL57D(s3el@K@c{^5tQ0cD9Sv_| zEi`teOlw;_721A}42!>q=V9ib2njilNxf?kbllPesA(*lUDz?#X~6RFZ3y#hsI{X^ zb+8+GUbvf-an=O7h_h*a_hWA|PoTYABgC*A7f=l{DvQVvi6!uDPvpQ1^S+3B?42nL z`ULa-0vq}CTIj2>cPd~I)}XAer3CRE5|;EGya+;$?ISPJwAEfkm}RM{pM_n87S0<(S%>fqW9XLyXng@>%?mQKt|ANI zR1d?lZRVoygh6dxvpc-ft*Ow5n;a*@9;m-7u#;#zIl+naAQZPBO=8SB;mkCZ2B6Dp zipP*Gd&)sK+&ix#J9JKe$Dwl_6ai%&!L9m7$QyV}6ZHo+%(ULu&Q3dK3P*S28sRdNF zpPHlq?&x_Gri~+e5aZt zcAXl#jrlg~<*?mu*RvGL4nKK-5;4a7Y)vXQ+7TZ}fBA^*JXco|#KoT7yrJeIS<8M} zKH$)pTjt@fL``uCGm#unjm$NZ#C|`n9dGJUY*0hr`ew-h7~7umau;n-X6kH1kw{E- zLf?Ldt(+ZTz#yMfj8I_bh)d?OUTRGY&xT9V>6b}^aG4ErzO(NB=knYp;Mcc@JSUPR zKPKb0ggkR}!hD;Jh%iHwP`ZKyoyAfA^+Q@t_3op zp|)inVs+JNLy&*ZT%9d=6d)jc7LG#+!K%(0kJ^$(LmV0x1EA1Y9f+hlbZtGb`!Jy6 z(CU_}b%!&g+L#*t0~-H>AGr^$l(7l?%pa?);!t;6Bh6YxorzWbRxJaWHD2lZ5t=KS z&bD5?*bgHPh5cKIwoMWDbMUK{XS1q$j}%Kkyel0Me3dwNBYME?le`n>)Sr2@Q#cyD z9++6Wp=_WjE?1BG^G+Pykn`(^%b+U-V3dw33qZ+NA7`SYt+0TvwQ?*E9EALy1^oFrjyt0OXqrqyl!uF!|? z`09NNv3&8G75u6%(98|K;s}{q=Wi`Yby&VP?ZrCpM%^H%UUr47ItJDmf8(DE_P@V$ z#qxWI^&iH$Fxvah72XSqz8e|X#sYu<; z+BDe;53<5tbGc}OyZS3YS_%b5Fd1_C!Z|XKuy#Sn1JdsuQmV_IXi+t0a)=}8LQqIc z5YgKQv||ED!h8e4P~grq`C5w94k0mZ2AFBbb7}SzJ;%7^g@4lrkOk|~ps$=DQar=` zS`EMWZJ0kZ3tY%0-GBm{bAJ9!bA2-+ctuHl%FL)|mLkH#&v^hc+DhJg%XuPxSc`xI zpB3`CbCk#47Hrjs67?=v^;1$rDVx2#>Zq;#K#kWg&(aTzXA8Hef2vvrb9}i}{L`148`PTaI{wK%!Kan=h zpMNBr(pK`QKl{~kiB%!ihbuB_AR>SN*HpMvM2mY~*xv=TR?PF#A!X$cOG;c#QSS#z zkYO2`F)vxks>CV@9V{SI!E?U)3qNNvBwgJnjKh8Kfo+b3BMvGH6>^imoI!0>P`)BJ z-XzOuS>CI_Nf4q@Tg$&A{~9yYRkVISkQClY2^!1YnNscKgj*RZ%=e4$a3*efOV1p2 z?9MI%7k3jMSDXrhfgkXLq1*oEFVkBaWc3k*tKD+vXJ?87fE(WU`XsYnwZVxIor$V1 z$Q@xl$XCemyH#;qQMD%2lbv5MOoE`JZEl);LMqBva@U!)+xg7*D=nppx6CPSLmoA&ic1Ev@%_T>m}un1=CJ7PB|h5sycWRR1b*Rds& zv{xW0bYyHv16W#hTKZhg1Im-aV)I5~=Jyiuwp-8tGrNF!wR#W+qsxG&f*;3nwXS&Y z?rcb6dJ-2ojdNA90a|UPyQg5t8x^~kOeJo(AG8)Hol?1W!GGn3tOh=Z6%I&JUrn6? zLQM?HM*&c8w1g*G8ygA+mXT0kb9{jg1%BraZgU!XG@ zluovONe0y)F27;*zIX{;CPP=rFBVzQ1&POtJ-sV^%g?WUGmB^O{#Fru#CjUL6!sY! zc|TD7Y(U+$dmCON1Ep)1PySDkax#ETOyI@{cvpQK@Hn89;5?7k5fgR8D6L`JH*P>( z&YLWx@b78m(y^aP2T+e_k6+X1(ppYuwnu#xTmt4D?xG#;vZ$)^VMBH2^X$l{sj6^K zBn*=Jmb9h09mQd~>sBY}g==IGrDfF2q5)t8Hu;VW-VyK~K_C@zNG)uS%~d(ybqtO@ z#Ldf|spm-N|5Ybcf40fE?$hDKEZl_DiK=s*7VnDFd(oeKC*qx9+|E>;L}CO^Gxo#G zY151d{G;kwmbU4OhN6Z0qvam2>c1~*-gl@nx{xSPIv;Dg_1TX%w^TjUQlR62I0i$V zE%V#}4j+@Pt_hb~ep`c(>;XkE`+Dq${CX#{V`*aS5%D?RhAHQ|uwd_iHA}~-dlZb# zW2~y>T{7~p(7RfZGtO2OJOU;7kTsHee(_ZaorqN?qx{-KF`bbWrn}0TP4TmDU|lco_j_YN9hvK z+iZVsr@iU++~?Ff*)%&7P1*Iye$$>@p1awO6Uf3lezVm>`6NTN7rbP1@|I(_P&#Ww zeW%=!?)jtfyQQ@UU>y4UhJ|kpv7BMf;P(qOmcp8EV5{r56e&hF2YfYVM+!kGeEmk5LWZjOX& zE-h0k9~WAtYLge59#!WHoH}4~pFmi|JA!brzcw;ZN!?s-C<+Ib)_wEvEd+&4qGTwN znV1h2H-ipHX56;*G}(;9D6nkVjoX&k0?Ys{xIx)*eE2eJf8?rj3425$u!~)aT&^RO zNQAYw6i3ZCusvg(8}>aVoIywODbbV4?^0)G{9hE0Ml%1JhebMTv?m6Y?2jOWOW-NT zxl8?)Mqtp^wk%lgS4YxGH`$2=Pir-L}BiZiTHUi5BzIe&ZZdPS>Ku zqca;bxb05eoTT}_It3BKtfMl%q0--Y)yAiaN{i(b6gbhQQNb}W(=uyWt=%#!VNO;k z3(-8HVgq^8s#_riQbZ~<%F9rQf308liR;(+y8s^Va(vSWkG+FdyZADrL zz*6Cg#?Bc2hT)Zr+WOl2j})7F4>ELC!<=jp=Bo=ih6iLt!KNoW;%7Z9hc7MY5233X zTjo?w6}mj5#fAMheiV|?K|kQXbb3p22bWoljGeJ6QRz6p0fbN+5nT-fYT0u^PgoBQ zmp5za@qad0X~_|LZ7;db|1MxYK|rFqi$~Kh2^0`CfNYZ~(QamEIChB%SLT=ARZat; zosyre8v|tprfK4#(_*y9R4to+DDfChdo(g?^m{*-%#T?*fb*SgHi1=$4$Huzpi?Nc zRY-nb8eOX#mW=}w9u;T(6+suT;qq0u*3vlwp&@RA7E2(9%~(u1EM<^nF))jnOGQB} z>#UePM@vdI6h9T45eSzI4M7paw@#eodts2#)&Celnz19nDz(`cusiB>n5yY-PT|y+J3Y>n6K6qO7aDeliKnE5n8C4zu?RW?PkVH)=N2&lmO*Hk8~a4|*oBsalIucuHMOALkelyxH{*&$=p> z6iIaw>nE9QTH;Lg%N@Y%jgvC{v>6;l^H$f;4U{)L6}F8~uMAXB<2-Gl6jy6=I$bd$ z@s3H5FH(~7HX}g$eurAD{OPD&F1g=Ez}2(o5r*DLt3N0A}Ra_kc!pBTR97oKQ zjVv-JH#U*?+S=OdTXX{6&bYCE-2K?aqqC{Ls`OL+{d9SYL2S;GzENa~Qi^i9}xRLVu;Ik2f{YLDD|Q%&}fJfcRYTaan*%&)zlW`t`% zJ^905As&rOeS7r@{Wtd@jhvn`{Xeg)__32(j4y|XH9H%ZXpCe<#*LOuBoOvpyLlff zmNY2!IWq0{lCEG!?DcbmgnJJ$;!pE5-;!+zww;m+@Oidp*ul~%lmVg zz!kAtmIR}yRBy(?PH2iFRki7r|CN7~n58nHVKN~g^inc%$tY0gFb?YSH#@qzOY^Oy zL1X8*ZCIDDM0ROEt#O4Zfo*(0asKFl`R>^Z1BW98#{v`BE2bVotESSgLPzrX&k?PQ zVCxqu0=FBozbk~tR$l69{n3oAWmLC!;%}H*jj23tEo{`EHVcv%v$)Abu0R}UT&jF_ zrBAN^1&{vhzx&EAg;XA4OCk>Z$+)X=3u+QcP5CCs{nVi6#W+1pKMQ`#jaGQNBHgC% zzb8m=!Pmc)>DNOpVO~_IQ2S)==OtqDLYJBacH4}?TZ9ZZ>|s@k-Q|j=Ng`8wM$hO1 zD(4)fz9TL6lWf^Y+ZH4c-~$0D@%afnbX4rfGtzGnSg?n3M_!2M6vg+S-laGxIDl%6 zLEdd%at?_4Jy7mG=r_{Vb_rf^0E2SgI@*00mu@ef*$i?}1Lj9cm^lNS`-p)sb9qg( zWt7?JZ)UDqfpIT*E^)+@@1(}b1wNfS=ROOF9yPlutU0rBZXiiB!r#2xTgtInJ%sGG zxe;&sji;THHwp&&OHasJrsXi*|H1g0WFQod3#3Sp2U_k?dt$4WrCc<|(jJ}3jW%_R zlIN1m(7e_ha6VlVT_Gx-97e~X)so7qCTz*?6Am!Ln0lm6vUV!tPuItDH@1TLSGTE zXz>AVM`OB>rl>QP`-Sd;Hy zE3pt1*5tLTUpY)d235 zfpHx?UUcB4b%2}u)hK3Q@K2yS2T!Q0*^Obz0m7BQPR(GXv@_YwO31ZP4ICZI)7nhS zW!_2bzT;*pkZWu+BM+Kdgg$ihl<7uU&7-8FG1)N~wF9dMZ>>7tdNfk6WqiXlx#?y+ zN9A#cy|U*JI(mm%qoYpbr3;r^bH#y}qSyw!&70?t2kYS71E3=#Ec2 z@~sO@s4l!1Tp3qrcGKmYKUnItf_ZS9#SNVF@lxVtDvvW=i|FN=KYS-3u{vn= zaut%&XD!m|*&bw_PxSzNx2j*ztL*Z~%Fnom)4iF2?&Co_<)Idv6MIj{^>isb6qS29 z3whshaS&ZXe?%}n`abKVBs z%3`U#C4q0jfEix*_1fbK*2NaSXyUoQSYLfq42uN3)i z2wuH>#_fjL82+a-Ove&-gM1Shh5J~m_VY@dpi`-!FPPO5*Lsw3-@&bP!M*fXr`k62 zGH;B3f(E=V#%sm5tdb5D%JWE!vHzl`_$jhyL&KMUI0{;*sNQKDltfqA@xkGgAVd89 z*C-$8%9`&Kfh$qpjD6pK%jN&AaBPZRVBL*jtAW^%{6s z5eX;&6*tbFma88y$?> zcbeRj3cUBqM?g}i*NoANc8y+jWb8te;8luc4HTuI@zw*%10CqqQzy#yzzt;8hvV4) z&4Z12p4^Lcdi5QgKgXM|j?YB6yw@^)FadHPrChipE#@oXb3!A{OfnG|Kk9JREtp5) zWuZr1>-oAsYdX*hmgcqI7gZZ*Y0$<|G83S86o`Hq7_So_7R-a%;<-E<&=Mt;o5thd zC2`i5CxPgW^_=C&cK<^bY$8J*M1sy{rROThIc$!#Vk{pFp)Q18vpNXfAOo6+_Hy&- z13Yr#c>pK0T%E|n3zE7`q~Kp^~&ZoyKij0~r!MbV7yl@4_Ox%EK0jM`0n=O+0Nnkh?(iX~YSutMcvwlU^v z(!D8fc&%dYG(}bTF<pR1?#4A8wFpuXt;F3Miwt4NG zOq(qWpj2Gw$tskyUJGKTCi&*5zX>##2nDD`^IJZDUPX9`2Ao$NehvuV3d-561;u2I@+&@N!?)OMQ#PvQ zR^*lkw)A%2q6<|0Xoq%lcj*?LZrGN8fin&?c+La0DLe1cQ^@c1KDnp&nj*ij;8b(d z%7kK>O%sOq45I2DI3X#B!9cwbQWkak`m3zFQ=rwtscQBFr7t0caN_Ma)+k7n^%yJD z5_#aJc5@!~7uc{10_)p>9hyNwbWq!V{6G{>*sMhGZ4D;_&71y}gUYuBdn-NrfbaeS zSx3NgEWr7M8M$k(-mU@WO4mqoGda^cpmIa=Pd~q zio6-Q`3ZcWT~9tS%!JNVdEVAUSvkrfrZFA6oo8&IG|2kE?T$>bp1Kqd2}+o24@yJ> z#eU&AGjinlEMTLr{b3_V*Fnw+6CRWL!ARM9=a-}Sai{WI2dDVI;j+29TOqd)rlsVp zQNhfdN`iQG|E|-ze||Fv!B;V_51yJ@3^-kCD~f+pApas+vDpIoI+b!DX;8vD$L>zpS)U#Rsb1)f72mqC##DLL9shyZ z?{p&C*D?mZRhoR_nP+dpiO>OGUcuJ}Xb2=`!{#!)}ws_eVm` z=UDbhTz(xwwP)*%*og%noE3~2(%ulnA?n~$uq#+)R)Do7B=1Zi^)A2eimEWr z7Sjw{W(Lbv+1}Q6Z*6zyu1@z;v3(Lbe()A@LXD}YI35k0%EMagsdD%j{x)`nJ_9XNYpI5TEceO4 ztM>L|*i>oUFXK!(2?McKD#9=lgdylx2$9mJ<==O z2&<%HgX$)zB37Y3SlVF)?jn7~=->F=D^EBroWg1e3h8Gd`xQcG|2Aigp~0L)(%CG` zHp9+9|82hWl;b4a7VX_GXm&J4v?q+VQ&k_=#+yR*vQ9NYk97Gp!?LwYf*P_>T7OJh zm%4s(wa*Y=hH0uuU*yt$))l#_qt-q~;hSx8LuX?3Vj9-z{XYjDj%x5Rv$dD$6g@oM zX%PC9X+5a=ah~Rb&?{&9AanyZc#YU;*hfJXx#kAJ|N9NDQXqV)SRmF3{iT24J1YrF z2PrQ^it`B}agrg`-8%!#gWak95jjE4#irF8s>7jUuSbT$0n63J;hkb{haCjQ%?rXj zj!|LRc+7DAxxdD5@y^m;iG>zM`fri4F8$j`w9)%PhK0;rWiGB}hzhdksw5t&j4Nru zyAHEr5C+PYfNULQ_sVIjgAzdYtCd5kXRq;fm?MZ5E$DgEsUAP+SW-^>Hr&{4pIBhZ zgX;MN;!~J-er1V(W2ZI1m)Mu$G&(90bUZp1GXgeA6|rHjYRmJlxZHY?5QOfi_BxrD zrroe1z-r%egE`Kkh#Sar%@mTwo+-m~BjfVisBnQPaEEn5#KH_Myn~RsgNy>3&#KtA z7MsY;?n!EOZSaTaB}ef)F;UF^OQ9TgLM8Mftd=(j(=#>H4jY<@?Dsyg#YA+mQWV2R zAf;kl0iNHQUxw{yF%M`UC(tQ-jjHbsR z+f+Ub-p-bYyEdooQ$P)qG%;@!^~8IiKxdoLQ4ivW0rv*FYHPWKa~xCLXYxcW4(H*w zNM=|q2ABlOhu_#8Jg>oS(ti9_@L37v<4gffFC`cr!sWa-+f2h(+NZQmP8L5Ys>Ux2 z+lH1CwR_req(e>^{UCYW{J6o(1WCMMjp(kn)Y&x-ibM9tn>ltBOPJhlPZHn!-efbr zrx39_q;d0$9Z#9KShhjSnAuxS!GyhSr`L)sZ2;w2$WM8RS3WB@$GrmEdo_s{NkqPy0yvrefQbvTR)jBWoi^bUy*1 zc$-1UFUlQ#Th5b&Nnan~9=8!49izWLZ!21>XN1~!M$irg(S}qR3k^hsKnDGVc)L3% z9%uFsAFivC;!*!SFh9u#PHs{MiFT9=r~UNBBVIrpdIyBkePwVmZ|Bd-;H!Pa&M6Gc zr;&(UvE{y#YWEN2h&S*yS@G6d6|9;w1u^g^*PO&fT6%iI+G?-rt4a>7X!h=bq0t8N z?DF;7Do5%*4nCX!R4gXL!TvU5VRuA#2!-?$n{_)nbhdcAA@Hrp)Q$Ho&U~A|@EpH< zPQ)R|RMkXC-~|<{Q^fm=V+?k+ed`{NjjJ|YZX6J03M1`N8UJVuR$@z$bK!~I9uU* z`dtN2HYC{J=Z<UTD&{pKlk#|p&%l{! zB93LG61Tz(dd{2bAG8RLx~|UO8PS^CNrsq!xXf!B7jBuH)&)8!o3OvbWYxFt@uH4) zL#Vy8YdVRHX*^d3gm0>;yrmPn zw++yUsgC)RDsyQ*8qdZ&eTF_E3D`$A?uFshdvLsdse$;uGPz_nx#?$ zxz|>6#w;Ikfs%=qnOn0kOcAc?d#2MB^&tu5Cbf7jDZ{3aDuhL;|y$P2ra zly~b6Q)La#$srWb@C?!XkDJ=y4~J%I>Jl>-qPmJ}fAjEP`p+O-e23X09(9!Nu*OyV z&_0D0PT+I(Y71Uo^KbO%{~{>_6_UfMH}}M8Y}lP{m)m4_ZO}4BPIL6t_bY$VcasOca!nu{_VN@7 zCt7~q#^3;=brM4A#pUr`AW(;oi5JksOUH#JW6S|KvzI)+L6F_=e;W-b zbIkM(kv9{4`ZAr%%B|w6udIea&X%a5(U#`QSQe#@e{MYsOU~AKuAth+)tJ|&OzzR7 zp6WV(s-xnR{Azvf3je}#R&IZm;?Gl4YGU#%#UcAF9X0uSZk>94z1OmG$f~#EMj!8a4@me}>eFAR|05Z9kDmtY=LX|2UFyTFzZ%+;Dx3N% zkBkB5LmOXPGkW!@uRls`etht_Na^TN?l~O5F}`Z>J>cX~5o>fmS^888e}?oK4uD0{ z$VDz{-~a$Ei{0sO+N+RSRYx9X=705|YW3y68qdTn7a>2CCidu>U*mpEPS%X)uBg{V z+jEzqM#~tPhAZZ(?nvA9I*(}J+1;W4^t5ffjc;&4eA111&eK2uk*qc_Zx79dP$)pW zm*B+{+MJ&K2;^%lOuei2ZC{@J0m;S1TO`q3&Y}nJN`!l*m_+Kh!XEj@j_`lT@HF6R z>B3uB8pI?~t-VexbmzZ*U;3EDEo#86faAiuP2fMWM{q?;9D@(G_*dgadn70d#)BxY zLAhEkWqV48uW5_TsYc?UoUy6?DNRK+Xrm+gC{6wTEJre$K9R@CJrTyJd}a+S+j{T>5B$%VVVfsm>Zt5Q z#8?@?Nsqb_Q4*Z`jQ@-=bp&cJ*v!*O51GU`K6Te)AFH0xeH@4DGQ*84#iUDy_d~{L z`mtgUc*Z#Mf|ZH6cV=hM2@*+a=a(+FGT*EV+q0a%R>ZZ5Qn;~Iq+1KnBek0mE3ASl zHsNQVvJBt5wO_d|V1?s~*sQ*FE%V+7ZfPfAuo#fq(=g-H$9c_|rYUollQ(s@*4`ad zwvM|qnVvS3p3_VdFci-5C)6OY+5VD3bD$_z^(b}>>VL|5kgWJ>eejLF!k`4dNiw&B z9(TOtGqcIe=ugQ*LsGHjR2(zqy0Ov(X2C?;`8pYB>XqWkRPq!uJKCK(H&xlKZbk}M zf8p2&2h->MPWN!q?KW*9#&RF&Qyq<|8_Do+mU6ggimMvn?KPkSOWH9A!jmZZ-YF$4 zf$D_IyqiIlJ*;y+0+l|m%L^P(=_1vraTdsHO%Z>p)LXZ&q3WNu<|KZ+|JY5oLPO!8 zLF`9C&gBlLYu6rL`=b~WlWFFVxfz||_V&TNp>~q!oGmR(D-(=H$o zdFO1r`AN?_xdebM89|EY`vei{>2rE3FLY01(_h; znC62G`!X5z)YId3D+M8A@}XU@2T{tL`cwy2nQQ&+2RKCYvWqOc#Ew?xOr~1wSt_a@ zwJxR`mj1f`6pq8VK_0s6HS`Q` zDs^gIcLSb*0UTJ3^Y?22YZ6FKm@NX9D9*4IXCO9m!{djadu$027#h-RLf<RTWk1^AU+#Wc4wr4e>pX(IJ1k+_liKY zVsVY0O1@g06W`$Uggknc%8hsHeG<>UmY}f{iIR_L-TItqc0C7ooXqvmyEMd4|ThKVJzcYtyjWWw!*z1!(g6M!rv?j-od0>8a#XImM02cgviYO zr#y`m1I#pLfDtMiiSqA1QZ1qi>>}kY=BQ^l*w4XFyZY?($1``-dT(K~$VXoJ?E3o) z%(P&1t;?$NPeR(DHB|BLfvjQ zzaNJ)d5CWCkwWo0wwY-wl0cq*yu$PJ-{XXk51g-4H%?Li?D-yTDj&J!Ee0o~oLqqi zCfD6bl$T8hT&#N68i_;~=b;DlY-FA;cIW?RJxYXG+`Nb~pA^$Ic#Su1*SD>xEXa8Z zd-(*Cbtej?Wp#1;26wRkQ&sSp*@Obm&lPUN$H6>ai0>DDu^D#W1g?;s>;7snq-D6` z$>cm<-(}pT1hqSDT{(_!xp`f2wLEs}>X_!#a*#w+9}mny8M7R+ibxTaO#u(w_Omgc z&`%k209qtS8%I)0DS2>>g2fHpm+#-5Fvz*#P*nJytt!f_3!$JvXzG(7wF^BD+Bed$ z9)EMZm3Aqa7rCU&t(90`E2l5(ELb(TlxKM}6}H&JyX8ZoM_lM2?tZ4fLapvgwt;Zo zqnd9Bso}iKipc9^n|s)O#7Xh%eFR5Q03i}Cy7A#G09N}WSE#>I{pMO%`f$php~pq3 zuamcg_j66-r>l1)9EKZD5cEXkfp3L?X4CME0!w3>dhPNvW(L)d*z`;v82X%AdEdNH zxGVgliZ$7w?hiuuJ=QATu$&?=+EetT79e`}xpSG5E|aT8xV<+6B`Pl4r+4vGZjrN{ z#*gPh-q9DH1>-+3Y6f4?K~Z{awSbVHWkQ;>*In#W0U|tq?%8w7d~2}}TIvEik^b59-mSPUW<+}YHYPktrtGeZ079Io(z^S;Qg69{9|6!9~EKrGyJZi zwu~cAHVZ4mr7Y=<-E3_MDPI^1N^Sb8K=yw8@vEjUSK|=Z14$?4JuA-KAl0tpO%tx{ zoFFYF(QkKO54v0m7%pNQcyI^qc_u6qDe4xmYp46~f&arepQs!N4alk&R=k{80p>yctN z)kf`UAi98U^RS05^zY-V&2ZT#ePN<`lp{PD^;Gl^UQ}Rb_J5)Vn*;#AtMs4YWD9K* zB2n_prw?By5+u+0EHDDi__|@7Ld|w!e{UGjL?mSdFOV{O^ipBMW$UxR{Ok7nwZQN+ z;f8a2>Z#>2H2CA1Ya#TI*@nmL1_vBqpl{pX&6RJf=3wC-?ZzY=%M%2T#! zN(yHynIYB*(DM%?pAW z+MU4HQih?c9g`JCQl3}eAFUT;wqaE~4}oC8%Xs#5&B|OxQY>ZN|9h7L|hVh~2L|;c#(oSooq|-H@=gn)=)P^Fc{|!WW!5 zF$_Ns_HdEwA!r14&XX~m71_jTo)zBEKav?v#iocmkqBsCCwm`DxgZ+J5?kb1J|=g| z>tOUGLvlY2OD5%6DKMr6&YpoL{KnU^GYk~!s_rH#)Ylz2+2P9dv}rmjQ9|=1G5=(c zE{zonMdQ7Xw4ip{30l)Ogt!7Yy2>kdOok*`USOvo)morK395kNAJ8<$6d!=*8|7Ir zM3W*^IthZRkN*yq@jZP2s;(6koAWCl@v{N!zW4Kuj{WG4yf z?7S)J(^%*2o^kK-#)w1+li?Fs=D#B*aj%0k6j1!Qwk7cT6&+w;NN<#Rdb*O2njAf7 zlcZ2zJD;v-_kGEh{GWH*$y;ysBW!kHBvF()E`RDTb~n}SvBPyg+{9TV={Ce&`qqI%Q*7B;O|{8k8!If(kvC2hIwpk z#?hxq8v2%PbR;{-{+M7b2o6ZibY~KLMJ`3oQ4zMDb3+K%$o+~trfw}}OzSHSiA?MG zxnYruIQ1UJMX$LOVYjKAlwzwyhif@@uIg37&|_|?c=TW3K&4QS{+if7m_^lXbeYJqlJ6gV~KcsJOD*A zrBRSXJXOcj406VJIHF0BMG>1>=TRsjKvWeS z#2dP3M1PP|{VYn+5Cw6_@)3W^>7kukO{z$*5PxHD_k3qi>nCnn>RZeIDY_STCjb8r z;5HlEoVMAVW9Br+oKHDyGYq3S&#C5o2suXwF~>ROd$>09?$`VIe7yKC=M2}x(Vm`o|Fz-yig)f#Ps*uxL1MA5r1Q3uM#L8J z{PTbB==S|mkdPhVLLLLFq#hz%6J#!($B|`sIGkY$8dY?%@4qniAs}ui1&btTD1U;RJIK& za}9Fek0_X*SuF1mN$MTFsrpsvu?YybP%+=rq>H8-(C1W}Ye{aBq9k42c)ogds=TgZ zn;jjCEdL0?@sg}{b)!@Xq?|Y z8&s|59JY|3rkgQ0gk?k?cbfAmAxbiBedg7fd6HZKArZEI$D;W}#JG0&Xp6W_Kzi1_ zOju}83TnDj)VMKSE7FJ)jfobqf#)FPK5=4Jm!K{moA43^m`Fyn#6JnX(h2X%d3`tC z-96n?bw?|CG3`awdwX%AC4+X61}`P*-QMc|L}a{XJm-_8o3#pCc`L(p^q6| zrO_zqE(pJwa1=>4v=nNsUx3UhPdzL5y?fE`pgYc;6CLhXulK-;hfZS~mvA&lDYAy{ z)fX15ipr_dlcC;hVCt0@;FF%xHE0*2>Dj>hYN3-b>$(%CUcQu3RyiF*UjtT8>`k@#RWO7fl0eQMbn9O z*y&;)lvTlVYQa!Jt;kplZ%*4vM9Jbw--ahIabrE{nwjVJ-$B5;Te{ZLSq=F_I63~v zTpBd&?$GJuxupcUhaX0}asbg2p~~*zf+R|Vld8g%8=j~V9F_(oUB#zN3)z<&)de9V zYJp-(+}!$~0MjtE))qANa9CJ`8lpmh@{q8yz0k!nsXtO8(Ixy?uFf z8nyt7W^VACwW(0_;A4R4ed0l~0F7*pN?XR1)f?Vo1^A(K)}dG-T2`&vp4g=?nU0eZ z$An=cK2Q?ovSkDj<`P7?DT3Viyzly45=JF%PtBMVP@JpMCQ^O1k| zTQDs=u+N*zYPzv3^w<<&NJ=6(EAuj5zu{YrA*Ng|O9?uYnq%%R!9NoOT)HJ(zqu@{ z!lr9iiTSw%*b2=(ok(QzSN@&YZMWNLfu_g_>`A3<>0N)RN4#tDt%&-yhGbb?=DWr^6o02#bsgFg_npDeTZ z?0CmmTF@CKiM*L1qKd5Ot45Ys$9mycPL(8}!$gHH$XRiF3Km9HTwLd};&I$bl`>p9 z4Kk<7KGEf6U_N>&!q+NVsmaSvojkK~aN=DN#*q}9=;mxb;JK<$%TWHCOZ#g(LuV^C zFyu*WWO9x6@U`HtJaRo7XK~XgXCjtD+{EPgRZWNv0?_%dL=tkc<4Xhk#l*lj<|>8} z4=3~@7pm!YHOrMZyOP!0l6}%jZ<`b9md8b~YYH*h2mT`%j;F^53zo^LL*<;q@bxS` zeu;Z(m?{2Z(-@|WJu|)*mS?4 zX=V%xZ8!I5g~xLc{J<#-2NW&H^@;z*r}4{HCEu*MQ`)_$(Y*#{lA7(X_of2jKw0*p znrHXK&q{Hjt*IpxULa3!ihU--(fA2w%ey9*`1%B)?;}bP1?=~fRNl_tN*7R`BuoSNgBF9;l*ySeltJ3$cb zN6=%X>%Dv-Cd-=JnVjt%CRGfJQG^iGVR1Mhv;iPT^|pGMF0(yd{B;pGM6w=w`tx6X zBAqklrI3mSUxMainIm&#bOX|4re0^TexX)jpz-aM#d(#q5gkxNx6Uk;qv_2cqs!`@ z6o9?e%0>*@Xrd9ihKxTr;u(sx7(B}YF`N}76tW^bm$rGlvBwNN`7LMCrh7&RHN3mb zKa~IwT%)HF%7ya@l=)5gL=lC(eQIt79XgEmv?|!o%+sFCi{ZCFbDA9TOz&l7=tT=P z_XTeeYn^|9AGXyGX9bWYbtFlG>|ZMFvg zV?=nUON|8UrFBIc#fXtrFq*2GkKuLp>Qk%)gUu;Cjv||V_!{XRVjt-pulYNEjRvX9 z;5B{7QAn=&V1&Hq+_Q&x2DaU&ZVxR-A)XBq6EiCKT5TU@BKMA( zOx|TWt}?GkpN(RZ#gmdn^#M^Kc^XGb7O~F?O35+u>>?tA)-Hq#I!l-zy>ibZB3|Lw zdPa0(eecfOUmA~Nakf`TmO7c@(KuHfm8X%*+^<$1hrU$MU3stFe$H}*bmI3Ls*vkU94fOCqD0mnqCV{UOFXM6LB4n4C7l{5wQv6>UftcQ%v zU(Is&h|>LRDUAt+?1D$dSiUz9Tv^xRWc6 zGcafR=5ghAWfw7(SuIlkF6fzXzq`=pi+rS4fOn}ly)=tFPL~MN4hxv6Wh=-Y2RKO9 z9JP4L}`Gz#o>OXFU8xr`}ENA^wYs7od7nA&*NQ~k86y%Qz}uq*vurS`h|%G z>aMpzm13o{n=bu0c{7U3BvL<~=!Sw{cc?osred?DE9KblW)l8eW^Tdaud8z z_W^aXYZW_%G;zN?ZM}-&ky#V?%0e6QQA!0UvzfNv2xw8WIP$h7_>;!RjLxdf+XqY* z{1my-W|iEQP*j83bC@DK_~ac-bk>lH-${74Kb-hFw`8hNBOUrgvR`S%9P~OrilM|CdANebsddfa#3i&~+RFd_FnE|T4 z+&Zh1_NR-h*&-bt5vqx)pXcx=G{F(tPIqRUFI+j_1Pu3`Q2 ztbA12V9;v5t*l}QP&gn{W@QO2Pn2@KfVm=%n-9+8AZjq(?UYtql zuOkk*<4bSMQ9ndFncY*hTyQdrPCYjuXW4seUWWBHT4VmG;(TO&>TQlQ(!jJ5|CEzV zhC;mai3?cVHm}klpr9AsB$8L})lj!tf;#f9^`Q*cOtj^EZ2GY>@jZfoZkb6M5G?jg zo?;%aUk^%YZ4tSwK6z1HbmcDhGt6XLyV)aL+Ee-$34t%Nr)S0_%-jeL4lBa=xRJ`_ z8~r(c#hJ~e+Gp@t4`U{*5yMjD=1M`U|Iu1$QCNk~vkarVQXltE-|f$?pK3F@>(D@@ z{zylEAi03i!p~l=R(I(=*EbI;$v@|O7Zcz($VNy2`~A$H!NqQT&DnBR^#Jp~cgwuy zooNMNqXU4RDp_^2y}$n^Hy?n#S;M0G<1Gf=pGzzP$jJe(D{+p1Tk_3%e8b^N2YRt~ z3IcDcZzuntNF0Cy#s9XGVN&9l>Lc;0;c*l!k1?0QhNIc5y*{77iFA9QEnwH~i+ zs0?@58<*audi9fKQER#j+792tFUsh6T*ZIC5XXt-$OXlYoE|(^W&cFlFZ+Rso^sC8 z%=QNXb4bW9Leu^nGIvqQoha==l-%+OSc6LF48ud833~!WP|Ry80;hgCLW`;(k7Xwv zBCg(PN&LfaCKEF`fA=#-e^$-*-u4W#hnbhYjr7wt+fgxb^vu4pkR9Z*MYcfYRGyv0 zo;l`qe*h3G)5tNK%xf&057(tcI+Sp-(x?SDuZ`&YKm+Zs*%t;MU$Q>-$WJH8IGl~- zg)$s}az(qo#Aw*)=CjdSM>YprzojuhI4%O6ZO1U{e8~7%x8x^oa=Q#|^5~bGhgYz) zzfU{)#G6*8$v=i4G#pn&0WuupUiAUKp7cB4WBvB5MExxSdXiHm|C_Y}+?pb1_qxyh zGRWx>fiTv7&`uxdFMeb*b9hg@+jeh_Ek^&dv65a0y2_5e)cbYZ+L|Mm+#VMRu{?R_ zUi1Uq{V4?*`>2?ECj}p?JrdV#86~fgDD5v-ZJ&foB)i68jfDURRX@iE9(iOwiSj_`p5neNx{eMi|C3ux#m;2oG0({g*&9$eH&E>gLnb7>|@bh_-BZDl!E zk=zeq^_ruMq+s7y(c-!Rulgf7-#+nG-p?@tQ||91LRI@ZeVB5^Eez<%^dWY(Ts3BdN3%1+fmePasgPG= zG@b#~=omz1tJM1evrm>u6fxC0w|yqGAFmLz)!LWqV9ISY#$(Cz(>_cwQ;&8&r3PBg z-6P@kAVjXBP-}L94JvpMafgE`i>6HcCY7AFBY@#V>JAESif^4NIgQ(wWfOTL8zmC8 zLzb3Yy>p$Py9F;bOPxQXm?rCGo?usOPY>}gF6=gtl?PjjHk6q4%yALIV#28K8+fHn zf(x%3OtHa8Iu+##k{&%yX41jv(;Sgt`2Xiyi%w$!4c9DM$NQ<@K zoc&fuovDTBpOqlKA<%W8h5j_vY-4;SpV;*n`-jr~RCD35TRy;pGpE4#l4|yRcZ5&x zeE46swz% z1t9PsqQyYq`tR*O@5H~4?ihyt8VtWydH#2i*!55C(Z9uZItZI$+l8u7nmxrZ3q>#z zbzeB$M%*gkllmo##!C*vi<}&iQ|-wdGYx8kC_7GmMQr_CPJt=s+boriel|?C4dMV* z=^5I9sgw?F>}x!LznxSckbTQkI-jxeM0xB`(^|P%;?4z)GSB%LwY7a>wj5cidS|34%H`picc!0gPd?ok zS#i!<3$#!b3N?%p6)C2Ql^U=tLOtJ#JsmRFq9D}mWToWD`wpp25kgvz*kT|HsEKH;+kvXqE# zS+0=A^P~@{{ly#1o0l2zvTtS$s2$b~Z=hhnf^ibfiV;)4h(C(+j;x^z9$PwN5A z&~=vgq`U~wh&G0B@g`Wq0BUWIl>8E}kgln|9_JqqEDd?zsMr;4MbSqZ&b3S|9C+i|LCwfwpTV&*k2_z;f5-Dd?YRucS(}2g!W&AjV$GbK zHr3R2^jmZMY^G64-LA-5hbW;HwFGS?hIS%k+xL9&bpC{adLQn98E1Z5{pH zs!5}wdNHqI3;COKPg-VEU$?Nj_|Fv#t3?XgjxME7in?}GI@gA(grUxRynam^==-wP zZ1icpLGfllZ$!&{$ookFofg)O*0d4B7vD63eyA6}MD)4BFVqDLvqmwDlWfX79@r zU&y@ia_&~aJt)6U^wk7b*Jo}m2a47``G*`m1JsEef+D`0~B^(si-*dESw@{0|l)Wc-1*AfDG=hnjCng%bH#fM zm*^Oq$#C_jrswa>yjpC!u}2Rx@^DnUSohAlHMlvft37XkZ?q>AvLXADR;rtqzvLpZ zg>K&#lIERLJ#y6+z1230!dPUrIvLdokWxXiVrhFOvs(h$w9zy1(ORZnO+D81ugJ}w zG-VtO>MGJ=2nac)GAnqz{4GMXtyoTtHOTAfU|=G%atgH& z!87e9nla8hY!R9VUZ}HHVIxcNa}nBzdDD2Z;FoNY!rxhLQ$6s9N2D>tZ|*FGB5Zn1 zgm)CoySQ->CV0{Fm8NS{?|nZ8@=N_#?hy5YQwn4#qa5BO)-c0aH4&2 zC*0?3tMq6G%#1DC~{H)kB*d%hEuqg;D&!wo2GBI9nnGzWF%_#F~75;7fH#OFTP zH6qM{BxyK0lzzLb9Aoe$z*s??TMVpM=X-+G&WErQ4DWy7sI!wOe(uIfT-@)J+#k19 zOSj*1>Gqv#E%Zn6d&9+2WyyfFm>mz0w9{zEtYO-N{yJs2g2OmAQWCt5Q9y`zBjtzn z!awq@uAPqX)uO)DqDI)Y)$-_muFB`G&3atjmdcxj-&&jG>T0ldw;PF?wH_tKy$X&k zOeH%#u3Z@&9h&?VG3qyzl&!9y5%V@mq6t}-w8I~uCjW`F!st*>1xl?ughI?_j{J$? z6N;ms(Y(?gwtJXoD))3S~@V6%Rvnn4iBKSiO5&e6JIL<~$N+UCI4cZZB z;dTg-aD>yQ8qyzT)QOBAiE7$bZy4%CacT(FLt2J-@#(p;oJ;fM-|0z97ERhw4XmnK zSlp*WqJpJKb6$Tf3?Jx6o7ORWe^FQ7r!8pb9Rq0xLdt^SN$=8Y>r!*xy{SzR&rc7= zSsgcb{xv-fK9DI&RUTku-|J+B)Mb}+5R6(<43Dwb;x-iUIJTZom+hWPlk_{UuJP$_ z5`4S^E7~duXnufA&Y%{k%s=k1^PB&i&Dl7yKtD-crZ4&Akc}+ude&exI8Qs?if(D$ zCTp$zF|N~(w`L7mTgyA1#G8t|QOj{7VAjTB#!907#$p4kX9!Zpp;Xok%@+W>g=vJR zz!vGS20CmN6X=qP)U=LDpAN*b1UA8Dg%q^rn1d(5aXJk?oA3A#O!Nd0b9{oH&mRBW z9zNbl-y+nZchnIKsi|aCgb%F}ET09F=9x|V7Jfde5#g~8X*U??`AN6)TzVUrtS4&wd4P2t>P`-|Ejp4 z?DhX`a+R*67vh5N_W^JpO}HWf zP@Bl86dKkOvEh?7gITBN4PlflEn{3}-;Qs_)@@o9M&Txh6qw((62C#mYZbmQp{0v) zYm-(ht?}ix@^_Quy_!c$Euq@sETT&u59=?qkg+yU%;uw{z|`xn*M9dCQ+nUO#zV}APEXW2WGuyRTi<}=~Vjl;}`#0nb{pSNwLhhMZ0fS+i zVs)JO&vSRXMTNj9=lHzBXG*s?c=Pv$=<1ZJ z&A5itpf5W?V{}}KL(K#SEU!?(qk}9*;Y!i2=2EgX41c=qTkze(Hk{fxK( z)38l`1M5P=y%i2;zoa(GRGQQD$>JiTZ9T)QS-@kYWy&cNPKWuKk2&VGdOZh6us47_ zc@=eb2>zKP#Iyo)#nGHs-a;W+FQxa=-*cDXHX10Ix}#LzZcJ}xl8zsrp{-d@CFWXX zZD3ixXKTq=%LS#@7qD&)@mup^cjpYfQbcTRm%~*$Cy?uzzL{(yTKidI&BoLjZ;h)P z2K=ewv$yfcI76RS$t&kV4$H2-PB)cwGURnh;sHSm@vT+X1Q5$DkBDjqE0!{dXQcg% zi&4?d8m-|4MiH|(;u zl|`O)%>|$L~{E8fMh#9Uqa`yR17)0D6}n zarfFknoIbWYY;Z|^Y=FlA3}sro3>WUYT0?2sKJ=lpzUus%=vFFL5wF`isUl53fPR- zGSO&&^pvd<;*9t>g&>`;pNKN={NnmQCE8h8m8)gFF(aonEk#VnwMZkNGL2I|Hm|qQ zSrMa3k(;n8x@TmACGoLchlc!Visv1zi`MDU5x&|YAI$Z`PO1RnEaNLy=Kr%RYEMsh z|7;;`K5T#s4*vTCek5bqmJkM4n1qrY?2*GPZ(e^TdM)w(T075h3dZz>5dr(+4ePDpr~zi zHe_Dw-%6z6m`GT0aqxg2ul1`fY_zrEE^9|A_ZICaa}& zr#xu>*n7pW^l@oArwWx-z!4@fMB?++LnPy^zS-LxG=(iF0U_eqO$W)>{uh7ii^rfKG9Uu?G0UPH5N0lQjo2SI=LyzGG12PCObE@XFUIpIs<*O zDe1C)h^>H{`6vH1b=Cuk-(GF(XY3g#{rxj9^3g(HZi7#mB^wM#UUC0YINd)R?gq4UpnRh8yvJ#l_S8UfwS@N#K0Gi*?1 zvr&OIs)lU>nKEHAwsg%;Y9{J@L5R{fv3hVG*uVteP-eCTXDDGD^q|$R7}FOkTiN^l z)Txd$?lfT(e)J8HmxE>^>->365X_AM64|UJ^`T1SP)MqVX)b(vE^Cvj=TYJ9 zYjr*z>po>Cf-P8o`##|BdAIII8}7b1dzWxu)`@uit%ET2+4GssH}Q&9b?tc==ULdT znKrMGZA6e%Br?z+;N3@d+jpNcFPT|bT+@{uf%YR}F3KuZpNHnjl3B&036`0PM5j5N*}}{-#q_T3Mlw3brQdVlo4Hkyj_pvn+la++xHDvR z$f_v78f8ummF8PbnmLXE(y3<%*A5d6|KC$Z%GBHVgp1~6xUzi> ztl*;DHu^)l>`aQV;ge?0n~YmffYA56&y z71uh{lbK>V+tiznZ*lc1Em~jiyKO0v&8D;X z%YrL8C;c_Djzu}ju3bw%7nM3Wcf&MGQ^R3&!ob#s*(6I$379V~3to$N^|isXb+nGaW+(?D>d0! zWMWQ;#|PwXdEh?`7XISjm5%z*tC1#tez3qou0(}Rj;RQWV#-wR7r-3aTK=E-tQ~iE zy3JeoT=`ZG)>`*v=#j6VZoQutL@y(!+qU>cP86S>W%vkR;mdaPmb9gkqIJN_pabiQ z+nMqW3aNt|Sqe3K+fZEf;W||Dm{ej)-Hs)CI9^VSn#vtD*IZF7kl=nRmyfH1$k|i8 zPl)B$Xslkeoqlng_LZc8g=o0-)MlT|;n5b5F(3`^lVd;LcC%?p=_YvcRohM8g5Mxf z8t*Vj@XX&=U_l#t7s$drXuSaW%Rl+7(0(sr>|*$FOHVYP?aidvQ|DK*E9pQdC7nbc zC)u{cE^(#Hao?cQ9osLjSH=iMp_SW7TLIFy^XIb^(tEJaakuoFY!y9*u{NfEc*i3~ z_)U2uN0CRT+XYNQ3hMa$DoVa(`7kK&CUH$rWPp1Sf|!M2b#0t{fP0*9vZ^Nk4_Tph zBH^t>7I2`wKU zzqs3Ymn)O5&ND9jl%YWqa#I0VFlOv%U=dHulQgsdEC_7jvG?z1mwPB;oslA(t@7XR z;WFLJVYRYpqN`zdCuEsD^K7adE?+#@mtd@guUAZNx?)p8wx+vI<`&ZZx z?2ib5jfuH6pF+p%>3`mnvTtlzT=5S2A3ma|&v=^)yQr{8w^7Vwuo<7m*HjHz*(Be5 zX8?}_mm49O*O!hVj?OBjZihG_ew7HPrlqMta74kv8*heYK}vqZ4gu;TqBFHz?XiI# zMTaBNwcj&r{(_KsWU&0GKaNnq12>Fz&1-THD-{Kz81W0&M>on{L;baG%#BwVX{aX} z2g5TlmL@_LT`D1w*`6OaMt>9X%upZU1&ZeRWc%YXH&!)QBh@vP1as+OpRxZ6Q~Vs1 zxt`mkbfGd!IWGwoyKWH}wM&YeXv`wV3kY6K0?GP8GPgLef-}L3eJDba^$~@SFFTVV z*4CI_o|E8wi7H#j`zEi47e4yc_ik}B6U zrsfO6t205fD!(&NlQsnKr--r=fO(4mpkXO(G`3G>3i&+4?QA*xBzRF#J_f+kUi*+7&aYr#AV%|<>=KZ+)oa*!G^sFZ)^J z-h%XYBFoH^%0T-}-hg;XmnFXSK&Q{Xk&6LTaPI;yXcbZ(#cs;D=F8bs+^qSL`JPv; zg0zJrK!xA*1+|K}KQqyI(0ZAHPRuW=XsIJf2g@9()UTDB$Y?b!t6JUoA|beY*ejZJ zWh}l`V-#;(AY-te?jH_&a}EN4EPv!h-w+9Oj38y2a1aF_07hlPt6YfYK+m%B20L6r z(XJDaFG61$oe8fy#62k+Q*j|xsTZW>Of{W4fo_9k`m?62rHyPcr!AM-8V&?nYuF4S zB~9tGA*=_#BVWI4H^gf73{NP!&tc>K5TBm-q+c)?nH$OraX$VmZd(>ja+`xG&5?Q2Szhw&3hYSCA5iwC|0fOnVuBI~1~j zxkDosMc_xoTQIFM_t$yDmc_)UQfl_8OJQGvB_P-FZ{jZm@p#tWRr_B(SPpJi=CKXr z{$GH!ts>#SG0*%*dcZx;jsY|GB)!WP@}&I z)el*4eB~tX66Al@PNhgt=ZpC8b|Kc7L;y=A;6OVb=u1Hmz7Kj7RTTc z34~tBhd%i#XfCLB)E1FwQlzF5K;`m}3PqyB*e5O3)j8jis^x`J_FVtWpY)F+sc4CP zVWSSdQCm2CP6vuxm$@_L>D1+zUAD2xfkLuF;ti^VaXn10*d;f{qije**8D`tY*;`b zmlK>QCvED6*B4-etRo1GL`O#2tH9^!xg0>X`l3^OET&?*Qd89-lW@#yq756!=CubEtLjs#;Co=2I*n# zll{_a_s&H)=lwyt|MUsIDDP8TD|sk6(Rbm?_&MKYBLMa9n87KjH&(77C_Qv3E&10ZR!7(z{5X4KJR z{7oXB%gGus54FDpOl20e@dOAml1fS744@)IC1!62~og015ociD)lOrzk$ zSJe$9^vbM{-h8RycPMfRdh-P|(nrf;G^oK|?EVDWpN$SdiIt3>zMu`Mj|e8#g*@)h zc`{iwJt?roA@q`i=hZQ>i9cCKx3Fo|jU%zs6p>+le>QB80u^>v1L4To{< zhyr=ojNm9S_SIfWPUg)%`T7Ou1+KUQIh~@RbVt0W!lH>{aannJ_~$vUfO_308wJyK z(jZO!ggZ8gZ<7VEXRPU_LQxo6Cqg3l%$ZqCR$#Jl@EP$g1gsfM$77Ddo`*N}6h`1Z zBRZWOziZRYL9ap3zrDWANzj$=;%Qv;U=$1R_Euv{GvPNDAgaD$0Q$fEAMSbRAmg+~4HkO6A14Q-iNh>(IcFlXg zF8V}V1J4%p1H;&)NQ=DA{bQ$Id<$~or(jjH!Atq8%+71s)If6~F#0`L#NO?Rv8$nU z=UswSh_F<+qtp`G^cTVOhlTVNUoT0TsR$uLc%p#T2^Q4`$+(${7RNIKlWm3yhDmx) zV!(0;senE3JW(VcwKXQ8JOWaI+V+LEZBzo8^8!~@u3 zHpyaU!f68Lp?Zv<7iK}dU&RQ2N}g&(-5xgHi&8Kw66ZJ&^9*YGUkOU@dFX%NR2wH4 z6(bP(U5KMP6r}*(4B)!F12S8)fpsJNxez)>Tjfw$I0OVv*H<=bgr~+kI*!BtX$4%H z0A0&8J<+2Qz99JlVNj^$xvT-cpLX`m2BUFV(6YA3_Yl%97gWnZPm#5^0J-AKAdP97 zjgjc^{gl6Tn!#OeSAU=%|AciN&_uN?S2->}2^oBRj`k~`&)WwkS}$5@F8_O9qX;2i zgMplGv$)WG$==(paTs-Bo=RwiS#tF1A)%^qsLiOX*0n@U?6pPRO6@Ml_MI?c*MtZv z_PlzyashGE>`y|TDx7a0OD~6nW;;sIAR_m{dpr>F6;Z>(#&k{E{BZbqsx>T zOfWUwRG4XsU?e?_QoMN4S-y^IO}?!~lh z-^GBopqKtj04YC4KgS96G@q`X(~wQ625DXT-Cz+Q3wcEyoZy)rmeBYE=lQz$z^!bT##!SS$8q?YZf$%L#>ozRXoeB z_m$h8ewHht``LlL*HW6PHD-2PlVhyT#u}b{)Wi~3 z9CpR4cyY{O{~*Lr-J;rsV!O&h^NI>Lr9S-tW7hQ*zUp{KLW<>bpLkT6 z)m5=SzJByi_)osTjAb>UPN;lXF*INGqQ$y_z=&k9bcI>3{B@6*HY$Hr|{>}i`aKk`QPAS+F1$?|JxDqHZ*801WbhbZ^6*DRzzX9l;5bm1T6 zzYB1lIeeBVz6FWDcmd9&!Oe$EV?Qg`6i$R3V4#{AmlDFuZNN*5VfmU@p8(?eok!0jC1_rm_f-t@SeW8_COu-yJ9Ic;KCZFA|9GIP9?6ssbE6T?5RHx`2_ z8$f^t3BOXLYc}FatW;1M2tf_UG~)`2>?ZAS;KY1=D4FB(MPGWQp;H(ZPtw2Wd(lM5fZ=8hRS1R42h z84y!U-on=ROCA!m$Sg8usfmramNm5X%@P_+haR3IDiWl)FPm~9rG*wv9hx#PRVjBf zl)ZH?{N+S|{-=l_WBzoNU1B2TCAL@WbwZwEHT=>oPUEBm98x#94L;p@d(@LgVZn?v zsnBsvWlqh7>EZ|c>U|%fkBTfNjAh>#}@*TA^D+5;KQ#qzQxwl64B=hmNcF# z$d+29`bCQN9sWE$r5WLW5|b{jAMG9>Hm2Kde{=GoI9ldzZ@pU7%a@6faqiHMj*&F* z=Yj{;txi(k=NxttTmO0MUC^SSi4+K9E?h5ynUO)k42$-BLD*x`-z&y_R1^YS0I!@E zW?`7Q@sh=zEq;<)x~ltWSfv$@d(M@`qmaA)f3(`y6F>W`-jWya!=Q0@K@kskt~UIkh-|Z~7D?RgnSExF-GTpoL@)?+6MYQ6 zIVqXm-~d?1?%Fq0=V^P-H~jyEGG9clPJ2f{Oxtn3O2aJ8T2RaFVN$E6AGt({Hi+|P zfU`wZ{6>uuuogM)8s?+;vJSB)Dw0klxZe^ibU)GQl ze3o|awz%Ggp_S4G^D(FE&lHF`Z^z$sP3h@XGCv-{zN;hkDmAQlm|odgx*ho6>c2~e zU$>q$pZ)LX%HLlRP=)RZV2*NsW+9K#Kqs(Wsc+Wd$w=QG(dJ~&-h7r?CymXc*|p8)IXSgo z2kDyjSy1U3tSz!V_4xOEwsKz&BU`Q|6qs|8%WEV@r&Du;S8qn2GfyvuB*SMjOWVA5 z{O|&VnAVPrAo(}-*iF@T`<>`QwTn0DeY@DVD)Q+ZQ z6w)Jn$-0afvs~>Ke0?EF$Vyhw0%z~%Ws5;PEpYpz@6!?>l`w$~KKCKN-;TC3S_E-Z z92Ge2zMhNT03|fC&Hl!li#z0Dzy=(~fNKU{`9(>F_JiVf;$PhX_tEwsgHhD}q2r~n zzSnVo!uns#JQjCw7i~aw@ff9+$n;Q;^J@+i~} z0&^4^oqTxIMi(7;Hg7FEJW=l4J5JNS$hl)@^vSb`_u*l85$~ymDaU8Jw}TuLwp!aa zvi{3B+{jjWp83F6SHkfvAGx_wHrG0$C$*4r@Z~>bv6qj(l{DjczQvsN^9g8jw;!l% ztm6g(1zYUrIvl#h(pp*+1lnu6P3+auib3cr{SrzLA4GbppR_t4jRLVR4E-gofPF=_ zieY3qwzMe}WRA+@0GY9KWW*J`^`w#p_#$9O$*do?_tzi%wQCX@09_tl?Ji@C`9lCa z<-+Coay1nK)b$AX1YMbLa?8)#zN_BVe>FdSn&geh=}g6?r@YE5G!i^!l;(Wq9*VFKSV@`~Dh zsqwP43(AZ_?!ltRmF$CgCKiaLZL?`=m}d#`?h8UIqw;zHl}oSwtfI!)#)f097vcYo z3em5eW>uX4ye>dV)~ojq&0;Bh0r4ZEVp}bLZI6Wj8pu{}1Y$v#_vhYJl%01*&Hg0_ zmWfyo9FdE8((fp2iMc2pMF=+X^9VN6m9q31#Jsh=|KsRf{F(g!|IZAYiws68PF_wY5IK>#zJ)` z7XYo}c%lsK1OZU}JKce)ZNMl{xS6fbTjmL>%Pz*YizJ?oDOQGAg1yD_C14A$E$oSW z&N<`qc9v8NKkPYO5!FVLyQb`~X%%Cwpoh^PbR2UCG4~;*wiGTJmLm&BI#5#K4zhl7 z^`Z%<&o^RA$|)D%7UaPs&vAUe2gsQ)0ILnOVBv>=iGxxLVeD&INkOf1hLfPCL zrp%qL%QCBU%^|@E=Z%}3%(7@;_4CA!Ec8Drzi$g*uWfK$&CQHo!y#O}no|4yqHb&K zdZjO*P)rq&P%W@2`X@i#MAOuI%;8VJWO-8E;>}6H=p4R(+2InlezhXDB??N+)#o#Y z;%L?^@FQifp=y%W&{yj2?pbYSccl2DMdP*Gl5`X0fTiH6bb;?IC(V_^!1q3g3LfBF zEyyWgBbOVo#~gjVV7^p}bd{S1|Cp{K9hy@YQ>oYZMpi2jS|q50z(wMpKiqWyb|s?@fpvZeAl; z7K4QpXw?nRWkOOIzYtxgDcop^NlMELVy6x$B>NtudR1sXajD!TlO(-~_f7bE^K#Nh z-!q%>lGlMi>+j;}rlLL$oka@eH3|K~84B4p_+598IFOGbC-uJU>=dQx0|@1^a4y|Q z)!}CqI+kE#KLc_6^SH{nt?{Si=`wEB@&i7{QWw)lZqurMV|+%ZT;azZ!0pid>MPn; zeY%bxwLFX$zF~RN>(>Y1j7DAkkUMDWJ80`h-=su;OH^68Ky(Sqt zoL$cO=7F(-8{QA=jzjjNP0p8sdH7Mav%rWy5OsSKrtazd3yO&(i2u34*upuubu6~o zp+!-datn+c1UDKH!48-9)CK||7RH?G_j1~$qDHwfwi%Ztf$_-y0jOvpQ zvWyFbin^4SzTTHuZ|G>Zc*_%R``12o`Oceev%IM1C7Ra(K%2TOE7&Y@Q*D#~SZ^D0 z$E!E}7RSk(#->0!)7@>}i;Fz2%h{X>rNJV=7BpllnvKll-e^%=H2{RiroKg#Qf^3d zD724NRpB8Zzp*Np1USr)*2Pr;s#dVYlRqjn*BPWpON*#7PAt+Zl)&o4i+s)DfQ)*Q zPB%cqi?pd#r&*`20ZP_3%)2cCP}LPxLZl#fBXQ7_O|<9mT_I1>#tMG0~zl24cjI>eD@@C^Y=)Rg07aE<{95@F&w4X4Ks z<)L(6GitxPa!Y7~G6O-=uJk!Ptr{WE$)w`~i*TcDC=|&opOl3LD7BteLa6t5J-vx; zQUWDw?9h;_e5+`!7qI|&gM9f2m|ihJz7A7&z*XCemNG4(eE7G zii<)U2INFnQ@XTuuA9{VP^nSksk`Ek)|oVdw$S@X z2p$}uIt&7JGRU@F3bQ}JAS;VGjSuK&zn&A^n5gk1Gi z(kiqLo~PA6{djDalqxT(1d+?i&125->-WiO_b^G1Z9BrdpY}4p)r;;LqFSZ_riY>p zWsiRb$rV4T$ZoATRZL1C8X*Yor&*@L&8Bn+HhN3SJVOW5RC>%F2eB4@{b~U##4C)K#7CvR#5JHeszo&OvUNh zG?rPPQ-r2Gv!IaTtWN~EHrp;98}P)E?_x}rb*u2wpok!SESKi8lYv{ZkfVquXi3OA zGABk2SclH8Pe{#Q5prT?Z!DI!aSDGi0ABmSlT=)jYvK&EpE=k{_Y$wEuP+ObFLyBj zI3uz{`R@N_3VzwLAAkbi`miF~l*1>e_y3SxR~R$#CE}UJ<+*3(`ZMcBF{59gr^2~} ze_;M=m3d?Bcw03Sy(Xe%l(`1x@0cg4p+vWrP^>HbdTtpkt^rmEsYkb1J$J5WAE1Rd z*XsjlQ(ODQ>slsB@3a(FV@SVe#+$22Bk{0;0gM3%SC<2m@xFJobayL+e6|;D#H7Dq zLG8Jjwu-8OtTT4U$xpNtR2=N=?Jzy@8(`X20c{nOYrx$x3x20ab?9<;Ocvv`MS2== zV+~THVj6cc7HAABPiJ~SRbyb%U>vnt7ol;q)Phb&MM?GCA+uYIOc^P_x@2Tg7Lp!*NmTEr6!UIMJ>NYh!opr0?&v-eS4zU+xh8t= z>c-n07d&xk-WXqrxU0e`Yb1ao&gN3V0t{c0o_C&eqwKd5Teb_&^&uNgSKOJLq19ze z>YFgJpF3@h+OuX?I38b`=ldl=QV(SlG3^?n@_lbi#=-}OC!x|~bad}LuAN*nnTc4h zznbux#d^jHFPUrfI{_4oSq2aMec6bmWMYsLqL_=S?Vd0UmOVCi0l%)Pda!3j$6)f4 z8PeU<9tFNRgav+dKCT4FvS>y@Bx-(|3mJ3i9W)9_iCnq}7|to$OcjXgprJs<(yjT| z#?baxJtyB7FumM8Vu0gIV1=)sj&;upZtl=B!GWcm<%2BllB|_!(=CqDb;_~x;dYsu zq_l0n;w}cbB?)m})Q`WB>e9Oy+nb)v?agy(m1`wE36XAw3EUf%RP564mk2y74z#h! z-b4Vy8*2AfH9Xjo=uCqPE{!>Xpn(fwi_6af{-Pa2t!xjtN_~JbRd?fE45Q9fFIvA; zHmueWaZ`DmJFxgTN3{-vMV*Y0B?Ek!#zqgjCY~lW=}pN$F%T#BO?1c285^prkLLDv zk=E$Bsx$ww;eE#WB=h=?ksR$lZV7|rNmJIO^%QiH@v?Tuu6*0A+z3&=CtzAguZk_H zHXvx<==*4rm5HJ7_Ye63!JMu^Ijeu{0C4nt<*4ZRmaS+U*5WdqMF0OsIClkRW9vt-(!|$N@qm|%Y&cwD>!qxP8F1A zI+m+wE@!mSq#(%c1 zI%~*B_PI!iSz6Kqv}U1w6g-N49t^%Trp)97N5+j^$zqs*D$cawz_(^Q2n3x7kB zKUHT&fen_Gw?Y8uH!wCBt1D6W=#QZ_6~LhTncGUuSCXDhB!9LkA^jU`oJ0T|cJs$- zaEUh^L`amNnTIeOHLb4j9WIsn*1eG5+Lz8ZzqKoBzf-KyYO40&knq;P)Es1zv8 zfP42e)YXs;?mAJ_s^DlgIB8H}wgHv-u$D!YY1W;8|Kx;s^*{+%hSr{;miGGNP|=g0 zNNrmaI_c(gbIu7^ zDR7@ubJQPk;j^5gh|Qc^l5H4X3rRTCvUMXdJPkIV4}z z{c%G+`+KoXc4p0}GxOM{E+3ctd8(Zr0%X)YBELO@IDV|gR3%j5;qetZmR5zAwn4>= z1sF+xVy^Z-C;hk5Eu4*lp?`s|hD<6z4kqsy{lgT;gA~RV(gP{)u#d)jj#y`quFzU0 zojmOfOSUK6KD$X+fPMrI&%0bLX}FAmmB1~}H=L6IyB$y_%+hf$)y)Jr+W#gdYjdi8sm23)Yy~h8fi_}UpLp-3YocxW81X3p}V z=YAg(MY}xMc(iV<_JHk)N2i9H(@?*uF5@?=DcY-QHQ}ObBv$?`ThiX^0x~?@slG!| z$n|1URhY$0np)c;Gvj2xcy*@Etd~N@-_>e+G=z^irFKS{lXm+|r#3~d`Cylpd;GQN zZqEHLuc^p}Xr6JE^!iy|8Cui}(>hZlejG%ANC%0R`{n+GHh@T%Pj}7MLF1KA+ zQ|mC~LQ7v7OdGn!BXzw$h)3GZjx$~Ia@|_9t9752g{!Mu8(xV@2(^Y$?e@}@a831M zN;JY=y3dmcCRO3pLczFSahx|Mp#k{8D%@9}$0p>ifgLEU?C~B|jRDEsg(gEjq^nUS z#EJ)Q6{n8}-r2u8evV$pMzY@QO5%f-;z-m>vu|q4pAY{u1Nt3DlBAT21O$r|x~E?8 zD(gS#Xji~-%#J{Bo5YgOz55y}IhcMmRvb~7a3rBt5s$sAa$JZWvr%&rS|3wu7LQ$1 z1|~ zn^{P_H2toe73vce2}~5IQM=_eCLWBu^T8+LT`r7~qow3k;t;&-k|U2LSP=Kj0<47_HvfDA=4>7e z+f~JW(*X{N!qEHZ!~ZVdvH0!jRmHC|LlSAn)TuLo0z=qWk{-c%dg>3nFVu}W+)ouf zRlF8|i2;DlW4No!k?6~&T#}`2nzkG-&$(OUVrq{~3w2v_)Nf7?Dhp zy`sf(v3A;J&Z$A5zT%9lSvp@nNvc|o6l29}MddzAiaG~XIvj068@6)g@N?Qb`<(3l zH4u^ABJ;K7gHiG{E>4lS$Ya7{xe9(P2!yef(`Eoh? zDWO*u!_?o?um?mqFtH3No2P#khP8fx!KvY@6fc6-t&HSzP$KhVNAWIF&CxmfZ0(DK z$9*#v%IfSdt;fFW+C|+fN+;dP!p_p`@Twy^38+ZH687>c4FKAw>15X)CiMZwV3Nyu z3G}Ug+7iqzVs8)h_~=4}u1SVhC-xX@sV)z7#p9G%q%_@fPNB;j~zq{c_0ZvonhPGuUP_e7QJ)ZDXI=tZB`Vz?H%!{0?KIX zf(2dc8@*A^sgLi%B}-b7_nU$v4sEhlZN^#YEV*`kspdCK*iCi@{%2Lj9`q%9)^JEE z90bCf>cew524#MGJvml5K(=afk>$4cs0CNiI=4_waH+ZCAJe?B${=AhVB`%(1d^RsVB>CG_Tvw3&#qq zLs*MWDeZJ?g3!9@lTZudpODw>7qcNv9799WJgv%1lF5xvgF;_P;8!coqS<;5%FN^! zdiFuk3{x&?$s-=)dSbjm1i;}}eyV$t)l-WW7*{i8$|Hd74-|VD%l3WE&RgsJ% zQecrJ6MJiqnt^kW$QCw5DZdS5)AVEVQ_pL;;o0(sj7=ke)JwUh5Raj_ zdeQet36#THivy%zJDZccV6?ON7h#gJFQXeG;M)1;TK@wESg;UqrN#I*;ACQ}t}-@* z+B2%8N8kA{>|%y_Js6eFAu0~d#%#N`N2S+Eyo5FlxBiH3o-PFI4uj}-P4j}!o>$Y1 zIaFW;emsBavTv@67|VuR1N4+L)=7;ohCS-Xc0WK}Mu#W7`9?BcS(p8t`HL=m8ODUA zi*sx9#`!rWVj+(fHq^E*e6bP(z)~?xf)|md;G~>Eq~dDN@wD6y@_-gW_`g5vr!*-Z z%L_&XZVyTwiI&?XB!tDkP2+WMGNUW9Vk z+p_QOqflR1Nz)2)Cxr2#6L9v#`gA%L_w9Si*`s&wc+ZZ{(4r{o#Y-oLR(7s1*7$=T zksxgTa1f=9PI}h#Qt-ou?!J)g;peNj1=DjLbrGHH zy;BdZ8K{Y~obz<83hUxUI0%CMDSY4swDhAL?|U^g-7z=egvGl_?3bJOGG4yv6I>U6 zxv-d(#UA9i9e1tN0++=6%&>3?Xk;HeoQ)eKo((06OuLB@#2EylsP1$nKF8KH!@iyP z>JynqMp!zk#5vCPaeT>OiR})9$d2ereiD6FGy0VReGPcSpaRF|;;7>=57lU}*i#P% zw`Cx=qzGLw#$uLWI`-|b@1LIC`&MkQAJ1ol;ea^7{$i^j8BV0MO9a|-yW?%Z4rF3} z$e%HJZ>%y9IXM>Yd~0`YAV;jgYX*5!aOB`WJ>+r{oRnn3bCXU&wgBEvPVF3yoRkF7 z0R71K`X5}*^pa4F05!!v6}I`i_`TWz z=ijG*aJba^W2^{d2D-2iOdf_tkBMp6%Z;Wfpad_sdn*&*p6&cQAV(L@1qp~*sx>Ek z5Vub#-cK&4YVcY6nZXZU!cl#->V4)xMDZqRiTqOC^QAJI20Fq6g>7$=PoT_x#{-*t{OVR5o4ULjo$4BU197Y3_^*L!uNH;guG+++{&n3s zrZ`&0Z@zi%(!fZ+8=6M?hW);jY#5 zAPeH4A$PYMz)cAoO-}8%umb!VmTO7#6)*3lR5sD?edT5*;4{N?={NAsVRn`+hwh9D z<)J`31?2h=hG(#y_jqyMoux-#*zgP(@()bn?T;f#lnnbggU6h#g=6RhAe4ZZyjzh4 zGo$9KOU5XP+`K4qgDt0r6y=l)b{_I-ze&H154hAO7xOKwQzIlT2fL+6QON?Ry;E6D;(Of2(BHzaCJ&wZ}P%vo_1LW zEA&4S>~-5kUvz!$H4ookU#C!nyYUI;hJ%sKE|)gPx6kC8rv(PYzu}EhrlcUM|0#iQ z9;Mg5-3$)28%2E%=t^t6nb)|G4JfqstPu5_|6=4!98AbCabLYdBK|<}+Y*X*t}XsN zCOE=jIW{rEVgh{@xO`le&7H^64lj!Bc%pg>IiGJcp05YW^s?<5oPBROpTAf%a{?aP zT^>(xypJCjLA?>n0UqfiheR^6j^{EjA>jHOw=I`WPvHuJAl!l$;{c0sk8<7`TS=7H z<*o@&b!kNcK=7w+s9>gl=5j>+Bs#xPPJj6I&d_;-Vb~P!5~Tlp)QeUo_Tr2cV<}(( zuzcT876l?9)r0*@>qCG(guqGGGppAt{;x=BgY6!#GX+Gwsi8@NNSom$>AQ@l9~8zt zpUT|5^(9>q>Wd_Qy!?ju)=v7bpY|$-_~^GIYMK3NPf5g8t2Ir$;Rct!&$nZ#ff)S{ z16Lylv=ei0@24xvc-}q=zJ+(Wyd;O>kXAzsBb!IsI{kyQoP`Vl3R`JjTQ6XvwjLag zJ_F=~Pd!19(l=%DY;=#4L#wOZvyR>CIdEA>*%#`oGdeDg-T88SmOi6yzvATa@ zi;~e_B$J75LYybGGhRi=IPG8Rig$9358Y{ZHF|9A*&}1PX({w6qJb(Nud`TFRpG)RybNyh5v^#8?bp;or#0PN~{I==g@uh z&@X2t_^VKy43sUGv)9A8&%g!O)6RW7@D}GJez^3I+vt~Q40{xB(KogI;&N2s^J2@} z3)~+g=yx?E&%JPGg^HRz8VOrb8eY}NcaycL)`Y8p=Rfc+;Y6)J`rpu{BfGGhhoNCG zfL>q3P_*T_4y)}XJG`y4@};zZ*7o?cd$swS0g_{K2P5g|Z@Y#j$k+&K67MOLs8HZLMgthwP+2=Y0Q2jZd?d&Q> z_(zECuiw~fg;v)JuY9+Q%zw%K%QWB33Z-7VVdM1HrbWQ)xFreEQvU0#AfLE;->Dz2 z`|)4wq8~<0kYO#H?K=i{LY&-hIXx=QajW6y?-(=W-00_?iUoQ3K{CU+HD39R`J4uv zFCGbLNe`{-SLh!3fR9n18&Yb5^(G1?q(ElEu50!)O0mj9#=HMN0R53IyHi z$xVgzBf?Xn!v@m7q)44VcwGH=BmeG)b*si<`?o0SPw49%3AvV&xj|7pgP^pr_!<8s zz~rb!zYMS9s%~EVhaXxN?^)9HoeH%< zM(RHaMCwiAuuV|g{Npx`y8pR&+v7R!y7oEhdYKgPORJ|2nx&R?c`KXtmsyPX&U;Tu zXZ42L$8V*=V=|QiBy(5#^PAmCyWKZ7m`l>eCv8NUPLSSnvu8DlcBgd9^!M)%jV!H% z4(qC#kMM@H|Cw7ZKuG;f0!ytbe0{L#` zcd$A#+9*?2NMg;3=9CE*E>G{`BwKr* zS|@SJc1`zmO4xWAx}EO)R2OMl=hqr3xD7}4lg!}XKG%y@y}EBA!8AF5t6}Nh+$SvRoWfmFwQnR^l*6|t zSvakG_r2MK)|`M2)rF_|D92`>R>_SB*oU2TJNm>U$AF~6AD>=7x-ED6*1x}pzkmNv zu9t&bI;R)F|K(nJROf}wf^RrOU<($9{swmh5-0OG74tG5^*S96!rear28G?-tT*%B zFnx+5_8fhK^fS6MKoLt#w&338xOhX@M%9{Ck1maUFL-L%V4zO%VK|pcMWj!CO>R>i zlTV{~3!spx-95_YoI>6ogS7{vD4AO0$-x3Bm{DDJ$~Q!vkjYL2;*-pTvLWCap6_kgW@Ry6v?Ms^2#k+@(LQtKe38;Y?iS~4v)NoYgD@e>yF<;3lXtSXwzHVQo-ZJu>1u7WSSL5$j;ixUUGvXs&p1B%!O`g!D?k)|r< zx}LG#6z%$=4TW_d>0w40W7?`_kpOuD&h#Sb6hUVvCWQeOc~ykD=ld4`AzJ zPEJboPRA-=-W2@#kvtH_b}lw*K9MyXx&w3l^gg#mnh4Cbg?&;OK~eCEP~DA665HyP z^j<)<6cZv?-OC6Tbnjbb))qG$xMd7HSnTH?){?}!WJ+FL2WzPd{{W+OPhGJ;wUjx> zAnw5Ggp6#9t_Yd#DpDLx7?^)TC^4J7D-;IeJvgIhV>aWhiaV2Ejod;X^R}P6K=i0KL@dv>}t$!JLj@>VxSt1dgtIQF_hzb;1i|Ao0#EcIi6^_FjC<%Ti}A zQ*L8)7}18bC^=ULvC+W|>n|euLH)u!8#!uwq#{n63C(-)WChtZc~e&Zt&(Y+GAxEF ztt8JE?Tb@l0Md20RFm*kB11cJ+6{ z>f5#fHR2<|zN@6V`v_GP-OFJ6Xskorto4^ZnjleuBvHrUNnGC+`2QN8-RfJK^3cK- zoU%H5T^3jUyAXn3O zQkOz`(D*(9?;T&!hDQy3S$s;W^)C3%WToLCq(Tc^RCI8E+%tO(+}c!Awv96i%C^=AWEtCn5^dep;?;W^S?{&{Xp zc#yKqG**nz)=<8>!9SO=@U|`*R`oaRkOs|SlX7Xv-icX^wo-7emaha!$S zs_`5Ek^1OC75QDNWBaCg#TG7LXV%mSCg9h1{0YcY5D7}{7}jM2Oj8w$C4?h~vt9BS zsf7cxRQe>lReIuz-4(KcWi3`Xj}fRnhuB3$VKmH(L&e{_J@Bc;>g^XJd}>S7!`zME ze99)T*9qoOJDQjn?p^^TUu?d@`DpharAsRxI@xf88a7NeQ2Et64(AY1Mo~W>Cq+Ue z=T34b27zbMMxKRR{7C`+i`*Es!>p?ov;dV}Lg44#M50{+2bBAIPr08%@@p8L6n6or zs=6b~B)v(jK^$~Kk0sEK%P%8Xb?YzGI}!o4TGYq)PP2rBZ|rPFe{A6m=Hqipi=6us zIfAlS@VI_rY}B%iT4Q~6P_f$W*uS6?^H#|(2;3Oy-(a^nb~337Rd3_stb371uZ~lw zpp&4aTSh_qDM7tkZ9E2ZsrUT={l8Ph5VLz7kv9QwaUSwHT#B>lXuDpTb!33imSpND zZtW7P5c-c&-#RL4SVU3))%3pH1EuGmMHE1;z{PVE5)7Sw#fPYhN{n($jv*CFCh+<) z8BnZA&FDk@LLY6%d=gB?yjx_<+#=5&533GOMNbP@o(hop?EShs`M~ToR$5-_UH!Cs zdi+Lu2M;SnYY;zDph5O*T%9iUAfJa7o;?a`GibxP1OHU(Zsa{Y?={{;BZ;ciMY=O& z7vj&lbF=R_-lO>1@kX~I57m^6BrN(hO>IDk2pr;pYuJO2adsiR#*WYIPH)pA(gPH( zI5JLAE?0ccSutwp^k2s7-AJ$b;y~;0Z|N7Qo#%F}B9t$@CyAAs8n_ywpSje@c27+M zS;bZO=xB2{U1P9~1E4p*xZgCUU7s*Rsk#|R_Yq2<@ts}oUtsd1-1@BM2pM{vhZEf& zYTQg2`5Toy8;Ajjld?8P3j70Jd$1-wl7jiNHF}_m`KF{jXs(kK1xVr2R&NQ8$~N*# zgSVTRs5&*_d1&3{A^EjHM`e>i8{_c?xMh$@rMYqCmeGpBRHp;)^&H+um*jSWq}Y(W zf)51B@%>Y(gnNJs5!hTh+M`C>Vdn`XCJfrg4 z^t;Vc`Cozm#4=Udk_DF;g5BqLfR3K3Yu{Co4{KM22O$h`G<4n)iZO%ksN8;GDSE*B ztzjCs!W3mW55%VU?vqZ%4^&@@GLh!eMvZdPDcVt>;V*UdM+`{PKsJhHb`69%u5BQ2 zD33mCg=Z%lssd}e-)pHBsk z9VKTLT}Fy&8qjl>p)xazgM0g1xDpdy(IE7X=#%pDBrwYHiPKj;$@BR>7nJ(ZN|qL2 zhm49sQ7N3#Y-) zAi=?|K~A-VPA(n)v{QL0hJKciN>E*~xrri>#-MHauVD+fLvcY6hcIKCv|1n$(nFN~ zLsXb^J^k7>e5a579KI0h0~YaV9jI&BrJRx;#ysQxpY|7~L(p37rurXVox7VNm@2hs zvIr{ZyRtq0Me_4i20l9U&6!59i_*&dUN@h9zRsyKMPb`^Q`>Grr?iE$biZ93x+wCi zJzz#CGw`a-9d+B6LVLYG_e>Y}5W*hMhD_5q~g0w7(+;gyEovdovRou=k`?Mlxsx59G8d}W`$f`Eo7B@DIQ421>71=trjYH^ zWSCQDV!Fc>5gjP9v&CaReg;3(E^3gNJ;cVWY+W&|Gl#@qs;69{@R)7AFsEg5nbetw zRfZe4nV)$|gGJ|@z76+Eft${P&e)o5x0`K=lXV*uzVd{ab7=TBXyrI@!hzO4957MD zns<-9FPsS7P!T0_t8Gnbr79+U858VGZ$Gx---TU<8-^ZKS{-!rcdoZ}s#^&xiabi1 zctqgkq}c&Ijgzwvz)U(?J%!VU(C>^sUuI7o%;m zW`g)YklbkKGJk;YqdGYm2@q>3)xZ)iLO1=)gt>8W-bE{9HYgS*Zhl6X7?$Gzy2vv{ zhR29{#(Y$evonLi201T+F4lM)2iZ+}Yh+`3LyzqS`{f&M6LNDfeQM%k?@&ZWa;U%p zFUl|jr4L3gGZN=NVav`RT85$@PyBAj36wLOixH0ksfFTLi<^!1JG}^jA;_J^#lbd9 zS6=m)c1zLDpzHa$>j%1LW6TH&e$bs%{o=1U=$o|oB+%DW^CXi>FuuqL4c2ZrM4dZNq>i22&;5Mkx2VpU-K zc%M~rtcPrJK}z;7^^(Dt*qb5b>-AIU&(oT(ixlxBx8Bu+Nx}J+^Qb1_8>XM1Q54z7 z0eT}%b={2-hr6ZBAFid-FWvV~zClAw6Aq+Y;RnH^t9|`Nzly*AQmK5QY#UCit1*F7 zm{Ik|+0$FNTB=hEfd^^C%{FwROxVaAMMa7`* z1Eu)+3D>TCr8ZMH$amX|GdG@{N6#~A-!VX?!8etIRBxq<^!ya2?OK+mN{nESEj>1F zF9I~*t}{&^rkdh(TO^zxw2omwRB{SN_mc5UVN^tp+s_hEji{lq0l`jL2U}~)P?A@pUD_5?)B8jlTz?s15#-+C3hUvdDoJ)%`+ojKl(ytNGZcA| zJLuH%E~(8@#|N+LHPBzHrD=2}2NNVwpyZf06en6{ronl{416de+8!0-LB>Xxnt~S_ zuZ>LDJdJSC9FmtFilz11i78o>fcY|i+vhxTv~z^kB<4yL3e%bwS)PrDrURc=tsW#c zN>m#J(jWoRDAQIOU9T)8i) zHn^9K@vL2)iB^R6^jpsIh|B|g{=h8OW(oowQjLD! zXs7I^wqZP?+2BxMj3-7H;ZtLtgw}C2f^v=G;<4h2#={Ni84f&++l-=cNP8ySXgI|0 z1GfY&I`4|n_}Xcf)U3kIsl6(%Mha}ZVKo1};i!@nm}qh;)5o6R*O@l%3N)?SgdHP9 zhOz4TE2<)W#s9fIoJM$det-DoKe6VKgi;Qrw$-xX35Ds`zqj2x8`J`v-L64W9aUR@ zCJ8p|Cg&DCvebJV^r^R@`P{(6r~QqI!drpDO@Ds+3I94y9(#2Oz4Wu=2WwB`IWBhm z)RS$ImHtojJrN0nU|Z;SGtK~3zd!*h9G?+utVE%R)Z za6^Y?or#YxUdzBvUphQ6N}Uw1^Inw;p`)o^L3@$$zRNY*kfCYF9OX`@7y{Q`+U^)` z^)QQnGGbjSqGoZn6BpqHO^RV4#Go3;r8nLpNe)o=>|y zyhRWJZvXzwu;Lq1ND>m&bLtH0vWwf<=IR2S=!ix&ScA@bA~;M>}tIw7KI z^Wm2FbL9z19hYUNgp)&)5~m{HvdnzzZ|B?GKBD8j@=>u=dD?yzSh3V#9i*JhTF0x_ z*X@nEu?_4rRb0dtA4;wp3qsW$x42N$QsZayXrvbQYNJWQ?07~~yF87S+QZ&6t=tDy zqcoqbLo!Wh+O9OF!A81%^Xh(ZZlyHS9!*l*ry*(}B?Rm(ME*tr-%a#5Tk+vygSO4K zcFL{ESqJB(fcD0bBF%)474aYHKUOCF`t%Whl%Ik}F7?)Bp>FMa;c00t{WP@)QViQnzbkpEJ;+itx}zx7k8Ox2 zi+S#MSe)>Tzn6M7JqXDY60EBxK?uo=v68vELSJf+4@?^gf4W2;k$zVxCM8$jXE`GM zey?hzJ8`wJ?Ba3K^xFN1YsEa0k#B;-($B}c8CywQ$4gx#IN`)3LO{mp+@b;@L2m-n zHRu)aH|SOiIIL)7=!8uY@^xZBJ2F-(YI-|O>N1{l#3!PM$Ro+6i5-)t5}0`95-%o5 zF~^TdRc2(Dj-&5DPP@-k5SGENwxU?PN@X&hPqk8anJFhkl&9Dm_Iu&0oBTd~P|FaS zRm@3&%}!%^^b9FE%vHrvY?v%iL5(TiKK%;o;q9~%EvL=*HnvcE^uOxS@at;n25zHB zE--ewsuHv=Xn3%tGjq56`nSW6jC9Rzi@&Syrx52Wt!>`YjK*nY24^JokjVm@Hfhq8 zZRle}1t8W&uKs9+H-$H`0HlzSQ}9Y&?OqIz-{lVH0I6#W+?H@QTa{p5y`{97O)aPz%CY~r^|1+;Dl}A(g z0uZFp6)d-2-I{==EtljUg@-5%NhC9n9cTi<7Doc2Igo`q%o@ctZk$?ifK%bQ!E$@dyhM9 zxS-cZhn2J3ky#-u6tGpvz{eVyBYj~dYCcB?{HYNTq<|I*(l1t2yc!l9@)l>7ofIXM zPqA+bJ~6SFng0!vKFYIg*H_(K3Cg_0%vY1#q`gp{Qt_}WRbyfcm^^T`oM@mToAMy% zLlU7fa6YpbZkcC68b7JBdarx``{{S`hJqhpxSJ~eIfn?I3Z4{~{m~TZo~B*8b|RWE zCv{^sPyg=*m*)J!{iJ6+C;m;`@9}@H89T#6tTUTB-*&82Zs;{^FiIB#Dk+$02evRr zu6h|%thONINBEW`NCAKlEzPDJ{wL!k(tkfv4=DngO6Dc7w~*B3{ss|O%2)ZpJ>K%K z>K($tIK|w$34A=wRcsuF%4Z_oaIIE#9Az}nZe4R)mZfGS)N4$i_4@x&bnfv?{eK*1 zw%O)3Z0<61oBP}^iH*(uGPm62l29tw!dJ!2{WkY|=6(syHKcOCgqmBClq8`WrBZ4A z{Qf(Cp7VHo&f}cV>+^a)pRBu<=ksfAuEpgiZYkfrM&QSXhf^sSf@He1=-%0TGM6D_ zi(0IM176c{1U&@0^4?A z&SE`Hj@9rafh`)_-*8+SU0$StR>}i@-rP0cE*1Cu>s7HVSMLvHWPB|W^kM@&zsl!YL5Xe9 zc=CWPf<=2+ozs^yGYsILM+Ecu`En%l&YmlP3+Q;=JMQq0uRNjL?w zbo}7S`>6<#=l-7F9VS+&J@R5As#`|#uZ>w^yk}m?7FEp|Dtk$5fwvRU;L>e@NTJ6R zUUA4Ct@-sH$1}h5F9E zV%N5mtL{*%k16wk@rfd68<57wUM}d5l7zdo;tXD^)0Vo`x`jPLfoJebdj$dkB(6t( z5+uz|wY$NGIGp}aY}MDz_V#Z>A3X0VKHnP|zZO;-wm(SzN;5leQvY zb&uhk_F@y|W?y-o-=*yjIka8;8 zoYvl)#`M0>wd3S|pG<~BhNVUC>Hl+qHAwTHMxUToW!)xjIWNfS*KjdgL-qb*BZW#5 zL{cyO!Erk}z-;^=I6miGKgit;O*uaZ4M)5Ux02orG_96=_zijkr@7SV&JhkRj(5!5 zcNYa;b)-q?M1mbyf_wSm_QD)wqCl2If}8m3&k}@0fEVXSLKZi1&-|33T1Iu%q9A8d zeXeLvLrf&&Qh!6tg{ezx0USm5y!vo4FOazR-$h?_s#aGESNgJl%C}{evVTf8%#;)t zD>(OtBJMQ=l#y0qyLRfjuY={jT7()kaNpQSxA=Yu)L?d&bJ;O&sqR8F+ z5QQ&<^&LW5%&i2;QB5eKF&<*iuT_A~unXW#SNE?EeO*E1H*~nF*aY58IdpkP2e2Hh3 z#Uh35a^0WoeJFX83e3f!3A|P}CQiru_?axS$M3US*16YU2rX!h43uLbO(LWbd}Z>a zIpz`J8@$$aCU#zMQ{%r)f}tG_JTsn~_lC6V#18Ed{zDdtK-q1Lu-A9knNmeJ>b>?H zlHUe!1f(Vh1aWK-^R?5G{enb6$kj_C|CJJ@j6+?B@^_>&b_7k|J(s>h=GQ>OMN`Z($4mhUaJ?EAi#(m=L!B3{ zXPy0|Ov5v8j>mI`=>|HKMzfWv1xh8-xL(0|cUH>Uf0e~`^1Nff+%7;?%%$(*5 zQ_sghan*w2T1qDb*f#{j$$)cW{hsfEdBygz?*yQW;pbXYp|Q4 z70onB{5!}!Ak?+GmYu9YCqj#cOz^rO?L&jH_tXX8^>d_CgOeb4I?xge6qhkf4HD;M zy9oM5@+T=bX^U08VJe?2w{A63k1y@GIVLcbL)Ri-xAbIbv5&W~>sllSK}e=PB5G+W zG}hS9QF&wd*djG{IE9_aVh=|Oi$X!O>X&b@tG&p*T=q;bw!>yH<&3mG@WVXVh5@$q zQT*AV{yPkOVK^x50(7hZNbOBBam=H{kBP`e@0w zl!b7H83c92f`aDNwF!!g->46w9DL{?PZCHj()g8$kl^xlP7OR;Z3siAYVE6NlYLur zm`eAXWYyr9UPkL|dTT$eb+WAQaT&)ahy3(ERiD19>;~A?sfm0W^)7uwYH_*4@WV0$ zE^gNfkxK1fND4ilxO_9r*oOvOadP;`dfkmt**gNhGH)Gt0H)`G^L?mOwHl$&O5f*E z+{QP`9gy-D5Oy7s_qsG)DWRuS2ZSv<4%W+waw2VzS#k_zRQswT@{V zhN#v;ti31Hq3cZi(<9^wr=tzn{GgiO!G$!iBZ>0eo^olQ`Z>&I@Vd=#z2I)_?QxL! zj05;Q3CL0#(yNdM(Gn@muzLy0pB_-rP3tSLYMpRT?#FQuD*F0Rv@r$MKJcYq2-RN& z-mmgRr2AE;wrPJi4fzHP^X3blME|a)A@{|M>`wSOe{zvl zrjQHF8K!&W0m+FpGw?kNwGX?-@0#+p(Pr}kKZL9&$)DpE7C_`K*4mAPKKn~w!d1RT<~`u`x=u?evS+XRL8<|RYLd?_B#3(t0at$51S{QZR=8Kx z;1e!+<#6xX6&K3SdG+)C62qsV!yJUkZg)sHl+g^$4Tb)TzR?miWyVi5!y~MsoMF}_ zbvQ^?XNN?2$*pevY;~82@bjcR8C;EdEZ z3Yh61d=_%!!o_W_n*ne#2@>Jo(FB*L!R0eQ`q_SiQfTsLDe?%1#GE0k(NTAu2xv!7 zbDBWyA3UZ19r(+<@rI{^b9~D^7mydD<#~sY@2sbQ^gJg~85V^*J1E-YE2^D#^1&Zt z`}7nb!eDJ{wGvxn7{*L>@Rs^_%|=s86vzRHQFv`E8_JZ%a3!f zS?@^>{O5wY;wc<=vSqqLpPML73(^B=j{4%x6Mi&4{zSeZ1+LSbvyTFz;fSqu3$k|Xx1^Di@x^O;@33d8Sej57x^3# z`PGs3_EB)f3OkJ+D>hSmercg{soOY+P6xA_912kd@PA_GH|mtargWO9f7tOTby<+T z9S;oAfSIGD4(^!OP`Q#!%CWvMzQ#8fKfPJ<{!}r>^U5c(aP_86uiH)P%^bcCm1lvb zzD;ZQB=J!|y#WH}2-25>P^PcZ*^~D1hd}|R<@*buElTi()cu>of@5D>Zchji>9HU- zJe;6>ZL0sXvnb$Qa!6`l+4XI!k57HCtaaJ216mGPF9W+-7^a~dEbH3=u6D9^xPjrM zzh7;6MDPV_!cW5o7PW1Y)e6b;pwW}jgUD0Tpev{HLEqk7>&?4jWD5+92M6yvVSY9CX2A= zx5})LbkrmcM)*CJFOL6+YVAoZg@e*qUghJygboSF`h&kz`$WtGug?Q-4TH)ifX?)J zR~qp4WkbFs+iQjeFek6~0bfhyTD#YuB6%1S|K9cDIHv9%M}~4dR;5W)ahMK`I`Dk346|WTw2{bVu|U7_7j~v%dZ|Vp(_#b{z--Y_5Iml|3JIj zXV&|_P3N-d!iT5AV5zch{N@ywtSIn~B|PJo3EhE5oy1#|$1a!ZpR zhhq1}CQN0B9+s+lEyOQNX~lK)WQc`S%cb?I37D-ZTMEb`@^zdX+aphKp5`hY3p6Kg zV+h-4+2hxp1?#ARG*o8>?;{qI;Yi?TA_@JimY*=bj(K zlXo8hw3xH`1{PsSRAUz3ak#O;fr->KsoJ{G@su8j>QrC@;y1%40Q0R8zFT>O8tmmf z3kJ?VPiG;Xja%n}eHA4 z(xVx)58rDtkY1T;eabC#GDl4@B` zT^BUMDPI>omlZnSG&XICaXZgzX?t2UZ(c>sJl_e$s*&g9kOtI9v$a?}p_W3Yk=f6f zA^frqh&$hqxfj$!;DwyE%}AUJnh1A5JW@~?Mm#l@F}?>&f7)bfABmt@v$jz2y&_vw zGoo)&MVx7r*0t5Z#s}BduIltug>$o3A`HVurjbT34n3mJ9(|@z?T*im=lI+EHu2zo z4*}t3FP_!$EU2H5p@<3{z-)|c^(L22s^-Z_X5EmD7j}q5=8*CBjNO%S>K5d{OvU@X zKV9>dlnl^jKMiM`X0J5?EY`AnFotnpvK<=-LOpvG;Qx1e9CXm7<{dX{D3)(`Qh%1n zFP(%adcdR6-Nw*Q)!fJzCPN?NyZ$XR^yb0X<)xd&Z6cbQ zQWanAz_e{BHkG>2O1O?eMah{2G&g9zi;RaApvutcCP8l@ zE_xIc;UK*V7p@rhb>f3h%4vt9g@Q&xfWljV;uSbil)kc6>CQKEuA@dx)Xh=u5Nzhh zx`{BOc_`Q(XqzDxd2bz=NFaDY3Kr8^FZrJL%?2dPYO-=ZbMoWwrc)GxsyQroMy?Lh zf$CUE!b}WV=$dx&-s~H0B)R(95jLd&A7rpyojAH=QuT+q#qR%a*5{Vevtj0OS0elO zr=VZIPW{y7JoC%iZ3Hzoa%Q&rv}s9c(y?=8xkY23KAU|io%93|^CrbLwOF9HpR%Dl z7wp!Qd*vAmSiW1*JVfZZ=qp;C4js(B{`(ag!7F2W;aNXtZq#unq;AR~*hHBWvImiikkSbE(1GA!&ku5&m3deAw zAGR_4Pz$^bpr1f0H?H;Z-#$ab;xVGt3Fv1}Ie&NEAEfi#(lpKBxIh&c7_tL@=u-Ph zJuy*RmJr0Hy*@<-asw-bQh}MesPgFfloZ0I>v?@gxmgMjgWp4IS!$TlaT;U3q+DK&1Y>mgXr>f)Q7Nc!g*S7DO=jvx%B7eO z>49|m>%p;mN-+O%voub|moujZd9Z5FX+)jz}kE zdBF$&&J)=WG#J@ooc;oe3^w~4H1HcV4|I(!y4QrB5Ws#~quY(8^gs6ZI~+lh>T<#k zhjR*<-*mp^^9mNRB#T%mU+nMaLeyhKl~kbIg+UIhxHxUoRJGD#bBL^=H-K@)z z-d}ONt$Cr+cW%8@tKjsNt9`kvpr-e@Y7dBPWC@UscT4lq&`KxBXWQX~LFb8K`qj}= zqOXS7jZF0}6Ko zEL6<#nSD9C(g07=EV*iqe|-7MwSpwsXQ}0C?zs;r0-v@IuReO#F`DEJS^qSpDMbZ`0;xSO3ZPG+$TH_>Rj#E$V!*{32*UUTYU>?=9JX79NmaHw7js ztZos&0lB73;W5QNgYbgl*T?V8{<(k5&9WCWMy$e<+Bo?KrG#pt+v#EEEY*MPGA)op z$3TQetuk+_5sTEPgHu+xMA;aw$~-jMM?!&xjWGjg4ikAp&b|DCj8rSjwUqn!qIm4T z_K!kZ6g^3xFHdqh?Mn?vpI(wyec#o;CtL5X_XgBwI$PMkcgO<~KlPs6ketxYa^JBR)$b zI#DBtOVd276VJ71PBDUKt%weM$Q2#vI5X!eFxUZEf2(6O)M8r#)%Ml!fJx(pphd0~ zN6br5ldp-m>O$jqLvsh{Pe+9ND)eW*^lSS{lTa~7YA1dwo!^Tqi)E8&+;Cd%u=ft={vzmFNDp~n`2JeX zt>3iXF0&ul(pYuCK33=ph9=!jjql*z#UygCmZGU6L5{p{hpLp1Wb20wu4GjGEFI7m zBEJX%{0K{2(M|knpJ>T4Enfmq*4HJ z+VM{Fn>_>`8#PIZjDgKH+B^QR;S=ZZXuDAVSC^PX8-v!EmZ+Rk%=AvtZygB70u+iLa z4#Ri9U?`V=?G;VXR4L(AemS&>$JD4*+A|6;~~`dc+?M9)L}_tp>OG~y1~a1>ufT4Cq8@9gZrJ& zRI)U83@i8bu(H>`0k31LlxSQ#=M!P4CBikTuHtnbYL@3yMr$3IvVD?};z*#Dd+K~F zFoR0e`3*EK(a74NoUkJ^gYsuaka``+LaIy=q^@>{zYzk<;Lki8YBbpam2niW!KkP5;&?Yn0HiND7a+pop*_xl`dE^<`#bxb6_qa?#SX*#McrNQ z9*z>56aARvB{cVK6SPp^AV$FKZ{m+2sz;$EaU-*+f~Nf@)snQ*^R?WGA?=v0foiv@ zld7(4bg?j0rFbM)Hg7-+Wzr@rsH@8-W05GIs@%o20OosAjG6>$`M8L#(?(PsEr%k< z9i#WVkL)%?CuwT0IiPr@wDD>w{Hk>E27j5ZdZT$d;f1snZzatK)JD^7Vu0`LL(P7r zw`MZD-Yt7CXTlRJjVOdT~Z zXL=Cnoby^wz*^TvN;oFz(NTe``q<1!s#HAZn*+9KtiXd+PMtlrGi(&|{c**9piPOu z5}oqdEz6SSWdA6kP4$!rqpuG*7LJhh-`PtncfZc$W_`>poTpM)Dwk%%<8?phXk++K z{BXkM$pmp%C1JjO z6<3s-hgxX;1_n%v8hM@)t(BTQviPM0G@%V3b3(mpH>Xx*cY88SHq%}tOrmFRG}zW}%Q@#M%n z<9GW2xjs#a@Tu!eVf5%0dAmR#S}~+u@?<5HO#xD@*g~nadBA;|>r)3GQ5RxPUFxqW zPsJ6@VFkP$K>8y_kHRubG%9BD#yV;gD@YHsGGKS!@ms~*nQ~JfVt|b>Nk#eUi>!LN zZ#R5px4kPFmygn#LSZ;{%G>^y{CLhOQqt2VH9s|hf#%zRyW_TJDOET4EO!Lxzl!_| z=sN`>mj(bOd78@mWXlgjZ{fK)ew*8ck_jjEM_!)8pqw9mCBmL7m^p_9>9?!(UgTFv z*b6r9Br~Nms)t{5GVIsWV|d~QRpMlGK2hO2o!nXO20Sr?RZ!mJnBx4XDIs6^PdyEy zF{?`SET*gv+sp98P_AOGZ&vhDV0Sa$0=&b@b(-%6#o__6yuyOSa60CH_;xjQh!v!- zCf3d;R%Z@%8^~`BO>5iM%%=oGYx zATyy3<)xCaRklwMp17M$kM1WqTHW=Cn2Wz)lVIw)z?q!%IcbU8pW?jZMPsAfzE55# zIhtx@x6Dbls4gnKJNxkNF&Ti_Xo^0WaE3SM)flU;;JBPb=KiaS{4v;4YQGoBR>{X) z((xGpy~J8>&=={z+7XJ8PkB)FIUAvduY<4E($t=yf$LI03f0w3|( zAh9|nm`M;6oUCXW4jaOxP_5QFO!t9i{o#Gd7>zo%hce~g*ve-h7Yerzf3$jZ-wQn8 zQ}YA%OarY@-P+w0i}p785qaVaK#nf^dZG7pz2n;v2^&SgrI1$%nq*Dokv)B$L%JC} zJSXwuWc-y+^PI`wUVxIGE%+R5V!4xj%)chuUVf$oRt}g`x$JN})%YXUA7W8*GqZa3 z)!ekS`BRYmI|%P7%g+ic_Vv8&%C5HNj)Lpd&sx#DYw5ui^<;V1yiT{5^2}fzHUw86 z^kqhns34d52%=ae?CqhI;yMark>`q4ZS}CwX=U{A6m(F{d>dp-=pNhOS+d# zhav5qhf-5U#w%-EtQ0dAg3XPN)RLJ5UC$+j4g!r2vn$|lJqpth{BAL^ohc%^D=Q?g zl5!p(0})XR1x)a>Ns5~bFL1|P6wde_vSNVQFLPL^C`pt5>gDs*s|hr9*J0`|D5^DS zrg44xZup8#+iNaqk`}`ocG1%#rXGpNNckF8*`F2WMNe zT76Ze=Z76492yhG->ts9q5pUQG(970R$_vcmo<;J5aeLm!h!yDyedAaESU|>VFxvivaVo6tcbh8g z2!<7$R{ylop>dKv8bloJ3@>*zDtp`uKNtwe2%7iqj{JVHhByt17ss&%DFladIwt(Q+@D%G6- z!zYtajP)8gWOuA{YDS+)2STVVTa~Ap(ZI*c5iSe${{dvC@=>JQ1`ocD?ID~0FN*S$ zNk_<^t>bRKTHm%DbNS0~2DAGQf6cRC|SYI##yH1PyDTa}>{h20F8CjDq(HIy0n74|>!Be`#rv@s0Bj}{4T7bz* zz3fQCTZjY?se#0>9wvyqbZ zNOz@SkeN%+5+%^BJK?-2!ai(5*unZ>LO9q-eHw8KcgX{tc{q_OMGaaolTZhky$p*# zI+&7=k6W0QtD@DwA}e*-VUo+$eh`J*RKL5iNkYb{m>=mQmWn&b@Ke#k+{dt?7tx74 zM*RB6*fCx!1GRCaM_kz0UuwjZ)@t|H$CGV+Bfe3U1i5v&_M_^@11)v`y_DK&K>I7) z(EZ9TU3xyxUp51tU@8+lSTw;D9Ut&D?XYRh<<0kuXANlga7swB@J{WJ;aBNDToBh> zPDnX-^BqM{B67!f%pQ*nkn`wfOk1fr2ah+p#{n#tU&e!LIcSb*0Rp$Xr*^NY-s?N_ zp42bo8?4gTJss@z-~KpzlMX0(QcS)6w}ao^3)4VhIkm6_0q;mPLc8??47}yq8>7ZN_na1^c{mZS*lp$<;+F{G89!(7oM)5z_$QZXs-)FOH%q4 zrXNT(J{OO?O}##*_#X5!U9JYP0Q<9%JHnj2TQJIVQ)um$5%brFM@Ikt{&SH;13S2W z1(}>~M}eZe)hccK{Jfa$q;V-+2iiGa@j~vAi2?)wJyEXkmmZlQq6uj)PORcrqfH3Z zs5-4F6%IF7a$q|Rs7M)8HxaV1=&j3h4(4`FP$P?n=CKdbr^B*2((7f%1)58Uf?;d< zZWq;b9&yVNwFam#bkzb1)pN6 zrjk|hn8QxCI0g0WJU6T`%^E(?qu!U!iRtIFD2Pv5n5V;>Nyf-NQj#Ef7+MwfMx>5G z(IyRZ24WKt+cDr3QaE2)$rxHGH!aC?GjV;P2$OZ)aucJ9tU?J6knm@W;sA(BALe*u zw<9EOE)SW^GX4PGTX}#WBWj|@B?*!+SBSA_!wC`gcJu07cyHJ3<&TDs?bA&PYTze= zaje@gjD!H_x1)e4V+t&)?UGkx)19zWZ&IC(Wj)g4DR}O@RH8N7oUm9aB4Sad)raL6 z8UUc2T}l^}6QET2Jt6na`cZ~-s`fC{?wO{e{;U%w&p5+Pvn9i0iJb0nu&8=7Y~dWI zHnz94y--OFL1VIvX18|cm~-eb*oH3p!noe^ zeorvW`2O9M4@5+w5B!wdL|;Uj2MEcSW^2d9gXJ@y9K~Wor}# zr8h9=BXi^cwsd+bT}`F=t@wyjK1$yyJfN0?`1G_~{l1?Pb-_|VGyvm{Xc738^+jdN z>Rc|2O=)BYbYmGk?p5HPe$IC{=F^gZ^p(Aa7@CQo(;bKygkwFW{wDP^u%`^-I)$ZT;TgFjMc23_oQYz z7RJgH7$nF*v@)$(67|%D@v0`>;{-+Lc^|eCg;;k))y-j@Gg^=B(CeTY!d{~nHS&?n z`nWPPdH%b5fna!Pa6Mef{`}kSteau}6pibQYQ7#wW`gyOHG1mSlTZ%Nm65>o4da?y z!_XSFQIVz%uslh!)hV7$EVUQ%+8zxHMy6&Xm~T?KvrlaHd`}+w->i8{og&;Qd~(SB z0g6L$(rfnNis1Y1``zes?_yeSXty7~(|Ght@WW&**gk!-Cgt=^p(7<{Z4aH|R6Ug( zHw7o(=VlZ>_z!Mx+0fdqC|hzK-am}+a>%^xE5DTLajzMR9%UiM7h-*D8E@e#&N6ZR z6Y$*<@ze@{JfH9a0g7F>u=;NNUjoAQ2%wBgzq4%IHt*7!wNy>3eATz^A`NrV1X*>= zS+9E413`_g7Iqs;w!*_U1?gf5X&YGyEd{LnLZ^g3ZY=z&5$ z1SlGr@<7P*7u94`w@Un#80%L8+$Z&KD>i6*XVGc~IbsDNB9R~+ZPsx82 z!0VFHFU|KUjMFy8&<7L3Q;y-Kcz#qCN5I&k=kO+L-mVWTzixv4nPJNfnl&ew)iT>= zD~Z<{K@MK8^mO8nN^;+sbCOO6PZY0;r(?H@K`=J;y!F-Q%5_STqff!w;F4PtszEbb zSqM*f10Y1XpNhA!IYwA7o&3EZTe0|MpEUuhpTrHyT_00Ac3Q4CA+OHWH38X0!y`t@ zPY3f!k;qSu6VP#dSqx^m?EW*))m5F!k+fFp$CVrkL5tVMIM}!ZF11yoZl_?njg_`c z#P_PrZc3Z0zcviv42F`=r{xR_Z$4x(e$YqmAA2STH=cdz?1h}n%*>ODral3lmtC3I z;evkFb&!(G5{}2$oZ%7*H7!s|K=~#()==IH6>Q^NZInFhO1Mba?21+!tAi}ZkI*V< z%Q&ci98#)HvbMEaW=-7EBBsDKq`=8KeQg6>K`jP6^s%LIotw%vmRu6gWc87q;KwDr zA4*TQPp-X;FK}fIL{##}}eM$_3uX{+#ewum3LP~PY0xCM4`O0OpwGoC6%AU}*6 zK|gyY*F-+Y)PqL~k)lvVCr{$nRumgzCJ8rI@+mTO^)zS7hJxh+-rR>qqd2a#KA}dYnig=gRHoX;UKPP6 z_&3X43FP5~@MIL&VQ7tI3LUP0F`g$)P4cIp;8^ zl}hE{03X(~qOp@c>lu=C@{P#4(4ywj+w%YR+4O>@N^?hkiw!@R;!_A>|87qGG*>i( z;qfZu&!R3$9J0!IjuWPaR4`n3f8D;}xA6sH?tqr#H3cRSnb*`jcZ zt|1Q**Aavgx$2j2HsmSp2OfL_AdAVFZF^Y&0ECpLo>VrA1~Q67NU3#9_Gy~H13Fpf zF!5@Q{D^Gph#{xp`B4@m*&?0YFLySwZ=s@HHeK2*{HR1wB^dlSc>iPS3HVGzm++;6 zVPH=ovWOdeg+&ryAW0w0>o%8P+Vh6a2|>U%(HBLl(@tSGc*mEl@U)tba~7*M)rdqe z+W*cK8un-ei>Ot_1l^RuEV|oQnQy4{I;k-d*ko;AeJ3clLv3$hN?A;K5%`9Fv^|$> zPg1sH>~KNJlQ#1#fm8~g^t(VYz6g8#r|yJYbJou&t1l;WFd=+0t@%%IBhnWESE-Bg zCm3BS$2&vv<2I|AQb>Bp(})sIg;4nu-f_y|D@6ieR7q)%+0eeHZXU!%{f|mU?dQp* zex4%nuyxG-Fkn!le2=)yW(yjmRv>szN>$r3f<*peO}>=5Oj60?kM`q_8|L*M&d1bH1~EG(p82-jD-I(G%UmAVtkw+b0nO_@WkXUN*xY+CY?LP$=|Qbe6Z*IK3t_Z zcH}*oM=4}$PoRTW;^5YyN!W!^#UQrWrlRXp+sun+%)&WK2U;7_Tc;ip$)0$?)uRdb z@BX`$m;OMZJC%4*p%+BW;zL;(6e}NBbCV;$rB29+$6rxv74l#|vtSPe} z*Svy1nsiz}bg;W`ttQzm@X%@U$^`+wz%K1OSAw!eFz|d7;9zPg?+2X&`Oo9gnWv#I zJ+c@cPmU(OY=Qe55=0mg{792c zO9VEvA6?J}@w9BdOxrr!Vz45<&n+SIA-7TPT1_Xu+CG6`J?sh#=WDa(-&!qa(tfk+ueLk8Fh7&Yq^j z*MK zetixGjwAQfm~_jlYkUL=V9I?kd)S!g0G55AX_l>iw!g0^a^G8T=x3bZK(*>Qqv%mL zerj}PX3A2YRd2&IT-eKKq;F+QewI@&Z06d95&bl{40PJ{lRB|rqDEcE2zk9AayV3x zRalo*QQJ$n>67s%r6w`av(J)9V;1(A_JWe1)D^;S&h_1yI|@$JR9lL!9&^e1*H_&q zf*tx{Hcw8pt#uegC~vH5p;s=C`n=P`VkQaQk`vER-aWZvg&ch5KBi`4O_`57BM$go z>klZSRT=$E$1h_M5E;t;v4Cf3mF}6Ra&;q*3G%sZ=4TUAQ41NvpJYo<>5rKiOgNis zQ;Xt&v&vZ-4-mpuom)b-Jz*>Wy`*gp4S+NTn9Ic9A9l?>Y$Caj3GOfQ^-;eYy0=ZG zgH8unl7yaX(rsP>-_@nrv3#f(d!nNKI4*5T)w(S+<672pT`ZgpYyCI#4_TGbcXE-S zaN{PZ$yGB6;frvGaNEq|m0uO)IXj0sF*PiKF3OyYrRm_wG}Z%9=05Oe~Ven z{FFEmX&u}=simhcDOU93JP(RC^V6*{?976zr#Ks5Q1X2JUw?DuG~s`uEi?bud1%keMy$=&Ly z=ksObXR-6oZ{KC{NMEgckaDxh23w$OT3%44zC)tdWsT_@y4T(i#l`>nTF+IYb@@fB zn$-B*h(_p>ikL)Mn|k>|C7BvR8gIRIDavak(t=;wx&%!OKiuJ^+2t5M$Xwk;ph(*G z)#1cccuV--Ll9EGAjrPfELYZfpdi?>(XQIGP`~ivNj0_O!ty|r;-m2Amf{M`t!aKm zhx7O|08n~iwJl9Q3P9Q8Zz;<`j{||2Wht|4RPaE-^nAThsgk{=Q}9BaX6P&H-0+5K z1jPm$*fH|XvQWmo6|=kWf9R?o$w*$~g0=YR=>3&d|3L04gSgN)odJq2DjxTuzb|OT zx!m;{CjaH@jr-Mpt|ysTtP)a!^%<)3e`Lt{NA=@uG5aMICD%5e2Ty+1)LZF>dfy9L z-@BYq^yOvT{@Qj|ic!c4X|Ktj6Eo3Qo2fp9qe5k;_5mF8gH0pp%CaxX9LmX4HBfBl z20cw%U$d4=!`z8YUFS)OF;}{5^Hz?9`maPjqPj1TkEl6qpZ|!(jk%labY%H1-|Fl7lnQQ1|DZ^*YvN~@nqG2zci?0n0$+di?n+Qu@fva^XJ)9zIU|Si+Y0CPe zn=mCh%A{xcaUUDZV4FV5E%l?sgy+l=)|f{>_HB}Y+g0DY#qN>#_CcR(ZtViTaUGvs zPO6>buIC=Uy(09b=8ufNZ$aV@!2{}=%=5R&ACihUp3T%h^vtB0+Paq1gh3=Z{Vp^*$_biuyH6aBa7j9Ze(4leB#-BC^*64OA63*CTY%OWVbN!Jp& zGmQC(fJNy-C$U|&{A{&fx%H06sBl|7=L3IbXZ>86svCWoZri27?W^16VYe6V*i+%- zfp~N1fRdf(L86TbiM38n+K826d*2%%EtB(SX-kU8G_RAgVwBX3TOyK2x#S6TfNFE8 zcVrIB{u4Wwf^HOvQ`Sk8o~ciZp3644xG2RFmNlg;sDG19#pCd%%w3l~O7nQJd!Eb> zeV@#C*(IM)*Uz2~Zd-fTcP?r@smOat5!~nDv)+3zG_2Z$$J2G3XZ?(i1~NyV5OqCM zj*n8zsb=|YBwe9i@X{HL2ED_oci)UNNuO`5><9bFPbw$r6&!3 z>dWvsW93(QO8m&Xyv8hQ(gL*b_Seim2T#xa`{kZP<%-#eZwJKdQ&1pLy}m{ zVOZh9NYDTcC_81NWhcZC2h`~>_p`VuT_BY$4aFl!O5^~RC%i%Cw(s#{!Fl|%uGHM| z565Jo(J8-36_?5#Pj>eT{)w>ch}-T|+sJ_x0p(0a`Ky;`&)Cqyn?Jg$BHz5>zFsmq zFcFG+^-Cq%I~2}O$4V+Au0pJ+h&nLyYm%1r*BGgbiK0uiCe0_h=xD{#VOYK-6Wm$?`g>Gt<@GtQ_`%^jhadLYAtz<9L?NOiuo_nw zHNsB|O;RMiNwZa&Mn)JXDVz#}UH*-?iyI-BvuM=jSmUJ%TnQo!7WSx`RKof4tw&{a zpxNWDWUry;4c2U`5`g)f4$0+HOjGuka23IO*r2xL(NjvR zqvGa?slPV`A3@HVm5<(eE7YiKEnV4q!I|_r^-feP-_FM$si)c6E@>rhAqF{P?y4Ys zp&ppqfm<<2LKE<0pyd3@(grhGN6EP|GuR$2n_H5NA)oXaX;QeOxij@ZnP$cX?`O~X zoZ*{@4h;M3&C;_y?S*ZZ#~qB|k_~55H<3xGB(KR$Sm4=jr3@z`&>zrPwiE1McCpg?-N|pnK1LseyKH^hl1*1qHg2z3X0?lHSiYkzkRs3(o721XO>{kV zCcCx8=F|l#(SQ40Ij!=aP}3xH#YjnGOU$baOTE?H!5EIB;L#KU1#3MrOhEc(nwn!Q zi6kVSSDM4x!o-2{zV!>PU3|iVWfnuT@E?ltAf-D2X!7n;Z1N<;Z2N7dNON)X9-r zQOvXE%wTNRN`#8!mS@2In}Y`i!>~-LVJosuRBmswvM9UiNAd513cv+ z4us9b#6tc{9r-vT6d~)!tM=7gLIuw!mIdU?P6eKGt$`u}7vucrCMmw+m)xEX-2AhW zqGM_gyUaw?AX}r8XaSB>_nFl(-@Q2yFG<1$;*k(xU{ z9b=z49xC>5I=^D8Cgpz=op)4{eH+IWQ2`eYa4%E@_g=XG_ry(RhBIfmGqWDW37T7T zq=F;&OwG#5y|Qvu>eE0|v#n-kYCJFRzxRLlIrsVf&V5~<@8=uG^MgG(ab2AJvCcfF{hy;IFZ;C(%O)9>{`MmPU@RS~}9|co@74L$wpR+if za~9$eO4sNi{3kZzcFHO!c1j?22fu7(F#PyUE;^<)^P<5LiOQ<7OTuMO!eCN z=Fi>HYjfLr$pnutkdHOq6;p;!2)AQN{Svc&A7iS2BwIa_*nK9LT=(y~(+8u+Ws+95r| zBHaQ7CQ5ySWLk5Tv2c~qr!5$H<`#{$Va&U7JO0wTK19i2CE#Wp%}eO{nR0fKlpql; z2)%EI^S^KJTR~@07b&f5A{3fYNxg`{EIG!~pf~8;rrh%ozvt5mW(UpgzG?0(t*8da_DKL^34y_+?#2+rNwT$-dry;jl6a^Oa@!MG2u#g=SL)rDWS5e|C~$ zRWRj{Cq_K!zVrP~%E#gDN$4cgTf$8TbGN2&8RK*&bAVe`+)TS4U_3t)Wag`&pIC1? zkYN%s5*s$MujKrm(ViwEGX)xPpbyQ}k)VX>Y|b1%<2sO`h?9v`7UV-j)aNmH^HY&u z)9(Akhl5;@H(OUWEV;SK;1a6NI}RPSh6Os*RU<6|4k*qZ=AjcIQgSC$N_yXthlO`;lC6p*vy6!AG_UC!)+T+tvx5}*F>L0rGdMBdnU~VjXobm!e8j= zJg+6zGhUGRF*PZe{XMB~6N%V>EioSMPMM5n-rc$Q9S6zvuO@MR zaaNz-4c6D|IUk@tK267~^e@yc3dT%N4?YJOMooB&@v6nIQxQ%Z#HRQVzK8gU1QzBp zaMPUo;0j|7lS$PPdX|W4C~Rlpe#No)ibb0jYq3l(y7NPpchPU2o-SjhX$O|qV$kH{ z#w~u!!{lWJup?3qKP~-qth&-Ay#2(zXAG z4H4Pput5Ifl#kC_6c~-8h8*HIK6sT`Ef{I(VGLZZb}GmNv_@@lFv6>A7U*` zS?5?q88&2aO3oUoSRW*D9b`wTTnneCu&$SVFf6HuueqMt+2KJ}X$aiHDGBFyjhsB^if$gX%42|X)a?caa6mepk58 zP+1DNeVD6{4zZa}e63dc!!;26cZhPvfSpV7%i|ZJW|{m3 zGzkkguT;H|j06-3Ex-2z<~<^R!Y5=*gVHxr%hJ_+U19#C$>vM^uBqRgbnyPU{78%@ z6~enn=NV7XGQwLtX3@6ubQA2D|IY6_Nd-aG_jZR5=Y<%KenC<60F#J`{g`fL#fuky zdx+<6JvIK312{Y|hdga<6wL`Rc!zp`%6lMD#(NZO78vj$v+xC=rO$yY(Jt*xH_HVj z1s+v->=SC>7|bG}UAD;XTr4jeSI}hNq?`fv_M!b+9MHNZFy#90E3u{0cQ6jg!BC+c z*t-oCA6f7#tfCcnGe3~wfeVNMtj-H6&W~W z^t52~sT(298~}u@+&u61;@l3)#{35k6Gi4pTz?!#8Fh7j^p$f@=YZ5k8O#+im>O{J z5~-Yi=ALDS&hzli;G@Wx2e4fM31xeZna|Q+h%w|ZQB!i&mF%1^=#3y?GlVTqx?c#|I<`6pCwK7E;C6Bf()7i}ArmvEIH{->SxY1YxSGyRr8rNku;jk_<9pNh+ z4Y5y&7&?0#&nJjlBi8e~8^*Bc9oS;KAOe{a5u1lV3i33BO={6(Q}bXwcb@2IWyfE= zCCjhN?k8k}5&BAjGFM(8S+xR=N`?%p=d`@;_`0vkdLGrui!f@qU zaZc~{W)-l07bgL<=YHYJQ!fL>+N&9bk}LO9aCz`^E9h5_;FXr_r zwbMrSYmKer?H0kWn~qLaReG7o3G1)~{Q)z7e2oy>1x**9K^LXIh5#F``4vo;Ocqny zj<4sYP(fB(3ArpD5%p%ASy6!#jvpW90tOCv^$R#f#ZT`4>`NoWWq5PI%u1)JpVOkm zUa|j9;S0g3D<9v)Sk`|;rtAOmC2_yed$|DI;HmCf?BrJD2$G>xUcp z3lNhhZ67UPMN321p}ZIq0wvI1=Q3k2s2k0P1ZTfWBUzaHdNScFtMsmaMBueM zH`5utKa$iUWlOH}aQNSTx_UId#-*oMJ1xVk!pUQ!@KI3vWj4=@74e3j>AZs%rUVW) zd=5&2=$CSgYfxUJKi8cuZosd3z)SlhF8UiLo*yS(Nz8I1DK<#PafyYxiK=Gm1s18~ z5Z};?O2UE`%n>4E;l6vY9wUAkfwmKtrpx~>8$SN9H>KPw`}!;8zv%{R)_K80z?OJ+ z5Ph?&veHIvTHR@*3NY3RY?Pb(bbI`e8&Xsa#tDzy~ZmN*L%so!-6rG>|^ysE#g;QhID-&oOLbCC-7)Za0gR~7yMl4M-r zt~M7+FUbD73GHyr%*rfb(FOuC@t&(Zi!!$7GOJHvUz~!`Ruk7c{~ABulYDaH)X%|c zL}6zLm*2-&Lr(dBoY&PF=|GJfAhF#aL|{HVGhMQv^R(A(^eOi}7OvbMcP(B`ZIB!Oo8WGyx>#Lf^LT)m zpV{?W{pIGP$wJ~cy>W6NYMiY>8_nPrH%bO+){T>el)Zc1`T=kjwT=Ui9i+NHe zaR)1lxG%3d{D+dh#hiY*)$RQ_ljo;pZn-+K!tf&Fw&-2;xk}rM1IcI0yUvfMyev93 zDDOP~AnsRP$ z&Mq=Fs%l}S<&i~=wt`BIb9l`$D@xU$uy?~Q#hDOKozi1=`GdmX2aV0_2 zrip31rXas`0jCwBS$#uXHY!a7L6NRW+=rm52R9(Hh+|BhvT^)Iv68ik*0NlSJUba# zjw0E*R|NWl^T`KZV6opVn$qI_E(=yk!9f@)VNZ9L4EU-aCR4=UxX?>9evXwrCRKEV z)9;Ze6Y(2bxnr-||5YG2@Ci3tZqP7`wpd7Qp=VRbcw)ku#^|u&ocb{6E?3pV<;5Je z!P5I&lK1AZIjWD@Iq&da-Sy)nCa$ouOC?|RwvP2QmF0lndERJ|co}n_y~I0(brMEQ zri}|W}VHi7um_T92D9;&eLI^mj1_PA{#-L*Ru7% zwDM1gUb?+kBNT4%CNs%PWnmnK_oR)(?1)o9Q3qqqNf8>h=Z#d#-Uw$@Q5h2prNG5< zH8icanPB&g$%~=&pUB#^(F}>z@K*LEuDTH+L2lJYy8>v{`JL}`Bd8zOUgc7!*z)N5 zq}cK$8}Jefm}Mw${CJ$rCQk*i<*9Rmit0A=^JyNV_`ppjKM${O@4?K3YC~quD2t*)vW632k0s*_HAY?bq_VUe-wO7>m_(Qda9*BaC(L~2imvhy ze3jDhfj`wWECshq*C3xZq!Mz<0j7zdXCZd6mCNb3H#-Y&dX{XQ!yTlP2{g!+_)hY6 z47*GSK!|pGL$I~m>yb<<*ue*ZK0_LpR$1?oc9g9M?ami{E5rV9=9|jhumE_Cdxn~O zDtM*EwRG^6f(Ia&!57yY;%B`2M0;WMhW5kS@EuOE=LMPCabfcE?-if?;rWcutm9F9 zwrqCJSXDSvR6(*eSj%*c##VGI^}?iVjoHos2im zx7tj|QT9Q}p$LIOd^+-&1!hTL3Tl~|9~IWgC#+w1hP2oSqgv@ID|VjY;T~)B4fb!@ ztm=3awz(jn*D%Glq%Uf@B3I)vu46`+WcNN~J6(GzJ-8vhx8hVKz;*_zBw{NkU0HVc z$mbxFmoZ8ki$YcEGL=1s*9xD%rp{|>+3;}*wbP+_vl&VR71fIiU&UG>(ml|1lc_WH z-Rait`cMqSCDHTjkDT|XpY_}S?s7mM>O!2mN1ZrzuH-OIY2r4hW(J5bV8D^Bf3 zv`c8rQkA@DlO^Tg`WM0dXLv!;W3Zf7gqB)l+4d7g|DnG7E4FBdvMk5FXv4(&IMExQ z=anq;AHs&P!bRR0vduiIThFkdEx0s#y6KU{{zuX08X4Nu^|q65cWeLS4v8oY5LaZ3 zNT7NDsyYwFcOnrMij~cs)CO&V{3w6<4N>rl}+u}S7aZ&U16K`Pgu(M;DW4bE;iAUXuAqr$bT z(AO@8SLXJF;=~!6JSh(hb4$lcIL`n%3=_-QE)YcBy9+6Hy?vu9Z~ZZ9AvCZZRX=G> z1E?{)YU5v#|KuN!$>Z|W%v80(5x%_Lf`fqhRiO!GNOXv6ZaA`D+d`4R3KD3sKhJ$< zgWvzaYsCama}YPH00<^eGIp$suBYAJ;;vQc7E^_}<*2?M(7dm~Y7~&jAW2oEd2c~8 zc{?2E{GV@%=z=L)N*RaMcCm{gKfw1oz{}ww;ZLx=XczM5+LGE}uI-Jwu&bcoQYnwk zA2;-tejdmXzDgr2TY9^~1c`4hA{oC&?QrF;SXVO=2aXk7Wm9%RNE z4N}dc_Y1Eun3Ur=Bwa*>b@8H*dc5Sc}Rd_5zjQKC|> z*Vl0;97g?*t5A8jI-voqx?)MD64>raPYbF1j5oGHun+9BUyg-4)v>=X)Lh#G5?I*% z1hr(x6a+mI9>Wvp#o`ySJ{d7)B!p;GuV@LY?VUo?7*|oRqwD?Mfg^OT2@TT>3)7o4 zuHZ#)tu67nAYcY2VI6t?++xtau%w58yT69XN-Fy~D*p0U5}F-{KtY2lh9F_!5d`&Sp(fRMy%Xg$^BytNUY$*LPv zB<_9D%=YklN}ZV7J?$@dGwN9b-@g_MLu6!(20WsQ+@qo*4D3+a66G-ot$l9GTW1>RchUg@~0^laM<3!AO18_xB~X(MGpx6t0N6nHn?WZe{S&FAkRgnt_Vadfy% zsl7w5@%Arv{tv*&6!{c=kBjM65gJhFr}BJog-{XSI~h=x45%tGB!h*LsX>g_MSMnh zK{6?PWknXzq1wIb_t=qi?t~g~wOQSe&IHlCfAYQ>T{<43ewg)p-w{@c0+1dKqL(WHP&laK)pHJNDC{}i6ivK%H`bzt|udf&= zR`ry+gSa2gUstg-`_PQKw`W_sDNZZl{HpIl7}NcD=yoMU;qaE^@ACR;h0C3Kz?}u) z@f|6Efxnf%K6#}a+}d<)wu!%xuO|h#Mir2(GgR$Ky;O>**#&P|AX@2={3u}lyw?qU z=$|_9uSHG=R&d)@hTj7@jglxB1|c70arRP*e3?S54n)~=9(d9WY>8oa!zx&sOKJ`% ztjb-ArH9YH_P$R9ZWA&;u-zElQcQ~xjos&(h|1{b3H%2k+SiSA70EcRN8OYSDiW}p zvo!aMN!}U=r|#?ex^XzjBnNiiij8K+5itYH`R9g>iF9Bkdx7mnu$;So!V*W;>!y?0 zu9FAU)fCX02Ba$rgxiFW%)RQ41a#JAsr3kxJ+O5*u>>jCS1;5T3oe-F6o$h}G>Y?r zRNQ3bi+^zh4{M~{;~46z?G>=b*Wu#=!@U5KX7R~0wi1~=$qsH@_wYKd<$?Bx4bgzi zCqeO-8Cs(0uBbwc>G55zg1XE+e=aK--I49^J8=oq3lhovouI)|N!II0h=td~ zpWVF@5e&cnQA0McDV*B%7jiE;ocd>&2dxRYC8xGg7Xq;Is@^rsgj$OJwm`OcnPSvC z92TOwhEih5Y>M|Z|RFUn6@wgnI+_Tsk7GQ5TjF*g6xG^-k{X`|eBgyddXQrF-kjk9qD>>oq_P(5tv*&ktDQ*1jj> zBNlW6@72Txs+kf**%JP6ITupFCjjs*dJh>I)>*+Z2{0b55E3H1m(QZ2x=pW7I=M!@0!iAeil4H}DCtmEK>sAi?dQlK%^vSra4i|?j)t!58 zUpoOI1_<)$|w(*ZZyqRnj1 zp}Ix_&VDu%QE+o+lNj*}nk;mC_u1Tcd+ggE&A{LivqAs&3-S*8OvA2n$VqLqTvxaT z*J%5qvSi2~4W3DEB4=BOfFdF&0wKQv&RY|#@hWN=oNU5}mM{_^dBZ}60FdHqPRg() z^_WmFp|Z!WqWM`WRQj11v!>mnb@#}_`&-c67E*WG54kG8n zY!{D322)>&Hlm1GTsn=npBhN44}?#J-WFEX8{F31N1Ir;13P;2!!S}IBka*)O_e!t zenHN=yH8ajS8ttn6u1hqnTM?ILOKcz8}J}%RCCHOgtTkX9A)u^1Tl#eEM+F||rR7ZSFzCTum0rcxmOD9D1U21@%GI(S62d8zYEt*7o?S)zM%tcFYh%zq&vZ>V*?)X`<2!Hc zOLezQc8^H&@7>q4FM7^06UL50 znyz!UFHy=qgU~BQRYp^1HV6Q2nHdX}(cTnDarXVG-~oj1FZ82-{qk3%6|AStuN0U+ z4dI*>wKHr(g>-Pean!MmoqzYNj~VN_Uzlk%)#!+uP47uhzHWC;?v}NU9&Y9Qm)3mi zM)n*@jlTOHD#ycaPnp7MC8vBeqrozx;5~Fe8&uereL`6L)#+l>egKgZ@gpb1`iXt<0_F z)1BP%jO{yu6F0LqL^jzv{@mr#lo)e4L}_`5Jl_iUNYetx+4&%D`6gs_7z@8q2nRP} ztTOx&)o&g&Jh!jAk1OCSeY?Hn^zGH+g*Ee#H9EcaJZMWxjrdhS8U#wmKe_pt^H&u_ zQmI8l>tAMB^5EU1^UKf5WQJ$7z=#uN2u}W*3cEW!IFF~?M@9-?q}jAszo>b~JgesF zZst?#xCuORdpbV&td1Sd=0i1Vu*d8n-K?Ykf$P$4!0YM5c3m34WkU($TXkh#**awq zNNR@jzp=Vzot=6W{ulqvuk*dK_Ls~}awNx(@^ML<0n=0yGI zbiJVE#NSW#h_hmzGwmm#+Y20UpzPA2{DU7mP}jU72op7(Pg;S#1@! zxE0`j6=`!zTqRpNF4-#R_8cLX6l1O&HL~*|TyX}7B(z%MK#MFmUWaido~!u1pZK9D141? zqs2=wObL6#C-t}iQmW)pYg&B_L@hqIDR&JOpx7=o)>jB&{7cA%jTR-y#)?Xg=i&yg z4fxg8en-J>Vz0_fOe48S!Lv2)ENMa&uH`(QE6SE}NfH(Nb!EX`(OJr5AYy@L*(B0& zZYU1@_$5JD)i?X9uG4LUTg176sP#qM)a4qJ*u$^=X%~M;qON?O?^nJB7FBT=nmg>B z7!X#qU-WDl-GT@+=sv@sdkD`#iR2R6J#YT!eUg)loI$mh1^M_5qPR(z# z#S%`FFSLbM0B`Dd8;#x6o(mbnY0ph>F|H`zWS{<_%j9r)tnbWceB@KDNfgtOT9fTK zpxoWP0YOIGMch;9oM)n~Hw4uTH0BSB%)L(hB2G|Y+$*{i&7+LAO01QdP9w4YN)x%F2x(s=aNG&H%oE9uWDs)-+-aS2xtvD})|L{;6FpS#Dh z5!=&aAh{z@u8&EGCe~&&!ZtV0=aQe-yQjd|BI{=i=8pc+c6mLoYJd7@r&jOHFJLX- zWk8Nvdq^Uea#?pIms(Qn21U8-2r$?)SZ;YAi-TVcEV9@86Ii0KmQ@?WVHhZc=?mS0 zRa)+i!*Ck$je?#|tuJ6^8?lx!M;B2e_uH`Z*p);cW~dQFQI*uSa_99~VDJE~v)Ih^KWbksco zk~VobQTBA>@51>PQKEAoDg6&=d`9EdMe54m=Jzicf8Kp)kD4tAzpP#|eJvYNMjhb# zw{_lsLm6?{F{s}*h{(-%JN$cvo+f-Faf5&DVr}w(s6`dVjz1%~Qqg21*qM8et+eV) zbVjKY=uboA?TB7<>8UGu^OMbDzJ=i7P5&n?oT`2nt>|Ww+)aH_1{0OV9_-@K8eH6C z_pvZ0Ckaz+hxCk82@W3sAI|N>UR|&+X;>DOj<<>#+|3O(UJ~WAdLFaA#t;rU^$;^Y zve%6}>v(G#pZ@4(s9tAyF+4(~Lv^JaVxKKIIT(d}zw6{YA?MG3GtojGxqvv8nUd{w zp%jGRjFD&yS@S(eY57O_OpVGW16ZxgdV|@GX};FEE0Fs37akQUz%(@s*p7e@^!c(T zkJMy0X!e7IMWu~rN&?hJ5@;#=$VKL;uwbE$Lj~Hvt+;1P64{FSFiB<&(KhSunG#6>PxPh%AY3Il) zxs;E|2W#H6)k;nrBRArOo^fCxX4zR#{hzDJgVx!{<5LRfEhZRpF&mt<4G37%?u_)j z2-(c1j?dwKx+_vg)*eq%%4r@KZx?9S8)QxK-h&d#8`IZ!G_oRH0CGJtnXl&*ih`!? zcZMc}AMaRRNMhl(eAbv1QwWWXogdq(8#i1`R3o1Ae?L+iF9c(MIb~^yw(WWE;Z~$3{}w+gj4fy5zUTpn)e#Rx zn6w|QCj0I`b7~k34eV1|LdZH<6GzP}%e|30g`SocsR9)0xDc{1+iqU)pO9TSY1Yto zl|Gt9M*9+M82@j-N`c?yRq;^=?^~%DR-#wkrY}-i?8y!$miouu!t#T<+-)dPFqfWt z7))3jY~>;)G9P~p?e z9c2(J#GE;R4QvOeBo@8=0vPqc`bnRtG4=xcv0HpOpnu(Oc#zvR3vvH(xxl|CnG2$2 zouZ1~dW-D9)rt1c0t#HtpC*hdV{~-td(s|{XUG{%ogJ=uh}-!(s-WH?8h=TYlqoui zQzoWfGODiTS?XmM`X(ej;uGDddOg$urzowK@J`vAUjWCX5fLr<4yX*scHMD{uY1OC zAA!eJM>O{{wi!j77X5l*SpHin<1eM;VTpAkN`%Q?=`U-UeCwrW4-^6?;>N^nx)d&} zjaJERX~{io?|p&xQK4fW2v1f9_tdxr-LnuT+7zwZrv(QJ2Y>jkw&Sz_9{0P1OmKr; z|C(5_edWpDzdzEuzrxhZMA003jON|G4G_Y%)2{Mgv~yyQg8m3uX+TV->8haMr&tR- z_i}4okr#jQ4h~VH#cn?@*y&}6lln6~6^Q0qz4mt$HVMdl*KDItAa+DBNA4Qu!!KWw zB9yU|-5N?c6L)P79`c8~JEs23FcQ`$l9H$Y`u<5{XNM%2pXW@!`BO;PDv8W`BcZS9 z(PC9Xg`Tgmwo3t%E=*>Zm58swQc14gD{LJeTT8nW;-}x~)W%8fy_D-#YPat3mR6%> z|7rQfM>z2oQ*v=`-(BE7Z}>{AcYffHo}a-Pq1e8~4aB`^jvXSzZRCv#hBdt9MauzP zDp!sE@-*C@bs(qmyr4ZpXRJ@JCC5|kWXXdV1_ zI-{sf1q|&E<*;%ou<$;(TDBV90k<`=_C}*LT4Y7aAE44+Ld(Y=q#;6rReFhv8Cg%0Y;4rn)Y`%X=yvqUF^{1!6 za;4O6Mb3a>p7xj4re{+Ib*WMp=Mp?Cs2km9aFzezjJT#j^ZjACty0J1`)ry1w8c+F ziUiaW8gPFYkZxO!9U~18MXtp1zjp28&AG=fuK6ycj}-P;TE)`Mc%tAFXN*XO1;3ih zu;xLckn>Sb4S#y`qUg~u7Pnh>GEZ(h=JP=fL(7t@Fw*_bv6DT3BXA*kq08;r2Lwps=ns0C%V^ zqcpLkSftlS9*EO;5?Kd6s2{vVFf(uNcSjevAF(yfbb8q~-CeBYBm`V zQ_2G_jO6AI{Mi(I7SLx-wRX#KaS#~-@&%l%uFjMwaP((^_uB& zM-@&eF(#ElG9l?l7M8X|r`sQ~S>e;sX>vN{P_9(AE|;_mG}7tJq+S6a@GKkK`2l`WnfFmG z>^Jp7{K_TwN!TidnlbS!^LTgpDuyeU-a73bwJg;B(YVAn6AKQ(~( z6y#A9y91f;JF8iJMgE0x^63%Z{#j?%XrRK$pnW3DH!Z!7RBup8vM8TC1y<=8upJtu zq35k`92Yz+0^AcV>}~GKZK=|wRf(o|_{ZnK_omo;%Nk3nuPpJr@|K}n2)@!Pwh*`1 zM$3>3@9Fj^sF!Elz`Mtqc)7pHiYahnPFI3V7Sss?cWOAe=g#|{I68#fT#o7 zMKWCfs?Moc`(`p4ZuywqTcj@$qpj(f8{KkaxtdgYwx0;#j}+OwhVI+s?6>fuNqYA` z&B8EUI5#Wg=4=QN*a{I{Dyx}e3m@i46f2W1*9@-eR=VtJ7QN4AZ2+iW8SFh)voW8X ziGWm=KzzXB-u;wkK)8M)n?DB5{9d$F8)VDXae&qL^OCop8m{>BZ+%(nC-RSY=Wt2_ zdcv!-Qu}(^Mx4hNdUtQC*c5IQm%YK0dd|G6nw4E~;a}d|o_}=V)UhXdm*YE>eMvVRlUOrYU!g3}U$d}WV@N*OWy22FMD7cn?v(t;0?iRG zb+MJELC0*&DfJ<8mgNq`Y4sb`r2WbjvLjoBJDV=^uS#^j{9)TegnU#Wyo!xi8P)KP zS|#MdpX?@>9a{e5B`I@;C+m|ha!}!eTOoXgrx)n7N$opj$}`@nmi@_gH2}KeOI(|K zTlX z(emS>z+4Q!LC>Z|QMp7f=Gqdie^B9C%}De!!4r?58{a?5V@q7-GhGuiFoeMhTO|ox zh!32P1DQTDj$~9EiMrbi?FUpk$u_YRb~;Bn0M6PP1=j-iI*)S!vkt(@cBsxyC0d3w z*t&9i6Z*iYEC3V8RFYdtJrjtoQm1y^6wPBTD)z3!df`6Zqu2!Soyxnv!9y_bBx5QRF;&^FQ0!b#4$jwNFg4$yPDC-x1ow2P)MV! zm183Cytwiml=2lN<$aPIg2*hKowT!I8?j2$?uKX=oP!-Y{4v7w%bE|)e7eVqsyYWy z>u#y|rjT@IO0`+FF0TC9tIZqoY%wNVEozZV98yegGRrHD0+DpDl-Hg%A*I95m3w>K zxB|AZ4Dy%NJ5JGH<~__r&I8_IyC4O>_Q>5aLsRaP25ZbP_=l3aGogL;wld-)lavd4 z(z?Vnf5Wm%3<{F)RTM5$CHN@+?~3hrUn{PjQ~_7@ljHhRBxBc^i9gb*Hu3^ zOA=fim3Ef?=F}-hL0UAK>f|Dlu`2_v?0KqDGhxHxdcO+kNx+tZ!tK_jbb>RS8RleN zjwZ^vFO1=xFW!|%Z3^2brQ@f-@?-*-OgUR^rPQWaHYWF9avEPW8{!BW7|M28{s0+L z)iu30D9ZnSTBI;zz(+vaM95#*cwga3oP)3sGUkkz5PQSomV97_ybZ|~y>karSy3)k z!Yn!;$Nt={pUjzQ5eL#D7t$V1v^`=^V>=I5TM1Tjz$?YRIXGX5f02i~pDAaM zp2`6IcRd3q!-ru>SKt;aG~g>1c~TJ);*pc@zzV!IoKK5pKWkk|G`3}Uu>yOZb;dsc zep~FkdrWLw?YHlq=^!hfshfGq^;MgYU^XkQD+BQVRBu=k{jli%JwvzH0YOc+v}&zK z<}cB7`PcC;u2whkdc5JlOmnz`c56nQkjtOb*jyz9`MQ07J*cWdTk!ot*|t3(>mJ@I zj;pMefqh^aJE|%b1FTSEU#5!d&6=TH_vIoo$4| zL-b<)7gs_(LDB0z(7YhgAw=;wxuBig)L&VPrYic?YmFSf2#;g188nZ50Y8OUx z(Xq&9m3o&q=2~JEU(}fX19(POKc^R&<{c{cE3Bjmm+6bX&i+!+!;1uhC9&Hj8`QEo`9 z3Keu+3CgVwm80U}UGj&gQorWK?Lvg*O>uqTGrZqYAWyhrWN#qrlKj(KDwcz&%~6G1 zs~a*n4j#2+gT0N(d^zXNWW%4^dVeO2mRn!SMy@qblD0mT(maW6uD>j1i>2`m=BfK* zVePMb(m^zKci+ghffP^+8ExzllrH)0*~Xl7_GA^UVOF z4Fx!Xvkir+t7$eaY1u_3dYOq@AoK_HgdIb9qj1ztmfDSAcEWeZq|0U&?AH+5SxAsu zpI8C2iq+IQic%BHqNh?Uv#Fh!$esW}wg_>6WeT9Q8HHP?(O|h;8><mPej53E_Kd}&pJwGw|8o$h8RPVy1SR`JSUF5jX2+YuUw6;a$DDEiqlMr_;TZO2hLZ%Qd<#VQ3G)O`z zCp?h0Fec;oX5in;W0LpYSRCT=^rdoKA?SBx?5vC@#MS0$rpO6Jni$$&?U_}q`|4cu zeF5Qf=|_ckZZ{THmEL8@#v{m^4?(Y7hF!=PD_v8) zLxD3rg_k>@OAhUh30@f5Qw&X>Mr94T&bpFpUY5$(ed{>y<$7Jg4MJ^YGirUW1%VOI*3rth??l>OVj!m1&&6_`4JwBLU1J) zFNTHYNN+E~|2wsYr5r7xB}Q(Ih5(@C2jicQS;&@}+k7s=UJdgpvIqxRx8CxMwPfuP zWq-{a?>7ki?g-B#myfWz>3@}dvLyp76{3UUWRvn>h5~xQ+`!gdlfs;WR9VvLN@M4^ z1~RPV2q&h~z@JBmDPFvd)NMl#UEjosukMt}^hJYQeLj}pU1%Gf?$|xT7HC6LqWtm4 zQm2$rXxN^G_ndH!7Q&Yk%+~Q~J`1Z;*X!y! zmFxk*$XH&h*>ysn$Mm*DTr`&ADNdpS?;JJID6B3ZymdyTMOKH+80 zf9Yw{a`|28gj=^8NU24urh!l)Ep<{8{3o?0AXRZ-4G57G@V^y%oGxv}IUOSliq9*T zH$5DY8yVFb=&kOsQ7Y#dQn1Wjz5l$VPJdK2bPB5Sbn$myw?b=jKJ*zjM|K*kZ9pSI zuSB#AZj+YkLq`Q#3fN6|_s*=5^oKTdKby|>@LWm|OtUtyLr+!A?nN|35oO)HP#29}K1@+lcyBvg>b)0Cw)G zAJAQWl9*iEXgoNkY#x{WqoXM|

hHln$?Wj&`bAu~3<27D9D9PWek|SFBIEH)PKl zEzO)u82X9z${r>7D9~b>;?g@o;VSJmPs^rbq@C%xsx}2L(~E7=#i|_}gc%v19AME17z> z3yxoI$KvOIGXksuP5$EElq*^Q1G z!=)3=Css0qR6z7Lk3UP`e1QGe-Qn^6wtj8Z;j z^z(a9t<1AmpX-$MKzmW2S5LnGw!Eb;o)sd{r4iN`l{BBmz;QHrW*YA|nM=(5Q)|36 zHRldK3EREa)~5*UnJuP$?a4Tqm3bWTVYc4%*ZRv9y@sDXpM0_|ryZS>&7;37eBuvX zjheXispI%P+l6kDNU~nUw~=P7b8hOt3H0$nm)7rZe~;9f{>rb+|2J=R^i|LQ0>J=2 z|8*fsQQ7VIp#ZR8C0F7t@#>>L{YTAJDGpJJqVQG_7{oLw=D0U)C|&*f-~U7NaR`nf zg|B!J$%)5xz=Be^ob>VE0y5wg^@Dj00!D40&OzFB;2%dQU;}F41|Cm7kOQq1h4Wa) z)xAPC&=?1zU^r!XTIe{(V_64f@~@#!Y#(LQxz7 p#H|ewB4H9*Og~^>{wd)TLgB4A4B15?_5DK?Vqq4-%0C1I06Urzo$~+y literal 0 HcmV?d00001 diff --git a/doc/interpolationSineWorld.gif b/doc/interpolationSineWorld.gif new file mode 100644 index 0000000000000000000000000000000000000000..f8c420fef4c98ae4f2ad93fd38a437864d38c52d GIT binary patch literal 520702 zcmWh!WmJ?66MdFlSem6fr9nbOcwmzJ?wz^THy`Ue0YfP|WeS&)I&oXXM)0NGe6Dyd8p0k?F( zF(GjI2$&PWt#ksWo&gv`;Mx?p)C6YS0gMxH;|Sb%0~jA*-(F-)OPH~W%A*lvTn2_L z;E_%eN-p3C|0KZ0;4-4>JRpoD=vJEUREqD8N9LA~=T2Ja_@Ukm*ar=A{R!55x{X0FjWWalmjo?fpIWYAPfX_O#|FOs4n<$ zZp3lVKo8F!v2E#r|9Ig3vf9{|lKzormH<6&d4A4zF?P(lnxD13Y2Zq{!g*KYW8URxUT$KZu7T~&->UTNc z(I-&mJWkwCP}>ktwg9xDaVmyD(R-k@eIW7%$h@YFJq0TE{vVgJ8=&hRXt|`SxZqFO z2Zn}#`R~AYG=N4^OpO4TA>d{Z*qaBg=V?xV07HAg90vG)4WO@SM$Uk}J>VJx?A`!3 z*9>QeVvFn614AY2#rfqMC95m{{{8!N`RDNTXl{M+=RhR@0PHsqf+64^!2XX&PwmBX z6(xN&(TBod(0?Yu{}lLtngIA%;NL!@W?g=7C_W{>`A}WKw+PsSCpnt+g#$5kV$RD$ z^+n%5v8hBeX*CoN$KpJ#G#_p#`H?PcGm@j#SUQ$1{qA6SxUuZ#XLu+f^OL6X$s)~U zev6T&is>@_q9?ge{%rIF5!Ak_8ELMXueJOZO%nAde=g{Lu+rj3OU+WNN^2JL(5JPR z!Puj|l^?COYhMx6BeP}AZi*iw$vHI5e*$TT{17_(ax3S%>*OU63`esd^skBg#z)@L z@=bS^TMdp#&XzqkH(b(|%{b{@=~)FDN2vlgwkPJjDJ5eT+8Soay7KQs}zcNj8+Rc3M%ZAa%ARbeaQfP9)` z>?i-o#OE!mZehqR!={rDK2?k^VAzgHxs7lv{c?G5=qyQLWN3l?U5>!Pa1mMhv=`oT z`*&gakDHLgFO3y*Oc022kedL1;krT$0;hRY>$n}`?X_qa&OT?793zo|!hy2Y!E4Ul z7*ESLF5mp9+{Y8F(+{PV%*Gvfg%a{766VfoB@^&|`)v(p;dEe73Cxbc+7HFT1W!^{^=RX z?S9)3+Srwm6P50Es}@r$C_b0*ddzd)Fd!Q~c`-sH?k|S-#icXP-@d zdb{I4Wy>7ar^_#%^IgRSjN~=SwVlGQ%v&x|OPcpr-`1+#L&uVJ+q*wMQt!lE+7(%-r{UaZO4 zd#v>8PZ*{REid@)`QxQwcw}qd0#N{Y%I7~izRCx2@lLd{8-uscn*I&w1$=4Da^sd3 zy+Y!fU>j5zuc*NNH0pJcR{}Z2>1aubxHGGm0`%dDq;g<=wIhB%15It3JSE4ca3vK( z@|Z{j(Kgvf9i6SF%W0|kn`%Fjt%XZbsm_{SUh5@gLuOs$R=M3o#43(8D1b&zf`P(9 zr(qtn-`tSjE)vbSJilzfJ(LHkiM(V?XZ_BluE-+r$y#umUE@Z8Wq8c)?i>cOGQS^op6A9PVLZIl@KTq>chB#z z6KoUQhTp06>KrqOx2fasb!|N;Q*x?{#7S<)19YF~{pl)Gg$@+kAfLN=BwLWHl-KIb z9VY(^v|FL^SN8RsE@;sDIyiCbX}5b@5_{r)dn48-FYkiNt#|wvR|~yMs=^)K7*)-n8Kjgvux1OLc41m3E^gCMeSckFljK-{ zlYQIl?1a;Z*#K}|8!_=hgpjEqBABgzKu{8h-8cKlw3P9j)(v5S)Oth~k=j8(Xe&Z|T`V6P{@wa;P7H5u??8XIN88X&EmLliFT+ z_ka>}6whb6kt0{p=-e)cbW<5E9GDnDj7ku7q?dydG^T;!n1^rZ$B_OcrlecI{HD>@ zKrRt?B%=fD!FB)KidY_zoSjT-%g6`A#LQ-MrLd-uS^H;A8SJhwnosS0ybYs)_Td@o z!f+Cj3N7g{np zgSIrL34|JdX*^)?_$Z;dzC!AbfJ6rEbEF$pKV5BVRFOY;mYnr-?x94=(_B~1%mpBN zS5$cfh7cC$VvDvHucoxNH6oC57{?goDYs;(-QHF)!_p<`M z5ekUqE&Bu%gjfF@ud5Tp+gkPE*U>3&y6@s0i(APG;~Cz1;0Rfr3`B7J9aW|YtBTY_ z>rdicK`3xa@bAq)<4mM{;63R(j4#`XdxYY>5~*V(9Lz85NuY`X5xAg?r2-uCgJowP zMR;SNq;~Du3VWo!@Hbwsu9%{-g~|UNR`t3jxc>W#0r36Xzvq+$NMp&E9ptv;Nh2St zvK*Q3-F7|do~w_>E{JQ~EtP$GH(SMmGyehcM;rSW=x9|?sh$7c3a+yWJzCi$XT|Sp zj3p~syd7;*(0_0)9Jt{VNNV^G%q+MD?0kKUB(4K~8#+vK`xnyq=NUT9NSV(=K@|?J z3lTvS89}ALg7_QAe9Fk~VU8p|y7n#az=^?*1&&JdjG^D($GJm26MR{(0(v8Ssn z8UBk75p3mQbQHm1RsjhuK0&-8M&uq?hm*e2 zf;Nnu;KpG)yfKZDtcXY&1tXXNom&^LRlNf}DueT{C3FDodoAUKa`1Ym4<(2DU0k|R z)&ZcQkJm4Q5L1f}s+>w38VF1Og@lL%06@qcJiK|&$JX$ZfHm!3cd|IZ%d-xe$P4v! z$77xkNkl_sWc;`_{FJ$ELD$KiM$V+e3FVsc8j(R{8F5wDDchQf)bwwE?IKd=fJLaN zmS$>Gx!q@qB+XXpFtiVF=7VRI8A}uXiRQyJQs{~eKL`c(OGxvsgUX@Oyw`o-!J<5( zeC>=unY?~uLjZ|;!epCCId516eoobVG{Pyq8l6(flNehAZhLR@Vzaeeu%89s83bx(11E{6~oD%DosFo2yNB2T`453Ft8agCnErh^vs9yXQg?b`QBqZ;>z%d^+9jk zKU+p55L-GaU&aj#hmQEA&^jf48A>6m{8);~AmT3}CG!^R z$A|cRnN1#rkUthxLb#X%=PigH&VdnDMDKeG4VUz7l+g17B((1{GaZ*r zVC;mx(Z(!sK(fc|hJy2_K`=r+DM> z{BuStQV15yKbcl&wdbc-Mi>yrSn^~HN97ye0-g;edAD@-S$2e0_AUCAxRa@6w9hx#wd{En2mQRSMzQgk<&^Mxn!9|*zeNn0LdH8QnF!{BNs=*fPgCqvbVUsV9C=!h>_bT|)m2TlAAxVV2NWGt3%H{lM* zr!otpJS(R<%&$p?Sm$O`GsRy)m{q~9U0;*dFa@f7u&aj>I!=jk9nGmk zEhYi=wAucIC}5Vb;7xWuiEIV;n;KX`1Ap&aEvhyA>6pd)d);arnBk*MQW0A6NEqxO3u_n#01DfkH>Ql43^WN0c zy{XU6@Mo;bnDVVKWJn}rNVJRTFc?m(?PPE_gYoe>24PYO>wP2zSgwXz?-{!IW!tWY zT0IY1-50x@_>%Yi@W|ck`W6BF&TJ+B>iOuL+-!f7yJq^)_UxE?xNkk{eR0xAM}lcb z){~m5yXaruAP?ZnFCy9tZJ3yVy{b{CR}3tI*D;rY=^h1EPbh0Otwk{Q2OqXp4%gQE z*ZLARbylX0mE$SiqB{7Rb<_L^7Tb5)df9a9O&#ic=h}0%6Dae&j5=Ft%RkS^w&2UQ z@R*0W-t|@2HxMIft!aSpwlDkqHnJ|P_X!|+;VSI0ACzIeQBbxEdywbjk2+qcrAMXt zAU*+n)$sy;&zag2@7n2q^jeO#TP?R!tpijO!`$*OQ1Fjh#G9r;;)&f%Xn0^%`2A45Khz5- zCx>+#2)0w{Om1`yo6?S3xJ;TsN4R|^)qWj-{Fmc z3DDr`LbsLHBfcS>2khN$CbHX&Jdg9uU`3ha*NYQ{@&Tg1337DYGdBo}nNl^H}Q6dJiQV5w2Dt=Us- zR&t`#ZnE5MwAA;|e4){IfgbB#E4;8EPBJmaT%OG@!OHUAg~#hFzQWV9aZp%%o=3-`eB8uT=fn%0r6r~jb)hw`)+I;ZHBKpzeRKJr( z%<$^s*2D^#x+MgwiGp@(7p;wL=N@nCo~+2NuLQ(H0$y!9Fegt4bl2A4ImOqd5_|LX zES(>FInsr`GTOC}^5f!35XawL8XX@SS!S&sTgg6P39PpW1pNu$Ygi`J5ng${Qo5A8 zJtnsit%p(12X)79$mL^V-12JLq4Ws6uY=R_2h$WsKq~QW#9ucNO|)a)u0>g(xbNnh zSDxo-YZ70&frlq6*=uC^US9F_at{y9#>lkw59Lr$tykM_(a^`Rqo?DeQ7o(H9hkS3 zhXRp1@4I)V1bS1eKc;IWh|z(D_x4{$EOALyXAN!I#D1jz+iua>97qy&void;`qzyR zsBZkkYz0eJGXnnFwYQy|Y%-nU*-k)w=qy*E{Nd_x|G|eIUC`c%mr$^0iNZ);47%iD ziKR|`5A)k4mt9KW@Mrg*g+a176j&R!eHp#sR*8x30b3~^iJg`PjDyvLclcRXN2@QY z<8~00c+l+Z4y~&~x2S;AGm;N$oO&SAv9pn~?e z_vXBd>?$8@!@PYJ59w!FMZbm6!!JZXV*;>$W87+;KFv9@oyiMTD|Ao1SFC;|wKj9O z)ZdY8({pSueUQ&GLQ{J-uJwl|;2L08T8AJ>@t}ugCX<=+nPySx_PRZ20KsEge-c(=%4TEWJ$R8Ec?{rlQGLBoed#uBgi?`W4DzI zI8_okRN@%MRNiZl7s-{gNHlE4GT_g&nLB^vV zsR^@wg{0;t6_l>)RSF5GXUNOHdb`v{N;B9_Z*p!sk}C9iFvsM=emvJm5^LJ0^8070 zoHx2Rw150Li@K?iR~%1sVyRl(BE2k62z@PiPdqcDQrkik1$w+h!2M*Y1!sZ5=ZA26 z7@_AHhaLu2(AN)LqR{J^c-wbCb7}HB=ha{T%j1==5v;Ej1_N}i1+9{ln(!*se!=2K zBLA5O)JVwr)(Mdp&(53nHsHK(=!cLuKljyvx_J)&irNe=ac0Ob-XOtcT<%W-jO3s zMbSwrB*I@eou$|N_^UwTH3CiJv=^L-1yXh|%VjC3``qi>Q2_!E2QaGfAq=O*&-I4b z!X-_e%1T-mhq!e)#JRmE44QObAHL`X<$AhC%)O#ah>)3DKhPE#=5JKq;D=wdpK%jj zj%{I5hYULoY{zSC6CXRWQ*2oq%2{MeG;zFP{U~i6#S`4bs&qDeI+Xj~*SUP&MSD!L zFwawWd#2;}xl&z7RUOi=;<27e)JfnEyLQP~j6Io1AgNWDGdAo8`U9;QQK8aoUlk4$ zpM8f@+2@ZPqQPfo98ts>XK5|}!Z>6;-$8f?V71X z8^`ve)kyo>eA7@Mla0l*aixlY=W?V_*OphmDvPcrE($-&c@FcGF%^jhn}&SiY?x8f zf|&gfeW6?5RKq(R#otFN{z6x#+7Kxa10vuqhU@yDHqml~#6N!%*F0V*^>E`5vb-J| zDoOJwr|R3^v%>kv(9a`fWj+3fjAK#wl@d=mn*R-P2|owLiFTKBJQPyoYw|m+BoTg% ztM{ra?9i_t6MIPeIw~z@x`1M>_<0WAcj+RTr$W7t*`}}z-`gB4ej>@jEFm)Q@?u2T z35+S@$P;E5^ul9#?eErahJ1P+aPAoRNvmYMxKyau84~QZ3U$vZYTQn6)SZnYB6Y$e zC%lf2ke9Rc(tjb{$6V+5+f)T7xh;+J3&@`$%$ll1dLT7Ff>_;J*)e#EGCor%h*kCT z&BNKx+^H}EN5|Ynj0SuAn6_VVBC~}zzA#H)I70EL0OqGzhAT>nY^+2vFhn%rbN>1i zUu4Ze-LA=RYRejDsZ8UyF7sKAAQtn0ojciDox*!csmtk`@rz5w`jn*L=x;_7lB%jf z)NbtB%SA9;nJSKx9o@$50!pGN6eovJluJG>V;Xi))0$>FBWdfq{16aAqbeG+@I?8k zxMiwHTAkwFw_R>0u|W=|g6tJJFvA2|_PYB`oJdN+y1y~J4L>O!xZhw7qE&^Qa3utY z*s>)X4p|&DMs4aojd+hf@@gB)$bK%GEBdmWTHoB^*-CFiKdbydB)dRKp44z zzrU}NPx1I^JaNa1QjSJk!oMh@21g|lVI?qyM1e$Ark0E0`y!S<_G+Kj+3;eMrOdU! zKUVEWB)){Zhug3K^z%~zqEFN1-&^b4wP95`FE2hT@7M|7-25Pf@5fuBF=9C9#IlZ1mWOHG+t%|G?hmW$V!*L!XZQ-z$J{ce&t?pN6FX@#-i?n` z&Zkbf{y8VgwI=-OCF({JMpR7d6x|Oeqt<8 zcDhNj!G})_{+@mJqEC!e733ht*17o4z7Z022Ox~XNU;^}ETn!yT4JQ@^)tlbse#1y* za?HhJjjC_|D8T~VBhaNaB+i-w_kr&W$g7;<9?tT-BImaH+SgRerkZDzLu62JA6a<_ zoFF&VQI&^2EcyU3{PZDCnc3lMK--VBOY4n`$|ALdXUVIJWbG)&Mb$3THd*4t%Xr^;+F-W^q!ZrbqBfFH&3eU-s=Q)Z(fT;cFh8=yNabvwLCG)m zv7JGYl(oiF=rqDY$*R!p-n#oKVo%udX z;zK_*ka+`UFBy$>%pO*}Q||P~ZIGb7TKO_E#D6Ze8{x!I^!$BodxaZn${@ z)}$Y}I{m&}{Aefo9Hi;pC29!q!`0oAW%J+Lw&;%w*L%hM{jtIm-O6X|W-H!``5;nX zVCILYYtidkR#trs-uB~JqF}@7a_Z(_vWL!ftX4-#6TQ8(@puAdv&2SN!n?sf>elw- zAMoE?9u5Rnl2D&{o;|0J&sjDl%6mV5{FJa!KxAEjC-E^9;XV3H4*!@xOa3pNc>LG6 zO%-s^5@K8?f7sRLVilV~o>nW{EE0kaHfAF|Zh?c@fIm@Zsp$NpG(oVD=)L-L*P+Hf`U*=l%Ii6w(%TRg`V6gnj>u z8t?w~gY935hqB{LX|RzpMs_hloO9vyzz6GFWXdi}6XJLs=UE~QRrR3dt{kEc)%?(l z&29n%{{CpeP|a98_l~6iMESSw@=jE_8A3Y01FtwIm={Tc21tF8A_=vXlgRN&sYY;J zlUQe{SZ5Pa2NgO7$cY=P+96j>IsNwSGt-u}Ju9k`=1YHU)nbSO3b zL5-BC@BfYR8|BLxHI}s_iHhNbs^69SyWfv?tM{wC4a*uG5v)*Fs*2|1NZ<`o>0|>! z_ORd(y(1(mqKAoT2uU2mVJUrhk>p{WDx4_Yk}3VZL2ckpf?uvBnNcS7M^(aI=XH#t z6s5Wik-D9j+zoj6wo&YnYJI9XL_Jbt6y1`e5}Nq}B5oY^GjwqD0bI6AM66nb!3Ls{ z@|}M(V!jcv@D3n?sVeuQ%C+&!`r%)rWWC;huWSNl1fC4BgSEC1Op%;ik;O!P-yNM5 zn5f!99}LyUD1<>mFn7q%-^lqwg_c9YmsZTroT)n)Nu!CsC{GQcs03dJDqES$2&huV zJ(sbPYZrpZSwe>YljL`yN7h=yKfV;iYW;vWxtfJZRDT;65NAA8R1v5ZU?xjg2g#Li0{)j#e?lWX_tO8r4_F?fjvUnWR zG}(59q?8_L+E5aIBGLLhbtN((qUtdjktD`nj5j6W7pK;cpbpBGIwcnSRU}Hs@;zA6 z9V{_qAowzrN(?d-+9E6-W)r6M2Ln}v$*VkuT#RTbmxqFL>%|h(C38i7{%*%p6aPy& zne13kDx_L|r2Ee031O4|ay6!?jhhaI2V5^;3AiH_n2Iu3-vpW|NT=Q3CW>l1A_J`fm{Ro zs>Y$l(fiRaRtK@ca7gaO=$n*ps>a{wwd=ta&pl)6@tQ>#i$c{BTE=W=)PLxbiodw7aAp)bmN`SaP;l760tNFdnjf`g+Ac zs{E^3-P82g_Iu8e(X)tuDGQmu6;-Rg<#wriYU}2PKA*g3PxqRSbF5!VmR$;bQZ@}Q zlvwo6c~Y#l=uHgdlbF8QhmzJUl1PsS3Md3!yr6F$C%rbJ!(F00d%>m&V$%mbdkLZ* z0?^ivS#`5Nep5)~m`YBX`c5@CkUfRpZjhMz^lPd?;;ccuS7_hPl;D_wM1EI#sLWvV zs1on=xFf_(1>$lqr#vwTRztnL8zskKa z8pVewN<&lueZX~M;)j;ogRwkScmZRFa)Ke=sKqBVv~)(dC>J1>BT}k)qRc#Brfo`W z3xE)^1DkWWhAEn1AUYI+GPYQR4oof7!^wv8K^}c5hoq85vq&$|u^7|GZ|pyq?dX5? zJooV_vB8G#sHKa+4X4TAHkwE7wZM+q1vA$CLT&k*Zr8)V29KDh?_Gw~jH}1$B2~{q z;rU?Ii8YmP>cFe#ZYoWZ_gb!;6O?aMlpe1v2Ne^qpbArE3&Tgs-!I~SeBvb@2{lIa z{&!D^5rHZ2(qdM~eUbilI8^;>GqUh z_~qFSntOGpS8dtkp;qMFRB|px&`vVFsgd%*T>A8rAD9R@90Ffo8_%)-;X19NE6vytU)s#qjLhmTE`769Zd$=bAVlGN&h&c37>ha=TdEZP3Jx6Z zwmqbTnXVp)8iNR2-PW74rPK#eCRj0ltYKb#_6Ri9DYp|LHWf~~%#E&6EZjkRulLR!{6wT&YDc`j}%ZqWXlxP4pQU8R`)!pF|Bq3 ziTI#248TixqSVyg<7a`z$%o?!Bb4J^j`+Y;YPO5^Zr|*Nr>~N8+@pbRC;teNV87((; z6G-B#nIniT5V*boK0bn|?sS?aDF<##5kE7hZgsAWP*W*ll zhAC*CUvM8KzdD^v-iHi$fi5@A$sjK^R$BQA@Q zy;TPRL4-ruxD>~=GxhbQ-mU`~)WiMMl~Oq5vGkSVb*PNKal^yIwqrtZ_#2MpzE`fB z=PR?OUw(IevFkdzddlO~!1{-U)hmMQ50Ylikwo@+Yh(D^sDXos0LL(O7(@vc{aDkJ z^E7}9IuU>B3yMGGpZ^ncx^{DEt%?uHUYpK(jwp*;|1oYkny0@Qvz{JtLva5Vi(hA< z`u;xq!>1e#TV8zdx}B^4m{bAldl=6xsm86M6q30uwCpsr>?d$gvPw}a+WICp(KPkt zg4wHqsi$9mGqUC9eK9iM?lUfjGv$nCU?Qa-c-4;8YHV(X&2EVL*b^q7lHC;Mp+5dr-QC)0kqHrh? zDrE5D#-tT-(c^PZ(B1W~&iTksisMsd&uiUsw|k^X@gKgx!1GZNWDLS`*KCD;5#+7fv5wDh zK)|F4|6atsEcX8P>f*Ha6D!p-_w_zq+w~X86gFL`=THq9-x&inA-fmkKBM)E%s!Uk zFBu$M!to;6TRN3BmC{kAqI`u?_Phm02u@z?fBEfg$3s z??J<xP*hddCeq`tV@@d67z%3!# zSbZTWjol=ZL-(MSiN*WKouNk^jg07d?n)5JTFs8*j&*rI+G3X7^4D84tGQmw+@+3v zYDhlhEb%*w=dx2oiVtB!Sp|E{=z;mOs5#(C2%7n7>g6P8x-rCT<8K-ckb3hsv;N-b6k z99s6?n%jxrv+sCAJ)4d4Cf9$)3>uQ@H>2mdZ;aE|t> zu67(y8IEQ&p_{;K%&-y)qKs`F#Le*Vh!GC-2&I>lF7E3BktlG?CoEb_d~T&vdW8ZOrEU~@<)24 z{+N|+(X$A3v_|kN!C8eQXg5X)VjrIbSLKlCCeQ~A;tK%~S`)z2VH0u}4pkh2Lzs!# zom4SMXvjopF{mJj8G|4cugiQSifu>?UW|}0giGA7yd}0Zo}f#azyWzS@Bxr@G=Kri z7(0>%WPs}>!%}U+9RPgcW&8rd5}xBLk=E{*(K@UsX2oVxBOoH-jCFxD?&AGhfh=O4+)ah{0t4u4~^hH zh9Wp^q4*WZlG(;0mfUd#0|_uO6+V%jrLwN~ISyG00s%SV0g3OtSqXl8(2P zLg`JKKbXlIS4`SQbX+*{ot5_(b#X=X514?9%F7rn9p#CH?$bhcx3=t!W3l+bDNlHeT5V2Lv%DY*S@ z{E|S=w~w;loiaP0>P=>#Q>{Hi2rSUDv?sR#-`_HV=-CdLXWJ7zw0Ej3j7ZRw@0sx+ zPH%%So(G!R2-^MTVNb<;dF)*b5!uDZ--WGaPc1f{6Cp?G=V0%mBHtSAzj=Llwt=rM zOyaEH7^-y&paNiNb!`-z+PmXtjJF8AYu} z{wJ(!k)41x%dp{Gze_AaaS{!TwOk8<^n6GeE^hfK5<`zvJ(nbVhvnu_EL@}kLiq{B;#wUr_zG&qBNikO?5P~9e zb1ze|(CcoRzSOS;BeKXYX zDGmuf3WpyB;7r&7a_~hqvC2hC;M_4Z(3{@>q4%RpFkv%S0^MM~t*AR=i7Y)fKeeR# zghb!3?Zql0?aseIEKmkapAq`*C;Tmp@5d;&0T?_;(bvazvZiiPDMD5xJ#gk(c_4q< z$NH`B+lyJ))4y_&Y+t_o@JN+>Fa4XHR3tX$X&I}QG!8|yK143VeyVITwB)(Z{%r9V zGB2Q?N#Xds-R-&8KmPVtai6#Xj@iKF^(wL=rO*dMRzCkoR?$-C4W_le`FIw;CKH3- zTRsKQT2~IZq)!s@RRMq)q0%<`x=io1T7xRyii@e8waEgnlr zd_y6lD=9DOJAx1%W>W5SSCj z4dqtQuHR=8vE&fr4e#M`UG8I6-yO>*Ea>$k zQGU5o_>cz2Uxf>KRLS$tNVt>~>|Bb>esy;&M zJ~sRkl1*#>Nf4<4liM}Yh_BBjhlS)uiFR8hc=;PSRj()u=zFd@%kqy8cB52wl#4n8 zp*yqEsa)wmVw&X^D@2=eQ!CtKH1`EVRSCoC5O#-IbxBp0Lb24%h1FMmP0XhD@6$dWEpA7vW&Oe8MkyKcoUzY!l1+B5=R3KHI4;J7e=Z` zC9L2=NEd)7zP@Zy_%>=AI8PB-{H-lYE(v&svn&uQxM_SvcHh_eF@wSd^JvkYcK~+Tu8{p;dAkkaNahE**&S z)go(--f-fggy(QtIoE%rqb!YQa@?rgi60YrZC*KTv^!1;|L!Q8ggf*gRFYePCPn@U z{1#-UFur9)vCE+22$p89*M)%`5w}<>gLndi29hZ@t~ls>K$M#|W-4N4CM_`>ndDTg zI|HFlf&YgR)CJDHTdv~)Pi1x-98zLCDoy+{)pcY4UIc)ovTY8m>&fZ~UYaE6@a;XT zczU_XX1l8Ygy&Hq?IQ&T=HgfX9X*Lj=o~~1O9dgtsvSMUb~W)s$ao(Z?iw9!Xv=M^ zerV3#*AM?XQAWe@IoO)P^iS`}F^l=Rp3$b(pbK#tY%ULnmn^{{CSK?9$OHKi_SI|39=9SAs5V|28KZD&9u)7W%h+#b>45yR0h`M*p>h%wP8t%N1< zWparu5NcY2&v`ZHxVb6ju~5!lCj35T&UEH$=JlNy5lx)<6styv@XbUuCRM&~)RgP} zg{kq8PtP~gP4@^vi|&xhsr}j zMYq8v-u(*redLhdm*ae53Rw#PrgEQ!X4PSM#es&j@}z_Wre?G6NIbT`Uwkt=R?m=k z2Ap6(tV}LnlA=BPdw&CFWpi7MhKTab2Njz(<=pl*EcTE(Or0 zs{y8bB|}uraw!%BD$g|TA0rHYlQL-SU(lN_$&!k*Jht)c*N5#v-5<_x914-pj(%??(b=~{i6_a#@swEMl?cfdH%J`(XK z&$N^z@JaZ|-}H3Xqe1h;ZdEiXMv1yT`A-ySap8j>2FIUy=Ry{bvEp>W5MxRRd}Uxlx?+b%04WVu!~>Q}V#<3+ku_*;|-78>arI&`}6 zbvg@YV0#2M2)Q;{K4#1abf?w13ZIyb_0qZ^X|=* z+a#H9u^)TY=lbK-Ex9fqK@2h<%Cgo776=; zm1laSD2ODzt}~=j5__8ini^fOCSyRiT;)|8m`=S0`t4+Z_x6eP`x>%aM{S#ctz{<@ed}$?%Vp`Zp?nqEx z`m7|iO;!w71}hPYn?Z>SU)}zh;ozwKs6-jrtKPz_mjVY{7jk1U8oQ@3x?bdJuNFmJ z(~~#NrUKn|YAZcs4Uyr!b`_9|nzi^ylB_p+tpbr@70=v+z51%WS_Hfp?F1 zQGCTVV8BL>9^Eifn$amOAm!*3=~g$oy9FI7r4pimqN9;=gi?wlL_|eUR8-ve@h80Z zdEPqroZnq({ZEs+^5=nwr8f+2@WX>zS^rQh;F~z(?NW&ukn+rBN%!cI4yl_#RsO$Y zEPib>he4CDc5Gro>@iQg%T3)U=h$23kRQYy?xq#KnZG)HI=b64 zPt(<6A+4HOU^f7I2r!k%e?)kotg{pn%h2?E`7Qyr9Lx>b`rg~Bup8f#OYG4a?s@0L zj0gM|MGl!~$AtpAg~l>j=roe|F_QFxx{mG+RSzS*!+{!&^C zGe(c_$7MXHm8GHMGEj(h*VnQ__R8(#wH{+`<;O#bZ!KQSaQFJ3oxFcFQ}}MkB)N!P ze`GX^I;f58aBp_U<_m#-&>uAF(s?OVzbEW9}QnO#K7m=u?f815`zC&?a92 z&&Qd&qYDB=B0vp-?pGY`&CFz%rau1_Za{aPO^SfuClJkP&v*UcRH%_kp}^Vvj95Kbs8QAX4%skUSqD+83uFgr8+$aV*5>B zIS+h!y>V^$-_<)wHR0RzarmW|M8ST$ z8(53n%lIf9pTxnpdcJ-f6BKSMLQtbYFgS3)Cx?3QsfwQ0_rT`&EDF!e72ZZKPR1B8 zO7!3^7%+&i`yeDqQ~(&E23QzPjsMk!5wMTWD&&WXuQs4rbk*|_Mm+RPrL&Te;@Khg z<`M-_HB#mV4=?nziKRD)v{$%I*cZ1jR9m3#P6^(T#*TM#7wMhBAsu=XWg@xCk8MLf z)O}Qv(EO2tux!m=hP=N!p<-g2EoI<^F}vU>VDu5~C1ZD$u^elF;3>s`&GqhmuPk6JYY9KMIv_PMU-HW7x~+ai zQJN^+8d>s1ILTlc3`=HSybE9zL!#Em(zc*rqehd9zn1w!`xm)w#M~1==$1W?BJ4frr8m(C~O}b)#PKSL_jlH`3gs_ z`sDp-?J8OgEYkS4AbdT#td+W4!rdz>dg&AucL1|@O3qby!12%FmKZf?~J6@P4Bg9nW$9o zydGuKs>RURMcZ6IG<22NWCnxrBahI$ZfiZkg8u?XuGV2qVuFSnIMY);;{mB}-dkT0 z{zrh*zFkT|<`Ll9E+9dOm#IJ?zFB6D%zp@I)SaCwhL zFZrhp-?|~}==Og7wa5{`_O5Wq9n7i3N^8b_pYLU@vZoRPQ++8uA&8Lm7N7{cx685P z)&&%!^%JSsM>>ZUdhr}aUyLd=2fh_V2Um3@FkH@3F)G|$E`marg>qh|yrj1R$ORU2 zf@cOj^zfg26bm)fyMqmkUTPz-ILX+rDJhJ*#vs-#v-#@t(5rp=- zf%6#89H|b@(^SeV_63;oNYanxG&GrtOG)qF+qD^!5Nje7UYDF%l+dYr)+_)jyZ!na z|NhYx#e0k73*SJ?4bzz!ol)FgF?QsKA!o^O^s@+Kaz4O{QOWzu>CzVj33Cy{{- z;#CZtfUcsvOR;w%^Og0+)q>WESA)LndDZ=#YkMCb?W-0?{DaDj`y-vDY4zqwoZn^j zexZoqqb=<|2Z3)8KqNCS?qPeUABPdjRU9t|WlaoAS2(ME*8hd8uK2!JUU4itLn@G{2ZS$g5y7(Ih zixQ=O-wiR%OV0Lb3zfmmnw{641o>;xul}7KMK^NoYqZ}U8`p3~1*{2pNe-x}mqB7@TR#wPWiY7--77!!GXKIw~*NH&2Fqz5(ex_yb^Ag{*|-uS|q-*AVGhTNNo5_jl(j;UZX8@TCgqy^Q=6 zhC)@RP~us83M<{M{x1(?CC8CsbRSHPBWLNZ9Kj*_-(nv?V+@^k^R@a7wbeULV#Rt! zc9_VGJ!!}nt2m~D^GBf>fOQXUPmbC&)Fq|6?t{VFI4~BEc$f~o+QoQf|JOr2I<{Va zj6|QMV4%hTF1a>Odcag^IZv{g*Cx=P&JNHR6nh>RW4sF?vR*2}CV^=S&t#akNfJ4` zA66|tBw9-um?t~>iEMs~;wKeV#hxE2!r#qaH&WgElRyNPCX4RJeLqFx(HDrg)1pi_XqgRXu(5 z1oss_nu7LGH940xD96Z-uoNmh83RwoxjjAN{SK+u+s0Z)z< z{r0mrG%(nr`6_y}+W&JXpAVgB=(wyTw*uX*T?Uqe2_7E`?5M=1 zXMvY-5$YrPUAV(}lb|)bzz=2<*eX6z`@}COac4SJltTLP=<{VjSd=4~;qs@sX*}j{ zkMfmt_b`1%f#B`M_c5{uLID7%HvlT#!&GN8FJA&_y+$7x1uMbf!=v!-Ie!uUg(@it z=V}4Gc&TD!s4V5*!!dEkj3lLds1POA3&m{p)*sF0XeII%pI=(k7D(!KGb6C%&Vqwy zrDP@2L6b8OfwT&q;0-1|zEM&aN0#Qc0~* z0h&f0*q^$h0$`!v+ufxyyEBNKnSpC3O#(%k7jc%XiaycSLlj&IYXqxEkYAvZl%t7+ zf%)^!G|3N)2S}pU)(q{8B>Ab#TEm;=bf3LfSn2`uYtJTjI(GiqAI+P zBWeT7zR@OnHtkNRc1)Y7cdSvp@#UM;WBzeNrZ+eM2uDAMkA&c1j*K(=jo?2KQJoYp z6yS+1a0)5MosJ0d5K(9$6p|^YdL0H{7}UUw&M-}u5LFtZ6 zgXrFeJ4_60@SA;FR4V^kgat*(o)}OB& z$*PZH-3n*hLb47EPG8#kv&9)Uyp?hdja=mBGeXo-=iD)>UV!<7K2OES=&yYc2=R}7 z8hy%75xvO4pLiD7&kMlp1xHp>rwr7)ms0DNe$!TV8B**NIV3sn{BIxZbnM6U+&33<#J!lZuQkENgD2$!&Vn--Ia zV}Ub9X)Z4~%giuk#kjm9C@z5`e|}6j!0Y<5T=QblUEhhVqW*Np0OIqA2|L!o9fD6) zr8pmFpe{swq9V~-5ijov@-a6gdZCl+0~hHGWEmK@%lp)+X3F2rOQ7n5g9b*a{YCsu z#=lp=F?(`-VmN9x0__EhGFK>MS_>Z!Lc%diw9QrYP>*)t!|#*B12zF156T(QNMTn{^1yu{HsQbYsX6HT#wW8F1v zp|^Hl&HZSDq1jCf%Poc7kfZPl$vjSJ8f!KdXY12c z`fc~;zHyfdn0&2h9+PNr&nlrZUe6$31og^DDpN)+{%fIcQi<=Eukrs@eJbZ=Y91$; za<e{KS87IKpcdstDCO1;+m`;E64b0S9-M{j8MWo>M{;)N=B!mFy> zHKsS1?1Db8Sxoj(#Qi%+L5)mT?DwCY)tN&@?gQ1RXR7XOLP&Nm)EGw_StHY24n@JB zDlAZZTztRl>BWC>#(HJFU*k>|y8W&>DgY04a!|dr+XKP{5(459-MD-@M#@Hwco;QHUoWSy#I2zX2e6{euzkP?k3aOZl*IpH#ZiD&D76U*@V3 z`bOqrQ<;EkO!{|D=ykT$n92f~O=?}C%yee8eVzbM0AMRPMi9Z9IUWhRa@H5ck`UCD1m#h^l58+*Ue+7*594n*h*EIKB5&_XX=KWU{xz2&%s+z$y2_kLsK~~_@cbPj12)MRVyM;ejf&&F?{sZ; zx-TNfZnw4RzqeJP9tx+X;ANFujkrC)ulax-UCBIYCywF)PF+WAUbFN_^2##r4V<+_+y;0m7Jz-JbQuH|j30}2*cSHrKF+rb(kemh_)oe$vXK1;}_!nO6CKe=#h{xX(h>`+^VU3vu98YZ@;L^a0Ai=cx44 zog1(n8-Os2fJkf}dQFHjUy!ba*xp*O#oX35gYbMj2K%sJcyGo(y{phPRV->*qn)kP zJY6p9HkeGW+%lzpZL_s4p|@rJLip-(^r-S(>kApw+cMV3-a52p$$!o%(IJO@;Mw4IPKFx$n zjU=5?>W%VFzoas1L{4A-8TNbdRmY0LmATmLh3(nuDy;MEelkfUyH+dq=fki$!-BfC z-VaYVM_qr0(pD0GPQAc>n6J}~+^c<2q(54%!QI&)1gW#;*NbUdDi*k&$WPw*gsh30 zDm?udeMZqw^Nff;$(k3mVA&rMH2My#zjFmClrCmLh?P%Rs3D6#SW-BXH+X+EUErBy1Ii4o(rBQ@ z<4Dm53w488)VGh3MJ7}`6l;7S#m)rR3K(ONJ_D5a+FP6Zl{;lDzqB#`=UZm&!R!aO z2}egR*_+6{%HR#}%y#4rZXE^yotukI08#OT6nc-KbP$7FS_~&t;VGel%}+bluc5e( z=u8vN!5Ek|=1P@hd1Y(ltR&=6>dpA07l2jX|0FFA%>QC|7Il9e+2<+Dp7i7@JW*N7 zQy`@aLD_ALhST_xcDpB;)j%D{ko$9wM!RF*6i+fw&=%YZquAqMky8r^6Wl?8Gy5@V z@p1eK@5`OvMlah*)WwrZU})j3Ia9%;55JE$g$T286GPv>Bq<2fgjOf{06&3QDRjbF zN8vOv$v6B-CtHRrtj_3&F)q(4FBDHlyzrzZCEDG%*F&N7}2Y|@wiu+?b5 z@uF(7h#h!YxsYwE7?LG%MqVh9J}Ckr4f9-s7cCT+s_jA!A1>Qnlcig(ba<>mQ?(0g z1)5sB#mNzP{o(kDRmk#XQ_rZwI9>4XIK@|6 z4!jaqgkxh|rJD1PJPz8L6sC{1EwN7m6|DmCX@_Zy@}j6WS0hhrIv-5; zm~4b}Og`HXh&m$kMe?Y`xkH0U$L?N>=@D zE#J1Cg3fgYkyF!Q;7cLwX`Cz!J4{bIHbt=o?4nG>D`k5o`Fp2?UhsPFd*_Oj=G8N& zOPUxd!3~lhg0)2{m}I~rPS!wFM2H9jcc(H}K+^8iVN$u>L5mm|Z3L-wRgk8h^J5)#v$2ilB!A zClqS1dD=N9Dt2Um(NAiP&JiiLci|$&r&m_zp})|RZWQKPrPeO{WZb&aXw-f>e`2<2 z=_~q`cr~f}7Z>&QC^CLe+v9W&PC}A^`&`!nC@eq-j-;;{{R1(Q``OKs{Lkx7x|LeD zK-FjO9~&;220yzwUp??uP^wn?=RBLQF(#xcQUYeOpQ8mci>7E%4PRz8r7}exL5wYj z>9qqVqT3xT{!T5v+C;WA@HI=~vR!M6>{SyRf`Z)>!Qh+*s3nxd6u<`HQKAyNNq9P0 zd?3oLs~k6k2Si7W=uG#|OTTSoaHo!NLQqwsUctG!m-Ep78B~@?Z@cCBK-iS0ORj5o z3;yoP)Y;Ce_QYFrKby+qODN9sRH=7*c9gD+lgN-L3!}gHBK1?U$Ss|HeddJLIsxPw z5ANqavvyIiliPRRUEdJqCt9gc9wJm9`xSAZ^fG4Nm_MrcgZuo3uOM^8P<(`qUR+;? z=a(JWhlNR&rsdnuAy5o%wdDG+dFW~2fTaiRVDUPuL&>;OiV%YM+4yuxa4Ji~Du8v# z5IwVsGV@I4CPl(;s9Se{+bLtNtfN}J6 zrAuIeOk#Zv_(P?BtY)x7oq<*3A8#%bY|4;$wY%=2SK$nuA=;JfuCP~?=O>!Vt>c%$ zmvr2YNA__gS+%nzrpvCMwa0oizjZF}>+Ce(xS-YlHe$9$?%k{U(#$FucW{Wnf63oU zBbhp7KE~)o1r;)1pR&PcTdl^wq77dmG_wpN88P3O?&7;-t9+BB)^r|98lb>6SPgsE zxz`H5a>CpIW0`udipvjWEV#4cmz9>ct>z=FM=qGFG~P~kpp&BZGQ{6XQS7WFr_HzO zEk}#rt$JY<94LRQ^-)VR`f-TQw{`nj9HHl;7}JH?CBW_@j$?V1Wtl)?!h(G(3+ErX z-|-_!Y6AjYLi!1z$gDJeL*E%fT?IKG?n*S=*(gw8Iz> zAdjwR8|@@xG9+#5oktjU4_bJp5T^_-geLx+M%StB&M?^P;DU%ntk3t_4sF#N9qvi8 zw+D3-O8=Pm#N(yDUTn9gQGXv^@OqyEm+EEdfw{dC2+Mx22l&RK3jmo)rU~UqemBrm zH<+BUS}%Gq;LF7(j!nfVa$R-uX)QJLJR|LBj}j@PwA~gN7#D?h$M&@0dRl>SpOo>@li|TU+M;b z*90;I4Zync1xlTs$89LLlyN?G8CRyHW3yMS-;KM#M)74>Bc8==m+O5JX{n6E@HOiPJ~@`~IW|Z~-D*xszaKQYAN2LcXY7IyH~^hP$Ih z0VaM6kidfkaL{Y8IQsqzVrlH^M0RD-7;`)KA4Wu^nX0!BoHL%yVg>4BXd8$G_`e4R zNO+1aaR)?bZRC~WZ(OlkQfW(Z z6gzc=OMz!pL>$hh=D!}rwbm2*~Q2{TjX(Q zhS9k3u=`-%z}8DCX^F9v#O`766Op9IBDu8`=z4_D?>+6M1=uxX=bbIVoOGWUk`EQ7 z5Jk%RYcCLLjJ0mbn!b>AG~!D)qRZT)3;z~=dkRMFg(YJmxFG(#^+0?^B+8L+#Tmf>cmv2k?vWNboB3K?d43iL#ku+1*HI0bq zbe7mqT@J*=Ys5SOF^YkDV+tL+!uDEZ$=kA87+4~Ow;OEs{ zl*&YD9)a0F6(3-^=-!K(#zml+ zeu>#EknV>lF2BO;%VPhi(NmY$mwrI4i=$82tIw0NzoKn|N1zb~01F8~trJIN1D~8N zsA&x(X$xu{010EjGUr=44Jcp4nb}Y!HOyk&Rd^Q2ck??}E)8W53qr4S!^=Qv{r+)V zL_$^o%XkrjHCtmCP={7apPO)C@lRifO*ejpa0O)8kQ_%AGp9qQk6P3+* z<$gPw6ahbTI!zDry}TgsM>shuT)_q!KK~sSa|BCEze5+PV{Brf4pksMw17R=sU2DWJEwmOV$s=_DT~Vzm59{OK5Vx-L#5**A z8W(?Dcx9Q(xe0BsFNt?V--_hQwJRL%V_~5;)qfwV`2%kq&v*%47kLtD(2VHYM)WC_ z9AC;v#$|4Obe!Gh8K_4puF1yXGX{rCdWU&*MoKJZTv zcmw6#APG~EXcyfGZm>+b*E4k)w4AT@XzsQNrAJ6WOi_O!mR7BE!3Kj>Q074;jWY@wZ?ndXKqQQ6iaOoLvBz~bC1=B{aMB+5cGgX zL>Zz=(R3J)o`1pXYE$bFf%_R2Ve%f){~KZnK!Bqe_x|acIdX~K$b}VwmSaRXZ`W^U5xTceP8zbk*_6GA@vCfIazMcQOZ6I zV_Wan>T2LAj@+(^?3L8ph`Y=I(>s{Fez8X%J*>}_d09T#RYpYQIIdAmI`3OzW32dt z*cPzf3Q&@gCypab1y)JX&Pm@hPh^H!d=?4rU>k9ERonHzaaF^KX7LMK1_(U#k`L5t zCB~iz1p!(Dj=JxCtPvvvxBXha!s#3dbk+cXH>JgNn&oFW-QOy@uo+2)%RcElaoHqw z)kmqRaaVqS;>x1LDZ?Fp+aff@&JUVa^h9lVG~*=Hl)*jJ*#*((-G(pXv;y3Yq-X}T zdS^O@MXHy!7Xdl7yH#*}e{Wps;5-I)pe|f%r*JT~KE(wFMDdl#+^*lLMq!RDz zb?M*S8?R@)LEEfR)Fnrbo(}$vdl2$@P@-q>X11FIHBX8Xkntj*F9bCB>G_al*IBr` zdxMRMm-}|Vn4<%mjH6BQfOr)rz%BrO`?uDGhjL(QcaxOo`bNzgw;m7`a#VF8dG;Jh zoa#oQvm`*HiqNi(QndzB?z?fow&$9+;D?c1A9&q=QxFx3Uip)ZJPhp(^F4Aw} z9hq~YV3W(g1(GrX&W&}U8&ue<*O_XU?>Mn|P$nNk?ab#jbIax>F7qUl&KaUY0ue$S zBeZ*=FRmZ&pgs(uygv?XOp99gpl}qR4q5aneFLUZF?Ox;WKb#gcjZ|B#J2-cg9G4f zf1bfXRDxAg((I(^AWJr)dEReouH42tbxKXqP_|6f!4NPx4oIg!L6n&2MHmp!)2!Ab zLm3jV>`5!(WcRaE;m>a`;dH~(S#=41?GONROQ$bQ-{>~hoOzy06v)P;c2uxD2Bg0r zGcx3bGPkt8Y|*d_41F+ym?KMXBshLsl~D{BegP`Y*~qw*KK#HdvG7X?n^z(a38>xG z*SiAWMs&u7Kc4?S-*qy=xU<&v(DFBT@}CsnSEB+Gah;U!=F=AhtYa}uJDs~Uf7npH znH9pUMZ!wdb=*fvk-zJ@7=y}j>B7$7Jx;C(-Mb4oytQ7J8(&&PpQMuing2EIN`;!m zv&o4EpCSy}Idr)QH=U}s_%|soOR7UGD#c6Mb}?>`pDw)0mp?JchIXgCaffgK(vcDv zGnfwtz!1W_GX1N_Foe;d{b$K}&iib1L_z<;Qh-U!kWy}>nNnTF(jLXJ}JzI|5 zJ0+gw8ylTwm-^-^uCCp$0rrb^XXZ~-&za& zCW!{xV;uAy9){)5jKxy+9={!ve=(LohVf&C4({HY;=eBy9I?nhkt}XaoOjdViRL{~ z9=dm*Z@V(^Z1CpqeV)igLyAzW2}B@#UmClafN0X?+I%zvc~rZp_7<+SAU>YU_7-kq zQV&J0sygfh9*H))r3M8k!-Me9bYv_K4iJR|Xk)+*9v}s3x3COYsf$|IDP!H$0t$(4 z6?QnkCG(K*IKuq0*InMt5Cip)p^4|ch{N>J=bwk46Oo~3;oPj3L$zO#BcsXTzFuV) zygp#PhPn{zYlw>^Iy@HIE(G&K^QMU2?jBuj`cU%tDlM^7OxEJr92ShyCTV%oU2}Bu z+Y%Z5@3$ba*>W%H_&VYGk^7zNxjH-bS*d@MMXr!0e`PI$;ZO26?8nFCgDA~ z|8KR^FEQ5kQp@AH`(j8<@~&DoUq0S4sY6%lDb{1&lJlBn@0eiizmcwo0>5f4%GB5C zA1D8^6G%{X2>@WAR}&k}K8!1TpST9$X>WM<0mZZX-8kyML1SwxdzEx%q?C25S+T+R zFdL5b=jj4At1#2Fgs<2|^o4OAYpDyL_whC|Ul(^98Q74T$u90#i`yC&W#Euz5peIZ zd3Ui^Bj#{-ZRvvzNk5%g%yqeyay^1Nrg#En<}(c5R8QZT$alQp&^xHO#6Hj4;oN&e z)mOZexAiK#DhN!nriPT-LRCr2E94-B@n8QV~^*3Q~?RqBn(z8tH-bAw^oBsfH}NVaq;4+Pgd8YyslF z{*)l$R6kwNIW(t9ZY{d|rgxjXsph`k?RaRJ`diFGk!IS_xWhygAUK5lp z8chytz?7i9t@ARD^yfvAapo-wHb?eipT7EF2HPIlio8^}cITUd3C>WV&;9n+oPw;j>Y{=V~Y!PZ9(#o^H?hr;>0 zqfnZ!FLD)|l$1LQCWUP^SK{*=GBo@XBMz_Zm8H)2dncksAuK(g0C3%sDLZD}Sj@G_ zNn$XVq875gp<&kv^F_Gt_01v|P=ZCx#_9x|_Pc@thaF-k$0R3JDJCdyIj zFcf{V-52NSL8j6x-bT)5Ppj$$uif}lj9AC1b#{(UH%!PXhYkD)FVJ-7z4vIvJ>&vP zb4us6Om~GW}-H!;1{<*T>YZR`tW!@5GsQL z9;^n?;mh2u_A{!x>T8%%G24lt%OmZGrY!_y3V`w@aG~E=C@3D)F+q1gKou_lUAVzt(Q38;RbeD$ zdrROCGAo)tOBq~a+ef23oZ0PE(m&x0e&)=}-j@;Bqfwj{2=3$V{#s=^08k94WATsK*pIZ%bu7O4aDiM8iVh@Q7@AZD({`uSo8Ukz!mbM} ziQzDzW!z03Vl}i6VUR?!6?8QdqI-dDT52d(X7nAshPs!8aa~Wlq1IT>5rMP$dpVOv z5y-#HR3BfoonVpy6F`^?c`*c5K^9ZfTJx{^KzvA$fo27da?5ZUV;PQsLt@Cs`N_O* z>Po^TwEoR?#+EqL?Xp9Jn?xfo&y~OsAMdguq`h)Z0Bo;+JCns{1a0h6CG9vW9t5TX z{euj>nd+rli%QBaDjK!ezlRz&0Rcg1BY<}~5K!v{h@udfk|k0%%gJoRdBBhpe{ePF)tw~@%L`WM;v#>wAcb8s%i$U**lHPraS&d10rV?svQ2Em6+oz_S7 zxqee$HGY4(5bbMcAs-N-X!)%vkVLOPG*h%+Q%%G)+sg z$XuQdW+(?@a6-`H440rs%#lJkPr}_wy~dw(!#Q7$rvd)gPr&+!*Pj0KIN>1sYX+qg zYjfI0!nKOORA-D`7h+u+*xDpLmbD}>AVm+OUulBlQ{!?aC@fJiRr3Q9pi`}nIFL15 zc}l$#SySv>GMf*xG{duQ%M71+cA0XGlW0@&=Q7jhIA8YkM=yRx^_0Dc9F{Aq=L?&_ z(65CmGaE={sFn7Ds!xn@Y_>=iyNA=QA#cgedl%ESNV@9BruNZ+th#DS(kAk&GQWji&^?JeiFN&mK;_08`-D9DG&!rh2)VL<~JdcMD(qbWjB zBipLKH6^LZbx(ORTklciV0-I9ly#f$C-GYxN~z;>cGc7Eua&aYnzrQbrMwEHqk@-B zuJ;k|4TGj!W|=wO z5~rjkdvdIke9a_B_Wvd+EhiPhx_#FKYZGACL{{G@ss#1TUss;jt_oQC0}ikLd7nea z`IOH!j=60h4D!z`8(k}GCsvcTAm}B2P`60FGOwQ2J7yWap*Tu6;KNS9PkPq8sPwLF zQsg)i5xm2OQhOFLJp8;c()+mVdvJ-Y*9RL2kzVK$>-VROk z%9f*-xYo*`9v|15vnfT5h`#cZs-`jJ82XVd-=6?;_%( z&&mU{tH?4X`_GjU`%?q;f!ZeK>zOyQz!yR$MuQnJMA^gTjOPC6FXZ1J6(w7 zkFz*llDUDjDFQE2AKeOEF_7~NzPHjdID*epxP`#67ri@3MPQH?jTP`}mE-lS?%}HBJ`qIm zDg4N^d9}FLFf*8otvp@ib@(h%1!+*x|#R8 zA6KjMv*~5C5wqEVNL%A?8$Ht8Y{f{8Um+d&Y}rCCDeed>VZbaA&HkBcoDx2u=S8Gd zW9WU1Os1mmoMX};(Vde@93c=*hx$&nt_h28ISy^Oi$VZEV7Yz~zb2BP2?z9}2?#UL zyKEwwKtz+vUpD}`kOCv|AV4@M0H4=cYIPIa*Zt(eOkmBRa$7CKliu9nmpC4_-*N)m zMR%l7A0JjQb#n%{O-CQYd>>}IW1%_PPos*=JU9CM%%D-!JGoB{hM(N=Hp}2dV-$o_ zG6u5prvU+tl4k~njI2YdQbSdFYKy7nf=9&v{$S2li7Lo6Mj>QZDzdntSg!~SzFY)y zE8?p+YkrC0! z*LZ*(H~@Jr_ffCK0?q;-_{nA^Zn>x%+%t+wnH*Le%d4Fz%NFpNntE#gt6ua)jw}g0 z2+f;#vEHPfl&VHCxhS=C0SQo*TzV8QrU@sU&ktNtN#Q2Vt(E~jOMpDB#8~ayAS@vn zplm!kto?>_zLgWIRaDz1M4upK{t3)Pk|H`937ug@ji!JL^X5;$H{sR_9b6t$>3)GA zA4w=p%4P?neSpvS{<%*k&qnqLa9IZ~j8A#x20G)@33e+jmeTR`8wGLLijuOtnzPP% z6}PmxX_)%PH0+yFESEj9y4bd{%oe6U9sj9_#V~Et$EccylCQj6RGCnp8;Dl>SX?Z% z679#vgdFeXGf5-xa*!;Kp4c6yS~|@-qo@G>R}0Bs6y=WFyFjzzZXod)<6j|4VgM^) zWXewmkT9U^lg#r}7h)A2$c6{9aaKhRq zyT7LZ%Q0Ziz3g*92-BHgt znKiha%6!a#NqbSkJo2i99Ri9m^x&@+A-$mOcf9b~6eL z>_4$fVtOtxzOq?9Gr*^(Kh4^wLHxbbFXp!?WSg>=?avoIB`J zMhu%ylMwW7Qkx+~I)NT*G3fhg&vNml>vH2Ae>@+#kKed%$u_kz00FX52~H;q0z=OI zXKV>N{rmj0LP${7RXva7P4gR``#(g4s$Txq9ys*NF8HyTil5E<;mPSj?3KIXHt3#sU7U^g6xe)86RaYc2B5yfG%!xdP4ZL$J!^pVZyhA#K_iru z9eq^=nbcR#9uCT&-fqin1tTp!$z3f$s^3mM_K@(Kg@sS0 z+kSZ>Q(JJEP2mZXf(PS+v5va}KM9;u%q-#0#qc0+ON_T11<;)JpDPW@{4&I%kK`nac0K(-lPK>Ssw^~QIr9u=%#Fv^E@+O?ON^m z3fqE&PNgfCR@q#LhjT9ME<{e`LBXrlJdgKIH$uj#FqKymKd;MHj*BkTewt>z_=I!r z{;J=CEJV4hj^@%{_Yw}!z!0(?iSgL_zme5{!^bHBCxDP(IY|O1bLS0sLnKt|jgsTR z?;_Y$6{yyj$hvj-m&x8n@rE~VnjsL4^MuC+Ea@oYT2aPPsA^PK<;cce8N`EqYTsWX zvv=1_YF~$nIay$eNJ4hDGSV+V*7G_K^s#bUs{#>!Md#&t12ib{Xw@UK4w>Ws7ir^%;@X) zr1{;5y)<36Bagd#cH73jf_~%8*1^}scDFBu4@hV2_wBZC`gU-F^iozoHt%v`{qn|L z>YZqZd0zne9udr#Pmb0RfV2?43s)=}Oa$JUDED1adu8GQ{Y)A2GwknO6osfzuecb5 zo^`!Ih5Ad~0ZPRKC09W&!ayGJ0dpT=cjuOo=8k4QSVNWNmXCOZ@fXuNCy?S}x&d2~ z)fTVmL%$cWt3??> zsy*$L}7-b?wo0U3+uQZ1>tEn~-$v5oKkR>Rx-hHWgiaCRtJH zd(EtDLeeEFJf9y^Nt~j46#I==w{Bke<~3NM;Emt~vK-qQ zngpVc0WAN${rLH*qSB)1>3raorj6z@?8V!T*?v>HhhP|9sw-(@hyK$@laYG zQvmRIyMl__4aGagH0C0h{U(N8>%^ze-seYgRIaccXKTDZ>pVxe zg^3LCjkb6u;qaSnQ~F#nie)@JOn(W0oB9v2*9rnk3cW68|17V%seORZ6nU88FN>pU zIO^=3yEEqX`rwo?e`)>ZZf{g1ioAR9qJe@2#XSzRD)Z*}wJUtK^?$UR^b(lD9e0j& zZK!?GJ_`x+JK*|7=9aqCdL5|TVi$e&PC1_nT+IIPa}>So*X4<*X-vW$#aSXAtU`z< z4y$<7#IqEG;}!YYoTE2*U3t4e{*k6p)+`FYQq9V941aiw*rnl}F&#^7$-umC#r&s%6{w4{8M#C{7EOED56Y6L>~tCCS{TB`mU^=xw;m@L)5Gj!7CHz}lTS8bPBax>6LQ;#ZU z4pKMI5i{-cHF~fCN$ZrbAp?XB5|Hdt7AaKiqJFoom`zYwZugaU@E8l34Fuza_HZcGtc~QjoHc27oWqe?QR0%?1j|kg*{G% zcvpcbLU#ema2)TSoHe1lCqT0Vi6e@LjbXK!gYCUx%Dk2KPp(QQenb~7Yv3n1OMPae z;(|i=il?Q*pjdgHeoKOjV0nFx z30ERy#)KcrZfAn^pQ4ycf3tzGDSVsDv(tTJ`!U(*+eV%hWh-Ir(IuCkvx4@l9j125 z%Q^FvTA$0|PT5;$@ljG~K?0ix<<n&Cmbr&!z}Z_&meh{N|MW{>2J^oZ_qBfp3%e&*&H?!Z*>mKw$V>Xc7#pV+4Tx ze1m&*2d%$0!0EzbL*N7+7+w!KIS9Ab>y@gsL@o;?BGCkx0uKLYI<>9kHJ`H73(&tWL6ql5wYU5Rt9fs zzD~H4Rp6>svbp#P@{z)djX?k6V3qckcwl@?%P~4v|2t<@Xpq0l6nn?W&O+;$9?!;~ zuLKv0L(JFOY5Hg+V>C;m>+Ds(tL|*&@Z40bx$Uf$?|Av*y!54*?Ni%&!HT}?3+VDP zF`+ zRS>``BFTS>j#~_G0eF)=fFaJTBECfC=X5B~EQs&^6y!?2@Oj8G9BDqB9lO$xeJSOl z7;D?=E!EG&+E6#?IX>^>qf)0?OE3>pJL(~VxxLi-|vF&NoSC#raJxGiQv1$ z-WKYmo-TA=u>{V*w?+~Y_>`bxL~~*;7MBmyO?PGFvOepXf3wsy30sGJ>T2?z2(RG0 z@;AjWa_i^APb@ZClS?0Tp5;9`;6s;9DjA+*%7FpVG_>D#{Qqa=jt&T5Af3*<F} zChVz@0^%E(dUUEPOz2vI4}Z^LyS-S+FMeBiUQF1HsQMWHcg9@*w$4ZXsVS&J(m;n>v8cs> z*-+ukf@6D0KW4zpRFQTN7c3|y>{}r!WYoc~7ia{J1!Jy2UAnSQ08ex^#6<4U;`0!F z;!5lNmZwxo)rJ__M55Gu~no!uNb!U5TPZ{C;;yhnv8ByD*hS^?bjspKhM3ff;L{ z6Hagb;SK28zAv){Lq2qslw|c@A?k(fsX>(dC)S0hS^piYrF_4ed^L#xj$HmL_$A1X zyl>neJr#n`8mFAG*>S)~Jb<-FN$*=XDOP4kNK&;N0NZ|zBnGniv54}G`zNWyJ?$fj z#e0i?HclF&T@n1&pLBDWkm?^eP&DX}BIns8e%m7dAz?JYq+_2m+hnwUn8+5jJ%`cT zzp}ay#!T^r@x~ifd7|U_-E~c!OZLyI`y=0$23)C*B{BF-4VWchm?N4F){FLT7Gf7$ z`=Yg#L*oyLnJ2;{2)TJxVqi;L5X>_SZVC&`qdZ?pkeKJRIikqKMzc%)z!jJd7DwDa zLk$5)FXc7Mgd@Khg0%T)#bRKnZ2*|%hWq6 zhg$betjY5uZ==@hgEvXFX5Jn)sg6KF7hAw3x%qQS@K3rkX3N$?>bxMkK&jc0X@)B*-=6_zz-@^=Rw1t!X- zF9g+w$?X(7JY9ail&st1k*S~uy7nADqtwvD5>5-fpppH3@%mj~1c*XeODj^SHGFAFxr_UzBr#Lf6!vUTR{mjWRBNRL)HQAb1d3PHyj`hbk){i@z8dx$udQLG*zUQGwApwlNBJFT>Bz^^%?^e|q- ztVH8vMYAeCFU8RL-$zX{5mm=HN1R+4XBT9(x?jHJo(W-HV4wtYh2N9dY{VW2TCMsM zNJ~HuR@X-x{F12?HYX)ZpN%SVCa`rA+d({4siK;%1goB+s;&rQ9bBt4avZ9N^eDa!q zx^9O~vTgu&jVoB&%l10REQ@sJ6noS#ftdl|_x8N9>~sA%{$)so`w-`U3Fo?PO{HJ) z%JA3-ALjx50m5@Y0lqm5PQt>Ue07J+Y&3UhP9eV}pfV_!&vcIE-qPv~uEbJ75}jE* zo>_WD`KV96{c88Vp#VMy#h%7lD)=erqhS7owebBtxwQ;I64z*H)#f6q%lm9>UR5e8 zu@2TCgL!S|sR@QT7(;$z7p>y>o9=$j#{6e6FD*Ae{!|Kc&;?=-nImY4W4L4%X=l8^ zFyxs)S$LyXX-o$=w2j!+9RO#3FABYYf%ILNGuxn6Ih;m}`nWK?OLeo{Ci-OB)$SAa zs9Bb)RXm>MmaQD%b+HBqlU3>hI~r&M0|r3F5ty?2M0)D;h17;^xYX*kHv*oAOka;@ z?3bC`T3p>7X4@@IvhJ3(K;Josu`#U@{+Jc*37&JSsAg@c)(9nwwQgFx_sKUPy+GK+ zdL)a`)+4DE2mDlz`y#*`PmjB%!Y9mNME>(?3T(U=fCk+5C*LN~`z=2(_mEL&AR8gq zKNoeDs_`?)!3+~kImjyB#mXVY%HGcA6zX4gII@5unJMPYe=##7_tb;OlF#2l#-kcR z;%c_rb+D*)kODVz@YHZreWSG3yXiAPr&2n7kXyEnn|(?VnUP5hB~qXW*mnBO#TwQbR2BrSBWC344Y%}WJ0ssc1kC>f%-=ktOyWd<3mjcWumg(az_4H0 zM)}K>@;8f_O546Mm5GIc)un;{OM;2(l#7AFSR9Z;%Id@Bd+YC2DM?cDp@8)cDS--q z1eJgY0i?@p+HMWPRIwX_YYLxd94hFcK;b&kx+AfOn4e2bm&=7tzuQ;#xF;RE+V4r<|++=PGxupB6W1__^V3gCXKl@LM7sq;fLkEZj!SH34~FJ${3lX#9-x>KENTkk^`=H{3+4MVu#w8 zIhT?_7`@@U>ucB&c8KT*I# zB+&;y%f>>a^Y|dRHhb>^kQrYQI63>yayzSPC1BE34Ij_N?ckjSH=PUWy6M!T?a(zv zCZ-)`uAM)p!}Q!`fZHel)#c7g%LdBsFprCC&Fq82-|DeYfj1ujf~8|!0`!r=MS*zX z*krnYz`2LLG7A);!!raTkw$}*9TBSmG8I2}Fb8Box{=0n)bF1_w*6j=^Pr$u@5q3S zax}tTxhm9VQ2tWBw?$2r9Z{*W*Sr4i?u*=y@w<;-EC}+L+&CO<+V^1p z=*obY#5-=r-CPfJE;rPw0&jU<*Jx4F+5l;)5`B3f#Niwc+y2QYs9t0ceO(&+TgF}Ck-uX0lXd=T{@udNi6_k~<)m?* zCl32US>oG1dDJbyaF#eq3V51kk8En%3;ywEjto3^aQ>Mbia`LTQyL6Hv?}f0m+dD( zHItrrX%0{^3RF1rBT~vh7=2Y3z#{8=mZ$&%#(PoYz)M_*nI2ADcRrTEWOi17W$Rn# zzmQSZ?TS@GEYk5w{0)jLak{j}At7@fN|_E07MX$`!_sSjK%Pf68-5+K{{J3pnB4!c zP$kF!avRA1SSN

  • Q+O)(t=(ow(nk<0G9EFc0E2B5IWm8@BEns*rk_@uzd0AtlAd zBXh{_Y#NPit<9(!y6|OhrU)`q9RM8-aPH46?SZdD);^98To@mybXafFfiZQdndk)A!_}VieE6a9txb^<%=-QFU1s_B&lD2kys%)S8M1eWHu4FlQ zy8P?PwtS)h$+@TnD7}4A#bs+b04~k64sfw*6O##1Z>t_%2Z$GjBN+r%dJt>Snb79P z4Q)q#|CYkL0aF}Q5ps)mfB1AbVj}Vl(LV}^~v!~4xYFd0?%@eP!3PTOLlClo4 zw9FBO@AY-M$+1o9Xuj?ee$%CvjB0LfZ=fTq$nf^-Swdki(7=NgQ|&CEx+w zT@G!{%BhqzlmaJ()!Qvw3Qz>)G!8vu;+P|g+P=SBy~d8Cl!Aba)NNlhvE&!s7dO`H z-r1WA_?=5oxIuWx*@Tze9ME%Dln$@^$5fw6XUgdPxBFEM9`G7_>ssFCSg!cUbrnq& z{J2cLh6-Nu6aD=E0NggjzksOP%j{zhMT(xQNOL?sm7ZwRi;@;R%!AzyI5$Pn%QhA4 z$?s($Xy{pVeNQlWF>%&U`#(Rhoj>qPD#hSxRPbOEuSI2;At!)rT6BRwVUOLHCokFS zLW3;B!h^Ec8}IH>FzfCAJGgpY_K+j8JMS+lLFq;8p=Nz$qZKLfW1Lb5tL8wcU6f>M ze`r)1I5iopc>v;K07^L^Tn;~1(7mj7@7tTNJF_XHF|Aqub!F{oxR}N=P1QayelL1< z@x)ZwMgOW@{v4-#zphjEgUpizr|tLCvQ_LyJ*Z9@wj)xyX7Pu{@sE3c~enq0kW9ENEj<*3l>UEhjigw#P zI5G&_aqtHe0M16xpM3El1@N%9?C!G~-^UfbAsSA9OLuNr`jasPqEbr~{x~i%@ggUJ z3}%Cm&GFCrJ2}?boyX!V+a@kdUP*M1IdrP~pv>q|Ry;&0VE4&~g?~NH^;(4Ho6Z~R zS)S7)_np`27bSq2P$T1l{V)4NU(MeB-|PzwYQF{!%!SWq;TrJG0vf0%^a&~N4Mk__ zpY(q^9ylZK9v}aS`gs)z;>5*hoN^Re((EL^{;U%8+XFy^v}0f#bN%p1f?mvbzNhh! z?3@%cF$1G8+jaJ|bBZF<&X80#5rd=*F=e9^G)~$j%loWjPhu4|3pzd!9)NKO1>Plh zs~Dv`5Fw=CM|+KIxr~Yg!~@&wQaErH4v%Fz28z#}4_l#6b0=SFzB;&$J9l&qbxt{K zqs{{ick9$xU8fRxZ?L|&^*Ch7KzvO1PCSxVJ(e%jb1yNOJG%N+)+24QaWr|{B+&&uaZu^+^ zRX=S10RQR}+qc!}ys?qf7Ss4rr8jXuce&;GRD4JC)m)tDLYt%E`zJe}A4JC<-@5f{ zqRns;m2?cBd0Q!&{U3sfT22uOL}Y`1nBjY&--f{=I?9ANI98;uGR5S0 z>-$TlFFBZhe0mUs?S%@sVat;Qu7r&Y@Q;_0A zHgQOaLfkq8XLT$*Dr2u9oG9zK%^2l!&;X7rcIXfj6}7j4DQ8Qx1h@obgv>^aK90{O zFjT+%PY2xIuMY&PRtReYuB4PF;m(3_5OHM?l6ug!ZF@FgO|{L`2~@4hakVo~;Yo2e zPtH#vQNWK*^%x{cj)dLRTDuz@GIh>GskHdowC8Fv^$%r;4cr;64GBE?i)o9^8Np+X zo%B&4b6b9ghkVy~tL&42Hx0xm(#?-4OfsE}xHQE-N;xZGZ*+ODM4a0RqAs}Ie%rnP z)2vieUAg%fHSa1q;I2w)jK4}|)-)t*?iPQ{VEMBBxqFpo)eFAEcrcOmafAGIeG98# zg_1}Te!}~$7%5TWS&SrLypNS^JO2G{Ptu za~gUpp4<`>!IV=Gc5J_ zfC9HW#?<)6S%SX&RJhF^hx!?qN#A#bt4^I|HF0#o-6=T8n*g5SpSXQCeM>$KWzkb> z;tM}&X-NYn!v&%Zl!xq%zDdRNL#4XaL$}tP!KjAsDgP&9qc^VN55coWrQlGv3MdVt0zDeN@yU;dCybKg~ zq3}G%W@Z&wf7;x#CW`anL4sr>lb=QbT(zeG<-OeZ26DYnO#%jlF`spsxGqslsf#?9~R_H+~4p zeYP)+XW-`Y7lf`S26My&5RM=i@v)BuLeo;%6AsO_S4w4<)Z)Iq7@{m8xJ1Hvn{hP^ zPuP=Vb@G)@8F@Dj2Wl7ifkig*bG+=_FRm*4+mcM7&2>i#pO^{ljv%x z=DNeVB@QHzeHlGe+8I+~v;?%#`T{8{SV7vQj*4}epQ6nddp{BUE@-NX6*bG+>>spH zA>0rVL=K`NVM#l~j8*i7Hb^BK-NRtz?be!d_-eFbG~+(T1YyemJuf@MP;(C z1Mv<6E`f#kdQ-n8U&DhRM3xL)#T*v-k=pL77U!$VaqqyVsjxy{0N_q>zaZ!!S!bV1 zYdXiuy4=w4zOS67raTI$N(1`gMfo*(T$BrQGA?t`SXd#K^&^Bax`%Ssx_{r~AS)aJ zL`RWGjb*;$QC&oO>~|5?Ykiiw>J_&~v*>m|~_UAbk3JfEZ{;;iP|z7)qLod<$T{)!WC_5|StxJ*Mb(4C3TmxpD78zR>ryw+V)$y?J+G)zv#v z!CY1;3Geo*B5(uz2GKCUxW~Y~Qv~@&aobaYKU2DT8QHh*{#e&$0n|oK(NX&Z*j2n2 zzlJYN(P%6EG61KWwf0)?yKQz1)eE~h1t1@x=RrGb>9G~1f(npwu&zvi_n=H-*JzH2 z<#waBY~Q6DMK2JJ{&0cCB<*ENM{v6rW|sVe^0_=MkPPDTj)$nZI%N4H3I)5RTEHf9EpTx@BMBBGK9PA>|KuWhYDe%f$`=SzI_MQ64eKX7g|zTp zhsK7>2w`uL*gCUa?YQy_6z{H<8xH&7SN^X5A$5r$JJBW`J?^qk?B%z~=R;dLQDP5n zY5%Ud`SP7Ex`|dgqj!3vv;HcGKOew+pmN@|@8Xv`?qm1<6O-xzYSB;n{?eeqzqn6Y zZ4?~Vu-E?kb+ThU4Q)%hDkgr>T(&7BN4=*~OaVZwtK21@0TlsZqF`k*AR4FXz3qt& zNnVbx2^;pv5cLdd&^#h&q|p#G0>5V#?*xT^LYRNzjM+!zJt)VUc?-GWg^qi%+a6e$ z^bLma4cD5HX!C|7Bq3>JP61*kHaLni7>~y7Nr5sm(3x2#$lhIBnhi3BVOZmFuBKdY zVH_(3uD9?OIv{eNq)hC}QRgHuLqPbCp~+}(45*Ry9Tl@2!q>vcIoyMSUO!bxMew}N zAFZ>$u=-3(Gy9G3qU9u z{L~Ub=GKcA2OLplk3v{~`78bkd-C==&AuZ2ZSm`0t^jD$1u1u9N#Ba4{2LH6fE0OM zqKfsU6KT1D&AEBILe zktg;fPr|xQ;YOa8bUOiQxnRU`7Atih;RsIc6cCflqvLZ3Kb;;U5|H+BW5t1Qx{{dR zinSd%O~XSJ5pL_q}b<_zR~0G+V>G zNsy)|GS|ad`hx$05Q?DPmF)_brqGj~>2seRzi;1UY9_7rC^2(wpPuPFm|rm-&#-H^ zwJ8Yz)tJ8gXVsu;kg^6y0{j;5Q$I5lC!ttcgj^a>2pZ`N;iFj1hOb49)^*QZLp@}l z@Q2EeBr`A`0PZu?NfX{GF6X~exM4{a|LM;7QJDDiymg!`U6yUZm|*4>_Yf4UU6jO zf`VTjVa)QGn58PRKnnnddHvIdF(~doJucGheeJ_nI`N=6WfJcK$i^XTZugG zP;1+493nvyft`m7%)^a1pObIMN;xiC0B(C4NZjpvaQEAb;>_c^PvE)wKmKj%QL}$Y zbal8Q?Jnng!0!9+pv&8twENIYwG5_(C+D63G#}(?{g2N4ip2bifN$q?$@^&}5>&}E z;i4U=#&KPZc2l>UJ7F7e+13KE#5piQLS=w!cxto){XK8_dlY|6_BPXhAFsJJfVyh| zhS8B(YnX}h*M;SL`yBufj@RD?dr}}aQf^?HD`*mCV9mil!RX-V+o63)H;51&HM0}& z@ywAP!}Wn*1R+PZ4Rr9HIaA1f8RYJo;pqZJpnXel2#Dc{7a}_#wGz*k(xF-NMt_Lh zI3Q*_D9A}n_GdHe>zT+VLo1rr?!aHiTs1x)?Zahe%}z>*R zJljW&Ji402l$BMu5|3{Dr+b zDRr-}_hRygCnfSp{T^bKK!Z<2gFRks7zGe!*T|JxSfH;L344NiO$z{I9` zZr7rl>s*|b$zh8mpW%$z!e*?Awp{X_T)Kr^JL)zU*t@gRZ`dmRI_|XPpU?c=3CDK8 zr8=Oy#ZZIOaA@&sm@^6L$~b=2C~=?lR+Xd#;ie?dGlvU=WvNTBjBo0}KXRmt9Iuic zzk0G%DLDnGU2b~nG#L!rek1T~`rMuQ2$xHj%zx)M{$M5(3;do%Uga0$9d~6$B@E|b z|M}>KYm%r@>(uj?pQwSYq!PJI2C*$5NLnT*2=}!gbgSt_+~ljUKVCu_y&z(c+GB1q5txvJ00LiaSsG@?S8RTL}d|ZwowJ+WvbiWW$7I#p}S)m*F*q7vgoH_{;Mu z9fDcvpj<%HN0c(-yyaP7@z-E+NyMmy9>_awm|K5zHz0xlZl@FE!}txhUZ)A4Vj+cs z7Oi5GEQ}nN!TV=V25?bM7o)_~$@lz@zLb>2y$+D6K#q(XP!9s`Udv!w+>;tW6_W*4 zDf=Nrvq%q=DQB#nMnX{^#EA4id4br`X`>@yzZ-=U&d2<2#s0PBRW7&6UG7WIj<3$N zPTf5YC}8AczOqSYUo+kbZ51ofFmJxuC0qt488YE7ctSugLuzDb9z@4(hmp>Zp)xayEgv}}()wLMqIAWw*|r-VsIbGSWB z0~f}>q%P|M^Q6JN$z#9a%nJN@f0Of;-e~+_R`jPun0Bx3em?h@w8}VLVQQu`eZjCK z6ck*JF+2ZmQZh|QfCvz@BI&#A3FtL@J6-EF=lTZ)>N|od$ zZllFyhl*rq2_$KpR_go0(qW$P1Z_eogJ-|swSN|0%Gzrwu7`V3*eMqhazV^A471XU z>{RF)GAny+2{)TA+glJVgmuT6#r=+5htB1 zA|v%D-k4tT;~X@fCiG`T>6Hz4E6`lOH>g-umVLSRNq+BJkF2e2ra=G`7RjVs)F*fW zx!X0}rLG|Q1Z;zAe-61Q`?}WjLS71>9vIGX<;{E~eem>u&I>vqo6z7P)6lNK*i3P? z%-612ON;QkIJWI29bO?W3maz9)>X>mTTA z@jmT%U@raoNQkt45Eu*t)S>4Hp&4f$Hq7z-*-e32@4e0_$2{*ATPqUW_AsRqON)}C zq}Ge^iFR?H7H@oB43+;SZ4dvxgqVmNPY_&?Dm*Rgu*}T2p?xDDxisG!c2$^mRVdyE zr}aT>NC4&K3P-YUH=5;j3;hX4aBF_n5YTAGviuqG-@8#mz$vnszz}*G0EMs3JB0BC z=eHgOiof}e$K+cgaS?JZeMaa<6jdJZPDim7A%;n(A5D~0vM z1fLRjQtHmZG{l7shYA*9`HJt*-(8zrm5@bLeLjM#ImnlPiY8_boIet>6fowP`NhN$AR>@{?ywRR* zZ?n>#ZQ`scCS5n&QhgWn@f5-p^78DL!6t*4#NmZ6H)5744(ThCiKg|HNf%F1;F8C` zKOqGnw+xul6#}KoCF*DfL`(crh)^L@YXVM3EOgqK`%Z(cp^#$&JBOYbmmS)iBxZ+} z$W+a>Xg@+HJk|wF$6r*BnF87Bci6<)=ogUUSv?BSAh@IXPa@)?aKRi5qmjtnHknK4 zLwJ;Kes=MxHU_%}kKmiT)#wF9?t7hTgKl4}i2d$rW=dy2%)(BKo*Dc@Pq?o*6Z!G~ zL+=mb|KaNo`dH5IAN1FKo*ll{H%&3Q9&sG{?FQzr#JSL(-%80LJ#Uo0^Mn2I$*?ed z^81L{CCYo$t&LM)nc(>-_$n%fK~#y1VFW=kjO*SKmB;XT?F!?EVa!?^^w~!`YX_!T zI89=ez z8jfd=)-dXd7fd1bWfON(DA^)pI`O0Gx<*wFQ6{IQ@3=1ajSMyRJ3^|95XY=Am%#6P ze=lg(N_(~GW9D9S)U4I{H*Ug7%prZ6CZ+#V2{mLEe2Ct8Bpq$jQzdygQdgBA^TdGZ z&aURaN7!g;9NNcOYpOUL?gBbpNr-%vu!!rEjMzrUs1vk8d_n_K?by3rs>M0$DtQP@ZO% z6&yvw19uMl)gFHX-v}~HQJL%Yia_uOr{oQ;u}EszaiRDgn*l%%*EHUhTaDGVB@2cm zYpbr2K_vutJ zAJ-UXF9Ipp!u~O+N@Gw^+SK5_Tc$)*)zEt{bIV=$Hf}A&Iz{0EgK$OD{a3YOb-=kR ze`-{hg)@WwKl0c_8)$vts{KHuAiey7%&z1*-EtZ@xdQt=Em?}2M6w=|#g>DZrnuVa zx9__eG%CzD*p{=2i2#u%8td`Lg2Ilbd>|8RW!VD8q?10)+$^|S7O)$54=crFn=udK zM^{(V4QLS26k;`QkaB*If$)EBUmsg7imHy`aO0UJT|WyBs*T*5vg^Vn%*?9J#Ar+mt*S)@MwJ(^hqKFv0J z8>bs*Z>w<4WlZFNq@yU}mgZSf!8vUQCvwbW-16?m1{ax($#G;xB!HCVJq z;xj%--VXT7#SN7|1ci?^~x@e^&2ID;3#8%{|RE?AL8URi;&>BI$Ei?DufQ|`=3zp zA>_oK*nC|?&LbwoSrN|z>@}cQ8KL9U-#FQ;cF7~YI9#@IXGSHB7KU{A)UQ2fX3e^l zh(E4|Id7(OmC0-={eU)lVZ*ruX6FZwTNy`(4Iol# z1_&d(WBz@-t~(J8gy|3B?}sysE~|U8xsp_ia_OPo*mdjZvl*D+753AcI=fgr1BX}@Y9>-TGMIp7QsW$L`>!;R^IG3lUNmDY%0S;n@d~yG|k8?m$BQ6QQ`Hc(;3cn)1 zE1@ivb|GC{&MTA#(Jy4!-oME$rGg&SP1Hh?&|q4mc)f}ISXX;ibCVahq7%LE%Kqlu zQ&W$I+c_YX+K@=;koiWSea1sU&KC0TsbnJ8Q0b&rhW_7wU&*|z`b?$U(sAFsaC`AW zGDGL+s6tf2zjackD4?($?yovq5@~kl?A@pO&sAW5`r2-&^xbg+^YM{+qA3{(lgHw% z^EV|ZEkFJMf#ARI3gCCiBiM-6{0ax^LE_a>Tz+d;qeEnalZY%E&D7|L-1L%f>ew!4 z7I9qOErlr=9#V-5J>UJDn0i@N0JVT3Dc1$!0xZ> zTGHWhEnqz8d~>c||4%*H+E`v=4jwhxuH0~WO1OGqxNx; zx%VI*QZH}{L}XV5U0jPewR)ZKPUNO2$;YJQrvFnPtAfM}P`(i1$lDZ0516Apz|hG@ z(GCx`3yB0&@?EllMqP@!jK-62epe2lp-#zu1<8FhmLm4(yT{3QpRxT7VdJ+?@nf93 zrv~Q_Hx~U7eJR0TwBJ9`5gwQ5pX&^V(3Hb*0NRmYq>W1qB=G*AX^r}=k4kqWXV89? zKrjvavgmeuk!+Wfj{1;(H;?)Yk;}!0`dGZD_)$80fd$=ETKsBqvMLXdP#iLs zAYRFt&7eyBUS$2vP2Shk{;&27H-un_!FCTJm*`e7q>ds(_J6ICSeoRJmsE@$1^X#9 zeLYlQQRll61mh(AK_#p{j@_J`OC;y=7uXI*a(px7(6h0X*MxK*-_kY9lN^kfdM+hR zm(oEilMpv$S8R6Y%u*z}U3GLg?e)2B6}ChIM48v?g+X42e?|It@V)hTtzjwITavd)`(I7Z{_epg>Oa+*WWr+dNWAa!liM8EO6LnRKZj$-W^{qcPHJMDc8~D+F0% z4JZnAa`J76@_Sxm_Mn|zMX3*%nt$AG-54#wiOH->$#JSp;IGYDg!|dVgi}*1lT4>B z-CC)w8%}+Ar~eK%SN%;ldtLG^PjEx!a{V*DhUYWaJXF-rf737Uwy1B99T|!h1#;>F z%!IUL1qW>f7{Dj0s?(;KtLidI@r|8-Z~`8h1P-zFuIu1aTIPC9x3RLO9G%VbyI3Ow zk%iWJ1Yn}#A5EjlfJN5HgL_kqdq6nr2AXAr#`3>2gmH@m6i%`skRVA^=6X_moCmyt z#$Q7DvfJ~fjq}_H2#LtW)}z1AmbZ21^6r9-re4Btw?MTa8UgA0E%C~!I_$%-H^Z2KImq7 zK~1(|Ks=_Ph_~9%9f=_b1=Mv~`b#eu4Yc_tHGC9P{LXWwqx5-6tl}CpF1yWKvVRP+b=4NPvcK z8-{AMU%~YW#wK4rIJ*T{#Dn@IFf8(J(>(9RG7sRdY@Neh`@=1q9n$-8?`zNNC`aMp zQ6x-M2s{(n2nm5?H4MmBT(EJ=ocC#*tqHD}LvM#(t40!9{h#U7KC9A9k9{zRwBx`N zWm_x2f?DiSzWg-^QO~7%nEDeLKEkCjO-*<}h?n>cd zGCBf(scheznD(WRU-(8CIMx{k>%Zv7|Ax!H@31~Yv-}Tz#+HVq1V6ID!9F{XyvR^R z5_n5Sir*|$;J2i}>EdWfCg)>0YdJEg^C1PU1{2)!0QZ6gpXVyqHbBS9KQKc?EI1A5 z9OEZo19YCYnQnWnwTwk5#V&{Qg6=ojeB1_iAccS@Rq8X*PsUap;NU&Wo2myZ$|1bY zH=);F^IkPC^sjmERmbOUQV94riN;I?@Ie7@de5yuF9Yyy)arxMse|BTmp{;c+_X<% z-%-f)$(z1YLU9~-YIbyg?r_J@bZzR0e{4hl?fVRgA040;WiTyGyn?+pWp>`5y<_=d z&A>c|$b%^!b(KQdQUUeCcCW7CYmd_6MNtjO4<1YvKF}h`URB{hgvtK=Q6B8prS)a* z@rDJ}^~$M0mU>0S>v=zR6Fqj0uxra|?y4eUdo>!FoSHx_u_ZNt6b(|9E^tujUiWv{ z$v|rcz`8FT(*BP1m&S`}n?+X~%PYnUYuX|JMhdfQ{fgMa8x~rngm3I31UFF{o?a0j%&174k^7pDJv^c z!>vkjG}xn8e$VYDgJnW+FW++Me^$R&{*6t5bikK+CU56BddDcHmcMr*RmUkgX{0BS zTzWy7ZH_k3?aWncQZ<701Igk8ZUyRY^Wo=bC}-w}w3QExvYLN5M2esCU0kZ}NxS%! z)7pfewb2dzQo#%@9YC`2*9@laO4VSLaD68idr!gF+y?b$3)hqaE?14LmvCLa8lMi= zzpU+)p;Pt%OW;tolC^q2^x~4fn3C5syDoQ5x1hY)N7CJ2^4M87r8}!OIFvliZLUAM zR+`suX{FHg>5|xePNjb&W@-yl#Kkggp^>Qr))~UcpJSG(gL`-6$*xn(FK{fbA&Y7M zuJ*sPvY~>nuRl688e>kQY4?I2es0$LKZ?#foUQ+T<5?mIB3A6!o7ieKA@-HnIRZ(qG)T-jss;+#0e*c~G-?^UiT-Q0z`?>GeoxkXH zkxwz`A=v48APrd32{FPds|j6wq6v9q5BVFg-P#nICQ>Y+Jg(#>7gEAf5qUBN$NpczXsY+{`^qCP|8+o zoEv=)0snfbl%j=Y!5O9z4p@8;Y0^HQI{(K)KVW#FXU6I9F*-a>Xn!!LDR;n0 zWCh@xj;$zF%$~jOIQ#Y1tU{87FaR)=9wuPQBTil&I9`?34gXRb-gLTg&9(Ml27>{a z@Q0Tl>)h1WtHEALlrZ>g!u7V;HEUYn&^Y3MfK@ZgToUM72$o!D)t|~%pkkMw%bK6g zo_C^ugs{$+X48w=L-#{ix#X}kEYNhrnpeTDW(Cln0?U(fqyi+@EY2nwCov&AS0&DR zKX5-21KH+nI+sH;20gK7mTO=6&~@YeW~)e7%hJ%VSt+|xl!ikUmW>yx%BSf#lsoG8 z**sHFeD6M{n#{t%d-G3~$BdwProc_MZ|39IUvX*%4ypKcLOR!Ft;z7-tlr@b3H&Vx za5i8hcLJaC{RFrk8-~8`QejnXYM${<$zX6u`RPXb@(pihTrY@{h0?GoRPZ&0X7Rl8 zhmJyZ%>;_kmff0 ze}C7y{+detTN8z&D=H$^!Mr)5PcP{!8OB+5*CKPPM0CF`}cS zJ=#bg=b&?KYXzdiwiHeiPdxA=qNio7Sh?YxYtv@QC-52csoT(*q6HR|DW z<@~tmv&_GSh_ixKsP-LjtsEv(^#w~Z2fM21kSUw;U(-xq-Ms^|;FB92SDt*L7)JDd z5va>CD17!bM=Yu0kn4H&ct?(OI-lqWBU45*`HVK2z$y(onX7f|@Ua?G>J@!7rZGH6 z8lN=$NqVDyZmT*O`_AX;)HIRyW?cVAmX^br^Y^r!?UVH9W>YlYGMq^X(~N0}DDD?b zCk5%gquOk`YZEM6%7$EfDUlR@@@3NhPm3WQoQ2M4fSkO@=Y+keyHi69x zR8Iy0S@1CN>jM^D0E%}AA*9LIqFEtnib%nvOr}5s?(>ib9i&q->o@%ssghS>dGEd} z4cC>UX0v(4XiB}X(I52Wf?E+Pw~ZRpHEVJ38vR$_;)gTNe_!O=anV+Ww}zN|FWp=* zlla|}#_qR8zBLEd`Cki9*sr{P-nL-0qQVF+aJN5Is>_n?nq>H>m3La{3={r+Vj?#U zA1KA|DRui~A|eUvydt%&hvvT%Wo_ysmtHt}CXm1yho%F_?|2l`M`IdHH_Ua<%VvpI z7vaza&14#B;l~QZz=L<&fNn6?(X7*y{-J7q4yZS=@0_+%i9C_`y9!7#!j4ZT-uy$tnva zFPJQ|{nWXO%I&0=9)x5bi%nJAcsRoY1$k2!?1v{vh6XM)GUo>!bp!`oE+_n_ksl2Y zR1>Oc^H@X1cCVaKOP=Jd)q1ptkA^yDF(zL~zfuk>f*Nv^$CCw8f9^G!>`N-&zTd9> zGo^#WZ>66U+%5rjS`CYOwghjRw`g%9ncnDf6#NaV_Dck!(*E_U1B9%C7ix1eQ^Esf z4Lx}eYk5q6i)3fW^w8a$ttk&=RyW&O?Z!w}SKE_CH4y-rQ*)?~rm0GRvg~<(2bCF|N*RQbp25I^*Ti;Z!XI^Rx=_D8AlH^tUS(V+L zGW^AMc^^od>Wg~s#{gt?q+dZjMaXCsN8cGTDef#8if!QB z&Y@rHjw=86KHtGGY>+hH)xiH)6hZ?^BbWei*99tfu!!yXKBP2m1R0TZdG|uWwsXlW zk(SVF@aC(vy*vyAHLYFt(-Z8)wu>D!C|(J6_*s^cAXh^bG_qyMxj{%6`F{V4Z))MY z8x^0a-1)S9nTi#ep3YH&)$K|Cy%IUu9&5IkS@K0-DL=>}ZPp=J#j|% zgZNq$A)1V-kc6tn?zUc*e4VD1(Z+KV0RDGGv%w`ebM3r-rTC$VGXg^?xzj!bt>uHi z{oXGQ!|9@2a1)oS0tMRDC}+NV6ol#wDx~EkKI|Vo!4gI9p80Y{4TZbb15Oqqp1E}4 z$DOiJG)vW$%1c*nokM*{)~>zAU{3C9JWZZ2AJ*R2xdRTXC9Wt~zF5;aRdEY1A~-4i z0s^Q3{T6kZBrcnqBjV*2iEI2XYmyRmtrDcKtriY0+K=I^g%*-UweKz2M`(hD7jQgK zM~GNpdUulwxy?Q`Z*peo=}U@ngV8O}tl0I%hfiJZ`QHL@qn_#*(23h?DRRLab>(m8 z+O#E$?C{1JW%=cNHBwTOPI-z6>poBV9!orzOnLK%d)v2d@Tbx@S>viNQ=_eSz~ozx zs1kPx=4Us)QHiD?;g$G7EwmGV>ROG+$9REIG=-o*pCkbxX3;)ZcagEcT5YCXQ;c|$SWFb&`dVyd~byZFE8!M7PJg2ZfNm{G( z`3mY8jlWK~FP`Jx^#>2{V&xl>mA0s)&C)*36)wScsfT?vr||tYmz-Ab+GA{aosgkY zlj)-eAj2h7mQ|3NR+Ot~Xb>##mGq#g%wSRopvQp+gX>+4gkDjc)fqi&TF)7?i9>b7l=EO7Ogqw7tFVp zvZg!=NC=BHrZs9MuRB1rDnyBov$V?X%oDdf@hr5wRJ-`LWaB;u`C4Wb8g|c{2gn>t zzhS_YBr<%nK>kL#JeLCL*gNmm$rJYlh`j>F`J^$t=WJ+H@s*~Gh@H4vbrd2UJP7^Ij_5)>gR14rcGds=*+mP}q zaCgBVR7JK>AW8mpQAs;nTs~X52V1Pc*@}1}B>j$5mXLa_f&AQ^%2fl!3T17VM+(aZ zoi*e~eWpfNbL*oKtR2!Ui)7YS5I{&!)Xupb-f-vO6#kxv(JBKh;EgQ#!KNI(+BaE+O6ljkf+5Kk4L_%(UCbt zR+_yU#lLb%sV9#Vk_qM{g4%__`nMe@Uw>ZjSs-rp)!RjL3GYISyta!X)Q>=mk2f0j z^6lr?#N9`c?zpP0?TV;blB5DzQlGpp!Wm%)S`!6H#j_=PHy&l`-7sK_X?b!ZztQ{5 zz3-tcz|W2TBuG8BJvguU;P2V{xdIR9soo*v3kxi&D5wTO0pn<;K_|yB6k->9;()yc zOHD;f3WfcGg>RZf6@VhtOu<}WF$a!^oHarqXE==tj`dc7$wC#=3+<&sbIi=am2A;0 z>-x^o_?T3Kti(jOXOOmWx&u?osb-PU~G|{iPhu1a7tVN8%GU z>dzh-g3VZ0$tJ&@0IQFh7*3{7%Nq~1o+u9}M0E{l+A0~VsC!WS7tHz#w5^pXH~U^= z_}}z)w7g8g+wK^NqgCH%x)>rJ8!iAHv{ffi4fk^PUE?m`U{=)5(vJkuxu0S>~{b%pH=pS6u$l6I-yE@^F9R;nI^V4ISGK? zH)-A#8BheD!^-*#X^*$A7x?2`^rUjtZy+UNy?{Hemj6i)-;^FkGJ6~Z*aS`+_~&Y) z+lhQIi4u|rjUc-FOhf-_G)2%Ta$BjV3k}KPR5(rFQY;GzOtc-(Q3ULsmCS_J4v*uRVy zb}EOF5DNf-%0Bho&U<*LeWDYvqoyXs^e^2>w+p01??+$ZW+B$~VR<&+M0zTU%W?6+oN_*-Ldg6VLdV7roz`Ui0>!1MZF4`T4k7e3dm0 zRhzRSSwEkf;kj@77!`Wdw%=FjsHzrjmVGf`=+hyP8zH}Yw`yzDey?EJZ6bf)&|%*e zRB=QS09Ypdc^mEXG6p{XdHOB4J{QIdwt7A;U%QJ4&KE zs~+J>jI2L4(ULiZj@Tr8*=D%;Nr;}J^shyTcI(p6nJn`esfx1g5re!RpXz*S0nD8I zSEfqDv1XrKb)Q_wK3Ua~0NoaT`kPy6g{gJFTDT2A3;t!(^I1!{6{Mzb3u5=eASf3B z&j|WZ8)Zt+h_mVi%Gq(&#_T1b20z-!>&e$d`xqCok9hqe7l(DAoea`&fi(U{#$nv( z%mPU)Bwrdv92;!4>(E&+d*v=O*JC_nWnDnl_pJg7pjRu(PPmE8%u5@KxQ+5~^1BnqQ>s{6_*jpy; zzP;hq7vnmNJW(GSNOPmUyp;j5MCm&dQ^H3mmM2iF14Ktod9Td9;&M}+dEC~p#u|Sr+cWGD2`Hu=&93gLFOsy`A9bUeJQCG zcW04IriY~pH6HYfwyaM7IdWX)dmd;SZ_X;JZn zG?3Mw*{HRTvGk6a{3c6@QH=h~02C1~YJ{0h!j+Yt36l^0S*g(f0})PA2awR3iDGZU zYLGr95W7@s?1gJt&65jF!s4w&*9zP4trK`j3!PUf+pQaeM#ODdU6A-GhI|?bB-Ss~ zt|`mSg(WxaI~U;CvICXX{CA8!@dX#`NFU#OzpduXypgTdz$vcTy_jemHt_h}8{Os6 z%6Ge!W@X|YoPo?cA#W$#_*Vy;-K-}+%Q%z^gCw?0q-YLSFLr0I1kRd&hzaMq9hC-5Ot zg^1#X3fjdO@kH~Z$8EWdVwdk%*QLO6>2_kf)7B19cUK{jk%JYdP0oUOayC$NvW>G&Z( zE=uDoGi_4ZpYi>**nzF#h*9ZB@NCQ*G$qs_W&4$@oiqkCbOz*fU&npW?n$ezPDexO zqspMCyt;nb8ZTZM{qm-(cG_MG)0&rDo(5o}<@RFa0`@9#Y;NNa(9mN!yWSUJ72@kM z>oaJF$3u#4i_0^#%VI0)Z?XetIe~9vKOkZMeMXUx)IOv_GW{3=e828*&2D|-5Cuq$ zq_c$73%FM8d1I$8oSLdoP*s9Lq&2n^mK?46Zrb6@?K~2IGng}x*Tk9i2_-g*TAY^5kuJ1t zmJ1fX{4tbIf~foLh!~V#XeSidH*~b-`efC0*DG~*w>D<{mEuOAn1dO0c!Fy^-7S!rI2&!&RFK!l@Vbg zIV(StA2YpWe?^2A`{c=YVLHjLnACfnwEHSH$ahl~4GNn_@jbxttzWdr2KVGqtqT+rGl_X{a&6IU4NNM+b-M-(La0%d~?00T)`r#Lr;M|~`TvnmG>a<*< zZlu0z(yjgej=2@^j7_gdE?0x0ZlADvPe=`CR0o0sYr4dD>>TXjXJfWx6Z~^Se$Zm& z=OB;&t?O?R8<~hN_+g%CsqSQ>6Pdf+$#RNhz}B{%A8+bQwdoaCOmMdFZ87cDY~e2* zO#oO@B|dB9 z?73W%W)KVeveuQQp6ExxU&|ifU&=b{yLP!mEAT~E2oD&VRodm)kG%n`AIcOwv%WOq z^fQ7>RC9m6)eoGOEqvqh%E2EHtAJ(zUyjhDKsc|atwYl($P^#MFQ;-B%P{?KgTL}T zEyT~XD;=p|M-5Sxf>03>_;D^t!@Rbb<9IF}@h)d$qP}WuF z8mnexJv;y2`~%l7&Krh;N)=N{=>r6a6B^$4k_i2aND^?z7K+9?UnM%UQda z!STOn%L{z2-+vC?{`cccDu$DJl!;+zFK}oLR$S%MdadFze&%&-lO$zl9n6<5TOKc! zp?JSXDpR%ZL@G<+SbA9e`kr5!XxwsqnwZggp7b5Vg*;2~I9S;**IBO6z&!JP0$yBb zy_x|q;N!vKaPfp`ZnkT`z<31k5L{;P9lOaL%v`~hV0*SVxv>@4MK;CpX4A^64FEiQ z(pq}sJ;f%BLUjszLVvL*`#R3lSijG)7_m(V#&hBz!KNmKg?NN@R$yKuEq@(sZD8j* z(;$}DwS&Nn%Jkc|&fxp)y2h~mt(a_da+_fBG5(Cn1CR76&v24;V%pC^kkw@Hn2lMPT`5 zibDf?Ko#Q4w)}Tu^0w}Y01+S z8idHe`TovVe~ExX(c|a+5CbW<{yosh^@KA_9+kb0AM#TU!42Y*LFrE6EV2j&yVoO; z_tOmlVt?pE@!$%XI{+qF&6^8uu_9W~OFV-?1Nl;2XgdpghOQ@4w-PtCewPj#4Je#T zq#mdGEwG}lh(a;MnJ#txiO}Wh{@cv|QkeKt0aQVMYz2{I?9Q6|Zj~#gAKDGgYc;#` zcRDqGRg$xQLj2FPh@4jQsC`T)o{14vxPhq?8O3p>Y9R~pY<1%NY%xX%BsVQE#nWUI zc3$cu;LevO38I=qwaA;Y^{&RLUd3xSZN&Br2#q*Jmol<5jx|bNft&AsdEWqUEuv;Z zyi^eet1jf8<W$DG-OKwl=C6KOAO_T{&@Vi!NlO`&-a?MqrXGjsLek zVEU*iGKsmLDUo?RlXEM)A6bZ*cam9!Sz-P8A9x4=SgF}z;d~+@k13!?My4+stnviS zfvPxEJssTHJ&67MD@SA`!~%LI{@ukebaLY2hPr~$D(u{e^X=YT`2W26kp^_oR7G$z zTfl+~Z#OyJ{;`frwzXT42VPeAFu-Pg2iju*+CZi050LJ7=9pD%WD%fgb2(G~#rOUe zHeNEb4G>P-w7`rUhFsPb7I}^yQgvj6YV1mre{apV$hx!NtaEtBrT9pdsG9dQ*AYWz zWCdWPuY_H`yQB@N38Xd^G#IOfx!jbx1tVM0p5F0_LQ3k;pC6^mRcA6c!qzl=qJni{hHz9`WYQYstq_d*e<03L7m)>Oyng$&L0mN3O(?cP%jf9Od**y6U*ft<#Zw~C-@yH<;$|JHv~7!#Hs*b zaln@&C4R^swMf{+qwA$)LS%lTjf}F>sFlYnNInL5^MkiF@jo^bpF?)WZUN~}e30XH z+;WmrA&ztNxPaqw4_~Q*yNr@XdfvHHZ8=83S(H&|Nt7lk?kg~L+ay)P)}_3kgg`YZ zGaMR$mr)@+W-Je<9}4>5)Q-n+c`OAF1?PyE8*Dpy(FbIiOb$ZsuaZEogE^}8V}D$V zhn*LamyeF$Qw2T>pR0(=lXOZC`?o^5j|fq-+Vw2bnqL)Vg%VWuCiX=welF{n zSYE9a`8+Um_7Tr?bZkIUV%(!W(c+oEhf{T&-^KQ(%VymUKq+yOS-#XOZx|z8>S(sn zbGPI2H?fo1T`~-)78SN2A$RRMqMgzZw^7kJqgPFRYNpE8t{#8cbXEQ?Q#%RjK zAEeHiE({`)E}fGMxF5;wGj&UqWYa$OQfwI!Pb9Jdc@#*9*g;MO)E@;8HY=aAU&pRm zEesfo!U@Z=KL$+*9x}0|Bc7&dMLx211a=40jyj+J`S5ACFYD1zmKV%)e9V+qKpK2z z8qXFobx2z9WOe;h0+tvHqtNyhi%*>+7y83988LQ#A(%ZQ&kx6$Yx_12C`7;o7!4r_ zbmt9(Tm4Wd#L2e8!gd6|_&5cY3poF(vMhSM^hQ>Ap{G~^99ivl>Tis7b&5V&y*fzb zC>_7bH&VH{=o3v648$cG;bsnsX5w*)@eJmwn7AnC5-)53gIN>3ft#XQ#*M>o?+wT9 z4acEi8#iVqTyX+0vj&!AfxUiZU-t&tWa%p-jeb@d?VRd-$xB&QUs-A~-NKhQNaFBO zWuA1+HQ@SIc@Dz*U;~IeDK8vH9`Z9Hg@8ytlIkx2KvV=ubJ*6t+f{Za+W39dDb#E_ z-Jk)>y1=FV{Bw7xV9>h5ev3tL3uXSA#SK;d{w)OS-ZcB)J9?_zr7Q2v0VD(-V!(nf zS6JsZLL&mFh(#&KC-08`ikSTK2Djl&-WDL%3)=SBuM*G#%~Q5L=b+G<--tAL58e1X z*kl2u+_Ey#N@M@HJ`%kE6KAF}^+5_Ae5YVLY1aYHHG&SYUxx_N-s%VOgC~t0wPG`; z>&&w+kfxsl1o%GqVLzNR7xNDZnzJYII{@EAOA4jn0-gZ^@K6RIZy>iajNr!BLjN^5 zC|vx3yG)F=$rCA?7n$PuepPb0Rg7(%ew9G~Q1*5#7t6;#Jc^%z!+fU_N%CY8zXz#+ z#K6P@FA3YP{aU6uNv$37hh}hM{(@v@oo;rqz9Cq~*`>{g`|=x+lp6f&Nonz2H7dUD z$<(Tp5XP3%$Qix?4aeEklQl{#Og(l4VdSE{?s2?Vk)9LJ^@w`PEmK=7uE zl?ggsmxjQQ*iZ|9R`6|2bvEukEbhx*_BbJUrfkZxL%xq}O2tU3&p83xwEBuM&q5^? zTU}Avf-zBTgFMDO^lvT}UYbrj4|Si5Cl1M*x-?9|&U>u|{&<{H#|Y z!_2#fV&lu6(^;>P7+}saLrewe`;|Y$YFlBlM*GIl9f$CB!}4Nhv>*t7tCVCl{@={FLRDQ+$dI&P1oKj*Zu9T zGJ({R`=os1(qjR}e}_a?*HHle-MuX7z43I`mfFXy(zl#Tet3GbRw&0w+Hr(Hua8b& ziaL)qczZj4h-*=iJ)Q_F6@+5(NkP`8kaHFIkS~E#+%(=7s&xnmw}Gq*Fh+*D#(Nwt zL%cSaPN@U0xmY1lpGE-=guLvka9fk%4>%vzF(L|XJ9-U;kM_vf2^=2_mkDQ@Dp>WO zZe(<^{f@rL(_CMj$c5Y=$wg9M3;mm?oN`%=Nz%TRxm`6$-px6fMKb z*UHaHr^Dwg-(-=H2f)ue4Do5I*y)A^UDY(ibCJPwkqwLqY1=fZO73wI03^$+*|)~9 zk`q}cjItjjSn?ODy-67sSPqK{7H(u42nrI|KQdhmhkXkh2|ms4S|4DQQ$7^4A+F#5#)ZpC2;Si{U6w`39 zGQlREj>OQ?YC_V5+l?O+jkC9?>3s-7$zfzXRqdJiD8f}_vs)k5*`Pi>%l&cP?7NDi7M{#(=F1)0h=hRQbj6an9 zKhaXm(-&7B(ZSyrx?low1t0lmiR&i$Ss5W^cQ$%fgv$XWoGXIBvODfzH6V8a9_gIsyUOBsrF4n zc``QsNoapQBhrI}yq2;15j&Psh+KI>@yryFyb2L?C@_vU`~xja^+r}y(?`}c|clRs|& zZaJKPnttzW4E9OK&~N)P)^@{Qw^RjqPy;MXGtresj5JqmbAfM6GO=J52ozTe(w(b>Ar-|7g#o%*vUMzVc!^eTy zG(Hq{u4<*@Abcu#z`P!$RA;I)sBNFjB&$I>&c~Z~>zk=?nek*~YWa{*uu5JD%3Haz z`LK@pHpO>JI=vnmy&)QW9=YBA$RHuamz~O}u_6OZDygiSi*?y>7Suv<|zkjo%KG@gd8#YwNFL6b>+Uwf#CYa`t(!+OoC= z8k}P$3%QmlkeI1O1UkuAJL!Gk-=x3wt)6cPEjULKh^(KF*l^Ei_0sj6uRiqM*|^Yu zWicDz`9FjNvp}S8RdnqN^4}1W|Na$pSY#qmeConSV@u9KEN2(d>R^QMKL(e6#JWj@ z;%Ip`ic5mZn4twT!*pSChPpxWNVx#bfXs-sytb)@&2^B;9X&q1Ui+{810R=c zZ@d}4vOH^Zk3xshTgC4_wq5vIcGZq>%dR}tGx8*eU|{4Q6VDM6#lzQqddB(*-YqKH zExKU!X#~hU{ZCv4SeF@=tbHuy8P{-Tq}irV{weDo7j}i;y>(Wpm8*F5ouvS^N#1~C~bZgG7&ZB`236ky*Qd1gtRnYL^Ba@xT+P2H;+VWao zBO}RBfZmjR<#OZWB=28+wYs;xyH~%kZDF52-<_`ZTc-}G_pxVq7(l#Cb53h@!!$; z)GNbjl;(R|A3IINC0i6&-BEHY*S20YrErMI#V%lG8|?GlTb)@V+;l^l?5a(R*!i1W z8k)BI9v=y)`##D2C9G@r8lyqzr}l!(;f0mz4R$w3vLV?t{Wi#R=j5%TI*)vl%9vL+ zs0V&SStO9Ga+#o%O(8%;7vhPO>929K^~X~mN!w%*Y}d@FeG&(29|(Hi(w--sjq33( z`SuARsXOSnOorvjSR5}eN)J!o8@su;&@0XQsB-kC!R_OU#XD7)i4-=GVlSP`@5Y$7 zI@|@|rR^8#Q8#D4Zg7;SdN&z0cc$7#ue`{)m2ZFnV=Lw3u0xGB< zbIaFRyyGIC^#*KC)a#W*-ZT06ZFRWh?7dq_e|{c*dH3?(?c4wRCvv7ACY`HL1Cv4E z{jn?@MyHAH5=Luu>3D?$7@O?eDohMYUr7VF>aRl3M8qM4+eSrWP~6o~GL_HJN)nGY zvRX|Mh;(Hn1N9NrEPO-=5W*1Ii)?)$5&|a!{Hc<+PHXb=Q501(dDGXVq=&?L! zfDI$jbCUvrR3KD{P#Qan3XCFAga}j;S~!r#cw-;1Qb_SuE0f8mO5GT#w(<&sxu*#j zC?K;mLFPr__#OTt7i_<5iBIh41}d-|7mNzJ3#gUTsF(r4@5PbVSZdo-**R)@Dr?@? zH5|>eH@4AhI9i5a$yu!YrGlpwOa2&OlBMRR%hnJK3#=U%;53T zZae39DHZipo=gUd^vOZErePd_Q`=CRZWoaGZDhRDQ1`WmX3q6e>(V7>vsRrF?~e|s zi{XDZx|geVC-jt>&=I}soeFn)X}ACMhpcr^e>L>$&zxXxUhI2NX81l|fNhx#Eazah;jb>Q5|syUDJH}rwz84uv;Iu6gUYBzb}+#-cT?0)Yk9>gX~ z8XR=8E)dfJh1w2yB2-KMbJi=Y zS=l(zLer>pAn3Rq5){H3+#doB^Z#uAHS17ttZ731S*{4dYM5h0l1q^4UZMV7g=6qc z`PGU5?T_s$x=V}Z>c17>UtKR5epIwbn2r`V&j5@4#k`l66tcE1SIFW# zNH+xw#Z{K<`yZ>IvMHk9(;f9jfUI3lo|6!P(0t($6PEs|a}&hGTpFZx<%<$UM&{O* z*+m)c4mQgWJbw;=Rl%7jpIJ%f>xnY$phjo;9DqERaWwmIDQM;QK}EG(8z-t}QG@G& zqR`+5q#jA@^d6_;(EbYQauL)Nfwtk4uB~3^#ut3u6m$3ljDSb94bR>nCdNuPPw zw?tmrG=_Lie~yS})(-F3T@g&};=FKs#sjOXtMde#qo3u+6&pU0SNMJJ5>904@7`x| zkb&c}sUn)=Rd!)5U;QVwxlyMu1(-03&W4!=zj_;Ek^Wz6I^oP~p0C9vk5zagSP`-_ zIBQ7r-TW`EC3YR(VNFuG&YmsG6G#F9AEL=yHd`mJIcn{&#xKrs>%6a|N=AI@Y{AXy zCygTC)2mVva5swp&qeJXI;q3l8lkgO=R$K5@BQY(vW)?)@M|>g)DaocY9$I9BGnor zAi;B`bwcscHT@6xp_@8z0tLVyUNE>AE0ALnf1 zfXKkkAqT}iyqfK~HZJZ`SPQ9qyqxyMH{9NM2$810C+X#sQ$AO?H;hE!^;l;nOa=UZ zC^&6{;bpU|*OW~WWDGzocBPxa>7+{fv-?Rv4`0fAoJ|e|!D;lXuh&IAG9dPEQ;F7d z!JRPICR46>n*Aq;I6_z&!cPx9rT?1r9@)M_9s7876;cyyNzvtojSEn(9jhmc5Htb}w1$1Uuf#C%)agPNH@V5EIi1Z2OW~6cPgS(S zu{*BU3@T|rHNE;dE}r-cKE*a`(GMV1b0~Jl4vKo8ku+OX+Vuws zP<9>)gY25mF^L60U9#ZV^qB6rk{cXQaabyv4-+nEUfhdW z0P;ycN_%oH4?eo`2$L^)9{0OfD2|(=na?wH%2&(2{ylpp;cC|xqw?(Jd1*}N3d;y( zCiv4T*M)&vmajerLTmaK`XRm%wo~#vX%CK7<#3Ffj=%1R*LpcNC5S6I{>b{s@%`?%T^{Yk8g_;LUpa~T zsWcw~6pc$ln@S1nNGe3EA=jj&B>8NBx7~rFCZt+Zu0e}cUVxRLQ7&o>Csqs;$_)|> zT=R5ghr6<~2ksBWXMIW7`x4HTTm?w(TlvyQD6|!ajzgCBu{sEDzEAP6&J!2ER_^ zu2^k5o}60A73yvhN+bzw*-S+xAHct|{Z_hEmz-TA-N8KIm{#E4u;I8b-KL=YupF)1 zCv7CGjMC1`!=4jes5N#_=hboI{Uga{wEZLaT;y*HGl$W68>e~K(BnXRaFi+x1OUeZ zU>I~s_+V66vqfxk6oD<8kd6=Dj?rcXXW&(cHrFyBYFJudY1XJNp|9OGb;tCS>lQy4 z`E2O2!}OJk6*ed8aK-OI$C^tYz33k|zrEONW$tZ%Tvuhqpc9X+T_9sDJ~U?}7ZjEO z;K+3$1i76!^`mSgRqh~_+ScS4NCgIR_7blqxrT||lQFo%XUE{9oieB;iSA^S`mq$K3)R-=?V69Bo#u51S+(n6OgUQ!5nq^7 zj9?Yi7{-UN_4sec5ENO$W$=aeOjK%0tV0u|ZenRI_4gjjANM9mV2Jz~;*Dpm%jC59 zTaES+faj%G9oN)9L4zu{BArBK4IZR1k25QeURTDT|97D7ic|xzhCyNM;PI<2M;gYz zMtLyRNvN?k(J>^FY{I>RWQ7uVrVfQ$@XI=XJ}pnghD!JC@rhSksiUH;&=Pf+r^LXpKAUW8|zi)VLv%@b#$7 zS>(ZVr_I;tDdv7FjLD7K)HGPw;=X3aJ+q}-6+BHQZK&mhO63{SpkcpN9u|{C`+?s_ zaH1$)&0k&T6hkFIkYfjHRzkLxAIH0$hI!|7$IGhx$u!nD`zYV$9wNQRZe74~-8t#9 z?&b7irN?G9c%crC_d7xAr7GKd<~A*ps)crtrfvPt>G6nHad7j0Yv*7i51r<6U~5yS zRZdt_XNA5J{dVOgZMYH?^m4D+@Z}p1&XyIV13H+t0!6Iqrv5Kh61nxrL@>--brQ|^ z;mtjZM083Ct*?7?a^aJJN0Smn;e_WOQyJCruegU&q)S1oH6 zn%i++t7=4RM&oOkvUqP>YlsneE>Uim4p<`a5 zbF-7%VdO1ZcU+{7{h)cwx^rlUg>#BvUQRKT4r#K+?6Ig2we+nCzuWEA07Dl;LN10= z!2~Cf*Wc{d0~3@4E2ov6#9sJ-__Wnx6ll&fzG23BU*M zL_%WRs3ph)m!d6^(H<>^G{AuP3pNSuz1&|L-!gly22o(xaC51XaCrG%;1%fu~ zHslieUpY_Bxv*3EN>D~H9cP6dBH>XJs~uYT*1uK!P)np7&f zQ%%i_ZwNIoIg!k;(Zfp&3^%9EJo;0R!{!TpF5xZs}&LqaG^w)4zZxVMmhwv8R zf+j~Fk%LZT|9!126@Fm|0L2jeKl%G_kaq@uZP&pGh3&91uC%{oaN)t&LK&5kzfGjU z4$#~V-P(iR6K%63`I8of&q3$i?-?hv0;;*01TH3^dRyeuE+%Dn`qC~!^&4i|eKX~* zz)@I$fpAAkWOAtckWRl@aKq5lN5nx}fNs9z>6=LVrY$_;Cwf%faOT;-4+d}K*9^{U z$7C9;WkE|&2PW|LitKtuGWutj;`PK#i#xk`2O4Vvw&c#YA;mBEZ-nZm=2+gkn)=-w zRR3e`q<`1+eg~+zEu{hNv8caM)_|E+L;(M#pF~_wcH_vEd>|;^Z{RGdK%lVI& zt7Llfqv=rXU*g~>udjz*qnC`0%b+zx2EnsPeifa1-aA{67oK0_dFJz^8^6gaFP6b4 z?k5)OClue^l}r*!#0hl<%(^7l-(7u`h=bP!c?EK@)}LYJ)Sc5%@Z-_NH~vaw(AnJE z(6E>P=V;Ac*sFxs?P^c0kHO`(EQthc92R##SacGwu8o-p zi-SLp(Nr1G(%jTi3E*1!!wmpde?wRQ0lXM^o_u#z6jk0omDDd*QFGpcgtE+ z&-BLR8s%@HJNL6DV>-GO4FB4NFy#}4h9rge3q@mA#hwif@cV|p|19phy~^vxuU9vi zmJr!c>L{e+)aU_@McWDwMkKSlx5Rq|Bn~p3-4Z) ztEM2pUbGKO>Q&3?hQD67Ui&fL_~pF(FTwrYz+JdI>A=ghn_44(5Pi|2BHuOK- zyhnpholkm#eG)11gze?Q&G+Tc&)2uCk;LcabHaLyYy!#>)s%`YbaW|U)ZIjCWvdzm zPlwpi=3#-@tW#qu9k#y6guS>qxuTX{(WG1!JGlja@v<@yk?=nBUf?DG0r9K8DH&2C z`C)@e(duI(R;NY=7$|v#@%S95eanf`PfK$Tv3)8ixBN-|?|(y*qBVYhp2w{+KArnX zlCZIDk`V9S+*~!}?Vfv?akhZ9$AgtZXHBv0`8^+%@a_L7I_tM4-!={}U<@{T!06Ep zqdP`-ca9#R0s@jUI;C5>!2%=|baX37NGV;4N~!2q=gWH>&kxTZa2@yaT-W`%&NC?O zPKZ}hi8VF|ps7Q_AYhGTQvi^p0y*^y1!+A<(rKs#40+>eJ)v2gYJn)py4ukkHkB@O z&4%P$RuPA)z@dxed{$w%&Av!apX`TmVE?km&D0*X#3GMcKg34>N>(o-Z}N(KG0q7qOg1FJeMG3RGj7T z%q#9MKWyB%%!3dYO&V|*u!{EeNWmj`^KeCRQ-w$pDpq9C0455`~9cva)KT31GCMJ-(1*=i~F-M z5f8}Ufl1E-#*HQE#Ot%%GK6?$B{-shSxm1(p;@W?5FU8O%RhAR4AHt4_spp)OZ${0 zQY|DlOAK5p*`F)@MrKdj%1r$?8!_E0-%xzYtH4x^+`G`y)WEyQ);0Yg|1ZgoR=A#5 zvsQ@?TP=phtt!%oMk$8er^NlKLlT7Jnr4)mBcdjOOdvF9SR?vVq$Vb+=}e1)l(sOT zR;V2?ssSc%&;)S93AwtwG9|Qn1aAtu5K6_PygR5(!mx>9i*|vT0-x-n33_MA%2J_q zot~;~`uDJz=}s=frjtX*rrlger-%}r=FMOy!nQ z^DL>K8=DGCVCOPK65&P6-5I{k7DMq4I^e=fOUC&tyy6a>f%ax2N|xjU`(vhrU^bBG|FVT-G|JUCLYYVEAd;wu`_AXrrQfy zS|+N0ywW3fGbG+b>}5;$o2jGkMQWF>G3;p3Dg~9XA1Gy!OCPG?0MfJWAr9I%ITs)a z4QVBSr25_uf-l9BpJke4AciFz1;^?e%_>o72M)%8#}AFMI<%c@*SL;4P0i=wokPal zgW71sx~DD8h|h+t3+XmD+N`N0u(hK|c~w49v%_!Yi2v-hi@^WA(vkAd3`><}?J3p*(dyo_n>ki504aJOZq@_^|@d%I{1#{E~u18MGJR-~u^4~Jqlt$KLtp=h&L z1@~@a6Ma6%HQq;RBoPwjLsE5)QrY|UhH7~4CMF$E7G<8pc8EPU<&htz<% z()@zFSeB@|YT%-2e)u!$gg-%Kt`R1=v6qf7r3$$vaJ5>ZbPE|D8MA1~J(<`njWcBS zOJ5SdgS3*$Xts(ak+0@j?#v+bw-dZ_CR#&^9tSpxG%w|ddp`{+x@&dvMq5#$DBV;q z_r^?@`{K<5ae&q}2BWkM^lGaKOXE({P|9ubCW@PDnq$r$GYckE;7J9x0g#A#DejaE zt0BL%<}9$(Nl+44tUcYtmJd-r>Te@OZfKd?NnbI5xBIm(&|Vml7)u4S9|f(bounqR z1d`$<2^s$yuncgG&khW*nSY@}8ZQ)R#Ihr{9YrNe3~(@ni>GeJu}?4M!eqfTZumtZ zmwtq-7V|4S-1}x)A?dY4?s2TiK+)6AEFO4sC$Kt92pW+%&4nqm=`x`hA)*>Yp!|yy z%8>h7gL%LS&+%Hi_phb(TE&jlEiZH2TOnz~>m3-P`#hdFKLN-aVw29#&E~yg(k6N^ReZ_KRAGg8 z4+$pSFMH^wd4hRyqR*_do3|A~(l+Z_vR$OHRz|US77=03Xgul>!EuT*D<^RdXa=75cd(VSQUFsonNG;ag|+*Kk#GP&hqKQsC44%3gMUyt z4fZ|nVFW%^g?Uz8wu1-1x-Z1x%Ftbg}UoCss_%QGpm>u8_RXQd-uV+?Pcef%H10?kH_bY3OZI$Ot_h3}8 zUja8UzYD7LDV6cjY`id!z1uf31;C?+t4^=~yE3r;@fqRrrOo1`k*JVlt&pZ=*o_`B4>e)rE~_QQ z@I%bZS-tS?7GyqC9p3wTH*_}}_5vXe4Lc`7mzv{M&*=rTKYQrg>| z{b6ZyRolwQdzRzG(h?sE380|L*S-yXUM09-eE z1Xp}aNb+uNHMul6ly7^Rh_-_!6M?5cY)&9-uV`uK6SY~MOUkuM%H^7UyLvE~Z}z?5 z{y$swfldUWEDpk$ZG=(39EpQAX3r{;9?>)W)3cZucK^|*{+ox9$|jf{0+y_SagiJTd7rSG7akeqcHKA>St6t;9fG=x(xU+3fZVdmhN;#(s9+Lkng(PRrC)68 zfNX$^c8Z7a$O+-(E4z^Qd61FhQ3VQqSfzANiU3cRfCM4RJ``n7QR%HuO;5V0e+H5G zaPv>C@cY#97iu+QP=T+D*}*kHB{YfFHdu4pWi45mbO`i;L501&<-J$zhE4g7PV1T+ z;F-|F+TELtWfjKwu(^WU`lGDM7{rY&+;j+GNHDuWU1KcbUJi@cqaIP|ivDK}HqQ&{ zw*=GnJd!wzBPYfGlXsV`F{dJ}0u+k=1#6(U&9U(ey}9Ih^T8;cC$K`I#wN%zA3!mQ z<~kb=DPwY+%?-J3m1peAE&0jRAP48)hrisGa3tiJq$E-))##BWQA{UNuyBvy^VRzD z&2=Ohc*6QlVp;FHGM`H-PO;hPft1sel@m!KYYO)kbha=Yw^pR3gr%`$c7A*v$H05q z&%rkIC=I2CoJLgqicFw=1fJhsNE!D=Bi-{P)uz1oQBfl;Gx8y?T)ZS#q>$mgsgkF< z@S8>7f(Uq#VEV+(ZhJfB(*LQ9U5|e@*#vZ_FG70-jBe=0giyu)B>rlvXwM6N459fT zJZ5J(b2GerWAxVcGAM}E_4QE9aAR=uPGPfK?mcc`*Nn7N8!6D5 zV)v8xrTLHjLZlFDM{@U&J-UX&;8N!A0%yiDDy9&ZTZA$%C{i^{g@vFJg8YxpWToH1 z3LChZ!u@F-xNe;H(Pbrt(13~Dt}zYxga&*R3n%gg!pAiN-nCOEwo+P0cS{?OnA0^^ z?sbpamIa0wRXulB`IF(+8MrP_vU1e3kyO4l9uxkse2u?%tp`-(?*qfI9mz|5V{|)i z65_=aID8jE(qN&sA|zy3<(-N@g%z{E5FaNiUbSWSmz!TotKW78+ihnn5VGrx9+w&A z&>yM)S#+P4Vzg{mPcjDQ1;y`bJ}K0o$Z2OfBs}Rwr*ouLGcCo3dOrOoB_}O_Jdqlh zo`>ghF>4%3n9j5OhzccZoBpFzL*ZCMnvq|+@XY;8>n~k9&o;;@+4Mj_%JkUVMfQ~z zD*TWu+^LV98LzY5VS9^DSGPUfwMA!#i`d~QFB4Uy3+*I>ff_XZ2_y-fd=F8fBq-iT zbIRo?lTWg0tjI=LWbIPCk`yvli>qK@C_AmoAoHz3W|v_A75C}eT^cHJW6HMx%6B!C zmG&d#Pv#9nMkWqR-ME$f>VPfwN<}B7Lq}lM8X#C>^i7lMj!*dw{<`s`C-^03Teo*D z9L(AM~rV~vSOxd-ol*jOEijw#%o+AxYCXg_N9(aY-Jk7Au=<%XzvvxwmmtJ~7{A<=> z+$fJ4$8FMlAVdu+=>d3UN%qQq40vN+=cu>gMZaQ}29uDR z$gy^D>|!G)JSxlXz2|z#eTS|Xq2aMySW(*W0E%iC5D+iay^fxrZ=e6}vPDEIjzSh* z+bF4Q^V7Nnx?b?RS}KBQS`yp9oPT5Zw_9E#$AXo6TYr^_VBa1Kpyb|V7=mqnM{FO7(9iQ;>q)C$n($058B~J<_9*W@UU2_G3>!kELGH9r28UC zD(_wQdik&sJ&dMNqB%m%&V2lOSqBOaUI^=vU}; z(>JxR_Kohl6thWckZ39vx*>eS_yMYGIto#*eR^MOP1W5Vm-f6mF*WE6C5v$4x%uXk z#q`SB-@OOiB_rduZ+4AP!HOp|@Ti0&+*j~p9r#=j182Gz3cA%~MT9TVbiX@;TVzuIxb;PLlR5(6{CKjtSh{&AHTpHLakq?f-E&0@iiGu6i|Opw zw?8w@vfdSD?A&AB*-7pdA<%plk*eaREnS}(!AP-YuDu`4;Ya?qa242m3j-YBaS_X3mYo5Z_M$TaEY~0aQ z--|yS{nbn|4|+kV<1?rN0?%tR1+VY2R_(EZ1ByxHw8Hxzbm-t`?G*}t{pWMLc;hE) zN-yz=-RBP6TE(1kBJRE!PGTk{F&r1C+hE%-8!Z5JXU-eMa?!tgllAj??a$AQntnI; z)}H=U(UBj^?!dWD-*RW2-uZIM%{G6-uU$X8SpcC7jQaBIU(+8Hv|P*CB|)kCXEgN_ z#gVa*-kq8$`rM9)O!8WAmtWu!Y^nXzje<6G?g z_i>DETjWRm1M2ZJh;4CHGiex6-BY$Pk1=uanTXqKiaulce6aDy?{q+N$%6gPx)vly}11kit)2xPmvW)7n&#p!zs_mP1=8ErbSQhsb# z8o3t#G@J>IO-h#Z0H@OO>c^mH6Gx%FK^wzqd5pSFeL5M)otNO8Ja+x8Ga9ziRNA4q z2Ywo1&3o>9w^}vs>ujDhnR&HZ{lBX+`rmI()Z-4X988?9 zzN~f~&F01W%A(ZXprkx|ME7UC#!4S#;hrjtc~5YQOW%8{6n1wZ=axYD-)E(t*w7?05Bp*1N8l~FFAXR!Y-6Z8XFXZ zfv{Vnhj=o~g8-bNP>&&Urp+@bB?t)sa}}B=kTTlhfMX0++O%T~_PAP7R$R;ig!zuf zLJG^B?S&Ku!)pMTN?$M}iB?TN1pHhsVn(#PViXJJ(+bKLqpM)MQK`2RxX5mN>h8v( zu4nIN*@6h%CbAoBizcG}$8?!O{)C+jrO%JuDb$+#Jl?9f9Y0SI{8Pc5q5898rzYM9 znTBFv3@fbFdF^o{@@OPnQTV($FJ#Jj{Bp8BN8w_r-=ouLyur)ak{`Km8{6Gj7IosS zSX|6wYUfqnKla`|e3~Ll6o2j^D3PN0skOfF*0h6rlYe;0qw>jNqJZycALwzrE)8s| zYuIK+Y+$`DljOyA21b-SOP^bE^v5($A~$ikzH{@N7BR;pZ*s$mZ$WvY~|37YCZZO{Bw z;W?|QJK&kYWmfU9_j8$V@F=+iE_irhyxey^dYt7xMd)w8mipo-|F-}3^k^W=UFgpc z&ZILayUa0Hz|&Z$<`9qCDTa(Y1zAT*=j6NqW(=(PFZspirjBvuTLU`~*0}wR6gI+YMyxl<`Kjo{K@ zQZ@QYj}#R*_0S(`jrPYG38)9wC>CcyoaG0hWyE3gIoHinM#afknfp_v6?+MSg6*1TeZr?!_ZE;YvPD}* z*lsODdKjO4&3nBhI?$oS_l2d-J7Z z_DzzJs~DfFnpBllE^t)th)*E0e07pbw(|sxQuxuX95XB5=`a_dT~PjhwaMevxjUUn zPnJ!519AXuI_o&z>1p4rBsXKqI5(u@v3-i{Cn}^wPI^{3L%*o(Op?B#t{hZv+cO$smd!-++NRvTeX*ct<4`IV+C zQo%|b;CzB~*BQ+B`&%JR zAXck(7vV>~$7G#{vnFhlpz-cV_jzJ5sK1dgUM3>O6l(NhCCn23G!v?#uZhhtbt%0@K>x;B=+M0_`on5Zcp7CFRxNYn*`Ka+Fk2TH}<7jie9j zG8Du-R%UutxX1Px4bGGs$!?i0Y|CwcvrS%o%{>Faxhrz|O+nn71b zGjOAfnfdur^pDqn9LPET5#9k&9Xf*P4|Vv=@JJC6%~i zGzjVePxaBbixs*Lsq8V=O>#B?a_&T~87@p&E^L#v{)!Mu>>lNGetkK2K!$~=yL-*{5=ES@j4mh!{< z*iEfGwRt>*$h$B5-20XmX5O4e&f1>3(nPCZnUE%9UPs>z2$EUf!2KNOv8;cg+rq#n zaO(^-ytWOIqM>v25y6N`8W`jyHWrjFX;|@_iuwPpI5GaIsMcy~YK|ALKE67Y`b7?l zo2C!{%$uxgQeZYy?^BJoY58t>Y597iNv_+0l&M9&!lnk))M8F5p&`J{bb|O{>T@TW z)t6a_nLPfk4)#)q*1J;JG#HeT<$68Lr!20vwht}HkLWti3S^_! z1Ngj@h$p2YsxFl)@%eM+Pqo={JTE1bltUHBLiNc)k2NLWdQ&sn* z8`hL@Es$#(6@@G<#aZe&dr)Vv%JWDXRTcN*PvsabU?{Orn5_sX$X(EOPXTtIj= zA#?^LtVDM7tMK;))T4$Ypn}T0Kh2dU-Nm8kl1Cv|KP8YPJ#wUqsMYs#E#t=dgf4CW z=U$vqM*#;{XKp0(Pqw?1DrCblfYvA&NhWQ8WTBQ&LRx%0O{QLaJTo$ZvYi&kn3*+1Ia|8LHgKsvG7~Hg9XpXcHcJ@#K>0Bko0up>S45r|^H^ z=(Mtm6RJ-N%3{{ap890L+ryqH!@I|t;$6>crle)LQ(x>oCrXKG$x)=@BB%%2AUHs3 zQ<>JYKZb<8RK6BbE&l+*m+}=vS>6SKa9ZoqJT>T||6$tP-qAxEFo%$cx*{e~jrBJ0{Jv zZ?1@xup%!Cy@rYma|HADB`8;$22;h>Gh6&h6SXAs(ua_+LcGqB`OOK@UK$qzXm3J$ z1RRp_4kST?szxR9w`(w6XOK#DFg{1I;Nz2*h-QBSCyVYD(w^2t@4zStlamUiJf9V- zoTPX!;e|K$s5AZSD|qc?Khm+275-rU4EeF8l;7|H$EQy2-!~A5QW4M6R3Hgk2;@`{ z@(uk`f-bddU6X|&wV`k!6qVW&pj?}7=&4`dS}`rX{~Xso&D{u*e+)5ize$|%w8vNq zl0MdL@6x*9Q624~^n3VR=y89S%uOX5!4@YMbHpgx`*-O-Z8zt&hp~db2s&T1J)3pPq4J0dVpn4 zr+JjN-Dc`;x~ET-U_})g!*K*J%E6|b(l9*OF7v^1xO^_C@P{1I~IEC-d z1h-?-xTOUCnqvMSh+t5BLIn`Hibrk(ik%eydMVP(zAZ{D)MJLGH+0-PK@AC-BL-?A z56sDQ=9yGVSx7porC-$18PxfgzQJ~;uGR8e52s2F(|w`L7~*2HR7xSI{8vxqIbSAW znA&Az=z%6nYSQdqGE{x` zX-3C5eeRB9RapJp9e;UYq*1%c!iXixWmGV8;t`f9ewCRM0Cr0_tq=&xqz{6bG+s(2C^ z`;iuLNF8g_R&@my^lZKKQqvXl7fM>5ZAMalBkH5$6O zg4Q((*SXH{v_l|1doh+g;8JF{4DC~eC-Fv0iygAN9qjbX0H$tL9mMmBmuM!KaDJz~ z9pm$wWyx1Q(ul+8p0^FwE^M0wcIU(A394l#!I_{#u*2al7WLH z(}Ue6+cSvyD{c{l^l7x^Q?wY`HK6F`Vw!Y+IU|8CQ9!@u*M4zFDe%vzYh*0qlsyf3 z4WNPospf$h`!y2;{pr>CAKxdLWTX;Zq^k45$b7i!&5zXJ{B<%W(Qh@iV>K)9!3{)P z8ee)_{HUI#uAYKYdAsbPWC~hptwBYEt#P4`r;m< z0L`4Z!>ggWF+a~&&PgBfNnJ}>n-4?IINsMYeCi*vmhC^x*;4M? zegFxaCF>MZnWv`-%~q`>t7{VtVvJJnZhx+yrOKpnc&(ONCzI-Ap6d3?)T=K!kq+YB zXWMq|m7byJcAb1V+c#6(;N@@u8DG0u!R>Y!@SEv9bk8hmBMO0`>{ zc_E%>n$VPKND3LbZfbBE*0(y`cVb&w)Utf+j@*lHxV}4gsv*2zzWM8uK4lBKOMMot z&r8|5!<9ReRlG9^JDCC}u-xWtW(RRWPom%c47W?5n-b-Vu-f9;-3swrFrc@81f-J) zE~`qQD*-~KtXXn0!!RXDp&itt-hT$p7iNRoYk?Gm+tKGPb51l zL)62JdZ(Uv+VQFP{4f!Z0ExyeclU&dLocgKmOpcOW!|tmqKuxO23v%M>|5*ve2R#A zm2xRjM>SM@X{1XQcAV{@-|j>MPB-+7+ZlCEV%bI|$76 zK4QBp-nuh?@+5Tf7XX1upl#?V*955nvSzmvBZJN7%sb}e>MeLF6c%fc7&$<;ZyYk`s9gkMC|z>3$Li58u&uXmsR@SX0mLX7-|(u=;-j zKfRs{#uGerPzVvLr`Sl3gN&jS7Z$0QKJ&UF;Tr^KKeu;1BGW=NA&dKhr$~TF$F`L& zd3r+Fxn&^K!5hXh}-phPHs}YJP<*Ca2rnezz}Yi+36Pk-JiBcq*ThC za0>bH$nM)s#?;V*=EUOy&LoY)R&gD49tyIlC0(DnkEBquX(pjNc&GB04P0OAT9O!4 zsp$UjTJ7*ny@`!p9rt(&n0?y{--q@-PbKP|ZAD$}pNl#F=1`3O@n`L>?|&7FYya?X zvtw1lm3O-{bMAlmS@kjMlvzvQ4Kg-#e}6=ajQV5WpWi>hNR-M&yR@moqOtTF1#;bb zRN|g?A~tD38%iO#Y+XPhT!Vj}qjodIs7vF?x35bVs4K0@5b0d4%aj;C-c`krV6evHz7AFoBFxM~ija$7$e zE^*69Pb~F*g&!+*Yim73C@j&8KqYf&5-UU3$+h57UzrnOlJfvTxD4D7S5xAyJECEa z-AT}}lHr|aC=g$o*M#eYwlRnl=!ILo@)2e#=L@<*{WX?);^vq!9rTBN zx+iE-QY#bXbHmR}P7&vy866Sy43?wX-lkSFhyYO={i5%pN|WXEjP@tiFX4{MO-0!X z$N1Vc!E>u+vX+bq07(9sQ2Bc8=PNhKX5SbrqP=!j3?dY#BUGtP^s*n>Se3^ z>j0a*Kby6xiC@xa!6p(Brdo3{3oRydN{fNgRD!MZCi249qoutcqc1=7ZpBTkQa?}< z?BAnF5>edGRzkP(=4jFcC*&B>0h4Gr&_YRv95*NhIz@PHVySG!uSS@{YI{>j(8|0L z)twc*&gahe=;YEnkf@txDeo)D4GmiRgz(P2+{(HNrL}WwSm}eYA7>@g!9Ab7b1{XnJ@&IYI

    3RDKwAtcD=W#qKZEn{HV z^MGX;ts{KslM!$Q4yt406EgCfes!)zqqa`_fd6M7>Uf(>!#;lx{ZoPC99LY%11iXG zAmPK}4LvX3ed^SHA)j|*q?pV8(Di+j#Gp{Q6dqU|>N|(|GG!j6iKqeCpjl{gAXdi- z8l@A&ToawQQS`NG3+|`ki_~UtXju1Iq&>DBlaTG&HPnvaz)I} z&C(Vp@yt$L0yk8n=RPh;v_pWobA^{)FxnG_H7J_)>K8LmBob-a5j8q$EWCOOlL=WR z{Ppl&{0@}K>Y3|+ky|{i@yn|stFV(LNmGD5f`2bT&^kq0ZD3MImj(n6M9H+!0{!y$ zSu&X2$qY0=hywzd%txTY1n@@1Ze@FLo#OM(Z*5Y_Tt=8bRcY^6B3tKTYIQolA}x$XQZlR*L0_&gLO3 zZ;yF}4IgpcuaN3)a}f*BiKOPE6~CLRyh$yi*T2r#N~Ya%OM@cx&FwSSgOwD|nZrMGA0X_JN0WS&_bCFv{G zzEA!+{By7>N}}~sD_wCCb#?P^4z+V~wWv;Q0of^XhGV9}3RKs90?1Y?_F~?9vrhPE z6=&71GxSvdfX%mzLP-#p-4$e{ww}Ou;>c5=Z;O&^i}z#nRfYA?@0jNliexNx9{3s4@U9R=G3h#ZO1f|? ziQ3r^l;giuhVQxY&s|f!#k8b@3kxdNQO%D7#2#_jLu4-PeO2$xznLGtW~-JJ3*I%o|z)AB`da~+mAu;I$lV%R%~9(5tA<{B zvhbfsmraJ!>X$~7s$sR*uK6q}_;>PsWlnDesl-hxgJZC)rJ$^CUp?Z7V(~;B#x1lj1cc2j} z6GBS`q&)UdDeP)Iz);=8u6IxlH~4C0qAZQ-pVy_P2pI-sEI!m+X>(KktYeVk5WY=j zHr@E7L?(I`D6ii~9o{bA+t2ieE)%9n!TcScs;Naoh%m0B?v~kslI$qdyy<*%jvhQ zU$NbGZU8jaXETGs#{Xtu4A|NufM^*6S|)y6Y)JyAV{1G{!ZJ@{J2r`#pH8pnD=c)V z*>r%@%?yng7Hy}yJWwc1l%z>iM2(0Q&PZ${$d_keyf#wr=Y8t#Ch zoF&{NotAH8RjA#NaUJ)W#}@=^BL$PLP}B?&h6-vV&7({)2OH6(I*eUbt>&0tP`1|1 z5_)GBLlm2lHIQJ9`88`6&yFD4J8K$jYW~_|0)Ww*W*8!fh^rv+$m|GA?nzooO}0)= z)=9OX>9aOcB8;R~j`eO&puQ9H6yTOBSjv@SJ#oSa#fxO6;{@kZO^IU^c7DubyO43a zlzKYz#b_p@42F_&`L%YX1;eI3cGN2ij|(FBmO@6_@khKsTIb~e1dub7dEyMi!7zth zu4Km>Lt?l#cgCxSY#g5~Gj!{1)!KY0%H!xUuEFSWf>!RfvvX|6m*!!_we$BR*BeYY zc!l#D=d`@%MwGM}m1%sMEx`QTJ}tLAJZ^&pZfhMk4h!5LKB)u=)p_{%Hwj&U=^uND zQ(<6dmSp>`-+tNR{HZz`ecB`ObX^2WGzKk3k4T$hK-6~)8QfMYxmwPa;`a>0Y$3Gw zWQy&EP!z*4)d-^3hh?E7-55@qFd$N2`#%F}Mb{z49?qB{x9>qi(ZPlz3yZA{+K&ko z!?bKayR_Awj>6}+=v9`qxVFb7u^JR!?SDXE@qG!=8b-kxvMQY^3mR~k7is*=v>%O9 z(nwk*c8=20;{j?FZ=#}5F4?6c9%D{_r73X@${B>Y9yh$YG4Ea@bIy^jlciW_q68c) zrGTMF)Y2*qS-6i+RMsqVI;)yg zkBx%tPWyzz7Z>)Xq8S<%+uenrW1!2^4~Qo&E{8zoLM=se{Y24S1#Fe)U+*U7LpM2Y z?vz9#ug`9a#Yl@zlN_#2?)XGHf?KEpBwR5p)V1!z@~L)sJ%HRvOw%-%q(mHKXXQ%O zKmqLd0DvJ_Ay5J=3wS(W5X!)F)kxm6OeHm*-CO&qRTJ3DJc?iw21;Cx6>qx^@~xSn+SP2hTfTEi5>>F}n-i z9M^#^@Ax>5fy@<@$hDl^vQwl%#{Ts;iI)oM+0 zDkB2-cLf2${#>8dJHH5h0XI+qzXF-|X&(B2@_?~9`BTKxMGz>jS17N=wmxbU!3k&V z@59EjuOeBmBq_9HZugLrTyc#`v1nhLcwQ%O$#NJ|^ZEJ)rW}3rM<&%PBmkM51(5nj z457X%VMm|BF=n`<&mox6ri_RmOh$lJ!@DKeNFaP2bYdYkH&~(h$=y5{sYtkCeGK#xys_bsqj*w`_1zht@j2N=9R3^}>(-bE{kg_~ZddupG4B z^M%1va=UOy_@l?u^LH>niU01c#&=J)n)tU@o*W5cf+Z>Hv8+TYR8qb5``s0QR>M?7 z&<4gnzTP~eUV~G?LEH!X^|4g*kz82|nnBMx{&@U-OxRI7MF7(o>whF7N{j&=!<XS%Z((w{EeHjV!5(o*+`;R5BUmg(`RnPwxi@b6QdXbMF;w6Q0&6T|deKE}H@?jX#wRUL%Gf5c6M}%rcmN z+-tPcEdWl20s~;SE`xszWF+)d!eBP%)i_-sGbdsEPRz2MO&()E8FTC7I}Ni;D{$(H zqF}TTlluWXah%`UxKQw(p!zuaD6s)Jr zC@zz)Y|ZT@6}+l;Q?!ZlI4xm-uu#@8;*lofUa0AazWVH!JG88{t50Z1zHWlL%>$^A zj}Es#;>q^$O&&wYu5-lo`EC@eCR)39?QoZyWKS-sw}?~jzMK8e`4AATp6GH`l$mE2WX^7&Fsbh?;I3nU$oZ@b|i3flVytUDdahGGkeRr>z8bc`~fTb|p)0 z4vU=)JGbOYT_yiz)J5y}NFDchAjZXOa{nV<^hjNUq;NomdPDR3X3D}91^s~WV!%i# zWPJC_4d5onXKmD(iz$ksGXoSu zNtB(u5~>k1@oX|pj7TeiGK&t0O+WdV;nVp02{M3+<&tij;`3RR4p7^cmSF7N&QQ2>xj{?0RpWQdHt^jbJ5G3ab8`O2) z+w;ed>=AEp+7by=IhWU8&-K2&tJi}&+)9?2-8!mW4R7XFC1i#?x{OQ@>=%Y|Z(sfx zfP#%bjfpFa1amt4JER$w^<`K(_Srm!CNC4|W&1WE{+Pl=v6cuPgb@!~9qa8?4jRq8r>-_5w^POWsyT$#r$Z<}In6Ywk3 z@>P;x>gxYqY_%pAh^1V%%Bq0ngA%LrK_+p-g8R{G5ou}vy?nhjV)6M)W^*4IP5f5* zIVHY>4)E2I^WoMj089|rBupHF0XP{+=)?U6de0^I=pw_<&!Z@{mBo@8kcvm;vU*;X zKjCL>k28K^NgiH0-JGlR`o2Z1pLveLn68rweSu8&6(#>hpJ}`3B~ci(Q2ZVG6Y;{3 zcp`r0^EviS|K)GeW!SiTp*ieBa$leXI=bP9;e*(kL{$0yeRIcpovIZ?6Zg$ACX|oj zZ*dw8m-zEJOK~V`@TR*qhkdCT*hgj1rSzYI%!xCj#UU2l49ooha_yfu-UD10fZq8h zxOd#f1g-ikC68q&D2t1tw|1(qZ0>8yG*Wq1=Bn%7$xeD%9MhMW=#!Xl_jK&8#%9L@ zPXSWsLz%O79=Yp&;tW{UyqGp%u8%&Ahw5CZYvkp`%a=}xvN)|2JIQs!e}j*{ympE+ z{W;RncwO%(JW|l{lk*QH;JYPQeB?Rc;~{`WVgm*MAY%St>}7N6+c2w57;8gCgN%l* z5{8DD=`DJ0ur@--rcIw2$!A!UWDS*iynAZIlO+GWdA6b|d4Bh<(KIc6y@TS5d{To%v)fWoj{%{)_F7L_NDImGH~D<>f~u?8-0p zCX1wP6-tQWuCF4#Q}hIsv`?Bv|1JMxgtVC(E+n-YcWCqVp6tT;?efmhFSpThSI{Om zBA6_6vjj07qp6gv=$Py6c=7_ik#tdm&LsVOZiDMH$xcr)PL-I8{T_ z{{w$OfWIft4(@jJxTpdQ zFhJ7CA}~S%DT|Pv_@bmOxcGusjdtbL3tdxV=?R4ps$#Z+2J-19pL8NsA!Co_f+(n} zUFs;Mf^kZzUY^QqTdX8oW~;5xBFijt$U-MBc-TVAu6RilEU$1#B!``GF3gKw679{G z9C6A)1{q#%Y0Q^ic5!MK%(S>Fvd?}|#wyPy=Ik?XJ@dsGUruvE3)NDiLN%D4a6z`$ zVB`KEhT3-ffCCOb$UzAu#;BPIC6*Y1i6nYX;yC7-Ypy*zY>dWIl`>M0r>iqOWB0m8M1pB}N2P`nbBOHuonzpHt2E}#O(O2IQ=^aPIzeE&_ z?+XP>u^k*|oDrL6a5Nm7YCaid@lj4;JQPvz;U~+=Ex#P|%r)Qq@_q7Ig3K`6^s?qJ zZ}30~Grhd?OgGAv<(!w14a1KOD;4tqG;s8 zLh>L-INTu*4UvNy^OA=)v{4Of)F?-vd^8w2V zQE&pvoDeFLMav-vao#wiKs}Pp<_Qd0ie-jUl>q+lF%z3i487%;UL=Dp>zbrU10%t{ za1dYm3JeGDa+iJ4>u($cn1)0c4ZWbH9OB5uEe_Tgg((Gxn(>SbKhv2V?!u_aP=*eJ zk>Tp$SiDLKae!nux|PezTFn3|s&M+>AhGP>iC@YF0Dk?94d+KoeSXwrGT< zGDITcS0%%duM&CIZk8+&UM|UwX>g+&F%qRGv4IV1fWk+O1JWr!F*zyigC9hy%OwmxyqK7j!93Uh?IeSfB(OAk(!_`(F7ies)~R9|?87{>l!mt01C7Pqv^E_K0IygXaU zyU}$X##C-NvCoKRhrURvQJYFIT{r=%S%~Ut zNQPk8w1%rAzzqjRuz@D-<^`bB*_f-ygS4{si_9?sdah$M@vKKZdVmjoww4E^RR=zR z1rXK(q(=Z9h>vGmkbxeHAU;AiZHShvG@c<13AJMy?T{NhQY07|Ur1kh$y+4*_Q7?y zc9hkiQEOXk3Ld5MN2yjNKAyCXe&pjG&Je>Ze_Lx?-+Gq*P#tntcZ1@tP6#g$=IfxV zChATX+0(r)7O*gY?*5LNiPC29BvL8zW~x%M0{(+}*V~d&In*bsQm1^acM*@w*CWF) z2}neukyoVzCH(a7eZK$N@kQim4+)- z7|9s2QhRY22$F*^5R~9b>yj@WNAiOnzoa|#TO^;z4G}#WFAOoeXj|f6EV-XEmF%VK3(rCvvB#lUtbK0{S zn#P54tQWeiv_mP{q%~U0cv3TdagqN-{wPe{I8wM$ANxpBKl%}CXOyH^_MjZDNnd)? zQ;8qJ6#|>mgr?Yu>2=AJJ)C|CCmYP^xyF5gpD^HrE^rqM;k^PF9A&&pf%gg7lgRRs z$9#u8YgF)6mAS{~PIAvzSL5TAGxFKrdZG`&CIO$lw=k4@3z#)N$qB!mbzpKHkyOuz z))pF8K&xP;7ay)+#A&Eh91a=CK8hE_!7j!@E_5s!6p6(Q&_XJF#zX8zL^?#J3~wE# z!SNWc8axRUumKc)|w2Dh2)}PKUB0F7V|5PecJN?e9FqLh#Uo!a?y^3UBhFlE}fPI;7>` zP%p}%19ia|Zh;t5$QOJ;3s8_Eb%^5ruc`b`8Hz#YmH`=hfnZJp=!Qtjiil*42voQ# z29l1;NZ>X^K#IlybfiuQ$Lu(e@FsB*38BL|tOh-z&_3!TK&+85hPRv7=h8;7((2D(HG6l zow9Euh>=&2F%s{MSL#W^yr7-{to+I^-pVf}tcsjO1t+`>{-TdH)#-XH!-k|{hrH#( z93ut)j~!WXBaZ=I&Vn6s!7oY+ANyuS60hV=E|PTNFKj9>Gz4#QY#%YiUCKche9R$x zffsh+;h4(*l&YydiX(f086=J)4Kx{u0U4mGG=Of(tm-6rLN=;^t7-rSkj^$-k_1E` z2c+(1WHM)}=s1`lI&g9a1R)8GfI6;2JnlozsIcsa(vG~wj%G9q&t^ad?T_A$452bA zt8ywK{woN4U`U&Q(X`%LTiSGd3#M$a(!luu*n9#{aGgy{u9 zak^sXG9PogZf_JXGc$2u6kp(W`~(1o=TU5tQjurdY;iQ14;Lk(RwlwBVzb=ViN1`{ zBTRxAm9gGRV%|`KIDeDgsF6NptKxNiJ^K!7cOxEiI%DS&SWIDsNV#F5tl(3L_f+ za3L4)vltfRqmarXo9h3PAz62>1(!jomSGu+fg?Q!O1VVrWa)6m?5_B$h2&}H^mVgJ4aA>S%2YBEoW3&oOR*wuMM->aQw$RYTkPLs6 z?xHdX>aGZ8mPl>(2$ldDV&p}*p&R&4(ozJGOsfI;Wp1jpE(n7zDvdBcWE-yGwZ=3M zUkffRk4+yTF@7O1?bO`>Y@fhKPD{cWDzQ(?)@-wcA8y7ImFY5#%h+Tu2QKpksLKX$ zATn{lZl@~;oL~%YCjgX>G`%U?I(7NPfcbbuBDO$Qu0SL}wcOB+zPLbFNcH|ycjZ^^ zG!lma803xKG(y6Nb0|D_D5B9B{Yk>8ihUNWp+bcl3r^h7Df%wLHO+0pq+;ii0jUCX zBMDR)`gK{8ff-82oiXZ^0LKfk6lM8nfUe1MVldYKf3e2EM8ULSUI{ z=0kPHij0GRjl*LP*g1HB3jM5yY_|%PJ9VW`z{dh}46FfC-Qx z8(hRi($E{)aPLCoLj=R7mR26@MQ?H}Md;A)+@TwwHV{4O8U~RqLH^+paN%HffvV2u z`@*lD_NiCCkDtJR*3Q<6pBPH^A-L$|2HI9J6Ez3sByOjR6zjHj9Q6hq)duR;Zk2#f z1i%G;Z&Ds5Q@00GmQPl;M{#SBBTm!4z+iSKm%ij_oiKN6&F5D**L*a$PVLQBoe?Dl zfEqO--u}xO?+ZA4lQp`r+Zv+aW_NsC6E@B53;2(zQt)-cuKLDi??W1bKm85eR&HSK^Y@clGsr z?R9;f%Euyd7n}fOP@}50pk%CUVY_)HFElquV4221>V_}~{*l9qw&=`KR1U0zKL`t+ z$7YZCNJrmpM_;zFAWH{+6oadBgNHN-0{Ui;AfQ1w8nodXUPK$Zfk}b3@0gcEJPQu- zB}AryrY-~zpA@xR>n)|$OmzV&%Fj3F^n8+WP6PA%jx!9J7>ZlkrS;(+AhWtIb1|zp zi^DjKLlJL(NsOZlZ|#=Z24Dc7X#iveB$lsMtblMOf^Z|ERk}b6G6E!S#Ue^oa<95_ z_sJuU_@6u%-ZuBY)J-FRp^@uNo6YaOf{6Sg*$Zw3-VAn#Tp+%n1yx8T3P=?g(JhZ7 zmkNTR36`oDN^lvNK^d5#7xa}Ghyj6^;aQo18IEE8u$#3Q;NkG#ux_%IS}UY^5osOT z0W1Sj#$Grua;&r9Q?%4FlSVsB$CX`oil^Sy9f4P0#rKq-*;x^Y82Ghck3m5p(ifnt zn&BEkXQCx$0Dog(C0$?xz-k0+hMb?fCIz_aZqhiSV+p>94|ag;`V1-Mc`3Wl?F=m{ zTb5>jlq%2LpMjJ}3A&(f_GW`X32?z0*wRJ3p&Qx(zf;&-*CCU}Aww+5AhDE0IJ-nR z+Z_Ngaj@YUS}PE>VHdnQPURGR+`6Q%(N(>A`^fgCH{5LdfebP;*^~(fE)$F`(*`Va zQM1@?ai9hsb*H`f1)L2FoL~TIaj9h`B0~P+3$iUEavWD;DKs6Z#qu$TE3 zf){w*9DSRW8O%YqF|H0*M3xP_hTQ?uI(zRTO>T5qlQOVxM2LC0)six8Tv;xd9g>(A z!(UhMUja=LBRMZG~fV<5OWwWrc#QTE98=qg+Dj5rBXV%!=o4tFWpo2i!$G}BC2^ws~zJV5K zht`r1vS6h~3Tb3g`ej}%8Sj8}XV?KTIP4GRK5spGf{sGw4|2gf_YzUs-oNP<-j zw^iSXuifc%3v3mvsSy~4VHlj?kmZdUW%W1VG~OP0%7GI&wYkb%_a#Ub zRrI*}bmcbnDKJ?`l;N>J4cpBJ8-f0nU+oorjiDe9DH`~k>JiCFJ6moHi5j|+LF8(n*gSmSlk{2X>nVZ#K`8Ct~br~QV?)}vxUrr=J-C$LMetT6{7j_1e zE@m!t1F*o=ZH6W%liw5l%NTEy^TGf*}I^X zok*2^^nU;f*z%JYkCVFLgz;N$xSeS=OM3n8>J5CeozxuykxUhQOcN&;ic@qY*UJBE zSBCSyicux}2~Xv{-k-lP`GE`uzHY17i^({rN8F1K9&f)GZ(U%gS=@H4K&Zn&HJBO~ zOTxw}Lfcr?$G@)&bkm(s)xYqmzv9i_>P^cHnXH=}%99@;zGU(8h2X$1U$%JhGLWE` zEm;aWVb~DZlPyo4RH4F!%El^Oo^+(Lg^NipCAVlm+FzJAs$##1M+pT&wDv$^b;V`7fQ@%`JR$*o;Z zv}DopBunQfR6ItB;=;v@8Kp~eaIqoBnAfkFC>f(f$&w|um+)A^XGs#@e3B&L!-oeF zBS?-bM^c12k|Rcr6gl!-`Vs5bt^2sXefyE_--Cz`vVD9H^5}yA3G##e`W`=^Si@%R z88&X(xOMC1tzG|hRVf8kTuOCSS6xf3LzRL6wxi%S)kJ7bHP}>R4JZ{B;{`BTC=?Mw z4-u5mLnHns1W`gCKD0$k_w1vOi~7VU`uJ_#ij0{{>P7z1e0MHf$WvBj8KbU{TIUx3ktn*xEc zg`2~$i4YiV-iaqde17o+LckQn=R$yf0ZgEW0z;6Zi~=*vFAfO`=s*!^(dPh?Ms$#f z0$~J_NGEY5s!5=lq>xK4@yU`G$;>p^C%rPDIZ6l2aYyY4#FF$H$z&NNhM zrQlLoO#`4+>trR(IO~jaAUj^M0}nauOv4U2a7i1^w(JlH7dyJ7g%>W!>~+g6yc{+Y zFaC+)bZbsI=>%D0_uh*PySFsq1TR`Np_vw%IpLXSRb+%(4XTwk!U!C=2HO&}jlqO$ zx826XZNl*&+z!GO=iGB7XV)Cb%~>~HcG-Ey-FHWj7c+W3lsDdZ?VSe%5I>yv1J69m zXU)*}X=9By+j!GWRt_?_R$U50C9Kp_0m$@&*HnlNC=*_2jW)p$Dk4T8BDBTXTy#j# z*&w1cHbhx~kDBT zOflsEP*{P16K1{%hMb@0`GuXMd=OV(*Db#!X(;^{xBX! zR zTjkJ2Uigv=UJzp@^!kasZgmWLb#O5_>7X%=A&y+^#WGF+OlAbu8PBK$G*1|f3rJHM z7?1!4Fem{Opa7dOPz*P;$xX(7!tYb#1B4!sQ5V^;5Hu>pjiYH}Y3;aLf|kOTIVwmi?idID9+y%TXGJJN z*Qf?4FoX?hWZ_UIIuSxTGopw5iF*R+kcrmzJ1+2}Zhgz7CO65+PUeUoWPp;AUQndO zNr_2=!%`}x1UbmP01Gv!0T!@eg#mC5Ph&zzF5gtTJaNHvT^I&J!k{QV4TB|t5=fsm zWGICcBvFepRP7Qa3@zji7{d6)FN`NCh0IPMi_!x1xF^Z7dEp`?sX|Fik_G8uFMB02 z8zd953ueUXRvKi?P|l$%pYTd30R3mS7L*lgtV0^pphg_|w+*K?bSVa9OD@6%76K7a zDcz!rT)6d>sKA3A)WC%a)kO?={RD)Hxz`3m=$Mu|W`yDh$GZM>Q5j$OVub`d7!0W( zL(`-N1~HI93`X#R9?s^dxJfF?v3+v9>kc>Y^Fe7cucMv3oGdWDpun8O%I z35PWH+LdWkrCD@+ic|RdAgoYJL1_sWI~)j>aD>Ah*izuQq!pKUyd$J~q2Rg>lM|cx zBqxt?sW>1*LJ~q|gvg+26KLv-TVy6P18ZSuG7^O+pvE*cz+ntZP}CkW!D6#n0>(5} z#NLD~2}m%`bf`)lC|+keQ;gZm#$&UuipR=hyqV5=z_XvR=Vv@SLC=05W*~qgLR+H` zH`c5TZFr+US!t+)?8p_q?lsO@$qF>80gb-`wi?ec2BUt*x`VhbvdTOgp(HsF$$H@) zmX#6RHcRPBTbghCa9k=M_gO8WHV0V1k_&KP{<$fPc5;@h0Tf;!0L~47P{PdmpXtK45?6Pw1y-E=ASSWPixAq{~DLsqn@5Fx~cB@xL( zu17tVkXN40ESsSg?Gv3a!=KB@g?)K-4s#f#zQ;fZui`BZakK-D0HUk0{M(LkG_;^u zS%>|$(NMZb7%b8FsJFrez_}n0F2l-;3H3q@c6Cr*DRn7M>it0yj?fq*F5xX`x-OgI zlwcXjf@i1z8qz$WhBK%E31T429#-tfwy90VhWIhxBtZ@yt15P$d{ruPRXp6GvX-;V z9`&HrtX$sN&wdv5G6Eq5DNq3}0(lMo49#a~ZB|+w^IaAAZG~xe_D?(BxU_B*AQf%> zGlif*jOP|pB4%@4xY@=w_5SX#-dvj&=B5vR+~e?=ytLvM&-faZfk~p2k}9DTOB{@P za#Bh)sY{LOD_sEtRuIDgPRA!&Uptw<4c(rCD?8sJ61l`als3JPyJ}+7n%KOiv3DN~ zVFZI$c>AGhYxmFwnVs`E(oUF^WFfBOl(@&8d|@X8#O%{ayXlLLqom^)=@3f1 z!7mPStfK%8GN^wQ+ED)nd>zE1NaggCb z^JWgjAPyu{3=GJC#;}0mU=02smkTsSaxK;byC5){(F7{j8J^+-FIO5fKm#z~0z?%C zW57eN0R=cm8yn+8J11nf5gc-m1W_h*-~ls1Ff-vnGh%dQVbyf!aUNqNbz~G~JEH<8 zaCIk;0y~oeO^`-iMLyEC?ip{?Yv&(H6Ib`94XFSM+|X8L7$Mzo z3#~Y4ch@@C{?;if=Q;ubf_ZllCX#Y$LIqjC5%cIs!2azm;2!ICetGTzaHJ@{2vW@SEuR!7(~U-knY&@(~_W?j~z zV)lejh;=lo0#dLG7g7ybGc?b@W^WZoNrM%6rgnD*XKVLnafPJV5J>aE4bR{X@Bk0z zaBR7=5P@=7Z6VA2~5VwlTLs zl1l(G!jS|!*c~7$Wk`o*=3yRVm1QpqW@J`YEoyZt@B>&Ult7>YS%-BepaLEX0;7=& zsc@8RH8ffHR{RlX{UKNUp?3ShA5Q6%VfPGJ2o2F9K$o zs>s-?2Vskf>ml6rOcBwW2w^F(s$Goo3t!-~io%9$s0EH;U-;FW%;}uk=&PpNjnmnU z!4)VJuy-4)2Kzk6?i!wJs3|feQ(8`{}I< znXWPQpW%=T(J&c*(J%0daw^9eRNw>|A%ZiM8l~|9P!I+xXmdy9Lq6oM?7MS2z@b`{ z9XGQ@^E*~M<8<&bR$Mk_``d&{cy(k3g&vD_8au!p>#;2`8d(4h{v)fSSa=`Y;0@Bi z4QkgPL#i}exP?jcvilLi+^`MOpcd?)jqnf;@z9OpAdATcO^LJ+jHPIu0*7PT5n);d z?Zk2$u?6as5mf*Tv7!!%N3}vcwV(tgsa83Z!?kp}d6RPmds=Ew42d-m1!Fr)PY?iM z;2E$(Ty;x3aSIGuK)2Y0JHxOcD~z|6+OvQwi>_&Gz2~<)s|>#2ny$&I-lHkWgU7KM ze0$7`6k$B8x?RPjUCKCUv?{C51u5B-45XW@+8A%yNS%?Kv(5<*)S0u_LU6=lP)?yx zxX>*4qbv%=$ym`W2S#D?U_WfZAZ7Oyb9Pq)rWLpV4H9(zye7oFz428;|igpB2|H?kX^qk)R#2pbL7hF0dLiBn(&R=_2k zlNq%Wx16Yoha$$qAPgH)dt;1jD%`hY$-S z20S0aA7cFpJs8HmH3+UKKT|sce!pU?sAi_dN#nKd0;S_R)on@%4da)NK=DfR%uD={p z6R55Z7LVm{+w(b}B z!TTW%TgYbI0MX%K!WF&PCmavtK;Y;gK>o`>$G@gY+fM7 zvN*=k#kZ;%xPse?yCBwrJGgYL1$0c-f;-1DF%e&|Jb|YW$wVou+8M;dJi__2+QnSL zhPhtu*LJ7Z$QIby#EQFsUzdy&>5vYWe8TAvrQvWb1a8SudM#wp4haQ@0CJAS5`V?= zKJpiyQ4`vR{vdN^+Gpn<-9Wr}(U0;uuEvlHAoriLoeQ)*fta2Pvj@C1A~sF-p)rkFdHnYY+vnpfSk zn0l!|KDe8z3`I`IfV<>$EE7wf33(c^IE*g{uVA#m;!KTfef$)e|p?jY!RM+`C*z-!vY zq7__7mF)lx@R=79bPE-jkieV^(F@GdE6l=N7MM;A#k{WTQd7&E1qS2z3mO{W+uk!k ziD5tnV{pDk1(MFqF+{`zT+~G(svg*lqQsuvKr?k&CzL%9&sR6k1U!@-%j_DP0w{n2 zwvPfPklwd1g6u5?RG+g5iS-fivHNprVuTi(8T z+fi%RuJ2xUcN4pF=U8!K%6${}^_JNiG+do^;mVckmN9X;!i6g>&KPQOr%#g`7wz;o z+Tn7Q%QY>RG10ni{l3*Cc$0!nvSfLZ{0S8*Ph3QaGGoS+F=N7v!9r#Xl$AoPkU zu83mMC~8pD3KtBWqESYrSo8`30sw=cU!Y%h%^#L zNv)Ro>MOO-Qmfpwz>23Wa^jIkE_mdjZ5nE}iEJ=x0>i5vz#yY{n!6&y*PVOq;`g%1 z{+g_?cD$KPn|8YKCYwhd@hlfzLMx{=*2Xa{oY-c|h2wENHZ7WHbfYFTi-jAm3F2HX zNDC*jXhJ#XqF^+-E5hIz3hufCdOV?-7{k2scyJGh_1v4Uz53#t4?h0%>yPUG1Y|J5 z2^ZWtg$pqZP=yP#vu?8Az zym4npapno9$8^yWa@}~$$(2^DK27M;FL26Y3*?w9bIUH1Gt=`(iOXQ#b(+iUMf(CG}VfzUw-l|s=;rx;!eE2aouQA{hf0_Q6N=;8|}oOsAo zFD9ZYRft&S=oc-xtw@VlmH7oF^Sd1%rDTF(hW%W3U5TY+k~wD?o-X$y0H1;i$|z)= z>R(M5@{9gKODPR$0#&>hkyTwqNlmcGF0>L1jrgJ%Y(Yyn&T4s(6(IWnbWd<6V>Bci2 z0S$_EMrGpAg=@x9nvaEyHX*a(IH(a0laWkiy70|!TsFogc%dLPdxFfGlblAmzy(*Z zP8_du9iV|nXhRbZ6PCb-Brt7h@`(@B;^UwD{NO)?6i|W?1ca<1=s=GQ(1ajlf)qf= zYhn|dg)#(!vVp(^AbP^vr0@l5Tw`w4z{ZN~wjxN#s2hQck&L+Uj1_4^8}5*c;@~k4 zU7#Z#Jwk^u*m91R#0pkRT1c~SlB_R?DGO98)9OOErPZ14N@Vg9HL0XJF@1p<%Qy!= zZZ}SHmeZW)jMF`)&^tph>QIy#-k~tnC`?Jgo{TykrmkRxC;oInW}S*i_(X-3jl2pg z5ZvD6IwC7utt1)o(-kjT^3YwiucFKlfU*QgtR~gOAj?{cK|Vzk%1LX1Oqz&BR7yc5 zbxRl$?AA#@Vv=AK11;oYOIzF}mv+rVF6@v;P}wmLphhEweu0c%+MzsEfY_ z)55(_CNPt^%)%&hBX4x08@6nbG+gAOCRQvo9CJ-BT0;(xxyClMk&PC|F^y=<)iYoe z4l!;4Mlm*F7X@*`6Ka-)HNMS_JL4G{==d`zFabQ_3C|MrXtW*xVLpJo?0lxCpGX=g zYboeKXS)_41szC|5vpX_Fr>+{wKhX0cr7PO;33*V{^u6jz{M@7a0^uSEk=R!#@}oy zIBR@W8_;0UyL=gzU;YRliv#94)<-LpEU6*=LsplXxrHrEsY|LeUFb$9CeB^cOU=0w z7ohosU!3C{_SgqHQyp zGY!Hlm4+^KAyn5f4ZvL>q6EBm|6*OS9ST6KR#xb5z3s0EY76RKG7dYn$Vt~S8yQ7`QO15Z{y<>U$*d9T` zr$6$6&wl=6ps@YmK$UEeBQFUd3zgPFn9R_HTFY7xaI$P7;3NoKK!vxxZ3{Gzj)?50 zqFT<98@RB>GXSRzY0u~xX~8yIh%}@gjipB*5Znu5gElfhxTaV;6r>W-<(eJ7u~GF*s|+tK5(Vi@dQSiIp|aps@`Xqk%<_p>-O9 zKH1?-77Z9q<1>%Hm|pkVSKeXj|2O>!3yXp$iaVYtIG+77K=5Ij0xMuYNCSofcmk?GxnrW9C8>&+ z+A)*k9$#1$0e~p>si>0J75dqgUZ6SmVg~mj2KRC=aR`8A2@1*?DTb&qPzeTU89Ju$ zf*8(P-?(P@el=Tn<^l%52=DD zSgQ;(rihA{vWft}6%stbT*;M~Xu)q1vHEF27_6WAS%!2- zhX7~@gs2JrqgWNGP@tix2nYhXjx;*0&=!>vvTl)}A{(EQNQsAfI`BIQVknmp3ZbuS zvY^_+Twn*FLZPb^D#1{@y-+)9s3FIQ42Hp~gn5{UkwdS#k-EDPi1{07tEE)p22iN8 z&d9Tnp@!HHM7qkNlW9D;f}t^+m(b|L&=3xmahc!H0+&IKESNOT3#BIr11Jy!#TtXk zEWMy9n#h{0CD1HJ8l*&Gq*de^Rm70einR+d8(Nc)*K#cj(M1j6fL`py-$MZo5CL0k zEe^l{8ju2DL^j_vJ}Cf&RbsYii#BV62I%t!s?5S638o>*C0{ZIbC50(h2eL5YxxlfxE+=oVi(Fc z%=AR^Fq$Obj{?~b1^IzQn!O2u#S>7?3dyz8l8{=o%?!!SPBH;r%r)35n@!@q*en4W z5Kdr}0%R*bDc}VZkxOiFM!|Uo8?mKFUnafZVWC;;viIzNubFfbL z8rESo2Xt^5aAcLCn275UAFJrGtSFz56Q8ZPFd>UN^brY^kf4xAN?*X0{+HWP3{8n1 zH3q5-2dTVDc3=#6ffsj(1~7DoEo6rr@(aW8GPx6?g=w=J*;22PC8&+17uh?!0aF!W zHdVrgY@o}!bfR*Q(>0BkLfi&IgrRv6OhS~GZGZ-9_zacFg~QYZGP;H0CfC|EZzcmgok*N2$MRw1Ztxk!tkh-u*#hbVxE+!Yl&F=A>- z7;HgeWyy3%;B>eJC$KSU!JbtCLJb4LVE9;ycsi{p*$Fa2WvJ0$n7U+uS*64k44tTD zh&q`|hGn=}q53*$oCbK|*(R0B7^aOa^t!ru49UO@tzsB98;q_(B3Ftf7l}hLZMMN# zk!QFYGEF6H0EMo-GbcK{L#$#IqEmSpGeXp%wWS7apawhxjW6OW-#E<0th`5ig3O}= zMxg?}wM@{XqtffNB_M-5(jyO8MbfN2MS|P_`I<>uty%s|o7&u@UehFB^Q749Jx&_c zv~grk;s7_24&%cBH!40Yc!q0Owiu~47Fo^}nTD&xvYo;{9$AYX8CGzTITdyZlxRBa zDGDgLoG*BSWI?~q$>r5a$M#DwF`+=Zv(mXe?#35q(DogWaE!uUys9+kp< z`zBoBg?S_ftUOY!#IlRg%3k$CtgI^@$`^%UY5pX7L#E{_ICMrBc?Kh%r6zu2F@0ie zfCgHP;zyuMyVM03YSTkZylIezvMpPrhM}Y$3@(!fX<)ouhz8!^)5LTcUsy~tIwLkt zj!bg~XYkwY_**(6nnex8)Jp;nh}7D1>#=c9P0O{# zU;NGAEIwfj#wf@IR6-G2YR2f3w!dMA!1&d1c&-upksz7aZDfh`+1-LZ7AX0yW-?yz zEFJaI5-|ZU^=ejj#HK9Rg%*suTzQCYb>`aE$9||d1(R2bJ74#`f(7hPwprihP+xAo zk}ntr2=mDv)5uS00&nCVbly%4WEJsA{#XxX<(6zu80=^FItG~R=YBQ@m?RS8xQLC# zie8W)2`X8XC9;u)p!Ja;^=X2TGzk&j(O!tUmWb&25wRa7hI#y^VhB4d%Y~q7(gSx+ z5*k`+AR!VGDtKr+%7BI;QVg#eqRo)Qwv44W6I19D)8O*06yXNcwHs8j2F0!hNO%Mm zZz5zMYAnvnwcQ3ST3e)Evu%j#XV9UjUcA8rBj1?Ytk&u@)&kARTh5V8zMV|a^BL{P z%%ahw$QlBzF|9{}5G;Q+)w(s`13pdyw%@~mTI@Ant7~1{MG@ctFb_W6oMhmnf#?w3 z8IS@mAaOB;hF9u_R$`H+I-#Kc`jL6Sz8=B8ekN9pCNY=r#%Vc-3jE#eLa%ltFDh^X z)do-V1f9@v0`uB}k`%F9XbE+=N82X#{Oeu-vnTdTbyc4d_8rhNY4vS}j^?cba25cC z_#T3?3JsfxGO`E@zKUHp*_7G^UhvQsRNw+mhZh9zWMB4Xhe>_@ZgdcU=ic@5fhi5d z;H@Y*t(b2c)o-fn;QKZS42|f0!{}Dt)_o%eW@yiO>}XvW(xFB0q6)jAWrv`x3wEG} zE|iC?dKia+m|U$pzJWs}W|0*UaU@nHtbJk?QS8&D)f2gfiCH4M%!PRgV=l(=xsnD# zbZQ;n25r!Bd7(C>mg@eLK{Vh1j>Ck+CXlo>UL!HU#4z~0InoYJ)Xeb+#U)SzD~H7g z=~Uf&O*8+sP~BWoMP#ElRbHgrP;K+NHr2iEq}lY%_M<;DX>Wp7vcG_hlP?(&lwrU-BeRcH2BDIS40sZf|TAtB?v=))vp69CRLM;aFgb z1t*FPZ|k&9@YZK&Z(t!C_Fs6qhY+8UJwhYw7KRpgisl8apt||tg_5}F9!2*OleuDm z-fxmQb8!A+F#ZQ)z{(~S>B#O?8IEju2!}9~VRD$V%jl{iio-YK@Pxk+B%YBOK}K#s zMieRWyP;K|KHY0TB~*~&Gerh)*!aQtcxnI$Y16g|l(y~QHfjmANz?XB8?}PbqEXAG z>()h#x|-bb)uf3pEh0re$wKAH6EP~ohzaA8jLR@%X40Iw#3qw5OPCBXp~7bh6hc#& zKv7f$il0J@iZCh^gisM8Oo#wc6$DfiScOJ4!NCNGqF}*3HCmMG)~8TGz?k8d#tgVF z-nxKR%^Ejsc)4-2rcE2SgYMR?V<(RtJ9zNs!9zzb9y)aC%%xj)?lQAv=a^+yCQMl{ zVZwg>{sLzD3otKVR&)8nWeXK5Tx8FtvgOH^D!FsVuEOQXN!hlm#I{Yv3$tR%k|kr- zi_Fb`_c%PpFvbJ>L%Qg+TU>3C?)Ig-Ug*@y9X zXkt9NII)W`EcOE7f(`Z(OfW3^B4aQ!_M%KL$>iu`jz2EPTr$OE)}xWdEJMsP%q+7^ zGEYjmj5$*tGtD@N6$XzxS+Y}@VeS|<&N%W+W7s-}xzkQJ+H}*6H-Jgw4PR{n<_(_y zeCeqtHhuYtO`m}3g-tbt3R=xIh!T1Yqp3gw2`G=?A^>MVn7=7C)J$XPG?xw}jX?+z z#Lz?9Z1dMM1VO_oMHcCj%Pp*abPGryjpRiZB4vRRN?@!MQy5r`A(Kos(X_-(#4gd( zPe=uIf>20t71gs37S%JU-QeknRt_$tDHG>p$ zy{knvh3W;^U(i_dj5ma>b0%W$kRuN~dB$XsZV%yOA=77WYH7Zy#JmECK;w}UNcw=ZV2jk1%!GIPdjWhm;WG}q1%!`xCC|RU)OFrr3F_Js^ zq&Za{Q>8i6$V28~Y06VrnQ5{^raOm$9?f9vxYNxuZ+g=WH`>J6CSTs*g$-bQ_4$qO z)&%PNpoQ9t%{9m;T4gCN}UX0I7ML?ja@KKLqNhId<;z`O_MlY09j3_PR7EVe=<(gy;W@N5PRQ@uiIc|ZDafHJ# z@;FR1MmLYtIrA`vVVz;JIl4B<&Kh*;23~qcr`qXhFToSupadm6;ekSVh^p5$Qo*R^ zq2d#dxaU1_VG)9SDk7bd1}+-14QO~{8-dxLL$m>nfO4uL=VKK{BFd5WHDM$bB?)l4 z;Eav71Pb^ggBbcJtePxA2|F2}QW7W@m1?CaRe2z`9EcSPK8ph$h#*!DSW{?;%LEwM zO1MCX0uHzfUPgtB6lkyoXb{Rz+|Zpjx6zJi#E^7|Sxhd%fevwuXmf4bOp`XlGU%|( zL838@7E)s|jQxgVBcqLQgj1U*yrzjv{K9^a7>r{0VmY9J{*IB7(F|miagByOEMgP8 z4>I7jJ-ty69@)dRInvQLQ9y~(vap3OWC0jjNace@qlE}ftqD#LO@t1_paR9HMZTzI z6WErpwYd#$a_bP>a{EbhNG5X~q0wj!*Tq%BY!^N9TQXwli)1XfNV#M#bIN96&7k)~)kGj-umlk2o8CV3PfG0u!eoahu^zJ$|H=G+UQ@}d`X z3JOs3Y#yQ-C1B@Wqn^^6-YTd!4Ne_|8VoszLq-)R@j1jV4_T=9E=4``u_`05x(G$# zrv)#37B^sUhD%V)E16(H3}f)$Oq76=oSgJ5PT`9Fjhj-fms-VvFTK_Sn{uujuf;25 zF&9{%azL+ea9l?&N(^XV!Wm$|gj06QEv!)}KSATE2AOI*+JP8?$wM4mrOf7R3*HN< z?HtYFOb{OynzNeb7hYH^XIaA=En4w6yt!3N&9JYfJ%=mIdZ;DiOGl0d>((0{rX8ZYRLG)1f$ zf`kE#UVMZ?Uya8(5{8br<+j)(vLR%|0grf?86CuE!f|T^GsE$y7uF6&g{+<2A|<0j z+umg{ic!mD@Ip%1UB)q#L?wn*u5!h+Oy>TmbPREzLmulL6Jl`jOwb+XbEhNBmk`4a z2k%KwT{dT*(3uzg3MzU2O`gMz_uq-90u|M$cq*Xx2uMjvpQHNTUnu;S+HH?7A%6xp zpz#Q51eE0uMc?`^@~T*gIDWXH!ihH;1{LSeB{PA-NNFPDB@n^JOnHh+TWXaZ|2PC9 z_<&SG0QC^8%cUM@%2&*lt*KDufaPK`TC`%Wrj$yY=?~}pIW`4ON(0ryr05Z*5E#`$mFa9c>!ph%qZ2$(z(n1G=IDx`uuWt=@dLZmzbG=Kv^NCPxHSVNp(oHWEk zkQ2UGLzg`RG^pG{>60!{L;9=_M#PFQ_(IJ+ffn3GOX!@6-A}LpOR&6HvFOASctE$T zMOiFekVRbxScTI)od|?L{uN#!wOG)%tc3>rvLxJi*Z*&FsyF$;c5EWC5W?jc5pxXe>zB zjK=VJ&DQ*fNO%p@M9nb}!!5)EZoLgx^+iG$i?&N<{l=9n38(c73sLk!uQJdoEjrI+WBgAB1l zH1Xr-j04J*(=%B9!+jY_UK~%uJzVoN4=Bu&#i0VDXkZ6!pebx1^gx0=sT?jSgs413 z3u*%{cmv9z+{lqrU+ha?h#>W>WG>)fhh+pu+=3I_Lf+hst<;JZ31SQ#$kx*Q` zOI#$C6imaG5hOR@LNqL!CrQ#L>D?c8(%z*5SA9sEF~d1{QFCk_#R$Wl0cL6-5n&Em z6&WU>?MLNN;%4#37yJU}HCJXdM{_JkGc?CNfTCt@X3p#b&p;MRfZBc3hZJZU(aeW^ zpvPrJfn@%nMiEg=YrUFmy4r%wnbsVVg1{Oh2>`hjL$RF$GmglxEu%5)9b^zgA4UfD zL542;LMtstFEkhDB~Foe8!d%fxA9Ujyr1R-6EWl;c!AgbnS(eaQy%ixTk=*oh(j~g zH0;KltHqHLf%L8L@(pawoD zDMSw_Knf^O&tFJ`N5)A4I)t9|PRen^U1&o!Bp@hg~1 zI73UEnEkBSOo)`QFhNm@i?k%AwKyFJ23tVVfHE6>)hy(R)60v>KG4x?NtSMKS2v;pbae7D(4Pv83 z%n<3CX{g2#ArW2O9OWqy614`QHYQ;nQEJ=*Uz#5wI?iiBM`p|nXHF`mg2z5MLn|^3 zYm(X>-AAX&2YQ$cWj%ot1ORFX!)b}lY8}Xb$fklYNZ5pgXb90RG{FEYgD!mMGD?y& z(i`3Ip>hsq-YuhDrb7WlCy{8|EbUU+a2wf37dUPwc7sOtPc+!zsz?;9@Int>6h?`} zFsRr@{p7Fwii^pFP?FRVv;a~9Sr!HLp% zW?gL&p}K~l@~Iazrdp*MYCKF?u?%zk$Yd7D!;oI3{w?5M$33KC>&;Of+1}BthZM+O zZ_Ea3_J$J(z!Th=7f20mp4BK-O)UZ@j8ILBc+JEVz%m2?Z=r}|NJe@7GTT;ll8AUn z-iZi2ct|cFtG4k1b|Q)5C{B@JXSor>b%h(cm0P-P&M^=#c%CD9ngepSBfUiiz3m;n z(HlG@hP?$$nSf5}3`YNzNj7z_K`|gZ5h%a96FgPmLKawoZD2e(=!0rtMWTYi#&3jv z0;E8Kq%iD-hMYEF1IiKPh~fo*o}^x2EcLLQOX@<$Mii{vLNADfN8F063_}>`ii+_{ z%gO|d1szocSxn9B7II-z;%pUuzy{##kV+i~NF}vQg&Ly3)h&gzI7Jvb1-FO`P(cfm zl>k}Bh19x$6iC4`lxKO`rDS+gT%yC8nn-c#-P%ybhy)v(VFv!3HJae$sc4`EP4RAy5QnQfj_cluYh$3Nve9Ffkk>wDi8a9k_jXD5 z<|jLNLqblV1TJI+USK?-Z-X+ZgTAi@o&qWy?7^Nw{9YveMhYY#Lpbe)@Nj5fcwg4ECIO$>CF0Ul4>DAe}F-Y zzy?fRLhI~7LtPiH#k$Ot8bVx@eG;mC#te#SDBw>AvHzt*M8k?$%O9 z_MvC7;iV4+-oxxjXgo}ToULo}>1u4&5_xeYX5L^b;vcOH#F()elkw(7hs?0C8!z=I zw$UA>BB&;AY)FBA%*QF(9v58JNeqo|Y(Zxkh^w(GYaNmme@!5JhBEkq6EH&n9K#>J zV?1CVdfMgnku=|t!--f#JiK#->=G~7F0+zy*#LGgr7|%vN#)!^@os1Fey6;#a^`GR zxH2zg$*PLXY&=FEv2JH|z^w3}gbHBmk>WI)Uf}sw6I)N;I^jE}*FT za0G>DK}gJV7VLsEl&l2XXg&kWP?EtCkU7T6oKniHiqVWlxP^Seyk`V1QVf5F94e3`9XNAdK7;KryZj!a#<&+Ez)cS=&^O z4?zjuLWdZAuActF#dty7-o~Kjbf4bYO{-PK+?i*+*^xjh%jA+5-8iH%wT_=&KZJoC z|G3e}5zx%hWZ51mo<#2rzyNd&-ds)oXi?3a&8jfm$dp(4-%R^7fziP`Yb_j00%f7)X6tgwzsvXaL(R0wuqrq5V(?U%TQUxStME54Ovuh zz`MZ3)5--6cmbQ9S+Wi1WPtuFoN|(G5u@B>4xRRp%Rt9xRB>qSX&9?GqJr^HSK?qA zylIR^%V^?cwhUz^8X?+4VePoaN7|*L2XJI{(6~p@&_{g~jghMd1_*!vTn#V`03lt? z)p(8O_RTLS1AxE`T8Bm{rFB~0LIDh0aUNqQE#q)K4H;`aKg9i~NRJf2~Lx&F`MwEz<9~mxOszj+$-AGvFlD!R=@J)jDmruV&}EI6 zj%rqO>Cj=?1Sa_t_|tJkhwW5@oA6K75wx?|`B ziz5dXan`Kx9K(Yr4j#G6k|nPr=T08G&hFTSmIr#>xX|u6k4DWIwY6)gs-?O%yV`8o zvq7OU^%_+wRKI=a{(b6{ZsNy@lR7nO`6yDRMnxYb=@X>tpdNv%X3ZM6YS^G*>;Byu zHu2TaV*@1~yn623p+VC&O&T<6xOC;puj^KSV!m$a<(4Lz&?2T`oEZiTFc1X8nJ^xN zB8)M@2t$l9FeC#*44GKMgAhOjQG^gi9Pxt0R#|GFrh~vLBPOA5KIvAMixV-j()sF~bIf7p9A=hLh8bpnT1pt8gaHPaUknB2i z)Qc|+g%nXp4^0%&L<<#WmtK-dMww2T>D13;iUBm4UV;f#)L!zL$kkV2jaAlJ9oi?1 zjW+s7ij*``38h>!`lzEQd?nVSk}lH1iJN|@iKm^Qb?RB5cJf81YMXM(m!_7w#ffE> zF@`a6vJy9}HwB{#ta!wQ=PEbFisu$$cv*&+x%7f7uDs~t>n_0b5{DRZjuFQgV+8(d z4B>oX$!EO`crbDQz6o*!lRg)K*((wc4OT1d6i6Ter@W=HA+Krk)Z?bS@2Cdv8c?<~@0n+$ z=^B^&bit25{&*=nKrMXHVizscc4ikboN@3$F)FN^!n-$wVnZcxRFMN0LHs}j4n%0N z#llAn0Y@28OwmNdNd#d>$*W8fNhC1UnPHql7E$U;$IyntR&O8%EOv`}Dn z;i=hQb^*2cPLm1sQ&0a42GsGL5s23H*>B(dS)IYCqmDA#$Ru1p@@ONCoWNE8Cy4ct zEI45RG@;2annjac?1Uz$+DTJ@l8l;25LKMol&DS>ms?|09STV<0 z*d-Qmf$$i-sLNdXq8EGVB^Pn2%U=q13xWyEU;`UiVT|Dza-ky^=pa`(Dnl8HVP+ig z7>8v{R}HyxPdkER1F&C0S|ht{sBouB2pXLkj8!R zqaXd;fv0SCk+1s6!6 zbyA3e6u7`9uj5KE3{9v{n30t8CBqk@`X{GC1t?x{N*(HZ-$y|jQjq%N3i{K?7EFSX{0WOAE!AI0 zO!9?-0^&xFr-ghO^~@t0k6xD0dL@uPG>t8qanJH?KWUT4pYEW}&)PxZ=leH`xVW5`7CIY z!?Qb*;*O@hBWm?1iq$&86xK-^G^&B?ME*kUJC8_@ctGLENbYt$-I1Clp@9qhKx03- z@XuTNbBkT43sFH+GhbM!Y6p=bl-mQjq*T_VY? zw{x0{=6{1^0&Q}@1vT)uzhwY}7Vww9EAa0)$(eA4SHTNpLDN{?M8b4*Fs{7I>YH{q zmfe}@EBw4u_=xAHY$>Bz3ePB*h74uN}BBL+nRQO)}r+xsL=RNm1 zLHYr#Cvc%yN-pwBMFK4UsU!+d82X|Hc&!BrV_QoJ#!X;$%{F37#L%O>(2&LYo84k4#7<3GDvjd#Bu>x z#V@`yfHkaV3cDKBumd%V4Ws2d2F7-5V;$3QEa$7y8#Mw)v&9*89OKBG=FD*vpExZZ zL$OEH?okwdTy4>+^N4H&dp+CXy)|%+>qz4I8n~|QcEYnAZd6hm@xg^4gFCi5L)*Ba z6lF7-;f(AfsN39@Zn!n1ArR0=M&~~7EjN(fzzL51H98#oQv}}hs`p7fqA%)BAf+U^ z;0e4SMij2V-}c5T#I1ETDQ~#Res(#7E??j48tI%Wy8Ej7J%E z?&pMX2tTSHx`2L~EG1HcB$}>%j3uUs?&wBB$_l^<5NPBc$SEXhDLzFhPDL4H>{Kx5 z<~pSqctOI}Wh#Kkog$7a6l3B($Xybwg!0Vq>~5?G=3o#e?-HZ$1T7o@QP3>Li6Fyb z7)>&=h#W%0G6Ku64oe=^f$}hhu`X?~GR?6Z3ye7L^V-21+QAw`&5b+@vr?@TQ!S53 z>-A1c6k@IRX0MM@OA?62XjTCnpn)60!#o-ZJ#sBQf^9o;E4Fyi_`X9MtfBdoEkBY` zlj^J(0>l@3L6rWq0QYTz81954_2dVCf*Fd!SynE35am)bWhHZ>%6dWtkq1yd zrFdqtQ+lCz!j4b=gm~(K2z~M=XN4cEfFzcXSfrpNKq3l=Zhr7bf2e>9G{WgPf`9^` z0B+)etZpfq;LAAWsKy6;K4mG&kW+{u8NekO{LdV80Wm6U&D4b)q-reWWh)@VDprUp zj3F=b?*15Z;jI1)VfqZs0B>OcG11U$(EtmI3U3kFp|3!r5ko@~9TC$qjS^R58zL(c zJCPF|iyPJ`XX5D8K8v)3rq!f_6j)IdWKT6~PZM0R_9UT?WD)nQ!xo1vYn}!aZYyhs zjXjoT*w({5jxE`g?fIfFKZqe0%n&MiK?|DT7qBln5o8#|0B*8zL%vUz#^44*r2I?- zM@(c!9EU{K(M8A&M!M6yLPSK~QNDcS3Yvfy5C&lcZ!mh{3a(%Z1`r2ipda z{;tYatV6es<~HA10X4@ zUgcqZV~=8u_G*tcSv3?~ z(=}z$5pd6Fw4*krCfE?k_n-!mf^(9J?PZ6KS#Nh6d@Ve6*~%wZl-=p5!rgw*LS zo$4xb=oT(49W;z%hvyt}VPik`9ANYYlcy&R1;tdBP+qRedWtD{%1=@y8Ft|oUNlBY z1t-CUc{82S=n3WokK|1uoLjvN4S z(CkX^_VkGo4G<^h(45GxD#J6fs1Z?vi$2CQByUmMVI3Tcu)+v4ITI5-(Xq6l6T3kh z;OIC$3ulzWj^?N|rDKm!^YvI0wO})~R@F6AOA}soHfK>g;$s-025Wv%Jh+3`cFU0{ zDL#@-kd`q&oXr^egBJi~Q?PFrPRSXhH$fcaTIpsC=w?DD1Pd}`49F{8afwF6>s!Ms za0UlPXau|7jr~T1MZW7>cce#dVH&ofUdO>+@e~k~Xc(+u9|IQP`Z1ei00jEeoT{Ke zn=+l~5bek!;vVt>%_J}JBpsN+9PEW7_i3#7i6c33cuFPbjQ#>9H3fl8j>TLSd1^2P zJ9Mf1WG8i!c!(z%Hq3%8m>Kv%XmL1b_u(EuqGgHrj8Nv>WxpoB)kusj1%Q$sREBhwC9Gcj@V zFm;kWQ5xEz8$LIay`dYt;Tn)bIiQ0%_Gmdu(==PJv{sdmT-SADvo%%oRbf{XBte#m zCOfhLlAPumyaO5_A#2bh6%Ogw*drK;w>Xm#Kaf><{-FXHZUGv5VN-^o7ly&wxKG=- z?c1~$y2hYe&+Bi1=|pbnalng2(ic6)>s-xwMuw?GCI=d%p;D(I8sgb74G$f>AV2># z0R4?W`;!A~0Gn#yD4P;jF5+Pz!-R||Vb%$%+^kNDVW0MiLN%-y#!7f18iU2k<3y4v zs!R*0tR)AfB!fx?QB>>1%zJdwPl$&Z^yL_a2VD3>tZFoeY1&5bfhADloaToL1eyx0 zzy)yN1~`BPQeXw_=OUCCsfiBC24DaRV1X(s7-WnL!DlVDlr7*w#^{1e!9|9Sfuai_ z!Qjb=vWh_`L#igOOwS_CreZSG3NZIL(FDW(j&q?f#~~N^7LfB4Px16mqbQLL>tiC5 z(nf>w4jD8+CNw6OawF?f9cyzp(;K{@b1`|7y@4Af+Z#Z^6r;oSNZC19ZPi$JRb3Z$ zV;Oc`)m3SCc4>JQA7K?h;g*Frx8MU9tpOBpZ99e!J-nm%p5_ta!+4K37xL2C>dY55 z3L2w%7@SqPlxsmA#JR#iy25~axwQmFfCR`B9LrNjW~9491U$_*oK-|d!1Eooz&_r2 z8s<3~@)|D7!3(4SKLM5>`?CfPwggSUkpxH7u zGE2kmtLF|a=R#j*s3Lu5!rYcCZb2^NYEDon4&wnX1!K_a)L_souk&G} zey1pl{7N*ci1Ik&kPjOYDUYxs5wRoDk|ViuJ<$^{)e{k2lP7zVIeC*)foD!36il<# zB!Q1a0X1u{6=V0)H6iw1m3B#;wP{xtQT-E0!5*;Ywqr}Sa%+*MW@>yf*KQlP!UMRU zPq>pYKk^b;c_Bb{0UD9vS^nKdLAX!4Dn>DyUufQu037f zPe*tJ7rN%1>o=b7SAQXc3a+4kqu^ipu^(#yzhq!cQc5JaU<;zwuRaKE)deixL@w&& zrOiRZE{vZb{K7hxEGU#1G>ju*x@UD#%v2DlQn;r&3rX z&hOg2$>Dy-0TwhKnH4WB|ReC|4T1;Zh$}vLBU`yWx_#K^nB- zbGd<#Hdz}mJCR7?6GEBQ@Q4&p3pG)5_B4G}U77Pmozy`;^floUWKotwp*p~Ujj{m} zn&ui}J(AKx7=zJ0rUn~;yF7wVkct%-^y6TRn-~J57oag2q7zz|tC}lB*(D@Ho_!t7 zOT0z|12AAb(bt<3hj7?+{mL`j%g=E*Kt8&L8sOPpqrtuL3LWq>{l!TDYv2H100s{B z3Wl7>pYkc~y%)#^)Xn=kIGbbWaf*ROl2EoE_-Q^S+RoW%oSS(k=Z$h$Bs#? zw@;tarA(VTeF`r{SKs6_cXBL|BUDpH&<>%nYUvnNh?c)}$Mmn~f8 z)|ETgix({e3KYAQtQaq4w{G72S?niJVu=wSTUPWI(Z}M5nM-#IUAlPa(3$IOES@-Y z$2!N07y5KOa_~-vg9neCJaXZ3jms5{cI|QE#)S*#dt9{J<7kgNK73m6Xwlfod+u)B zI(F`+t&?|sojYpJ*-gjJZk#)L?x@R?)~?;QcHP=}d(YlmxB2qvzxSq%n|^NItdTku z$|(KU!5LSpGg_l$qi6)Xr@(GCGWCKk#)nHRi ziO_&jjWwXS2n{yaSYyqJGGcR0j3%Op;v>~Og3BY&;6h|Bx!{tEF}d853o*PPa|bWNebnYpFog(l8%`@6iBh56DP7@6^&9OrcI#y6|MGZ4d0cs6Xcq&5) zFUT;06jjv4YO7qFGmkv2adz4*14#swIR^C<(NN3i`fE?i5OWbvJ3T~@u0qLF)BZ=v z1oO)-EPdqBw9K+J)3P0DbPhAbFr(39Kt(i>Imh%=lsUxMqgA`^z6)=>@@AD(r!}_F{YF7ip!%{KR`{hof_@W_LI4@#)XgA-nOVTOupc!?yMIPxKgtALYAiZr(P{vwT#mD!AW$!Y2q55Mjib_>zYR6kBM@Zs}X(=Na)anJbm=O#QzQiU50SZJU0xn_wsv+j8p#vYou6gNjhdk`z zy!g?Ndyqj8El@$gfN%m6sGtL9S)vL6CNQ_O#a~^h%NMxt1uszk;R^@*g2S9pfL;7T zNb_j_Ghs9?j7Xbv!v8@n~lq_n}WW zo4JlI-muRNrKJ*DlfMXTe zFwu@KH=}HJ4s$h<5hzNOO&jU*b3hu>>W;)dBN5{kPKr`9n9&T93}Y9=sOOfP(S>0I z&r4r|!kApZ0X2<)10>+no|;#uKFz633*FNP5+$dHBI^E6f%22~q5zFXISLw)+D0@a zbt!oqqYG59LKUtszbK6Ae)?-^SL%YWgJJOtct#<&m9sx2d!*2tJV-LHammIY+h3vq1i?^!y(5y zm?IseNfK#HyR9ar!?mipBO0PqY7zKzYVP%4c|E8?Tg`eDWhp{^ZA& zx8%l*^kWJE39dlDWRNCGaUsK%VnT&uFET5n%=pIlnUMnrI8>31RHOnF+^A9KN~g;i zrRYSUcm^o2!QUF~h@3)#hAvcxi*Q6kowK`z#^70uVIX4|z3@dnhrv7EeTkpK6N8w@ z@PZMjNlhZyzy?4NzUe76Pzp7a^g=+rgW`Aqg0j<`a_j^eHA))Vct$3vp}uL9N2Fco zf)(U<1(mWCe>H$X4OVqUD-L!p@-X0QY!*nDNhBS`FxR<^+Cq##zRiE|L5z=IZ9;9lwH1bo3gv%Vf{xAnKYDhzgDB2k2AS*h`Q4fBsb<&is^j7xK zk4BJzES#2NT9Vk;6YR@~Q)G(~2j+neV4$#AWEdA;{e>*(#S2XkfRq-4>yXKDWF>=4 z#>~;AqKIR&b3Ddo#SzHUqzr*ML&rRD<};niqc}Uug*@URk8rR?Rz4ffaENnUA`2 z0j@#AEZi?61fj&eSD77RCVZLM%*Hh?a-WzSD5`n7&!OlUqr0Z(Zo~~1wJ1dgz7flX z6r|PZV#4YqhB2aq3}*Bqp1tV)#fOK{jCx{ecfSjs@SsqG7^t`eAtbE3hFD{R3EU3fwi=10H#?N3y8Vf9?H=tZfG zV;;{oplXb$(OjAp_Aw*_M`YU^^`y`INJb6R zu?|;4Qt&ecRzN?XLIe6E15dC8|3eprby#1}3(g@c>|j8C=Q2TcK@AZsJz*JZb{P`n z5a%Lj$&wDl^8PCVab{SR486b$lb0{d2}XdU{yn=S9*;$R;95=H)9U@;Cj2r zi}BJ{W1tpk@kCH$S7*_Cqb4u_vqWfNdu8!yCeQ&n5EoqJ1+n%8z>o#N@C6Su0MjQJ zj4?9ez-uN`N8Wb~xlkFW=Q_hC4oQM+E`vbO)><{=e(=B!H4_fAkx0$~8_{5oQ$r5a zAa1^KNzx&ZlVTm2v<;ZVH4C|r4e1WJz%)=}N=$`f;E|Ok+5+evI?t^3fb_3G?+~YMqn+1VBO>* zCvpux{x~B+D1?vjO+@ktxTf1P_)9*Pve}0u5sK4CfOm9kn&?5DZk{WKT8)^Ya9w zvQju81IdR))mV+N)(hm}S~jIxoDp~g!Dc@35W@1A84*WFbr}NTc|%bQ#R4vO)(gzy zn#|HIt;mXV))R1sD`906WVJ`RIU2}D4xgb8lGcmENt{)&4@)q6!gm&C0gVE~M053f zMudBA(O0ClM9HXo{_+A{FqwxnncCO{S)c{JV2T64YY6c=BvTBVWoCCoY?X0G=y(hM z!?sytHC8>NS~UZIK4Xup5r5&~T8ZQi|0o^sU@5@S980r**0B!Kph=kofDF104v9(a zP$|!ahuVQ0?9dKU6CL642(A?!<>8UqV4@UQa3<+p`jJbcBO@mQqc}ne5EpR}Qi3gM zg3Y8M7H5+^+DwrU2`ktkL8_C~R5_{OA|-btB{w>KsbHbwgGic`IC2d`m{F<&4Y)C3 zwQ+NWp%L#S6IK#*_5_wxNQJ>eCNKa4BTy=8awusS0)eu1aSBm-qELlmCok4wBk%-G zpbMaI3Z`HR`jwZ~6eHyW4cc%%)1W@<&<^eZ24K(ySI`9~B|lPNFZc5TSO)%UujU27 zPz(X;T3u!{<@Z1pku2s?XQ5eU=Tc@GR1hLlo0}+TJaK1y7I~}~XawPT>A(z}8H*CJ zN5i^DjMkgtKn}ixdsUs*=@uQ(0mtV7 zQxI#w;04*3je4PtzYs0HPyhiyGQqZ4%Wy|_G@o{4GWLmj?KoEG2sGg!TBkuY{uvGN z0DtbsZRAi>NmEnr7akG&G`LWZ>%%pgv<|s&vHrIW59z4X(6J%g4%{(HQ!^fSsAS!d zZo?IU(a@3J;j-I6k_X2PPFk}o8lyMzgGvbsA81U+ByknuI2a<6JpM`{ILSCSd6Pgo z370SlI2k#bunMZ63aOw9C1OniKso~kgrRd_NQojzsh3F!3Ql>YLqZL>z#O{JQygOu zKM{HF?V zuwVL>BP>!&MJ5d(D-8?zs9(?pTd)Q3Q&Ls%hd3}QE)WHi`JIJTjmFR%UDjpKrc?27 zD+)0#x}q!Jrw|#TXhY!>4dD=On-LdeXgP5)S(Ot(5u3Jpnwv;G7E%k zd!%jVkSV(OtljIZ_W%S=w4B;Ht^u!&<-mb#Z`>Ok>CicaXJEb@&f*_3d9r&pMW5y@Cm7a3WHky##L$})}Rd;B@NHOQA*~hV6X*} z+GKo)Qd1BGq9Q7arHy!(MfeL0vJnm}D>Zx<8Ztw>m+=z{F*474EWq--L-7!h(L%hM z3$eN@kkyL2;${iai35=kw_+5Y!Ds-xG75Y%+iVQ3qiy-Xtllfmym$}!au)F07E07< z{jx7jBx>1uYENXorlxA*+5%VbsrY-1`Ha6!05Jv71m9>fHYaTTYDe)2!PmRM>=QJu zvsycoH1N={3)nvPm^4$vGz%z74rnR4B`Lm@!ZYlU3OS+b;SK7s4btEZ=QB!J^IR7> zN~$!NQNtb7L0qK7O8w<>-o+y_GNm{Ywm<$@#z1%trtp&Mm7_b#AykaTKdPfY+96B3 zf{`N$s^D?eq;jCs(`YQVZQRv63xud(gWqIMXhdhXa1N)K5lmPNI~NQO+?Vs~36 zVSoiM-~upE0;rOODwd}bWj);kC*kt}EuaKs&=11N3La8|ep4WVY6_?zxtVNDoIHn_ zdpV? z5wXdNr%7kG0#pz*5T4O!qam!m`Hsj6G(bZenKBN-InL4DdiOvCy0kHrwdNNKCokKr^k-&n82u48v%P8 zyMb)c09&*1kL+;T?+3Bu@LUcnN?hZB7pp!F`q2xC!VcN7{&&*qfzl((9%%y&n6x$1 zW*!Xa97@)aG93*Fs2!x_4l)}$p#u#}8H7GKwn<6U*MJH|4aG()lRYk9EC{4dy|fvp z2|$XIRZOI%unM41wLNJ~K>eahDYk5E<9S)eUcFyH5)Goq4AjTlnTHWVK@1hc5xpQ! zaSdW3Mum4vCRG*#YN}!ZH3A#JbQR@LfV~1aKn92%&Pt&Qj>8}VatebE+4`k&)>LGU z@|Ww;4dW20p8Eup>e*4i{)aBm%Ad;5pZW`4@Cy0$_q^}0J`9g zo2B3Fh~Gfd&Fs^T{@RYe@f!l33leS7_DG;pel_U?Uz|qaEYnvP(vQFRM!6u?_*Iq&Nb$V%xP~o#Q_! z*+EN_MSgKl-J>}E*|b6q6hg!L43TLPAJ9R^6JrY^9zYocNwAgA6_C?G%vZk5d)?|UxHqoA*8(*_12o_QGf!_0ApcEdmocrM-3lQG6wUgG) zo560{+G*S74Hva>>)fpy=T2TUckJX%lb2E6IC<;j$Nk_#T3OM2Spaikueu?!jX}kesa@sM;?3h@kbzo z6mm!+i|mmf4^l|sge6rtp@R;VWYPl@ROsLY6--D$1rIvlQUx%#?2<|+JE+nF4><4u z0~cm+69x>NAkT~Rd~pH*CwM6)mvF){CKna`G)5di`Rr4ia0u;_Pl$4frq6K3{s||S zao{R(Spj)@uMjB~! zJ;)nvx)C;^VYTVi(~&xgCM1!l>4=?aEMnCnYTU6X7m+N2BrUXT!p1G0bTXx_w%9^t zTvU3yq&K39(&VXjhl=Vdr6y6T5_;`j3M;7WeM%`ux>^OSR8$!Y8gOL-7p|UA0g9V& zF1#?AVu(owuLm#03&CWFQ4FzjlEH8&&wmY5zXj8|B|&k{sqjJ# z`5Vlf1B)r(Kn?%<3&0HxXI#K^;z_4O{rc`4KX^`j(ZyS8ywOHUWyEy#amKNSXd`2n zeRkSww;eYkq)fpBCb69I1P{P;(#b8cB;HEhPv||#-A!l#gcjO#QwkTxOHYemcG02< zUx*>5fLp{dX3#$WR5VdY4TW?ZKF4{KQfi`kRMXbo3CF#4@?Qs|h$7OTnpfqo9kXhO zu3$wfRq1LS4H?KZ1oEqfc!L_<02T$i@r9s!9*5g0FgA!Vx}%%DM!XcGFNXOGUceX_W+WpS&7fm5 zAVZm9TqX>|$V?xh5HlByzy&3sSqVt6vz~E4Xhp)uQIIBzQH&xKrWl1OPT{Z`LSrV? zc!o8eQMCsa18mmW!WOK+9V&PyJWnVO+|=_*VJw3_@CY5=*b$HUgoBpoz)vq7q#wTo z4ljdSkT}E`7!CC&7aNNZF&1Q({yft|{Mk?EGItEkk*JsOu#x_aWQ3ykc=J6ql2ka! zv5tJu26ne&XFJ{b&LEM&N+?j0@|YAQ-&Lstyc3?2m=q=zNXd8pIi3T%> zf_b!%o?YzX7rh{c6AC~+WB3VD-Gmf5!pT1N@hKYan^dGmN{voQq*K-Mpa0f@(p4=` ze-2dD0^5=WL$i;<-p+;u-C5(pwj2ro~jKtuDv27esG5#nvM?0o$Ws$jzGn~;GD7b(I zE^q4mTI_!lb(b|1$Xha>Qtu-*13Wej4Orj zY~gLd5C(IF@myhq2u1Wc(R^@;qR`DlbG$T=f(*2bUmjy{3Q7lo7Q`Si4#*q@3fy|r z%eiW9E_3=hkv22O%Xp~BMK1ED>O2~$_q5JE{!1r34SZk(vvVK!SW=Wsz&qtR3Bv!x z58_aj*;TR zedCzMN!?efjEtil{evp2PIanVk?P23Y3EYKU%5b997u@GVfi)MpA=? zHE93~I=QfxwK!rCt7Zhq5-GE%BmxO^_|GEGXkkwNI@YqL;%Vp7^PW+03RB3dT}1q$ zTk$msBhKrtiB_~#Br%n*fJGInAWIg@g%eDU6_csJ#f5mm7rrCIdo_0B5@B1JkU9toeFUN+)popD5M39Z$o37$Kpjq7gtQiz-#8lEwlH@?@XxN`lXz)i$t( z5DFd@SilMvG|Zk5Z#W0;(!fR6Nz!AKNTh@#5y?nS*g7_M$|Bx~;ahAN*iA#NhUfZo zaR|MXO4tiuK&(XND=*i)Ucz3EFd|m|m1wLuF^U5VOAQ0N_#0ls&v9`YE(WK@jge78 zYD6O#kMU{8f^1~WKt^AJQH=g(^di=g0RtFltr^bDKy9RTK@3Kt>k)il1+A5x(T4KK zV^eYzpBPsSvB+#|KpPs(4cphikOeDj;R@REP86)*b8kcUxxq+AI%s*H`;!CV^m&nX z=dth-xtwG&hr&n)X3!4_S+BgHkje?12HBhl5r@F>oX+7KUs^bXiw8f^E?$}k8c`hp zdyipa!W6l}}lf z0lJk10-#m#scG;jT>dx+unV(ofQ|u& zBRrC}%MgRj2!ksiEzl^f8ZZr;ISmoGhZQW6esCnDIkr$Bg{2V-pr{5=XbEQ9Lu&{I zmGJ_w$%1OT4(u>4D5E0Gc56~&N>*6I9Ik&z!Hx%h8t-=%l1C@v)#09bk7o16& ze5ZcUr;`H{FL^NGX)uB^o)f?Tf3hdw;hi4nfh0i_HSvHKP^i&z0WSCjFZcy5*o9uW z%8ChqTew01qZCTH!Yp(j_~9|B)3H|Ru~y+RBtt`6X~UO_sa`1{37WE9iJ-OH8ftJ3 zt_iB%Y6v^TAZwtY3hFX$5SHf{s@{?YXlSY+^Ar;*fQpz1R=GN9kxX|uL~DUWbhIJH zi;GLTB&b1!ODqoJD2_n;Apu1lT;HB2tQX@jTEABB^MiD4H~aF&G=V zBwU>SAx%65YS29}@-&T648S-Hk68x2*o$KL#pv9a0a1*_Xa;3S8OQ*J$(Xjy*bFFm z0@0e88L*i^(lwkRgKsPn*g6VHK$=g0BuFBKNmPz%;0A8MhFk~+FffncvbO7>0`0)Z zV30p$P=;XeM`c(B_`n-<3y1n3H~sU!dB88jF`RUeobQSdjk!?E$w>Y{hZSiMbjZlM z7!h8=ul$lg&{>iCN>O7tkGdugSsyCLissMG28|o6GJf+AU-|Afrv|2ak9Fc%Z6~f=ir8CfDU45h(Aob zyTlqhyqay$nxFzR9n+u2oCtStDZk6R%Pg~8v6gCJJ-K)WsqwSV%*Em;j!!s+NIHd3 zXe-SdMN))K*Sx&Ca?QJniqE5~xpIoS+D))91>YpqKeMF9GtE;V4r!>)$BNDiVXWhn zkiMwSyRaqxv>4-8bvuMH0%TyIr zd4#IDg{^&P=W1NiiU~2N<6Il@w4u_2FC2dhoTO?O~zahk+u>Dlxe(`KK+BQmmcQqx^xR1OgoZ z0;>&zAMmgaXaNlP(xzOf8E}G~Q^H>Og<$wO@G*vH&;>{Skvbe}s%XGb9NmU#zy&w% zu{DMWxjoCK%AbSC6@qBPgLp$HtK0{|AZQZ^MAZgvaE_~~)V1T9VQ~%&%9>u;OI+B) zZP-I^h?SIz%rbM9&i&L*c86`4h=HJnT;K(&44W(fhG=NKrdd@}AdaPRU08PAQMgsx zomJPYD^kQ=*sMI>z1>}9w13IGB5FlR*aTrEm~7a@Tx90rSejE14r(|Cz*q*6X(LjL zPRlBzjq#XIdroeqm;MA{B9H;>Hw+aAg`ZIu~^yLZK%6bNg%)lszJSE!j)X-*h8#ARA@s~ zPcqzLNz}L-s)dkT!@L@3AeMHB>~5etOa@&|Wiw6fWLn9UZ4d`92phNA0xj@@EcgN^ zaOP(o4$^d0SdAoe)C5{}O+>?8-mPuhCH_TFc& zW?fDsP2oURNT3S|nKzKB&H;JOZbnA!1(}aAEN!){$3U3^#Utax49{?Z_5(2)kO4u0 zfpx8&*IE~&0FI=o-=Uz-aoMDG#0G3YhUXdvw*edBBH**Bf`4>aW@uQ&NYG=@=>3Dx z{hNmk)M)zP8~k7#XA;?x)en>29Fwl;6+u}SO_3N)QF6!y6(xs3;lP|$Q5B_W5>W|O znekb1;~7_#cL36%-ti%2Frt*w-myWD!`dI9+8>xw9hhn;uF|Kr+9^g#G^x1~Xn`Df zfrS#&Ey$j-Z2~mSg#ci&ld9uZ{)wM)&@nfD>t30aSaIWRxKmvLAZqa2t?^^7NvcZj zEy=~2eZ`uq;UsPV1;>51%9cB^{U%@v#=yZSuhAgn8)?L+DHa6InBuV=1TZPTK(&gK|?Ow*+)@-zW=~dgr-P8=;NkC>v zGX=g8{}HiTm*gX2gR zh^+}+$-QL3u4LxO8o|cTtg!~j<|IgkRDpm5r81VS!E>&8wk>-G!Hm0zGoj2p#7LJ0 zP#&^zIEG}9%Fyog&<5BqFl{f`g42cs*QVuIHb+QOn)rmIQIKs>%vDy`U0=3UTNXv( zjfzU33cI?BCVKt~WR9XzAU##EBuX+z*Yyc6`+IMA{MmD(zo0$Z<7Q>Y<}h;3<3CQm zu&iW&3}-|c^u-J?*tzPFnbML0(t-gJc!8InU-v}!bVv6|sv&jciE2QGRsx0qKWJ+6 zf-VqHUjRsmcHnAP44n4A6wVuffH!X(x^V*0$wLt!ZR0-+)9Nm7mC9eZ{9qO3vZfq7;W9UZ9TUE{Ry;NJ$*)xB2B7v zDbuD-pF)i)bt=`WN$;IVkyV9<6CFJC0Mf%pkRCmBbogP`hgltJ&8iKe1BlqUJ-&L# z>){1o7ydP9%!m@jMU!7%f(7g4t3ZKV#vnDBHg4K9YSXq&wp{u0W@^&5QPbvG+UL^R zNPF|P&6~Dotf8s)_Kce}ZQNK}(`JpEwP&_@b9;u(S~X~}eS7PsO*ZRp-fm0l_N?2s z<;z!V>*l=M=XUP4xeM>k`?T=wsEsq1ESQ%sUb4LR0?hpYV8GhLkAG_vsZsv@_xA~Z zqWC9@fuek(NhOm+63HYFGRR;h3pzN-f(t%4;Uybh5($SJGPt3K9)9S^h#zjkN-3(a zs7flTm~sj!qnYdX3R3?EVIlx%rLV|F+~c=Off?m$;>g#oO8}HP%c?a z{*YA?$;^6M1|v)}zYG(mm|}==#S>2qHdqZXtO)}QB|y=SRZICJi6ok6B8e!Pgo3A^ znw*k~prBM!%{8eM^NTRU0P_nlU_9#H7hO>}M-*uk(ncep6OKqA=}Hng^PtKQOf0=*j5sHqWD~LuIW!Nk3r*A0 zd8%#G&T8$Xmd~8qa@(!9--3J8KKH2L)d^s|)q`3d`~XC|aA|-65J8*}#1Cq9U{+W^ zu+>8lVCj(83M;fw!wWgg;DQTiKB2`gy9kp^F}>tMOfCgLA{k|pO;#CDmjNaI4K>?* zMonly;R4h)&ybc~YT9T+a&X&lQ!{SC0r$*o++f4oGsIaFv~k|l=2~(vH|Mf8(5%Ld za^64#vvx3_C!Tlhw6hM@+Zgjp6ZdTai~#qwCuw_HeBoXeS)|>b7yb2Dpn;)`GI!l~ z>j|NS4K_HTgcV*0;e;4|C}M|&S8{lWgDbg{)1n`-{q{**)(^J`5F z!DEc5s{$KNsWi>+5JmAA1055Q6+}8xE0lml9J>++JJ>;vaD;;$4jI)#UV;u(HH0G$ zVTnV+(U4-LgIVynjJ2}Xj&6W#8{ObXxLWAK7s9YA`{)M-df)+f!6k?D0z$sd(gUyD zD~Cbg;l04(0k`}>ULNQ`3p~I9zP!LM33GuHqVNP?IH3tzyoIp}Ab?!tVjSzZOv*mS zna`+f8@Nbe(Y65%Y4B({sd)}JaKR0j)n;kHsTnk8qnq7S0~>-2q%}bCi0K3%JIav; zE?g!ZHzo&k-oVAwva=lRjLaQ98IL>IkqcqCXFgsSQ z8U*^!DCkBvQH0_^qPUYLL~)4;@$Esu+?$0e;h+ooEpdi39En8a2o8~G5`|0A<0dyb zQl#P(qtNCjPH~EBEQe*Z>Wh6sW>j_5g zzPBD_1fv;WT2wR2=L|BL=?N}~LJj=l0vNbp1Tr843&F(?=~0h*fl7rbw08|?ECYOq z3DcwI1BNe{4-8LW1~1yDDJW^m9KfOpJW9epQGtY}qY}tXHDU~m$jT!c(G{;YGE|(F zgs399A3Ac8L1XwYSOM&xIC62UoCpgi1=+?ltW_II{>o7s`-mY~%WBqe^`i_rP?ucv z6&7{r>j!gD%e#K?l^@s(u4ma{Sb(4b8+v6gdvQSy6t=L1W#JZ1SZo2Ba0@RMU>uO( zsx&-C88wn@WI!1W%$Nq0)6}Lqt+5Sje1i>`Rf9LV;YQSk6Etjq!nJ^e1~+0$9B4?V zw4{Yu0dxd2OP+=`Qj^ZognJoxNFyAHB4ygx=C)C$vTUPV?0v}Qp7?xWKed!w-9q7A z@9Hv_k)V*@98@6)jn_izH716X*`X0>f|-otkR>)m2}`8Nagl40D*O|p|D-mO-G~|r zi6IVjE`t{dR$Y{e@wy@vNp?tLMiVrJPi6G}q8FI*g))l4VP*t$7rk55Fm^GF;5~tO zXcEi}TD&H|P&8coz(*wVWaB?cuW_hI1t@lm3T+gl8H-w!_)0pAE`Wgxzt~hfhm^Ww zFyw+dou5J;$dGw>5FX;7NwZ`H5~F4$BMB@CImR&#kgy|y4Lox+$N>*_v}zvW$jGNK zVv~kcP$B8ypsH52tdOiDIjM0DwvuBHevI|3ie5CMm%@)F_<#stxyxJIB9T)Bl+&IjJ3)PgAp6y5{%GMBxan}UeRpa!8Ane0Wl zhK$)DNi1`|m#FWD@Vg;uuEKFFT7~5>H;Nja0u;0vG}Wk)3v>|U7)D|el!$btbqHpan~Bs}Gv3$++S(Y7w1p-}pnbGZ(Y{8Z3dMa$v}QJ`IS$P3=o;LLRyjt??aQj= z4Qn-l3t0#o+UBpy_S{>#_5Q-WPsz$urjiywLoVr(fehT97~r2^2;iWXgaFgt9FuuL z)8a@RCVYqmQXD4WmnS?9E2zTcu*i&L&gFc9$kB!(Wd}8kjxihqkW9%jbc#AXiIZhY zme?FXF++xBScmlj{xj^Hg(*WbB!&?BPKg~<7Npo=MZwWQ)I-Gp8DyTf@B=}7IZ-mzE8_B$ubawIS7OV@y{H>!>^!9mhI05 zp+f*=L`f)6-`Snpkwcn^(KxV!nYmd_sa;Np15`oPJYWP=T@bTqM6fu7IB3~Up@Xyt z*V915H)I1iR21itVkvqH8RXSjctBpwOQ_uyUCG5N-pgB%np&)0yU5iMU7DnM00!hm zUqlfGoJophffhA^FYE#@7=tn7f&e@M$dpmYtW3*H60!M4ZY+m1_=aob1|8i|AkkKC zTpzVjpY{d*lA#Qe_f|ZN|jThX)0pijD;t4P9Nz@Hah8WX&4NiJp$ap!zM>dl*NgRh* z;3nXg(_LH#vO>nKNPqFiHhGgN1Wk0n5pGdKIF!RN9GJ?TgO$LJmbBFE_+ZZ|!!2M~ zF9gFa^qw*_K`_`(rs$3^1XR#13W^QmnXp(5w3x!&Llkz)KIB6w#Fr*uVLu=mQtX30 zoPsIfLq61l5H`bzJsfyBw> z$_4&C&>^nbAReNb9pW^w!#V&SmbC;<_|GybgsMQ|2T`Kq>6t^EkZmxZH&BB&fC4^% zr76nhY&OL`_yD@lRW8;l`go7=PvcF6~ZIxKS$VLA(zHH4d?13O@1uGFDO@LgmQ;vo9nI%KAqt;1yg@Wdd#nc8XDmMLC5 zyvnC2ga(~NO<+|#l*A;41G(K%YjB5a9$KxM?yUL)5u}T6YQU)J0J7do2e^goqF%c2 zRl7_YTpdxs5J3|`k?k3ls~w~66azEfLNr7JV*o|eUw8i zv{?hRZC@ber+s=~etz%v9Lk{-KOi&Ag~XTm0M zAmq$!&05*#Y#%#>SZd@;Nm(x+)#J#LRU+^YmFa}c-j)I_# zz|AO_!n-cbJ!-==M1y05L&~W`kR$^yXqbj!m{W$-rtkvJSt(JvR6gYsl>(Gp4nr`U zm@_m?7F>afp^3so0S(lE6VK*aGD90;d&4cTTfXHV|BliV6l8qlM=EUrd@!sjWx+3if<6BU zFKI%JNe?jr(?%B4i5{Fj^K&Jrq{~{cLSI}4Q!q-xw?bpW2eV}4*hr0B&MADuH{f+? zB^MYiV+#W9Ehxs$^MR)TAQ+US15Mc!{{U{@(v&>VM5qiR-=$dtkwY9e z5N3jPE`W8kL<`~?1f0nOOVsTLDbP$@Za7flLP+AL%$W$qLjhp9LIm2;(AK}2b}5Wv zU#mG;@dL7o#l5UvTI3a8<;7XlRb9Y^v6h7nAQ9-LMRE#(?Cr%9MG+KSfiSuneEb4) z7XY>jKmkxj0nnq)fbR3*jHPccH>8%d^$cwNs4@$ZebOs#U&HuDv-VhXkM)?KpaLi) zlGNBEX=n$@a7R8ujUqjbHO!HqX@f4jTYJFU7d!#H$#WJs!6`{>bCpeg=-U@S0s)uh zhTusgNP>q9&I0PqiSqspG9jEsy6AjUut2-0)7AF{*QmKajwhtZDrB50ltRsZLcIHT zHvqWHJi|6*^a?MdIjEe2{czIuoRUUm)HZ3Bf|xHfIEN{vk|qX;A%hrXff3s@6;Ofk z9G!^2scZtZJ_RB8fX^7hn=hPQ>F}lO(9Saa-k_30qSDk&0ZWw6gFIk$r8W@a7CELG zB2P5A&Nn$Vc!zlCF_339BA2F>#{&Ve1WTyu(c^?lID|3iN+lup{AL3ruld!(5I?A{ z4|%d!^y(13E?caMEGCF=kN5Wx#zzzZ0R+#lVmxtbOrMlleB#eh*X z-~uGThI(GQZT^^`&+x{(wkI@L!*C4JGeE+9&a3vMf}v>7_f9@F@0cmHdNq4t=A(is zB+_emGt}IAH#`E=XrrLj%y0KH&!}rI$lG)SpuRaMuw%D;tdc^)$A#Wo6Hw37L0o*< zNsgVjFrl~c`*Vaa+$4xQO48`W*|&>Eg1Ij=^>?r*;CD5-`@7Q!e|!Qq{I}Cg$7f{p zIP9c30m+dV?GE2y)IMpJ)ErCyFh2Rh%=w%^fl2Ua!4n{%N~u_207R4-Q26OHco1Pi zg$o%rL}-uMxnRtcRcsb)7_ec(b`5J%?A)?tAC?$(u(` z9z1q7{&(se$1WT@cG1|aV@GXW(sk36CS|&A+cs(2imn^yj@{3f@wm=Ihb|sDaq-5= zB-_P?g7MyNJ}i)L=#LX+2qPiFyZpcFE7c&%S^t^#7s{-*@P8V zR$-+SRze|#PC7>+r5fzM@dlS}y4fa|T#^gt7;}yhDH&!cN+ua)7M+NhWO~^}nO>A( zv=?76WrmkaDe^^`V0uY3nP5!q#Tj3K%i;-Ed)p1SD8}fgv0548r=D{Xr6`zCg&9T| z5{F49~0&!|d+j&YEhf0|gsss@6_D?LIjVJ^$i!@0$Jm zL#6Eb{+kb!Q%w2q6#YzL&Kd_F)&{`=^%~F{Zo0wiIj60wE<0+{^a64jQM4Qw6d&=i$4GdLL=qrxbVQONo20VH)tOY1$^Ii(w`3A4y~N~_ zFmn%+Oiai$bCci6^n?}Si-&WSQbU_Dav3KVV~i=M&|^cbRMAp< zp=cLoZmHDLUV62(*NP(bw4(8qxu_XukkLX6Em+NhiYKCYf(lXSnHXrbvBvD<9=f7P zrJA7(VLUJ+Ug(9hM6wKGh=f_mV%AFFVH22iuqN~BV7A6FEueU7TTe;hIMDT!bwMR6 z(rCvFr@;<)ScM!t(bo?Dr7yCiLoHyLhd9Jxj<%>}97)`XPX)LH4&p?oY1_T{# zWCI@+GvF4v*u{(8qcSR!j1LB&8p%jT2cS9GYb;|j&yegh{x3V@XFAXV*?52hFUUa+ zcm@UB{7go^XhIVTP=H(HA^^CESOB(@p+;7x8r0!h*02EzZm5SmUCShU!gdW%oDDtq z+0TEjVG2{E;%#w5MchvD2~$Es0DBXVfgJXr>2zai6?)p>vXdR*u*gJ}6Oj|X&^Z_d zvvQXE!ZM3lqQpHRMp@WGE>d?R(eVg$Jj#)gVAmufanndnLXssaK|3p1f)bbzlR7uS zrFMqtOI~Uxn&_Dc;~5W5rO;=cKGDx=WaAlo>c%(zgo|jDBT&dNhcV1itYm2_8NLt| zqY~vP`H4z>%$SHTC^9}pb<};45=JoUH;fgv>IuC5>5Xr$FoQ5?(Tj)a2Ql8)D3X#? z7{3697A9B{Vt|Ah#5f11PNFN2paUlCsL4E(DvuJHa9Z*(3R9-Bt)*Ob9Y|@%QoO+w zb#)bn+n^y-;N^}IhGQ!;2^c!cfes+XWUc!`2Q|=TlpA72C^>OQUih*%hv_9R&sc?E z_5stF9u~2Py~i0n6UGkwAPAocf(Ja1n#p{u10H~^XD+LQ%S@&RLC`^GW+nvLm1EE|1H(H{G} z%|4)j?%E*XHdE+_m8TfRCz=BdY4~X`8FKzwU#+8!NLHsh;rR}A))5RX{GxFvs@!~m z6C%!84s#>|krP}*qRBCC3taF5=m>nH9RVpw0nmguWhbR?7Kuvbl-)V4w52P-Q=Psu z6FoUmPc*fY6KcX|o8a^b=JoRv*#HM909rR`NCOwtm`0$YA&z5+V;RR#R4+Qk(FJnU zeZkPwMaF4N!ms z8d7}3HgHi6Y6L15fKhM(8D3o&btI!1MYhOD7p}pfG7DMf;032fA`)g8OC0l9M+c*7LwHSV9rC&= zQm(457+PK`5A%kDqOy4zMun_Nv7ruOvacf|btd$vM?Lb9kAn0A9Dmv>y6)-@y0ptd zRWuO8w4oqwIH(#~to!hZpO}60Bebje*lT`p0?)1y*KAD9tvwLg%D_z4mhk|~YU2T& zsrCgm;G?rwss$~?_7>@<@iYnmiRX|9lHSf*aVyDf?_@2KkLb45tN{v8q;0xTX>H!- zy5i=#Ovx1RtpMHrW)wo9{r2KP{LN{iV>-}ly`&);azUeZVe5p!{A6TByx<8o2L!XA zL?{PDMC1#&;0rpA3#ecVsDKJKjtg`FNK)qpbwme4PDf&AN+PVB$Vmt*A?7Fyo!AL@ z&_u&N4ClzC!*ovPcrL_zu1!`UdGx6ioF^1aAsdSB8ItY`VT>B60U64n9K?a4j=@-n zp;1E0qQYl<(uY?lf)34R@HndMEJdS|VHliD3!rRO`lmPkCkn)%_!y!ekVT^!s2PMo z8GgYdZXqO=C8*A!p^D)c{w}BtFB!5T&fGy>-lg{3p|0A&h0MjP)*;aTEGpW8(D+6w z+QA#xr6~Svh+DLxUM7tm(qZ-Np&$4`i}=AFG*7J7;m+ViC|>Ltx&g2X1TPk3iu&dg z1mh5^(Hao~`C#MM=E$=uBQ+xHv1CoOII9OpW->f$`G7z(L<=^Ez&3W~267-bu0S`g zU&62_`PsS}zum;?qK|Snalp@kUu*;O_Z4~0> z6Y@>FvqtP5A{8Kl9x#&8Uiqa2LE#tx+z8l|G_5)SoHQnn6!K82%# zA)-b_4@0GXcESA2?+N(pwOruJt`Q;j0V0^88Ir*fdj(j0K@u}a5r?W66vZS)V%jXx zuHI#dYR?#NNL{93(_rXf(&b^IBJ=V>VI0OeX7OR#;m)cm@`U0gdUIdmf%OP$A%syc zW@sI@>MHQcIiRC&wxK`<1d0emFRURj9Md|9j~^H-G%}-&EbB9N&5Sf708|6Cw2wRI zNEvZn&Ixr+D}x6LqfkxS1fQ_56o&2-QXzVZ4xkn$#&Urgq9N4e z@)$0N7do?3lz|sYrBUMWM8~I7icAkJg`+YB>>^6*nBjhW;TI$aIEIpcsDL-};X3u< z_|!oebOrBHR2Y(>E{h}Z&LK2S;_ytuS&H@WKzc0GV6|rKxbTlXKDZnz~BmmW<`X<7clV{j3F9y zYiaxw8_vyY&8;5{gz6XeUai^qgFdD$|Kd)5+$vG%L3>=Xfp(dCvY5q)^1DuuV!~6O>1J z?qn5I>>EH~Jiej#t}Pc13ZZOl>ew(D(odo=V6JWf7ni?0O$(tp<4GL9~33;Dxz0R6oZPTR1431&J0wS#T-h=7?WbF?kp)tH(io~ z&{{EKB7{~ABx0Un8vtiP@?wT&sIEj2DA?iAY$6^c)iCnm6x?j9`X-|?eqaDvqt-41jv(udKE`9PZ)PsTj&eq|_=q>I zAU+w>{G#m^XvfQ)i2B~d1#eVU;coXi)@ zPja*XrB+G|9JgBeK^-FEWSik4%uMh=mFkcs8Q82@{4OGn;Z)y+8s6nNaZ}S^a}_s_ zbvrLwr2#K0gm9X%tG4Q@m^(y5TRhL2bW~ zVx-rX4d@;`=GN8-TvJB0MB_EW(R#VFHC*E}EQ2&;qXm>8XLjZZc;*SfATe9z{9@}7 z{;>e4p^&O3)w(T{{dSz38;e#JYWn0pL4!T!@AtoiRa<<@cGLB|x@MeWFFq zbgC(6u}KFV;SwC-z&p$1eRAa6@JOjmgfc+t5+0T7LYt$?o_tS7lWgw}2*fAL^kQ z&LQs@r4c#x?+ovP0xwZ8cO(?WSk56GjB%^>`i5#Zbul?Y9Aqj!*$e<3}n+t z`G!!4H^YKh7Xos>K^8f!u^ps%@urp>#BcOwLG&UO@Zpz7`(pNi3~J3}?XrY9HfUqnnhgqc;|avT3A&j+Z=ngmnHnG=7t9N5tiwCh%NnjhYx);F zDCxMUra|YK0XMQ@Ig+0l_)Z!yf-_VUL;-ai0TQeM7sBDE5L$#OrDXXMp^+?9C?$m7 zEA4hvM}ag3Ij%=Du2p*SW;gy0NPCihbao3s!4a@2DN9at4&0?Jp}~b1YGL{+XL`be zXNkQM#I&}Fw^mJF!4|}n3d5Ex0h$y(Nfn5ipx83E>K7T%&={V&Gxt=hFNMY%MNw#c ztCeg~!lzdfrOC8FkkaljQ;LtN@sHCw$8EeMKtdBQC=(}fB$6Q$8~Gf_!5s_@H)l~6 zj}taEPd4{PZ*H|DEhLn^p+IO!tSpZ-ZEspS$Q~497%97UP0=szyn(21RzT@NJ9sNO_(hsWjq76+ejTJ2gvJ+$!PM)QuKt$hAmvX$`%nH9a@-2C+t%y<0$|=0xVtkJymj5Xw@VZvIJ_kx z6d<7qW?W@WnzG2WOH`*s{wr5#oC~pD5 zlQKsR>`1FJ!;E;{W7@;eWQj8z=bE^uz4D2}bj0$BEGt$OR$;}uPk@qio8Mm!-@~A|i@~ z&3vkYylfdvQFPPXcJIb@X$fkc<3OmRZ*~bpJv4B;PS-pr(4zm^gAL6lPc*Ns*9iPWS@OKW5atCMBzdm z;h#m}6MkJ1K!I>U<%1&{RGb}UeMQ=lJ)+e|$X2vNq)7yMa+#_<<8D@H^qVJHWrc%s zM>!7UKu!lo?r3!cN{SeWtrAVB^xf-8iR(SYbb4z$!HGLT`90wkMC_--R-Zyac}^S@ zPF#A5?i+Bypkj;~#vwUgd_<>h57+n>n4x^qrwP8Na3`XTGXDnn!9%E)Zp$qrQW>CG3~7VCaMWLVvz|FJoAnZzg~ zCz;S#V~w2TsAGKmM3wC!Kggq$fz);t4BDvQo+>rK}=JDXM^@3N+w6k_|M_ zJo5-H(&R!7HRXh3%$dX#GZ8brB;)2oZT1q3GRXwPj4#ZbmyCYB;K@ufe+K#xGs__3 z%b{8%s)ZMdKJkPYNy#PYr1u2c415ZmLrg>qL3BBoj?E*<|ZYtwQ7KG(fdulsoLmBTqj2$h8kR&%A?CJI{zEQcftL$YYR30tqCNMY6)A;+r^GN+^%7qDnTaqyh?;;863(Gt}TRO)ld^6HYD_rI}DK z#lUB0Fo3q13@>#4=_W623JPfJ51qpdGRW}a3u?e?k;N0kKU(hbP3_ZQ)|=6w^vEwZu*N*sNq*$|)PSn@udmS0 zI@64^PO)Z5y3aS=*a4|8{dc&@+L^Z3XY2(b!iM?4g(m! zu46Ud_FbzC;HP;gNfbFz<|g5eALz-Jfp znGb&Cl*TaPM?LisMliG>jH@LmYa7zg9kr$)tQE)$3o;PH2IL?EQ9%+P648lDqzSc! zNJN{!gpFRLH@xv}Mtd_{kAx&RBN1tEL@H7!Jz)zaAxUwHdlKYGA-Qb0aur;PX285OYw_15~L%1rcU6!%&CX1@N+vsNrov3>G}z zKJpQ}*Ae5J5i!U0B%-_REdx*kDaJ9(VGL8bY8wGG;7U~fLX(i-iY51CNpjvtvXjA2 zo*${7u-ZWscetY-5|m3m0N4&`tcoiksR~!l$G~j7j~fo;20jv+&5nBXqx#qf27k~2 z4(i}B?Ba{N0&^I2)yps`G)%vKpaRL9z@|4%%)dNv0~u}x3JC+v4HM-Bhuz{##)!t4 zLIR0La3eR#q1F08p)!&+5jiPy;&GDm2uP&D5t5KjbgXEd?qG)$-O1v1NTDY5H24TZn!}5bhPIF(tWD@Zh1?K(QKm!!GfJEkS zk-2i@!j{JP=0u2ry8OTnn1JF%GJFBdK{3Nl4}o5EnZXO)L8Kgp>Jw_DnW!fS&om$v zS3l~JOoiOy9ID||sL;ENaUSESW-`Yy#IZfDaAhmru!j2LcN3b>iX|!o4psG;oQvs- zCEoB=PA)>fY2eQt>p&>D_F)fr`l=i990^82k&SCuv>LA54NJb!zwny)#O2yYBRYVW z6tW8g8t6eu@xtOCKt>2G7J`iH}r%$Z?LwG*4djqYP#^0crI4MK5-N#yOEu3yb!`@DxX=N?SP}-W5MOu>)0G{@5cV9=WeI9s!C}xU$2p^zd%7q0bVp`{gii3qQ!< z1HS-42ZQN>zV3CHdXaF)Jr}|WPS7uyc7O;%NI?qv#eyQYKnFs20TDR!0)*A@30JtL z7M$R))U1YLvU$WK3UIO}4tT3G8BW66XPo4axf%et1|%S1Go97liaNV<&Tcm6D~>`F z{Bg9<=o9#-;YS$E)q?5>4NUv6XO6$fg4Y(S#{y~SL0)SR=EYXn2WdzPhy>Bv5*eaI zj))RB(oyPN{p!yeX_KEMoUKbc`%cV4wW>v><6s*lRZMPj!v+N?o`DP4z=j&5Ge$1H z*~>JsDH+A!&vd0bC{XGCPMHu{r$I_}4t4Y{n%n(_qP*aRd&C?r9tV_~2y%|s5h@*O zI)?JcL5^@lLzm(>lYGrV4p<@Bd60AoQyd$E94d2LBy$@E_Z0_}5%&XO5*9Ao zR1z&=4XKa{tAGmGkP50`a@XKt7UfC~^bPjFQRkO}DYy?bCu1b!7$@}uFQs#a!D518 z7&Rq>CDkuWcLGL6WRg)*D&PSgKm`9HLs&p{2!nNsLN!fr3&d~>y3hoWpbNP0F&%SJ zZr4v(wS@_XfJpQ)*f1Lf;0Tb=R+=yhXtf=ZP-i%^GdD9cjxa?6U`%9WMn&^y$)GgK z;AiK79)8wWc{Tngy%2d`BUpR=D$aEm>0i=rbA z;Xn@JAP(k$jssLJyJ8#V(_gm1G4I20@n{>?a9h{V8y|xlz(GE&(hX8E4bl){C@2>m zXAh|GfghNVslb7*G&$FR4cWjk*0o2Ib~3yigH66b%lwa7@G-9s?W-h#W-p z8yABdA_EH7V1|9SML7c=-k}LD6Ng@OGu5$`-vJ3hlOL+{XLOP@LZdptfFJ$Q9`WIa zeaJ8d0wD+jA&hlLSaU~#WFZAo1#!tB2ciq27YU9eB5)&mnt*z(mYA>hYC;lPq(yt8 zcv_+K3Y|ciL;?%1pd`7LijCtWoA6qy&`QJRO0}hITm}tF#cVyqOW*Vm4iP&K0V>MS zUIr1H+sJ*!xIM|J5WUn8y%27{!(Eb>1^%FsY|#v-auDj!4EB%@{orv9MGeys4dYOq z{^2kV;y@1QaE|6MJ_dJB_P86x5s$}V9Nf||L&Pz_k%jOxPugHV7oia@=Rf-(QvFa0 zr+}Zn=YiRP3MS{DDJPLB0}k_PoCXR~{h$Po;d3Y?gN88#`XXdQrY}WzWG&E=ME89HGzQqR1Mca zF`pm_T3IvQ(N@uscU4J6I3o#y_lI^U48YWf%D_fUlQi(bS7$j!Zz&;`=O`6IHhn|| zUT`6XWJsarN19ePz5oeeRU(9$iK4d&negI9UKn(*q4*4TG<4}(JcMKouhfG&M8bUr6jEJbuhCK*DPbThRG&{YNS2m)}AQk60$<30>WRk!gB4Cfo~0}T<`qmKS?3XYH+GZTl^ z5gkDKhA=~V3GkMKyPSD02CBAw-lcG?QGM~by~ik|Qauuz$lNtu6IN~+i-P|{kG6PkrOnjA)K zT;@4rf(yQ7Cc{-Kw=i9p%6-JRUh<|8=5P)IQMl_w45HdQ%?O-YAWf&S1;weZPH_+F z;GAc{58&{g)v8pXBRaf#j=69X_{4y_FB52!<_M5ufew z4akEJqVTP%u&w*)dmKovC`VNsN4dyLLCUiPIw*rZCUh-OgZ`4yWBOWCIHq(ksjnx{ zl1nE9Fqw2KnF1}q0z)`;O7H?b)nrp}qBleuM%4?vFogvm00ICBT#_6Si5qRlkK6(i z>ZvOzvl|(6vY_AypYR+ylfYgy3f=)8H|jCk_82+t|G;%4pptv&=b|U{;TC^j^qfe;u(S@(;M~}k3>YW zzfnX5z&;!!kM=k#G9fJiq!H*!F8lDUuyqQjFbWFkp9~3=A?8Z`fRV{t%HkqY_s}mr zpvr*(WIrHuH}$Xmvai}pzCb{}9Uufp){-g^umLLsEZ_kF>j45|lTC&NK=lL`;;_Tu z1;29(w~%GEh%NRwM1|~*B9qAcG>=7eth+%mqi}|Awlm)`MKOyrQzU2Dft8~m0D?## zRLVxbfJPwPG-(;7MUz*4R)}yMSbj7ip$0Z|8PFOc!-?pZjhG;SX|*GA!dt+N9r&yV0+oxp9r=Bni7@Z_c!dk%o#tObya<6D|ps;1oKucnR3y_*+$Iwf7 z!hOqRD(fXq>x8&pynn}l4)e8)%csV^;|r&nD06JeO_2}LLUG&B6Anh5qf>w4Fb+HV zKKtZE#nBssOn^@L8z$?>3kV#AoMzk*Kp!Cu&rr$Z(hp9;$-d{i;Hr@Qd2%Ai)=Hh% zlF|=`L1aWmukfk@^x6S2>4QfGut`_g0&8T!Ouj8Su;a@DEzkllK-o>ku%UsfUNFMH z`GiR|CTg84>gjgcK##EdKDEJ55m`h7tgHtt03WhjYg|AQqBooOXx>av@yc1r*$-4*f`sXqHX5@#sjf`WW3Y;wob;7j$~X8x4;X;zzd{$D8Z>Hdc79;U=4R{tI9^MRLcpe&iq*A|QjbSa@k5d>O-q zv{;m8AT`|GmJlMhjtPzFn4%SXq)3@XywR`V3PNnQWg81ae0#T-YrLj=rN9dHEjcBZ z3ihjP&p=Dk0MkE|W#Z6$+h>f)xK6xD#)g~VhFiuyy`BD64$4R1eey6y4aZNg;r$7p> z=(`Cy=Y8A@dM3e1VUuP(W--izfaFw6n_GvJIzjIocin3Z|GnQuitO$4sG8@JH7BQiQ)tz&lD6EEniWs(=aBXGY+{B z4!WcbJc=>?$&m_vj=vZ6g&<=S%POA8sw>n_o^BUEz#(zkkkkgbdsIRSK(3$R>VY8G zfxDmnX`uuwxxF)QWJQ+PE{S9_PuMsXlPwUiCP3I+F4_Gr*#Oak1q%-?JSceq1xvy! zSHy@Jrp1?*CKYq#x}^)!BV5p`VYBuzB({&(uwDCj?c_CU*Id55mg*&{YoJo03Lt9K zCsC3@=@j+J=O{^{e(DV6)9BAnNl6Ltl`NPtValxf3RYE%vaG_kQq}TH3$S0ngn9Xu zR@kqzUc7K|vgOGZE?cN@;X;MV6E0csQt|tju9LfXzs%*!<%yRknl3$lObN1NOO-Ei z!tDOZlcQBqQHN+G3`C6PNt6;e=9B^#NlLms0tgjUNP&eiS?E9oA^y%x z^8_IXQh|jQ>b#SM6g(IRg@Nq+b0C3MXyJt%UNH0uhOhwR2{6FWVi#X-xuuC)!igpq zYMyzf8kMRki6oLftw|-9Kw0S}P-40U6`D>tC4fDXCB( z*+m&Ag88KvVRjKFn5md;c3EMBF-sUH(jv=?wb;^P+FzXbA}}Yacp|Vb?AjvTFaAo5 zE_COrE3b6tqCyhLHi66%$|AW$6HQ7f1srL**`~s0x>1F+R}@}YwbW?yWVY69gDsZZ zZga&oPhjb-W8jF}WEECcQH7P|l5;Mb=%9h7qwKERE}UGxBgVY)$Sbdy{`Tg3Pdstp zLq|Si&>^Qj?s74P7+#j<#g|@u*+q+c#H6}v1@{4m#%HwA2E%E-?l2s3rl}Dom#R6@ zrI4zzro|d-1l1ZAMHPvpkM1Vv86UCXMo1xvv|68i@Bz5+QldQNI4D&~1>y1(RS+mm6If8egF63Q{ZABH@N)$eRxn`&7EJKq21KEF z0gHy7aKce7#MmX605iHpQ-dFY#6}WJJSlBfS7kLOv~O|=6;one%2u6l_4QU@yB7ti zT0<$o31h1Yrk7r(a#omLeu35tWZ80JTVKQ?i&`&s0frW~kOjW}j4LmAp$okDlCE^c zD_vBOOT7F-1uv-U5thi;Brtf1N?aloq=*sMywMJCbmJM`_zX8n(}~ldMm4Z;jl^Cv z!`i^&Hm-3EZeU@HS46B6ngLEJSmB70DGoW=0L3RDk&0|crz6&}&P8yM3vqY{JUA=Q zF^=)G^@u|p>xqwiiiVD%g@b5B!%xy~(H&m&qG=M*0^lq+M+fc08hV39g{C2mf^CQz z>&QhksNpG?m?9>q@D!?80u5BP%_P;(8;x%CNKkQ~1dfq}<981yBYt;8zu8`~q3jT2=soK^C*n zFH+SC;4Zw-EiHH<3t6BG1m}{#x+DgHbs4~6@B-2&=mjtFs>>H{aS6*{uo9Gz1SqWW z4Q;feI^7_cHo75=uC?PEp?R1KT{xRg#85V|NlgwdhOwzy42P+i1uJ~>8{n{lIIKVp za+b3S=cED@k6-s{D4|A?8gv+LpsDvY+ zA=Gvdl~X_^p*KY6jcsTn7pxFXQd_gs9MT4=H>8aXr>f;x%%aP%=mZZV791dcwPYky z#d1DDR8EsAGnKFezu@#;ko5lw8y=rcQVfgfaCWIs!L8r1wz+*#rS zlGWfEr}(&yuL;sa(vS&fUDYZ>zQj`|;RcJ~hAO^2vQvDk5jQGXBc0|*)tCfH--0VS z!WAwQg+pa2RuLt}se(#0nKh$@J?z`wLvwjr9qE{<0%$UmAht7sGq3wh?b@yd(p~{V za)1LUTmcK+c2pA})xKU(s=XKfVOghaQYuf;L{%)YMlQm^jAbw*8TIDHGI;R_SDnHX z{SMZHf$|AW93?3{`PHv}QWOanfEUW}MMNXYziIU^fb=6vSk#ghv3xjy6$Ghb6yq+s z$SW{)k&B8esF)nTxX0)Ef)^s82~t#J8`~fu*PxN)&q$+$K-ESbOPCE$xZ+_CdrfL& zBbzGU(1xyQ4}qu|Ar@y9XhzN_Y;x8nzBxPE$y6?oaSUX%hm7wr zh8N>Q4lnN6j71}d*u(~+5FsrbG~-1vo^}g~fRfmh%Lht^ytT1=?m(Pg9s8 zZK$oACExZoZm5VyY=i#JBOOU2SnsqS!lfE+4VPPAsp2??OC@p|clyKE-u7GS#}f3E zY&{JVbS&W zps~;vjuVC^kc%6G7r%h9z!<5%(2E_5sV&ekn9IONu!e%^1{BhUZRiGV_>5;Ln642j z5oEFuJSs4QA*8b*Ez2P;t0C8@I;nF7SC9o+xVqXfx`>&Dttt-T7$sd3t2MK{=1>_% zdITuS1(=byW&X$oo{^8e`WbVeJH8?szQVh}x;qdlhrud`@VVVfM0B+t7|sv3U4 zhfOe?QV<2h83kU06<+L|S&D$76>sE5QP6~*fQ0<%C~WDl1T+gRP!_aMi(TNBZSgRS^9r}X zK*iXL{+BAL!yqXM!V51r7lG6<49qcLxP=f@G7v1Gf@#Pm^EnY5K@x0-ZD56@!=cr% zDvODYsmhqEqdKUojah)YjG;Ol>WwhdIv^^J;xIzwAO$@ntFvmECVZJdx`=Q%2D}QI z_)x~50m?4|k#P7zzSBE$V23$7n(qj_L`%a@6ca}ai5X!$J)(w6n}%yR1p?bj0&|sh zg9%A$5t2|5yXg@gu^U$t2~a7^7|DiUvl@Qzs#1_dfT=_$alOPTg~n+mxP;2TJiLCG zlR%lSV2Y-J-~c>%rV4O3%;HF_1hKVTt zx1G!daU#Y5c#cz{B6B#0WT3bIDhBh@xAQm$dn<TaQQ-B2U@fD*`xTE-$ zqVOK%?1}PmgaM$I5bKr!L@~AKpKJMr1S|_?2@7iJmH>(%7ju^ zP%qm-9qd7=eExC!fp^-d-h6}N*tCR-sbCp;61h4+wG?YLs zx(SIxtOk!L2~2Xs8nL8D8cS^Wq{)fIy8M^A#I?MHy(qDVA5~LgQvzigh!PN#?jl8J zLOxiGMeedw8&EzOcqSWo0m>|aL%Bs<6wgPAnq4S2ix7v4&k4x+T?}XjKTCzw)7#gzM~0n!g#4Cz%dO}&zQ@xEdU1g`~n1IPc6u!cIbwRw2%@)q5bTs{YV!i0nMS3oCS`V(BK$C;=s_aTLn^31^xqjgyw(_ntYiN z#Zf@>B5^1hW$ZJ)3#@V2yBB@YaG23?5HxvvtNbvmTM)db;Rn=P(+8;uKV+LB8!~N} zhMU_X%lo&I)t*ndiGOPqQd0>neH*d_wHV=>RSSt6`3P0}25iWNYS0oerOU!0)52+z zRLaCOqrHqpT3hOeXflChiY`8(9cg<-?ZP%^x;7i&(>{eoK4r`mkO4yxRP!P)G2kXJ zh=}$HCx}hPTe!`8LqA@iw|XlExXsNIg>dz|maTD?p>Wa2N-45F2=a(Y#~W7e&e% zC5IJdhsV3ozoS@UnAltJ(WG6Fen5#-s8Y7k8*Zo&X}HSn^-4YbH_jTcRxukz3^grX zkwUy19&uT@VF{D?25_(kP{P=%k;LH;Q%ZCafYD2sRE1U8hY#l877iSKV1j6hE@WE1 zRwNYVV@1kjMGla~tRNDZ>$4BxI}kzG6?Is4NXmwN2MzgUV<WKL>Fcd|1~R=Aic#SDn5z^XrMf? z^EXsz4u4C9PJ4+&w4^G<(o{2vR)ZUz-C+I>?uY#ioPHP%pq<1@90gM{VO8);YZmCL zxrgo=6sg6wj=5!ZWJhLXiUI~=P_hsF3?{qeChMus z=o%!G252ZDqq2n` z1mr%Of#;ioCwPH}=z>RylwfFvV4zKV z%hY0+&DVTQX5fXC<}dzEhX2-LYGg+HhKF{bhExcsQ}Ah2r4^xG)d*+Rp!S!8I*VBS zFt4a6Zi!C?^kV?>iVmYFujnXnDOL=0i*spR)pd*2ZO^b~WcSR1Y3YR`8==pD>u1>A zpUUJB1i||xAy#nEP*zY`{-A{#O5VQCLF27D8-xXt#6gRJx=skfAJRIn;wr^%5>jw% zQ)rG|hK`Py1}M~p%tlJ{1(6R?W~A&8`DKT7Q06xW?K&iFnR%=4IEGwUntMoYYsLpd zI+09z!#E@=YDm&l@J%m&CBNP6m8CBmL6uOuB))kDost_B!3QF_SX=Tc=BCR{$gSL} z#GyR}R_OEUMs*0mB^$O=9G12}?XHUEfQl|}J(Xyzjm+|%Xjdjynqj+SYeX9z|?x`?6NJF!t_hILpt?~rML^L9|?c7SuDUx(4o$%_z& zLgSBONYhjooPOY}Yz~P|p-TOf2EVl@RQOwyP1z@fi3tW3o5hAD(mZ^?ht{SexoqyA zokUA?y-^5gs>k~WIWFz)Q^}0Q7SK~?>fs>P;jF!AtW7=`sA#V(fgr8{7w8>a+~_9| zgDi-MCwBgydJAxAjQ0MzH+!pg^8@24PWF0Bc3l9p`n-l;AxCn5aG>^=o=A6eU))Oo z0082j=*&+0`7ma|7I+Uaw$NMvf|l$2C}i#GdrG;6bg&SmL+#pvQOx~)i!2ykO=iQ-|lwQS_FiCLiud|79 z;^koU*IWPya^%8|V@Ix_!D#FjE?hTm+`5Gj+p%-FZrZzX)1rmTWvpYaV#SEv+o$g& z%9JWsvTW({B}|qkRiR2%E!DMZI;~mLCQaHlXr@r1G6kt-s#HT$5iM#8=e4Lgu|dN| z_5K>PZ`i)XkLq-c3jU~S*F&Q!p$(mnK&QasV6)0k^WC0^a%dTI;d==xx?A$qK z#FiC%&FnU_Wv-bOqmA44vSrM8ofDq>7V>G^xS28~Nt7r}&^1vHrO7(=?Aj%1r%viq z04KY40TcF1m@qBB$^%m`%*%UVzka1IKmV5&FY?<9lb_}P7Xbp}g%@8GI3R)p3iAap z^7Ut5f9TC;9(v?-bKx`6tOH3m(rB}dH{DPZVmsYltH|;qjI_WQ{>v<| zz!HlrvD^qtjPBhd+Q;tW*5JSu@ zx#S~OUyVAdPd}zygGx0yRfA16&{*?~PeP$`N>QgYSCmtvHgye7*j!^3HrD8r4LJ5J z$|$3cj)l)AnQX$!TAQ@>D_f$lHOeTP@M9~o$tt_7Ui>KG*kUV`P*@2q*ieFHD{$bL z4AV|~En_9rz?ch+arT&HF4Q0c3^ssyzF*cF~#xzl1y#E@s?Y_ z=k)elZ@vk4&Y`*J0*yAHjN*tSp+qO$#hP%}opzT{cS$6uaI=m(1qjezFy@`7g?$bx zc;9@$6fmF{^r?KFeFSEqpMD5t(cpUe#kbym6t0J!guRuXw8eX#6rs~FV53~y;^-rhW$QT0E3q8v zw6cmSR!SlXB&3i6$tqt$0w$Sc;zCWD(Yzy2LF7!s<~j;BWal({^66)v?NBofplarl z3o@%8x+t@;!vs!JHd(5vPugfxO>>|S_0&+N_#XUHsDP4GrI-F%1x`Nr@N=x}F@?n| zCvB4bMZNCOF|2@R<;PidMrW6i7b|0>;mJ zwjQD#4Qc1WnJ|=LLt*SfipmfMFSemOs&xZm+mMEdoCcx`od{yxz?wF?feTy6C~Raa zk}PHcN4Uw6ZbiZo+|*{Hw#AKZKLXM#I$?{y0d7~jlKv9KO5q4nq~dXne8iWa@d#*` zX?4*!NHjvHInHg4A{Dtv=-5G#c0|Na$_ZUG0M!v=7^4`*;6*;hC%%4w!+18S22Zf@ z44!O5Ou;M4Cw%v*Q$T_#Lm>)Oq+%6()Jm2z>4z=SqAOofa}%1tUR>D13TJY&o6hV9 zU`lWp8DO9>ieU`8I5RC7*Z>CfGZ+2lry0rE&jtMhjSEBr1~AmifWcsf1A`;M*yP56 z3lxb!14bLzz-Ac%c;GT1nhs;+A^?yug#avuLXJfuJEs6eJ6`BQK*>WM>j*%~v_Qls zsw{`*VOf42v2HTa7wCIgNBE?p^7-R(G|0x1=(KYRUI7(MmO@&+=zt7JI3v9KVnjopaeL;Nr_jI z_=F_7cUR#-GE9`59OZIBr-v+LbB6t7=<>7;K23v^qwCW&q;a}&oT($>Fvcy2fs9ys zlUe(~M@>L+4Qr%=D%E%f#6DpPQ8nc$P5GViP9>F9VdEQ|?d(eW!3wk(QY~?L3pUx3 ziSOaIxW;wV7#dTVYemLgjG2sOt|gfgoGUXWaKSuf;DUJWuYUXs4HUr81p#J3JX+`l zz>LG22oemS%g7)>lW~jK2*))|xJ7RMiW8h-+`=5_Fb5={@rjI8`@_*G(}H)@Wayn5S3*@t5?j()1RIt2xm-u4^Y#Sv|kui8Ac7p6|dNf zTwDl5+~`nH(wN2&aY~EZFp*C}qz!O*!WA+)a@dAMq_z^N6>XCvj#}ZPvbrJ`c_h-3 zVBsVvMKf?!Vg*$M=ep63Qgg%C)yC+Ynv0y)i&pstVP9auK^C|8Tzx+X-PVG1Z#xW5)g&UFv3+o!X^Lc4NSqd16<)IC#MmpnwJP@>2`LK<_P* zksI15TVTyz#xb7#K=%g69Je_~FK8p2Wh6=*@R$ZSs__Zyn6NvdU?eo$@nCh!V;m)Q zFf}UjU|l!?7{RFF59jm4mX!yn{5e{`>w`3&H3&XDH8F*dhP0(2&Bf?RS&W5|ix5!_ zj9~Qf)S|kgsC8o-QKJS6HDn7}fK^6cg%Ol-R8|`)xym|98t!((a423 zSc#0fth!O3MaoWG<^C#Y{LZzitqI(hatfua_Df&Vi9MQGTz>2})Y!Wou-FocTyeq{ zdM`WTJ52^}u@jy5lfkaHD+3&KH`nysUkzw51A1;g1~Lc@0H3hWV&khB@XZY`B3cXw z_KO%9gx~^;!!Kno@Y&4h1%Kn@4Q!-h6rpg0CJr2YNtj}V)M$4}+3~{VtJ@*$mIpNi zP#y{s6=)*1VQN%tGxgwfrw;N0%le(e^S~!UH7%;rq6lM%ySV+mP)0Cv@r*EnvB&er z+KH_GMQz~Xi!5x1JAj-$oLn4{+#L0Y9PvnzRN0H*h|2ZI9wiBo%z`cGO7{GXkn&NK)Xp&SG2 zkX_>KML$dmrdCE-2p-ch8B=IA1x~;USg2Y*ctR$i1#fwRsI3KDNK+>0 ziVyyv7#deUOorn<#;)m4x9pl`L`JR6ljq4m9MV8$(11M+8x(ZG7MzB$85_Xx%WV+H zdl^h_ERb**)Us_`1EpRCB?Av8$~IsFDvW|CID*G~RJ^&6Ns&xRxtqH=n1gjr@|jcs zBvBKo%!5#$7l;^pjK>tM%=iIA_5GBC=nzqv2mBRPi}?cl!B`c+m@@bRGX%piG!@o- z(TaHf12lvYRY?O@;X*s$f;+f_pSXjby~9@_SvEG{%Q@hXz(OlXnOLFK%f-zd0n*-R znOxNsuatsxyag#Zf}~wkm`u`NK|?N3gJS8)3c6qm(iw`>;8Sglp83Q!n4m+Xl1G$- zG1vpDjiFtf9VpyHrKla-fl4a8-KdmGDty#N5`|Q3+N$9LCtTqsfEp$MURzK{_O!wk zwt_A2!{I?BO@(FCe19{0jxW7X&S0L)}Jw*+y}!-YxXT>XeC@i9!KX14O*gIyhKCxTQ&HVkrLR z!YJlo$rOOi02ON72Mw`|gvbYKOp#1ch3?<&=s-RFTfa!MbTm^Lo&D+ zGbqDl4&!C^0yLUP7kL9U{Ma#4(lk&5HL?&j@(IW(hc~do*<_;}O&|ldP1}gojqs6< zIH1hI&DcyJ-^kS_M2XH>lRL)am<1EjK@Kh~XEcz~IM|s#^2uXe9SdngpLARe;@=rv z-C|J#pm4<+{KC48#CYUI7+3rT*xR-g)&x zFbLuV@rG^$M>5pcLJ`!#)CO!&TOjJfF~9>wNs<6eqw*EjjjEfwwWadysJlH_Te<^} z764ufLlcl?3fmv z$WK6nF7zJ&G8W0`S?GXVJG{d?fI}@HSsV3;%UPM**pb{UU~P^S0#YCa3eq|TPBm%5 z&pCpX2%S-Y!sC!&nIL4HMO{DcnbnDrb&^qb?pQP`$7F59*QrU~8K_-=R#I3BPq3#G zf&!?B3MjbNFC_)sF;W;F*FM++TIhD9IV$B3Yc`#hUvDnf?=27)x`;F}SeQ9R?#>8EXGNQ;A=^4rN2{hzMpHQQo zx!^jO;53X}*^nI1?yOqv>259{psG!e#L+Co!jkk2lyriZky>_q!Xo|LCrmAvh)Lv} ziPZU{o`FaWqKI{#$QWInj$zF+ctej(Lur2JWrf428f#4c@PjJg1XSq6Q_Nkch)GeT z0waY=QdFAUwQZ{5=M{n)f2u`0TF(~>=t;5yfx4~ZM&vzA*SgpbS30* zJy?WwBJir4oFL!w{V2&uL^$+oE)>AS0!@PuRm>bIhOq~Q)r=Pe0}$zu!Yy2j!I;vJ zEXiJ`veDjc&|di(1BjeX3_6xONP|1Ppq`KpDFLKAtU}qe5m*6DCn{uHONkuY6&!2IvF8QEr}4hAvWatF>yL=W^>5&j3=+z!Y3T7-T_*8r!|#UPQUZG86zq4b18l z;yLKcdtF=ka_KPgV!oI|c*co5M8msjqC2Eg@|u($k0N2cTSY`e{1!kHKv7>J=}XmO zhuMq5ou5%9O)iG-mcpMhykBN&axdK8Z=kOQK||@Zke;1p3&F2Hg52p$BV;MZJK%y> zog7%fh}u}0%i*b#r4`B@8QDx=Aaw%H(f*Y?UejGULMcowGFR;*tT35?gA873>6FM* z=?>OGgEE5Ag#ZP_bgi8UirTVmHvuoCgC*(l@!6F>`9PtxU4$_ z0H3h3kjj~mzApd*U;rK@Sz{wD{&%#ITuM3ewyUmFquO-3qt1;xOx-r;|k^>|-@4u}K&HyHU40ZP&Rr*yj z_%bz@X0nTQviZs@26<)vL4ESH1&1NmZ0T4d3nkXfx}b7!Cx_QrJFtRR)oI!I>{ulU z+Q3na@GQ?B*;h>Fnq33FGayz$lb1@hI&^}@Jcr-yWq+V;#7ghsQ z8|y|&k8EXPvZgn9CN}}t!2_GQr6v{xM8HFx>}b111SAwJI}j|ptphnwgLpKNUrt|P zKIRkkTlX?}j6MFfWIlDKVY>zyki{I(o*lEe_F9jwr&hbhlY(gYR!p`;FU42K8`xP#H!!b_wlV{B~mq>9YHF^elR=4%d0^_wzp7WE9Jxa*sd^==pNLe4)#H7DKldyMPN=0Y%r#0I3F5;$CY2 z6pQi#N~5$!x4qj}CNFY#_zvTVQdH)cRKW5yKunV-FV{MD^4P6&7fqhKgX|7YTQ|<# z{y2&PvHFes~T~%sM6;jpOl+`R+UR`;mC2N)}S+UO28Y@dJTeD-; z#)bR!>nvEXTD|h*iPc_Kn<4>rv`JE^Qj!XP`UGk*C}_~AeVgWOn>KISFng1xtzEZn z(7I`p*0~*J(VyFO*0!xO)NRwIjiZJvpFZ2Sap%^(n|E*Dzk&0{X9^XlRH#r9Pi5*; zs^!U5;p@k5UvTT!vH!-$DHEqno4kJqUkWfM?wPuqN6+1SzwGbf$Cp2!etmxaG-A+@ zL8FEX{r+j-j|Ld>3y=mEYA`Us85E=e0~#2V0>T+wa6t+yz_v&UYJp)#bA{2Wu=u&OvaZMXJRH88+$n?9bT0aRic3AW;mIT|s#S7jV9Ts+<0HK=TF~%|g=* znx{N#=MhLg^UPSxFl&diX(k;Z(N(T}K+d+sW!3TWG0eEw9KbYyK{`+dH!X(j^*GHgvM>KD6*`^z5y78tRX}s~(T5oWF26t*iJFTL zZ7i~fAAyn2Zl8Xx0mYP5K7lS9aPaY`y5zCHZ9DeD<4!z#&r^>(NAk57AL_DCU;XuQ zy9Wyh_e(H980HUfV+Ci3*uaSMhtU5CVNjtebOB@^+r=)1u`-#FsU>m3TFsQP3zop_ zMJ&OZ%2E;xUJ%0^B$j$;ZrT}glgIkm*;!>7cki}DNjLWFvLOIGMj*h3olwS0*m+wS^5|MC3=m-M|#3)8F zrg+4zpb@NRNCOhu@Ju&cCyisRhFXrqjBBLjjn`>1G_0{AHQoS%Kz+Yak8ZJ#ef!u4 zKA?vRRe*zf`M4e_lZOxR#LGMLI*-2eWgbqn;+C8kB`kp%OmFdn3<(0zegrh22H~$k z{&4{eA|@gK^shn}dcwzs@gXhrVkHWMnaom#!5yLqWj>72167s`V%$O;>O)r7dOnQ+cnivr%dg@6r z=5&sn!R;7Fk=rrmR=1E6LmaT#+oHgjnxuU3q*@G|H=44JFg^+&t)Po6YSD_fl&URi zsl^=Ss5r&Vq83EO)GT7Ls!n(Z6PBRFQ(*;2#5f`ppD5iY47n?CP-Bs+@r-3C^Az0S zZX39B%CR`&jEfb>^CW=@tu2l^j`C^n(|aSRL_@{kumq$U>y!xuvYqD*K+Hge{0wWS?m zOoFkDW85Ma@EAxwtE9zn5dZ;%iECQRpbdWrBN{mr zq76*OGL(U~vn8=7yvV5A^aRBv7R5($^AX+X7LRzO1078HVi>>Jjw7`LTkd#keYKLB z!KrjpkrT^YdOE6~dPS%|{i!PqT+~a+!V~tQgi|9C2}?*g!k`l!Vn}gStTyH`;9!j= zOQSo?JkpYs?8Y;!v#YbWB;}fSnRvfDI2})ssu^;7dKW zc%_b!tk-?y<9*89Ut}$-plJeV$`kru|7IWs7et{8T?iQ%h7pWkz-&!BQpwjY=tDNi zBqg`#1&Cylq8PPE8BMswF^HjyT=@RBD)NvGLlVLcB<-`e4LRCG{OnsJ1;7bn0twf| z1QQd%jDjudg~?oWGMX@>7;8gYP}*jcJw-83<;Bwy&7s~up*J2K%*7Yo0nzas& zx8StN%7!+c4239rl44P&h~D)6DIPvrZ#>YUUUZBjjD?~KuCanS@ ztP#LGO&nW@nqXw#eHNYY+=KfFZD^h#vZ8QUV~mo5QBp%HI`Hfg#Zhdk?&9dD=t!vW?$`#5 z7CNC5GU2J7Y7+YBshp|?tIgU#=MqLobO>oN7UMC#q1|FM1%4!<0&#j8w#Lz zAgPmZL6gF28tlRLtgx}R2R$$Wd>+T$p44w1!T}z3YaZ5*9hedlnt;-3#N@8)MzV|3_HP-W?rb`W7nZ>s z*rwF}q`Yo1>l!c@fl=%t5bWk59^Nt@$YC5BWpGZazSyAyaUnH+jowa*QNk#UzJXMN zD!~Tqr*P`0TEP)IffAbP?;cDBztI~lp%TUs+O7>S&=JFWa20^%8FVLEE=eDLFBu!R=&31tqrqZEIM9xyi%`{3JfCkZMu1d^v9SR^9+WwFI z;K36=k^STWE{{O~!iIue#OdNhE8XO5uIm+TB2Sj#Kbav<0Ocs~WQxjbz0TnQAyCy? zP1V>B?9u@q;Icgx0&p5711Y0X3a0}lqAIEa83zYRq5*My>KYC68j(#FUXTXK5vpL6 zkHit$rmYfc@DeNmF`_CRKYNi{{|8)CCJ zsq|a;VLR4iu)1Rt)TK(j6g%!?WB5lSt<172%S<7T$};ld=tts?uL{0^;|}O1$>fK+ z)6#S#P0WcVY~&_zQbtgO)0V*)cIIe6h-rqzo#Y`LoYF`jkv-iLKG$y?{t5s(?UPT_ zhD6q;D`jhK0?^aU;TXcwK%+?O7?A74VZGLpy}nMp;u0RvVIIhVJ=bB^`o>WbrPs8A z8g>l>GZZjoiYo9SaZvOt4l}`siWWG55;DQ5ZqQl3aUAO|1uSA{Ldz!ju-|s0QH3aKmkQ<0Oc3}CDlL* zP=YZRAG9qc&{f@19AwpL(E(P;q3!5vDmrun^@}PnbWt*p-t6lgEX6QaFxie(Q}`(G zrcE*_>{*}6Mqv;f3lCNz?7|X*6chs*zyUPB0eFryG&VysR%0_VNgIxZc5vYd#jP@M z=Nsa+UmbT~u(Uf;g$(!gaV=LL)DX(va6(2hvIKVGG7HNv;P{?k3$`FmwSW)hteeP0 zy8IAD`tX}tjwSjqC7Phq%mE#8;hl;SBFKR#*-sbN?>C|cyVbZFfLKnDV_dyR>7`4!wwSB(-||g?DDH> z<2O-$ZBmlL8^Ts>f9e7ZQx;&s6_)i`C(K5nbwOu6;S>J9qd?DkrsT} zGVIDXYT?o;134T587|2o9EhbVYW3H&_BB5AD*mV;j2xvy>FpRp$rkiisEo=L?&1}; zaRz5l@FuKUo%L)XZ14atS|dyc=@x?35ge+)g1>=-NvsJ`_^aBLHJ*Xok|i`!^H|u? z9V?fHFIR?%`Iz$ovxd*I?&q>P_sSrSBM(HH@~1))wurxA7`#9Wyhcr=>qSn+K1nN3 zT_Ps^R7dJ8qITqpiQ#umwv1!-Wj}Fu-Sc-<_ITwPW!WJYZs8VQ@g~F)cm1!UZb23| z>WvH39E_nr@faQIW-WhFy;4mAW7Sn7l>Krc7-2O+;W7X!bSe6VaNtUdoZ@e^;wgR& ze)nb@SRs=U%)mMUFJ6Hgn+lW%55j0r{_r9Ul}-6wabcB%{D2 zw;)Tn`GI)hiMx}bx@IQHWJS;!Cu8PhvdK} z%w~@v>SFO2vagN9GE_avqlC7h0i~fO@EGPnZsx%lP&QUkn~>Shj~VqXIeK_2lr;jA zFAL{TIFxW|m1-w1)>Nt+FgcUw=zn9{1u-F~YjE%)>;|tDs&0B(tyQQcK?l*Xs6A7b zts&f2$1lTxQ1Ao8o#d%gL!AO2NM3)bQ?60`EBO?~f7 zDTH*XAPeGj7=+=|)(tuF(W*Bq+_)xkYX_`^3Q*HnFu$Ht4!oNRF31N$87b z^<~`?9{9OGJ56n}FSD~(XvHC+J3DB_0UbKqp;z2h`8a*sQ+eTX0@qJ28_|#%8y-?M zAtXYj2F1RByl?iV>{fazSfg;dp%wHuS=*u$TA>x}6{>og+Q`vH&o;Ry%m!&N!UE&k zA|Z4Tqo`E@8Z0;)g7m9aW2`iZc4&w4{&sK13M#aL8}Qd2bd$aHe9wE+y`fp+1hzpi z2AVEQ;vSByt(giG_6z>L;1_m*B@Z!8Z005A`b_*ZO`g|HfQUL(q!$KN9KwN783JaX zQvGIC9!|Zn!MI737b@XX7jVWadls|d7*IIq7#Q&!SUh)EJa-!!9abD29GaqGR%u;3 zRps(&R(ER|y(k%t@hKWvrKW;2Ja`&%AsY49r(}Vb_9YT(`jjbiMs1Kr zyU|)r853SbsG*HT`u>gkw8< z!@*c7%h)Ly_5Ph3d;Lz`&)Cys*N>mQiz`QUdppV)Ix1*$SJxF9k5@d{h27UF)Q^Ro zQR9JS$-%VOFIG`j7%Ma$RC|5b<i^9$3Rsase=t{Kz@*br?n5IH?=Jp~;KNUdZQO z(c`#9ncAq0GH;qjPx-+dffC?dbj19srY9Q=|68F#lFSN{mXMRoZ8W689_#_fW?11Z z|MKrG4GlKpCvIRda+we|$`+(TW*`cjz$85$M0#OmV)7+P>ziES765#&r7uNRg5*@I z<#mR`YyLf(k&i`0p}=zVq(IXiccVZ~d#q1g)^h(XwwUf65PkDd0| z!hFcbJF6aF3s zclsLv!jeEslq^LWNNJKmf&vo`j6~^DB#DzEX_AET)2dbAvSs`B&6+i7kGy$<_Dq_$ zZtc2lW2vp3$#3}b?bEmKroNp#d;0tdG^o&_M2i|diZrRxrA(VTeF`%#0-tuAJyeFFE17A?PkY4LSSnX+Wcd@&0a>~FHazLNRU zt2bD$y@>lR4u;q;uVlxL8575D9z1#M$jxIXj~u*t^W=pa9ZlZodEqpZCcTy0kCadhICCr=I!9y-zF;%SaYE*v^|@#2Y-ZrwBK z?DMeCGxnOab?NY^wOhAto4a=O*U_iH?Y=i@GP^zN){Qm+dSgvD(9DA1EUsk2U?!Ag zf(a%JM#2e$4^l!2M3z*#tb^#a?cG)&UC4Y#$KxMgcA=u;>?3i zdD7Jy>pZiTXDfETmKQ5`5n@Qthy{^&5V;7E=;1+@Tr$Zemq;@2iju6Nibo$klZ`dsbn}f&CjIy9H}=@m zPfkoO%y7dFKMZli5({;Y6lARh<&#;h<<^y1c06U69J>|86D5=Bg_?&!Hs@h{HO3d9 zdg}F9oO~|E7oK^(c?>b)7!zG=^N<6YqnFB~nrNz#mRV=6%`*-=n*MG&>N)7#7V2@t ziIZw`&uJGOI;Tzds&uK2W2>&3)v9Ye=yW$)a@_?hPHV{xtyy&AAe-My_rb&xfHr!g zO|*nVTkR^DQ0T3N4T3x2gP5ROBDv=tR8fYJXlP=&l}z&a=M!nNVkoO*15UmkJ;M!v z-Kg}EHqY3TPr^Y?jC=07@6LPgOYU<|R#RTA@yAbgxm8*ouY~~yAG;7HTuyAEg)qD9 z;+I}I$2n)tG}9?(n|%edJ)O*)uV-$?u*w=|rICZFYo0~Z8m7@$3frWgjV9}+y$$Ld zb9k*e4srmk{yRgH4tm^Ho^9Ny9WgNp z30o4N!nLkIh|@;3xWPJZSc4mqh(x%=MTu@jB0`zqM7J_w2~2E`Tp|+4<`7~oN;txZ zk*I_dLstoj)X-j~aM3qB0+Mg61RDOK9gutn#xRO;jARt!J(5R*u5@f;#A72{IM$`M zd<86FIT@Lp0E}P!LN9UBOJM@@7n`jte9CA7`2v%SUYrjy=<`c5icy(kcqTLan@2Rz z)|%2l4K}0+2mY7_o2HqDHpUSL0G0C`c-(?H+F4ZCUU?e$MaNPPWE*LKwjJ19Mm^lg zMQb>y9$alFgY&SDu>=Mn0Zq$=Dhv?oq&34CaswOw+yF%m8#Fn`Nhm@)T%3b)h#}B5 zWOMGagd@&{iG^$qbdzW&=$zQj&Cv@Z_fmyD^_4|weB&8EDx*LD3DAHFbSh^A3mq}$ z#x2EhEC-!|8at-YlTpD5S@41|gwee`9i}n9=*66P@urOqW}|sRUonb-zVj`E7nT{v zq&y=YbW93u>8aFehUP#{Mk8&}D9)gakq+XZ!&G9s6>~&0Omwhg9I6UhqL!MS=Uj(7 zY~!GIxK%s2;bk&_EZea2Em z+l*;8^O{M$lu?Gl+iR}c9HNrrl<=F*c32f1SHc5P@Nh?@4i!}nMn^QXD%7l`!y4}B zqJwjz)!N`En*h1ab%+~S>!2k~Za|}2*ucgN`wI;r!u5vNlxtkaWstij+|$IYfic%y~O z7P6oPFR*qnZ`u>fT-#$g4F-^WRQ}{6nXwGsrWDD{fTS@_v)!Y?W|A`%k847c8T~Cy zHJll$0S{PIR~0IQ@X&5JRP#XZcDK6?blPjYL#tlGZD_v|o7~hB52nH@Jkn5R>zws0 zZn*G;fu5$JMZ%40_!k@102jEp87>JqLWtL7@VPEsq6wqOi4$(86PxIWCvMup^1^Tx z^OXv4fCDAjfCflR4C`3Sde%p|N@r&PgN?mdp&pCUme9DoH#*^DTcGG^$CpU$DWd?7 z88U74)a1bwL)z!_?J`iB}!2*I1n8vwfoL|Mkc>Ho5g_Cc!x>4U52Kv8?_HUy5 zdkt)qA`{zsD>k<|p&ml0at{ez6WwX@zk0eNPh7c$9dQwSsUmeQ$_6&Fcsp9_eCIru z>{Tqb6&QfbpmL-VmbfCkulyPc_qa!xqW6T-p0>4m3WhJp$EP@*Z!j}sh9gaiz9gT| zHp}p>If~&kE7LMPlmz9W+Rn7Ce#YLGBvf+>CCl+zDwducM{(W34t;}09`$wyXXLRC zzh7rPqj_?!NJFSp0Smno)C|yg71sYEPQPijMt>76L;otezo6(Zqd%cT$6e@Kas8%U z(Isk@t6X&NoV}?2KR1a`%gYh-(lF{kp$cex1SH_-x$%#W{4ri73I|QPTN1iP<5>xM zSO~*C`0-eMhyi*}7?WI@poKg2Vxw9wDf$%I3*JsUrMz7RG0p-1b1cIg=kpCOma*=q zQF)f7A^d74B`Ivz8m$3f+A8uH){?l29A=Xc~4Oyn^g z3dbGcaVu*>D+(tb*3la5Ksbe#R@G1~o=0(>$7ud_4b_lw*l-PyP*)NHE;jUNi&JTn z6HcLnaxJ%MD)(0?5>K%QI`T44svvV7kuO=~U&%*>RcM6{13Xs(badom2&HtQl}0mw z1!O=5_mKWDKH(20(|yxZQFOs4jG=Y46^FB>WK4Dpy>(LOuvPx2R|tSA*AZ4WM9Plg4_I!$S?i2|JWdnkIzr z#7<8nSSnY0xCce0b_trm3iy&b`O*;~kq!26h27|l-&hsF(-pb)Yg#b?x^@=9MguV5 z0%ce`3iA{DuzeDh1zBK7T*nNvwHI+RTYHjHDAiVqLgD9fW84c834{3M}ly87nffR@|`IdOIVv0~^9TGGv z7DP7P;ThP$9n~>a+cjuuMNOtRdbOyFrN@gj$cw!wSCSKQLX>(C5+M;{M4onX&)7sl zxK0((Y0!9tgLM(5U{CncA|BBZ(0~s)2aaWFmS_1B_izPs^lNCuMsoyoGe8FU03>AT z6Z?>cB~xtncv@@HCivK7>_-euhHZEFhe>u0x3C+#Q5o{*8|LsS2h)|;)A2~~&9{E;X3Rf%N!5S9CD;iWQ{%n(* zqhW$SV;$!ui=Ib|o~LL;36w<1i>Yu8sBnYZB8=GdaZEXkIrI=K_h1!P2?5|~es!G` zc5;IyFQss5sq=fQgAZtlp6Pj({eT5of;01sia~9M+&{GxU=- z$Y?V-lt`+apg@Dl>7=EggPT(!97k7EYG63z5JU)#6>)O3H`Krf?0Z zfC{M~3D{&qbY&rQWsI$dIkFdffdyC)wmG*KuI}_#(^!ofrfP{r6K=|`?W%M95C)wU zM;NdcQ(&iNn0@zY6#L)|F7T)J=nDXv37 zNsB04S*9AGVJNC`W?L4j?n8LvkQyWj8YGKv>(FK~nv#JBAL}p;?H~`-ppp$V4&%@q zv;rNxG&I|RUb$Ia>J?}1Whn803(#PsM{0whkgP?ioX-lay@(1?YYI?`A(F-*#n>Ru zDOV8TEtG(jP}FkX+MP)VPw^B_mO!S}D09B|5o77DZwt2~wht*b0|U@&ULgie*AMv` z6~F@qF0hxUb&vOVZM_wLh#82GRFHu=h`ZEF~D%@s>@xz%KTd{T1Wt*fw zgV!{g7&YXui48=7rhBp|It_u>syb*PI2w{SE5N#5 zt5_Xu1B1IrgU8#nMQIAm39V7=tq1-)=my;W^xCx{5j z8wlDP4*Qr5Ix0d18~`*Z@PHm%mN%YM8td^%JB2hu)2SVdG#?zY)IfL;h^nYMyYjIO zv#Y|P7!B|-tFw!EA=(|L2zhanDY^h>76ddyI}hc+9K13Q^k59eAOO0Eq|3^*%Nec9 z2?|kr4a@7ipCB&T`a=y801k3a>BJBMF@)9`{=TE;PRsaC0RTnu#0si##^_pe`S8AN z?8ae~V)ID`{gfnR-~@lF1x^qQ0y}?#=%~!Vpo{siyda^zfewmExrTfh&hazWl^)Sx zWriZMnfV#%F?an}8c`FoNRxQ{c9N_q!hom3t2?{-CJ)gdA1b^Kud9ir2^za;$>^X9 zG(17U%0cLHH^`6={;&$TfD1*54a!*!%)6Y=TFg+qyvU3Sr+^BkunFBFA>EXMWDo{r_(e;?4`sr?{)rcW!iT%H znArv@f&4!VEI`_U9Lb?>05qBLkPD6e^0DE7Hp*qm>(GCu!5M?cn)1-96g>^&fU+p7 zs->K7GOMbkxvCZzimP0K(clgq{gAn^v+6N zfSKu19}IyK4T=$M$|dQtEgBy#%*rY(qZT;3u__-jTB@(>!ljw3bS5jb;u)|~L7&|n zG+htx*c1I=54w;G&``|E+0*_?+pNpX%*2tZ=?FXHThi&SY)f*F9qWAQx?T7q`F*yzqX37`YGpsFEr`2?RiQ zEkIqPK@&?ToT*f@p!PIGsxFM8GCB?cUdk+c z;D!QI7_=(xWy!&E+H`4``v4A*fD6M6+fE#<&&$lq{0Yl!3b#!Pr*Pt=pb1R*P2{rF zB;p8n^-Tq2DM(^5;@QESx8dkUj) z;wX;Wq%f`Nlub$mPB}Dblp_%7L@qV{#mXpZp$1RmigHsK37a6EK#ry}2M*O;u!6D5|pTT9z7_X}XzTgXx^uSo2HAFSg$W9Dg{$#wWDjE1dDym6E1G*p#fh_8p zvf8Ts?H=*b4%?vg+rSREkZ&kTf$gsCjos~SzTlKC;DP5r*kNa1RS)%mFigP@1>nm; zEw!~>;-~NlxNQmwU+I>93ZanjNNq$U;)4$|A`U_jPPs!t2v}Xp@l~zkVhpD51nXRl z#$KHY?`-mo@Ayn|4`Lv7Ox{tnF&vRPC@^nIxET&y!!<`$HwENLsUkJ;y;Mch!9gGN zsG6Got%{;a?+(&1AN29Ed?O9ze!?Fe=k0*e{cVAJbAga8%B4BGH7iT37{v5&FlWdV zW?cY`zMMmS+e1z8DURYro$zh{2@0?9qHqbrZ6cJ$)J+{CKv)nBv8Bw7+_M+PQr-TQ z@Z93;)%jxUk8l6?FC_e64^e<)EZ+;a01&r~nIo7BojGyn5~3qV&Ri~W5y^=Q*AN}L zaSaV-WS5H_xsT(b$s;Lm9Z7fcQmS<4Ze2@v?OwuM*Usk6o7=p#^Cpd2G?(t!wR|~k zXiHo`+qq!uNXxvn9(dGYGm%hzw8K7C)ojwM^R>^^?@1n2^V$`q-rV_f z=)CiZ(V}J7t|qsR5i=&voUw2h5gH`N&^-Byo;mknfw8TsiV-N}@qywp_aH z<+GS5 zy+lC~Fi}Ej@e<1{QB1MOB54dWM;tlKu)-vZ#1hU@3sOkXJOjv*i70aFsS-MVK7@os5#`!T#J@t(OIJ}^3@k7gC6S~uOln*#lgEB!43i%V z!^E)4Hrp&UYCkh=w9j%ZEj3FjX)U%=W}_|2SHm>-Ty)b_cU^Yd)zY3atMi2yHrphp zJ9H|d$Rctef(N8A421|^t4ZJ5zWm$JzlOC6=u{=jxH?S>l!U20G$ zkKLhWCaFN(v?Wj1$>m{{_;l6EM`E5!FH=nXYu8a+1k6QWc@{+zNn$*V*~=u8aWc#n zb4;?zR_lz&YN1wgNN>5tjFTs6qYWHYaC7%-u)`L6Y_iJ^Zl8Xd$if%vvLoh}@bZQ8 zqB_N42cCeh>i4~Y2|c*ar^Z?5srwLR)Fp{ys!8GnbLyrWX?S`ZQ)woDW@L91q-vU! zC0uGKsYXTIC5DZ98CHBA0cGZ!Z_bNXz;f=@#b71*S+S%Sn^EZ=EyFBEr4{S8TGXa> z+IVVroaA@RTyyft*`hRidg`mU{(9_>+oy~ss>^Ooh;o7cha!e5l9Qo^`s}k{kO(b! zPYmH7yw7N63UI%h_KUny0tv*_oBvJD8{E*w0Ih)wPkl}(+mO&UKnJo==_eX8Sr||{ zB^7p@?m7FwM*$%5iM#v-Sg-3@uY7evO@ty?n4u91mBzFeN+vN#gN*K^Wi8Qg#z@Hv zQnP+%8CEWNi_KbK$BqmXb=;DVHu5*iC@PZe{Fa~OEjG`OcoWgP8z zPw3h)R7eGAaXZNvPM%T6ZiI7V-SEZ$wf=EVbb7;_1bhT8Tp}t#ezj8#;}cYZDl(W5 zm7Xd|q;vMMicdVE6un|mCNcT5f=VKVD&!gMQh3qF0PjXh%S0#{gS%$|>4wRx8jq6p zN@rQ7Se_8#Yh*(kmu6P8o8>H)_VG*XsOc6p%>_9Dan)*|Gmi|~+@fH@k_KV0kf4HQAlJdbZnRaA z_JG7Ac;%~t(r$K`%xka6YuBYQ?J|!knqx4LnDj2~FvrtOX1v9t-u0+h`^^L_gP65h zrnIvICUAibyqkU?Lksh&S1!U4{;2iQFJY;rt>7j&IGKzLQtYrvsH_R8o9vcSZ=7RQ zH&#_>3~+$YKxd1&femzS)fxe4he~Svl0%JbCPonz%4TxbQL$6I%;Df8AR%793M*Kb z6fcvP+@es}NJf=$mhOVLG-i47vC}e4B|r*U%oIy9{Z%g~gjfpLpi~vMIB=WY{N|SO z!ya1rMHA=+w<^9T7eIXv;Hm=6K@xSSX7#X4BDS~!SZhNVxJoS0xrZYP;0O~6%Y?MEBqf&|Eb$I2%smnw zWpvcZ!qo7v(E2iu63gHI$Y7$s#p-V+GJ!RcLT@&3rgpWhZNz&tp%+akMlOz#3tjlF zPkhD&PzSf5qN+(aTcF{+P@6OyJ>++C>!QG=x_O7?z{ z?QCZ&+u2Scy=7lhik$ac^{Z!nmOiU(HjOqKHC;MX7=&Tl8`{uqv{d8bh!c&`k?RH2 zYVpCIP8ere#sR;E^0CqU=Lg^=@Ej|s*zpKYeYzzrg9z1ZNxp7e zlA#Fs>{^sUybe^?$I{(pfTww1!;s~bmyG8b%si8r076socmXwZhI0xlEux=FJJ7EC9!L%V=`zD#Sr8H_r zum0;i{%SVR;{-4iMq(U8CyAxYI>R+wMrKsKw4oPb&;??kK-F5D*s6&($_bueDoS~( z{-)w4X*jMFYX@>NL4D%}a-y^p1h`7W21$%W8En34kU@Hc1Ocduu%ZTP;2gA436{`1 zcEAU;Ad6Dek|GQM_&dDBnB*~F zMC8K;OvALJjKoTOzDsn9hph;|g7lI_@`sA!xLCv_ z#4|69J1B(;g%kps%CJQ&>yeY=JYOWUnF~G93q4{CKw|vMn(Krha-Jtq$(B6+OvL1@ z1fv&YfSU&cF+L2j#@PvJ=*f)PiJqjYs;jC3l79C{R+ULC`U)!FjuS$cIr}q_5c?M=-x7 zG%poONbqvY6Oy$H4W9KHnqz~E=$y`v49PGQ$!Eh(>-2<@{IAL~%<%q3Qr2t>R2Wbybv069 zprw$9XvhbA@QSkOhq4SW@VYoj5GYGZ%UKfzhhmKQDi+D=NR!jc679lh)0#8J zlT67O{Zl|SqR)yw*~0}8le(sQhW(+GtJ{Xi;U=DN)QkaAOevrOnTA7b!Ayg}7Ub0b z1keDDN~xT|0xeZkfCN24D|fI5eDJ&8{2G3czr#B}S}tZ9UFX5vJ1Vd zjB^CQNFnl4Q%(9ATI|2Z7*S!(%Q{U_JVjQL4I#Uf@vQYpUo4&7!4B zQ}~3rfQwNOfL0Y$v?zm52stG@p`Ka4#8XQR716E*M$>)a^#81?1pg#QmWz!sf(O$#Rd2T$GwGyXMobyl)+IQ zP@%P6Q!Uj~fC~^RTDg#1M=$^(te!2PHQU(jgl08H(%XdE#a#j};N!rDnB1ahkcLN;rW!$9fQFT&w~YB)B;^U{ zg$C)JQmOm|svOWyxCT>jO%N{C&6Qla_+F&`EdT=uShL|ESW`;@P~VQ@xLA`#w{*)d zBvIA<%Zq*8>@3^<qljU#AqL{LcM?0t(BZi~C9WmvXlyP)M$aD*~IqD30mwuG{^d_VBA)r1lj zM<|6&NL^*V&O&ZoXMSe>h2}+m1&wZG**!*H-e!<)+kMCfltmE1y-byb9CcM!Lbz_fWR+Ih9-?WJWowr8Y`+%-;G*W_MQ0B9xhhgHD1;p`dms-%y@ zxD;B2e!z!KaD+_|7QZB0PH2U)9pZ{sKy2#%>7=y_$sUE7 z5rFQl9(*`o#A`)L{?Y`L`qHr62Uci>;FJWemT&pSX!>UDX>QhLg@v-#Z;jUPlJwXh z>hJ$9^6)I#9GwQiwU{^Zz(zqtcjk$@1|V?sCd}lCXV8h8R%HwK>FoY#$(CFWk6g(v zRZ!^OH}(f2f2n?8MOeHzQNV{U?e9k(?T5}&{k7)39E*miA=c5P-QJzMx_ zBTw|h^oN?F>zkbhD-s^F0hi8BW4yMvv=3WYq<)Xdrpx)e3 zzwS>E07NGnNN~d0>Fic*S{Sx!taj+r4r_}R>l+vJ9(V0n_;DWR@lJ3BK-Y0cesx7} z_GRP;TquYBXlS>I!Q!ZL6kG^FBBhiGmQ)|jV)m3&NYJ-xm~L6_>9+^~Q;6fFbqk)3 z+%rD~*#zOaAO%-fqJf>AQ9wOr2Mc^q?^eL-v)ywWZ*3emYlJUr9*6B$0Cdix6q!Fo$`` z{h)l73s7)`5vLx0(1i0|bKS6NwjKfPC2YaZjLa?L2hO|9)na zvrv(SL+n;dog;3lYfJe+@|Rh2CVSmFQf>eR`j_lc=VuT?TEqt7-lyf+*H?fbWk4Un zf(8#FOsH@n!-ftYD&%KtQ>#smJaOuzQDer98(+QZ1af32SRhTdg4M~@t5&T_ivHBd z(qu`Hu3U+Hg|m~VSDx_ggD7+;(V|9=B2B7vDbuD-pF)i)bt+Yc`J&;HwyoPXZPMCl zYuB!uG-{hx@p_GO)NBR1)jBoW~~~iYoAP^I(5p_V8Vbu6+RXC6sW&} z0~0>=3DsXntN2yT{B$2be4Z+9>gX}2#*im-zA{O3=g3wkRla1|>1Aq>v`6CX>B*C= zpqhUJ4=#K-@#4mhBX_#5UoL80r9BHvjqJ8()6uq@zHP3z?$6kUh33s{yY273J$nZ2 znyL1mKn+F(*f9OV_5Zdv_32Y8z?Xd|7vMg&>}HW@F`*WdX(Pd6QfeU0{)Uq)uECO0 zYATiF;A|>M_@G9x^aNCZBa&F6i6^3%qKXdfV-GddsI`q+Z%KnzT-~shRy&Vq;DOQcZh|p+bs#@*!qem8d{ASz(|^>0ULf_ygdIz@S@iaDmBgA!V(p@))~4=&J%RU=sCNyF7! zW2LnXE_0=YBUoEiV^2Q$@Do&v&oBuJVO0uds$lX7mWpJ8S^1=vr=kLih=@+*nJ12* zSsH32F{smsEu#GX*fUL7->3!Mc4K`d zO<3nn+EzR7fRj%@`-oalKj2jJNPmV6HrQl_L8cg$gvmGMs)gA@t+q$?V@oTXRD{!l ze5&@!n-?}H%drl+QemFH^4ZdbdM*fy!>`|oZR*liI4X8w2`8*pz6*VgSmzUAgG84xW2Gi-cGB2Q zHX@;oX^4F)$>9EKXu})QE+068OI_45jo*0+UP@^ZD4NHZBMvNj57f`m^s_1~IqeiQ z)E_=xQjwgH?^wnvpGz7fvM;uRgcZuk`f3xukNz~MCJ%B@gJOrnH^MQF*J@EWfY%Lf zNaGv$fSM48*bh)Fa59J?8e(2006{_q5|bgCkNG2)l(@Rn(8%WAB zo$6etX1IkUc*Sd%`^X14>Jz;x!KXc=U}C`Ls!_ zO_s!Aq>E>d_&>{p2S538;$lnz4p!g;RIi+n znPTI`ZBo-~mh>VwyLpp7xzJ7{3mjc#R8-&BzB3Fk@AW>Msd)3M-0&2$BY($B`eW^#ER{!B?0?=PKm7Ae2AL9yn=-L(yNfJv7MgAOt;97 z0lSx6ssW1j{Olt(Yhzfhe4Lw>qPHU1#k853T0cK2WaW|VPWI{Lsx0Hi zRk(QlN*JhTaFubrF}H$KZ6%|4p~xB1G0*XN_M5#1fv4yTneh9r>e~@dSJ>+yL{2fK zE}Lc(7vIW~9z4==oYx~Tjm&xViYO?8s$A(|v#FI>`g5oCyP4NJm(w+i){LI`sd2d|z#xeU=S+^1QEe&DP! zaZa7cVUZ{{<%mOwdG*5-j{b|xu!(C0SLbI+l)nmOvT!Wx_;SZIqPm%}o_t7KUnx-) z`FgKJ-GqDLdQCTSXiO-kBDybAvaa+Q^#B`PPug%Sr)k-|3rmVwb-iTMkdAA0!A5_2 zYYLPMJ{#gZVfzJM)wKKiKLf2l0ozv3037L{K=riQ81s26iR+<;3RNc&Giyyx%kI{} z(FoyZ>7IYuGZ6py)^r#5V8?L>VEpSE+x>^$$I(Z^4pp{zu%vE{gFngZrfggO4OOJi z6iip@9R$K2e)m@}I{>vrZlt>_`5YYQvIiC$c#h=ti}FT39b-$j74@4abv^YudqJC? z*wd%-?zAHKSq$a2n4;IgX=Seb{w2Sx-1jeM4PDQCjAjU@*Im!QuFL=S`zibL@4%- zQ{4beHvruU2*A++H`KrlBj|*V=9rEL2T0=p_8Z{A4ZwW@62AfDZUCthK=kMyFvkPT zOMwQ2fh`{3h6A{H06O6TaMHkyIB+8eI+4D2C@j1yYBmq(i~$bwz?*r%bpWJ}159y% z$_=1>1E?PZPi_E<8^G)sFgUsAhy#3az>6EeKZKqqE&hkC%gBQW;{G~fo{9Dy4< z;N}%@;t1g005@L1jX!YWd+)$a_~5zOfu&8}tGr^+w@MRjn;(%lvfVlx8Z-B59Ao&W2IiM}V0S!2y@Dgae1il>6r0)ui zjRTi`0B#ProCUV}fIb{Biv#+ufY~cxcg#YkEX90sr;J+#0F%B@p0qPfk*#*7H4sf?vZ?*x)OW@5V z?W=uJYn%YX3{Vpb&MyJx!+^PD&_E1;3j=O2z)d7@{QuZ)5`dcw;5eD?=mRiU2+TJE z{S^SN5V*+$Zpwh;{|9_i1KfNCjvMHXD+GQg+iZLSVkd#hiT@!_!2w|xK*|L}^l#t} zb0ZEYx&Rt4Xus@<=KcUC#sFL&aMJ~x4*pN>jdqyBtpsi*n7mbr zi2GDd+*0Z93A+*)nwi`Vxy2E#VmTyv20g!r`@-EfnCG5{T_*9YNBx~P(cs9?j{l+D z>vWL=B63T~iV&xDvU5GxHyps=@rkE?Q1rvvfNv^&HUJMp>bK|Q<5btexj*CHtSSgTa^ebulx_d|j3OY|;`$yq!J*W3nXr}UPY`aM z67-0V*ZLeKwZ+v))~y#9=|{Jb`ox2WFX^4G^G@;0OR51(x+=K9_V(KBUVd(kCXpSs z=vT=rb2q;ex&D1o3S-5 zX(N?tnNT=IRB|`S(mJ2=6Dm?(jG{|aQMblGcE*{Kbh2jB9#GwlKR`nYMMT9pT4AY zDMOPy7Vv57W`^zzG1>2DFF=1boPxHD15uMNW?S7OT^SKox3Lzxfhw#bW z6ZXo6P1*l`oP#tIZtqqBkLb;A1z}sMV&>4d`eh>cw>R4wcrndKgdE7LLM+LDt;N&N zUjs{)=jG=!6Me5A&IF#j{w*ZJ1m0XdQqGXu|2;|m?s9XPrRl(u@F57hQ}bIf9H02} zk-Ah{W73C!_4Uj>THhuZKCkD$NW{m8k8-u!WNzc@>H9gR&G=WNzCZt3;yG}2P|^N?)%ZG9JmYX;;{OPf{?{DFdlk ziQg+D=y3n9tS$W{mn_J{-CsnNJ!}x$4O^cx;os4(4oZtYl`(#_XMP(en}9G!Cz^LrO%QUO7}d? z4n1MdSn}$B*cU$Pr#~r>#gnfjP>W0D*0306)XeMPxyLth}B_upno`Z6dz-Rdl z8*Pd#y%&Sj(S71<_rCIs1-&E41+vza`3A>mD5kUURt)56&07P3={$ygoH8VKJXEIm zzW$FQ<8{giHT}Z;BJp*tmvegTCi+S04|dJ=Q)f5^s|pqNN%bir;5n||2t5hhGhWT< z92Q6sq$teh&PmG;K2u30fK?P_K;@-*X5;a=JkL!X?=DcIj+Q1lQV{R0TbRPSY;Fk~ z4D{fSNqnhJEmhr%h;0G4R}qojZmZohPg_B}vSyKR1h9S!J!~`v9Y>GVt+kTBgytY) zAH3pHN`I1ZkP!5Wxs+>?PM#>sM7AWl|M98$Y)G|w9lO`OVt915to`@_p_ zC0SSHi!9C9v5!~So1nhM4i4tS?B5b&FY#Z~|Fc*iVj}!98%X-r^y^sbs6-xEfBX%z zrbTqOlqy}cuu8zSxA>kpdW*7wYDnqJ`;cRpC9^-{EP zv*oWp$({>BG{MvrY_HtZKbrZbgXD%7mJ3?Mn`i_>#T4i^=kDSZn zkuReIb|zK*fTleQrfl@26n`9Tc5*A&+D=y?-NtuznvzZ8l2RQvM53Qp=!v%z+D>0V zVmz#XTWXdiN$n&M@W3d`pjNu2vWQm?%c}Ng%cr(?b#M#x*wk3N0&2%>A7fkEiDCjdNMP z2&;v}#BzN|m+3q`hz>Gj)bT=7q+FaUAFx7YYZ-rD3S4T@kL}XFk>9ZT?NXuk?zi84 z)KA*aZ(l+brqX4_^Ogy`lmz8=KI6%=21?fYy$)RNo$0!d#t#q=lLcN|U$bPjt8$5E zUntR8-9OXs?mIWN{}S0UY!)h285|9~`@ppOyIzixsAZer!hhTOH_77XJs(vH32kJ) z#rM0Ez13y;{>=lCcr~x(GIV0Dlj2|syn;xJM}eyMdv`B|2TTpekVIyKJQ0AM34L8^ zvw$7X9p5fGmN{7c9I!$K&87P_8xeky`02j8UgnIxPyyf}<#n733k3h<4@2++R;Y3u z$nI|}`Z~N}d-+sbi3uwO?d$VRu^|e!A!=XcK8uA?WdRObu6AMnz2FR-3k%|X^VWsK z@5;m}Me2oX$U|P^cYdq7^i_UDb??UP-I}FPGUqN=?PyX1XV8TeVYXGYw@zT4J_w1@ z8i!>GLyh}s5Xd)co9tkpR|nW)`FT?A zO;@2+&+P?$oyS92(U0I-_HdGOUx7x4T8FTLJc}4(rmYiyC25+v4yaZ?3SHzI)$V)y z5fzX&2EP=BQdBD17KMDg7f6>9BJj(@T-`^|)b=;+3-;N!xu*8EP*3MaVK2>SuPcc< z!aNJ4;o>Rp#O7=wjv}1sD6ZiKkl4uP#z?w43n;5A(X?qupTKz*QA#^hUkVx=OEicj z8tV7ePbOOU2vbGc8uECM#zw!W19HN`?ZRH(PDkgwi8g8UUP@L?uU8Bjizt+)Jx6%o zb)9PKLo21>Xh|k_b=N&;7?{o=I{&^I&3odb=lCfwY;x47I<~jacc9SM$A$&0h!&%J28Nvbj?YQT?(QMLai+*4m8&fbHZmorm1493*a}xmZexKdbBTbN^EdD)Oa>Z152bEj>@ZoQxSzHJJ>F%ha)bm zUz#LwZv{E^2AVV_S#F!yN{8}2z4zCRD9erFZs?v9>d7YRfJm|v9dM)0w!({zd|RB{ z+?ec<944dgh)bfbGr;H*dh3QqX{98RHO5A4B@Q7_4A74(4?_+@ z2rJsHmavl)<|n%|*ptrUV~CDV#L*p`H}6aj@8EjPJ+VVJ6hxWXuhHwpeSbH zMKwN!Ck<1TeU@k6Yvn3fHW1w(9u;|*N1m2KR+Ko1gKBIihSCwmA|J!Wg7hx{<^_P6 zICJS~Qa*m##GSCyFLgmZ$IWb_wh6s3I`96>Q#(y3|x|zK^yHnO~j#sCWS4L%^=6%*lXp$dM>;;e%^ou3Wrnv3(WW z=EwKj@P;CbkD7USk1e$cvr}w9xjRuBZ*NmZFY}@*p@tCgRN6 zs|t(x3RC*P_K5#(u0jm4;j7_E?talEl`-(IwATP}vJH`lW-*i2`|9w|joaKiNku}A zRUjl>(JZ5JULS7({+Fm;rUO<&>>UYjfb!Ik?j#oRK}Q`4V-EBBQlbPRiKcsDRE>Z> z9q1)r>GQ!_NP4tDaxLdVMLls^cS+E-dCp6s5WTM-3|`SZ@h6Jhil?ncofXBi8}(oM7bEi$ zVq))X;rk4tjn)hx?5lW~O=IlsQ0=%>)ADws8Bvphe{{G-rLaR8Wo3RkBW+!k?-Scli3F_qAE#+r-BjO+*^uk@793^f|O(DPS!cc)BZcm^@EY(Q)Cb<6+4M!9u*I9d z{U1sGD7NA0g7z&k&T|l$W-L(nS|b+_M^hGkDN|c;{%Ll%QT@7Rp)vb!GeEHd)I&Op zpv1#P0i44^XYHLSE6@;l2`Nv5_hLrdD?(4%2Az^9zo9}1D>2CmpugA6)LemOEMPRR zq}9$*aY@SG?otovxYZ)fd^6l(>xf9x>M;@rZ%nprADFcMMujp%}r&0a28QI#qd5m6g>v@vS>TyZ@^uBy-%t%{mxs#_fk%D0DV{$DcaUyDD}Y1;s&6ngp-2zIVB_#kYKM=ZCug9Tq0__FWtnEiYjxq$9lUt!4nJK5Hch zCcK#f6^5f{EJ~MfQ}`C6aseY;52qQ)rVGw{&G!Lr-w7)NSZ{J7{+{sV7&Q2>$7*<> z|7qLRP@CRhXM5?uNn`_ja3C|l^2!a?BnMJ0AF(dUp8i^sJdiE_s_cDBJA7nHX|Ics zA)L{?G`cmLdK;i_GPR1PnWl(_UO>;}*rDdotdUM|M(0&}##w2iD_K{X9MpXg`f3Ck zVnf&$*G1h_F~JC$Um9x=2qXu_v5bM7v~#r!bF#1cXfvWicjt-&Mx&p7G-v@n1| zUCbB^CldH1a6SgLUV;kmL%a8ST*`+edx`DfoqH5 zZJo9h%B4$c30$2#KnWT>Sel0iId%Zz(@I#NK#Qq2LA_JC_)iocr z_CLwb&Ef-vX^ebe)Q=iDi`Jb7rE*b&PMOh*+EeE8^ZJY%=HoE$R}I<1Uv7i`Kq+E2 z!7b2`_5twqkCW2x@h&*A{U4&AmLs!f6F!ZQyR99xu2&O-c3c|ANmdNaroakIlO#Pb zo%IE#U(R2E(8arEa3RGVO=oP{XSB)pZ|CXIx1mm$h7}YO`~A#+GGrNdeccmfgLCH} zIAg@!|I)>AyZmf)tm)ZQ?asFJLHp0`@!{5~9EJ7Bo9%{A?FMonFU>fAo879I!W`kT z)5Vqjc-RLdgzC!=GnSIBz18l3$?|7yOfh>)uiKVBeZQYPq$fXrOoQ{M-k3nFRR|1 zwcebu$nQ^Roglv-9z8oz85tvUTPql?(fkLb$j%en)a!nrzJU|_FMbD;{wa!wMIfP1 z^)9bS7he8^9*q7rJLp+_1{IF}o~1Y(74!X#@VrzTq4fQ8?t?vb*oxY}W$Wd!?<~I# znfL3T^`U-Vz0sTZ(wu*@G8*1imUFleg@l~=_q&3Lu(799x8zsfVOJ+4SBrs{eWR;r zg{!6g9~WicJvHN`-XFuq&JITYPLTB3yjv^^Sa%n^;Idld{Icj}*;=l5^5*?EfnuS5 zB_a9PN!NWEz`bHDM=hH6A>{@xQz4X$Sph?5u%;S8BVg5?VzB-whFR=@L=75;P{t6` zuvHhqm4gND5t%0zjSnjm=#6&sLbtR@hy!HYP~2dQJp2%eMHulw3dmXHu<&fq6jZPD zkr{Bu8-Q9ikk_T12H_RJQrPPJXwhgW^0zd!c5L0U*?WJvC*Ab7)wjT#+tWE%d~UEf zqkKGx*^zB;^!7n8N3~tHY6xW7CGW|v_MvE~>22?lsKK2P!>d82jVB;|dH)#NXc=)I z8Tog)rV?g#lKT(i9Dj0SNwh3A}Y8MrNTgOcoOvB)0X}MMR`o>nngtjfbZd2!P-v!YITM{(;A;R zd0BRrk#1cB2hQP<#H?M7j@11>TXDli)wg?<`lCA>g0eBqydv?T!40Em8<=Te^NSDS zr+IZI7XR%>-k;FsFGtY1%b#?BDtjHTvAH8b51i6 z|4cgYZghmU_K#?t!Oi97^_U=%TLKx!?19okuH56&fz0gWZzOqq*8$3Ts$99GwMfpH zxwW#wPug6nb2YiBUzXGCcBag3G{53VGCZ^sWnW5_c+ZFUALzbPh?vaBG}lhc-+E>_ z;9oy)cI$#|m3|%-E_G^stgI^cCnBQ&4OJ#@iW?immHK{r6vdGjhYW{LRjc49h09M< zuc*KX%^8J#;x3m@?4PW%93yj0HWLr(qjrpnbuNF6X)9zV$i3Z64(kU;Gs~A#Y@}MV za9~1;lv`QV|M~48wYEgYN}qhEJ)OeWDQ}WHxR^6ERpWAN2R}?Avs!mk&7LxUCT!|Fyq|qtV66P5S{KoGjDey#ytsRElzerp_Z&AL09!xxBSm|GOL(_Mu1coy73efo-2)_ORB+s^P_j z#CWaRx)O=SW;}%I?P~X9+R2pJ)yK?mwr{NBd;V=Q_LT=944;`2ly-QTO57}-B1bi9 znF>Q-P$+!N+UYSIpU8Z$A|h5_AmNZ`-QdG3cr#4}BY`3s`xCXa1Nq;)B^g6$N+RU1 z9Ri7=?LZd2PN<}j$T|G}MJA$`6*`uS`CH797i&KT+U3GcfVz>m=t)y%h}Z;Kt#MY5?dE?71&;NLwz-@rH2 z@@0%$H@Xz&n<+GfxLHbO23elCfzR@g14U#?!Pv$)b;YZ?VWJ(l^`wpTYy$Rf+6OCA z&1caLztyDeB)4-OrcTK5(#p$>3Q^x=WT8fK(uxjzcDDO$0qG+&kghIG=A;k_p8g=C zzFYQ0MU_Aza-J>-L#zx(Q)jx3@Oc@f(?8Il;S8P``T>1fnZF+mQRc2AVB_ znP~i45IEOGWEk5?ooRy4cfsrL*!o(lp;)J;+Bi6+Yv~%vIJdo#Q#t87^&%$c4T%Bd{Ag5^V@P`~!oqAY(hn1_bMFpmd1|mU6 z*rMr=x8`(RR8|KE%d?uB%?2Qd$0sX1FMWkW)&i0q_l)~gIq&Xj;VrxeMAr^L;I7tx z4+%L6&P+V*1^XjXk}`B^VKRUcv2JC%|7SRcm5HSMp=ja5;0&j@3#WR9DXw>=vAXz1 zse!H2DoLkT&0^KRqsI436KP3XaK@SB&1aPT%TiJ4?PsaOh`@=6+ zKlop$fWNyUYZ=>7_~I)7W#xmm36;em)=v0*DVmJ~>q2?d1=YuP`uAPo_-^fv7Z<$# zbc&mW>{G0kW5}zYTBNgA&96qa;y0F9bm>Y|Q)aG+GA8iVS@uy*&C-Py&O43_V(v|Q z`wQo%`PYwTa{4*OvY+StrNBCfAr`ojeFk$|0mX(!76(oU4XF~APx|4~8{($7SI;4t zvJBtmx~;xCF_|lynfI#FDHAMy^75Z;nUGnVXD*T3EZ#kBe_LMMv3f3(1I2YzWIkgI zD%$+7F!M@_&^v7B+(T{yMRMWSiCT*r{`K{>+_C#M(<&6A z1xK+?+SYtX^r3HsuEIwEf}mR+pEcU2+Tr)yd%Kvs;!_EiWvFD zP-(|eh|31;84PCk72@_4>dggDdZJ^}*i!#Wp6nFu&1cR`+;WLl2P@jh&wZ6Kj+Fo4 zUKjL)HIhmptfmg1y$FlbN47A*}{rmw3f^kl97$)_65BQO*baJoq)#QUQg*VqJB3U#z>4WG-a<7Wa{dmC>(i zG;I`Ywh0a9AbN)o1uR4tsf42w(OM#*ZTXh4D670D>uk}4*C@#dp?wbrPq2ge%#>N@ zc(}9hJh~qRQ*^Rr$z4>-ajQ4*+LRjwH256%vEEuJkK_t5u!C8#vfj>Wh0d+h3C+{T zDWwT&vxh0ORlILJkdc;^5u^%l2Bn|M<@Yx?dry=W8gjpIsVTau@h`&2FLh~1cPO@W z`C5|F)++3#cO<1N9lSyjrJ(#8d!^S$IwFb@jMh3p*4 z1#>$}?FBJRmV!%{21%;3I5UK%nu9?$%!PhECK)otB#rf5jSBED^Xo{HK|GtGezBZ> z;_IF?P4*UZZoUK+*qt-=^?=+!7iB=Nu5^b3MkC)YDlit6kSn>{^$lMdrEG`7Ljb-l zNix1@L}|rzi6*O?_^GXSk3O0stM8U=PK5ois#sO|((thgT$9sMfK|WG#}mz3G`Pr7 zr+BC%pshahs-F+9ajvV8Y>K}ux1TiN)2YUtvKaY1qvy$BBLoi<9pWka@~s4@m3Wp=>Qq8@%OR@yrm}VT zlS6GCqg!^e)|T81&yY_y8d3fwh0ZmZPGb5v!ov)TcSVE>sNN^1kmMzd@jgcP5Tl13 z5P8i&ghVN4)Vt;xT83!@FPdVNN-gHzQ+Hj) zav5Q91yfR^z1s*`WDjC%%Y9G9=-B|FXks)^e-XdiT-ePVjXHQLukXx4$1&O@PD1lC0-S3%S)OPj z{Rv&UovMg$gd{Wg$zTvhZ6G8rQKO;jZCt1RNv&b8)95ebdX0=xdNbn)UI>#>JSmq# zC7vd7!2C$?y*}!(+w{o^#8lvW?LI~wIjq$P(H{#lGoFw3op4>M846HJ%pF!4wxD>D z@Z5D`85d@9W9x8vZ%7B@M^Kw z`Rh0R9|;_0dV#nw{ljiOFY%!#`iP>i-}#XUX*7pf5CWkONTOLWn!G4oX^^^JquTTndF@7T3t7}6Zqhm$sI}niZXGhasJ$I<@<$~E zqk2CnsMA>rkl|ldqoX{~`0_RgV2phRODv71k$#eFtdq&8JhWI9)ojA5E|ri3W+5r9 z@~A!EA@cqcEPFUUGu=t@$SS0TpPtLSZKKoZD}R(q<)aXDf3gC++UCX91tr&h9dAD7 z*5`V!Yt&cpEat=f5NjsJ!zMZwj;a=oJRS9st-aL-A6tg#BwOj{DDzh8uvwMj@G?9AvOXQ-Y6LhI>H zBO!k!nu5`ZKg+s!$?`D?7!~Rm*dNAa7L+Qv{!s$WrasBpzQkrZ`B|&s@$th8v{1sQ zL9aEu`|{3;7s1odo)tFR{1n$(!_->@C{6T4yIfy^u?Q zVcrbZD8gtSj>fC= zdn;y}*nIAC@s9#~?b^a#GS|>L)DVmoN;(vMl))eC+#3$|*xy+l(f!HhO5v@xwwFo~ zxN34TvbH?>U}IL}a6vN#viHcII?f89`>tCFF&){}>EGRzH#Yo+`MSJoG7Z7q>~WYp zbSoPkT>5sP^|Ra&g{8bK6tmCGJ~SS2E7z~%?U-b zb~~ME>1X;^#Fy`%SIaHFQ{<%syW!7jW2ypHarK?AExbNr~;$*;^%#mih7A-sPz;wwT~*y)Afza4p{;T6DjU2tt4` z$Gec3mLD~{iwerx-Gy28ghgesA7k`|!K_($ht-7f_22~ghADgW$T#%IzkArqFfy|s zx|Ho(`6olK2gSWLby|LUmcHgnvBz7sZu&e#Y$3>hV&&EKrRv*m<9HgY?mnren>!^xn{yRKM54rn;>7OgH%|UWEwap54dr zeTQf{?#lg#^-q~=3DMreYZ3a1v){rM9ugAt#ROD>x#l*X?SoE1$(4u8BE^vM>VQ2T-$$WB$pxN=C z)Kd&IqdDG3A>5;7AMHx)PmKzjJ#O5$U0daVDQ{xa{4@Kk9zm%{jPWN3htP+2s8?)f z5Lx|~p{_XVpQqY$ulOrG9yLPJgnVB74m&hH>l|IotdLyEiYSCa`0Am}Baisaz?@Kg zfuCXg`WWdj^sCuz5+Ss(8TC>PjZjCY&p1iUbPE;8vF$YxCxf}* z81?qmx`P*YCqjY6SIc2XTWTvu;vkgpbQyeV_|rdxdzm8Nw@b)%%^0QWsD^B{t08xA za;ee4LK^?=QfqL%Z@}o_Ft;r%m?NJ{>%Qf$zr0f#FyHT;rT=qzH+Gr%CXk2Vn9xmW z{@l?y0T3(nky{O;sR`3ZLQ18o&NTfvY&JuS2&Egq?9lTm!Mhg=Ue14;>dry5zJ~(> zFT`}f97UGkx}|iJcO#okoG7qEi009ona4FKV8u=&3!>=w9tCrFALyLlyP_59TqJnV zErirB^!@3gK8uf4c>f2WoFg3jj3&Up)kxX;07gPVM@PqxDSM-Qs1L)9iYY&9q#f)} zI{e`nOyo1IcG))E{1$jhJ-6-Uq+g&bBjn96<&^MU_oJ`*MC$egrm5Cuy-kj8_Q8T|C;l>D`HZ_gyZ=q zRSo+gwFmr9!QIeAgch|}P_=*f%b$>ZRp)5Q#uuy)tQ0or&rlx19%X6*j2mwjX20ZSb$MN>E9MfZm; zpD(?SbD<{G^xv7pD}v2dvN?k-JNs*-iHx7? zCacCL=#3M56aCbDnL|_`6Kf>09^EhpYj#cz5ybQ8k-hg+?g~0<2}8oMi&sm*SbP;k zc)ztCBK|kkX(jeMg%^Vop_Yxn5{5!&FPuJ;5wRzI*io4B9mZD)4<_LAB~_t#jLEp= zcB$y-#ZZ2v2OSUDcDCG5VxZvN$B8^wa2nWOD_e7!}_A9-9;oG$^Ge#g;)WO29 ztPis9ZOB_u<<)8$Gd%R6N}m!?AiP(J(2z!oYQtqB-#xHf{hXKeb{+D$`dPZ3U zVwGW5ew>7oEkVJ~X6Xw7^8~fUO5{e6Xhq^Il#bn+8Eej>PHc}djPoTgS6(`)MmMz3 z22Ax~tebX{M_2qR*Aj*xiJo{n>SgX~C5vvSpoe2S-6%9d9douxgE&})ouI3ha7Cz3 zA(>@R1n5}`P2&_qj+NEN8~Q_-y0};y2Td1lIq8!!HXGlDAXm{{2ss;S9nT&3s-7|ah9)#MF6ps z0a+MkwvNx5E^FMu2xS6IVLTbfSW>2qmyFAY1QJn6B=*t448BgaUgf5FLvBBnrKwUr8K%W-CW3;3I9*4YpYowgar7$J@QFi|j1apBig*58HT6 zLZZ<;NA)){U?sft_&`i2v8lSFaxw}dPn!+yV|w7i{V0suQao1>+d*Or;K_K@YL0Z- z4qjmCcR*VbzQpLNh};Yfj*0xC%l=V2V&-(iK^RqBnz#JhPX~#Gffe8%XBwKt zWL0=qDPjtRx?m3G)ow0(39P!&3b^hBe6KqzRIG)S{Pwjp9^-W>fuL75NtaPD*i`8}b-K;2ZKz(4*cCE!9LkgsQ5Po{&pkodm ziA;Mzv=gbW+aELL1i<_!TafNFNy16aJqVZds(;^VH`~qF@*{-?V?CYE-l86#kEc%p zGnq=>7QZmcNtCuM@3S z?1Fi9HhRi!u*yw>lUZaCy>PeomP4doBIE>KG&u_=Rf4G6oDtp1Nt*sq3Y%d95vaE( zXJfDMy4x&g4#>U4)>HtUzWKNKoEd0z&iq4qL!nrdg02s;TG~m zgUwl~hddIyDk+jJ@Hp1@rz`AsL;*a$M(Z!QFc#AuDe$KIZ3h*YB)05Db97$dk0+lW zGk_D)QdGxd>m?q?P|bn;7Pu@sv~0@QnMtnBMjjIlag2HNTCMcni+$J79MVByd$=f? z{1D0`Af{<8#D$o94zNDm0Ie=rZt@g5e*s@!33iHUGDv*in-^2Q3V33i-_RnT%X@Wg zdX1Z+=hz#0Xt*{+CEMSAcVU7q8ibvtv#v<5U#i@jvzZa|QX-%9EjNKrIm@d0&RV`1 ztjhc|oNZKu;nW_in`4;0NvkjVgpli8bISzV_b6n|S+*y@6s zDEfz)Hj_F}Z2IaE6~!$bI=*O>N*@#_fR$%T?Q17$$%Z&R1#w8HZoY13>OkVBjDyb* zCU8B1I|E-A`gBJigN`X9tJm3=n)dlPfpAABzLMrM3QFmqDkG-ej(N8IOf3Op&se=j zMU85V=%X+@&i^ij$u=7X*4OREo=@&PMyQh4PxS0(~P0HEate( z2T5SowNCJWVbX=3F$9joGKg97IU3PU^V3Mn@_D4S)01$=NQ7Jun=}~wj@_slqS*gq zxn~V;a4qVDS?(DkdV4KO4PcQ*B4Qy>7NVUKEt-?aZ6*zK;vl#Y$U$V81_2`7n;~hu zMa6qRQpBJo(o7`pY|)C46mmvJhWHToO!)wSC}n-CN`u5Ps&|RgHE^Cu?P-6vuKY}R zN~IMAyaPZ)DE!J`vA6R#Q0_ftxs;~i7+_UNLP^IL zthaw!yoOe|Gyjn5k&I)m%lIMbL{dqn%*tW&oR-Usj#fY!@pIg4YvV`MI9>f}N7O0^ zwUAI=5*J5k{66#1FSq+f5X{WnrJKs%FedpsI!t8ShGAju(%M#sfmU>>VW~{E})JBxn z#_Oy`@$SP6<5*oKRn;!^@;1U=o2Z@)OeHNx#hF_(r*Xx0&bx&c>nwE>%o&m+96b2A z(KpJ%?I4EkATPs0PsvyZQdAXP4Et2H_5KE_@le=)o;6t(_sr)vx4aAZjFm)acJWRG z9b@?DmXY6R#3{3&`OEi$z|UtZrgxokWu(xKiUJQ>K|~{%_$iIBhPh!798ltkdW1I! zkgjAA)V7oGJk>PHb$b4Ssvniyy+fcspPPnh7GaMF?Tqkf$BzYW?~XL1H}cPzGgC2= z)Tq7B5y?DVloB^iEdHD#i+~EDX#{eLwaH}lr@2rCeBNW*fitGdlJ8Zv)3c6PmBy_FJl%?dU%gqGA zE79q?3!G9EPr;YQ|6K41;rL|6`$>o;Tm4}Y79PWV&G4p#*`HvM?SV2YMmdOp--rO5 zfAvgoZLLnDWDCdk)0+>1;jC9e+HB6*Fga3fCp7+`!aVArhAP3aw2p^(Wy_nywJ3s0 zWN8jY(JXh)(5m7KikuSAIkRbV2P)I(6zA{=-P#EqZ=b3?vVbAyxmZ#6*HK)yArZ?BGTS9?j{*Ul4qt6Si@O}nx@u)+mmevPDnmpS<<)1KwB zT^2l&Jh&K3?Uk7Lr1n|I7^5>^$s`%p`il#91?!Wb^o(`YGU#+;fR}G9xh<=@yQsg1 zT7pnNNgouFyC{(%U4+g4kD{~iYqEX&@H&WX5ky zR!2xHsUV=w2&D`VRLp0D2tKHQidg(!-oN3#uj_N)=lT5}hq5CKEb04UkI%lx8?YBZ zJqC&pxbq=9m?fVe^7TTfK#AY^^>BCCYrFte-s!BoMtfS^S@pcJ9}ewaPnSld&s;oz z{nq=HLt&zhLlD+E7&VV~($l2hMOiqn+Tqyuj`EOJ1^F zV+3#UE}9R}6K;uZ7s;xZ3<-{*3y1`GUXoQFrwlAwm}+j1dy!TjRg_ zI_`@*=!aZ^w9|)Ue9;$N@f?bj_lJZb3JGE75|o6oixr?-j82yVAFZhOB41vFJU^OCweI520^Uf-mOvgJaqmtn0EGagdlKUWQbz?zzVIT}>A!xWERHvak! z%h&S=p>qKbH};9gg|MF)@vSLk1MYk5v)SQldA12`8O~>OUB@S*l7CfMN3j8di|&GS z%BNCh;=Q)SgRhCrnghl;GJuaS(={ZzdZ=(IsY%Z%(0c&ryq}fj z(1{AgC$RsW@ns`3$qe;hlo#g^CYh9xI`WW&URw~DAtCxRJg}<1Q|H{!l{|xAB z1PDt`d7`{i1>mdVN^cC%-&=YeBQwq>B60xvCXv>EwfVPn-$gTQpkF7eP7Mp`38WQ4 ztys#*V+xDsR~{IxKK&kUUKxJ~yZYL3U@$O4H}(Aa#_5C72G+X=moq8>Fvh}vlJ$6lX(0rK{sylvs_lN29dEl; zBQB#^)Qh-(&Mgr4pGl&nQcr1*9vLIDQx-4%TqjK7;hNriALjO2YFheZTe^N_UH|ow z;+W5}Sn4lX>i=spD%y12)dwIncwH1g!FU6EgcHoUttuS==4`LIMLd57MYz>mbwS(q(15=%yf zh5p8^*4@IUQE&yn#Rr+%h&xgoW^tD(n2-BVbWHkx!`;x=l3hCy$Gb+rQn$XD{Ce9QTQxDOz8{1fzW-_b|M--)e_9D^URc*val7r^%hKr1RUi&}>)=FsHF?Q0G17TlRW)?}BYVci?F z`Sdy^Nql-^KF}5|d-@&&ccFu;EB{1yA6&m*>@5l@r%w&wekpIjv;H5sJ{2hE5OT$+vAh}ZeV z)JB;`xd94xDjn55pI?V|W$+8D*%WVd|2-^G|Jm?mCS?98l5-Afs&pGQP5AL;Ir5!t zixpB-C2rqa`VedsoGNXESY`oC5j6HE6C5xD)xW?2i+R&1P^^l_a;Bh14scxTR1N{g zzlDe`b2*w4F6`=15JYf=sl^f;JoIx)nITpx4cYn)3JMN~E{n-rD{8K-!~Wogf^0l{ zgJ7DaZ`YU!kqpCEDQzm0I&KX%iCoo?Xu3)1oU6~03FA=U*SWYx0iB_$nM%KRP3w1N zKC5zBqtfAPo&9{Nvz`Ayem?E&BOzzC$r8rpLU*=I@`c9uES)eE%y7#;jyjJ#7My!N z+Op<}I6?FrIaL#MYzP0zz|8BdJjg60-x*D2cZ{)AnyRQdDy&v&j#?ccn(ve*0+ff} zIw<*kcT<0g3l%e=`$Hg`-4WMlWAa5KN)Ihvvj896Di&gY_f2MtL=7&(q#uSA`8v04 z0wCxOK_*zh+`AYIxfNIp#kL35XNq6FvG6D({l~V-lrJTMF797jMbBYMM+1^TOU^|Q#H+tiZwLae<_xO0jy-g+V+J-!cVF+ zU#d@Yv&kwSiM?KvEh;>TU+ucMp0$;Hf@8lAD9OZ4Sd~<<$+R^+7Xhkr1*1w4x6Gyd z;e;E^F|lD7m}C?|z-N0*BF#;}2x;kZ`K7HHAg1N$W*g@Gn27JatQP7ad?#$@mA7mugnXB6Zo!p@KI*l_J!m07>!I>fog zfH3UhIzRi-!@fTe(}d4_BF03Lmx@xk;O_8n_<16aVK!1$6jfrI)W2FGV91qKM7hiT z+@`=-m0;<8KoPs&X_tlpp#f810*4EyZZpwG(G&!$B186D=hl5LR8|+4gR?8MD{d9h zXWHk6^di5@6r+iaR^^c1K7tO!UN0l3NVnmiU(dRNM&6t*aY({c$!u5DZQwv6-aRe} zE5arc6N*W@-3_WBRRhv7Tm&PNZ;`|AvoWT{X1bhK=+OO(V*s{n2E;!i-SbaT2>x0*3{j#*t2+6QJV*41>F5l_uN_ztK3=^53GiTuJQC~4QG@!r<@MS> z6AQd`|K%GB#%2FOYrYGiwH)sUbgH7uRIie|yPIyfMzrmLKHvYO z5za2Znhd^`S?&N2$OcXR;~YAz73t~ls^Ya8k&@~z)_O8d}e%* z4fxYhuaq!bQ;9#^);-S6cl#y%&4vbW6E3q(+T?9o9litTE(_O}U}1`RU^r0+wr->; z{)hjh=u@(fq7~4Tp&~5a*Ws655h#8)PDI8B@dWSKTNXnlkkmB-)P=~w?=}Jl>P}22 z7<()KZ^^1U*sV~z`MUZURS}dxx%^g4rfk|W3%kV=pUBPBLu5Rhg!}KXjIpU}>f3n+g>c(aJcroY`AQS0`7=z&{&t}V`A#evjh8=$T z{!#|2C*$oFE=pEH06$)G&jT95$dIr~9n*{H?)ynMJg_!O%YU~ z5ygh42h@WnU3aYO{g?0XFAyta51?9+LbVO@iB+Qy^@Lb>cHx7i8PLJK7_h+ugP*GH-<^#VX~K4433YtZX1bo%Bm@mV!P%wYMLk6lO{R`e?;TM7MlUi;DWXykp&zC3vknm4$vN#?F5&3wX~4zOScg|zrs+$8ZVzW z%JN~332PssHIk#q@bg@Or>=Td%DG$hfUQOd6#ymCJE%`iSqYRGBFls!;HkXxH^C$5gQ|89x$TSjfzZ20bE=S2Q*V&zGcqr3Q-J27taM`PhBCCB!FKnYSF9*;ZX zJc1{ItPgRH%5kLak;nOHwGYRexN-OFj2Qq#9`{~A1UQclzKI{wke73(cTyP?BUe5h z9(VbbF~(_h^5@_VrRh`V z^wYc6rrjiPGc>V5u^h5~|K6OVQboHkmAxNq0d-r2j z%n=pZh-@~ z=~$USxgc)guJweP>KiIoHs{k)&m z)3~s~8|K96aU=8uS8zh#K2bEtv_Ft|E%U7j_mE5%&}tvny!qWmAuw${AZXJnM*D|1 zgsJ4n3$qHs^Ak`m%TA@CO0)kWa+Ln3e4uoy;igi^1XeX4j9v4cdMtj1 zDki8dRxjtPXKnl*Fx;Unf$<`L)DzFv7X{eZ3&st$qJNRmqP)dj00uI8w;6BL>1JF& ze(qF!DUS{ z&7aJ1H!OFb8`Ipg|KGPRp;&~b*roca|27d!jO6nCgudTupdS8%XHcf+U=C0YewTV< zYvS z%TnPZn5*8)B@aKjMo#(ekBF0kF3$2@50kOojL2mljw*cJeHQAelu9T=c(_t$C{6B z-KqLd%~1!C-x^KZ5&a%??W2;$p6azfQSKPa`mtMQoy#>X#DfgZ>E7f&by}Z9sm$Nw zq0BWUMx)V538&$Gr+?EQ7-5X=*&Qy;=@y|#r(*jfbpMmedi%?84X+OJ!q=_qAbl@K zw?4;oJoFR50y53-ZMSzq}btzA6E1zrl^@pnQ4%UB@%m0AR|2)Wff+KK+Ulp-zA(IJoo{N z0zh2=9i%TH!zZWieM++~_9I$ZMMMuxp(v@p(i&(-3=V# z3h=k%qryvP)Rw!Fn-5(9j4SQ?DM0b}dcc!nu^+(CUasg_MoN91i zcCEkd<7#W6(gkZ3}wXfBr z*BWE7yHfMN{XdsX;h?JfURAZOc(24gdcdp~GUN2mzM+TNAzHMJF;LiN_zZ{aywASR z5nNJ8y(XU}R-Y|YKOb!*gdtp!x`D~zWQQ8X__Urlhr4n`T}L-H^P8%Vh_l#_JK_?~ z^Hq_)ja3-LD^BolozDae`N$%@zy5^0VYH~N+Y6vZG3nwWX?7odz!63e_!_v+!mxZ{ zmy9(yATr)m4;S>J2eG=y8p(wXcKsfsmmVpTbXiJXXRLjjFRjFMY=ObOGfyW6PG$9t zIu=lxLZMqtVI<~-J2f@imEmnjCAN+7r$?8SJpV0_2!!n4fUYpbHcU@TSB5=#;7kV83M4&XNUR@eWUo%V#F$pc;cB2xXCb zKR7*7{(V;2v`^++cCD7qRTSX$6W_AA=K9X%;{Mpbiwf80g#D?)L&;Y=+)f#3NkWFw$R?>T>Os{?+SFc z2vD`Z=k5xoRLwyGevLc|TzoVx5J9fH-!He0k9WH&sWEkLoSZSjfwxkId&Xo3IRflo z?(6b$@DYen6jHkjY4P*aROOf34yI%Q{`527w}OOT`@Q`1qHj^=-wRm*C)<=BcVD#B zO*d2uJh{ejEEV*56EXbv;!1p%yVZ^+>|fG;_2nx{^#zDJG)kvzka{j>2&(qf;g4}h9!8oJb4b1dkMk>Dn5)+deSE*bV!cY|YvW_{ z30c$kL!& z13OnlkzCHDgT|>SJc+&kvECoiC2X9=ougzxO_MZEjFnHH@pY`!3LaWSo_*_b1$JiU z_4Gos<5jIQuN0QbTI}+KpsOfRh2Wy||NmNwQ4nk+L37B6^tjQ%+D zh;_T^{!Kr}cxbR>P;QC*flUSkd2(^;2aysySRUS(J%z1@CG=;=Gg$4r#pgCzlFnzpn7a|aXG$6f%Z=Ro`}2~xn6Srb;*YjTnZ&0A zT}YxOTes8=WsdM?3%l6)XM#R8X3M5*%)_%K*XIe@=hk}a!Kq<6#GLeRv6Fe}t^2mJ z7XiBR_zU|&NKqRI0V?8z>zNR?RuHnnsN+i}_#C1+qx@#ZRcIO2COQi#9b@h0p;yk! zu*S~sSXKob&_>Z#Cvrk+elPYskp5fVUu5Pxw{49(mF#AN(~B)}%~1ZSXNwIQDGzb5 zGd8e9886W-4^VDynN$xiCLM&3W{VxJ){G`-aJiT{3S7;D&V*XgSw2bybK=K4uDp4M z^h?uemh`_O{ao^9ZumMfqzI{09a85jE)i5m%Bl(|QM|1Y*rNJ;Dd1w8p|?WCn)UJ9 z(en=wXOs4ortpP-KGZ_v`{!X&QAXL)k`_4PTY{BB6+(z7VFY0ru0CS@-Q>`oqZ4*F*+bZroFQjB=y ztkgI4ld_s%YJeQ$&3wQmjf0(Rxiq^mgs2Hs2qHoe?U{f%i3%M?bftSnVOoQSiPgRR z>Vv1|f0oL|pdKe8SRTiVR^{{8dPfi-SSGr~W2OU*(GbObHDPlr7bH%t-Ax_Z8X zlJz?4@hDVk@y*|)@}u8qmJP;>j4?q8qm$GoX-*8K=`xEGj=-`R;c)3tw9 zPMzB`EG7L!v&q z@`Ydc(}4x{93y}8RyGFR>J}x!x(b3#C^zv{OjmN|yzK?!EVl!SO3+qFE2sQADmmN=;`f7e~X3})K?>K>X zT=u_**_gN0MQM^kvKg_qS3e`47~Qugr9Rz5+6cCv`$x*-Vidwk@Yy(p-=yK_R{aR- zEiKF4u21ZFj*Y}EA!{8Igfe6~%fSvLVs##(04T9nBZo6jocGMw&On*B`o7oYGH2@P zFbSTpjecnf|CfGPH0X=NFG8NH3QQFF9Bxq{pJf>9g#TM*DHyVnsZ&rd5Qqm$yy8A7 zTUt#Ez&XI$gkYpOGTd-uv>}29YI$?O?aV9?C3GcB_4>|$tA3FY4&OCD`Sq5z$9pQT z5|{XPFM7qC?o?5QM5&>a@6GoTOAPP4)2-_Sc%!_u5n1lx#yX2as6@yys1|c5PqsS;8 z_)5f}JpL!5>!Kg#LK^YFpaz&pyHA6$%SPLQEm_i^JhF77nC(F-mcxz#Xk!QzwZFfE zRpVr6f1|^Vswje@Vq#KrrfM$DZ9bH4v0V238>e%FfDkvQfFyOT8&VLZo)6O_0u5g5 z9=4`sN=Sqt%-iXOUq8Z9)5!F0dA80&|E`0Yx6dB;_3xzA{~PDzkr|0;`R+{6AVF?r zE?}|{*9dBN{eB$cUa-SeODb%`tcg-P4h4dExXk|_crEy-pcD`<_WWx*H~i#LonM+|kZ!&qr~jUFz? zRANA$!odXziXKYwqTS+Pa#&%pl<^0XPF=*}LU6x7yf03(uMAt~@7*7eI2T}=#&Eda z?{ElCyH$>BQNRToYFZv~sND{YW=h4yO0}|(Mw2G_JVZV~dfZKojrC#E5nsx*Z`+(Z za}F_R!`}L8zFQXg@;l^X8CzW5_qmYEvb-x#Nc&$PDRbNT5HwTD)_cGRt0Xt?L3)f3O`AsO1lYZ|u`X>*($3-^) z5{Kh(obCW9K{;R!7TkR}*7U$q1-B}dg={@lZEV%%(XNTG7+zpZA07STNWgU!BSuhu zZ;*(WfA}p-WTIk>*l{u){xB#b#o8&RUak6@TH3sQFAK}~u2$J?syxUFQNm4#d%kN|0wprNGltof*Xi_(SGk#`v-nAPBf0S)gL+%tq>gT zq-!8KcleJA)S3hCWeW>5tJK>ayF>-D*vBN8{=b_I#dv7Ik7z>-gtP74*Mw`J<%8$Z zK3r%39(L&eeNY^@I0yYW2~7?NWc0xT87Y6}q$4o!voVzq5kY}uus%mrZw~Cl1Ycr- zjk#$d*V8nxs;AsQ0tBHzArOUO!f$UsTyJ)^Ud?n;t^FY0?0ktMJ2(NDdm^h|GWS-< zMPP9u#bI9f&~RKgmr}RTfE5qJE{(@$HcJinWC(1^J+zV&C(GW+LQuDpem0e{>5-P( zNp9XyrCj{3UP{@A@S%#5vQSy-hIV)6A!H|c+(1^uQl{5Nb~6@_UNg^)DY8Ei1>*v)x+`c}`c2h-?7WK~2kVo8+m+=U@?K8GC zhz<=xih+%QMO7_Xdcb3~;+p5-nCFVo0KlfwJJZRtit()xe4VfFhoMFNgm96dEjxB2R5glJ;D>s?^Q88Y)@j+O`bJb6kEIf@=FZ@OOYYj zP*&<~92SSX2I%=sHut4fMUu_m57XM}S+4_OhU@95=o zU&0YC+Yk>Dlzd=vbC{p@hoh^~M1#^MS#8Uf|k>#Y+KMu$e zIs|0Xs7`h#ZG*~^-95%Zf~i2_cAp{zZc2_b=nks)uA$X}^%+8o#s1RELbCPHHk?PN z9Z+{0apzb_TT|%ZE|OYpv)B#$*q{|U2Rlnv`AZV?V?bj?V>dv~QM7w7fAk3qJa(I( z%czjeK&QBa=_C<<&qKeFQSg1yOL1{U!eU3rhRlzP)ZtPNy+kt4MKe$x5lP?uuYk?&WBk|wjZJI*@|M-BLGg}a_@xwhwS zvBJLbG29iU;8JW0`6xj#O+hqtl=as}QpwPI?r^on_0_~|seqe`$7rMf5ydX+=?LfO zLM$%;5EfrY7Ka5W{=X)JxQ$a&dqi!$^F|pr+ddHI4I465kmvBJ zOX8`Qi_fHSyGrm-kdM0#z5DHOqZG|R%^Fl+3dC(UDn7^)_KC~y1sl(Sa~nkCG3iYk zO(FQ+zoLq!c(60W;gN({NVB7YAGU`35Gph_wF7&+13Qa>XCL&TPbl`OWNED}JpQVI zaS?+@GhjPgvtq)^!I;r=D^LT1SNepC{1LB9AO;GiTG{A@F9v$sJTM-S65PMl=vjF2 zmdOoWEcK{&lG~Ns%mFWlD@4I7pN-cK~ONbrA^e3am;C^>B?UrZ_;XJ zZ(af&Y_W~78AuogYsz_hcg;&y0{Gr0V)#b5y)tl$spujH=1s2B9e(|IG(W5K&~?v0 zeg(Qf=E_+L`qFHC0Jf*Lp`4fCe7%~>GIkQ`Z`D4~PcrQy+yF`348b#ld9RM2ysg=u z@y;*A?8Sop##=1&`$X#vW&^wZ@=4R@eMKK|b-lXSKk4@OCyL*`)tnTS&iPNSr&$(S ztWE7+Kpxx>c-(Pz>&C$F0-p=il75wZCGt#N)(6?r^JzM366d(Ll751Gl&XE0Z?57l zL?(7lBHul5AwlVy5DU*$Ao|E}JT30;&6rOIr%-fSqqN)8z4PLVmO4R~vj$(xt0T*b z*X-{h9N(?!kPUR^K+xOK%c;PoK=Bi&0`@pyY93fV``$&5ATt0=GIqU2voek+l=RZI zBMdh85TRamf_6^53s@AtZhG!erjQa45d%BB-8?GO|A3C(D~7oyZmeZ!eLMaJTM7-w zz(;xf!z97GOFFS*umD?btrgIG zrlHdS)4uT405xs?1<^FM1Z!U~kqdqLvFi4h9Nf9#6TMo+eX&xPhD@q><5|s8CWGVY zU2>xGh?Sou5q}mcNRv)t`VypG#+CaWRZ>((^?Eg zKg7zID(o%^^{k-u;@1yHr_QU=#`s57o4VP{_T{Rcx@*TjzzPK_3=?+~+R7f)*1-ga zHaFK5uhmAOJ|z?>R_L91r{NjD{-VohVQbWQ-1-vE;KZ{*H*of=8TRki`dE>urEdEE z9y2&UPR=4CU?M?CFGK*Rec&_pZGX%Xj?NQKT;eiUVavitqRYul7Asd+(a0M?YC818 z7K$SS)~58DDTO5C0Crn~l2awbzc(n?O=+nb<~Orwa;$|ipqZGrSQFOlXqlcgWdG;s zXD7W_$u6_0$B*6`GDVc5bCb?EmN@7|yuI_4V_gUd*YapB!Bal)3rSF?=0x~C>kvZj znS5ddm(QzmAS;W@${&Z%n*RoLf)Ky!4x^aAa{$GBmhHtP>Rvl(qS&&Xyq3%VHg%;~ zISa5eW@!jR0HmR?k#@foJe%rCdXNc-vPq$*y(PrPK zEQ=09MNMd>uLo1Bg-4|~Ef!^?Tyq>nP-=Hmfeu?l@Hmr&Qm(kswYAiA_ zu*|=(cOt>Ao7X!Erx150lwFCrkQPVwE4HU2Y-i#*Pb=lw;01Bv{|dBLVpauit|WiN zMlA9IUIzC?SY9$(tb!4`TSvz#{ks)IPP)HsXfDv5!jJQ7k0Ba;of0=Feu<$~1h^DW zQ6QT?rn|mJglNeG6E(K6eN_F0C?S@NL{tA267ZA$=YT*#!`A`%O(MJ?b(C>~(z_c* zD+fx=S|)FMO&<@skhJcs*+rC{!8q!^e5}6!L0#hQO4~P;*gTh~7F%7VKS2_kTUqx( z;i4-@D7=X}Cb1dscCWrtiFl}EbB zBA2hmK2U8M)XAd_Jxe`%@AuxYt()~ccv`WiDQ?E}W{^8j@hd=~i1d5O-O1w5{&?K% z?Ao}q;iK|CVRN-=c9Fe`L=yt1pEH_?J-OWn7BeX}JIvJ%GVlT>oRGybo^GSI+#lh4 z*|HG`dHIOuO@zYw`>9s`i^=~>l}p_iT!vE|ZX$v__g!8Ro`NM>=Z3avV7Ke z?PTRpj_rs9@38v89UT_UV2P}CKqOTdP(C`mPO|}1Met5Oxg;@Pl_hk26cTj`T=VtB zihnQD`7C3h*U$b#z)-zQ3_V__c7)H+X5TUMh9|O#^IwJk`w;uHL6+pN4S=arH8Tml@X7u?aDxlrzSWM9XpC=%-o!Y z0>KK;;o z8<}rBfU12P+T;8inXBL6)0yE;zONMV56g`$wwX>*?QDhpx#lCWEaB_5YeA8`)rrM z`f&36_m=K|{!>xZk>fAux5UCt8NlLFC~)1s{DOa2qcRifa6LPx5gMmU05S?w{}~>&~>qWred({c>-Kt zcabRXo9w~3Y?~RZz|NcTGEg;gMsVuJL|+-{|1)E2!4SZxw2|57Gn16Bx%0Bfa0Iwb zhsrOxCa>%W?a=&$iR3SSc9MPV&$n2cBa%1XMkGLE8r*Mn1fLn$i$yERXjPQH2AA%| zC_>*5Vox|oYu`yQ=Eb#Dl>#Pe->fMak0M>_k{1*VnTVrz7_JgA%xgCIVN@{#ER6ud zwYvRGrpgGvrzWKzk~2u%k$(Qki%ym+C56dWC_?O2iLuue15Hn5KN6`4b~ZA3>1R_H z=a(i}-qKfbiiCZPSH?0HuFnDDL=q1y#fP}iKf(6}$M|dtxlhshTVvP>l?S>NgiD2c znsTvW<9!n}m^MSbd0njqtMPL{pwr06}GaX?ojxp?#pHE9MS0N&Xfz=w${m6&JRX3O6+gfnmuM@cEkXE zgBfku&+b}>2d4S`pILeWDWmQc7xsDPg%^y)<+?$Id z&OK$v7OK9a4b#wn+{b0Ry>eQ2>oZ8L%q`VIoyNjfRaNhC-GKbURT60nfO4{vJA~kc zS6w?D1J)lT9|6E}cQcLVSp4I10TSW@O<8G{$cQCqnMhVZ*l5>=RBo-24m~4SHDgF6 zBR=<_O_tsz>0O!F29&J=N-Z&Eiz}tQ3xt;d{1`x^Zc*KI!EW-9#%{r!QPr&>lh>_8 z)jr*&sY`7p5|@AKepOZfckWWBt{jhEEv?(|wwTabLvX?sJ?65n6RVWV`&67DW=?DZ zj&+sLgl`pkFk7TjTr}=8;%Rw{?5odDzeQE=S7r2D3200&6g5d`bdI8%B<{jgJaf#_t0vG8Ko^ z24w6-S|pA0ljcPCYhb@>wbz$HB2oOQIpB(gBdHvw>><5)qj$CHQrb*m?cgQ9w!*Ah z91mBmb+oX;AJWLk*T}hc8j(fchU%-pfRb7IIB~kfp+`nspC^79BNnldS-P4TOoRC| zU|$!cDp&ao!ZLI@_F6eT@ys@DGFAovb|T0U`++Mx*yIxh5-N-fJ%GFM)UOzvtr1!+ zLD#5`AnA_l@Tkg8s8$IW?qOB^2k6LV59@)em228NB-Q((Bq(!)On<${-C!1>U5f~5 z5N@=>v+r55M--ZDd>d&Xefby=o_2Rcc*3(z>goA@3)A8Q&-@Xy$dP-jTBtqd4|n2L ztUeZqp$zpO{Uz_Ldjmfxv;YFB#F(i7SjP|BV!qCIQ#9YkF&^X!D{UH_hy%Rsy}ry} zrf+|H_QdVglOjgOB6BHab{t4pxp~+c+mX()a03d*Fwe+~M)L!AUf)b#W-R*V?Dq1< z$66!^WDJwA#yMR{4Hm`4V69g0OP}1d?VL*KE*qT;$!?JIoLV_>@MGAeYsG>MICh3~ z9+Thn)s&zU!>EUrahjo$4}qN?w2OL~sh>k@!i*MLfdiADd~M9qr;Unhz=9dDxP@9{ zUY;I3!!Qi5jmd~@yAw~D)MOxJ7zpWErp(d-9wj*>iUBn#sL9VtD1Re9+9;@#xby^% zYc3sDUnDF}4OQ6pbr2ojaB$f{cAa^G+G{hCHSHOjh3XNGb0l1?al6<_wiRAYPEr1@ z6-3XyV+OJ z6iIDPIO(<*}o=b zvq+`?r=Ho_1ehp=>OT%EH$0r(IjVrLbmkI)8KqW^no|1m%SMFD5Z-2P3Gf@^z9EYP$3c|`|6X$3jFO>mU87C z)NeN66f*~V0IEmAXs3B(pvfKmDVClc_)jjW7txcZVV^n$^2fkJ=rDg?W@vGih-fK& zN#!QD)qrC!B~UrS9gVlrmg#Pj5bz@9XOuIw7Bh?69mohdmRxpPtQX>j} zA-gZk)i1QxtC-4dE!E%9Gwt&sUUydSTccjyEL01q?r5}}%b9(&(eSNxwsu;=;QhE2 zK#1rqq}OZroP2t() zQr-DSr=*phyp*=6f*9(!tOl8flp1~z2J!Lkp$2dMM`WToj8D6a&wNaNnwRJ{Q=~~& zm*?_BDnm0_RaznA=Ym&Yao5ik)<$@K&?cxf2$8zMROdog<{(=L(|2~WF5T_d!X!xF zF4d9-U)rfl#Ys3%WwVL=sD!!v!|&5eb6P6iC7pAB!Tf0(nYqq)ay+v_y}jKx;XmhF zvrOi-R5A>bIWb7^-6c@MqVZno{6F1HNt_9)1}L$O<=+^tJz=8bQ2&rzq{=23dsJOF zc`Cs=5X`*Oa56>keEO?Cr;az>y&9g?J^JbmxBMG|s}--;GYPnn|J;;E9EXmwb%h~! zeTABlEVBN{@N|bd%4y&diyU;f-_O9#()vCWB;U<&{ngZ5U8`HsZ*)V-`4D7F^3}Ut zWN6rLJK=GJ#ZpZ+(|r)AN(ZUr_?oD^nAHq&O~3Kz`Xh~LvuPmY)LN5J)>oIF#BF`9%M5g;fyyaP89&=?Z&&60a9i(Q%1$J(@=fvH z|HsjJh9&v_|661Tipp{?K-_!g78LhFQ!`V;y-m%^%K8HC8E(xHt}?Syv(mB>+#^#n zGqb``X=#})TYUcf{!ch~zymlAuKT{O_x*aE=PTs-{cPm6pjnK8DN`gXr#rQ~|MQAV zUVFs}9A}MQExao=KnVR7;QGJ~r*o#M{bNzvhZnQbqSsc$SQ5)u9*h1*2vp>(%Duy> zB>Gf`x?Rtz&H5sCSNH<0srI3q^8FQiq=B+z3i5v%19r!)4NDl$hkWJwOUG`@4avFt z4KHB#*Zc=w`pI4Q`kKc^EU`Y>@&xAE5lo5&NDi}^B%mT^N$aEln015tR}pQEI`Mi8#c5fW6~-`mrS>X z>D$Y?ALJkH6coX!{#!4EjMOvdUNchY28R2Q7pMHwD;_0OI{mr7R6ZUVYM%L@sK{Ap zrV{aun%#Y&jgB0cz2&&XN>@puspWc-Ox3D|TXL4utRQpmIWnFUwv_$hd~{|prJ$f| z+av!x3zGMJHYyzwNrl7`xmeuIlZsWf?gg2q-iGPj!J`vzzcZYgSo(ce6*s%#h*0Zc zH>Jv3n2SbwWkVNKi`&)?TV!?IK2t1hQ`{?9{PVWxtqkd_WwHHdk7^wBdC`v3BKSyg z?tdlr7zit~c+2-(2@ispu7SMU&)tq3up1fuCaz8#Vf&i2NiwdUZ0Rpf@gGV#*ejr_ z@8FE~&>(6%OkE>aTzF6>{_Ky@(Da(@UEjN&4ypozeO2*VF^l&mspq#HJ}@>4v@c;JtvPq^bt$m8QaGENt20Z#9dzHss#&qe@QcIIO`_Pg zb6{s&vG{>vEkrjJVPH&UOZJ{PI{OCd!S|_m2M2gn&;CM1Q`$pHP8zO)VYJ$3*-;KQB6rmW;PtWhO3u5^ z=UH5hzh$1Lsh3gnw6D4Epp5Qy&{sq}?&l@_( zAC2=j7E}&k+&v#uA1%oL-(uAnl>KNuz2A##xsTtjr~$HGaZs1_whuX=uiBPJx;b9E zgtj%CS+56q)qpIyS)SZ8c36L;`X6zDy9nn$TpfVD9$kil$r;Zrg;wjPv-We+<`)-T za-GceA>lQ8Je@&3ouw|b^h}XwLVJclC4p!kz4q6mp}AzsjBM$QV(9|xs&6_*UnUrnud=UZLtRa1V8n9UOg>r6fNdasrC zTm%CMnUu1k4bnLL^1MVsMAulwn~R3Q<1F2SIqr2jk;|Q>Mv2Sv%eNw@T#VFC*>-$i z>jUtn0v_@^vBb%UEuYJtk98s^joY8HNL4KRClO9(zJ1KB5ufJ`{QBzlMus#t>}=ig zJun0I)j@meM(~3w7GSWdGx!{d5eEI)7?ALGc(oGfvXc>Nz*q6N3F$I3Fl?TI~&zs66RIYeGSIF47 zU467-dIWa#t7p%|(Z+OCP1yIa9=reh#deVLP-1dqMP)KT*py4Pw{eqE8bYZ7R0xe)_0hl6&|Cd7EUZkm*;EDA>uF$Sd;4mmH+>tBswm z$e*kUa8jEqGD8&@3=Q9PH~95-%uV)TL@DHdG2ePbWWP7jF}{Ch%fWhLc2D7%v(sO9 zZ`}v27s|!9(pTk9!C*3e6;zlEm04Q zmg@of&9WP+uVfwEQN?=5E=O(ePLzXmHvsLBK+Ij97u2T-%3}de=)AboZ^a^UBG?7a z^~6LsRDwoz(27s~-CaOPM$<5X>sP}eGtfWQ$Pahl<`1U}A{A=jLV?m<2>H%z86sOW ziXtdC&yN4Slxw||e87;>X&fH|e4Vpou#%M^n~Hcb{()uRzN>5|^*dW{ZC2JfZOwvo z%X9Wdxx#ijtjIjG*<30=@T?IB&^ZHnIO-xzk5952^d#`%jh(}-C z_;&AmpXbSLd-1BJAxB+Uv-QD(`Oo-jsPayGx;=InmouxrAxana6X0~@WOo$x37@qB za8UXx+Ghj30=@t*-Qeb0mknp(k!+W1fp#__E(En|d>(mYEK5Zo@_()YcBm4+Ijz4p zX|k`>oh(08oYn5qJ{>T1XOPDk?C#VOe`iERv3cdYHA+?V!^~fw!`h4RGbGx&9x>f?@=9LCJwc#HATKqI?W4o>qCp*Qyw52J>!o7@1_g`aD%Rzt-0-3oQY(%Ozr8pN z#jEF^%1E8BWc=byg}%O#w%H%Gwdrg5^qEWAS=Y~%3+wkB{?5Bx6j@;9kkzq(txEF_ z4jNA98-|*MefSDZN4!=JNK0J?CV4d@)k{_0?C|Gr5|peFL>YzbtBox1R9r)UGRb0b zjU>DjFLvU!0V70yM!JFpl2oIQNPkx^j!y`W{SFL*4_5{Dg4wn!xbaiF_I)d1y0sz9 z%;T|ADu(+cF^FSUZvS&t%<=q7CmArUgbty=C0|7HWzfY5nrI>wsFbIw@vDZ%9mypCySm?*2A%ie5uy{A>Q$ zd25>YygS;uP#Q!iVi$&evy%*q;x2w)*OmWudsY=F+g?11Z}1j-W}&4t zTC<#;k%BWD28czoj>s)gkKk{xO(KY;aU3RIG8>R$OI2y9a?4YL7dX98MByM3>ZF)Y z&hBgI%Jg4^kD9Swfs?&kK0=r8_c(cNCLY+zn8^EHRZ<*K=2M>j{yrWi=$wfse<^x@ z)Y+TV;75J!%s_zhT+;(kB!hpOKg)~y${Qs9y#zd`@fQIOm<&rR=%hIL0S@1|2G^wwxD2jRo8e?(#OSd?B zS?lUcJw;l#Uet+-j1V0vD=mk$Q_2GJH4p_1ZUk**%%j zOLSzeQ9VF3INiSc1@*|w8%-kQ6^8VgBL;d4#AMEOV(Q~xM^i06QI;E3&W$v*PQhG{ zC*P9~|AVm@T@HN{@OvOV`|y?THLwRwPklZO-hX}Wnv*VD>IBZE6gr{JQ{iZtKSyX6 z;H=mPGd3CukeDWa9Tv7WkS42;y@jU}LDmoO9DmYg=4)?G z&tyMg)D{Rcg2=Bf6dJG}E4a<92BBIH&%#y_ua|6Sn8W+h^C@nJ)2Hq+MeaLu7R-a) zV`oFs5EWl4sN`DMs+$^F@L`ah8kPagpb4o<2n7iU5!_+P5MgIO*aDGHjPl!IPR)Ac znkmWE(_dXB<+0r-Mom?IfL3p#H1IjA|yqYM3SSiT1V9tQ(@0wO5-Y_dY3gD{wvEdS3+ ze%x=x-bGw^v>;OkkZUju^${n}T|hYp{F5&%9H~KZgAfD&s&f!2oh`Ow?~PjZ#;XYI z49)r#-o+}E{*x{R%k(p+zzuHh&oIH$JWTNBh-V7J<5}SYt{c_&uv!`?tX}0fhBO#7 z7|}(6^&*7piLilSe(mJq+acoslw8`gt`pBzdf9RdwGAFay3n<;Z;nS~GPB#+;>?+9 z_qDms+_cU7>hWnAzsAO4F;#+WZNPHvE_^O1WXCxFqpuWUoF1W(7vTU@jAX}$NPc|F z`Ka>l;O>ysh9G`!*=*^e(Ev~<4s5efst>o%78pusAjuEYWdr6{79Jyh`5PC|rLE*N zwgi3xNG(BiK;HQ6U(gG1uL}qg;M2^fT~EMFbs6iZUZPl~vEaN_`DUxBYk4JEcBvh_Q@0X1r9nbkpZJg7E*W3pnO%jQ$gMGx2}P1iSW{ZY#`iVuYjc z6giQ==gW015j-GMUU@Ou@5p2rnGqY*BR^~}Awt2>3uUJM>C+#tt_Xuv{`)5Gvukg& zlxa<|PgH%&L|yg6w5dxs+^GQH7pPT2)Rw;{sq}&ubY2|U&c2_4IGSunpl~Wm--hPB zdj79s$$_J)&k*inMhvQOf&{<|6xasQ?-@;Onv}Jh88Yvo^pGwGde=2Vr@9U)oiD#>@F<~`bNOhmrveuVRdo;H;kDWezFk{O{naF9s{?3RD z)QTc?w8eGAO7ir+F|LsutiRbAR@j@%4}Gc}GON#wjvTT2#(9c~PWWfn1ifrV2hHD_B z>V==ULn>?@d@3L5R&Y9^d)rHhvw?z+C5Jh(fC3od*Ky|4fwi<6FCQpy9cxD>6 zlCXjyp^J2;4cI1vt=CDHkuJVZ`czLuZ$*4~V1ibynNay{Afr%RmlkLGY$i-2A8VCg zO615MaE?`hex&Pud@+{rP~VrEx$`zIw!z-Ke#ne_F>8CsSlgZ_t370h$Rr$wuFO1> zp`f}?)E0F4;C7~_6CohhdW|R#0T!4Bt!P|9;qf6cO%AoC+BC0b? zQo~F2D)_h6*U^`@%WTD-@)BjwYr=k~miLLeC|ikLs6d;0eEecXr2%SMS!8=~_R!nb z!pN9^z0#f#ha#I!Ffd!_zI5)QxQ&x<(d!G>G6>z%@&$*tg%o?o8khcUu0RAL9~UP( zC;;G{G)RU1%$+XZ+rdy!D7@|)bEd2Oq=-^`cDbE~3sUAjvyiX^7=U(%jEgL|>Qwl> zs8V$#1o7{zJE7@K{J{S4AiIbl17R8wQbSyNJqsS@T^0RC)I80W$Bbc{Nh+_B{P-2q-eJt&?wsEK(7kV*p(`bugC^A$gK58zTSPUpwW)NOHH=Gyc5$G7@Hsd^}j zNn{vf%M5ECzkkQ+DEJiiC?tjGV7noBy(II-hY#jdQ~jjun_}xX@1?F?E#i}VgRZhu z=lyfBa#8{CfYWTrU4NM&X;Q3(vRD3q2|`dn8wG?H5i?)YM}`Vvsg+e93}=D z^}tYh_quMSRzJN?hmKw+v^EJ$0Dnl4Rpr4avocf3^!`c5-$tkibw0|c z2TS*e+WarD9r97!?q%zYXqv-TD`f-wAMev$)GWHERhrVbRIu7w_^jUJ5es^^EvOQR<4Kus%(7d)<*XZed6w3^ z$=LC%=zM?j>iWhfSOo%o;F(r;`LWofgZ(?GcifMLFAoXY&@UuJOHk;0-Un>t&emU!bqh-2*d;M9=fBbhiaDNcLlyLR+D1`lF4)?_bGt@_Fy%L5~88 zMrs~|*;5yHr*6<-HwPgUT2|d)>61v`Pyq$Xz1)KX#i9*)h3R*T+zP@o+?}=-PBS5q zuMXMmKx0E6I=}Ef%Ap`{x6*S}33d@IB6MKY*QK)7+fOu$hlk}%6RYc?E zq1O7KA=xK7*n0-tUp$UJVsKbQ!K8wY?|pgCp?rrW^|9}eO<3UlS0;^Do3!D!Ocd&8Jd_g^<@GEfb zaNbK0@X(>ta=RLGX(XMGqUu+3_&8%gjHN^x`G3}|L^K;G&p|WMcxO*LJVRUK>pDEf z;*L$}w3P8BrAMM?FAbis6y}~U3)3~2c-N=Y9bf%vd*)7D-Pd>H2w%FnimlZc*~yG_ zef)yZQ_I043&cOz{#!pM?*tU_2wv~xe~z^~NCEz9JarcB;Bao&`k--f(uU`qpO3+R zA>0_0m08Is5zb5Qg|yQ|>IH-`{h|OejGnf?^Yj!V)Gk{@#x!jo5k}5OYxwu38-&^t z&ztf3hsK_aGUZ8v_twWsF1c2!d#^3*y`8G8*GyS6jxBraQfKC{*E{k4vPZSm>7I?N z2j@L&4TF0kG|&jTid}`7fr(R&ta-vL%X{dfq*3&IAK-_`DlvXBi`-$Q1 zd8s4G0#;cF0kk<{a1j+7!M2l)xL(Sign4kD%91<~3!YljrEmp}onC}V0>NI~zkz1w1riKxfC}al$|%iHLbJ9V zOod6|OkfL^d?t085>Wa2*9Q#qRWoUZ`B;A@3Z{D9-3X@nG-Ay~yPPUG$#2dxW(@CJ zg*}$=Ut&R}sR6hgY4|x3P$Ebj2c%PoY!HT^lGpEU@~Yygr*+#Vp~QI)Nbupgf%7l; zXszazRR&gST&WK!J5gR=Fd55Na;tnO^Tcm$lu^si6d+~X+cDW_&ptr5Oi~v+N8!vY zpi`f-%Mmf+#)#B>e*NKx)KNz1lVGMSNmF_=nxXrgPh|nNTPEtpi3Q1d+!^ zXDz=b7*77Uo$zKJ8ZwN^AVmz@OC8oCBS@&G%=*-NjrTRL($}w7mo(H0z0Tg9i>yzX zA-!ujRb=E;@4gl5SR1_*JSr8MCle)oGy|Y2ZA|-OUShOD8xn0A)4CvHuo!c*SXKam z%~RK|2@}>h)4G=b8@}~9AJ>TJ8U%`yH;9V@5eOnFq=K>|qG5HN$wS*>z6^hV{fGjMSG>}?0s>Bl4?70I*E|KJA047HP;e8wv+84uMc;?oxJ#nk3JtSR*Cr1~xG z@<|=rQ$DV0kLnF4Ri}Cnx*E?Bdh^T<(B@t3E@A#n7&WY*zAG2x;qoO)%<%c5MYhIs zQdB+#SJaq0I1i5+B(g+6d$>zp5B^j9yE`NWX8O2DobdhjtDRitijTdmQWMibSPVGP zV^Y>&RomL`c3vSu!}E)TuXYOTvH;ts^4?@m5-n49i3$ncqD!UGuIpBWio|bv%Fgr{ zHS)ueLo5-CNfXh5T~5}+cA%|1M?5Y$l;41_i-aG%Na8K%qZ!iVP}NLndZ?X2Wj}6E zKeJ{6E@+ruCl~LjoR{n1j3{71ETW7`UdF7N_Orv1%D$9*GHF%pcOEsH4izhJu#fyg zU3K_D7mwkOizb&GjM8yM^}p6il9puBR}gTUJ262VzvnC4Hbw@C1qhb+<;pwp$FgOoLzRDkR{18pkVwkLd+oR_e!plUkw9snVY2!Wv6;m?aH`7rTIjxr@yA4=};Od zX;IhHff({(xSy_^HR0mkPTOU6F_t}e6RzXRuRff2@*=F1q;U$-D5jdaG~cmf5I~2B zy&aGu>z&cgTYynm)^z!6KF7zM#)l7i7lvS3{z1tqu6{P(^M(C1o3dP0*{Hg{RyFn8 z6JAMn7*BYcdfn!*SHy=$tz?dd*TgWkrVOS`iG!%bND8wY7UVanLj10Q|TvXEp$33lms(sn$$KD}P_N<|DWdPjcF%at|g z5kEt8ikfDM8JzSk3Wh85MANtZ@6HM|8V!;}Qz)5ovn>!)bq~?7_Cbgy6@YbS!ydb< zmRu%+Z}QQiM=i@Q$ zqSw-6=8Fq9KTY z;c{+}so!&m^P6Es5g4aQJs3OPbmCNf&u1=W1rD(mBgP#vrc??* zFNeQc;FFTvJoweqNk6fZ5AyTo;)&)*?f8zYpGXGc1Dc>gWW(HRR{mFw$PzIkxvlZG zuY4NNSW8K|)qvBxVs1aQ=Ti2LzdtGRU~MY)zUa69KD zmx*<6x%e#LP-5o6I!vj7SVXJrzW-m30ZlEj6l&Gt9!tn^pL8L*LRmzAoj1Z?7x0hk z-qG0lucwIn3QLNQ@8oRTfrTk_tUjRc_uEo*BO*xAZ|`OG-#~mL%SAxt6U@ktxio$U z%XtXlDh`|ccwDs>gh2~(1!l3e=oQDiIVb(-# z0Z5oPwKg*hJ@2%>pT80G=~R}}u$8;(3hXqffP+vOUUq>Ls^G zJ3DP}fdW5T<9k$*djh3Zmqk~&Q8|e+tpJ7DCMkb8v=Qh zaN`Z(xxmi?=$)JLp}B@T*D*uLh$r9EoO3WhV~gQg>6WB-qYewIU9MXuQ6L~}ReBaD z(+k}nc9t3@DH1+nH*x$oi^gt>#_@_v)Ppr1sd9^2M;+yYa z95En_xE~a5BA;xs==e&N3B{6$RvO6t^_RT99aur(YO4U0MNKUr2s0yKMMO6x2aBLu*hP2L^}F zd%`k5frAFYzASL-6`-!b+5eA;6m%T~-Qa-qX+EEBJbO5+`+5HC4-zJ)h;Tz!lwW4t z9z5q8woP&MKN+^2IwJZ;|8kncPEPZo3VguH0;C~ZUmIX_aS*brD}+c9I?4Kc&rV3Q z9WubOzB9NxNnBoJiS}WoC7%TKYGN+Xr3PK4AI2#z#wZEci+y@Wj+ztr;`mLh*xtEi z&IUB6DJtm!JPHlZUHg!faFh2+ez@9w54$BGd%UHmxBP%})GbOk9|9~F?Qv_3Bu|7q z{~f9rWiL}t53Zo^WrWHs7@!MxqR&G_BeZm)+(d`Nt){7WwFjNQeN3&N__vw4sy*@2 zbhm8dnj=V;C`NLG=i=P1A}wO=IzI~Fn2EkH2iE4j`u0~AI^^=Xd;-MLW-I=~1!xD$ z;Uf@A1NAjiRhy`wCKj{;uj(9ewLN+_5I8=7{R?<=?eZ_I!39z zNfb**-qCs;b1WzDiNwz6H;avLlFE5z8xqet?1>xt^OF)%p@@L2s+w^E7=R?aHW zjG)y5M|3okiE=5W3H%H45tdx6?aZ<18m;-T&Mk8z?&`LjusDm}Vd9lF0R4s6UMxj$2pnyZgas-6ynDY%MKMlLO15pm(F#ak?NH{`s z4<-TwY5Wzjxx6=3KLc7$9i`X9R{hA|6MneFcWzmhvlUiIiaB05$Ec!`C-QuK#MCqVE>5MkV#>|j zDs$Z`lYx!QgbB$r!#?0;f1oZ4s81Z#ehXUi#Y%U8df#u2#~u63+b{XY9$!@R<5jho z;Ze{-`fhP4$M6*Ka)Vd1qQ@Q7BR;6p+71bi(+GZ7T-_d2)SRtAbWK1#Hw^dS9nQyU^%0F)3{QaAL z)?xF{In72Ul&i0z2uEO~#PN49Y^ZD+F6gFt&L8Zx1 zvwHT)3r#Z1hh^R!?9JQx-K!jZ9-#XdD#n0VEwJvYb5%-Ns?~!qNBu{8ALG6i3I{GA zcEg(vbUEs}0LAI$<55K6XuH~4g!_+tn|b8l3*?uo6+GuO!Qg!d;&mcQ2w8G1>KyqI zO$2(fO0_A=>oR%R=Tq!|u=w&Hm-2*0D&{E_HTm8}r%~CgjHD5iL;FoL7G*pC=2CiD zU%{!Q{DbZzm^z7*zns2~g>EfEl>$!x%voz*;U&~GFOG}>`Mo}>vSaLZ3{ zMdG+37YnYs*7{n?iHxtGXc86M;KFT?Pgc+hOp@%6PXDtw*$SL&D_we%i(D3cV?(Gk zBqZhiOp=beE4O<1>*dph24h0VyG_&k~z=Tu>*Okw9~c~dvV z?S1Tilk99|@GF4g8cAXNcKyrtpY?Qk7F#CbvQ#6P?H1E@-+i*&Op) z@Z?LDpgOU%idGu8r=lYSy5#cm#=Dw!8sl?#|Hc#|Y|(LaryM?B zi`cMJMuoZewDLW0xc>tl*ursT9iuR9f#cdjst3lLXR?mZf^5j!`4ZV~g?+Jp++j(T z@w(irm9qsmm&d@az!HIp?By|Wm4dcsl5-qz@aqt%V5pFVuGAtU(@qIF-2oT2gw8xY8`WnZbv#E)jDCaFiRTyu@t83UU-V~k}Ut>{K4U%AH(U)DWxQMmA?@Q~D0AEFp zysyxQ7!%tYqQMV)uJ~yuG&qf)wSiPzaT}|8-!{NH)5wB206Xp_G)0fpQ_d{iDRQBK zgRnqHqVThT!w(yUZ{iO_k>GaH%BuX%i3FwB7B}(}{Gd|FAJ3ctCN!DUy%u4gkuH+2L}Toda=$Ymit(u3p5dD>pL^t zg-1Z?JUUuge6N*m-9l}wjLt!`2>ILW(t+j zh%7mua+D$OA&4Z!IUsWR)$#~hai;vf^|hDJ0E&}G6!-`~t9bd@7hx;6{MYlOYH%fc z&!XZ~Z+8w!{Z{{Xj`V_|Iw(Rt{^J}Sy!@tR5E@nydX*^LNE2QXkAEnN?eHai10kDn zIZ#njTFf|;oGYe+&r(O??eak?uD&thI8w2NDatn{qJ^m{r(z+K8tF(P$RT}RbVoRq zW#K!VqD5197-h&3I=Ik!bWm#1c!Da~Qj$a5``axut?4hS}V^X&Pm1 zKX(lbdWK`ppL60P00M_&9<|un2X&7~hh}v<$Q;QdIm#rav9qOv)7Xx3$LhU9<)iD7 zV|vNbx26m>$>?IE8RwSiyvO@?x%gs4_qa<*SHwYg2KPDieBu7jH+b_;W9!A{d(z71 z?bkNPvBmnR4SeQ8O}LAmWGdPVjSPE>&VpC8;Yb_JQ`JY${Ax4%kOvgE`7?Zn_vGUD z&9Gv#h=O%7tKF`rVz!TVGQ|wXD>C8vGt70k-V@`e(?%Tar|t$E%u_c5rle7k9vieS zBAfIV=FCYm)m_ruMP6kgVdBIblB(zLg zse^)_Z<~`m(x==NXH6(`)jdtlbCihfog>S5_m)*iiH5$#*+2U*jPW6Wv%wVU(i_M& z$<|+B>5c#;YQiyylkKrgk>a6^@ah}jJ zZLk4X7AiEZ8ulqE9@r0awiVOZDBM3sXmzoc)wqXk6*9l;V!$A@^<+~CNTh#A)-?oi zp=m_DKTqbe#qhOq&x>(;nHTETTA%){|1g_>`PiSD@ENoBMeFY74~WN`e`ZO>ZMGEY zmgnd_+%|;EvRU-2axpdCB(R)*DG1%FD?z^J>VhO=e0b8&uYm%xHK1+6y@ta?I4N7( zdjpX*IFH80Ao8gjxJeGw$;`(xrZP)er)feca*r*#Og=2RISxV7EerNRhq4fYf@6N! z0(NX)AALV$&8)6U0@l~L%k^-Vp=4JVI9v-mefS+ie-hfMTYS|m2ozOa+|;I5M0XDq zI9_$bj4#S5m45U|Vq~J12voS{E@Z4PD8-~jU^aov|o|eM<{N zM7bSVp1pHNS*N-3FZ+UmFsW6lmc-vj^M<6musM(vx@ZDrNM>1odI+pwj!U*m4*)7|4LUVWe|eG;;CqqJ zLomG9R1}RZka~=8G&<8=7_2=cHSDZma1v1Ddixt(0zm|r>Px7o^K%t}oU4mqVk?;r z^^K9Z9wCj4oe^h-|7VUWg#S6QI17zXpM%fOlb`m-nZ%>IN$Zh;RjK`+Vg?;ItH28{^m>riJJU5v`lE<;I= zgY1v+H^FykR;@{=re3~Yj8giU*P8mb%XpKZV_wc$R_#!}?U{5vu5pu0cxW{Fqcu07 z)%eH@-`IRo*Y(PONb>)Z$y18YoDs}+!0UUoY|}itNMa07A9w|#UC$PkU7OWol;#-w z7I>?aLCoi=@P?SIMy=3%hV8sLe%Pqtily4eFpx$1L#V2$W?3Mm4+L*#i+u z*PIYW3d&5Pc{i{FK?27x5gll&%~DGI(vs|}JOis{C-IFhmz6$uHJaC#!lR3nr8dlR z${GO0G07Njd}4)u7TxBkdz{Z;a;97y@hN`T1m;X(T&?NJ;(_&rz0HIL+OVJi?N+)DyMc_HIFPp$1~2UZ zjV)nxRB>)#K~27{P)>DWa@Ms@mgc$0njqg<#;}by77h7A z${ldQ^@M8&l1J$}3E_Fc+Ytd>wNqU*5T7gzHGN7yaE~h}1!W5n%jt{%huqk05q-$B zPLi7jcs=yEd++&!Tj!16n@`dYC|~+2-*Wi9MZ*Rt?SR26Pk$X$;Qe82hhwA9Nrv@y zig?E6EmKE$v(5LpC+9i8F2OI65w@Eg$?@HgUmdubMD==E{obobV}uW~lkMAdP0S-( zLuG{)p^g!~rRt=7!rDOc`=nOxiM@g2R&l}3>Q)44`VB{^E73cb+pZUne>fE2LzT#) zW?SUNVyN>D7MmdP27niQW(-wB! zz)O|pk-I9d$EPqmWsS$1aSCCD1d$`GpOU0JO^{64wd>{)e}mfAZYZaNL$sjhNAB%E zpSeQ~FHLEdIjkVVF!?WBHz0gW`*=LZ>`RyuI`PNcc)+KFmvyguJ`6WO%RDZk-j;U0 z4h<*-h*N36mVSEQ$iE%=j5;x!sJpzMPyTzcYmb@rhA}b6=8&{W_OWVm^5KIf<+}>2 z0L6N;;(ChWj)7_Qu41^6>FY{Z%^>~Ps)u0*B7z#XQP~<)Z?w_o4yBweu5-d(SG_MLGQDkvz7vtC$^Yk+gz(yDY<{xlhX%J#x=)o zBDar-n4pNgqru0x@CtkU+@Q!T*LrdgK8c9TpI5(6gm0qZXrrg#_Ohd(Yu*VY7`=@KFx zg`R~YNlqt-M1Ecn4D#v15LpK;htGycg0z^25=ueBXdrVgqr}AFP42m}x#AL&z~w_S zAar2a7lWp^8M9*Fy7C7iHtmQ9{o{g{oRjR^}Amgeo>WF zMAImH({EoCkz-KQAtkat)Y{I%0Pp#J!$U0;e0=wS^d4k50%u^BnnW`*-8?#&T(P4J zA0oo_$4Ht4=p^1#cogNL?xlvS)aQ7%+Pht}ce5Nb|HD3RlAo62h`Mq&#(zzRPo>Qx zf_e-=hQ_)+RPa3kE6%}_+sx`!g!At%@xQaG2ckr`sG_I)#Xio8pURVqmx}nzw4QIZ zrlp=5oAp*05s|$O$AdKroB11R$YF{Am`4OS5hYx(5{0Moi?3j|QZb1V;BqxkOAO{< zE>Q@C$>COAbVAe}LWr`XAC*DHLkneFk@hr8ueWCgU9=fLVj?2L5TOV!BL6#KoD9Gl zYoM(%d$%r7;X@Q3vVe{pDO<}s%rwQ% zpp<$<)6OsqVEdD5f50mw7L6ID?k-g7m&W+}Kvf`qU^XHr+1HnLnm+1XX*(W5WrMGcp8w!dpwRe&qydX z_BPL{1aIKV@P|$3{Y+oo4z6Lg?6Ey8_B=^Go?bD2SRB-%7ECY45q`F&2-xnlxU+XN zW0>HMIB4D-Kao%!ixmDz5haULA=zas<19ray~59?1RVBkEbmn}@W(k?-n&)xr&X(M zNwe#P{|RFIJ&I`7)tv1vG2<%LKSXhcRt=+8>?5~tTi<#BCsq_|{i4NsgCaIJtM-() z0e?)%lg(B?GX|gP5-Ie7ZyLda1(*_4kRMX-Am5D5u`ha#aYTS$)JEMbi}DiyIfOQl zyY6~oPk>6pUQQz19FP*Lh3!tz(@|%hnEQ!!`|kT9Lt;p}y{D0@h!g$=x90DUr{9Q2_3UVv+z*4jcGit>fNlnY(vnfFfOc8YRgGc#E%iB;v%n}yk9r+P zvs3QRtoS!mW9B!Gf%`G(30SFsqS=be8$dE4*0oN+6@1FIm8=wQq{Q3nHWfWJe5^$| z;&i2QsGqPY`hq@64l5Kq3rX2+4eY$F_S|QPsu4qsOdCXwuKAUyqEv>p;ZfyM)kvxL zP?)M^Cs0L=e%bX8@_DPdk}B%5RMF&pucsPyo`X>XU%j&8L`R>BmYh`^&lE4TtSJcU zJM9ua&@KLjO8G>COP;V^{;D=_eClZ{d;lRTciWpY2 zFhyc~Nn;{@FaXJq8r!-QRY3*f-1QNF0+HQRnkdf% zsOxj^@E)t(Zfh3s=&ZO_{k-PCBLe#z-5q&jE9mpNV~3s&&8fJ8a}}2=VZx_O3MC~=vAm))Hwj^3x)#1cUTvuTKK^ncp25STPIc6 zE-@Zu00>L8^n#gI_6#8jY_x9};*byGuDO;kai;G*$d*z~ZO(Z`t$8z>^DkNCz^EwW zS6|_Z+~4GhgzAZPs@Pd)eBETkTr#}!9Dab849A&tT%MXN-kZeeADj!241qLuO<__; zbeAST6YAjhdH$+Xn<8goB2O?G#PC39XK)Cj$a9@pF`{E??-7OTL4DSm+`D;-{CKE`r@r@|ZA#xJbj($)>O4 zIM1K4Q(1dLThy7~QzEBa=5yfl3))L}`bDB*Mn7*0&nF|^FP6Nc2-A)_&}R^pe-LFt zE`6-h^jq*_0Mf< zb=>@USz^yLa?J=h9TK@I)Gv6+`_JVo>QS7sovptM5)p1}P~zLQPZBfrJRnrP<1Y?K zpmboz`NX&Rgg>yij{}teOCoRhO*#Dj+l#0Cz}S=92PQ-$j^=4dL6h5;Kn>N)DA~hy zvZhHb%(BEJLiv_vRTRsfL z>*hLH;pSAFLp4yff!9}qWzOe>gt}gIcUgAdojp*{Rowk0B-}zE^3E|5C%~H`usSqictFR)XeaCuYcXC8*2%T!eIBNQ5Ir(@%^6K6JBTv=KRJz6yZWq$GFo*jHi(_(@O-e(z~ zHnenitvS0RKnWtdDb8DwC4m}$3%Y#eSNGJy8@^YQ5)}4n zHRASd>@#fp5`_0H22@nRJ_n~06QuKwV7VWR^kseLUA1L8hz7C&1y$#!!%(*RgR9s> zF*5*uF~O3X6=yC9T|cjisy1hUuu5cza}}A4EDb8P=7qVj%qbZfh2IriNequLAvJf_ z_>JsgGnw!o!8T3W{shAB6=;!)d-Lp#WkqX@nq|2$4Olm+>f76UBmDV|S4KmBzHPye zKQ1#kyU<(rG327m(aRM_uKp;0Qg-;l&O&L@>B)tj^P^)$fq#GFdVg~h2cZ^g=m1k};#FVN5u*u8moN|BHMr%u1jDdD z+{)ch+&5DNzv6@>2(jy<@?`TbA|wW+q>`xk@UJk5q6L8Vd?x-yUZg{M)>`PyhqI#G zbX9gc0J4<@3Fsx{s{+%7itPyCH8L_&p?uqv}BPvH$Bk) zycEEXFz%+((VsR+X{H0a%bD7Vi+XZXV5Lrqxrl|nvxRtYr?Zt@%IxhcyUf}dYt4OChCOdO!$mVn$GxxjrTf< z&3Uc5;kXl>1N=JZ>qP6Jz;*pIGI6}^YJ>+wH&*% z0&L$Ywt%?j6z7pJxAWGhur@o!`st%u^r%Q`Y>bV{DRF-gYS=AiRN|3-%n07@a|{FS zY5e7zNI6EH$9VR9kIHXU^poR&uptTpP(vJS>t8_{ttUgHk{7~@NrB6R!2o_qK z+|j>muNQ2PPg^+t9q$S^v3|zDWW;&c6UstaJT>$nSyxwsRbK0<5H03vn_qNViL2@2 zOt!C$VVe2SlpoGRCFAo`4spn;NOelLA3?N$`cc)sBjcWQH@cC!x}UTyZnxsjESL>f zKbSWL6la=;-dTk**tr4=@!|wq62y!}PpAbjwg5}8-jR|3<$>&Ti~*f*R6=m8v(WIR zfy_lpq4B)4WHigtpwTP)kl*cFF~$QDD^bIdQRX=z`pjCPu$^uB+19)R%tR())rhv^W& z_n8%|sO9j~`lbT9AZw7OqzUD>ER!ji>a2Y+{RvqAk#nt$VS@Gp*nG}H8)rXKT$6CR zC=cN)Cvx}@)I~?7Mw;;6w+343ey%pMa2L}{Nj03U`cMAUkr^Y%;r4ULikU(gaGttL z)0o?~Io6C)hh(mNb}vc5TI^joU}e8Q&_)(3u!_)mt+h&CYIAOLN?JU^HcQomZ7zLj zIa6bs3lyoA>dr7Ltm+(6a!Rjqtayf%XV;aPd%1kQkd zsN3Vi!#ZB4%WI@H&r3+>@(G=e`jK-u+)}TdNc&G9Qh+YK0<(BAU{YqIu+V^b_Bg3O)}c0w899YWZ)sZKHl|LC+7=y&SXr?+;R=_gjD4 z(igNWUJ(T$h1R0#3p&jRDi-Rn+8q4`K5VB^*?PHhVZd`fecp6|jXe9@m5<{N=u1Qp zW}UO0YV{Ts1#lP~02HtoCaAr$)-f+<=uf^q)>k@s@$47Q^^)g(NFO#xe1r%MVeuct zxe59K%yG7+;K8G_LkCl%v!F#H&i4A3^BO~cZ&I5nP3rD>jsG>9=(KnVd3j`oLKMD< z=M@Ezk3S3;Y!5BTD>F1x(kohWV@|o=a8x=Ll{Y1i(E$-A`o-^UTS)%UW2h)rKaNfo zLnY43XC^4oy8@zJphVx8A2BYUlOZaI{v&SI0ZJ;rd|Pz* zU=Gw}6Wtn|dVqrTmB{&%cSnvNypk-(T(&yA*x?z?2*rVA#`Bs+%~CfPsjB(r~^^4>l0TAzD~uN~2HS11V|Tg3L`jqBM{=yK(osQZuYn z21mRtB^%~<9oS#V@wn$Fe$BB;D!v~p_uII(}Pg-?PUAo;J_lN)v@3Guq=P`_R^(PBgA;A`S%)`IZp%A1^JwW zzJc9F=h8#UNy0`C*0Lv!!Dl0$W?hE{t`P&B;Xbvru{gPXqp{Ds<}G7o)&5txn>lH8 zcJUu- z(Vuz|D(PQ7DgPc7tZ;}o1}HosbG_xJa5q(^^WYVie#AZMC3*qkx+sQSAab2gs+|vG zZc=+dN1L76@Q$nXjZ5wk{MO$gHLjD@3rfL3a!eq{QTL8_@O#@ZQ`nbAOOaY=;zoj(@U0hHHm>t(__2_QJ7tpN{v@=Eur7mP$z zugJfBnoqxrQUwaDs={TS&P%@#eXU`ejmm)Id+$z)NCA4CpjpEl;_ z!)r>WcZ)fro+jozCFBXQy26rkw(l8!gaCWP6las^t);b}*Wocwk?o}xcx|cp7Pvqy z{eccho>R9OAl21TwOmuBY8ZRM3k&X3>3)3DmN zXZGI#3KpoX;#Ik{WW2fo5Z2b_zpYa4+AlFkHGpcbY)~(b9sIpq4|+wyD>k6;wumTE z!>Uo`TAQ^ODk7?8SH`H)BLJxq8bZ6bS}IxBx_9drw;eOCRjZRZgJ~Vm(P>ppnP=!p zGkM7)pyRY6V|&OxcQunt!M&hl3`;<{i|a9_(b zOvqlc6N+YP1R2+yPbhs(Of}4?32j#}HRGT8Eg{n{E#6*^OXz+Ykb_pMMLW|K6Qup} zbF5whHcMJI=W{qLpt2|7vSMzus7RYUPK8KtiV^vZ*LwH+SVoXkx+#I)&wF?xprt1v z_a5N7%6gkp27SvD*f470KSSIl-}n|o3;J08ij@CbUF9FQTfV7BkJM9!Y5&iyz;J1_ z!oHH{T>#%56=8|$NyzR6k31l@BvQm11)x8u_qa$F%Xu zZPNVh(&Ks-uHvr*uTB*j-Y{v&1X)gDQljK?YzO4+u)X?_Lks_H@Z`LePG-kZ_-ljXL^Ms-_TCJ@ukV? z4z(=`Kgs{>o>Yc-nFFs84s3e-5GV4KUj)xSu;X$>89+a?T|LB`KM=8<8p#n%#HG9p zpM1Xp4!Bco-k%n4Eg0u%@D%^xspM;(L`_zPB57Iprk+hBpa~2PQ{(M ziNo8R4$l!*%zLkjnhz^K6;_LW_UzwaPIFILvqbJ|6X``RlH30N2+m#v&d&w1TS;m}I( z30uWF7kHBB3h9t^-RSZ!bkc8|Bz0N7+oV;SN~64)q-qzV7b<0Y?fc|Pi4q!Y8+cQL zUl*U;B$LdreR^Z{<@QpVZK=r*=!xcgjbA0OcRTlcdepSY#8dJBGk^g3i(s>-_Vk>az#KX}2IOtVGZ zj$QjEU55srsO4=D2i9DUO<)5D52FDn}CC-fCzT? zkNj>izk{Rz~6c7RF|X_oHf!z z&9%A?gm0X3a+&Wk$&EWK;tP~Q31oc+-c<7AS&gXC&B6?Esy1T36i~74N;?&@I+gg> zHU|C$)tXC4yo^Dqs2C4me9^zUPE_=y=p}W3DScU3Xr+XY%)1`I_50fIMzw36XlTWM8Ot$1@vl71!GFjL7PTSD3MrxtqP-CkeBpZ0EQ{a|9LYLM)-r;&H zb=&oXzZ#$S;nI9He^PNfARz;HQaA9Y}YqHb1p*%lgQgW63_O?ixylm&t5(+IJ)e(8mKTnW*O0^F`1FN z3~0yu^NFYARZRm@T_1@$cYiZLZQveW=*-#jl(weRmFD5i>Ane$mdbyr_F2 zjM0yT&K_hY2=D$(_sIGE3}IF$JyRVZ-bG@7OX0lp^Cx;go{$9I zSerUh3nK>eUJ9W`506oeQnKD-K5)H30X{nV>qB`@VhcUgbzHpxev7 zd@Dh5rcyYFOB~a-T+^6~Y7EXA4fgEv4K%=9+1DZa2}YNAgfr7T^c2n;hkPh%eFkt^ zm3m^BQTmDkK2wQ8El8)$QAIGL!sNV*+2z@P>o!Kt)aG%MAc2GAlqG#L>f|+R?cf^ z>7+?R8f)8L)@bpEX}@V0-f379bnb5K)O=-J5r)6r+Zk8%^~``hMfYaCxuTO=yO`U4 z9nD@ZGPel7|%fD*l#iPp7L`<6_4%9mXEQ zb&T4ojHiR^jePnX^;mlo69mR!mYU-p-^IAh>t20gfZ>6X9r zFm>(My0V+CaLYF6^P#5A3#(`R^RI|r8f$=u`d_|~AhQ31ApO<*)@Z2W#5wPdL5R=g77ZB>KIM2!+o ze5^-fuvhA8gz6j0wYhQC@53%>3F}+S{GS31OScLQRtmoFAdat(17^z5gcs63nnUtl zQ;9LgLJ>Ix)v{P8V@2GLM^%RPJzeLE%RX2?bTy=O6O69f-#vf*J^jTGhZ#x5GCF=y zGFCJVg)nSe;Lttql4 z7@nzgy?T94`}?s3;S&ia8yBvM(9(~~Ru&hC0+^!8_H0$1f#DQMy^z_)4vPt188dQ_ z@~Yu8VK__DC}wkgM`46Tu*%ms^JT^6N-{wxVDQ%J7)e*bEC0}Xeg&yC*84-@MuU=F z)|CK)H%7F^qNF$=W+il*&_IVB3Y%@D)HHd*l?ZN3>l(6uI?{%*P9fYTPofF>D^pb} zsm*Tk0oI>H31a1xD&4wsMR@n$E;{5@8?1bckWR?n3Nr8R#V1EC$uBgj%o%7Iv%*H* zD)pi#F{yukrLT6Ukiy&rWz z(RmPMFYQc5k7IWTXj|>*>L@!6=fP}C?S02QWnZ+K>rC!{#d0M3uV7rQcdnhagL$N2 z9F6l{VTj~B#dEHUU9a+70P+?{TT3XT=rAlT5Iq{%-k&DNH>MH)Lf2Fb0Wr&3j`q!mpIXYkGAa08;M*6=eNW}CzTZ2(NE4Jzwh+Kj zh(Lx+;}l6yYktElMZI;A3zHp2@*|i$In)5m%8f$EuvW}li!ONB{VvBA^8Ov#&KCK$j_I}eu5SIei+eV@p66RKFV^M~an6BAsdm*%?+!Gw>0m9& zq7nSk=hvqH$>7zwf(2;x=IXN4sJ~S&#ebiv`;XA9+K_Qld!s2WF>K>|@>!7wHJS89 zK8O;7f`ovI{Pv*@K@>CL7(af=ededhHeGT*b=R-MUnpWE?KWYbq3P02e?oY2q-!-l z%)w5%czv;p`(3n>Ifb^67<8trLoAJh)pDY$Tw$mp3r_)ckM!s6ZMP(DL%5o|x^@qa z7E2^Y+e5?-;0E&{Ix0wco>6T7;}7}Wy}bai&OwEeP{o1{c{fWvr)_c6@-2x>6c^dd zH}BibmMANY)=I@Qd^D2FXcs56sp-JNkkg9t%uiM(y4-BXmFhM9)BMM#QsQa@E1Em1 z^IS8_47*S{S7I5mZ`&=6<_Bbda?E9RSR$s&(Oq}8(vI!PPrY0;6h0kG1B!Eqg4=}+ zhm}4jU}H!K{itqS<6@My_B6`2vwBVAQH*WqbXLwN;jz$`mBrLFnm(nV_N~#*QhkO+ z)fSMi_!M_fJ|Dxt*J|-Sy6_O%z+y+$%KgfLS|*?}OI#U3+GhpQZnNI9#N{8P6G74( zj$mzCqlhXjiC3NYwz^CFAw$>pQd5~5M2pf)hlN#Lw_X2*9#b=yZ?0k3?sJ+`=zG)6 zSNHTr5ER>F-;4eTv{$m^pmv@faf)tuU(NBnB>D=I?v3ALQ(~5%k|5Q}3VUMC6ecF7 z6fT!0GCF68yurs(13j;Pk@_C~N&5 z#nzFSv5U@V`r?ayqAc|D=7L<+q9c9-9BRJog6Z7X_XIx$+PR>OsuuNBS?RGJ)%8zy z;U>Q%RUr06?zHk3G9+!uzULPl>K;)#j0;# zsbqn;2bOgi{ObG0?xREM<|&1E9Q#=dc;+FxoDG5;vKEHSCu=9r5RumS_U?ADPHYvy z$_M3^0e3ptF#`Yf4cILFWAH+HqC9f*awNuzGIthJx~{)GoSp5{mE zOsLm1Pp~6Qs9t-9H`7V=&l>z~*0C>a&vk9*7*-9|$~zRpFarmMBE+seibCl&me%yI zHCm3fu0dm<4vp{328U*+GvcvAtqtUBXFplSg1V-Y-g<#n75mBQ{CVKkXrYhR+1Pm< z!|>DnFP~2qD-^fhFqlV0p1E)<;vTl`+@G&GL4ASJBlBIl zf!P|&h<)9w!gDx##HePm!|JuQAKrW?WT-l&VAkJBFSe+xF6Xh#( z!ig=JamPTj;QnUFzmX&O>HhFLLEc(A*GkMGnA+-0HK(`_Z~?ye@jDgj9%>-r8|dOr zw!o=hgb2dy?y!TNvY{9g!HxMLE^pm`&<02sn0+a(iK;r-JnrQWa}9mq&B>0DhX)0@ zij%_ar_RwH2Oz(K;3Fwo7u4(nXFq@j@RoCSCNu9ZH7F=YaEvRnQRfqd__>vH{9JWaWdu2Jd}&xelN2VdgAVreb|B@ z4ai5411lFA36UEw;wC?VyE$;_Nq7V`wcCcNpK~AOiiYII;L}c5K$2ctbA$x-zmHJ) zMvbBUv>i*NkLV!E1~Vl-rHI2o_-K4KNI?JkE;CW)t!ahzh5I&IJsdELnA!mlAVL@* zx1Uh}(vdMX=ylEuPwN|F0`n!=Rby3sXi=VYb6*Bp^7S63BE!PJ-n43uY}?YE0i_VZ z2oMYd5-0@hGc@y70p|Ndk_iqUjV4}5!$rKFyVGCTL6V3f-L8<4`{Dm$XZG5e%pOm; zeJ9xw!o6EQ)#FEpstxrbu?Y7RH@9az!fwUl##BXQk@AC-38sC(MaiN0AyEKnkTO@e zn{wjvr~#iRHq% zYQgw?O-V@4lV=$P*Ahl^N1n@J9dz$Qt}ABm;MiK^$KT|y-?DhC;daV!o~xPl+G3Oc zXIye(Y;tEE|6w<&7v22l;?Tdh9z~bV94bksZgUa(Ou=1t>=6iKKYnw{rXuJ#9FYSU z<^bZwj|{z9Viw0p^D!z$(#hq|5N#l7FB31%LN00`*+gS!0aC6 zq&w5XW7bXtYj%QFACfTab;&+J-Yj?`1&QF(lSSyQIU76Ju! zgTAqd^#FgXXj`i~7;NxK%gB?z`RAD4ih|w<=!6)NbYG1@BX3voHlR0k>V5KA)7(7>ki_rDL&{XBsU7=Viks z^O_urLl^1`J=0r@ay}Y+7p|lZIFr_@mRsa4z5TO>CWba->_0wE@j5i@gGdb^BXk|b z^o}C*glU`l>7unO=StZ2y#>+b5L2vE-Z1rTHvpj_6hA@NXs2s*w{$$?UYa?eNy)#+ z;5SYfFuL?MGDXg`ng2y>zHzLJY5A#h6%K#yoH|xdd#xznBa_k7v5>q1WdMZl-6!VH zL3>|{ru=fbuQSQ~;f=_84%QGv<4z?y=VXmQ-fQ>MdqlUJo@RSI{T#HQPvbeVexvmH z&<;Fjq()ja(k1OI6OK_z-AUJo2K#)Yv+m@~S!W?8L z)k$gx*+~q#NzJ;|7`DADBOi$^wV$We>8|0?&nO&UhuPO~gA}~Jh0923uXTX%Go**F zg-5i2ckFOTiSzz4U~G1{AJmToks>$Mi$ZOXn?ptI>|$KH;l?lq@F-ukywhwV`V%66 zLJMXNVW~owFymY_bX$)VcG@tC~>b;00@*S$}5V(=2Pxn@at8vXj$Y zRFQRVoW4t68(m}e=J)Av%@N>(5YW-kWTPnapF8hO$gg(uvQ4rc_ba!m_9S2WmUj4C zVDuS2f!W8k#u>*fLMuI0h3BA)LE?*j)VJ&TY0_u<`cF71lSbQ^{9TY9TVccAr+Q1? z2EwO4BNq0n2JA}ue)@Ore2_!$({XUQ-iBlzotf%`OZ5f7DdLrvIF$_I_dT{?--3X( zKdA)ZF#`ja_+OuMdO0`Nye;xCiu!UA_A&<}V7+whWHfYktON}E=fk-cAIUE9Zz-vQ zvi&Qn0Y1ZZLJL%(-7N%?Wu8D1kEPjaV1f=HfxkKCWy4`PijLM%yaN{R;ac z+QY23)a4qL@5QRCX)pCV^%`lfHEh|&9d0p1mmjWz6b|~Q5PSk^9;UGb@%xfseQ^3Z z6Xg1i1<|ewU1c4J=@ZYHAIbdfxZcVOvIh$$^V!(P3$HJFzu)V$KQ)=o@W|ukgChW` z5x6hwZyDB344{7&6jn55+Y0cKx*lE6*x~uyczJTmnH-c&khsPx$! z?5kz3m|~A0xJe82susEUaS49)y@L`$&`R|{f#!JZnfR3B<;vmp^^e^62!7}Fehi&d zOx^UeDMF-Q{bhOO`|vtNdizCu$;M+-9t-|KM8nbV{_<*UkA4lL*U6fXdmC zcu^7*J9U;TU;cS}T@ICo;*s&DN+f~q(WP!Z7X>G+sgL*O4knFrkK8lT%(A-35_xKCpzqlr zzI0u|BhMChR{UJQW{c`sCm#%M+V*LwT`e&g6UdVPH|tc?wu<}ogueNtwWMmlZ@RJm zq(FS|Sh~E8KL@&yTlBA_sAW~+#}lFULq0&3B=DA`u&!MSpU{Z>bAy$QeGNNPZ^ogOyqeJEQbw9*oPq$`09LbZw+6Q(R zVp#&BC@_je&>JS`38$kxsh`(VS+lBwvZHy8)t^21K6JVpXa9~;L47p#IE4cmT@Q#- zv5ZPo`M6%+Iz%W^mF8{@U&DK@?`o9c(lQwyC~4s%@=g`&LZ*Sq-=Ez)&~29V9H=>A zrol))I`Q-9qPgMT=YJo50z_h!^Mt6f?fqkEs%o8A`jYi#0RjbMn1ipK)g#}`LQ_^o zQ!Z|&n6EI-Y%WnD?-~!Lx2H3zRO}iy6N}!XM@FWmIKUja8Pq5zaXvKbVz)%8M`t1`dFQbPT)ws_6UXeg*B=MUFhfr5;zJE7VcQpMh3x zFILT4Vx)_z+7}Z04L+u$PdzHTli|_w0fGc-5w)MKz!WY`M3G=&c|xDG0)( zjBFR%^J*+}h71zd*-I&3igkTn2CY?F>WOOw%(gn;zUX-La)Wb&$NjRn@aH#q{*Q`} zT#t`@bvN+yy9?(~3UBXU{v)Q}__Nv~IW>^0&qOI(=12?0e3SlNZ8=qC)O)g#LiqHu zMP?i@zE02-AFzc)$dw$`f zN@YS}6_pMrLi$}AOFk?nH<{sS{3x<^21Cnzil}1JawM>f{+p1R4WwGYzPfdsSZtHAYLxI zi|dEp;YaJMjy0QY|Zw`F}|B^zjepKn058mw&Wp`OnOU~ ziJit>$ejAp{kCeNW=qHjAVtb}(jP1pL751Y3R(0A%W$WvZawKmCJPz9M4D$!7+=4b zT{=!t5V{ie@x}Z9Xu{s>RnAX^3O6n(2pg~9yasuBZ!|ja=+#30$um}MEuYSi+MWvc zk^2;C4-+_IWEL61_b2`9+~L~$-!&3)VZR#jTub%xc05Er)=ekl;el8#6sA(H4a1w% zA~RIY^ttJH#!6l^->;K9WIVt$FM~g2laj?xQr!id500?KyeEBD?T?3gS%?||{G_5gLRS7=6b3loQ1eLfXk=NL;ds*$riPMJ0uPYh)p-HR9r+ zqOG6HE%kg*skT4AR;;{5ES(fhqR>_X`T2Gb;X7p;#m}q|5J(yAhl1njQnPrCQ{~lOs($?X8F>fKcfiDD;yW}Xl`}I-X@QvA z{6}8;3Fb|cgu>bdbo~5To}mNd+BIOER{0Q}K=bkaNmf#KdT3GSijq#L&9iL<%uqA~ zpO}2dQa`&eMfXzq?y)FZ|K0|fZWy9Bd z0 zh2*Mqtk^uJ`@@d7~@Ym-aNCnFqKGPZJNE2980pDO&aK|~4=ZQD@7F--S zm)=1ViD5sI*`^9!t?d`=fcdt?Y}yHu>MG;BLdr7oX_- zw>>##Q$_wd%Mw-YG=}(pEhGBTQ`*$~4A&5UGwe5hH59}9;d)1BODFkNla8e9taHd{cW(2D1b|A!N6 z?;f%|(wrUU7wEXqZfSFG=Sab=8mSG)ssCoKsU}E=UDn46im4KZ|MbI8rfgxL^)q}Z zi~v)H5_av)#6D^QK=XESZ*KlZZ*rjwTlq1;cZ-lBCP62F!TzYwYh2~WpcGwa>yC(o z!>^oMZWy`I9cv3g(T~U6w7RJ|7s?-=k0z!Ehg3tg*&X*gr?bPOH#w6r$+V{EeQ`b^ z_&h$GOA*u2E9u7^$i!V;;+!(-es@!D*uv;RFxYr^J|KpgEMt9G@CZv&gkYYm&EUIx zVi73Ty`5?pRWDTOwK5SjmlFM_SaLG%=e;F|&MU-aqv4K8yrmkGSDzh&`kgw7?>Zp! z>FDD#!_adV&O+@N;)KX_ycFT3o$Osyz|k+I=U9~#IeA2tmBO-fa)TcOB`3^bUPs=d zMxi3OpR9BLI456G3_!PNom(m|KO`ckC@^HY_M==SO)Chmg8%eh*koau#i+%XfUXBc zR++IUTT)v61a3F?y5`Otk6R58YY(+JFzFWL*%2^ZcciU%Y|@4vOcj+CwT8!Nqm9)+6% z#CU$`)>FA1ulq+6kymA`Lv)K@nDxBc2LC;ux^P`0JM`olYg7IWq#YoHH2lGb*~~_< zYEX&E#nMwIza5a2(R<)e1)a%@V*Q6(-yI$_KP=gHSlaQ(6nGg)yT3LLbYzsI5+UA- z$9Bho>hF)4FwPh_+DeYI;CYL&DKJalD`y;0f z>(T#lxNS3GO@CWns*Q&2UfNx`1PUIXdheWH1y-kKtp}&q za{0CVu4*WO$m}XI^(yWlGo#whKCg*-Q(y%_!$T6NX&+7o567OnkRSj}4E_$8 zyCR5!@kGH8Hh3`?>;^{gRBPad?-2Ny*TXj!PAUU_-W0Nb2QY|HfKSQEF7f@zMiG$w zP~pO|cV~KAOtQ?8-Eh<40U)PlY0?e^ue!gWj1u;Lfb2(p7zVC|3@BYq-l}H7L5d{nSVA%iRaVWxSkSp(u_fjin-PbTu#xf?@U?#en${wrfsGO%1{n_BJV++GGu=6 zTNJS0|0X+bnprT>=P(c2oHIAEeoI*NdAT1|a$I?_y=_TQv}1dfW4C|OdhOUY*=Zzg ztP^p0zF%fhUNV#lRD}y@@9#Q@9;GAvrT~8AXJ36Kwb@Mr3juymD0NYTpJAq&YUX|g z_=K(^CP45QO!=y9ogA;?iRQMc3LR1iAQU^xKT!8H2|bZPJyb`&(4C=`M0nys1y)8s zGQmr|Dr%1?axEroHv{hsu4n8Gbxb)ww-FOLiy6<#W(LXTDgAe-YQ zKSC_UYHgkunqy9fo0}QfJ+kBzjl8(apv=MSBfWH$(C6sFA22eem}wa z{v$N+5DiGjj0tTZsu?#MxCQF!N*;Mm2PlAy-`}NQJ8PS+1%l>Yn6AmyXuhnB6eKDK z@ld3Vr+(=-s8tSgbAPu>(uAeo&5BF8HzdK4syjQRA zi+G4s`br|c z@KybxBL0gzRPis}3{a{Sf0yVJ*3WB!(fDtzcyPdp7^Pv}?D5L;NwguSCsSf~e~SIX z7>m+B)RTQ$CF~exzL^Bysn)Bt0iq7))ww_qr^V+9TY3!|&R_ngX%@6#o*7bEAh-6%JEo!rQ@1XE%yd0TH;# zw5RYRso#*Pu_~+lHb$-FM$VZdpUia?9cZ6clvg6|iK)9+Gu*7bT|yOOSqd}xQIlfv z&9k;?T9D`8&O$deRy`1hfUrri>y~DSS0*-WjzY1cvUe7HPaj%-SL-;QrhP7vA`~{i&-4Ii=vEpun6ZY z296V1A@z5OFNGHI!VB!XrY6GQJ}2853hSclj_eJ5uaeu|I(f(dfr*mK3n34p_Kp~89IGTk90g-dSIi}ANvxG~ZBU!qGOtP{<;oN#F$d)m z3x)P{g;uCdFR#n-nWVZVKI@5?_w1K4j~qc8GeypxqTAW{LV;Au`u8yAAzE-tYpIc) z5{;KY%^*mXa(A@>aE-f|lQglg{)-|0Vwfb1B@HWEkbg4`3)4Zub=(|`;{Mf2?XIBi zPRR5ESlWx3wt(&RwEv^%yrYtA|33~0$Wn3R2HYF>$O`u^oT;g)shL^1( za#pxgw@w8zGwBldJgE6VPw1A{Dde2EG62tT! zZ+;WzmwKY|uTc5hddQ%Wz||zJ9)lZi(=);O0=w&A=!gMKHe8k#229D9s>(m0V@2ox zBKBVc&3R7`^A--jd6z%@tJ>hL4F9J1+n5XG1)t+>{0}LyZ{4?w93sD(Vj+h=;~ui4 zuj7Q&0y%3eTkGE_q95lcdekB~-C|Pp#9$KySZ2yCX;U7H^E))8yvAu*yP5)16JCEY zz77k$u+wlW1by+(d&hlvz`>{Lu1p)7u0tM;B;cPjWF+W=ny#~F6k$qlU;I{s*E%elHxC$}03(3*R>C#u7wms;4%3AVS~ z;oK0ruR*jw@Oz}u^Hd{%)q>g@FX-j@5cHvu=|6p* zUK?orMZMevVvg#)e>DSt?mxdtsN*0L)l5(k{kEx6C zeng#JCPJvr8RmhvOB2TZ&YUPXZtGo3s>7$blxn(^Tejl)-=gW!2q+9waq($)V5Fqa zFT#pdt+OhEJni7cDlSx>M(WAY2{F~Ua)OLpc*hB(E8}~_x^yfWd+f_w$t%)`5LS5Q zMg;!E7qQNwC%&fCU(C?KNDJvqkMOZV$;Q(iB%rN5N?JCcKen#k_NJ(UVd4P`H!6t2 znTJf^vtQ`=cla#^_?&yu5i@x%qB=>}(lmyjHvRU`tX$v4S1;pE_1!z!m$%b_W>ATK?ocA4Vj#I*=%zU9?dd|*S@(3DHMN0tn}~XfyJyB$PoR(f^0p@($9URH zIv&PBJiWX{$0UeuqUmT~-KJ8}V~LwSCvqU6xD%ogs%&4e3!P1)(D2PBso)}> zWG6ew^?TFO*i~z&Jvzj`%plwWkW(2HGV3EX>d<0R?jK)SDis9t`V*F=QRN#zH;4+s zpJNuHtD&fPESCH?E`+AnyTF;!>X?~-J^xhqFjD(vNW-kjqT5Y(lXrnngp%JSew$rd zy<7a$a<`%xB4yHlW<oW4{c^oCY#kOo6cHd1ydq$;!SBKmZW1qb~es-JQFeWqL#pq_rXDDpJQ=0a5J zMmL|ZRrL3-A_&HA2;sa@9V)jik8ks*RbJak)x2|Yep%x-^$Ux}ILu{eHt}lWZ%0B_ zo}vE=ue(0}P-z+XPQ5-7I<+lbOO=IUUR?n?{0)xjOvi*J)-%Zy z*m{JWMwUm3O}fSg3E>q>6~9A}R7W{zpOl$7p~feYo2$VS{IgHbcL7yZLUoJlkm6hM zokM{$VMW%iVzgDl!xT}&@Jct)wiIdAn6D9Wlo`LUNa?I=4zTo6odX#W#v8oaaR~oO{a^PVQebImZW2 zp81qvvP3b}>1aM|)K9tUvN|QsSOsZpRbT%{U`X@Ys=y=mGe}D7ga~~#7T-^#Duz!8 zGl`Yb(G-N%OORBo22>8Dkm(ycE0#$QyF7FHlT(8uhCFV!zFSDo0|;Q3g>Ut`s-M#_ zo0uG6nPM2^l6V2?V+!MlI#~qq){Kv^({)~CP+c8tW!rYjsF4@IS z;g=6+xt*oDR@+<9OV8_&y8RM@@p3I!f2UH#Lx@K-U~eIpzcsSlGX)-A71MVnx}h|V zftAhgTrAa;lL{wRNpM+)W(%?}W4Cw-`WTO0b3p;|I&ph3MbEUcfv5OfHBO!Q8Br}X zepza}vXerh*`b?WTfvXA-vbczD^$6mW^j1XLRC-S@Q(<6QssVaCC0_W@+ zr9|#3v0g9fY2v+ake{Mig`^*o$myUS!ghnFpl zYVWM*06wAQZTAw?#B!r-fDj>Qw@A!n4*|+zoh;<<&=Xn zm=lPei?sbLs&m0qITi>no1BRl96zJGSAcY~tw)a?tL{3io-vmiDqK!KBdX?M>3`;s zP|T`{>I)(?iUv~Fu* z(jLTp5xcW+rKJgD>EU)*;)>j+wNT<8$d@^QcO8Pp^V526Fw=t!TD579&B{3OD-6S8 z_<&M3v%ydk%mI(t{q8^EgPb%_n#r#nS1^T+zFeTJ%x>!)OfRm?`JsNuIg!*t04Iv# zf}B%b9&TlAYdEPQ{0ph#!}#>!-x0aV{v9U^V(mF)zn7exY(9U4F}o@r7>T-mmh4^n z)Y&qplh?UBm3Xb3=KMA5qQ4(!fm7DApcwkb`waq74W2u%mt201-EE>WYb_-fClC8_ zgM2ALxUo*E$0;wa$Tr)`)pIPgWW(1@;(#(DSiH2{>k`h5Wjk7TMx4?64_ueGZD;D@D@FHm9?q^uz~vVh%-pd7?qR3!qtN(ACh3)~13 zsHzumXTY+!Rw&7%Nkxegsz*K4J#O!7TA`s;_zXL#WC@5?ReVyAdU~jOgne^5>5`|q z>d|^bXoDd%lmO+89R2(L=!I3SNT~LekI-SVHeVXaTt_a%qA4Hg`LImboJbby%p1;` zbby}mSJCNt9i<-KbSb^eSeOM+qM_f{AWhGPC~+JIJ}jZ%;3(;fyBxd*_F!Sc;tbkv zI*<~hAKbh)o*aWnh>;_Mg+{KN6*Zzq_;=lr$}W|9=wR^3?A*CJ%S*Tzj<3{-QJz$9 zdGym0d=T}aJGi_XJ)lb3$$L2WY@_49?Lh-^ly6B&Y6ZaqtB7tQvWp;ppdmk5C;u!? zsH4EduR&;$;rx~)^uoY}pPG8j6?$DDjM5|rFcr_@)xQ{={-3DpZmFtYmy%wYob;;F z(hE6ovmDegHZ#FVWd0=LX6${O`%~jMZAQqU)9!}x`04Rbb6b4*H_Mi~xI1hkV+$4Y zZp8rzHETo;Q&6HP1Ck+G?a!sbF=iHf38(f1Y?-ip7R+}~pn6_2l$;^42?=!a@RdqZ zg(Mjh1%k0hz0_}>cJlN(5s_4s;cez|D=b{1RI_$I{YUZ97OGY_z$=``gak1m=edyZ zGN=UvCERl<16Ijitr%g^3!^H_ozJA)Nm;JXEK5njv32n5%Ag;*@2Hs(=`ce(y{II; z;{_7ONs!}vdOj@MxQG)Cf{@+`{jjf+*CB+njSh@RaEI!-`JZ_G{QyQfc(9qE1-fDn zxH5KdrLjz!d)A-Xchxr>?3I>N1C(j}N6I77ap9-bJxG9-O-^bfzCIM+2oxBESiWgK z`Bmb4@o70(hRTg^!J1O4pH!7jvJju2T%YMRKA_9@#tJPHE-Wz^D}aJUV!>iTL4>U- zs#5p`Q#gPNfyAbl>}z=cQj`c$>XJ}R6$fb)9LF;1b){5!+8Ijyb8_y6SR6}kB+(od zU!t-aJ2eVY4#7PI%MJ9(-smyf>@mW5#>;#x*1T!tOa$upH#UbJlLLhH;^a^q%IKmT z2B3P$)^)rg;j^_`?!G`83q}hOq_JQ*doX^zMGTU3Ix2a;yDX^RGxCyW3>;bof?hkD z9Bpyb1W;xiTb5+gawat?8Ih!&el+qUBw8BUYy%C)Len&%(W_A429!@3PH;pOWYROt zQNw%z4^hY=y|T5fO=48!?Y>xWllWU3SZG8_jkB1}!kI%~b?uloS&^{nK3_Wz3D-hB zZ^DVAV6Yt+EJeEPzb5I4#SBzrOMS~}E9Ut<=mTDe19y}r`gWXD&xJUPiaR8`{`bmxX`hDE4=}x%TWul_8?F+Vq#1!t1$$MhV3LG(fYdJg;8u zZlb`(50|eV37q#~zbU}qKvmrjz@bFr|0r_EE;(?RoT)6XXRg8VoD=c=H61{)9@9ed z(#cz=X^J+z!Vh9Rqh%FAhql3%)!!QX?1A^cVKrXdW-pq_6M-Ha)%y~s&A5uDMBoty ztc(n&GVf5y@CpJZL{aM;atLFQP z<&w)DLM&H33HDki`Km@wXofTN90}@&CPtGY{mGGh67yXoip^(1lTZ&=ksKzHMMA|t zXnQ#QaHJmghMH+?Anq9vbt1yYurRaHBDEpKcfF|UoIRLXsh6)N`NZ-B5diT3Kzv9* zO8TQe^VL!`sdoccwFPR&UMOpI-IaKccM6e(38-*o?9UloYq*2&l2$46@#}zIv1SE$ zHV*en8ztKrjYrnrmjtJ7;H~RxS8lqi)KeYmsRLfOi;DAx(}74a)vWJIE(5`8u~sKZ zLT=rNF0y>VD1tYYp8vOkArx?7B_!z9sKWA`&?3?FMFAwNz;o%FTG+Z`c)ZoUMzWBT z)xUN1*jON^xcgfYg%Djt2*A25E~ci zmUo|GVM(J|ZJB3xtAHI(iMO2pB&jt1Jnc}qz!7X;J`)z*))$SK$k`M4@xCQv#xpq9 zQ%6#(4zG1-%CjLp!mGLYifnRY(b0qhNJ4;T+V8T{{mp?;XapJ>#^`UsLnBrPBA8IW zz2u4=XoE}JSt9Dz4)P(kQrP(6e1XWLPt%WML}}%^Cw#;$Mce(xbm}asMykc>H(~U? z_G~E6cC1a${j1)$d0TI5j9=ji5&%pj%iP$Mb}_!XJQ+QAB4+EAyTv?y=@NKD>+$pQ zn%7PS-?h&zI2ydtyvNELh0ufocLz^}grD zM$e|7dz*)fv9tREU#s?9S(+IOkEf9K&HhdX@6{#btqb_>!BVf>sbJorkzYnf!^?QA zzDTo-@|+3n(xb+)H|xcq=UOA`x*++xo+m$e@}X~8I!o2^&5`OYzl)DvhIvIWrfME( zb?hDmqzzt3jvOXUcWa}HG*QB%t-}PNT-Z#f?ki-R$Xa~W>-9{NP~a0()!TaURYR~8 zHmj{N)kwmYnVC9*usgbtRpB5x0Ec)L`nzHS2L0^A>%d`@=$Fpd(ifi+sD#f~uURue zymtKC%a8y33GfWRqJ_7gOl5tZefF=*6+N4n`mX^_Ax0*&Yx?VWe0;p@PYX3a3n{$& z^hT^Q7ds3IysB*eyKqz>(gcZgc33M$Sm$?P(+IY@RQ2MecC$^*%sAc}y2@AD3btcyw_7kg2 z2vG)Hr+ts%Lpn~mg)xlSRSmf6ZrQ`XEZRD8jw`*v?m&Z^>|w9#j}ldtazF`2rQTbx z)PFzZFkv|%@H1KyiAP}RD6K}roJIjNf-;)DBNZ^N` z@aAHNFs9?&4G)|SLL?9#*JGQ7K!DaWR zscN84d!2=3#ooyVe9R%fOul>PT)@Y8p1^s=RN$SP`BR?Ryu-4BpeJ4|g%sTU z@f=ba1kKJnnxAt()tbCsJMm{^IhfSi(XoAwr3En7jzjP83CdNscN&BFmwbgk81DG8 z)Aa74yS;e#1#!0arzU5ZQi=EyzI~O`-jNE+AZHmT+Pa1Uk6D9TKY~xJb+o>ebhh)) zNit|%G+a6#O$_@?SRZ~9uKeq*vT?jJ_wijLs^!G;+f=)pk9Xf~eEy=x`OJhU>vHb? zc9;G61^@Q3qZJ76a*-yBU!42LZQkzuLxBW*0nqGd;4ly^ZBs&wqf&EGrjc6#y)I>d zfUfAdHr39s2R>hD(gfF7EN!i+?(CGJ1@!RBSbpx2BIvZQ0^rg?kq&a*>hL9e(FQtwhn=Pcjv7Z!r!uH)@2J!@hTleW^+sVUL zx>@xhaCtd!sB90cm| zXxB8@_EH5QxL*IK5VS8z|K#Q4g3s+AR_KP0Vm{*Uxc@Q_e15+!D z-Jiskgy5$%N;PcYDn%^AX_W$vb-K#1-8x;_)I1D=nb0xHl$>x|cQedR`9{Zgd4HP` zDp~?$O78FO&*Jw3DYMGEI`wqPVPm6A49lw9-6@}rgJXQ@p)~7II(uF^jKoft1{J$9 zj~m4T^?G!~Lw&@K#P+r#yV|C}&yFz{)o(utQN?FQ)kR48Q*T9-1w@BNEQR(?evmD6 z8T_DfahN?WcY!$x;URSxv|~5*FEen>GAUEQn{ts8z;yXzEkB?q-Obrx)IvlX_-^e! z5!?2FLl!_-9T2ro9L2bT#mqz6+tDksl=NOFvMW>g*jRh|LsSB=bNq) zlh{y!?61Gi(FPF>3`0>~Qx@%7_aFl+;aNaIJGdyH7jGAD#{jR@cKj8 z1=CTIz)52+Y+O1lE%Z)BM4IS$`Ja@z;}tUJv9H548%J#DPId)0 zraEZ}c8G0Wpq=#*u&Ahnh()9AVtWcTOPx+=MBr*G>a(=&ps9|yD`_B@5{(e%tX%0G z2G=ZiqQdn@7UF-Y49>(~HY{u*&p6DzCO$VdyO!|W=v^S&)6n32;=J7xJJ55({{^z2 z{v&AOts{#rzAk>CP zxf;g;J6Z#+xr@b$AwWO&eyNVUjZG%{ld`P8uanEVP;o`0tk$-JK9fZ0SlmFq*#Y)n zE)YoAB+^Y`E`r(dR5A1@ScXV}+A<_kteZ4(6H~q&o`n0PLIEWfnFw|uh*|B02=ls8 zCyfcz@o=|rYHH5J9>)MQHAap}%#jtEz(|r9pwnw)qD?I2S}9q;d4?$7!Roe$feP)b zXP=Q@RJjpsqRKF7s)n7$YvE_2kDUvU88@miOsf-;jCvJI?M^2Z)t#G!Zzi-nfPDI+ zb~7TXI&Mj=)|9({K6;CfCSXAh`q|P~rk@#BuycZ7$0~>TKKc|~?p3#ARnHqEP3~@E zuV2-$Rr<}%MzHJVRBaM6i9vYZw86!JEx1h!2UkmiEU~>{HrzsqwpC?yr%;4L0Z4+u zeWoch>CAaJFIE9K%(pqE%8|B8chbOg8*lgX^9z+Bv2!l|iC(4ayx`kVRZZ*6``2^A zl&V)o)&K3iC~zwJ`A?1X7SkUh&{xx2(BGGye?6~7Hkin6-dd-MYH)RBU|MX}Qroq^ z=T7;i$qd1Y3dB~U1y8m(z?C@&f6^$vi&WPc8J8Q8X{WMCgqu!8zX(jML#`l3q=!Pp zWp{~!7E9J5mx~1CP+$4REuh%>ANQIVAy^F-z^g(GBta%>dxL>ctB|p_el0NQTq#R! zNlGjP+k%S8KKXi`D%?WWyT;BQ|DaL9zM2)5$DV#-Smuy>7Zn-QF$Donvem3YMf3c? z&*DwxRs%Sq9jT3~X{J5=zu35J0j$s;Qe(h3gN|EA@D`_t(|S&`(StI_b#uL-el|~# ztJ~qpDPA?lgMSXL4}5twHIiY<`iVMkZY#f93_XQD7CQ^8SuJ5BBVY|Ovni2B@1=%- z)&1C_D~=j4>ojCg6f6@Rw59VBhfc~vZzihe1ct+GQNYpTDGHxgx4{bTz}p@Z%@POx zR?3p0a6?nhJ{6s2t6AsbhoIK(csFm&Z67;rX;Wn`OUtvFny?>MDmsIpSu{<$83mm! zY>@VH&HSHR?x4o6nCRAQmz@cxBT7Yc3r9(dO+EFCAecOchZ5NCpKef9bt{s z+hg{%{1cYii9uSab`4+62@^kU9bz}$IoLRGJg6hgr>dw#O}<|AQBs<+%gC!Yykt|F zQ|>umTe(fOpZ%5SQ4wNmuvb>y`8IHq^h%k@wfw%br|GX2n2fi(DW4y*DpxMBvZsC| zQ;-*oMBcn*D*n@gL$YH9uI)b0IRmqm$wU$;ke@S<=DPhM*GBOPW7}njua=7vz_@wZjO{01|b~?4TYSp!mDRQK7f8TK}%(g!S2s zwH;`O23KOS+g70Q+o}SxQPU?^>w*94Ue47C`3C~?+eJ;p_0;R02kdepAHs;#w>(ow zBkQDNfy0?>j2-XaXFU2G6U@6}wyYt$h^=xd5^|MIv!GWW+tIt$(9|18{JIJFus;u1kZkpR#E^X8)Y&AR&jV^0m_ zOYmErKh}!%DXpfhw#p55>J4`8&N)XqMvnvng?t}ets2t&PkvW)%1>>r_aSzS7^spQfgVHZ?%EAD&S*0BETX` z$fcu^*r7g1Zfz;=h(g3K;6z+P3yT8e*f1yF$lm*--B2X9VqufV`keRvF5N zq1c=|Emu7?dVg6ZdO|AW{O$Bi-`usR!N!;@R`o{hq^{aT^mQaDi8lV>o%#|OPPv7;}2W_;4X+FxYfW%Zl`25FnL|P!IsbA(kp9^~t zPE*{$-D0%cWIIHI>)(kZL_Eva8%monFf_VjoMW;QcwBD5>QC6Q-c zd0cgIK1}(4?>kVW(rFl`d?2em<%mfCU11IYZ$o*=$wagOR}Vu^V1iEpkF73@*|pOH z0A;y*^n#@x(+Rx*t?|96YJvvsUBx5aJ*ijiz*`j*MJ6Tcd*)kZd>yg;UH7c`1aMvM z*>ak6z}evzQpb})#LhRKbmHrJpRZY#UQfD++ z`Ogv>Yz{rMbhG_)nEv&eYfQnmU9?!|)a)GdR)UTG;WQi?gl;Ir#8Ff6gSgeg*P)#n zA+9&#E&1GCHIE|sS7PY_tv^zW4^uP_!`&XfKV-2R=)PIus*>Z>1R&wO#~Gu!>`^BO ziiCUkc^T8i8wqqvbQ`9JyX`7TVk>jEXNH|}o@g*!|46X0GK)PqrrJnCy-~$>)|0OK zqhTFCzIUr!E|=XpEYG4SFdykN;d(6@YmgW3z`iG<=poyZndF|}UC7rExjh!Ef7$7N zXP!bEWoH98umZfb^y2iFM^pc1wpf;n_XAYKbiTgEiUXWH|1`A1oc!O^-z^9tRvCFo zn4-2i*yg4q{m6ZRyU3-N{}b2cKb5@Jo}~WKkqn{EHVKH(VTbJr1O7E~ZYImeB^OElm?Vs8(N#?0^!E zn&NJiUD?qyywq@y&k`hD4yY|$(vRZuA=?dl-fAeYdS$~+ZQ-fJo5$u6B?y}*Vm?7g-5g!}pi9>@kJ){zrad1H_F+mYDe z(G|uopJ(r1)IX^wPyQ~yQOD?DqQ>P+x$#ER=B39`y2kO8&&s45i)188*XwLI{Q?D# z1}DnhqyLq+-_c!Qfom3*O zDZU!q%B=lRX#0m!{99(0yQnz{DRojujisQ*CbEZDvmY0P`|4XM$fSY|IDf?*v(h>=5Fsuk3L5VOKAFHz(Nr+KPpzlb#O*inO zv%@D1fuM@W?b-_`q9AAU=nmBo-xg?)IZcl+SEOV9mAUq#zUm#!M1M=Fn)p$6f}#|E z5yzPw`VGe;vg)z0R11VKR_CY@rPZlp{rZu+j38aDiu+p#OYMU$4J0G$iPy3tbcHPJ zCnJSz6HW>0BQ6;Q96aOII1u~Z1WcrZiSI5?)J{Hj2*`B_5Ze5$`@UW%dkE~n6maVY zr#=Lku+B1i#S08Ne)H-W z1LOSo0lVLhR5$AV>?)vW!(=d#9g;KBU-2T~!KLtqP_M&)GUSrZc2(;2$fGwg<8hR6 z?^o@~j?(yj?fCR}SDM{*J$2Z>FFlDradd}=ps|xg`@66GeMheY82%nc!gM9+-6^k+ zlSy;dkZhESaY1Yyb)r5aPhMBHhhB)yq{(~8k4B*#9V+-*sI;?usbiVT^&TUQ;wI~| zfZ7=q@nSdo_@&jDh73Ni@W}Ge8t2X|>9*Y%)1v{pP118(WQukt3Y8n$KP)->E%9Te z(Zz-SxNmC0^5%~R8O{mgv-iRtrTn;j2UXR5dTz(kw(RE;f9Jzb0O_O<);Jj=%EvlV z4Bn6DDcK&W5t&C@^A%KsZZMDfr)dNcoMGBGew!Y3*f}=1(Gn@d82fozkFhZRE#RwC!bGdf#muy%-jU@>6K(9eJzH zk$X)ciin0QwF*|HQz2H4|vl1O^15?Q%^QWD81S(V^kp)63$S+WkvN@|Dq%xC8B}#uE z{6u7Sq3v+#M3o6!st#4OI}e42In6s9I`4=*Z>OuQPiYiYD~tKJ$j#8dXwoU6=c|LK zRqNN%!RVB9aqsgrbzWY66R*6yk6Mp;dB>!j)%QN!D*EI^G>c*{|Ck`}7{HdGIY@C} z;zIhDRNv=}r)+PcjuuknyC#&21G^?OzlyuyE3f%ZOx?PxGjS#p-MK7IXC$wPOOdS8 z(Z_mB<cVAf0Ze=boA%G)J@QB4cdzyi3%}35 zXq*4>BZ&k5^fBr;ys#?7vg!8o|5;>L#UmP;b?>E6V7Rala8JE_M_5F=Utx%^Oe_Tu z6iZ2qauQ(StwD036niWZFLG8&Sqi5c1qX>&6!^M28H(k{ZYV2iI;)xT_I2|rven*2 z*9}0e1!<3PH%~cd3D?c18xc2!f=CFt9m&yJbVP`=j<{!H{7~{HTG%2{;L++T)HrQZ znoXzaUoA{G4qw9zt=ePE%A~{P-{*W^dNR4PHEzZ+$je)H)CeCpoZ)M>^v;3LfDOPl zIZ#omv7KZaxvCaUf%Q<_C8EV4IIuP1p#kSY*=i47BNRT4d%94-?cI{cm1uLHLOZ&t zpGksNui_}lEF*@r#JwXrtJO3`^>)O>U5G>l_dRUAmdE|<`_ow@4f?&d@6GH*@a3A< zY0Fg9-d#vn{PEX{XIP>wAru7;nQqRg|8Ib9Uok=!3?AhHxpe>mRTcoYApO|76d-8A z5*JD#(iBtHE}xDKmaS-fc!GFVvV--qY?N54cXiSYy6GwRRKn_ZVj;QzLe7#7uox-PDlG8QcOe9iAQTF}gRH;W%a zCh!ps#*KB-9AQ_>KYRJVoUlmwi&lPdF=42 zmxx^zP02zAVnJHiCR_zM@C>v(HCWz%Y{;#AuwjkvI_raCO#Mu278ozPlR@Zl_v_U< zAv3{h_ai#@WYpvf?EqdDWCIn3Er6__09HZpg=y#W}#Go&+Vo48gTu zho2e$eWgA8h^IvXWtP4+_BI1Oj;`vzeE)`op=;!wCuPG6i|udQwGp*}Cvf`FHbre8 z(3>UIiWt#sQ=f0~4_a#Eu?l%FDjVb@$Rp;f%v)KgFf;dy$S@dGn=y*eWw6!VB?LU5 zHkP)co5q7G3_PwIt{aw6P~m%=Be@G|7I2wl8@%VwLl^mnqBm z=3IPlg8of$uZp6xIo^#4UYm)w=kAnl{Au{;JLdv%O8+)32oq307!Xa5va`hi7j4YI z-|_y5b#jkvM18B~mA{tx&nAg6+iKP1D`^i=xzUwK*@l5l1-nWKR;dQaP zqJh)rE7&?lQWK}6)ArJ8-@JeyZxK3QA6wlBv{tbOqG31VAdaGdo3R>C5>n@rV%#;^ zL`~7x$w7{n$kHk4C$4`Ld^02V&iq)%F5>E1Wjm2%BVW-G$V&a}cppW-TTpXv%caAK z-ZAvjSi!Dc#|LEzyZ_w;5R#;Zf~%Dt4x*teJ%dao3h^LAB}MzG}dVDez2=9g0W+Rl#)78JC)dns%1l7HJZbIEH!qbwx$5L~ z#n~(UyF|^Ti`ver@jwXWD<4mn4K+XJVS)CV6uQYOH>RxKJIDg2haB5Skc3J}a5RMC z1&#IkK%WxadM3(8x`$?2R1t*u5DV>8^&Sn4bE~#Fqdv#XgCmLR~%&Ps9>4f{hjl)>YvV>Zmoi@$N z3jsh1o{D<63uF@8qlo{WebtF|#WCx>Lr3vf z)4FmB>eCBUy+@tA?U0%Qx`T@DX$A1RTtq7O#w351o4$9wfA>Y3aeww1im8}m+6B?^!9ARH$nOv9D^a{Ls_P=2LBrM6k|hNk&5xASij9s-p;r{D!NE=S6eR8tM9vPs_(!HK19WeC!mJ_a1hO^KQIJ6 zLTC$6TcfbN7UA0;dOSwqSWH!GlC{UxOx`JAy65VW?3Yp5yo!nrXBmJDW`UJ2>Rc0> zU$DLQYBp17BIuw(-&e8=GFS5eY ztS}~q{bNsccPO*)Gw$aSSuq$_T=^{HS7v_W0=#hn_q*m#2zh(d=}%0hd9PEp{95x? ziK_2YKqfsZKFm|ir>!5Met{STAbNeeBW$wu~qZ5fz9psFpqEe`}!dsr-37c z1JHpOO<%`W>O1JC=13%tX5Mk}Aalfg;nS0iPk-kBH~F20@0fY4#=-GTrSc#ONasJE z2T!sHZLD$O;9X45$ut+rMLYL6RqIDM!D08=1rWqyDp6O8_{UKBLotx(iVC*%)=H0dC$6Au?6$kk4Xja7{B=T690*jl0YL#ja;r z`8};Hewr%Nv=wFc3R+pqCDlAC9N71+U|6fURzH@-GZrWj$>awx_ z8>rPbXrv4xY-NpYjb5jZtH>RC`sv@Q5p%BX->PpG`DIfuvHv2+#nCPOaNyJa1mY1O zM^6XzuhK;op}1er1*eWN{LOg3jhC@en%6p#OP(Y*MZJDKb$P+vXgTDHL_~Yy`pv|8 zbQjM>aD%Y}r-bt_(FAJR;7OFV)K4upg9nGamn3ZayYkV7+vA@<^^V zCTB^?d*R0x0Mj2N!pbbz14z~WkbDZrC$t@>weB2bzU@68{^j*s_bj-dS{e0ew%dAT zPNn5@t1QqG(e^XQ zmOJ2t;>yeifrLhi-nRfLV>j8Dxv&4k8|ZyXv^;nBk)(f$`UvL!{a+vggG~UB5O`<- zgI)dt`w=rYW>6x)AC{OuYra}#`>XC-qSw#RU4f$#TbAN%oCZfcwhtZK_aE;)uQy{5 z0#x2~xL{|EwrhEgc`0Vcd?a%-CLnei^G^Ts{pSqp<)A{*0@;h3=LN7AjsSA{ktZnu!q&aQ&K`Gv zpp!V89@u=Z6l=TLr$^GQA>Jjsth{%iJFjrjBD)9v0+Yhn55>99P!)N+9jCV6Eej9^ ztFhk+%FXvaR?z}8#C`MWDVmlX+L8r>4^LKexkBD%KJOXQYQD$zF*O=0q*PN zNR3u~H+XUH#{YgM&;1a(WI)Q{yC%)PQG-=%^=6vQ35Wh%`Q*%(!6APIFMP)1ruStA{<9i#bBeQBPhZ?m^S`t`nWE zrUYIebIEm4Y+H(&0aXFRSfTR@J$1@_FX=uEL`Crc{mIj$WLI zDnn#)U0~RhC;y5ZJ6uuW><6=2zhl0(wb4`kFn_1x820yM(Y2+yAFa{|k$t%6$<1Kd z{{`Reb=`MKlGyYy@I5W8YG0AaerfS+snlBjYS+M`z*JsDmW-7fwT*Hc9m42Tx6vU|QlgI0h)N4s zY=be<(J78jkCXz6IywXeL`6gorD7Zp7##E{=h^Rhz3#u@&hLGFuh09Pqp|xR|7~Lc zwYkJetYxZ+$%CjAgj06f?r3>UYTXERgSneHP_yl-(t49dR(-&BpU8I9L&q-d*e79B z($>w^x+3mc1YO%{7w5?ITiiV0qN^PiSvacKw-fk1R`e_+U)I}Y-_-j=?+Ch15!zlT z0a?zsbsJu|v^S-93v@W)<#1@u*scH0{kK;~!mvnggBZ-rV=vaMPPDSE4rZViU_b-Q zXYBX{Yb58|#rl97#bM_u7YAmRcQdHF8|b~2wjRps|BiZu7%;R|YmTF{G*lrPZ(zGe z3*|;y#71~%vIU>0-ys;p;%yj28XpX0L9mh{Pt<Bni#!OCpVAV3h1*VXG__&%vU09xyMGEqFEyxAm5K@-qS7$dvFg~{+be9r;B;R_j zEA&n47|P4^+_G>mB{WLG^vqgM;BaGhh4Gn@qLz;h(`5%jZl?~)k0HwHEe0-1)N$Ds%I+F*pB)$$VA&%YA0^L?{wu>5()+ z8-ZX+S!SJX=@S@wCJ*Pd&^%jfn=5PXacBZtx5>fl*M5dc)qPsR`8DN5VAZx?=$lJ= zowzIbvWP=zJ!s~WPYtF5zCv`$Zk`e@@6x5Fa~bmjJ?d|^IVF#=Mjb}&Et{?5OxITQ z(CwFLpj^N!{21=PED3H|VAgg>IkN<7R~{O>`lc+V$`MM439fQijCs3ie_bJAIe%Q~ z(l6`;FC9(qKziymJ9&%J3b?68Jpd)uVXtR1#OlJ4xiJ@)rS1WsRbZ+~G!> zREVr^^eR!-Zng)6)5X)$v!FvO>=!l|KrhQ+@voX3_*5!s*##AthL9w0E_ma#9LO9f z-MBX3yc7#uXaNI&avgS8*u1<08Y*ya%Sq4+rbjME(xprSG-ubnnx^11q0>E?GC>np z;*oW74(vo`<(dex)^p+gWak4nrajtnjcPp}YBlfN($a2T_NdD>x#Me{b7yL0NcY|p ztS(15hPT#iDEL5YN!WMXB||Y(@TpT#_v3r0ywl2F1a~feY9$Tn@}vaBck{?J&QSQ7 z%0?@E;XP$qP6$A+bVW`Jbr=ntPp{Ce&$od)=9#~%Ds;tc;w6sW{W35X%>P;ex-jrh z`@=`~wz^Kc-k~*11?Pc2T5cT@=MdC{Vk`n*2*iQ;573IgMsa4}hWC~I_qqC9>4}RZ zXlx)4+elzmtcKvisx+Ibg2%Aq3bWSxE>&MDu~PiLaO~8z@6U>R)Unori{ytSK~F9G z1!`^{NEYS*lho&n$TNneFm|R{wl6)?;vXB}PqNsNHQt9Hjc@6nf*8_sHiUac5W5qb zMj+>z=kaOZa9!VPFs?GRx+1e(qH^frJqHsopRSc6*cba`h6s(Bq4A2fyigmSe?OTy z`|}^xzkuw^vIIwK3x?#+{xN0zR;sww5Dndvrm8@p9XS*yRXHsNQD1aHn{Wu@4qRyV zHXR?nl71kGg|#q#Od%77JB=rj0)Ah45ZWl_k?{QBgdmJYKEz4u3F^ zx%+Tb7(Gl-vlGvFQ5G1=(4Djjg(}}g_M6pp$zOa6HtEciIQyl%Tv*Rhn`1bb5siMP z3&OYJh)~9x!)RY3jM|YZUBu;ykW2X<9Dn83+g0BJ?5&=X_AL$-n(VaSIQYKPCSJJC zqvag2NXLw5-6ZBPx5D=D-}|rXacRU~Vh%CC0ArWm2JP?fU#0()z;Jh@od2CIz~9Ha z>$}+GNc}~}-(}<*)as*8Pc_>aN@iGWty-MBELF8C{qDnO7SCFQt>YyDi+NOt=3i*1 z``uLO)Ri<%8xlXq&UM1sdt$sU`u2EPyDr4{Yj%X+HF zNf~hsLFMxyB22a;6{C|1BWoPMvdz${`N}*yGhqLt)g|@9e{X$>wzrD(+!w1);=R>f zvs%XLSPNppxWeo)+mgPj3YJulwOSK-sg0jh8NF)A1nZ6Z>7Q+kSOASVar-Cyj zVF(Ljpk$8F{={{i_*=#kE9l)Dv3b&g=uo2^Db7q{K0wu_4)%XTjwMvY7W*AokiOfnmj20WFfU zL?~7pgg~6={BlzLi!q(5kUdbpn4UBlqRUma#v!v8yB=XEmskn-p~$j$W4jaCSc3N% z;pvA(LIaZ|WwuVRG9vZuTkBW9hHFN? ziyuyqx0BoIK6z&w7pta)H7Xs<2}PR8P0cQ|XRvqVT80%rh^$}HX@P~;72aq*o;&oZ z2Bsy5bK;iKOVX$it(--ScM`CyifU!pA_2EcEu4KnlBNQdKI$llsTQqbP|}eg+Mxvm zGqqV(MeAY-ytt{%1t>x=5G%<`|As$lWp2BxXuetbZNp9sZV5JxDvj&1S{cuk&i*Un z_Av*4Lx-O;S09G#S(cVgjStm%tAVR?f3cz)&CKN7+YR&ef&g}xFf_ivyqgh2bnO zZp}RlFsh(sKp|{EV~c7AMll@+-q!sY`To#1XW$cobwPxUn2s>323JieZ&GH(uS6$&0Z7I^f+P28-ZoQVt&EXo2E3I47j8JGxx&4X@PhHB zjg9MBREb>`feBHeL)WT~~>gk?U$a>chA0y_K zvmaO$H?|rfk8Fk>c?Vq%1w9H4x;(F=?Dc^ht=14=jXAE2_0it0`mp7})Qc@%l`^yC3y)TyhgH(iLrVZyp@(K^tiujT zy0QN4v-fY?g>NfnC93$akqwvGGzqsTiPtKwA4cHY8_7s5=>2HX6gTp^D=2OHgVxl? zGNe~^4%vcARHB2`*q0--NOa&a{~#4F_Twn-)hd)9vGc`e9pm{&pkL#+dfG!RUOBfbWtjWh&}J;K@yjF%`}* zdHa6Ip^*1iG=yIfu}2IXxZ){8!7lmF-Jt(^HTHzEw>LUDA09PsAdfkz`sq?Zo5A~~ zTHu1T2s90Yt|3aqMm|!0{qv~BZ96fkd2^vPN!>$Cs>eLs)G{rO8fhMs0KoLxe}tQcSh6zt1gY+`@4;RP*(EEXZri;zOYSFhsvdo<`w zphn@KoQ%Pa`B6kjDhbr?c)FP7_L_p3=4uYI@xv_@`g*F1>zts|V?38rM>umF!P^z1|*2R2ke4ZG*m-3f-8Y<*0GhmIE zcLxHlc2cDRw+?9>_B(C(xC3S)+|;4w%f6S`xXH*A!-~cBX=K7E22mOwmW$SRrA}H@H)^gZ$VBWr?Pq>;=1gc9oGJKp;k-mNOfvtCIcSb zB#|y~HWk}ks~;`1M-+>t?4${xS`tiZO6;_o0^Hpzb-XLjbK2g+PVAF|*eCB%KS^fu zZc*5*E63oep?tzEWP&?HYMWl`Z{+Ye3i{Z@Gj@A?FUE8t8vD1AQnCMT4yV=jiq%Bu zV!o7lzM^y6qOT0(tN{8)D>Ql~V9KHGnW|OT1VZT}H@-PA<*CjTJ?1ivma56i`+AS3 zPiM1eoA9#47M(;*-fmWg-QPED^yU+<2G(~X%7ED)=z4c<9asFz()@ATSezBXy4x(< zAZ@KXB{zLO#^{i8E0eAIi*ib_82rf1?d`}?Y83uMZV>XH9p$5WVh=Gbg9QadA8m;^%BDQ1@r!f9tmIxgEXl;>J zev!pFXQFJk3u^(HW6VR9N+Fbv*-K zJ)6lAIM;~5{HKqU5GBf1M)MwRPJcV~Uoc4M>o)rh;w^+QS3XFFxa%~4W}Cd#-b^YD z5qWRC@MO~G9Q~G%xPNja4^QmVJEnAy>hDT6Xi+t`@G)MC*>)v+HK`h#^os6z&mYsu z47Tc~#&NoJs0Z&@GBach@>OO184uVkH-m@_XKHaf;+s)GXHi&6zeu7j&}q79Wxv$? z<`{lhG+t8W@G|2jdm^K`wipZ5YVIX88D40?UO;`+i!?mtu_p^ha>Sxog6dSNMDIuyj0O9km#P^d8uGuhG)&t^u`X=G zntbV#-tB|a`Xv`5FkTo9L#)9EWR@HB;VI(}oHncvFW7kS(++#7>805HK8+8b z$B7}i=R`d=8X;aX{CW+pmKJwt97@PhoG0;~uoROzcyazso?-i|cC}i>VA125{R{BR zP4AxBjJ8sAZk0t{MI+CAf-x9pAR%tc1s|3vu9?%2q47zhH^grx#7~l`(RF#>?H{#{ zvaGse|Le$aOK-vay)|{tbA8FsvX`@_uZmBO*^crzn7fK9zWK&5&6lpe87`fDARv_5 z(=jETP8Saq?scK-xc+l>QtZKw(ASbnR&a~gE5iZ_yt#%q zMtTtM8eFga`9b(X?K$uAl2vQfCQh+Lnqv|{?p+KyCDuVjSW#n>LL+!Aaj(({0)Sl7 zAc4P%k8;Bm3@R)R4nJizJ_&5HuNo;p4P~-VWIAMs|aG z4R}u#b&LU7{xbf@AGKwl#wlx_;BddZbl;v&UM5mYu=8=ab1jFCdH&^pRr2PGZ|!cV z1QoOIZk9d|WqJ+8`-8qql=EV}_b^)skc9$iMo9H!Wm{Q^Z>P)dw~qqS6SPOoX_B!6?AIZz)XCvW$( zqf}FPO!F-4e_Om>`B3(Su7&UER@w#zoMTTr7b!1hj?-g)M|o&`$T1ZnI06{>nQ8Ni zL@TxW&EtIH`+VLIUBA3Jxr=iaB&WkN0UmKu7^p>^a=Q zxds!GR%_ICMQ7Un!eBYYq8$FK=1ft&@}0HB9(7H1IRQy7bdiw4QZTqUSTLwaKijyk z+R-^+6{qCzbG5p9adfc0nPUO}JPEHS!t&l_RoZ8Zw+i?xM_a?(;BVX#r^inU-E-P= z%aO{Ip-F$pWpr&=fHnWoqsv8+k1r?kae`zEfGuRUkz z{519}tTm+?xc2;Auj+9ZBFMiH-2C|G{6u#&@q~|ipMG}5pdn>vXik9}7~Ort?4|0Z zmiz3$!ykrMn2u*HMpREb`kwkm#e>naVmz_y3}C1%cI?220M(J2l6-Y9(0^v`Q{W&ee^VDg{QS{a90VDL)W0QnWp4$eBj4U!ki*adM1-48ZZv4^dU89<2&kAp7r?rjZNvvQO+T$eWyb z)~@LpdXZqTVPClIp_YTAFf2Z9eQB_JqgSB(v7;tPd|lCOMO5fi74WSC)x^|r-ae}7 z0I1~&!H~0Dc*hXbR=N{_p~3(oQb&=2FznGi;ujlox(b^~vNoD`AZ7P0@|4+>HC}d} zbnJRgw%M9Pj_ICRkaD&#sg7v$x(~)TxbKigWLv$@rpy>ABMrTnEe(_*owyLghiRHF zdZRo)m(qtAj#_z`uBVIP6ypU_Z^r7Yi_yS0NtDr}Pw!oHCx}6L=70A|9kqDX5rneL zT&sIr$G6jZUti=M`M#knwDo;sRpN*DO#&|b{h@#GX?z(wo7EAjw*$Zyj ztS!yc+1>al2Q?;xgL>Y$fb-c?V00Wfwy*IG&Fi1nm0ljvx8#RzZ#;YIbAm{@MTDxB z-6|cDsEcMZ(2qs6Th=Sa@aW!~j^UvEbQU4hC<<^Y?08OoHNG~c2AbIRrbM37K~k^M z3*Q}jITK#5pA#!Yt|Ouj|9$c0nZZ7+i^ADoUmiwAx66)CMfYq&anCbrxcJk8oCI7j zZ!Q5BQnp+jb}bhR#RsOc$wncmOXWuE?jd zp;N#MfmnouyRD3?m3umgM~sD$Maapux9QSfn0%YP=Af(DF#5)({?1}@j`gF>A0MiF zm6VIpMb%gALi}XTUKL}9{l?&4>I>CtC%j*Tl#Jee->7%4q$TI`F)c%NqdA+p>F*oC z*IjhqBBS{BImOp}@i*CMIqiE_%;GZIzgUP@!2D^#Rx!gT9Ce0f^^02si2gAc7}govlC_ z1s}4F+h@#e<&i8mFO??;9PMj3?)d?wb@)-;#DfMWlwHId6eq(g8kN(CXT#Dzj=pyu z*e#$WVbwx(g3f;)u=nVv6*f-rjHI* zu~v9y=4CPAb3cBTv;W^k@n0rWb9pJ>>S{%^<)2HnG%zEuuP^sY?}&r_2{kZBH@f5= zUyufR^bO{?TWqg{=b(C4ATyCHgxUf?wnqTc(yW5k7Xz;GQb9Bp2FeCLt;6JN+UZaE zRK&8*%tZ$#O3+rm4E-@!T+F4Ul^#3m+Yx8psj1tOb>bV{TbAywXO!cFDCGgPN{BSI zW!*K~16?PM zhu$XG>1UCu0u`F@hhC=3U$lF92)d4&VWBDWvpr_Qn*66f&Lpb6S9D??F*+eNll;sY zYLK(q|EWd?uTy9;IdH~cw*`3xlg&9$&48+!(E@+&5EBWI*4cR~v|_JVi25c8qeTy` zr)ip7OM8}UIgMm9{~;4d?`?ae=1npeloe!r6aI+9eylKBc_hJvu^Dql?D3p%uSuuJ zLXWDl)w`h-^jiX;4%Ba&##9NCOxVSrZWaq8EI`cGiEWDgL$U=LYIN%Rz~*q&-mfQ?brAul7q`D1u@X z*YNZ95PpCPovjK*9p81uEk#3(JJe7js;d0n;&>n?C~RVfpwEku4>i1i_hTr)Qvs&R-yxrGQ6;rj(uiV%5_A|{CQYnX9lwUjG#eptXU%`tPS`H% zNak9VDihvl*gLT2Qhn~9!qKEQuEm*SBkg(C8gw*etRVe5w&`TRx$`>rJ-GHR4e#bW z3HOrT8GP9|swJT;=WjMvEvlP_P?awj>SjEPtI6KWXkD*)<~Dv+%62DNaBedE=-s8~ zf9$)Q#%$2IWFRFsgh@B6_r9$Kw2QsNQjXt%1sd$Pqj4Sw-+lPi zK%{$f+~@qvtz*xlXCZGx zjVnR|PP;i)NSl1pKOGrt5@EeRQu$I#z3*PWi11kilC>s||3i_8l@4VA2=Rc&v68xO z06dwhK!%7++@4g(F`{{z8~JwOsfxHG)pZsWdhD-TN3O*k`Td=v+snwr1TJlya;L*& zQ(^JKxW_`obCCM{Fp@UTq>aZ7Y$1nI(>)xR104uzQ((eSnm$zB#~wW?fXoRJ{NEwb zsv7CQeQR#0>>>0=>LK1d3OAaV(wA{@@lXvB0t7=`s2)eQwA?ztM`kg!S+EPn)4Z5; zS2C2SpA=}4q`LxCsnIE&kTjf2(sGk}QY&TVo}9RI;84uTe}THL`7&RaxKqWl>DzP; zizEIW&?L0~Gg& zRE^fpp1YXqPT;%Sg~gi`8AFc~PhX!4@bh#$w{__pM*JgQd}hvmBo$hxiX6Kg)h45` zgGYYFT^WCixJ&U5Gw?V4Dk5ko{NZkNXB!bNcGmR?^eId6&vD2~Cp0S6cs<{^rY2y{ z)+DUZqzV8va=T^N5=qcoeHywhRhQW4n!ko7=b|=2d$cr zK4t0m`04X|QdWNWgDP)bk9m~n+a<^*BJWYrJ{due1l;izxAkcB=N0q^0s4@M`zryO zYU2KWMdMOgSyq2p$^5=_v-9k-5Gtk|9SA-mMm13N#N~V5m(*eR0%1*NGX^vn1KJro zsa*8~6hau8a%|f}TBRuK<`1G%O|srbI7im!dZUl$H=oAmrdMv^>Pu53zTjrc0GB-} zw>4~L`fU2c!*N7golGKZp4C_i&`Ji*5l*sWat%B1ATlxD+Vr1i`Vkz$N|MQ1xZKQB zMep@XxeJi~ZTXuG{{9TZ5e)L-SXA4wD`7)cZK}xsG>{`5{$i1Wiz9~P?nd^?_V*jE z?42drYb!fOMMGN#p)bdw;^9gJb7%=fZeP+RhLCX9n((9vbczCsdt!Ss9;EfdbQ^fV z9SfW_07_E`*Ql5bCxp5ArNP=^Cd4lGB+{lix^3LEUpuK zr58ZKNGjJzs;mM<=obDv9X{@WiGK2{F91(ldXt0hk62lyMOnlU&bDZ;>RCBaLqw5| z1*Qh3q^1LeaObqZ6lO7HC>c;%65(WH{iK{YWNJI&-+m8w5>^OU3$Y#d!6&WP;tE;v zh9F~VwMY_VEF|ogfFfaXgycLK38kY?3}RN~!=rEB&gB?y52g0b7k zA3v`GCjCdb@=I?K4naoP3i+=~M$tm(a~7l}CN;9-(s;Uo-*9T>w}2qb{;ynNV z>Hd@Pcy7$aj(BPCJAh&|fTCGw&yTia06bQ}mX;8U2-sB+dBO&!Np=+xQ|;f!BHx;` zDVFZ$MIPm_G(nH+dq$a*s<*kgzGzy3k&qO7P#1~{+S59Cp#bts`F1=oogk|oGZeS5 zehWIPKI?{lVTeATjDEvFzpg_(>j>g`Wbix=B}|~dGJ|WGSh0$f%cQ`Ku(V+&DcUej``i^Dz5AxjuaYMbo)mbToHSC_2J4@ zKY`i^A393B8X=6jKa23g2=8`Woi4n5*Nwkt%DM9L?ePZ!s6Zz5!FOnTjN(#Eja-GX z-;)5jNhQ^V3`K0LHT?e1nO#p|;82_3#}PhA%y}-2mE@ke}UJ9z+*u zAJP3EM<|7Pm7mh;>akjk)n)fw`>Nt}VZ_F*;c(e0hX{bIfPCA!m_!$!rr zF|}{ct;BhqKls>9{oYoCSC~41n?A2xYV7UiTZ%Mm$}6(Sbw6C zd3=Jq>`oUc&1S*HOJFH?tTV>5+~3nM9juKB6@F>uZkxdVh^;HOX0R? z3DCRA-jyz$S;t3ZI*tRCh_<>mdjr#mdo^zYIVLVP_`F3v}! zjEhI!Z@VXgbWabk(CgDub@=I05MyNjL8_f0h45MbQaETo)B5yDWu+5>&KEJzSJ(jO zCkjt)U%$ViCfXMK`Yx(1MB#*oT0mEnM&sl0(5V0LNT45o35s;$Kx2#KXWbRgb{HI0 zHs17hJmHpKT7T)iv(mQO>Cf2x5mE(8QuoaSC-C7Qy^8={e|*<@>EeHM2pEtwpXAa3 zup?qz#UQRLV9yn>*DPCa7i`?*Vmx8qSa-_Pxq;eu#O(#l=0Xp(g?zKl#TlvUcBIFh zUW^Sx#zr25Kzd^(nwWdZ2j_%wcNPl(hWECBR+B>wf7yP z_w8&#YAfQR<)M$1=0vly^(W}8lnL&o#aiY*b~qSS!^>O*I}t;UYA6dp1tu3iuekYBHhf#pVOzE*OgBj1+SzM**aFlqA4v(on+k4l5(e%l zM9zu+04}sQ`VcPyA}>CPz&v@Wr*-nyUpLYM^)-m16n+2I7}Gzs@0aNtL`a=`(F>Wf ztvM}F3|nz{jO~1oe{)({ZR!cavsO*x8REy3Do`64GXHq0`*AqM;l?e)Zd?1V!7G{4 zHAlM*!Z6~63yOORpQ@{hMBo;s?VXuODZ&}gS2-m89NN60h`kAxG4eO-+c+tW0o$%b z!$}Y-#)Ve7Rvcu`j=tqv1*_8MUU(b|i@6E^Q$@1bnG5NPzNRNj_z{hxzs z;x3QF=2ats9ndzbCrWCICk4MHj@#5JbhsNWy;X2pKkm?N@JPR=phywtFZc4Dot&nL zTKB7P!~G>Rkkyv$sWjgJ8-4Eu8$W=|_B=rJDKI2}#cZ^HD}(6_%#e|}o^P=SV%?+7 z99vSad%nRwr^xl*h{wwq#r<(MmSFok>mJ%L(igDJ3OIiD;8V}0Xh-w_{~*j3eWL$q z=$V5XVqX~_$A$#Rabm*7t~ZIt(MfmRl7G2fhVQ%bBPh+nos;#J>ln;Myz{>DeMbP! z*>ibUJ{gktX~OX7`AfQzN}Yi6#mNI5l6u>j*I~(&$xRE|u_iNIMX4U5RyJPM?9wpq z9`c^K;Kr&gQF^_0ZVg&RmG%USmk*~|^CIW-(GXH+pS=w=K02#f776(c!lQNXzXIbLVgk8~W`w*;-eP99~ zlx;Ag!9f~4BU3U{7QZ~vkV(rda?w|C1_^*L7mh}H5*G6GDwZi%y65aGNaT?{X9nM57jcW`BV_v zr__bjuiB7X6Q&wn-TD_mL^HfZK@q)+Ui^lW9#9fF$%N&M^2?D!Az)sLti9}UcC^YXj@>SiFD53vrl z_1`|r{c(So#E}%Us)0&H3H9!@jd!y?{ZiQ*tpNki2m{6C;}>ZeN-5F&|EIPhDQedT zatz?Nma`ApN?RjMHZOwgjOTY7;!WA+C#Fwad;xi=RjOGqPRw40OoUZn8}TPoS`IpC z)D?9RLIfiPWg&NZ^zo;{+p%SaEY=>*wEn+_8M6hm^-+^GFXd5_J_cxX#uBG&gPz=C zBJ~DfK{*nC{zs3IPZa#gRrox9H?3O#yEzAGArQh%Fs*I`mV_Ojjjeu@rfEilc~NX+ zkSrbvvxdpQ^V*Sgej1F)K}U?(!`yj!IkUvUwTVCAU-ENQ9{R`<(;TW-(zGyva>rUG zovLDx5suDkhMMB$7tPRn@pB`pE}B!l?Akwyw>q@m@TbfkZRf?6DHHr0xw;EAh#2V{ zoiG62a)B({*%74pN;p2e&}V0IdoCCCGUH&C0Bj*kl90+qhUh4lt0>T*_Ng>6`?2z( zOgoW4Ef;!H*03xy6|9(=J7bnw`3gB>dZ&M*p=1morO{NVwy6T0Dy;gDiaKb%_&Bla z$^Pz|f^!@Fr=E`48GkJkr+VL|p`xR&^_=<3a(DIU(|PX0U&-pA)_L zHd*Y@4$i1Cj2_6tpwxN~!81v2CEW_RXB|-KGkUf$Q`Omx{~%6*mGQ%{G2N_A1hdDL za72qssTj--+1p~`2Ey(1b5sU2WLgN*o1iK=Cxq2yNaY**Q7*s;vDaI0C^?O3OS26$|-Zm*D zX}Yn9DmBe644`xwCLIi9vFOcg@b!*%lGQ4PC;R|M%nf0gY06M6m}F7_vuTg!JdlII zeH_3&=#LUM%_52?gQZQy5{|{#VbV25!p)Qk7f`iF68j1Si(t7a9<+bqyHt}xkV5jc zEb~@}QIS(w?&Ms$Uwe#Qr=UUpgw;bIvDIlp!&7F$(ppzP|vodRlfY3!6snBt)#^QBqI47sZWyU)&~KQt#!q}H7a?SQag>L@EZ`a#vw(WV72%s#w$jgnilI78qjI0=7*$ZW29=jE<2@7HLyTYK&P z=3H)kk8+>}htN@}NZsdOzoI$mFue$|E+5Q(`CV$vS8^=(L#DF)Tr>V}8w0y5*bIJb zk!x(0XO*4Y{l~ddwwKr3GK7&z5Mi*u&R1s6KV-G0r3jm

    M#I|PPIRI zZF{jbM_KKvt)0skEt^4T=S|CvbdN~M+%&iz?ovb6sRsN_&CvAh&zKCK`Ir*JM(YD1 ze$J)~9vx?ULT-)QC3Y1bz*$g85(ZoN;8^YBDk?QFiZ4xy*#UeMwPL78eSz>70-q2I zAkw@Skq*%;^sgurG7JE@ILvZNNxd?RMZ@XQnizrLPeJ{oWj89I>5a!hu?kue!iWW{3EW<#7tNZQqnX4$~=E--@h^`M4 z0M463P`IChS6s1|R7&Zl!Y`*@-yYS~HE|mGSy0vLd^f?*? z)JlaZ+*UQlMj2Iyql1Y-Szl7dE#tS*=lh1W!}bC)2&Q*GCJ1bGAYY>_OYU9X={=RZ z6AqL#p)hUHqPm)9T zrLJoL8vOF!^ojX1uQrk7w=J&9^#Qm~8svp6Lbx7?MgtA9;1d8)KL8i6H$QRN8p+(YOkI*il>hMEQBu(DG1l-hwc(%I!6cWv>LyQH%K z_{dM$uvw$FiS!sMH^zah-C7&W6aPC~JZVd39)4JV>DDP_L2jIMW>@bu0=iaH z?joq646N$Gyt?e;m&AQDj9+BBPeC`6k zhK!1h10=-dKIfI6mjbx_5ECD$zxD&Q%CG$Er^-?0RV3wRpj_qG4wl^FK2mUhc-NGa z!j!vB14OF7if;aUQMDnULu%vZw$N!vzh8k;1se3wQB(-`r>I8tkNRQ6H3uplc2L}A zN`4mJ({9mp#v1ok^XVK)`$IyDq7+9`tHol>X8I(*Gh9P*WCJo1Fde&>$&Dl6#-g}k z;hiyq`s2vvKpN$zAowae(VVR`kmwDoMfbKhxD{?Dqd_tkf;TkdyPQC1A}ngQ0U z06DSIh!2%5?^}{znm*kuGP6dWwiJL`4K1?SmYm{ddYTrVeehq`_Ibf65*QzOkg1tw zcVUdZ>H6L!jU*HxwAwx)jkYefokjwc%Q(s9rGHwAk5}N5KJ}apeoVZh9XpY(Rv}Tl zNGjd3n<&7=@!)YnT+9SHri1H_$v(H(&hCUlj%1u8-eCKQU*stpY5*dmv*EWEvya@k z)Q2Pp@L5Hy+=IaBRMypERxa2S7Y>NC6r#;?7aVjYcg6PL{Q8%>dLhkhfC%lIYXc=4*)o<_4<6&e}A&G+w4W$oP}Ct!R}Oz507Qw~HR^nr&nAc!jh z(0<=}^A7PRLyHoPjEok}j9?;P#t*-xeD-C|ETue00re-@RF=qEA4hvxeJS_%QK=~6=h|C6`0w2JXnTE1j1^8M==1X39-Ghz+8u{-hErCFNJ>BB+wT)j;>jbyNl?bUFgsJq93iPhzV7a z38reOMa8B{E%d`kW@GcUn_b2VBi4h>M=+(%1I@=U4N*+U3jpcBO9yPX+$@XW8`*;j zI^C)%*9<5hREpPG`Vu04HUFf|P{6+2CvKhXnpcNr`2p%)X{^20VAl; zD|uNde7@G-a((z`Wm#DK_Pu*wv_D!tPwuG=;AI43GU8|Ldqk+tT`nlW7w8&( zmg1|+I1N3m2Jgtofo@}ZvoDEcOiC~EPl&R<2^{`~q-sQwI{`;z6}bybC&lbPh!sw6 z7u5GI3+roYbfp&wZ+Gi^2utr4D?YF6W3=jV4F~IVtA06Ps-+F>0*eTI%1`r;YHtCN zTFjr0L#nUm7ri2HT#VF{?KXPORP12soT_RKRZzQpq&K%pkEi+F?|RoV-=M?5WQFay zSL|tikRuz|bqX()l%g(A=#pQ}Cuo;?o$l13MvWiLI=yOLB9u)G$gFoDJ0IfOD0v0; zT{|Imw?SKpH0&$|;xf%FyOsZ9G(R!&>*_5Uv54Rp_F2ZRN$q2`e8W21n&j6DL?>LQr9Sa| z*>aiZV);rDxKaR)sIaPfKbS^`eAWCm zT95AfP1mYFjMjCp#ErSfsmdCT#`No6T{0?7iKGwKd}6gc^;n!{=^kbd`yDrsF_aU= zo{m%y_v2FpEIpxlB?5GAs>|oC)OO~G)GGTU;e_F&OC17AGW@>U#x z=P!3`?3cnjzwaV1(4j4&FPE@tQaX`i_2<%z3>Ep~-=}_FT9(R>H2Hh%&AhXZEz_EZ z60PwP1#YtNpO0)b{%&Kp15(RJAD>u5ejVQLR&u_pbjWQ$WBGQX*0+D*B9W1O!DzA378j z6%~u`yZ3#MV}HPoaX*_o%JYr`#Of$GZ zh-HQpe;pX!bIh2!Pk!++6-(4FK>(TH^eTc~m154?Q0{=9@OE$1>iImvaoPq)GX_3& z&FJ`#oz8lA{;VQ{DW zzyU@~J7m9^|6zBYhEFW3P;$f;Px70H&^Qw`DW>V)(H0s|lUu1rdt1fex&-cMhcbte zWh2-A`VS`~U(4B*YYphsPiapR1}8Nq%<54(Gvs=z&W2(!RcDSIlanf77-MI;K`^y9 z5VEMp>hzJH+37q*G}~!UAqMRM&wYG1;Kh? z)k1u?r52X7nY!&Q>XYcS8Ry4hh=u9wvM5NxLL3FI?9~B+YPNL*30UJ+wI8A_im4A^npETP`mATAw^z=Jdy_v@u%X>h5rZ{=DLX4#brmJA-wU z3ieKS<@!wb$BcknT?r@gdA*lGlev1!9?xv~)L&9f(S>s^CILHZWD4|X4=mL8dBRBJ z@wZpmxKpux9U2~5iQkyKYKN~)c*T0z6kb(XJ7J_u;4E+m`w!g>ag6GyNsZl11yZFF z0RvFQ5-JlZSK?UipP_c|3)=9pPBFUZ1Nq!V-3YF!tnLc`tC_mL-?hUVQq#naLPw`* zXZb9@!YU*BZ;qtQH%nNa?PY8Jy^itx=ksvrtHl*4J|IyO_VRoI(Lywwm0pAQ?)Yp` z{IO+qq=-9IMTwbx^q3+IZ1mdZOsEdpW%cRQV^e00m#8T-2hK!;S+loP15YYG!eF+f zcrt@0x0$N_l>8O7`&4l-Cr9V#hi~q{o+V1t_}5YZ$sF|6mh>6AF8L{n^m9bqt9cG4 z?p@%NhW9F19Tr{+Rq*azugn3#L}JK66}Sk;{z`Kk!|b{ZzTb?WO!i|5#=p%}5OTp% zQk%?-{SeaEc?vWB6iOS0HaL`5D*nX~$)*|aoHMi*Z(@jwW?0bGqw7gbXcZZv0O$wV zg}7p)iFr|WLxgessF9+7Vc_aJ_s3rr^{)!G#ZWP38)P@F=($_Cn)MW7?5NQiKVPEb zE%D`M*u8thYT+9o-oX}NL>O6cY#HLMU`jzNJLX?qzLn+HCoSAPR&r%yoyTqU8t2Ix zvwaMps_IDb@L-Sd_mZKZnRvL_J`m$b))1X6_c@YoBo*dpC>k+Nv&+HPmpL#!PXFm3 zdWygbKs$FCbs?k}yr4fC?3;m!jgKFiRcz83_Czb3KT|0x+o^BZ!BDvD2y}R|67+{@G-eGdlf$jpVk>}TS+1(@~PT;7Ny?9Eb3OedARh*4P=^ZLs zJ>l@Ll+E!5(Yj;tVQDOjA$^Q_20=sBQp4wPAcKymeiu8!D%zlrPT~G+K$Q1f931F3h!{DJIg)m!L5vB- z@-O@n`i6CtGWlyPwD40?*|F9+tm$Awfe4}4+jfw#TLq{rRzcgp6B&sAYE=VWhD4Rj zMo^x;1JSbJ>amQGJMrgL&SloSb!i=q_RM!;yj|+WWcn?1Pkzbu*2#xC?NO#CpvB|3 z`GQQ%eiR4`P!8+tuKBAPQr*RO<*}41q?qFBK@}2$OsR;FWjrkkgzq++L!@^&@C`hO zZ*N$=@52Y~budVfzM{c0u(P+12btEf3-k;c&c{jFzrodti3jk3V+GVO70uc(%&#~|B64pqT zX7tiRzYjL;;BoV=lM6G9WEuf)J>oH3h)Nh5l-RSfv}r5!h`dxUz6JNWOBav6dU#=}9Eh|Gs@#cQEZWnim0Or|zA^kwMYVkRbwB$n|2#_}_2?O%d*7~c z>x_@8Nbuynz3Jy-HNFmMdWMa2&api~KJON^HoVRyUh3|nX{dU^sY@nhv+;7urK86F zRMV80kB{UP#?c&dif($8-;1Bp76beH*(DSypNtHGOk<_F?qmFx{IJ60DbE@wFm0J4JgP>vSCPbSvoVOeyCc z)bH9PY)9bbH+2rzhe}>nPNblUuw4G1!Ode12>6FVWXx*q$zy^wRitKve95OSw+HI} z9C@W$Xu7)8bhS2>B!!q{ylYAn#tG@9Die(<^CmP9baUf`tbR(HL5YyLVMw9f=sWi< zD>royebw7H*71X4>Don%HgBR#>L(h!XAS6)&`|&9q)x>BHU>&2sdm-!^7NdlHkbz= z{a>yD<+P$B9pspDZ1Lz60Jd`Gz|>ta2c?*Ezmp6juz4Hks6e{-12U{&crXV5E1(k! zIS*Z@B3BE&_spZvFrI>(FUXu9t9A}j-Ep$D+YCf1_F;5i;Po|7AuBjv8L&(?9 z?JQ$S@E2b57bC{izS%uzzfe_M4lQxVJ}(;jFh8hC5DXjt${{RyAzwL;ADN|&PE#^3 z0rE|ikYay8vv1G^D6l3XCI6s!t`_r-l%d6WwxA2q$uZrQvNchKbOyeWTqAC&PMRc+ zF=quC1k)Wn<|S}UYb@h^TlLj_%RR&(31wR3`s~dHM#mg)wp%Su9@o4}Nu&W+&g0^j zUi8jFd`kdOF90kS01Y8mw$UrwN^FUgTRktgtbsTL1sD4kw=#Y@^KBKsBO5Y-&ERp7 zc*Wiw$4bq?)=hJa*JEX7LUOn0g#L@AJk$YVsS> ztP5vrEI+tl@P_GvU^F0BNnj1y8UK%=QHI9y%!gUH&Q0K3G+&Zc#j6OQ zD0M-&U^)(0b+FQ4SA?t}Q&D@oC=Pu?sGnboVyD(`2c)>)d|GYQkF)Eq-mtd6>+si+ zvFDxTTK)D6e?8l(lxQ_8sNY`|$D@0%sqR4y)~o=F2Vx`0+>by62bSS`+k2?-gssJp zjg||mUB}m_a~9r-upV^vRb+e6Qv&E)}6MqjKXdmGd0or6Sjl&NX2-(b8dGLo!PXa!G0q zuLy##`%Y`MjGEqLi2X64{>pobZp`1X(q_L|i74JdA#%t4I`;j%bRTOdB@^et!C5hydmJu< zO0i=#O;bntzZaT_fJFy>NA0Z&Ziut$gUiS1iYKuCEAauh67&C=0pH%8HIgzlrgGO^ zvmU#p28qX-&IcKZLAD5{cQ~$|QL{#4l?Kg&KjKVvch2et0!6445f`#ZVt@RD`HNFI zofP5os{8>}Inhz{pis)mCBJ&SAMkMY~B+i9i*3nWKlrFN@ z<|^54;RjI|)^_=xwyqhr!tDhZ_WpT*U zUUYO7y}U!Z0zb8Wo5RcD@br!!J;4cb7PeM{tMw@wk-^)m3-%A1-cu^iK(nAaum0!* zHMe~F2cF*0-?K;C{GJlE*Hy)$`l}=A_djgI4hDYg78n|5H%cgC3hQ}a6fn1Jf}Y6m zrdA?5T@l}0jhn%T!(gMah;(^AQe1x=6*!bS623gud-xi~rW1ih(be=LB$WnSxwQ9tmx;2xY_63ac00{( zS*$z~tK0+&*@``;m5#*PgG-&0K~)${5{j^jh8UgH(T(!3I-ZcF^=OL%1X|ppy{m zk-H!}-Ro$9976e{oL>vWtX;_fE>vv(*anbp#cTi&G-3$V7>OV%z@SoKX@?w zu=GRZn^dmQ^f7~Mzw~+>~}AGlDNM%lrziq>*z zfRi>*c^Ovgo60zoMi%Ltd9nLHBL|P@J5kyJg`&E%E?o3+@iG z19`^W&R$y(e{j9XKj)%ui`~cPzHE9_>6E>&#p#|YfzcbmRCkOE`st8+;@`9~^C}Cc zcznUMy60-VahQd7`jT<$PFnklxz?&bd?~P^@}q#)fLEZeC7NbgTO9rS(!(Vd`lZ*x zue3F@I7XyRh4%FKi2T(z`v@^s*n9SyY`lH;0h4K*Vi<>s`L`ae&1)n!#QeeocOAO3 zP#<(WCa6--Xz@%+1}6Ufv*Sq2E6u_D+BcDtGZF8)^39%U=zD5UceUQiRg}&zO$G{7 zOY`h#LNk!i5@dKNz4tZ%wSS~wbF5$O;rm0XB=;x!IzLUr0%*S)e#7zbcgUhc=z(S! z4NL9CF5`sk`URI&*crW-o&RWj@yE7h@h7kA{o2;t-|x;iW)TtL8G6?9rz_%t80u*v zPw0)j7qj{y{j4#ox!Qj9K!!%M;mlTBqfr%2s`CQJ!Y;8Tup=a<*7l_BXIwDn2*?3A z4nB%_u$T~ck`-6re}N~KQ{FwC|JDuO0fo0U3>^r+{3Tp6b6w&(2U=j~v#p&i>FhXy z>K|s&dIS^=s%}`cUw__GnT2ks%Uvp<)R`);@ks{A1X>UqR>U4Y6!{fs`l~Mg^z}T7 z$Si%uflC@mmX-A5kBs9>y%vOH`^92`id_ujTR@TCkD}xfF)BkXxK76tpN}0R^+~)6 z)gWEBS3h9x7Gz|fzHu9r9X;ska}(RniZHBM96KJubIIGR;aS>P{WB%2HO1;(luFp~ zwS0*;T3kWy7^V;+FILr$HxXUd!Oz@0-TDt#5bk!q90g6}Jn$n|+;!t6DWC|HSSBA? z)~SwVjg_)s%f^D_Y;a1>b&v{avoV~4Nvlh(Kf}gC**?v&_RCOaalSk{6K7pGQBr2# zXk6i(nju)BebbTOpJauVH)pyic9{(42Yy_W%MQkbb|rjfKhYLhY*~ofE~wW2@v-W8 zwD+C(D@W<7FFFHeij*$P+j(gE4bI0J#H8^GYx>_~adVBRat*^L$*XfIaJ2aGq@|@! zFdQSUAGxGhSZ{{JDcZZV+tr$+g1&v<6+BTH8~UutsmbkeWnB1+JAR{OC$1l>=D&Yt zWv1E$a`COGR>t8hMIX*bEV#_!5Fv2Pq=6T}4+P1WlCz_hM-7Z*iWeT+9_vgrUX@_Y zf!m!1d8rz{eXPQNU)a9=6|ldqaYp`sN18r>sZS?0j>N&JKTEIIPJ#H^hW16cU((qYCZ#iS|8g&+N z6ojW{5J#^0X9P~(4ysv|s|+g19H|HyBPxgmRw3V4-RjtTR~6X4Ctw>hVjWbKFk+mp za(hO{(l+>>aZ{Dvq-YZ%c&t{t(x{f=tmad`S6mTP=?QbZpUhu`mrfUjp?#MT@)-SP zeQ=)sTY6_MHx@55thWElHhoBTQtIK3m0~Fr?Lu}10k235`!;w*Adm)4@- zO3f2jCaPMVm)f-6er_H^(A|#Hz7;hR6*Lnv6=qTHoyc!trPoC>ML&3WgfC2cGBCUP z_}?T%09+!mJTYxlOz>%%xMJ~Mmw>(gY5-1Og$YgjYDRgVkssJk$C`MeniB_N`kB%VBS~k8TcR-Fo+*LHDHke|u+?9BpWx5VV?=1(ai*iIK@TahL z?%m7Ylmg53l4D7;K!Ij1_|1J2#2u%(N%XsNRkxHZ@-1mDVQ))D;Bxj0(l`)#K2fB_ z*?E2?7Yf3lWxy^nq)?f|O4Iffwrkfl&7OkDQ)tX~rXx#sC=9AO%Yh{Ug&N9LB%L$U z^;;G5_AU%dgw6Z+6?L}XDzLVVF&wE*nnU?0)~h|*A6B1t?9d_Pn4JSG`z${vWql^Y zZ;0if)kn%DSm^Y4~}WAH1UclF9UzdNQZq%uN3$S;$W8{Z|cm2>2bpD(fwxO<-vSk#PjiwWgj{OAThw&DLNeU?PPg_yD zB!ORS7ffIuQpG#!t;O9sIlY!lyANL!D|@x>sMYlNjP@2)Z8Y48CafoJ==gHOx(l2Eo)!!9Fc`obg?oKD>6|qt4%Xn_Os1U93;9C6;5uf`rg=NMSNbAUdRGr zbDCA;V18hgC35SG6rXYyINPJI4tGmGPj&u%wzu?p*}m(|Y>Rr4hz4I_;Z&$Ep$&~Z zhox_=ll+RNjgL3?qww{egyeLF$IYol)fDFV6dMEp0DvYj)|=|r9!y`zJ>g7du4Jqf zKS7?4rOX0RCGQLfhn%RA=Y*S4Y{SI|Qwz*YO- z-s!xo;{0`e%jqN5o3CaI+~Uh`x9Pul{r)9cueZw;H>MZ0qopdhR`eC7Biz24!MFCk z_dV<8Z#Ul{B@K$tuwnWr97ZkjjRw8eNM~#&*W@frBcAA#iE$8p|30dOt35Wz+_YKK zPcNM86xypm+6A56ee`NmJ?ZovpD1Ox!3LyhKlfAeEKT6|l)F>rFI?il&TwtCLW4I! zDE>~&n})N0(nMMqXfJ$KY8X3(;IUXBf`0`yECBL!k)diK6qMJj8J++{T9ZxqkF!~4 zq5TLh^nWgeZqolcG+J1qQ6>(GfTuGMjV9%V2Ouk5{OMT&N0ZetMmN#t0 zMC2i0`soJ|ln&_}^}Bwjks}16DS8UW+hHkh&_~7sNAO9*<aJ+V!e+A0_ zstclUMNjczZ2O6*L$i1#u<-Y8SoqfIZ6W=XnMvB|(6q?w<%3V(?w_$wwAa446#I*T z+*_T!uv)of#(&&)yH2PR*y>#{M~-T6A;{^*Kb-Wg&7hpRuWG7h<$pt~4w9fYd4v?T z|J+tI-n+N=q1x`#7bENSS|OQ#d3#x9aOOwpt5aB)Pt2Yi z26_{h z|MdJcoRLN<{MJ=)@wOu5-ZOG}oJGWmA*w42DZKRj*0uZrDGw@?()*Z4c^0Id0hZi3 zYxAJJ8P})^{p2e9-DvNmyw<91eXL>q`XzpnKfCOoNX~%hJ;3&!75Ntk1pvP}40)1B z){I?wEVi!sWF2Nh4d|26?r4QYuaF`pwWX0O#`|CjP4{pWZn6s|(;u1~Nrl*vgQ-Y} zq++S8y@9-aUsXM%6&!eS%TPK%3xI^v-W&h20%jvgnEijl$QnNFsO7XO`}~--UF0wu zP!);prK4i=%+79HtjgmZvA*7=kVJd_d2+@=ZLYd@oW zb2tcsxw?w-*=7d@TYhP(ozKH3j`|+490*UXBW*r!nbnt#j!&^{%X4z>Nvo_3dsmrc zFPJMY_m8(RReB+|D-9~be92kCJxO*=l|xPOc6C|6#3W)uMnf$@4)3MljB0f5Wuy1@ zW_~GZM)E>?-ht?i;EX~Dm(D!90u{KO=?{PrE@UzR$fI)lkLRsYWh+wjPeh1qN1GhN z;`Xz$n}=x#`7#F&l=L~nX`=L62Ynbp@Ndr>Loip`;&T-&3{G){D$`} zjlSM14}M~*CF^KxR@8eksJ07P73lv(gI8mF8{$vR8;p3kA-$`0ixQ>vYFb(U$wz6StZP` zptcaaJXVx@nHu}xd#G8Bq@y|GBq?|-6|O}y*WEI51l)QO0Ez)XwH!60k?=4!pcyD1 z++}$s_Q4K4*a`qKK|)PdioGtvQofWH$s3f{8=A1SDucpQWx^K1VbUpbqXC*5;jpY0 zzYvbeueB40()m?NW(K1%zZ!X)k?NLhs+O!+iw1M&z}VOsI^fxi*>;WcC}*c=2ZOTz zJI`aAjv}2Wb+@B2b|RBSq*|WVcl#(5%sDzxfAZrVAxsNA;`@Bffz&NJYsvpD^=J*^ zqwlouGV!uYL04Dh^2VL4U!7S6%un)jwq@HY4=q3M1ir%EvF>ZLE|L{v`B`)A7Oz0U zSAZ>ailsc%@@R!TGqd9O8Dw`m3)Jz>K%EXU%fx5$i+Z!6UhEf@ny`o3$g2Y>SyZXE zIo2y>qI1Z}?%}hM86I1L9v$a18maCZF{$%sB>X-Qm!pVP^!W|`c_}rRA}6y=cWK2h z>mVx2xjUPF!CUsZPQIGx5M^vFkZ?GxCDA1kqVU=o#k<70XwzV_mJ%rqd-FW#NfH}2 z5cEdf0(>U=vDSXU(sU~(AR?9u>tSPx-dm=|hj=&2p8-I#^c^|wZPUol*Hd3fpVQ|~cF z+lSKQfnkmM+BQjk$yKYOb*rKUT*htG_jw*(*gPQ~g3r>%LpyUUe~0&RdVN-ZFukl65{?pU8dcc<`Qr>iE9^s z?q7ShvS?gSNABHM@K5cOLVGDv!RlO2r}ocE?VmBeze5a4tx0y^i%%uF0#A=>xnGD_ zP5j@KDsK|-?mSoH2T=R06k8XH>IIw{SV6p&e+uDlHorfPW`o+4!3jt$=Prw51x!0~)f8S2zuJ-? zLf#x8n?4_;oV6d=52(Q?!~zyiyKh9jB%^xs-g~gj2_kC$#hbk?OGUay?Z(qy7dhHC z@me(%+BOBQcFat$3%H3cnTi=77TSIfEoDA@^3zwE?1&*Bx{KW$o1Rd{XkrF?TyL

    1+l!nxmOS(VXlSU}nCRvw{y4DC@HZGwP_Q~Ip z6IVZ!*H+%}6ZQG*%QSPM`;C|x9Q573D;vlQ0fQ5yz${Hg4Jn9hGdOY`-~SEj1Arx= zy^5&d0;wB!wGnGC=2dUc3owy%DdM|l?m5jTgViJqrX?n|dGNn7+)ndsP1H^bx<_+I zPt@Po?0IEQr^`yG4)_10l;lS3p9P?jGWQMv;oWAXG~S=js?*oCj_w7!mu z>X%e^d+7QLH`L8%s6+Wb%Fqv~`J4L}tQADo_f^GpTMw1;fu81wVxH6KL%%XRPX`y< z=I6tkdF}0-PZ(GxZG24{vh)%c&JO!9HT5A);YyArf3Sgl`$kg92ZHk%oofSLL&TRs zFSb(iud1Ui*1UWG{E=- z#%jqv1+-}OW`!h=1S>0&UCqHh)E9U(GEYhjE`6J9CAny0?9f~*;lC)K)UNyru@$x$ zYyJ-(vyShONWI|BmO||5@i;c0i$;4LCxd5?JfUMR#FlHB+P!|qgu4}O-Tdxm4V1IeyFokG_I$wl`SBpz%e|UGY|UO+fX;}fqsyClow)Gg9A^%rQ<4B;M-oMUJ@(BahbioFZ9C|1gC8MlJmxsU@asF}58R*4#DTB_C|6p43)dFpKYO zUgGJ>rV1sbUn;-&_s`VLq=zA@^Rh`tU96*zo7S!8Y#JaDEIz3Hz1_1zApB z+y5X!Xb-6}=m415*i#d#f%9zj<1mP-qL+5_6L<2Je87zxPMI^hSFeB&?V9e?>49pg zx)0aHw{23H93poHT}u^rKxC>WN$?#h9H)2E99%Q_!EA<~3SMcdcI}5#mX5x%OR|qY z&!xlR@8e8|*vM_!dUJxQ> zeoD?xrV;K_G*Ngp^Q#}GGRUxCu%KoTnjRFw>e{8y`--%}#KyGL$;R?28TCaGZ@u8o zn3Ew=GIBYUu+h9Kd-Jznj?@VTMU&*>;;-hQov6(Y64HBK*Hh$cjZ+Jaq&;kYHoRN2 zg7k>|3HcaZqx|WCx`@Vky8Z)9uo*hitmPLrK2O;xt-s* z@s;7F7O(ip9R1F<;T+yi^@IHoI0|p)GD7Q*M(|1M)3yMh zA?U24U516z03-{g9l6jO1x}A39Pjc^HLABPC;9F%f36MhmTUS9l!O{K=0t0r8*3xV z1m(u=UU-<{G?;e!x}Mik-{24~t3Dc+#thA`KpzpfrbZ-6+jT(z6`W zl;T(JGL`&)N2vv-7_HF)@EL>ks+bw0PaP#wMr(b7`34{R&Nv%e6uC4MT9%c_7E2Ve z=B++sl{WIW`kt*DsN7|(8;mb`%ouFy3r^?E=z~w|geVJgy_F{iQQ9)Ux@W_}Qyg%#x%zrDVn3eI`q9g83K^Q?-XGnt>ot=9!YjszhO zlEQBxpoK#)YzrG`E*eOqXh~&m*c*Nh*~qin%7H{$8$F51Gg{9n&e0|roWW>J?@Ldq zKWZpU6+a1FGEbPyto0H-M?k@%bm^bP@o|rbQ!tUWi>2rXsij~~{RKxijK0_6Ad3I} zb1Z_XS6)`=viQ4qD}@!d#^8?*tmBF7DU zA+X}6sk_kvzf`$k8^Ubbwnh+ZuJVX+*R{Nv5C z2M5hg_!PzPPJ9{lVmM)OTyN#os|S`PZ%vU5uW9%7EY;a4mQ=<`$kk=|SV-{qTLr{pVU3$$gj2aIKMv}Du+eyI;uJvAWF_G4F^{8b6C zQ6n$9$?U0rI25>aMgavb(n|xL4&^{GnUp5C0+uv^=wj{x6cDIm$tl(%Y@4OpV9b8S zKRk%uFN@?ls)`H*h;X6_Q<73u1;1w@$sSBZE%ufipcWyH013G5V?`Xzz}ahbk&#l& zD)On=y4Ks?1*f9*(@LUibocU+Sk(CfQ&G>QYZ`wx?r0N^>{0KO1|5e;T)|~6%mZ&a z5Y_=ryTpL&X7KPyH-ZaOwAet_i=RF8EOVF@vIjt0SQ&^t?btdzSqnzFtt|~qA%zVE@N~a+&B1oVS4YnSnqxs z=Pu*ox+a01VW8Kmv~wX^8++xWpdP^KBRWcdP;`ZxobM&#{~Z%dJ1K(V;~x~6JS-rU z)#eB)fz9WrbJ@{Om=LdgTW_9crEbyfO1D`@36h0H`pd*V86|7k&j6%NntqW&?uN~& zUrzZRMfK5Ee3lNz@W(R{nds(B0?gG($3-^hpQCR4?*sE2%LQq^Y(_c5nFoK*F+~zb zh28Qikxj8E#1zmWsx%<4%L)kW9|naPgD{VkThAyFk%84KkaN&ma-@FN;924B^3Arh zZ(7}9QMGOAh+934cbSwO6|}g&n#e)^IpPk(BBPhTph{MPWAxVi%$GdzyBl_zQGy!L zbJ?ngCcGg#Oktd?1e@#M^WU%R4+D(6Sx)uSDd%aWu-`Lh*#eGWJq-%~uLzdv1p3EO_X;&}SO zs+w`sI#XQC{q!#v%j*9{Z87`SkAJ}yS4FDii!GDw;hkSEL}r+hBsX}c|1uqZ5+ocF zC^-VUDQ43lX{XO^G=>zc+btDGe2g!VDFRs6lMRtY$`cI*MP@Psf|(W^Ik~uyd2KS=7qC-}ou%o>&6t0{lBelVu_1;1&S*hK96^E2jCBiP8Hwg|+x*dI<$-Bs- z;_!NcSs(9b!h_(a1ZP8XOemU5e&|GMpp1jCv=z%zASPpwFh&}EROD2zrCTpD^aLxs zLX`-6nBHSTR9h<1_F5xNl|Ay)SX@~6=OaPRDZWt;=sT zy3_e$VN3y9my=0$d!J^(8+K;bRry2p#M7BRui9>wg82f62H4ksd`v^xy)=oo;l1}e z(hq$eAb)u$W*TGkkqkVdrHJ9+x@KejQ8B^GVjF26Xfc$bK-2Uam)Kt-k|V{+#0`eQ z#Ju~t(HQ2@w&+!UxXw^*OvwK5PiE&9=1PdDR?x_gN``brnx~I%nd+n14H@NIlUDcC zt*z41ofHBVGEUpKS)63f^_cF;o;-UkFSq&>8uL(R^j;Kr8|;DWWb416Uku=3M#-sQky#GZkOSnQkx^@hh~g8k z3eN?&5Z-x=wB8ff-+>?}wVXi_*4!MUR`+?&c&O4f@gkjhS=0VVuoWGO$NyXbo0y7zfnCaR2C+YTRr6mYvc>dFZ4|IR z3S{BHC~&BgrB9)Ydo9@EGqf#EWUw&t>6ZD7riAwj)2l=xOvZ0HHX1G*%@=K;za$m5 zZ|?K?qBwm*Lw%X znKiJ`Lk&xzB&7`x1r&5)aY}0_HIR%>)QK^=%*nJkmpY?IXVf>loFwAHN51mUT=OtH zNS;%Ox2OxJI17wp`POOb9@m^v=M&<8NN)mUW;xQcfH-?g=}9S+u)l)E_7QLJJ{3@O zRcIFKLk4R*f<@Sh#Y3XU_JOikknAi_lni3RLe%#`q@=Tje z6srZ=SjK?>|0JN&Z3kBisViq61BKkb zl6=`&zF19XC#@H5g%`OcG>QmnP#1}e@}K2XXsI`PXqC_Joe2U_2CZKUiJ51CKEr%g z?~3Ua=twMyQHkOPvqD`gAxw(}vRmAW0{ae?AlO8iGW649PJiV0m)0|gJmc^B(>{uu zME3B;S{*rzNru_2WzIG(eiEhx*NeaUA_4u{f`StM?a#kJEt1 z9Z%KpgO1IL9-9SLHGpJhPxT&xo{54V9lCnm1@Ueu1(rhcgOtDSUcMu3s`>c*J_Hq}Vh^{70bdO)ZAqJNVwE?u~2J<(u*6%Q&D5AM7WMHF)E z6qoZL^ac7(I30(4l{DjT43~jL4oYYz7)U*bhOnEw5%ADig=i%Q{(&a_C3}M=7^FU$762$!GEHk^V$}`NknROZc zE;&^>`Qrm8E||!N*BKtxp+dhChe)W%6@@Jd4wmAgOA;0$iB&C#7U^VndR%%c8lt=p z@+@^dBC(ZjxT~?7$n~S`RvpSMMaqrBl%L_bRnITuAj;mfp{yt?}%;!7vY>~fC-YMAvIzwGM$ zbdz3lKv#LGZBbv`!VtsJK*u@7JDZw5{X$(hktb0?iM6=X6w-vI#Lr>h7jt^AfieC{ z{&C6<$DXHtj`jbByI;cVBG7d*>fy;FtFjL+rNrP=zLBxahhqX?V$#lzy$8qg2^={H zMEg%ZR2X6_7=I&5`M1aopp>=RR6&oIwXf$JoG2X6P?_uBBK4U=1Z>MZJ}#wGO8DD< zReVqk7h9dYpHtC0B5UX``}C_L`MKPr-HBIC0nX`}+HQt7Q-X#ZW4~;)y(qcr19%cA z|K!p=(IqjE1U9=++EtCN_Q5s;)&P3((sj2ogfB3M?QhyP-`-ZFT6E9NoSh4^yD=65 zw3MRQ095|3zZnQYHn^c!*o{N1a!1F6!NuZQ@G3|^v9F5ZP6MRfF z$5l4U$?Gkd9h2i7qz=*=N^y$oT~}~IGFDn2%)3A6iWp0YeAi>%#lh^4{31;y=nZmJ zBSOR0w->Hx!cR|D;Sgd|N}^>8JvW{1+O8*d%rTs7G_?UG7fQMviIIs>BDPMxT6R%_ z_a$G)>Zi(-zAtHtdi)m%Ye!aNEW2woEb9H4QcTx<3bg5( z-2(+-xJfGXpDF|To3^8j2V!*(1`9Np34(Td0SZOZ;PaVU&@*FX8TB}s@mX~~b7!I9 zIMM!e@#XX`c}#cN93&}xm;Fct$oEiUD(O(RHA#RIb3QJk@2ts*n56)tk%S2vO367u z-r2DB3~Fgg-^>Xxw7R&!!U*$Fo!jal55|oZuTbE!EaCJKQ`+G9F zA>`0D388tTHmC+e% zq3%~)5=Vwdo8WZ{gM* zA+EIY!8hE%UFgGABmECO#5~zcP(b8wB zap$PYTiaor)L^nha+1Nnj@y*Q)P&vCFB_>o_*gRZC^iO@R&k5S)HB>TgQ9Q8Ix3*F z=1@*Lg0I(6UD}vYsdRm&oS8sH?oME1#T--_^Kc5&4HLkruRckBPw9F6kXPVCd4ETi zfH||3e=+0KT1H!*O!HOD%OBDqCTAYdr604eKO&!Wlf4>7!VNnCjU9m-y52>rqOX&Z zWywGp_6-SAwfZdRVF;PKAp7tbSiP40>H)cy3Hd2OX&ZnD215Q5-M=N!0sC+{=)Cg( z!k$8F$iJRcV>&?<_iu=jK-op!A_YMC0x(W;ulB*@I6GtR8GB}yca)v)NkVx#0uFF4 z@7K9DUmV!k1=@o1-++41MR+qsp3HR{9i3uIi+TByMKrU7ns;aeuHe3f$G0- z7kj=JfNFHCpPHXi5pAe+(Q!ljtU$$EaJ1k;O&`WTR7c>$DBHiIxUG9PmCM)Es*Y`a zJ_h>&JHa^pDRzlpYy5NU%WEHBP!X{QIPJO{g;)^n|7(Ij=AM>mA`P(y}hXw}Q4` z-|yppbb7V@)uX=u-anKu!*9M1{t-CrGc~pzKl=M!(Kj>WczI~5^bh9%`ya&bxac9s zZB<*5pC`0*yPN#X6UOSkImC&bg=s;*z z;NH^B0JuiAe)#j{>8j9~t=^ci5xML#xfkmHzc;UtcU?d1E$32wPYYf*;yKOp%-tNk z=J}o^QSJYiTI!nxm>#z)?=a*<%<%{DmTO#yOZ+L&c)_F7ZzS=-gt>}noBu1sy{4!8 zenXi;8bQlTp997U0KtStVlcowSOupN#i%+~EjC34k~Bimcy|<_avQv>3>ZG_nI$LL$^{KzE1vA=G)hOv5&gE|MVKDpL@*Fo2Sb> zfqb~7ae_;!Kh5>a`h5Nx*IL?Ge%=I^R^e0W*C=|vCRDyMgl!-%7EDzQt`e=*+^&j= z>>000n93ZjKE}YoB@-8voU3EASe7@-iX!IaO0xostjn5N!DIi2q4WNy^8MrZ+0Nk{ zj(zN7X2r3O**W&^m?30uvJz6AV;p;ikaWzfWF-loV~-G0QPMFIl1M}Ae82vH``1ZBEIPD8py5*_$G=V@vD&Mw3h zjC00%jbxVjMuud;G9fcFnKTS{MR1uTT%aNF3u#&Knv4s#WI+-x=^F4%rwat1G$~CN zZ!iYG$N&|Z_5sw=`ZKZcX-*rhgeaNpfJMScu9v9ZW@9abY=pXB zkrmOr{c4^yTV-;&1)uyBu+3FQeIlDZWBz^4OLeDw%D9=w%yIBU1OQP zp;~06`OB}^!P!;phCNQsj>ixum$G1q`K-=k?KS)8wQbp17U7U*;VhzwjOv}9{vBZJ z!#R219M!yMmhCMx2g$95;=K)2EprX7+*G?QqD()T);!evo^1GKn3mk3Tt-{PkLdsG zB%}MkBxP>q{M=W=v3qS8q1P^T9**5UnooIb0C~Zd^m#m8`|k+4+|{(qzhd1)z@L;# z9m78pzc0LKA@=c`@Jrzs;j5$7!7}mVPM!6oIZ~Y#afAN5Z%bOMqoqre&qrUC3_oKp z@^(l#=2!W~(SnS|`-H$sp}_8{@t{dB0i_+Tk^ zJ@`7Xy8vx7*p_?${tQSPRqIO%_i_? z+N}noaWkP6>AaaN{G&q^KW>*7Q@82;yAX6T^w2I71T?pfd{DVN6L3=8uD3vZpK z1!=_axMQej>bll{>pmA?R9^Z?8p;P=9=mpE@ySb^J)Aruu>W1;io4k)*cb~K;YKBC9W?_d??fYr%-2uDE0m*!eZCl z44K=_9{B)bv7fPCeDb6yLPXs{X`x6rXKOy*WwS~x!AwtnPcJ*qB2iywLboW2{nG&A z?%55fGO4a608o$lqT^%#2G`iJL?~?a&J84B&n?h7ZZ1gx+1zQse;s7d-9!qjC&`hQ z4sc`9qcy^Nf!-QcPOL+`T#E1(EEXuv7dB~><6q!?y&Z&+8$M-iG(*P;lES+HsKGFW z%^iDDnuZdLzo2{hRJ^6H%JMy^7#VmdA?OAucv>7>e7LMYI1!W{T#nRG30u5$K|IBo ziF?I6*qf%{QBCBhlfXIB){0le*&+v3$M5G7ksbhRrv|Q)-N|aPD|O-F;nyyXozT=P z<%l6|W0a*F2)I>1$>uUCS#WY3roTgkdc8<7Q~jxh9tm5Tr1Ll9SlHa-6}iOzP}T7M zm)Y&X1IR5gd=Sx~ySqRsSQ|Mt@UwgnLw!rGPP=G%t8{P3ki>3Q{T=SF|2yj9wM{a% z8epqWO}X$!(U|Ar@2i+m+F?4O8yVo&%Wq(8mrbiiYEL!U>_X)77L8>Fsk>%d@{9T$ z&AK<%*sHDgOto68=dYZ!3GKGS2(Rr(@2@pJGjm2 zKAEUaM>(^GOXI{)GKQ4=vJ%jnTU5@nstDptB0xmSc$hkjk8C~}JERsc-D7lo3MsqCYDP_TRJBG5O_gVa^~UjRKu!* z9(z_wJW~DM4+-;gkBfzq)W}fF zRou*T`3^AcpC5v7pJzlQ|GEgv*`4A+6Tht|Zzc&`+_#37wwB7l0u9fm@bkM!f56&~ zYzS3(^g{8WdleZ5y1RttoWvOMUn}cgz9{$`B z>RqV6B}vT#4|`97@+DcP77E;&9~Rd>yv0UUbh+bH(a=-a@W0_Fw1WCjL-bUX%-Pn5 zd2F!h^)w%bj5nbvAf6hPNX3Y=@DX9!Ol^@PCf1YBN`R zi%Q2u7Q=nmql>ymeu(!?MbhhcH^hs?s|UBeRR@Q4@{;@ZsyU-E>HDYZ4{f6e5Nn_z zt5Q%3D>^0pbcgP8j~kykAJ4-7X3;`;hl%nA%R=kwZa&ly*?uD2~ zBHAK;lh7jp6Nq+!Gb_5TK-txGOCM(8;d~bS?j^z1Xy`fTc=%H0=oEb*2qR_dLJZ*-E}G9O9G${eW}I$9e-Mq^!`im8nnIvO*G zvRhMkOP6&n2=PA;6UmAeZH>7rwAU!0&2nX96mwL?N8~Iq1b?CPYtWO47Wa&zO@0D_ z=y)EJp?d{%GG{xp*b3NewGO}cwRrKAcB<3N3oikxsvBhwICAniRnKM4^EOw&vs`#H z@!f`M3PwVwj9SxE-2p!d_;(6$QVsa{j4UWyXC#>J{6ZnO0wH2ab!Vg%2#sCJFzcs) z58w}LNm+G=Js)LFn&_;rnicPc)yQVm__VajOXU6Ug@mHKWZR_0U_s4?6U>d#JWcv- zwStsHfCabyf_5^!aHsa&Ue2@vg$<+hGdS0%@9}j9sT!3EQEV6EBzJwD^e_9r<^uMi zLrv*E{%gQ_d}IOOh+|OuAzeHFZ%ut67>25D_eS62Af|XsqMN=Ipq?~v9N|$b$SZ zqVP#!7ja9Jle=QM=z6DhoQts_x32Yoic#In#WV|Mm2eiRTUj1jWT~RY+;UE)rwJDP*9*zPvcDM%T zq{$pupASPh4x{LUc>!Fe-9CKXmKnb8-N~}aD@LWQ_9f|&1K#55Mh>r!`p3aFWQPSZ zI|=w$H8(WV4&#x_wL@2$zuWqvWsob~eJ5=M!Fs&>#CwB7!tm51m7+w*I&Uwr?9IT=jvS7^0NXr4s+f| zi_M=rKofH9x$C$JP&8tlNFzn~dYuI*TQHLCmI?c-=(Dy(c@y@%V^;Rfk8Znk_SPri zF0oRTt~=1MRIM~iHt^dL394sVdx$*M+dPF;*Wr=JMd`{Hg(=GF-+O<{!z5Mh(jN3f>av;it`i`%Q^vbwZ&!EURKKcJ~HVOnFBpH+g1E;S1$D5y?Y_H z+j>|o9a^Yg$%Sh9mZFRdc+2W7)0{|}q2#zdXLo!qMc+X|R}F=Xf6Ns$C4@B-ns0eC zATBhWw((9{YdHrk%w58{ zr++<;&rYs75OIkI^vIM`35oAoZU>hCPFoe9EvG+cwxO~-3hI6Lh+lNG5-V@xWzT83 zu+|sk9VSZHg4PRPvDz-W(96zII8(N;cto1uhsJX`^%D6Bd5z({f|^1En~Mfkuspj4uwI>?jmGY3S;s;^3J&Z_i`xLs5P9KzC2*gS5D;6YS-@bmLTO zhu|M-?4i5i{?gKc%5#r*#>F$|91#+_FU{PUPOpdhlvZT-?6@nJ5e1!Ln%_kAcN+}k z3T~`|#%qD)8;{kDfK`Zz*WLWAaFA^ujyo>xv`bqBQLk9^+#75WwlIp55(;$sYIVd zf7h(3ysZ;2d2cR?=R^99-gFWi$~$kvjhPZxj-I-8z%AQ`l$D}UERu`_MKZpkk-aJF z*#lm|+28ng0L2YnDfSYdE@94nVa9O$iWK(3F_6CgHyCuvnw{K`rIjZExrVx862!_u5#OV!Vm%KkmDdhY0G$``c zi!kmu)!Tz1BD}YrN!TM7^nS{H6;}rSbVc#>0(s2ijW)DodddXNF>NHb9B59lNY2i3MTV8)5km-%J%(^+ z{Z3SVT2iV1?uE)~f%*>AWBs&G zq*!153w{O&9g_p}j0)#r0?dL>F_1L!TtH+o_`de&Xr3iZ`HAdvB)2_>C}VfT`G@=I zp4lkp^MwoV#8Q~wFGpT^9rxKePyF=*#}fKysf1Crp&C6R$%mAY^_Xg1>WR+Z16}L zN=PNJw>bEXNp6{j^Xu-W<}0UXmp-GBt}mRBN+p>evo#k3;{|Fp_b+IA%+2fTyq;CY{}*A%BJ+;F z{dQ2&K$1n+?Narjj9(HmGp{?p4lGt)8qXPwe~sSTKt#M;|<+|(b_!S!*=j_J-y+PTAg>TzBYxQT1RGe-p4x3>KIEjNfo}A z`jyKpv5JoIFLhJ>Rd@SSyOE!ce#3}w{$V3HU*oV>GEYZ)ocn&|QEv=;&LmciJzG{M z1*tt3JDIIKOk2Oj2gO_fUKUw7bYs^pCV^Nn#aY^$mW#5XF2Ui_~1U0J* z$CZOCkFxEe=+&ln6L-CF{Fl9=Oohg69y#)dwjaH6at|tT5^^S*yb|;;c*Nv$^R2$( zkT{_BU!F4I^Y|v~R(( zw8-HQd#$s(rrP`SMjYJ>G!2wDdEEr#o3jpe^DTg?j#<>NQim?1k?Ao(qny^l|CzsD z#0{DA=O`?Wmt9SpeX+v8+FU9(_KksX+syXPQmv^qAJfPq( zXDaX5+;dmD*vfONuEf#)=0B~qq?Fu}cYaT{Zkxw(2k3Y;s0I9C0mVJ*Ol~ z@w1`gMs9;&c?;@u*f{R6@y|uV@aUY}z%tXB$bf04Lyc<5{nd1RL%TG27jIQtG>Eef z3z6sf97J#-F4@j^vzVR@(VC>Aq+SZbO34)MGUBTsl8`bP7&fmsf-(J3V&-guvP(Dx z%D(8lIVOI2F=}MZ^K@F^${>Ka#+6RF=bk)90!M`fNjlx4o`>nN$C>j~O$hd+o8{ar zVd|r&na*!1Su(Q@opksF>4^gqj$Em#j1i>&vV(wdh^cxFFgGu6Qb2Cw-NC6yPH*aA zd~DXOytvVZQ+r{9mtm1c-vUY|d^d5mx2dGFSo$DX`M%*;@b|`81C{#Pq&?q>KV|Y# zw_$R&_~`WPwZe0JkAj4+8^SVly6@d!CVZ81Urq*Ip=rQ|VIi{cSvMmoJX>z zxicb)V5Ic7div+E*5KFA&kPL3(_GiCvO4uXMAsdr$^+IB4wFb8Kdi=L**5GR$XOa?Cw!X_A zL<#vkPb?d%4vb$B5QFY!I2KFjKL`>IaaLn`ZslqHFQ{JE{`B^k=f!dT7Ym2Z-I9nt zhpJ@d`|la!=UKvo4#E-h9?hmzuM3yTI%^YbZ6^LK0-f-0p9?EbJ1|ckOAwAEmTo`g z7t}jt;3igw>MsM`!Wo3d5-g;nG_+yMt*|eP+$KQ>u$Y!m*mLNqNmqst9(2Q@5NtcV zskH5sj4J^VXCl7OvnUwZrMj;lx>}S~2iAU1=EcN0vuKBPiqsgQi^yPXB?GF4OF@pl zf_eNE#LVFu-<%ErLyS9?2O77$dWZPe{n%}zLB*6Yac{%&>}k`S&eYT6xFmIUv58MT zCJ{v_f4G(N(yJpCul2J+{6`u0zrskvLyu>GrplJu?{AOjZD+2qNY#%pT=8Ph?(=&Dm@2Oxiw-!<=?ip5pL3n4PBLtZ zVty&lzdeA&Dx70K_o+Ha?ORp#_hknRCJm;XH^dfQEO~We{#}-H>VKHvH#fevEF7(U zTvRHKpOAC{uU`vw|kmCbb$ zFXfJkpZSwnJL_^~{9fe{n^;%ZB~xM@zdU2i=?g<+r>JRt&@lLSri+ zh3Kamw>v+f0m4=Ys4c+jurmHK&bZ>j@FvdxW>aHVjaTjxadoFMZ4mJ|EAZ+{0F{PIXTyqnmbUiwlZJyzhl9=nZ#`Mj$SDTQDnS_ zsNq9lhh){$Uz_nXlm=iK6@(7)!s4_3CQRQ?C10w}x&*u!^6wt&gHzIEDzTpcjUaQu z?Kqc5F6|rX?~|YyyUs9zwUX5Xtg~USU*}6!Hg|w=5-Uq2>nSM)Mj}5ke)lTA(72Cs zvkaor=z-fee7nLX^bTd~xDnG!#66hXao+g2AoX3{#wa@%k4_Bod!e@7~mXO{b< zlACANA5BD0dZY0qv9IeW_bpTyB(xhAwoc%{&4*2nzs|^gl>n3$UvyI!=WReHY9Ln` zP}ko!SN__(1%fwD3uDq3F zDc^VD6~=A_!n|d;_xpE!51qgVC^x+yYqIDH-3?D&+s2>Wn|i-_PDqGCbY`JBN0s)y zV_g2HCy2Y&yt!zpJGr8&@nY9#r$HM(X0!krgRD^-k_j_p4Q(w!EQ!I5(GH&T_G^NO zR5DA+mM8SBB@BybBEw`;yN$itq=^1UVB0+-gHuG2xm8!Z(1RcXM55G6wBD-;&>l<( zxsHD5lxi9c=nJzmn>0n0*~EWN#`PM9dz;A|T+DjMC$v5*^b#^eyDu&z4^qIAQr))vYQ#qg`37pTlz+Pj#Vm&0&<$2TjWa=L%=N3pUkWfA>Qx!H+V+5)dfz?w*vjER;`jp(2O40T5 z)pIGS%pA%4mZ3uuJU7kry$*Z}^1c-CGQB74=+WkMgQVtst8UNcp}?i{b{zL?@@uu< zl(~Q%D3W;Qq~n0=Q9nGp41B2POCy`{os2rf4)LjnVwMP4(UumI=~ma&!sx7vS6Dq3 zUa}Mb8Y4*|-gI~Z)+&y`)}O^TRKU8L)y6|P{lq{Z*tt|tmtJwmX%`EBsm8Ik#Q-I zZ)&J)Vp>V}i44$&-t1mvq_VuzUop@S{ov&oXPN@Ic4lPl{?KrXe88Fa;b-1|zdO9Q zoT}~_?{j7##1R}?B_9#^RNhZ6F2nRnv3b;`F^Re?>)J(UUng1b9RfA`|Ti`X&xSt25n@&G3%I5=p#pV>;*+Fh07~g4o>+S?G^CZ-T+3|aSrBH!dm&~N)l((hlZWAF*bNt7@HpTUQs;O0 z_F*KvC?U6u;|*k}V}Vvf@#OiUs@8S7Qu2Otzv)W8p-tp*ANNPwEbLTr@&H3LnXK%j z-v5y)r|t+C1;WBu}1vr!`o*xq?q|9DDoc z_`nfrhS5ZeYUCy53?A+H3Pe}=-PQbm@vV;KBbFZ~t>n&E=?6`3uW7Rjk`g!$KOfG5 zj?g2U_SaH0|KetogV--Uw@H}NlH$!Q%~$%{dMuUyeF332Z=UN{%M2q=wwIxBRNrK3oF!^jfgB1 z6B;)lH*p6OIy=zF4w4sT9*U1 z;eo>JrSIg=G^{dcw%s|a=(L0;O5I#1$uXqG9>oP69&gmutz#?26oJ3xuB)Kl)aw z;f`ltQg2VVT#%?odX%-r;3i_e@x70iR>@HiRJ7%jGQWX`D}PParMRk*V&z`tUA>V} zcD9x(HqyTlsQ%64^P!88!r{;>cEiv}qF9)Eoy7Iz_Bf?YX8&~F=cG$O{DoK41>rrvpGYC9<*sPZeP_ovfBcQ)#^w0+pYMhlKwoiRERaD6PgaPfqZ?>ZZgcrC5JK$l_9w4JM58Qv1crWk4vl ztUh(T-aX6R1K=J!eaWg5o<><0*j?T5J@y4d_XvUMJ|z1hjjiVqEpqI`^`g2w4r`Kvwy>*S^rSBt1&V2xvM;^ z5o{+OW&S-k>}>(aPX3wQL89QK^vEM6vKIgJ4l@G%wbQM%;#t3)_5MY{I-oKsr6Kfc z-}wgKEiR$ot2YLUzH*`B-xhH~hF~XT(2&-vcDFQt8`Kg3(GSykKF;47vkWoQ2!1_& z5*=MvPd;ZR-7_li?iqPr0AA{7t z8M4H{Gx=N1?sZ$Jbx*zjXnwQ!s=@ws)iC(Syo3F@D%tQHzc(7=76rX28e17w8YREg z8>_y1akJ(pbv#-Es5!kA%x@G|m)0bUj!olWK=7=_iNzE3!i&>TyK zk(xS&&|P5wo~;z0L$HWC#Yei+kdC%$E`a9(DwENnFWo}J7vKlvup}asRuR!NbY<(U z!Q*%L4&J_>q1n#oo?lHRPuOJ%-2P8}!j>Mr`-8R$=a=0r++(#LLUz4fs(;&^E7a{T zODP&X)&8&=iO`<*-8zS%f`q;bwi+_5(wxYh(>mcx zNteM&0oREKf*-^WER9olm!wy@ts3;@d4QD(a)9oNQ05UAp`g zuBpWQvR+Xu?=KeFgrWkwgJzkr@{$u)_icj)DiO2L+4AQ>_=I<(E1v|^t7fT|xp9hb zx>~1ca>uNn1zy%qSMXkWm7}O$Fx6bQ`ID1F?NuZ6gDmt9&za zlV81CZ$tur!_IdG&mfOjX)!Wtv+=9(n>lJ*dYdTxTD*}2{taofTI^fnkPx9bf}-rnzhwA<>K; z&XjA8_hFT207ztD!|;?89>OG}UnIWKJ6$wj$2(mlHvR`2W$T)Jo}oP&U9C*unGF@%imY(|Hd^@ zSuvIn*nV|`^Gwyys@T%m|A1`+*Q> zz7DhD(CIxaqS2E>RN(;9LkJHJ4}`F*vH|}MnXi%d!RvGP9J12P+ z5nz#@INRM_pVVkSN~n(|7L%EPK~ks%qVL_MVT+% zLHoBE>`vM8u5gv859?p@vSedUzJtiQ5ZOG@DFV&ur4kMBzYYK&C>46DHMCSZAK1aTBSTs3(*7n-;sMXX?gtmlv?Fbwr>GgkX6!5nTu+gES{sl#78|N!Kgfy zJWxeQEvxmL8kH*95x?gI-wUSHTiM?YWdp*p1=2T4d}r#Fu4tQij<2i6F!n{Jdh5Io zN-&3y9$Q17HZ3zgY@SjHPw+`n$B(Xn3fdhmz9LN`pv_nDhgLQ{8rJy+RF z#<)%^=VPDo*`RE@nW(%Nj7KjR_gs6zJqy$ua3X=)lqU%FruE{I#F6?1qU@4aQ-oI; zkS|Z@i6k_LC$bHqGJPIyc>f+ci2;&;6Zed<$!rA-^><< zO6U+EQ7kU>C7Wt)O9(y*@>QNz>C`Aq@ecfJF|jy_3q1KDm!K{s^Z|~#LpG6>aVWEI zPrl_lS}5#>eHMGri1fos3QX<1#ji!NTj!+&X#8QaJui*X+Q2*r%HO5Rz3%C8^rQ-{ zlHUXqxP=zBig;VYY!n|-tX}W`6s$dQ3uz__b*-BQ_axkT`$o4smdA!a+k!=XGpe%U zNv-k}o<;RdbdLYGWQ@pAvS1&#aTsq8RdbnwBH>a5a2(J*6<`wHEBUuO*`VSW0RMVS z0hAwr{_cJ(Nc#xl>n1=|;wiAm3&fjs1gKJ(EE~klE{k0|;or*nud-grTuU^_yo4gE z2S*K$@3vYUGDmUc<79f17(;km>$ z)%R7C-~P+^8!YiZA(iTOGC@BOB6)fjz{J&^&^?2yMMZT!HClM=b!?9y?9jflL#?d9UptxJ_LWg~zG!!uIS?^0jfX?UQj zcH!;JjR!Jf~vXdIHDQ_p7YHax89JNP(GlQ>#9(m`JvPt>vUO1|pjHLlI~?#6x!g;{0`F?e;~ z6Y)&~)`XoFYEN%eaLE^&B-BWH0r#^W_vL`#VAW(s~hYof5L6I(FIm@S3CWBDq01VamqOzPa*m-I)M~ zEi2w~F0)sUoC*|E_@VGeO_`UHHnX$DHEr2Q?`2*nzyo4a^(4pFtT!{R}Q}C6sLZ8TW6?H zx8ai{;Z+KH+!(wj$Yc*_OIDhf1#-f?{aSKi7GBXle%7WSvjB#3!>7zr@^`MVj&Udewo z2fD+%Y=UN$v5;sVB-ECC*soO8p93agV{zn|on3>C6jMC*vyRt2a{@#bd&Sx~?gmzD zColPgBDN3wlAL~pCl#!NR zpR&?POwEnCQa^hyOIy>+NwF%J?yYZe%?ZToX=`$&T72l+^h^w#lkZP&NYnR$qW-6GU&$$tn|Zc zck9Y3X+7iSBc2v4vgRT^t$Ewn<_7WDYkC&{K=53$K!v!cn;}MUQMxB6|F=nA?64yK zu<#q|@#K(F4NyRkgbZa97)1+C6CdATQ@~TbL)Z#oFv;*xC0wVhV1Pf*L5}IT%-vAG z3SbWxtmwC?vdoll#JF~9Tfe;GW)Lo@C^)>edUHvp1UGUU8FqURCS-o_UvB`PyChSn z*_+R;_CL2;g^S=)X11oMBh?`W|V*QzMZ1PLJsHinKL(sx0>cyEGv!q{tJ9zxX~34T(Z0+ z^!k>*N{|@6ACTg=FPvr~wt_H3VpiZ|_u;-v1b z3ooN&KYq@+q2OIqZTfQO@r;jYI1ea&xF=eCjT{Qnj`a5mDC%bm43XIxeWs**5Xdzm zm`dF=wfIQd4G)q$8=e{JvK~6A3U^IG6h^}H4+V$0=$%vzw@l5AY@rI6P%9;PO(sGD ztXgDIo=n9TgK;y}mn}OhnkCtUrBQvf(Md8kgb+1IW=TqgNqnru979ec=Oio`6Eps` zU?L&MIgh-8p6xxHx zEd4YXs}GxX$ZQ{0BL0hgG^b_3i?7{Y7?&)|8!G(wXX~R2-=M#KMcVB8DWh-->`Cj$ zFqIn&>>b7A$Sohp|&rdItjf2`6u$Ml(a0)U>i?;0U53w&=~*>pjfwd4(ZKq*fS__#nXeNArD6(3$`sZ#ZFN$t-nH7E>*KsWU9{A7QFwcJD5IfM3kv z2)B({9H$i66blwiWj75M+b2R)kM`&0RIi2|vOY`*qPg)sPp1ay!apE$jP*RG@lCV! zvh}X6AuW#bDEF-Th70v|P8N%_(_flp((yGUN@pV7YSHOBnTX;;-B^+$F-C1=m*(AA zrMekiE;Rr+LI3m1oBw<4V0c>AV%D>gY2@`|M4i`f+ez|@odJcwT1SU-IVXTPjwIqv zQN4E0Hr=eFE+T!{ghO@T0KPJ%C~c`fxAR-Rp2rY2y4(yU{){R3NGKwwdX)llZRa7` zJv+7qK~b7e3I_TIwnpU>;G2K9W%y3CKq=|RW3G8qGwRw>?kP&tPl_bqrNHP34JdXD zl~cTY5TG(j6c)7}FqMlE+SgnyRyQ5l8dX*38nPN&4FB*79w?5;#UcJ^B92^y`gzU< z25ZvBw-+01&-xYzp+#GX!h75JQQ*joxYPyJU12DjphQN$iPkeRjE+5uWkfme!ve7S z5#+mj?Vkb^AxcL=Uzrf$g;C*~%PJP&pgvWF; z{#ib^oEx+1^rKMa6CVfOdBFLZR> zt|lYMG=Mx^LyhLWPI9gLcn6)1`d%aA83A$S3aK)5are)dL-U!}O&B%^D-v zhG|$q$5{y;o49<7{i~4;-zhzh^={f()E!Au-!j{S-xS4MyFZJ+V_bR9Z`ZKLvP$ZH zYbwV7ylpJ2+Y?Kv(jmPx3V(&T04rAL&&t5R*P`)h!TGTjRlUN| z-ctG9O&>PiLB@l$1C)ANij=HF&*lwpP((`YRTe*~u>WEWl^ldWIX#JnyHa>J@cFyH zAAHdf3h}=DS~x$jn(r|F@`s-Al~T2D73!6+a2c?Ym~T6US~!ItsTA*6c%k*OoV0}f zmlsZarhMd%WQnb-w4_&Bmw)n$8Gkc%ca$9hIx;u`Kayire|u-?gu-gU-^1{g4Qy#mO@P-|nw}9y_WL?o+VvR`2-fqnv~v_m<(madO{oUMVTw z-*bCH+jL4O@?Ds^4mu#X398 z4}S6GZ~lI;x%%mKQhq3rY*FOstJGH8dIxf8XP6IU)b@=KV-gK}FiM}|Xc-PvCBQVEw&uGG0cM{LI_tzG@w|)}$lLf|ki1`m9 z>!lyUh&3yO1<_}ahO=0nn2&+SJz2|5XD#Y7t|fIbGp<`07-m`5=v^mb6s6e=d{)xM zulXPS?6~u~c644dS+YONUK7Md-D{{!wXFF5qYz?rE;Ji-h7E$f{rue@wf~7WidycBvkI^d9(^U31u4AnpL7{+dx;y;}MWU9#^QOY{8-)P>x=_uiy@Kw^y z&EZ_GGZB?|JCG5K2aBh{3&kLC4nQJ#2#U$T4a2JsYo8}0HFp>(XwwrfgL9E&Aj_|6 zIuRkgioL|HwnQ+(cov(J_u8F`7{t zgOtNe)ek^^MSQ%Ho4Db+!f~Y$z$Pp|0$E#UG6>*i!438T18`m-u(co^viaK0WnqLFFEP4AThuQ89HpHwvL!6oK>9c^lputM?8CUN>B|@~JlbL<^eN|1IGht>qcMX(9UT z=@8how{+9|>c)))9FOrDbA(%RYoj(rYbOT8sTUlRc9u>(CHixm{>yF(K^}huyu0so zj5GQ3x4EhA7i9zc?so|hm?~IJ#BrO28WB<+Sou=!g9uxMQO(S8 zTA0=_l)-uahVcBY&5R87)03St9@K?=JDX7f8pLs|p@LIG@z1e4VN$@w&XKLj0S=(> z*`iJP(%MNt{02~Dk^vQ-BzqR@UjjC}ijC5#^RW)FSlS3eatj=o>0p)MRf;a|$jLtr z^is_%watrF74F>ij#A99A5P1uhmI-4AlQdb-)o6m%9T9$V->QH<d*opE%G zoh1@b&)t|wR`ZW4(>#ll`5gga5gwCmuNZ6^v|4BoYD9PtE$xvT&AvA^v=iAbA-KkJ zKBlW`d%stT`}^Dl;O|@MXd(c{#A5f1T)3$1Uht0?}Z)#Jtg@v(H5FS$JF|B|1sE2_7`}L&A&CE>?3S`@^P9PVNjOF$07!_-ry@^l~q zmLuV<8teODy_j#O8d0+rx(%N8(i{faOkT}UO0ao&q*S)~Z?}RRqm3(n&Ii1;;bm2$HCd1{+QSUcKs_ta93Ic^aw z(h!=w<1h#LYQ>3WxpG!k-Swf_E0eq#VtkSD`6lHf(qpQa` zp(e@n)7w9;xY(i6_!sRkoX~JrttJe4IA*ChBS5ScGbrO*Lr2W`Pgn5Ze&iD zo1RS9@&UrsfU|y@!C8H@&KFl#dLG7om@>-$k{3+WSR$Ih9XGz>>W(ih$LVBws2F)v zVa)xV6YhIM8rAPm_zCu&YhgdP#-A4^p|d<^nc6?#>pu0Ol3j>--6GLfZBdWZW};Qy zI;^}-dP6&1J?D+Ty?Pl?FNz`C1!)UMWk0})Sa(tN4G}zNbX3&Tq`6x0LXNIR!hNCC z5msN%I<$Ttc=y5j%M^zFw`$8WaYHQkP7+XX_5lMa+4xU+zdmGE$&nJ z5-alSE)3HE`hE~#7NYN%m9Wx(-&NM3Pr2~(adU&gW}ZU?M)=5hi|gps-#Y9-|KT2m zk3g@rQczpGg$``3f7fKAcM#Cgq8+3&byh3dfcz*Of)*B2CUZ2R$NL_A>8$#1>c`sG zdig}!AJ2f9nghW4lx6x2t;^2dsn8#M0%etYR9&A$AU%&Qb);-$y51#UJ?tCHfqQ~f)hmPA})v}UB zUUb9d0V4Vn2EEGyd&17ZNhO~rj9qG(evVtj;Hfr9T3^?=olS?H>_Zn<1*)LG#)$%q ze#r>acz%88SVW=tLR6y&<%9lMJR9ZY2w0mhzmzEMp+NQerS zU)DXDGDC+>w{!K!n23+TvalIBeB5@zIf6B&`Ts6B3%t7nspg z-;~CY$Asd>1Y7~I%K){bLNt4jNGe}m^{BO=jOCjEjdk?pWNpMsyJe*#>_)fd#|iJO z;OJvLu44tR&+c5GEu()=ivC#>U9<41<`biDMoWH+E+)b5xoSTHASqbno$t98QdicN zxFU$)SQb9`sDXf)>z%bLEI-+_c_sGD4fLCAUunn1o;s)f#Gd zN&do+q9cyL(Bp$BWCz~`-;<(D}7hDhgFfeEHssl3P5vGtOi zFI@;8$qKgwAsJu9#BhlFY}zN5ny>IaI`vjt6SuO>tbV|?R;jl-k8l09I-^6}+N=MiBqfDsLBq@c9)slb0mlU(6y3I@E5HP8`>Gbay$miA z;fn++oL}XdjWKM*nKlL41oU%JR=Ji(&Ip(`*gZbK>BK**Mypy1W{ZTr5m~cEdF?b6 zoj93R8AA+ERxFm1xTtbj|CIlE40JM|3&5Ln+zfw9l4&4RQvy)?qlcGzpngSBroBjmwh;8YM zwA&YrfRIff9hR&%3R}|$Ea+pVV21?=>&CXx;V2HG>1<2jJb;)hXzlp zxWA?dvNcXE5`}g16-{ZZ=J~8eR+;zfFw&hazA?(|9m-M1 z$+2{B_y%!&1h0`~Xun2%&J53Jtm5ZxFJ}?T`y$G-Os(9uffxWmuhd1xz+kf|Qf`8xK3yaR6c*_Nec5U8}+}0Wx@_82k zD^JikAR@1BYUAs}3EnISfa6K8w6_+PcTb0#73`ls95mt*Qt#I{>bE{x_<13QI|Dcy z4E#L=5X1v$%H@CZdEx`~4DcXHCyC8kknv=TAA`*||4Iy#joZ<1yfg8WAiuvd)Xl5+ zcktbFgeva|E=iKf?_h;qj^GRO&_R5O+_*~QhoF01hN0Fn&S^59`E30%P&c1(v6WLO zM-%@7rfHA>uitq3W&?Ie%*d*m44de?WeuSQD4t1kqOV@KWyk8Xnsh4=lC{rTdB}=q zVFi8fr`u+V(E&z2EO1_F9XeaDCYG>kzydxk9Y*{5S=|SP*4y`uO6VNwA~ny!EcHy9M_8Fne=zL&OeqP|B_oE5KXcKq zovpGcOnK}7$=cj`vO~-*lS?pHt<*lpgJYV@{}(ML59C$atGg=qV7I@Uwy&i?1?V~u;ePgm(&`$@H{ z4EHT`_GMJ#5YBiQ$nKL5ejLavx468iqZ}Y9p=_utZ;+<<)UQ&cs5#+Y8`n%Ah36p9!Dq63BPF+$Pm)X}6us z=#WDJ=VC)v3a0;xJDVw9kt*5zYhs!phIaQ0Kq1kv6y6xWK zz}42tCN<0s&fg_RCpf29SjZJyGmHT#d4itiuV1YdN#WC2VuybbMN$jA#v1cWHod?R z`M+(L;4`JB@#inMnVlP)?J*nd4qWZ|pE;sG|AG9|w}RmRX!S^{qvftw0tzYo%KFm} zT)<|B_ml#3b84F|hv&Mihfb>h3*V8oR7-Iw#FfczmX-t*KE=zjUz$f2OUmsCCj0$d z5acYFS9GOb$jMbC{5bFRW3r%9(HVbIsp^uC!eE&dmNBe%TY=RM$t^yh+f9|W4us(? zF6S0%RF=s!i|T^3dDkZoY=VFpMc~DaHzQVaH+npGX3)ui2h$6euhzES5j>hJJG%cf z_stxx@p+D!i^vj0-OR-d4=@|C?-B_MH1`mi%l~SJ>RT=JuGKr&h@9tMksKFH~RqrF_Y|TNR?-6*^pw@RM)# z)CiraMC|OYm3dHRQaNPYPNBK&zGc~}MKiXZ-GfYe!J)aDXm=3MBG&uooY$i(Zw8tL z!W@uK>z~~CA6UZYBxY-j{7S}YmqQvib6-%B0&x_=;kaQ^rla_HCD#`HSj`ZdVw43P zPT+5_Dv-6x8}+CqjB#=bp=O&3o>`RX2EG~uFmtKvCu1=GR6uB_@2K>VYPf|AtvXH~ zsZbF&Zoobgi#C3bj31vGtG;T13^NmWXT4XmzD4*_lRQdT5EtH#wM2>#62i>j+t((l zgX543$a7;~jz_M>P0dZj&VIkb*VpR#qD2t29WG5`gPKYON zI4amDt@v`nh5LN6--!H1z>jCTc zvzqDEnq~bdAC4FS5?Lc>G1h<}>6~fQ88ftZBU~nLxM?$6-DZ)LA)cbI$c`NBCN+zV z&uvhuQ5zc>H&%7peBYgX8JdxBTdZXljofd7<_z#|=jxteL}8#C)-oz%uasESyN)Bl zmAz}gRzl~A5|{ep5=eWQ10Pd6-0c`V zaN5&8U73ufh5=ZQ_o}X}c8pglKJP~(F8z*u6mjnk)iCnL0YPm*frg>*N^u+PM4EMK zjT+&a*7C9xT6j$dQS;=$OzC1s;90lIXp08ZUSp*HMlm0PRsLSW!C0Q7j-df*Sef#9 zP22j4(Y3E7+HsQxjmWTRYzmU3pQ1)>-JDNNjYxyX-u)=X1er-8@eCcA@ z!oLV}B@xeFM?|lo_osGdM==|KxF7cWk0*l!+VSoFM^0C`%y|h*k zPkP&}s_Pw6BvfU1IA|f}=Cu-vcZ)<6FI&j@hLqR}?FyFK|NH2ilf%as{tfURl=bP< zFutdpO*Is7hO%k7*fLRYPRr17de7~Pe25&JO!uJG@`7qNMJ6h(#Mauu zp=WY=(J!W5$3j%~WL70(My*v+I~g$>!2YfUz-_~;R!%=_`cGmm{HVPpXY(-vo4^5c z`pSk*9zE-S14UlNfOYz?uxA*Ys9+hjE5`ypALB8m`6DOXtX?E}$iwsPWNDajxOQT( zjHh5@DZ6hgTIMj@lY6+l@C#67Y~NgiMws*^%E7W-X0h~zoE0Q4%*2*Tx!Id{*#n34 z6wTO;iye$*j%4053sI^~x}}H;gUnq6s=x}WKcK@P9kRo`6bzdZ@pOX25zZq>>1UM@ z#F`wDE~W<3(}ct6Kp_T?aBq7$gJV8hUN9)lCy72$b2m3RqFyTw+doZcLb`PFQptc7nHiO@I7wstha;~WO3Kudg zA%_3MW&l`k63gLJNA_*7My}#5+tvuVpJF?8d$ufW`U&U1MU05us7!BhkV83%b2_pn zjG??VFdpA8{&PZhY4GaEa_g2R{w53Fm6qdjN7}e_<&Oa!b-3Kxvu>!_e`s}@o=Wfl z*&p*dl@@M7LxKTXGCnlM7M)6M8oChZF=F0}p(>|PPQiqeNs$D)yF{v#oZ%YwNgSh4 zVuMc8)gOZ5iD@ZKUnBlKCOIGI6rw2v893jF+1oSaSi=w|S0zYWuyLZFR;pTzwAYqh z6<*Rmf+sk_J-=vL_hQH*b8t`3*T6DgOiqxDH&t_y!POyHe-_ZP(-__23gD3G8y%WYT}tS@zO?pW}f+#l$Ae4H(fS)T_sr)FJH68@otq) zV@Cz3m>MNsLfN}7+}9cylwP4Oh;qI+wD61?s=dah(sc1%JCjZA)DkmW=yUmp9Pl@JrpvGJOpH)_0s=4^8>Q_H>oxG)H3 zJCb;&i|e^*mI0Y*zVhOGc8!u`S`|lcq6o(?O7s;3vg*tok*gRB1EO0$U%|yo6rxH9ypi4PJ`(o^Av)gv~q+2kX`G_+WmqL#+Y} zJ|5ZiNiDhFrRcSwVs+15)$qoLZD(CKSJxKdNS6}M7MAM=ob_L?%>TY_jz{otoquoe z59{A9V1#3~D=()j@ABz5>i3RQbnuGkN?!?hief_22dRd#t*R{^P_;(^+}u-v=F?0z zO`lQEfOZu>$0sk)4Lc7F_5nQqKm^1l2Y|WaCoxA~1Qib$Tt2;4h*hGHe)0m0fCOu# zY;xt6fCqwK_D9$(S%iOQ%Pm#0oo~u?2fQQO^w;9LJq9x;dEjAe%mLdyWg^&a(`#k?`KF&s{b@)m709GJNd9} zNc8VPo< zW$KwhqW5$X;fIld7=yW+`RM`$stF3g7;qDAK!l_qR#hN=Z9u%1Z=J^ev7+GKeZG`J zKGN3$0W6gR8AXT9P0Yp-(?Ikua6w8o7Qqt8M|ZJ0&ptE0R*3u&kcE(7;D@y?-IJa zFOh`LNZ!}Ds-F=w$rk3pMKIu%`(CGi!lSzQ^k@d6xkd{;gO0L*E-lMxvfxB0|V0z_iY{4=R(KM&M>4Jn?LdE`UUwuOi7j(JLuv@;rsA|0#1 z+t^D0%2=g=va5t>B#~r*P&it6pM?{}l3Um~n+DQH@#E3s0Myt1HMqwH!G>_IdX4l?C6^Kph^*XQ7GD z83d4e&HAb2Rw=ScLTVcIp`VA72@s#Wb&IpvGNC9D^TZQi?|F?5i9FS6o~HhkDz=BV zIHnellLcQ0norMkxuca{wHo99Dq8>2a+DIp8kGD17?*VlcztMSOJh%(ycdk_j7JfJ zBoY3TX_SCr0bscn9irhO^%kUq7XyWLsN8Cj4(}G;?y`vfRV!YZ`F@*GDw}nqiJVel z(ZVdlZv%DuO#UR0RUpqm8aYKBvP+oyAKoyQ8ojVfG9mjDLFLug#B!H5`hzes2d3HV zQn{;67pNWe&(MfCEhsLK7iR;V2&V>Fsoq9R;SYEVyQ^UZ`Nwtn9M)97WX+U~jDLfl zi}|XXuc_}%KK#(mvWwC8`n}+hGUNsXB65JD+P8Wgfj>_5ZCJ^-;I#iouL|w62uYHF z$&G&*X=T|4qy=<3gv&guVUYL1HNl4*J2iY$Y;8t-O-AC&B%GcP?wRrYQSE@vC~UBM zruo~<(_lUXxj<5pPmH7R;iV46SoTEG`}%Yeg2*Y>1Smf)^oZy9fROGjLa8&-jy7+9 zs?F82R;;~t_Q#+?fDXDiA>2!2{jRR_%IPeT>F(|498=T1(+8cp?aybgtSuMQr;R~b zElq*x&u!0L7y`RSXnPNp_)O(4Yh?H^fiL2b69)MN7H|OG^!0Ue*$D08p-DDPN?nq? zF`_Ka@>JAAM--D;lx&A=0(g%s)VH&1F_lmAh^26T^6&LlwMEW{yj)!e<$#(CkRIlT z-OjI0z_I!rGoJJOBbbea>R|f9wO!ADIoWWN58Dl@Bp#$mwR8U-Q2*Qnlq?4- zLV!||JTfdmU{G3%YnrV7Gz>p2)Z`?xPXx=5xKTtPvr`p4tY%dWG&mEg$!<%lEzlcc z(wOn4jy$A7fhj&oj%CeaK9MPNM8SY4NbxFT?4GT_NaDc5xQynJ+t@ck64r(SnT0r2 z&8tcSzL3m&`?cbcoR5lJ1j|qDWU?eK*OqFb**|{(ClQNkrCiTqW#_F|T_et6Jy%Q# zt`=COdK=^aBG|_78++e1KHoL>s@mS?iM>@p`X9&QCMQYOl(By!gp8+(ydvCU8Dr-E znx@fu$J%rF414thAekQb5C3*+hJ(~-%3%nys#Q-j%hQPN@u*r7gFh45#B%*){I)pf zO*%-OI1U%px%tvv_OJ9St}}!y%`XPJu#bq!=GFGf{hqxReg;hC*GM6I+^%@^j|(%X zss46Hz)BX?CpDl9b__|U~h-8~Z8dnD~C+nl-8SHnbnV(#>`8kl*VIWBk`pLaft}=XU0WZ#fHg@B`rb* z=H@^GWM^>nHk@zg!pD2EFC~{bP*T=4{F`h#$7v~!nfI(X)GJ&hz6y)cGh_OR68xDG z<&D1W;7^Wk);u!k%|hp|DF(aVxd0GsPHQo99J{Ff)>E~`^NDM~+m(R%E*Dg~yMCxo z$y^9n$k#%Mwa%Aa)Wl;GeCdSRme#%eOE!$=IKZ3To^L|PB>SU;Tj>y8jDP56S`4h` zY#H)S(jFg>PLt(1o_($TJx5ZTWEX=4Mjrd4lclnW$~qfBmIz3iBgEe$KVx~~AIb*x zV?~YF47)GvFpZZZ!lTnnCcQ_EBImeLK9MU6yP3e%#hYtoh%l?<+J2SZPn^h;QszQh zKmU+F-@jP~lT(+~D1+U-#=CVVPxSg)p2WWo4>6RVb=Fe&yq$b~rTnzdXy7L^Z_ zX^NDe43xv9u~psr6+=3sYc?Gb`FKfO%tcX2)2=a~_S$q?tJN4$bs!+OMr`WSG%qP| zMr1q4m#*;gn#L0|0plmOkGXby{&tS~;(Y9iME@-5QG870#M`#{j!0m2)I|xV)Q5^P zwTjc*YKS@kxX8f*Dl_Z7CVn?TvhrA?>ylNM388DL;f*UyX#K|AE5R}Urz?c{Xb-FO z^~O0D-o3i%k8jP*ccY8vagr{cTCOjPjGL*El8Tp@Y#;W_&ykpe`m|9i+Wbj+YXXR6 zh*Njt)+zIRf21(nu;+VkSz&uw$r_2X2}Bp>{HGkGMUx6ADQoD1)RcPBKrpMW=VH?u zO+F*I{1KwDy2cTo^2h3+koP)BJ*QERHwhn1*S`IM>!5C9rO#4dw1Q`1GVaocQ;I6& z?%}7vCV7JnLD=2k^4Fw3B#E9Moc~!=FYiWQ20ulgo~SM|$jv``S1Ja0H!1D&sg+ZJ zCa~E)F3^;$^StXig2 zgC_b5|9of`KclJo%-;J+s)>cH^op%+v*EH;vq!&xhxNIA@xc=fLBfAswi-%xqMtT} zKM@@EJlQ@umH+!zes3B?AG8EU-#O0vG?`L=NnmL|4v)W$jd?-#;8bIV&s02PTK2bd^)+P|3pI=o zv!6;XD6bQ=^*ZsQ1qv?-_^r^#ZAe22_O}5)OW5;%R8D<>h#k@HdS^W(%dm1Kr%9Kk z9W(oCF7PNww#&Nn$gf4J?FF{^l7s^QXXFwMc>w$n9Vxni*=r&9+4s)C4Xu%}3@tp3Qb3UYCeu-;1S@ zi}y*QyqPnt{^GRTd)c#P%qHs#q#Q%Drt&P!aPTs<=q1bPzeZC z!AXh!YD(TeKYD+RUUvV_eLvdk*@_cwZv3#ztblDfM~R((FnEmW=)vy&MZ&6UyQ7Zz z`ghLkq;~Yj^Os@O@og8s z)uRf{@aZ~}OXJyyF5h7#&cl_~ml_dEe|PKmRLV@lwx{Kc^gj9YU)>(BFbey2cP4Jq zuT(4p>e(5)m2WU|?=xz#!KO?z`ry0ba+A|Nrw6aJPtVoiF1A3WzK`awDgF zttq)S>SywsXBDIHIdIR;Q7b-qyF!$8oa}g(kf=*vK&>e*V-#r>fWnh3MASUm8@}wG zaRLH|DH_i5b`_m|5P?$XUtfLgmp{8y#VdTOd7S(uaHLB7Vzp7?*49wa3o$>#v=Q{oM9WSMPGqkNC%Z`}8m78F>=g$w%!4Z!LJl zwBqQK1-P64@yqR(O`?M=VEYRjXNCM7={%ixF`({7rr zf*dyGQfX`5vQd687$==2Us`CRh-%yl%v8U9aw?tsu)(P=^C82DQ{`bFa7L*+X028Q z;g>9xE*MG9)mu*pvNwFQ-##-p{{U8Ma+V0pVRw)&m8SRd4D+<^mQZIkc8fvIt(*_E9n?T2IBrK)Rc)nGy3}{5 z*&u2O5kBjYu%I@LC-c<(-jK1^UMWq=i+Dd6pQryY`te5_vx+4F%`I7(JOiB)t>@>n z2mYuHewjWLyl^p`%}vNOxkpIa-{cfa@i5chq*S_`K+x{NBu>i zjU+BL*+w{rR15|SE3j{56E5THn$@h(Nv0~QW2}h# z%JFEUL+m_O?@jC!EX*hNi1%al6;l!Ss!Lt{@jV7#=%MpTeJ~+QxHi2^g2&`L8pLxv z7545d-5Q3wp?Bn-22=R%4&?l_f*BF^NFFlRT#a#_+gO9=F z(Jl-xPVdUUO%7CikkIx^nf^LCDEDD&c#yLC9{l%i>Hko&85X+dvnelp$ho>J3ERPX zADVD?jiz|hdDX|1wnNIpPgw=*kVDlRmKEW>Lu_J~nij@IeMS|*hy;FpFq}1QGmOWd zSc|JooPB)LHPP6MS`!&_#(jw-dX;Kg@MJj5SgVvPBM#Z2h zfFV_UOd8)FkTL+5g7DZ5a~2XQS^wbV@n~4YLN^3c4762EqNBoHf+Xk`W+H0 zA@SP@Z0CKYvR%WigoS_K`v|#bbXhw?e3dySGf|L(>%}7m*UYs}6mnEpgW$8-IMEF{ zSo_H)Eb6#PbhI6;|9}9yCXM?!ji#Qx;-KEV{=}zv;!VMhM(YpkKUXEeN51OZmt)AM z-;|1|1lC2F6;4;ykh_I$a=2!}YR{I?p8IYFAbFc~i;E2hN~C-l1Tt!0%SV@wDR@YJ zj+W~FUNBsLL>5K6aM(skb4Nee6F14JwVxjvxm)FW6ri`WO3Gr@&GDvu(iR$U$at<&z!1ccNaCh!fZ%;BZ0*cP zYNMMXBa-84S$tNd9d^=+{j1Qh#mbMZdxld?*z?Gds$?@&iB*V~BCgqbH|A@R8P|Mq zq;vHLm$0y+otIIAWGcG)GnfB9iTi8|h|+Sw$NkT_BhhzGpi5x={EM*D?_|5+-(l?g zcd@YG$82glf#O_F`Q#Q--zDZJ(}H-Us;nhfjNfG;6V5l;HY5i`qFRkk+WQY%28M`& zPiFu6m@6M!XUFhQ#oh`^-vWB&UP-7QKjNL3UoYT_>Sz(+&qS4-VJ7^;Bkg{YL4^z5 zjy6xQ(5U22t8b$w#sz?jevot5Cfq@hM?nwLL;Ov~(NxXB2+h#A5q0JUHLw9&C!R?) zchDJh8`>e7HEUsMag2s}mHVzA|(z#j|E>9}jyd(84r-M(c*X>hDijq|=r$atakRQzU zgcZw?{3~iSD}P*uAql>`i~(B_UqO9{J;*+ms1C^rwO}bO(J$#?Zf?Wjn0l`Xj}6;! zCtSSjc4%*N@S~P`pZ(yB@Pp&I#|7W4@rz;xx1k}}d(=0(zh{w)3$J8q02%1-#JdD0 z7RJmzFTO)GF@P{%Coyy%Inpnq^hs~x@&TN(OHn!y9NPeIg_dm4)s6ot&~DQVc@;QM2y`gy#aIg^K^icg=5IK&km^Yk_E z2eu9`YF-5MyP{+(i zH;I!Pqa!qG%BIAMg@B8IyaSW%Xw6!+K{r$XEM78Pwss920|->vOXJJm03sO}2s-AJ zGoTh+I0Y2ecFKt&AHY|n=j=i|dz7Lrb*G4y{|lLj@2g5Up(YN2mi6aiW~=01ip5z? zJyxV&aVcE(nOmN;$jilPbi3G=+~TIdPE#uE)qa&-Z_2%~#=gGJ{uV008O*}D4x8v_ zPZ?a+vZtzPb4*9zbTvHEmrZre=67gC`8m#6vrEr^t|5zw22$Rwn6rd6Y?$ zF^BE;;qCplc~>r7MkTao0uw1-fRnP-0CkrJllx+a_PnNH)5mMN*^9E{R)SV zf{2(Q>l+vE>=O}8qVUehrzx%r4S?#&i%14Ztf}Jb2~c!rHI(Sbal_lRiL#~YdK$9w z0ORLuT>_oUw{7QqFw1I}?0PZgH8>G(h5~7zL56tTg^kBh$pl-+UU=MG}8x(Z1cTXz?6cXr5Vt?Lk5p_ge-nWPy ztcpcT#zu*MpvPAtt!$C5dHpEUHnuy)Grix4%&3IXz`}%Jo zj8%X$l!0Ez9sgj-(LHBfmth+XXuwm|Tm*{3m(n~Z7go~FPnqiH7U2Wua~rsGQBuZ; z5Mzzn=bK0Y(UARe+970W$BtWBKQG%HLSBX!v^JPwWBj-h#XRRg=QnWvU*8&kXH}b~JPOWTO|`Vo z_x^kaZ%e4Wys@R9-{}7-^wTa#R-cbg<(&Zhju(9RtLhyAl{*g%NZ&|~@HgorXcB*T z5WgURAM%%57YC{cTfcqFbq# zOhpowsrn4DJo5}JU?N6a68F~IRLwHR3X@OA1d%BAcT%xy#r7#omRIYA zsiT&s+#3w&x;ytehI=DdBNz3?hxleWX1&>m#HosB}5Nu6*AWym3e zg(II1$v;3kOYAz0FDag^7jQQp>{}^&l+!3y8Ox>=fQv4CK25s@n@%`J=7$Gchd~z0 zpd)A&P(|a=e@$46eynAI_}!)<(Lrmm1nf`xa!vjaJRukck-nm2bAEQHp&?9q0D#Wn zD9{1*niqHcb?f^ebo9~;8ZCb`mj!(?>aanvPqu_kWgY7)-52yzm&Ls|AJwu0byv%~ z?BGs^_ViEep2xtrn{m-uIKyPow1gSs;Dg}F$uO&vLMkY0Gv2PbU|6Z zE#yAJq)b_=_t?Y!E~YLsICdDRlestHOR#E|b;#01y>B~c~$&lgb!mJ0DQd4d{zMO?y(0X zM_!d#{(Uxq@1o(JVf;~yMBsQ*FGDPm2yQKfbO#xg-n&^H))$Hum3=i0AC;=Lann(n z@8(Y;zPR831GbQL`pEGROPuhsVJms?iMr7~@R_D8N{aoDTGKC1%cM~5|gD z%--e>IbcA`bGgemtZ(mdead+A-I9B4j$<;H)@y&t%>uu^Xk^p5O9jAaE-^*L!S?wMfw^C(1?-y8;`|h>SjQ^*Q8}*F%Flo@JzcyT8az(V zQ>;YD7n<`R8M_u^`$YxCXIok{8T%6z1zX1*x|yG!91?3)L6$4N^RrO*sWJaPjJ3P% zk}jrruwrD_c#&A==PDHXN*Z=8qj&V)eLAOfx|vsrs0khPqE$&frR?x-c57vuegau- zz3~CnOXT9$!RksawL5~Nm!H}VeR2YP7e8b$%n{LUygTM$Qdqq-VSbk|C=wt#M&!y5 z8XsKv7I{Ci`3`%7KcpBlS%d9ytqPAieQ4?;Z69u1KMt1tNWFCQIjMyI_p8_PSnJP{ zvhfKcdW_G1l17M&Rr3FWW3{ysS?ITuu`KLaYl6s8n^wqxJ;jq##4UT_bm-ZJ5c4C&64PY7c`D_c5V<^Oie9K%(RBCXuP)K>;jvckR3qBg2W5W;nRQb%ZlyNBqau(``Weu#@hu%`H%NuxSC|XXWjc9%L1XWaGs&M zJ=A}Mey$~0yDlK+V(bU{ELL0!qmQ8fYx|spSSE??6GOGGsLRHqg5%JVzoj>pSsE_0 zj=;~3{bXSZsvTHwss1FxXq#o~_72A^@n%T%MBq=O_r#Yh9(|_M-qJ5MJV44mBPbt` zu&x7zBh#hOS&%>C`4hDB^syr5J5EoVX+yY`KWW0pp=#`qL;7BFV5%431RZjXpt&M| zh)`OydQOCsSmgvEA&?Q7IBTuc zX;bZ$-q|d>{6Mum{{gcDo4$j)(`J4*xL~`iK73;u`AVD}JQtX_e){-@#>JKVglD?! z2VY(H^7=~L)0@Q=Iu=D0*Z~UvToYsg46_0V7w`CPu>JUGu4i*!`5{Y3G)n-{p9>C7 zP9j2*q2MO}@OaEWE=1wrA(M>Q#(9t`-iFx0)qg8&#S+gfb6)quzLGrS3gAa8) zQe;Lx7ln7p|GIP~I3wP84ih>gY@BsxP|%i*bEJ*^y4ex%k^S{G##rT!?E(91TKMEV zJ11l*wfZ!e2Q5H^d5F-4#2}F~Ess8G=k2tb=I0DEKThWSJ;L2HT{u`Tczd*D;PPNuG{^}QbI_NI)19jh5U_J71Fyeqf@DD*N?CD$QE5gKZpNy2~jh+8a*6`>PAEK8CSjP-eOg(U-9@yU?6W*Ghr1-WVZ z_5O#`r1+*0qVC*3ezM4fp%dt&A8>7Gf%p=d1v_!)>9$N=VZdnTX?qy97!^+ZPZ%8o z>$69*32<+)s80phcKH97K&qf))hDC!{H!><*RuFFjsH91!X-Sqa{cDHW<})xZoJdu zy7&ir=A7LrI-hB!nlrq8gw{J78klJMTpGMTdL1D=qox9SkrnZxP!auin64&WDD($G ziM8DI6*2Y{PdO2RV3>O8CYW25Bo54pl3UK2X6Rgs`HcB|MOWx?~_2bDG#)jhcT&jC6 zTRs+Yt!xW-xOcJEqQtNy()GT3tyi<=*i^BiYlB&)bV!y*hXaMirYQ``moqO#YdFbT z7fOm9NGw#bj%SHzxQsIC!)#o_YK936#wPg;E-G9_G$xy}sYP@KucqZ7N8-5cEwtY| zNPk#3*tjcvZ(j6Z`8c7&b|SCFFzGOK#&5#m#iPp~S|51-%zZs@c{t)~k^S{+_@u41 zyEmU^LlNpBy~}jI@tHCS!>5P57wau~#0;Z$+6kv-zmalL#eD@b6R?w0UCoW;TlK8m zV!BD~Bz95AaxIry`+i-v)){^@H@Lk*t}4o-B1Fj3t(L9S&5OiV>h5(-uEgC>QBFv} z*+8yD$Te6)$k~aaF^2FqHXjr9HjW+ROH^SSb#o()33-GocAC1KU6Eo@eVdJ9m&zB< zTz;Z9)LNfP$1{OY@=Nn_QWioUrk#oa=lU}fWZ?SiG#PIF`Q&Y=&T?`+OlQp_DEBC` zo&Ej=z?jlGoz%0GBw<>1yv&bsWImK_$-@p1y@V!`Wl^`g3`Zx_NKD;jlJsw`WhWXAiOQ8Pm!1nXAUxl~T zpCJC)KBOR1=npf*Lz#JxRRL9;#{*g_%C(1P?*Dc=uhGk){+*a5uJuM+J5TK`ZDd|=jqaSQ+1^Cpt|?UMC2M8hSkN|6`fWGzjcgoqbl1pN*9LLpepuy8t%EiyK*pr%+!gS(E0hMz~`&N zu6kr#;KFnN|NZyRGt&oM!*!}1tN_mSIG|v8yXvE}>B|)jApieSbe3^VzHc8MjE&d^ zBNx=@?hbWyBQ4G7MoI-l-H6dRIs_dl?MML?Mk62&1O!B-RKNmk^uOP;=gs~8dU1X3 z`~IHi_c$sYSR{qS*bnrLp>BZmtHBPcr%q!}7=<*>M7$bi9l`2ABJhxLV1C*-YMDgz z{$4Mp$PW9yb@C*e9VBvsuj1Mvbmw;x^*&LEF;~-j_K-6=a$fawH+$(q6;JZDTjCh| z#AJ-h78H5`f=(Wx0#80+88eyZoGA{#AM4v-jY>jFeTb&uLDmHw8rSmoz`G*ZMPSCD z8Zk)$ZCw$A`Cxc6mbLT5+1V{6Bc^gia>Nl&Wcky3U%gcfw-Q|a%$NQ`Fh6KTobL~t z>4SB+M5ZakV`UfJ(K0Pt9R!Q{7ZLDE!@{OstuWqn0!2##S7dZUmW#e5PN+JorqvB= zNb+*Vg_WSU9q#Ke3@OoJCa|+f1A26?^j~V02A39`z?Y7Cmv4S54s!bfl^tM^Q zzbJ<^?d+UlVW`^AolV(C9*`~0_dOj=o;5+VbJy!{&2Z9FR9n#(>)-C@j&sG>m)5^x z_^En88DS_UHh;D8eob^{3_r!|bpV;C)PY3`!^AGgFheg-RUo4P;A5vTh&P!qM#8g5 z{Km2x#}cM=i9nLS7()-9hIRo!!q|ji^Gn5fs!`7TkN6!G1x&ACWwewd?IO#23nir0 zf=AJXmq+|dCDGiv50{V&A;8=52dz*o>NxT-9ISe5YZ$5mSA?QmZSoEMWD$<2=pD9q8raTCG=9qVfus^=8|F=^rDQE@lof?{2Op(x0a& zX97{w%hI=6rT`-4se1=5_rGkMznEz%u}i7bAQ8B3vXtKX7dtcQ8)BBqPc_3fUfm2GuWSf%ahDwpPNx8QsUSR$6?g3^(LonCL3p10Pm;$jQi+R0-DE6?Z0EAw?5EDga?jTUK$4tl{Kl@ zqrN$(Q)c3@^TN3tqH48!a?bvpvHvXAT<iXG`){l^dbX3gmg^j z13t`UD&yqY-6KHCY^=9zfh(DZ0XSb59801+(D>j!o zC~>#O-x>{-ygBZ+HKWDJ@vPD$FeWgl5GXg98#L(u)gk0-d05a-MV&%f;hG)TAeKhK zL8ft#Gq#gN>I3>5I1IZ2yz5n9tyv0K!1#b zP{`lcarTp!5v5FmszK3)l0SE)VQpB5qz zQitxVL+iuqS9b1-cR6vy2-S8d&aVFF@G3o@}dT_$9AxdH#L2)KS=HH(Z&Ml;=Z1E zkmk1P-NO62*bGAePyoncOZBrS7i>vzOxY9T#ZZ_4x4vUHWpH-i939dSsE3>GG!1!v zR}ywx0+!i;&X~~2PZRw9N%m@>_6ieh6SF#tA+cDUaCU~CwHeN3v(hYi>Y7=<2eQ&y zBB0%dE5+wmcnU-m&Pm7Jo|HJ@QQ@_-gHDnk*E}^c{(x*FLT(il*-5k0C2}lI9#yrAElbLuAc7ini!X63aSx8o=Tp z@t#}c#OibNhw?&#i2avIoSEpcm?}P1_%H3yx)_v30mMN3MG?-IqcW8P`q1?pNR<|ayXoGPEI%UJyRMX=4NoG1}LLeOrD4_c{14U!@2 zWPOh4?~eg@5^)A+v6c_O1zVQqcH>z!Z=b&5!Irxybw-^_0$|T*26KCm5h{ebtv?8k zB8R`eDhAW+LtDo2TNC<{f{Jgds40Bo-&t9g=2aJU7D$k^2;qu3-?--1D$uio9`xrk zH$ucWFkJ+R_rcJO3aBz8t$xY>%EkU;F?OUcz#NHV=x`0>_(#MWQ&<`wBw+X4?M%^T zf@8JX-@AkaeMW1kpDDpo-~UG&A5CVjE`C7_WoUe6|Ha^m#`zCon2mhVW218fHFLr{ zs{7BH!_db+d{-xH6ah+ky2*EXD- zEO><>#X=PL}jv zQ`@QKtFA3$f6MC}i$ZP4Mkw;Uq<)$kPrmRoF@z#`Cy{`BnWdQ2=l3zgw+H}1XH9c%EflsO-`;KHBqwU*D&#ejwtknEwse=ebS~DsvxcqnXP4D7 zNted)^?0!^m2h>FP7ax+h9sJYQUUqX2l;c$!N0QeXJ_GciRX;9gP%>zUB$rXCzkpW z9}KfWr^(QPV#we&6xnD*Bp_X0pxl`>f-lCdYlc^>*}p5jOwv~W%%}dYG~C0{%wfN1 z8*G^vhcNgxh;Np&aIdaxJMh;e-si0DfWbVBPAXj9b9FF^5fo!N{Q9{Mx{KE1&^kXKojh%gWBdcmj z^So6w+iCV|caPsY9J^`LP8`bKI?6vwuFObzYvVp7eVS301#gNTLZoEEbcfK zq=%Y1`G|ggJ7cRqN$FX^NCTh`hnOw=wAHF zUb+=!4ERXQL*?v#-js-21-mCgIo8&@qs-gQI?YqwCl|wdt3$;NE4ecTDlhca$2>)Q zu$W@i@bWAofqo7c>Gn?-dccP907wr2Hmxk95Fl$Vk#ftp-M9H(^h9u}iB5`H$LXSO z&3?zvMM2+{K^$N33Wx3@z;+0uaIq6QiGzM`%ll{Dvmjd~)y_H_SoJyn=2U!-^vA0I zDxMHsmQtvYMDmUQ!ty3DH|Fv7z6Vf_Oge+v#Hgm(HO6FLUDsU?uU%798>|h7+}-Ib ziH)>~iTmAEE|7FGSk7Y2VJ*96AsiAcv0(31tP$H#CzNbd*ZUyR+ye9F=hia46aBIs z+_&9C(3d&&Z%7uiVe^bFIT0d>AxL#@MDeB}6667gzD1yf@&dI>Cf^1wS{f*92^IAY zx5{0;-p+LS#ow{^G*OJvO#UW#CX?XK(R3u<XKA%dNkK> z2OCp7%TFxC>M`LDo0dNOXx!6XvQLBf)ChIN0DW@k8n07bp4cB;k zJ+kX7DrHRfQ717zene(EH=KV|Wg&MDog%&~6oG!?m@m3X5Z1L79bgjF*C}|JAXxc& zt=~sfIpRv^s;87}Qw*u~UiD1KB~o5t8>@sjH_FHWS7e0+rW`R3da{t<9Y$1OIUG2! z=of{fEVT4Jq-JWape!?m(;sKy!1~+v`pX^J!(;B54VOyeVYQQHRY8$ev%1nVux(uR zvJHfjg%p8<9=Cz1+mODA;EjJvl6h5AvXuRr+W~LrygV>9U zFRPkqHjjf$E_^K754nuyy?a47UDzl5#^s|ArD`5agRrbMT(p3@KOcpu{G}1VcjATs zO??0QnLbdfOzh>$5!CIO5n0!o{KM!M0L}p{Y#7J((}JJoBqN-yF~}aG`b1=mHSVXQof!OmHA2F>~NjIccr;=Tut9@ z(qC>$wVk~633RsGygQ|uk_#$@0>4PH3=X$^IXCUI>{m^rpigL;j*t`r0&0(7i|ryT zXRDj*$D0J6DeCrBA-CuN$dTkl<-CAy;Pdq9XYU?!8C_nO;Q2l& zVZ;9!GP$RmjJ0{|XLC*D```qR2KNIN_EmuKLbY<#N}m<)j2&9jqm(h|ja+HJ)GB}1 zI#_I)O5N1!R36)I+o-*ync zl_R7VvVO3X&Z&=Q0>j*cifqz`Bui`!EygAab&nf?Vg>@^y_^PzjDHrL!_*hB?2oA? z0XY(BzZvVJ9hKraTcq`8YBAI}u)yWMF)%7PYKgHRn&>zo;1^|-&Z%`wHR19*KF;LS zl=YZE_yH`_OKt5@WKO%A+(gcErW+1rsBINb4_P zCaU-Tj>fajMIiy0UZEZ@I;e~v#1+Eh_P)@-ELq^T!CwA1PW1-8d1c?f8NE@u8!icU z7kgYMVA>s|wU|*l9dhjZ&%L`QenFTp$uY;T_L}>-F!uzvs-X}NDv*vyhoIWYMy!gY z?X($*z8Mj)cq(;_Rb*kth)sx59S8rZWAH__|NW98_~Qtf0_@TadCKoZnhN!gvr9M) z))@XR;-`*Yd!5&GSz)aenXBIda^Ix(ibub70S30N@$s?>U9K4eA);nIzyeic5m6p4mCdJOnw5DQDeH5nJrq}}r^G!O*L@?6M%-a{bmZod2w$)9m#0)Ze z6HglJ%nm#$#ACZ#$a9?OD(m}R-*k&NpWXdmkXg-$ASoiqw< z6IL}AX%R{t@Ar#K)44+2s&tJmWFst1}V|-94=I5es3JhQSxmzU2GcH0SzcZ z27o=+)cFn=K9qJs#fT;bjbw9p;!ZowpXN+L+U4^0I4mpf*TrD%@;nTP8ZNHjD0TTRjo_O?5YQATuJ^(NiM|KRy;{iL7I*+Z#i=*w(AIRI|;6#;|2ZN}lGZW**iH#03g*SXl~elEKRBR#1I$pu>*a z>;(b#%ii+Eh&IVtbcWb%+;3*&_;-*LhdLDB4iIM_l2*-Uit(jm(gR;&!2LZ;jBIH_ za5zJdY~S7=h=ao#?`U>;EapNN5^J}NivAJ z^hF)B-Te#imnsufTZAsEWo4*4YtFCtdY|BO_4ZFLo}Lm#9<)~6612>_v~NDjqD%?z zip`LWBI_w+Gw}o**A!Yu8K}CCK`@Hl$S}NtLhKmFQ|INM6dVg5?(q8g?HBYo9%n!+b>6oEn9A%K&TK7EtNx2yeC&LNrqN4-^h*mj%zlg+!TH(x_FGq_-( zx+dsP{y3uY{Ea`AS(>vukK?oV)XX)kA5zOMG-sO#y|0`}DtT6MgO)BZ@$G?jOmD8; z4Z*EX%9IQ6tHKA~i9qp{uuP?`B}7=30XmFACt9417pEznlPI|j`eqVm!;BC0xS{}m=L>u z8vJOBsNPb?fV?u_y|$LF|FJB_Zkh0Ws8m|#?NU)epWt#_hji_`KhZa0obNEd2G0sK z!gS_%g?bq4*owo*AV+Xxlil!(&c)@T;!Rx-Bvx%=Gb(Qa0&4k=utgpu9&X0jK`Rj{e(;7FY@>>Tvsq$|3E*ji}T(92m3 zsx-iK_2^|-gKDEVC~kJWPDqKoq_I{jy48&tN-2eaBb@jenbZNd9K< zCk-)7BJmMk^}(7<@&t1|T|52deJ8a7SQ7rI3-&T;%hy9jw;>QFR<0x~9|w;jP?$k+ zXs(82gfZ~OfNrvzj!*oh@B!)Yaa~6XOrCQHXgL(0U{UM>)<2at43()!0LPNSu{3ZT z8RUTn2aG|N%oLazrABqnvNWFBs|KR}*J83bit9N#SPXh5uU@}q)1o1(y(HIxff#ms zHK}VklyQz+v8`R=vo)eeE@nU%TsT)7BIj@lYww5~`}~s>NDLt51x9Ex)czlp>o=C` znFi<3aiD2;^eZPmKqKFGN=!;6`W1zDGQr_&oTD8MX^n*dr?abMjecS-3+(0aHyaBA zMBdaHzh1g5Pd45q7z;HpiLEhdYBGOaVp5Z0zR;*HL<#u8#Qe*VS-n?OJ3-^)%bT|* zLBXmrQ8bWuEV!}+{C?XDaq9BhBL0(utDUr#?NxD=Q(l!1yo|ok8ye#$1|EY4X^fj! zWPl83B#IL+MK}SI`an0Hr)tApsColp%@B~FBrUeNRm!$;r*oIw;zMqj_?Age0uC9jn2HA*;@usWG>g;gz z0+KizgFccWcHfkCocwHylnZn?d+L1`P0xK|ff=#;lz$*TR`m(wF1nG%RUKwOAHelJ zmUEYidWzGu3cmP@pX(c*Yhb4I3=`9>3fXW_dGz7>p*D9@EF^EeERtR5FP!5ZTdoio zD571l9cQe(ork*g3B`XbjCr?NG_Ne&Q(=c%K^qyT+B)QHAPEGokP_k*rgmg27rzpLwNo`c*11p zK6sFR{hfkU(1|69g_)GHdYi=TeJ#1%7>(0VdX)qhg*qz#=d42>M?WTFQ99$78piA##$@&0=t}k9nuE&`38_>=unZa6Bc!sxI%>>6_ zSi|r+QOVeUG_G&QoKST?Z4c#B5|^|mV%I#T!yyJ-2J4HBpg3@JZ*zIeH5d&G{-m*} zP=$pv)zI+VRwPi4&*|zAlgPB%KDWBEs`_D^iOe@9KDhIR(#ju8>dHVmvlNv{FOyjZ z2h^ZBdobUM?FDUYkYFg*uy^34;}q)#F;@+7$8WGTD$K)G+hHld~LXRt2B?jFidfW>&z+aQ%qRnI?DOWC2 zL6;r0y?#Q%uy<05!J{E|FL*ERI&k#wxBvGiXx6%RPOu9_l)n{tb@`%203hAI!=SUXo60@hX65+e3MzH z7%nbrzptdSh}N8caL7F;Nc*v0eGkV2nn5?I9E*Oy{tEGrj%78^%~jb>eND(!Twz8{ z7$>zh?$j|UemCB)W8SFee?4G);o9Oljb(Ip)z&7VUO!<+UKwt8um}L-Y3bfhk z799%?b%tNby7fwoZnGu9@7Ip@6fK&vuY@CzEQTzYMTE%J%UfuuSc_^=BITFCF4&rN69PMc1?pSV_EHPjs|RbKcV1n zs4X{-^3EyB&M~s!1Jq#&`K_0MmV;(E@-N|%>D7q(NALy?1*035Tn`xb#qDVJk6aWo z?*N6@AP%;Hf%O02Xs2=9iHESYKY9^~h)Gu4Rue%#GFDhImRMyLD#?9s$Xd4yzp@;GFMUS zrNASu{L9Q!!ge(_<_(5(0$Y?PU!;X(eeK~9nM_QYL}jn}od&&L6f}o{TBk6sq}3Bj9kd?O;2>KraBuc( zvUq;*dw7R!c1G9tdy-;2l|4hXJ#-Ed8=rU&r$3vklS_2Fc$v)(UvIN-r-H&`hpud+ zM>J~PP!Bu|16{Ux^0|lWv4YrFayExSjPg*Xfg>c~@bUAH29($cI%Vc|KH^U-NWQNd zJz%^m==2t1qFCC!qvj+v#r!}w;ImksT!M+hfVv^yXy6=^bSyI>mid8U6}=m1pb9i+ zNvj+J2jL!GO?y~50glMfi-kj744_95oZc(ouztDxJ(zg>xK?dN<4U0;jnn?{3JNHxD1$m5C1XzC%b1 zPEp_!}AZBX+*qe$VNZPK+ftBwbK88WTb9?;I^&7lTW$R?@!pG>?( zI!b3lzU4392dBsfJ;Wu+aQDL{MK9IEI^*N`>sg`CQku{PyDCR`z*N1&HUM zREGq2JUnWpHeDdBaH=p0^jslzTmwpqe&ilN8DC}BA@S-3(Z*XjZq>uaqv0|gbKr=6 z^Qw~I3s5MX3ZPA5Cr6oOXYsGv$9YE4Lw`0r+b}~3tV@*1L1;loS(+@yUq4-)yAuo9 zFNbZa%1ic`QGa-y1)^%|rh_db+wVXN)y^$wGWaJj(_o))nw47g%ExEQ<4ar&WbE_* z$qj!f))HIc?Vep~pZOGB{|f`Wo7ydzX<2z69@{mt6hay*Fe|s+;l6BUw>X*{&IIxsd%#5v-s7kYgt2c zwKfAyUOuzbOIp*f$(;65e!tsZKifl11$#dSDy%Wv&1)(3y@D`xLjOK{TNQ)WJd*SJ zZBrKy!~W0UnGXlA(Mo04;a_W3iFZ#F`Aj-E15_uOlajkTkpV0(MI;!wjs5tBZsIP)yTTemXLQ z1k{WAAzj>0^1ha?xeMMI3X9&cn}92B2ik>Xd0RF?R#opkd2%n|+PyNbd*aC*_nPlX zjlOE1A^zmxsrNgBaD1_T`zD~RDM6H=0eOfOPV#IFtJiv%=>E02%5hVmRVWz;{*3t zakA6rynrFy(P4LHgah-B>&$9bnFYI=wYQ}V;W}dZ{rX#Acffv_D_qb}LhITc`oClS zMS&?A1E>paK6ULcf?n@|gsHucGKv!PmZ+2fyHi1UaF`DuJ&HfXMtOs7_9ZRmbS&|2 zbCb_k1|Z?hCy8_7Va(hfkVEqn0}1w>&wgD3k#S$f$GfupT|SJrEACi}aBn%=-YaV7 zpniUJvhhmxf?VU;skYL^cIhDOpBzm4<7()alt|ZFcdkNjA5XeWUx*u30`xD`tOvNn-j& zqB|u_Z8;MnfOg3bQVTEzS18N3U^m9z&q9PPNe7tSv}`V+^GR&nM*;#bBDWt&IJB{xe3w*ceK5SYy2geAt?2rd6EZkGp|y~7hA$D z0q*;_>NS_YVQj95+GsawSpDBn{->pYm(b9L>2G&*W4Bw1{z4#V+(;@&Vqm@^(0`#^ z?IVBZr5^9?PLD{lxySM@hmN&Qqvy}bxil}|(a*ej^Y7WI-O>fKIlfkBd;gZwG;a?x z0XK70rXYCqaJo8X%_`LR>Poi*16>;Tp*CqD`GX19bG;A3+|N;=LZORtp*3M-u`Hpm zn#14<-P zqsO}-{X|w2yae^3HpoTDVk&-C?tV>RaU8KivHWQ!Ua(*DEUd9)KwZck7Y7pX%&svj zC-8Z`D|6yo9xju4OHn(sfe|v=S`LSI%EG{1ectMDNmlQ8v$CIP8)YQ{nVh>HSX+1}*gspI)LxjVmXk zfs^sohJhF$?fM_K-cDK9p!{Z;HEfhMlSk{qFHyveI=0QV22Ws6w?N~Mx>fqy++0@% zfx##1B)#1ePOd8lCel1h&!)$E<8>uMA0L~kaNuv>_!Jmru-C2kgjMLdY7OiC$}VH%1#i^}uvr&V;+@_%Jv|`B{-4sWK69TA z6mph#oZh*1CuO2(eVpho%|(e^5*mmAYwr_U!Ck<>78ML*rl22v$#{@-)lc?qjui-x%Yt1 z5{7NX?aI21 zSN?#@laJ4MF2oQ>mykJ@W@%mw_UHEcSom z_N(9NP374bAXdtVEls@??v1^e5oqn~pgP0r4QOL1HC(Sd0EO4F?KpNI@@D#z%bg%d z^!kF}@G*Eu)}rdeZk%7eMD2ksuj;@ZSD&Wz_O&4+Som?-foi5T^=vgI7uw#)oHx5B zWaGZ#Wz$4VpH)wkPL2TFqvV4WpVkMAV_=_EO>R4%=Lo_uIGT-~3jur`v-fp=CmTgZ!O7C;7HqAr!Ykyy-xNu) zQ09{t=P^nYy4&b@p7~#d`-d>m-Rb=__Pak08qBUm@wCs7U7yZ;DY)wfkZe_ zEql5w+{#96{$2UAzITW)Ozl~!qryPQPT!Pe`qkXA(0~>WmAgWA(WdO^dB~q+6mtPqO#9z6AXuyN7y? z2W!^X^#+B>iX79-=yM(iuTOu{*b_nxgb%QL@|J>SBio=yI~b0t4r3OdDg)KTah|)e zk8}*O^cIWq`A-56j}J1fbN+XA&}Ls?6nt3J7UGn)Qjy~zZ@KpSxhNep;fOL zocUp`qwKlvr^qYn{z}tN8I*q^M^amKeJo(h9`y@)H`hY&fSdKkcL~^IV<4I>UUMMM zj5A`<4-1U|?kUY?|-u1qGRVW0m&WA>vBGhPNM# z=|)!dG@51^s*(Qu@E1TJ9Ktgwh3VKOFZRaUd5H-+wMYxoL zi;9ADRmT2e19*8lxy6}J3^FmwqZ1EYEi;{u(J25!c>Y-70V|4*qcGT9&=%FY-+0|a zL8zsKQV%;>yiM$rAXm%d`dP#1-iFwD0uN21)wmS3O%SdmoUg7?Ibc$u5mw-N?~6(o zD5Z1a(#vuc!`Y1q{>>xnnR*`~hh*Wgq%y_9LMslU20q_UH(j|U@8NI$!20fy6rdtr zohB#!kzK<^4)~R~U76bSH4tL){rn-Yb|Ch=OGJUI=lP**$wbG|9~zxo$%v=`uhbiCaaQ+ikl2wHy=%wduQ2u>>BZ4xvWgB&P;-Kv39c5^f== zQiLqU8dogu&Z9Mgj5%L8ru!b2>Axz|VB;S}=7*nV2G6E>h!F?Hi6fXMgM7(z|0Znx z^#YF+w2-2%DI>W?>W&ranq^jWcBbb)Q4?OQ`A4o?G372jWw%){ZjuQ4$4Cp!Id{pO z>8yleEIf^sS6u9qdKL#CE4LA`$AB0}qo)Pw&Ln!xP+NO{8O1; zu+2GOt!Zl&loSH*0XTlw>*xvIB^lO>=RytI&K+vQWf|`h%N905YpjsrIDuok0Yx!h zzCJr2SDGyZ>6ul3PVP42sclr87(V7(;vk9&5=XJ=+X?x>*}}`{CQVtrFT=)ro@nbAPJn!CGE-^5c z7=|U*$g#%JDo$ik|CwldHJbgybKT;W0mPA=*jhaX9o{*0L7egV8^x6L0H|760eN7WWvGdaSZgx`h19N~YrP#cJ0S zm)xV`xwB`WG`!kIj<6(QH2m49Q7-&|azT!XSC@dE1+>YknLH&3Bb`OI2_m!ds@QW~ zb2SI8(|v4f7kpBN>@Kn_&ULdHo5rR^Stag#hirRW5q%pe7d$J=anLj(b(p(*wI)1 z;4eww30?469vD@O+E_;TP>5H^X3Q;SO|LrNa=`P3kiME-QRF`BZ{Qn8#Gz7n@gM1r zM}3J0njbw;WrsHOYn4?&81A@1loCee7QiXqtXgQ3HKj%CNw12#d#3E!Qhb5qO^P55 zD$l_vG7sZ}4S4TRRO{P#IcXF)8ER0o%0tUz1Z|yGF8Y5~Bu*k<|O(Zej$U#8w5j|Ar}E%C!Hc z4>zW_@ba)Gti$=vNO6{6Us{?s{$*0ZmdK%OM-C|cxZ3N0wQNr8snR9R-{Q0aUPuY= zEq;!>c=lzM-1?T12K2hZ|BTl8X7O9gyvK&^vxK&BpUzDtjc7gBD8hNpAQWzIOvnz+}L3-u)32D<#1U=RtkwU@w>yCKD9=J@GiuEVakww?A zL~jSPtOIW}ojdUghCZAb+rl&3xwFs+hoj9vjYHvyQ}jpe zjaov>EFs>jbZJ7KKhRPbkgh^;x0Fj)t%Plp3VOq&4ojY!2NW(>u1tM}FzWhd4;h4M+`4*!&Cs zz5^nWyYnD6KchkTvjaE;zWuUiHEezE>o6)|_QL=6z>#cOAf;DTMKBo z){CP@^X3`R_9L-qX&4`nbyTl>6(GjfOnvaW>qH%j{NW$I#*Nu^q~AJT3NQ55XXB_p zdKsB#F;Z8eIma#`%waIZd(NnB-L^*Y30~!fvEVG={E@_))iy9_nxf$CG4H z#j-uuv#K0f<8WDyw9MGw7d*db{Z|C&@kVYRaala7^vLdmjSy4E!SHe$Xf8Zb7S$__ z;_i3r3Y;$Gesm3<euW`(t<=z;B^X42@Ue`m<{&|QPzI%!sBJMOIdDt2hgl@^Q_a=z`n ze$RKVGaMT+4DFlWH}I))|A^)%fa?6~!0}Y`BeVC%Hf3lPbp*KwvOf>G z<)BLa0vKn{73<)I>IB^ASH-_Bk>EQy7oJP4ib|t5;-5dtRh)jU@xL?`-0bt8Y5ARm z{Lb>XNp~;Rk7(%vap96u4G=|l&i5|Tn(kItH!=^siJFztyLr8@(tYP<(?0)*p2G+S zi=TdN+OQno7_DThRtwwi63*l z_J4iRuLFfY1Z~DXFY~E`&f(wqE|n(u$LJg|&&j$zWP7_EllRq3_`aIarKOJ#ll~>!#yv^NY7hh-4S!AAo5k zC;-E{Yv#FrSgor&WuRawoQb+la8c(Dz8qtz6*2`^aAE}t{L zdm`6t_PTWWkEPbJ#=&ZJE859M$~C|=&_!c678!xYq*QIlXC>U9aHk) zX#K*UpWC;YA6Ig8-nV>2w7#bwk~t4KO6(c1;dElfZze->vPuqzIhoFakY^3IZyt_L zCztV(D@*Ez$DnKM?Wlx zSc+3~mZS#k|8ea(ECk}IJcZ(i^VGUpm%e%1|cz9o7Z-?s(3@6dG^O_nRkz8MySZU z(tk69J8~b$JGI%@sRti1GRs!$vUoEafliP9kl^{N3?#ti^~Z7T16{9%ue>$CANa7) zCnD*1dFZOJ%3Xt`qwOi)icj9^$-lodaVe+jp6pKFmbloJs`u^v;yshw$~W|X9IZVF ze15Z*lbuu4H2XJp*Es7`Y~&WJig@NPIMO)w7<1t~8(hd1FB`Wrp2MSIzlAel*WDsb zKn*^rrgIv8qB7P(Gw4PpNE}{`hzL#+V=R$oGn)3%eck4Ws162$^m1$+SRnLqow=Q% zFpGtdM`IiqO=S>DRVSbt+-5wWUWh89^bc|{XCEpuN9#2e@swTwIXhWPHzo24 zIS#lusVY6q24A!r+9`Fuc(hXF94x*McH!iffU3>2P1x4X$iA@Ee1hkH<{nyirI7rA z`eV_cPpTnLYxuzFna{%mEq7eYzy3>2H-4DS`DV&ZBjp-9dU6$eR-7QMRX!zc+V}h? zp6PU54YUh?O>vIY`jptf8FlR5uo%5Y-LsGB%SnK$?|yHn?U`49)zSOhSg^D2h0~*p z!s4+s0^2*fKj{tYCJ}DTA)Qgd3>Id1=TlFghWgz=ZiO0yWoz)p?AlwgUtzin_z6y} zbutj9kCm-MXyq5FqJpv=r_sStV#Ge< z^DxhJoGqcu?Riquf(A{OS3vI_Nn=qjtV*e+?#p9|4&9^dl0vNp7mYk$f{*?ouI>1L zhxeOPIZz5c6m{L!#-6kz#e1$mw9i|tJv#hjV~JG4paU3-rGqHY3zTcI4xHe;SLmGa|m=gtXH)hvcr=@c0 zVb;^X1243gApMiLr;)+=M$<^|i~}*m_QN{!Khckwb_ErW_NP&y|0H{6M{#_t=3I`h zP_#3*#)9&QZjhznrlacB3?eg+okfgs@gg)0{Ci9cX*a=RdAGczwv0t4U@j*=eq5UC zz3EMp>*z8-OG7q%0x^FKT07X+3f^W%FU1ly0GZ|3Dv7N3VRsBBm-HehbCp*qW^axM z5bU2iRjW?Dwi#iW!?_}t{+0zr)r5kGsQ2it<7u5XCcW9R5Vtj)osLuB&^o;_U3-it zOJmZ%FttOuFuq1Y_+!}2%I66YAtYgd;na)DlmUwV#lr)@w>QFD) zSEKkj?4nh=R)HHF=1Y<{+~o#bW5i;r4XF9-`|AJ4(OE`C)wK=y&@n;7Fobk>w?ntm zT|KfNDkjuen= z+mW5>$npP~7CYdl*;qec>xse@Q6E~e0}rZkrIb_0R15;9 zC>FfaxR@GR3Uvab8J-mGS$rzveYx>t>(4-^ToXfoM~IFV1$y*j=SFjv7+MPoGqt5d zD8JT0Xj4f@)^nBuP~xR+{Pi#*1=s;yfPRGf=NdZ0CiAq! z^I8&P9^wi7`6niuBAVi!g-0J*-c%X@OYMkf@BEpTsLVi=vP~%+KO*VvXUw@6#9_m!hN_B3MkOI_R-Ior z)3=upoLlwwMG>H(SiF;N1c_h0i8VKjKz3~veA|x4XwXgs%IJlPc}+wGmx1b>4+iH* zb*ZXm)gFQ-q~G`vKIx4|9Y0^Ub5lr{xYmMws~!`3zVndkSfve{N!t5GF^$Re=|=Qx zF_miVPt|BJ-$SA8^h3q{M8>qOPxzgwm?5xTp%njo9@2bBWiT|Qg7FDGk)VlxV>^%QFD6q-Sr zV_b0?^&*ME+;DXZwAo0$zAXM%d6q~heS%CMp7+{__J@)3xnW5K!}~?(%Sy+4uaWD* zb(xEpx-6?R(Fh1G5m>Wfb<~h@pt}jCp!1Ei4O?x{yT2=B&6h2W6_rUg(*5VL%jL(m z6g@zKSv3e|B1L_Mkh8q((3~<%GH?-0T8r6X7BYV@V54z{yqDOzY%|uot7`d~xK)0olic-q zg%{Kk+1NM&>yMGVNE4bGTnu#7|Gck1Lj4d0Z^%aT(k_sYZ6D%MwVBDDr95{%+~sy@85a#LHaEARtcKdJa$OVdX&OzHcum_n z()$teV|a=|@JD`bFG6a*uMKux?APPCkY;_W&oAe74TH!~zS_?^%L?OIp2YWD0Ph3M ztXgO-3y8&I7$OcEUAhpH-A|mMOc$gz+(t}C9z8b}m2W|%!x-hLKCIGbood4h?co%) zP^Vqt6nDlcB33;}HzRFIE4<+Q zs^BuQaqX36Sgq|pspia5UpU7Vo7_|`D3R6@I1*!^Gs zE02r9vcwl@8C(w;1Q<9OM$Z82I5@Nu`xf0zb2N6W!qlqb&d8NE@*;zZecReJ4Sf4* za(k<35p4q1t|St}+HW@lDNP49O>ePUT&5RfsRo!%8axr_E!vfFp~4)o3l(vn!{cl` z_p40tJiHV7gv^h_2;WBwMN5rI5kfvo0!b>hYBBeoxJl96+CE0_tDRbh%BxG)x+PqG zgWMTTN3DT6DW5?%1*;cT9MVySL3Jb6V;uUpo?{6=$G9|^n?4)lyOCZ4AvtKsby#`5 zS7kXsG$%kPlU=o&_@>eJ{8h$dI|5_2aI{;47v@+;?cZG16tRPro|!_4*O@=3 z3e1^k9jam`ASJ z{-kzHEn{OXdAa{^Ex3N~5{ArvRs@^qR6AErlfLVVmUQPH|9t!_!;3i| z@rK7UgzadefDL*LKpE@#c4M17Td*J;FR6uqq4peUp2I-v78Zbu#!y)iZ7O_2DcFl%1j z>V_sIcR|H_i}C7<4fP$p;6;AjrVXpq&sqgTDI1M?4yY7MjjG+?+xoACo{jEdbmUEu zlK0r+HoTJEV@h$+7ab|(AHB+%>#0W@C%4dG6ZC5bfb^&L8Q)_Qb<_JJDjb7|v{;Kw zqKq~fGo|IBZ|tXSQ%+!U7yLEEkf*k*pCe2VNsCyNQ{IYBc`!GOQI_DYJK%WWw?yKfS_bOPv7I%jHoyApGS&rJ)wus;1ll=s>?EGi?1Y3C6mh$ z>V85yOSpDukvcTjE@o4}Ay?{;k6(33MOmeXnwv-Epm#gon3S(v!#UUINV2r@Ny=uj zzD5PAIECJyr#`-?o4^|cOPIoJBx_vFS=i7zGI+vzevEgx%9B2PE|9lO7YdE?DwD z6^${_TqC=yv`dn-6Ln!$%VWU(Q_s0^57TuLQczVOiDY|nC_ikh6yyH%NdU;UiSzBo zP2hX zc#H80$Y@Td<68Th8+;{|(br%?hl=p;~R4y!KY1iBq$yava-PZcDeD z9NtK>>PgYGd&jVB?T%NJ&C^W{&#AACbKffz?Ma#=EvSedBA+uG5r|13`@UBgc5Zyo-kq1R!MB{ZI$ z(MPrH4<}aKmthgFj4q(o3G5OU>HR7%#@^>U7$#NCU093ot_xYHwc91D;die}4R*7& z7WqK7?=7hFi(c}De^<06DO)vaa9E#3Yp|dAyCrwg;Bguk$FrTRzLURcC2#wy1()fz zxs5Q7YV$m;Se=@)Aoo6zja=uzD)eT9P3?o#_L6tp|)L{E*!Jbke z=Cz9m@yYRa)#@p~M3D`8+_VT)`l`xFBv59CO!oFME)ObzgcW;x8Xm+ooTD44QaLZr zKTfeV$BU8?gZs6lS^~GPsGEkc0SA^(lk_k{*%)(*lF>u$HAm^@6P{rkD(F|Kw=u#WMK zyo>U70lzE{p3$Fy{9j^E$DcrD1Id2TdYyC=OPAXs9yK`7d3jzki{(DJJ)~AV*AQ#0 z1H-@5rVKK(xkl~#dgAdb?2o;~t9WhrH(5iha!?xeZ}JEBI2HQvA9~8TOJVQT%(p%= z@Wq?`&yY2cfL!V)^z9~&HEby?s#f$*!0bQ(4qX=|gAWdaKrPebxfw<~q^WyKQ|9M^ z4{2HnDAu$l_NJ?9eb(=gZ{317hj&XYw>+tf0V6JT+0|@N*h#E-y<_dpt7u zCMS4T%#n~6Zu8vNQXDy*aO!yPhiXlpFP0V8PTB18+e^!qe{o#YohLG#?@#x;T0T&I zr-iCB4VXt7HagudRC1%wf-LeycW{rUD(^9D&C6)&)nyEEjh?Rwbe{lg zRu1pmr$_kSN_BsJ=izkpw65dXy|}L3Reu!-y(OlTdIj@!98RQ{e*O>U=RBUtYu@pS z-rsflt?Y}de{0N8My2N`C(5^N9?MD}uk(C&hmzN%T=&Tp@j8rl{?}( z74_Qrs*zs8WulOGkKh-*dk79M99bM3lW%kQq?+F4c+s8C6+;!z9+`D|P#SrE60o@v z?^Y?r$as;d+I?2lssP6$MG_q)D8D0I%6&CHIfW>X=Vwo7yB6kd-OO{n*rfQz6ciOj zr2Tx!Qj_UAgXMsNI6rEsFT@NRX6!(`B;M7Wx=0(fW57;t-1S z40gN#bM2G3FZJXh1zLG3u7Y-|*onx7e&;)t&p-Z@mO?^O`RrvdN|_{hJdU3HG?KW? zapVj6U=&|eZN4u7<=BS+Nrkxlq@49Cy2zh@Yqy?Mc*HQem&cj zW8zVC6xq#HA`G6#Sb3NE#uVC>;ut*42wMN0?;fN~-fyQ8!UZDw&YqV~Ebe(&9-2Fk zs}>bk)=WpUGg+=gCvH=1pUPo_RdOX{WP-;k|Hrr+Zx7ex%HN9Dq+^XuighYlLvk~n zt%mzCWqewv681tNU8v1EhIIJq+cJV_S|@aj1zVRKGx z1LG=y9Zc*BkA*VGjy#fn$w~=>fHPgAC7ddh*QZ$OT1)|HIv<8wKZ8ia?ldAN?B57z zpO5rz7!qs;!=oQEz!N<&fJ8DB-fNETZ4Wzin)n(bb8}tiuVP^ywKgHI%8KK7@Pa2* z)6Q}6Kg{#8hwN_;i&A$8itz1OPXuWQ7oN%y+CE8~{$bnGT1r8(-eS+_Nr*mtpB{FZ zs5Go)E-WS8yGSo)GciV{W6)aRhwx$~*Bz1Px?(>WW~V;{zUpt!b3D1=U|J!c;ORCL zQ=}mewJra8cRX5!>SE)Uu-1KhJ4$1XOYZKQFew1mqU+rx$=jM!m+Vp|LwJzqkDDBd z<*!e@UfYup64+UF9D|GGl|@PL^h3N5;S6zyQc{?HXaHj7zL_%$gO44g^|`J;P^f{} zIz+-EWQy2}cfdX;>Zs6`E=QaSmKl}DqI3STQzRMwD@IOQ)GOfSGL8_6XuD7iB1%A% z8u7u$_Cr?7{B*b)$KAjejRaQt+a(Z7-J@Ai zXbGBwi|SiARYx-HOCj7o4ZEEo0`MUYdo-CRjZF$_o8CJj6ufugM)a(83{j`RY3{ zyK~)YeLV@MtB-U6MQf< zL#(u?ahE-0o>|F+$ZI$Z;XZ&qBP4p;stg(Fj`Y6@Ba+w-xBo>*DC~tamA!Z?U%@VO z#P|;49X1$P(Dj+mY~Iqik4`ynCsAoj^Er#}mr$$^hy_lPn_lwwsRV5`%IzdVBSFC; z(rEM$ubY|!wdWnF&^kQLB$hb2M;yqRHGEUpQ1#^BdA?hlpqm;yed^MD2>*BElRGV~ zU39$M(7bk)(DEx4Ued+S=E(rjQvtJl(rNN3E}?YZM#qfk>9zd?)XWqbaHg`_z~%ND zI)DdRmJ0QhfkM(?YyGrWsD=?T@jMNgIyi&WCy{~vttO(c|EQe;o%WcQ99qSe!cznD z)(`%nWNpX`1GeU(W#U#KI?QH_n<7b^lo#VaC^SMiT9fP)_SMc=={iDsHQdrDI6nmK zCn4yP8JHp&M^AoXpn@!J`?yJP^&;OrESNIl^&h3Z0w!@iJ}{Aof=a9Z_pYt3IiT*e zY~DKW(Rg|^^JSZ+Wd8n@lm|yp+#no|S9R0Vl2VaH$*}4E1GnZgt>|(pt<8WAza_=w zyAR1sXv$t#}r z6Th}P@|B6fPnz2!69&(W&1K_p5^IvYp_J-bc`15PN;aP3MrM@4P#a8KpZW&#Uj1L3 zbKhD>QBpv|$b1tcr_#MJDkB^V&KG$2vLGo|#!qD_s8W^jmZ>B&)W6?4OKO0S;(_um6xR_H+=0)^5(J`@7K z;{_AXf)&(F_D6mPpiNx0O#9HIHZI@^G$;#i^D|l&HVfI>20!O)4`qd1llTceR$RbS z@)`A;b5WLx?VIACUhtY?bk#^>twH~sjG82>&{T$U(NPn^A8B^B9U!)Ns+HI{^4!=9 zM)y=Es@_GD(2*jRY9F=|aJu4iS`Bcr9ex*(^P?RgR9zRwC`MptPd19Y$=!g%U5Vl#q0gcM9RE6JVr?^cjMUE7y3FUNVm(S&lj>Q#7#2)?*ldp89Jo$A>EQ zsur4mj)vJ?`DUD(tBt-roU6SkAEoa*NwS1I^&scb~t<~9oy`px{- zLt&0(q8dZstJwh?+EegWiJLFGV1Ib6iZmdjSB|ami{kT-nyRJTp&p?RVntr5c3r4y zr2O6oA2U2;n+#C~9TD`s8=giyd#F`2Rml3#gpB@Kz2--9E<3i`2vTmJa&Eag?gF(> zmCiiX_ZFz~M@LaYN5Wwm%4F6Wccgx-cr7lqxY(Y3mi{6B#uWbNt}79QgBE2?1Ip}* zMv~^4l4Q{jFlaEX4_GY&+<^w`8Oh3^B%YVzy8o0G8veZt1xuhdGMr*_DnLUlazmv) zyI6E_mO%UNwtNK6L_j+15W+6!`20){G)G+7S4;1KuSxD*Gqdyc`4Q4+7g^3qhtQkizRV#wp!ugKv7(UByN`?=_hw!AsmOB6dyy? z7-vp0FcjKtk0G-)-x|w=VOpzg{bAd56y zzy&|@gXm%_C0}G|zLXF@*`XX|p>jKrnl1&SJRnmJ5Z5r1nRp`XF$fENcI;Y2DvbB= zN0FyXT=gC#fhV3VRW7{$%bY_3%Yf~Eba2uMqLdXhf_a$4k1P;Hq82#d7mQfAMokE- zqs60|#)S*4$-`X}klJiuwYrMUHzkaEaugC#IEldBSNcG#Ku@y6%;jh`AdJM-+Eu=d z;t)xWT1XpWzHIn=b;=+!^}1`uov-m9z7an)C04?p@5oKphWfihnL3kLBW|r=0N0~; zNFe5W-m5H&#AOSLiU$sh;2y|Z&rG~^K)cgH+Eph!tP2d5sn|Sf~j`ipM%FAq#$cd*c|;TIW5?BnB(nl z+7;<9IuV-4XnuOO`iCZNbPBt@7%z55wd+UF11;_Vo78mYC`LFJwkBkV!*zyHV%brQ z@Kq37U0Z71+&6|8mHYHgI3@89jf=ZB+?=dqmS!DsWWTyczuVWxd_LJ`=1bYmO#)lE zKN`bnj#wpAX*?@BBuhM?*VS6lZCc$3ZRG~Aj~7wEPi+sx$Kei-tJeU^2c`>nxR9^UzBepTt6mpFeQ1u zy5MI@aAcB^;Jw0y4nH=HJY1G}&x%~C7o++fcBLLpYyKL$64c_jO@NtgSV zxm;JNZWDXFfv)^eo3DHNmQZ;Q$36*O){Ha913MT+&yT4tFCkEt-?$zh*{^iH^0`~nh*=!pcJ7Zt)!=j;ryM@* ziEmD!?-_nhz5ih6TBYi6gqucR4r+BNL(wMIDa z5cK7sMbh2x{C$@9S=6sS<>EaA`E&uV`A<3TgkE9Y#NYRr%Hocil{?9)fS|SPw2Mt& zYTsMZ?y{{7)43d_*nRsG(ysv{2?$N(%lFk>`Vq1wN*{8>DJ093S%%b8(PX^w9n6@V z5m4EW4DJFwv>EMM$tuS>SwH9BF(O0io7Y@Xa-rNZoCiEa4l|6Tn6rl9Kj-1Ey1wa< z@aEv=LwL{uB<=+>_dp%7XiDK_=Z>q_S>pu)5Rq8_aLG1`;svPnujWjDPw7 zy$T*`l10CO>?5EPEXDmV2+P}W)y8oDYDkICnXbTmax#6k0FVLySsIT*1c7C}mSP?& zWP3TR$W5scmE^e2e?U!7HEqwzn~}DI&9G+!g-mcRP4fL&^8LF+Z-Psdx?|nNUzx?K zMC?KG@UaoSOcJ)OlJ3ue!=sNKHC(mLD)#0s?Ws&^<2)zxc}_V^85;je%LPU}#Vx7b zE7obOl*OB`6RNK3-@@KH1r9jt0|7{elbyoRf=2Zz=BZN16au2x`tqx+&sO)#=!$it zpECHfpdK`62+iexW=g18yv9DW(y6p3Snh{r0kR;)597v z+cO@oHfV0mEAX#}JhI}nlW8+`WE{hx=evw1a2BjV!Yf(fLMm`G=VyN^s+^szxn5|D zWp2ak+9t(~gQK(@%N+|fn9x`v?WvPmt!3@f{crV1=O_!I?R|bV<0FSUbxl^j)*ik# z*xqaN-#Ge8`TL>Yz*0Bm_09yINK?Ds0$q`g<$_d)_~$FRlI1` z_n}FYfy8EAVX--?5Nx*@tXcO3L44X6{ydtlHnWstAZS6IusfZDD`AQ{MX?k0I8e>e z>`RT#rm$)ulls*oCTj3(nR4)v(~BP+#mexZ9+7({c!c7Elm3xYBz!Ec+{C-9c;2TX zyfTr|@n5U6lViq&&&Q;fPFxbt7t``02mb2BKcE^DWj%LW+09Rvu3xs9YGCWzcvauI zPt)d1V;8>Fd`(m7=q`TVU%5(~q&@o|({_{VgKA}M62-X+yy7xdDB+#Vh{g%Jl&~W# zr8x@^k7&-)5ZgvP$_=tUqaB6B8L`6UUNj~;YL6y*bJ*XDatu-xYe1Fvf^F}oxk>!7B{a-6gzus13*owlo?u4FviC+)hY7c&k z+}YZ@>qVAPk3IOcXZvsZ!9QP`0$BO599keeeJ=T=BABKpS_7MtHKXH1~1J`tHufmEZ2t(e@LYJUE~mSy40`w^N}r9 z?)k}r<;%Vl+s?o*U4cK$epyR;ucLa5)j=*ej=VWoHm|?!^ zvdnM%{3NsA;PLDfhs&T8S*PqkJy{uEC$Q4r#&5I_?@pXn6)vXsT+&P^zNg3@V~12- z^N$6px#U;SgHZX@s`roNz6P96%YF43)Gz+*;ICiuroc>Bs&Q(;${!^|H2JK*No=D$ zjk&Ydr|M#5gTIQp#^c$H>=C12Tca2$f5VA!Rd#K4{ZV~m$I(#(YJ~5J(rG)6y(Sw8 z2P>mjR=NSbWPsratxFo~cDQ3>KOvo`MDI3(n@@NHgZsbx?S}?OjtB`*P%Vl{D*Eq= zPM_c=Cw$XTP3if;9Bm>dY^P3Zer6OsC4Z2YDV%=j?()baB6*Kp>_5M3kfk|m1xkFr zQvIOeuUaFgQrIc~8N_+X;)RohWGHnbDQcR&Tk17ZAoGi0vBUP7mEg(f|pAs=E-(1f7i{YGkyZ& zPa!^ywT!@=V+}`O6v}G%32BxwLI%&iroc#w9%R!O^nO!D?8nNMq)v8Hr$upD^+k}? zT$=woaW%+gW%9UyX|wqmA-(gb98F0x(?5i~A`ZsL>?zU8iV6bB8o3W-N^fX1Eb^l~ zlGYs4!WsRfSr=tnC11u6!Y9|<{XYvt&4^8UmiG8v_;h7Qi2KS3huH9Ef6UPFZ2}|i zd<$IV3cX6J%}A}ya-U&uFg4BCTc7pwVn(V2XT8;x=N~j6&fmTcV^y64$^__aEL0=5 zs-uOrNug9d8`_(w4BN0c*yOf4tt*?5Z_$s4eKg5n%r1C*of!GeAkU=SPqx8ANGqBm zRwgb$_yOl0lhTgC-T(k@=G4y zR1XhInGq?9e+F`j8?t(GGC(_aND$|PV>vMp2LrAJQifPLe9$WGr~^WKd{t|A_jr+< z7I43$Dm{%tt{A+Ajp6y62D8Gb=m2H58SbGl08UPagIq8w>`%1Ot4KDk zh#etx;(FmFz4CMk%3vVlJ6dzPh4LrDYn2$gvhWJ=krX`xq4Cj zeBuY~Xqd6`2T`o65sIf`0YlNUG=ExrJyoOhC%*V)pD^sQ%z*LMqC`>x|LL%ms#*s+ z+F3C19zHp^+1AnU4(EdIBR~j`P)@V-W%lnw? zJZ1tLP_W>YDcR@&^=AyMGeh~i+3EebT%*^(`kNgUu1=cxQZAELB@aB%IjFJwGqL({ z_q}320uR1TzIHR*4;zWYqk|=sh}9w?PqbFpXgFdB+F7l9(94J)dxXhi2AqSKTCQBf zB+4&CHVEJOMA#prsxArMjK%qsj0hUE#SCLa|7ISc6HMIpQEd(tD79KNwepb0Q|=X$ z!bBU)mq&wXCMvT~qk}%vg{EQCfxZ;Av%E($A=zrMRS_^~ra!#g=enFP+hjg+;d<0q z7sg$!L6PWlG1z=P-5mNyw|#k>6^1K1q7jay#05QJqi6!0>G}vI1CZVjBURU5v>6gz ztT67Kw2p+GGO}g0N-iry;T1`07i>V9uT=R{S*zg62>oHrb^#+~$l4%V_g=IUUlP*u zpYZzUlaH9eSYx-`lz_Pzr|w=o%Ir8(FZWf3H*kHAoRtEU98u!YWx3p!{4LR9>7?Jb zPhh=_j22pM)SUp=o7Jg9sor3PU*QHKNy>swl{*MvS0zFtgY0ErIAkJ(hXIwgF5VUH zO zIud$4CSk!3^F0|B2{TM`2&#p#xDbkluqN5PYW10S_?1NIR#DDFplNHO`0^#+i>Z%FimIqES&8J?dQ81K&0Bwo z!sM2ur(eXX2Z%M!-kBC1smU#^9;sWwj%WqBJ6Aeq0$-m+!o7oDw0xfKkownbndS<5 zc%+={CK^}nK|UTiLmu1bK@Ir~57O0Q@bKYvs^oRdO>(7Pq*>JMFgn#SXjjRm|Ky~{ zFHtSyPyl&`XhC!+Jz|HK5gKy zfgR%StY;L1^Pw8G*1toV(q{O)=WpII{C7Q;3xD_%NhY3E2EnH+Ri&Wb(ZsEQdV8c6 z)2qFZ)XEACmdA^EFPUW9wy#=Q)h1$aG458YwaCaAEADstne5RchduJqG)H=l%!;18 z-=)yHoF~eZey(CPV`*S5(^ti@WWQL{R4=%WeCWL*=sDl31sg$z4*dsI;WcIORs&G8 zvUr)8-H*Tk13K5oxe>;r5yozc?^q(*5KQCdky1gCO|7r|eF#b0rCf+CiOVS-;81=- zI6PCPTROo~Q07=#Y!jxMMD-hJ?{|VM=a9o_pA0FPat_~v6B$XiHx2uAmN>NP3&Nrr zdXYHtQR!fJHkhj;*X}mWu)5~8f&8>dxFnsvc{?|EMYxqDyr12rwncw?*=uKs!9^m_ zC^tfH^rdiZT#Agwf*~nhTA)l&d|qDs);#m@g26*#chCX>XqV-bOPfH0X_lwmi!z1%jN(UHI#dsfeMkL6jo>^q`UWYUo zkmeAl+1+I4YVqSnJ)@f!@TVez?!JzX5j6I*!Igc8rH$Up6?8{{KLSQVEg%VHwy;(3 z2ZxM4jMW*DF^hyJ1Gfk^!&5FgCK^Y6vI;t4l6mSQ$~T(%_aakb6|(5UjeTCutyw3w zD+52kh>cQ3sJ?KSGkau0qLG4$tMf_y@FKNOle7wW8`GL?Lz2_e{Z_Jz>?%#mXOV@4 z75NMyn9AWs#|2(;;PXe4;kmvD5eGAlAlZ0j`cR-*gwgS;2*o#}$Zj3^a&{srRV6=_ z(I8pAi=_G(Sa%2PN1f=cTmHYOe3?-Qhm-Aaj_I50Sj8HBdsCNptadpWcBe3nR^C(; z$=ha+)OWn%ts;z_=(m(|W!9Z!{{DnIFv{sO7SEGs?rDZ5U4<(xWRtOi^aNIXJJOSL zpwLC|uz|NWnQ1Fy)^hC zyIQACg}z}(`g}nThtOIJCJI%^5F#`;z-MwB(e2JARR%6u0>!_l7WV@e4C=_qL3@0l zTrZ%k=DMe8;CkBN$29(#`NdjC=GS3reNMKw^zbiXS#Ky6Y!5=3e0i+vd5mwW+Q&=n ztQrhnkoFWbXsUvij7dEYs|Vy7LzbE0d@t~5z-|Un(C=v-7T{qP$lZ0|2On+BH_#zB zl{pWXD}z=hT}YKeSTh~m&GJSjgTwX|if>$u<<1|%E)~NTZ9E+z`#m+U55m-gZPy9l zjobdV2jN5h3g-0++s?d?MgywTB9ONQf7VbWJ*XPQTTXYy%emB{kQUgJCoe8oY$FR{ zIjl@qtetD1Ckae<4rGf!)0;@bfv_fVWuwm|ki&8|-T5NE=Nt)c#$qNM+-=sVMODu@ zz4v>?dpiHRDN2ydE|$QE!|adX-@RPo(~NMmX=DbN?XeV-AJt zUi}!Og7I^&xa*hp^^YnIQXL9NtI4ZdEmOxuU$)#&75wc*H@sR*lcuAM=1WhDo@ z#+glbYOPo`>!V5~XotM<-vJpn9u~ec2I1dpu9z#i`2pW*Q%Ln=?9OczsHl%r zG+ZXie!DO0oE&3ZBCL~lY>rro2?VdW26UlcC+a7NT3!l8;J z%q6;Haqx<$Mex4Qz^`)ZvKZs{oYp@`Gj(xQ9|r0=8%@htPB&MB@V7^vRJZL~=r`)X z^*q`w7$Vqt8jLJ^9k3fHC(@42-i9{$Ue}|z>NHm``N`|TS>GKpv_tNQL+)3$F8+zh z!`;apL(X5K5P76BuS*91KV`)XVb)4^B}!eXKv|cCH!)?P)L79NRx*BS=oNa}t3&R! z%BKj7=>oF7k}XnVkI^NX_xD&pZ%FEU>kjB&6p2D_;#k0g##sc@lHX1Z8bGEvNx06g3I7A@PEkx zf0W%wXt$gI%hk<}31j}32D&$ueaZtxt%4+59jl+`sj8c(1sZ<}6h00EABW|&1{h;l z$Sz9P_7BMnt0C8a!|j*#&2Q_26&Ze9v{#2s41SnsdrA6RucJrjt%C--3%xeS^re9v zQY1l@{+cRo(CDzV6EjbC%>v;KoYJMBiP4O)={Hu}?MmBFaj_VSQLeL#Xd9;+ufS1% z$Bk-a6`!f**$d<~)J(n9>K%W&7*Vu1{B$j@h_n{5G5=+|Wr}R!q?|pYC@D-wtnR(vCL4G!$L!qRg<|&+MP$1wR2%s+mE!D4{?Jc-%vT69 z@d#?ReY*QWUgVuDFSaY!2`YHJ`=>GR>FXZ5W&LQjh^ABhNs33SR|SMRYxoMA;ji~6 zUw1?&2O8L65KqbG9F)!Vp?zT@k^|d59dZ>H$_~o!NEe-AD0JhsMHKiqJiZ*-YSOj( zKq8HfOgTV}s81E!JR$lTOPSl6p%YPx)xVQAJLP*v6*teGV)~dT@3z65@kU@{=m!M* z9`Jo%xm;dNw(Pmze=57V;v7mYP?lf&rJ=6^S|E0u5mn#ygYHNt2F0DT(CyvdWU>0B zp-R2&p+7JwKk9u*FP46sDNTNzrc(3Oc^?R!nd9S-BP*+B|8&W&S`I2yf_+1C8ve?@ zb^ujTL>Ol&SUriGh*VtW>g{;a+x}=jRB5ww^7MTo$V2Kk+k?pr?+nHO8h%=u^AkR9 zc`{`GyQ6|&B_o(k1R2?4b%PT~MoE1;dsV`T_Z=dTUXUXMfH9>r zgOZjz1SHXlRu-3o-kbBU1Kk-pmzxF6_}p&qadiU~XiQwZl#=12X8?~(ApM&Q&EgBK zXQcWioQ7}y*y)k+bWq0=(OQ=9U89W^_@>`0F4ODMH8}7T>!Bpi75bCcuzsH|w3?4~ zh0&cpWUDEE3WUr4iIDA+tH`L#o2H-CN09A?L4UK5{YGcz&%V7wkqW(*=;~)!tcaMH zKJ9w^gVBD!QiSyJryKOw>YF*bvsK5Oo`Xl{-RBPHm5&=`OB6a#jP7cW`tLruzCFe$ z{rPE^iZ^%L|KA-@r^@pmyV~yE&(qz*hh;vDAO$;d74hR$+7__&cGmAxTs_h#DE2nB zrHD+`5(x!FpOq*@5J2ubzYTU&BJk*yqF{!*Y6&!gW}B<2TY?tN4zGW%9WC>xSLsyA z<@3?hnbg=6_ytc;^X650Wyq=5Z>bk6zQ*FiO)v)K>dDON1t#AYu%$O!ijr=}yh^cp zO?JZt?W_;q>>xs3nUb0{nlw+;tG)H)(l-{_m@7aqY!vxdeD;P z-TWFM{09nr6^08Fv+^AZKN@9-rT0;)WT^wAk|B)$P(z9T`rWXf3Vd3>3wFxM6G%|G zRkmm_T<*9r2gCbXMx(Dzi8`~bZkq%<_RmGNIdg5G@Iye4#xjR|)XOLdl}O-3x7(d*s)~J$5`TogkTsrx-*iLe-zYduW?5^si5n;r-PhB8 zzuF^f2Mpet1W%dX8hPqUV`=K=D#)*u1A~=C&^m+Rg3X5J*`dV>vr4oKn@LEM0P4IxO8vqNS`nYN|S{o-_|j zSwHPO=&*kFi9p)Mca*c!#(!2_+BR_2rPKDs*J$aj25dS}r`=20f7~np>kU5181Nq; z0Ng+8xDB|m_ir!+45guF72*=I)LIk+eoFxR)VPZVIA;dH!ZVzkAmH~?V8c$h-I$rU zjhL#A-Uda0KaP*Th7Vi2pDCi?Sp&r9aqxcP5**^gFaX{i9_S7L?m+nG_*8cQ!yN!S z2LKEma7P8)F#_jww8!+^7(fOCaNGd`cL2{hAaMuCUIUUp>2MZ>0Spgt#}3@_1LxcT zMjE)20Pf_0b7`7m3E?$SgT;F_AfSZ-%rSu49iVd!nBM}Xzo^|XzzYoEb_=|?1-!r0 z+HDBqHrWG<1^`A2xKjhJwE>JdaAyKsTf&ZYfW>D3#vQnE128Xuy8z%inD)p=Xv4{A z*1n<+e=!y3CJwmC12E~pA_};v0dBhh3<_9D5lUVHPzylpHy{@S#NGnAw?NtvZ4CzK z!~iunK<5qc{ySCiSK;{u;C2+aT>~()z$yk9y8+g2fiVnl`whU{0@v371_R8kixzD- z3^hAJ>E7WwH%r&59QCg8FFcWDkd+XqgIloo;3R-BSzU@Z=q%LFiSz+Dt@mk6B40+?LjE)%#b z1kUs5ex(6xHNaXIFops!HNagZaMuW&*8-SM;O;$e*9V+;()~t>>=XlOi~k>~I1G?? zAE_H4?}jS%9H_+rT^OMD2I#t>sy!5~+yU0cfUz}TZ5=N z(EUCW-}!pt}c&${ao4qy4X~Gzxau@b+Xq}y?z^aip(>+Vn*{(k^}K!Cr$d}ZUxolCc_-KA#@9N1gnfL;Rz95{e`x3J;E zh!ZQO$PX=Fz<%`}=sS4d;>(ybYu*fXUxNaFLH`A80Q3R3Tsf;=&APSgll<70F70K|a(*9C^U(de1`;o(qUnf4BG-&H>{aJp`zrX+g33)c&fTGPdnS6jXKp21wHt67X z`Pet0d7%-wmjl{8sNsejswRMa1r9jhaS0q(Kmq=AsN#w&)|HouBGwmUeV{Ga;*B`w zh}TsE#3=v*;9D*L{_2!PtGVIh!X0jDQrO*;1u!44)`|%yvf#!mZ*P-cJ8quD8VjqjuWFk>cJl@-@MipEo9U;& zhI+5HtUjx+z9>~O;fVA!q6Jon5Lmn_FAG`iL&r2<*>)VX&Cdc%_S|&Sl+VQuxBW2w+Gx{k@7HJRod7*` z7jF1UXCa{Yvnvb!GUIUb`*+%OVtDxFn1AFZ14DBj^U?}yz4zIv>dkqkSL>Yl>a16E zciWEB8GGysryV)t3H-5h>oTFtyQ%di;5qIrw~e*zlqdiB*Sr7zQp&94)4cO(IDH?D`IS?l|{pw_kJK3@k7P`ZA@wm(%>y z(%ps!KjIZndB}^O@MPz`XDL8#0c=TZE|j4NV#yzhYhU&Vm_Y5ttZlP}=axvq1u`*a5HzAltl|$MvOr-O>syIjFU2%a{{M;GiXvQfP5&?gBp(Q!8LLw4wdaLY@KaxmC8phFn2ymnztr$Bs zaxRV7V`Kx26ibhEk%$G5UNLor!Sy9EkOj0M{1zw5VB+qEzr>p_Nyt7sE)ygD*y8~# z_e}t~NdZZmVhz!_Nn5fLjW%587&Qq@DK-(94E|8S#ei5&jr4_x4!B1@|1-7rDFB-5 zOQQyxXir^&GLfI8=R-58PgoB0A*>K5IWOv-d{|GD>cl7epee;sW-@ApmCm1rr)tgLQl%m83r?&gM=qZH(AnOg4BEY6bw!&f-)AKXfO1z=u&}m z7IdPtj1p}p{O~!(H?C8O@(ktz5b8{HZgi>-@yuQZz`_AY4^3!o&eW3l%uG5Gnt09R z^%$waGXj&WCmkeS(dnqTGGvH*6o3P)B2~k(h93?{=t0w&zx>UUn|)0vJmKk6qn4D7 z?Hg-8En7kdMAfkkL9A09;MT^jCp=i8{s%qsK}?!hCOjnRM?UUBkGJG8rw85XSVbG! z(6W(m_N^z*9l`I4HhuXtV@Ibk7KyCeV6?zB&0N@QT00uyS(;g%r14u97 z9FpGj9%LW%Aa8r;o8I!ekRkkNF993^UjhU`yxxxi>Qnr1e z-K0wEc~X_Oj|3}=7O#m(9Dw~Q zq#pquz+vezV-ky(09q+bcnWI~_*#_#7#412!%EbZ@^p?4Hf3||O6B})SEmF(fMj|K2u66?4i^jLBJi^GeMH2YY_;T^zs3!>r@pE)7<^|63^9NzWPg&*{Y zz#GUwhI;hFwRm=b0=R%+1m{z;Z>1q=5`)NW&T00Ef3ygnV8=XQNem&`yul(-j`+rX?K6=8ATVn}&3` zCyUNdi`v*7cB-hjqUzqjSG;arh={>!D>nnc0S}pRo5Kq)Tm3u0el7@(i5;K;h!@2K z$s>Hf8*#Gm!w)-1gBkv^eFj2{JPm#Tb3^Qb&Q6mS!&jd0gq%0bVe7xe@Gg>CSwtIk!2d6FO;VUV60RMyEZ%es3<;=J0(P zfXbiK>j5Czj{b1ELw0SDee`fFVLOQixw@0?>_T{zFY6{mU)9Gi)7rJcJxc_hh$h7nyzo>=mB2)L&SXW zr-OIl;Kg{LIR0;J?iYmCuii{Q(xB~YkGu`6-$5HzPlg@r01k(K2tT^8=;BXyjJx0a zxqmPGX9jn;0Jvm4rvSDWNJ&<2izjONCK-AW0La%GjfWBSAbAZjY`hk2H|Bi=fpx_; z5d2VL;3a*A(GPGi1mtISsMmU^r+y-525Eo>@b?h;Fa}+~0JKMYNQPvKhGDr^ZVmu| zdDU(LXjwbQV7bRWFt>vWAQ&RJWnG4N1rSva$QhPrVxR{R)R$`vp>PKQepjdu2B(D^ zm}3WFa2>c9et-rp$a*fgdS-BTZn%0a=m&F#5LbatUeE=M7H(rjcMIT$x|f4^S8n-4 zi04LS{#S-hia1;c=5`1cZl(ov2r)^AM;qg$Ox(c_TUUn?5r)Ej*}N&-O?;GMrHx9Y_4{3%`_qeerRx$E?AQy*bif{1&UUCT(AW-2y<~)kTLg%!I*oxw|fI=WlZ^p zRC#4q)@Y2Dm0KW`oLG3I#(dayB1yL$JmzBHI1vVia3OhpUHE1s24wuUd3JUXGlq$Z zF>N)u18c~7EvT1o$a=N-hC9%HSwLhP=m1+F2D4{-Hn?bU=Kx*cc8+L&e^_pE7jrqN zjDpCN2S$+1n0t_@05Mrz;Q^MWAsK_g9c5{C7;%bci4fw5W^PGiQaEa4Xb|GngwmD| zHK~sgP?K+%dM%i3FQ|qgX9oJH27{Ln{t%Q#nUzGDm6=(8zi3%~_-Mhnlu7;>kU9u+ z-kFTy_KyU(1@uf5BKmE!M1F~wmU3&hINS1f+Y zZwiorq^S>G^i=e59bNewt=5s9sEP{_n*(8aeWr3Y%8drGp9fKjm(dRqFa&z(el=N~ z!5N%I`hr5blh?Kb^{_K@)di86hg=Yu1SqApr-v2VXyJxoRtk3riJ|2dcL3>~7P>9mcM$35lK$kl7+DaYLOKL_ zxs!THe#i-n`G}lDpr~jt1QFm(=L7~3TBTH4dq-J-(n)*JNq_@sfZJJ!JZPpcr;GJR zl)M;j5L$GF7aP`rUA8e!E!rC_2>>SA5Z)MmYY70@7pMy%W?7ecb4hg=m>By22Y%^( ziYjvYD41%9kJY-93RUf#w zr8sM)NJe|Jw*_O+tJUQg(vce{QUIyx9KH6M5V4<9b&4G+b@(M-FT|tU7hbv<7k(fF z5wHUotF3RSpo*G)MrsBoXq-Ecml5Cx24N3t8lfmlrBphuR=S7HhQ1%(0Cn2DE-^Vh-34?)iO%nt||%tSwm(Im()c@p0}~ z1e3Z0iaM!6`mrB-t)%<4qbmeEkRj8yreYA8V9*6?O0S)2p>%s-oe7X#%4ni`u8ro4 z=cYiTa%Q!s6w2vpi8=Nupeh325cIk z6g<0mc(e9Op`4nff9t7_m_Oqhyo^bdU7%=cT6=Em0Gzs&3NQw_x@G(D7YJf0eW9Me zL2G7dQDXL97pJ+J`@-+#0NrbcRhYd4;k5n2OaXH2E2Q@;y1!Y(KwPQu zTd6-xx|Ui5`+Fw*papHK#9aUenwp1TaJ)qMk5Vee#7nnXNx;o0!A~r=@|vY{8=;}> z1zO+$V_?39B_KmPAWZ1Et3kd0HDE8qB!JpxNOxOEj9v-rpnXPLwABx~yV!Ks z031yKFZr+;*K2lGUL5^hGj@d{J^q_H24;hr5Y!i70?^SOox&ja%|?+AJ)i^Q47yw! zq=~GLllsGFTdD3Ry4rfbJG=u%0DJk6m`dygp6toB%g_AmspwR$MVX~HTczj}&iO?GS*`PK(H>X(f~G=otLc1 z27WZ=c>-Y5Mo|wsO$6lZ&h6WqL`uK(y8}Xym+dRMiQK+Ipu>ab4~ZGo|EsC9JG%zxclZEv^Mk#bq6k1Z=P5x|LP>$;KO@V*uA2)g(iEACy8V1E4#)eHe@dXn;y$ zG2MjxAYyz5xgx9(c&%sT{`K6}45OOM+-@n%!`%~pz}Q;5**o06;yun6d%ucY-acFe zTid=vP|jHZUtiz_N*v1bt*NqWyaJ4+W=($yjip>oulCB%q}TdG#!vu0lrU3pva;UKOajRoQm(Onzwe;i8r@AmSxYg2CH?CejP$LxIfaI~Mt1&P2f2I?&=o(B6#=x;uQ%?9958 zy2Ebn=HpBRI&cL34xj}}90p(@2J`*YQVz-}d*o4^-*2m>;c4XJNx;V|%S_Cs_?*_} z866K!CY6KObhF(>q1Z&g;yvKbZ4Tq?tphLaenc?YL_pr;Y|i6M&JnPtiD}@U9MzgS z-}imrtPSNTJA1z#p~t)Ev|19_#Te-WRI_lC0C3z0*U`>aVT?5a85dAO`RL*`aKdPMqweZRnnSr71hRSuLgF zTD$-Iw)L*>K%VSd8R%=OT@2pfY)mcDGAqif5&U2e&c5&k!4Ep113j?uIo`gEZQeT_ z*Uw8bGvaH{3&)>Ul^HNItHZR(s4fkum1z)gO3x5{TF&i->{BeWJe(DEzpao8USnjCt z8~(rTn=SQN@A<8s`8y!}JB{^M&*o~b$zovkfG-AH0O*0<_FEv@KmPjXKiYO*)>5kM zQEuzCZ|k_e`c*#u;{OF&z`qMW9OnWj0D&Muf&vKyA{ekw-$I5B9X@R6$IhC35G`KB zm{H?KjvYOI1Q}A~NRlN@LgaUZhz=b{jM6YnmwEvc2Fz42Ub<{K+69c(s#Bp}?c(JtRH$9ODDbjH?UpV|y|%3?2B}!7 zU$i)|cT(?OzJ2}v1ss@T0|SK<7${KK0Kvlu5EO7g?_|F|b|NSgoLTc`&Ye9^{yx%! zB@mcBdd$=zWJk=LJtD{~q9cM3p+0HKbgku!7&&6TG+hc@jF;g@!<4036)PAAQx$kU z`g|)G=~};HC2MsmcDc%<%JmXv%OA|2&7Vh~UVX-ViU%5AEO4M>1P%I`%m>F#nY`=$ z{|7KY&i3giG$2}X2?!!w5<&;lZVHOEm_)1THkxK~X$RfH2!oC-dP|D9rQC9BDlv{T z(W>Q=%g#Hppqs8NsOF+-Ijl(B;)^lv6R<}ge*}^tehNa2vBel0C`kwWDNiJR`e1_% zKlll&AGk#DrIo&PFiiz5yvf1TZldWXAR_pXx1^BTfm_7co=Z!Vo=!3_Zk4E}D zezLg0UmgApxTTiByp>m*Xwu>8Ho;u*z&Cdjwl_IeKGCTYjomh?M7NmHJE}y6>bOL! zl}clhMpEBre!=9f3r@V5;{otW#F1tL? zrI)5Yu+3XnY>JgP*H{e*@dGEh>Xz3O-|KaI>UkW%u1rN-6&4ky7 zN#G1urXI-4S{+p|q9Rv5I( z_@2XYka`JVfb~EnlE%$zXk=Jk809E4d#K<7D0mf@Ue$y2$gVy z0qb(WKp3zj#x+i8WT00)CYMTHPO2U#@If$9{-8%7_-lqd=%GubCa{-~rkR~PUk}J2 zLEX%OVjvn~*&Hbzl&S2JbXtnq7FDbRHcD>7OO`j$))d!)GAVJeSoeB4&nxv~gB;Wu z2w#~-gDAiOfAE<|{P2b{oWTuh=o>v1YNdVD!vZbv0SY9_B_HImOQz{k1pJjCFR8DX zp8G)$UPXqliNSt~T%_12#+xFZ=sV(6VgRAI$?be+i#AnTB+-^g--uxj6Z-=87CO`) z?V|x5WS6>HsQ`m4X_pzXha1*#hBdswUPQ&JkM=cY1i7XDMMiOQL@LXvH**?5b`DQ$!UCHXR+v@Bs%Ibm zVC4t(`AWwyRRIW4KpZ=ALVBIy45n&qXdTNmiMBwZ{n}g}^T<|a^6{-sL#9hO$H z^qMMFX(&PI$WX@afy1(??Chjdb>h{CaT*>FskwzQJXN&M<%^~Aaa0eM@s(&qBLb|a zfW>}fU-KdZRsG;x=$2P6`#`}7E?|L(Hq8f`yMRT1@Gl_HH@=_al1N`QUw^&ohjUP* z9OwXGi5U^VEES^4=0vSIc~dU`Gp7>?tIopWkEI}*gPa^?moM;xyygXQNX97HR=P5~ zXjFhdE>{LJw73o23vrD5!VmrmSO5hqXuEF7on7~*sP8Dy zS9`+u!D|m%{?8zFUO;8{8F6A8`y=*P_8MB81~Nn-^a;0VJD zvpkO#W%+5<3PhBy+tch;^wZc$*gz*2l1y9)3obv zAMG&$d+Q-IeVq{?Y=45DBldv9#yv}WHF$jegQkEF&;Ymlz4V&9(t@a93ah;nrp$S- zADF1jX_{erljd_ioinK@yQZHKBFSSZ>%*p%YKjl}IV=0Q#UnqTTB$WdDU%wokxfhr=@lAhw80qaE>xi(59&YOx)7wi%Q$8q&L)4D>*2)mBJIN75;GuVM0upmDSv3{5U z5Lkf}XuG#t0lC95-!rXIT)>Dzxo(rFy5oTagaA#W1DYeSJn$*RvmfarwKdDIcXPu! z^gzekf;FQN%d@H#Y#xcT!sE=Vztpa(K& z12a$qGZ+Fg*nuf=Mi9#f3ZMWDpnw!m0TpOFctimkbHa!MrW~6>yAviU1SVl>fe8NC z13iQ%l*)rQiN$u4piXPI#3R2nQ^9MJK750>FvzeqdoYMmvv@l^%v(s^*n&-)gM$2m zW<19b^M`%f84+JR=9#0a1V87#?O$_IATfS^2q0bGF< zumBdgHhg5X@v%qK+Q*23r~_oQ2zV1d$b&qfIjg)mCPS%(WV*yd$ad?ET=b2i<3%9K ztx=Pp4xv7a;YG15zfOCyO=B`GxXPmG$ru~G>qvI6pf( za*TioK)Adls(Q!(c02(JP(rseN+!fM3rNa4%CWf{MJZgxQM9pt^g=qYO8&0Q13u8X z1KYWi`m{IXz_8Rv#oMwp44bbsL*Ed~g#<7&>@(qzxi{LBG} z13vgd3&cvo%Y!FdH!-w10jrC%|9r?sTDOIizGOVS=zB$YqE88;hhy8$ z=i-MrLrK=#r-@@p1>gcj^g11E0QMH=nYfreL}h ztV1;`L&X!zgnUSy8$;$3Nb=yxm^srI#Rz*~I6~w>4y8usbjdmOP%lV3huDV`HG@4x zgFW4WB4{%;?WGHVfC&i7bzFe~6 zCfkEoyvihHvM0+=PE#}Hv&F+B!?M(ZPTR;v0?Xbk&=-V00K-)#TTMEs176j`J4G6P zu!nl62YbkefD+V@m@XV7#Fgwi=hQ(4_)rg3L_6Jxdbmk)+|wcW(;aZpWCbIBFaZyc zfbay*0SwCVOaadPJs#yzL}Nl5>na>Gz~8$73b+7Go6jZw`$E+WNq-H)-!!}@TgZw* z$R}gf*F3ym{EYyu$gfnh4nf#}y-I?8#p2YoKJ=S@2pWTuy*8MtH!#+31=okTP{)`o zuH!ml6SkN1f)CvSm}EqfU5I=j$1|A39pF|oD1v&R(2|v-eyD&9pnwp_fDkC!@C<=O zJpoSqJtc(NCbXj#;JqJJukx(HmJ@^8y?9b+#KD1Td)-=ZcEGf!hOT)o?? zoC73%()lcd0ifA&;Rio(1F0GsHvn0BL7}0E06(b2(1i$lvPR5$Uj;zK=Y+}1ja--| zHYUM{eIbKA-Bz95f%NTO_N|}gqY`0QHNK}2gCj(P1joT*MjQ|_N0i(Gj4N1X6DSq9eux0bAzxf_ z10xRKHW=blZiC24)9vgBVUsvQoH*yC#s!Gnv!G&WO{23&ixiuj?=^!I?cX7Y0B#*) zW&WOh$btvh01vv!B}MM&`Us_D#F}R~rt)tlnfL<%4C^jRDXlH1&fP3or8Z zScV2!KLgqF^{m5W-^U8f$JIf}m0v`J$u6*5%O&Zw*aH212>#94B0z%(*ntKa0%V41 z=h+7=kN}*6)x2JRrcbNp)I11CP~P2J<7-v<-Ze-Ayv{hO z;%@RCnv9$1jcYOPsc6Xbhe5QnI=d`srA8|DP!E;Xmp$x~UhJQ-hj5(4At(Z%nCueb|JyA57`23Y3PRj-x<>qTVzv^l~%?yL^gkgS7vE=W(VgE9aua%mht z*tqc4xbSXeZw&t8@+CX+T{btElJf4!eHa5bU0IgAUkAwLm#ts4*kvwY8wS{dU&cRf zm2CYMW1U#5>JIRuk!f8`?!a8o+2bi`8C6V`CArKAOuJ z#`-uo=h{Z+;q_XuRc_@5LsI?MNEgG^EMBtr=T3)b`ds*sv~7Pz&D!>4Qqcl~zLM`% zgJyGej{CEXyY-<7@2Qe?A+*WylJaxZplHP`iJRX!tzu-aV#5{-#P;&~Zis$RgCXEn z{+6DN*w}#sF-M?JntsTE3NT#{0QUo5V-A>r5U6uK|9}AOX%I+(p1yreeDG>U+7s9T zK*j@e-dlJlaXskZ;~(+gO--zHZbRl&MmA&{UNTc%`*(iDCY}C(kI=CFVB8MKz5V1L zKlERo6gb$^>^6gm_Qo_gau*ZAzsDs=EPUD{|B|Kh5DjdPhDndE*0b=?umA`JT?TsT z;^m+h1zxs{vA0hj#C>Ye4B0V6$POJsdI-_cLr1-b5J!?MY4Rk>lqy%UZ0YhP%$PD~ z(yVEdB)%LSButpl!Gi=095#H&5W<7e4;qwy0I?JVh!7z(Xh<Ey{nXHFirdE(HuOXo}7x^V*&?i+XxpFCgU#L2U# z?jF958}D&jxlSBDb;`Uc^GD>(&@}lCFq0`1DuyKbLb=(n$9(7c9*;dOT#pM$L8m66Q8f#V3W~FPo<(AuRX1tb$8D!McB$;KJiBdje zIM-Zr&?&@RLI**&1$P1wR1ltEfFTAL4%nwpJ!TZKUV9q7_Yn_%fOaOMjXL@$arMj~ zLIy~A(7^^7RGPsC6FA601{@ri!GjMjMS+GPG!>OrA#h~}9%G4BMp$MsrkPuMxFuI* zb!p*PU5V8d#~hEzC9GtI3HF#>y$Y+=9C3WXY+J{gwTB*jWy^;iUMZ=CJ&?|{j~~75 zaN29Fowh@6Yix;H8)l?NMsKurNgJ4I^dm06{f_$wa|=`l-Tng0)oC3A)Oo?(!r&eB zok3d|Li!l2U5zQG4v$u z8Ag1TH{>S!0^V_FkU|83vCu+bfH%4V6+`655E~ak1QD;x_Yn{} z^s{K>x$D0BNh-rofe0l~ngPun5Fc}>6L7%u2g)DC{(-6>FvV&JtU{m#9@%Gq$B`wP z#ch#9R-G1%iSbc&i^2|zK3aXT582pWtL2!mWV`r%WN@QZV)k($T?QPO#5;cY;aq>) zfp28Po7VIOH(vUZYjQ)lznuXMU<%+qaL2n1>ZczK5Lm(#z@6s^Y&s?!$aS=15Q2E; zAYl;07PR1x;M9X-I}k#9UI)7#gp3D4P!tD)D8!Tbt^&gIKnW&*0ZLg40~7GTP&RNB zqvT8j5&%^Qau$Lso(cn9vBMpd7Aq0ODsJ40TG}3y#;6%N>lR9Yoyeg-3ZP#Q#zNFBpCrX+)jhVJgH0ku^ca8&VWv+l)gmCG-M34 zU;>jvn5x>9@S_1-sN5;1lex{YGCLD1h{aikZnurR9g{7 zj82<7h;FwK%ROy@w_^ChLblKcdl-Q|I(VH&luLy8@Zbk5aA=LQtlEBHK?W75?#n8m zDVQ10QqM#Xs66mQ;*objPSg|zxYAxc*db|WWg7Ufr7JXQ=6q|>Rc7))&mgsJzw;wB zAM-o4L#OS)d^8fauw^9vElmsTU4w*;5QQjE;R;faf-$mS4-Px3AAZ!Nfn%bKCp zkjz*mFRR&gkwHpl{;&v`%pintX*s(70HFvM-~~8sM^4-UPs9ciOBm)<3}Mhy7@q9_ zix_tZ^GR+GnR|gC{HfR8CZ;`J0D~D!3I-(z5Hm9X)e#u414=|t6N$&EuMTCb9|+0= zx{^IM6jDS=3(JwhLYA?Zh%7`>OBwWNwaW09MEm4Riu?#8xVR;-mC;ooy;maeg-ESx z#RGfG;D(4^feKTI!W5*CaxBb))MdIDJz~5bM@C7KtR@4yPTQN1wjrV+t+i<=X$Fa| zX9!sSwo>=;hlNQ8I$dDE!mdLQfrLldz6G+gPv?a%Ao&YgAOl8>D^wzcj6N3#<^{IB zFQl_wi1?8H0Sv&*%$J>e1U@lPRXHWIPIYqwpi-jWD-{$DTtG?e1$mu4PAfcoTr=qu zc#+<^aLlMEEooDDWDd$lE#U9K`21(VPZX9i$X5^9``;n$_H`^+p$b*_wCj;zg_b)i zgZVgudn^K_5L=L<2F&%kF57Csb#h8Eo@lEbDX6u#{iI5l&M8629q8zGrpbmSLiQAf zE)aQ7!2Lo5j%)2+_K*iU_yPKP(1I)^wfXLc+&=IDfeOSR2GxxL30gJ*F+&PS!mqSklr15MaV?}9z?(qT!HIJ0Tq0j6-dDoWP!_(2|YwW>!jN8ZB`l# z0gM43tj(IN*&LWS5*ZjF?+pPxNY?v>(%w|gYY7{}L|u0bgv97ccnlc~>B$znP#E~u z3whm>dBl{>PL(ki5BPu_fu9Ad%fk)uqTxcO~M@ zP*bIJSDanI4low1dKVWRnyy4zSY*a1>Pkpn9170WwXoC0nIznd1tBd>_9RWnVVV|1 z01~_&>}{G2$^sIwAEVTR4j6$h6@kVWkj6NpB%RAL@()(}R?GPWA;C7*g2!7%RQ z00GSOX(7X`5T4AE0+{1(dEe+n+f6y!7ktMSkinGA2N0AU5Y!_Npui8b{y+=30Iz8! zU-m~o{^PjCT|m;E%Lort84pwqph7z0%v{w%O27q>!5XXq1AYh|Xn_N^U`A%5(lA)~ zjD<*Y3yGlMDXPecoKNJPrsTELpUH}>NFd|!Pa%cerLh4SL;wLuffeN7>*Zh+Bmojc z0S}tVlZ04^rP`oS1T!XO%~=FR$Xdos)M@lyt05mnEMr9ofphic2IWHoJl*uMk}7o} zkdYzxec{6Zm$Lzv7leTve1{x}ffnc*5WuC#%q80S01C7K3Y@?NbQ^aDXmRYrJdnUY zzJUFW8{G*{AhKJ_;7kUz8wQ+N05WD(X#l;HfgM;Ho$=dQS!OH#nx4R6;?iKt)8Nl& zip6T~!C*Z`Vy)&u0bDzUBn4s%N1~O8B#l?p0UOu>8F+;qoB`4t!EP3*7080?Z5k~g z!919WJscMfp+ONy>2X#B%^e>_J!9{Y7|os5l~RP1w$2V5!Cnd|?cj`y+Sk-d->#3K)s9UP)SUDhQE1gZ;sl9?82XrRXnyuc0IKw!dv{RK}T zzRUKI8j!&NL_z)z-XIn5Bo*xDrV;9X>`eqb z*)E0Hpco+`SQ34bT7$zyPCG0NlOIqySIw z3`hyMOb4_KfgA`m9ikIuN(8I{8}w+(R_2GaU;{E98L3t2LCtFdoMGK4W0WF`?!g^M zUgW_|!Ij8^fsZSe(T)bITJ@-gMkJ=uOA-{RELg#_J}akD0Tl>ifAE7);!u0EPRD?$ zQPNzhS;Rzzm~<*!dEu+LKHE*jse1AW zaM8h$eZdZd%)r8-9HPL%qJRaQKz|-VK5V1hR&GROfgUdExV?Z3%)syTAwg0KGnIg* z3`kTR;!a2t%^=9vO{N>T!OCV27;R5Q!fc7S7ynS8&>j|p?Ln-p1?km_LHTZ^b)<>t zu1I1=>3ODNF&<{_+aaw1()7mHK>)N~Z?n<@r@g`}4Cj8-19EXpnCg<0eyt-xq1iHH zmtJS89p!PJ?{#(zMj(~t`U^jV?!B#lX3dKn3JqRFN(cL1+bZ(@%(i6G;HQ zU>eG0Y<2?BME^Kn(z8r1Qbds zn3k_2v4(0~oVzzfs>+&OAMnj8LU?1KuTAbzZxMQF?z z&ja*^$Wf-L_9&f&kuWo!CB~-yF>?>FYGk*_ik{_}TY1lB)C%{wBEjkK#*L8<6SKd; z3K(G;8>Gh9(F++wfhT%n`FPJW) z*qUt}#~4LSsSuQJdqe<6WC7)ha)0!L-3Ib?NKBHMqn_*u7(83F^{sreqZxjI7{~$P z{skEjl@1*20_$hOo`5HJ@&#liLpLlbGrl!uenyTyqa}7UD8A0I3jRp7EEQ$E4Xa2D8j^yuNbqeY(gIVM-e?=k9=4G;1 z1h|3gzVI51l(NbKEy(_YELd$h17j>uK`k(BaS%{_-ViTYYYyd*dW5MX?H)3IskVZx zKyysTw9aw4hepKhOEU^TH~>LVb{HCj=>S9P(VGvb7b>nJ}7~1zkm|lfDPP04b*_Rkz1pNE;Eh5fFQRA(A`gW zQwBtUWKO10%P=eja2;SK55Hzwk;oEL;J;mD ztbCm8@~9nPnyAi8t?d96z;)GjF%_(HUAOZUxU_KW13f?h4}>2ME%=}ifnqB*KIb#G z@*W-cGd7AT9sb{Qaox~RN$_nqi9ZA~LKFmg7TInc@)$-Nc)ZX>!w>;CGU2Kx9e{Kh z1k(@rsSlhT!mdCIytYb5$e`NxhjSx7BmoWR_7W(8#NKqHPRgX%pYSj!atopeOn~rM zxw>V*0My1A6!m0Q_vC@WT;k1blD=J?9?R z67(CRE5{smg)1XQt+r;w68|HVdc#v!8$lLz1N5`jna@}8SK?M9MO7ExDH~R^szzV1U1w4R48~?O7K@%u}OzXA{oO0YPY7J~~ z=Q?V**WbATVg-!A1H3&zj1W;mf|dwt&LDKdMvEIecF3?{^N=E&I}a_|VT1nX4jztL z>U6AQN6#HS98c;=d9u#RmSyzRVN)kg$(9`P#H>?>?b3K>!a z&E393_7>3_w@6?#LV5^JD?~_ydSxL;mOPnqWy_Z_XVy$MAD1p&6m0PVrVAL;r@@HX z0wzotF|A*>{t`xx7%_6>(60Su&YUoG(06)8?o&=6vJmVKMC zXV<=+dw1{OG1F7hgh>)5G+xk9V&le*7d6n!fFU2oj2R+g#1KIOzy64UBuFTsf(jnk z0iiaII%gXh&SS%Es z^Vqq`+U9NnEFC=F7Ml=MxBfS`zgSo?hW z{sHHQbIyG~9`|{k>vcWf@!>^JkIUte_Q~loQ*c*wP0%b|ifu((!ZSN;`Z%*=UHGSG zwobzW(3pY!&&klpBXsjPGXsu%fbn%2au~2#F4Z@d{xDgBjRVv=yl9^%&5I)-pyx+T zOY^E?o1bYHwH@ZtB=4$9P@y4ybA&D5U}{C3w|#yzDq}adEa#i#9T0b>)-cG}#>*su z!9oum$0V1XiJLq(y0>!A&aXg5JU?09T5!IyT%Fac4w%T|f!$4HJLr^p>+~-TG4$^* zv2h2-$zWfZLAo7KN#*68e}qsI?HJ`tJFf%RmIcuJXsNFWkJi4>Bk>vcHx!i?V7kxJ9h}3cB|9YIsbEiSONwTY}t8tDS*4an? zI$oGclIxH@9XSyObAh~8^YC>Y?uxQZhV%B#uM~T?{AyG;W|)IY-(}$IMq6%or1Q z=Ni2`z~R+)mG~~j zV5-RwW|QL=+e-$4NbS4!;R~iJLX0A*BkFwtP2_ZWWi*_lXyc#&9#?=C-r$G+GUK#Y16zrI(dyfp z?Yq#H*yYM2Sdx?(wema~T`P`>Wl#h73XuatHDDmB(J2VuctzXG-IM8gkvK zcmeTP|DKKl>L7tQj;SP@K}yGVj4hB=8w2t7N~K}ooggXL6%Gp^H|NKVL)17xDAbwZ~LH7%* zY_ZOZ^|FC%tC#J9Pw#9#VD$jsrot0XGwe(L7Z2vNorv|BXh%W0cS;#|=zZA%XmS~N zES1|3_ubGh4mK-UJ<54%hvvA5Wy@ZHwPy9V8;4P+3~NKfcoG>$%FYsy1nCvhK0|_% z0l}}DR+Lu8Qor|V8pfDa8qcT4IPKni^eWR0nzkXj$IO#2#kH4dryAf#(t=8}cdKSL zPv(=%w}Ni3RBG1uz;N>3tc54s6U38T>1;%e`}F;EhjX0Zw_EI#|6z+uGDd*+ zraem+F6ub!P#cx*;dyYs;eC`so%Twif>GWmOMolK&d^WAprZ`di*sRpY9Y{bpG-+D zfd(fNA@E!6hcsVVok*o@Wq)Pk7)yVV*r@|S9TxAQZSTrnF968o!%@^R)ryaZ%_PXW zp|?dY^IHO+?B3h!!2~YmBhga`Mj0Er0Bh!-w%Y2Z9bZobmX_$Emu}rb2Q(T@CgZD zuH4H`QX`a8u}s+qo8UoEGYlysdF)zDJ&@7^3sS!ED|hDl(wZ+vVO}Ig{-wl5unzKk zWh;Ps5iCyE*#?S!5=(PCXC9ntj!^d5(q#X#23bfJrVZ3WOFVI-^5f9T8#hC@GZDzW zhdU}IE{;-jUnML<%Lvy9O<03 z#hse2Ebn?J_?Psl;kU`S~kisj`fYOyXgV%>+-a{t5mt>FwnkGVE6! zM*m!o2eum@76aQZSuRwGNmALvAkiDES`(xw%xKbztq4V?lpPCcdURk6k3z4;z#sUT3wVej{1JMsiDsdail@gLw!k;=gGsRTx z($>_sszx2}CR_MJ17B~^AS&)Mk0o-yD0fWbaAnUmPIRjTB7=N$b$`x%v;Vut(l0hF;N)F}B!$%zJ&ut_RR$8?2iD5z)R;N@j{ulFbG^Zyz@wU-^ zWFvK?t4CrhU^Yl?a;oPn^{(NR=wwHePV!dDHvKo@AkVEBt*Qz5maynaCFY_XaiBv$cDohwuA8N8Fa> z)qDp1ML||tk7=l>tSjY9e4s9sPi@uC zeKqhyxsqTxJgA8e3N(-F*!jnu-cmBuQUbUBcvro~`-3m(m=j7PL}x6d+C~y(wAcc8 zq!(C1^b0GSV=(`M=B!F?66oNsz;{*i0kU37Hu6fwJD3=ju@YWv9izFmp|{m8W#Wh+ z{`FY^wWA>!WEQXOOJxc=)=jJ@RAK zlM12t7e?0&jqb>a_gG3o-DgN7fRu=YCA{YeKg^>{@JbY4RZ-9w+u>tz zgIaQ{e`|s{n($F!yZ~!pKu8pr9{^sY1O>skCFuRSPKURoPD)cKO5t>cSZfz|iut&b zlZld`Pu6bmQ-44n?|VS7UJ^k+X)QB}ab}x$5^Z3fcA&$DY)f{j{i^mEAyW$`@|nG3 z6a^id0AJ{^d>En%=U)%oVG()X-G=JTm1fTT&ho~W4NSwK=`Zu!*&r&QZ(61f3!Ag{ zd7Yk34#$vVr~8&G41W7^e4&!Q@v82kBUq&F(quw1u{)9$t2gNSNJ05rDeo%LHx)J5 zzmsqNdU}gz9Afm9_!Dlmp3i<8;uv#P7%jl7lwh^n(P98t5C9?xM&7f$myM+?q8O>6 z87V=H&?|hR8hdWL*?w&)h`|jnB#i(o1C!jM+(MUx0oKzyvRZ zB<}9r&tH*yyiKI%CNp4KN)oya$C9K3kMDhKBPsDi|wWU~ZL=w7fe&l?0maW-Br~ zU?tRw(bAF35UpaD-gh^iAT+Zay@KZtJ{@5SwZ)T@EV{tp)~4exN=7zLaB^WOYJSl( z|D)1nNuYxfS~~|Q^cmfgEVQ1nt=BG;=4EfxsQD(C*FK4t6Su7<{hjs1j?pEM7f+o_ zosS38gx_|Hf72&8OS>l$e4N;M{cUyzQJDgl`&PQ zdr62Xi|TIDi#JQ?4R6!`OajN24WsE;$K52;cSJduSmS{f&gh*;Agj3iEWNml!j*;D z&_2yqPz>_Qo%zi(b3%cg zRB^}9C!%t(YuZ~-2iwAYSC(4#Z4VV3@Yl%C{%H!WH2kj&%0c&soWnEk-D{Z(1WOfw zA{(PmYp(DT?^oKT_HlwDsM9~HSsmF#7KDP-beI+R-7587ECNIpDPG*B{^g&HD#u^! zNlthOi6qnsw=@fH$%%Y1F;4N?K(dIiiULF30%^1ZgT@TM%ddasWo_-y_+rWG8^9)X zk0r94r47M)=nOeVL!yRe!?7O5-!2!M?yLv))k)X=wm@a2WzpnI{t}kzhTdCQWVf7# zM7R00ApJ)hwVdPRPumBRuN00jM4r(h?ANrzy&W8l`kIWJhfT)&R&Y zh#qTOHfPR*sXptEDaMNM@wA{Y8;|(5O-~M|{Z!};3h+ejDdI^YMOdeL5F8}@=z>h% z=;z7<_eB7UAxovihW+P2m!`X4FJGi;s+m3v@+o3oKOQ%+`JP!p<(O{wo7AX0S5!TW zoJ_=AHH$Tbg(3u<5{Gt=i)HOXv$UOyoeb}&b$etKMnq#GW7_T{+(t5&R_08RF?h)i z^T@wmua}D?R=%@80eJrJqDtk8i)pR-G&aA=hsu>kk)1&){mRGAin_j)T0%nBGoRMS z>UJAaX#z-a?{wt>V16PNr-YYVX9jDdK%yA$Z#Q|P6+A()lq7C2`-h8a7Uc3?$*GBmg9d4{xmT zn8}TZM$W~5fz;N{1%#1ric2`8au{~c^)yP=3V}kxGXF4uXiOk7O!>-F+!FwW31orG z{-7wejDU{Jzd)MY6`pOgrwOjK7jT+uENz$z1pZ35UhDW8308pDNaMjOaIiK2%FSM} z&&*SSVJ5om##X~AxqVMI$l_;L{5B>E&c6Bid?K#x(}!Zn2`KfYJlD{=z(K3@B3@;% z0)|a=BS=PwZ!f8dns=){^0ti*fL`-~vT@7`b5J(SsN|`F6R6zjNVHSW(LSX&L<<@}|gR_y!VdX<4IbY6bB8* zAHB@z?C?LbWy)86p(S}llo#QlSCA_fAnem(O(kxuqt5)^B0d zjEK$$^DlxMR=_?RM|ZKP)9`MFK5ml4eB*UW@|@zD9mnHo$8XaoMI}T9+tw37h+`U2 zN?S?2;Oqf$Ma{veh?dY;U0ssLHi7*4MtTGjs-%*3)cBq;^kv3b$O2$|s+7u6T`L@t z&YH*R4fxy4hHzx9=wsM3AWYmiC`8 zK*2tw?p=?4a_u4&y-mZ95x1|LP&c#N#mPD%o*IWpT`A^xgSZ^2;8qw{LjB#*8wi(9 z=on;)Fh{+7I`lJU=T7~15A*jC4$~1&@1u;n@9f`{75{QWe1 z)O*9`kX+f~^x={k`%txcHhTllo1#8ZX{T8(%r zVH8#fUeg&WSD@Ogf zos7wl!ln&OkN5v^CK28ZGH4RwekGA?rLpTCG?LnLt8cLLqBqz>M`bbV*d(9aGnz3# z@g5b3sbUJ%z;x?Muj#iJ1vvtbx)Db<3LNRg#}UBrQC?z}+3jhBNm)hS(s$d^0bcfG z(4)RAvR^5}oObQy=e2@=#Dbsfy>Fg0N=E?qAhe7mQh2W%t(PMSR2(W%fg5~pkicGYROyCkIM zi|RG#<;dt5`b|}Z{n(&BU2a{Uig{6z?n_h%vv|1xa!`1&?J^kcV7e8Y5kY)~#khJ;d>-TEd~#cMM0m{1M#6U!z?$SF@hapYu{0dq%RIC! zZI~T9(UvKfG?(w4I;;Zk(35)NDTuong5x0;M#{g)myD(6|i(b1LNwkmQX2ku>5rvHA zTTJ7OF^5+|4~*4v;_2fACP)~P2HWC@G+AeDV0SIIXJqUJ29NE6pGka}ps7ii*zmz~ zLr&QHyU~sftvSPYeLI_-pZhnE^|IGDbMj?OB%=q8L%2zQuapt~PG@K6%3K7(nGo=v^Pfe^L`9BM%I8!hhz zU~E9$Dp~3+$WItX2`%A(QwnizWj&{qnmyMc9vsnS@Dfhl=bH0Omq&MV z^pIepJ7#JhJg=W7-Z9oq6mkk*um0fllO_6Gx+Jt2nliYiwQL`a0;a z*b`qov0mHz@r=W-Zc)(DzoXpa)~Wk8QM92+z<(n!-cS=NO))Okt(OUqa&#!4(J^9YPTJu zmh{n5(?LqP`dx%C`y~4?o4-OGn~9GRL*H&ZS@Pqhd)wjTjr!b)Q^&vmN#vXEN2J082Ms$ml_$* zwb%otyx#s}<41MU#{K{Zhl1Q^1+%J^oyobbiOQY0px9*HYogb&PvYUr>YQdoS1%`E7eyesN^js z{_{Lnols6AD8?pX`Ap{b@rAq1#n7z)3Rq)=Ct(w=A*Z?lu?}Dxo%|T?I0h%m5Vfu4 zs}|5ePjdFpX;dorD!?1X6!KEV8E4t?z|%s%a}60!)~hvd%)`gcq!o zVivhMj9Ve(X0!1VR2k5WK;0iA`~0=mRr-$g&*C^2IcXFczt8P!u9Pe~F3YGMd9qgo zD^EpP^=iUFblF$szcE0Lx!+`p1A!BdLckfDYdSRIZ6GH6PR(WPHicvWZgs^!j0BzY z>avfgv1BHK1O$r(h3SQ_cs`hBaO)>qm8{tNOd=7EGBE`J=TmKCuK}YOM!dOs2g1z? zw+%lk3jBp*i+T|#I|)tO307RO%I~nq7j7^EkD2HAlxN8vl^1F`9%DQpInr@d zcOqY$`g#VVV00u#%W3!9uimT>Fmp|KtPC#;PsYoUn<_Uv zCfZl8hCByzGJNrYrvu3&(4c4}Q}~yfpn)tC2l(Wpv)^Z=WGrUym|8S~zN}dl9N-|l zZ6BHHB8Fe9qL0EsOn`6z%Vgia9m(o9cX297{lJXrpVH6UVP6a%}uj1}ZMlb4k* z2cJ47Qh0fL{!jIk{4NSaPvzLo8$LYT`RgVFWvM`HQFdV~<^DdidZOfgGtbG8_0Qr$t@=!*dSCj;{(d;Rp%s zt-KSN+HH}sWXdFJ$=2Hk7SN*oewTerhfJkV%bt;KU0Q3LmqZ;vQaTF$xyQwlP4XH` z-7-PFJj88$?yOK9_KQ?itSt<(Wa;-IOr;y7e$S6&6?BP^442cNyXNWR)7LLh{ahir zGVxfW+A^2~Cl&ylOo~D)F*~oQ%V|QCE9iyG4KzCp&JO7{oEh3l81;D>MP(T;JtA+e z`Q6*VMs!Ska3F6skUzjpI@`^t#%N|aoT#ZsXBEa-6J%GI5JFeWVI0q11%zx(B+?Gk zPTN2Skshr`A)Ii~f{lD#g3vuPQeH;SmIM}IMpk7Q?`4(eDmsRzz%*vUyHHx>KY6bZ zEyaQ>HWNr_m~2SJh0N5!m)YRvHHG4GoYp1OEVIUDVP3LXpwIM6W++Gk`Iz!L{b8nc&doU6JITrw$a@V1~2>G}e!SZMZ`rYgoA|OgwEllo_Qf zi~{NfkkVovie!TrQ9zNlOnLc?-~$O!Kt^AprP`HB!m&iax^w5K1PtZN9;OPhmIRLI zMpmg7diw=TN(6-PC3JNDy2*TEfzn>p)_w&H!GJrVq=xcg{N(zPk1>XU znCGGR?EVx;AQ1yWdoYd51z>_~^##F3HMVjAVAqSB@8pm`+YnPXb8H@GvAj-AJ2*nA zgc>L`cn*Dw@_2)V_F|xlDNrl3WDadoYcPw@hrFj3$f*oyOF3S`(6 zyVw$#9YZR$JkATUwW7ZNEbt_7l9Gm6P=w%jpT4KVdl2%Az&_Ge;&j<*mDj5GJ>dZq zsgJ4HR*`ClGVa(%ZUMki zD_bJarqqB8EQ16i1ODIr&{Ie%Ns)`WBJ+VKiA2~fh9pe@?@tGYcY-0FJNiu}6wpy{ua5C=#{vXqF%;RtwmR<6?LbXtJn6 zG#ey3lqui?Ts(BIe3V)>Tr@wGVy<=p!;O92!c=zfE2Bq zRICdE?b@n-Ho*Rv#fvQPvBzmJGsv83X|ymJ1_m%V_Cp>774 z=i-Bez*eM3h>SdY71|mF{d9m1-py+zb+EwdQ6-nN{x;VJ_&DU77SoAfnH67pi41Bw zf=?RGb@BhRQM6`Ljs%Ca3bTiT@%Kf%ilo^FJw7ZRdt68ckmDxTFy!;&-)+zEDwX^ zr3?6g;CNuLLEQ~|{L^e{=1zL`#ggYg8Sd;dw7bdJirQQVKI$R58ESs7R;w}eh1dAv zNnvnMYi+xM0@$OkMhq1x4P%qp@79Iu=@khCu+iTV8uKpOeB8d zK1j4Ytg^wPSgeJ$v6me?|GgW06AbhbQDzh=rt?|b)!8t&_`H&qdcY;#m+A939qt7b zNiFOa>d#Eap(U_9R{nC>EOE7V_!KcqPE z->>iwf$Zl1UD#k9N7g@lyri}Nku`(jf{R04LX)!i)W$cvnPtTduFFtdrrQURV6ODimwT6l=q^f*)T7!typ%P)4eH zoVuS&=itfdh&B-WIZzi6Z!KOTCaBS9M`SnxGiV@WIz=YRdtK4PuQ8Dj<2@O=Cy>X; zc7{LM><%b>W-zxHSRP+0@`6Mzfb>6(EFTwIx*fJ{9np6{orx7rVlPPQqp z>OQSo6?EV5O}_8DeKz~xAdj3>p=2);_4*(S05Ek7Zm(;qzVp`1!Kt)I=ZQ7f;ZM&$ z2QO78X9hbOHlg^kB1LQdv^%{bvS+5A+1-iEl=`1@OEL?F5jHN+ z4?+Myt$84jIw5f;ecSgTPJi^}W`!grFzWTZ_;hg)iK@^dNO8q7w%9U##xjucamwd0 zIja7xCLjV2WY__rGYA()w2Z|4{x3cLdM+|z46pSx7dk_p*9bl8w}Y^4FFZCQ^Myee z9mrs2K=5N*d#{i=G0sn(^7$V|WJoeCoEjZ1s#g(U7g#t6 zCaDn!eo+zm3RE?d*)%tTXe-1&2RJ{EKNPQS&?Y&ET-L2dG3uQ z<5Sgetl~@_nMr;?jMN9xXM=wQ^mk?i>S#sCRgfAe$qcH$Cij-bHBte zDgY9hy)eerZjXU57`F3y8zEuf_y0h$0j075U`Q;4szAT+g+5+nUi|6Nc#kw=7|z1mbiJ-K zt|=}X!u5b_h|Wo?n^RG_D%f5X|3#=Am^wS<=w)v>qj>2VkwKQ#zQ@Zn_wXH8aupch z!W)@y*+bSJMFC2SPVe@xLD2h?BbAVK7__|=TR@uBURnc}yI9c8p zAmhRJ0pdaLYMkoV-v3TFSdhmaG`W{k{W8PSa>ESms{EGWt{$bX)DI1RtnyQ(Kpqc~ zaos25<~j-+B2&!NSXX7Xa1cwtosu9df4{n(HMe)E@%8V4^ZrHskMmW!>IY9i%bg9*}@Az2lypK<5AnBP=`= zA8^^&8h_`u++3O=*`f4^)g><=3pz)kSE> zGm6OM9>C;uLaMfggY@X+gp-QUc^)3Kw{hly+)}4!$qVmzBGrlIkr`e$?<;4}@+?h> zSJhV-eeeN{ODi&-sy>j9wv8qHrVk5BAZ2D2FSRX4j61+YG|h^jpm?%=qR7`o@^Vew zR*%1knb+&R*hGd$+hyU|ywV9{4=wBNw`(SlGKq;dDFyx_Nt@4C47N7!m)V?T{3zP< zP;oS#!tVOG^8V(v-`1G|>oSFvuAHD|^=ca?W6#In zD1>s0$Y1WUhamf+Pu6$S6~erc8<3?mvd@D0#r`BNFH1dCu8L~(ta06G^xoZ!^ zH9t@>CX9mYIi@Q%f%U%6aWxAj^80w9y%VAX?&uOR&MfNEuEU(jO|+Pz6l?24iF0Fj zc5hqv2<3cP{q!!gIq~83RlJGeA~o_3IFXwC5TBG9rfN|Gkr(+T*;G}Dyx@kHAr&b# zTv(jt99ODdenWPMnLY#_Lf8fAKP3Rgxy{apL5wDSsAdK^+gK2_W;TH2&CMbzZdG^< zDh0D9%t($|*cP-|*r=lAdpLuQtXCwLX4~gYlz^l&YdGJIB_l(0!k9%Jm6W-$@ot=j z{1hC#?s0kT5HQNrs~AJn^QZY-qGj_cU7 zqLR8qW&@oXX`+S>Kpth(2Bz0tpi$v8Mt7Ccy8aCC>04={A}MfQ}bq=m6G z6$#I5m@V|4B~_tDc-vwC6*KMXGJp7xuh>%>3h4!o=bnXViZnd)-KaOy3bsfU#((Vz z9)ELus`|CW%fhljo{8z*tn?rw&KE8|=rz+}Cj12lS=AJ`b}%IeN>kWM$dg!^yRWQR zd}A*Nv0$>CTYYZ{mtQrPs07%Xi#dpOLPX=PSTe8`j-E0)m)g<$mgXsC-;!6gh8&B8C1{U zpkH2?tMhg!r#BzRFhK{21E$02Dw*E`CbFZ@^7Sh?=I)~L6|doLJK-uy*bd{f3BjJM z5DGuPSE;QB+A3Bx@e5QRbsIN z+Z8j;yz71!nU_A}gKAS#_kfcSdBOo?9fU0U8jFI)S!0dgD9Bm0VbtEz{7r+_i|{jN zr$D`ze=f1DKVQ*eh>@mGK7wDy?Y^ge2#;fi1KI)3r(}w@IO_a!5Lk4W!oW+DAvc@$ zxP1}*3z^8qOHi!Fz}%61T4ozaS;jMr)*o3d)i~U6SWndpm2)t7oJ}&y%$4Of>Vi7- z@zq>`nB_<&q+-mWyaL{E6PLx6NIj_7!H&V5K0R2Mn@C2;J6}wYm2N7EMDB%%pt&}u zK@~2M9Nr?R=uOFfQq%j^T{=KMLc}!GMMz$U)I@V_xR|w<3E}3(rvl@s9^%zy?Aieh z$y(RJEk*lJ-SZz4a{xWR$w93aDA3F2TuvZwYn$kK$(PXBQ!|}@-TrawMalv)s~y(Y zi9<3tJL@_@k%rYO|9de9Lk|_Q!SqDS_Owt8&zm8L3hG)p>jhY%{l}oAlc&=m`oD;2 zOj*o#L-qezn6gd7+kS7;I@6i4lK8;m*oQDB3brHkl=1isrZx)mAx#%HvC{SBH~^F8 zv~pZ-KGb;1!!ujxrD$D#*s8CPnxB4})8!`H?kI;AluQwqL+$ssj%64=fs8sJu>A%x z_nwc7`J1QN8ig>UsazNxcfgE}Zb5b@K-%OsI(P_)-vfgNn(2@NnVc~{?^OLzbBp^h z0|6naPeh6xel>==zn8+2Obxqc79_Ip6MoaEtwNdHYD0ATfp-~jkWvPJ;^Euu`g~yAMWYQgf|Axc8D%1kFPbzbXhRjI{X;WFu>g6 z*s*uo|F|QeliVkfr@+yH58AU zxFtj`xd=;ki+lSRp(#%e)dn~{@K=0L5mm{Tf<@)j_s+FM`M$mrkM1qvBCS(U2Z{}vd~IUS2Ji;{Ri>$O1aTK(NlpTNiYB)d{uXHkVJKdFR!e&3DfvEp zV>U@?RC)e*xA4zJf#*-yERA7rT=aP_S)DEbq|_HnUE?ji8J14*F-lXhHaq^~w3_1I zDb2Ka-uExIL_`=YrW3*{(B+Q89tn-_N)J8mvZ&jiq8fF@5+|UX&aMMv@VipPX^tu< z@#gZrK16PSIka(n&!;^ZM3R{xkcktpaNUp6yTdEkg1_9L&|v6clHb!BPYE!Om^S^S z{k4p;JKbGe)Cd-}IR5VgpA#iVO@+#2CmtZjYFL*f zTIDPgw@_}bQ@zep0PVRj?KdQ?Mjsdt7K}njsI_(0{3(?2Qo$*+)}>`Z^ZSA2Kwt+e zSR~so5~q`Po0fnqU%!oROCn#a4>q8zwylMk7l)jr97Uo_+w+2+5GfFCcmB>~M6W?2 z00U>59qj6P|+4?BDE1L{W?DE#tLiU7UAuIdBNIg}zeHE8kJXL)a^hOiul8plh_cW`~?C24GiOgs4uQ{mh5e*kVTfrL|YpQ0bQRY!%>gwVbGRxbcdFPz)UR7s9g z#j{{v-3seKPm5n(VQDFwXnz*bQt`*h2Y_X;SpGH@LE=c643)i4!w<@ zN)iY3YW|`qucKh;Vk?NHWQl5tv`?)qlB|Qry-ZEbHH%~TtFzgc=!Z`%|4!z=L*|Rr zWZ@lfW^IMnld|^9*Oia_Y#g(I;Pf{s@WGgk?kYg#lTvnwyD2_=wsNOg0bl$l7S>#8$sQaZ46izhm#Z zTB!VPi<8-zh>z`;4G^SJ>k>f0gvf{akNQQ-bj47h|8ifE0~J-!DS0V{xH=k}_LV{DBp6wsfFMku9!s{lVv^umU z*ca8=hR3ERi_Q#783B>EV@*;N^+=J?E|C=3s`tH!lzfbqSgwdtM194^dl^xa!bpa{ z@$Y1{MZ$k1rxVC)?c4t@GR`>13UxLNPmOW?>7@#|(_!>#@DlLzAvYD4y0rvA^-mF7 zDIL#ec>JZZHKcFYi#y)6VALyvKtZhPp62UzS)dYlbt}kwJ2p;rYs$;U`m-7FRdYus zi)#=-;|I4YlEU|k)sv-np9a4C6*zQNH}QM;B_y3zmDN~5DNY`c!9=*LD&ea*nykEzYUCGl%F14GRK_J&dfMoLX zWe!s1si$J0a4hrcm%xuc z+r>q&Lcq)S8?qAH7Es5yU$!;K6;K^??)EEzLr>066yNegFtiCIk_-wnnwQ#yfP_WI z*chL?P}ZDV4t`ImfaQ(*cxiuD+^*+6`45WX|WLu8VlQj*^}nG+#V@1G=#DEkFv zZlb{mdn9RHP6>Ym(6wDrVphsvSGdOIo;5YHfU}-N0>`aXU)Z(srzv$wwbbd8UHy(j zu~LeQPKx)Y1JNn8N7`A@om#|5|K63hsfs4^&T;Q6FD3T4zL9AHMR>-Xu`=i8Og`Vj z^$!AU#oBNC8CFa@{y89wRB0{YPU}U(a*7R<+K_eyuzJ6baOXYo&e+Zo*YXPz}kdNWk5>^>gxp6=6%%${gz?m41O}@1KF)MoceZGnF|r|KD$*gxXkVk!Uw6-Ql~9 z(SS~e+_vv0EOno@=%Lw~*_)AEEY&$cVtyNPGtK=^@xxgq)wTxv^X(fgrH$_C{^f1G zzcx2{*nmMD#5RC-Xa581$GzKr7X4v|J!PQykV>)zUW@kWyR|FK#1*WWVgUTDnx`f$ z%l+hTJi168wgjWd;bg`0BeSp11TDiXMcQyynK)9Ma>r6EIl!@`f2kZ<8aey?b!;lR z5_tGmMbQNkZp|2$29S!iA0A73jD!U1L45U+&e++%xlDcAAmw;v^{@uv5Ld@fOi4%u zP``^_{i}ITlJ0p1-1C}ID`x|U99GZG-W{i#&hyGC+;QIIaO@RPuM{P~!xY0DIHlGH zC8ZTIEAljh%>X1e0pcdgX^9!s_mx}n@6b^1&k5X* z6S|~tmS=*Auj~A>xa2LN-Ut1$?YW#&6A>P#nH?N zgwNG_;n63S3I+)eZ3(r}&YI4H>c%V?Y`?n-IPVNb2Xxnwoix7|{Ar9!(gWFHNh5cX z0)98gV8NIIk=4zVqTJ`liyWFvh}B?q&M3+~wbCAQhTldFWzUqOyb_3hZHXfudWmCX z{>TyE^A=wuyB~5SRjxJlbUtZh3Xy{Q_$%L4I*l2gW~9H8_qQ%>XJ9VQ8EIEB?yfK{ zLZMr4nu|pK4apDD;;UDpDA@SyX~+PU6)7-VZC_9`tS_zGW85|LnpaByvb0?=?;<|$ z@{GY^kbg~F(DpvRZS#RE1(q7YNE?og`|C|i%)YZjb3~v?z0dQtZw)+Pgt73cHgQv%xvSoo^;_ER&KKE3 z%Kz>l;yA-&g$OnN^ut27lc801VtpgF*~WT}#`m}15ycg$p~T*|Y@xx-Qt6}kd~Y+~mSe+X)JIE8Lylq~T0tO^)22IL zVwRCPPn6j#76QnaJhI6hZKsk@qCL8O{{%R-#VtPV*X|!HQT;RX(b-1=^}X$1ql5!X zWncYQkBpVK@4u11-a}q{l``*()0qGH3ZMuFD4#vD|C|wh1fJRer$%=^(B$#BtiGMeTHg_ES{hyQK)Pd=|5V9jE$ayT?Ie@MX5YQ0X z`z=G7fmUAi1QdVw+?Lk)x2@MQOSCgMR$7AiJBRkB&8_-Rr^de9`KJkmqS}9K?qF|R zOPZZ;7EZVgL?1Yol$2Gd{3q!z@6r?oh$kI z#`<5Y)L4vk$S;{J09>iwab**p7`q2g{9uW>_&$Wo2TOHG~W z*7w{hPcBd2*(bd(Q?b1oTd4GGv{iHewk2XocE+XVx3K5z3dwR%4O`m@b@ilvpy0OA zXBS*^Yb*6!tXdB|(4iMFE|bgQRqn_awyx7o(G*~Ai7>w-yKVDmGLu{<@f5`Xq%PrY zS}2mPEa^T)bhvh!#0h2;b9Fp;tKiC^NBP z<-=rxYhak#IYEo|4qz8fglS)*v=g)ggh>*$85iP`G=+65X!t41!9kM|G8&xEY!h!RVn4bGJIwrlW`lk~uNU4WpTK7zOq22Vr5P?16Ak1C9WAEJQLo|Ff=J zhkmv;Qz!vV!DIzTt1p_{)K?d}l!(+=oedXQV^Tuzak(d7G22#^gih84bayjz1a3R) zlC-w87v6tD`s@o^EVYL%M~BGu7=xwUf;Ro6fq8;ku6ZmQeLL$?R?YI2EFhz0I60A~ zncCUWr{#=5^dqScg>pWu3srUWX^s9riq89=>i7TSXF3N5$3FHs9D8)k?2dixV{OqvS^=Sd+UfNLDv$(pva!IgRBjH_Q81F{xmOJZzr&PC7g-PSOMe-+;FqV`JX)D^ zdM;Bu^J__&^lQ{L_Zn_xvrG_&(_<2lLq+%20EbdN6AMQZX~_^iL;SRTT*)m4mnFQXgMOhl>T9hUUV1zfCl=8g5+14cYq;u< zXsFsS=Qf;a(iyt5f&EP)J?Q5_BB&GJa|k;6(w@0c2Fi5oJ6u`R0=1~8tPR?2bNCF-#x;kxf_yd`_ zGK7{`Ai%o1sQN~bTrUn6d)Bd=Try?s5|?jX%=5d}1#xEqGNOK95VBmsMmW(t zuOexIMFmTLjB;vvoo$brr4I7DjUm?#U}Qg)o58H1MUMzj;hsu zu=W=$AueKVbW$PqxnJMBM{70+;p1sq-t<~Pwm991;fje)^@J~%x;1HK#;X^y^Y|xYZ=BMd5_)?hRsMOPt#uWTebJY35_e%lm$+74d(#KoyVNW1@#j)4Mr=#Jh z24*#f8TV%FdpVXW**7~piYL7+@s}NUAKOy9w#X?KHB#zbRfBk7I7pg~LcPP6AckAE z0!xF_ltybkIy2K${i3rySEYr25yOmQNszz}g^H!H$?hlvd*Q1*dO34GnipKovsRS& zGce=KH_yic>Nmk6TMGB|-X}`{di=#^jvWlw7IVMSMhqD{FXCi%bA0IQcXf@D+3wVX zI1P8_vC2paf8RR@=DG= zwhRrCV9!!mea*od+i$bq1s}2K1l`Jw6k4wnh&O<}%XOGTi{n07Qs~7XVC3)ZdiO$U3)aqu-nLLiyp-mVM)~bd7#- zwWMc*tr3B+)0D-DCz?4Y?xiMLK``bUIH8;JKxmKw=SCWE+uT zz`U6IU!;u0HXf!gB=q{+bu+P*5DVkZd@gK=zwlD8JD?RpJoH>RLyTE3Fx^i5RyzUX zcJRGks*2$-=}HrwW~Lc;t!7Cs)N8FMoGvXSMV*T^`|+K3lF}6(PG2l z_^jT537xnNrucRG@2IV~;9PTXXyBrqHAg~D(m_UAnjOEQHGe*G95u@R50Ij=+;M;6 z^9w}Ugk3swBKhOQE4X{cYUZRsEwan!HemhJcRJJ%{*oqk)x!NIT;S%4>yfwhUFM{% zx%dFogRO`R3%T$U>OnW6|Fdw&ypM9VmZV~{Ydu9WIqcFfDA0w{#JE(tCdBZ zGKZGk-Ds-Ke*wt<{+`CZs-fn8CdWa70+oxKKHqBL-DOeg&DT2g>VV1pioHbfqeJ-` zw@P<`e|vdFIZ*!xn+PSFo0J^jnk;z8cfz#{I$Tul2ZhXnRC+ zR>#`txAnhBy3nr<4q^=6Q{B;r6G2|*TRmL?gF&3f6xYwS45k{sQoDaSR$@d=9i=)}y#e$|Y{ zCBi;~cw1Z=qal4mb?v1WnSvcP{lcO{bC4W=JqrQnPfC06ko*z|2T^cngHi^APs0x? z>H+}tx9>LzWa=gHtYW$nA0Ij&Wn%8&Kz7gk=m)F6`!yeBT2@xkzi_ObrO>g3M^3vJ zlQC!M?#}>-embXujAl&G=*K}43~@j^|de6$}vy+APPdna(E9sX{!}a!RDX42CQqGme?d(cUp$ zwzXp~pE3z`m<*n0ud^pIWBRk1JEPMo7`Ht-RGbl%wQ}OT(#;$c=oln)faBcpfR(u2h2nzJ?#8lP1<-e1 zpLSk__nC+tpID|#^nL_||4omE0|m5z(Lp6fewG5qAT_d(%FKW=-Bi6d`1?Vs6uK~r zSi}skVnxVeBed@~sKF#Z_1xG6;63ES!KVnrfi+_|)}!4$1^28JT7?dF??d zu{meQw_b99`wV6zAh1Bff`6`e1ca)&N%;$Kno@ZNmRP~v^uN&KV!LZ+aX z|B>v#WZ=(SfMZTA9900Hz$1oE5{LMp>C`rm#hIB@b=)PPzcN*(m$nn-&Qi04NGv|d zgcqLl*@gC z$E5EW4}h-hn%)m}I3v!;h!x00CSObtsC~f`(J;5TMGG_h#9PglX->{kfc`^#@m`_jqOr(4F_3dtOkw$y$9H^D}r7IX3z%pi2DiRM39r&wV5|+)Je#w*g^;u zg1#_M$QPIm>0=uu+co7EF_Y=aopB12O;oz^DB6ecXqJRvQy8y@7H$BM8fka z@8GIqBkt}Te_a+r=r9W2MBtV6!Q=+H_(#>xxGv} zH_MHtLB`t~#&ao91_&22c-hU-Xp?R&yMRe4%Ap2lddbhf7>$)1nd*NTO&;y$WpEqH z-Wx;AsARs$^EzV()-VL?CDwO5Of~rSMX)2)pevP5a{=5B=*k+=QII@kh~#U_g@xop zR$UjUfoUH{?DFmUY zNa)I~mcLm&+bZVnOopz^%x6x*z7?4vheX*o3N0Pnqr=_v?~mjaYj8%rOc#7vaQ{a> znc7^7Q&T)2dI5^Uoz9Rxwm!7)-SSr2{pbC4)0M8CMP`Cj5u_k)GR~O92;M4Z_erj7 zJTwl@GRm|my6+&~4-M^WMA)uEI<~p4%X~(MDnGfzCe7xrUNZG!xUY%B!ZQ0I5)}RQ1)=ogj`gwB~6X?7?#ab5kjzyWPr3RP=h)m6T|^I>O}UxunG~ zw`K(8FJ<(LSz;1amwYl+2OG4ec030g^bZ=~S;~NNtfA9>3;T{CZ>lnri!C#^m`vxO z0E)<^_)C*tEO&0=rc8d-r&UwGb|B2kB_|Y?IbKZk_Ys|a;8^KEmDE$IlVOVcHDQTEc%$esri+Q(8XpO~7Bnl1TcXjHscP7qMb#HXBT~~Zipa85#P9+>w=^c9O{#AkMr>G7~T) zLwaxh(fDDHk$TiX=O}7{(puUq7AU{##Zx+V?Cll6+KL})CbYyR+nAissC$!$<36gS zTLJ}l{v{PzfIa2cd47Qsmj1Q~5@1~&HI?mq;dS4E_Vu2CBg#k+j=fT`;!4l!S9nE%Oi{^xa^T)+3xvSG9j8_XwX&;d%J_#?ny3xm#~VtHtnbs_1gN_kNkwUokpJQr_I zM-g~iL-TsyJ+{~DY(V5A>FkAWXS4>@$*GB-c=U?+1@9EfU*YTrY3H-B7)J{O@<9!JSuIqua9beYm^q*u~3h*`f zq|toLYyR?h0ZK;VM$Axc3`3Z;b?>{PenCxhW^e6;pVqk`MC=c+s~j_^2gCbsbEfBY z&>=uo2@4-at7+i@jkHMWR9+aSuSRs1=Ppbl4 zaC%jzJWPz*{@i6rTv{rnI&2m53h zkoG})R|vA1qKdD&8$B%WXW;#u)v28naNvGta8^hwk*<~-(?qc5P1wHkq1ord)TZ5( z*B^`7my@m3v|hx^MC4BTO8V;$yLo2Lg=T^&X1dgb_ui>`Uf|}2rKC@$sjKX>ED?8aSO`pB7m@&xZG zZ3)dlXJ`5*MJl_^~CR_GSB#Xl?P**iL7Dy zJiC^^_okhHO0C|CckfO2_5UJ_48Ly87K1N78vJ)#@=U_t-l)5c=vmtqDx?(fOIzxHIYvT@0mT+2ca7im$#6f}>uovp zd}r@v?z2O*%&Gt8hzISF{G8z(IwK3FWmcdrM)r6u#8^i>){C@wj}3WIxtVZ?k0I_t~e1U}@0pZhoGp(y_-5 z{YR}XzYH;VT3*@aEmt^>t9(_~$hbx+Tv)hTl)PO|yKBN$8A|nql}8o1Emg8BQsk>* zC#Ir8BU?YonZuQi3&Xe!nX9QVt+MC?(fu4vE5U04zR(lmDQ1*~IUm9RNo_}9UdlMF zGGN-J^*ou1SD7ZpzgE5ijn%=zm!GTOeyI_q9cGzq{QL&>4@hsTzuiI9=mVO9&^f-G zk}6lWT9fXUGKxK?oduk`tpsldojV2Et#xxr`8TsHoa-xFf>ym>d)EfHTW@RheXKsq zuZnTDj#T!X4HZE@s|YH{+*0)LV=uYhw6|9N_h|CWf34T{m>b+Wn**s!13#1omj*eM z2h|yKB$?%*(F8m12sF44dzme++*b48j_@-S;neg24Q|%vaIvv4_1uuO4xqyRRMZ>J zw+OS-40^iG<`mD7h#71$+A)R#fE*I;8K`4TA^JbWzp>!SfwG-7SHcNZTjbz$C0FjU zHrK}gFc%|)bW@C&_e!pd%ZR?tTxZgO+yPhxlRZ?1_6lzvdvyCnC(RKZd;nL=r8+?# zbP)u5D373!!HFEeob9p{Wb10Ua;D4e#QG7TN*Yud#kaB^|5(V2+xq%>zV{tiSqT+B zdshzeHTXSo>&7v=+?;}vrmj&b;0Nvj5h zw;w>Uop_;mo!4!L{*q%+=~~rmIZ9bz@z;P6-2p~khsJ2@c5k}gJK$|xgn#HVJ>AP2 zlgxp%aZDNKUogA}6lN$uug#F53bY>nLv@E}zvSf=xq6JrZcK)ka{<*=YRq~U^ks@6 z_d1|a3i%M0ix5Y~l005c2eYiNn=zo9J?;|s(NLifUO0p=g*}SoSo@WZmpf5yF#{ml z9^ULE;?pbvVKUvy)@u(zr_d&sgWJ5rB|n!I9c5Z7IVV%` zd(zu!Y6zN@(Y^=IbuIS+PWTDKE-_MRr6S8E$k()mB}@m-jY}OOg|F{5+=yQYCUKat z4IvwE#^V%Bz@6!u=G$Hox~qZcJ+)W;VK4(~=`&^=d+f5ZX#W$54np= z2XcBt%*3RJEODM+a<53XNFiyCA%)HAhiI6ALG0qSq*0feKD#E3987^~y84Ik`zIRg z#X>3t%jrc2u~ZKqk)L$jzA8Q_GKEjqtj2K1r&aqfUt8Szg$wUoKO-1u+> ziJgUEy;n8auwz9`-Anu}4VukKJP4v$kPq1_0@oZ!K{e&{ zpPAsu@*M1{!_&Rrq>dohW{=X3@dN>P08}2&SdKsOf~VzyNHU|h%ufRm;sKCLo7P{H zwv?>f=M`RhM|{L?G4UTAaZ)WDu?*+f>% zwwQePi85;F$Fp0L0ene;+3qV>gdQb8^@G)oHKfGXHaDy;>%ym9Zs@yLH8 z?&9jVSc(dPS}GzM0?5tJq4V7DwEZ+!vTH*!X;+8pQZYN6aBFf}cp@;{^BV}&hf0r3 zVPuPc28kJLTd=q6-F2%!)D_|^d{K0#GUt+=5o$j#CcM{d8__*(U7~-PP|>>?uo%Ug z=~d`{zFzucX0wGb?o1;v*B?J9a#1M5o#C0=o^F=CO0@FG_sxrI8x$8x8PU<`!i4s& zKa3D}6&JZJk01abQZ%P}ZQ`yVakWi9tFSVu9yHQ-F(UqYcs}~+(sRZ8`Hi^+E+dlr zzq_gxm z!?XC5BRYS+oz9y*AXyZJp0EGYwinST`W>`j9r?tpeYSt=#X^3|N9dx^}B{=Tbdi0le9T<3bMgCAl=kZ!y&RZhPTLw%t1Ao+IKI!32I!< z+%Jq}QY`E4HP($^18~M9*C!^YI!B>Wl2PGyVkvna;!Px_htC``P->*8yg}PubG_O; z|K>qIsu`@&4Bn}xPe#HG)&OLY@50NsO$ge7oQ(pdjIL=g&>TO4?~DeO(+~AJoD*)uXrW?lh!>* zzHvZ9Yz|0#7~ncY(=_sM(nvD;&`YUqU}no}VGAUdrD+}xc6?ZCV`r!|u5Vsvs5_hy zv#N7#?c_$MzN_YRk{YT5vlH*jeC{hb@kQl_iDV4=JCm{()TqbOVbjwJ@{ivMtlY3k z%=Fi>WIr2|R-}~H2C*-r*nDdwxRbk+Hi0UniBUw0De%)m_#{Oxgbr+N3;8?%e0^tF ze8pF61sJMfZdQN?q5X(Cs>dm>b3-T=rs!hB4|z&Fw?XPBOLmEmlNz5(-Ii-Mb&Mo( zM*iNOwF|S?n&MS&FZAQd4|y$rS#>@>z)H>WNCB?`-7?ofV+=_kO8~|vT5gFmzE-)S z@xxO17q%r^(J+9>>^|zkDk_lVmZE;G`cj3OsdG;Dm9G1!hL&gH(eLIyKPy;gDWzFZ63cy?CenK8o=7JhGX3J`Qs>U9eBM5 zCrq}rV5W-bCbvk_=wx%|D}f==IiSd}ujv5eLF2G!E8|Q)4TN2N+?(#GLqi{7!R`>S zT%_gba9-layeRA&KHGN4u9f~JHJO+82kG{`hz^I(){qZ`y}HQy0NlmgAKPpZS@oAx z@RyYwEmKs%Zkr1vMR1}m(VRxqFm*L&K}*&Aev#-}$xd1~qS@>&vxTm*HIFDn;Mqa| z#OSFz;m{L&l~4ohos!_SUM^IFmG<3S=QG{c-knk`0Vom#D+^YkXaEQVU}q`{y}DQx zg;5Gm7RpM~i!9drS;Mn4An_;-x0A2m;^OrR&k45~RBH8V`?{e7PVT=9)7bE^{p9mW zHU)JwWCLz`I4Bnf;EYX94VXBci9y8!*;9Zc3BJO8K(SZ8VhO%tOd$RZNXiq#j@s>X zRo%@Bmp!MTN8t3w2^hy{=%?>oxF1f^+cvJQYqZQZw#l~p)kugKwo2f#iXq?P=9bFC zAd4`ftDjKmjVG`0tM!RbtetR)W`>CZR(xqslX0nLSmplZpRf{yAueFCrlqI`JFu>pZ#@>y@>uDSm6(p$wr2jBp6@ zobAv5u^mc$Pr;1>27X)9jxrE(2=WriL)l*wms+EhiqLP>)U6xBZ-6!T###~Z41yl| zXgjlJIMHAD&OGaCd$MR7aA%=gu*p~WQ;qq5pcYRI%yoZOXrx0|ZdXIuzrZH?Vf}@v z`NU|Oppu89%yaiGvtf@Xf~ceR>6;+9lLH>jnRWEv51^EmNlOuMvIsM2+B4Z467Z7v z`G=ax;ejaNwyEcuXrh30iY)|^Mnv;J#;r~{-=BIlt)d)xl=R?8MYWA}$iWlVu4_NP zqhVXF)6B-trwIF=2l?(7*{z#D=gv7J;6&x-ytGLHIpkYPM#g3eXjt7lDbHfEf}d)n zxzvnQ1fiWc&pFNCe%G}Sy;kzi+$EywkuYamg(LvgZ7uBaMr$iK;=QfnLl~RfJX<*Z zpIj+>8H?;%OkwuOAOIZWp{j$g;}>#hA@NPZev`+ZAII)}DEj)THA z+AeE6e-Ur=kgUS=ensBY-S9CFhfmOll#~L8z!})ldkY&jJ|3_bx*(q5B@!e&Q7oKb zGP0c|`d5>=nk9S)lp0Qv+GI#Pq;-8O$k%nwQ{3*ms63^#|=Ix9^!n<&+r6_6Zl z$r!S$#+Ch(!$9grZ17oYOF16o?$ErJ)oq`!H@HjConhog5O0ln2lp;D$UPG6X3Lr% zib%kBY;MPhhRsLZwqJC$B4HQ)W~raeC;Wk6_KHe^q|21Foi4q|;?Z`x`8yie{Vsye z*7%`0A9PEm-8xFbYZqs8zQ-GBDq~7b?h5_oGf(&lv-y< z^!~J0+ULFSAnMa>!9=}Lfg0)kPwXWn_}ZID zE&R-nq%Y;+@wc}L;A`f$zY(BIjkSYzgm>E@3U5q?AqIvz{S1e#1YQGvu;g z)S{YygFG+!$>AAm4kOwG#3r>s%>BxTUf(fyA@X-utS@9eyRazLz}X>u!1<*;Hs+x!H2M3g23YW|gf!XY*KPZC&Pk zf?5%M_;e-l&K6f&;Hl@(0g%mxN-IqgT=@O>faIQr==k6SluL&d1)nAt-6*YVuBbBa7+}mbP!Z_c>(g z!g>xRwboDtHC1bBq9sP3HuVC!D_-qPd>Y3oRao|4Si7XWE~uz^NouutsVV%wAoNi{ z9`@1m)JxMu-8S71ZOE`U`1UlDd_s@TO!(xRKG#S*d;X_+HDS&o)cz&bGAMMY$dh7; z#XG|N7WC024zj)GTP0|6v@*JhasOmN^VE$M_v~X>7-7Yog?G}zF;Ds`!pS4~DI=wQ zBO7J85`x*?s20q*`ww_4ALhGWptD!6u+t1rDoRrJ2!wj5j78yqV@qUKrk9VRzYwga;p^AzHWOS$V4O>KTm+3yp zr+ij;q#($0b_jc6@Fz?m!&pG^Jxp9+ZL=+L(&BHHBq)coPHeFTBML8@bc@Xz7{^!g zi8Lp_S^$c(94^i=B${jby=CuQ+kaT%&VrEGAM*{QdJKWFkEZYdu=Ga@Qh+5J>xjf@ zH8b3%br0Uvw+dH#p={u{&mx)*1t8ux6L{~fsjK%SdnKZekzi9`*uv_5H( z_MsOmJ9=9j9Wq1vl9HY)tP`=)=9`KhNI#8G^Cb}12GZFyMH3n7YuRErzUj=e!{KaE z4&TapcW~fPDQ_v0R2#rPS?*AzyLf-ox&TY4MPEI;@8)!&-EU1PRORmTd&D}MDx2=+ z*%tTC(6{5=E%T3vKcD%YBuXVa!smLOTIO<>bt0BpFJ88MD5ep&+{IXyvlr96I9&-8 z*X3H%3W=wgxIiY6!xr%ZyrwKl46j77BL5T+0{Kh!QYBpzx_%$*6YkoiR-_<&eqjsz5_wCSgLLG0d{%!Hd79HA`%1@ zaAoqiBQ3jM8;xP>a^%KwbqK9j=KQ&u>$+bjG}kjVr8PFYq`7rB$s2yUvt|BV26N~y zrclky6SKN>?5aPEKY?n(#vj$j$QKVd1i~;0G!wXZB60vG6#^K536R@N;iC0;lTxL6 z>Hvp)Yg-CO07n8Vg+oPa1jG@_8ZqS*?jqf*idxzoyqWM$??Z)(J0OG%@g&OKkymMA zl!}JnfG1{IYBEHOgfoFkW>SH-Wp{cv5E`QZFhVXZ){IM5WQf@;H-#TG7a61Eo2Um; zoXofchmfXS9a;q@3Ts)-%>wz@H|?hv%v1UFKW>`y+Z#?n_#lY1Z0ASjKs(jm)pc8e z7lx>{-p!J*PfvDix*etBR~VKe5p8QFV(}AC=RBjHM6-!R?{*K1Bu#ZcqNnBiE+8)= ze24vl41+BFEf7;>NDEiHc4X0a{LppNgrD!OE~Uj+aX*1{ifS(mSx$y86I1i_c83s- z2LC-_`RD2FyZhVc9CU4P3$bdV7)gJ=v{myk$E+lh<~)9SLzcXeo;=1&E(Nk-94@=+n^0Juohtt}Xuf&{@G z2aLB5M4M=!WhKM<6o>qVXh~Y6by;Q6uOH^&Aho7g)=7X(S`_&Xjv_CbQ~WVurD^ znF%*_H7h)7Q0%F@$ff?Zj!Sfvpwn*_4Vq14F2iBLa|*;SuX?KY&F|^YU~;Fo%|x4P zGV$xu*jaB@^Qhw1}&LmrjBxUaYT#2 z%h7)^#B6Gns%a_0MYjNptfDJ#c?Hx)QT@dSFIMKdN~fUQ)m$V{EWQsKZOMoP5?J!k zt03ze5Yd}wjiCb$Tz~59>AkUoi}FLc1JMG8kFG2XZGYJrdddlCwhyfjzs;|{wkLocQn!-neKEU>q0g%iAXc!O? z`7A}@Iepa-H}r;QY_0w-i1BO%JBkh#=%p;?hCBT<3F; zf-dSZ+$Qh~vZjHtB=g)`-I|_%maep!=}7j{P_4HnS$aLZx68W05+8T$BU|&iuzX2mZ3Qq9ZAdT02)&&?c5uyQ>+-3yfF(W>4?^ zLwr0lBtz9^cQtyf8tUwUoOk@i3wK_fG`-=Hu2I>3+Bu#eKB6G5TdnRDOR1@coCSaEB;3{|Jrp-mzQ@o=P9xbN{?S068wH z1R1rkI}<_ORQiL6*>%CT!xueC493-ijeEqrj-u|PjE>+7n;z zc+#xq!747qeZf!iYZ=DD5>|u>3)GQwdxdk-iV0WYDKitT`N$4>u)}uhl?hj*SE^_~ z*-HOtsp3l8V9?1H*&wTvQy5{BkmcPv#iv)LJJ5dd#`D*4;@KaLVsokYbh_snJNN!# zkMzSf3$?5Gp9vVEO_Tu)YFBCUHN&etFWoH_O7amwC^6CNf2bXIfztdEX68dTwsfnb zS2j9Qg^^@Br>lnE^>`(4@n8d7hjr+{L)^P8f|A%Fp0nd1t%8fb(f3Oh8|EZNZ36XO zI8>sZYL{Qc|GdFpai~lK+*c(=+PK_tk1|-sjN0v0Nr=H2vXa8%TR2p+;=et@rYF0IFYTo55 z-)z$lC@FQ<);A*I?1SIP%pAr-!1FBioLj}Or0VVjkMb`WO6Tfb@8B26n##RY36{A0 z%u>H8x-&j}P~tO{*Ki_)B_41BhwTqbUg{SyoY5$0|K9E(X*79l?xs#&&6Y#(`P&Op zNc((7Md8g~mm2xSd*h;B0-)*G^VOf~q)u=nZMTz82dP-1zbxglYZY>jfTjgl>bjo9{7F$mM$b8>w!rs4KRj2r zpVhfoof`g6br3sd3{Kt;aYE0b;U@+lf(>}d??kOt$e1&7+}TO%WQ;d@`6N9fPe`>Z z<>xMfI37ZfR0zujpz4f{6A*yDo9482b3wTZ9IeLr&Zqh4n*PNJeKTbXJ}s;&Ane_E zDsC-4)(LeTh`KptrnianoDJgR7ZJLwUeuoPu3cT~jfi8HcKdv=F;j}w4sr)@Dw=Wi zwqJdQkr~Rrn#<2UN8+9VKp`4vp;dAE1{g_`$||4L@xrW(WLpx$Jc4=zw5Y{8tplAwvWs;jw*gs9 z6pQ3NEh|LJZjDob#@mO~%DvtohiOt(qU6AQ)E*boA4?!xhr;ZjY@T#t@sR?58_+-l zBujFfwn$PZ8jG*-$(Z?ShCo~;&jGdWK$+_7QuCKUT4Ad2r`i*lC(L!_APLbWI(w1O}eJ8^N zki0Me`h+Sr*T$9I!!^Jw^NFf?h!$U_f-hbMLiy09V04^@R#vxE`47t~mbOH|o2;99 zglaiYCU5qmbgjlM%af}{V28o0LeCH827h1%3@ybNnVhm%o;#$RQTOmyr5G`38*vcV zYou3$t8Rviv}%X$5&>MGsify;`_mO9Lj=w>L?arb=~}=_uznrCkIi~s!yA294Oz#S z+Yk9c&*v3_YJs1}BEveUJ(sEB&Ljn9RR173z*(VuhwL+eX5ZGAJd~v#=~+pikif=HT;hlx#NoRePhe`v&iOwJedG}iei^>%%NKai)woK9Ww zO;0ot#!*UQ9)kmzfrbL8fW{zqZAcbI-54w4y>%t&vB=HG>g!Xb4enCrsh~3?`L%BV z)m4z(DhGoWvVF)sAEi08#+@X{{eTKauTtM&6_Pcsl`qOqGo&mB-8dd2Iuhj1UKqr8I>{fC9sZqAWEQPB;* zqW~dtKYke=1(yF6Ay*K{fkyyk{9PYsqbHU?zBU$`xUM%Z1Egx?iBR*q18jeFU8;+T zc?deA&<(M(s+Er`I8z2Wwdnt9AXed5fnjp2MrfP)uT*8d+B3eX62C#pWqu0UMb>3? zw#TvdREV*XfWT&vRiEk*DQy5>JWQ{!_w3XW6Z{K+S<0G)+&ks_BmO3DP*VG;fT*C9 zDV(l(Q2cz50nyxySZYQV3Eav^+*N;zA+&~EXMV9nM(K3*-cmUs5mUj#bk5IFJqK;v z^GKd~BH|Ps&DH~YS9A+-T7Jy`T6(W!`ZvpkFSnvMAJ=$DWm;ur3TpKPUw>ng{U@Jr zx6hI;qww*L!5>SbSup6Fv#j+%vlt-9m}S9Jj^wDLvY+@Ds=rx}4r6X;+DrsV-wTjl zDz#Z#<>>qdLZX!lWMbYlD9VzP$_J|OM-Fd`AHA2Y-errdEwr;4aA@^^!r}MCD~9A3 zgZ3)`{p+E!6&T3VALc6?wF+LCF$4NfEBHz0J4yqU(Lkv~!21`rl1MBcEuROFr+x^K z8att_6@Z`m$&c}xXHpcl3hbF}Rv+-zRup|+I$EhtPd$|_JB7g4|Yx(n}6K;s_qAM4S+>glZtly&iZCFTt4atQKqJXWe4Ex|kywR!4kGeycBJPF)W z{j~5(k2$^3Rv@t_t$a-2ShFpDK(Fd@-d%9yy^XvvW!Yg@S&pD5`_Sim5Cd4p?Vjx@ zu6qwbeYc*MX8US9d(+|o|Dk`Vlgx+4R@h>9N?VTw^pt#KaCl^=vmastLZCye0YKLI zI`~U|z7~GtVHU&uVx8JS+b(V*^q6NAEoXa4@ ze>6@yjZDTVNDh5TQXo5#`r_Y6ElEb;b3ff;imFh$5<& z+>!_)?~>h;%q5O|wNi`R)0%qaaay}~Zm~^2;|T`tY1u>ho_xTfD?$|D=M3wuvdzBU zIeSnZA|t_?Dt|02as5YAT~qIkgYN6o;=m)hewVo~Ph`*g-G1t3cUKc=QUHA2w}>8DzoO^V4V{Vd@g;K@W@uN0$b`i}|zY11N`!&t;q2I3E%YZKx~bRz8VvszN@Y53Pi z|6#M7^`qNnRp09Tj+OmGG5XCfZ3k^9nsgKEiHn>n69a>E<}tog@Wy-J($2u>^yv2Z zI9?opB`ou?A=K^4Mcj}Hwo$NiNT5*Ux^D1|g;LB{2_xJc-5ax`{+Z2j+5hXgUGzsb zaQ%88{CS3-9LKTTJ=tqlOz+(|y6=2L{&K6-bvG@88(MA;+|v_0<2v5_(Vl}@%l&WB zleN=bT{!c+&@Tc-0)5Z5E@y7mkmkqm;S+6$#_Nb1g=4RdG3XdwY{5whTjoFKakP`M zw6OQ8uJN}b+fuM`N4WR0tlekJ2hUNmJGQdl%1FQE4ZQs123j3p+de#{*+TeXwmI3p zGSGmXQHK7b39Np}KLskNS^|(~;0%<~0}C=8HE~FeH7Cu-1vbL9j>I~#euixmzw93n zvdh`3_pPnM+f9|X2JH--b-UO>!GokWrMTB)s{7Ob`0YP1BoAVp2+Xb%Hw%FC5dfiV zhZtmXo+MfaR+)o1#HpP33zG5s>q3s*LRv!&NmGNccMa*7p}5CgdA#a;{;X*`!{Cb? z37;7vwb33AkDJH`^04`bu&dPcm@sHZWWWG=M)~e^svO(;-N(oB{?FtU-pMmkHwO7f z@|UD^lXN;W6PjkFkVN^=1H&49^uJ7pgA>J>rS)#3x7GA>hP&xs;(RTRqmGu?>4~}a zfPJJV=jrS`W*SqScw+2}VXH-PKD%?+ zg8-vHkE_w>=&7e4I0{HU8b<$qKJ=^g`448W92)If5Haw0v|{qDh0i!`+3?0#`P18_bAydS_L`lzDQ&o>uYzn$lbBim1fmJWuBd|IzYCFcjpKKtX@ z4GtRrB;ZoYRjnSpl|eMK>X7%GSsP9(b0;5&r^FmmpUVAlH?n*H{4nYbiFmTi z+^l^RJp58Eb49dC{biV1Qv{#1Ikkz@HI&IKYnZvi#IRE7O%iNDJ9Nw*8@G#D>=q3; zn871zOiCc?P}q>76X`TSim4Y;S+brGZ90%8sJQ-6H{aCkU5|h>#r~u(_Pl4wxe%S}-41ABwdk*9rD<^tXm#z619234K z6<}`_$lEpIY0u7I{kT4UVcB8bTtDi)LoNTKx7heX#g!+HyJ`*N35u?@L=#goz2!n5 zi7~CyDy;6;wi!0~*l|6H_3z*RU^qMwhHaw*eqQzGIz8vUk)tCXi{sLmCJZ7tl)B#KJ%g$e>HIv(-6G0CU69B8DMii+-x6aiQKWm`^H5+g6aFgj`B_z=1Tv^D+p0%=i@y)Oz@hDk- z_gkUk8rO}E|D)(m{F#3IIDj+T%xuhDbGFSe_kAR3n_=$zKE87wAqt^u8)ME!2vKt% zMM$Egxo^3nR7izNx{q)9{`~%hJ+{whkN5lae!dRIpJ%;&Zf*9V(-mZ-rg3Jn*YNe} zma)Ze`u@)Cg*NH@yTpI1&Y5lii|hyjp<>^R?ibgv3!Rk?io9G@yn@mahwE{6YSY0t zwDbE%sMI2qY^a{XN=cY1jS%A;3Ro|vb=MEj6H?awj+FB7&&-PppXbr}uvz5&lu^2Z zQ39Ryp7h%?C>2~eslmfXguNX$5opU#l(&-v8PVtoig9|@BD^pFB<)5K*ua)U9P<;s zvxKV>u;%7Pb6@F}i^H?m3RXq$zmie;4bJuraY#s5xU<$aVnn`@FVQkMtb(h`wiUfB zJ|PM+ap9G4Nwd&yTNaE#D4={7EVVB39(1)aAG0&bAy|0PWy4z=#JH2b&+z(~9`8m{ zi5=g|?{6@AY)D+DV1>{u8i*C^FVYDTQIUMYhqZICDty;}nWkTR1k*&RyeWEpO{_u9 zTEJeFL-@dxCfT?D&JOS(hpYNpvd=F|%X@PYN;=DU+cR#TlZ~wCXfoZ<_;@x4`Ql1n z3PWOl_^P{)>xZsdhE|iNYiPWr@L|9ABrL?OUX>U4)0xuwJXo|v^~kN+t7i7mK+liC z8M@?-n^y=5Uf=j6kQuL}rMJoY(%0zWx+ZBTr#yZfwBe^}M{-HUmYM9XXQ5n-dMIL496tz$zZ|p1__y5)u)TCZ7Q2FAFqJ z6fI!d6x|d0WKYH*MK(sCXtN@1y|z`FQzSwFqRBjnI|%PP&J0nBPw51{s)9Uy6mAM) zK}k-`O`j0<(xM9hE4G2s>Kowk`*cUzXDKPN8d!X6n=i{}b^al9=pd!_)|3yO_44|H+-Uruh?3NG+0rN8%cnJk-p``F`U(6+F6~XJ zZ@dqCE;7AeNiQ$HF|=9;n(M21vmY^+cNplMpNEEP4jc`StqAffX20#JKRO*)=Y6(& z@X4pcZm$kw;neE=Y|kmH%TFO8foTPKW)f-K;^BmP132fxA9_q|9AXXYHZJ6kgeNUL zi?kJ+Sd=($u+RvaLj<`2$C^6$@9h=5icX+U%^|I=NJLI~=L=(h8erA_N^!kp=?;7Z z@L!>=Bmb+bnkq{7!<$cixb>`Fr4oH@zG4C7u>O24-m^DJ)&JiVEne8(0@1G$rN+D2wzoY&_GkKFN37 z-nQ?k1)aYa@rXyQnZITY1y7Fhmzd(YB!K+(p93`rZ#W^S>Xas3T3@Z@1#n>BEw5S{ zImpsmz;gOsm&;eZ!whotp7A}5?@s%cZBLc<%2V1le*C`md?jF^kqS~BW9)Ae2jptj zp}1{qJAIL9*iisC+pCsrdYbUY;89BESB1qY2Xh(qgbV@yM)L+CzYUiMX^y)wcUzek zRAcOcV>{AMN^@QdCu`LD$nQM4xT#rOzSG-V;Q&hBc+v+6)3SFa0Ol30aM_n7sXo3s zp4HED*$Yh1ooE*U<96#h|~l+fXdwSu}#nb7vo& zOv;ri=aKO#9c9yc&>brRg78fmf3-l?;t_2*AUiA_<}80QR~dP(+Ta>gY~LX07q5zRoEaOg8ml*z>@~@Y!v=o zs!zGn8||eY#5J9{GGtw$evy`Dg)|UoNAxuzdWmU}F?JuXtoTt`@m2bOb%6xkzztis zk}4~=%{!T;h~A+;7ewMPNX7WVZ_--d&fHFrzVc4@5J_u@JW#k&`TOc!yeh-GGU}RU z>KXaOC{Zqz9`jD~bh+45U(V)pZ>J&)lPNp3V2(;tcA@I2nCZk&1uc*_Nd*XF;l^-+wzUu*}LyPn5Ho0~X|>BpmobbHZ+H(! zWN!nR&w!3RW1uOP6XnRy1cIMb7E~`Q!=yy{G(40}QTS}a>tlma<>aeo1CD1SDcRF2 zB{5|^6YCO1Q1OZybfUF&CT~u|$%E3Beol&a>G>R34=U%vm;SxQo+O~nwQO`6n&ss0MgMvIaT(qzMOZ{SL#OGEfE zxtA4Ps6t7}Y{P!eqYDL+j~WHL(4svMnEtpSmnv%5q!}e<_Ia?-Mr1U0&@4u8$)L(? zM;CTZU`G5mR4Kaj%tjUCpj5eu-GkI#<`5VcjU6fIbO*1;9wN*LInY;n@z*&>KC3Nl zLL54DWMhoLa$^X&0xI!&H`YyVpsOFRl;+UsQA8q=D-m5r<0JJW8=+0>5_=*Z@=)wmIbl5Y;P#@q*?Tp${hN5>Uhh(nPclgJ z!et*X^}&flzm(~3?D_}>4h>ysEPi^h&VPc&p1mU@)N>8VTZjB5V;b5bs#3S)BkO_$ zj72KWR>&S4>94@HSIlhCsb4Cd_s}TL4PK#!J4o0d`pWeVnxb3Pl6S5!3v>9T9b{GQ zoN3k6xw2WV6{9BV!(963zFbV&(xk;q%FWwBK1#jGJmPr2bCa}A%D|Zd+T;q2pQ9{w zZcZebmXktPC&;+cfP8v+y^2+)MJvB3fE(?)(C}V|%7!7QIZr zf1yTKW$T1A(0GbqQ`5+Ue0M*;eJ&3Epl~&B9U^>Of4)9t^&!BeLC5=Hs&{*|H|XMl zcjX0dm51y1rjDtCgv*`}KAgAVPqI~wvprf3@cF6sg#++QW)7cW`ovw6cVNf9I( zgT&2=T1jb1bklTK>)h((`WgivaRrx;nhb>YUH{^AuhG7Hy{W6zuxqwxklOXiq;J>s zioQVoZV>&ky>ehDQeWrFn1=g9aoEm+qL%-#iOkz`&7jV7mbEs~c0 zG|}U`n=xpJ1+FcQK0dbo+#}S>whSZ0O3!=Uf8go;2o8V5N~s-2Eb z$F;L7Joi+_<(hTV8apN%d-$t4<=3vB$ujx^qx)hsbN~I}ToHT|5|6H1 zMCDb{CEMs)>0=vsYIT8HCvZdf;(Ce3YF|fqs>Fs!QaO(2mMX&bo*kp`!hC(C^pTiV zRVGzk{PLqhkT>4+E5yf-#l&-&_*oEcUm+Tup?5bhdMv{qVi(KhKcckLbeG?NQ)~Q} z-5Yq^fn=d*sUd1TJfu^HS+^UhdWa%Elj*;UKE!rU`#x?GjlFfnSfuq$PoZsr=2O3| zbN$w}uJ`L}XywgSBkY{lhqN%v{bIrOSEuDP=AJDGD1~a*Kv zLb>E*^jkx_q4HSPz8VIaVD%jq* zF`bbSYz%IXuBnd9yY_Q{O$?v!<_(jAW1lvPY~goazZP5TNUbc5<$W6?GTwlA>0CyX zYet7ju

      0K@DuJ}-y;gzwX6btK4p=^qSa_u;;I&D8p%a%k6kymmj^nx}oE^ zt}b4pRvO+_6^LKEo{h1oqn}geYvFZPQaZFzn|}Q+ z6YbDFN;Uouqco--zW2Y#bUvvr<2wKRdeuO?A}ch#&!y-#lSSnuK%hS~Ei}&mX+~_( zqjfgtP3%@N*Jiuulx$v~d?_2LbVZIj({qP3Gx#ianppX=A3g!i&32R4he4n93A*}d zQ}w>7Po(7_X4h?W()!DiIj;o(4`GzkyFL3+_@5W9dyDUC%)DTtmK7{j^lE~QOcw-R zZI7P}j@fne$HQ#uBr3K~eXrBO(!-992fGMY)7Cd16_l=hh!XJWNLIsPUu1nEYiKE0 zq>^gOt_=!&UU6qmprh--?H_AlFB2tqU+ibSd~s*GLHb?u<^b#Z`Fp?cMjUx$Z<7Bto?`+3P2(NCs!5ydpOtK+ z*7)jiLo87txX?oTw>Phih*6T0q~ALi{d8b4rb47x0lS#F#zdMr7FOR(a*p&!VX28r z@RqsGv9>zHb^tceu$i@-iHoMOTgNEp`-=+2@{A7!oWVOvg~$aF-paD6NS3?I!yUAJ z8!U}}Bmwpx-00(;;l=pif~@JN$FICPex~c+ACyadzqJ#Q+Uz%3yT(Ao-5}`pF!6?V zD3$NX==d(PEO`k&pmpNnA?0+&P$GzdW#8yw`&g_&Xt05s0D&nKC^XQ>iz!cmMnQ3eP={Y{DxbwNn02JIQL7i@ zB>U|fckh=@ldPk3tx-$>h2=8%?T*TSDE zicEJY-bmSGvnSW7ae9hHQ*Ji_QGDbR~Nn*R!>T`~HuLVO#T)U^BgXZKy&y%(= zzlIod_Xqpmv-+T96%6wC9#R%Xwa{j|`W{?IP`D?km9bIVSz0)J)sJrGk?={rea`N& zP{&BcM-M%Xx|=KdCY^X+@KFSA442{zu|0ETbIY!pc-wuNPbJJM+vVMEx{ZgtK$p0@ zDU}bI#(fv!sgC()Hr01(q<*0nPLF1`EHEGe-c zHJQo6q$vH>&%rKEn=2&fqk`lkm@YO)LwfCoDWgU&L1jbnGF63Ra^j(dYa$Iz`dC&{ zwwrG)6uZT+5h4vA&fBb(JxbsjN3%5(ya=NC35|>@Cf&TAxlE^dL7tjGDE`|~t?(yW z;Tk2^Xnm|{ROt~P*%)V5k?~bf&3@lh@jV>2+^g_KD#38*RA$`&lS&Q2;_{D zkXIFTD|)b2B`noh2(6eGu0FqhT<|)0Gclp9{lbPQZ;2gnj#6-bRONjZMSx2vhXp}z zeJT8tw)Gv{!v{+2L%DoA&IPxYJMw;`A&M*px!-S@^VcXpi@UOFVw3goyX=ia)s7iO zg~$4%VqAsk#A4~sT>0*M8H$nsBpED^m#1;gt$t&ON5qy3c3kZ`zL!<5Q3LaJ9RkGx zz1HUAo)06(P?%|itD(@V2f6$0J*LYp?*Jnzg8`s%idAN<-j z|Wps~4|2B;gNT4S3VJ@?#0GD3oS=(rN$@N_aBiMNJ;iA4F!ag&Aa6SF zmtVY#=zV@UyK}VDGMhQCR|LJT43ek{e`p%Y!QjiV#Gh&(&~QFvRxP3=D`GD)0s*o9 zWdxPqlKkB1TYEENqY_`_YnY_J<0oT5sW);?U5?K;QHM`#WW|hu4qE&#x;NO4 zPaROj3g=(h%c#;<<2iV^1@O2(Arc&~c zVzv+L;y(Zh9kAO6T!Fj@>&~wcR_fsfQemdq`nAY}EpD$V^+0`wuy5SzMq7cbFys}p z+tj88Pr1XtzfBl4iJ&x%lWElW_nE0o+=oPc_s4f9!rV1B^X0bidM%#7=^u61 zA5SB$9>5e!VUjA76HFOMx-n(#SY|?`4$&=Z`dc=ge)^k!wB~*$(J3s?jOix*a6{<8 zax^R;_0nXD&3U8<{Y4#TBMm#0u&Ygpt)s^hO7R2A6C#3gaT?u9)M#`0mabmPom?)N z^tLPL&O(q8=8lxhaTtqfdQ)b?VMjt!T4G*jqAp|N9wMXIG%>yNrWrBy>{9yL*Yq3a zVUM?*p0Q-RUDhevKUw% z5LOwGzTx7g$!NJ5lled@x0x=lF*e}M zW)_N)GDo$#=n{v=y9qn>LC{F`tE`66mSb0WZSBLCVrqmLLLe~_82TWF*vJWo=!t7P z-*CtG9Qag^>F>ta!~AX8Dr{qiY=LcC+!i707)c%`&WjCGE>(oLOa!ANBIZ@Vz;25$ zDv9|=txh_&Ey>9|b6#UCG40S@*FYCK;A~x!!yGearSt2m^Bxi>Hn~Q&ZkJ?i=66k| zhfA0C#pX*u^PeK}3pMh?-{wvQ+*}CITbRg`(##an%o1_Szx^yPP0CDf1QXLv6sMB* z;JTnCJDn|4#g%I53S~?#BtkI&qcTSHqitunBuQq0iA&q4(4 zcFTdN%4XA;>zipyO0l(Xft#;z()X&nn!->+ClgLII;Lc@sKnDX_tB&vrEo=OsQAwj z!CzFzw7-#MpIx#iCrg5ev)^FyzR_L3A6r&8l^Hl$J-=0hGtX;wW38I<)d-Au2dP_4 z&FzWHYx!PlQ&m$7iC;0oJwL2-&yIf+5kImO-+si?vlKVVpx4fjj?B$obIVEB&{=+q zO{>o4Mdj=UHawRg%PHeRIUrEmN_bF8MczlP7sHN2s_OjsrTQI1}@i4P02{^U-;(Rkgxz>sTGSp}|nJXe~9 z;Vn_9W-{ggiujgGdFgy4Edx6({u(Xv#Z|_`Rjf4y3VBf+HT4{t#&Q8y=a=bdh!vB& zj-wB{WAtmIlhoV!XkvaawwtXe#4fc3eUSfvlBYQse`F!1C(BM4YJmxDsHPTiiem%Vb`H#O9 zx~7#o-=p=(<*Fnw_j=qr#B45WZ(gA+F&fX|#@-iHDbYP$(Kp@aUelMHWo)sTvbU4s zY^swqY09oqg{4Ym_$DfYO0mm8jE|ZKY`3a(6f3P5VRt)m@Ge#6=t%eK7fdXT>c_SU zxwQ>Jb^N=L3Ddp|@p!KoJhDh?bK-~c@>&b7bk_vc)=dv4F_$}u)mHNk3HR3VTDCS$ zCv-n*ARtQGH@*J)X&4&&`L zD=ZC%ej5fnx@CKN26=`rXbtN-4v*%JQTB~-?+y|Nw~}1!ZoSf)-djS?KlY)jyJC8% zDyZdl-Po{OdfAn+TYVHQ?O)q95>NC=S3Vt91(WdgEe=SGyPi?FXhr6y!O1$g=jZ|e^B*6RH{={ ziBr^!$#`k6m{-@yO+rg@(s^YX-0(Gb_$2js_UHE5qlvHz{H$>k(FUO|GW5FK@*iT( zbb>@dC^3K%RM6w#q!YvtKN|GgR?3rwKE{PN1yu0TO1F>IWJP^)InRwjtBDj!2FcL% zhp+XSh!sh&3gw!CDmTJ>VhreFe2$hy?YpfhpROuZin`bTxE)*Adl+b*^uQE?4Gjx} zgfIXxF;J4&nA=e_7yhwD9^eI_;0qvtA54B5MZ?{>RlXOYjBJ-OE~%B&jN{(lqeRcj z0_1x?!p=BW9b9(dbeZVEr1bf6xcg=sSMuEiM|dW&Z@yDh#qMqiuhyK?<&{!_LEbR1 zgC)WN#Trzb@n;ZeoN=WIh(mpfBL&)jzF&9ivWVU=2Zv)$0+*CDPi$`SXoolBHIzk~ zzt=u5@xelm9Au)*fYA+L#a0&OB+WRZejKFWYLG^%j4% z)ht3Wdq5-A7COvVsC2*^aCo0?l%+uA!iyYxf5`}zk4hlWS)jou#{pO~DQ z9*3OKo*dLZ?Ns~4zqLOuB8>RoH3iRTf6^2b$a}EW7O3Of6ips_V?XA>ws(Q-@OzT) zx4pQC0@#AE#CKxCA|;}+aoB`JvE+~#;@m zMn~4t)!ozkU$vi^oqON_nSZ?S(NB#+cUPR0m5Jek$^jO^+1k|ul|YCa5u_IO4T zXDW4F&62md-IaWu0ykc?=}rw~d9LvULR4qtLURC|p5_@wiULv~iLQY-6$g_%6@T<* zU$G~YDW~dIHF!*O`pAw6H+Nwg+{I+SM%?pK_xMb8jR{ZRL&m1xQRk@6BH6%fe#+1O z{J4|9?9V9gH*N95UcJwEx=0i%FVTILv6y@R;~0#{@QBE$=$P2J_=Loy28HP}?-+Ba*-VvUq;+O~F>Jml5;a_7h!ujjYXxpzEva zjITyVuCoYpI_5y$YKXaLmRqS1L6Fa%lWzv(>mg^8 zrYHy}2F4FS5O(Uw(aJHKjaUfGP(E|=T7nhBc>o`DBH_VgCy;$cnkbqE#^=luBDs8=+k;He3*Hg_u@lcf}HB&GRi+qYQKxH?Gn;e(rM zd-wjs=x=?5>QmcYKbwJz`(M?5w`Tu1>ryjN-XEM4K8TerEE};%38YWjJfC-zL(Eg0 zU)=$h&8%4M=Z{-r!gQo-@jQ?-ZA%o^9W6o6MiN$ z{(*%6jVRUcv0LFOlov(uqfpbKnk-MMq^9J3x~&P> zc38L>u%9|ESH!yag9QU%GChp$V`E+z6`r#e$bi-LfEB<%3h#KLgp_4hejgf4h2 z4_7r91myDYh3_*zz!;YX=nV+P4|OgN6HL5uNK+QcBfm7fPRx;OI!?RHuW~ys5)+C6 zI&V6xY1NfIak~}tQMYgdB}(Z^w6^INs` zfEr6!rO?NiOijSEx%lUf)-c2sUAbojD#Hr<3gHWKc(}# zV2H0&9fc+}R6$u8fRaXq1SYVlP$<%n0FVrbB9tsc8A6iy?}gpT1{s{K_3lprLy*@F73zWH$6f~u&Si^PNc&qbsx7*CY;GqCZOei zM5zRr6?Rb>6|tgz8kq!!_Bb}T)S}#)x*sLYd|hum*R!5KN{#Y?=nF-WMZE#98hG(h z)NHY5phN*D@S<_T7D2E;y7))Qt`1LnCPfv^lgV4dRkvO9A?MM^mB-%|eh%4EvPm-} z#^3*dIE$eG+66lecVqoB4bFlQ>;AOfw0oQ*(N1r_#G3Cm3EUW{j~8PnwhzLI#pDZR z^#GA_Yy0$joc=0P4~eJbvmWnIb)OS~ygHE77N8#6i2Od})wn_=4zN~^()2_mh0<~DocFTi5Tzt$avW>{u#ey{zlab3uNy`hRqQz zNstIx1X-BK84gMV9$;N@lIcQEljY`;oR8s}RrzxswC2?$G}AE!=auxEC=j)9H0}Lj(JHqaxu|BF}ef*&7p?y}y+H z3?77$n_PrDO%)q`*HVr*-bwzC%eFO$sC0@bHZP~(8hH9|7q8wLnNZ?fz7uQg=DP6* zO}rUEH8|`Q4E5U9_@9F&^Sz{)Jf!rUMR4K&!@;v&KXWNQJA7s{{>8rkKm2FE=KqPS GuKXW8Xdw^) literal 0 HcmV?d00001 diff --git a/doc/move_method.gif b/doc/move_method.gif new file mode 100644 index 0000000000000000000000000000000000000000..4be9d7f6a78edc986ac13f042c27f62aa7921684 GIT binary patch literal 57693 zcmaI71ymf*(g(V@y9D>(u8X_7JHZ{YxRYJn-QC?Scouhe4Hg^%1Omi(pcM-Mg+k3-UCv-&H#auf*w}b^dAYf{`S|$w z`S}F|1PHE)I5;@i+1WWcIeB<^US3|PU(nQKb+n}=HDtNjIpJUc0KjXLfvN_TjD@Gg z>%WM&FUZ2m$;Ok)(#FogRg~sy&nFrx2WwFpeLhuARgkoey@P_kyN$NLnvRvfla-(~ zjkp+>^y8%oLpQ~{QT@(yswgTu~Kn!a&dETzW(^xxOj#5_=UIysQ&e#c^%E&+Ez$Q zM($r@y`G8E*n4_{gg7{Se0aGstc)a&=x3YQdPWyK#kdU;yjfLlXcb)g| zo&UXx8usr!-+S1<2T@6D^HVXZT39)_{%v6TheB0VNYT~9)56utMo~tT=9LG#gM+mY zH#ZO{$;T%n1C$oz;*#Z)0&+`AN^=Tu0Xezlq$H*PO)K->%FD&Z)$`x9*8fK<`(J7Q zDuWB?bz~VEcL#49YdQD#E>!pll z*x&oSyR*Huxv{>sy0W~qxG+CAJ2O2sIWayqIx;*oH~{_B-`CsI-PQTAqrI)QrMaoG zp}wxRrn;)KqP(oMq`0WCAU`iRCp#-MBRwrOB{?ZEAwDiPCORrIB0MZK1OomL926Mf z@8|2|?d9p=?go1A>f-F==wNSWYh!I?X<`1(%+$o#$k0GvPgh4V~xOjJZzNDwH%&&SKd&Be*V&c@2Z%*4n*|CWxHhMJ0!f}D($gqY|JApt%f zE)F&pCI&hhDhe_ZA_6=d?5lgAeuhVY2VenMUp>XE%NYj%;9oc=6l?o{7c)IC=8OqO zR@_K~Su>V&Xj}AZfi%oLz@}b0MB`8huui3C7zZT{C%!vGYt_D`Ksogxjgggj@iKPu z6jf7jb={%ABBNn9-FtMvZ_rR9!2iO`Pn=KRTgX>T!b?Lz#84bjO%`OKV=SGLp5$Ss zpXP{S?Gofb@04p7tN?Zn6)01LMC&S{!($@Aqj$q&Aa!-OBO!ijN9csYBlbfFFoxj~ zFy|(RXQt;D$CsxW(bg7LcGd=$rl4qYheP8ZSNgW$k1of0`c`f)dPcuIBF);MV3O@g zO7FoinW9sqX+WtYkq~kC5J8uCOM4ButO1USV+DI24-Vx3xjdH#{^Ht=Gm zQLXp0lIMj%vsq#WUoLF@V!P!Q4X9h^db`SJZdF%^FFefjDrrOe(YcV{qvsdFY=;vm z_lM6!YwqZmU;*pBPDA>@P7)#CJHXP?LqhART`1)V3%?NYfo&IETu7@D61h|(=Ekmv zm1eA56z@X;uWZCy*6ekV(0(;OpV)WZ&Z_MZuEC~skT$nHtD%s+2#IRG=B?44}k}&V) z)1rhB*y^%y?wC{Mc=~f_Sq6>LP??eKBvXlqgpq7wwwBUqaaqV_bupxaS*5lZ_s3~D zf{c*lJ3KG~q2{o+wR7`Of{wGq81q!!3nG+ISQk$C)M>T>$89M07cu{`ERE+gvD# zAzz?><7VjcPVs%-%_8G`f$VkEQR2R&eNmW~MrUq#gn89iWfX-gcgZ9iEaM$R zv4M|eSX~;rRd^iYc&iKEpFnQvE0~X@Q<_y|-#`-++bAa`_eM&?I#`fWoZve(Ct2Or~UL4%`{ zf9X!}xA*eOOuWx5i;(>Dj&;EAgO`1aIb4q6tHqzqDFi;~Hly0^c{llz@Fri*4PA*j zJ~ayjHhmIcN3YB)Y`uUT@(~hY=$Yt@ZSE`Y5f(z&FNk&SniCRc?>u&Nx@uht`Eu31 z=}sBc`MCnE|8a=_(`D-y{lbQOJm5_=JYwg|S?S%U&!xXO0FW2u+r!4HmmePQ5?~pj z;AM^vzXK>?cGkk-1{;G#q7VUiQP3ZXFd+o2d$7eJ14xcZA@|=t{}$`~gwQWR1b>!) zF7sHq@isBMs+7F&j^ORu1DZDvP1b0)PS4&BW@LBn`pq_cZwQKd_%~Q>^mnJt;waYy zVR*xz3Bx*uf6LhC{YdXM(^;fT69Ys@202*{M(#^|S#}Sl!az~ z1C4RuwUQXO(en+P*l^%|OKh1h=Lj5_;<;^k^HC(6MOkx__aOwXbG|&+VnW$y_&Eb~ zEX)2mY)Wv3Tg|>DJm0VxjW>USz{f0=`KY&2q})*5Sr4t?k&FS@9<6Et!&?aVmQifU zK`pGPweZQLlCQQ}y(zEdg`yfA!ztrT$;6$PqV?Y1&Y3tHbjh7f`|#F2hM34a4KeFY zJpy;Arpgd6ed&xfE&h&z(vIhB%yqFf1>1xyTZDq+ba4)msG^((w{F^IHVxex(Ig{< zmZY|99vuOLPLbJSmHLu3rFb59=(Q8)YJWJjj<7_tU-m#TL&hnlnk zs}&gpNk+9~IxkDw0@sqT3S=o~zuJZg__-oP^7gGB2@JO%K;9zL#g~h86~2b6Dm}sn z-BCnFF@hOhbb2s7 zkX3K^`%JIVK)!JoI4pQf8~q#k==RrBqq^>euIj4ba020{+PC?R7hm2@6eP3+z&2qb zU6#Z8WXKg_l)QvSj_<*bDYo%#e!IPovlBD^*mL4x=G&YrrV_gruyH}*za}r{S^c<} zFUEJTV-Xd4bKSKqtV51r9J%p2M<|%S=?c?? zUY7KBfXDHsj~HV=R?)!hcSmFRVVni$obI$b=DF!ioILMW%}KiMmh@WZqjuMZdN207 z*h5DU28-5&4F!)TshBO!MQ7vt>t;hZr_li;lPRK;meIcH+t^6IA)2o@lg=u447nyV zzlz;+8D7NhW99^tTb`8JjF^|=R@2gfrsyygVh>N6`R8HX{^!A5UL+1X7y6HyYt`3a zLrYVVt|FoJ>fpEacA}T<$Uix^F_kO64W3P^F!5NGrn_8w6l4GXDP6zEl4(dIA`6K@ zt5{;8y06iMq1JlSHvjm7ABL%AFR^imL~t=YM;yxBbHcBVjki5`7y6!okKA7);JTbv z%pqC^pZjO_ct3+wGcpV;01N}50`wq(Zz8b*chM-H29QK=6F>j_j0Amz;S9b_RDXcK zr+DH-{&QPS2|&CN`vFG;xXGprI({+x3DflF+3gMwve*B;`7`n_k48_c62z}rkZx8@ z+Mt)?$d{MdwSavjfcBf9&69wclfVVLz)x#|C^vxzkKnzJL1+fSg92cbrU2xppx%>! zgU3KTgJ3wuAni9QRm)iFkD4(s*l+as`F%jZF|?UV$dEuFWfXWg6VjCg=3@*-$O=AQ z18+r!?md1Wegca`pk!BF(0zd*N91GxXWUq1ycaND=rj}#8@n_rkUmONCi??(mNwg|LOY`^H*%z%LnIs^ z;(;;UaXfQT07l0rSYJL4!!MKf2_iop+LsBz0Hv#NQDFdsoB+cV0pH-^^|0ab0Pg3YHRK?bMR$E* zCik1nxbbk#)9_?qjKVr(whAnb99*OjZow1+$;z0Vh(7QM0{R7!WM!;JWyMw}8EoVZ z66+RZhf8*ZXAyghb^#>UKVS%kh7kuZVnbd8Lg1bX9-d>%fG_z7jNr46`C^?p!N_0) zWU!chb}4*bj$f>qo2x_;0}#rkL(%17yw@! zlNy!Y{Ty@e3o*_{^MDmTM5e>?XW;$;%Q;|*Q3JwEoXwt--ei#S6D3eQnq9QZ;f@ccE5qe;hs&@Y)8w&}pc!oIl`wOyHVtMWa@QF4U#1g2hJ2 z`I)CcUa!C?9erCr#j87>>@>0L=|jb7D6?YtVsw5g@Fi9K2ZSj*dQKn$cv@Ugm5Z!Y z5T6y5D`=o4Q|&1juUG?~n1C=&mPoIItE1wnIwJ$3k z1w8Tu^UgNH6Hn21kmLW@M`r-BM>5N1m~-^I@@tra5sLB`HbUF{qGx=|8f)@V6mu*6 zf){_dZy4pRFjs#Rsx9mS*hUA{R;4cp0=5(bv7btiH)KwEP_<82_)!S9 zZ?EgjWUgs4AZhfmPvYOmbabjAJ8xna0wbK4K*xeVzQJeK#PuV^Z`J?cEudX!$aB@rgm zXg!AIB`{=95o=an>1uy0I++~ZJ7;r7*9`QOr5WeJMim8iK!iM z=;xEqOX#HN0CX-G)KxgrrYTQD~*G=_+&hA_S_U+jZh@=2U(PULa zktg?j+CwHX&(90o{CnPAG@T${E^w{7tehhpA22~h@1}W!+)-Dng z1znKzZ$7pUKSir5jeWStb7q5l5nkdnU6P3y7q4;H97z_xDf{El4Pc6F0Jc`27U&SQ z;byIyZPc_+*S^Fy`vFq{qDlQ*<=LZVmA$NC+?aF} zk8!Nk!H+*D{?tNj>KE8!n-(Gguu18SOu;pi;H~JAkc|Rs-^4!?XyJn!eB zn`7|?+3uV5Eq?8ex_4xuJEuMU+kO6%0RtabIO>{)(E+gY6?WO3HZwiTYjJV;>6WLT z@_~aKY_;Al1+kqk{XaMRjdtprp6Ak8%Nl;JC>y1iMOS|j-6$AOG-ZR%PNo!3_r4ge zeC>sL#(&1H|I7-dyU&hO5`t|0E)j?dY@cWjc-le2gjPBv;ZKF(yn2f67=&Mic$~D~ zMC<8=urK$%#rXM`H&v|6*q#7~5NG0hJFHd3>$WUzKIcbA}!=g!@9 z)rj;ep<$~itE!Rux;r5un`d}B=kF*+(e;0NA&)J}*-9c^{$rf}M3#Sd5unx7#DeC# z4S)Kp?2T&f3w~23o(~#+Mo*VF+K2i1Kv==%$c@p>`0`BV!Rhg4Rn#*OGGNC)x?drz z;zz|4YUAXV%@&zL{^p&$5uzz4S5TLO?VE%K{h&j9>>IfKc z{IEVpdiph!5mKWRgiEn>gZ_2RC66^XO`L3H9-R5xulORa%!@2CC}#^Me`bN`VCC#s zYki$L2ZHhGkT`NhpkW2?rQ6Ovu0c4E>MRDfs(O`uOriJgIsc1N zoybea3zu3R!@WqCkvAM4aKyrLq`0bXhqWU#_jGu2YP1rtPzeYTe+r`nz%~sDjKk5)7K_Fw zR!miE|EV4{`cB|_i21JGS9Q|=%Ao;K+}U)(tGo4_{F4|3Ane1B%C9Mc*?X+r>Bp*# zn8-<}J&RetP2Y8|iDpmExoW=)PV0dJ1`E1V*u#?4yCmjoc?H+s#izoMcgZoY*MF)- zb=uDTjXP2AH@doAim_AS;;bvNgXgkin7`lCAGG@`KodErySom(`Y6;Xj?gK6kZeQm z=Sz|s*+tUUr%UHAx0o>O^?F-M5fwTcl0;5i^cPBGlhT8lMl33=L}ADgFnd3#6yW`( zDc_Hw?Ij4&?5$lg1%y_D9!rm5kr@b+Bw)Q!q>>oCa4jh_>+qd8wJtIg5QS&>^MT{R zep9)%)d5_@6GhTI=dk`E{$xtHG(u97)!ULq_c%3!uoyys9#m46QW<5VZ=@)7#MTZy zQ0cP$8+$L|wCH%2-b2~qY7J>4&u+~h`O9k`t3Fk8b1D!c6?E=BaDI*w0*45H%mRI11OflKBew@7fgw6+FQa68 zo+A=WwAM|6C{J*a0_qh7$s|edk=s2p3oePykSFmuvQiYb8F2OnA`y}3)5en+2BO@7 zbVT9zjIfw0nf#(TybiFHYQ81L(m zgqjk-Cx|I(CFdcNu0>aIld=W+{t)>L@nal0EVR>$3cNP|J*Y5C1CbR>&n(os@B1Z* zd8+cJaWiU7**Xd4S(3s(VgpWIpZN%f$S8`Az661Ln7-awhGZ@l zB+(o}@|*vF)YHIiKA$E?hI?FWF$^vg`GW<|tPHYb1@ChX z@z5~G50-^&kszW8+*sF=+P47I_4#ZJAD{<0P~A5&K?tGQP7vVL!d?hVfR5c$Ot`$P z^lZ?EQNPSfS6|ZEz~~`jH?8^b*4X7d3du5TuL?RrMm=3jCX?c+|KZ6YrdAY5){jp}h^Lb$ckCR1Er zG#UHyR(oDn7XK9;>Jv})Q`_3cp&tff>*LAef&qCq@@TQdvMYDoj#+G8UJ7G0q}iBY z%Fbp(3=vT*U?>v1&d(~vVq;PcEovV~>7wtXYb%V&F8bEXY;%0s{45=pLB#|nO#8UY zh9}TYMP=|zz13rq+H;<_hINSKarw)@7AZ9)_bngs$8FUnr#IGj$}Z88h1``9^s&mL zR8A~it9(=0opRIIhYifP^TJHigZ<*Xw3YYX((XRLoV*pVx3spoF#hmHo-KMA&-X~3 z9V#lpWcNBv)3}WEbZIKPiuM_Wmvthcea^@7-RA)#W=Vy>^Gm>DD44_HX#kMvvElHd z%;9FWB~gUHp$Q)G#u>N8`nqxKct7XQhCxE^O_6$|wB!KB#ZMGORHik8o6E>!T$t?U z5aK{{cs|Yn3U@FBao!v$>=cMaNN>Y_fi?|W!5#AQAPc*qo&U{w37#0iJVKtRpuV$> z#tdQdEhUq5)-pF2_be(h+uqc>`;aCeDr*d?u!%68UH{kOuTqs3A-+m!Ir42YJQCw3 z48g}Grx?`9V>gJ-go+6KDYve8L|aduWk8gNTX5nQ`GNn~m^rwS2&}V)VxiOWGT`#T zh6pgBp(*rcw-TM@i16bqKpFcs5j8n5Jzl0obQdQnO&*q#kIYS6ira8s14y&7}8J5oBLb>uC^PN%6GH1+nUaBRgNp!BFZ!KMoqmpf3)eJ8o zZxmff2q-Q!t_H55AW|dXXy-0FmWxZz*sxjE*)B}Bl(W6QD#Or7i;%#}7g}85U<+^> z{Bg&6K!y13R|?_#J1;Uvm=Tz-7K@Sd2=G}ZbBz|+Gb#hb2wi(fj$}U}KMWLy+IpGc z_!sqU@M!B{@##O#l%Rk5!v`rRq@qH5kzj{w8Uh^A>kCcGvP&l9ZhztTf#K%_cxHCf zu}h-roj$GJLfsQt!2-1lwYYFG^ZkIEdi5r0)A4({j9}h1qoqDqudAOXKPjrZCNUsh z%~K}6n4r=tnF@K@l77JaxOJ6<6_c2SNKR9;M>4XhMd6#mkL@#b^dV_7J~d<4hP(qr z`Be!=!?j~YxN1L(6m4k;cJbFN`Vv+s~ z_ks-SviY39_1kx5ZjYHov5Pg+!|}~YpmZvGNXLE@zEgnl=iPq(PgZh`#g37)j`eN% zn&&nc0;(o4ish-_a>zv{`gY2YWEi6_&amwE6rH|ie$3qA=?I3;&da!xN9JQl+a`+LV6`Ib8) zEYmITx5@C5vly)9_uSMmBkDCnw&kqhLbP-G@?-Kd8(xBKDy;`d~l!tKS* zYE;Uc@Rb-Z$7S2*8;(mT@ytBJHo?Gi#d*;yJo|v1H*}#riRNG5i%V_`@Hd=@XW^Hh z0&Cen@K5jXzlg`H<{s4(0ZlNJ3;dQ6HH?dWQ z7qHAxZ{)gQ%~Ff2W6LEhY7CnNlfh!t%Jud{@$1-<&ZmSkT?2zo&>>|>dhOm)E0MI= zJ~WtWDcHst9M-4q0S_U3BCb9>7-4VW^yfh+1&?IMA)OEx6+xU7VV)F!S!HW9GAkZR zL;%~5WDyVZl+&uj^&&c@gKlGA z^i8&uQQ|>63%-|@rKPq58$?fGHnGTAW2i+WeMGb(T9DiciUp5u5y4ed&m{pf1 zes#mVz@%bc&>#mtH4X!nj-{Zs2Q$VF4g~?+_0DMzJc{lpiq~gV3LQ@)si~+sxfPm5GP>Ujb$K0fEPs(GGG*YKiI8@Wu zOkiO2&=%C|>yk$|Z0A}k6Qa_3KS_rtBhoJ2M({B}eG2^@~oI^ zEDu>PpX90Ny;ZZCnKp=5F|MC6DxX0)ST6pl8yCag@r&cPdqd~1iLT|<;-l4)Hl?yS zrAtet(!j|E=Z0#LH8&eT-FBmIGl#EiL!-=8a~p@VOGE3lQv0<2`!5rxG)iZVQ}4-} z&~ijEW8%<>#J?&V>{=O6(|r26Bo)ZV@pY^wZ=2BxWO>jT2pM>2yVnaPGPji1p~mC0tTMRkp%meG85tTFUP@|RER zU^enr?E2KUhjmP@W*P2PHAa-x!=ZY7YC3Fsx}tiP2&VEuCI<1_iuooE_1mjEYOPb- zj=!fR$+!3DR;2k%EC_a%Oih+{Ovi#&MomnWz4X@lRM+!Y*J!uZuXK^hcKXoGP>ENE zWp{KDc1Qcn)>+LAMR(V2kfwHYrmu8n(uV_*vfnKbTlgVc3NA$|EWJcCW<*B8@ta0H zd#OL@)INtR!|$W~JW~Iz%2Kedembx8?pa-3vKFrEGickeSQpy=WY~?XP=XQXCbC)0 zXH=ZNiCM5&rTPgg!yGw*2Ah5#PKOBTW_@47BJrw^(9Gh@-eNq?YgdzMcTNC^hjJV@Pay#w$@;8oQ|)dl4x6#j|&fZ28u2RUPSzt!_DE z7C1XJ2IG22OWO)ChHrdxy`0 zj&}2RKbIdZzui@~-BAfP)jzg2jh6`k*zDE~E_^W^j=KQi6jwYl20jn})$N4V`< zG3fX*3^(^7sZE?f!>TL$sgK7>Q{CY@?N|G|ANSfWqeuV>?G_qy(RN}no8xC*W(m_I zl7~eyj810L6ABwGU;af#3?OUJVp-7%i`OFKh+RN}7K^GDgVzbeiXG&7F~IgjmDE1i z){e6rmGNOAcxusSSL;K7oxg2%sI7en`>Ee|yLh?9NU_s!%rhok`=o>uHqo=7gwrU@ zCHQM~yJOoQ@wT1~pMgQPfxb(Qa&~Pw$3kD`>Zt8-uuopH%xqyCY`L#wJ7_d!-|A?x zo5&aF9NpXKG&t(o>RpoAs`i^$f8X9r->Lkra+dC>Flu9FJA3J}tfXhE$G=-2Y}5JO z@msmg*2Bv2ZxgKo$5GP@#qi}?irqSX+euY3gN_S2<0Io?#h~9?(tnI35l#5$jos^~ zyz38vwrc|YO2QFae(i@{2uJk~hoXcA9|&B=XO$-84qe_h;g26s>{`-XAFO>hAVst! z|9(KxaYe4zL2hQrs<%)3{fdd*auf0TTjv1{qAQEs!TzcxX9eoPpQ{~uOY&fIMyY+A z(d*hBbHVOC%vo~`#P^tLpRm=8@G?rjtzM6JyVmh3ymSg(6?tBkn7A~rI8UlsO+_3w zO<#8OT?WT*&Cy>8Ut6`3-L$cSo_9G`_>Xv9uZ;dUwzw{9t$u0!^JPWH$!0}uKySBm z_h`slN?q(7a;1|{)=l3mXi@b-2lLW=^&CsQWkAjh`>S;?qSIQa8ENLtVjbx7gH!)1 zNXg5MnBn+igc})_8~KYh3D%cp_7yw#xDQI^1J7Eows5H-h1ux$qUhqvq4+OCREfapbuzimzW^p}gj``;r zmGJ9rM(N$L`2*(WeZ=O2H|zbMZ{I>Uu2K!ROE)rZG!63Ni=yj2W4{=vH*UnRZKypO z#Ps!PHEv|8Qt65tCjVZ~lHE8pGo*IhP@D72Z8!LwyUxWvCGzp>7@~J$`D@vY2amq7 zpxU2>?toBh*2G)P zLMI%C2!8q-@Gms)e89C*9&aC>z6%E*vgD5137%q}KA|^f|kwDcXASpc~Jx(Ys1JmC3 zjY}p05@Bu$NlK+qbxnN(aUH1=N+VvjMRdDpn|(z$BTQW3r(vCs#{K+VEh96tbHV(* zx@8^{^XnVNQ{7_;VfMS50te!2hcrX{#fkZ|&E=JsS|@KFGSE+1Z_K~E-TOfgKvw`6 zA-j??R%^G-qe#hPq2%0D4i-fR)G#I|jcX2%GJPZSPm`3?lqdCx*T5w;ps^lf#PQMz zQ1n1lM#1@y1>*p)0~`TP|16lOT#f1X<35KIs(l+GecRIXnr$VbaVvPql=-&$&t1ER zT}DYKwK#r2Qcgx4`VXV_cxSzD%@WJKr>^`z?KNffBxTK=@=#$A5iOp={Aw;J{e0fD zWAYj4JLt8NIRqRL3HtB>HwYy(Dk(W7H4Td^Ju5pWH!r`Su&B7Cv@9#u+orsxwyxH< zzNxvTwXGbpy|b&kr?;;@AsN~q5neYkls=Z?4n`QCn_pO50%I(%t#52@l})EtZi9FC zkB%n4EDfGsTwYz**qmJNea)-9k9vBrga27__Xif0Orgn~!wYeas;!h`nS~bvPwB|h z{GdIOa6@p)-maK2ZvBO(!eSncZY;HCwAf^#rF=@A;@#vWJg7o7gs)V$ccRs<$Jjw< zRcS?OzC5(g9Ti`QwPLPPV+a*h-w3`O1y#ar-g3#>Y8qh z%i3gqZ1ubvP)&NI-1t4mXI|~A-{dNtO{~f9#goHH2y@>l*q+2`ci|L{4d={TW)u-5 zjwTjq0kcUArUp@1+Hb*- zdOsCoP;1$j#3Ym%Kp~{=PoxnnLU__~zB2!zS?sTx<@BmsuckPk^jz~=HJ;ve{f;pq z%jYdZGQ2fQ3(@85y%Vn%)!M5mW(-qH&cm=J&@wSGGqQw&mD&T08bwR2!>|0Y8e}I8 z9&+Ze2Cb%*iay)X{6qnNy2yZ8&}9AaO9Yt?g9qKrpBYV#$JaZ7T1&O-VU5(kAj%e-$9gP7D9r8+?G4c z-b_5ki-KN0vd&PJwPEWj(wfTNumf8ALi9Ngz5BEyW#+m)`Sz|530-jRJBay2{is1k zx;2LMlluO5QEKb4q!iHyOfh#5GlYhyl1@u$&pfL(uJHxdvS-+44=J@#LQHXes927~ zk$Kwj5jUYW8`(EDosFu-zw z1c$U;ae?bGJoFli;jhA7S1eigG79{2?xovmI7~Wf*3G!pj7=NE zW`>#)4HBIkhUtV?GT)pbSZfgC*w63hYf^yz-KR0y#6h&h;v@+EdSMevK!2L;YX z)VKu@nk+_7yK<^&OA!1`34toCMHEb#njIC%^#t5##ee$Hznbp&KbrnG=;U9X&-9oU zG9;8`sYq5gIA8RG!iRZ-b$V*WA~iqP`lC4`JaEkx_i!N}(+A(e8=1DHZ`qnORAS z*)o`Ug%X}cE}+ti$_V?a+PeCN#wM#~SE^PP=Z-GUP7cHhGuD2+wC<5nQUS@~v1!uY znfV2WDVm8zlNz11t)vasSc&D443@p^lT(%5+7jA}vzyzyZ&_dOAGcSZNWZTgoKF0a zyks7!YD&(2Mr7$ZCvNKzv zvs{HI(?x{LC;P&OBaFd8E`KLX(C9n?d4r&~#r{Fo;bKJRQeh{y(^MI8b z)5Py}V8cjF{@UPpJr3}!aaC_b%+%QIx@jHf7Qw`SFZ4@(p*m*4ip9j0X`ei0;mVJL z2c+HIw0F88y#3{o`7a304=0q8@bmXMkX}`)Z1AY$N2*XW2lHLpIqm*(37A#m9!(?*4H83^-YON=y>YC_(&cR}SwsCx7 z+(?X6GP6$5wv`HBVIxohze}RPSUqvXrI^Hx%aB#1*1jPZe5YhFx`vFA8Bb)5$*Jp) zq0YTCZf)^FP8tBmQ2;wzST6PYlI6n>cs1C@jv7<|iP_09b5q86a($P%*I_s@Ar7>G zbT+51RuKjYEoe^RWl?I8rLJ`f|5#!<;f1V-z^1hcuQdcq28);I4>Xn?OZ zzP=k<1E$9noVTAS!H!s>vUFex9EO*sJ1ow^ZFkapUzpYzt`~`jDb^tqo=LOuOOFU( zp$gBW_|H0C;{SAVTmUYBF2L&5WE1~|tb?%rZUVFZ2U)*5xi!F?XV>!oAZsXd9_us{%N*E zSX-Ayflq@2Uz-AX#gRdXftc^+FML8o-hX;L3kVMMga6oo@*p<_!@jX@mqiDMgIgPN+w_{+%72)(On8k@Lf?} z)%your+L_%AJjZF1%G|dmn`Ouc@!=gm8KWvY9>_xZ3Hq+WMT4Ct{WN6X`WXo1X2Pa zw~j3K#BN|DH~ohEOlC=es<4;1P0U0N8rypt58|l5$4?#7#8U}}{d4>-3TtuPB9i~jnZwtieHKq zJOFf1tXy(JNsQ93eHsU@5T(J&v>61d^Qy88$Mfo{ikkD9x{exVCtMI1g&tW$>!Pl8 zSE;tX^ZR*iL(g3fpsAnGxK1V&ut0*Nn(q-MC6w6WpKm(f)`m%E1WvFhOgA2R9K`5 z@~r0otigS7H*w)Sq4}{Duymc(7Mm&yd$rh`>?(NZ$a8rMh~04hGw+9lz z^z{#+LP119QMC+>B{k*Mg~X*0nmC&$r)Fc>W#xpzpk&w=hz@VEsTVURKlzu$jbwOSwOP;vVbG5ekbQMv-PvEnr`#ga0wO zfGhzY&Ck3%15qyL&Oi^J44G7`p>nmvDE6vFvZzk+4+2bu;Tv}ql9J0%yqquDL2O}vQ5)s*}6o*q9 zcODzGq07J~=LBn@X`YT1l6vcPuQpgfGn)JR?2Xn#GrIcjgow!;owkDA8tG#f{cibIrkFG?^-a#Uz!sSd)uDlncPoKq9Aa|5{IegUm1E7C&7%)?;e&O2*n5O^ zV)LHmm-%eJTs>@?@??Qx!6JQpCamapo*J+S9S_<57v%QT5b>RgViS5cFhI7pIBA`J zq23l*_CF&8Gk^nN@=xxi@^6G_-+zU{|E~z~AGw#qghI|t;=d6B7scQ|b1$Lmuc-u1 zUPgMasV^}8Gp;?KZ!DPf+%%f#H$1o-mY9?f-}zjQ>2W z{wodAnqzayxs{`@thG&%EI#);5m$$Y%2Pd#Lhc{8+O&530&Mz*{VBl*`ufE+s zY=6C7`u_9R{g>z8u&63X6Vq@(aCpo*ckIgp;n=j^F%g_4Bf|sH9hPIi#GUpUEk?punFy-=CeA38Z?d7q1Um864<_61$o*>3bscukI^X<%XnPB{ zsQd0)c!mjPm|+G1=@vl{5NQE%KqMs;K}0|rqy(fxhHj+0ySvMwySr0T!a~8|jNbSC zJU;LF{od<+&-FVOe*xEbfA(5?@3q$GeB}Xlw^FXAS|FSm7duF9KVk~e%y@y5e%@HOKmgPfJ2Z&+`47h&B(qHGLR)UVVT6VLSP@74eGp z^r!jrZ6nVgI>5t|7q=StL_EtdA(u@V*6e=&D{qx}{eO)p_ z!+b9{!9<~e^oy6iBwfbC_s_}0eQCN2lww5vX?3-4%FvZ)L3==Be{N{5;UBE|-&0uX zX@bYw>FZxoXVgVvPpJY-=@t9*at13FOk-{o@dPZnpk;fECsz;^xGR z;qnpu2IR25tq!a^6J>}IDYKG9*+`MVcmZFej@85i2N`&%302BxpOF z>YL4H)S5KJF3yCuE-M_+2Ni--%tE9i01l~@K9i!r7FB4>*LP-ih;}#p=au$1;Oh2DEg@cTTq!>2C6{eHgJgBO$X~ZgabG; z6Pk#~0_Wv}q0k~^zK$TcJc~H1rW9P4mDiXDgJc$h+Z8g2+q2M3otenSe8KxDrxI@l zM9ICll4bQ}4fN7faoQRjh0@S~VMkY{w2-^x(}zgJyhhygH^CkBCu$oTruIle7#XK_ zAIUli0M5*byquxm0j6Mlgv0`WEk89Fw-&&CD;H433;fKd|`Un!36X} z1$&N2laZJkv>O7{|Is4;EUy2(Md%FHl`huXY!0OUM~ira1tEU5i1p4uvg^7-|Fnqv zja6^)Eh4|WA);V=G~;ea-aD6?y~zT#V%_1U+Jo5&!@)GA=DNehhL;B`!_D=_t2iG7 zqjF2b`^~=S>(547&IZGQS&He(txcZ~=Bh1LM|9l0RcV?-7**O@&UOd8u4<09wSN0@ zvN@Qp@}}*_Ihce?&G?==xjI+`phxeSFTjLP^GK7@uerwGFM;C~kN zHGtqh?das{A504U7n9;oyryP%qc>u`aiBV~rv4X`+M;Re+0@tLO7p#|e`Z8Q;%j>O z{TNS{pXIdIq4_0xZcTUP8w_BcWDJ|?D(skY-9`#QXo+}?Rs#nFD%b=Dq5`0yq3}pp zbYy^PsD4OPWJn4e;_n!WK*s3XLJPwgp^6oiq`(>g00^!@02OP1^^I+;=r^_9aCl2y zS1Yi;eyBzf&{|(!(NZbVT@&zzslU2vvl3J>)mpg=AVh<Bl3*L&dL? z+g0r>z#GZ8UiKBhS$qE*Q2FwI1ScHk%n`SA9C=046TX;Bez66YU}rlJy#41j_8LGKe**f=s>fOk zQv^AtLq1h&*kQwSytbiikf2o70~5~E0_Dhvt6?ULgGOI4;-q0lhLKDn2;~K^f*uJ9 z!M-oCt|6sOhQ2s8xy4 z@?ml@adG5O2$C2~tpV1H4@*r0hFt-RI)!NyXTwX<*eV5lV2)1s9b zAfAx0<0hU}w|UXsT3C9bvg%F1=uG60KZ=UUlnbbR7hm&SFkUI!PM$;XIT;jEEMxTn znK+XP3fuiIO5T6JN-mx69zuy7QQ`luK3lECL@_x0%3?=d0)8 zoz^{JCoi9`0O`viuSNxJy}mIpzNvR@ygd=0x_Qw2)b%~2u2f}}RHwPQp+CUQX~w-} z;$(a0NnYYB&9@7gi-tbz8WI9+zD6OqjqnO$^M;w-#rh8xR=r(9lvV^mh=YB>;8d$n)iC>AuG0WS`&W|7M zWU9RJYcTM>v+x)fvVG|mgDyp)bHXz|7RlHENiDN2=LZXqjoof06)b9sNoZ!po#@3H zc&nK|&T}wTh|diX=wLQ{;Djt3O|hSOzLV;_UAU9xe%jBjbbQ9Kn}KK5*Pb)hMBby- z=heb*2kYJ!P(+JfdQKUOC)s&Xe4?;y4Js1gzj+r2K;+*yjF^3wy(!OtczrWEFLBWjyA!LfLz|j}xT>Okkx)l4tAiL2 zfCf^LX50qmXHh``g>cmE3dt0722he7&{&bvoY@Gh&Z&dfcC|L+l2zNALA}knquH&6 z6C+Kepat~ESk2Py@s`z!!fp6K^2D#p`SHmKYd>u8{q5y1c=r6Zp9-1qnHJBU?>s;- z74r90=)Y0h6@c5zRc_o2++)*PGP{{5jUO2$U27<-Si6k~d&~s-AFjR$&0h zJ6}^@Svs>eQcA-Vo@rCtv-iBd7p;KPJkEcZLB%fOG4RnCQ*=+|wqArCr$(Zz{3}6G zd#l^(PWafZ z&9f81)3R)m+WlqNA@zHr26w5cuyAbjnZ3Dp?lW|(huFx`iW{E{!-|N-!P^`0!aTv( z&pwX?b?&6u{uDhsd7pogKl|$YoWq&y@MjG^00DT*WE{F-g~aCFfsuM$GXIbZ-JPO+aFgCZWIVcqk&%2Qo+mSIq3IYuc4iAi^3{FpuPY(^xO->DD0|xU)SLe3}>DG7f zFM*Wu=#L5H|1n46N#cJ4`8ofCkpB$}{yj(j3HdxY-Np}p&5?MLxKryp6#XYjgbQRy zuc@XHd7hr!GNMMCNF;GM%}lyT87rjUxVYI${a{-h`sW$;IzSB1?SG$PZEE|+^sBk! zZFGYo1*bn>UY_$c+%vZ9VeKBwcwxx8uPqk?VyUOS9gc~5TPyEj5c75~@@bIK#HASN z>dOV$1|e}qupsmmI|C+O*olxk%882Z6X80BeRmzlGT|>kWp(UwOL{zw~qt zc^z%@2;l`s1Jgr+a3CNDXp@}|lr1bulYNz*8! zpnm(Sh5cFpaB>xJf+OxCek}lQ>fa?MW75Dc05;o0&=>Dr=;ZCL^o6o07HOZ2KLc^T z&>Tp)Rgp;zzH7FhGk+rK1#)*J(wRR2+z-1Oo%E@9EpsAY@t%GRxVES(I_ja;veu-r znzD8$sbxbZ2AE?oDa6IZ?Nw1@6Lcolu@*Mdpkd|TRXp=nw@tq?3xZVVUB|uRXV`YF zJRIzH+1WRHN%=v!J(m09{S@_&YC~zUG^o^18xJOO6Nw}N1hr#ncg~C)m8y21FNl8T z>}h>cq_)B@3o>M*-QMF{jJ-z>M851Sym<}gPRrhF z8Xmk+Gq2I)8cckN>&`a`&alPL?E861&oaFn7j$NyT}a?rU8LeyYUhk=$f5dFZ|%`rsYbKJNpB(m= z`d>HwoAo)el5U5~nc7_w{S3R3kmp?a2(JRz8qrlfwJpOGk0GgMsB!+B6rGh=>G zTG{kjogaTMIVi`S2V>Hl$+5CJFQ{;YRWIl;1R7OfsspI&fO5z?U=Zdycg-|kvn=fr zPslq0N@q7f!!EZeH}q|I@(`uOx>5Tj%YKU~&<7U4i`I`l$;X$@jx27p0?9(7aUTe@ zPe8?c7QD(toAxjMIJ58oZsVWYZz^1I(_XWA@T%LQf(-kEl*g6^pkTGwGWuxpt7_uL zhOEn1hC}9nk&C%hueS^(F-$ODLVHoAhsA1a?WDOv1rN=c&%LzDr@>mSseBc?&J;zW ztVcmcdT-twGr9wvux?`BKJL!Gui$QA7Z@kd)tx5H!zIXBIKV3{A==qT9!|(?4g@F^ zM=OBJL4eX?g`$d@vIZ!&tX#1{zAXnWj2CbBD!4QRfvJbp{Fw?DZ_Hr9WD?~w8zmJX`oOuSQmtBmSC3siP1`Ejw$vcHtXz7PZ0~D^32-h}X*5atO#M*C z4XW1!*|R;;N~2<&Cw4jUO)7AsM1=)%^7fjzsL}9fI@xwdy3z~#a=92N66DFKn+#Q( ztPgv;IM#whYnZaY<}y6XH@Gcco$9{)DJ&%7^xpN9g&($cLuvd5WI5`yL4E%3e$3F<>G{|cg6a48j=0heCL*;$=C`jm=xH~O8H%z4wx|{a%$Hyq;49853M?wDBeE!|X=~yvt_`=l&XLQOId+-Y_hvVx9?4ZM z`d-nO-K25=w-R!+PQv>AsxFNOrPRm-$h)d8p+9N$P5e^q?|Wng*XiH)$hDbA()^1s!(#tvdO-$o~xu-9M3dGsZ7k_j^C@Sp5`&^|*4F9D5ECNFTP^at>Wd^>dLMZ;4z(58 zmX8fPPWPEYZRRwsZGx8X>&b7-$YyLm>-X4K3P8pkDORn26!|>(MW_Ki_3hTHSdb=L z;%#rPQ05kW;|>r2aV9Uu$7O)vHRDpS#4=^~gaFSezJ?IIH>4+U`jiMZQhhtX$<2s# zJ<}hQOrqgk=?ZEO3r!U#hOANb8jlfeVHt?YH?Jw$v!-_Vn%ft0f}xxW!zY8A8f8Gc zSj0)KDWAS^yA*fC4A*pkRb)@-^)G#I>hyM#-hRbcEXkutZf6hf26(kQkA{yO+&=~- z2a;vq*Tax)MnLqIewdpWZPmyZLy2n=Y^oq1e$oioo&`RhzOBnnQEdN7d-8>%f> z@a|#-WtTjAq6}zU+}5EaRUB|tTFI85Dv*}QE``Vk?G##h=}RUbg9l+FUz zFZ^#gGK4Kn3Ow{GHKe{tl;NPg@#lG(4_^*ecy{?~0a;=^*Zg<(uq*gIQ?CQ7A^tr5 zy~5IvN*dVbejMV3@y3}6!2Hwg3X!Og-mP%?QUX8eD|Y6GuKXjG*jVaAu8W?^KAX53OBdqG#LvyyumL>!sz^j&_+u3JI2dC--Apv&7XkP1W(zP3tlFy%(*avxmlJepc^4XxP3)e)+1Sj5?)b8XJ9fS+dcLdg$>; zpRb>8hKrALg+93gd9q$)1(TKxXWoTs;W>;ngbM_bhfc()z9luw);`x{CwqPGwcul! z;0Z2Mq$}Fy+*i^HI*`c+NRxVtBbkt{AkA|>_hM5o5cAU|)_1thO6CX6{HS$#a3a#M z-;soMFiERS%Er(5^9*RX#-V*l001ytK?wZ#d3gSXl)@TnKrtgGt>LX6Ld<>*VC=Qg zH&hWA?44LiMG$|5@n!H?YRpJtz!p(!gBgJZ;Dkbh(=PU1`vb|!yGji;CJ)e#PX0kO z72A#VAN?=MMI6~^+L1JHrrJy~3J+|l;@=`rocWXSLUSVhjO?vCOz#?ZIG$6?n>hADJCH&pwc`2fn8Gt4w$ z_EWCJ(mOb>0eGY|_F~>NQ-jV#T{nbnH;%;>asLyY+pIq3t|}RqUc0|%tc}zk=q&he zbUx{qEwY-aa=+ESwCzRxB;2ea$5fMg(2!h)6f9r1Qy;$gM(2g;=DM|{zMYvgL$vgj zG5K6J7+g9l0`mvuV0#Oa4@@{TIaS_5`q*N6ammqj&a-fNb3l1?tafYvtsEn|ZSUYiQ+I~v z$FGf_+s=N}w;-sff4H>DBewbIt>bXZz` zRqibGE7mht=G7v0)ubBk@j0mS9pZ^=<%tRCAAZ-MBNO&oWYU7&R`LG$c^k0kJrjqy zwi&U=*y(w?(SusGr;Zu?^`*mYr7pT9LLw}_MAS5Q?llx2yv^w_F+%=mFyb05=3kJ# z>t^5Y(ZblGyVNY7@wPVkKKAMN)3lz7=K8j$Kixxst`E{L_&h#)7%vAfUI3{Dd6Thr z(mCDIuntn3O8*%lJ%-?Lhe3^4D(0CxDG#BxkJ*!J3^xp|#xrfVEvMBjs1;izy zY|mjcy1CZWDB;0*-RlJP?f6TvqIGIn6xw_lEIx)%k_dH6B6+s>){OaW>t{3aSY2od z-}Yq*HWCt0sEp60Y+6=ny=;&BM0>yxAx@4QjWggLln~kVJU2b~Ge<#|&^|ylUC0Jk zIG)qgUIZ3V4FVI=VR24X>pCbmPj2;@c0$S)I9#8e_AmBc(QmOvM3E4>`ag(DMUU6m{TfASboqG{8rVsq`~ykK#V_<8%ast zUzxy|0K#gL?$|9;O(AcSF>c+3KC!5^P2x^_{Q4%Nfm+i0^|7qC1S&A`uVD}bl-RWD za?Md&OF(tWkI%vuaov<^);iiXDFnq&z6fG%oxQgj>jQ%0=$k){E;pLK&Yu*A5I#2E zbUa+VcG0!ay3IgoVSyA(F+~fk;e<1-RMprCeYdf8e`<+t;Wrc3e{CjC`b`5{MWS;X ze=<-6>zpNS1>K64W>sMs6`-GWD(!T&{({pvVb2j{4coec!%OP_R-0--H!62Y<5c9y zxKKW+TW?vlOzJ?~?~_Zz7Y~PDD0|`s;=G=})TZ1@PsyQ|fgt~1YExe&S)@EM7!ZxO zCB@v=LMJ>+PR}n$Rm#dH4lS&x^ecwN%ez-KHU(rpMZN(8^P0OVT_6zH0KB1lBwdLR zjUt?uwHci+y3d7vgKY0y*nHhvnz*$WQBxe3??1k{bjTlq_lH-VW7sS7Rnc@H}5@6W`Mpdl$s9 zsTTf4f@hYLECdsMRT5Gs@-oMeFOmAx(u_sdC|AxCb#NHJFYnS4N%KRCL~Wt=$C5;X z+t_wTi`zxe52hEU>rI_}p^=x*Y}h!nMeD5`9Z&Xb!%aFuZ@ayHy41XxY^o!kru&`Z zIiIHlV03JFzW%+s?kn043h!Q*-&43qI$oqVWw=mVul$nic>&3|wE=$D%Pk4J_Q71ta>eO|tlnUGmQgQRmPwa9X&D z)9`0vW6B6(LdhFRlobTfzP?WfWCVyA2qzf8NHy0Yzd{mNHDBL{o>@z_-(JZm+`qP z`Y3F%=^Y_Sr?5xJW$S~Zh7*MfZN#51={9~jYw^!Zy2t4Fs$)KrA4vTw_LGsSOf9Fqd`?|H5-BBUapA5CDOkoib)6TYE^oF6z1G!tM5!u};P z_@&z(6&?uiz*{XYES$mcyT8mSf9bZvfpAfu*RgSURUT=i4|ft?Wbhg&tpo&R6&4ld zfEDtKE34vC%B$-ef@<-qJlCkYg0{|*D110b*FYwo6Tz@B z;qs34ZU0&*a_602ZOq|eiq!k}DSY|kpBGD`a?ZcyMVeRetToz#^{BT9xz?p@jv1uD zd9qn`PQF|Un=u)iz_7s!C=C^yFNf*j)u2|jgsRzrxK7@VPu+X81BvxX)Qv&>J0J`A z;OCfWbMRdt>!K-IN^~)}36Kc&9C?sNakzVaET3-wh6>5>1}XrbkaCOdh>FHX87SKJ%|> zPahi&ETaB_q@ic7%XN@f;4WjJeKgziF%9SzUy(GwIh?6%Nm;M-KVynJD;`{ z_Tslck)7KWJ9{{B()-bXtau*{4 zd5R|(0z#2Sqi7ixj@(#j<-ILIWsUxvC{5C{`|(;P)Z5W;UOoRys?O`dAX(h}Hk`N* z?hR7Fs+y+QZlC!j=TDsfr-t`*m^P)sM2*$BFGv+QUoPLAA>HJj%- zi9D*{Tq);nTrR|2x)3O0XU^JmRV;P1{>_&@y6c+y`TXf;E1u2nb}>4?DL zY5&wb!>IM>^CrB#=*yuAy~``SSHaa03G)uXdll|rwBRvdydld?5{-buAz&aVF(=mo zt7Dc|oLk@xEUAnrE2^psr~v}%TV6S$38^2pb_GU(VKK(tLk>|$NDQoYcsjoqM~!Zt zSte~EWpP^DYn z#C2hnB3Ws|@C2)Tq3ziseQ)$nwB3u?RsKZ&70+6;`4;p5n0Z%!SF{7 z)|!ZIBA&4QcFUFWmxCx2eYNJC+n&N5=nVhIDg+%J>R9JxR?+D5Nj}vTzS6hpiq`de zn$9x{C&Mqxr9EB|KuvXKwJz-U^(VXU|LkXd=oQmwm_nb1onZ8dHu8=3SWDE`enG6O znX0`DOIWZ+FZkHh*VBX>-GHCsi)fo1cg6X}Hg!CW}YM_kwQJWdka* zNEn?e2AF1FX$1Tza%Lo;ATgfT%LT#2 z^|n#-I6W^QzZnSwf;o1rgTljg4FGqA7I|e-AotnR-AP^B)4_r4s!UXR8GS(Hqb7_% zqQ?29v{>DRJy?qC0FFKTr+_&q&3OS=2^ccemJPYCT4fapeBT($ z#{83bp!NPq2lche$(Y(NBS|kB(n4wfIP*#3l|BEM_T;5fGUv!c5u4Kx*X#rqiV5LUVJipr>i|F81@RCMYCia9nq_J(Q5Lt7jOWC_FNeR9i7QTLVnJ4V_zgT^qBy8Jy3!ytU__ z4>R09P6iS~+D=aF5opHo)6Fq7;QVaTKR6v@d4YPhcn^~zH99)RL3jWJ65Pv zcL#?l8J}nD^nzTUl6;enhrZL*cN3m5STMH!bi$pcQNb?VXq>g(0;6N{!;XR8KL(7i z&TVObzbvDNU0h;MQTP)1sprYbP1zLQb)|+$YGT2@6{nsjbIk7LW}2&(bOY<*&dcO$ zKK|Y(8>uexN{=qjHz_vy5 zp($1J5nE}A{b#0W-ZT9>sa;4d7%0Mof-uLMH5;9aRP`#%iPzX4%p0&j$L1#JdKEHd zK0L>QV)PWc3eh<<9K~6rwtJ{Q;Y13+hcEoU;G|V>{>s<75Zi-!1FtSZ2}W77BH1j9 zFTCW>2MX^OzYCHJkzui=Vj~HX9ZxVK4N%s@+-`2O^Zq;KlT2k9za1sz`hb0C31mTB~S1@7}Dvb1xjD$>}3YmP)Z?`Hsj~|&( zjyE>s0AZ4hg$-|T4SB>}HSN89MV;Mk{Uf8vgRNszQ=JGz&-7w@r#y6cX``+Z3WZ$X z+^@|;4IP}6PVBw^oIP=Rmi6)cM`|b1#P4JN4IEGyh61zf-k9+MfeDa$b0>1RKyun6 z*Z4}N3?L%_e@CE zXBwBI#9KnX#B+ctzfCNQD4i_kG7}^2itFJ+u&Ak z(hxB2$yD-WDNee4Ff#zqu|&9iZfAv*%`p4`zK{Y%Dv>Zv;OSj6h zMJ(R^NE38S@=ZgbyjgDQTUp!DHf?#c>i3Y7yF{}Hn^w|41*Foy-SjVhk+-o3`Msi# z2L3N+smwg++x?83G&Vkw$TR&D;qr!-IN`-F@>UI&3dE28on6T{`k z`{d?oxvJ3;IzXzcWs6FNaeOK_s<#|Z;<$i4f(+St+SH`T>nRcJ|-^3 zmOG^DSU9cu*mfZ%Nc&69Y(Vh!cR`<`N#wGQn}*rj(n+o%KZLe!*aWijc*@=NihybU zj`aDJP;(+Yo)P>@CGTWP3Ld~y304d|6Qo;d7#tXh>Y?CAb_9yb6F-Dv()L2X* zmdZ{Ql52c8ifMP_mXkY=7wLSj?AWZe1L;Q{wro&uWk2o0^9)tSQoe=nOug2uj|7QE z94fa(U%YzN`{~0N<9~JpHhcyA?g%HBOap84mY&X~P0t3c$9jayyz>9Zy{{3I(A>`W z{vAF^=I?P%Op4`?W#IH(!^$pv1ym#?M%ef6*3cx6rOcju6&-hOdHYqoIs6^oSomLB z&;O??;17q(e^mka{}%I;n5qJ_<^#A5JLPS-%M9=nr;_39^y!zx!rWNL-UFDt0Duc> zgYUCGDm?%Qr(=m+WB{qy4KjMOb{vj?;3~?jLK55VMf{XV0H>EZ3`Q_mTJJRiyu1j7 zkW`ooNdgFzA(#!ffWxVR5gq85=``+{3%)clS=J{IomNAb8j$|RJAYT@%|LZ ziFPdY0ox6~L^$5vTUdu&rhpw$T&t+}+M?!WWeg0>z<7f)Bqy!NTx)#B(&PgqPBMT# z-AI}~|4Q{btCl*QJ0c`*bvr9n)HT4gth&RNMxFX6dW-psOMNd9H*n%#P1X<}G|;-+ zf-e?pyas!g>4d(nP6PI$r8PeGp+5l*f1WVl#7F>oZPyRp^;47LbR*sR7*-7B{Q4pY z;V?ZTY@|LGL=tO^q1$81i3pG>dgrzdlI^8N5s?>+Wpsv+@^H2!u&lE|!bM-kMPQ?e z{89yl*R-{my}Y1&&NRGO%)nGJoKD+=W*X;Hs7`C?$GN>vUaZC_Vk0U9^sao=9y zt3NMCQUGQ=0k{4|2`Z?h7P1;l793ljQo1gfnS>-1QYq##JQW{(5B@uQBEyEteTcyq zWcw>%N0cB8i^T`*$9|TWwI#|X#IJ6 zE>IzJtFY*p=*#X=u}R6Eo=6?}kOm8u?k5uf?HK3s<(@}%7ud_+ z3;Jh40j~t2=xTB8Nt)Ny+wW3Vk4wi23N8;d%0E>|6D`Ej!XG_o1VgRGaZh3{NhK(8 z%oE%bFlYA^DAo1QRJTYA)unubR5TmCRTWIKtre_60<^K5tAo_MJep~6+%q^#`a)bn z=keZGn>Jw%8RPf9rYq*_$fLk8Mg3UXCw#NH2+pU&SK_^*Sl+EL|-&k8mQ<^J3Z0=iotQB$CxFq5FurV!5l&fIN zk?4Bq-YMd^rcTu2pq5a0(K;Ksn2fD6{1a~P0O;^dscCH4hl!XIv1%cNB1Uf=W6w&8+Q^J>W{nLXBrunj%2vzW)aMpTm+snZQbM-s z7(@@uN0L^W(0Lmehc1ETJBFQ++N=^JkrxQ5DXlho@p3&?3i6zc9@6MO|5J# zw^8Q}y*(I(6UrK-?7#ceg(8NYtuKE5(X_L$eMaky^cQ#qCMz4LvrOp-D6G0gLRe{# z3IS7hpeNhe*mngGc@FqOh`*qw7d z#sN6sFkjSXlkLFhG{tX?+T*-McTxyS<2q^74m5mtTaUnQfFeyh|5v~Vu62oG&XjX? z+}nDRZ51zDZHJ5FEtT4qP95=nrILXX-!P?noWeJG_?ffG&E8Q_5P+o99+tf`w^bh* zKK15FK^~hKhzqAHLmsWHO*f#Zu3-YM7|c~9y}B7f8^80W^<@w$e7M|v!#k*#rmRKp zIlR~BjS`8SgM_g3XX55iI~KktE>&-crx60lW!k1`5D2LZFB^7XT6Vu99l6 zDT(UCsu@ta-Axn(kV6A5nEJlQPLkdRH7*?~!2j~INDBrd!q=h)gCJXMUPIn|-M6Uh zdI%`FsA|t5xeI~nu}bl^$y6WQ=+BeJKoRy4m`d}THUJqRaz)xon#))$q@Vnoj10}C z2r#nSF+#5P^MK5YO5UG?7?74-$hbVx=9|TnB}Xg{*S`etmDyL8z6nf#TUs|zy1Ci* zkPlk)^&0!NU|5*R){eV@0ZV`Z%5v=&gP+^DY)G_hF7;m0D~N>9h~>YBj%tyVf(edP zZGCBFM1b9wjJR~{Y3?TgA)K(OZEGV^OZq6eXS2*b?l0X_1xfU?Qyt~xrX6v!TFGHC z^VXfq4hx1AVFQXX4^yPbnUe>-R+Vk^L`-~UcfD4hB_XTVtF9h_>6sTFxNN=Zymkf| zjJoqD4&MgQ;@4om{Q|tDJ%P0&+KU5qD?0*=m#iU;4sTs@pKZE_B8uWOtyEUYf-nYu z-&OE9952YojQKZX(j_o>Uwl6Dk6~HZaEU2#^H*m`S9$ly9el^lUZ)e%S$e@|MRtTIB216d7G<<*% z5{{mA%+!7(te9=^?nJSC%C*rivjo%EC7J9|i3F93dJy@cv)Q~ZUx>PfPTAxXMzP6f z-j_enmX3?;%Bhk=<*}L2K3lM#!bYJ|#o(n#EwgLmk}|JPZ8;utFhn4dMExd%(ry>3 zEsMzEMj2;HEHMNS1Utu*Tla6IbsIWbX-Wt8H0kj7OL~z%+c_QE$e6>?I9b&?( z&*+bKQ+%p+Gg(W3{!RP*<5D951gSs->tnl(&UARdjF>CW6wbPM=HQ*Pg%_bN_p`VS zeWv}|+~w__VdvA$m9}Y2n@1d)x-;6le!kt1A9I0~y(AZ77bOkNK=rk3h25}8bHoYB1;tap|;H%G1VjYOWL z%T8&sI&{|k=u1no65%^|(3>oDuO*3gxWC=+U}8(baeOW+{v>IsM1|rZIF`hF{RiNg zwi#2}{{mGkgaQh8NVBSxlW7MFO#qs$3Ld*k_5AyH0l5?z&f>_Do|abNtnW zkJl3)RGY!ccky+=&U0|5>{)#{ot6;mg1=SsoWHtox_t{i$4Mvu<&()Q!*4y=?k*wQ zBiF@7eJJg%S3O*Q+-q~O*;}Y0ds&b4aB*3k$Uhc315})URzhfc9vfIZww?_dwY8!9 ze(@L;%Z?$18%vm8DWl;&^V~G-dx^tiAPH)bH2! zJHreUFbqhyLpK6~AOaGKqyj2ZA|>733^{ancb9ZacL~yx(j}lEVDQW*?(glhk9+TZ zJp0&x!TXo%TI+hB>s;px2bY;^HEVd$EGVUBr~|KpVS@Fb95^kI#$7+p$#tu4WILC; zaq<|4w;mZ@R>6I1;~fB$b?n|1lq`@PhI^LDXj8;IafN>YLVbI zahUIaYtX9{?gRw3_M$**!l2*>At9Ksz(}$1sL+_`goKEgxM*5L7C}JbKbb1Ua0sj- z$FAhBD671(3YdRtJvPb;lbO}>zPGOpR6 z>3f5}67c~Ti9U;A=x)R-pEoJyi^a13%25irL+SsDMKh>%Yd?3?ybQUEaEnV-%oNY4 zKu}w=t6IrMsW}XG7ET!$k6PJYJEr@FN|s$;%fCE$=k=k*y&%Dn`(2H(SB~@Bh~mtZnr0Mw43|8eBu1yL(str>+94;)77l1`i|G;jI#^rY@5qU zw2s!B$-WMW^uO+Z-4-L4N&4y9b7KLVN0uU+Hi=WAFLM(QiJoRw+bx_< zaNXqmaPsKB!6nbWc>_8wce{HUjkIodZr zt2-JWn6o0;g`1Ca-6>1ONA$Q@8u-9D>5Xl|C zm@+a(lgKc&D{i3feA}szc|c+SQRTpM6f5;JqQ^!~L@+qO4`fEfNQlTM)(j^mlrSI} zvem7Xc><)$H-Lwcd?7N$M%nyxVO%}@I@fLyyZtTE+7RNuCiV%!I&S<;LkYvJ#r}I} z6D#CpnV9|8(56(M9)T__!(NyoDO@;v6{a4W{npq_UtsmVf1v!KL40)|Hby=*7p6J} z{4l>TJ=3s}^byY#f& zOUtU1*JF%^Yp4}}w{!PWp~4B~h!Xpq>z3gcU+z>(|N6Z=%u}_di6*3Bve4i!W2dAK zuso!EITYu`Rpma1-ijGbea?c6NVe6QDwfSNeoSdIKa&&hrU9UKE`q>pd3Y>no>LbS z=0lD$wC*Vn_ufve%%F|i--c_yM<8BPZ~C?6)H+${Nqw4|xwGD2q3`PI+y5+U_0+RH zYil8`(d9i%;%tA3)!)S@CCL3dSg;y!g9GP2S#|&VAqj=PIKt>zY=79n*wytV(OS1e zbbWGr|9FeqiTLa-gB`xaJnk!+An3>7_5|0Jdn@luwSBgRVA^O9x$9aOfnTv+6fviZ zfj;s~WD_IxRIXEie+9bin!M1YMg55(Ws`AOZztbVQdj;%^n+4ZPJD4-&fA!ERgPzI zrs~kG*SAgC7h-3_d5(Yuz!kN2@IYz7Z+omG%sr&#M>jPlK^y< z)*-bl&@zzWgIh)_Ifq1=d;r3)!1$kNma0)=ecU<-@vS4`Ni~B`EMW z0MHFRs<-F#gyyvOq_Wlj#c{XdQri~+6{$g-4ZpM2voi|;QpPguE*<+_)ZI3S+&u>% zQIZ(md#W#=?zZIVO!2;FYW1ucByK8mFk#N~s2Mk7t`=w#TK#D~NvA0GEn2dX*>QkI z&j1KAjq|f!WJiZLfK47oUjRd@>2#*O1R1_B32s_`Uog7^c)XauwmcxBW5QAVZX`C<`?DBWMo+GeDoRcb zC&-qMe3JZKa=BJn^&|Zcy9!0VWv*f))~yj=;zzArMs=!)4l7&rp&;L`Io}>= zvXQLk&<_b6d_af~J3Vu5hr=K^II0wpZ%{5%7gUxqPuHad2-3vcdXBgL zz2QbTv{cfYc64(0BJpTN7_b1-2=JNh$AHtVm|#|`?nClYT2zL?)C^bw#E=w=8^WlW z?T?9qcI$A~>tktT_wN^Jg@%L>He_kpsDHZFKlrEV`th1vRdo2x$`l1Kv*Oyu zN4+0~H^(K?Og^vWHabANmo8k-R%q5Dyp|-}eZCvqqi7odAE37f!ge|ydid-oj}^@g z$fkI*uIWsqTmZ~dm-`oym2?1Y|C(F7WX?Okiqe7_fdjgMZTun`K5dWBbId)vin;@s zL_q+Sb2{5BddmG*x)DE@UDvc}{gUainNFs3w^`MSwfu%o09w%>>5?SvK}W^vJXm|( z=O~fb;DUH#H&Y{5upob2u+sj;THLTyAFXQ|L$i#dPS9HhWlOEuJX_J(EA31+zpKwc zJ9Dzn;g1`N)6yQS5f!T`@~vfn@jE9a^ZC=iOM)V`@}&wAH)^|ZsQ%PNIk0Ej`rotN z?jPOu&nn_B3$tu`Kyjtz2)W|A$W#}z)Y`G<1ZzOxiLc(KV@JOI6-qEOd?QA_qB32@ zY<&30x|%@Nm+w5a6&$3c#-6o0YFcn&YO{WsPpeAV`W4M%W}zkLi{aE$m30Y@yd4@C z6-O5eHHwH&C61!QPF}Hm!3zFG9Uj4i?N2mis3P_*mG- z`Go|c3cBxlKoLcB$Io<_?vW|W@`E77*i-+(?v#2AsaJHWs-c1Gt&cZ4&Dt052D06@ z6;fa9sun;o%&+kbLR7cO464l+N%e1~j%T2x6-+0IcX3fm2theBK`>D&f10!(XFcOg zX-IHHZ>pT`K$Z^wS{bTKO10!h_x?OJd9S>-Nrc2$O*IduxpRMU2K{}tvz-PFD{p10Q0%WK%WvrSoD$~vt4 zykb9EBz)AkvT*#xgwBS71|l}w4XO?A!2veSx*Rp85Uy5MJh(sCaUb*LrK4w~@-eh+ zgp~UJD;$EwxVC#l+HJ%8drMD!j#J!izO!&t-HOzfHYWx$P^@Y?ftgu}yji5!(u~hP zJfZNry=+4FstZ1Un+Q4kyJSp97{Z`_)T*!;&CKZWL6mTucmbF$1NU@v6@- zpb4wh44=EcMt28hiNyf*zj_+$fGGYvZA{qHX8VuUb~41F+VUhbEqXfxY&_xY#*!RN zYi7@VF~sq+IREkc1La>3%%m+G$JJTdZezD{lY}xw*wU%yyC|?{g}e+8bOmEp5W}uz`7qZ@Vv%c5b1U@=PTc zMCNqtSbVFOIzi@2N|2}@?VElbOMI9T&8k!aGU@15P~pN#=vvprc!`5m){m;-8h-+?PR%uKIzd&LK`sYazRS!pU~&GRM5D%q-#q7q%}A_csS1N zc=kKVH&GmE8VRP{s20wk5$zF0h~G&-DU<~vOZ zA)65p*OIpw_%Y?jOwx-X7|bY@!#De}C>cwrW&eC;EIJov=JqTSS`^Hjn=lI0RNH5? zzrDRz>^%5d<1sLhnzM`g6_)Pd+FtEyh6z&A+A4ZJUdoi3Te?7htI&9GuXrZ#RKK*; zct5F9sYAXz%+A2bAiGLHRPo3~7;?p3H{`WV8kLD;Dgu9gDhX&No|pG+A&loz0Eoxq z8?@SwLpWjT?-UhN0N+}9+aS?gJDtMiYj-$De*(}M;&lfnFFCcAMtezLS)TS$nv|dR z(Q7D}vf%ny!cCcyXypeZvndY1&(8T_v}i#0lhHdp+;Vint)m!*hkxErdH~sf-_PcK zgF(I@Pu<83QF_Umir)i~A-r<_r3GXY!OtIBwF?H%F*TNm;bG|fC)tVU1K4w_G^@Q9R%AZR)SKOxsAGa3#JAV4^|xPpPTbtM1A8t8c63I|uY64cbycK#K+ zI@*nVikLv(D?$#7m20=9!Kb6=gclm6&p7p}NWlUx~x(yN6A}LggQA}wNE8&!SmZ2u^tR%^f zKU+?np_L79FjA{|E1dZ&RegQ2*otC`Nzw|q)C6w#B{A9IUGdbWqooYL_|n<@5s!v- zcRFXI4^6WZfUmitotJPP(!MMFwV~p+jPpf$g!ynny!^8^HJc&RnK9na{$nck9~SCf z{dgXF|GUXjo81pyaqdFg;&zPT^H=BQ=3B!M%cE<`Yq7PN3WuKGT0fMJC)&SD10=1o5fSg->{}?^)B^mj~_FbxEt`oX_BH_H&t;M2*#Sf#_RY} zP#t~bl>Y=s$(Xd}-_VAMeOdfrU>zI`q+AKExi7-VOJH2b_>iZ=bp#-Oq>c*hG%L;x z$B>@nI51YSBXAOb+I{v1_8Kt-ZUCcm!vta}4dWZc5H?E>GR6*u@vNPwGa-IKIV9#<*px6WKdp5jwGN(XJWZ2Uk%H!+DA(hP z63#U*13goUA}@7=gi7U$B#V+s&HD#=E{tXA{xwe09$PuNKQ(s%pwW`4qH!b}Pr@@C z=HsT#M2q9*-9j#2(tE7g$E_#*TzA^kk1jfi@!R-Em5c^&;j)+oOa;CNQxe6IL%-9= zcB@sl*meR(V!C}%yLz~U2+3Q4^bpgZy*T8GzNdXYuAiO^8k=^#8zRX5*^AsIYr5rK1o9U^>J_#d7Lim<1e)qz8#Y7~Jv%2(8$n`i}tJis)5OfOhxG^ieVe*_8J;ADm_aiB9 zNDS7$-`eb@i${(wnNBfCfFc8>1k07HdTR!1%Bl154vgdhOh{)_3Bm&*inI%H^8p|q8}*VnYUs|$@&g(XD~Y<%en2=ns&fsh%iCu$K^&{ zOo||7mNSv)APUCVec5T3>I=}rz?e}+zIWB2BudWna(RMsCqn&R8==N(-{-c3X+R2XXbB?T43fk~ zyZ_GhZM>~FKU+BXHH-;#n|pCRhW=-;ezXiVH7$v1+tsH2FSqzD`&?Or|1d!I_sgnl zLW3YGFow;FrtQ*$%C^5Vtsp2d>0437+0i8I!wXCc?mNloSFiG4=dK6C$ zQe&W8dd{21svhB}T|oy6Ho`Qo-a|(R0V2kjT&Bj6nr79I!-#SQe0@bQa^iGn2s zriA##2Bv3VV4e~2!QrKu%-K=#$yMPwx$v5Vw8s31ik8&S0Aes91$bc4VQ@fW1WbTG zt}-^&ia9#YKG{D!Jvf1Oef2xP`g!Rqci4*g zLN4JB`f-bT^H>guRKbypA1wM$F8t>JLpiM7ELrYD-e0-!*5E55MNlm8#a}!#79bc& z$sG)=Eu6>_bior?%kK2gl#JutYT8osGm%SD$hbZ=9yeu@S6k*xVCgLw`hERFb-uS|47z*)zY zXFfI_uDz0$a=eI}{-9NywFn+FnfpN$B>=O-`B>7&n)n3pZEfC6{valt%EcOo!ENB1 zIJK+ddT$u?%_r>tP3tQfTJ({QSp*@HmbU%1m-)2zGplFEPhYx_Y;HDMZ)ZyEU7sE$ zblA{mmD>f6V&;+vf0pWA{1_92-RRvFk$jD26W>B3gU9SrykXaZw*ziXZO(vpUuwhw z#c9812MH1YI!&N{O{#zv@lG^^B{lhj=suAF0Eed~SkT~v>gFLgD(m0e&t>13^!zh8Kt(^$k< zmVLz}G111GbS&1K^=dP~X)%y3!--gP*2mytXaJ`?hiW@ANL^?UgxoG+%ZgC1D@wOk z=k!fMiLK@2OZV?_JQ7ta=1ADCxTMauAx;@%h@KkUPXpRUGZjl0rj``?84Pchc&Xr( z=M8KLmxCD-$#5%qFQ{X0oJU(=on^)b8vE~vd+*DED1YN|V|>W9_U?Ab9vG0V3y50Z z9(Wyg#8*(!R9un@nUu`EZNy=nce`5sMQZJ=+qCtHIv%AOvX}7>4!S`v(x1V^I zGw|$O*NDl?6MDMf=%$+ z)dzhK?H%an6@U)*40l6dVq(3bAto?wzksp@g>df|P;gp$Vbx#j8({a>gaj3} zSfFeT7}+HOZRx<`2%6v{(6YXv$q$9~?u4-Nw5i3Vtdb}5m7g{iS6;4t-u(5dT$mPLap#`2BPZql`zPq&)jQ8r3=( zSO(YCtzdni(V#m)G^$gjb92Z=I`#gg$VtH<<)Qgvd6DYQxQjT|Z?L=Z`lJ`p{U)&% zf@D4m#T13F1L1`#B^$EVgKlIN(~1=B#<(;u58q`Q5A@-uscTJnN-QxduA#a>XhQP% z1jRCdG&agj7G!G@iuJ$f;}$<=u{AIP0Ql(FFZpYRZ05DL>ovIOdefe;$c2FYfs;9p zZ?U7M&CLy68_d0bnRgoWB$y4PTykc(u_c+@Lbkhd$9AUMTO3y!GEL+jQyOt}NdXx2 ziGLbQ{`(4GbAemJ>f+h5fXWDh3@3vl$Dun(vtvULkX?tdjL(S^^47biWcw#%y57{OUAW$GiZULh?Q71^3TCVhKYH)rP`-9jmdmQH zDSWcX>&B?;sNs|I!BOK{5SMk+Od;lp?&}k~0hrgC0j9;{lU?QQv&;iI-7n)K*0;Ye zs(fiVUpyUn{|%|8ch=(-wI=-jS~)Ap-GE27(2{f%B0LZq zq(`)gAEfU;@&2;|6xYSx9TpI1;lcLtVK8JcI69dCX0J$SgDjR~ zDMosfmCHdP)$pncSVILITHex7TH7w&-r0`A?XBk9p&#p~>Zcc$W?Sc` zXIAIt*4O7(KJV>r?=Np}9l=S!gb*;|5{&DAi2y^Kudg0VuIWk`L4E<1M2H?g^va;; zB^_Lo%*4Prv`FO!GJDa#ZXU(NN@jO~aM)FKe<|n(Yal z`+46GErKt^FWE^^RxRghI@B*}ot3qv>qRjpbIuW|QYNFVE@2(zLQSXZEfN0Y5lu~J zixCG@a=*py!mv&pl`7tpFQ#jsq`vsHd5Q3BcKntzzGl)4A${>zupRsCcJ-FC8^W$)XC zxROHe#u)WNbjc)T=;&&a=KyT4HzxuFx*vbW(GhGih}0WnTaS{I?PJ26lUgdYpiZT_2RFd^giCf4#L;akJ-ug_r;rKG9GS3F@nS4VyEtOFCndB~y~S9A$$jtu zq@(+_?53s-qOz6~!dv!2)n0mpD{uCq)S^_+JkY9ec^rhX$u{@kdeB??fGgn#V#B#288dk)?ZHnHf=+!qn1gVQy$QczI!cSDo46QOgdD} zM+;l4=(*Sj6L9o)eZAFb4}}0pt?L8G?^_ll%l1oEW8VY@-X(r6pt<|zS*g-4!4EMS z2S-8eu-cKkBuO*>w&qt>=QA2_Dja5YT#nA?^h|_wTlJHyE*3OzS3hboZ9H;bDjc8w zwB$IqTu=X1#OnKs=My@04)ZU$KpbHhzpIcJ@+pYK$xNjwj2eaYrYo`kzFa?3qSxjt ziJTK?-b}p9e?{=h95tr){WtjI(}y2k5Gj@~ZC)#ioqd}=;F$S6t;D^TsmAeV5kUf& zu&uL6fuf;%@Atoqx%+%rYm@?^9xRW;gt!OjsxtF>Ime6bG zZ)vP$3)9tfw|7*HvT}IqKNZm~1j>NuN;Z;O1w?2h)J>K^Xa1msfGuc|Py+urlu+ z3B!&krRYzY@xN1oWsbnMA1(A4qJzM2Bv`t-f4mz6Ba;Yks@C@nLGtq&1)mt8f~jsO z7(bcXG5N)iJt%YxCW^mhgXo|_b!Kljf&{IoJ2j`beIfS^$!&?^0j-(*K8!4Ub-Ux) zLbp73hvM1QAkf0apHI#?Kp2n&21%n%;+p*}r8 zP`aP=5yiGE6&0)^C@-pEET1a$5%E2MA1^Y6`Hg_Yo<_V{zlb_ed0eAFxBa~7ZMf0a z_l=}Ms=%~3qmIDmiDnm%-=^tQ!c5W$h=MoMtr$$#lU*ft2-y)Q3q=`>EB8&c+%wsC z(?Rn?+d0?eO-pTKRRNFk4e%rbLyz5y%d77VTQ1j@kuRAAQd=%^7WxqUD5>!e z#S5*&h+5>j%&A{82d{?_G~eygk!&1k;%96OEE?BxuEy}wKS;n@h^ z0Qc8X!8uEZu@5WdU&qD1A3BU=e;nGMctm0KZOliRZ{dTI@R;LNjtKUBFYyrdP2;U9 z_I=O)S+Gk996<15-srnb!@Nme#s$<2G7KE(G+@akHP3Hm=P1?CAc(~b{K;rE9o>h$zfo8F;>fqIlhXkpg<&Y4kPDV%U!t=wV$0e04C zsGl1$C=?$?5bBGuic5eYG2kc+K~DS|{9IcYA{QSCFDQju7Q&z z5QuN5=*#PG-!H%Z_v)3p#e!I_u?hWDcEJBb(%b(G z<@qnt+n)*je~{k(pD|AVf%3e0NdmZoj{{Wu6XWFJ?B`nlH^%Av{!+0Q7UQHNe6oSX zI1vJ9`$Kmo^Zvy+F;Ej}JRdglwV;21<6#>??DCwVKjc+?P|_3ghI?WbCwlW9)@RFE zdWrA%(439|_ z&2P&GH^eGC2rz4oN-!@x$p75k)Uqhj#(C*bAT6-k(bJfg+=Op|AW5Q6t1y51J~J`Y zQ{<7SH`-Ik$Cu6@H_#_C3LYF08{_E{9~}%!@k?Pl!e9R(Iq~}%Cf?s z`qG*L|K`HDMy!Xg`cZA0g0qU+3szbhqp@B10eBUw2zdOlalY!vVg1Yb?AIC@M0+)Vga0JZ&3aO7siIi$-y(4#2>QU6`1P>kZde8Z zExVOMy}2rvW}(*duoJTqo@Q$(*^hdu`FEyeiQ;JuJRj=sE)SCpJ4j76yV|juR+C_6 z+tAP4?ewy3KXnGHs+V-$duIs8uSSdiyyTx4^5FvU(g@XVHv=;Xl-90lwUgsyWA0^K z29}JMlNf4FiQLoWNwxyf6QPW)maW`=@TyRYyjmCcp&r1G8(!XWfJ-LeiHlkd&kW#A zWYAdwn)+Jr{5qy-b**G<&ib;L*8TNd9SU3B14y}EN_kNHj(Bf&_2bvpw>LNFmoY{3 zzMrvfct7QH$hbLzmqiEq<*^(Euvt(tJ@640tmp)=Po8o%PGQ?nrboIOc=MZ4ZiKSd z4^RZ~<+2+F3eA38a=f#BiMIWbvYV&Cd?sw9utul(JXT@$MVFs)!#BMs1y;0SJe$xf zbeKlvCJH3$e3cij@2r_0Z6E3s3cc*zO~X8$%>(nTC4`1Da@F)ZgRmG( z$!7_&dnM_$iFl=XLf#_Om3-YV@Jh_4LI9Q($KTkhxMr!#Ln}DBj2kt*$t*1OJ0&cV z;QqwJhlNX_=DS6!Q|=ake`gnE$1R5q2gj|4#DXks-)1eov|q;l@Jo2Ob@1gqU>ZLT zTn4c`>4FjdlvIZaA6B>H-TiseOIlQRQte|@^PDZzF&+M%>RF9le}mDdAyAMhtpJKX zEA(vmL7>jrz@50Z=fmDgdUK#W=5LZlU^3=ONysguqzOri$VQT=uHh@+it-dX%mJrC6>IRK#!=ruxu`ri>YX zA!n!x3l{h*F5|Cwgi`{-{}JN(e-B?7{r?PKSrkM|0ABo05YPX&(%uC@f;Ijm^t~O1 z!vt+@v5z?{q3`baPn7RpyfqJ2D=jRcuj=jqTDkR}=@bICJG-p+-CC%_4LT?GbMj=R zE9S?&%%85O>%D1&6IOrnJrP*Wloi1K?_d6$M0Y8FEzQ$O)h(r<1n4bn3+)=TYSN8jMm0Z)wR_%07mZ->y}K z@VzsgrwI$lvo=8yAzbj0jxMfni05k<)YsV`9vKxJjYXvR zI)q|8GJRsB%iKaLlcEB$YZJn&i_>z$8eBRN`Gp;&L2eaZRek|A!J%0bseZj}$+JC> z*6y6;%>K+l+Q7NdF!aoay0Px)=J}J3ps(5K>v;v6sgh`XoLs41NtEwHFj#;OoA5#n zhTuWO<{vTi1mH1<3aas=K+=>qxQv~KCz7NXd|B&{B(Z=&TuJHV!AHZJKxuc&DQ>;5 zolnz5=yvl_bw%*(N4Kc-lCyn5P(?P{Q#7CmSWGV_7U(|Htp>tPJ`=N*+M8k|sz@I7 z(^J$ER_>)V)rK&};3}R_yGlyJVmrLPeiILDlqAC;l<)>4nr^-6Ob-_9RKWlulK-K! zIw%1M^^75s?%-_zp`3%{DA3V-toSP!7TsyTHIn&P@76~jKtX8m%`egIlZo!z*-xJ? zo*e=j%GS1(|3WZk+#joaJt%PTWv%DHTlYbv%jxbkhAk@DlK%YU^OuVgTK)+GEMH?H zU9a^P!_E;~_KoMS59F`WAl6`dk7ebeHUBx^?Kl2J>X#Wl0PL$dC{x}vn_gLDa6Pzs zhN9bpxv*)$!5F}v8_I#hw{FEZ3+oM^TF_wf7u-)a@V$MpYZxkGF0vW)JFs&o=FxcK z6Odfn;HLj$h5K7*0Z7W{1UYjv<|NQr6H784j%H?kXR5}&T=FZ44Yhx1Wy@QsTdrnrh z6I&nlS`JIY?m%~rwKuYV|EAe*-Kn!Ti=I9o#fiZTi*I?Lt_|FyX8bA};<$a_y zqlbNmeG9?;-9e+YUFay^)>Qh42y>-h3>^xg4StI@Bluhz-~ zFTUAqrMu8K(nfgjw(Q0_Oe&|V@NRX3-Uz95f=ccPrGVbWRZAXJt**G|m6uuj9xq!0 z+V2&fyi8#G#XJRH`?(JgGJ8?r_{RIq z4(9!DN@c{wpHUfvfQSESGVKA(3YUZaB}Xd`Z?#{E)3Wz zW`hWEk1rzEHxI#zH*CnLxv3I1!A?xsrsGeDab8pk4tvsDui7j@eG=#fwBf_b|6c2I zli%SGA7>cU-OdYR=j#*@?JG=gy(>#BV5n~MpHi}LYdjqghEA%Rq`u$X6)9MH*enaL^KkCdO5NnNL0QCn0h z(%XbnbY7Gsds|2fB>uzyofI9thQ1A8W=;p3WP>q;IFj7|7gF@r|51~9MJz`x0GR%7 z#_+=oga02euy5PI#NhdVNYPlRr*cc3*%VyPOyVC5?ESLHzc8?~C65a@W$~W!fEv;7 z&)P$MPhJkF-g?rC&Ppr#c;=`q94z=(klYPsvKlBx;`zuV{Z+;v~!KQ@%` zd_|0*l9CCee4>RwfT0j@Ts$sravT@}&B%lj^!+wP^uT&KR7x*)Q>wk(hKXK)1U3LoSTO)ewbUB8kqUm8v{KY#yy0h z$WD$=py!8Y$Z!2Weh!>``}GxiCtaLK;ZR8CR`r{nfD^`{YZeOX zzFIM#e2Qb4aq1fib>fHxKv(>&bXYJ8O21qq$GA^dL3@@P8<#X4>cuw;WN9&;la^PM zuUzf0-_zX}=(0$W`v(Ag8Us*4fh2V#YkUQw6CU|la!VQ0X0ko&r_FZst7w3U=#HhH zqnSXm&%F7v??rNF-+dp{PJ^+Y6fvLRRsQ*rm54+8F95Kc!v+u*52xsD#sYv-WS}MT zPT20#B@=ZF^!%hdrhu<#LlIK=$&>O#m>F&XZ zic!v!RBL(^Lfq^*&Nnl{>w)Ea6xm*s&P|$uKit?iFnyXL8zF};d)GrKYM{!L+>uRm z4~P18862B!4L(PpteXrm)V!#*D4q-U&Co{|1G*|X%=Z~Q(z2!f;)rWp^qgMs&S!^e za#C(azveV!PS)S}&Jz2!(8W0QXTferq~(gq7U*LaWs&F7 zsI0~ul`&6CR90R9l-{nON*%Va$ot)*Ro#70*799g^8#H>&$t%bP3_or=}!J6YZy~p zfPjZ(ebm+Pk>`r{l2x9KaTvFUU})OBtF-kbqHzCOme!>xS^KbIbz`KWW9AIss*Es* z=uSw1{F4KI5J`Did-rvjRnxwxCvWctr?yS^8M#YA1?9u&qI@A_n~_q96ZdI5=}y{N z$BiB5na|I)Ab!Uqa*$11TB60-@UOF!f#t=0g-$Ggb&`b8*xbP^J z&z~0(fIL=)_$O+leTGvec&0%ocPUnB$;tF(Qubbx5NoU0!BW!^*+G z`Ur-uI1v^k5rXNf-2I1pyj%MEzAU{Q0pC{K*G~_=8z3|XjNYbrOy#aC4PFyd)fv3B ze`Doq9XT$RLj-&E37zBZz3Wh?#srU#8Rd!BNN*WY53%e0kUXfIgUY3nO zRu$mGXtV38Q`>4`$ZBv?Cjl(gnHY}5{h;{p11>!_Z3NysGYy%UTU}dPSo!>M0baTc z-<{dtI@-Y9o`K5XVht2W`$yG{>hbpeLrIiqdh``=1}!OrgJd9fg{TJfVu(m21yOdn zY|OYfk4z6;W7aX6#7JAC&NGeoNqmM_r%CM_bdn(KlTM7D$uny4M%*U1X-NP*K_Uvc zIBufMI+0Jrmt9plQ>G4lQDAP;Nm4#WcruAEAJ3XPSo>s`t! zXIv7imKs%sN5`;A^m@c)B`tfu z9(XTT(oe}3I32F_{I-hrbo+X;9ylVKm1%$2f7n%q#jJ?#Jn!I~5vHe0tNZeUZ0`2W z!y{LsY=?q`xma)L@x3?J1fsk2*1eB+7yZe!2C0Ln6?VzlxOnDstU(usYr%CK4RnGx zImsKYN$hO7VHI|ApMyxQoj;r2JEmOpVh|X}j*2}WU=#-sYi_z`k|pQIMwb+4N2?gm z8YZZ2i_j)2dSB89=s=3L-1X077eGY?g<2`b-t(J8&uZLWnY}S)XLB^1a$(bdb!_%3 z%X?#wCD7Meb|HR;OzTz1Q_kz1H&>S~)Hsp6c!pAG^O_|jXlv1hY*BZumqodu-x+dc z63xxEGwkMuh)a#<$Y1WOxEPc_lcO@qZK@P~@mBj{*ep|T16zd#La8$p%;^~pZ>p{N zPgqSSrsQ{Pt8SH*6b;#z@iZ*>QCrqyj#EoZ!zD=ATB27}BLvns3lW9*q%;#&`*fYwA4KUO)dpo{;V(FUR`hJd%3JrkgH)Ha#8gu)-X zH5K3~_Vw{^kb4}b!k5_q`qdZ2-V=jvX&Mo)nsZ8aQ|7r^Ei${yHWdSLu=E&8qzt3K zttoR7?!a{L3*Iz!X-9WY_IAu;XN$K1wNOwacHekdsVBtb`+WQ36~gQ(diCQ(sfp*Z_us ziCfyMo_5t#$~H9B!&?Tc5QJ6sWwQJqXJ+Rf06l<&z?GF{AbbU~;<>e9KfJb{yG{0K zd48sSitgd%)%A}b07CpzW(1{3=aVid2%vWvGmLo{fKPaqb{T_RDa@us<)=k^hheQYUkMhpi9BBLFb9zL;KZ(L@S!!Rb%=y50Wl2N9gFMW@mp z=P2b-vs|HIK&V>nb$M~03`>QcnfC)fvJc(WrmEf+s3G&7I@>5wx>&)=<+Nu9E6ZVo z9921qa2Z^>IUCt2TV;?e zU1I6Wv2yK+h@V0YhXBZNO1+nM)OuxGy*(YBPU-%JW)xGD!g=TV*65DHJb~Aq7POA- z6`N>7&%u!b<^cER`TeW2r+2(1qIAExUI@wa2D=e~X4Uzu7G!+?Sz)AmgXSiX z%T|EU7puGXawNxEq}*p;v(zSWf|O% zAksZI2y;l7nGdI~AbS)jvMq;vwt7Ao<$3@wi3*cNCccW1zqdsnr>r2U#zG^zko24- zxmQ0n@fY-Myc{)EVYK0e25TgLw{bx%6|klt`L~%|XPS|F4?vxP5mNY^)q7zxKhT8K`^zDfBrt$j}YlFZQOX+Kn{O_Ur{&5CH<_EW*-wzK8i{wq4{`d=UivC+LVCq0#5SULtK7J0S|;Hs8CYs2(Nm8Zpo)595Sd*dU8= zoWNjpwocexhC8ZfclmaR?{X7}{TT*C3sC*9-W^@vtfLjj>dz*Fd8C(i5Q`jC+xn0rCUQS|N=k+&vzYooSV^pA>X@VP!0v94&4nr- zW7Kq*)AYwk-LLQ1lE%>g9a!$9NE&;@xHnxuNoqSE7d+QN;BFA!ymrBX@ccQ04e;XW&Q(isX+;hkqDb~OWkD(6c=*;JSwshE;l1i1h z8DMkrL-|sp&WCXsN#WbvSSt$S;}O(+g~qFMJbEPub1iQKMIFm1W#y-8Um8W$AD2b* zL&*c`4XMqw>di{zKOgW<*Y4E@QITs{F|6**y?)-BipwQ%xD@E3t1^N*HTcvh{H6s# z+jxT48`dLnjA}lc9?f|89YM{%v^VnhJ&q^E1IL~VbqZ6fr5~I77BoNa`A7&EU3^^D z<|WLsb-X^u&HLhI;Pt!9o(e^O<91VDL?f{@H1*my{IoC4264~%O#s30097DBON7>& zGEqn$<37YP#=j>A&DFFY>!-u8SqIKO{8}G8hY@IbY#2dr9!wi1a?i;y%C6vI%}G+N zkj@I9e2>u;rzR0?p#X8yGtCoH(Tdmj6bJEXRJ4wEhn1H6`d?LDg7Anl-Nhl74dq;0dnWQmc1V@d=sC zkJdR4{Spjx9yZvgt4DiIIvaP}8r8d{m(JH!4}DPBXz62C-(bv@Xq-y)(4t+f;~#wz{Ei)czzmud z+p%OI;{*E`gt8PDPq&kQJxH2cB#uYw`8##J+!Q4N^t2UNlLO}xz=5IoXV11mxm1vf zLCgwL+tHM>AGUA4jY=seb3MJ`j(PM{iU>a&oZP+p>i=bhJpdTu7W@Czf%ZS9Ovl_u z9S2!vA$ACpX}HSwGj-`|x{vM|>EHInIcs2Jteu?X7)f@9T3IBBQmU>HV*C`^Wx{6S z>^;Ucz$0>R8n~;P9F5V3m_1JlSUOEoU<4M|J48Sn8Xig-NEQIM43wZ1*x3eeHLt5}MN3!m4YSc91I%Af z&&=Y$4y7sDIreFMMSS9A{15QY@K5jel)8X0R}{hG{vTfA{O}7nEPUhY78l#x*9B>p z2?Z#Hk=?<0Eg(9}Q86=CaWBrgG~p>sRwvY9{h& zHoE?3b$FWvq2&*a9Ibj^&^6EDsZ$yX797dsm?vWh>zF?^_DJgOdb#qv5 zdToMX|f+IewlZDqLF-m-GOQKctpS3`;|Pq3l+~N485Pp(hp-E%RDz2mt}z7 zUpuAz46@g8-WPi%F+cD3Yth})>(!BdE9VD1GyH(Ymr>-W>(CglpXeDFH@S9;?(le< z&0#J!Oyq6*;%52s`n0w{nfUi6v$K(^ zWX_#mW8>4}lhs`tD%kAC!noeE~|-cG851`3@clmCP^7emXP zh7bJ*nM?+f4kgb6y0IK&sXymt&#?6RSy?P|(4LWHT&%(z@6#F!1dW1t*|I{eBM$?g zy{tJX&LHIBNk$o&Rj>n-Cmi#9rN5U~^#*PO;0@foQ?$WD)h^j-Pr+QVt-d@QjY95M)-VJOx9-L`MTsgg?Oj6P zF`{)ZJ>`vvvhYOf-WbRQ!}?&c^ItWNY|Y)747!_zK*rdz;iLzdlGun#S0XQACh-~g%9ex%#=s+uUEbOHFj z6Io`qHz#JkRp(U~FJHJ=uYpYrl6gbl{g(k%6r0f#UP;IBB6-O>M*hsBzTR?ILHmFi zXO{_mSvS?&p8dU%4$J38TC$z)eg=*z*FjgUKwT)~-*YM(b~-&(5n^`&4W#GW3t?w8 z#r?ZqKW*~4lfe|^hR#=J`1+^U8h*ujX@)5LelB;>A9T0;k+cvo&0tv3S#oE9wZv|Q z5|+hSh3^(|Y=sZjXRSt%U&GB6`HukLDC%OdC5p?r2mqYvplvOZ!=Gy1mxp(8%T@qx z!i3m+wNf4~>|kF=B15}{PU0~mAn>_T&)F6AZ$a8cKGb_t5rzG5w3X4fg{X|tsNO&)fez&BnRD$Z4Ui+N%A~y!#niy7yUq885ThMeqEzQw>hk&wm z5SyOZHJn>5V;s`)s)6Nfy!7tAG53X@l~0zhf66%=U}Gp+Ayo6|Tl$oLXg`C8(C=rV zbp^EcC_Cvw9;ch06XYo*JXD!~e%stH5!*iZ$0Km(Dw72qzPk_-Z=)T_TjIVDWD+{y+n-u$clag9{&9#D6c&f&deM_kVIEgne-K zs{WZjJ*alhUIaTrnwnJRqK3w8R2Mbpfgbd*aGjOd8Gc&jp)ofZ^)QTqKa0?FQodac zr2pI5niU)y3Xj9H3E~d_e36d)CB(?+G-mz6@B3vgyAyU^)gbE>H znUrId0t6AHi>c=_0n6m`3yU+AWU{%?T45DrRRl`lLIId@ORroTh|q~p3Pc**$BsYN z1_e9KI6>^j7TEI1_+riD7a24+81fA<;~)uysO)h~KuE5uY=jiGE!{uy^Gs14Ai{#Y8_f+?$x zZo#9>GBE|GTt!;aSRr9;#_Y>WUc7*W?)} z2*kh#D{CLL{F4WIw}prA#9%>v%U+o7_?}q9R@SL3qQUix2r%GT)4c(m-*1*C)9SW_ zB2}*C`;04f6B5Cca7d?B`*tZCLvRy~ z!s$&FFNv7q0zkm*>t}IRq$c^=#?}4$&6#9odDfLTgPoRlet1S|Rv}xzKSDzw@jEN- z>teB_o^m6;d6AT}EqN-E!lBmDHgZC10#($IBF;MD*zGXp)~=n1zjZ$D_zrQDf|=ic zS6lRQu2)h@zEKBTd%$HXZPNAyqDvDHye6=??p!2eyl;JuV!)aDmjdx`-+i_d@~Ma6 znbl#^YVj?oYTNWyfr+YorGXj__nwY->xFF-24(g?#1WbJg>+lkQo^m(d~yCnQ?pFw z$xBE+P-3#8#7l!{SJ%&sh%sg6H>M_<(DT@qp(NU5F*O=@`sLSzOVkt)wMw8f;&=2M zG8~^%9+if^iKim)gM|0t# z-&N7hMkoTMOnn2l0$T11Mxc7y6?EjSRNTM z-pSJcgz#02i=AuX!DG}jCIf~WY1w{=AUZ*xUBbICqJ-~@9|q%5hfS>ym)-LZqlggO z8GmT#CGoxeVdi3u`r-FsdS&j9qV%1?9aJ=XE2Joqmah1Y?Qk^Wk?;zVre3Ybx8@Ud zf$=$_FNhgAW8Q9RMXa&Fblq#qxLza4EXib%b7?wd3)4)V5}7_I%PAiMS&HxP)C16Y zmWe-IT^rNX@U;u98cvJdJx($c5NT)mP3zeLD6@-;_iZV6!K*VuuG#SkQ>s?eK(7r$ z%595A5h=UeW~lEEMsWh-2f=XR zx%Jn#zekKwKZAv1248Zd=Mx3{L?6R~jRWyFR>e4+qy6a515t;KQ{Z z;~gC9CzYcX9%bs_n8TVPrNPr1+=5&dJ$xz0Xb+JQq92dikA19>Px2&oHJ28Xs0Qqf zR47{=DxZ*I!H^8&(=R2b?R$Hd1e7Bhm2*OIN~Q1^B7wCnu6LyxIYfH)-&m(HGSKBrNjIA1 z`taJ8=>rj^_$EDkC3^Mrm(=Z6OGD_ftgx^;Px<3rKdSPNeav|>BQRw7)&LU>TkhY~PPZlYFd9_a5EsR2lVhk6=e{Z?ZZOcS<{;8xlVN{R(mT7oKrSTXXT{(g@_~ z_hD%|cEq-pzO{Ff#EOv6cJyQ6d#wKKzm!Q_Rx7(;5rSSAnlOP;6INtI($S9lU>aIJhv>>(4n3vc^7-vM#wHS)Yh{GNu>RIX_BIia3_zi6ZmVAw|Qw4 zg0USTVnB!|Dfkn1-3a?9q1P3O9tLKVYrgM4wv6AbE}Fgh+JJY*z>g7~KQ3t)jbFvK zVbx);x@Di*KW!~iUAtgT<+k7&45fX5p%7q* zUZ()lCq!6h?>gwTDDtyuvLZR*aVj5-x3c|6V@xf`8>I}<2})1)t3?%l9(%D5P8CML MU;PxsL3gtM1DTxNLI3~& literal 0 HcmV?d00001 diff --git a/doc/setposition_method.gif b/doc/setposition_method.gif new file mode 100644 index 0000000000000000000000000000000000000000..21b87ba906b840a694e7c5830b05e07d88da4159 GIT binary patch literal 256424 zcmaHSbyOVRvhLvS?(R0Y1PIRH?(Xh3z(8PNU~qSLch}$!!QCxDNP;CH%FFM(d+xn| zyz_eXTD^C5)mLBju2tQ8t!iZzB{6ZE8Ndvn0}n7dI{JWskd>LazkeWlEy2UXBOo9k zBqSs(EG!}-lEuZ#$H&LZ%L@bo1qB6PUS1epurw9*_2gx>6$N;KNC*G`;IGJ7Lz`Z~ z#^2`eRq{31+s4k#!JppN!O6u_it+QnTSj^pdnraEVGW>$x4eV13n;|bK`%s8-!8<> zPTZdHwKTmXSOV_1^yG# zzZEq!{{N~T9{;WF=dbJVKYah6z<&C{-VS`a4t`z%zIG0O)tUZrtN&W<*V=I z<^J!dsO{|K@8#$0;gO-JpKP|YyUsC3jfje zpJedx{_9!6!Ph0w!CuMN%Y*)3K})#&XD+h;5%0fj?f)|ux&LU(_m>RcKTG?+miphK zzxnge@V^uH@8rKz-@)^5zWe@7Y=oCTzkmJw@%{PR*Dp_x5BGPUKYhIYaC3e2{_^7d z?DXXL=*Dk3Z-D8LWoJnX&d*H6f}EePXSH%&2BjX)@=ggJ%o$Oq3=GQL38&k%T$U3`I$53f+r@ zU6S(Z#``bUnlu(tyo-rZ57BC7r{^)lcdvzgok2blGX7c;D$<6&@jN#A$)c&OnerHx z=IJh>ZXVG%uDuK$q-wdfq6QK={2+xjL)J3 zj$@R^+g1Pc z9yLmPh?Yh*fJ?hlyH0My0YEhr{QYjl_c%Knp?BifwJ$vx#i5h@=9eL?p92&uBo<@1#LqK^w0>%y&Ljm~(})UY~?8AK1HU>C8BXt|t&PGPt{i z!^)&?^y;*2AxA*r9~#$GjRJkT9{F8Y47H}zC27A(++^UUd%;Ciy2LuB&BmBku08C! z#at9aX(!|wG8T=+$;_rO)HBFDHgjb z4iBH$D)D_0j-|uKl3bfdq!+kDM52#DM~|W-@qRifPn5}Kw@(xzHc3e0H9WD66)N36ky9MIw@1*K0z-mxxu0_6cb*oh1qg<9a?rg?;Jw)lD+ILEp!vg2svlxSIMpGQ`F}7%< zS51t)Vq(Rnurj*pyhsb7;6&R5*3qJt9rp1O?CDn=ls-o-nB0k^l~0ZgcS_`J+im1-)jg+L$}_^m%XVCuOdcm z)KmO{(lLKn-_+IP*>6a{e8FJ>aln+c3P5}r_&iCKQu81KJj#AR5a;`Smyi8M@@_** z3-UOk#{cW^HR-#b1EB+MiSdAXf;t*4U$ z%GP^k`Qyx}$FlqWi14Dg#)VHpSAWx!zom}*`-ZD9+VBk&j&Sf0HcL>Lkpst-!4}=G zW%uT?V@88#5u9MldF$rYvg@5Zwg{_a=xtw%T5Ou4tzVf$89x^@6gR=vBJ*&>uevEj z7KMNi*plQkX48GE8}qL%Xf(S>_KS@-Oqu(XD6M0Z+!6=PFEYXLb~F!CdoP%<7LW|GDH;!vzg}S9G@D#VxkI|P}EPf9l)4qW~gAo z(g)U&l-4>R7BrzQm3F_T3pFJI|Uf)S!@KjkXF z#$`=qZeOq^bO8lSDGF@vCo*--PA#jeTdrX!P*iP?CSf?o>Q9{Fb#23l@<*)ge=^Fk zMQg==%n%n_&miYg>SD=XdGXM{HJ*^$mQQ!ku|`F)!z7UqiP2niA-!-S`W&pwF8yRF zeoi6t8$*CD1Rs8J!iY&$Jq8n4fZ3~aC{#=_;EkrJlkO9sq)|5Fp1d>qv8DqE^B;K; z=Q5$sCq>9QfBnn++Dy;Z8c`3~u%bIb-8lbP=OdfMxep)Mi=@PCJV@%a%d2^}qv6Y@ zkrAy7Q%m^42eS`1QlqN@VYp?HHfyocgA#_#w|?tff~5^>F#13ZlYsJmvgL-}e_JzKQkJxC^Ma#QhJzt7DqR4xrOqg{cD(_9>+|jD~nqQE{iqFN( z`xdT|x~-Us@*MC`w7(n_5OJ8wzw84^DK3(?TyIt)q53swJau!Bc#%>^#(4Rm6a|iK z*&IxgYRUC0LNU(e0>X8BWO)jL9WLEs#+9?Y-NFr8XEgo zJ^DDbM}1xT8WAkw#5=4>5h^6II9_?UE{686RmeEhiH*-L`Cn!hQGJ2F9{sKn-qcZi zbS|Zak+0!#x&Bhd|D{$HCtu5Nil{I>k+)iD$0*x!%kRxT_n+^*rluP{so@389u&ci z$mZ5r*@dobY7}#iq3yqxo{r*ejjPbB>(r$J6$wA|i{MK8kbR>nA}PomksS&M>FBU| zyb&DvO?;0QJY-$)hq7iIgCkf))#j_|^Q6G5vxsR>QI6*QmH{?DX)jl23hIFK4;-d9 zJqNY`E~;T?1trJkz9l(mM{zoV5&~*6b|eus#iH1=D1_hJl$x3hPZ@Rem5?{=`bb7!l*2d-q$j;y*FWBQFf<)~kfsEB+hx$n7ZNXQ)K)_~WrQ6$S@@ zvP(0|6D-^>JBbo$pQ(Y~BkY8Gcp^3!sPQ3G1^d%jRV5tUi-QJyc7G&{R}|R9`exKM z$0}NLhFBO!2?40|0EAi^fOqV`9twU?4_U+~?efq)gw}5ecNPHmoQT6C&x%Mk>yMr} zBL^Rvzjdn}e}-E@&KTZ(n?yRk&!P)eU6LlscOGVS>`@seQNi;^6fO9PA4?r18#L1s z255~9+q?c0)UC{f;8!EH|NBo6!g2URxG3Nl>2>JacZc_(M`6cp_P@@irS6tv2XDVv zf`i2>Xs^Aem=I?1LO1*S$@`l_G+Gn7kd8kMro1{uXbGRDD*k9^(`vRvRwJ9wfL89YzZc ze}?3+ML5nxa)IGm%0WWUkz&qFXd}>Zqu8t(SD#!%Z@7!FAwjBv(T$)n+`tH?3{&rY z3HNmZT=s-Au`~KlM+=C>L>M98vjLn05V*k6Q)mH}y)eUP$l_Lz@H1Gj*Er=%97H&N zQqQy!=4iT-NO2rZXbqu74{F^G((Vm?oDTdb8WSxRx+)r^@*Mk1)H`YmyaS41W(T(f zMNi~{GYll`5t7KYHMX2W-Y8&uMW-}O0~TY!j;US# z@KobBIk5>yM!{%kZ_s;_;5FdbobZRBw4<45gsV`B>%eufq~BXnUt`jHm0t8^jXm9R z-QJbLl5?TBammx)z@ca`&`!eJ90*ZFlzR?@sW){^IZp67UE(?Z@;Ru=8R9IKMTVL+ z&&sd&-ThmjXV)==m?CpECmL-g6RS1Bo;|Vs8!U`1vvwwVyBC~lk{a2QOmv(Y;F8Y1 zkt0)^M=&EoRGTgeeN(v;vhEzdPy-1NOKN)$4MR^v07V5%$AdT`2A!BXwzJJMVyi{Vll7?KQOmO79vL$Hg*>#$%oCL6>6>|fk44{JL%M75j$5f7mA3S z;G${eq`n+jB}Uq)3e)rsuU5K#>7)282akTXW966$^>H)-MzX)k3v&2XV8?6{abE7j zxAeqsp-2)?S(6AvFid{7fDfKM=~Q%g<=bBV%8E3}*VZZH)UoWr2~O$~&Wc?R3Lc!z z?=p@JXUh|&NEM!eT{(f1gEOFUa7X9l*WTHKJ4wr;Nr6t_gg~++Ru|ei=aO;^-|n1a zRN-L7sxtiid;0ZNEXH%>#ZIh6Z@iOB5fys&7DZ}=XvQW7EQ+nLATH-w#B=>i z9*{Iktv~CTErAdt8IL2zsSc**6X6$>-;WMO>^ivakGeFcBnMDI_SQ>X{By=1(V&#rg49`PT)w;W zkBDN9XakkVfz}Eyw&0e&n%p^XlS%w{wwznCw2`>*aL%HaI53lG3~CJ+Cm24hsxg1Rq7KqToZ2q4vv@$&k@fiiL1ehh`uH(+uROsy^7R&4uKfG@!AO? zmU)xO7Pso{o0RG6-lp*gDjBgiDPeBaZH?uSfb8aG)N@v48xGKNN*7 z&zb8t)tm8^6BKn6#vPr($=1gC?52%L@3Rt|<8{!3)hQa+UEranx$&W)4di((A(jc8 zSsg!W+jh0cFv@H~^Ae5n+qc6}XUcsz%WTEktW^3;oI8hND=H-h*LJIe`xrdXE&Tml z=2lJFBgC=p^0U6x1+$lSVjyE;6>^IMBxPPQzP~T(LW9Y>vDZ6EhUN`q1yM~XO zUnPjP3ztkDb4&toNC-v=)sYCWM<UZwnje1*ccB5ILf#0PwV}m!inLda zfFsBTdO!ULadUZ#8vmvj15n^U8bCNo{cD8ic3fs;{B_|d5p`?-xCwHCWB&sp!fXX< ze^svw42z>j1-(pHvW?dqW_*=ordm@&p7_xzBP$`G?u$fM#)O3vLWo%iLtPhB9oFw- z?2lXkTyMCQTTAtG0c}E2r!xFOZL)wfSS%rllzdEhF4fo^uJ0PO+0)~Z7!p3;^%BuP z$(7GI6N?m4hvXD}ubi~oH%8~y=3n>%|BBWrE1DKF7@l4ii5-_*{;N(1UR&|1FbmQ@ zJ)bj6RhPp(uAo*SM+HX@PA*Q20ICl~fQq={qt#Vlo1lu?;Jn`jdDx)-(}L-B z-jBUC7~r%a(QN0v@>BN7^F$a%f0kBnX^dF&&kvQp*9#zw;V7#7ZplS9lm4@LM6GGa zUhb?hVHD{=RNQSyA9-8+bF9E%REu*}kW*a$ba=bUNLbHUBSvTp+q=5?+AZul!@NlA zn@XL+DgmmFv)&q;S{M!wRQsw?WEQ67-2Bv^%d;Db(m1)guicrrxT#u3xm*FNcFS(Vo%{t^}r6(%~E-P^A^Rn8n{MSECFf)38jho zM%Em0y>I?K%S^IG6&youF(1;mN8!;BTbHR18Q{u~ynr`k$A*i#Prskua_WORnZ)$N zmjaFQQrSb94hledFHq3~-PZiQcGq{u(?@eu*tWrMB;#vFq}qfV-=OmLgnmq@5|4_S zi?zYZAd+g_%S(ch1#dO25ss7oiq|-=^gZaug-$0o%FuMLyx6@gZ`4e@S*ip#6$FBez6u zXMi%UZ85A?4Xa|d@Stz`>34yQ)1h= zycd>Y%gd8xYQ5iL{*YM=&n!Gb72u%^FfRFG`fi;$?9J=rg11-c!MwQ=#ue#5v(#4~ z|17O27@R9ZxIAAwdgCDhX~qaR69e61!SSJ{N8iHU^#!4KX6%$CQ3OA@#`*lH+VD6h zso$VGK1--H$51=NWYWJ3!ezt z=HZ*CUH#Li@cl*>ZzQ|>Nf*1 zw&H1JeItHn&V4G!wRdY`I>>_v^S+dvuT%vv2|{mn%iAAp*n!^c)-pWKVq%IkQb1># z0AK)%LqM2ED$8PO8oXm3Bm+lE>}$Zco~$h+ckweRBd6a$4-TB#uJ*zB?kw3i4iD|% zxv- z1%6BtQl~_i?XT|_9tFcnX~fya)uC zqyl09`5B`KgsI44-UP8!MPAbE&^_x!1!d*L_MzEvC8h{rGddbuomCr2abm$>y> z?H)NF+6xu^Pt_(5O2RU!SR~NEI^QuYZgSZneQoBz!4sUNaZ+yPJZ;hyygsD>8Po17 zxF!N}(31)k72zn@bIH8)=Yz7$(rX*NSLWWRy z*}YPL{>njEtVGaO=DNwHWgKLTX7Y`4@x6V4z9hQ0MqZ%1ukZdm#i8W7AIA&R{%^wP zDXBaiMx2&*gsBFPD*%hH$MWZRpLl^Ok}MG% zJvLrcp1BSx3c#>Ob=tI6;6mXK;cYZk1YE}Sd5-xTseQcZGRk@Q?(|Zf2M^;wwnJ0B zR`za1K-fypY;#W`54T}XQ}}a@lw2(Xx*RnjAU>}^7#g!Pj*K@jIr4w9 zgM;5wzx9utE_ZUW?x;*FkLP}cT*r5AuFYC z2A#z}KofX*FRf-Ku;!^8k---^PgP`W!?x*U_U^(fvb$J;i5jQ+ zDv)bXf0D}daKBgN^pMQU$V7Ou#SzxRve&GOmYg3)-@&e|>lkx6NkaeKE0RZ^x&uc* zw2?6-tg0EVboo=fDR6U`z1e<4`4bnPlX?34WxWR!fs#_(a2x&QTJPmo=Nk4zaW?LZ zbr+HK$J^|F!fKRnDR-z!sQdQB-<3QsEGXebpj%pZq|KgDH|;bz?>E{r;*up-5(NjP zF{ew61pH4&N>&H1wetL>@%Yj3VFY$c_;5%>Yl@{9W4qPlDexiBVst+i*oYkr zyy?l@RR)32c+t$roZ@svl4T| zY8?Dba;*&4tDfo%|Gl0+i|=+aX&JVd`lT}~Tpfzt32=wSgNVd-F-EhwM0v|K zXMgTd>@iKO65RXqs#ab>bElM=32>Aav@Zy4#a2pDQ&dhDl=GRASXgdVq9s|7G6|-e zb|O*r(kqE4u7m_6RukKv5U=&^C1{@H;^s}TMxwWf_1JAAXzC;Q_pK*8qwRe};Rdm) z-g3=%Efk*Pn@adDbc(~uIVSBa%zbfc6#Tw9$+s*RR=}vvk!#t*-37#CKop=^t3VNv z*?8eAew>LjPg#8dn&xmf(Tu5@lKwHjNc^(WOVt^DNZ9%wvt~n=f_Nu-% zIABvbw$yF~>$>+LKVP!M9g-5yTFFRUn<{NhXac%R| z`0(_MUVx&XjgVB|=zuXEvA`Kmk~idTEx`3|G0@OcLzQ(0%sSXUX)QPN0m%up4CpB$ zwQb8Vf0sBh@u=;`Q`qF5<85uS5ZK*0`XYtxoX}u`BP6#%lV|1hds*SGLnGrosmc zsxJGg#RF)oUckIgkPM5^KtH$3YwjJ!Bdn$8_>Q5BOiz}&P!&BTHlKT>h!gWJ{ZYvW6~lF*JiSgTM*$O6b( zj#e6?@vcZW>IJf^)yPfT$&ZRCQ07l5)x?>uv(HuPr4b+@yy752#BU`OZU|;WbMCO% zUAPoKs#sL}F0XJN!Z}_q7M{yd`|`1MlD_;NZwRp5fntBPOI-LB$rpqmXM2eh(Mhow z(A-(|vC&byA#bU;yJH{*lkZJ!wDGHjQrWxPfx+-jWsM83EDIVQe|{YRwPO0O>d^`N z_;fe$GLrEY%+;nKWV=eUOB$Gsn|d%$LqX)%!N+-xoMvP#^V2({oWWpSciNXRt9-)t zLyJ!OE1$F8+}yIJc*h|3gZowvDSDI>&gz9*$$9AGk(TtU;F{IK0Ra@r-tCKqTY zL11ZHVR`0Zd#&~9*7Rk80>RVU63P z?5-pTkAg4I^V@-hW^TPscPFZ8I~LJ1p@Y+HWM|zTXUul1BH?7#`EE4a%1(D;p zIa63GVg1ZX_K$nDnlh=qGF>&-6%lykE~HJ zF0+T0IU19=wq;3alT1W*<>tRq97)U;WG}%QH0kgCV^`bqI2^L~n){@0%tzv;0!~?u z6jNH1|6u@{Ce0FsN+ZtKfnR5SM#NOtHo(9(iq%gdB#W;g3w!9dw1p=lO1FF$l$yFMy!hIAbAtY!muFDNG(hA__}qxRe-pk@Rnt>cLepGVhLF6mfDs@ zRbZNiNhF6ryiFq!U3Q-u^@N^5WQwvjeu${voSMs~V~TbT!&euFK1z^#ElPdU?dCintQ`vOID1+UmgZ%-4xzm1w(>lQEtG;PbcGj>& z6bf`@Phw>&glQF%MlWpia|!Z`hsYHP=%qk&40CfVG7l$!SK74WB)x{=7!-_%a`uCJ z9tuq%PNv6KNw$wjr{SPMMfzK#FBEbM4XDowG|&!7OTMVxvkNHm@*} zYCIA!%B1mHndTF0tr8=N*nJsl37Cx z&?KnFah%dgJl;ekTVp=X^Zl)7J|YYC0Mp%^W~nM^o2n*2jiVI$)*m_o!D|yj95+|Z=p?JecFDZ$6UR0;q^C8 zxiKP?lk`dD%E`Uf$zX5~9TjY{HD})(jW(5Szfp0wbI}|WCy&uSY>Xz)u%uMDxDzpP zlBvMzEm%1sBsQR_ArHMhUlQ!l)ZWuncN6@K{Z9Djl87GZM}L62nbsG7tta(&Hw!{9 z5AIsR30mJLG=JP`J}kT|+13)#%PATejsU_-W`^wLh$Xh>b9CAz`^cHLkgKk;CF0OL~w~g}yWe?g`Xe z2`~nnB!e#1=b#t@3uQbtA7SOw4dS81&m<0VS2l82t#iMu)Pu?r zLFxyf*k3d7=ouZB*+wcJGVzVHMs9Y10rT<9*7AB@^i1*K`pWL?(wKoXR8Sp9wU}9T z^zt?MLy!tKgw~8_6BBO@T7Ry#h&xq|%-F;=QO%x1>!5Z@^}Pp}X+lqtD=N zB;sT!vv*Rdqk&;Sz>rJU(00e>bkvr6ktFiPB*Eeq-p~}*?r`{T&X40;Zx)9m4x}PC z=q=8-APzGXi5oU7NremRu|q2Q!kfA{v*rF9S^66bwi}tqO}W^-Ca~G$F2sEQ*@9mx z7A%OxjmjmN+twEbaADQh%IzxsRiVlSmUVSG3q5%nji$=gVw~Mpd;ORCCtaz@wdu_D z9&A~~&KCaPYXihmHmT@5BJ4=F+;v~dUQ5AnZyXM7 z=8a5Su}q&0XU-12hA=)ISboH@x_6L#tU`R^L3xxC{1R~V83q3Gna1i)JuneEP&4LPm*p`XecGKo zI2o7Ro#inDec4ml5NB;_t*f%>HrS`)ReL*O*6c7}RZ>rNMT1;iSo6VL8!O@nDaoR*&aT*+|nquhJ=hfMybhF2k$UVEhBBBvJCN6{$d2 zXQRcDyC(nIA`Ol%T>uLG#}(rVJL0Crl<#N9BswQyhxkd_FY2f(=p@Tn7h7tm7dV6$ z8qLdk(ib=^^?C#L&;V_%@a3=>ZR4p)_3R6cWJ_BPZFA|afE@>YT8Bd}2mPs1o9bn? z;d5I@2g{foBh3rrP5XT33rp$4?aqU@GiUq+_TdDYVc*Z>4jm~`-fyF{lWN%0UXVjn zER;2!l?o`{K zE^ymX|Je!8wxx~Pf0Ml*L3_%hxd&6as+E#YMqQ`$JcTsRg@v1E4BLu++MAc!gNoP+ z5MN_*+1L&3l$+a-qwd5{Y;(@I1m7HIbRH*tw9YBqc)|DFAu!x2oWRS`xFIXvi66R7 z$OKj5AAf4HdKhv=!nH=8vT7Q3MMgbtJalDWjzc_jZJDwveYWcOb3?mr)k$iFICayE zdyGU2MP8!+fKqRHIq6EJxwe0jl5x@A@mW2nd!F!tS zPFs45_X$)rb(>9XaiM#YDWh_}>b}u+Y<$(oPsKALvvZcuZA1dyXgww-8ZPJz@<}7>3SweH48P%o!w?{4Zr+!73_$5#J zVP_g|mn72tYs?c9Patv)AR9CkFR<@uh_V-+oeWRHNVI@LwKWj$~u4D8spMBgXJdu zH;6##q}tIW^P@pw=3QCz4Y9HzWYGwEp-8S}Oh)ET$<}q*bpO`U_>Hjf)TjHfBBR{~ zqkX?EcbbO*Uf=x$dgdcTr;mmnIKC`e555kD%z!QC97BJeLH2hKTwcCRDT7W~+{8}S zb(Z%6C3o>ncSX22xbKcvF7Hymc&DS-WRUpavHB26-w?#^5PO{nzUUW9tD)eH+_2ic zSbk3T^g`gX6XEq1r*%fI`5YyEdbQLOHu;3BzV)Q>{z>!Olh)A_`u}PX*&buD5F&8#%t$;ok>oYE=Z#T8!+fh)dMf(?;Gs;8UWcjNO+LlT%{Y z=>w}&6UJEE?;1&^k1B+0YB4j$JDvrksW{O`j}b~|(4NInQqgo!S%UG90^X1SknBFP|2BW19kELy{O{)rMV5On!VugnX zB(&k7Ceg!)huB>nKDz!ehT^z|i*k+(_nAiA}#BV6&;@}TxOvzV}t}1gfhH-LO+9#8f$fTOJM*?Dc25sA;i|c zDjSV+VZJtpfAOxwij>^d(38JNC-8mui(g;qWMt8obhWiEZe|DHT2Tq3OyNCf&HCHn zUAvQ-rf7ANkkW#3Jte7gPQG!jpRGe9E^$?RdyM-{OZ96rA)wjyhPbH{w_=sYl6TB* zt1~=AM&j$|Werr8<%2Wv7I}wK8gkN#FCiGxD0z0Zmz+B*(8Ms89L!d$u(H)Vh=StEUwWHKxzoPAipu3hx zeF!c!bDnf@d`E>7h;N}++9h|Ir*@I6fj@5J$0~y-mI}bVaS@~jC(#4h=oob6q9qs* z-vih#0dx=qD4w*r;YP9UVwmm2HMc3AC8#% z%PUz)rs>wHwC=gjHt#ui8LC%t+NyMUUZDtCj|AxZE2LV3@NJj)FHBcenfGHhv6bPO zSSleIx?OxY560FJMb-wn)S9967gVBY%XPGb;H9gB@ehp7m*$u2RG0wdfe;pQ2y zw_b@)DyzgG%#D8F>{MK zQ_6L?h2KxrD=m^yxRmf1{p=8J#dy8>Ri3qGfz}}vj%Nj)-8+fGRuajxudEZQ2gN=B)yf22Kuw z+IWc4rJZmadM49dJg>kNdQKocCTNvHxRz`Lua^Ty;RGUc2JjQ~31 zimBRa$_bIQp=_aTG5tTzBVJ7m7`@?$(8kE$e^z?Ei< zbBxYCyj8CNdFi9bdgL>hM+qilzxe5-cCo32@-{RQbIN|htHt#0shz7Qxk%fqRGe*7 z1k<~ztrq2!7h4x6&9h6|WYgt%xiaGvNaTD|)j%Sr>z_2!1`j%Qh+#;J80CUW%C%Jt z(v^jI#G(YhNh%CraZ`%60eR77brgwXIe!#vL@32d{S5K95doxQ!9b^8fh^s zW5tLkl)N+cXXM4w0r90XoWHa|EbiF=q%`OYy&R6Dmah{<$pyKR zMZtwnU!QIl;~8pmV5yi;r$x;lmd+U92+10GrI8oMVUuFqV!#QbkqII=F(A>kO&kleu~to9qe@S zJR=%i2wr>#ah4^;M!*e!l%>LMp~iU0a`H_>hKB$Haw36DJc$^UrXS_>Ne4zC(!^;f z;CAig@szHyhT?=nBpR%U`4(#l?%Gs7`iPbFvuH&FO36jxw(%?z4Kw696t}!?AZ&VM zYuJ=p23!>u5umqT_>=yu*g8Gt$EVRzQ~es7l`p@kpsJ|Cpm`N z30_Q$=>@qO*u71}A{`j4MF#bw7z_=5LZ@apAGl*FoLM+4o(`&uMQ!jP)-Bx2Gy;v9 z602Q$X8Z)`t2Y4N?exXL`dsqesnV$^Ac3GNOZi!8qUUOofeyMo9d_Tx@DP-2%3Ca4 zLQ7Nvhi5LwZhKZB8Bl~C9`(X4n`!oVufy z3HAx?S>i*#29LLIDAS;XzZeEfL=ukEGGOutcjk}yd~5m9oGT7q^`{%|(V`IhLFGW% zO)AXQ-Ea&TGz02ZXBYt_=Ev}RzAW{N_w~XTp=BIri>##R>`^J1Oj`Ddf@Kr;B@Tg9 zxGb=be#HnxH5U6RkDGHQ1IS%?AF8n|DxcLl3y=bS1T;1BW?hK5@}gLKTZVmIk<3mN zf6{c$VqOoa_+^~qGxO3nZe3eTl68-k^qRqmvG0tEW_4dN+1LulX#h3uxK@T<)rfnn zi}Krt51kni5n(fIu)y+VMF0>n@rP3koeR0NC#$Tfh(olVh~5}$2D>VjQWTt3fxrht zz9UZ5acwo(=zOl@t*tUspl+<@_||8M`}n2IC0d|NfQb|)*7kN?JnQ>~n@eu`r@9OE zo}@fi^wm0|>(a@1avI;xYm&NVdbPPfX0NLS^F~#ehLsvtT-Cq?2~Sj?>LX#fnVAm!EbO(a)Ll z3-Mw6O~&?rz}PQk7_##XHq<`}1h$wR&I!E0-`wEi$o2Gu`K3CHL`CdRBTR+F#cQoDBgy~F&86`+HP-1=|h10#r8c4ZmY zipBWQ(FNt0$lX^a>YSydhG$Yi?kkhVJu&{&vVL~A-Qk7G)EPg@w71cz@nfqY(hSeL z$0+i1Zr&|*PDA?KNt(iAD@q@iSC8CiYb+J`1g&W9zte0*M$ORIeTD8&x!Mh+6fh92 z9d}nq{?>n<4FE8&8Yh05C{KaKDTvNYkHZI6xqKGrV2hp81{t%%nIb`I1R^s5 zP*zwic(;O)MRXsI12qDHhdyY`o0cZV2xxcsgR&HE6Iw|+DLK7rjKTsAkz#evp*cW& zqS`>}BP+hFVoiwCWi6$DErnRJqre?Bgb4p0a zviTt-=CewJYD@qFQVdTC)U}#^wnaP!z(`N5y!7xmHsP+~L1q-HM8e!2IU&DCp@Bep z={i^{s{Ht>7z09b_I+}11nDtML?DZv2qsW-(2;xSI0h zf^;%7SqLa+edo5jM(Tf$AK^#Hh~gN)ik>hk)-Qzj{gH|hN%_--R?#-rdWSqIYL15< z;p?vkXm@Go$a2Y}tI*d5uZhN47_0dg?m=STL?|{xtlNM909~~B>tt`mPDUjS0-BZ4 z*NWD~E{Njl##jjg>U(Qi1uTBn%;fRQ40U(v@lniD_;9)&u~u(3Jz2S?3#V`q?!l1? zX^BeoZw~0+))6YVJDcY3uOEu*?$RD82w`%sYo? zA|R}|1O+qX59#JD8i9i$CEchsU<5vG?}Uhhj*FZnD8rq~26+5IF3n43?u3Ekje!Vo zi48{ak42*M@=vsfhQYkZ&E33Ez~Hddm|_Qd+M*)+3K%RnHY6jaETG6cp*GaV#irUJ z#yYjw#TA1$TeC61AFB*J<2qAaMmF;{XR+N6)plWV+Q!Z?u4u9~E(B2;s+Odg;8?KJ zlwTWdpA*{~vreut?$VX)R47)@@_`CTzmfI}23x8&B9gE^k6U%UAs3#lVO&1TiVhMu z_@%fAdWn=>X5gxd>)z#_EGm48*_P1zS))N-K-kh$m^ZuPRmfMDj%XlrBP)YiTWD~s zft1t2r&NxMnyE-iiZ1>~du(!`Xo`Z!@`dv;OF2rnFI*|jY|&K&a`qF6zl!A zr+`JK8o*{?dn)?kl2XfEBW165E34^u;KWaS&Clz)4M4)lW5;G9x3=ea>^>Y5@?K5+ z%!EmtjcdnHnR%34p493O0*8zQ+V;I(~`g<*+S_3_QLM1cdLn zwo)D6QGb;QNJ{n3CCFDtZVFsbq0sm`iYVCpKHZ`Ny;NR*BU!rcW)bVKfI59ZBg11Z%ze4szY%`l3B+Zk-M}#ifQ#=Be3xW8(wnm`yeRJN@h>KYl?Xx# zvZ?mwnge?Ed!^%Aag5bvt=X7y2Ka8dyp%akXwT?Vn5(5-O9|lt_5dU#P90=zBu7wf zrd@EbClJT6FDaxx8wra0vu|paS?7CJGu=<0E^^_Cn>|YanHIdP)I>0- zfI|_bia-^Q!>(GUl9-WPje^EWKuSc!ZI{Mvmhq}dwOB~RY9U6@;Dw#9*nlfjW9loP z*r<1wpkRrAmay7wNKIL^Pk_mC5xk4joU!x;N(sPSch0zJQ2hN&%h7Lc#FTkIOR4ke zi#|uxo(u-p`?pmE!ra5MNTddVgzM>f9;FuLV(X+rvw^S}5=Er!EZe=;vQ{!%I``Wu z5H%u$H)>nGe5BM4vmF^3*)a%c3YsE5qXinqLG(OD>e|)lWcsGC_TB()O_Q-@fnrC_ zv1=Z?u2AFDKV1>DVe(FoGn(j!-6R98XBuA-RWxV5q2eldW5SJRTR9csiQaq+qOT_X zGP5fz_Ej0M>JNi>S6>Z_BipQU#n|T>u)6i)61wxpf~bYbeM<4&_6?(}3r|dWY|*xWDpOSPlKgTo!HhV$4;lRig+h zNalI$kfyr5*U^wO+11NtW@GK2%I-Zb{|{GZ71d@Jb?Xq4;0{S}LLfK|?hxEH!KJvn zy9D>(THFi8rL?rTmA1ImC{7hxN-1qWPX9B`#Xrv2_wU^v@1ASU`7GHkAf>jydXui} zfkg2cmIpH-N0iu^#8!~~MR<~h6Ymqt^4btGTu#!yg!Z>L8@IE%;_4Sj^R8WC*R+9; zHix1!wrzH~ijLW$5CUeIq?q8+Fy!4aQmw)M6q>}9=EJx|A~vgJon?&hqSBF_INfV# z9HUg2Af~Dl$F%S*l;yDqx#~c$t`UZ0!r+CU|Hv~v$4yPc@%DbeE+fAf%^J_TE7h$) zfXViUjK&2peA%;x55?R)9!@(dg48rwI~H#^LqMD#Zrd^Q37>;IFXfn7D)ef7o>ZWuA=#4+@eW zQ4b_zOqcwuo=9nuudRd-y2IsK!L_D$2vw^effSF ziT8TTx+Ix1clJT7o3goDgm}20C-j_7XJ|EA>A{7|0B4e^jPwfZ3p}a^qrA%8*MZN2 zvH_$70I+<776k9j)a?YkBbp0~J$&^ja#}X;REKO&a7W@?hNWXcm{N$kk6_%X_jqDO z1sp|X$$P2PzH#V(`%P3-nsJ#y1Q`XqW_ibhl>S_?ANZv_+uF_G&OofIF?_wF3^ti( z6xY3!i=_rUX*rN)eAe(Ts$9}jkL?eochu;0AzrF&J8H=&<6Wfc!k8U;pDKMkcMW z-VAUk<=sT&CG{Xwfy;q#ngnkjS#ICT}H47VTXMU@{By;%^%)4km3Tt78VIC0R0A z_fMKT%}ke>-24HKP7|!+o5h})McfAcPj7yR)^x-G7t|J(mpu#0E58lT{5X@85k{H! zxm6nVGl$SLAumuZ<&P61lPy|nHnpcAlQSQy&JffJBaUd|1f*+VA4)2wUwi5`dK>ch z@;e~m?&Lo{OFgr1lP<&fjwE}S>ASszzvGcFL<263dMnMlU%YTCZ#4+b%;gm1eFS^5 z_{<{P7>vF`jk4My2T08Q(t*USKiDDpU(R%ZAIBovJrd zU1zd7AQuWvJ`Id?WzMGRQ1!fatkrm@8ycSM$Sg7Tr{mTpEjT<3&DUxsK2fAA-T-8- zQ-9M(bwUks~PWs>=Y>7XW#qIG5&tMrM+z zG~gsU--RPkUDc7n1U|0k&12KXq=rkBGF#RCLZ>T$ z6OP-W)?20PBKB4z7L;j-NkFrWA4q(QP;uD|(gK;(l`6IFQGh-00x*9+9t}Gt<`_`? z&QJBa@05T8dtCzWVxPi0bD_QhKIK*8Oa|O>4>glZ0;8$oO9suiOrdkcRP?Q=V^d_9 z6sOP>!q}a(7ez7Ji&Ro~p`DGwq=2LdO6a6p4W-GD*RXUptbLkEmeBYCVjr82E z6uQA-;%^cDxkG${&)*^JGj0B25eD+T+jMpn#t@&)&f*)hA>%=;7s5A5Q=n zm%W--plR5sQ3N+`)zuKel}}GwP{$CRN_JWpvX6(n4d(Q1Q2xSe5iSELJ+!ih+84~Q z{89BXJH`U)eLqSTd#)&yhL^o{)1^g3FS#rJS0a8{k>fRMSTk=veflnDm1rGH15*;cnvjs{j^yysnNi%Lv%LvFwIf z{9!}76|YJZt&iadStEB96|tqHB*Uv-v+rSHc5tZhFw*`YtfnW^l0o3+LPDL79O)6d zf>u^r_ehq~WUqjW56Kb}rBhgeZcW|TL6LwG0|hO;OOsIhVucY4nH0w0*+jQs;M#^jM;WE9ox^F+(Je6vX(+9t?DdFwSzyN*w-#wEMC<`X*s4%IK=#H^K`7b zoy`6_&28k^5*GN+KFeZx#qAvMGkvm${RT%z+GM8JqL+JF>0JkFLW7wcF}jI&_yNQ$ z0AfY}#FMO3I*~}zkyx~?lWCcl-LccWj@^E*Oe7FMg6Z1y?mFEA>|}Lqe(2gEzq1qF zg<0-8@_s;*^kBogt5ovAp|{tE%C1-P57t@!KQ-$8|I}!++Wq#({X(eJ5-M+I-!wC* z;k~L^PU#r5f~&2LV*N{qN}YSzGE?R(vb$$Wl7XRlkMthAYOCFtWT{1QhRBhUz5F@g za}+HY0|rRgDH=_E4hmO$+cx{gIw8c%jX1(T!PO4PKY1D!pU5PuXKsYE-M6s+nta+#rhN;MfQ>#igi$-9NL{TDlz=k{s1 zqhqlSKLes&AIXW{BhzaZ1r=K*9x`Shh`eN%<2N{(lv$jABBu5SVAVG9s!GJGbNd7s>}(21FeXo`1M5vxovjl7S%Qe#=fD!nAAj8X`{|1zi~XEi7RoN9BI z%V+IbX`NK$kJ{Q0^dzGy%TT*$NP@9`C~FGc|I6rzR;W{R8V!&YG3Tresj~ zqMVSaYg}VZU4Uk0ZL0j?De*1hHJXT%rs~^bJ^HLkJy*uWex6YG2Za3Kn$clK0<6{& zTXsMMC5{6j=$7>GGK37pFxJ;3#dGj{$g(Lp%PJpT@VB6%@-5sfl3eajJw zo`}Ae@?MAcuJnt71I{6b=ioU@8a+lR?=P}oyZav(_+N^?aO2K5yYn@p*+;xZngR>v znsOiMuY9~ek7)3uaoy%dFTDV{unA|{DVBVddnw#g%`SSnVo7ug3^SCf{h`&)@^iH3 zPMXN){Uyu)mgM@%!5p%|-oGFII+CgGxEDZpxmr1;hV=_uXpdZ%WJ;2;jGgmf=(3m1 zfBH+UofnfNn8BvpQF!N8#ofB^^lgWRv{^RCSxe68pfBHuS(t%QfSp(QK*+XhIdnCW z`B(OH5uC*2<{Q7MZL3#0i-xoQ*OKI5AT;WDP4?L#%i$J){nM{9p|Ks@J8||%gH)RT z`a3@bp4vT0Ugh}N%})Gu#-yk74n7C2Re!oIv^jC{D6{G!-r=&Ss5s5sR^>%O=A2<%J}*oJX6qZ`008LHb1>BakP3}8@VSsaDV z*T;@|pB>Y0T_;U4iT8Lxhn`6J1%;vo2nx!5{`}wQl1=`r4FA+bTiW!5mS+z*n>KUN z62|+6@Ta_0X;+P7b+KjPL2m_8Ig3A&c@@A9&5@vg7TIWhRCKd5>{lS+1e`y{Oc6_ z50q|mt%&w)G#a~{z1*Auz>;Ta;AP1|Ds-0rK!xVAzwe{5M^qhc_2!}5XT4)hfFHB? zZqWD|`L;shjjOtvXPr@EwA-o2VvG#YWvOPIE;D}Gs@J^0T|>7L7+irYN$z?tvU&K9 z-n|L{jD!<$Koir+mWjZ)_Zg$-hTqXm7Yc}@&G`b?tNG%l0G8goh)?e~PfvMo zS#|sPGoH4G@~3+WiWo|rFgTZ57;Q!B5dJWcU!JeS*BZ%xt~*H`cQ8zDDORXt$gY}L zXFeo*!tOw|A_WY&FLY}M`lU6cml11V1=d?c6S0lv1EhFVj4Ncu&k7-&&K=X3jMq2;)7O*$s|!jQA9u^6T;9{skwUQ|U&9RJ~K zURBtEaaJ4?5$Sa4P>xnhyxm#x8^_giSs&`DB5F3a3A)!h_QtjiQlco|?X49Zg^X=Q zAESxtb$xDetOVzxS63+2!nfVGMISQgRy+O$(@l9iGZ@g@!?o*ffm7y954pc>{*GO{ zb=TK2_BQ4V63B{FP+C_U3lz?+;ovspr_x*OqPTL&6G|Yhs^s?9jIBy({2#cU(U|{W zSP$^Vj8QXhgVp&w9TqSds9>&r-NP@_#~Qbn_|_ zjQB`?G&(}pZB61k+=8KXG-ho5S=pS?fZ9|BXQ_pVySMo6WSq(oGL^i2<_KegRHFPO z0lsBv;E~q?M*_|*K3kARzBH(&)6Wg$!|`$VO3Qz>xn-`D=#`$&DnIDHnVfNRHF^@a z4-1SW#AD@@lW-#Dm*wlP9Y&36%$`4U&4$0|??&=JT5S_v8=~32x;+me&0yv8r&;AR zz{*xj`LC$a1gpA5GN^1N0^clCK1Yb?0W~Gow4O*|J-CR;%e@JTRVC9!!`FvIOkKjaL-_g%L{jKfe^1Mp^=XB>nN=54 zotg8#3o{KHrJZuY}ZghI*qM8|7XjT((d7JPE6Ylnd~*a+)IRHFBl5<*!{Q>c@dHFbktYr zDp3$15OFsx&={XWos9M`Dx&?0vh&;E2!3` z>bJR0qVATCr(40St#f(NQmjqhY1jI9JGJCU*v@`%kFR+_)L6*cY)!FN9z|J((i-V7 zcIHj_*WaXC(JZz>G%$$76DM|^5a^a^#v9i}WTDunHM*Yb3v#B zX{3WNvp+)byWr%@3SlKk!y{2_t3ioYwzLPAqtq>;gGv95H1)$0*&C2aL%4NOpR9oZ zHg6y{3?MAaD``6rXXWLkhl>3f9QO@I+p%Rnn;JPRLG^8bdm9-VgW&@Glpm;bVrdVJ zE;bE8P?B;vG^mCXE*-A|)AOGZiiZePZ z2_@g6DGn;@50$4%$6QWV`1eYbnv^rS+;Y}Hm{R++f8)|V$QT=&YM2K4_e{xdfA6!Di6@$vc`I-=vVs)(JJtEy@0=)kW6t3*~VDipmokvi+ z{z*6c@mf-R@h1jaiFWmG7>(9h>H6=n!&)W7a3{$RG>0w_JT5Udxik=iq5LUTpcyKB z5e*V6WZPq}8wV|j!7nz*Jx180B}g~bIZxHFs>Es#CxxG(4&!xNUQMKH&I;5>k+eeK ziEEi&NxaAkMC``*{#^418GsUw{P`vqhqDU5J4>j9$;Mg{krWYaD8+_EJ39a@nix@B z+1^v$UcK1RhP=KCkSg!gf8|?cC|;TGi`V z-|f`HcD-HfT+@3%a^AU34yOBGxm8hs2*CH>`R9f9Fk!u|rH#F9^*1IwU9ELJCat;L z(~fRNU4w<6m3_*by5-_ZwLB-v$0T89B-mIo?hYjWF-^^M3-g!<(&X9l62U1!>#94H z7`~+sSqFA>#Jo3&xxxwu<4HHD*P?Lpx_JeOeL60F}ERAyQEIk0v9BJ~b{DAG{6hQ6d@n7fp0cRotWc~`Ij0U26nw_# zf?!Qef!=2cMs*ESscfi~Sa@!jdSAQ|m_M{m$@|F6H|;<- zH@nH4(jNJzbD>J9E%W+^^ZT+7NIftLkRbt4@(9gl?nh113shR!c8=ou@5C2ZPK|sv zyB2|+U9)@T^#nL3IP+0ml@hxB%u7Y`n~k z_$s&lWZ^6`$#ye~vB=~%s}M%9E$V{J93p%ayH~2cY?9mZ6h9@)c0m>EkF$+%;?N5{ zr}+ABh4jB&Gq?>rbH3|JSE9v=TY^p7Q#&4K95G6f>5OLxsC#c?3R;;?^HNj^7Bx1m zrF0;0|1lzwH=DN14Oo{xt zj82xv3%E;(aY=XI%UkV0&F`N$8q!wzSg0fE-HU-<(P5~lPlNgLWklFZpXfupR#KO_Krv;%x5i>G^SUom)gS1YjD}-n$^g%iE=A-zMs1n%WchM&g_fBP*gJ9+ z`w5wz+M&yi0%Nz1&Me2}Mf6HFLrCz=3;2d7#kGwyyJ3l6h@RICCG)OrTYOrzC-;0p)wABAtQBIbS&EtcU^4 zPV>qsGY#Y{nKP1O#7~Tuw(ro5@*^!F)4?N<@2eNe>)fnV3lpOUs!` z|3F%O86wSaH8q1iMZ%x!4Hj9=bg|}-q`{U_8qN!RVx3-@$mBDX>jv_Of~<2`*y;d< zueC}Kuir}SYfw+e>HLGDs+rZ{lsDW8aId^pXT~FXLHt~RRJ-LM^=IngSV5t~`8wo9U`SX@a`bsx!-Or1c zVVne{N6!_-Ep0YEr<%T5>5wWA_G-boz;OeBmu)F&1Yj6}+k)=PG!@qi#QEhULvbLC z_ly&yi|43l@P~_mvO*%mxw!E)n7=&^$3xD}eW$y{K!|t0ttW7zK$j(r>y6La*(3!1 z5kM+T_iDj6%aLb;3{a0Do(~-P)nL&q%14lNZtodl4N{}j)?UyQ&v2=Iv$8LaD)~S} zUD!Z9!O;C(7pqAxE3+-;cE`=^Wda*?bJaUN#P9lp_xixbKn7{14Uk^ox|bFD-;vAs zZT(pkS5mF2hz_nt^~GGuvqqq*iK3|&opC>oldi|#WtY}7g-2#*@-wE-n7~rW3qjE zhx>$}6V+O`Z^2TwdHvO0lyWySFpa+=%K$c(W5-H2nTF*D#P33y869}&8agy@%}sGc zU_Ku`p`<_-^FOS~^}iZyVng(*fd&IX?NYZ=?}~hwX}aR`)$h0SO4i+sdOGz3pLA${ z)BCQiU_JP<5M$)ty;n}wOnr}amhJwOEX)gmyzgfEPCDA{{bsZ~+0*HMvkejx8+LV> zl$z(FePS-wsLaMJBc1}Oj{VaeKMr}_w?`S%6UB+ezbTp(7neHI{Gpel}bg8??o3`*OiZ&agn&zL=X!J`RZQk*BMu5(@QL_$n5u%8Pqsv2%D}|b3hknI_bn)AJ;&AL z-B~%}Iw`X+hnV3}l97zz&S=a(&Ywr!xMOki;~JZEdQque$zW$I$L8;D!TPW?auTZE z$X)%fz_z@X7}KY1TK+jBS4F1QRJN1e8;54%D~z!6&WMI$Teh`?H~d9|0tHaMp`E$$ zY0=k=E~E$E3;+gIk!JT8ji_Jbf-i$p(LEJ~M)AY7^h{?n!kYkOhG}1k1x0brq_ z=HE`e2_S#*C2&I$5Fy(cciAmmdYfih1bJ=^dlKpY*1^5d!b&#B<+dFxwP-V~Yq{@m zU=p*<%X`op>(mVTihnf~0Q<=mHvM7O(9P7C2SZ+bE8()*F#AL=#$jGg0D!E(?~SXbXe0fzWon}n z+6s3yYY!t$2GLJPhyXB+)}FGcI2(*9;wV^nKQY+80HPuh`xCF7y{ z$9nNSNr98_TCYmal_b_PCN~l$RL3p~%#vtN@iDxN z%@V$8J&ECs`p>}n$`bxnvY@0?)adX%7Qqc9~ z>!~_kq~smDGXh6wc{C*R26+9}eYscEF?fI63USe;ZlPJ``+XhvdVOYE#0vx``&1Z&A%863ypncIPkgZ9FA|zz0SUoyVQ#c`Ca-Jyl*1DSBO10DglWpUROwe=A=?HRQ?N@@bikhUUg)%b7RnVQxJBM>k( zF#N6t0*=E)whOdLuFQhG#Ovks``kj~&ZOIh>=veI0<^PE(B6x~h~Yy) z4M`v$RB*UhlOQ2ER;mn@F!U*BKf5N0m4YvaNwNNjwFZ)UItN-2LruT48(3vc^edhX znz}T4u#MAvWaKvQbRo{PmP zIh}PI!IeuY^Pm-MkOuqFRxdw8pY@&UFevYfR{*q<#bMR7^`cGzR`Jv|Z*!cuKvmeV zobRmHU(rqT3EF@P$i1}%1J39xp}4TRA>!*bQ5pKhb8MxBnOsbOQ0MeJ_)!vP?9qifwW%Xa5bfMxfVZmiMc5X zVQPeL6l6YYVaYutabNX*TZAboVjf=BJ?wR969er}W-fO`Hl5RK%BLpkFed~i|zK+*)re=duw<5#C;{tyWI*aN<*?4IlaEA({#&4QYZ z68{>dzUt_{zUlriy8Ct)ELd0WJy=5P19GY>r~U|n3iZ<7r>14?rK#%Wr09cx>_x@^ zOqY9kD0*QEy$UA1+^ql0Vio?sBKQB6GkXTjy_==`?J9d`XM>(^yE%x9cX-LUoOz?x zcvgccGNUiYIi|)xnrC!5nwa2FkraC?D-7c}BR8i^KX;Xvp!@0D{?UmOf?gTk8qq$$qF6s4vV3K?65_nfnBt5~e=RHj z`bdmohCxnE?1P?Wk&=M$bpNiVdSk%o)2tv(nS1#U7V^{UyA2+91U;-IbXUB5nFEg5 zE{W0%5F})ezs<>dCqstwNT_gn3bfs*oClH)#|KdtzMPcZ`48>1srOt+GM5YNou*?Y z=^PZ##-CW1Qg2&9pSv<>P$nwdaSM`u4dlxgBtRa;c1$nLKQ^Y6PF+08B`7A?qPXhN z*=$29(>et}pqOm~U$<+sGsqZIjE_IQz?h_(EmyqB_`ILNOJdyIt`pZGLz$o2pbN{L z9KKvb2$Zlz7M|>-)%w0z5*rxOuNIIH5reWk@?q2UV|Ra1(CQWB(gV5C_|5;dF{>B{ zqiL|F-e%DCXNVp7K_$@rurF)fM{9lI{qj+_L{D3j zzAfA@{lGnvAZ1*``p1m|UtC1aYu^m86xBslSGoA3_puJPcjLZf2!XghMd`j!2|RLQiSg9)2=)0^V&eFSUh^A{Nva zb`CamYbsJVT*kv(2&rFFRd+K5fPFI=S|!}i2tkD61*r~emqMZS*QzhX4>F1j(m~C~ zYo=7};AssEx6ZwI2I|9HiKipI5c3375uJUnaBx*t&j|BNi5`(_{Ys48`(yj&&&=yW znl+)=5|f<^E1eoUBuiCM(|)PUBY`r@I;)(tLPC1tFqkF#@?=Sy?!vS-#*qH_ZtaA5 zMn`u!x@9wBKmfFTTU!;L+`^{FR=FO!&i$iVYBYQSH(+q#v74(SRaG1t)rYeqmK!RV zV=LPZqP|zj#03+bcGR{K0K@m3y`)QjXq%U8SgPteU1d*ojh*dojd!L*u*0lM%^Q>m zJ#JklmxACkKbxIUB5H;)jcw7jb9df=>%))9I;r)V&sq#-TWNP6Jy`|&UDpG7^ z4OI$rORTW?&T`{!QyHz3Rk4%XK!koy%Mhisc)l>l$!yU22L3)&{>_74jCiC2nE=$| zH7GzDXSce4`zrPGs|*w=bcU*Oz#!7nx3R{b(CKm;=GYDiB8$)^jF*>pBtLBS-p_^j z9>f<{KOQL;6-E9CyIX&hZ`x!V!nBh!LpgSTXE}&BHA4T6nT-r|*St%!=X$p|l3AuG z61ol33y9G(t_b^m@9@Q4>Yxu_pwR(ywn24;cPnlZ^)hD)T}whV4E1HOpzYmN(4^bv zBqlWgW#ARV8o!S4Ni<``WU~YjI#VLZ|{S)ELJO)4)> zpu`*cF&@eU-BbWW`!RHyJS1}$L*rw7wKZmy+;Wp^`_1QSemqRP(-5Ivsw46~Y^B&w z2^ik<95Gk`cLQ?ue|Hk_cqu`i5*gXZEv~N9E@!|pog!N;$MX+R&{DC@Ldv6z_qz6) z!ihko$M$AL=n*OR=C#!V2IlA$o*ffnlNoFF$yF-%m*T8;7?|AnC8LuUMJAFN!;fZc zpWB)0ok9RL!QJsO6PxJ3kQFAPOKa;Ndbr`UYXiXfI$l5iU$EqLKrnTDBp>DW}#{+u* zIQy6{fA5o+n-@#X3CaFGzp|IB&WnVWPVBOuyBaau$GNo)T@j5Fag@MZ97cB{`i8T< zbg{0aHOL^9AB1Scm}X5?WXI2_mOS9$RAs`DD0nS81HX4T6ikd`4NRWCr&#oT{x7?M zD+lPrLki0b67$l&;^%C?*aO5?7*<|5j}zUcZ8et=g)+xvIrf#$_>vl3p$peG7yzW2 zN`1X1l;~}$FCA=C6lC5o)<}@c&MO9UHs6TB;4-wU_5BlmaOoK<#cgt7RxUU$Z)i<1 zus)oXf2LDAx$}&wg@_uBZ;D)`!nr`4|746X> z@8YW22l**Frj=dA+#O-B2WXtd8@zaOvMvl^mG3^h8d%v?lcx-`^x#Skpi~v5-DO~E zsubf;@Xi*PO-;SKLabeBTjQ~M<4Qo^LG(kvDIFK}ODG{xy5f2-AN=ZL$J~i+V|(pn zU|JtT7xeNcnd^Fr@EZc1hWxL-C3fNTPR``--4PEf!(PV{6E%b#9Fp=gWK4|{U-p?^ zMCF46e>Z+^g9kof*?nvi+Qe8p)$_fubf+P>BuMCEKxfZB?BKRj*$f5K9I&cd|JEqP zb1{h8cwf%<{7}^4#kU>*nzy-s&b6=|{nB>C?>^XQ^HX6DJ{DvVCP@lPJb(C;Rv)tiG?U-O}4SD7i$4vyU>^#ACTM+D#iQMlkTH^vk?`m)=D9-IE z_elZ&J4G}DHnKd~5XrMTZY{())=vfo1wVOT`ydirbrTt zHep{^nb4_xH3%hnh9pdyJ61A;eu`gh0y)C%H?S2Y#-O~Cj?!&5ik3oRr9&*fLvLKv z6?-szyv&q?fo3z3Kk(W#rxgF0Gs^@T3#{XSsN3KO5NcpNG1Ef7rp$`kogvMQ#4*`) z-dUYNjYnt3d1?(p)1cg&B79d&R$&dN+ROZAO8ulTKDx{~EBvn4pm>uE<4lsRC)S^; zKd3_O4l_64!I5`$hU0FqQEP}vKsw1eIPD_su0SaEi5im~f?4U5`}Fid8@rS&55>oA@BnoNlilv-}fiB}s`DR#u zQxI#HqYMECJj1ip@v47ziX=TE6fxbBi2ls6hsVOMV;NzbmjF*@E9L@IT@D^TJ!>bP zX#=tn0a7M`rxAFm0u)`L;7yX~P?G3V`qU#5TQ{N-8rgXIS=FT$+cTV!m7AQ>FDL&b zz&XFZMhlZ-p_R5d66vUe|D)rIz>U4szaF8oF7^@1D1v@A`r6|!rozDyF0(a`q0}2=DF_)0+U!!5sJs z3F8AqDwA*id)a5QsHAO64%6IajMsY;PD=N5h!b&+7Rsm@p3!zUZrQUK!06TFM!i`Y zuXY!oTDcXh|E9S39<;!Z@7CI2gZuA_SoX2iNMh<2G|v)IL_ZXo!=00)>f?ao`o;ys zY*6yFlIDjbpCoHDdWdieq>ZmqG}cF6B3NwCD?;`eMCF3)=~KHka{q0eQ9Uk`o{MPQ zfG;7uWt~7GAN&u+Q`vZtgAkcev&cR5oQOsVmtZ_i5RYYY%ulaOgqx88qhdyK!Jehe z0Ll}^@9?)>iuA<6*e@wufAw6zZyT#=&F|{WA}uR&DZy>G zCHZPCUow+r1V}!Ap%vd3_$pnUES1LQjLRHF`}s1C(t?(FIcQ@);9V;EVF@z1(eZ;6 zs}{PhWySbd03M7nQ^1d_)CQANp&|c5{3-yD006XF05+lp;xP9Iqsd3e*&gi@7bM-M zY`o7S2oe9+F#=%c%TWV7R)6U2jUEeDpgY^7QGZ z&DKv$c@*i6XaFg>i#T%~uBjhx?Ko-BSp8v<>0VdO+Q43Qi&D?bg8fN;>pXMo6$04t@X}T=Q-~)_Vr@zLa)Cu#d zArP8jFKr>gtnXilWEz$z}I1T3&cK0YRTs&N=^nkDf0m4|F+10)KVmsNGsVXtein-eLZy& zFEInVcW-O9>J6i$w#_zgI4de9ikp?044z0Q{Q6BjM7PIx+s=3~a8-->*2HrIT?p@E zr=gN9+#;;^T+%Vv%jrBDB_HORrKS~(~( zzoyCHy93vp#+=Y*2R!-4b&7eVNEVsQ#CVYdi^A$EyvF@=P#X3f<7A68D;b@+%9iJ2uk7 zKxgwiRcrrzo}+y@&(zNtJK6I>>cuC1&!`eARKE8`hO{=Lts0gHs4dG=fa1Fs+{sLe zDQO0<@gsP2r{92E00Bg-O%?ZaepIsOwmSldIs0**Tst@dGD&!+xF;j>fd#ZbTWt72 zt@(z)k(7MAYvNL?Sn%+wHQ=*E-dJX%QnS^UpBwFw$s;gN)?$UIHLFGQ@Qnsq_ zu=18tjG5fa>ZBxi7t!F53^zNN5BcenM$N79AzHawnY@yJXG+1(N6c+u^$PSZ4#p*Flj&9vJa3gl%Q zkCDbjsGHv*+f7pbx>#{wF1xZc@!Oz#mZ(dZ#$1kEs=xpu=%jz*iHm1#?y=_~u4=?k@c3r8uLWb~^x#VCLlsg-Za zlo=ZnJ%mM#MTrt@1pyOE&YOkoiVn-=Q`EjC>1&^HJ1d|@9?LeI>NnopT{Q{Q1B<^@ z844@_A*>i2d)&>o3N-?tvuv(iUTku9&l?Wmv=@dmndB2CnpctKx7#|fr#c*hGO*bX z{B6`v3~1wXR6(tW+3>A4lC>|yLa`~16?#J0(MnVzfJaYpyc%b)Y)PO;LDZz{6D7Gk zi*dPu8Stw8lWVbBcK-3(TIyVFDMWcTsl85}b;U~<+qi`62!*Vkml>5n8~k-|i)98G z=5>p!5%K3{lm32`*Nee2iOc2!{w_-TGG|hff9uu83zpyuC~Q-uj$RGou8zbI&3j2N zyQ`E_%eFoUJDOMjN1Y);0Kd}ume-%+KC{FNDeiE`5*N!wZY>l@xi~yOtAoED@kdT~ zZb?6+Ww}++g}#{1oyX}yjo$7cv!zi~JtTfApI6$`^htP|XQbi&YuU0!{nh9G{y<28 zdj)^<$fcpfimACM%hvS9RJjc9Bbcs9f?Bo_vmI2ZE7+@9Lzv4qj=6!H1t6-l6JasBoVQtnEuXdi<*s%M0w3p)XM2SR{-* zM+u#`rSsPxP<{1ps3-F@%KwYYftRIS9rRzmu2CTk2T>rsc1j>!2`@p3hb0Rd0^FA223}jim8r#v=<5=ntQ7JL5e&Fucd8Y@GD5QRwAv+oRH!F1b)~d@rGvh7Mos}Z zxP^JyVOOp1lTemR*~9J7;`XDI>prYnV6 zVIYC09%T3lV#_X-%^z`MS_{Q!xvR12NvFSmF11$SrW$G$j*ztc)U!UBu}|{bmd(YX z&RFixG&6Y|A!3qdjeL~8CVCqMnEal>AV(r7d%nLEdXUcHPP{8#GV}g1G_Bswd7R{A z<6@Fmx_!~eJ{2`?$U6^k)WUNc+nCQ?m>hcwS$N3FxD&#Th%J8~IhervW zJ*qikbSFsb$(<+{+ai(r8moViv;Au+OH;$w&qqM2f>Bzycm8id;*A%Y;iE_`5d9=E zXoOSv|UkmDJaps_*Aq{5B==(+wO|<*J4eC3D_Y{+J z-HIQ$iSdA_4gxV|g@U{j%rX;9NDC3s2B_h&_(1{GU>}7qi&!3)-aVl6IdJ%tj))jQ zL`ZVUUhz_;fNFba|3t{)gA6+yIkfgM#+UAzE6y^GLJmOMPX(%239njd02m8K_o**W z6Td`281a%xErJ0B6!ts{8W)T^X4&twb{?*MlLi zKYI>K#o{kCLk;&B!b}sSBPjoqj`!47dDu^>NtgB!tXCZ(c3glkJTdVE^A4;=6}0&A zgOcN2WH(D_`-<+c5Mj!jSQHYaiN}eYfDBtm^5jFuRqdyEDh-7#WxjqVx!lu%F?`pKKHy=t?PpWY9T!pM8VutK6&1ZnIEh?);2p2)iKBt@l1%9$xI%x<)Yimlzbq__1G=sg}mQmCx4qB)m?hlL_W_6W4?oBXd6yP z;irhq6!Q(bP)L$##>^Ev#>lq8`mG~Z0inOm=i6N9r&^C!&!zbahQYYX#{~@*qS+)& zZk?N0(4sl$KVe(~;mZ7@3e45az)T>UwE6=VY>rIn3l}&^wv|nk8@@Ko-m}c+8nG

      ^n+NT+U*2HdvnDTg3>S}VK3}cqd4Z#^axR30=(pMc%U6C z_ECd;pGC`}^gBdWST?mB>&E64j1xeKcCgDdazVHp>j}d4KO@y?V>p0pf$C*+C%A!N zsiu9NuMJMfZkLZeXj(Zxz1ngc4~w4QC#2CytYaZEl6OROLdL_Bq#0~IH;NAGaJX~m zFITQyj}kSN@*@G^hGoqDS)}NQa)eo#Uoe7%p3?I>8%FlAbfBp{k|Tm2-*sWZPTKW& zwSaA0&BMAQ%$JBbwI8h0q0uGO43#8DcOX@an{^0){y{LwF0I@$NLbB;@=Tkxf*`>K zvZy9V0YLN;Al@Y)YXC9hZp(@_(MECWye`rIz1tQ3|Fvd-DAvnYMyj-|8IqlLScqR( zG1u~Zh&aKN>!>_c#Du#;y{q%$O)pCJdJR~YB!SzO|# zuKc8|9FH#!yYHJ*QdehE7Q~<4R;?ErS6AA`-;H}vQ&^VcT!x2`VnzyM8S7HxC!d77 z1I_>O#(kqFJQW9A(lhiFso@1(R0$;-aj{LFpLXthMdOzil=Mj6C8l~niYK1ACuE=$ ziJqlV4DhQH>4m3uW=E4{6i6uIlt=L=*fH$jt#(ND7-6$fZ)yv6h!-qp(7c?k9p9@c z=y*(T^g`+lnGK)Yi??*9r{t#jEr?eldoEftfRVi zv%(8WQi}-~Vy=LGt%=PJ`UGCSiI}h4x#z|&C_acD&#gb-&nipQZe;-JQ$!}JkYUEez2pw3=o=b`5qfpcD3c%a__wJdwH^KQ^`Pl>O&v80~=f94lh%2 z!=~&pgcZ4O#{cgsmezi#h^11p>#BFkd1Uzf5WVzM6^OoB0OkPJmim2HFCe7rJarSq< zFVz=#$V3AUCEcWlEfFisq(`dFWu#gxK{YB-M9iPL)V-Ut$1?9~)LxH832a%NNu@zL z(AcHZOH*5FuYHSTs^MXPdlu#O3H)`|978piMjM*CKjgN{^Dgr)f={&u9A*Z>Uorrxxmo;-fs~r}hXC3;pRA zy!%?JKju;;hz4Eiy1yMB+t!Y~q~A+DtF8ebi*+4dZXK#%)G zm44MbVu@)+xlglG=jz{7@~&(fl!vh@T0-`}a;r`prg1u4pVbI1KRh{d+>+Q%)z;F` z)g_(%V^(C>z&-fyLn50OYYdA~?@i0>+WX@Uy4en$%0|IS2p=PHZ2oJj<>GOMG<$<~ zfT_^dx1s^$10;Q%*o;q7J%h94{msXg23;6ZgbzMMO665n6+b~D40{meT ztKA=aVfW*ilW+mpvQVuh^=?|tPL+B_m*w$~0aCAWFX)98i~T+^iwQzF!d9JzGa3r- zw#|}kMHR#dv?W(DHzI0V>GLQb6lE6}Xuv1gw` zx6@)@)2~C!#hM{UqAochxE$q zcpudsZCh(8u~W&fDluKtyz>|O`F~B+<#bQ6Y(I>|WOAczp}@gHqY6^k$ zVy4!W#I`XCnYAU^l$PzNCXv98f{l&;O`9DoIEx_lP46ud5v=oOsPoLQanvIfqnfGi zH@CUoBC&+Um(RQ8c!)UeGPu8@iFamOJD6Li1l2eOk$J`5c<%jYs$h$E*3sjtb!N(} zz$@fAF~9Yb36z$)(EWHPTjYb}RGlyZCozD8z)C0es8Bb~R6D}faT{lfNo`R1WN8|v zx3C&S;3rD&PFpU*v)!1#8q%y64v8w&G=Q^9HsUu~K%}j#{ZHeEDm&&tcEGIEU`@-T zRbFu`)3LVCRnl}UpPp^?7~ejA zB%-~sSv%1ZH5b({!@pr>wW5j@?V~(#x67_;$=P#!M7z)64n7^zud$<%tbaKhy(gK` zHr8vP;wIc&=&)?8gj_FBR~Sm)If-v+KP5EdDD5ms&QoWn5X z%pV7WXAwWpvm0`8#g`=63+xfXhL15c%7qz3YxLx-PshL!R1$^mGp-NxG${pU=9Lt| z1|DPoV3*1CIe42FKReUA6q86R_fuAObo}^Hmf9}aoepomni0S6I-eij&=pnJ?-sIA zMi_SbHR|7^)~;|^m|Ui?QOce{81=pMsEI55QAI@ zIau2y5P#RP)040p|Ma4+x;*uSQw*$85{P?~p`BH9PxDnbwc(qL`heKtmgVfN&a&F# zE4FIJxh`)ki!c$QH|oZBVsM3yp8C1X()9M|U0o)~db;ELp z`-uZtc@|4^lMScYyeY;f@22-l3o3=$GPbKt%bmLN-D#J)uQDN=bU#b@c#e7IFs;`^ zPy7O_?9tN)Oamu zU;Uq~;JgzXdz8n|zsCmr&L2TbQbVlBmQ5aR!e1E$SHwPIHVr>Ig5}a9X=8NSpm>+- zpy%|k+u)#_KnG@131MkO-JWnI+yx>fKSZpodP#FaLc^@a%q?jszRt{((ar+;~; z-|;b{qu-+dv1u^X5FhH5D)$33s=`%(z^d+awv~V^)nD0L{h>ex=RK0TUiCVB)TasV z?>1*mtIj zV*;&kPVCBZ-B3!H8VN`7lp*yq^Arw9Xf|CeB+ax7_Uz9NrMiq$MgmjAc_4*oRUHcr zkGQ+E*A#L53S6(rTrcAX=p)&>l-PUVT&5zg0OD8_zYr?Y$~nBqM7BMKOQs<05SU)l zml{>Y917L!`oSONL`Rp)_e8?IKa5Y}JgotwJ6KJld`ZQ@xejtiDMzy zePWugbT#LZq+_qN*3}6)EI{{8Rd%^Ckt`tmgZ8c4x{7E+y;1N~93y|MpN2RCSzd#= z*Hb=-G}_Sr*z%KG9?HrBr4}Z4W!@TKtAU4~@C1fASs6&cWs{trT+(w(kb7ulwqoMm z_9<9Ju|B=#-969Gsl1bs!#Ty13C#5t>^LwZUZv>LM%Buxr z=4KcR%YfqLw77fg7&B${xZ%NeE{Vk4u}7ECy9ppV9napil!v>lSM``2nFr0h>~Yi5 z9bJM$m$KoxBs0jsuUS}%H>zws{Pz+$jy4`2JJJ7&;l2};EgmQM^_VuwLd$tq8sm~l z&BGJ^!}HUA_Oc~Gi z_4{*yIE=nZbVB|L^FJVn+X}_5iOV%YU>?9>>ls(A#-Fk)a@?(P&7h%N5WpfYoopKN zC&*sJ!!OdamV(qxyHN6OB{VElKeLfSv$il;F48q9J2j`~{Rq~I0p43BoZOX!froQo zh~dU6Upg4H`mt{{6B=n{sYsL)*Ex#TSt9G)o7L%b%r)&*p1{Z0N)qfqggY)ZOuX?D zMM$1^%LOg264n5%sw3Z><&@nTVV_|S&55xCT4c4T(8Ofye7{o53nU z`<>Ew^)Lwpv~g@Ckdm$_ed1_Xn~QSJ*px*9!A>&ORZM0Oi%sb02D8zp-DF$Y%B@Xl z{-82p)DdHW06+lk7(fyL2m}L@)6zkxjFgO25GXYtQjngM1&%4M($34z2WmCc6r{wI zq&#V_fYntL0OK-C;))Z}%3_lTQcGUM55An7nCu*Ds)}2zfBAACcD0?7j0`-MT{NEm zY(N_}co3VFnpj_0JUdWSbg~YRtOlGuD*}>q*(b$>#_HVl08;lnKvhuk1vO&7!>bUc=7}cXSH8EtQ-T9kC`FX--X{p91z7 z`ZC-^+&AGIf?PFg{puSs-tGuei5moSdk8t7EvG+#V|3QJ7Af4KB~! z@xrTsg&MSY%amA5d6dj6w2Sm(13&a@GHT!z;DPlDUPFDY!V)8NyBhnkPd|Y-3zXZA z!rb&G$iKhBUM(rFJX?DG((ol-%tj-5WVT|$aWq}_sfkZ@FXf@C(n9^DPpkbGL&ooS zCOs0Wn}aL}I&w~Zv#QlwG&1(h;071l}1oF-~Ezz z#~~Lp%xILAXABdt;Lymm%+ro#!mQGD+wiz><#Flc|C}@yxm*(9EtuCIv$Pyvo?^qa z>X4u3<>@O(uJMLt`q)NliCq$Hg7F0bBGelUc z2IE30ZmZfEb37|E^*27{-BZ~}Bv$|7M&3|2+y~Jv%w5hx!MHl6fvz7^O99-`6L7f? zZ$tBu-CvWKndJNt48KE z_#UlF3gydTw7QlK4cIBQS0&_^X-Rmqq^J(c+Bf&S(P|&lH~F)kAZ&V~6m7~35DsKh z=RE|f(xdJmApZs~W7;<{(jt0$Mg;pb`c!einwJ|uB-nYb_btYP}@!XZ|?*knF-5yoFS2~3Fiu8aC(W52%mN3%(`}ogv0q8rljKI6> zf2s82gCUQhr08GxI-_`9tQcP`mm`aTHKl+GnpK7TVavZPkDwtkd6lndK2i8$mrf(n zz4Zb5BPZB)8@=mXrZ-#z|Fe}RgGeZUK9i~T7&rXzEQSl?8Ba&erT@=b%~ZO5s>xs; zGr1V)o(vUL6CoQe(6o#}_%I~6j2^%}(aiNlxd93hmD=B_!`fUzM481*vR9JLD6c5v z<0Xmg>Lageg*2-jdIta$mlGMkwRwUhoA$4J7|C_XNjOS`mWImVl7O2plHN!Pp50H~ro2r(G_lM*LlN(W!*V+wbP4^H1@3EZzv*%3*^Vn11n3L%Fa5lc*{ z;*|SJWPAW8HL2l4gUhaPkznQ-OEnho+*^%NO2z{<*J)#E+*-zLpx>=zku{5?s*B*+ z4G%!Pbk6P+$76r!DG^a@OfJAhQAh`Msy#POfI>=kHAEjCg9tz%TJyf~S9DDA;@ug^ z)-bX}!M7iY%}IJ1y@9U2%d;DtG3TQIglj^Om)BE~1IF`Z%IKIXjGjJ8%1l;E4Xq&b zxj+IHk>!=-Uj;hoY1Gp!u!dzLt==^dDm?X>jIJni<^3Peo~hmoLH`Hdr_s6QLx4kl zN^)L1!Q3c3;+sXdzR9m&CyMTuG4RrdIGn|5zIu%iYQClct7)FaAECSUydzI^>;4Yv`pb z#_z?wX0Ha23Y1r)N7~d}yas0)a)>@$QoR`DkxDW4SxHThjuR7y^DUQWF%O%dM@f}( zFAN~@C(uuPhCx#uP2QK4{PECBbj~Lq$n~%OD6cA_PmUQ%&#H8I%M(kh` zT272xPGgYBqkxQJwCt-~PN;3s`5APZ5J{7*?MINkNha?tGLyLe?7~Nc27qV@|9Xz3 zh*ro>cmy1$O39$xo6U6VEDgEKnY4o8y(}Is_>j~pj$7Q}{Hf+k`HAK@sERFfFPE-Z z)X4PI3T@LieSF0KkXEU)R0~aw2(sW`4>mU?#25U_PIuZiaipghp;q1SN@c?MN-aN*e>I7*HA+% zn%C|mF5?7chWK9^Y6{#@&qhJ1`((9JOiCQ|oVP_xK4a{H47IQhQ~M{$f0kZywk$Sx zuc(H<&9gmEo=ZyEXvIjrW=^c-C00pVc1yrnfBvGR($(B#t#XUwCFJLc|pwan#d;oT?Ql-m1c6#AF7geK)xQYZ!+@x?ihX2{z);Lcs@NJe_4L0bjp~liy zCX$y49_&4?qa+5FAz>s998Ttzy&b9wNKM5}oVkQRGw;K=THd?n)*aI*(l|A16;9=Z zu=kp-Yg4K!AaV#3Ck3tMe=z;ugnw*2Ej|rP=Rmlawu04-k5vy0k5pu?xl?h)kb{ho z9#I;v)$?@K?t9Jp%axB;C&?oZy_OR7?Wn8q1L^!F7GwSh7pbq{Gsf-kMGFkoc z__w4yDktuu=XPT?u&>>>Iu|3ZdrXO?l}X`Pr=zn(<536C)dcud=!-5^iPOm09?SXf z=I78LP$7^_hQ@^1IZ7rPJ?%9r8~W-;{P=MgpGMd-oH|;PrW@G}STjS*Fp?oR!)#&9_Fwo))G2qVw7140S=>H%@Qh zUr2z?kEK6V_xiN^&@B-lCqedZOykFJ%9nhHv>L8i3?s)VA=Lu4kK?s*(X61mw?9hM z-p47frG;X&!6)28n-2=^Sr|K2@va_dR;p`_#}OL@rm^82OJMoS;hu$Bo{DmnX8}5B z9!||;lmUr#hFM4>9jX60j-M}ap(1f8_HNWormHk-8lHNSA6lD-y&qeS>JsR`$esq` z3cf3|;PW#(pfFcW0#TIM&jM|&5Ev*fsxdorH|<20B5W-C6IA-VFAG~K7FQ&zof%NR zspj!PI^2=C=qhb)lNa77)4WDjqE!)#3H-O@PDv_qg8P2ywIcbqrDcvAkVi6`N!BOW znQgHJ#|n3wg^66q4CZ)KhES?h)x_&~v&l%MC8+JX2K!?4Wq%aSLVS{C!Uk6DWd!`B zvmy3Q8?3bCqA}C#f&!fMU=(v)d2k-;ZbQ|SHW~JuI(iZ{rSI&BZ;DQA-%-)KHHUTxbH$<+?1Bgfm^hVH!taYO@K4vQ;0ER ztXDUW4s)E#NVOR&xzW)Gov3`Kft}RPV8)Jk-5?@Sc$R65hy72BQwa@BdNe-qz(_*wW64)30R>Vk<^SNZ+BC0Vl*U`k_iv| zr;IxR{r$kcemuC#2=Wv-*3~lx7=v^Hho0+>faW33rsrlx#z4zMQ-ka43%$U}BnU^> z`-!c|sh;hm`H6w8_3@4F-tOhuH&-)L{i(}3!|9t!cFU72Ya40lPtKPu|Z4R z{^eXUeVoMDn)ULEJ$0zSO4w7dlXC3CENe+9J2o7gV5xBRDB`$?H$7gs}l+AFf(`vFd=6mIV|MtxVK1pH^OCQC3YG<*wXqF}aFXgEOgK?xVTHhS}do zVGdH5^)>zZOe+lXLR-@{hpTeDDvZZ2*33BJ7;K$qxqx5r2Dn={Xg-6pTu&hP3sh+!~WJiZG1=*7-im zaNwChps>w-CfRi(t2I~L7 zC|4d&y-KI4b2f@!pZ$>!P;HTVUw4)DdNXGu@nm0D3);gfKARfC6C2tpv?#|NJrJ232$Yj(GvYD|808XSCF3=-Sr{bmDM>(KNKUF+fed&SnW&LS6Uf%a>d!zDY9u!PyF~FW!8&V{+q2hO~s7Wsvm9%G}GViiJ(G{si9X^Tirq(}oa>_I3GODFcpNDTv znCKof##=83yFXb;4EGV?{2e2_19MuXo)kQ~-+MGN-0h>lK*tOXdsk*Y!>Kzmp8xQ- z-BY{4S$)Rb;hj@4gMW7T{SW#Qo{Z1Rl+0hsNwr79n7#Bd*NzTWRArRdF`&!O`gYUb5Jb6Ei^`6j5CL#ze>Ab$%x$ec z@@4+EpKyR9Ma`b7dM1sGQ~air_iN!3qtMgaV?PpTu00B_$OSZ$T-A`~#Y7o6Qx(y{GmTnoIErjUn}>OxVJbKK5S+%%RapwBGS zGa^t5)*-Q&Yo`R6Uz>H(-_c%;E7o;CCi0R7JlLLER;9MUC{O;>g;RfepKvxgErxUC zcY!84S7Z(8KV0#?jXt5DxNPU$nXm!F=Ix;xh0)Z_Kt&kceB=BHK(-A^W04nlNOTSSlo+YagPv%w=MA z6I>LL_aWHmqbtHdSK>8`gpjsb?l^G;0dS}lqB8UPvtyD-%L1<(en5aokclqa);k3` z{{}Ei)Lpg~M@>Y?y?g6MGnS|$r;pKc@LM_@vX%cA?%AWP9 zE8E;O4#kny_uQew(H^Ck5YMHHJ_UHz}8AcLZGw%_m9md{0Kak18qHpU6cet&@nlH)sblR;Nu|MNo zVOAWrK{@8iQ_ySX2v0q_;a9VW(A9c+(UDbWAeIzuCrj>V{-QjM(INaJwzyu{PjZar zcyA{v0*d^ayJGRwMlWn0@`iz^qUm$Y9$MkeXu=nF*W&PrDm4qAbTL}(R7*)Fnrd(Nk~Yc|FDqBpd~`;>zs!zvM(W1Yf{;%a<|oR zWY;QO4O}|SwT^JYl_Q_ZLkKE0Up{pQ1gl-ls+r7+2;55Bu!2HX~xnD2|{u zL;%*z8!*wapiR|as1Nn1S%9;KN5kC@RmOIMUSjq$3^Lm<`P@IpPQNX&wskHOJWzcV zS3AZD3(gHAcB^_N+!AM*Xl1Z8YkR?`^^DkMY;qH5a4<&3*%=hDznjvtEuS!6$>hPX z=!N*J#;;R9ZDzZtaY$&nuQ!;4c)``zQMQv}uyI@UiWF=V;k*Z*d}r|@Cm~(h_SDBx z=0dVwTdDt|)xfN~PfoGYyzvE@ZNrO=&nv315v{DMR|r6#ouXbA@f%IXJko+)%zXFG z)>bWC;ftrmT*&O&N{d-^W&N9bjI+UgP0ZeGhTK$T zMc`aQZ^QHT_EM=r}YUvQX( z-<73??g2&D&b?cHhrI`*3ui3v@IVjB1JbZDf(&t zBi~*=w~)A-Wq~X@`L4KXxHo6UHlnLdLv2*Um7#XiC;vf=nD;#Ds}Nowq`b%v*ZWN=@f*I+^lG z8@2-!s{TF+pLGXb;)4d$2h_t6?pxYN0A{}!k?YqX#ix8_a5~7jAmcwyYpmGtl2g7E z^)kQj;RLO2kJ|TLLDAkMJ58#FN=p-Bz3&(9mmmjIDAco$T|oM-pa~}zT25qa$;_1{D0u?x<8b5O*bG#fx7rizEej< z{mbR1WFb-lWi5B4ZOd_F{W02#mE0As_G2=%_Jy`4BgT}H`odA*OXEjSg5epR@X8?* zeAk^%O6F6%x;@-N0-Qn1v`;fLy zd5!9OzXwvkm}+L2@HnXRR^VwqaQS{WSNo4Zvpq~Y5yla0a(ApyLD!5oG!Y}|6y67= zo?{UCGhV2vnMfC?h|#834NbZUkX$Z^Zgq+M?#g+_B+?@Nu(nXNk0iKcgzDiD%im?5 zIXXRYzBH$&1uwDaCoJr_!O|!O5rhDN7cS7VopvThf)h& zK-~~>KUP>0`4t|YIzyPmxBDU%HtyoWXjN;eokCQyI=S2d$%zM@@_Ax-_F3l5UDz?gFw0GOK`e;2tH{rXf!2lCdQIH7G$D3suCjn`vjJOGipilI@NRO0z%Mbv0I@ zU$JYIHqWG>6B!`x&R^upp!|#NT~HJ;j=?BYN41lgHCLpj4s&Q)o(IPs!*F;ys!2vF zmrNsbmq!w7iV0@Lc$ToRakXY5Rt2|+%}X5wLmnwaWjY2m=1k`1S|?{-$`|kBcdkkb zHTM>Bza&w3Vg?WFxXa_}O=0SD)D=I>K+lxOWC(6Bj1~{Kl-UP8304t&j0=fta2AZp zIcA}a?7yYYbfGEfqi;gn=2ymvO~^WiYnA7ym5(OqsH&b#*=r0uQjFv2qpcwdDIVsw z<#82m#1=kr3oPvpT)^qRkv1_tlPs;g+kz7HoItM%5}MSIt;u4?$F*M4fXBU3Z2bNk z2eRP^c+5H=4`lAWUwGkcAaedl8>y~XjSPzLcpgB(G)7CgBq)?jDQ6Cv*N(t9nOLlH z>|m@S1v{$OI12i(@AsHwE3GJmgzuqp2q8SYCX%lcs(lg=e?MRiHmjA41$FlVD@HJc zD7nobeu)w?7Upgn0*fRCvvf(f%YE>i_g} z0B?7(D@1ZTUyqHS#Wu!spD2I9tepEKXp>IL>n$_H#)4@)d90g(Iwjg9$wQxJoE#HEfEtvS<{KqI*{T)EnNG8KqE?uG?`UV;rWa zHH4H#zvncW`)M+pnd{|I8gsMCOW`~CFPy%_Hi8C%Jv#{s-xqXkzNgG1xF2lv3Zy_r62tQr z;o%(!#eyl9|Ma9YTvj4J5?<{0SCnVt+yzMHelG%c$AA)VKduMcTN0H|Y&HIVZPi3F zCZtfJyk0Kv+ML_l`1I#~cTio~F**NhyCE+r-z%xVK^~?D!8_1DlUNNk^WU}_mvV(L z^C#R1DVO%2YVKcb<%M&SzB{;^VP%v|f3GO8$>TMZy^@TF>+tNKo38ZRP-40q3Kdc^ z?kB3h3S~2VUQV3r8g}^5ry+g5=>?@j>|zR zckxzA9L~6wo2s@TU{UV`)!(_ANEXhLvegEyItn#;LLCg(S9rvBGo>;@m^GL;@Sa;9 z&gC^4KaN!RBgS$F!AEi~)}IA))Z=C~EGcLzmIoYU7-UuvnwC3<`}w~%iOZk@3m1Bd z1oN0X4nT-Iv(fcPL3+x~oi*BQT@;sju&&I^D=3>`4@R{f=E!%8oJ+N)sucj69wyow zoP2CX2`U)h<5@W530l3pJarQq;xn~IK@`fQVOvib%3O93oOf-8)b)@agFT-BPzmiS zLPYwOSEf=;Hw6eNhkol=eRat(&LjQCq)nx6%gr>^`nVC`A(7V@LH}peHB@9dm{E(Y zvD(XMKbp46n(yBA>#z$}CPy{952uzSJW!X{LP3N3XX+wq*wyB5#nS=49Y_Z8s2fd6 ztbLE$nt&)pfJ-}THL?Ce4k_-UT5MT+q^CHFWH7(*~&Ymvp}VV zcYWB(pCW7Y8Mv^j5qOLyXZ-ry$GOKo9ERMY8UwKgQ{DR4C^Y!`0}wtr;eQ)hQ^b%g z^m9ax=ZJ7?XnKUR=yOUz?R?46=j~Z^hOxtvMi-|3?kk_Yv&10nZ1RDBnt0``S!mK6 z@Ean#%X8pgAQ#k%oTIgEM?MG6|Ana%mEktC_p6!bR1Hl*CL066dqM8{8OmzWHlGM@ zzcTFliwmyYC&xmsdxy<`2P|~O*3~G597UK28@97T#eHEs`mcZLtA6C|(fb)45?o2I zMmzj0%Z19qC^O}S41IQ}#B9JoGG>PrSY3LmrdsBhjY9Xdey77Za`$lKXSo}^$-X_h zi7}TJ8tC({am6xsW&A=cRcx#CBWt;BhR$XG0SX+G{GO5PIES7f`qC0GB;gho>3gKm zBT&pAA~ME>QB`(oN7-Ltq`C7rX;x`4Ys0Lr;~+|)_E1uDiHyti9ce-Jux`{}kBS)% zmYMgtv%Xh22g}LH1~tia!#jed3m#+j!@g4v1@ft_^RX00?;7PChW{<~4s*1^JVVOI z&F{~G*cu4+wv%Th(&@RPiQIf%y%MW(@7AhARkTdf74DSh$IuQejWfpX(tu9f)%y>L zz5RQ3sryy6*F>_T2b-)b@HJD_HDns&9x)%?4(dm3$#kPYbDZrTv;>fo4;eli?)}(o z8W&h(q*qG}!vCvmnWyBaQCy=sIe!V(ak({x*v>8vXz04PeYVjxtC}IH03;y&f;*$Y zw?n;MToD>}@hmxVsoDH-r7o3S!gUaymDD744MyHFjnTm(a@s*X#mq4Mz{nTulDJUqL%6N%@zZL)88wW!-%Q) zm8+D;bdHS;K+1T!Q}pLmT_3}o743~c;|?hftwU{&oI!t4CSk71fWn>=$4>G$fg5s} zgJs0!U+Wfy(uUtQQlol0xQTW@M2v4f8Kzv+CZmPO&VHm9h4`Da2BsNrk+*sE{yU8Y zYwN%O7WUzJp1_r{+t}%}5J3u#)mv{epCNUO`_LHTpqb}Fx0o$d#LttCZOP{sJyW4M z5hyZ8tH@80z({IdNbAOks4R!fw$D8TvF~7w9 zsg`m?Y`W7`gLUT(!sXT_B0Vl4h7Ko&}qzw{OYA2cOlX_d9$eXww}KK>mPc%N=x6Fpkh06=?4DG(HHeISnj{M ztTmmzUjQ%ReaH5xb}qj#y4Yu1ArY|}TolW-n(hVs?^j+D_|9F^fjpi*-FP-ZwR>&l zB8C1RkxG^7CSs!oLrRLA6BTVyKMYs1@6g)hY}&FYj2GD|LF$#~e5>QFLyq^Y=&p5- zT~Ugwjj3xj_lRGZ($D7HLqhIokt`SfnRyiTZbq$HGt62xd%G%=qn-H4yKfn`UWd=0 zg(`s_LB0{DSybp9ZlBG_+TO%6Z%8mtR`G`fKs`ePu2;#qV�s1xUsi5!G^5TESsQ zd_9-s=PHbk%?K+8>dz;|&VUbd)`hKN*_*DlXFD|ILmA&K>BS($9c!E(tw8;2=`8uF zeRus&);K7Lcmqv&W>n-bV*-sBS)*vL9Dcn-TFC@+_T@|Scalm8@P{WrJM!2VsH)^T zSh1ep*EW#c(n4hq^ z3`x)*(6YN)gf4m~JsH>n5n0!&NfI3cH{SYl7R_%*NkP?z`aF#ENPtoB1DG0XJQE7J zCTG`$Upl&_xVY5xGY?rKk`(QNBX5%Zh@FQ~Zj3=T-74tMNF!mD*kw(q;+0ulzVIMS zllVY{cpZA%t+B{MGdU^n04{u6fcHG-aNlKQ zWi0CXOgtD3g4fx`RFplOM9V_e&W>cgzUx$DDfPpM(UbC**CrM94|;oX5vvM=S_DS{ z#gib9je~%R0po5nb=8sJ`_tYzHG*9gE+TlBMx=M!4YO}SfYUPgHC?2riBarPxVox) zBFy+#v=g-dE`1+fiC;6HUuPIEIE94A7G`YSXBAmiG#g_{MRAQ<$Zlj(o~RmqszDU1 z-%>x%WbQ;FA&`3&L!1yd(5J* z)2@yw4?9@z^asB&rf2}d2C4R0-x}Byyy4;p%;FkU_-=WCrNJlRG>YE zA!Q>kb3jgfjopCser_xc!Yt-Eib$Lx$+^~iuabO+%O)VoX^WR7DZ$+y8mF9x`^=ca zpdRH=_u#NMNk;IIM1vr({t}{V{%8IdWE!XVrGb0fuspHDt`1_KE9x|>^@q! z5K~H|Fue?tC2gKqN3k93n`CYP6l*C6U@*RmonIgb-fHf|<~%;)3Uv zs7`oQLB*4h@Kcj1iHVh1;r_==jG=pUKPjS<9+i2>%@wQstVqVwgWVy?HlFcuP!-iZ zI9cj2fT9C{tsw1mAs=E%fsN)MJLmcazpp78cUX@I8L7;RJ=!(!1?b^B<)|Mg^>#+$Dk+>WU zpZ$qLz89x87_XM?Z#U1lUrlj-esEvo@x!?I`>~p=T0js8s13-@$pnJ{1)}+RX&Gt2 zG5{nS2r1Jl1Q>(sTO11ufHf5@8R;OS^1-fxhK$}Sv#tujcw={0qg!oDPIhNS?ecgA zB)zKc`NZm*iN^USt7$oP1AALs2ql%4<1Vo7^tQJ}S(+_}CcSLsl+` zN&Bq=lF>f+1*<+M%Td$TyhW?j^tM$=YcEYI2No=`zI6YM=JODs zvX(JTCC*oDpt5Sr;eH4OO^91-8!>5c)SihJEeC!}c6BDHo3FL!2;^%HU3$`)KRBED z=@QA>sIUikj_a#GYB94dOaCR^PFWDk@C6 z_6Hu<+iLzYuhM4q6`oBpy*&=sEz6^``UIPB8?g>PMxmb_bx*}_?cKQUN=Ic07|fKA zU#Jxj8<_WNHnC(gnKJQ*3Yi^tJQ_2;T)j0@|Er$QKVuw?M$JFO#qw{$1X3h4snlUn z>)KcBB080Qj`xM+PmLW&?D2C!@3_=i#LxyBr4jt*c?+)3sK7AZ>dxSGhcG+ox$w(U zfen`{iD0zmy|~`@9(6_6^H5l4RmT5A*;{tCp@vb~A&}q@f_s4A?oJ6F+=4@Kg1b`) z?(Xg`#i6BwTMNaV7Prd5p*`(ky54tYt(o~Y|Ki!tz4vu_ePcAX61QB11F*T?nWfpO z&QWS>@G4Q2Ba%7bBb&0Ld2^1T4^xPy+aL^w~S8SjKej|i|;B_ zEAILYe8!rROW`fAG|iLsCGzvC4QUBDD->3*SlsSEcSSxTW1O7a$hgG>TTFam8>xS6{?c5NHol<$S=bG#g??6M#SPD%o5b)>TsDs2 zyGP{bQd=6nRUY@QDM!ck#|P@Vr-Y?^Bl)XsQ2`>M#7-*9A~EP`dV7(h(X zqv%&GZ<^xyjpBx|Yyz|i7y6iel}>YiqPeN+;g455LzPOcB|6!XKsH1RWf$p2-d!6g z70pnt7?@f2-nrf_LLtaLuz;P5OZce+`38 zGrBd1zs}uRlce8p%gx?(Yl`G`DtUWL>#&uyg8z6b***gPH+XA_6}RcMd#BK57a_B* zwJXJ(*q|%~U-KlF^>Pg2Ps&zi@Se1Pqi*D!5QD88uwop9M$zcU;&>-mQ zVE<4tW`kvXZr`!Txe3adCz?4L_0uik@uVU*;sYjnf-jSJNom!wsbb;(PA4fW8|tln zzN-3|?8x^^i8cRQ0Jpbsriwc4k}cD%()%a)%aE|>?9t)a5`Zv~et}kc-sKg2^8y&f z_<_s}?l^M2J1v@&O=V>aZ@}wt)*xlU{_L^Lv{;p(Bd20c9$#Ic)~3ro?1QJ`*2^Fu zFr~Wypg>@+b-9;8%ExkRC_P%EU(K5R1f>G506Miov0V4UcSge4onTpg$gNlVboW25--UV z0rQCTfb4Ds8rf9;4l&iA(y>|DGq_jA%8JRvg2@ii$-qhOX0hZr`)ad{GlF}PTy8hj zBtAl`QHctF3MY@aSCldL<|&fa?oaeTzJ98qG8^Fz5#s-8+!!{=Lgo*^02gLB^p+@< zu&<1i7OrOAf9q5q-FKDoz+WNuTOz`aj}wMrX9WzBLC_)9OowtCys#7rv-+C4F<#Y` zve+WUNA;F9|LsY-B({R_G0lS+Lqm0*A+_cv-$eVkPfbfnEClDzgj{(%xy%`C!S&8t zVJgDDM=juT5(kqd-FFf_iPVb68eoL|e@9bqC`XR){vCC?#^IdD{C0TGC7V8BYfq$k z%^_>ExohA7Z=$CZW8h;g(Wj-zsk6_iLLazmcb7nkX2w{0Jm4`WuCt8~B!@gH7&(vr(Y+5BMXg}?iX%afpJfCitA`Ro9%1*(5li(Yp!lS990q+gxzca$e zH2(TUOIl9*X^`jRqK&B;T?D!=*jP3%0DLgIV}31HLQrQvB!dqGU;ua=mh%T%mDKC%_!oWYF{C$$$yiWhf`87iCYVAPPeYidyS#v)n;fv zDh>;~J0`9WHqIWLeA<|892VzDnd`7StZHR__fkpSw2rubd(_`?p3Z&Rw~Y`P3D*NQ zBMlB;SFyAPHJ&ATW)mzLWF1)a(A|CF`NX!LY%mq0%gOaP3$}EH! zZK8EL&FrsU>RXsFF7_II{AClff1zvh*M{X5N`_^gA>3p`?e&Dl-&m#On|RFP8#|Fv zP>5%0GRhZQdpfYfKc(!RRyD}eqR9`ZN{Z9f`;xzOx242NPj1sm=OR^l`9*>f$5E~9d8u~b*E&EvT10k~=`Hewlmkj!7?hMF~{ zZ^NvZpjr{nGRO!yVP(<`#=}p9qVV<0)1;Hybh7i;Fyab^;hy7cn|vcMuy@BX6-$vl-iJ#mT99Sb&?SVdbcz5 zB?^QO!-!xiE58_}54c)5(r-%iuU$B(cEjcJh>ND;T(6^LdcP)y`#9*iq=D6!9EQeI zOFE37GD=mhAi^_M;TxhT!Y>TtG^Mk6@a@lDL*Ct z_Qz2L1nyvnxlbd{Ac}97iDwkCQezSNU3eZbrqygdUSTP+j|1AV^s6^d0n8fn>Q zD14{tTj$ELMy+$CQItSFiZ0P9QIkLSuBOcf8;&6e_^agO3uv$xfQB3L6nRlb zd2rbnI^0^b<#mnDL!M2LP=`zA6^@+sm`XwXvrpKBYsLv7F8mt89vpClpNm6FpL`(D zYZ^mn{`YK+%Re<7EhCQU8G(g}o0|$d*!$CcU+|rA*>dO+s-oXsTRP(tmV^)oz|6=f!(5vPZHpD2n@S9C z2-)}&hl~la-zrnyJuADCu3nF|9AWukB6pC0Q0DTM93fqU(oXs6Oc_T0SLdxM0@lM( z&{dgEy|g%`uiALW8ZTvZGdoHQWP9Xt8R$i&}1H~XT@OYtVX-& zQDnY{BomFnh9t=}m8A%WDWVKHEboX6hqDasBdQXgAhJuZBVrRCXS~%w_l9 zvI5A76(nAO5wcK^Z($>hg7Ml?6SbWq*z9p4sSsYtDZk>m{#|%d>v3U$8O0bMEB|tN zv1foeVlxZqvmi9!XBrkK8YCoND*4jok}0G_BW6L2g9cwP|NSO`7BS9GkS96iIf|K%_CyYLu(ShhS$wj!0GX!&ikPA% zvNcC7a^1sa(@5;rBPCcj+C<{_ehtT}rYsya>X%=a5Fu^oE7nUs34OtAq1-r?Roh*? z3N8$|GP5Qi1@+N~7%?nKx)laTy@RrujO3(XN%I}O5T*<4af}A^E6^DdoEQp4W;1j< zS3V?h71LxrHzAQ}u$0YXzJg5gnsPfnLIrccj3xK6n zu#OM7w*<$+wpGfg)f|KKDg}hs)H=*#t+fZnTLAp;Ig%3~^p_O;|5uW$;jVtS8^yQ% zRBJET&^DW{DK^|KdDE|W4j45AWL_~oC?LJpZ!R$uu&x2x{{lW)k#G6hWI@&T_0NL( zKKrm*q0@%I-C=(ysfTy{W78Fe&e0O~i)Q*b7zcbz91uS;&LuV`IXXEt3gaC8JT?JD zQ50W*1ZNbcCY0rsW#JPM5)lEh+kv3A_IAKaK=;c|?3f;4e-}0eyZ3E-QHKrwRPp=X z(Y*Powl)C%yTy)Wpq2GoKt(U0e}8QEodbE%;o&?LX6!JwqhKkn7yrwChb!@Z!rf0G z!$!~Pym^(;PMkOw?tGby-vhWgHi$$2S;$)gyFAtJnJ;~)o+9eW!4RrGyEk$5X12qM zaxSelAaXH*B2f#XHQJ?ok}{SM!rwDE&f4{ZA(IzmC8aFS&+(EjzeYe3nKb6XQ3z*>24r1(V?4k$ zMH8=}E{Jm``-o7AsSo&vA@9l|;iah(&(NGmYHQ(m)JTLHYCtM?+to!5e{}=mbMUgp zndQ>nTg1-t)n~Fk6AP*->u#I>BILJ(_61lSs^8}OXwRFfC=+Za{A7HkR=t@_l`ni1 zH||XzNsX%=R8yNgRKIJC;c_Av`ztM8<0bi2Qh*3HC|Ov|j7U!RC5!AWs?$)rlzTKbZ$wTNAz#7|i}iN0$km@&N%;Ug zp{Uq7Q|Q}RM$j8P=VjCnscw56*xjn0KrPe{afAvwhB-2Od zXwQwADL>h%QlrPL&=$H`#<={3`=h@DRjZ zSOnJo5#}aE@;i{^uZ}G(PKwFX@Qpb+wJ_DqC*7ig)mi2^bEOjGe2{BxreT4!R?wg0 zW~WeuA15Q`=+%vS7Cn_COQ=bWaYjM=M>s^`IOj@wB{Swo;b}sP{*@FY zSmVm)cWAP9+B1ThB(R?54N68>ZM5T4qsQZQJ@bo)QlZF@At7P=m_zdxY@A>cZ16_| z@5;W5G}Uv_?)tJUhTvlJ#pX`ik7Kgck*6sXr>gQvii>1mlNj!#HLxh z#qO5!CI;Yj57&SFGaJ*=|E(4#h|(0w`pMLeFGz*5QPe7IJ1j?Tm^2J*zf8nGR0Pqk zWDoGpO9gE7GO3X(_GQ>%6!UJhXI&!e0JBbsB!#S~l@{YCdkSWk7T9nUDxOUVr^*rukc_eP#eMZHC5SElueM^kT+`jI zHci*2TX1DFU6~K5Sioakxhh@9O6@v*{5ig~uX$d-5id8QsZZ%^azk9!hiMQ#kZLF^ zRlc~yqDFtB$dX;zH>J67;IWoM^J$PjabPw9-9J`(c}a+ISgEjW=;ORV@o1w*Sveq+ za1xSu^5=E=Lwizh*)90p34i6!@6<^O>j;|ISY&Y);ACN=4J_iwsU5kfaErMGabLaq zxSIoI#=KBfbWX)JGgBLiABj<6_)TKuC0U_b1P@5`NnVU`ENArX(nIsu83&zbkEMTC z1?npT&@S>UKac&We=gpCrX&L#h&aU2?nyOB&ivVRr73YuJh=X=EUbeni6D+;7@7pU zUO`2%_ejVkL6u3z0%h2NqMVsmldMdL_=aMH*)`?Qo zh0a7pzet-8_q`lciQ>iSQ?|{|lvgc%tV#$0>XJbN9%*z>U=o)vh=zlT9nAMEZG}am zY{FF~w4ZMNPztT7Blf(o^w%6*%Dx*D61OR+GiR7@@4=-c-9^u6ek9?lyh|^8$NRh2 zK{;FFvydm7rr+IdgR#F>(J#ALm1z-1-@)v$fJB5%I=*lzUY6Yby3TOE8vLnPRgV=k zxP8^iRk#oSvE~NBP}-|)UREn~HB#8_EC+K*pC{@b=HLsEh$Rf#hM!D{SgX`q(6TUA z*6_^!*vO{Jy!#-<4azF!z%T!k!wsV9Y$a(i5e_0I$vb0tlLN@)CZg4~PNr zN9h^ZO)Z*A1;*1m@*N4H^%y6KRAXW5=7Ozh5>>ly`Af zCyr7APJ961MU?k81#5H&c9&EAN#-+OTO%}K{nEvU{wgvP6VC2qZ~lx)!WKFVM9HRZ zv{(YAMe!6}F+JgTi>7#V%&OV#v-UKgMpE~l#pkJ{gT{+`wq7q;$~DvPbWrIst*QkB zZZusH+6-12s$mkr4h`1i5Leim@*9^EP-wrw*FR2w_N0h~U?3G&pO&1qvoAZ+uJQwa z&l8jE!)ja}mVt4c?vkqjFop38<&_wVq(^)=U&+|z-t~?t+Ycx~)r4jo5SytigZ(B8 z&lGlHF=Dg={b#Pyr^TGko~)^jmOw2#i9?*IlVJMJ+m2DO)Zp)t?qNJJAIx|BO}Adp zn0r%LLx-vI#5{?e?lLUBA%5zj&jYjAmJ*}p7(N>Uc|_~!zBJK8bM_O1JCR&`r-g%B zPb=PEDKR7SXUH8IS{LiQS8Fz1<5wbQs-vC1fjt}OZ2qn6)|TMK^b5R7%@iKB{i)9+ zt5VfL3P>_{j$t<=JOAMxA!c2%#(rC&9HEZp$>;@7;>71f)`kC`&7wr&JgcJbVRl@FJ=~f>OC=3?_;|Resp4+H1ok_X$}dbqFpHob zRDSsG@I(GMX@zxEmdyVR+DNSzIEzjjcf6im%LzT#*~Y6yukXgfM1@Mq!?{gppX@(K z7`zn;V-j<$jPtS;V@XD^1EFjW>*5>-ti+~~^f#J*2L=f)RLcimDcI6eS+aM8dXOcFl*T}PmCCmIgq$!$L1V!L{o_|;#pbwD6A$}r*b4H8(Xxy@Ooa8 z)?FLt_K2`jv45ZpsvITZXQA(Pq|2J1yRS(f5@Y5OP2)TyHZalN^DzuIWN>%E&mXYR zHvn{-Smi7*zoT;Vh~YoX(m4h3R_`UAnv zB5udR-Z|oa5{~4F%KT|?t1JWWE(u)Cd`|{3&ZR2aLlz5L9BLSdOQ6XX;L8UdR~U%J zGX5#4hh@9usy`e`uht|M(dE=!n@v}U8RxW5qGGPye8M}{Py5;&U=L+kCS&Z1p?PLv zb}yW#Y2xIUUjo!mv7?X{tPRS_b5@V0XnWl?zao^;;0WYW!c*!etxh!Q8!%t%q)V?K z0nMS*;uVBU%#fts5vz~x4H%uAT)yZ-DKbsEXm5BXmY8`RBH7Dq%?_;_a0lwYXhI5E z8q#CU*kGM1v1%6B1{<|e!fb`b-}YlFSP2$689wyMT4*paqL?49;|G*@(g0-gc_k_* z46ST3^F9cwDoKbE`G&0zwh-0|LM-RF?6iI+ga)XfdrqGl47cUt2WPX%*3cvzNM~u3 za9z7F$IA0jH8zWG{a>F(a)Z>%t*olUe)?t~ zR2sxkZJDkb0AyLE1Lq1**#f%4Ai%FGjGP3g)txo3boe1!dS@W~15kINNr+-5+NX7$5N@p2Q-0pbY>xY@qD$${U5h< z6O#K0fy)j4b;Q;V*<3W~`L*3mVnW2o`hYM;I`TAh^s8zccf;0)BOS2>-DsGBcGH({ z{J(jGn0DO7BfmQzZik_w@#(`oBJf=k-9cdynQ2i`gvvx-*w}zTU{QGq2v8oFj%|rw zR8j=2E-7notHTb&E9_2JZEfmsvn(#_CT!^*de`MPfvheq2DHt&&CPY&cPuWd;)Z=% ze?PUfux`27VtVAYwv4S>f`8cV0p=s_I9+U={k|3!`EXyRy(QMwg4b&#&VgIkTi1kllO$gp@H6RA zcvSsMi!vvJO*B_KdNQb1x9=ix-n86*3WsKcvyqm&><>g0tZ8z8bytN3} z)eu&an%?N*ecu(Gno8F0|MRosbs!#VLty1Rgv`azeltu$x%n`e{D-{vvzr&W*#E4E zl&LdJM11@3T)WZBlihNRh_dO!f=4>`;5xa$`mWoWuLLcXo@Lj|NLEx`bOUy3c#1^L zw=VeM(1MIb%M@0b)N1$jcB!xc@7%)hh@GRm#V2tWuU7u`ubb>%B&JuzwkpR>A4yD8 zqo$Vj?H&A8qb)e|e@ydB^ZAiHIb~APtXple^x-?dh(1iTzuLvgx950K!=y#|-`EDd z@(aUp;94_kS!kWCu3839<7h*jSJ!A+XM0a&P4j6ye=2aVtaA!!JA7Olt;$k>&!S== z#hP}$I=sTGEaF?ianly4r39Ic8D^{?3P!Po>YL6>{b6}EWA`dga?>uyPL)KnlHd7D zQBG*?26CndbdvGQDsYDNzZGac>RC2Wmje}wX3z%_)!HL3%ukw_DLl*|vV1ZHrV5F5 zF02+&KJ{i6EE0x0Z2B+2wAvah^+v2n?eTN@rVw=tvaW)AQ;Ggtto;~?>;(K7D(${S)it+s!ihLwW3Dzf{L50 z;t0-}(32T2mvM82qYdJnl&K-#PkGj5mcV^!LSJB=29yi<-KkpU$FE0T#w+Oq_M$44 zG`E1ZX<(TJfUhg9##5*hKt_DTeio=3!d2zl0APiCZco>w*z`CZcytRL8`@crleC^v z5i1%{R?}?y(G_l5XiYPQRNOfj&nk7NMWgHMN#nH2r;==62bS%KHPS95FLn@xYP&F$ zv+`&q6AfdqEB>NNy$E%kc+-~JiqY;i8gD&M#HkLmUcmhGgNWrhslxhwQ@YpNJ@|oj;#3bcah5hjfuZgb3*BIyB9=JA3{3f##cFsx96mw)b zL`$AwUiyn7=;sU%-|db#0SFgNlyk&uz05WI{_`Q2un@1)$Kw$VHDay*ZxldRtV8*( z*ceYVi~IHosTaFNL;l1xn$&&QZY~_2TnNDi;Bt8>NYC26TnTvDy2)ll!hkIKs5p{Q zJep=X4P+iJD7D!*OHgC6bATaghys<#v8p!nCRt>?(+EsL^>ea`Y%zqFvCM>a+SIZI z9C-FAjIP6JZm_X>02d5V6skH(7pu^_k0XUY%<$r)B0~*}E{6z@#`@z?-=owq_SY~{ zxa&=W<;OVtA$@rL=#pg2>X;ybmf?1dHg4Q$!8>-p@nz z#-E>aY#TE?E6=#mWMB{_Wp7SJRwk>qJ&eD3j(OAc8 zfo;m#PhybepS}wzwKUsT`=>sU8p($HuYKrL((l}w5vz|EwgFk{O_Odduv1xYr4<_| z4TjG%`Hv}k7@4j`MO|*f(v+n459v+`7i1ndyoB(RvsFK-3mrkEwA@F)Qr!g&B~!^J zp;xtoc8ThDalAl$(K+pxjTYA8i5jCE`x=3{tOP$7ire-1{hcx2&F)8C1m|~CvtK;< zWAvYOTX>usH4GX#)|OR+fySIzI50p6s0zS5!UZiy6!e9Jl;z{hRp7br+jpmspANc} zPq=cljDGm?->-EM)9T8aAZOFpw*9TzTIhkxlE62i%vy%Ibc-%D1+rk$-X?s5hKz*A|q5S-iq}#>CjSGBvO2lNx_+w zB{UG=YZQ&4X-43=(J}F1$-pY-__{Y3(zq$C7TtLN{#fbJpP2Fdo;eb9WyO86VoVc^ z{;bRQS;o6&9k*Os*rfuRpauSMzh$^p>#pK-DZDd^3Zp#7F7RRf0Ihb}-0|f?C%5_8 zP?jJ6#cVBE2saB(Lh-k!*ZLo^MyZTp5&?qcxSG@P0Lk3a(8;nmgm$j)#ml`Dop+(H z0c28(kj3AlS}o_}xb`4OGsRqO`ce~1dC_4vc$pFp8!shFii(8k`kjF+vH5J^G;_Ap z+NWaIi8oYh^5pkRZ)oNOdQ}B9vw7hAC6{4Wpv8wrT`2${+lXKrO7R@sH?(S@Cc)W6 z2PhiSh&B_haGl|;?H?PP)lkMmyrdgGAhqwAm~LP_ub4?<4))3;e)*Inw_ecNj)f1! zkK)${N9P~|7lzerO6jPhyb8L@*0l>fg(Y%Bj6Jo%K$It(Tg5`(H0y z+@$NRI`JXAg_NBAsevCwfT&5`n!@x9AG-(fOF5~NA>8)|vgjwx|LU<|wOW+@^w2

      8O&!kw;h?NJ(FLXIc9wH+ zSFUFNGfdYl##7uM*@YeGJQc`*9rvY2F3t}pRFwXUEi3=H7Iq>YNW?^_AAXi#BXS4( zax7P3!ge`IKSTA`KI-xsK#E(>Z@#ZDeBj%=PjwR`MwBG{NgogDPXbS50Z{3zhy@lE&+{%PBogYAeHTwVOumSVtL37e5-U44$Vk+qq<80ExgPMtnF$xi#p%fQ zH41QgAn8#U_u3#bsa71jk>)#=-{wKe+ZcSCq>Q%-A^8vZl_-kWJ(jCxrcYpn{TgD; z0PjU0rB0mBvv|&xNs^K1XElX5DR(CPD_o8a5F>=AlL3{ixN%?|<$Db=LZBP=i6PCJ zZpj|sc7WV=EeRopd_>V!CLxg70q6CwZhV)98@2LDz6~dfNK+FzGLbZF!T0($H9HsP z=!E>(rz0aFA-Wp;%q6l1qt@BO_N>o-sW;s%_{lsJ=pTDyFLj>zaBWQC%obbiEgOS& zvZG^L)Q<$F)c61@Vz#8v1q z(uo!?>dejlRzXqJA^;m+yp+Qs!6|82C{WE+ll6jojp*>foc7w1b0l756p=_3Z*2Zz zvNyc4M?cln?v0;BT>&%YBy&}-rkI4t;S|598Sf5;TsDySM)6tr9bIII>R2rk3zj$@ zt&dbZITWCQs6~#Wd`Qpp&U zJ(qy|BcyjyU{K0h40Vv#vqKRdzi23WVv`0-zxKCW?|dN{BQ$pJ*DFGwT3ZMm2@O~v zqge-2X1V3zmBr0S8z!Uxs8ccaG6D#mUk%PeX2vN!xVDF30$gm^N$RRtJS9Srq;?b| zlH7;OxO1B-HU~jL!M0vYy0Xi@h#CZMU(~ceWiP%c18yAbCo4~M>{-U{SJ!k5bXzs<#lWMD?r1W^#}ZVpWhF^#o$L8`-b#$BusaRf{GanyOPcYP zv7s~!hmOb9V!F-jioRNns+OqssM?48lm+Y@mX&DE_<+~dUer*pimm;Q?e*_*?3EHb z>pou5Q6M6sAPPbvX8d%YjI7Ko5IN9?Cp#TjP@L|a@pluLgI|_iTT)kEQD2M)B9Z&s z`~?6(J-xmCgRcj?u`>a^z_E$(p8hFpyjSmsdzlA5^!Js*0IPj(XC_wP;7_l?z$7#2 zeVaqGn-_p+pPBDt{TT(DpJ&JMAF)e+X6BG-jeV+Yh`0+`y>b3tk{~uE!TqmGoAFQ- z3A;@hWmAzPrv6E&-(7|DkRxh>fi^t%6Fqk3w>BsL-Vyy~>jBL!qJAUhu3*p>?a|Mr z$`L#4zeW0j1RF#ia%`fkVBVzP=6vl6TiLthjufVK3;AY>YJOZYh(o)>`wy++Yce)?#2cVq=i@`&>(_*? zBO~f&F-2AXoY{Tm=)4%Vp?VS@m-A$DG>Y$1_&`J7gPNpR_T5q)Jb!C36n0laNAdG7 z?DO+glJ4~xDzvin#*uCwW)g)n@`YHYT?Qa?oR&_E>~}1lQ3`c`S0s?>n7Ud5)MFYiVF>7uwm?2%9ase?!8zu>5sI(e^E>k|!#y`|Np2 zHNHrL2(pQy9A(Snv1N6-;g)1({h8ZR>pPkwJiFr%c;WL!>p17|lBPAPCaAAOw3`WI zY131ud@ncD_*av(4PnM@OQj^0LI0V!fnfn#60e&WM4Xbv3Boza09zK=-obH9N~^A0 zgf#<$KZQ*t#P7em;deK)GcQ@Ujr@+pr`GIhA9^kkDHixuX|aYpQ(9k#vovjuVGp2p z$R1GM(Xn=Dt6L*2lvBg{L(9IX|BXFEsIOnG7aAwB_hZnmSHN*7FnNRJeNunzS{_4u zjEJ#xaVKrM@aw5!d3THJWcl4u!fN4*&^3UebYY!P<`@Hxkr3Hi#HeW+NB)Q5SJ9SU z5s?(z#V>VcB@845>nSqkFLwvB1@1-uzS)=rCH<64US4Qb|NG_-HS+A6DiiQBBZ2Ly zWUuNwU4a>RiCdq9q4Q(XH5s3i*;fUEErs2V0f0kZVlBQFwI?xV_~AZaF7ThuZ20$} zR~ryy<1bX<%dv}{7J$c*rb*Y2!P5ur_DKh4PqOzEdP#K0_isc}p5Fx@iZm2#y_~WC z)mmLE(5~B+s&urotx@5r1wPzUDAf+UN_^ckDj@nZO%N{>G7yn3kstfE@kc+Sp@bM(QCfV1lmr%L3YVg}|S22Ca}XahI>CEQ9D|C;uT zTzwrXG{Z~+QL=K&WtIP!MtyKjCOG>*Kc;#a3l<|fxd<-o{qqs#eNKC(Aem|UL^J#% z|AJIim$L9t4v#i6RG&_q9RSMGdHzH;3`{|EJ~ffWjpT0R?VK>i5DN*^Ac%1@9rzs< zzY!DQ0fO%HXnXPZ6n#r^pphb#b2hY>73Kd-OIh@#%KAk zJxX9FX2N-=ZBQUJ%degIHW*J>^f*OdVzBwm8=Zf=8DC)NL>Jk~-?FH3haCVWCWTjVK&3OjjaHryq zvtd;K@OZ4Qni4FGt(IpvL4I0aE1XHLh`TCe6A`pXTUQKvw1+!j5mMMw+UDFGAIsM*Qw zGA@nWf$$nG)0{MA+m^S_9Il?^Vp~UkdI*FYpL|qM;fi}T))?89UDi=zs`djPCh?-K z`eI-{2*Mo=ph3skOO`TBk(sE`b!Y21^AW{>TTH%Q3(&r)!=572|KV$h{kyp7%q|gv)Noztj$EF;j7@2WHZe91q7!rpK5tUk)9-(yUCj3sk&s5gT~NXAfZFk)ObSW zlge6Z?q*(8()N-zsGxeLw8Unn>9`29`8-ayik)W|c8aXm*(P&0&i=8lR{#ME5YU(wc(xL7j&;F!d*d=) z2JjbSn$BI#;z^uaLx$PR0La+*Sm)!-(T=x5mA-p0atoEWlZ38KoKtLMw2|xY96;ya zcmJb1BAX{bdGFwoWGv_B#c5Rw&aXrkYj;Z0ZdLJgztV?EbqH@O#E}bTT-HjC1%XA{ z2yk7Gu)mB4w06FeCW{|&`|)0LBFC6>((!G2Ol9+#M`3V;c+s`Of5XN>K9y_=i;IWi z@Jd}<1U^JKc3|tbNn%Vs#pkf7{90dJ+!(&Y0 zx<#QabIPI@zyU$n7y2k~UizpbVm?n9e}VeH%O-DgRR2K%*NbP*5A;I91@<1CQl>c0 za)?O^$w+f$y~L4ntaO~YhD|DJ%d9av*NR#8uG%y@0DU?_SjcIxmm56D&@7s4#o5d( zToFP4F-M6n$lvrycWmjV^ z_GO^$C;t)@iEsZ`ni{t1r!9z$HY^gNHjvz_Q_viMje?n$ZY91OBup<8RT_z>ipFge z`Hl)BC`L>WCL)jqc%U)#5ykq~=isZVsQeeKiwJgHM-6fU4iem6AKBe3II643=NyNN zaVh?&lOID&smC5egvr#Xm~(!F~97|0)_$3+2k7t9~@Dp zY#e-icEvtL&W&{qlUTsa#*;%IB0DcwazseA0FcKh!R0E!qdh9cbBLCnKo)@I{}I;t zcH>Vj5%MQMEdh;xu44WEFyDWZ@zNvIQ6m!5G2WrRGO_EB$5*&1VIW-%kWbUq= z_9guXSOtIE8vSs5%1v7)?wX<3%P}?}mxC+9@gDsI4*ar@6M{n_0g}%2XQcu;?0}0< z_iIiLDZUFtB4pk}{Gf8WM+m8Q zQP;1ER*tLVBzjt?GBuDVxKO0Eo+$7Pb9e)Ctc}#(Ri`wZNplF3ybYjFuVyl5*T7dR zJxAO9S*Dm7sPLRAoLnNksS{eO0{35YpAZeXP z+n|(!K;?SET13-YLtyZY;4Pa+!!WNUlD>tCX(1Qx|B4?Wp^1Cz7p}~2G$}$uA$W7n zo{j;6?w+E8s*xN7s8>^#S0g6xS+#vI>9bWL^pbkB91cq4^>+X?42+qC5%*+U>%|4; z!(kY^3aot&DG8YnY{kgeZTCseyxpV;K&PN1Xg3Fsxrp5NBC*pw#c!ATa}TD`ECMtX zNlP-)soc`PD2ykBYQ3<`u8d3&)wuGH20?Jb4gzYDFk9bxlvkIMUNytT9mW1Di!n|? z&NGtBgN`#H-SUUdpNXB6=Y*P?H5hR`W41hb6nCcucLt1D!AatL8Xr82ZZmX#RPD9| zbWa=Wxh>))htPR;VuAD-VyjAA0cg)lO0rrkG9+HhIUwK?w*uB{ZO|JGAZ5kJ!-rsD z0a$+GfN%h$06tED`2Slf&gFx|*Fl?&IZEQwx`FK$xnLK&5g!49boXvlU{Wb=>&V_7 z`)BV-T$0K$>K`uA^Z(pDc$*WEd*jJrB7Gy3lD$Kc`Mm&tQ?GY!e*RyyQ*l8!b}4ar zbvdvOhz|fXH-Yj>8CvqaOM6OM8}%BBysKOB-?UNWHowxduG4F6&6@yz%xy#JwJa7j z2P`annjdL<)%YsByr{CQcVuS?ZvnjUWvOk`wruL=aqR2O=EZsgvcEWnN^_UnckHMS z8r)*rsd;qNt~8}@p)7O9G^*4&Or@CK{8X0Ci|awBYTMyv?xxtPC}@limRnST0I+lR z09CDy^M;LXdZRe0jW1U_w3!0^{3nfe$J};ESUso&N);<#L$%LvQk(}ZNHQ6T2+rWG zF|P|O?#wl-v~5HlgqCS^+}?X191&<>-`l;j=joyBd62Q`IzQE7XI&FVb$o1EonJzNC+v*Cm5NUw zK)W93o0@}5MDT(vUd84xZ`~F32k1s7^V7=Vxw8Z$tbS)vaI&S@Y!a@N@|o{hHFpT? z2|`AaWZ64I7F7ioGVcGKs()lnf3hkYY)sYax57*tm3?z0(lIRWoskm8&r%H<`wm|c z2T{W3Bt=jm6qX<5f)=R%`NolF%(T>(8T}>V5UPV-h0`i6Sd$kAe|;QfGx!x}_QCM9 zFP=2xYg~7QTj_8Q1%KTcmkz@3kHaE82%x^qPVHM`=y9qNYAG^w9I~CZ=vc^+^qYt} z-F@Ti)Gks56t9K&MI0I+%E;E+3-kSuzX9Q>x9opu;IAJUYA(3-9$khrr&%}&hdS-VIJ%+wGbZwMmXyRU(UGFy5NB7 z47`hAPIFCB^HN*(N&C)ZPr<)-sMM+q((iVIep{go`~ToMkUGYg2krSAnIATWZdZww z_x?gsoO2UPow6w|UPyf84gK$k1R>gvS{L{j0r;jCnSImY;=ejZDRvZRHk-f_AFzw2 z1)5Vvw$bAHwgkMD7F0y;e7BB=@S06BYTCO(N0bGy!o{DV(dJXm*mk*e%8A-2wUDemf@ za4e2pZdxt0a2_{?SSB+Bh0zL%(#r82f42KCMSE=OcHJ?clq#jt5C~|zFU-X%Tiv#S za{Bja-l`-Lp_PNYj**{st zDa+HKLB7to-s>5Bp$Mkphowjv!*Yqr66|0MiepM-FLk(H3S5Tk|FoCL_pCxzv9Ls_*g`$q5@HBj)p(lt}AaW3aG(E>2p5oBbUxo8>;!>)>C*~LMr&proP4jc`J8Cfax7TrdilOND60j|~ZTe51|bVT;K ze+^2mn`xx!yXkp$*1RLNcQXD-Zg=Jd7yTp!q8}2Pr5#w*)X8YE!FsJ}83rqE_f#@c z*l&1><0{!7Ic0QOj(^-SOcrwERJZ!&WFp{HxV{LbG1x%T9gz*}2)P&PbDMZT*J<>o zU7yI?>*k%H)ASX$NHv(Ide&L>JBCFyK*RQylUWYcLAfx4?@-Pu2~-UmpMV5?v^MeA zJe{-lokx&TDz=L1jxolGsu?b1M5ApV$FU%nSf>>Ax?gxt zth`>8t0`%Ew%2J=?mG65G##6vn}=_MZsLtL9QaaP3C<6y+3ERzXoB>Ic_Liu?1h#i zKe&J0Kwr&$}+*>(IMSGcmr1zUU*8L>h%j#yZ7?r{eXS z2G(4vUZ1urm7L%W5Y;BY(FoU873&FFte&tczr9GkE+w83goLY7&M=QIJs7>t?jl55 z&vRy+ntuN_`F1CD66bh;|FFDXzWwrSY*?aQuz`b#(23qC)9x?n?nI=Fw?Un@Uhc2= zCMftfP2>FXtDS5D*G(Dlo|of@ZGUQ`D=j5wdZ1?IYLXNF&}x2IQ)S2ScYn`iLgfq^ zEu3y~j}=w0F2hNYco>f0$!08%YutOvoVm9=YlL=OHEE@1MgXaQ8}lB=+nUNQM^nE> zJN6B9xR~=e@5L&gc2e@3z^LLi*bL42(G3mk6fvFTZV3e*L>C>N{la%&z*u>&qJ^fIgZsVm^4wem$tgm08LyKdm)&R|D8rcSlGwa}MOF2I?~< z{e0jh5&X+ij@`{rV?Lr2(itbw9iOz<4?LWx@!&>Q;PNO5Oi2_bvU=HB)bkvdNIgDg z_|SsA?%E?C=G#vZ)bHSpanxyrbJa5&4VegJ^@d{A0ZT?36Q*r|U!=?7BdP8@3HlY9l}2xrQ}B4Q z-K3;o=%RA9?mq>xsP2F1x{#8uWs`=25<$!}FW$%Ydjdun1bLN&P3fF`4eGWhau)^% zVADN$9@7oi?Ouf&(&Nrol4xM+Mh@8dtj<*Q*o&PQuah|Zcy--=L*jM`1)XnqEPW8souRppAhNKl<>jd=9q39*H7TSr_T z>r0mRblQ)vm?3@gGa~@299&|6UZ{#)4M@m!ipN)6`lA$ky^DZKA-7mH61*-QpiI9G zBb5n7pF1gRhy)T)*nQonc!FZ2KH$pduzPiG|HxRZ5)%Q>2LNUiwXPI5@U$L^fh(hG zp&Y(POTh{}G)S{(06z4xm1FcnHS!bLK2P6*0+ct&)(y>uihkd}BeH{<=WtU-Y z6!{bqZ=Mv~EcV#a+~?R)mSxlXk2-w;r;w8=$9HwdrCxoqQMYPmXkhg{f>A3TBogR> z6Zj|3f<4}%p-?nM!+zJ5#F0lF*rn2>8qFgKwU{PSs}*y-v<<(&6`qN<%*CNBu$Wnl z{|*OGjX2Zb8l(nms-BSNbjHq)!C0;XNX(MKu&Dyr5} ztX7Cl0=W<%=bz_W*rCQyZI5j9&|AvB<%vJtqhQ~&zfMr=J7*?Rjx(qZe9R&Ew}=7( zjQDJ7q>H8sN%J$OG}@mq+=44^*Z4y&1+u8A*9b)FoK;$?aNZN6l(|l& zf7kg0oBBU@9-rf?kD*h3a z9Yqki`WBrc(crL^4ePf%vX%IBcg0LT>Pa34Vg%0OCO`3Ju=qMq2}cYrkqTHS9Dmj5xg!RC#faza z|NN$fAaN1z`y2qsALR<|xXi`JC+^^K=&<4dgS-IXvJQd~Jd&>fyx$#^vK@~Z@aX3| zfx`f)oQ|&Jjt9OI!#s}E{~u^9_5ba*Iq-3;;0g6`vGxPd_(Qx$4G62dT;Mh{=)X6U z#3!sjM%y=ch}n!0c$(%^A|b%Cz%7A}(kMYSO2p;Z6%n)}yx@wIY2%h@F2c<}ywPO1 zOUEZuEOvLy5@C44L6JeB^r70QL=OmpD~?Y+Odb)e5SI~zpPT_EPPeT_LF?-9(4h^_ zS{uq6gCH65(rt~cF@1INbi?t81wsKcvp}VZiF!~da00lz3IeT95-u;|jn5}8 z1C-{+HYR6Qr%xu{08c-kzIpq(oa@IT;l#}G%8x&rB-&coZ>6GqtDkoHr$|Snf=TWR zsSs~=%hRWtD1&*Om%DPo_wUX)fQ z&yoeBz+&|obPz^HDxw1>zJRH>qOdJJC6IGa3u(SIbhFQev^-*XN|F!!m}co)86gIz zzgK#gMY2=hWh`_4AKsN#kJUsbS;)V&0g;-wiT32NEFw>KbrN~2xz?T1Th!dXT(L%T zuLNkv+@HjX_Zu=SjIV0Zt^fwb=awYrTclifKrC7TlTNvl zO7ifyKB^(necp3~5Ei9wS=dcjH!gN+rJfcAxp%nza;`Z3rYdbnV;(~iVT0=v7j%9+ z@y)6)6mco>gL$wZ_g;}OH)w<47#v=N68uGH^|%s_KPJ0n+zk+;@>Vj_`54|!qQQ0U z^hP69Ie-a(efS=sxHnp~VrnA2wy7-8;##ZHOtS$X)Fwr;)7+PY7P(CF9=s*xLl>_} zib5vXLzsI(rTE9VDQ2drf`kC>WC0|H#kW88q{-Cg)V8|IOY}?WvK~PeV&5f-4>0NS zYMHF+sByOJIqIuw`~98uH~!u?$@(HNKFc{3pq2=g6O7QcNu8;t9}s9G?O^JMO{9aD z$uLZOwiNJ8&kfk5H!|k-V?4k08^8-bnO9?sGTv=c6o zuj}ec+Y}5i{!NY#s$4;-*Z$(wOTGPq*XV*bF;G=Db29C2P*P!Ip)WBvFXY%9fmmzWWSq5LQ? z2W~DnGI-MdFu`Ab!8b18sb>0^8dbOq527E1Wi9Pbgo3fu+QDtzTi``tGJ#$YKjwMc z1nk~MsR7rA7x!ACMm^=2ixp%BIwIe7&AQ%Q|5z7leL;Ta%gE~+NM#mnGz^m%=4W4Q>w6M$vO96rppEuE zmsE!Wocspk1O%SXl1TrgCj7cBgX8x36E`L62+>8eN2Z(WjyUs1aAWnWH_lROAnh%B zDgJDS1&Jq|=4z{&0_lS=)I1}V6v;*Uqh`UV5yq8P)NN7MjGpz#%KS&U@xHe)+{iJ} zoyyEOz+A_K!?eS)6|-Y*Rx7vaAQfe9CJzSCN~FNZtWSMb00DvV5+3E~`qUhXwcO{_ z>gz<&kZI;fKcSXKe@rxeU@x!X8m&d+o7_$oIcLSv8~1ji#;HqAFFRnX(e2M*vR;glJA zeA(=$ONYSa6Ew(`mRUYa5ay&1Dxp72NTz}D9z|)}^QLpZ7Ahp+-qB(oT7;^40X$N2 zoC=U~5ps9EiJ0Ov9kW+~f{W-0TzAe5{)#*tv)v?t7Ty94xtf{{mubCK+&5TfO=j*{ zZu>4B)|NSR0x3>fUK;V6hIRIr??&pQSN(NsO-uovw4P>P=pFnN)_NV9Iqzlrto59c zQ}j)uf%1x1HW7;(P|t7^bH?bLWs)1svw&n2iU~6wIyD{gWTS|y)B%72mWmxoS%A6;CFdGykD2ibC7%>O zPA7P0UqoBHl9+Gfht(#d$gz?MD#^bAHWKUzje#_07tP;f_>HWfeQ|AQ{*W_U=hOq%`JZuVf&UvCj6!qipof7Po&uCXS$}9q>Jl1dY0v(%S$x?K)m20ztbYDU>@6MI;E)iGib(kJwM%hVVu?a zw#^~)Pl~((fTp=Vy*(l1j8k5wF~s<}lYmKw?a8(BhYu7nz)vGM;1{bqFmln&JC?AD z!9GLLRvdaNZ%OT7%Fi%WQ|~3+4+FESQU2Geee}F1LNzvEclzYv{X4yVqn!z8Xr(J28&FNp<>0%CywYw5iL6pL?J zMHWq(F%9B<3%i9)>kyIJuU;rkS4Ii{P*Ux$l^uz|L5|`mSUnD)rR(97usg}TWqLhd z#7iyM`VK5n^I&&Y8%LSE&l;H0eZe!~d{Bd_MRK3k7tx7wSVN9ryA8J5V-N4vQN}>uus!*ilkyu;0&2>0bv3P@+vJ#j+3#o6 zDzBU~flk`*`dEK!<;c+rd(27Y-h0L5f8R&77O-3TmLB)Lzjpp5DeZCiAXg-jJrvtF z0o(p_hKr+md3fB|90SR1DI93-wbXsDoB=bGUb?xLW_IvCk&ws}Rl;=1?HI`PeLalqT0=%#B4=>=M*q4MRk}6VC3e;kB z3$?nA=?Nx0W9s2I03i4$&s(V9pDX1f3bl1K^23dRalOGiinvr-ipU)Rg*wR_Trb-$ z_R1;!n@K+-DvNLHiD_8V{v!V8H=;OdPL43X2TF*?I{zM*_rbVmq>6{Pr9Bgx?$cpV z@MHS@sm3CbRDL-jgtQMESyCPuQVVVxnwP{^}c4fC4~MLY(F# zM9|1EsLMR~3V6E{MwAlx0d9tmVzyUL5=EyX6132b66gnynX>zX?D@TsCf^!2;#LD5 zM7h2jB~#0RTVt>8!c9plzeM|Zt48VS##t&Z_H`a?V^aQ>k{p^uKYy&(c|oBzmcim0 zZa&~kRZl>$2x_^6tGlVGq9}NCsU>h3l~*{*R|tMri)%n6HH!_#I1qR73B^W=-!{BA zlKf0?%?^qb-zkOZ_QJktDG4o6`yMkXiBWj1s?T2Mc&4b8NQzARMCD9cxcY-qmgAoHXYwQb3#Y|PGp-&Msz61KG}=592@>kekLzfgWJk>& zAt6;ao1kb4^SkIl!fVJzH9mYp`-tPD@HO%ve^L$G!{lr zm$Hp>r{n0DqwRk^)K`&h4GDH9pk@9x$4sZA495HC4%RKv6xmZYE7XL03+;h9@=k0y{_`h22KO~COB z3(zrG;`-*#C=p0MrmcdQ%)d9HOLbPgbM<5g%isp(JQ8EAr;nR=v-*VQJgN`D4KCE; zgq2UH99b#%ojW2d(3c88dhKi9&TkM1%3 zN-aZ4;}gL`9l=hvvADQpPIhjp8jq33^B1%`;~dV;k2gI?FL&bhk7Zm=TzrmA)&rFs zxoK=KJw8@>3=}A8psBM0B;WPW{MgA9z{{N#s2R*n*h0u7$Kdz%Y28?Uh->oD|zzgijq3DtG>ahiau?~PA zkpGkR@&b?#G^+pQQO!ocN-y^+JeTQbv@4NV25CpTrgnQ%k>CJikPkE>OQL7H&0_P~ zJyksiJub*F>w<%ZG8Pd}1X+{PGN(AHGU?INX2cI+?1qWO`fFvxUvJ$;MY+09tRcl8 z`-TY zp6&7OSCIa}$==!7^|^yZ$i~##&GIfIg%3nB`bQ4$3-ce=javDxXSD?W9O~X|xI|^W zQ}&Z-B=;f8UhCw{eMCRGvR1B%%cSCabKn4oHb^3B?FjDhvz=Kola8QDyxH&}S6eS; z=f{4h9e0QHZavdHFKeUY>n6-!d*{&3N0`XCBkA9wYyV#1!qY-9ufLw&Oy#e(a2!|A z{(pzwy;bq0zEe4mqNXVvX3(Eg3Ek^SnBKG{*bGpm2(F>R%u>)ybe-lEBIykf32dNX z+tS;CBmSd-?GJGlRCUHHUINN)og%(mQ@=SzmMZ%z=1YsOg#$mv%CZ&@ef0P^g2(4} zB*gf|ZInFLiOKj|e_+{)`m=-HnsLwfIM7WlBd&uva8Luyud*r(enN~dYpXOgG66p+ zOz++$CIqo0t|B_J4&=8|TgCMXKhj8efebR{1{)PF3oG)%Q34P!4OZ$+aE%&4q-0X1 ztH6;PjfJ_f)Cznjapj}aRVp>TM`ei9qKRmIgMLuuBmY^4FW#=7b%tLaSaRzU9a+oH zM&#RNzc{TYNBmCY{-lVE$&b z>@7j{-&7A5`!aBzZV})sN0^0H_RW%@i+~iV8ncBU^4NEi{AP-cV^d0HAPjzu3CnnZ zHmFpNiCJ_31zEu552c!VrSCYn^s;!3i!wZmw8<(Uwas)%f=dHvEfuxrzSqE>&iRe; zuIkagxy>){c@f0r-=*imqrn%-{+mfvqig?NY^R(|8IjmHqO&AeLpx+Cywz0m@xknG~A#utLm?FV9AWYezYo7HdXVN8Y@A^$oxi#*a! zSvnI6GYHN9?*U$4+UxzXS&}r|d=@Vwz}?Nnbl*;W2;n5Y{)3F}U(1&IM%tf%eA>g4 z?9N?}yS4p6OX0B#9MN|UJtE$)lHC(Na-_yZ;zd4R}$yOhJX`9tT+SI2vmJ@yZ(2n zLeHfia-$gV_Zr`hNHoO~uI!MUI^Xx&8NeAO9L9vFGvf=AIrznEAYeNsAJI)0voc?cd2{gJL{R<6N~f?LJwu7-M~uj?$}TZ7*4)2lE~~1LH^9Rd}`c#`6;26QQC+)=Tf&)J;Rg#ER4$yMm!2FJuGDj^%R5t_cn}3WNuNETfYg39Y1v15zFC!UqQk_^uyLb}VJ>Cmva?SFtLIHi~r_nDAUA(|rRJ8u)b{T0rZI6?N2ac^N} z2W)p6O);M18-0h#Ppk10E?f~y(Q$j*FVV>b4D1U|)(LgOH9?T(9wtp^0sv!ow$5$iVpNH;c$^K9qX?7*dDkuYb3M@FH+jJ zXtp0{{$&}Q^RhlmWOLS7t5ByWhUhs*Ci}GI$^O%>x)nc#p^3h+XVUR;bUjjhpIg4m z5_2tr+zA{OAx;o-a~03p)t{iGr;MZNp}M(E)dlxhued>o&ol|+KN}^tA@fB+F?WTa z?k_Dsv#s1~J<2S8q=|+Ek?uEv!kJP&d%XPoRqS?w{=r9!F(0nB8Tgg z$?q9A6m`vQwI|yHR%RNl$6!qL?hIopv7s0V+_E&4t;xnSOH0}>q)R=JmjeIAGf+4x zqp$t?I$619H^;i^*RR_iOO~l$yBbNDI1|~76K^)1oFtxU@|Q<2lg4e>@`5`liASAhKkYPZPxHv6Dx~*6sZR~D>+u~i3ikvr(5sg_;9wN9{k0MYsdU`xls75ETy_Ka zp-D%UO49#POXb1y^P8Pzw^2lBj@cdd_-g2)8kSG>#O=(O+SrP(g;wK7_!)ANbn_FM@HX=|Nu@HVtRmrPpnh!3bSZ8oSZ(>J z$S^>IeGm%j69rHOGLbrHKH*}%a1b~Pb{woBg}Pb0jk8|EJ+I-`C5`lyO<@R8FWy~% z3nb2FN=^@iP^e~`GnLR0W5{%*-%bfx&5h{n)#~%N^sBNA!Z%h(WJZK)7djq8a08Db4I}@sPJW-c4qZTcGNhamsHj3nmqcK{;_;QmoNXBp~@d zCWceOwe7K5dAByGV3S9|_a&J z(MrYZR&`J{=gp;}3{$p1sdAh9{Bc!fb&8b2%`EQ9D@dKJDE*5^HvR;qD+U>E8@ib8e1v}$VFZ!2>7;^U}SE@3v)bP zvu$qDKe#bCaS!UBlsiT0Ihq&;o7pgJApQc4^c$4wH5`v|HGoHf8o8Qg4QYZB@Vs@1 zCa0IVipy&^%^Hq-6TT^({WXv_n9%r;vbKB`xc3SO%S|awja&So{quaX=ugpI1{*NzBVy0T6Mdn zP5jrX#g;=6Ws;(`ZtQ`8tPfB+CE^6oW$7|-TNuZ07Qz?{h!n$AszY6bOntwv$ucep z>x$XDGt1PU)DI%ed8taam8WQUsz9=oA2QA4Eh?{a9wpPoshKPruAOC06^UFi_To}4 z2~XC8Jnk!cBEN31w=8gjQXNhRm{{=_3koIOTpaQ|xf z>oF%@OUR>fMQTpgKOy!&xNx9*g-xJ3caRb=iDYQS0Y|b(H4o8U!~CM&&VwU%4j=Iy zpML9_^2ncGQ9TNOxg6h8?nQ&5A6=ozZRYlYdx1N?b*LUPOg}&j^i3(H1tAf)`A|mn z$KfPT>SJVIBV3~vIqIrc-WEQSa!<+Sr}+~66;K&LUGXB&)O?F#9YC9!E4?^MJcXs& z65rJ;cFnBCGkuDx5jJO64IvhnX-KhnGO7~(buW2|(o7HjV3Xmlc5;p%uUh03k~YTi z?X3VvrRu9C7x8jDvos>4F<3sY|FW*zdE@^h(cqgKbX7Ta8Q0jIn=O2%;*tTgZla&! zLA#s-OQNnfZ*i2li>16(n>Kzfb0A-Ik#=IHFgxir3*s{rHH|e98L5U1g)_a!cJxpa z#&nwRiG^IL*6ER~rBRDZ>^^Rp5+6{LCD1cPCZa z&n`HAH$QQAcP;^$2w1XA@c(kE_y95wIq?6>sakB+uu{qFJ2Y9>b#%{4ic8Uy;_!&I zer84Rrq169#xHLME_Bt*^Cr@&$E8W|ss&SgE z9a)cN5;)QyV=QPx|JsEp)zb_}uz5d%bFnsM76*-#+MZh@W@xtjt%6hA?@J{WKS{y+ ze*E2jIqz;kTf%XRGgHY1*{8%Qu1Bw3a*wE;u7yh3%;q6Nj7wD=urh;98>sAaRm z3h7~iFd1==cdOtDTbjMma*LwWRoAI}evR*unF5|AXPhPqKC&jlfBZ}i?bbPIrMVmhfO3{yA@f(tcY-f_#7 zBs!BqEHS^e|6q%0=pvrGYMFk?R{jqS?;?{c$)2(_%U_4v8Qs+`Kb&X4{o7M!I20Az z6hE$+GUl-trjL`-r1vwm;?mw447PQWsR9&=i?p%llX)=-wCO*jc~2t4Bp3-j*066S z$92K?n^ZpcR%?(!A0#S?`%+Q-xUdX5*9sl6wY9Anm z0pd_gd(~T|yzy9K``VVF7j9CRFM>gK|B1m`@mfiIZl5OqN#tJ6WVPM6{Z)vNWu5M` zvI3tGk5<&`P)h(k1{$Ph2T^+5gOK%979<<~8d{=a8Cc4R!BYm=b+g+sd`s@}mgfpr zPB%%UrE0K8bKnJcF>}VEs9z^(@bBPNBpa6BwW?q$U2R^U1p~5h?W`kru1zOUA&6L66ZgY4tQS@C8hF;Naf%1 zeEW$zOjJb)C4vGz&*^G&E!T+6wsKCR)Sl@($nNfG-%-ML-=fNZ`Cl0bB@}fF#f|;fds0EDwqziVi19-to#_2;{_faBC zYb~3dB2}5maJCPn=CGi}o-OBiGEixO477d-byY7?@6PTJ+WY+vT0#B~wW5-AyyWIr zC{8bj)>;a!NuZ{wrlcDptC%JCirw*>X|o7uDJe;^9z=7VRzQL;|A9r>|z;#V2t=e%<4B+-DO0zb@j)cKCOjp%Au=o_9Q`pF;4sI6pAi6l9zuC zgmLjd*3wRQRm01fpH#}IUwNqDXm&EAjAk0fFF=et5MCQ45EXnY6InQu*0<2LU8%M$C(FOYii9$P>iWT2U8;Y3Ys%1=+t0 z`WbN(Wt~u7!Xg93))z$qKL{6x&1NE!)rr2_A_w>C-kJXReIdi%ShZaX~}LJJ0C86!Jq^xqA9V~{EDGkq-y&jb9ZhQP)G znsfCjZvr{w*Mu4%$D%qQk4QF-{RLR0>}Tz+u4aKoS8CwSz9%y333sNkM8|3NR$Xew zMxsD*9U*1*M=Pw={EDm(j^#0+K(#V%YZy>R8(uh*wK8i&6LmdPhqU-=SrUP{e^J(V z6=%zx2QqzQIpWC~{nGTPP5|DW+R|N{Cy>LX7bE@kVMFxieT+A~h^f{x2#tI9VzlvxEHr^67x+pQL)UenL(6bGH`dk;TII;LJ!(x`ohR|% zKbdUn7+A5poR6Rk6k0_VXuk_qfzyOJEY#n;yIv3SqjaqT7Ri(27|eLegcRN{iiR&` zRul)?&UwEVubGMW_3hVXn0zxjTU(LqZvoiQi(e?|m$B>y)A}Cn?@%y8&gJ6mASw&K z2UIDo&gJg7P>M7^+IN9pwii-bwkW2NeXr88CrVQ5AFH=dQZskp-g?l@jVo_?k+>81 zj^S??V0uVch90IR#@wU@EpM*gvVgy4cN^|QF+^g&?g@nsymuREvm1Dxc14uo7+af& zR0YRep+y&KB|ncaf7wNE)YGj5QmPxv8t0RD7)w-%;;=XX`ges4$L+1B(f(9%m>bn@ zNlCYH-w`$SvEw*>F)!3EqxNp_&~Avq0six3D4i1hD-^73$IC^Pz513B^b@y-LyIi| z@G6(-PDG;vKT!WLG;~*@l0(ejNd8j*RPx&Ntbuxw(@m#9Vev@mE4RD}4wbo??V}nc zzBs%3O9;nu#H$SpV3j|wh04$r2~Iclp{vxF+mO~eMsj*7$8K06oqkPcK-VE+lPc+c z(QgqLp=N11s-Y+Z6tBBr4R8>TR|y@3alUZ6Pmf!6OmyZrOQv|lp@Ao6r8dLV-sG6L z?#by$l_zRb0a1B8rSMR&Wr54ih|(0*5TtPO3#l>Sb24b*NLpa!xQtURQphyNbPVeB z{b^LCmU(}~8$_9yE5`%QmaR#-Dc3^?S0pqGFSNF572@a+m?R0uOLpsAw=QLR+5mFd zdY<^kCj=(+#Wb96s^i6WX+9*mHPQHJooEq`>$B#>T`qGa9>GM5!uDO|2~zFnf$GJe zm?!51Z%@*lu#(c_>Pr}9JyDEzAEb3u_QQqs0&RH04Ju`trD0u573oGgZRCZOe$qtW z+2BJ7V#w(6v&BoCFd^(#=kl`9C{MY!O>p!IhheXm*RwF zNwTuhs#7g9g)L?8(etq+(7gaEY*uSrRpUDF8esa!XTqtEEqSeqgm=d@TxcYPB$#Wt z4ZNLcf%Jq9B?-4^6`ECNG{`JW+(w+*JrCq<+`vR!Px(>e@ek@$M+nSvikC1>Zo?$* z&kZE!&IY|9Tj`{xU?!*K&yt2UQ{l~4@-W!GFe};Tu{9GcJ#>`5cCo!wsGlIlUyQlS zQ*Abjed|mm9vBn4q`VQF{m()c?<$)jP6Y^n2%HN+pmaPd%x6c&6?w@ZS}lSVYBx)^ z`3q8#D&K^0UY|TXeNz|6&3#aUcyXpHZ3sK9<)y!tiC?0Mvb@KmVs_S)3FYiVB7r1? zh!b~TZDeL4yX#8D)(srlZ<95l7*a>f)9-f`5CrQrwjbv&baa#oBD@@=X2tUkql{C} zOES8$!R3i++r=*!5Z5cJ9?P}rY*j<_mokV1p7+(8@6Fa3L{+PK2gO5Nu|W|A8D47rXol4{+9@(i{c7 zqTlC|Za+a}s_`;jr=Pl6vo0&fjJRfx;M45NafEWiifY%ktj$#d%xdE?mjTDnhz4ar zBRT=uWg(!l^9YWghoF=^d3@GON4ZZ96asnGReg+I{~<*AETWXzTjLTJ)`<$C!sOZ} zhKtAq5obCnm*pjJm_N9J-aOSGbs-x1W{x1});1j@oxOt#cfd2r!A0_bT^Dhwf3{gD zfzcgpd)vkqP(0)Sp!NXw|L&mt09k;~|0b{gy|WOJ=H!OD`m7bb>yF4vV9ssL`{b!rnf8^7pERK~>SnWZHua9;M97fxJvueSuD9X# zUw_?dcQ>r1-&oR(^xZ87f?*B=8J&BQP)O9vz@LGY-JyHFW&-8s^_RpO<+govbf%qw<-+LgiPq5`WY@mOS#+2cg>}!9_r7SDo*r;M-n+mAcOgUV$t^ zlg-kb1MO3>KOhsma6d9OaxeB=1W>6IQZ&F6v!FD5nA#}dDyuRoLs>{m_4y=d-8NtW zoB<-Uj9WB4gYLlZ8%bVV(Ig{(-RaxRQgfD~23tjFTDR_+#~t4!!%A>?;Y(oEo=@G| zmBfcC^flQ&Qb(SW3Ixs)_>u`ni3K$yJE2R9EsRj#9PT#-fz^oCHioTQ#%$%&l+D@# zVC{I|aBm6uzy#zV6W@Dewk@{ed}GT(>3hwZwoRlHF&3aU4++8dVeahj;i=_Nm^@8j zDjp#H3#s)+@?&FNCpQfhn7>7BiOEQkoEO(Z_>70&$*+CN)&6kkClc>CS?9F_72!7g zeW*pA89mx_J=vW-mF+2cUF=x?!t=U9M0{FVeUqLylv|>6)h%Gau=v{Ash*5iLd^KJ zr-zD7(Prtr7z;x1rlgVmrgQI+qA)UEz=lh4S>ZT+hWISKHLe$vH zZR6&d5a*gHRfFcxK>TLCtSzofhKPX6sGvU(as7V-1SCDYo*p*nr&f!}&yqxs znXt`7(ZT3}&(JKc+-@2^^6{C3k>pnQ1eMIUW> zj2@AZ8{b&!5&C&Og}2P0(GDo7v9Si4c zXWVJxs0$a0!YB!x;%N-IDcD{mgce7w4@dUAqF`Q-CeC2f`!HI?x|Cr^p`BycGfJI; z;)_w@Fv|L7$~eti2f#4`@W|xnzFET0QYfFt?e8WJfxaQUG$A%68sMznsZAm6&MY{( z$hy`i%qVTqz3sVZ(z%A2G<&Xk_HbqY=$+%q^<*gaZz_jYYVZyLShW5G)|kh=jg^m| zbmQ6qNWr+0$tdTR{(+>+lLW=WJy`(j$LY^^pLp2Xu09nrFU8(LaJMHcqkVDtTU^@j zxi-@FRUmW>^8d|-E{jkGC9(@x{pw7r$Zh1qj&$Y?0S$zS%;W}D`0M^Skr5#^;J?KA z7~=dGIsWXqzg3nSMkP}YW)KB4tJbKLtme|{TLHmJYj*!-0YGca&OcpBSVj|g@rL(g zDwa}-qJQR641cQk6>E(#zHal+@)9p@6s7qup^^8)d+^dyyI(6N>u+vZx`-rsk@6g2 zbgiKe$xYu(orK1SR?8jFS_;1wl97(d=jOejN4hVLYr~gVeW5~4#?8}KES4jD zU$~%xWnKf&BsxxiXKeOg2jXj5j>R)t^8j3-DkIP+_Qf8oAn8nh#WIh0>U+D$z4x*> zf5?ZouMRn1MbOqa&A#P*mE-BtS@UdfPpy?lU(`fgySSXaE>Y!sG~4jv{vB$*`qe>{ zzKXGW(v2>b)$c()23I4Jgm1?O5&`G}@bD`Vyr4lHPp)+$O?`(X6 zh1kRfmK7q??=@H1PU%eJAMO~(w!54ROP;cs2%@1?RO3w>hKy5qysrOhJ$9O&eOOl3 zU<_`Q{s$uFb01+pmcpO;^J0rfp{%@&q$@ZplH*(n#Pa48GXmwx{(H!fzexB#>eUHi zjhV|#eu(2~bosVdm2eW@b79vPYUWz`gaQvL$)Bjf@|wvd)H0YDGI0OmTa~V*=Kj>R z=7-!OxIW48e|dUMVZJbA8S=za_LDUA8PqO|o_VF~QTetvF|IRt1IWYB&`ef^`J>}* zuPS(2xfD-9+|8tWZUD{0apsR)B4=HPGWq})b0|fU)(-?fkLsG#Gst+gEXODgY+K&oe$1cd7oiq0xneLimnOyEcOdf#vWIKqn!|!7< z6E*5F9LtDFURzg*cQ?+Zn#kwDB(%x?wJC})TJ+o@aUXzN$A!0^lF3_zkzZ6$ZcpWF z3Rx?s6hu{&m5Xc4mHcTa8)xHVITOYte}E8ve9*17buNRy1WnbH<~x%_-CFJI%LHP) zNYOnfR4owZ2C&Y|}?4Bvd1>>41oChOF?aKGV0_K5Z(y$iYJj$R>2RW<>oq(_pFTu$oP2J=Ux9|( zjgpxPopN0jQsEMgypzQMwE(wXLhIZwXbop;!x4p%$5f%_)Cx(HN?n1fKNs=pO(Dyj z>@4m$EFwC>cZ#AwpRaWc-}kN6*iEcArJHw&`#Z9iPmFdDv<(D6qD_R`g!c8Cl;<9w z71jhuWp_QE9J)s9Q%FKL&KrH@da%TU?q#Yw^eL%HAFU=&iZd}Eps=3`T@SbAjwi>| zQLJ@{4vMg;bjRoc**+&As_BAigD7P3vj0dLj2$CEiN5(KVgwQ@>$S39k|d@ySs7|c zU!*v0CB+SgdZ~%)O@<~HB*XOFt!3yuqk`_!W~*S3MMZK)CkBvxK!XQ)kkvj+afQO~ zZt=+rN?$_;(e0nGeG0trYL@fWw47Y}Uz?gwdaTk>ifzo!P<2HjEzRi<%hhQu;LIpwKT zMcyfMuAq_YAq+Lgy7HTc#2wb> znDRrM0!c4ft0{AzKh3UHNl^ZyliGXKyZ*4Tb@q-0#u4r=}J@!KAZ=2fjL8FF;i4r zr_(e;Jt6|;1X?>$=ch?jroP;w3cR7o6~SrN7N$duh)oNnP9>jOQ;z?Ks<-fpatr*u zCxM|EYUrAwyE}*O?wFywQ_&%Yj-ear?pDzQNP|d+O)7{U5Ku4&h{yW?ff~jd@d3REks;R=oj5pkKUuFG8Rw?om+K-02}RSLys{Ur z1N3I3+?-Mvyt;#hVp(O4FYPjlL)0ha=}F~+xZ*U^i>zy9pCH3!kTt=oFr+Rp%#yzXEL@tIv=rCOIl5( z5uqmM@lq4*C!g~4@>Emj@~&wleA6_5O%L507#`Lq8qqKugfT!eohlk1jL0{CAQht> zRLhVgSAEf4a$f7WhkR+K#UaQvaL8!%SiXFOj$}>RcYvlxN}Gcw&vK{i8@Iv=7lSl$ zf*x`1^$?t>PJTB$zTup0%F>N!mvN}2*rFYzm%JK7;v+%c@09REJYz?;TspM>BIe9G zx5-*vb3Venhs5wsPk_swz?m;j&<-__t`V9{f^@JtyPq4-w+1p?3n2>u##Rj5_YgVP z48@v5{d++2nsswaM~S5Wr0WDZ%k5wq*ZLR2Km#-=X^dFBkX76jK)jK8`pyAdypn}2jdhu}_Dd`cB@%~A$I}h|-BUXMv;T@Eh0*qkba^lL`N>D=# z0MOh5Ehr~q$p`S2!%EuQIx1>Qf}a&NJ^810xE)VqR9OUVYb$t?w^V3KV!pIit41I^ z&TsC1x7z%woMd6ybRqcQRdpVD-n;&p;5m53hv9>RsnsX#*8|~Rg8B`5jhDUH#sz?= za)$wZ5?X*%GkA1b15C`F3g%(B6@z&U&tpgIJD7zn2gOobllEmJe_PMl^%SszmiDy? zhiU;p|L68eRPgQs0JTg#-8?6*e%b49-8JNJ-rGou9xIT}n5P7;z`>8ac)bEIP@C?8zsWH?(?=O=&R1+WtPCLP;*-V!`8i z;UQOji{Q=N}E=OAk&xU&r{K3tu&bhZ#R_;S{|yz+J69ZKhsV5>Lv+ znmIlSdh|(5<`J@1;v)T4Ld|+|O`JDSI$frwu+CO{H~?hp`f_^$Z4Pp7%12Gv4VtO` zmbSbb?h)T+3bzGX=LkH#iDF9cHlMH$Db^^Q3aU=Hv`zg>h&D3)<(p_BtpfL8GZs9W zm{D#&AW$p4tKluPTs=t3jXq_QH5Rl(9kGbgK~pI#_jc9`Z15eEGrrwD-rQLC>S}W$tL4&P)+r`}#`I@k*Y3$y)`+r(nDhYXdWgEtSEqq$rF8thsh9a) z-dt`7>%gJRl%CzINNxwgw)|;o`59o)fXuRZp>}<~$-9@Ut^(qbrRq#`y^4nz-*4e; z7>lEfHqKzXG3c%KN$>TVT)e<1ABCG_6s=+c(H2JGtuV?%%skenMCiY9xo!(jv{<}Qzz|-%VLVjb#l(si3XSO&dE&&Ao!rRPVDnV1HPvZUGVhvC>zA)}t^T{p ziwcZ-dP#|vG0n7z}c!}qAv47v}VO?J2Jle^Mkd(CBV!Nx2L z%eBr!b`JQ4rESZzqGQH_mh`f!Xj0u_D*3U4tJSB^NCWtp;6~-IoQe3;_5ds)Oct)5 z(lzJnL9v#;=yulmEYZF58?m zzbDJ1bJ1*W=?cO_T;f*5-^Y{nq_Q?TS!Ho2glpQ#PSKrOey+~XwX@&rfl)J?1J6WS2gDW7gL*BTZ`i z?-^bDb#c2+EEWC0IW6EOk^VrLIta7s_V2HRrji~{U{-G$pdMJXMcB8+a+44jhID3i zB;GgTGL2k3D3HiA1B6`@D^x-fYu9)0Gp)gO z3}K4iZ)_Or(0<0F2hj4YPOF(Sm7G(Plvrf^zEa-`_skME+Gk`*!#-A)QH4sk zIPv@EQ8|ZpH!Zd#N%_BYAh~)%UJT7N=j&zJI%-1crE~%gaCl@*W8v^ zfo)@K3TOEa1-$$)WFA@Qh6<0AEZ^M^TDJ46#bLY(<4;Xq6?!3kXj-$9F>Z9fVwTLE zze$pl*q3Ab8QI~+ff~4#BPo@~iW3;WR+~BpVI}Mid%{ebf%B;@9 zi~pNF7i&(pY0H?Sk=oTj-LB+)9<8b+;?X-5j|DMOYB~+PrgqN!QMZxiCaKlf97`wg8seiLu0Dr$Cjf9fqooZ4QP6TGs zo#2j<&8(;_5{Y4Tv8D)XjB;M0kp(^FqVQEV)FLE1cf!G`ds0PH2Zp!tHExX383Qhv zWTK}wgZ}6j2OE(-`iGzQxz*6bJN@LC=SBtVUWbw=y`TK56m5KN<2phrW&AT^8Neb_ z1@&2mLLbcfpNX%%T<5iR5v1$3REsq@sooa7&7*^}$h;0%&L7*8*uLH7N3q2H!0YZp z3mf{Ms`4a}L3$I7W94Thj`K^fb&e-t8};hIRDxMWei*x_4}Ue>(5Xsrp}1>W3clAt z$i=>tf$LQhYE$AiEm1Xs3!!c0}F^i-*bBSYUQ>Y&+`KjMr&)i{@hVXD8#OrhP&!L?pAzdRBOAMT0yqjEM z@fB-V$r~#!dJ($+$oV7`hClFwkvivUA-kDY<+Er@FNw;5NId${NM%ZPW3k8Vd~ie_ zxg4|NOg{IKSdHpY{%2)Y`{P`tZw52SJkGSC&qwv@OQ-f?J}=Kybo(>nQa+S@ceS?iLf?TQs(f-B38mm zcg{){gM+Ge*RDiTcdR~>srM^oh;=5m*SZ8F#7CX$TbwjGi^){I+C+Y9_S#~rNb%Ni z?3xOy-4?ad%b}st8o)9QS+0B&O9^!0<9KemSw4<`DRs*oSdv*kA-27t{aaFmXwvm@ z?>%Q)fq4eT?o(0*do`0t(;ad2SiN4%z}6Nqa++p`|Bc z05$q`$Z0Yqr1^s^uYjVd#X6(eioE|;>K_}<9b(2Ctb1&uPA(+0zYc-8-M3Q3Eo_GV6wxu+%RjG{MQcGIAqH1mQ8sLzsn>$BUo+{4$3Uq|pReAb*i zVDL^04)@}f1BEBdNdLPP+p(_rbkH>nE^H@DbFYpKQ_K7940bycPxy#Lf{8g+L;)mm zYTy#({D4n2^p)qaj>VWKGvrr;{4jHJQ3Y9O9+=;Qqi@%a;Zh?)$H)0GPlFB1jkePy zw%~Pdv2tv_A(~5ffO5Z9P{+E&PKtL}htpK%{$E=~v6;}}R8@0Yeps<1UY+B~^96-)t67Gg>*N?p!}pf)z`}2MOS)q!C$NX8Vg~h}zK-<_$H2!&Atb0-8T~h{ z8P;1Fo+$!C2TW`=UV=oW(PsM3iA-CInX5bqJ!z;oIZDP`dG5YAH9a zMAz<@Vb>`sJSF})PWUv)78~m4IzuxNLR;F$%A7(=erC`Q3SycrZ26Q5fOBHL*Xl+} zyaG||*;3h?<37OXHL;-sbY>KiTppopLyh_&xbz}MIh2B!Z=bn^gj~{!!~{5{%{pf8 zm;qT|K947+Jj-~8xD{6Hf8YZ5t-MiQ+^T=?u5{k4AHtx;F>liPNziV&G=#dE^+G_A znp6g%CNoDW(uv3XZI}<{0>3}qSs5|1c>I6p zxbpv_<8padaXTR4TpCyXwzb&4sCdRv6NDSXe1P#I7L?APaU5{S1kJaK}k1p z93+afdI#+}Lx~@6b#8$C{B~77xH=iuR(+az*C5^>N;mT#It(1U&X^;`>ng!D^V$b< z1_kKAxY5pX#Cm~hcr5~bU_~U*nPl{6C?oylD>(6G>DXR#x<#Mso3paZ8NowE|7nN{ z^MZeVr%#OgP5<^+D=~Md$^BC326vyC=flCb2NA4&#ec4e44!rYl^wxIY(>4Sg@fX~ z-=q#GKCq?}t)+zWW>ebb@S2UwTh8dTMrz{%$ zEuOc(+P5i2SX*rCgiW7WW8c`5PfI@N>a=d|3??1PSp!sz#{M?5y;&2KeiK-CN?i{5 zqdIbNv|GD%E0#5YtkI4+rG;rlElVY`$azY#*miPR>SDI9xy_vo@1zf*dDstju`6wQ%{(Qh0P1ns`fknq=Y}$`{K6cc6Ao@ytC7!8CaHA+}6y`ajbGeUc29{`k@9?sz8!wM<+M^adshJO$M;x z!p7vq$GX%Dea-hX`EeV^>(M4Nw!P#+SC0+nDPsdr4;L;;UZ3c-%GwBCz3%FrmVg(~ z-YVc$n4vhG-?LZVtF<=bihoA3+&Gr6>Dk+HPGK_6kA5ldTcX*7PqUcUh!^O8m++a# zApT{mSzi-wRLOV|7+f@UV6O( z#JnTrOo%-KI)B$P8GKWVV!SpNE`oR1YX~{KT5^F3EE1xb&Es#aN~Foo9D+uJ(+`YAuQJ z793noicm0ESgo$A(Mq>>Opn?#xM1d#Q3~P zn_3iC?(7iIi}K?SU@)LwROR+)nTR}mm@c$wY_wVY0eC80(7W8^b=a34A|A={I32v) z&>Kn6MN*W0@UNUK$0+ltwa;>3Nj{hC%4bT&CT65}jkC#Re^Ml-wjK%rBDih?lMu~! z_m==#^=6n`NW23>BU)PNRR4hM{(S0OHDmp8Lx*Ta9>yu)igzZ^6kw1w+18_76%flS zYTjmdBWc57DlN>w#Q&O&JMp=A$BRroPy!EDsh<>j^ySfO#Ru{imNO@H z{|*t){j=r*QdZ|=R1C7)DAU473OpA+_v9!a*C7T;acBs76nnK6N9avWZ9EI(@DXMO z<=#+Bc!QYjP_gQf~jI(CTjI zcsyWyhvy}CQi&~lRtkUM#sH)TkQ94>*r-_3YX+BIi3D1lx6z>DFIqiDv}A@8EOQE_ z|IrFdbBL9&FwR-4$zqyfgo#kuxYUEqo6IdhK2*Ft8e}u%5z=dO)~x?&YTB50bMH;e z>F`JOPQ*?(zM-`M1(&vitEBaU0@32aQbTn(VNTLGcF^m>O`77KD06H*q>*^@yyud^ zH6ZJ|&x4^4o*v_&R*jqjMU`@Y{o#ojOl(gRa8_tzM7n z>d2blvwh!@U)&6XT68Zz*Au#cJkg3PN^5axj|$G6bR}DvuT^+(7=uiCo3xtB$;Fu4 zku|#sDWP)(ayM-!XJOjksAwxo3Ej4QW6ffT{WKel{;q92%@5?qJ}*k$2nK1<*^z$K zm#6>5;sfi>#CErj(1d5)H_6+w>%E#5ES)4_K}pY7NoUxEEd+I`%yjdJ>Xna*%+*eA zX3*y({o%%MevFn6!&vmhiDEExF=>YD&r7oiy9+{9`ZaE!b19h|Z0i5JSZh6=3LoPl zQzqv$`|>w*&?!IIeI(>y=fpVjo>9$tn3Fc3@?-n~f6y)A^X|$&Xd-%_BWCsQ@FT84 zWb`os2cUG8{^=0x`4aHD)^17?HO?0!>PsIIgRDQSr^N{$KV>Qg$PIw-=Di87IIG}9^G&5wf@ zzx4Ns43oB8+9__&eu^EFYX_MZn~2l~s>!0MxJ=`^=-j~e8V)_y=ibB5-mag7^_u7C zEbnoMQ>p5Qx0vy2V!kiy&w4Z{XVQCVxX`uM%HGbS2tA!+Mn!9CE^i+>yJGgl2HC|% zjV}fAwhQ{iorJ>v+mumuw&w=TqP45x_#08>^`#^d|jO zbUA>`%*dqd*Kw*t(Ta~ud-s=@l&x(rt&FNn`4j(M_)L+=pP%0<&D5V;`YH6~uY0WQ z_I%BI=4Sff^ID*bE!Ty$AcLC2@rwR%M8d*5cWo=eWYG1Cpu68FLoi?4ux$UtHf>nQ zg8XQxmc|3}B?dfgr9sc-^3tcw#~R^TAnw2}-oB?_|4w*v?#xLxXTU=}BZS|KQFIq{ zTlk-5t=?b{J%DkQDu;ro2IzHhvg{wYEH^5Cheky-vu&QpgZ4zcGk zBPBlMABGz~U!iWORo<238#edLxngA)v5Gv$_G${V(uKFsK?jopOK8+zdYH!F|Yks735xEcMXslVrby*26WlSR!x9m`3zukQCPg_cgoR zU5=9yPy5darbwyppW>{&$SF8Am4Rj$1Y>-^IXc8D-9w=3Os{fF+O&hE$Pb<4|zS`FB|6LpF*1sL)Q9T z*7g~>e`*O@MqTHz5@|}nwV1w0x>7`YScaf7#!0$)qFLO{4`WCbX2|^{Vo0})fH2sj zUD=*#ZTbyr;WaVOy&!fbmpO}DflZ=^QCM`xa<&0R$74gbSDQviKt~hrmL~yV?=e-- z5t$&$`H|1L^^?T1)>7~%&re+JZ%YlS2==OEo6j07&k}MY8&IKkDuGi$MOT`MJ4|R> z`D`nTdpJL#PmG*+iQ7afqk1yXDqMv|AVEJ?!!B$ciew*f+-4wUr&hs0gr0_m)a7eu z<|o&!2=6q)8w*`J!B+Sb=b_dBA~&%cte4V&Zh;lY94xWojnY?K-{U8cDyNkR@k~9ni%Wdwu%JyOjXR3C-NY6DkXh;*q9L2tJhf z!JtsWD4+8~5G}=i)QBC}_NeW_)%v2RkMVcP!<1v<=FXIFJ>_g2inGf4I? zC(y(&7mmAm<}03Uh)xq|0&oDgJQ_Y6fJ+xh><=UwBO-SL6q|{1sC%G8U`)FJiF%-m zxZHg+7+M@ie^()`flwRk6~{>hiQ6#>0R_oGjmJ>MyLUQH&6CFvOb8LC2JGerz>GmS zz6cJ)aSEEc0WHo3uwzgoA*g&0)MPB$jxgvr230W|+~OL%-wYw^0sK#VmH?;%f&hL1 z0Oaw;@>#0>B=SHYUFISFf75$Oq@Iy|BbOmYmtHY%KshNm8U}PsL=AJOI6%zmpqK+PZ7Yho~ybpGZSG^ai zMjeGrhCLMU;AHmhB?df*^`)$-!-i*PJxxwXvTuuhsvjF%;Y z#;U76r%etW4p-({{)0 zZhv$D-b9j0&|;5lR0o~lZ<)6M(|Xpk2iP5P{WS4JURPmjZE%Z6v5Q!zbM&@t@BLmg zO=#a0q(Im+#Wc>pvjHCs^Q13B_bk>j@l9N%@yJ5PZ^*KLj}>RpHbEejF|lu<^=;YNxhTxDk>xPaeY8X!lF1$pwe)IxY_6YuKHjWkQJqgF zKvCXDhC)%`Tq2&`G!}|b%UZgq8CTZpYP~t_*?6$75{2;1K?v#JcA1T~((1Xy^R*~7 z#WFkVXx?mS+qld7FZr+C=bOudZ;Wiy&XNe> zMYPzMO67h7#1nw$W1A40wiiecdNAx&Imb0sf*YL0=!L2#);fC=aWcbtfy7w|>l5Yp z4?M&qwdw%U`;2Sy{pERpLLwrp9y-kY`i<-xotS$6Zls6nz~?$G#uAc4nz0FAQd~`d zl1OV&8mjqt&@v)sIZDd?#G$afs_huY{P5Y(aF_0t{CWaF@Bv{z_ABsUE+y zL-bCx#(E_!AFxg=9tt53@2{n1JrY+-v_jG#B*?!!C-AMQ>!7|fzis#NX7$i+2GILy zg+gK^u$}tq3+)rNzbuOr!1-b4?89Ke_w zp_ji%$EkEPLBY5_fFB{BHh8JH*i_gv_=7qrwbOmgu&Iw-y=*FSsO>G#sUDecRhz=g zjI)bNX{;o{0U#tGAONt4IpQjHeq%@rikQG7Fp9mv$;`yH`cX8Wut)9O&&~Qu&ck`? zDe`9d1c6G9CUb&xf6gBSdRAhV257d3z604<-T^6T9*um;*N{Vg$jz8u7xid= zq*3mkG!wg4!wk9pgusrYd*OgWyI;}5Edu<7nw!#6hUmu<@@Hp;PVWW;0Pt`=6wL%+=|_q^-L1O2ee%(pByiS%b9=Y}NG8(qjl z&^uN)eZNMMB+^~om)dQLxEKw`I#^~%8cnC5y8+u(#+KEX9$r;q{2?+$F`oT0o)^0& zy;%36qsJ^IunkmVv-f&;JH+DM?RDM#X%9NKy%*9s^)#;JWm!Z$`OHD+uK`D-`Z~NK zO+PZI1%=w)Htp#J93}2%>-FL_;pFsd(vAYWPbs>bvbjy&0mHaFxLQ#_hxwBuKT(~X ze?V@KiEA(XQC&_pl310Wt;AR`q5N&wG45N>j59(@MKcf9hr=IT7kaImK>7XtH6Ws1 z?Ab=fM@5-m7QDFDaN>#oQr|p4y$vXVR83(Y6e>*l#K$gwyaYUyE-Qr%PDlpsrNbT` z_N?Z$Kpy-{0*S1E@IY{G0P#Os-#6TV%Bkwp79pj?KkX*rhDt7#9^>y ztNAYZ+x?qnIPnwe5TD6ghoE0e4>z$<(xT1}`1`o*PR$3Ii!MTxCWqufvg3Ocr;kP@ zM9FX3RVb5^!uq2uP5;~|RLq*!WYjD@Q_XQd*W^dbkfc0>>m}#Ws#VEy;aDr^QP3N?| zC2>Aacc#6gZcE5wXY4H4m; ztvIW(m9pg6qhKtIxMkg8+nSYQQJo*CpsR_0c8Eosz|skmYw0ebqwNxo3;FO<#Zcxi z(66xt6Wj8^*`zF1(M!zoe84j z0cq=6oPWRl&(1$PuRGNWVgj{4k)XxSRbbaV?S!etf1l&FnxCSf_iG7jw!I5()f^lW z+b23o12x6B_6EAIAHPxyWE1O($)M>FtQ1Kv-=%mnCHh@zPtyL$3(>YE5C*L4V=fZQ z^4~|r0^S;4xA)&beS+6a7ihIfCq;^$WUKZ`ePHDqV-V z)$V~*G`HLqb?^ofm(eM*hamy77SR{ObdjD)>N668K$-j6B&_PuTl>| zILl~tHF1k`H`=q01lC9cR|1EztVGV03V8$F^oUJj3gVf>!!IEuS8}BJ66PV)j$t*7 zzcoyIi`;K?MP!B_9EdYP_;W?}ar|@XRzN!iD6RdLHTPrVspx3PcHGGX;1(PcXOl zxEZ0gvo=+|awKeL>29P|ZMsqR#s-owdb?*9SY#;y?)41DcYeAL(#-e(q;4O}&an0E z%r8RI(ki;=S}${xiD&iwh{gO+*(yb0=9uZOgE~LQwtA8ez*D!TZ2c2Gl^;hb5-Hq_ z*+EdbrB~!1Koqu?inKP0ClP6d@Q18@x>q=%QXY8gjw%Te&q-@UM;^6CI-?5e)+T`y zy*2KjYHe1t$7)jlu&@~QdI&LWorG+AQ$^3iMe|Jz{9y;PgoR2H%3ToPzc7_@U*oRV-E z3Slfn+YrPX`)MyM^#9_mp93mA%e80v9@yB@D2&&f?-x&9kSKURGO9&<#4>+a7XF1p zx`Tt}1s`Q{>8{3=AcVx=!c8Uw?IN zL%Pq}*uIm>eUIywya2oBk&M}cRaSsJI55Z%456Y`pX`*W@U^FnlTD< z9|Qn^Ku{PyGZmVQPs;%?WTfOKg8{JQ)QXgJym|&W4Uv%<7!FiYdGui*$)s(G;KIBBRRV{#m@Yw^p+*RRvqm^ z{&UOGG=-wtzUX@GDMp}N(61FrmLAtHlJq#FndeZ{cLoQ}pHv8x=_35U?yM3glUZI+JH1G~kP^kfjpl3|$He4u-%#4{van+Ov+^m5&_9yrm~!DizvWhn zlIZ_oNA-kWTR3H%7?EO4$TTt{eClVic}aG-bFvudoa`}*?c%qKN?9aZ=KGD6M)WMV z52pgS(*l|ln)6IcPqoOTemKFIHSSi~j7epguJyFjJeo~Cui30V@O_TS*OwysGnOXr z8;G>_TZ!+_*Ff3zm!_vJhL{NV_CzcyU#CYQ90tsaZS0Tj=|Ez&;{6#|-W2*d*E*C$ zIohZ%l}e}a>x4z55wpj-cC9*uDCv<*)S`ihV1J{!Q4Mm_{4)XhI)l&Tds%uE@1|R7 z=C;|V(!DHx%8InBg33bfvk-uw?=jpag5xW)6;&^9w*~t!b_qgHom!CV%fGCr5!X^} zLD2e#+S7%xGx$27Gk;mV>CmK?HnEC(LdzwjI0)x$82d#x@t_$97Un^pqfBpmc?Lgu zOa03wx0F>|R&I9(+;-&^pFhhNYt|-Al#$$SG%hG?$m?6A?Jvz*<~KKZ*^V+;443n~ z(Wea}gQB&n`pldc7RKkVEi)?3fZMEmlszp0p5GdYKIS*+X&Y+!_7^I@%FrTZdD1fV0`fLFI>Wcv=U<+=BeMrTPWzG|<#rgW4Kt2#(kJZBZVCJ2PEClLei>(@+i32Cu|yMFx`j z3Z#2zz~sWC)1NX}bKao`0G>Jf65zt3ogEl^tbv&_h7-aH0BT<+#~03&#Z{6B&{?e; z3Ii1}$a)cw21ko%WUbCtc!i$tWa#?455tQilT zNMl*&EKwty^*843iSQ&=+9~Ad&$nXmwBN}&W~mK`JOfWR+#YPWm}Gfeh^tKAp35@4 z#C-r#@M;1b|1F>Of^!!_#Z~GXBdON}Mdb#8s$%E0q_mWE1XT?5EBe06hv^k)2)IqS z9$6tGW+4FpLIEFC9T&!1QwdP_R{Tev9n9n-9q=0ym`GO&>%%fs5lnJos3p*6S^}o! zcC4AUONq>vHTf}VqxaY4{7S#^x!p6v&97I)aBJQYSzU6QJ@CkLs};!c?Q8s(^+XAe z6}5dW2^*IuZ6$l0;5_7(Zl_2;G{*Ezqe_y9(6&`j`7NjPAcXAoEV{!qD34VTR}Y{D zXw*@*XU)^tsgNefR?liCn=+9#xeSh^i6^MoXF&ALjFr&5d1GLQ?ZQNq!gA zdOVXBhU4v0rqGNIKQ!gvV&7^tyAmw{>&Q<&glJE zq2|6W4OnQCQHBiqJ}koQ5>qbYo;aI$(%hb$E)R^9YZ&+-5bv zU4tBl@xxz#(S6+_npyKEoy%`U22b0rkNY}L7*7^A6=_rSl^RjrQ?_xGWF1+ z@A+SDc9DthTth`|4|`vV%}>adbG{sqnXE1EY(uI8ze?v~pZ3_gdFk=5N-<2wb?&Uo z^=9kvcXzsr8t9xf2E9HMc3Ooy{~dHitu&>2gPLdQgwyX?o8ejNaZBV}Ql)`?jVYQt zQE{VcMOQzEF)4L;Lv)VrIJ)_%58ze@Jj7djiWLR?$LDAFxj)9NMtkadoHlZ!*5A#G z-^*!TgDxcjiS`W?36PXTvJnCvizk|l29HaIJ%Wz3+3OYwx%2>PwJc4Fzn-!{e76a0?7jri1E$yw0P?M-?nq(Hh9dz}6CHB`IY4N1dTkTwdePk%xx{rBGN7}%NO}ur))O9Pe*NG`NoWBjqkgW- zV(7lGqF}FDKWOuPoJK^Pc@HqP?ZPh7{ESMq&W4qu;HSY^l?TwXf+=#-6s5o1Mih+t zmT(1(0%u4V+f=y>EN9=%oWWz7a%leDG<@vqq7h3`tr%!1mf~mIxv_)>vWcFWy*B)p z>jvOrm=UP!_dH;8`PnxXL49=@&i>4g%KMSPhp13ex6n52ksRib%2J%a$)lJj zruW+$iJ9~weoeBDk!Duy_?heI&1}l}w+I=$EJsP=`IxxFemb0V;VGRehxxzY+NT>= zq&|EwY_GB#qh3)(+)}*4M@meq4e!g(*M>2Xl zs)Skc8MWASVDyr$uyuTNf0oVohP8c5Q~cc}t`db*v?;X##54u0s+WEd7I)5Y_rUKM zAlB3|%wXr7jSS5?2(kFUz|)Z*qLUY=R2z>84f%9owxSMnk#g0Y#cVF)wCb(zVN~qF zWDJwMiXU&&M3QOJ*17k7(ylZxa2#l^B=Hv1s?3<%`XwsyNF*U>40^3i7i72WU$|Xw~+>^qXAm35ZNxDU$*r z@fYz3$&kmkYJDq=E6KXPVVvSIs21wG0wdBxUf)x$jPW8_)786Eo%+<0kzSfH_KKf) zhGu^ojd912PrEhOxdOu-GRG+PTEhNJ;)N`H>*RGuhE%U>fY&~PrPeluykR8CQN$Y5 zr(@vx1VG5Tkt8psc35m++Lnq}pv)2x^gVo>6RyM#@Z64YEqx zv_#U}O&Y((Xhm?4CS48fXpS;@#&Rvus^SE~TGVTAaaAXB{zGXDG|tj#+-s#&<$*VK0V)$w$bB zETR!+aX|FKT=tQ~L)KKPU(yP_7;6@!{Ggj*;7W*4p=xTqkg=66LLB(TH(Ry-*6d5( zy{UdIZE<>Q7*#{P(A;&v4p<7DmmXj8NR-ae@KDad+V-7RVhq$(*eZp1zF@*Iv7 zc29M(hsQgRS+06;{2KkZ6>9;tys^7{!x`vb*u5hjjY6Ddi@i*&L`I)>j?QC+=vK$2 zIg-vjv$_kD7N197r)n+o?DKG1LmMcbD2gzU#;byA*-gG0Z^pR66u%3R&S^XFB+(G8 z!SC3C8bsB{Sp^%AIWN4oi?;l^;?`EDR#Q^QmQKL*_?*)}%A;c&hBN4?H?S2;Tgqki z>S)Lb_>5kfG1>?#a&l0vaWfsL&_-}MMd(ZJ>#8YKzo3_WtgmbwYPS+~OIxbj`q?-A zO9F{te(ubT5OK5^MP2C4Va3M~he77R<3_l{p>(XDyNS8Nmo?=4oJR%KpfIyuI9Jz+1V6vJ;TQWgty?y>0ED7VvtX6YBx^nh4ge$>e4h zT+v8`Tp**OA1qFQ(={_|ljCML&0k9}M2~Yii?bV!LF=WU*ABpdJCPPpZ8=87StA7l zfc{uP9`vwTii0xF$&u8(#2<;_UjUT%csYJsU_JsQ1)yY(#O@xFgM-avIB>28Bv%3= z^6`P7H;`PspT(?SMx0hF1SpRKarlF@#0S^`5LM~{#8^KoC;0&1Sn`@5kl*qD0c6=b zKo0uffE@C8(m@DOv6%T~I?vqM7t8HuWq%^vY!lQQAWCH7oc@syUmZ-s`b!)J=u!Ve zgNN0Q0oW+Wh-<6>*^=3boLex4@WwQ^OLcm3z}b5@RpJm}#Mo3-2+3I#E+pzMF+20koZs}WxrWfYtg zIZQ$ZQ&`d)Oy2AG3VQHfFK_1GrJ;B?RnN979{MsV{Kxb9!JxeY2>18a+J=`72w%3_ z-qCP8sSDaN6jHm|gf^VdHR$+k|5?Z=$+T%=2e_9to(dwf==)-?uB5dFfG`OxbVW_j7VvE*{i}j6l;A z*lL;sfJ~9O`wq=-4+1KFh;0j@tjtgjtf>{U+HifC6mhSAkN6BJ9T_XJVIhT2LHVzi zG->Vn;C?^ego9;+E|@Y>Z_NEY88ZW#^GVD!FNt*D37Yp=nbk`hNk~rkPEyaALLz#eZoz&tG_N{D zHwljtuY=lU4+ikOanO;!{9jC+^V8DPeYIJvvZW!G#x@DtVxI@iV8@hNSCN|*a#x(M|pUj=a=s<*FSK-Ue|RW$8nzTV;sA{z{m)iG8r>72n#0B zn!y>E8M1YGJ#p6K`lHrD6n*^$_uw}uhFR?ooUj3mf?+xyo!@>Ug2>@hwGLa(dTx@x zr1(pCX2yVHmSe*MjFK^RNl73GY#>SZbvm1gUU8L)(T(h22FH6)JlQb$fJT%656{Io zDJF&aL=d5S|2pzUZHANR2|BiR(uG`knH7|um5h+@<6Y*HP(qh>#sWe(l)2yW961c!z&UMw7^fo%p~;dj*ihTY=zejoz4NU zV{b2^7C5;X}4)@*1S_JUmoxm z5X#iVQ*3-rBM`>iy7cwq>z>}jFHMznWG+*I$NhpV58#aDkx!&LGUv6dkzFuu z6sg`bCJXh1OO7D9?QUVtWNiZQZ5UX(-I}gscvHNztXJ`C8>^s(*u6NRvTx9{6WbGD zL%|i0?AzpSi09sC#YJAN3JK`8IaB^K71I$&HqffB{|zAQ*+5OvfSW~)vCHPBYhM`r z(cVyc%yds>@Y-eqD=-WojJrFoV&F()xTrD_b|`qpCR{%A?O2ovV>BsT-7mDB2>7e} zF3dlBW)0Ki=4ero#HDRlL17M=KAFhzX}MhQ@CIUPd%t|lN5-jolQeRXk zx3bo#?nFtOv53D?@7aFnIP9xv1Y5YR3mGPpt~OTs?o7>EJ;d!>uNf0QNk(OyFLl)% z7RHl6#}rY=b?!3`c)kJt_zvD4N8Gkh8JSDcC!{}r1T+CW?a5J*x*W+F&vapZghnpc zfJGj|ZuR+3VX16=F2Lu4&qU$d<>V@QD&25P@H(GYR@f{$O0ieCY(a3}mC)xqmbnzC z7u0|4GSvd+?)*M0e;4OUN-Q0Fv(afAtiIv^6B?rZCL{0mB8xZBn;QN0=t?TlnCp#b zE=}}hdpQ=v=E|bq!%Ews@y-Svww`CDC4{b-nxfG!9p?x=PgPw1W^sQ)UWH{9uTeRO zH55-(lkWTA&wAUZMNZK?SfRf5fopMUfh^pfx!aB2=ANS2Qhv>hF!H~V)Vlkr0!YjU z$uo5t=_db7M|%@qGdW;9sz=QuAgn#&*Gwfh!I1V|RICp8F8grNu~0pUoTW`bJ2pzVL#TK2Hogk51#We&IJD5-<;C{z>*D2x>{GIis5V@)7@u8Di>^y=^9 zdKrcB{Cp>``FL=K;0H^unv%G8w6wVZ#FllT=02WB6z4#8Y-2aaR+uahotbV7&P*8z4Ng7>W))n=}ELd z8A8F{vi3!K1ZhlFPsiBTKW&G5-pArR7acUbvmrB+p}Bbb`08)M@-WNn>{z^SqsY@w z%!WJq(bnw|Uv2jD>ks02<3)pGFc=AZ*1FP-xzD45b>`>3wc-k-7rRc@o^GS2l0J9d z>j77r+}y>@>`YV53!m`IkZ)4fu?(1CO+0^xB9%b7;M(T!Y?-ZdH;T7d(gqppy^!gE z2U|1WG+ZCb>`Z%a?Kk-SQ=AA|KeSC#LsP#YuOV9>gr&b_H$knv(_%t}Zq>^hPK!F+ zuS_r`;=hNY_DaawyAqMeRPQnem2~ZvPs{8kdkYv zoV53-c-?IOs5+@nWp5&#)A%F6ZjNUo=qLGkZINxfY2y_Ke0(g@`9b|zf|~$6giNVH zyX=b(tME`xnK6$S`_GD6*H?}ATIYY#eokeP-sBGP>Oiu4d2G51ST2#eyq`Xj8W+DH zwW7<&Tg3JxlQi>2U!|bg)GYkdD}?$2v>g{e=FlbcKkQdocKdln%m8{8%+|&PgY|J?KKfQ6toZe^~S3HF>^)!1{)B$;85sjJqgB_Wx@s5m;J&fK>KAV@!g0cg4E~9)# zN-94aBW|xnl<^_XcC{2!*g6jd4T{+Q2pe=^VSwrzB22{pfO7-J1cJ_P7bE>TtJUQ4VsR_c1^g7M z`BvF1NPd*Q0)g#bzUaNlIEg;R93`Gqm~4jAbghXKKEKafkU`Y12K7u2p^hI zFY@0zcB^^`Cp)Y#{h;%4lt7WRqAr_R*cBj+*`Ko-tW&6I&U|-KFVT5FGzo7!2GY`m zvl%AqT}&tj%0mr`xFb&4Cg!PUeGv2C5&a`~1|36x@v;2E@N_JY*Rjg4PY7+Km_t|O zby79gJR_@P%<%Re8tXv>Z+dEeMcmJLE_hl7Wm;vu< z?0~ChoJ7d_*rl5dU~2I+Cll0*QL%DG1_6tbnHSjg9%w3=`>?!BRw^@B6c&&gZayw; z>PyUyz{=$mkkB)4|LtU{HWajUSyFt} z++>pH&!B&$pkgwKF@9ThN%=~dno7%@C7tb;He0>!lUQoD0NoA5ZT0{G6BhgGNrz7T zLf`7b)^Yj6{K6gEyc`FyN}@m`5Hq(A?m!Xi>k`73pw-77RwA+tx$I6Wz8||~&xIo- zA&!Q*j4zu)ufB13$YF=@^5{OcK7WQ|y%NKHmR@@ieMb@Np4dqY>ikr+RRt=js(2es z*WKfNPqcynXH}G7VG$lFP#+_e>+i%YBZJ)d z<-CUx8Q<8iVr3q{uXx^@h`X19F?JTvW%^2B1``0fv82$Vm&>!{`16QHI-E|cR{!C| z9i3?ly#Rl{W$HF#gCS4(*}BA9N4)8J(w97^(v5;5`J7UGacT)AOiA+*E92)_PJ9jO zdrhHXWQinOQ6d@Og>LegkMy&1u4hZ0&yx8DkGvYJ5m|5n#zL~}rNm?V{7Otn)=$|g z#n|V`B}$h_Ie7t}2tX)Aan>Q{&OuO`knvPRMZybG%doFNs{SGy-^Xe^dIp?R2qXe6 zf*(~j5XxD_Tpq;}=ucTgj2Nje@k0$tG=~v%jv_}f(%7O@p9>xLJok~Jgl*v>!T!=N z(FpBdVfMhQ`oD?+duWq~vgx<*(D#=*Usz~JdknX2!8~dHcIlE9xJnszz0X+qhbo$g z0jZ8+xh0T93zNjH9R{Wzo3^S7GCz_15h?bg2ZQHAzS{a;GmHdkkC3sF$hwR0=W3wy8Nh{XCjtNxgHd~pkbR~0olGJMA*n@i z9m~V9uuqiBW#F?K!N8-CB zZrRcC_AtBB{RDLTEXp$R-lrk;(qMQlNxefP2Gx&@8r8iQ^H8-vy(or0D&0OE47b)3 z&OS9)I{i#FI+Bc*S%XP=uN|`ABB=l0V~i@t|8x?oUX!sy|34X<)F0sRXl=J5CV=RR zyb<8*lt(J@V)_~%%`NrfsK?UwIL!Rt&Lu&!XBlSs_V+ebC@K*Y28yDB;6seGQiylG?690AoK)9MMvh{g)DBQ4J{5$WED*&M}i9?D-&#}Xelm?V!X!E7fv2(hisXX ziPAC;c)zhj{?Rwa!W`-ysK&-a?O6@r38>6kLQxGc_R4>y+RMnk9Gr0O2Dxaq=eQ?N z{{2xO|1^N-u?^MPrJrDF787TbS78^XT!uN_`2NJv^Z+q=Ow-zs`~knGU9Z6_iaM)@ z%3z$dQy<1tLw%;`)$XcT`>OwEm&alP2a9BVV363SsIfAaVja?Gk)*Pd`bJ}wKrzNJGdAJICXnjmq-w^tOp_EOi{6mDnP|x1X&MH1 z53=B7DAcRN?(J}>@d}eNHP@?IZPeV+PypSOP-X-wMsYpnZQMZ#nWhhxNy@ZE&r3RR ze1`^IEGo3k^5!HKqjgrLk91XnCp!IAV!ga*|Nrv$)D^RKeL8}NPB+bq>XC6=U8ZL zI4hO?H`URpi56U<@(>k%PtQ$Ok1gzJwkvsReVG6Qzmut64Z;*W-N5srFnmdA7@{Pi zn3PRvtO2Ojb@rN|YeL^GonBg|h(hqbg9qyh!0=Ch6DdbR1F!_CH@9gVRb#5WU7jDz z>{IKBuzr%2as))<*wx-%*eQ#4uzsDLu}ggA0oPG>U3%gCyNHOV7Jd`lbUObwG;3ZI z7rm4HkVWx|8sin&!!Gi1a>2%MQDp*tXX#caJ5KX zu-iYj&G{4`>qGPB`%7xep+D#=#pHXkyDU_qIJB@T_eWaIp$z$^_@4B#749F_wr_zK z`+UQR&lJfcmupuh-6c_?Fx1J*ABVS^e3SyMGxRJa0U{>gy4XRXc*QMxmSFbvx0z4J zQor%&t>$JucHZg=I?G!t^ChF0{eAAimvdvNiJnC$$x-$@gQH2XXyk4QN!xojwXo8m zNekL(^M2jnt0bS$&AuIKrtooh5>}bv_D2OK_&Ta&zS{UQm5oM6AMlT#*w(D z!JaKCc~NeRkGFQP#q8K0HGN+fnu|L!O#D!-uT+{cc;Cn>XK+F6PYst|T%)5t85Mng zQahJII<3tp6GuTLZ~O2LNgrC5F*HobH4inl)W|LTvaKD@WR(&m2c^&TXD9HH%Rfl+ zg%KtpQG*m>VRD{2Wi^fBv>loF7HW=6<79*AWTF|H5o0x@Oyu_0tRioOPNW~jt!!B{ z@&(SfI6-oI+E-U}GF4TD--U_IVR!&J0APGnh0`uLaP{`wW_&t)U+A5(Sfj$|IGju!(}qY$^%^!;*R90W|XA%X|ryy}IVh zMb4II46T)kQx0#(x~?%$&N|1N6J2;gw$wQ23bC^H#`y-m5f3Pj|MO_hHz@FQ2aQ?RV;a~`kk}NoodJ|=0GW02^ zauYq{D;7P(8JOZ*MSd`VF_X1_)>P_DZ7pz*EKU7y10p!3EXF%YL1J3U=#_%uAKuYf z{Ov4v$t(Zq`!+7smxWZk>rz3F`W~rL6fUNzH^0%2XH(`EHlzM_n%3O#dk$Tna(A5Z zC0%%K;RJPRf|}OYKMTsS%H7AY1s1V>Xc%} zlaLGY;?yhe8}dBRNHI4y>es2rA{)f#Mvr{<4qVY=_cK|D4Mc>qhpVl==BZ zH|%+TTF>j)@ALVYt+*;ZXDyedaYi~qs^n3{!g|z}0k&`SmFG6XfG=r8Le|&X`@5n5 z{ok%Wu+xA5&mTenf|z@tnURPO3R(5D^%ql*?ObnsctxHf>oh1zt{UcjH}#z6F6(9K z`lnB0=5xN~iiE6J_d?~@f9xC8J?_-WK4oYiIO=fJ7#un~h1Uoj7iByYGRK8^nBw0r z0M&BRMh7%t3F zcF#&BQ%eQ+>vKS0H9BL>GVx^(TQ1`FEpIOy7YC%Ue23=X=f^B$zTx;g)d0cYA_E3@+wp*rrfOkw~PWFP$zMmHazj(qxL?M*9f+DCBCi zM%>9)^ybImgDM+d^xf(t(hpF~Z-DTWr^WVJ&~V2y(`VF+NGidB&+q(wg8%dVv7zYO zmi7IT51XmRkiEI_`8P1-dp|^Uq_DoWquh~(3MJYcZSknMx>WtgSX1FD{TMFxp0!jn zVMgAavEWJ0n6JD?@$1PqNK?j%gF^E=WIly%xr8VlbAwI9=p3_pi=^U*7`*EuJ58+P zTcHTU&{f~tD5=l%K4+CBbrKQTADCtK52epUuPumnb{@-8k$|n`FoDwb9{U9iqeYSR zx%)ZNcV?djD0yT{2v2K5;nWqr`WB0-=I(W;3-Gk=Ug=!$gTS-SAs%D z_9OjqEk_Jr3(YcNlJ33&$Y|*zJ4G!51h%UuejZYcrG9_}#_ihtvxC<~im@or^7nBw zTKgj8<4PH5y3ax~72Uo&hSw_C$`(;r&+8)x1ZtMm%3_Ug=X&8l9Gz?QRdoSA;}MpM znm@kD{r1#O^1CDPU6@YElZcK!kF;{_mhv6-0Qd1H@Q2XC`NNG=g;iLi(Ix@OUW8$6 z{0kLSjVmTexuoB{qh6G)h}{LGQtRju6R9!o$vJ&Qp*I{xRnHO9Aftv9gYL>(?@>F= zbEl6=Df(N5==vhZp|g&W^}CGGdK4B*EFsnKlPYM6kv4Kwfi}$ct;m%rID%DGUrnjY z`!GhA8Dix<#*Q5Kd6{B);i)No0UTNtJ=aA^hbJ$Q%$#@S|8!y76kK0a1-hlAbo*&w ztmPzPEt{g%-Zr2n2UY!(eZk)Hzl!fZ;nU?-X4q*IlmIfxep51HpbK{7WlAx7cq*IX zq_HrH5E)=Bw-(M!Rp?!Ds+f<*Hbe&bnZc`(zVit^E2))Z##Bk1e|}g3$e6Ftf||v? zPes_8!Fp#{!Mm*2*C$o93SMkI$iUlyS|`FJTrmg8@*|ACbwn~X)mc>*qo(Kft4g!2 zC;o6<$7PqEK2CqQk0ZXDvrZYzKgzD?n`|E!%@rWouHd%Fa1~qAB_upjL+|Jom$0U?`RnXCI@XkOY++I%zmoKQHNdS=-o-eY_GNbzP5@S z2z|=xG0*1Q1y~PHz#n01JSC>)T{@lOz6vYnAKsymlNKw4{60e^F$-;DOFm6_jCY6q zC*+phDEp_;?R_Ixa`gZ7(YfrLEDxh4m2YzdmJ@X){fK8cZ^GAq7>8)nOa%453P zXYwV}Hx_myD>Sw~^|rKQz-{>OCNUOwr?p;M5yJyls=(Y1RH60Mrj2*F3i%@TWy0(n z?TLJ$%E1Cfq`Li>U672$2;eFf5cNnXyiqq`)f*1E64{q${X9=GW~9;N&*I{ol0P7e zUbOnROr@)1+6{uVDZwL0#XCoEvuwE#VD*}Sgt4CeAwr22Np5;X;cQ6r*;+RWn3xZF zaF;LA^f1Zqn9+~Qzs!JPKdtCY0c;hWz*$$;awk}n^cTT z-FH4ZE-I)|S}Ydf=POyr)d2)XGUb2z_ z7tUUCF8CvI*52hAV6`6b?4%^RmKa=MMJ3QqLC&>REBD*+%kOC{^7E%T(RIh{PV8FFR(ne#unn-rN@nHf=2{Hgc9VI7t^n@ZD8?~Uqn6WeCH6^;#7}e2W1$!ewd1cho=LJ((9%4dW#kGx(I8u* zcvYjCvOHi>zBe}CN>0~N-8`Og-LI)yFCNLCkxxZ4O}taSo>Rd|`QUI%!r}NtBw+0@ zeXusqgzrH>g=N0)5u%Tfrgk7;9JZ~4U#cYas?HzQJ;!wvmS@07O+|tsE9n&N`35%g z;-}{RWYUbFDhsZs^}&wEcJwq=w^q$q9Gx;KmpPEo;HhEt(~vDcS7+{&=`Rr#KjoWw z1wEgf6!yO+@!tKD@Z^nTIQ`nkG^nw{i3Q{HTh39@L3_4eZ#?k@b3(*|7Q-oDW zU%6{yED7PZS3ZM8##}C4Fg%-^)>siPqs<_+q(s}kw<&7gzX}u0NRMR4FiI+~dW}u> zZY%hoD$RM$S^Mj#_)dfDHL{FXXAMns&feO9jkoW`X9~(Kx_nn*Ch8jW*skju=pF-r zDd^=ji;$6Z8(obUIW`NmduMYww?ZB*tBFJ$v){x3hc_5QxSBmh8|E2ow3|h#wqoAz zv(`H|-S^~1orA?T#p6cT3qn3Zs&Xx@*pw}KHCOP(4E%>DFt@u^d6VITpMmN2Leorj zzE{F9u_Oxf7C21bHGdhYs{x+$v`g(I7 zN5&oJx-A6~kb7xpejAf%6Xr~QRBvA8#U+!ii`XOCSrp+IycJSHZf~J3mSbc49+o_> z{b1jwyaFseir;Q>5Q?5dQF+OH`OROdU?oU^jyG$4e~%Z*5s2YHDlq2Cny`f1rV z=DISm#{;A?3l{B~8x=?v{Ghw)N`^tbe;uD}JS%J-4l|1t!iTTqoowc&wG=fP?j~Pc zsS9&$Agr{NE{q56Z$w$!cH|OBXzPc``=V2#U2mK3`#La6CTd!+8gV5_tI7`efY%=W zy03yjK7-bq0&CUiXQP1uqn7oUIeFV3&R`JP+uumPiRWt?USc7(jQ5aki99HvS@e{ z?btH3QO9SX&gn(!c`|)TB=$@*z4tG=zlzGxRwmCH5-yT1YPu(b8q?=T+xO94gKA}t z0T#XM3l!;`rU~KKXuyKHwg^s4_7i+Yao;J;UWmSA!43oPi&3HSp)P3e4P4uM5q^F$ zW&35GX(;c4?qA(h+M+F7QM`uBwyBv`>+x8)T!FN#k8kG7TW+a`OLRJJB+jzEttWF{ ziE*)#rto|y=7I!&FCo8EZFRs)e zptV8az7?PM<_A`}N5QU)LX}#P3PmPVHzn;;T8oQL5%0^-08tQ`I1S)e+K3IES8Z_$ zx7?Beyjr*P#@56JIEK2gVO3O9j7}ttU~ZH3%sU%@fe-EXPU8@SSh|YOvFPp{u`32tM@pt= zzeibG=U-%iwqD6nWAR12k^R}HP1uC02lbB$GZ}1p0NSo4yxpmxft0Q*$Xd`B`htpr zcQ{8IgaS7+QXUWWV-eJ|HoF+xewd_lh`M(s!fz|0dD5x$%KR-xa6Wf;GfBHhe`Pf^ z!<5%hq;%-T{ic}})-b_u4Q}ag0PnV|zRa%*eXVIdl2ogxb879wrXQIH7Ynuo*kNeC zb2_=MNWV`7-_8Z3fHw@hpY%y%Lm*C zf&6`up^F`{!tER$qX-EP+0^>vPm{cNdm5A!Y>NDkM;km#T|HFK=qMo$YAuVOkTy|S zzg#;L{CNRRcVifC~^jdbyW~=f#yxOnS*N|#1xXNals_S?;$sn=WTMqU2c%stS zIc;wccnbB{9R`K`TbE`h*h`8)KZzi}xTw#VNH;o}1AO**iZ1X57CR?q&qn9uUC8g* z+_+RPMdmH!9U zgRT~%vqR|NQ7DS$V06>wo?FoSm>n0u{C~k5dslE3z?-NeHl0W!EwL}gR%VUK8P!>x zcG?Iocg@)jV{UxM20|+v4QWw4_`bRoQr!>xB%Yb4Bph=qDhJufl`9^+Kd#Qux?2jf zDu3t*6QtiL|M&x*u|lC3LftE*yO8^?ciExrlD%W*`~BKLyi4Y2p%UcHB!`ILTe`qsLPnN6Og*&g!FzRthbhYP2-kvj>N z>bH0Au~t+Nwjs}?tCMZ)O$rvKn5QAL|A|ZGnsY5RS{W8JFYo`$OL_3`!KRx&O3|cR z3%%lmE`7>gT0#DOWVQ*EunQWzfQe=QL3fG(R>8OVK|=}UUHeA zC0CKdBPo>o)V@%h=iOR|g$8A|RNT0fSXtw*NaY(fVyxe&7d@|e@D6|alK)yugyTbH zzz!=YTTmD1W|C+jklW15Mg16|xqB6;EhvbIf}Aa|Br?0^)yjwA{I%<%0VRIMN{rDH zrr-C4&q%7vwm6Qu3}+@z(Ny(_AMv{idVN1+)x-GLP(I|n5)YE)f+q#We+261V=l<} zH{lMljNrr+qn9b#53eCxLU6`Zxa=yP?}#?KIA-erQP|C8KO(Xel~iEtM6VKl_CuxB z;ZFCUd*dR^jfKqu$hKo6tFI6scW6GNe}f^M>m>?CRB~Cajd`*s!P#$F;Hbv$fV9D9 zDTQ$mBC^8p!J)FYtKX2*i;ULYtWJBJ@pz8w;b<7Yn7*NCGgcbqZCj!jU$kJjf=25) zUl(@8hSaisS#Wy*^mu*UDW@G5*bzs4ZVhWk`@p>lq^Gl-$3nm1(!Kmy8CP#BTk}4K zQ4|2v0+z5|1Yc?qpHzgsJQ|v(^NC@+Z(VkDY-*BkWTdU22PsR8sCj7U|mZVA?ec%tTJp~%JSn%o9q&qR1NJZ zVml_73cs=U%ep*R&HKJadAca~2&-S<84(puUAHX4=tVHY%LJX$yiheL;ulyjbUqCy z)$KC2ujtA8vPP0(s)hkg3y~rdQ7v{#O8LmsT%8CU`RoAys4St7L^f66Q>4pybb&Iz zRMrA<_v|=!$6hfcj(gIH*#^VG3ncIXoI<(FCfTrHO3zB>!2R>3!iiD<%{nE;d`a$d zkR}+W$LYO%k7;adWN)hvtR;ORZ%U5MJH_aq*tpn~L5iRsk>mn?}+v>c2L)IgcknE0vyVbN0}3CM4>T;|K-f8;H136Yvx zBJIepR8`6A(Na^|9b$j;-*^JMZoCMoPEyqIFD?64i3&*jw@CNuv;r-HUsDLe?$K#b zNR^Fqw-555;lN4~K6F^7GmTXk$Iy;vSzvGH0)XOj+r;DA|C}ZSZMQpP+S#kyUp)r% z^^#fff@!OOzDS_PHe?P1qWcE62LQh&bYjCgIe3AlBtKOg#V<87qxtI(0DuI!s^hw7 zh5`ONKxihp(Qp?vO*bTy1q$m9*@i$}0SJz6EUcTBhM6t1OA`kW%IrE|@6IOmh?Mti zJ(6bt0Qi29gUJE(07)%?@-=ii5O zz}HyaYG_PG-EC=3()*=l3ZE$%Q{}f4|7)SmVp>$S8!3((-A6=Aekd*ZJHz;TJDU_w=pzZpVSc z;mb>c)5^4T3hy|7S?)I_P-SaWzk2;%;Nm}&(8EIUg2$g5CJasv3W^&Z3mPc0&5C3474SRZ;;A@{s?&7XOLphwTQbP$B~S7ZsTs;+umE~c(UAV z*8RGvLz!>wlJ#%vI<{u=N_}6Sg+iij1XGB0&;(}ce}7frnzYs3XXYg1tUs&xtH8Dx zu-wN8F-m(Tffg(0 zFiM^}0by)IFD!VYSl%*&m_T|u>Zt}U?S&OIMBz+S))nk?8K;=3(1>ivJWA_Q(rdG6 zN-~;Rt%2|H&XqPB_0POE;>-e8I_frJD)8y=5gQ$K-K85M$|rKf@&+CIRNu)wQw9a9 zA3yD+dLg$ss=@PJ6>+V;UhHiZbu`vGiTe;AOq%<0eZMUj`tgMrAIE6^eco9V$R%KW zKMC-87HqiXpNykyQ~HH;>fjpi6%)z`LN}OU_a@51Im0MewO;*)7Rr%!?78iU!?M_f z|Nh}Q)uIw8+$=SIxoDm3vy!BdXK+x10fn`(y~xdQn&L_&EZRmE*t?uW3aDbBg=??Y z*;|H$VITa>t0VVV-Txfsza{%)&-3_Ibl=TTZBvRyt=Y@j_ARZ?=Nz>PUsRfyP&t!_ zja}^x?=fpJ(LwkabPfe36Lh zEH$+8J+xWL!}`dx?6LvfmADjMDv3+p!mK+xyezC-gJs}jjrMF+2fi_`r$k3Hm1z2X zpb*GkP;neuP(OUULQcU%Hp<$Us$j%9z!W>Pw1l;pTwD{3-9OOmVO!n|#XewNFbdT+ z2L8M_tndCI=}5zb0|Jo(k#Czs|LDMm{v(l>{0IpNQQx@jw1ltSv4YNiE6Tz^aI{ML z&Y;$}KViyh>rfq_R=Kg+Hav4Mdp9ux_V#KbHdknYAJEQ7kjWd#n|KTI9oRErij&p0 zxw6o~)d!_OZx`|LAn4;9jrhnDAw^(5E6B=bs4Ong^L_BxAHcH(@od)}~#+^14OeoZR+e&kgHO4sqc zfM-U+ccgH0uBEe~*cuG0P)I92oPXg@A6nDJ@-mw|;7hV`5`jTA!F`*e0QZ*iNj1rB zT#W2p@YaGfrOc*DDB@&sp^aRqF%6rVA|U}Nyfm65irO*dl39t7O^l~%rC!PZM?>?J z0!v2z*jnhikD^CWQ7(=9ACk!TG1v4+r_vQm?7y>1vuu3ArXJ zRP6uW9V9?nxN?&NUiL-TRm)Ka6mAvlUxLszcj!eSNE9_*maBMXl+MFuLM!-~J!p{7 z8nwQ<$|)~qZW$PSvk%0nyImTag@Sao>RJzng_As*Sf^3WuJf?L63(D{&?Hy5u@LX-&uLHtw$*-s^%f&*V%V`oCstNyti9@Ovy--vBu-m{gmq50249F9)t$Gm7}u z%)ixWvi;-owK6dB*=2oApoC4ED#3U@)&wYLW8B6pIZm5rf#Ef_ruC9wv5D4FN?&L) zUOFaJ(B-z>wl{s3f4u!hyyeI>S{28VYQ*|p>Q^djwk5w>)Ivg(_p>sI)myJk)46%U zS)#qo;O*(RN8>*U65_cTdYO;vbao7H4>twQ`4mV=TUV?Az*l>7ObVPAA=QcEZM=`~ zD`VW?A?9uTI-WK(j!&nOUtqF910T$5TZCS`2&wkW_GF0pdvU9J@2izl`sf;b)N*A| z=I4iqw~y~{FCG7xIbTlfa8Qns!T)yRX~FH>yuCTb6fdH_hr=bA;Dt>GCQ9iPR5Hv> zUgQ7)o;ZBwBm8%6rY;l8cFaEts%3d^tFcd$#42 z8fFbtAP1?l+G$d`l-f^`yU$^b|CE-K)VaV4kys7ELJ>5r2ffZb@e3r=Dpk+zYIZXvq`A+L($-R zp|M>VOFM&4k$2;5LW5Eb*Y={^6hpptb9=y*KSj};Il5FkXi|66Q^0tOv2j!0o_<|Y zqm$HG*3oN|u?qtx@6R~$_ktt7^Zh5AaF3NsuR!mck;-F$IvI=C2%oM>KBe)%okL1k z;IM4 z(hVh>^sVSOf2V^~$?Q!k@UR9@DC&)3ZlJ<$m3T^?j0#7f!o!nTS1CCD=xIX^*aQfA zCZwCUfCzs+=^rEFBj340!+n#(ETLG|nMm>Anya{TCPO18u{b;S!9wVgj*>-$bv#b1 zH4k;lq~Z1AZUZrSnIGjyrg13e^I$z=<52Ssi05gpTBC^8)d=+*g*26y12mNvCrAAx zDHu9H{k%X!&WP_UKjJDP?8+MM;m8+RC;rPXaqiH?glHg+)qS$(MrEss&P_Ki3XivQ z3_J8W{+1)6$KwKn`s7MsDOsp+L63*o`*bX`5po+7**Y;Cn?>*k20^OHJ~6eloy;jC zj9MJ&48Es=)do>$xMWAS%LGtjAfLI>CWlTJN#=0#Cv)QPN<15o`ymOVfMxh(tFgSx zyTH#V+mpB*lRU|oenh$(5=HN@C;b9&C9g6jYhTaf*eGYyaY1#J{a18wU7uH}oL%Rb>WrM-&2T#v zh)AV(vi!8_lmWflzVMfM@GX<8w1pj$o6C}uIL#U-v^zh;hEPC2y-K|8gLKg-ps~!? zQ|eRrQ`EZ8Z@_EE0o zVtTF>wsiovWnFalw!^uSF4-{`PdJ~Jr*$D#-e8-{I4QZbmvJgtbr9k)O}eEXlk=pP zM`^{6OOTBc!ZW!89ZrpqOVh(Lhd=}@T=!{J4$>Qh7|2C5?}}@UOc}Z1%(;5q{-u_h zJ*t){teH7CXI>06*1b}350?NW3+7e@afo5t#VW*lcnyoCyq%L(8R}z>714geWO3w} zKE58l5DAb4tst%`f`*?hWZwi&S3qCk7@7^IIB1G89QUdgb@}21LY`C5lT%fHtJlj= zdyro(AnIVala~WQFrg^_EHQ&~tID_A*bKCN!sSr_QxvK5vaIvJ&CY)_owXO8j8)7) z*RFFA5JE$4D*#g2rsk*u(PomZFmwx&fK0c#Xs)Ow)Sb1layS`QBQg`X?nD2dekKPBIJ9_XZtP9deBe$#LNaHg9g-T zdL?H8c2D|g0loU_4?WC!9XR@<%|L#wCDH#ofsF#lUu)~o|EI3|HV|q)7Kb)BT=EsR zQ+c7+oZrVx>G`<^lWo}xMdlHMDWF~Xg-7Du92P3Ah;S%XJ*r-*W!+^JQ)S4u5vHus z7NKe1B|1dwvEf9a0?oU@h#vwpd_DVNca6&d-@Xkl!WBF z@!6z=Y;FqPL{Ksy4%FJ34s2^?>&|ZnG{zSb6I!#{v*O#U%R!xEr2~V_odckj{Em^w z+_LWD++D<}@r`tQs>ZFUq|DCg!A5-J*vWwZ>y0msNdsGP1^F$+hgp>TS^TpaRFZxt zi&C19cT)U@K8tepuN0_0IlSCzy-|5QGM`2bNcP#f3hh@P?i^KdDJI0nO^}K-3n;-# zwso_lk%G)c?04^+MP;wobSvh+f`|mxEb3;Cs1K;QVCd%q8s+V4=)L#g2n=~3Y+MZ?i4%UUz}3%`mp%ZZ2hS{q3+HoGZW&GMe$}$>wh&|ro-=fr6Xu8 zWgN3PmTI)hKa@XnNV*Mz$#S-J#1m93Y@nSz*k#tQUvwU+yLu<9=8GHH9?04qVDs_k zbdEcA4{o`@GslrHc5~z$M-OLz!(6R0cC1~l?nutVjf6@(~soIYM3+Z^lA&p&#wxiXUTgGYDF{oc9 zRC+l8SamIkG)M=k67B&ghgB>2i({q*s-l3T!Fo#J_zz5pRuzn{q3=sx(CG;luCx0+ z9j;wL>k7??@^J}n-w%Sgoi@}qsGPB8j(<+`3k2&5T)d#MEUIrR@-*YAsH=g3V9p5ipMQE}3`37wFJqJm$*{ERt9%-wp-Pfl-!vR3Xma1*os*gEuKm7pn+15^Z5SJb97o1 zf!XVe=zvVVQ75NuU5QzM^Hakg>pN@pO@3gGTdhp780F45CXv_}QY>#WRrm5WQEBEL67@J_dS|G_Nv|88# zxPzteB?#gSc6G%N$dpD6q1u`LrcA?^6uAX)g%-3kH^Or9`p8pG>mjcKF>CL?-bKP; zWU~f<0!$?nzre)lfn?IhzM!np+AE!yDoHQZZ*S9JDjqRH|6sllaD9S8IKv+fHmRb z62bq6sk8oT^8erVf-y$d=-5VgcSwv5N0087ZcrQ}N5^Q8E&*jUf=Z`BOIVaBU=U)y z<>vnW^!X>Q*W-De$9bG(f8iIAh#?zPL&yy$wg>&Kv+hX@!5_P;kvHTRtLxU&j70A(!| z?3JxHt%h{)+7PP&bEB!pH-ar`@MgjqNza|#jhVf0VL@F~kzftZ1*H#Kq3Ysi*xHou5c~+rzSWLHXc?7B&J7jXK8a97)W* zV3p=nDPXk6m&f=hEA%brD%M>zS5$S@S)EsQ?vl#i9WBnzTNqivQp%2KQGJ+L-XOk-FD3lOwK?ccH z<}(N}jdd;!hF*)8b?E!X2YU<(Q^iIa9~MEJvyEE%XgGhcSUcXEYNUj|?+2Y$vHmOE z6(4W5*a|D{`jq7VT5&ToGtW+gM3$%DM6Vfl0D57P7QqVK;7Qu@>743)H0wk8qFYqR zyrX7TakZ8$m7!pY&$CtADfQc$2*rejgK(DJ$Ym?YO-gunfq6;c<(s{}YuQ?P2&Ej; z@nQQjYP$44R~bW|BOixndeqMf$HF_8 zD6?AWERfyjZ}bWyOgQ=@#O=O%=|7Gp(QVePa2`A`hvXBjN-hNhJeLPo`x2L<9O(qC zY>UVrrbkH!g*UWCF^TUpv7G#1EHpTWgxvpEsOP($a15|@PW6uldYJ%YAMdp9Jy|+xc{+=+yEJQ_-d5}peQ{wd@!XfZvp<*{ zmN*sR0e57DKL3D$&RosF{zC===PLrl8JpEYPsMTCId?AP60oO%sX5K4UQo@i^lqST zl3)_Q97$(}k3DyQ^)eiBawz{7Zbfe4)2+?wm}GeKkpGuA4f6&J?j?tt!T&a}RTAJJ zMc)=))}XPbQ0WinETc23OMqR*e6e7#p1D~ppz&KfR*ad2M%vkRC#lUEgIT}R(L_es zcjHeTv#G!>b+q{_diAkg1tTWW1ULAz8HF`#`-&yE^L5kA0w1|n!Nf(RUZKY*81=aE zN^HAFOtDV4wb`YU1dmgeFg(=aDq}&svJf~#o|BmOWK7mPU~9Xck;?&A4c<3)IPWPc z{cJYBW(3Tz%g z;5jgQcl1z6>Xpj}HfIt75(V*=OE=P#M;LV*q$A+`-RgzDx9$9bImY-$_yind^P&VJ zo~HVHSZFR5WiHRqllzK^mcqilSW^)!@;~_iT8xxSd_7C*i`U#{W8~j%E&hHtv;j3( z*UFCE!nW{kKw_gIij;s-Oi{fQZups;Eq!Gf$|N~o zAL3!*!4iRb`cY!w=WYH}&MaX+e=P4EID;^|?=T{ja!;NBp|&a_ibW$&nvEXsxykKV zFelS3D@y3uN+Z0an+G{zI9{oJN0CTAR|SrTb)5R;%*Y|a5t=%04;WR8*YLZu0dfxL z^?g)kq&pizxdUJ0H)-`P?6<!WZMK+FtDapjZQR#N0b5|7*ru(C6MNTInAg~!@ucHr%9GcYiF0CeBqRDWe!$Ef#4 zuh<$bqtj^JpBzs{re&lYpaW8m4TVAl=t9a}cNMkB@z*x0q$ltz!I8$AoeK?f8&4&7 zmEyx}P@`yG3~R>9odmbyTOPiu@?4dp8d)j~q!0Y}TMf`yaX_EZ=Yn{Z%{ycIOj0q~ zDwbHQsOXhxdV@)|)U#SKa)3;F*kBTy4LI&#;6`R^QI8z&qm0|#)?gC9R^0W{(V=R^ zYQ!kmIJZw&)PvTIg>z~)dZJf(y5Dt@Pr~b5dJ581ClkF)3_D-tetb$^g)sVhSvm#~ zqx3UBvSrFF5{p1qhtEX4WVLZ#RPXx669N<)nY%d%qrLP&5f=$Gipdus z?|pP?QwWWE5+28~VlX!v#XMgZQ=#!!P?ot#TKYYJw)QII&%PpkqkiowH-=G9YZuuo z8$B_QQVmJWG?EA^g3V{7dTk_Iw+KAXuNg}=vPT!gBEs)_Y!(Bt=JLhnTKbX{fa{d1!u@Gd;wotBZ`2ECd4yFCY)abukZj zwGmsGh5;f7Xav2XOMVwyz732s!l$;2-;s@Co6dd_0AJ{a;z*3c5YbAYjAIbfLKk~J zxl9(nP$-Cf51_p*eN9~Rqr|nc3Sf6KEnA)ZXu3DPu%65G*zj>NudE&_B+o^B4?x!(iDm~l z6EKvKd4Gu1MjO{r-&HmIggBC&(l+{JWbFQJA_mq8SlAqTGL_jTX!-6@XMA6NY1YHR z;nrdB-q2>$7mIffA^4rSxj08y>n)G9nSur&+*)EBZTjj_MD{p5u;5c+^Q{c*R6rSJ z{tfLXS2|}~He>l2)L%0c9yRQ|8Pkg6vgDjvv>V4~dt{E!&S;rigDxYjJ{mR;=mP^c zmaN2`W@Jl)E9;8wBGlgedh*oNrE_({|oy~$r z6e#7Fsw?_lo8u2|_XR~o_kVf(U|yYedYX>y$!(T_&cby?<+_NZmoAc+ zZTtIb_FWdmENhOh%8S1MYXwqc75kp@*&Q9KVTJ4yM9F9yp*u`e_c=?<&}Q7t`Q^kY z!z&}$e|B~{@80awX`32F5cJl#R?;alAl6zi2xzw`O#Ro+sJV5WA{F8sAO}%7oI@`r z_W(U8!q3V2O!-#(X3?tj4)6dmmqjkeTTa0eGA zySY#fS(&0XnTu_m=@e7EO9i~`nFLGR$T>dnp4W_C?)T(MbD*lj9esiz!%FO0F zNm~aDVLkAyg~{$E))G1z&FOSu-Xv|A&-GA4`;u7ny0Vi<;1S;O)5?5rfM&%(>06qn z*~b>M?phj6L3;EOF(YdhFT}KG>$Han;T?n2ey_qi=E;{oI8?!g0qeR2Y*vG*7ffH& zr+f z&(id=(+T=;Q`pKEowV$fI8!`cb>%VxPc_4)Cp2bhW8gE$5>X~VIX7y!u(6Z*po7xt z+0UhMpT?(BkMSa3MB$BOMLATD3CMwM+iKb5baHf_48p<vt0}p`!`V0UPSJ*d!m_<7*NYxA>VuI zZ?giwzO;{!nR9Ut+wzG77NaZn$16w-QK|^>*ZJ4@qG#i(YQ$UShdZoVsW=!&sr zHGV_>kRY4yr;ieJ_xO?)P?+6HtB<3!!vUgOrGYF*jbeg|a+Mk(lO7Wl`-%CEP?qMW ztzAtoTA2VGxuk4~*CKK>FyQzn;!2|mfoquzB!zW%oPZ2Afa{f4o{hD$lEu z%N6csV_F3fN~-=#r-i~9G(ea1V_?B!`&mpba+fbgh1r71>W4P$US0OR+|~i-=>(o&g6geM(51Z@k+nXS zDQ$ueMzMO<@D+2^y6crk5v#!Wea5TG$4AA4FpL(#lb`t$=Ji3wC8O8_xZ#ab?r-+Z zx5=E?^{KqEmf*{-@7A5ypPJ324286B48?0^D`P%urvRS+dIkB68s&xMgvY?g%E3XO z`(L(|+0HATZDPD{Hk)4!35561ry_^MBj5DLCIDY+xb)iRC`GhGE{CUi#)qVtci2=c zG=+z{x(do$h@R7JArh~z!v=e4fS<6=%uOrJ&c}8o^)Dj+(ti!1d`?RHZ?S)i^FfUr zc~evnlQs?eCFfYRY5~Kg`3&+^uqLdLDv;UnxD~a^VxKOzzBt^$W^?li^ zpexiuJ7%1uV9o|F$N1ku!&GrLX+LDd26gZPdftqIPnRNc;BvOpfhKDvJs3|3Fnqh1 zobDsVpL5=r6zKCLo|;M1e(&I$MLZT=NNI@SR=!^3uB6>JK|I=YD3l6-3Ia08kk0Nf z@~4bj2gKAz+cihoOvkU0l&s0(xT z(l8slvsGuMn06(cIhpl+*KAbJbTD1Hi7AruFsmz-R_c;DT|p0xSFH-u75r|Q_@mHm zI%v*^Q;;!)(t!McXh-c~;ky!C;_IX*tP@uptz=|c8j;t;qWio>dU*unMO0xQRKP=N}a=^_MC2gW)*EF(z5Y>sWyerM(UoZH{QXYf~d%|LJUp9U; znt=B(OfisLOD=w>R2x1kj~JELrz;>+*hFj0;5azkLC-@S_%CrVEart z&zRY}sLMgylh=l%(EfwnXG>8cr5dKfdvD1qY*m|8SxGO__bv(0Uy}Kq6?eA_ma)Y8 zOu@)-lHosa$$#=<&O4DN(MHOA-uP?9J-eoP5fqncpn(#C5|gOGO{z0ua5(zuWujHa zl}?kJ+~}a^!nn%WnEbB|1XPLe@+?{8yM5wO>5~2y(asiSIvRL6yo(okXSdyFN7Zi`nB%lf1|-V}NPs9e_nXmohnjHTIwp%$ z8KBUj3Q8CV2JOGwNEX>eKR?@Ec{-mg= zxV^L-oKK4$8D4tQ+eWG&b#8PmR;*FfjlrG~n)3*owIBBJN|n20pB3zny>B?G zhon%QAEq(P6(qs$oAzTNOW!GM`XY#kR20!{5rCj2Jg;y5SWsunaFxtm4?kHRx|vMr zW@I&LKWPIMk-?6BwAb^hrw!K;UT{~+rE}MBZ*Jr53vSItJ|_aQAe<03ty_Mx^AXa5pJZzvZuoou$C=x!$I+=b zk3madr7S$t&OHuL6bn1 zio6U08&bc$A|0uz)Yoe666t5M{8UCkgiw2T{F3tChG%wsOu?&_(8Qtd1;U)B24s+q zYf=XS%+>7WBzpRbu z>3oWamgT>grztd!Hch0(6FpY-{wb*Vgli_IB-vg(W_RWDi}QF_xTlQ=G`rL_rPCN9 z8+;3)z|89h{nTqQ?Tli>UA&N5prY2jK#`dZf>^Y=(r*lknD;g&-y!=xS`e7wlD? zt+iD~mhZU+iugaTTS6Q1(CZ+QSh8pP*65~wKJeLvN+xp(NN=~QRE>{{oNUUD@fa+H ze?VJ;=sKUXZ9{%rPTn(L64ZTmn>kI;G5s6m@7BUZeS@ZF{TQ5<}*FCC2 z%0u)+(ts~t1{dynP@Zhco{$#F7h6`~S-CbIRCKI7X@3~mMo>9bpIdBbYDT(g!{{Sa zdW4cYDwj1Y8!?93cW#;5tgv5uAH-{$uFXc>3#FQp<(V-C!7)qu+hX5+p6qv=AZ?B^ z3&EqzrSHMu{fsI zCjW@8nVLi8&ZqT^Vu^jXKk6A+ta|<=)|MiZ&8RtMhd+|4m>RoW@2VH0)}vA0#OHbY z$X~{r zVf}^C!<&g;vwWw_y$1E4y=>T&EjuQFZP_LhF^=@&^;XC?1vTSD-EgFUP zST4%Fy5W#C=|0HT9KbBeQ)A$M0#nj7-CsLLQStHm3Yw7rE%r6mIdK0Qp)K9#NkeDc zNQDYy;J&re3JTx;ihWtWQkCo-&Y{tTcnGJ=XENOrM^0~?7!jS*92p20N={!5T5(ck z?&5^3W@k+d5_eTEQs+k}9KS?4n(pE}tehs}<88wg9)jQE|H2vg4c&&~FG`zqi0C_KO_Pb_}_R-n3gFZNCrKHr>On>zA9YgP%S zl+p*s@DbY`9aLBPinh*H4DIV|R)44j>V$}5LPf@&UoR6Ad@ZUEH+p3vxXcPUhoVZ~ znH5?%)tW!=70H?$pA7Z?gnP^3YwlU_;raImF^l)oyULRIUhK~a1ti77hu_dFEYHvU zW&5mT!k_sebg?I`kSWGZ27S{2eT(%3b)&{X&-=MM1cgemWH{P>Nb9w%-OnEw{x7WC zUt#aG%*?IzO87>xk}NreXrRkOpxMgDNkNZD&X+-u*A7PKpFUy)V}xZSBe_P0M1vOt zZAEmYb%a0l%!UXakeT%xG9h1NS}454Q}SoUtU@;c+yWF)>GOfSulFhniyK$H%x3gc z3TwHo8nsSjXFk^~;aX%Rp3D1(eXNs|><)iY@n%|1Q|R*>Jc#V%@>wI0s+B=XE~ip! z>9xAZdOy{>aKkgd7b%^7T7S)x)*#yKHx(vt`dT0G8sA-}xh|W{iiI{3Qcy9sVF&VF z=MGE=VH3`eONQWg6#0K>r#KxKsT;ExLzy5*sFU%Uf0E%eQ^czWn*ITbk#@ zgYooAKT@OA8zoK1?;QkNeOq@sc5yyVU~6U^)>d_0XzEh_&_^ zUP^DgO#VY^vUbc{rl8|B0agU?)<F zn7hb-MdlCTd6TwIS!*@qK2#2t<(7x&CUzTb6fa)eaxFYW0wq^5XDSKGU7L$(r6(6j z)ofi+x|( zEMb*CSnpT03e=t7usFKb_?fMQ1X}aFfTnRB!EMl(JL?h9=)5BD)X-AK(qfKlxjnU* z_msoVZj0yVt|xCdzgJ8WTbZjuvPg>!ZON1-ClaJ5LX5Oxj-R%oM#Zfb8#GU;_kgx>6ds-n`_SRX~z*4Z6N2MQ1;D@ ztch?+^MME$lKZo*WRaK3MnJ{*nyQY2%6}MXXg9=_39d>H=XJ}J$plJe0a-$UZRtHX za3Brq9$`0GwLd@u`d+SYG`w!IU`ld>_tXNOWRCBDQ-h9}qq}-jNo1yCvcYa-NgIIB zE^-Tc@SR0wTQOOx#XfSJ3U-kkTmcD0kh^{B9~|wy2_QGe^_gQJ6rlsrY6Hfj1D*)z z-9R-D$AQS>0rSz`Ft@?X8rF`V(Ee`>j|PZcTh{(Bh7TpJWJ)}LU9D&iZ;10EgqcMpwfrim z4wUfOl{c;bI`u^;!*!=t&NOkh_65oDCv8@0_~9%v2JKandEy>5whfgAP{iXR9YR@% z&_n!i5vJ$4*I;FJD0m+nD&}=pH9RH82LvO}^a_f-c9Z+Uyt4vDAmpIHYJz`!bx4+W zaX_ojomgiiY}SI&6?N-mbnuZ8l8A6 zDeqa5OlMu>3~tcZ2Xa3pE=!kPb)&yKPvdKE|9%8Z&6{AbZr{K$ecybVX+eKj>9Z!P z1CuQla69>W;o45+uzXZ^DkICw>Pd%!E9JMlKSTDFZAUaI9ld84kmyj34XYxAK}!H~ zp{j?ag+nl?tt4!`6;oQOa-magIrXr9$c%GQgc||?_NL+iz>z(wn=0O^Y)H3Iio-{7 zUjPqaswDe#18Tp}aW6r3ajY=p*Ia=AUX$Y-=HK7*;Fsq9zm}Qz!JW%I+#kuXQ7uK{ zcr35|*&mqy_AJ3v@MzRj*n>wof}QH`4*tTzm@&X*Sz^USkIYaqu~69Y#BX=CvP`1o2`4#{=c z=%`Mi6WmPvMIDHelj7NVm2Gvb`^Un z}e!548t)LAMI^I{G&=4A?{j zmS<#>+%9`IRo-o_K^^Xhl)STn?$$pC&P_4ejaJ5Guui>hYp%Q7aPni*Q|%vEcx)J} zyqFqX0kzBkIB5`l^QV&SC$GLQ>qGip7#St;uwWt`_#o$PE8A`tGN=JAk0dbk=dG`H z=lh?SMbkIB=da8epB}=vDA>Ga^z~fA3)R6I$&yHIuNhgbeIqo7RsBk0jr7we&)2Fy zD$K{CzGpmP2Z_A($q6)-ssAuSqVS8eD&0&l%d0-ac0DIo@pC)BqZBGCrv1Kt!5=36 zo)bjF#oBrlQo_Wj>-72Zfo19nEb?IF#0Xvawvei<@#p!A!!kV2Yn5@@P{vAs3T4$b z<}bKgz&ye1FyY2FLq;mhlrkA;Am=%?v~=KlXn2uQT$M?(M7JddA5PD~mK@|qKU!bG z|DY;qSCH8S$&nI6-*z%&0VXQ261RCaOu zL?TSNg3|9*PH9IMT$g<^@-KTMm7VG5Bz@PoS-2Z!alaVdLvh$ zI$Yo||EwFH`+%8{g=s{A7SSJxy)`PdqngVmMsY`wyzDus)X3mWZ0N;Ed}C)(kuZ)5 ze%3}<%ChIIGmaE5KqWY#pkNB#tlia2$Uo$r-h|2e55-TL;l}g}^2;0nzwSA_*%xeH za=+(>o^{AHu)D4vK6}(X6Zbob0ZzeP-DoRF7Bq82K1H~6}3ErkFJ0fpa-yg`4ItkvyXbq+zeTvK!M(44&{v*cA_Jo(vP z>Lc$I1(g(6KqIQx{SheD`PK^~@!7gkeiG-M_hjLJyKt1xAnt|nP)@tP^t!a(kgh$w zstzdMMCi)(K5#R)FA@gzL&W2-FM*r(v)5M!;3B1Vnk!P7r|m?_6~FBggRkidyVVjG z$|IDt&Ybc^8wkYeg><8obM_~_izaWf{z)oj;Gj$&RlfH+{)4d2yag^WL%bq?v)Wvg zg0UoOB`-3yc6||o?ZgP$U$hkkVAHd%|8W3NCQ@UU^tiK6Db{zJy4fxWr0J{w7#K!8 zff*DhgDh2fWe;Y0>Vl7qGveH{(fhJlaZN>IwdF!(+Nx!_3tR<(JP9KyeAoxT?oz-4 z0e4uSlp~2u_4bXq&?--Oyo#P|$luK*vHvdwpHy>(NUN&auM1;GzzGtJ6|yLHGW z{>kKsr-i|BY9DcRLKXaFi-+2vTV;RHRPX+9zaQbNbBBDohTDOy$k4oNpYh33sJxS= zFtVzgsiDD3xF4inRK_(i&0jsj>oNI_pOUdA6$?uTe1qJ&&2 z zz2%et*fol&Tz>PWv93jez9U;KCS(|KvKc+4e1D|BDL9#(`}OP!5Au7>XzhfFmRD4F2H&JkGCqOv~p$0cNNJ|>2w)Sf)tust4v{ z{_`T7@UE2XTTuCvilC1lTuv-kz}l3xdX^ zN1CHTZYv31k!)roW68;^6xP%xr@0QjV|B)5v0<{Iz2OXAVb#6~GDtPf0`gMhe*{{nYv4!tPAeKrH|Iw0(PTG`}8SB0?O?$BRK5 zk$WK-!T`g9)UiHpXMH{^MXUp>QlxbyUJ@^P42NlB((ysGb^*)g05wx8BbGewLj($z z&fujTemhkyOb413&Ut7nw%sd2WHf`*i~b>TzqeFP3TM^#lK;=m{o77-V=5(+UO*1i zCc1|)%{sbb1$RDal%$(>wa4HI#twVl{VdPX0=+VwECo4vTA-VK1DaGGb+L~W1(L;( zOO4xJmb%I_$sA2NY`YFM%()n7ILCd4-y7;pu&O7?s$X9dQbpYe;*P=8}c5 zQCJsnXLJ%xvj1aeJwOi`S$4G3mMir%reRYX@?t1H7hWXM4u8NWNhbt{8lN>Obnl5b zFUK06c?DXK2k1LfGB~#QrtO_(3717K5>-U4?|g#a2ygHb9ps?tRyW#D4@|x}Qb1o5 z9!LnK7)rnC+^c46$G;s#IJ-3D-_ZTYdS!ONi1lo-b?n!D3JP!Owc28({fUe%HI&a! z0titkh1rd<%)RW1*h%?54c2Zi(!F$pvGf2CFZ;1|ehE(-UqMu}TDf|1Ruem_2pzf5S3X?HBFq@R6?UqgRq1Iv{8CKxSTd#cxs`Z) zFuaBL<%QTxf8trbIm+ARG*tGPR@BE(^`iITZS?UsfHphCz!jsa8^Wfy7Coh`RaYkr zM4L?8n4(9B+E{kaKp@!)lg@37&A+qg;$#O8{^;qR_>$xs5xbcgry>&G#RJyH0;t6M z(5Ny9F>tdKDMXq%RDy-mB%2wNUdu-Mi&H$Cq|dVfH=C{Kta2KJsPSFypK5 z8AE*vbYzN+-R8aBvQr6i>1I*=HbjWh|J|{1OIkmRV3h~QtUddlEiTyn|VnYYAHzavT4GT|7PTU zD;ua3PHxzu_oRV~_{c_P|Mq`CzAAq)#*))QUS3uIwq*JwN`EBsDnK8kIDbg)7y zv4B`;fth5xImq*=w6MChnR8)-H-T4C9IdHw0tX_`h-VqRky);DaeV^T8pKCkVan!<1y5A=O;`$A2 zjOn)n^lNGL2W0jCZ@7*I2wh*({}-+=60HJ)6iXXvq|zF5ymq{dlI?k|Y-eN>rLclR zMf^H1ziYW7e}1xwed4y9&U`(T;O>!x0mX1?pT`7I4(lX)3b9cGxNvbflC95qqnd6@ zf5!CnmHZO8)+FVn~vW*aeCXe0Y z%?sum+juz59l|Y6VnVmoOuVmTqyN1BGNWMVz?Nc7hR9-JqKTXp9TY;;C;aHWZ5(y$ zW|8wF)laJgU0;-BO72+vC5dCiG?l+vx#^gF1h1ji*Y5TZOEORmqcL`XTP=Vn@?-5O zFKraMIDcjc@yoYg$T!l2tS1dBObfYB%H5nV3dJ~yqBpH7h#S1ZHIH0D|~UOtWw<3 zLU+mWi-;sNoc1`UTK*xn)IcJtZ%A>>PI!x3hDT0q^W|aS*4pH$HTuiy!;Z3eRvc|r zK&bA((0BiSzMHa7LIE^a7DZ#MQ*!2}#Tiz0cfuKk=*ZoT`QNTtb21KoCneLK|A$71 zf2~b75dP{t{$9TtptmR}h$2$PULa%vu`9|u%Z?J-AOpCGN~?|VL2s(bO(?8(LM?dF zpwZ{aV>XlcDlZ`lwLWi)0(BidYkeaw=`H{ZY|JuK%|XW9BNq^TuI-hjv2`0lH{;%zmL2o_hs>(%XGzeuf_;zHyCiShR(-~fxrgM5FVlJmZklapUv*kj5x<|bB=w+ZF4 zeS7+_?~7L&qoZ~PQlQ2!T`e7CXm zG|_C#SvL3@UebE2uWTq%$j~P$|5-e;v3`yj)jc%yhj7TcwLswqQ_*f_up3dzVSO$8 zj$-;(;gj2zfAp2#fZ}!L{%ftd%lY1z1IOw)^xe4W7oGXOJYS!mCxgP!xY+VHl3>s+ z9MR~e4M&nZZ&E5p2Emwvf`SN~rht12wFtaMhBRVx z4qXeW8h=LZvv+ELaACzNCts_eneF%$WFUmV0<3;h<#%4&XvuAiCA>Io8Gk~B0VqEz zZc3|U+KdW{%&f2$3xTf>P;zv)=b;>OwvMKJIWq*Kkk+w-FT%v9wb}QXvzW6K*P}F9 z%4ZY7IBVgN56HH$SxJ|of&;ahj21Ij^k9lueTkq`Q24{0T{-vH&MpxxoL%;U zv8Ryg@=2Ky_FuR9)}VLlZvyg!J=bYayP@d`gH*un3ju-qTYi3nU3q#_a&PN0;zcbc z3Yd+&w@|gqtAhLivToGEVWVm~6j^7px&WZ?g5sT|YR;gxd%zClvvD~Md&>7FJPTxy zGbBZWa%24;qCF3Yo<7iPKP;`dNh)ymUNN(f9qy4aNm*Kg<;WY~2UyedP*;kT|IEKQLL*!lZhJ=z_>va=?WAWKHxtjvv~n{{0vKd&rjp$gBV@5TQm$hAJPnJvB(WNvLEKs zDu}3$DOh#vK))a#9&m9)2Vf1M;7%vU`Ll2Jh79jelVozpH>G>*T4I=W@7McKK7nH9 z$kR`Z+@Ddhu>(WMM1{7hp|CQ{Pd9|pBHPBeMNEEbYrX`-5RXyF)veLL`5Ux$mZ|E` z{DqF$9?QIvbj_KN`@A?cVMy@s&DRbbp&C%(c^~UOz2Z%wg(IUMrR+%T1DTh$C!T!~ zZq3)n{ByFWqZ}}kiqF%2N_m3i{Ik&!?QSsq|EN04uC^97+J-=Y;1=8=xCD0z?h@P~ z1g8+(T8g^_w?c83phemqT#CEYaBDdSE2YZi%RBD9KVW~{W9(<`HRqz;sMmPK=Cj|< z8Y;c`)nNikIhR2d+6NcT7+gqA=Yu;ZoMP{D;ONy9STw|4HhYaK(5BV!i@k_Q0y;L( z?6c>;Mg8La33M}hR7vN3jJvgSW(_qThW#H|ng2x67KTDA7w`H6EG*R{yR*daODpeo z z`LK_*4)=hPrI^<}K;J-08C0zQ&ZC#$sz3c)rgLm7W$#9Cl}AQU8oBRja$hV^1Kt*{=~_+-{3=pqR`ppXIz0FK%aa*#DnkC+DJyv zdvN@yCT`93%yi}oJw&ij3o3?~scKOG$6-mFzMn4R-qKi-N=D>p$nykq^j*cc#L;~= z@!$$Epp}Tqz{tGPR(TO%DUlR2I11NX(jdwS^UCAa!jfCw(U+|m{Z5k6>(glsAP96* z7auiLLJJ23;T7d31zpncuRPD>wcc2D1|q|%Vv;g8@NYV)6<3lYc^)`^dGPmf%j^e4 zZpiRCr9enRwe zZX&XnJK39))+!I!YodA-t}X&q%EkA;s0=zD6JnBkpj9xB!RM2gyONE^_lGoS_sJx2 z=VhBEBfUWs1e!1N*a0{?>9#N;)4a0D$}qaIh;N%lziLCAu|j+~Lf}MC#*s9SahAGd z&>odcs2YdxeoTQ5n<$jP(36Yh-WM=Qy`HmhE@P0E(8G5U>;P)aDbBR&9qp6d?m`-xtXDoiFOyqDHq4Q z5{E<#NLCr0yM;5DlUKwJWW@mGVOj#0IwQk?sb(NaXX`|Bs{j@-bKVL@1C|)6S0h_l zv8`gJZI{(R5)AF;4&c3Bn;5!vFRf^55YVI7HuSUgOKIEGPU~rD+@?U=xoyWrTKlzL zJHK=LXGZG%!PcYZ4xF;~?>p_^ezxB+cKnd<$hPU2WNiD>jQfkI{f{kn_q^>?9=r3i z1OI&|`E0w{Zu>|1&gq}nImS+=^samPcG{>m5= zdEaq0+Ql2y0kLZn*YEz|-APbJ+WmK@hdI4l#jcB(3FrU1&eZ^%|Er(FX1GXm+baZl z8)g!jon={VkUG<)7(2RL(e#XVXqlwWD~QoK?T`>{MjT?mTAn!Rq`C?v`ErZzZubQz zmQ-Xzw;*fLLnHnj1ppAIrl#64MU5V$ViWDZ2=)g)rHTcUJ=Z7j14IR8#KcF(`UghD z=jc68L4yO$gW@7^YirAab%2U!0l#{{qoOdRma0Cnu`{O~J6M4YX>Rn#4Z>|NuE$h> z4F@VZ{D;BI<@#eQ}-ut$E7|bYU$>uSnQlM$VLqdrz8#;#Ju211sbgwUHHzYya=|KjEnKSru_QF+^H>JRf&TqTlf}^RD2T6_xK}y;e1ay9$>R* zLwaLJ@zghJ+QKHVIBupR&dE8jKvWnjWbi!OUI-nmM_D`FS`ni;63`ZR2*PnhTDEzzNfWuJIoJNn>Gj9qri~V}zD`1fN z<>zpuOzP^nd+tqp^V(Iz_-4&z;?ml-ZpTn^&Or@feqWb#*U3{>j0hz&lr(0s$_=)) zt5Z59VWwO`yWyD8&0_B}6veF5cs}hVdRAU*!ThGc_(3F|@Oar|TrA(oJTwGZCb<5g zh8@)jTQV^Zqu{cz5y`O9$6?yi-cq8n&^8Qti4#L;EF@MyBw_F@K2IlZI=_g=6zAJs z=r(K&BwldkO5?NdjGN{8`vcdm+$gh0wdSujZllz&rIkgQ(B5xGVg-;praYP>w?fPz zN7$;QaT>lRH;0%m9F_r>amOK)twG8DxFTE&TccTBA{s;WSw;h;Jy1I6dHh|`OI2Rp zfXt__@NoC!)VI_;CM>7YQ0L(RsAy)U*}4YFU?w8$Eh5W@0O ze@JB651;B|_m+m2U7%l)&iJYx9AMxbqABAKw+owCgxvd8Q_n5F&5Z`#Mad_gq;IV zE&1y@Hw~Uxv!^d6>7%%@kuxQfXp<2pC5pr+8^e=d=5Un^GYKT?T=67cXkl6?2(>1c zDK-Z~2eN4Ns7Oz@zUb7Fxegqg7Y!^*Q%u#?^QF33HI;iNKs(;%TmpF>;XUV-l1)!C z_PXKEUfx!DoNth{lqVXMs0FF zGmb((PLZ+%Fn`4RRNnI*xfuH;hZSlP1^akmmQMz@iIp)4JpoOLmtPDRxR?1Gu{5N; z*o21IF-~9YR$yk5?>X*#&*4o6<8>-eJmI1(<4wCn#Z-7Gq6})5TzBiTAI@gS^3fnL z`{G3{^^Pr-GWv|Kg=I>-;|df?L*2e&jzx!b@4Svalq&CUhA4?~m1PAFaXv|6 zn;o{+ypx8c88kkPFay1U;XsbV3tB-(%gU_~#>a{P?uM;Ps=FnGOLsA^!Uw6lkHK>% zQ)df2XI+>MVYQX?OaLL-pPC>y?KdW%x_WM5z721%EE8A*k}uA9GMws)-M;zQ<;q6R z82U(D z14eAa4%vqMKM&{DaXesfY?c~BDumd}c8hT5r$_qO>V^9|1~yQ=hSclnbEb`^g8E&8 zV3pa_(`kCq^Ncz>hKwAN@0xP!lEyY*ue{p0pXuKLi45ixW}*LVrc{DLX!QsI3LaHz zDR|AQ-*HSlJWAe>*L9942K5Evr^8W@%1#V zi{QC7oJ*!Tc`bk>P&E2=JfEiDf9md9Zy!M%@yv^2yo=jU{|-Y(-d?mO(2Z#`&{pT2 z=*)e;L$U*`b&||+>EpgrXX8>r@*%pNPxfbqk_kiA5+bd7rkicKH4_cyU^Z!!{JPK-`F(WtIPb+vB>(zRIRB+($L`da%YEi7=k%!SBEH$J)BHjlBA4*$pQ&}FL;h) z|4{ik{6iu@$5L0^GY8ngeQ&d`M`-Q|%k1tQKv!$o0Ht7Pja4)5hCNWpX`>hhnmgcZ4 z)+Tt;(tc_EX|fXYe@-veEKoI@j61s-SKb1}_a-y)UoG#eV*weyBT=zMgo1D`o|iII z#T`-1ubs`Oqn?(RO~;G3CQwjKyWieUJ0_^T{Myf#)2MuH!?~4RAC#$IozTef@xG&* znHc(GxHXI#tSRwd%{zwI)Qfe@uS>P?pI4CB4zUHLd5QI1sQu^tm-)6de2_g~4ORO< zFtC%El50CfVQ@vu%+M zRzRS1H|c@S)s1%3jYC0cs;#9q z+3J82BL@_krq1G2ptvByyl)W#SInPB0JKQna4iJQVW?oR@Mj!pHk9EJ3QoMwJAnm6 zN>P(0CDDb%bWkxf!=YbHgYPTNOxL5d-C?GLHZ^%V{Z!OVAhBTppOHiuc--z6Hl}hy z8SE0%DxqfSMn-*L@wl$o_>E3hmPZT95EToE4(3OtXgX5aiE&aL(Q2by9z0Yx`96*~ zuV9$sLj&h6M8wesR@81>g^p~8#3u#3)o#+RYn0n`iRfW)igUDYCpT}3$z^wPWkLjf zm(q{rNRwlBa~FwA8gT*|6&oF0rG0cbw;yo||Na4)zzO^AsMtJ$ft{Q5tdDVeOfTrh z-|N8UH7fdqTUcMxgH=K^Dioz(CG5FH(~zq-jLiH5+oVTHm**HObN>P>ES~MqYX4UNg5~ zX`?tI&tAoYt)%GhL_;@tNqXZZa}_LW84kH{5uyCp0+H)Fufw1R9)O0Xxw#-WBEGEP zF_WkAY)r2=WocT^KZrH6q^I!Z=3&2z-tM)AyOJ?Y`-xYR5@4jrdRcInOy8`8vCt6c zz~F2M3$TubelVY~4YOT5r`8mWQH}(?TMS~0<%Ko!hqH~IwBUkN!8fFD?-48W9_pUU z)P2+ECda_*_Nl;k3GNY807~|`jNsRC@hu?d(W+cVsuEEI(KAY2>0)9z8_A-CK;~|O z$rQ^Pgw`0BBELA;J&aevwJ;z>Xda>+L+z=H6=0tfqYYz{s!igRq!7K*XT~+pN-!;> zNhFsjJ%#fo14PqRO{L)?tP(Ud)5s}jSE_4mq4kL1pa)bhSKtbUa`g(|gNK}9DOCb4 z)Y{D}u;remktA6{YK5VFdn9z7$HEdOAtvt5yA`q?m!1INYRgw@-z7_?vht+Vq^zMb z%0b)DpfHqvW768y+?2Y*!m8iBXX$-E@UfA^*YvBi6Bju?CFHC_(3k9KM@JCjdXPqV z2xoJpwNP5h@X#5qn((fLy}gXd4JfVa6maz9M|8=5+)#LZglMM{R@pH;zH-0Oc8Nl& zX%@?Nt?7Q&u)r;*_v9~sM`dKQ$IH$T6KoO8bf|DPhLVs1@>myL&=fsv!d|NddCET~ z9m2<(&z?%Ct!_Sf5m4}ygTTo|z-n70z1KLB@*$!mASk|vcL&iJEJKR#See?sLwg7uUMn+NmL&Ly3cdA&quJ2hW%Bs#w#zMR}O-G#pA%3AzWrGuJ|xc z{Ck{apZ*l4{)D0axY_;;q>#8`2Zy92&qulj z9GCc_qM{_MHnO&?v8Jvr1d>?MT31{3SShTKD{=(mN4lbdkdsMcBa@R}qM;>yYcoN9 z;YABxr0A&F7nAsLgsypuK{muB#LJOD!e`28_fIeToIm9*-5$5ZwlgnLk2GyID6Wnt znDV5Uii=n6Qv4VbVQevI*P-NA*TA$ZG(3n$-i}Z}IDBS#TmlQa%xewlEzX zx8qC8vSzs=_QiO6XLRR@VwU6zm4xeHcbCif6NB+*OmDO- zMvQu1m*Q^4FRue7553kjWSUmc$*)JSYf>dx2|BU5<*EAYZX@oar;@LEg{qXowg_1) z-79*5S1TIx9@_NBq2=zG8K*}(&Te+}i+U8J<`rGXKMB`yvyQoS``kAMILm;wNwck^ zq{oDl{!S_3a>U+=z0&mF6;)j6wh22%mjm4ou9JCJZ9~cVxNEzd(`r&+9!_$rzj-Gj1jqaD%PX~2&GXV={6kj4wD)k zrc6csb;jvKyF)xUd1>bIh@vT$#fwBk`E%#-d-?fn1!m=L!9wSWmPrBzN|W58A6vh# zS*_~ur6YpqF(9t8{G24~ce42elrQcNA*n7Yqt)&?A>c7`$usK={iK+pSZW~{?^Zs= zU(TEyS1@Egk@h@*heNO+$o5&)E&`D5zI{hSxI27&oPzk7=lJ5w57+`-LqRWz^edql z`bJP<>?c?3ha$rinm~NagYP2kt4ZxA=6&8u7?<_p%J&K4WZGnv))aIY&)YJ9)$pOK zuzG;it}c1VG{BeFg>K&ELN4BfE(exCsgwK!e;%q;4%Q+f(MW|1a#~KlBS%fH<@)LB zCVt_unz>8k|I5vN`A#iz*21bA@$q*wlSC>0$QOH*m_%d>3q^N1 z4AgPN#L(_!aA2fD{aJ`_kKKNBodU^SZq*5pCk%^7`$h$C|r|M7BOs0w2 zH<0?(-Y!zJbyEY=OtzT;UiUM8*%q7}`4x*JA6c2B`R3JlHPkk~i9T}`Vn_1(s0g!z zUd_?{N^t(Fj&b61qbN)d_q!qEMON%tX>1)Dynk~~V;e&NKG4?)y{oFc>`-1xU%b|< zCiydP4jJUI5J*^SHnaDoCj`s`b`F(%y@W--Gnq#AxfWQF2nc_)BmB2GFkAhWgV5f` zIbBg5_wUnD>uOI^HIc*yKa(@b?Yw*%#fC9cZm%F*2K#7wtirYp8UPPZp&sUK^i9wV zivP*57`{A&e&{*jpztNX;`G#n2&X@-Up8it#juGTpVB`Amw??gI7^?!XN-v(vc_BW z_j*AI!I!K6HC4qf9bCH4!%NJ=AZD6KQV-EB;n$mX4Q z?m_c`Ihbp?xRxuGW^Cm2Dp%SZ0d_*s(4$pF@AMtG9AZm%=ZTE?W3AiUaUU~)F{j!R ztZJNX%r}(cUh5|&kH4Qz>iC)@b$C-YBNmXUt0_Q2p-CS5)hBx8 zfzs?zlh|!-i!pzLTRe{qtEB#&B1?>PkWT%Q{~^4yk)_STq2rfK7Fj~N{`u1G#;A~L zlN!m8yj#bl7oB-$O6G|$p57dX&Y$2o94XEf-uDXc66ET{V^^{n8u6y^I`&>>+wdk) z+h| zv}nn2Skb>qcf>eoU{(zz+$H!8`$OCG#$mJfED|I(2Q;qS#5Ke%ZKx?17^n@{g zZrhzT+aX^{7Iaw#1j2P4N9r7^@v#GjNvt^?kpH+6a-))}O3&O!2et;(Wq_R74_+)h zhI9{RfUrW$i#vopit0s;eV&uM1aZCX&o=LvQ z8=Y0%e7jl{0lTv7Wb(MQ-P@7KNyEO>UH|xQ5(O9btbUU#J)UFs?cE6X`-8UMz)47Q z8|Mq3rP{%(qq&8YUEGwvy0aQRRqJl!fH23hGEo|?S_-^g=6Gf@xmSrslo0$DKj$nM zKNPuqxIly@;9u5nP%`wd7?T(uD$C88p!uTxzES|;T|fVFV{hSGdd^zHgYxiGp6mUO z!J37*CEI2{JwadhOItv8j2%z+7Mk_Q{LuQB%Gu~Z2DdQ#KoLQlkl84)4mR$gTnY<`B)#>t{i+P>Kq?VdOK0eq52;jCha$O ziNtO>BB^OnV;l;p;ETq4>v1FCfo_!f;_ps^Z`9WOnn&m47KKr5(@I%a<(H){tK_HT z%KK6}BaYoJ>Ss$@JE?oNALce{uBV5K;~%sxrf1vWFck$U-JjXCeh<&w!lXV^an%J0 zMczVj`h4QWZU31dUPq8)U7b4v$=_q7^u}39QBpmY2IpZkQ;BXU4kxF5&TrbJOWl&k z=3*x>yM|h+CK>#pT#?gZ#ZNHlhf4;mDqiTg>P;^d1Eszfk23x;b%U$v?F}$zDb6y) zscGNpzdN!`OKx59sQgf=Le;q07yv3)Nz&~(U|82Qh1!i0UW||?MDs=iefcyDndr&r z2v}M6*xvUt|4blx4x|r|HXOKB+=!QAP?bw5grL?$z%c3Km{6H`9LK5n6iSFGZA=AH zM!Sk?9s^Mkhoi0Z#P}d_)UmTcUT0Tq((%0VIJ{69zLA~>ZJA`P?NApHh&?B}z*dka z6lJ}H#n*z6b>}ifwk%LOh3^N%@IfTsvCnjl9U^d|K;ekI9%s3lCD*VLE(7i~$#*#2zBQ zpKXcHBAt+^*o*Y&MljcyK%2n(cQT{aoU{^vsbhV;e(kGjMSFa;A{UWikC4~*)<3!= z9d`|ar6EpuPt-MqpSVRcPYdnK@~n(=1b-Knym^qH8PC-ncMm~JD%A1RVaayf69sI@ z8SC=nxRfeFl>U+6Ob+2^+wk(@B4CeYb)bFP1uA-R=uE)r!HOF@%jNyoDz6jHv031< zSOCBj`KVuIECTo}Z&aQGtVdO)Sfrf39DBp3ETpLH?>TK!_XTXac;u?7uP+(gYZ!%p z$U<^?B4jcv@r=C+16)J+Z&3VGC zZ^NtMZYF6$)>R*-uo3+=yC;HE(nRZ(<8Ie7!Q(8xtPo%x_>;(JAjpH(hy64i`XHB=el%?DNY)G?R3Av-zq8QMls?5iQ55Y zY;TfS2YjzsAhuFXMGb<0K#l@qZ-^p%C|{7ishaJ zsj%Gmj0Dj}!R&Y=pD^yDUQ+REO&Qz((!Q4n)lV6`GO_GND9;btE#y*>Rie0tgC{(b zyiIWFu()=Bb_Qp#5e!#)H%Dq0AcJlD?47_)K~8{ykxk-GY2x5JQ{TP=5Maq}2XW{x zJAOoV(4cvNUmR`+0XKsk3p7|V{E%Ne0F_BBzFh~QJ`O3mlfDc{4NE!N1`y3MGM53z zU|k%SuFOnbZ0|d7-gW*K=wg14%QgGBD+as5c8U9RS(lP$ftMlS9VF* zb%}iGdkK3)HBrCSxi`oDX5smIdW z;qhLcZ!$o7qHHoYmYr$C#NFXJeospgu0s0zzY<@UEI}NsL|OVk7#!%P>JthcKXqDT|>_6k(2NjtJ!gN#fg(yt~Y$F;_! z^2Iw`4ex=_khZqv#OEd9A@*hP$Z;U)tEiz!efs9`&&J+yADVokG~Pwb!Izuflhjvj zw7hh2uj4r@$va-?@*t+5*n{JgyynFU@JY~R6>C20&oU{SoY`tI2z|JPj|A#&Nupx? zCXkw_xL69Vuk+Np@3bcnSq6!RJUY3ZnZYLYwYa{PDF*Czb#ZkFqt}wu%$2H@*K@Cx zal<}(X-S^0d$_#g(?2*+PgFVN3y3e^-{8q!TT-q1>7k~Mec2Upl;=aDB=b}&R`Ial z<0mYpzdqIN9hZ>1v}Q?{O;{59+Ya$`Il6acgf^W->|4a(0wZOhzv<+7f7`j0$Lvy2 zaS{P6?3No^$!G}S{k+`u2dg^io9H*&FKM;2qJ=GtEYs~t!)IjlcV>Q(ILjg2m6-V`4O-kMNc|i<#5O05S7H4iA!mbuNI#vpU%$9-u*$ffrIs z&4w?hiNnP+)$-oZFBHF^!h0?uWRBrEj&`QM=g9p+;${zT3QpvDEKsH{5w1ZN?#-uK zx3$*1(=X^Xf~fog4|2CA#!%C`&jt?E$FLi^Q481ZzAz61xM(rt)jx=iz@(C|Dg$wBZ>!at{^DSkU_q)^hrhFmR zyAAd)u~Z%S@){TPPlo}Vw>*kHgORnSiKkYW%|$09JOnR$^)#?#yFV|bl!gXTlty*W zaner(a~Y3UlK6ZoSI7hW|(4Eqszk6(o z+k_|57+m^87k?0psVF!0HS}se927YnU)YfA7Y;?V98AOHb9ls3lc7&I>?%kCd0uqx zA#1~npeswQe$RH=H zN3CASL2M2=j6FqR+@B&#uaH~okiOz!rXzr_**pvHpmXgbP<&|#e?3dJL;M2)iAgx# zbE6(1Yd0c0)K*oIqo#lZXgo0XdYT_|sPr?R^qG^YabNog$g6zpnP`j7kuy35Cd`?I z8di&aYbt5C>z+|Di;y;g;ozoKNk*J!B*;?!L$u&)KD;&GoCN7zt2(mDL$a_Himoi!l~3$Gpd@ z)TT1Zjsw_0XGy}+8WS5yQW-5_n0T$wzxdIYc24KVovfL1Ae@}(#SW_B*qi`ry7Zl8 zM_?%ndl#P#S{)&uQ^yc6efA)^=nbJ6x8|;mb;CfLsr4LlC~OBwe0c|GJ^C8UfaVC< zx%-LZ(MpAIYcD8WkY<(VA*n(Lp)^)EU-UcxFO#OZNW?7RIG3=cri9Nsb{`o-n8r<{ zIAzIe4(+TYkSqldMKLQJi|tBx3>PeB;C6W~CGfuZ?@(KuJ>Bq?k!SyW?O}evbtTE> zZK)=V9~rw>pL=H^82jvBu_1OKZu5_UQXW(KblIa{-ta}~*W@CuHjIG)Og8sVb7z*W zZ8H=47vh(@0Hx_B|6nTR(x>Mx90OeTBbF+If!w{%G8S)R5K2V?aIlqb;V|u`hNJi8 zi%u!0TEJ$9$7lvI-ovt9U(7yvp!>VPsU|XoK(p*>SxuILHlY{3wM)!rxipPTLMkT{ zW9tIarmTuaDy^~FMy*)OUqWU@cizT(32tp^cHDu$uezrtU*2{F(WMjv+vY|xG>HH5 z%)QWG!V5VwjAw}H6M2_)>%!Bsx&7IpVN%mlx8~({uE`KG7$ZHmTYj#Z-PdTwSz)99 ziWcsh+N;yGp8KJUDJ~BEY1V3#0=Qf7JGE?gLxl?qR^nCG8)are#`y<9e#OVvjIpL5iPao9&u7w77-3LH4QztR4V426!ZTCCaL?zpI0C!hc&~{}v zVg3vN!ej3@Em(W7X0JjrO4XZ0;ezqC89bUYuazAf5H`4*Z?2CNkBhTVb9iS zb{;hcsoU_eU0+&}w(HkvCxigzQky;0k*%q(p`tYx>k5m;LEvE#rDvUZ$?*(5O?A5` zUg}eo9+pN0Gi~qT17_nN?JkaHxs}tBxvjdQ)BmoRZd6(c@xPlhsDH*Y(uzW*`(#jB zNOtCw=0q9wk??%K60?kjrP)!b0(4~a-#)w2VjwK{H>hTMX&{W$`($5DSW1&Ij;WFm z{P>m1`P5TKR^&@lV~^3-6ajxgPb{u908Q*W8=#sLs*p_qRC`>S`GEAR-VNIoYN7PQ ztWGzw(ZxJ4BbJNTUb~fbg|rAy%QOGXOY%ATJRDrNyll_*ZHPs8Yn-f#cCAoSXaIhg zm>zp_%v-`&ga7%fBA~sH<&U@3C~RZTyL5d3U*MbWG}<#>Tgfa~vwYy_({fqP>kqyG zG`A@h%6+*L&oJOw95O1va%?7xM#H{lI6{o{^X$tw&NY_-4uwg_o917T9_RatLh2ZN zXHApo(P!1%5t;`09{-Ta7)s-;Z9GBc@NzH^sy^K(9=@O8jRDXAN^Nv@`p5GPPFlyZ_{&v%2d8F^7G20 z6I8=>!uAO)V!DtGCaFwW8wACn^l@iwr=}?KA;uzM>d(}5h}pFWDEW`s^#~}Ppf@C<7H;w1z$y?Mrbo>=jxd2UZE}_3C+tHA zItVUZ#Svi*U)oGS);lCoXk$i=pXT|5u7;2Rv@_Nq?O0aC39n9oEG{e&>drg9tRa3S z_jMQF4n!#hRUtf~;v7TKXglP5XJtw56taGm^QdKw=xH{7OChj4^A@XIFW?4q& zU_WTJhCQZQR%x8LYeGykocyFq{51$70pmJ-#lE^q&?_N)ZqE60AGvVgyV@{A)|l8Q`OLpEnE_@FZUE!5cfK-_$c zYNysz_Q(ba4dTCz^NITFj!~qa2az!O#0Tlz3PQ{P&*f*K#mniA0JVlprG9?-G&h=8EQ^ zl68Hu(aq^+ihPb{GXltodgjH3Lh;;<&+lL-c*=}5P9D={Q!sjwS89>?Y0t0aaN_WL zBKTQS>2FoZUt-(|)JmddEiZwjjS2KB@yX_sPc(F7e~skm6Uv?^J(zvHhTl(DNKe6n z4?rbJ**;drveh;NE7Xs(?w4koWmitfYnqS}*kPlBN~J16yz9J&N?IRR-=>pxkiFAM zywP;ZU6=EBDpO%PE}c^bg1Sd1JY(g7&*@}_08duv5#4MqjnUSN;CP~6lFS(p8maI6 z*GI`e<#@YPr8}U4C#(L>P>v98%yVP7GvBN@?>Pn# zvnMQ-0)BCU(}#muvJR5?dG{x(Ry##Jz%;;Dd-M%$~#*Iz=$C zo5F;|s*^0jlG7N+_@vq+d@XYb$~I=aU>P%)JmL8Dcmhd3F5UU zG1A{DyHGakdLbs2cDRAeb)_h1|W!?%+q^G z{$HJ#5`gi4W81K*{EVRK<-pjp&udPqyI!R}1(m;YO zWB4Pv{0;?iYs0oW9r-@+Nj{TS(s;}B0cm=q=-q~JEhE9WRInSYYbSfds7RUu-x8k` zp=WIA2m}BhC!(@38CjUjEC2$Wo|6UufYUNwrWfWSUI4xGO3NHe%QG?QFLSV6C3T^x z<&|l;Z*f}y|1{>cy)7RuYj{&Jikp!!+Euo)k_()9Jv^GRxRqV)PeD7kqs6PAC#f#F*|5l1`V@j^qr`fvvXz=OtkAbmr!E^Ks;VAHMa>@p)-0(3O z)3D~^!)Vn{$(9ij(fvEO!Ew^h-D#g_P@>Np{2%jukLtBZXg&XM*Etw8DmoeV4EWG(HzI~cYNmwYY5r-Rn47>BfO^(2 z6>RsYW4)0LOi{-aM)7{uTT-bvtxxZRvoBREXx)yVdrZ%OKObsu$b?1l@zRk%BuZMW z^?yN}O)Q;SeGewznAgKtU~<(aat;jtnfo>G}iR#5a|>&eCRQ2kTJgKe#oRjk#{8s87qd zYxZBH#1C{#E+pnu-@lf8;WQXHPpuMB&V(7T?V9|B>tukI_Gp9xHq%ts{2Bhq_6vPC1(L%kOIB&bDt3^+M@jk zI8q$2&)ybpdJjjmQLkv>$#JGJWzc#F%S*3|Ulyce>-nm~w}X~#l_|d#G=7Cm`l+f< zNOSPuWLpm>44|rQo_6^1d=wh^cKjYlz+HBnWNCXuR zX&1(hFWJ$4^&P!XI{aCFuwh@+wJxk$OSE;4fpPAkKa-SUd1#Z0 zHjVGY5r{5|F|wT)t2Q~wBFp#j*G#x^m@GQs(3i$7n|yHyP+zj(-dN}|sx*i!lxwW7 zemQw@BsKHl5ZiCZ6mhZ9hh1QpEc-9se(D0)(e{0{qEG29gBSI(_u$T53HJ-e54{qC z@~ZzVJ)mAlVUs@2-!wgDYtN(i3S2#%O#_F9+Z(myj#b^A^iq>)?+%3i; z0AFZP@vL&cgGxq_o=j4{h^-a$aBE6)Xmo{-bZW9(+M29beiw6pn8Sr0j!?s+H(QJh zoB`wD8VG+}gBGEvnoNd?PB^Z7%GFqSS`O*w>Nprv^r^YXPRTr?yQ=F4j|l0G#iFwo z7Vm0|x>at{6VO=6WPiqF3D5P3T+a*uqq*JBQScdk3>yC6o*dh{aD$oLrUQQzd84BiFTdVgYfjUtR+kQp=9e!&fOO=%+K~m)6)X; z)_}T-)`!AznQl70vB^&EW4$&{JqyOM@!&>~M3spkdQqUJ4m(j~^R3nDzs9B$qtQ31 zQi&pRAvFWCbZy_EaZVG{NTSNoZVXl1 zUU|Lbj95!s^5;w`V#oZxSL@tzKj^G`lCnr~rVo$S=^;zt3nRyUKZdH;%$GGI zTa#Y7w;MKiBT-+f4$QWRK406rZmFJI>ry&G!byo^-V95Y{g@F5Vs(!Z(fKmUqkNUL zWS-6FDAu1}XNz*xWTE>~LZ6Mu!Rx-~&~TY-9HuQdRMo9>N)}qQ{WdPSNbU8#WFw86lb^-CJj$0K8vYXNfkoUL++sSSaCJ?X%^4K5Es}|3_@-cS&sTj|3o)T_-LM z61Eg5TpF!w9Mvxde1PRYztj=A~sAFQ?)k<+|W;j=pIiPa0t8!{pW|7HI!Tmeuh#GxTc zZDy|+ej$)zG-9-n3E7}$ZRZ2&xp>Rs_+~M8zs-cLa%a6PJ!08cv^2)Gp|92RN(AAy zu%bYp{tuZIH8XrK9L$E)7>lc-GQ=`!WNJ%)B{-44eY*Pb6N2{d&HPtT!th61%d2lQ zOFZv_G0(x^g>K%-m2}R%m|sxZ3VGx=Xoa~OEt6Ll3ZHseomu{xOfUVL-||yk)1MXV zI4c)%2|;W>#uxrXLxiImlj}hKBJ$Qgw~3wJ6X}G-%$yW2Z;wzLLp-8bz`P|ZZROt^JfiE zv1+#oX*MNya!?Q`smdbSC5DgFF$7opG~ZpK7CWEvLOGEO!Vx~vj;7bEr}+> z71bFFF-;=EQw8K{0>HcRO2v<}_4HhjpzdpXkwpGaya0|B7siA@a&=s4bD!oyp{1pG z+x|p*J}RO~F+*{&a!$pU8th+r$U^c2*zcY$=Ti>5dNjZ}uJc5ux`=L^4eRql>%$mVPwB!Nu=)~s`pqw?7l>7W1 z%(MI_l}4@g8|c^(wW3qVF!7n^B7~1Vdj57df(U%F2ORakW8|ecp=c`Y_pY!Ei})=w zx}q>mz0QaK!_-;EHTnN72 zJ1N!&&`&}!qjy!4Q*zejRT~)gYi?KTC86Vt^e&k=C}kzQ1%3n@-jVa}TuJzTpe8D$ zk{Cv74d=S(rJ2_W(@Hhz7fAPyOOs#{oym(R+LgzrxGDO&YH5SiI;^7fc!X6MYdhq{ z^z$67S-i)h_ppqmROP~PfAR#IVF@A3ZgZEWSBz=xuCk|FAIr)1#d zXvM;uCqm+}2ac?vzP3kkO{-XeLR%u*KRqk>I%<5clp+-sckGvj35p108mG9cr;XA0rZQIod6p=B$#hRw zC`WsmDQ4f4aT#D;8Kp3;{B;$-Q-YP9Jno2Zp>$_Y9y->p{0Wv1DwYlqz=qjfg8H49`5Cd-iI!pj%CkVQd- zjG0&hnSL0P%j8hGFHi-^P^HLFv8w+QLbrRgQF5e%xgSt-r-K+4C>f%t$EvEJl~sqs z0Mi`kQ5%43n@UvOOg4&&dANhCnSu_|c?%D-ccoN$-Ep|hc2rr_uE?YHKtl638Pcy* zX_hF{Quhx>ZoRAk(v6}9<#bB@?$rI)5JWLpr*|v2uscLiQv-VFD!b!EyKqrJueuI5 z^)6%e9)E{!7C_GtltWj&n-J9-Lwfo(3>)&S|djki1s26%d2D?)o`qE8$ z6QX(<7b#I6@|=c&^Fkd2V!!wxpm|n z9oG1O76}-0;~h z(l_>`7E`cgMA2pG#-i&cP*TjyUVoC~r(jB@m#1yw*v~qyJ>e-cgb{|jKUHJy1lM~U zvNAJ(JGVI;`i*&9DBUn#RQIf9O}Kyn01%&*os&zM55N}zq2O#_RwaPE+6Plq#5>Bm2{BEw?0y-#tonewY*}sTgsT3;dcYYbnSR{sk=f z!eVUL*GHI8_-v!(Bq;Titj_|wY5HtHi>u^hvYLY{fbg^~%SzQ_NaV8KJIVRc%eo!nHXQFy`4MKoJqXU+Ee8$-Wk;H;{8&Bt9`r>Q5Ex|IHM#sq&S*g zN7os1s11E%;FtQnC|Z^h$|!xD%Oa{NY)Qq7y=%Q`lh`xw`Nm-4j}?nGMaZ6wi|iTr zjaAtdbylf)jDn?BmT*vIOz>j=G>~M^mFbZ6w&{qom4ZDp0rIk7rS!&SeJq)&=vhLz z3R|tIo%JT`_I1ZzBDE6&rH`vOd}`_W7IE*^0F)q(-q@{kPNiB$#9S$Fh5D*T>PckQY0N=<#PpA@{VI$_g) zPum~&;Q1unQtD&nIU~}`UbH%2``2m^OlSXgr4GY39FXFD(UF$XCSb(wgp~c{F!K6p zw7^-h08}(rf|V616HCl@BJC z-nHPW>jAC`apdlOa2qm-|G#_(=cjQr0$)@k^$#l8s% zetq{ZLs!OuVyS|V=uGz?t2gA`8A4z8kFqaG?PqTa+?MNeJZLSFz~k>t1+uDObDoxN z(1)0B$a}CSk`c^w1ge7~S&Cyr`o6+4){Ta)wqrxeysU>XZ*U$A9Bs)o|64dk|K&6^jURCk_S%v@kEbF%o2bTq<5wwOkxTZ9< z$m=^?3^fsV`&Zh!xndd2nj)Dca^evXRko<8?|M1I|Mr=C!_F`|%OTbA6Q&3OL1nPq z#dC_p#S+c^4Vl49F9$At3Yp3iZj}$#F|8*I-nT>L1BQ0_q^h{o6>=az@nMdavd`yB zGK>0%Ea)zkyuT6d$}*DF69hS<-2aX_dHdsQbVgJxcgPghC03$7OeA!V(yIOGqfS?gaEFIR++5di>K!OuE{{aCq~feATbH5qqk3-p|1)S4=ZI zDxBh4Zjif-XL-N=QoOuBJW`|FBnr+<8iG~lasM47alFpw{s&5M5;-ZvXtk@ZUSt)s z#Z1W>n`~AGpP-gv9eo7WgbpSGxnoqBG!tMh zfh)*CChXxy_PNU|?)C0q>rl9KtcIbVNa5J;vYyJhnc@JJxEqQ8A=+=3nCzLV>l`eJ z+>d!JhPY&A9ks=0&0#it_mpg=n?H)9^+hx>d-8Exp#pNc>kc%XMDAbagysv%kA!2D zRpCw7>px|LzY-PqX1cnhwkH2j6^OL{ii?i160dy*E*6mswtMq>^7?YdhevWt)MF^u z)%xjZW9RY9+%z?!Q%;ej=BCK94tnbmq-hR&2*otz}phL|attwz6`2>M}H+ee)pjW_@?S73f~g%juVEKX$tU#j!SjoZ7?> z)OL{Hal_t((!KtIK+%oas)zqQG8&i<>C}6AaLqx~P_O2&biD3xH#GnJq&8;D_?SM` z^KWAmmA+M)fZls<+N@yeRv}lmnRI1(p-vO%`nBPO)XA4P_pNw60MGB|yIU#&M%~5} zM-R?_IBnCzru@x^@Si03UiEwlY6@QCI}p1u7rgS}r*Od7yEKDkL8Bc4Y_4*Pzw@^$d{;FJDH zIQ?NC+HV_pnew?}!XIjb1W1eF*aAswO_jE2mAGT8{(aj4yRhFt(Kjz9WVJ=nDc>B% zg$sr*EJxirL#e+ne!iw<*9`Q`9tfb@iLzp<1n4%AVZ3;h$x2wr9W(|0od$+2C2CSyKZg+{#t775TTs1 zU^o#vvwipLC6iwm?aIE{jc(;1^$5w*_k0z1s}ir$zs6?vkHJHwyj80yzsnzOO^-*0(^r{M=BcApEdKosBG)Y+*GGm5 zQ$TYJ+6A;4C)9x$yIJb+W+Wt45E2UXiXF3wB$xfVcehN&oS=-pCXd4h3cOuPP_Vg` z>7k?T!97PU`r=5+gqc4p&a$CM$;(EV!ZMA*19N*OWH6;M%@&h#R%UIeGIliM-}Stzi6De!CsE#$kh`OGk{4Mh`nTy zJPfkKpXwI`GFWpEDk%8$_i3Em3HRVu%@80xF)Trr{-p>+m}VN)DII3bVdj$V@4Z9-0u!#+m+G?!4U= ze5_X%erdGBXAByp6a>+5L()2vHOQhmzaOI(@yO~|=t&-|o zIf@q8^B|H-KishOuF*2pjZ92*_Y$~fOs#=4XsbLYaw>N@DhDN9_G;hVGjIdl9NW&> zMrK)}(^t{)YwdZPmvk8%%Gx5lcUketUiTT8q+1ax`)gbm`*1!(qKcQZcM<;}YuwPj z$wdm$5k!r(jC+i6^-2-EFp!(oNp3xoe6Q^%9abWrV7Qbkx-4R$GHz^98TEj~pTQIf zfMMoy{Mv#O@ze_IK0IVXs#R`GQYFg=P(FG3Qq*TG3BTKqA zPrLxyJW%oPIa3uoYs4k!;)iQnF2BBKZn-QEuaCaHRiRa4ie!l9<0_ebGT_5vgMNM6 zp`J1o1@X!*@s|;WJB>cv`PV@=KuKS=x#s(gb$qDSDZ^0gyeN|Oh-$HdP3o=@k;qZD z+K8iAE)GX#JQQ*9VzKC5j5krhs(X}RMGPt~OleA)O6xVgUTQsG1FihXr3s|@yyQ|l zQgj|?*++?GDZu5jTR-hW^c=*62r-`ZQXlkWYhRl9>peV#@`ig^KFJH{P6#EN5^*LY z+U$!GQcZeP-J{Vef8FV=$b=Vv1TC~Hy(dq?D&9{#`)5jJdElme6HAEjiMTCboYZt* zY*Gi03Es*fi_@!c+=RNy5#QC?EsJRt`P6Y!G+qV6xovavVRl9BIs21__pcsMbcj|o zCBk=84A%IkbeKn#ue~0K^VG$~b*5zclEoOD-~V)+Rnkr8*BH=PQ!ktE^cBRbKcZD| z#ut;%tbu97AI4iD*mnp}WiIG^a~%YsFnRv&c5QKX`Df}- zckSuyx%GhF4-W|Ts|tw%{D}nxKQNAT=>3fEjd19VrtJ&G_QpE&e!=&KJH#b9^xbn{ zN=T>9q@|4eSj+)rGo&F3|Uc&sXM-(?zF$$kJ_(oKmagM(ZVkhSH|9Xyr&0@aKIa59RD zT4so@ZD_KEVlrxo8cBYCn_+JD>FTWXD~V@I+@SxB|H=Tie`oG~{}=xk>U2InVq>>^ zyX0cX$+j$Gr=9jXvH#OjLh2h83>*>i@|yB(Hlh}EUt{FU)oaR#f<(M)u|h7gmSwhE zIyXhfJ;M+{MLckMYR*pKPYl_1qJ0^ruF=}X{>RPB2Lsgh_K7fN!AAhJ$-{iZ!|&el z@?~(7kD>aU*q<_s)6dG>12H}2)DC+%uJ+BLa5U70b4I52bDYc=}ki97B7uL_<86dbf! zt9@^$;i)eA!uZhjDkXMcRo}jkOJgn5kBWXP!FA={TX^E(@)PHVYw0u2x(~~R*01fg z!9R{mI}z=dSXP%gy*L@shWX%biu^}G-utotkjqZJ-uC)guSWp&GWOl!)3LZlXsRp^ zh54Q155pC%JiMATVGAOH%FfBpTzgX(aI_}XLcfE%7L{Us9tV)fL+5oZs3+af>pzy0I&JwOFAq=qlx`Hwx1&VCRP=*9)hHby5cswI)^F`RAlZ76O~+fAU)9 z;9jlQ6kk-jx5=N6c{NuQLQS}qD5z?Osv-cfWE65yIP)lygyQrX5039uNIR%WC_QJUVW7)HUTdU}_l#MmoD*E^=>90r zsa_LT>E(UJ8Zk;~2g=+EG+J2wgtCjCSE_#s3M_1k!JW?TG$FyHM8;dlLik8I8W4=( zg_lZao+NVe-s-0+NpLV?S-Ej6TMZQ(=7IAF<=5(`^Fz%M%QlJKJA#6iD4f06)x?TW z^7~_tNn%H%TjC9-dpp|-;EsBd#gjA0Bu8<<+AYyq@H$J$MoP75pdXn7K`?j(0 zFfqllG2c0ZUvXr|X;)F6fA}G4uh9AL=cQe1tC!={ym52xIvN9XdXLS;ZhSBdo9bSW ziWKaO@~jEWOrP?t3pvSfHAJH-gi8RITd5yP!pg~hnybnwzOJMRd7|CgUATCosQ+Y* z-33g{jw9~j+Pe`opT|*6FAg2wZGHeW@s!GKBe+-Ko>vv+G;98s?=VcleqEe%E~E>rv+HZ1n!w&|{LIRQUpWqC9GG z{tgH}Y%tu&c+}5tF-6wRyPC!Pm7H)!=gmiPjIB4yJffsW0Gle@xc^^bHAX(DaKSRO1 zG*SDqsw7WSU(R*enswGS2Y;ZQI?Vk-$_-UabNk3hh-|oPfrZ5f=VtO$etwcpn`yB4 zTgrV6maHvXaXNw4h;|uvAo@GZTe4RE?T6(Aaa5nut-DGFV&;*KVbAEE#`COQJ!mdX zO))LLOHZjXeB$Ce4W=Uk2^`6;YHrlz3gg&Mfs6d+9m&2Eod8-HW1f4lrkqJZK94)x zpG7taM?E%Svp{3u#x`l(l{y>-=~9aRXBBK)y|H-J8MZ3J0+6Vxu1k_sNCuatUV^ILC&bm9aid7X zKa~SMuZA4Frg%|y$v>PD@96!}HsN0v)2n#9iE{uU*7Z*tj-+P3EVJk!z>B=I$SCzY z;XUT$sYJDxlGd!ed4x{08M#zMUgATA$i5YX9usS{x**9-r$^P?)FRC>$xj85{l(+1 zRo-T~uI&|!OFIQQdu{ZdF&^;BTvmtrbk5H?fxN^9{3=LToVtASHVKxdbN^MY(?>Q1 z0JB06Y!=L(TP8Ly`16qrTSBFaBLxRp0!12cywrE;U>zKKqLj5I=kx3XeNAPUole!rh2O#{A?WjkC z_)FjXj^MIq77x!;Dq+9CkO|kL5!+w6iWN5S&1mxOt>Dm6h@^40#OfT~(9rGfHpO?E z-fjlg1L*FYpR?B>A-CT3Z}`;rRyR zd;iAIQB9>3oj2ZnF+VkATTjlLEn}uAP2=RF({whhR~YVfHuO#O?T_MFArTUjQ1#K# z3xyH=^#bqT(oAK;hhjeKGW8v0gXov`R%H+qtOFHHQXkrz&gLkWWX1aUZpPJ!0+8Cj zb3&*qF(ftIq5EaEQj6pu^UERtcVC{&sxiVt{MRlO=9NDWpYw0@HU*N7a)H4?^})Zx zXV0-r38~ZrX`!d_AqAZxXcST0-5|u;b?=*Gr;_Q^;Jo{g5%!i!{)kOC2q3uO%~LU7 zKV2BeHS+VilTx4#&hoVsV0r!D*0bnS?}zPGfZ)gT5n;9>so}3)#C=IWR+WWveJ$Z( zp(T8;m+~M}iQ;}#P}%p(!qhdxoVxu#3rGxo>4Di>Non{~@dxxPR?hI*ssZW#M;XuN z9igjK*E&Pb!$Q0n{dE8CviBWF%dr-dh5W7(dqoksK$)PVxd*ts<*xe>(J%3H1T?V`xIq&JV7UURd4^azSd${ER|$M-Q6bX@e~izv@5>72JIF19nRU1s&mZ z#{(Jw_QBh>thUb2$D~b|S$vPI;Z?dBi3+1K$i6+96p|e4QTRGpjAuUYdm%Q51;-o+ zAOuN!iZ!_h;ox-TkVZ;-B&wY=Q7COk{AN-4E)uJFtkL#@mg_uF{zy;TMrD1$B-%s5 z&r@=HIq>Uwh=VSG0sy$(M@}Kbb@yNU4-r@-$lk#4SMP&ah=BP-FNGud>$U)$G2&~8 zkwd;7s4^+7FD0XqoWD(O4JoPGc?0`Rv{8YE1iGodAi2&)=jmlkGk)XJTiyVw`Wbbt zj|yfBUVtOy4WdFMcdg>Tx(QW7w6yk81Ld?ZhM@&J{9k3@Q{VWXxW&xpakIr6g(*`> zBZKqVZyJ7MK!vJB_1W@|gh(>;7lh&WR}fUx{H5+xI3fL;c~s)TkhNYGt$m%pA=XYE zvM&pW6)JK}6?KkQ3Gvc6n z)p5?*Ot^pJ&cFt0B2KQN0oLeg1#iEvKN0;j$KfTL5p7)R4V)b0NC)x*L;Ev>sYo2h zLPMI2sw_4r(2X%cYk)*-ghy{5yzp(ixF0KQz`q=pA1XO4jG@_!6_YbA*tkx(Ai6n_ z`MtMFM||^(G*EQVyVt0ov2nq6^E7s9IDz4k^Hx=OMrV9)Jm{1F{|?RTCfH&L37?ql zQ%Ot~9Ku41t_G?(Ddb@)UBoF{UsA0SQdVFa2{Fdg9AUGC7abppn0-GpFA33n;>KJ` za&ECQn9^aq3ISRC%;;V5vnTg5rw$<>W!X{o{j3zdPaviCGD(FMW`aFhVGfFCQ8b_c zmAph(J?GSI+^N2mg`iHeS3tp~hdB!spO5OEo3AnmG7u`;w)CI~hJ4yf>(~*OyK2SM zU?)G8;KM9m(H6teVH1Use0FKx&S~E+M|{u0p&VjW92@9ZsO#o>t%yXiQ0NtY(~G*w z(^j%Vw4c#rlz6G;-sz#t5YS~fZKU5w0B3n8+_h#tJW#tCg#UbH5xT%03cxzW=iaH* z+ti6%%MFyPhkw>#&cO$nv~l(P;EL#C+B$Znw+s1W3F=JHWgYeWPfqMmP-G7(Y1J(t zX&jvga)@8Qb6%bPe2s8s6x6y?99O5V@ExAEm%6)zOhbBjiiThBM11^_cR?+A*h|Y$ z=Q>UdzL`k;DRh@3l?MrATS#RKUQ7jmwC@XhnA<$a9oD?}LF-1c*HbH#b0!180&7N_ zG31xq!kApjsCNid#Z8X8Twa7HyiT6kh{_Jpu1EWt-2#0ujL-{ZWQZ%l;0s$f5`EBR ztq|Bf46dp+d2d8ZNKF%&N77Dq4s7FRXS!cflQ2l5uob6zPe!rNwa(%+2%E$+{UeCW zLj;BNJXUGdyrk^u7C6!seDeXlD3lRe4VL-0Ul|4-Z~;YSfTb^h9Bsg_g21y6kI!$@ z=({|ru_kvv<*5m!6U75Wwx68jgMqV8{zlSKw*jct+x|-fQc1METx=7EP*D#8sPS#0 zkapllfCr}``(PW_Yh|9-PyRR5%KjVv;Qz(if1y@})8=-d*Jd^CR%RdvWgfx-Wk+XV zKRF9ySe=+#shvQl6lP^ljD1RZPJT$?2s3Zs3$`z=z6UlKn=#|5r1CjFcaZ&Cd5A(n&>M@PNkm6pC}MX?yspGoV*_o zjv3jUt}bA0w@_^)7a1M8*L(EJ;c4OlbaUkC@w-Ioe&WK(#^HV3TTn#l4>8s}D%#O` zcm!$bwxc*HI&q7%yQb^fZM@DUC0?1Scf!)_isY;!*|sBY>fWIqe;wbf z-GSuVpEjWdAJ%x3bQJ5jE*nUZ6|!V%jc=^QS)|#(m%OK|ZpG$(YMMiY-~Qq)K^bg@ z=x#W4Z1c!8@uqG5Zul3;K>p73@mhLbXl`Qu^tabrx67;K8=;gnT2vLWzbf%>Jl8~J zo4p6jojGW?lqljk2S0ZaPe4g@*Q(c!6d-X+&fzJ}&*)(@-Otgvi=phTZd0+@fIMr< z{;oP!_bTvt3L{H>2U_v$Jn;or5T`r4+(l|NV^U(oGN)a<!Eqj8lHq?xhTbMmEFe zV3yM7O%ZGMIRs-Ku#^KVQ4s!YSPZvh!{h+`D3UAr&+vQuKG6O6Ot3|`HV}cIrpoaC z-M(Vs{YFD9!}i>)h_`SZs>qw9&Kpnbwh)Mq_0_#t;lzjO^rVMs86VNug*3CkA{bNz z>m!JdCOtI6&PFQ;elr`QihS0#O9;zhecn9s6*5Lub4*wTj;_RA%(9Myc`8<$W1&*S ztvxkMdKJ{YRDNJfRexQK=1Whhlhgn48WXQU_TEJ4FvXm(n{V%)&A237A0%fy%4~Rd zGFYNkm8n3G9JLALlNlUGl?AO42O(ndUdLssof_Xog(v@%x|7XNbY|3ve(qd}e&!iB zEaaE?V%|~zgS!tO&QO&dBN}qGl9%Wk=1B?a+q>hSMj(|7c9m?d$;sksr{!9MxtKVS z-xpWRp(j*{;eEGhGH2_RY|K#IO|z!MMbS#6aBoVL*fw7nKEX(nI)w&#RmNOI!A;jA zIKTSYNYXjo-p$uN3sTRE^LcWt?RAIO>&?dEpH7ffuyFkJP5`+ZGC2uSRtHmaYsr_k z8Meldjp@f!Uh7rZO5wx1jm5lfsby1~I#5rJ8{9S8{I)`RVoXgmJf-9I9bLdK&n@9x zFLGDUZ#Qsbt3?K_mB$+ut6s?Ak~^P&$?fvwuRs_tx{g&U&|GW{z2wbisQp+qaI~N% zLIBDcc+s*XWU#{o8wogh`;HLrmn~}_7_gkb4Zrt>_2*-PsVZzFhiOF`$uH#)%JZyV z8eu2z1*c-crDz|qTq{(^I~JPf^kNa;`~dXKeZqg~eOYa3*3k| zO&K`4hEc_l1si64P!@D9H%vWBo4iEGGuA6o%QpMHDlHY@T&7QyG10K5J7cR{cXju0 zn%<^X?$riFYr90gp}O2{EaN>LW2E*^?|HV77Jii+mAkW6(|jmUjoqa!H%%tz5TK)f z3#LrgqtH0N9E?~Hr!ne6XP*~!+P~~@IKk|O19Wm|1H9G7)m^y?VPq6aC?qP4Bh0wF zhv6{UqiGOjG|5twTZiIE_b8JBBr)mNikVSwkUf~866f=JWSS7#ckgJ9n5NO^Zy^gf4P1qJ?E znbV;frvUHzkK+>?eG@5t(yd2K?!d$=Fm+!iegcoqajnW@H}yhiO-$@XnJ*cLzKRDu zYkX-yZ_3mgEem3CNiSVI)iJrgU=7Q8lGgm)nvUOo`H{?m_{vIpcvihANjO8^WOfu& zL|&43dBc3swOHMb9mK$dNmlqKo}wT$@P=&JpCziAk!_f$(MLwW`4p&4d1jW+Fg(mi zdypfo%3F20pJirO!M{~oY=Yf+(2BKRekN<#P!?avJ#TqaceB;tzZp1ls=ucFc81L# z7g{ig%#=}H`imh^ovRpzZ7JRe=*hV`toi82WuX0|{XGFH7XXU>Nb-6iR9XHSEs^ub zo8$A@{=E}U$f>M}Q+D){>x9|9-AAjHtIS3o5xs5B%_+}e5t}3LD$aAfiG^iJ^oO!== z$~uKGEuhgZKxtYA1#`P6FQzM9sv3GodZGLzf3GGmKn&gu@|$4l1mm!A986_jRJ~m1 zZlsuto8+gIAlHkywV~Pn0bUL0glHLX7Mav^E=Nbk#xZ$mJIa@`De`nnXxcM}dG1&w zuK$9}Wgca3&aL?Ov<$H1STQ3ujvRYh7UC?y&;M4LMFZxtaoua>Lsp&FT@*`l#*(A~ z62O4%KDJz0aP0mI^?)xt#+aIX5wVXRF9T14%bRT}%-yAM6!(|i!_(|XjB8yYC(mnX zM-~lgKbib@=(dp|hvA|2(GJC+mb^y2G#j{^ZxrkMR-T%NePJbi>d9SszyR>B-0)*u z!wE6#f!M`& zLjSpJx~S+h?jeBMI8e&LBWbun-u843>4<`@WJp%g&M)xnj5wVJ2l(b6E?GW0-!q>; zyh{F{O^oFdGe6bYDlZTUTHqCD;9FT-+$J6=Onf3=UJYH!aJ71WJvy=S>lf5(nj@dQ z;+ah>hLz{x;T8pnuQ3xUa=A~X2f?Zy8=FxEl5cqHmfQ-vd~9`2ZkVfOg%969GMwdw z1(uAiq9SPT6G86*PQn!eRB3sJw8GN&gxi~uce64{J@n~JMz=5Wvi~%>yv-0S@+`>b zT$cQZmCVte?V&CNFiN9yMm7@SdhKac)B{{Ry!!r8ZwS(fAg3ML`!5WT88mlxsxhGhZi*1<^JzYO#|oMHOUr4p2 zMgtMjhguG#h*tRkOrrYl*t>g70Nc8oud&o7Jwc@fawns=hEFL$E2`uZ{&udB97h)2 z6d|d@i6ZWTKXfd`mg$5FXu5s@(Efl0x8LUx4LiU2`L!nnrOnK<002Zla##c9q6ByWV;ClT_LuwR{&kb zsJ9ST8*6`mAKp(1mP4@UTL}T6u{f?O1z!Q}^g`H-XZk`_*f~IDR9=-glyHjV0Wi@I z+ag7vm^>GtKZ3K>1uo=eFG69Idti#396(MEMGgQArffR8vtBF%f}<#kBSI(s!G4(K8+l4D z)LKUrj#otaM{V`CkzW`$10>dn#(HrkXKfo>%1Qjz<+^$5hW4T#-NB0L%6t+Lq+q_6uFA}5 zc9AzTX@I7^8rc&cr1BP#il}(!EMlgCHl|bvG_ffe~(SOxj+YqPgu=`XBPZj+@ZTv{}3m)uWqlPV-|+r$A^gSdikM%O-+ zPh>)P>-DddHMmK?RzT0}kf+zVR0^w7>=$@pZ?Z1>G{xS1TAO91n|e2wFR?*I6n86{ z+;3<4R_W+HHnvhSL1_Ap@yBo8eLru0gDG?b#_N9b>udu)+C{60azN|z;9IhTL9kk^ zW7CCJJcKG>x=?sbIBF?ID2L!SA&wz2ch>Sz?mB&~!cQIh_OBzmmXSk24-Cd|3*YGA zu)A*$%RR6Xb%##R1*C5O63yw%=8UbCRbZo>L4+IM5#*xUY9g!XvUE+=E?-w`|CvR$ z;qpUQ=7dGQXOgva{F()I{NQsC7lKPfXs7u70=bTgN33ov?YeCx8vlVDHC(OVj!iYu z4`Xi2_y>B!289+gVI3$NtwkLRd@4pcdG3%D|D>aFe{Mt>=)y|({ zSG%a-RV2=G*2ba6V#_FZ-)jc1vlO@NZ!7AemoOZ{%!*xFwn2ER3tsv1=o~6PX?_L6*c#+bz-uI-|@m zNl)?X^BL`vwe2H)q|A72Q)rUzn$wpS1puSdcXRs6AM^DMS8`iIXkDu z1JffzB%+ey(?e;4^KEI}l0qH=$r~FJ8=ApEVZqG+^0>mfNBOO#o!wDGLzNA2ab2Ae zH$tXR`3Km=O*d5dPAWeg%u*Sf#walufzMwI7)TpRp&S}s= zn{V$pnct6NU4+F{{iddv9mgPW9Ai&1%*k2N$}rc~x&kZAj(@Y|BY?V$`)s36dYC6| z-@R{{q~XCwCX2r#yv6=Ux!Qo~J9E`UiR>8=2tL zZy9mUoUqrb@;|i=G(W%5F6SgWwB}QG72AD)<(9L4hb5k|n2EX#U2e%Rr&8uwg|yie z$g=GSuL%Y&PO+2M<}bZVtoRhit*)U7q_$)BB?)Q`iLvb&wGV}4+1`~M<1skYV+lX&cnDU|ZD;=>2q0E$>3k3l1>tYp(`%JU=eQ4Mw%a%j;R529p9w#r{ z^30KXqm@lS$2GrX#b($bLY1>28=~1z6X8g<;C8bM53RU13cMvE zfr}SZe#1hmPIT*;gKKOhKl^e+h41WTBKN1r3HgT`0yy(2LqH;#rMeD0R)ch0XbIF# z6GR?){19mXXx}dDPW$O^DITW5{zfn{3&`lWP*TlhhWopGyNihy+=w{1_pxO7#@{IM zH@(rq52XcF9lBt7@3!X4xkyGUq3IfWYy-TiCQ{elyQakio$_08 zf3x(`T${-Vu5K?p)(|1Dg=o{-ySV?lIGg>1Gvm`P_L#k0R)xaemb}rCy4_uz7+o-; zceo~K+n3~U5#yS~OL+fWN>C&CRz&(^#$N7?gk&)_LPY*Q#;1>zXPSr?+**45r#__n zri~GSLp-67_Kgo5sx@K=epV~skv~Gs3N)u_>smt5{xB7>Ri9U~-5Fyv={8W!zev+=4NAMhRnN zJt-B}(Y+Jywx7k$JM(>##=48Z#<=b8HQC3yf)7@Y?`i84PVr4v&sAj+jfi}vwb+gn zgx(1bbfxeNyvOn8>xO1FSN2`I{UF&+^(YuY@i zJ-XhMz%0{PrtI~dy9vAR4BEgv(YVM-_4HG%PB6>+HVl~Ux*@Ya!$@n^SI}3icY`X$ z*wfx8^Vva_N?sgFZB>><-1lQ>KNn^r;irZg%~>Iem8a(_K|gcD6XqJv4LYGx5H^pC zhb~vsw0pGl9~*^c_APb}h1IHWW?Va(k3y5hQFE5>1U&_?q8~=s;wiR? zG$i-nUM6Du@uAGj3E6!G?K#=w6Vx}r$JF65oX_rYVV?lnf83`|vKyt5J&iIwbO0SB zvGAh9!8|_9=<{DfMLbTgA`&D%jD8YjRCfhwbVQ0NO;4!Ah13#sesAS*1QqJ0vG`6| zt+%J(EW!-WJ;06iP9M{Hfcb#iLB;izr-20~xY5iuSA=~)znpb0*!O`)rPDQM4J-*^ zEtfgVOSu4W(pnameB(^=$SXhVSL%FSL+*hz%z%|rYQGyreIZpnvn|!Z9VMi|q&|xO zxO3@#`i)dUOk`Fk&X^5f$4?;p$2pB^4{HE=uQ<)@OUTLS4Q>n>iar==MJl8VVxOi5 zrxwv^lO5I+?LH#o4^jRdyvins6%_3-V1)bE7FVwPUJbzm!i3`D`UcC zNt4Za_~VAxTLgMv@Ljt56dbOu+G`r_YF=Y{S1j^-D5P?l!<{Ou%Ps1A+ zXMOA7Q?QMv9+uf|{QgB=I?L7T`Ou!wJBQ>Q_-BD4k-n7B1tO-R)WHzKL_)kGi8|?( z3bl&Wn5>J-a=ewFFV_Gzp}G(I`^KNBl!E;;JRU0vCds8@PGxWdtX!O>m3+8f0cqg2 zd9FI7n)HQ+2YP(XXw*~pN&44gKbG206g{+$eRRT1&lwuOY!vi(9(xc5bZ)~B5C@v7 zgpExTJm#tI*wul4i*MTIls}`q$~J(y@?r2;lJmyqPH}Gz;F)xacbrRef!U$RIJ2r@ ztF=Gb_ZAat&}OTg47COy*!8#;1z_zLKP2*?Ig|NMK(y z<~1VptKhxsX00FAMK92i-vpmMNdIru7k@)B)0^b&b>FDA-9AAZz`KQKzSYjILe9CZ z5a-~j!fnm)^ep$RaKeWFzi2QeMLkCb1MctQ0S#z4;`2z^rHioURI_n!z>MhN&1y1q z)Jl=*z^JuTc2BKY`5n>RA1={_7RnDXwq29OOblz7GEEE_<6&)^$%x?{)(Zn zoyJznknGx!Nlc1!6X0u(a^2JgFe5Pk9+HWe(cW5eLUJv1+1C2K#&5@nAOgbs!lP@^ zTVc&xU zj(N#U3Io_6ve-(^p#|PXSu=TAL+NEWa9nV7JF*TM_#%mqHBl3(WS|*JjT|NTiy-=f z^fiM+=sI-%3pBhq;w(M82Pe^-3p#Haq?=l2{Ez|o{$SST3Z=Kx|aknv#rC?s-UOh;v{}G*1 zgmW=SDrT1;`*%>PlDT4=&RWCOgmSslr*}udR>L~&E{@V4Eh29yyiy~PQ78V5g#NQc zp%;(j>wu>b7?<%n>%y+} z8Q&C$v|Rbl+7Q7z@Gr8SK}=A&aozhEoor_3`!+0hNM0d=EKp948g^xhQOUY+8mMcO z=%J-05OggRsxAPPI?xqk5=10~xHPgVp34jeWqa6Km+L_I33q>qFqmFlb7qev$f3}N zOH$!|_nXiuc_{l_jEAaSO6o=oi>q_@1zEyj^6`;`9+g)uo5VFt=Jt}8lah>bv2!Yu zbFHwf38yAbRDxIAmH#4BhMaM&U1EEO<{g3CkSrU?>He-p1uM~y zR;chJJ1RTkwlrFAz&loyiDNhr`A5G%UBN7YnK&(TuR=BI)F4YNT%kqRPG2l=JyiKe z9YJr!!0yP|T$wW_g$*9$kNW|}opQd6NK|+8WuB0I`~BXfr6Q^dTJ25fAl?o!#=$b-ml-wDkPLd zJt6z|yui2%P1~%XXBckQAw1=Z3UZfVNfPGC3-A+ykzWRK?~yX~F#)*_KqSX~Yil}+ z^bOgtH|MvulR{#?(;syUeF~O9T4(==7a1S(dn;hGTq)aj*nRMuX8O4 zhcxmYe5PmjkC_c;nD}u6^ginZyIdEGpYqK@89EIOZ{(&GXs%S`Z$}e+rR)z_mr6w7 zhmasF$a|5GGgq}J=}uQqcIr{dhiO%uzHgk1@Bd@!EZd@BqqRLjH#2lO#L(R>F?05iDa@4Z{VA zab%2v?~0l5Wb_!pB9y|~sp^F6cD_Y-TFPV8e#gY=ApXCnYL2Jr*6V+#TmG52tn3#x z%!6loN@`dN(e_SyHLF_8Wdmv{OAbV-Mm{IP@Az2FbP3|^qH9sSRI2qCS$+Kp+7H|pLSlOlYR8#6U95&(vMcuaV7IKVy(V1^r$mJpeil>tfy z8DruC5{sTD+_<8clDx{?s)(p2d;GQ{BK+*gEC9H-H>MAq7nYaS8~L`f7W5Wp0t{&e zXT>GV^<)*zRTP)J!hJOn*R#D$_>n+%=@@@!>*+CU)Fko@@5UP@4HCH8m?>jO~z9KxcqY=Jt`{t>rd=K^g3K- z*7`<;yLd!vi>0i)F@03nhXq(1tAdYg3gy{H|Jo*I7i<4PFueQV_+J{XanjC^zh=~S zA=jKR|HT((WTSj2JSyLgVoX$VlIitNHI7Vj5T!}XE_ zfSi^U@04F9n6k%?nZ96UDXzYJW=eOi-tx=VQUm()%+Jk3VB4u72J zVLV7~b$r?kaGjcDaMX;{_)9i5(DNSkjKkHqX$jmWSaRZk7Y}kf zqHM(qAK4a`D3i^K)qI^v8Ih0p{#IiMorkD)5*+B^Ufqc`% z+uJ!FEs?1LnT(~z9Od=3gG%6>T`wKH?TbLHaE+U2LE@$fGf)ulp}SJ@EiC8Mdie{P zuCI$)U#ZA;`mv4_`qnGjU)R*=lz%GxlMc64_${NX240bwtd2XVCXdTRY!nYYdv?eR zxE!RGP?ixqPlyeNZv>F7#K6QLN|%sw%|0|R@3ySFS&}CDBr)TaJi^JB?HW@DmXOm6 z^AFZe)-<*eIh2bh`lwp+R1GhRO;!`_&tK>}FSn8Xd9ySKVA%=cN=)13Y=Zu8H zC3__>??fA(coIb>%!Lx0m)7&uT}9kySw4DZb{FG&T21QyS1y7nTS3$v4sA2c7)?C^fl#5YDu7<-j3?3$d{@_zZMD&%$z!NHLiKB zgE5Mdbggc4jjT&hI^RV{Vtd4hT%QdXYvOf6_{vJad*1!_gd7&t+M91`v+zNqo^3Hd1q zM=e>v+SD`PV1lOa@(AG<#ln@Vc@joO`U^>s@~nJ3=G@=V0hF%br4|m^uTZdefPF_h zFpBB!aQ~ZJK`IAzec-p{($72JnKB;bK|uUt`lAsCfrKPQ$Mq<3CiEd4=)Zd9E9%`& z&G@KnCGY23s{{tH{5-#(Oa`v%7Kl4}Udy}=4#7E9D-d~F=k1~+hrar1ogl6&rZcy4 z(&A4`{rY`iGAA)^xlNR6=3Wya(`pmB<3J9v?B69Gw>7n6bAGHml*6+kc9pEW#3D#O z@Oi0ijWfZ`%nM;`Tm=`in67npw~-gj->@uU24yC=OU{ktz2J;Xnxm z)AHYJ&WtPk8am}1S&mF@x3G_hX*~rdtt$4Qdf@^upBFgY;sj*=)eGeF8 z@`5&{sKaqtuOg$)9`!yQ)lZCzu5+^-%vk!u$olK{R9TNBh5y$`biGNoSj{o9q;JR+ zVfIpka`y2L?Vb)K>$_aptAZ^I@ucs2LV`Aa>;_G<(b`CKNd%0XIjWE1xUQ#^b79Kv zpmDN7iCxZ7T_vpyRPaTZi*%Mk`FMIaa zHOu<<%v4#STvJz`@!Ll_N6ydo$`lXYNLKwxy=00P?}jls8EGM54LFVLgubcxUs-vZ zcC%=*SkyezR9)pA$||!iBFOEDmp-94f6mM_N~Qd_JX=a|ZSh51)&R+SJj?yhi_C|i zX5l#rROfTtH{o_+Ykp~3$<9uHHny53?A`lCneg_!&gPSWD$$Q0FZ^XM()Itv*#eCD zRhmBj*0g(7zmXAwBh?%7H9k;m6~~<~5Sw|sg!d=qGsD|tfOB%}5M`>26ZY`)vz2Dk z)QX$i(;$5J16@pOTbJQ#knmQr->N-HisXGbW&~8zv=(Lh$H7RBYpsf??=@41LJNjL zjR`IFSxAW1?0lH(BZ~)9f&TZJk;pKLmZ-AVS%8)B$sbdb1U`7L6_}09X{su?+}TNI zr?T7$Qk>+EJ1R#$!yeqpLc_hlfo=AdUujK2kH+t-*Kq}P8t~MdF`~rU14mwMMRlZ& zZIE#jubwH=1vUCe;5=sObDmXyW!g`L)Cawt@7pFMVG#m_I2)ZQH>zm+?EJ|&f$L<9 zT}6>5&1=KE=?T?A^IgZ_pJrlWrd-Q1_&O1T}NSPc0UF zeLoqKvlUJzpd(WZK;JhU z>2+rq`ey|Mrd77&jo2xzA1z!7HB`hE(s7jl;`I)g@nn+S<*wkBINHx&C@8EBv{%K6 z7|7r8RY#&?2TAd@sx8&`L_orw6S^x*#GzTg+~({D8! zG-@bN_EDD`nLW|Xl*`B?3ip0fpxwkmI+*p;5^nv9KdeIx+)&MSSMReIk7os-8##iv z-zv#5(hmW(aZWUyqQjECtvXkz58ko;cP;YW5MM2dnxxx5%!YPbK-MpY@v7r0*31SY+3b!EK*$nPIjiki zuR0AgLYj_O!*4p!b?=B?ZDdePkT0&&gK*a_3?0t3A0z=LLhK0 z*?En8!dcI8zhRLN3JLxi^;f2ZH&JF>HWC*+wMxSQPq%3dWEPE07G^O34@U0-l(7I> zBc`-uC|xG{qwkg#SM_Zo4JGHVgziyUFzOtpWUXUT!j(-Xc->C5K z5REYflHcAs`z*M+_T1<4TDwIuuWRt9ZA@;ic)h{lr^`GYKNw_nV;Y#f6@NTh$$h8p z5n-69k>)20vH#8r?_zitM96QXD-c6AbB999b9Vdl_?>w>2TFccLhwAe&4AqV44s?x zxl|BV7qK>VaK2!Uh+S-dMU<#(q2@Qm{DUNpy8?lTLTLnZ0fn*+WLzdo+j(y z$UjpZsQ@&#a0y__wD!#%K(YwQV8oEF8f(f2YCngNh*D~2*YX(1+kSA8im&Fmg}aUP z3x{$LU@}SSe=0pT(DCin9K(%!IHGh+qI^QpmDhR1W5{m2DZN>^9Qt*=jywo+>Fbz{ zhrn8%2cF~0X77VTpDW9A!ELe=#J_#A3RK`rSV@=>ROrYn6*5E;_&hRBA?YQkBEwYk zWKn`L(+ZiSvIl4qfU%b6w(p1DXcSaq_h)&AJ$zEYV&q1$`=WHK!F1_6U8ooyDl5uO zB#O8%*iu2X^_uz`+uK$I0L;aBAICggWF^eb1Nf8@w@u~-hw=+o>BajQs_G=(xlP2o zeqXBqQ?jv7R^8~8{*nM%DJ6|2D$_upJ+J2;RWsh1CIpk`#pxSGu)t0YQ6h2`r)omS zr_3J@AqvYH%=M!G)KXkFf?Vx$eM-bMq5iJ|%_xi-6>r>IqBN!TtOE6!%~tTy9LCoW z7V;KV*%M}rO9~xTx|Z!|KNrm(_w+`Ef$<4M`kQL{&fHoej{(m27In6gRx|S5U}*yf z3TpfE@=;2dkD25$5xOZ}RxE<4t|r;bV%saNctw??u+FckX%X#}bs0I4AF;|-$*0T8 zJej@CK32yQG?Djt5RJLGFt%w)5NnO-J5 z(`XW-BRz*MkW9Al?<0B7z&hVkB1LR9GC|}RVU~7;4e!UN!Iq@ zpdb$<_7^!Z8QPw2Og#p2Jto%n@}b=UNI)ncwX#q#g%HMRRYjsBhpmNH7Gd?Ux+2sW z!9dO739qt*b^r-TdUaiUyC(pmw!ONoB)Ox#+D8DFIXnU+&|V5k`Q$u@{GY2a^Z%c# z{}%zDQ9I3UYG}LIr`a^w5)Ws(FaBJYk#Nkfw9Kt-u_{t?k5j^E^OKxP$=17C>SqYi zc(<3eFdeq-=n^}^wZG!U9Gz8U^1ggQwg3g8ZV2k?7Lr;p)77Gbr%6WOiq9&cNFKpP zlcG)KiLZ#CYk>;@13;J{KzT(8s0dtA3ihomF9X+BgFppE^|g{6C6Lm>;<6Vn3tqHV z6*rF;*8?C$C0>ez`M5(b-nUl1tS+p3AHOm7YPjsx;7T`SWBu&oY2VCH!Pv`JGe<9q zo#${D{8t}}Dw=oyIlKJ%Ovz6p;MMjMK5sBFBBs-brv5BE3wW*D!M-8|XashvzkT$h z_llQWFZ25x^5b{D9p#j{|FDR)k@e27ZMFLKiX)Fnr+G!xsQSSOHkiwxElctID|K_? ziR8o1REp71{l8&vun|vdzvaiY>+dDKyWOEU;&xd+pUo72%y1IFgVudR&EAxm5RvxE zj~E0MYJVSE63oj!lU3AEy2uq+pw^BaySmL=mqWaD97RR5QzoS@`hIppYJ*2k5P5uC0o--#l1)A*BCt& z(Z8JvN(5F&PdDLg;Y@Sfuag?^85-Q4G{@Th@wCwuBJo7F@$G#mZ?WJ&sGqh)7czV$ zeY%v#s$6f2HU|TuWn9LO)K)fqJzmIqJ}JH+4E=e06#Et@frOpB7hI35M^)`oD3RtX zh8|q?t)~FQv#1lQNQHM|FS9q{GQuO+_Qp_YL^k3pM_n>qYWz$IJAjI{%woc?w-Qy1 z3u8?!nXxrae5G{0$XbXyK3nFj95ce=FSkY`r>%!kUw0!u$Xs1w@&mspkshiqR{i4M zB+>HWmK?@#TDWhY!q|}#14nN(W`-M3?$yf=O#<{lo~fOvkj*2Aq4K|C2lu8Ui-$L3Zf)mKbs zuF`|$qoC{qQXI?4j@1&a^^s70RT7VDx+JXo?VY?oF7>eZv!++g~N$o1n#@m$a&0{iYXrg`|w;|r!$Rm-Vj8LD<0JQE`> zSxPtPyvDtUt61uO+&B%oMU;M)Byv|_sX>#2`u95Xhd@cy3I~}zvyYa4vN(irZ*ga( zo{9E@OLMzhl+9jhTg!{~#%j24P4-%vl$dv2-W}Hl_VS6~O028n{l3pMv+rV}h=bSb z#VU!fCamc`1Cb0_V`i!eDC;eCZucEH_L37iIWBqWu6SXk+cl{Wd*UyyQ$b-0j3nHD z=e7aUU{?LVtY|AC8}x^h0&kfUaspL+tgxl(oQqo4A%z6tuGrT@&B}~2H)=>oF5SeI z8h_c`bdcm^s@~5k9F=4+;B!~*OU)M9*NRHgZAUyWAE!B3?wL|^Zcht75`tr9sVrq@ zjou_BaYL1g%1D&fi{4E9XMN=*2Of(Ry}BYyeJPb|rOqZz;x?$+IUxja-c7j z*K!fO#lA*@{SwBu0s~mchNa*6(W$2`wSbx>3_ekfw9FpjO{c4V{lp~)v{^n8ly8&f zbM4VB%NSu#MW?x0R<2dG&MHuR#K2^j^|HR^)svRkceg4@ipJQIi$>=mBo;w*kV3fR zN2T;21o}Ae6IuxGFSceKq}+SwU44cBLCC{rJ$|=`em(N1{bGvp9Lzvqk)MNnjYA(F zbBW#q(MaRY7*8IvBtAfWV?3~&C-eF+E8<}OQ5{ESOzxy-64ibc5ji)@qk7Y!PIjGL zHM1p9SeO=ugF!u0Gy|Xm)$7psaeIBT#jyVF0xM$wag{L^ivuPV@V)3oiZ+dh@jC+V>K6*YoPVgm zJ zyqdmKca7qEZa95#*;hJZKf@l14f=%Z>X4;#jc;;8edKU*{9@7mp#P`;Y$vNk;;OYk zMCE0ryal9}v<7M+h`GRKFFh;I>>*V8q6aMcI znfz$gp%1xgLq}tAwGOoskoTgoRvcIDR!)1nP6YU;e3Cc1sEfU=%bFJ0H7Y>M;fR#G zSKMT78S(MX;+86m)lYKW;=E(lk3@1uu6h>*83R4@sLwseM8^USx!0+<*cehg=!)e4 za`Mq#dE#_h^FMCNA*A_hGmFJ;e^|oxN8<+Vz0+XxBw`;7We={|p*uE}$Gcr_?{L%`mmDO}i53g9dW*=9x(){(0dM7_@Zs&#S6n(RRtU7SBqsB(l zaBdfc0ENk&C=Cxd^QpGI2}Ws3UE+Fe-A)7{e%p~dLr8U|8?esjB55!w8K+R;z`&Mm zOU<*0G5crlsBz!?PGFz5W#P|lQ(56s2p^QhTt#qH%eLh!7e7wB5dFsr=dk+mvgbIm zp#VIbs1S137sYd-`l!ZdusRcSSi36xmn(4xZ#rvq9u;foui=oo$S=AOJ0R0kclR~= z-#65UIxrJXm9{X!qk<)TAX?t?eTQ&{0?|sL2ax+ zfTEv`g1>%pM3_lEa6gYbX!ndn@A!_E10smh(fL zQK{krbPlAdv8(vo;wkE zS3DK)8}Vj(B_1jYrQ?qt@(16WYHCnGQjCDPnP9~Io#2_=bTAm zgh*oo&!F2*r^!*~nw7L#-JOEq#G3(BMYsY{X~z~YW5LU^qcd!Zr|{N}AA8Qo4iKEw z>O3Nv&5`hkj|+U#W3i)f92`F6(4xTs=VC7Sc|w2LJnvOqzYDvE-xQlFMIvut=oQX_%LFLkjEIYMVQp2h5Jj7NwYX= z|M@%KIudBB8gl6&7oxRVvB+hB0L3MHYC&8tFAl=fh>z!?trwR3hdhIc{<2fPT5-0(3;37(7EhU)I*;L!ZilJF0B;XES4n?Zd8d!=R&2*KN^nQsO}C%S?WqaLiuN)YQ;AK)-Z<;; zb`Hr~ z;<9C~w~6E`P>Evu1f?4VT4?Cx0jc4Iz#SgH<$4fFs(|9PDP&B3r_M*bPboYHSY&78 z+sp7zE!gBt3MH2RQbAnp1W$;xM%YL)kP#pYfz8@NQYVA3>#A%UsGWEWTuSh$OAyS4 zp_ajyLJtW{&2rs#flRMf^MC2-w&l?9=k@gzJ+rC85J6($=mGSrFeL%~rXyfKd>j>P zZsifMMOMEl63fpF$J3Qc^2*{F5SxUvUyMX4+Z#h=6yW&_3lIkolf%uHAHqOfN4ooGi=**o%e#+ad;g%56vgZ*F_3 z&aTWKV!(Crm9`K@DH?Bm!J<-J&=wkTxC~W^|Ywiy-7=J8A1~0G?Hl3zg5Q4}Uae8Km7M6Exj4f0w zk}v|7FfRuu8$S~&n;@QAQC1Qe9a%$=mzUT?7>$kJL?G)C0{Wks-XAbDJc!#59`pxm z@AEm6$QdMVDfot@r*)ZOk;MqLI3t#48e&di!z-m1v5xWiE zq(-VEm4AEGfFMlSf4E?fjONSU`@;7=)MO4lru?xhnk|^hM0;XU=K)Iow~5e3+z8dbMw&%%CHIf|*89Y3wft~U9P zgbLBT37ag$Ze8YmfKV=j-lVHG_5Na#vpQWG)T}6R1~=-|YR9Vw(NkBG13z?s{y8x1 zjeC<*`dbH?UHu%>n)LFEj<|aUCXIWm8FNd(^@mZsnGb-8(!O?h;iJcBQl6I2%t@aX zaz04eFnX&vcg5|E&3c9B8w>Fj$$RgU46fe`V7f3*#yF%0i3ngp(AeHE%B^Y}p>K*y z!A_#)uur8O>RhdRAWVtXzs%Y8iIO<-g7hBAtBg5gtTqimV+CwJtmg2O{Yse9v9U?c z20u4hCGc{|j@9OMpJyDUGu{HKphBpYFvKQC^H$3f^T8(-iv-vo5ii4)XoJ)Wpf+M` zm_k}{3+$x1Q25U*MM4FbmmC6G9f%aoCtas;)y)8t#pG=ZUV6Kd(x94jUo>gA{MV~A z%T`ASnN^Imw4>IT__G2p9s%}h7WB}wK=R&IEi+|dDjhRCYMjdWwLo2%M$S?dhfU~Z zM9Oh!m0m}c67i)L+v7`GpwH@zF#}*$l4Kk$hCx5tlHMce8jfrtU<@2J+6eDgTQ9pW zQY^J=YBY+I*+vU4LBb_To{}G<`n^Vrw;TDMk~~RMNy5R7E^1q_^;QpZis1u(6_U9l z9UoX4h0sw=4@F1nn_FG*Px5U()kh{{&loKq{oUpu!r>e>QHGxsUE+9ABLnP&Vo?l% zG6mm}58sDhzJE4zbG?**s&1Rmvu(?id9aP6J8)xo*Hq0HCxB?U|SUBXrc_mTE&YWZMOe>Vkx^OMo`)IA{)kp>qMKZ0WwrNLyR z2Y|f_b{=rUL4hnAiR!qrRizhzEEUD%`~AdaEFRo)Jz(v$Y35P4t6BD;>Qel<#;aei zzHP=IOP(H_ZYxMe+ux=F0rJD-7jdSGJsg=u9;fT<{2##fdWA{}KckHNqBEbTfTVd3 zv$(nai2RzE^3STOC4+;=L6kU@2I;t_zmG}1E6AXwT6X?#I1R>2P-VVw2TEILp7;y- z*7CFiKbmQVMz1Y~_wz}psl(h)(!K;b>Ihc}RMu;0HGxFfL4HIu9G4C_r;;@qF*=hq zMo>h%ZI^D+v1`GBixH)vr6FhN$1E80gE$Q1IOW~axIWEN!Y8MZ4CE46M&X-!woQxY<3)uzuvUrK3UUHHuz5QahU$w5F zWy10W1SO)!Sgmf$I4D*fG4u%)>%7?>gh?|pC4(`FjKu=x4;%piF-4r_wcVR)zArh! zgF02v30Uv~?pCKiCumt|f68Q~xrR5<#&AAoE|o7zxFI$Nk_pi$z|v8q|0oevNfqU+ zJGN%K3(d4s?Wn^nrsG3W3cZf5R*QKq=Pu2GtAkI|Zag$!I9?U81#S~y>q(OYP#f`qDaCc92uqu?w?#1p+&5v;ZZH-3zA?RNNkt<7`DPDDu^o zT;`Vc6wc^z=s5`v_LVp>qKGb+%)gA>iq{1b2Ma`j$&Z$ED^{OPHjq00ILBhr-n8@a zxZo^#vgCzf@tTsr1bfuXHLoy-u)DN#Pf>^#$n(Y6f?5&T9>KQ`ZwkCdXr5yf?Uji( zo7V@Hyxu<92j$ew-_?(dsdT&sCMSi5IjP5Q(A8pm+%!fkt&)=F%SDSK0bqef!GRyE zS?drL|<@G^QNCA+Cg?r8<1m=}F4UwolXHy$>!cfW*kfc3bQDs z)Ng@64oepG6R{m-rmmH+II;!`8S%;gmBU(sPd;x*IsUGpauOWBBzEaO;wZdJzIh-VX2TpdtAKOmFAQ(j2$c|qF z6D=#HVv=X5)_-Fe^rS)Mh%vH=%+oKOXH99N1?Po$){De3RecPWV2xc;{k!5u#r+Qo ztIK6JU9TT$m@(U3r=;_5aUu^X2hc=9Hdw-|OzZaUgNk&3{4mv3O-f3_$87&mh+$HU zi9;j3cMsWn(twvr^!n=va2%gATt=BR3>%1LI|e2DF5HbR#O%W>sAo1MZ(fzOj4*|`JXnWd88j8-cc$7moQ1FtW4+0ZtsOOsvHrrghok0lX< z;!)lw$6>UJ=}w<1FF!dfjwv=rHLo-B;V$8E#;7Jot?7u^n850=;q=2fmHy&0rb90 z6=lmbk3s$A(BF94{32e?qRZ~XVG!3(mLP1#$x$EW12XJEM(k<;aD?hJhOSpXL!Q3& z>h}<;WUQq+y;kv{h6blQ0Be;X9U#{UH;I6g8oA4gY=}#ya8Bu)@__bOW=}nG8T=%m zzDusyjMRoDIQ*nt5f>!<5i>a;b;2h7Q&7tngB%B&9Pc~=x6UvJhjd985Zxj12Ps59 zm_TS0 K0=pQ=?AjRg-%3Zfn!!%53ph7;>P-Nt(kJ0BY5Vf?>BhSvGb$c;z91wWN~Xv z#cLQLc?_mOg8VnMg1;A@=Ag%IazIR={9=;=4u-dpsDs!l0YS2GK2>@ziN#x(A%O0Gf@W{xx4xE*`|*Q!FVrhUc_1NKBV)Gm0{E>_jzRrwhXa3TWAv{cwjH>x7A zagraXvJcCg){XdEEU~*p<9wcgrFz3l@8E1^X92gxAA`+P2qn!(A=?&juhnQQJR@=1u}G5|2G;dR0i3#PZ(97%H3!YA%__D6-fe3~ zE_FA!2{V-3BY5OKq8`TzpX4Co2Sx|K>RZl|ji+c;Rv}ORB6G;Ktx7XM9oYD zn^%+pN;s!L@z??3`inQBC+@qt?}fLK!I^7LwmTpCQRSsI&xSBYhd({PV(L+B5ER#A zq#<<7Q~_AfPD-xnh#iR5OIjpr#6w|ALES}?6F%iM-82@x70c=Lg{#{qVAT2%okwvE z^qJQ9%!sr;+dw3vkb1%C2}+Uhn!KPhw`fYJ9el7XN5D>%lvQs;Vlb>U#AmFJ+MEk=Wf^l_5vTbAjX*;G=?4%wyyL^Z$#BtRMCEkZObpUNCTWXI$U5p z=|g?NEhHnXp(?eoVehEDSTc8E$PW%ea$D$_Ug{i8;+bUSr`gJQM0*S@^^HCylGRrP zCtEy$?NULk2;xB~@l|f4P?UYd#wnRA z=Sr%erwmSlM4FTG1nGHK`f^8NRBbH5Zn4@N8Qsu~EXsJHy`ic1Xc7A zj=7WfUatd7qYBII3Ulmm;_{0?SQYjSfk3yEN!%+UCpj%gFWffR@+M10oIYH+3V3CW z5obCCe{!Zlm_&W062H}Bq2Ho?>3u|^wlI5*bdhvrn{l+Zj=NVUz2y=|)jQxSkXMf>E zNje`@GMH94(%3o<`NQcFc{Bl?c8b99m@ibUi;PO4zfBoNipkg~3oow-Nv_wbQB{As zUey_Aeq3$3^CxP4xYi2QwyoJdBl)60h0 z5b2Aj`lCgHp7?YUn=f zh$F09IU`#GMB*P>Ia(pP4CPk-=fN3mY}J={A>gVKQ6X>#e1rs)Gp`yG(m8xkz*N0c z3#d$v-}3xCf_(1;Dej&R7WFsUvSe?YSjQ|8pwRYX{D+b4Vz#eeVYJmdh1U8{1fDM` z)+|bq`a8eCEF3?0T~EZ2Kyh6vZ{5z==8yj-(tm78aWyuhv$k6L3*gi!1aFzS5R4~) zGlH3=1V>uH!VUoV2JN?*4p^*Dbh$Su-ip?s8ewktPvU$>^VdWoiO;j(E;_dg6xj!{ zU_q?ffQ8WqQlpCa`hDFW({PLDbt-_sDx?vOo`B%`qL;YrCRrWsDcgp|x?!DF#v9-zgK4J3-DcUt`ct{IumGYA{MHBajw6uOBo_E)lczm`(v4Gj9)`@;eYj& zTM8}svU#Iq{t|J%6(DtzgJpg&KNb*YKvlO-fo>PZ&4u$NH}fCG>#eVj`ltAivNe5i zU{;IvMpdN@(FoOLvbC>|{`(nr+hHnBSD_kQg|}@-bYWE1QTD(YTbETTzid@z;LdzU z2Dx~I-2_Jx*Fr|ky+nWju9%>oQM$TF*T`efJOhsAdkwM#me=kvk~(+?`gV$ao`EK! zJhY2ChGG%-^f4~4o!Emg0HkG$E5uD=nIxN*$hT7Mdfc*9Mo;3 z1?R)63{!5-%}z%fc?FGdV8K0 zydbp?FDMR3o=Mn?yce?Zu2WvNW<7m$IF+Dxt2mo~w){Sg$}5WD&XJah%Ev6DExq1J zVLrYCX#+}f9EyT+H4(5?J{~4H)+y!g=Hr{-??g9AGqv{#e5IHCT)ZzC3pX`n7yome z3?RxP?h2o!iI4qz3oW9t~$f8=dR%K%FPc3m|51*zf`+Y z2kVaMuYGd0{+^blnq=!*tjxajdRMM>{mi+?HZ2n#t$4|C$s&Xc8~1WH{?n{iKg-yM zD4%Dn>7cHh#g$c9z{iq>s&n{o=ma%?_lvJj(iCYL*7H7xsjn7PEV|Uz3EWf<+MpL$ zg3b1Ba2D583>MK6M~94Q~umf5N=Glj=^$|ucHct5%*o<)!hkd8Zx89>`CNdw)V zKVj@CF1)^L+76ekQxKrDp_N4&w;czs-3Yuh+DlIK4sP=TZy*DH$R2Qp*!T{?(tD%y z-QSu#BVprH>s_ZRH~XAkD^^T}#0S2}iY2n2Wn%@VabvtiJli3nU41r(I8xcAI4`76 zxPJ&(cWu=k`oT^Zg5~ZR-m}nO{0VFqZ_ZE|OgVi+(8|`%Kjn`rUugX%Bp*+T=lR>1 zDhw&P7BYM)F1FZ=|#QIc0mR&Kv!` zGxCk#nLmngc447hgGwJ&n1E}4{C6TBM@NiU`V2X4$ZAVt3xCnhZ+i zqUG{TlzA<>eex?i;`<#CiD>w-?KJ-1lMVE*K~IZCaG`5K-Q|II6M$$h3IXw9uEid) z`8ecH;$Hmxkk#Ne+ebt)*sMBo^5eglR}%plInk@9sF3AX)fN)p2EgI3M0V_=R!NsH zGaSnu4IFg|<kfb&qyvCe<;7 z5$P_2QZv1X3&xr2w5}VxViT0-7-0N{wPE)|zXB6XhU4};9qHWoUs5{y6qef*5x<{T zCWxQM#J5$S|lCzhcB6-ZNE21WkLJ9(cTLQD}g>Z7T=B#Z~cqmsO{p1I?)0K z7a~kyEWQN!EpE@L?kOTLu++9__{&3oA4!K}^0H9cIP2(mCJ|w+;0_@nm4kClDOiyfMHlALc&$nYxIZFLD*FLQJyie$Zuw_c}t^dpJNfqG-Kfv{?4Ge=n>wmTcYFST3ctv_VU+YCR z#g&;l*tww6uM*7yjcq4S%q*jm+G>cfAF`ia$fzr_sxo?wtdR%#g!U&Ye^8MB=Vhy> ztYM)md!B`Hg~hD{l^H))Dn?Ot-g6ni)4oRozQV%C`PH-Zm=X;bqDI|CvEaDe1gWrMorcQ2rgi`Y_9u@aJG!=e-hE%> zzkYwqwQ$h^<57L#nVbNE72z8;tK1wTS%8o+n%7v@QXC!|b&~!BxZ~<`D`QD+pE=Wm zE!NIB8sk{wm5J#El&Wi>EX~|HhM7?(AoeCb)7uy#a;m!Ma9|$y>pWwESTVIg{kPqk zisMOZ$LlwQ2vfHX$eT=Av~mmpBE3c0G?WXWg`GclNQINM;v75=Oe4J_ZL>-tF zsc7OUv_a;@5MtgQM$j1X;yZ3aMYc*-85xX2J@+pQRJyP)Y#LnWJ)$l6*NxgV(#qcf8ki!9j!o!jJxhaYjaGdJTQtqpk+MIUJQHk-#!SYB z+Fi#c%Z2#8eozP0Ayk3p!v<{QgYLaJ(dbha`aD^7Bbi;yN3l#nxV}9P_#o`dvCULH zR2`H;BJXy7nA#62Xj6?SV%HS=CGy)>+-uv(lIcJPd3-L%DX3} zL{%zq@7QR)!70T_(y_g)*0iZ??aO&lWcN-$vA4^lORwOQSYb}d^Do^+jr`%DaiO0M ztSs@*Mwu0}bCFynwM3h2*&F_3HC!XM(g;fWjCf^p^2|wof0sjP9w*IKAdP`!E222+ z<)&6#0eYe4$>AJ`;mD<7VsO6djsAaBods7LY`A5EySuwP!8J%A!6O8BcXw%UrzAK9 zihFUVf@@20t>99qP@qux%I%t2v(}w|@jma_=j`hk=Yzls+9aRinP)66*+AU@;nGMK zy87qB1=?1omz&M1O{L-@hAzn{msVDu1}FK%Y*eo|6IjiShl%1oJ_!Z9Jz@d*vX>4UZ2l8!v#jLb~v5Bo9oRa2R`_)1dqCR$I zStjxnobs`Zo#0~WJeE0#{mmGQ**eysc37(iMs7f(rNcXwSLGu^%13~^z)kkNitMv1 zMPC)!2sil zp}Z_Ru_C7=xs)NbwgK}bt)Z>1uA{=4pwF;>kicS)Fqj~0Xl%TXVvC``-!9u6N#l{57S=Yk^PB z45%s@O~At;76t%#22=YeMfoEG(dg7&LP=jGz&rJvy9aXKUcI2|(JXEeYkK0UYVA~3 zE6G0*Q=?OfOaZjML(c@J1-JZv-9-7>m=tU(RZe))SD5Am)0*7~uGJv@#KJ^l^?{iS zF*+&UY{R!0vr39FH{@CHLouD}?<@JvuE?LE=!pT+PMD1Td9KEGuf*kf=(Cf_>~7rgO}%~j4?9N{dBbY3 z{;-&#D!j_R1L`8`05{9JOo4$MOKEkx(yr3}ya)cCxc(Byk8)x3;Jq;vmYh56meVWx zeb}ZC9s{0*Zf_3qLxd$kq?4D|SSYs#VfS^3HJ)!!A=0KK2}740Dym)5uRb`8K;_v?DLdET>7Jz_hO#*k z7;85g9U7S=i9mZ(+^w}rOx$>CVMKt)PfO?~OS7jPa@~B?0hDXL5;<%p&nNnRuY}&_ z#rg4R=9>8yOHu=k`6%v7nr({5;7WSzgW|X~zdjg9NR-H~z+pk}=Vow=ta#4ZZ1EV+ zU;|d{P*M8X?&3ywsVJHSzs2w*k)PQ~@yD+-?}195@eTe zH$qX%d_1|XQ}s_X86`TmOXI$mt=1NOVq$}4HJ{c2`t6D>qG91jZ4!i`ZmY%WKdr1$ zbub7@d*Lc$#eulVn=8_>k9_xK=2bu94arOXYb|XC`Hi)ZdLb{nH3lycXrH65Z6mvo zdvJQU(`S^FQuhP;>}}l+Ga6?2IQlRc%2h~L<-??M`$P$LEts_FmL@0C zeLA?4#zSCV*z3?MvT4>2v(PPl2)dJ>{u~L!hTZggMnB{D&_7Ff3zqy51mY0$1w0+2 zp=)GS)}P8Rwc({pK?N)}{6@Wl*ck)!7kNDl*-e-O3A**Mo@8|&N|DW_Bcjny4N3mq zVs1+xqC+j&WlCx^1)c-57=Lw3u0G$OIXqTkuOBa0K0r>0ghaO? z#P7)91?XbY0O?W1$g5q4s`aODT;0UENYb3+i!02oT&azQa*^)Xm%@Pt`gOaEisb9; zKHTKcN$(v6_oOzmGGC$B=lOx+=%zFpBE+>w2_4~S+ufp%FVoD6UBJv75Zm52;qDD54@S%Xa4n;$#>wnO7gF;gH9wyj#GHLs{9ZTCr8 z@DJU4q*5~h4wd<)Cprue^|UN!*5&V&Ewmu1Wk&9E^y`ap^036xuQ#80pOftQH!zLj ztT}s*^VX)~rcNkCKZ|u!S*ZKQl)_u^O}(8avELCayrg`I&=;}47e#4yrh`!xJ>?y- zwJ#nUi;MiMnx}km40#|o=KCAO=R4jd^V>7cOSGGl*9z4_{9+~aDGibQxzg}po&kS; zflbGkKUjhw#WtX}4gPFu=+oB^Lx;rA4-BF_bjX)6eYCUJB0ey674uA@+g)4&Iu zQED=^HLI<@au!(CLslw`N2LQNrEN;I(&$%N@J&BIHpgG?ThshXcA^ePlplzJl)pWd zI&*8Vo|$dSMZ0rQ^x(drjQbnE4n$$bo(Gt1dczJo8meuTYhzw)1xXd;I;~Qe&dOxQZ>6HvxR5@oQ}t)P}|_rAYD8>Sdp4P&}`t zZj6*rtC20mm(Oi``P~nplqXJU#ORe4g%QvqLifZ;$~cfxLToLFMt(ZQ@J~FEC`PT1l->&Y;t6RNqCg|7Zp~%;DJsPM301X~=e3X6}<*fZU}!jCky@*^RH->Vj|kRBS$% zw#GXhlzI^jnkCJ7L~c~H--@#$ZiR$;E?-WzW zJ_DZ*wQ&x9x@Nm(?A9Is?F>PHuO>FXHOI zzaI8AUKNSR?yUL!3Z9p1y^V?$`tz80y;iDJ-%g8x5RE%}Hj*#e6bSrps-F3F?Ah3D zZIP2~333ED589R@{7F!bi!Mp(=iq%^zD!C@jXw=h+EvJ<$Q%f5hDxo-%wO@g66l?h zLqD;HzTH)VKC$WLd518psdB?7N$lXO7fGHxsj`4bTG3hoLLXGTW}1wWO(B9Wp9{LN zDOT3+oeYrcB8G#;=zn;=<_+Z<9R>&w=aBR#pOzNN`_djE;et{_@)6o1e*4`>h9y^e zG%l}cAIB%l$%dI=&M?U!XeZK<@82&xnXl6U9u@DG1=XV7%4q*t90^!6>#O<;{D))` z2x`88Ehx#ZXi6pz9;<}MUxUZEYoWPGt;u69ui8WX4NP1vAYLI5P@^ZsbFA*6O&I}9 zkWPrNsUuU?iVz6)Bfv5K-hhmNd4~lm_#?yAwe71JJ=MGA9Y+K};_`Gm%|cie_BFKU`k8ER7`&#iG_jY1i$?OcNWp!rpWh_}Lkzp^&8D9<%SR z{3)FKnoq&)JG*%w6W%Hur&E?ij;$^@#zYW!sRdoo;w{@?`{<&JP8Sx+=X<;1dZzVg zG9vO&$F{Oi!+XzAXkFASg2N+;lDkWj8()W}$e*biFg=F6ADf)PVu`j+D>uvtBjD%^Zkp$!NKFcv@}+zQ)|G85JUJ-upY)HU{OJk$0kX!G4&5-1pAb9>85hXI7YZ& z4zAn#E*(|A$UsF`dKYeST&}34N6&)MW%W@rF6s1p(&RTV;XYO0ex_|9s(N81$tb38 zeYo!tHu=u!u0aV1o)kBXOV2Eq)C4L(pSJeMm8H(gI5EKl}436V2|Ht9kggTS|lT(K-Y&n3IxPD{dZ468Ue=#KWH@9B$Y(!Zf%-YZGisDm0s%j z8B`%p1XX`0iq|+Rdcu^KYeQ&`T|3=Mn}pkN{cN2ysNeYB0FmjO4%wPcddR+&~! z(OIAwnSiP`Onq{Mm!6?aOtIucZ6Ntb+X6^Z42~#K6bvgQmS*YU{7PNjE0|>z#J%F^ zY=H}yQz)wG&OsHL+(D^ZoV?;-^|gEuLp*f{h|RebsO&7rU%uLmDKa74cSg$)X(1EE zS0qs3?Xg`ml|| zGnzS)tX(?cd%OOWW>8_N+cw7;GqlOZ4S7g>EZ2N@mMlZV>kPIODG|mgp$RW^>5ygn zsl!v3U)BkQl_pVtm*d?OH2cxSYH}Y>!koszlN66qz!Rw(M3`L7Fd6e=+^&mO=jGU` z!?}x!ru7V8XxXHDdX7%gcBJIqGNAZe#U^PbSAPY}A4J;|GR3P%whOZAY0Vw3|47( zl2QVoIw#%!IyJj4+>m9S?<(H)4D)$EoTF}PcnIfvLypoadd)oQXd_Azx)`8Ow3WF z(M&Ai&;NctxJT|XN+$QeSNZ7y?Ei`y|0lX%qSsqc?qM~$@M3XMcIrww*vz2ZE`1j* z?z3F;+Lmv{hr4OYX(~{h6{5#G22xNZ^d<2{TaAQvahXg0F$G9KAgcm{(Q7|2w13oBJ}p-K=dJ@XhE7k zy9UnwG*~o`szN)E`Iw_k2$ZNsNc8Y_d$kG1HJQFgDDI?`SErc3$C1nLMaBN&3Ax8S zTg2hf%jk>O0;7>8>{ZqB;D)4A30t*sC((`VcGjCwS=$|ayWyrIDAPExFFV-PnX*bEX1k$(tPUlmk^&|A}Vx+tSj1`?{ zhG2?ZM8AZk2+PzxRBqp~G%`HI;7g1ZCLAOPlq>!nB*N8Iwvyw5w`I(j(}SmgdukmN zlgox8$Kjg>T#S)Ss{WTZI{{)pC*J7_bxnN8Jj_|+2~yDVO!3*2_|E!h{y$U!!{=u} zkhzGJQWQ6v$yc z4TIOpvpDQFs536;&xIaJ%Ku|>?|AU-W74F2Hpi2^W5@5?ruVGOqJDac**zx6n_#!d z7i#Hg4k88n3<+XJs{+p{^rRpFPiGLp&vdA7M7G3PbC96u%E6aJG7Yq>SocIy%)&g`TdULm2;}+ zcJj=PM$#jZpO>55`$|zSXsvNxK2tyXW)gG0iVFG&_C0PzvCV#rwY2tIHS@vdv2vPr zC5^=(a|>-eT!!kcRu80yJyIvUH}d@YKj1ZE4vyU3ZX+E+xn##+g|5D_%KSD>6otGN z$jY*t<9NUzZ1Z96F0|b&jEzFo+u!GR^{(DATy>G? znOt*ovls{v@MN}Pd+YhH^nyCso?d@gVO<)c;(E^tVraQ;>@d2p%#dMCC|Uz{hY9o3 z@l7_g^U0_@y#JCuca8nxh@}*A_e64(5;Fbi!X_s`cwm85$@uX4#yVp-gY#w~`$;{A zJBcfYDx+@vbr08PO78d73zSc^!3)_?htx@9Wn?#6vU`H~3Qd-wp1=k`ax1jKITig-$b^Z_nb??pZQ;`*OE91>ro<4@{E_Wv+vU^es zgs>HO5-EUwW}(PSC2ODiWk+36IV}BDC94Tl0#VQqfdS2X5>)EK6=qwgU!%D8)8*0G zA5HG-xpvb@9)}pdVOS3x$i!TE97NKSkZe?)I2pvZ1XaP>iGT~Em(CO-qpv+D6{{iH ziIEvb8UguBiADlE$|1W`zlynD{imD2JZJMu^d1{zHfo>C!SbRv^!0n>WM?+XmJxM9 zt?pb;EI*rYK-)3PL-Vwj$HltCflFmc99>o=aE&-6tc9n+w@bAT!$DFYhM`pmbADiB z_aovr&2XFLKOLhN%A)P43a9bq)-E1SRKW>))2%{6vvBrJg;m^LAdVi_pC&48bij5A zJ_RFYB4BC?<#tbH-9GQ-{0fMpUqJFdgu37jY)GdvUa#;U5#pRhIm5Ww@6^A-oYY#@V45x3#EbYl*5E* zWFurd_QEBd3;Qc8`SlW(SY>$ZqUNso5+mZ&RsYzvhPHn+lZ?uu{Cnrw{OpV9`Qbm? zhE2kJ{ZX=Ykc!=lOra6y{=z0DO)UDRbGmw6WNVmL8T;G4dBf)u?bQ1}X%FUpfmX2~ zn%20Cxyl~Cj>YltL5{3vn)BLjXZ7Ai-*>#A1tJiwr}Y69u234hH|&w$fNInP|HP#= zPmEdT=1y?vt15mgD&!ann+soo7Zb$B0|Ych=+82J<;>uRaS{ zHl4@^PBL0<51Q5g+;13mwjGLDv{2&qdJDO?>zTj36!ndYx#5N))W-nK6h|=u4lyC%$)huIx+^n^-AR1G^aBW)uPY5+-F&-N;`_Y z%0so$HDZ{V3PVO_i2yK8d zTN3l zWdR`YZ?D#g?6gazBm2X0?!0#V!TUw{lWt~oDBr;CTh zwve_IC_uL?#u5A)z6t)aihxBQ$d9Q_h1oTO1QLppWTSt*`|$v;@B{szX3?$&Kqhtd zE#x_ZKqlS(Es182+#VI<(KXPEfcbghRV?L4eK-w0X1C&vy1pjoy-<3Z5Y0#M?KF_fi~5obq!6_Awh(Xw%p>WmVtm|^c0#y zPwrb1pXRu=Q=L+8ozeVva`ZUNlcF$YFm$EuG~V-?1vBG>E}Pamk~qy>9q-3%?fkKD|66-8$I z1=hjdG<>0NfayzkDZm4M(ICJt8kH^#0n$x;ZWGkH7U=bZpHW^mF;)2&OUm)D z4Jg#lU49sk%lnuP*+92kB*K%TW5>W&Di;zQs$I6s#CD{)(FYkEXJ=Xp2&>J(>x-@x zB#_e+8m2W6r(-7R<$B4S@c|M>b0S|%A6Y4Y`z?rWz(ddi7IoR>zE_z3G>_{)N8cN1 zW0iH4c1HIuyl@Ind~1EfCPGBlcP%iC{8NL9Ntit4X&{>3n=qKD?o_jL+Qh?Aw%}O* z(PRp76eVRRBkhSNK9LF|AQT$q{>e@K&?$d4@qw~0DMS9qyDCCrH;6qH@hEwKXNjL# zl`z%POZ|DI<_ms>gIhTlj1|o^+r|d7D?&sGHx{d(OXn8GUJd2AGM=jU9z!}=;46FZ zvf$~KfPeZF^}t`9sLrgV4kstSzs|*(jvsUt|1^+1&*!9HAl2q#O~#1v==b+7(ZC~Q zUj>`G+*#Z48le-ow)sTMBWxeln?n^rJs21I1mT`-W=Xv)-z~ZFaecaR+l(k)Ct!lw zX)5D5B!q_^o?aSKpi?xHgK&hDO}eKh(W`{VbTP3SRu?c9!}RfVBXO+e3#>2<{JW!J zE?bJx*E~i@Z56tJUxL{0HOzc8aTH+>@u#&BON3yRMC`|IP9C7+Z86q4*pB5^o9+iQ zoxIblBTfGmk-_3zG#$9n+%Chb;M_U*XOKpjkV4=b{@Q+Ar7k0*GmA+A&4zd=q} zSF4mkxg=e)%>CSQ5rDE~JfjZyF^fOt3WaI6xkNupn+pmQpUif{ai4*0>5SEAN%r5T%?e7D~&dEWG@uApwEif)Shcz;x^9D4umZ z{^y%iHaNlRayo}Wgpv^mbv7WoZz8?@D zg641Ol&3W{@+Ulc*rh^PL6 zC!L`h1%va|@YsLtio(^gO~CVS)N@dzkM}F({$9XmZD|#K1zL^>`xP#kw+(}^ko#W#tJd-C_wX!PfZm^jV(Qvn^c{Qm|?W1 zhFe*Egh*qgH>;DZf!eS)4-`JUL@{SZyw-{D7zltl5-*_1hNbZhJITCwDJTQUt@cQn zqzl>|iAEg>b^`ky907V}Q1fW`9cZ0=jq3aT%N@?>G{^1)Tgn<`3F|#xP zjmAYZ!~3iO=#5rOBJ_=SVGE!G4~4SJ*Z^&`@_%rC5gmSkY!xSKlV=NW+3B|Z_#q_= zr`lrJ94F8GHA-e16Zb_W{!f0FOP?2!N4T1!@M$k8m5<6oseorIiPB+?74yY@vB!2p zVU)7MLUI0js_VC43G0eZ7q%|4-PYIJ&03r9W7h8+S~F8#RITP;e!c)`V;3vgRTkcL zDN0X2V^%VHbpW%`ykL~FnLLCA3|#)*YNVk3SL;(9>6yUK__?|MVE#v>ztE>Sfnd)! zi^Xys#g{^4Z4Rm@1X=!vnOcrdfYn!+GBBIr5)|yEZ2C^+ciuk7tZ5lqfESE#fZJL@NH)yW-_fqGB5(ZI)-xk zORSt$VwJAKlJQeZPxeym{Y2OjP`shVs2(TCzRetu-l3QEd~>h}J8);#_8v{+*z-b6uoeQygoh-$07oz7dIJsGy$tiUKP7RLg@m zvgilCg=y||6xy|E9leoZ+TM5QM2`Q1qXidtY*b}SxPkT|^&`}}!9P0e-Zg2v5aN+v z&Jn?$WDOsx0>z>zBmS>6iQ7XKqutr4u;xtA1O;q)4eW9w= zVAYBsBf5UbeFHcD4OyAtk6(APb_JF9VzXJ@J1$=Mzaft1{$YAZKiSqPM!$r4YjfA^ zDQ0iuXeU9Rl7^I=Y{F-lvL}mjFGB$?QqdAmd&6Ybd+p>^Y%H4bnToBjC}Ql(Q*~mlr+d{+%|D5;MVQL9nx0FJ8Q0InVfrm>V&0F$ zrjC*rRbTu3T@eNZ`U7KP@@LLg+q?gT+S}Sm_`39bEg&*Iyy3M2Svp#;0uLuR-bZ)s z``(vpXD-()Z)Zyq8*8eevfpIvyYRUgw7QJod4{&$YVOJp(z7zDQHsqHCd##BHE0}#mLPTTxU}MD*E}Sd?$;~Qd%^O@7 z$#QE^lf8bs^Uke7Qaeb3*U%us=%}0;aw5ivi|%+wz$uC=j;&dsyr*Y)$~L|;x5s=-JAf92Wr)z&^d}EK&vuIo zG}!mKjA(p1){594$&~58rrm_NWU$=u*v03U5!s26T15T zXpm#Cq!Fr~PbKRxw~Q;jSqf>W9sjqj=Ndxd=HM$sBP_%E_moODf$Y+G=;OzER;(`y=iPg%LF`9WI9F;? zHXU$y2I((IYiE)-3q7kAMe(y_jGLdAjcF9+UeEgLYFBoVJ%YJ|vSr`2C;eig=HT<@ z=*rhsK?ZBT{<`v7QebO&C|I$sB)uWS6!|ZHqa5##)i=D|jUZF}s*TZaBHc#jH#xYi((SptlAv5$F5PLaj*nibWV;Qw z*PDv=X5QI^Oph8`kD$tFrH`}T4nTK7>xpe3%)Z$02Q8n;z|pg>#>_JxW6s=8;I1Zhur2RR%pwMc0jjvXTU68gSe zpAmYQz=-$IwUB0or;jTrP$z9q>QceXB*c7DmOtLA9);13b+swrzF)cTr)_r3howBv zzgmuWGct~(&4{e=Jw+aZadg+64<>sPMZ8XYE85@ol8l<&U3lkaKzM7tVY*QT6Ux?Z zn=np^Yf6tAoROvqg2^o0Nxx6-ON|?CJD)p38-yz6LOtC1dI~;As{j(}@K5XVtQi;p zy`#-)sAN}rYJ;w9XXYScx%FS@l|beMGPmPhQ3f(=V313BORX!L+QWag_#NyXtNS8Mx-b4&AN0C!AD_;K@042?%TxaOAQzi^7A`(B}t;6NxCmRW?Ohh0foJF!po7`@KAR0gzr6wYM9MWKT*6(|??-zko`&p<|EGsu~ zqvVat%%Y>)wZ;{L!_3hSL={H!2#6^2IY}x&J!g$rQnl3yapl~DoCpP0`xV>jya`;r z`Db;rgq**uFu$u&FR1a1lUA#kA|HuR6Tb(lgsOi6M*0ro`a4Gakuf*yLw!lG+GXT9 zIY^OKe6Z0a7RX$d`*I8H;wPHv5fud5sycc1)Fi#(58AEPXwrr~Sr3sScD3)1hY&Mm z)*u$s;CWcSUL?{&k^b)AfA+p?t-QbHDvjg;^>PFI?3B#R5+OGqlC)o%BQdj?pYsg( z&!?hdtR%;k#D2$^gVOO03?h!JqW3$@dRCO>-p7uAXA4s>s*@9&FM%ZqfR-ku_<@>q zN3o~lCcWQTOq8Sw2P50VBi97X-6wL)lBGHdBw&eg)=s8(eWC3eUhFcG3s=gx^g0i8 z1_mxdVuwNpI*)f103)fPQX-(3`6vgC%QfEJ>1Z&6rU=cctSrVkPzVg$V1eCbwZLIIN`5v|A_PP&OofJ+$Rkh(V9Lfi|^Q?m_v^0u0XZ zeec9GD-zA8l$<2&Tj6Hn4hH_7RWF7G&=yH4o@CLd#P9)?+Ju90Jp4~j0KWNELhH6h zo*Y}ZRd7VIBu|3lD!fogKu}mx!a&_?+^h%BEn_9^2aRtP;HP43aW)=~7+rY{PW z9dBJ6g0meI&7ZqU(P*2+j)!ew6yUW?q83nDH<{;SntyMtzl`ZTho~QentvzT;5q8& zo@;cAFhj#l+PfVv9&;-e)T18#BJqW{aCwj(e&4m9mh0he?{^{KHslM|r*O`47e^R2MK8wwI!Uhr*xbD> zEeRFFWmOw;Mn(bykCrQcu8Fjyu{6+*JU-H1R8V-`NjVEr-~Eu{QbjlPAF>CjzNkp8xLuce)tK7WlvW-wHcSA?cOI zQmf#@Y+Go!sE70K{(t9BAd1Re*-o6jt_Ypt{83EoKA3-H2zBqSw8(#r07svS-5gPV zX-UwI)(iJ_@HYvExgv~>%w*!Ca-H+CX=B|r69vdBSP981$Owpu32Mj**=xw2R#(&! zHCDFtRPwiV^^&P0N$q06wv2#Ft?vL{7>K0F4Uc01^oq z9P@wzIS!jpjlWsA^ZkIA zG4Z#LHM$8^QIs%DAwJZI^ZF6V0&2=!-kwO6Vz=l$x-vOBHOj<}dN=4>b0{8AK9haa zWn>8>EAT?=K6pNf4noC7-yB{Yv1>xuQ6Wqc&&~&Ilq|YhnKypbP|s@5b+i)K8cp%g z3*MD2PeHwVa4;vBPB0*vieQd;Kb2a6h%{&VfKzp~hKf(iIoY;!#u2nIjSXtB@nIK~ z&(ZxB7EuzB-`B*HTx>PCYPT6yyoP)@YS@9RfE8*GhdhjBcAEkWnOa-TCyemB?fVLs zPsDBoHbHL1mVpd1#g;I$mIjpjM}k6R6nC9vLu9}@u-3P&`HsgXHDf5j(=27l9Ud>R z;qDUHjdFAK8;4lO;AKx$Sw4{{U9*%|n6YyBkK=~f=4)~~Q$f+epl#NoUkkHKiuKf) zm9ADFwQbmmf}Jg9+3QoPDR`U5I;we2D3u#mq&DSvf5@k;TYJh30d-oc^}PYFv!+KA z%C|fO0gT-)-9>l1LIsY|B0kaKTSK`C)}jDnbcO*^wR2(Jc;$BYBunU5P6?x8g{#q?z^t#& z)*Z*sQOApf&Df) zz1}}(|2A}q^DDcO_QSDoPu9tac_bT)*$oms9dgx7>HoK3m@(^p zP_vsmf{EjEwoNl##}|cjq;vN;wAHDfn{s#{bF)mZB+tk_&C z-c<#2{vfrQ^mHF%H!(D%!Z@D0qgd6w3BrOh%y`Y|4VSByxt}S~nkz*XuwKpr{%vli z)~uFqfZ%zKLsi|7F3kqFS!vl`6iF9~n&Uht!^)L86hBHfXZagOnLp>*tnACL>rhqs zvr6>8R{!~^n{G%!5 z(N!hjWMUL|jNz1KnfPNF=7c z_Q%=ns}@JEh<7^KH}-w>Sd@A7ClQhIaboBv?m392)w}lbVr03@cN3Wdb6-GDBZoZ3 z2KnrRo=?%RZ;O6yN}{lHUc;-(6b5(ie6nEDE#+zZ48PaBdlo75HH`Iv9xFkZtvcO; z&-?^s25e9EEv+{i7*_Lo=KcPNu3BTOk-&bqD|%&zdkwcmH}+wqR+j|X;g8A8%T5s# z0bdJJ_gzTk+tmJb^;~n5oRKCpn=%V+dcr9u5u@gUh-x2c_n7qySt)0z@$Q;$LNg^OKqAA5>ypNEQpkutTf5$$0^Wg)mT?k7LV z+mZiPmqtQW&2wj>DnGzXXVr8iECwXE=S`5d;K&P|D{bL)N;a0-X|8#XBwW?cbPbDCEu8gFR8nYAfcotR= z70o7h;ae#d&Dg_4S|H!0|A9fJ);a;3<)w;%=oXb)qMVf4-%#+5yb%_s4M(hasyfgL zqGnf)N;1!JmmnR;@g=87|BNU@zG2A$feD5P%7-++S2y6)cd!L~AA<>WjNdYY?{wi@ zZIAoj*9NL7Y90{ zdx6UbRAiWUwM}>C4w317&uQcCFz0IjoFIoGW^0P#?V<~PnqFKy9zrIpik4FOeuB!86qHNxS4dA8{>k6D)WV>Z!2p}oc9r|nWp1cj;oo{q%H8Bs zfG1Gq_}bpI=~-Volc1U&d?Nt@H=&I)YJPZBw5T(Y&(h@P_=G{={W1T}3?o-k=q|<* z(eI#d~Pms>)A)g5j@kv)=ymwxu_NauVRT1%hag5jN z1eGJyixODvX_=a0THKYtpNPyIa^6g|8K@H?WUwobx z?7yC(d8T0rF^F%F=~3bYl{^x-wxn3e%B(j4nDL0DCU_;pGZX}Ubr$7Ik_-?`&MY>h zty6xyW))N<4or^Rko5u9xrEUqkHK^yY2r-UaRtEv7j9_jY4Le|&MRN-V1A_ zaJ?r&Se-&%tY}(&mr&K=E0{<{dBtHnuQ&)te)uhWw2t@oSR7oUxc zEZ36`;ZKPHt4hFiJNCgRJdega?5YrtSQ72bJ&_r7p(9KZD0j$(URoGm1mhC$d<*=0 z8IS3QyUjXZsvh^9oIDmIxvQPwwjuQXF!O;QCON}|DKcm%H7~@#D-)lvo8?*vc{Zcc zbhNc!-Z+b#J+cFfEzJo^2YV*zifu6jEu;bQmeMf&VF&36O4|a3@?6FH1>~z7#Cfv3 zgn&T-0jT^VeWHip7-lhY^wazrcw2v|>NvW(H(t&?iBQRsQ_I!GEfkezJT32>hDl%yag>LyIsHaCO24P##&z4~WMC3(bQh zPQ7ZJuo_RWtZUlP*XNYe;|wa9YFe_k18~N&H5TDXv&2%azb;F=?Vy zC^J#4PaOhD^V4{NujY6n`e$u4qh1=QOz^Xdf1AFTh(Y<>OjbcyKK(jN%9iR$PaNm4 z=)@r-E67Ntmg*s+N~?wGvlVL48Kww!Zn~}Y(MHdBNYQM20ZVdHpb0Rz<%X+z;jt!P zDPwTRLwbDCKedRs%6BCCM35+0-Kmjwbx)(?+SfPAZb{2c5f4pv&Brxv`8*UD9jX4t z35HlEho&0Ct5aGaQKAQs$q9~@V}zZDm zT(#$ptu9k3SgVPh(k=4phn;IWY&lcKP^%Ri^( zEHfWoYN)nQ3hJitIf+P7RJC+Nz^p7vd^p{+p|C;5OYOGpW(t^B|7fhlkFm?OqARQO z4rWjvSV_0o_Zq&+o`>hZGYGF?W;k0gaJT)i|P2`z5NZ?xEs~p~lXktQC#w5r8!v4uIz;J^?;}3Ls7a5C!=BE4cs5 z=a*(nSLB}c+jJPs77DO|qpO;Ngd&=r9r1saE7}s3F?=P>Xy1Vb(Z`bOXm8=MmP}4` zHJ2+$yacb!msrKrT`G(a|0X3#>)U&y@FAz$1&2s-KZ}Lq@v|i6NFX|vIi5Hvh$teE zB_#lqmYtIgB1$LEOb@jtAYd!6ASc(Ss354Ntzco?R_ zcT^Hq>DNMo0tktKL{UUi908O-{?!mU%GX?sy9Oj=3sT`yq2aVoGY{4>DgTGHvtVkg zft!7Td$Ew<5Zv9R1PSg0cL^>*g1bAx-CbH7TG~Dox3;(zid##ImO7XF&fJ;z1Kh80 zCTC7||GU41%(9&diG97%O5XG!ph>KJ+%N1?Ja+TWJmtp+fCT}tz*N(z zaH-qfh;{*)I1eIt`2>beW2x8#L>W{54sT<@`ZaGuM0R7!u=uKV&dBQlZQw-FSx?=usEE6eMtyNZozKU^z<4(4 zrXBDW`K_#uoNf=(ArL?0t#lBdPTFs3A{#y>R3Xz0is-8=gQ6#hw^-^S}` zxWXiG=RwIs8f30LP@qO{W|=rZ=3{$hoj;7q&xqyXb=CsbAL8 z0reKre9G)AG}OQaRl>k&1(>i4+@lh>+%`L1ihTjsZs@TLPKilG1=dog2R}zXVDFC! zo*BWo+J=?N4#$Q?h#|g6Gw z@M@(v=JIV)R22yL-GwQ2)SfucLUy5#ocgCSZ$0B=WN30IO@m$@8c>KBAS;<#+V&s& znKU^jOfMR?{4R4X)7rQ^fnC+Skb(K)s;n8OD`K`5S(1Bo7XsxyN5%&s%?cX7+Xy#|nhes+0>9u^n zmQh%rl5Uv#1o?lj2jZ5se4C}!gqP8&nsj1R-Px_Iyg`@@gojv@Ha#hHV@mV^RY5UO zFn@ypS7qQwMOpDfSOn3br`w2OS9^WIjNLnsHMK!yP_Dodj|Bc|Xn5#mc@7S6B(=Ld zahBZmE-m858M{e_^X~qU6b2o#mv89Hq_+rzNtC9oGyvk8L_b3 zr%#i;dFJ@z1m3Sya8@q3wYX{Jd5A^#BNoS@2uet5y+R)2Jj`A-LjUuyo>=qek)dj5 zY48=C`6`iUdm9-V7?t<*EiM3BSCCS&<3E_l=cjkS9IEDe z-cCqAlfc!1=;idbo4-raenIr)WlUT??ic(Jj!n(DQ_<)4?#@q+;s|xkZ!nQEiJtf( zv$2#v3q|kRUC?pFRf=o0fi?*|I1YwdWWs<@!!K}^GECfZa!001wpQ+3Mp#;IlIZp& zptsEYS$nPkk1BD>u5^96xHGvL#3ep#FMW1bD&{H>C8M&js6-;nU$WQ1(+%BnwjH4K zi%H7JW6MPjV>E;vdBWLdoraqCS=+~2%vv{DNEfcbyW-7ZV?@*Ue?%Eq=J*0uYZ~Y! zMq2dMT7x^bmS7VBjd<)ZqAR&g%w_Kzq>pbY#pfsgMY+~i)l5Gm^d>A9E9KR{U^oLD z?ORr8T*{kTq)OKARlR$KO@C~khT-b1bea)g`l5EFG-=p?uFRd6)x0Xo*s`A~HIh9^ z>9!#mIqoV&@?D#!n>=44_^2^2XvmQt!0+Xtl8aqP_E&`?|5aA9k4bZ^=y1}UVSZ!| zt`ri{i;;gl=i|5}HlhIHCF!w#@~OVo)mAlS)uUGY#!|R-8b8iXAg5Y%a}6hzGVZ#Z zs^!<2Ml3fAfT($g@Ccrhkb*2eU7X#(8x~%e5<~9rvPM^AhTUN8nvaGQ%sPL~PoaU91@4%%| z8=-DZ^rmVZv@S#m@VdIRcINXdCad22*9W1!1~af!34P-*Mb&ZqtqZv<@5kpmwFU~` zD*5z{*J=GKOXEm-_77eqXD1VmimePy% zgi-W6G$$9mCUQwQ&F!btv|im~b_x#Mtj6G3l$T~c*fb};9xfQ*y5+K$9A%WsP(4O{MRjMJip9dot@OlsW4)$HeSdzq1Myap|10{#A}0Q6 z|J>4*DgYe6PRr$J5i4jUUKD*=*K;e&;sNOO)Vrk&%1i{{008|1nHNOlN`MlO$Kd># zYORuCc;fec1K-hiO{u~XLtc=969r$k&odT(sj4XYnqK>w<^{`ttg|9m6n~NqW?MMQ z)04*eh7;URysiT2Vmjx))f62mcwKjr)Ygs9d^seAC3=Bl%KJy78BVs;*1~B<%f~op zOrhw` zQ?M&bhImkeOE|LdJfJqSB?zU9o#t}*VAW!%jhcx1ho^sn_(pB-8 zm4JXjm|}3C9DtmdK$sf8$Fv5fhy34N5y5P{>VC zKu;{2OFUbpk|g0RC0TB)>`m}PH>-bMpdFYy?=XtqEpW?4tQY0z2I@uy-(~Fm@kmpcWkSjktO6+zsRpKQ;!g3lrrARyoA?uL_Kf+kVC6{DT)ki%*%R zA}j;s=3-|bpzz`p<9n=3$?rM+?S{9VSj1zQiz|iAo$#0}Dupf4C?UNaYWZWtcp*5+ zJP5N+|9I8~4m`@#*+Y$g{w%Mlj9HXpYel(Q9HpO#c%m9PPp^Z*m6=%8=sT%x)0EJ^ z^2o;m85w?{i*7+|PC!LG1Ady+Qzs^^9MS1(ekWtiYX>WW9xY2T#t$MyoXL#Y+-Qp$ z18XF^-#WT}&t)3QnH3z;6({-~B9K1j10M-l9l?`g*TOU@S}mwG0J-oGxGcvio0EP= zX0}d1)?5i#GL1_9z=KP=gXPtz*H<>Ev5UyZ0|lCKp$2SBr5KZPzn5i=Ir}5z2NrIy z1P-eqx8tVT$Ttx|NDJ3dDaAlzP`(|F?!iZbxm@JGn-n^vR9rWnwu&SKbZ4Pi>9Lm8 z12myVIFIJz+MYOyVb$|J|9VLky-@VMU7yk+>3TfsiT@LB$p(Lr5&2 zsNs`CBv(J(jJT~JJ2$#Wk4{9!pbvV!r^%ayBmR zdQ=D4EobmS;a@|_vj!01K=v#}LqH0v*?V9=V%(`LsG5yn2rdZm-3C`T^olv4d7 z1i;_{PtvHFh@rZH_%%+Uz!!6j2si;YFkl1NQMfve1P%kI~DDsQmh zAAIHT^+f7hZA#e$r`!>!8NWHaD_ap;ejlUDsgd0{CANoeT*SkgQ}lFvBHu$s|K+;Q z?__>i6ACyB%~yblJ512ml>cf|qa`83#WnqQ+B)S&&FQUpf;uDB8TEgQS!9mZO1)Mo z`4R$_wr>p^jS?T5{Z6)x`A*IdGIGo+FZbBAklC+f-XKi{F(~R-j@Fc&eBZsiCZ{If zRss@Y;hMBTl(3rsH}7tznv`L&S0edL$nukjMTUsj9;bbtc;u3Z_)?_(vPYesXna0_ zsCB+qeYW@cE}&tUP=1~Wy$evgB;8iRV%#MwqwL=?0225CehXu{&Gvn=2P`X*-d~cc zbz)gtk&@1n_>_^(#sH+qbF4jqKXb6{(*e<*z*ttY`AgExoIyqa>D>HaR@)$k_{G9J zX_ggfy48!6t^O?Hcvra>g}(=D+Fn$r4^lj$*Z!X{CjkgN3UmMeE6jyE;9FWgMun7Z z>1+s7M>o>s2$NGx5v;X6=vBQ87vIJy=zYz^U>BT)BrU!t#h}4B$1Gr_cF1=26x*lS zW+M=CC`pE!RB9*T9O@sKj-MIh6Pd=# z$S5UW0)> zv>L@xK#mDYVF6X^R7^u!36ZT4O9J;XaS16BPQ4CEA)CxZKPXy;7~8*1%%=ZYO>&Dl zgwqmRHp+KhXHJ(wH+sJ$i8f|XR4Own2RWJ~!=YN$jzLNVu{y++jmkAVt=OC;wh}q# z=U7eFQVCiOYp}FrEJ6SYfCV5BGvK#HWIl^N_=to4L_|J}{u=W-8kc>Sc=*CDEB;Ba zUt7`T4q4>NjLWQ~z|qS9zR$Yx!G4EherrVUU-gT{G)1Us@65jJvIL}p!vD#I+}gg* z6iPYfGw(j0t;5Ip%7^cJj1_e@@s4CbRQ>qflRCyo8GrkuflpdoBx|>uSftet5(f7J z-)G8S#zxKAUf*sH;aaVh*~@J$PGWlW_yL)hd!5?|<_FIa5WLvK`!x++1ff?0+;yXC zwGy=*Te#}&iQE6licyuD)%SU1abZ&bv^vE9O5&K+_siZLw&jEi_qxNiL^3$^H4m6B zI;e)@V}>joe+yn{lkzb~_&P`lxzUmc#(o9+d4TaAAI5}^MsnG@dDl!a+xNy6+Xp0e z0C*C^ehQ!rUp`BjqX`V9(eA++NpVXYIdNQZy{%K{F}gz2>@1t7U6!d%_ERv{=@-a84+m?~ zQZrB|!o3Rr&m>0^c1R1)a@TfnS$0&bnwdLW6~8DR#EM_a=D+JQ`ywIG-^R3)akF|S z$UirSLAq7RdvE4Sq^tKj-b`&4=IJleheUSdSM#G~453U}&w1aioyfPpcZYEvYo@Q~ zj`{Y2$%Nb4GABZX*`NEm{^rf|8=&xPiB1EEI$7!wO5lH0NRpfXT7%&6691YQvmO~V z@7kZKPzkmtCJ|>XWTX*l|{92<8+ z4@R%^L;z2K6YUf%Ji7FJokPjzp#*@K4Aok3TdEPBzAz*FQqq11Qp?IDOWPEK6*uO+ zy`Oe*gf7tqiS`jgbbV!r>JCm@@px%qNKtV2(uTcL3^{rh=|lGkSaMYHLt|1p)syB= zeTsB5MV6Bn;fGc7WL6c}v;1Q#L!JT2XLU86E}nHCfTbMjO8wp5D8g(%4|f#+XJ=0F z&Gu&Z!Dx*GCz9js;pdMyZ4YkGr4+lVBNee2@BIwp?M2C>CXn87>^Fd@eO=Gi~GdEJBs%_fO_jYX*2c*{C;VH#n@&Xw; zd0>?kc?rw*lgD_oH&=-dy65hc<59hQQ9s+$$>vFHs#i+L+VwSlZI!y*I%zfErHfPI z)LBYbv&t&=YT#XJ4-Pl0gBC7Tf|Uzbp*^Zzq)I@b0iZhf7*Nb<{8Yz-b=q;@*%}5J zZq9M!uSGaRF2gHCyIixAMF&ulInjtXm@{_!C1Q;`k};G~aq4LP7WmUUEVz~TY~7r3 z@X$minlL74ld^+EAV)dmd>=E1TjWNjS9arE_v`)7agX=>I@WSeymG?Yc0<}E%V8_8 zrIVniti*EPW?JHKh@NRM5;q9xLdK=XHWHLkLcYV)*rx_eZ&2;Y;7oR$-+h2NH+}KX zzkyAVhSG?ZBfN$OlqJ=MkrfJWI*9xrbFO!*@%-b2*l`>c6D(mqo)^`tb@{2uYlZYxqKv;$N#y6mg=#nMZHxB`GhuJi&YCZmav1<*hPX`ZCO zvaB1L#rt8ZwB5I0UAp-UJw2tdIE=3hOLvV>Zds?rPgX=0*lw#F38J z;))YqJ?M_`P)uh8muFku@;-x5P|F*AzfMk8Sa(k1-H>DYkk84H|PTHht_U?!iz^Zd2^x(($UN_ED! zkm{DSp%v5uXWSR-Y|J;p{nPRuK+?))&(k>_z1YOgv4f1o348{Kw?s4r5o2fZ%Suc= zm;1xz`wuyM4Fc^8ks53^AzXfEx&Ah{5N%~RfLrRAlFgeHYj5DG8eB>Z4Oir{p_ep6 zj!RSZYJJ&{2CK1Nj?g)A8F|M79P$*|0z&AM>{n}e1mT=n<3T^~B#=iO8})XtSQ%A~ zbc=eGJCj8tT~q*4ZfOgA*!dxOA`Cw`HSCJa-Ifz7l)1*KRr?RMS#LP?yPRt}W2$R? z%*SbJ3=*M-tVJmCb%Z!iu2_7L-Q69+p+N_B$M`FmI~s>K8doapAR-E>!cUbz(qw?o zZPkfV(E6^mD3tLF>_7h2j`EJ z&M-42k@{h+UVAi72|Jcv^@uGZ&$7kd|bwE=WBDD59t;0#tG7)0>ZkjAghn2e2n z2&%Q|j9xMgjCNvITW2e52n}1OHNHmFi*XI#!zqm;R`5;yAe_E#8rq4zz3|}X@BX_t zS;{89P<*x5=8R+ejCIO<=OYZX*Ab_0C7DlEIVKH*ZbNpYfegti3Zr&-=8>+w$=x6w z=_VJmNq;sIPyV2gDp!eWW#`fxpR;B}vXoZKt~Sqg5;&C63fF0Fz@uh~sWi}Ez%4NB zkhKuVGFNYRtHGSME+Fs1Mlvp;$Sz8!k}Qhl1T?1fk@ixSG5DMy`cd`42zwux#TF6J z!|)9#=Pm|T6}6IA%b*KPzfogMTJj~x6=w^SiJHU_C{oFWDsEi6+0b}?7C|>J(V#g6 zlM`$liuCOuY~P(^rn_0^z=8p(f=Z5VvWZzwYpq{$E3kyXPJe_v<1&OmtSyt2EBzl0 z6-?uj%R5w{@^?sc7s~;qrE0!sq^1eQVnB+N9J82ywQG=9EFMrz`q6@6RfGL=VrPg+ zj8kUJNcPE@ppV8y%GU`UIF;rDS@j%^wGkQ#1+Gtf!_@!|iDRh3@R8yi} z#TLLr=Q^iK{hO+-eLWb6_1{GJRj)n2ySrEkH_-}@(IG6@T%nYe0_36IgW+0+EChs*0Yaiqaa3a1wGpOEgV)Lky$JI>;@B`)p3w5|?^>KUk=?Hn?Q= z0WP5&ku}=NCl183p+6E4?q}-$T$$9`jO7y#*kM)mDkic% z-MWz@!!A}`0qj6T&e75{ZYAPG07Y#$Z%e(8aaCiTX5N-`7FMznf^M)Bb%)lo=nww} z61iAcQDSScxuy2Kl=)WcAbkGvri9TS%kZ)rz!yVBb4bb2Mafq~)psy7GD{&V@@ib} z)s!bpsEaZ)hv?fbo@6iqzgvJ6DzeTmGT9zr%}PRRKoh(RSZ;g0Uq&=?NnF_p(q#n= ze#YBO2X6i*vqj;(R(c&E{D#vWE5HDUX6Sz>>PZ0NkH&z{|0iSMA0+)Y&Pl21u~83u zCmgcunHLUxI=2)=7#+hI5*bedjdv%c@kkBQK_M5}-6>SDJ*;q`Zr%qHJLUfi&<3t@5N=S;+Smi1}OXjjQ#&BCI;Os(-hblLkHgbJ@aXhdWM8xWyKOmdw~sC~dw$nuzOp>MD*2_z zd$rQPr1%Z7M2FYHF=O5P2Pf^md=vDbni-`q33(Ee7Q=%0rWdwFPni~NiBpU<&xW|U zPZ9^b+}wBrZW_q{A_?rrfa|p4`RO&XQj6{{R|!g!5UUPd8+u#jBUn-oR#i7V%s1Y1 z_)!tPDBxlaKbdx^PmT~+Mdaf*f}r7hw3_yMmLPXpuVEAMBZLkJfd~QrQLYx#K0;cT zn^hDrSfI6n_W?f?`jx`FT&Smfd1_XRjo#BDD@rUi3#qJhB%17fV%|D8_|T_T=VP$M z$xYO$w_UkXqk2#B8XlX+oG!E?bl}{a2K9=x{LOlEa|7u4+7nMf(@j(MtSQ^)9^Ph) zMmhWFvw(tsoof%KW&c9*B8Nhcz{cZ*!}_|*1wY7*9InLA)u>Ee+@fc7PdDP+uS4GD z5jVbE@Ex!yu?}o5paa_?;zHPplD!*{#r`rS$4+J4O_nyA+X$xU&n2owLDAdJ&VEXL zcvkq}(0kKxg2KXb!>V`U7lr{P>wc|bMD|MAxD2tM5EiUNh-e19RFOc=8~2M;gPnHk zAx?=-Qv)`+-4+YR+0uYc0^=6CsMgSKrb!7l)3czVlAjfkUASB>qYUwnbN5)MeM=)J zkybHpD1`XI@AymV^NrhP`eG(Ww$Z@c4-VdCkDtqWtPQ@6LMq+5WB8cOp5aIm6knrMlO<=NU*l3UGD+-!*?7 ze_`U}z+pk-0pz2dH>z?WEuz!#G*tC$?|T_}ys>+}BShCgbDNNi#2=k@(&(>DxEeS5 zrTq?z)p=-hk4UbxjmBdbx09W5+SIT$v#)%Tb>uQjs3wi!6&j0nFIG^;wMFMP?GW@x z^<$$^opnoSQU(sHxjyaEcN|$B!i=jYd;;#pvLk4Z^0{F_Sj(B0wfy4_=^B$|_TxnT zMSmY^cv84(GF&fRo|!g$GbA>FB;y?m&l)_}x=UN4Z^J3-pK4OD->^2Ptd61b5l}AL zv!C&y>7ONSL>!mW+zLxR|ErXo_)u$Xf|XnYm;xF-!tn5-9$yhzpAe#Qa;6UP&H{&P z;cC`J4itZ2+7u)L%u1KxGbsc#C=e7}3X@ZVES(9uFU#xYun3gCnL`Ad zWn2OONpEFSt18%AaOH}KPy`cw@3}~APPV^I<$vhz^xyDLl`TOGRxiu9?&`Q6zcd?n zTl%kVKG$7P(-fr%vd%8}UWXXYoGw{?2mmzIo_S#{t2r6Rw-cQzK)7V@E{@AOK*j`+M<`V9Aj z`F2wh_=2FqBXPV|Sd^E@0C{cHT530Z$i#=3^)3tme32kY@Q+^&M<#RB>rxv^UoF3r z9aDGtcL>%MpTpxYewI?>n{L%kzhVxO(XN?Mf|a}JhI)upu@@+!D7PC^;^`K;QjGFd z(nQ`2h}A+mx-Q2~%#jHcO*1DLER9yVt1ytW&7y{KhMpGvW^LK&xU+np)%>d-!8fnF zGsTD8{>!!K+0-Sjm5;$*sZ{Nh_jh+=U!bX<0}p*tI}3hdNy>0?Oo{tLtEKK>tM={IZnct?J{MSpxv%jkCS0EdrGM^&w?bH+alXCU1nV zVo`9@WbrSVKmTGN=GixXPxoW^^l>~>I%N>M8WAl2*(F)9sNm_<3HrS2iT`&AZN#0Y zWel{sQdJyhq|{4SVxKT+_oNN9lL7hTSjb48&sn#}FPG_2+QERU@oZi=Bfie>o@8dE z&Vl#26G)e!1&bf)eQ9wRml=MFSJl^_8!VtpkUWoZl}lb`6B%weiZe)2W;5>}T$ zM9u#AQyf}i$YM{IpPoe(r9Bcdfd7quBA)eV*UB9Q{1mq}&nm*SWkMeWNB~yCFxnC`joXK9H%q4WJoW|Y$Ac8G z&H7a@L@uod>ge#>=v;fF^mh7!yhgl6?Nd@lN)6r5m%eIQPqug5O^_}C=bQdns}f5y zmwV8lSq~DWX>EtFm@nbVb?q{~(W9&TDnUuK4N9M#{1MtjlX>2U{=J{CXQ8yU4hu1U z+b0sBW<*%g{9nZ<9a-S$Q}Uwku=;3FDE!$JKOR-g(V}3%FR1iC3`hmhV6vIcv;B9Q z)Yd4i+-)LY=FbWT#;nj`J81^2c;TZfo)i_`mvE*8oE4JiDq)) zJnj9gz&WQ|Gu!cI4-TK9I2Sd`c-m87_U{=MGU{hQBmVk{0o9Xr)vi93E|usa1V3ep;4+&mk(to6ur=h8 z`^T;#_=;=sCfFyQO+kX^_CA1RMJ%U)=~P%YmP&;zKPq|*_;=OuN<4ggMAgU)01pU$ zb;l2EmYJcD-BuA8Mj`&9Bf1@Ql*~d^aX0~ok!WnC*jQ45T)`VB=>ugr&OWc|ihz8w zc>$8a#Zi)-65^5KWdqcBF!Y7^QH@9%@?Q%LcGEbFC2t$43l+dronRa$f6)|gsP9ogy;)pSVVKk#65B?hAvY2L7$()hu<-oC0F%_3IF(8;i|WkQh>x& zPTkN!yK1P46Cy@0iF(B)!0?Jz@(P;`snKI5*_zMgEXC}CLjoq(Y=w*c!HXiJ@6 z{&WCmip#QHhcM%X|8Z5s<={$5h^VO({)v`hatNhzpxcmA!_XMD?(qvx`mIP{GOrX= zduW~fQv{6CztHgii4(|$`j?o?yoh@U>@yLdZc$QMaV(uAWinQN)622j&8vJbYn97h zy~L+v6#ayn#bMO!k?uJcYvgb2i+4&3mv*!svxrDmftSce(m?c7AMd$rx2RtMPFXh=qwRi(5>$>3&h?H}LiRqE6_?RJC|UGSW(LFS?QZ7f zPN7W|PAv+paTiDkAlG8!j|BxR7deoN6}W&S87x8@UD2Yo&ZG@xLl}6ih_Mz_GJ?SW zdAFKEqx9zm)iX9!MPD%%{J|JTk)}0WTooiwmJ?=FjEXFF{g9lvCXhP|>OL;IwC{z2c!f?F>8C}8O!n5k%ii{VP&yNZian8U9Tu5htUY(;$KYmW}&KnBL=O;-CSZcFcmTYZT0|}#f1c& zAQ5ka*`5^3-VAy_U1K)J;uLh{UIRL72OG#LXZ8lN9d|;tl~wdd1t@@qHfy{y+{QFc z`C_SI1##}8ZsAg_mLOEKUK78;3WrUs;n*PNiwOFQbKwxecQr5Sab8>KmfbtZq3w)) zanbpDLB`DyCcDQ@-Dp&~OvA921~7UC@Ry#ZYw;iuTtZ9rsh|r3VpjG$O`uUP4K+^J zJBXl`A4e?@S2TV)i>j%Bf7+AuPLez*RS<|Uyv&CP%J8PmbmP zDECMgg_&7&rh1L&N!|(fod{EiIQ1=5_gVj@9Ny(z6~=!g^!@K+y7VLC9rZt&c{=r2 zo^tD5Pdoj3XsSl$T5>M5ITDvm4A*hYAH^W;&7we8yRama_Md%+NF8HVk8=045`XE0 z{T*E&YwWwRT9^+%WtK<@t3y7R47E`%++4yTMO!)l?Q?(^K@>40$~nd*E}1mdlMp|O zBq_k(*Dcs9(iasRh)xSFFDt@}tqspFXsn43$ZXHXq_w70y1LiYBP#-2tFxblqmut? z8bS7@bcIaKHuZSU6h^))y z0?hs0<<-{hm8bfb9a=H0hZibSS((_0Bt$QJ3|QdfI3O|8b~6kdNC}FlvwU5F2 zBFf1EZNQmIcNH$YHOH-sr3dq2VT`WXG#N!DR$kBsj7*ZLXL5pG)~YZx=)-cA41HCM zsLce#nakgw}# zwTIQaZSN*yRz{8@LjAUTE2wT=Vv4SI>O!}%nEw2_FdHZv=QMi=*&!_~aX~VUlRXhA zfENW8MJ6z~y+AZ>xGh{9@5X;1TrGHH{UOujEv6UlUVaWAWQEf7y*3{naR|$b8 zQvQ1bU4`=nx=EioQ<6KuUo)rF+r4|jF|ZF2W|q4vz{40a9aP-v8i{Cb@pUvnTHAoT z`eKmvx^7nfP#2RmJy7DRO=s!R>M#&Z>RAgQ~`5`WP17JwPhBWN|I`rnFO>mzCd2#H!6U)BKk8!rXdzZ?rW%&9Y4_9k z&Q8a&Q^mF@>e)hUCdHrj<;)wN$DUF&gxA>?J0+^XK?J1w_2}k!XW$d9%}PHuTW>47 z(+P~D`|nU%XqISgc!^FI^pd44sUX~mQTLx!#nNlMMRJNrVC?BZ}?riUJEFAP}x04sb4+u|xE zV&7XV5AM+n%az?>(Xk(r? z^$p&hFqN?N7`}wWV<9FQ5$Gm&XLD8h&8e{4{T{Jn|5)|M*mex(?~P`IQn;zL0<#zoVL`cB9(oX!qeS6ZGP|Q9U;o6ib8`zG|_SSF3B0wWoM$L6n+!X^PDiBV=iB!u$Na1|$e&obk4YDPi0b;N=^Nvhz`2pm+-Nk)gSOoSKkIn*+ z_P|Pc(x0_#xy~i0#YFcxn7t#e+2FB$_iW6b-JyiIXYk#HOU>P|N~M4~fEy>Ctkv9v zaoMdtw<+c2VWo5-r^=(HpW*(BZlIMmN97rgb)1rx%IjaAW?Np1^w=%XQzO?rR>qB- zG-4AUTT*urN9yKq?Pia4Mwbtv<-@=FhMTmBH}k)Y8wj}Bwhu`qTQ=UuiU&%d8+7fk zTl2KE2jPRd%NeTJ&SPKKI7qE-O->yTh%9dD88wb$f46>Zr~JakXU2hjSMQI z%tz0szU2z*c#I$(7>~c;wCrW4{ET3d7QufG{>t0!w6gqSeGQ^}a~ZK2!J-4PuXIej zX&wg}{#jl=vw(?4m}r0U+8^NfgLpReMTY(?qC1AUeZ}JyqPW%UFB7}2pWWLf@{rUL zdQ?{j@a&yl=@gi+vVkKFFNKtRfAK$yi%GqFPRE^Gj_zg-N)e}?+}NGX!NBntTe2AN zN$#&wHX*-6cSVX;n$CBdx`<83a)T4C7}^=i9s#$U`Cew3W0@==YbK(`3Z0G$32Z%S zS|Y!Xi_2m{a*Z64_P)VbN4mN}I=xx~)v7>#zh~nyxmyjihzC_wbLOUDT*hY^;5?a% zP*7VFv6&;^LvrB^EO>|bq@bg(H^mU)hIn!E!D*+_c6il+`U7RvJ#Sz) zS=JK1pud`1%hWWwq#-ud>Ns`!$y3%%p=lf)*Z~JiJcI0*>o8>z5v9YeR2ej0i^RG(ffVyh{H5N2dE4BSl<|+d?L3FB_0>n`Q5FUf%ZK zgA5FvEf0RT0tUbNETV7J+vCnWp1_-q1Nln9Ux!{cRYQF3Sw-{!#qCcp^1}?#3~+Kk z{U9&|XZWh8t$~Ur3jfKNX#Usrf96I<2G^Ts7Ko5Lfw>Ld7N?{f4 zqwz1wjnk|1a;1@JQ3>%kHexrUDGOj=sF#zXWTNaxzj+a&DOP)b?ypUEfjc)w| zI%34GVoxo4nej!Q2E_@y02axhOv!aB!BS`~&hAJ><)}|1)wk+tTZ1f8b^o0ga|Y!> zQHoTeSu&}@FB;=(7F<2^MBlpM=dOA^2ZEDv6DG_wnLrk_Q|8NsNTvgBizzFy?{J-B zX>l&yjzLSs)5vtTh{!>YTNR^jBRRERSKMS<+8_#igBWAi*oQ{dNGg|bmC*eH-ku~^ zlct#0_0lZyye#*W!z+sAqW*vKeE>OP-zCDumi(y?;(jD>q+PKwaGIV|QuI-?-QF^Y ztRx>(itBMnN@6D%Y1kf^0;(K<%4ftAxg8#gt$ z!BufS+2;&e@VA+3&CpP4SJ}Krc16mx<%<3MmU*O!`Ndln3!aiS8bn6DAmNmV6qHs6 z#?jS>pdF7FGVyW4k;GBvZ@#wUH>9~X(kBaWbm#_iQ(HrnC|3(}e|7tfQK);4MSj|I z5FTe*MdZvLdBiy}Z*x2yr3lIs%LH&TTtaE+s(oopJkxs8Rx#@PCJ&+?Mi2s=GCS81 zA92M_@9d6foNIP1GWcoyL3Fh7JnBhXG3x1#iuCZu-k646R~Wx2V>&a& z4bGNZjOV?n7%K_QF-A`~Q4`Rz^`=$R4My}l{#B{rZQe~t$AJ=F~ zJPX<8#xtP{%=nf`(db|o74=kP7@*jf^vwH93JfUW7&%D!ueydKUW+%$xw%G6az>}i z&7<~*M_aQrYDDk-dd!J2ep8`czL5ut2z^~I7b>l@7>AxQeQ=Rkc2w4YC*_CQFA`)P zQLPuZ1|4X)y!6umvr~H55}3ezLUca;WL;Wz4ke&+u7;rOZOj`4wEVp-aU>8+;Q3Y& zr^aYUS%Fb7i^8FN)e9RXKir?=u6?B}vC6D|how&kY8bi^^A7eJj&WlXxiheq!y5{G z;m`?Vjj&{u!E-zHLbn7~#gzn~4-M6I8|mj}_Hn(Gs7`O*4c%yI|1ny(beIYxo)vWE z3;w}mA=!RKrB|}fpvs2ZXTlL37pF9)@kX>oDL1=)?9&PgE=d>268Tetav=bB1BQ_P1?$aC4GkALS|rc-WEJ^9Vy>7w+t_ zT6rrTo&#`)!a|cW4_h)Er)Y>Q_OS0!HB|`uKI7o zE=zaR!^@QW0pwIeV)juG{#gwHF)N)}oboRUmE$o~euRP2~esU(ev1Cu(){^ya*W6((9&UEUGYg##=C>Hn!1U;wV{gT4$qteA9c)kE}g8t$=nz!c(XG+DY!p&xGT7v zz4%jQO}~^krjJF$+UkaOLTRBZ{j>q@4}@y3J49b@O10Dr=9g*l#vdPQ)t zH)jlRQ^9Q2s{&?TW$wdRZSFAZz`cch{r29{>q>X(BkImONtIye>V7Lgt{^DJ_v_C! zbB_m+T}Mx&4oUj-95wU0;Hn_?auX%l0cfzw*N}aCd=rZ!J<>7!YI}FD5K78cvqOt_m?m}~jbdnB+%aa7A+{VL=@{VJ3U2TtO-y!(_b?Jd?kw0yC(oa?~p!nhg&61OnFu!gm|VhHa#=182R(YjBhZ~5LM{KCT0 zyO&wZJxiWA>5Jd7+i!YPAV(`x?>N>?=*jlbQVia3b5p`VPyrfqdZ;Pp*EbOHxV76)P}FrH4zO8xi^ISge!%>u z(&j_eVF6y6Gks|jP%8BC*s8nB=iDnN2J1%5k3Y8KABaQo=PT)8COtP{($2_lIE06_ zqik(dKE4lF_e639E8n;itM2pkKRE~x7DrNkvxDyK$I~!QBSIq66ShL3>`$^T>_wlW z>dP_Jpsdr>&i0bW-d4Z2ig9s@grvgDyukT_{lKQSna}gLTWyjQ-ky3zbm#APywt*Z9!a*x28>+ zpZF6oM*F)No`mI$u>_%rN;f$3T%JPwVvgMCReXZ*dI#e`g7?tao4K!cPIsGy<+Y#l zE$vrTrhhkNH;D?=-0(@}*?A7W80xJt1yiRSd&r-{b^_G)o#+NRw zpob>)MBc)i|U(W3ZJ7z+rR1D zEtp$wmr&>I1SLjZK7K##Kc?klPwPujniv!6bkZ4X{1&36iHN)9@=fEbckKQm8aw{8 z#n_rR$=g`Ta!=D38CdDZmG8Mko@PtI^sEWrb#id==K867D$5kLmBG&jLn+2{Q4su~ zel8};>&_ykiq!ak9mkfs%gQ;_95h)lw|EfC1cKD)(gUn2+~LFiPbZ<33TjMcd)3Zv zXUf09F)Bd0f>>%e4*&FgyGRH=3*!*^snfn6(Gds5W1)Luf{%u6oV_m?NCqo7fX9tF zlG+T#D(_PYo9Pp8J(( zYg+`R^_J);60c6W+5cr}79#?@nyS}WURfUgfT-ciE78j%{{lrjt7mAS1fpArPGLuReNQ;FCHGlH1E5`fdFYZ;G2j5j2gUpeo_C`1~xWt6<&<^EOjrrLUYbr zSL1h5R$9oN33r%2a2?1xNM(>xG7oJ>iE9-ROSib zkF4!0Z=*OnUlRd(rS-v88yU`WKs)#y*Hm3LS|g*(o7K>6(cJpFj8~=_lVG{wA3T&{ zibGh#3`qGgaU^;CePOAqJeXF*Muhii)+}2ZPAG_au+aXGq`igCf+O4;p)8m%zFl1B zy7}>}h<4w=r;9c!rHMKmllWqXJ|%K)rQu$44_tG>r{gWfTAU0e>)w+{H~(|j%m6!k zyY$o3s^}I__}?j}`2*d&^<6yyo93h*^t!55h3tovYblwC%4{7rFe~ryJ(yz6eQI=} zO*>NThssy9!-cz<0zPX&c2caz=(C8Pe8{HfdzYa2<%G7Er-CgAoddV;kw|r`;mCCO zRcRW+VZ%iD<(%kiQfSZfm0Eef!c}tv=8KEFSNa`+0vY&R(J-1f0xT(?^s>0C8;{|F zYWZg0YkQXJ%-bZEuewRtpC0||vILzheq=hJ0mx7{2j|?_u0p^r!4d>EKgj}OdnG(IN|dt(E!?b8f$XYx~>`Jh9skIY5NzozS}AE4co*`p)1(ye?UR)XT(Av6ZJ>*+XjTdXI!AD$BMdApR^F-AZu=njcHjhd_!3i7B zc6*U8`Ds-Fr;}z0CEje})uv9LjBzQD_Ig1O?4$OWT~&JeTnQEAuZ?t6=i;r(;$Y(j z2z7AbR#=WBTszJ9_;Xd72r%Ejiqju4M=zO~b@>z>a{l9thb&9eaQgf=;zGYFv6iF1 zzoH3;aDRcY_Q0&a=L_RrP>RP(Ef4un=jr9eEBwrpKRZuUW#GLC5Hrv;_YMUQP1q~a zD6&h0Q|{o_S+KS6>S+e)7cQF*)uDar44?mG-rdzhS3!y59cmIS9CpaR(>+0(r!ZMM zn~%V3))YJwBF6CKi@EMKC?)mUR0$lD>`DpT*WwX4zjQbYQ!E}vB6Ws;1fhl1zF452 z?zZBeTuBaJl?i;AD5{7FZ~|D(8!@EKV2UFyqxDf05y-_(DkgeR9a;?~w)klq*NM$8 zVA$30ab9K82R}V(&#+4Nej$}QmXIu{6>i{^REiG^=wKJRVRFPlUhdIPYFZ+Rf@^~; zi0d?{bJT)WL54@Ts*Xm=wet3yR$tKZ{75Y1hOF>d~hLN0`6A98tE`0MkhQ@E?8aS)Amrvgcn9F zc6%Qyxt9t9+>2b`vUrD@sE%1%uEALA>`S@)4QaTS<5kp6bB}|hK)AC1f<>;V*gVvI z3a&W9pcYm&NHHGeP=5h2$;Ufm@opRRx(B?=mZBNiKd|(s=$-4FmRgbD&A&>xz z4Al`+RevPDx`X0`;Wu?5`z3*JD`iFkUQMVrPf@;~I-9AB>A6~vQnt=`H~0BDvnGb! zfG$i`lXd(?ZQ#aVXxCG%!SUa6&fX4(CP=@m9&>r~;B27(k6P--xLkCMO_RCAZ7-tH zADfzUFSoCiFI&v@D3=S$>8w}i)lVE=OiLYCXJ`1@KYoO*K+BYD!<{rv;`;^f&VFtM zF`%WG(^*z~OpBGJ$TjLvXO+wAy_u%uh#)SZ_HC^wBVl*|CWAgNx?m|QdIYyQ5#;kr zph^=DQXrAl%j|zEBn{WOlhBY_^*H3z$s38#8K$3wa7o1L=<2A;5QBK?#Q7u~CqZK5 z0qlY>{N;6{WedNJ5$<|a(mhdCD>STL!-8jz`(X}-LnC!$^f54gx@l=GXS)!|2&yZ# z<%2Z3d~F%GXKz<{Rd&+$!Q2~kB1{hk7%6D&Pwrndq0a(Ro6jwOC9sx%HFB1)gkbOE zWng^qlA_vv`21LNA=HH$S9Q1{b6(B9*gh;MCpY2UFyVMn@S1DX-cf<6 zGpIpQ%)3}R7OM5z()sPR6i=N(ud~r(Eq$Xq5N#Vgf47b*fq7TgyXneH+ZhwFr`Q9_ z`zvl|AM`T1%G#GD@s>&rGe#&b5OhBhS{>x8+$TNeU53(`D*@JiC zFZSdz$9dt22q(0-EV6N|N4V0IA-qt*?xe@i!tI8x<@ZwPTh8XLi8MWegcE{L_KlFT zD~V6|=FPw)qDj4k4x((|hvRg|ol}w2YIe_6uoVmrVd+W@;7{ankq)nTHWBfOrY0s0 zNr+9j*=vm*5?7LLl1Qwdk`UTX@Qjc%7|2P-3`=h3hY6+FPKxvPNC}F~CCg~IMRpA+Z4=HhoS#Fdq4$%J!B95uVG%S66_{NyKE)=)#5OvTGO4)y`-e?IpTM? zu(Ny~lI!|2S8u|69TPRQzoM$w}2nfmvC^*?BxE=kS1GL?vubVTvfwZ%IxRZ0;Gb76j-DHd1 z$TmA%ylvds?R~)Rmu*1Smp6c&AGkm8y6_Iqw`q5pew=gykFMWtKEofh?Tfy|#V!|e z*s2HQ{z*?EjEQ?4cTI94FzI71|CI3_^fOg!@%c!``(0w4!Nr}vumNi|!O4pciV+K+ zHj2RuoD8PSA^5-7$t);=pmJpOUmWU9@3O&e0wp$yVh&{%{e@h zp(+{EdVfT{OJ-{GV z2n)m)?s#6|*YPTxfX^kLm%_;;Vq&M*hQqj;yHSBK{rRY48$55W@$nZ%L-z^X^m*U1 z$m?f#fhyS~8geC{zWeQOLvrt}mRAW48KN=>m{nHW@KR)fMd(%J8FxFqq0INCT$S~_ zV1%ysc>zM}y*}cjq!0RrESR4PJn!{Gn5NtTbFKzb4tC1h3}2A)PtnZ_B&3d3i^C4O z$i1aCj{d4azp2?{+#7=<~D+rv?Z4t12~KeagEJaY=a=T z{>A9l+3Qb^H(U5cI-+ln%&~vIAuPmE6z1molu^|x0O>}iBUr9Rp@Syfa}x&RtJ!WY zH)QbUj*HLV6cbp5U7?+yM=8WuAq^YqpmR_py#3rG*oRg@LQ^W3)rF>&lsf${% zV}yIpzhI=m!^LmiyjRvOPC#jQTFZROYGewcNVo9r6mSW%LhYHpo*N(Yq*tltsjhJ+ zUG(BKaa0Lgb0(rzUEYk(vP&>r16lJNTvB!aosRp#bu1BXQrW`f_;h47Xi){vx>wai z{1;;(MY^QsxNlpx`-{v#Ik{RrY1J?~ifYRpOiDT)5k8LvKk{BDQ zoV-WH@A88)Mbf92=)L2u)gL9QY|nr+pdE01rK|MIQqwM192%X&frGX6VmgcE5sY+% z6$Mk51aTtyk zJG~8!B%_0cz&&s_in*cR_gs@I!|!q06(rHR#_hAV0qYD?0L6kf;?Lricqir1+o#W> z<>*|ndQYQJE^O<=M^7j6@!)|Je#?`L@pxGVew22MGNq_pf@)iGVzO1Rc2GE@@G{=> z8-@8Og%k5fOInQ@h1sdAvT^P=v@Z`0<8y6%E$DLY7H` zW8_EGi7TH=W@UdH$CNnh2Y*A85)LMaj&Z~g;cyI7^Qhq5o7y!lIdj|N6FSH++bPJ! zv*|wZ_M9mK=`?hU#i*()Uh`E_Ch@6_Y#BX%$-im$#xeCTz6L2??EC5~_`r|R6KBG# zl&N`SL*@N9{Q#{~qsqe_F`8H&dZ|&`x{4tF>jk9ZwHaj+Wi6+JUjzTd5Z!s`6<=Lr zvs&;8i~gD##mhOd@F<%xJ+&(KUTuQpH+|&rKWG8(^EtS?6S3qSKvqwdU(G;nO~56$ z4C*f|ZS!Y}&`FKkrz{En`{UZz;Dc9^*2z3;gGIuK14hZMY&p4)+x;ag9QkFg9&cq( z{1zci_pU=MpO#9r)+|P%6?F>ms8#3{zg7vu<6TEL=WD%xF$rb6sBV6&SrN;5G;L0u zlr#C9A_+1MrQcV25H4Mz+G7N}5_tRL@I^{xQp&V{fOhyxL6Qk=CU!3*P@reV7wU_U zanF0WfWN+O5w3C4WZa{oWtca!Np4jP(lENR)c5%Xlk3Zaq?F|^`rpedxsPNX5CwEu@N~!GVXYTVEq*g`HR(*_D)4<_i1B} z;p)wKN$S+$HWXOa@o^$v>y2H4;%ZLjgmh6cX(NfFJ$^}qCyZG^6UY}h3e;yEEABfZ zvKVRC|3sY-<78ki2|r1abB2z;apQ^nhF@FOi_82XebJy&UrUy-mWFjBC~5z!R1v*i z;BkWw#knLsAsUlzUpbHJpXI~qYtlCwyW!>toa&oPu`UW|K-NvlL_DOZ+rnmWUGJy3 zH$P}UIxI@dc$B9u2F58SeO-`I9>G+y0W<49f?5Be`gni0Y%=po%Y!l0=;iY~?g*s= zd-e!WD$qV@D2{A>_itq43ZmB86HM*moIMzA=dUr0f( zI?TlN_Irv>+8)+g$JA)*YTc+GYFKqQoy9^hl~8_{A7QoHG%yRtM7_>)---*18Ow~l z9ag6ZaTV(ovZ_LKivIJvVd&q{!tk8TcbPO8=IH5VylJwfOaxCVK1cc{r77&&8NW-} zM+Q3ezqZMPM(!@;FG(C`o~Nct+z+Mc$_ss5-I+Dseo>=C@-+sC%#`BwTE36wjjOJ7 z8xMiq(h0vS-R#4ERW>HYo( zfhlb-1+`84@RUFN+Q@>4JK}MQGWRjB#A=*ha{BaN!eb4!W~RQAoV0wYN#0ESs?#*A zk`fgv`31)l3A%evK37UpK3@CO=p)}|_{JBm=03iuhvHY>pLKsPxCCUDi$)l+JW%y? z<7pV#<9^o)ZyhaP@1b9HM;;@Ji{X6IzgtM3iBFL}W7@^)8ny(E+GLgX*sw3P$vD}V zPX8S)$8#GrluPQ%(dK^J#Ph>9?pxkd!tvFKQmhenIXSP7Rr75c5#Ihi56`YiWVGud z>_|Z9xT;CCqinNq`%JUR?||l0g1$8K`{AQTq{noKq;&RCJ#GeW9Ai@4$ZuTR+s^nPPk-^J{J zt6+P}WPjYn&q)}}6N^NGO(yz@XqCn{tJs#mH{3oCO>8rlR!vm+^4_TljI%XgnLIzE zyy@2mN;WEU`i9)!9A^3{`||#?Mkl0&EHT~u*@rwuorc%6?NSyZ_pvjHeO@Sk*F4p@ zT_=hHn-3CXJgcFcBMyNs=0T(UPkJ6t0iU$&P&G7jp~VRZCvZv}kJu@5 za9slzABz+*m4l!XNSrl4sSh-q9pb!vmmb7WFxMsX6^6Eu)^S(G(tAfng>5Qqn;)x4wVGil z8D$sOw6k=GBO@+OfJjLAU5~@g6)m(~tx#Qczg>;Mic4jQ=d6JDXTAGV3BM3`ljg96Mvmb>^;AK0pbH|BFB_JGjtU*M>kl+2bv8Qy zo3(VR>g^LgN0~;^J&+8H#?A$+xqTz6qf=3q{|@fOQ8{4=C>rf#AM16ZR;0$2IucwQ z8|~`gwHVE6~87d6A_r#D9GfL9bX1)xKgmx8^@?*6cBP*oswek%? zDqQCU&)yF{WZX^30_4ZArtQVLkODsmJZcXyr>UR%W_5ZJjJ}_%Dbgp@zt&6zGtt;&@b;KV^z-G>LUtx<_Wf@-UZA`X)862ibVDot3|8zr(e(2av9D z>S%D8X%=u6OVB$JJhHfzM}h>7oZ*}k!VQ5^6qHsbAp9~Onc@AoG0W(NFrKB0*rA*3 z_97Ms)k=pDz9%~z&wNP@uzp4~sl~X)5{wlre2*_tS&&+)p;`%79JNK0NWsm-oB*aG zTGd}`oaAfPHKU#!?WtmtoQxl8IhGPcCP{-E^r@i1>+0IK!?dImUKLk$e|*`&OsUhd zwa6-oRKD;il`6@akX&aPPEh={g%kUzUnh|d#>}B*)rL>kk`K7_|5H8(^Q`iTL$_my)K!+V&K3rHk*2(cJIK7@K z<*}MQ)p`{QtqZw}-oTJ1i3R#XIh3wcV9*B$gWbY*sm&Nw);g9s&VnGvXCp^*VbOZq zRFTaQw{@5v_kz5aQ6Sgc)J?7$m=b@)ekkho)<_?Srxl)>q%A7h{!Owd^HLd zrcg^fC$3w*#zs2@0s+dnIL}6N6tZZ2uYXDY#eXrnE9r}6?jxZs3P|F9Cc7MBX!RAj z-4&@X3mS*9`c5j0Ort;p8f+tHX^lXO+SgTlzt-->7uaV?B@=7(1SvRIn|^3zELGf9Db#c6~^Vra^=`OO$LBLEKoXkWwow88l4(`!83 zG~7?Phk(O%+_j_A{WU-h?3D5C_iq=iz{6WS>Wz#`-v2&!;r~D}HSIsek@nnbt&BMG zrpk_5fBbx8)w^mm4*!0&E7wwF@3rnX`;5pN5=Yz^!AThO!^D;q?87EeVWfXB6x0FC(Hut za+#p(b^DKdG=*rbSf7s}Wz9mEyXj3*oAXK;Wf-UDEvRucgq9|AOEy~qYjxN;6`A~A zNUc8J?Z=7Sd>J%Q!0Lx5v8?cmI&Zw5+1@L=mfE7*#iN@rXRFA}e$5QU*o3O!SazFc z0>2iUB(2L7@JTG^prfYP+X9S4l|PndeB%V^kb6`Q_l1*oqqKUUTXscq%s}ZW>qeRCEyub&bMxvuCEnu zKD)#n;L~JC6pz85?rDzanko7r21^*C3NQ|ok2UJkd2z3oA;JYgCE;@hT6M6v*!(?M zstgZJid#@nChS)}_zSpk1M@h_8GD;i0q80+@<=?#e91nxJU&w7cxqPl;xCwirfJzm49qAzky2N zz3K}lbb%a@vGsFCM#(QrksT$$GDE^~><=|Zm(xei-wpEwi`Ql7;cchnXAYS`EVO{wmq~jBVPfRPwJi@*^(G70L#6 z`GrQeZ+c0+@JTt;x<8M9Gn!47J>mxR^cH;ys(3kSn%0E#?w_*(=Sn?v%4DA6VCnW^jp>*uVmL*MQ#WCfP$cer+JLQ=i^C(=aphkTohC8%iIEY;v3 zQ=EN0?UUR32#I(tf0=m3^TBbP0Otw?v4D5(ViOTXC>^m9oJKPKZyF#_>VvC*1t3AK z8lP=TxvVyRy5C|QD?r3&ou4!JIx*+t#_T{Sy1?!GlGnK0ERR_ce<;p)^qbrH3rBHb zgQg5V|HaAX(cRctT8@+0+&7OFvL&UGwNVNLfQi;cZ~x5<7~f5$s2@;BR&}xa z8$N7`KR|A`FZa|K^7wc|OzX08y_yrFbx&rXcy_k=S7KStuxiOUEgLOCDm|g#-E`0L z#dIXR=p|RPP@j^g{sxUg)3SN=ysHQ-oIP3~JE7p~@?v(tb{@qOaTc!%x@r(x-jhu{6fN1U{-3Ls#h?q-1}aB9jK_PzN7E*0Fv`tl>{=qPceoQ^3sYZReLlmSr71xo$<6C=HD=WT;5xviy_B;UQ zE>#3t%-Uu+jS=(B7l}SCPn)K&vM%~6G(g7{Q(9?*iT8I&*dTgDF{TFxf1v2hLh zr4LTNKUx5?Gjj54gkVV4tLDw&4bB*pvg7;;o1fq@^BzJ1Yt5j*r#A{b1a9YM`G6fe ze$>wf4!&KTVxQAbKO^hdJ?Q)qgRq8uZUC!KzYw%nK^6LImzKXzU3eku-e#d2uU3_Q zRh0Mli(NGwP}b+^u8wGfAEAr>hH0Y#?)09WGg8OiU9unjOr3;b^jUYQlOC`0A2~N2 zxL7s5%?Sg|{On$&7BT4~zu`54l9rmrQB~)1PjPtMvbK*5)yzlsz0#_!tdeNc5 z7WDp8IXSMl;<>PRJ^1zDOv0;|-hcU^{s$6kp-8K7002Dmu%wE~GYUhM$z7q}GFXgC zZ@BVoex5$l?yW}-*HUzfI#`&1~=jYOw3{a=@i zh0gI%hys0BN#to!uSERsHuf(rYsw*h?%7O+iI!0fd%yhzqB!aEw$?UPbKf+f6ouU$h{46IKkfxs|@DX?Z*6{|J>_n7}j~Sz9pId_neH9 zK&WlZ3}>=2AYxBV_0t#{8I1c^!3uS+H*RFx_xY2J&wu>0jtwvl>-Q8N;dkGkxf}Ub z-i{E7JQoltBA;fkn-=ycp(->?c)6l-PW{O9lOw>V8ZZ9aP8RQP#Y@>$7Mi{#Z}G*9 z9K~rV2`!X^BjWX$U4sW>e@jj9pNy=Mjn|XFkpgRZNWd8R_vB{V@z>ce5!Ya6;=onm zaQhczXHNr?mt%8!;U#pJ%XSUB^MW+l2y`9)=XoL)fJ|KUj`YB+8RA*gt{BV3$$1?q zU0rl_BaAMas`RI@;^v2BdDpZ#HJ7G6R?L}XinnyvqBztX^cg6RlPQlK9~?R zAIQY75%c5HCr8}pJ198kr^X-3$WC969e{7=u8&DP)uI|ZYS=Km*8bkfVU$jE>6g0W zd0;F(U*RZ=4p8|&2tQSoRHLJ3AFl$JrlQ1^6fao*Pc_@6DbFNG96F>dYUz`g=rhXe zgUO*bkB>p;2KwMAO;!ck4!cCasbP7FspESVSa*fB>r5Jc11*#Y6wKM^sL z#ApX%Q`vdt z?b(Bn2Xis43brDiICR6<#4W@M^=HI|kEBIHp!Zw^G{!VY%z&2N>V(fS)>P?z)IfR=X<)oS zNB*Po1@t#D&{@wD;Y2~}ZVydyO_6GPyLFXXYBCN}{%$-5^8}B&2EJ0QNaBZCX-K(% z587(N&Y9rx(T|O7RJ7)tB4AWPPzpoYCD9)ox*2Q`X^xOxw3&K#j!-Vmu;w=Os;N*zv?XrTZNWUNi2*v*p- z6Fq7nEjMJr>rK_-0J9#cZHghAO zqrz)#6S^<%^T^boXFTNqNJ>CyP;wr*3sNHsE3b?%i0Ks2Rv|fEw?km$9gYPTD<7$$ zxrl&BzYvE#ad-izQD722`Gpyh*HJCDG36)b z!3JBSX4F=pwZjG#ySvu*FBW+Y1Y0Ay{3I-HpPC%(myOTJ6(UH>flHz#ymcT%4wkfq zM|WhGTnB3nw&%DV+mUZdWnslErfHw32CSLt?}!UdS30|zg!>$tWXetE-{z^RjfQ^y*TOwJKvAi~)ENE)1l{IaP~mF5W|l?T*^gcS_L3{51j< zB7*qe+{nD!078^9pFgm@n=d^Dl(rkDkA#d=B7G2=vvHiDoV@#E#XEm$LLHlEKascB z!JoTS26CF;5m3e5#e9mZ7~mAi^&{ek;*mkx zrr`|^Rg}e|vBG1L+RML@PGQmUvDmm|x5T8#@buWHi4mEhQDlW8+=XO77T~i|>GC3r z>eA;AA-BfbXJzyiWQ0twURHE8a@4idu@Sb>5>%6qk{OeYLe(^0OV`Tj5!Zl=brd=ebhm8uT_w4e9j(o(RDUv_7$@yz)fpPb8T{}CUv02Dg_zrh z@EHMonBs*?$I{&{i!~9q&d9ep_9qgroZ1~oX`Y;RoS0_cQ4x z6XXLHgWB6}L&F7`R_9ThY2q-(d+$Vk%0Wj5e$DOZ-+y^yfZxOD*({4?#Vj2?nPSQv zo5&sWt>w9~j~#35E}X(#feY(s<3TJ4n8DNqM*nYfqsBv9ReCEW-(d0sPVDM>72IsBdp&dq$I;%D z9}C)uLCJE}P!1AbfAqKbz8fPJCT>v_={*Ge0v8_VRk4Vth%I!FFF08CDIMS*jLoLt zr*&$eqojL6IID%^stEe(q^K5V{n6FsIf9P)H=xkS1>6qvFn@!li?KR1=WcxFx~Sz) zul%|KOf+%MfOdHy@X$Sq8l<0L4PFpQWX%UZ#WI=_-mMIFHu)DLveN0KHbrVRPIhc8 zcVO@up*p$mojutFu5RGNgHxleK7O#%*ym}&szxVSi$DO0F5J;_fR7f>U?9!Q(JHa% zd%q6Yk;97U*A;PGOyy=_)H9b`iYJdn1`q5v(7ze23btSsZV0spr)f$UPfYAEdJP>g zDZExW$-|<)Ub-_!%$_w*#rMp`jF@K|**Wie)bpngTU@Wq{qsYG?_VfBfd~;-gF9;` z(H83SUv9QC^`@_OuNZL^xO#9=pQ_gGUiP`Qj_oeLXZ{F5Se6{2$G&8PY!p>IYUeC1 zyzq%s1`qOW3{~!N3;&z_l=)Y@{=}{AHpvcjHT137L%oit!YSkXug_#*;k7M?MPFa_ zM@uCw=B+uH5d3U>^=C@PwlWM-Z~FOAlf{o{&auH z#BR+x+EDQWyD51uX-8oBCwZ0+M`@>x{pBSgtun8@kf2c8$s_lbMPI2dPjqRDA}q-2 z^M68`&0acW2JT^I7*CBygXs$*m*OO&Pj`8wL56-Z}8jfIWE zC?R!ouU5E%)BOr5>QQP2t`?qHUE93zzm$)y#%4lpUSI7zZl9%jUiObz9Rwz8vsvA= zwveQ1YKO<}u>6v#ToU(CQg$o%m?r8wtI4w3FUkF6s3{XBX86E_F!E%C0;IMH92a-k z38sbzj@?el^ew}W(vh^xAa z8)#dIi^siEm)NtU{ah7kYF(LDQXar90lyyiBLK6P88e14k5}lM^XpOSoj})t#{HvM z)}=x#ORI)5?~V)|)e-JW*Jm02{D~x^WE1--S_*+LBAbP(ZGJH35wIQSQ>XF8Xm_{E zx~GM3bTE|Nt&Ht2*70S!Gr=t}<+VF5)jnuf)0aidFApxg%yINe7F>+o3j$b}L%DcM z;BnCg^TERU>}hccoX`Q$z~6VDTQ4BPkwIeC)kyLPLwfaBKvP*$wi(aufEql4G~OLj zggH$=i?k`f;JclNhBwXVOJJajTVLt~M-vkvI-oKwGSm6<}hHO(v z#o)d5D#+vtA(LwEzx;RouDgq4hgg#+r*zJ&-es|rZh}egWI61|+Hh@YQ}VidDZdAu z-F`ku5E*9JYJ2Y5whyT{UAS2L3tNEQ)IJiq}Sha zT+Jq}60hl+=~ndPD-FvzH9o1T>Ng%t!_OS8jcW~x#lf?Mwq}s3d=Nr9ad{?k5(>zt zGD){j^+oC5F$;g4m?+LKDQKg!A1vjQNmR(SQS-H#ph7FiXXx7s+SYMs8qCL3;@#7T zqX6C%M=2V%f=TiX1(rF(X>&8%o;YBIw+L&eTOp2(bX7M94*!bdZ9%_o$>4ALIFfu> znwqh=yf3pBie-;m8RpW=rdA9ML28f+rHa72HFi104iv>O~S4u_k0r;LDr(4|^)%}25 zRd1x?b5EJS_+ERRn$AkNZo9{)j5Z#<<`#}BvfbIYXpfl}%g=%}yOGezs4)K+OdRi} z$sOHb@RNAUY;Eqr%vQiwlB-mrQQIA1{l#lf)jGsxHk}YnPj(5ZA5d*9_PhTf5aG7F zRQUoqJV`Uzf03B^`@%bvIZ8WcORSLmONiZ=4GzjqC*9!@vyajXhOtB)SaKp~x)OqE zbJ)1pULf=7b<@hVG#v^2$iI%dx$km;r6%}i=cn5lL=FF{QuY?NOLt89X3a2;@`g>4 z_tbhwqST9|5r=~Tp2NrS>DVg&?0K&@o#O9GW&in>liXiRtlBvg@Tk!lB^4;!#$Vyf+ba7Nr(&5xYQw{{BZ1x>M^gNAY6pN{se#Kx#uz5 z;LWwOrj}flr0Q@DSBn-yI*x3M7Gx$+3bf4n=UPjuIxI85sLS7=CNMOw&4KJvp}3F- z1EM8#(tOK64z1Gs&h0=IuhBcsN`K~L>F1?h$>G7x%$=kv#-Q5Fqe}NHq9j2&Hcu>K zRfw$)(%ddm3}rUOOR7z9hR{kIaxn)l1wv%xe#1;>kd~S`!Y;Lmp;986KWWA(<-f;S zOm%7DcVft{Ent%HYbqx(c(9B)*m*sgsew+_pQW$I;P}cAKy=Rw3895MyOkPyyWMc& zXn}nLoiL0HWS#t0NzUQ15Yh>*vJjO)p0p4K0xmy~=8=#rOPn?y$yIs=@>b+2B&JW* zpk>E&QacTqjnBJ`@`K=VzhtT}Rwbv&}-7ay>8Z_;)Oj_WsEtVc{uyUyeHnltywUK)>v9T^w2`#PdN$mAR(KcK<%lGmvsOi&Fk ziq0il7OeydgCPTOuNnl{7C^;erp2+3sK)NKHPp(;_LUT!&E_=9x<`19{PMGKGl{Y( z?KaJWR&|YvnJAI+Bfp}{cs+Osgogr*a-M7yvPu)@LKlGIBX^Mr=w^Ay^qG<(hP zefGso5hf&buit^*&YKoHmcTRP$`KlUt-&A8hx7!E3`N&+R~1v-_c%!BzO~qB7OAp;!W5 zx|y`T^OW>3I6P76*D%C9pb3A}aA&D2^?>?cf{G3`w>rF4=|jizT}xnNa0|Gl{17y@ z0a*&JJ+6Ep1FHn{w@AyIJKeI{A`?cIN`BxdRCMtTUp_hGw2eCsJ4vEGTjD$ZWs|?; zrdrbP0>tC;#iuZ_r@R@&xs4&F*`e$^dq-nJ`S|u7P-u{d6-?PSh+9dO1tk~*0Zk}} zxNvZ((y58G3CRbkqfLjRhpB^?9tru;{2hF$Mma<#ha^}SVvMwB{KE@k9pZg6JhlVO zV)$RUKNf(=L#h9NF8^(?LcO##lmwbs!hF4#$r>;9gTJ=hNNuyu9CK*VtOrX<(R{Vq zAc}{Sr)!(i<0UoCFJkT|;!V>fng`VVtOz{XxbpGEwn}h&nFGDs-=BzsZ*4GAgYzMU zaB{R1M%E3g!{BYe=9e0nkr*lxC=qNE>Pb{27aN%1Ks2p9z^9qGSUya&Sd_+F1wl1@!=UgSZU>+bh$p+#@{bru^oGN=u(6yJj&L z%U9@wSUbTG(Wy4=?@cJ##in>X%aJ3!=+qOP$ zs3>C4e-Wz)X&?qKmBe(F9ON`Rvj1^{T=%sYv;3)+R4;8;9+AZz|dl&cLO$Dm37 zPw2HSli?i>S@*f9`HZ9)!Frf=>xZ3abnU*NU4Yf|pa22jUQQpPrd~g)Ao_Ak%4L+6 z`}w^snoh%o zTP^J17q}0+1j9}3|C*Plv3n<2Iuo-(^ql_VPF}G)^}61*Bu|FWIDgYf*f9K#zM(Vg zKMv0Ed9*glX%?TqPg_WEqivRU^O|wrdt`CkEXupKdQu~z>>7>@&BkBHh85qMM#aY( zV|2^Q%rSNie8qHF9#u0ZZ{Dpbj6K#MA=lU(i1{d#L2SNnNj+P&Zh3*9k3fn`NIRvj znisGJg*=xk3sl7?Om{-j$;5b$JgG&S5~-LY;PM6|3?-uT5GFuS?a$LdcU_mg`@nJUI3Ouas2XbwOD*hFwqUiTl>O$_k z_#W2_QG69?M2r6)rp~gV3HJ~8V|3@}95I@~7%51N&Jm*o28;&j?(Xi8Zd4j1ltxNg zLQpzHf6^cZ$8*k;|68~p-QTM|-`Zy?-_Cq*FE%R#rPKE`mgRh?dt+6Jt*KgpNtpIa zZd42=MptyTcU5*+2paeBZ7jTu!d^)gv5 zOv9R2iMtVp&p!Owr0Nq99tSzkgZ>q{mbh1At$#Vlh)f#1wg7E=;qmzB{;G)x8+wx9roNZBU4$ zwo_a2IOLCu9i>*^O{ z-sQ`gs;KZ!jJ>*()#a9T>Ybb$QM%odUA@g#w?peb`SwaL-iXMGd%~tZlyJ0_bqp3 zg&~UOZA?a+ij1Zb0I5Wj%`n9rN+k3HKWPM!e|aS@w%&O*CI9`RM&Q6c&!D+UF@ah> z2k7*P0nEha<9?}(@qe<>=qi)sBB@ht!WWVDqv#j)REsNh!5ma(>+vQn!vmL(-UntY zU{XX|qIafIqxkxJnhP$*Vqvk*zu9)9tMhRKDLg)7gV?B@^_3ptBNOcBKeejAjWq{| zW-M8^}ydhN&MGi4h7sKWJ= zy)?9t#HC)}PKH8}q%owyJc|0~(J@2HqLx|-Pmp(2G^{gK@iZXc0UFiZ3qOg&N~`|B z4e8~fmjbZUC_W@5stALSs5j(TB9b0ltThCX=qG7yNUhGTJ~#9mdGQkG?iI##PQ;(1 zP}_?49f^akKu?e!znCPaQoAQpHb^3IPg4E&vbo5pa98B<&LjB_d{xlrd%-pjUU8)$bMRRE5s&0}3i40h2YB}DnO;EH>^QmF7-h1;#^zDRh z+Ga@*pW)U(k*)|Q%zz)-Pm6QmiB2?t!><{}8gM)9-gyk_Z(~AO*c5J=J zI!|^EI&N;4)}GEfwvRaERu}n7J8$fSbgSZd+T=%RGoY+dE}HjfPh&^7ENvR$#5X(r zSF&kdFwc0B{YI&;{`AOm|fqTrtU15OIb82(U`x*6R?G! z?eOOB*Qdb$1njYCNXR|;cAuQdEi|+d7l4i;$w;PXAg-;Qk04%2aPW)H<$W`)m!|8` z89BP;c}4Je!)HI@9-X;koEt$7+ctmX*Hp&5+th7RGn1yYxU;zO6>jSvdSOzwUVmTY zpd!2uf#)9r7Q*9YUyivR4pECx3D{b%9=@r&*P#5$`+fJFuwU{;heozT2b*0$DpGRP zkFXVItwC~Nm!2QO4>7FPdvNO_$kel>Q<<~;u4b+n7^gB)-Jh2~&awa1vQ5_Y^gl)E zdC%vlFdP-GB==N1fyuJ$rOFheF-8E(X4kwCvQ!c!Rz;oLzcmN6sY*U{DZRPd4e0xl z+4l`$OJ+Pk9pS@Y*8wiXG@@SzN{6=|&sH0O?vKQ~nRlmjf|9!sJzOM~J%b{R z_$RK26ohf_vRt~FPtQNLk&#&RKGRgUsbQs@#Rz0~RI>Y$-waP7Tuqki7HXSCyaeR^ zbF8x$z;-<%M2jIhr8EC|6zz&7seegNlP8VBma260cdZZA0f~@}Q3v2UBS+!cHO@~O zc#ddf0=PoofOHyS?4VJwr(Vo(3Ce!!xrv|g_*!(wJI3ka68KzoB7K!O36M`Abcse+Os?71;An;Eg@EcI}-pkS}0!iG4|&^Qn1&z9p~u^4!OgUGE)@#xnc*rKS9Pq0{dVyM}Q(Q*nGor@p<^+_q(;Taci|xNu16SSvakN1?fp zT5V2AMLg+Ju|W|dPPe{lbUUm#K50d}>1~H1!3BJ$6(l*hH0rpXB|wV`MNxbnR@OpI zhZXN{hhgtjeR|sE1oNF1)RJe`o=6`*#t3vKxK*n1(+Ga)w60NxC>+syj$85WNj}oq zJI4ViU{=Q$!Od}z4+KaD13u#^5?$(?GY)J>fo`=A$#RFEld&+3qF=RW*tY<~gapym zQRL*kBMxV7iIbd&I3W9@sm-_&!d}zZC*0-^0h4+zn8WJ1Av+b2G>xOO?`5Yb_ml=~GY+mnt9u1_|HLm{SPr)9G-h_tX6gl0fQ3h?b7mYEFXD@f z!89Y-Zov~maZ+hShcfjY@sBXhW&x$O&b$ZnY?^0Qo;ktH(@-Ss`0Cd}lf?XLZ=e{3-~Uj7laOR!M@Y71KmADP25QY&C-3 zOHo+{;Lk%yU`P*0h)@w&lGeuRK_rSHX8UaO>)8tx6K_9a@)0$IiHW8RZC^h-a5zKa0%bsQ;*X-$?#I z*w9qmWkE&lEdJ!J0T_Bvv?AmE-|A}%34>oF-tGkw%&m<(0I{gA4YC_4V{!e$4&Jlb z9Bva;96PGH2L&I1GitNn%B>#8-3?n>ls4VozZRQC7)(ATZ4deds-v9Rd*#XA?(hY9^pDmyv zkiGV?40glBgG|m3e0J}(zrw6xH>;W>bvd9;{D(*GOPa$vR#*YMkfPwF6A5Cda*LyB z>ffO=C!HbQguTuyNgL<8S>ZuP^*-lry%EOkB}H=pCFVSv4bBW zFxxXLJKr-O7?K@akW-LHmGiv1tQeVFRM}WnT$A;(pr*JoDh)#-0sPk`DDKA|9w-Kk z0G)w=n&G#@Q-j%~L(@aKSs#$^#z&W)kB(37U@y+S#rt&NN!;T{x`VqsczH0mpKv~K zdE<%Kxp28Q@x2(rryz>+{6KoSuzqqIiuf^aV!fgDj;u{8nI)MHqs65VUVErumqN@C|Z9 z8DnA9025VoY}ymYkIY&co(n)KpdRcB&`~xGgUh$Dwq~=b!`{|T*#Q&)y&5XsCA($h&u*NVv^<0qI{QBBv{lGJGBLa zfqaob_;;#IBV+f&w16Kw*u-K&Y5FBTag{ka%DIPkW=6uI`!fZRcwcK>M6J{*dB9;* zNDYb)m&R5M?kiboIU5Zuj>n?OWWhbs@NKKwC{8S{ukZq^_zIUPcBkKSN9Eq-4buzC zRDY^#bE?8YYXR0tu?m4JhX~`>Y#)92<6GkH()}>^bS{rxV}~^sAuBkAhAqG}&Vyt^ zz{%(5Wr{gOsvF+QR4Rs_hYTqHjMp^ww(LqwX>&)Z8u^rPpB&pmqkm}$UOO=5r6>$c zxyiD!)^n>dyAM}RP`fVHc}cJG-tQ*kk7&M zxM%-|RzbBVl8?SKNL>jc@lDC~^mK#AV<#Zwc} zb)dx#UZLqVo;T4o*(A(1WXM=5{<1hdGXxbZ#Ix&%&iVAijy>6heUF*0oeELFRO_%_ zQszx)lUN$d+BPtqD2c?yh(HD*;T zrvh(%Ebmgtvi7z!`wcQLY5ZKGOWFNkIDKp2r5VsTja58zOY_bu)!C;*(pUQB<`?>Q z)1UtxS49ClURvGpd(cTduSW?PiUU}I>ozSG^9D;gJ)gDpA7bP{EKSk%`&~PXu>lA9 zA1Ow*kJbyCHB?-&>~;%|0MK}qAWYPgraVmXN&`~yJH4H(f~t7ipw>%Wm-)V^_80a; zfQk1AyuA_(D<1#Y&nffQ7p8BLC4e^?ubjHH)QLu6g<}}a;GXGEzC8J5p(}*OOA8yL z^f}}LXcbP*D}w*%;dmA9|7ll<*(}rycMCqoyKwZr`CMNZRq^@4N$pa0y_r52%JG4l zVZ_cf?Y_OfG_cjn^o#~0WuI!2hyaiUYR0UrM<#wFq5j1Ffk!n_R=9mZY(Y^2ixwz1 zFSxJzpSt1mlgScHmn&Sg5)f@!T~a>l7F6H7S=KjB#JBks;k-X~?ky?X=l9y|5sU03 zHMgUWotIrljN~GEWyEQYP;DM;CwNovdV5DGv;9Gl40<_T66eZRgiWqcdZhd`ZwW%S zr)5P|pGo1TCA_rv(WA~b+IQOxn%9!56#se5k zf}QeCd#rVrI-b8HC4XdFrJ1}0;Uo30%a`Q$^4hqvtlzS0L%tZ(InkU7wf@sIab8-q zaI06-@f`3D#I}@AP&=D6OV%j)A%P z&5QodIs-@Wvh7}c7t}bJEYQh&0gN6ppUYQ3;XyJc*%xU^b^z~(rDaO&TjSmvlX=On z&BLP*uL|!)ni`!DGP6a_{7{IN9j`~8aI))YynUdbSex<+X*nRtF!iTkoCNYrh_d^o zghc+1;Jf^HeveL~?ond&et|6QO#H%&ORq)79}>I0_}JfkUn}`E?4{4Z@`i};dITwl znGEe7&(*CnDS?V>5y|>}J3mY854+{f)s_B!uq+K1Vq`?}d0JUqm=O{F4mYcF+1N8V z&C$?JvR;DLf9r^Y>|*4-Y8Z-l2>q?>_die;zx$ZYM1^H!yegwOAw_iTVV>j|0_xvz zk!;|OuBpkoP;g63JJ6p7r3a~5qiKn}zW38J3Q5o|22EFmKlj|Gb5_UNeHt96>sTAdunL_PQ~_XTDFLk{Hdi%kc(Iq*8x9qb3g1y*FDXore)eD+P9*(_j4!4fv5}ir9=Tinsj2Y=4K$_u%=7L}1bZKt7&Ta8LQq7-^B`KSCE=_E=C#60r~| zUWjM&i-z5$%UZmOs!vtxT>*a}Ecme?!u?pV0IAF9<8TZyD)1v9j6o3&aglXV;CY8L z?URyF8bR+^@JEA`Fk+vK4Y%{8Ch!0RZE}4Eh(}M!0esOL8iSHp4nqPE#}z$Kw0!Cw z;dQjlTD|xOC?wdAngs$4!sqzdV-krCzuTvB^(L|ErggoDtO85Q;IVDta8vKgmsc~{ zuIYsiJC32KuapV5ypVrC+D)?4+^?$T#Rm)LvZCHgKE2Y(aM01j4q5Qygx!W*a|`I< zJetY*aPZTFuPM<8s|k{0v^cMAKw{RW_8v8zdY+sJ*<*q#d-^&FDB*3O#DYrTrA@D+ z?`}`>4ZhOlp0}oA^sp*Yze=ZW++yQ`g%p`E2nNVq@rF-6v2*lY9$^f^VqGQBKjR_^ zW_Nq(6*D3gcM->M5yNmNE=VB361oEB1rhsJYGzEzKDJYKEk+!~C7Fr)UP`6R1d<-@ z5)o0W<7d0;9$A>$A_c~&e&5SbRC$Uk=+t&XH=WehYuUGvcqfkP`!(7lH-5z3gcFQ#8}GWCDdu@6Jz9Zy(|23yTx*3R&5+n65Ll6w5sf zDFaYRSL0UKm3i@T-2%WNPxt-r{n57^1MM{P#1#eW=t2BuY_&eR3g1 zBO#9DA^-j(JBweZ_E4*+&3f6`fvyiPs~cdmZVaI#dPJ$T#|7l% zzbFPLG~e=NIGTHzM=%U=C31Psb`TbKCOzqlo{X1a4nVpr$I9X30PfX+k!3`N06%_U zKy6sQ7-0O~53oZyGG>K6B5BlD?VHz-LnEGoALe(&^nBz|Q)My{%;{XJ+E7swCt~Z& zJ1xc^1!puPbOWU25}D+AF@=bsFa7JfZhar90$=mTF2cO(#ohBF0mep}13=LWsATG{ zhQ*E7axkaIp5%4{%-Th1!P{rQmmHs#>+3>@Wln6_d+d?h=r%(|)je})QpiMy1beTC zyS?qXH_b`BIzNudtwAQ?L(~sd_FhEUs|I=!CrSl#kH}q1?ennepCu0a27A7`&e4L) zNG5GSISD?on`&I32}y=a@`SPwVv}W}immL{H=jVG`O5dbruPpJ8%u7+rMjzNhuPIN zxxxWW(0Hi}(Pp0Joob5=5+yb~?=QT*jyYU3%i{m|w+wo)aW z%MJwII%@7ckbSmmnBvzsU`Tb0!Y^1T&tqP9^eGD?Xron1YBz3sh(BYqv?5#xk!M&6|pcC-U#yT^Lobj)m+;o@63 zc3}hhf!Ie!9e99a-~hme@Z=D?eXs5I>c^G%%+>cc;;$Q{C`WcV9PA%+?I;_TLGR_S zZl)$&SaE)jV`yq zon|E10a-hMXmNsf4IW~>60$E{dXv>?zm5Y57Cll0vHNOg-W12P( za9g{zwXJgBMjvhUEedD{pJeyU%sFXcoYss-zOjVD%$yfJc9}#3Bj;Qw+>_7jzu$`t z-zTG9;tg!mfEn0F0FPG3iFiz=cF!heq{&vrv*pDv4qhnZ-g1$#l>EF>ktZXIL}1xO z@v7>Vuy_ItVxH_qBKNO5XbsVF@r=UJH`Gc%912gJ^e0~%hM=NkYkGmBsdvnp>~Z%C zP!1|%1AX}xiF8>}rLMfJQz6bQfSmsZx85I5BYU$u-^6t_fxpUj;_M3@*tDNLtB0Y6 zOGx^JwMasfC;grDG{GUYMl5P?IT8&b><>pWqc16|HyyTgx)p+jh?I{sFZp_pZ5@Mo z*3~{x5}iPW#%g&3CElnvIN?e~zHrLYRM@C&$C0ix^x8!@$7;(Z(q@bP+#fCP<+q;; zSxO8llWG-SWO>9~+;pWlu<_MV$(^A9*IVJC6*YyKZJ`KujE zvW=>{?1eH{G^fxh?yA+N*Xg2kN8;`ZPVDcq>XB`DwmK1|ln^PsK^hZhGg>viw}-#M zq&}kI#V^F|r{D*MDDUY)XoMUr%h$j}=EV@zSv$%2Wqi_d4@0m_nu1n#SI(Q&qp|Pf zU%TwU$vk2^`~$WO)jC4U!#q%$IJgUmFdifQVoaB@YY8@`%SZDf(mzwV3?5~oHbwjC zAsAJ(4$5J|++lXTw**wMWa~{$SUq8`8E`4l=HazP&QZ6*7Vb?Ne>T7Y&D_GXpxBate$Q`^% zK)N_9WfuqfeqiY#S5XMG{JuC-bFXOGtMcX;qnA{Yh1ZHJ11E4~5=az!kIbAM`sT+F zqNk?d%^X_cLPwL8PRBe>mlmZO6cF>mlpU6$v3O!Xl!-u%i1jAu&jzmjG!Z#hkw^%` zCN|PYA79~u+Fc}xlIkY|$P~zEn$F~Bl;$pX_CepH4#7Uvg!JLZW$j#e+EQ5ww?}yy z8IJ%*Kygx9yKisK7UrA6T3e=WJGDxvj)7P^5rJ*DZEChUg7$K8)lNYHp7DoVOE+up zp|_6s^^O{V9l8W`&3iYZNUVWc+Fm_>4-eHi_PeNJOL2&bELnIR?AxrHwS*v6?E|D6 zyCr1*-OaqdSromrOBx_*%ulC@HGa}K2@8!Q#yJ=dE;P!-g6_t#_Ex5?MQRg0_l7)` z!;xBqe!2VzRBh16REP8HUcB0%i^GXAlU&{*uP`J3sQ@uMJEeU+mBUEdPzC1z0KQ}NzEx9xHVJ}2nMk#GEI8JSz%2{GDPXxrYG9i^_A6CSk zoCu~i&Wr8VoX2HlHaQzT>(qK+9_N^+R8HS#e6Ks_#r(9^6qy6B#f{5q6p0p z#%YQjMeAa3okZ@hqLa*TI^yWXGWB#Qes!8RQf!ZP`pafuMeT}VksKBUJZ2fN<|I(z z|Hj9XP{6T_JgBC>I?Rif+yP_cyP8Licsa?=PR~uCM~=zi9T*Y5V!# ztT?G`=g*}~X7d1=wQp9Z;cPv>*Mpj3O*HtDSe_Wz(qpkxVNZ#fnx`^3{jODsYVqn? z?X$&^go*aA3}?L`J38Q@g9a}x@%f&DaO(N0Z3jtF<~g*!Bm$7c(pdH6X(l~00*x|X zrv_DF*6WF^&)H*o;c<+f;xD<1s~akKO<0d&#A>mG`aXJ8X=+r3pIX@`G3W=k&^ljr z*L8Shx-nQ5VarI1I$rKM`|9Yiu65+KAaI^Q+qd2{_&~rpQzgcPx{u_8Hp(8qjo4v! z&qfxo;r&r&wv9<1)?^a$UElEAv$xOs3F`Hz!6IpYxN---_8l;yjw^Nn4&ikxyz)t2 z@z^>m*d=kAPG+-}iAqk!)D49ga}OR^huyWyZkuB)!?LC2bA1**HI(%So#C!@8!AE& zg^Rb);)*J^B|@-k=Ze!k*H-&7RFd*~^Q8c?lSi_?hI|>lRK-C-UXE{LV?JN5cta`pGm39&IbwDjffbJ6QwB}}jASD7{@yrqXnpG^2@U#w4c zqOhjFw%2_Vg-vD6L9{`yuzeSGr53WD6KgEOn#>Hv*QWZKeGgfCQcr&+FM?Nqu;gCP z07D(8yD(5%@T|crh{&=c%cK2}UkNHcQ2rABBE0GQPTQtD3*6*GZQ_UbXSVS~@3%{O z)9W5hop!af{C?5cnNVbcB0CF!;kn}rl#Y(=g# zmGw8SE}%(o6eZpp59_Jk0fK&MLrl%Pjsou{Y9h|{u^#z`6a(mBKB>DdBFe@BSWK(O z?)z=jRg(^!0c`6?p*ZR%EjQ2K9wMrj++?`r#PgqL$@nN5T5 z&*tYJJIy0sZYWp65yGaV84A%{-RJw|?ck3ll#30Grsf1xYo7NYbL*g$;=C*d7y?g> zDrJJul~xb8zyEc3KaWL7n-B2LUbmY^*FGHk-VsUTsMpQ`fzzcLscRfQp?Bo5x=?Fb z4ET#AG5Uw->5z}0;^@K(kHdu|jJrA4@PEO51n@m|wbP-(FcD!`VyJPzU zVZWjPV-T9=h4zY-3<@8Wzg_ba`RaG>$1Ko*Ywq~>^zlGYZG?fRU8H`6Z$u<*jK{xj zv5I8by$S1hA|9u>p|`KSo%h;^06(YhE)|nWAhFOPQwG`zO3B%irF21{$E}=FtgJuh z;Jnfn!I=5XmIApM>+q$=#|_44RQ-seH$bxA$U#(+Q?bCp7^qVvS%58h5kcnTd*MM^ zid7$0NxrNBPX5wG2dIH!n<)u>G+eGNJ2hG@iy*g^6S3kiu(}|%lV}aSjg0Y4 zR)bW)0<+NZ2z%$1UmG~!6Rp^izr7BR265Q+`b5}}{>M$_QVDzDB{N-cdFa*&Kcalm zL9CNNdLc#Xt@6ZwU*i7W7ubOyHo@V4uZ)Yae?sXht)Wu6F6XkGU=7DWM;sfmo!Hi$ z^Wd_v(wtsc0gyxFOaj!7L$`dKjzELmnn2+xwX=3oW_vY>;4y;_cEqw@5Isi#ii44C z2OuB$?4l@(4hVm%68OCK5#Dx1tuv9C=Oog&DOWP<+c2K&c$Ev4fG)h=o24n7J7S;b3v*e+hxzOb6P){~!6 zyI0gKDgv#Av=lftl!Zpd(SGxyfwC}A)wjF?0|gNkh9ta9l0F!{OWfQslW0*0 z`z^CV09yvEdLi?%a2&1g{?R}-uKGE3^0ue4*?Ke`H5gJULsm;~i*Hrmr1@=`ZHup( zSi-<0QQ#F=r9}hLuB6e|#A?c+?gy+lUe&PdYlx~UPQ_pR%H+GJX&SVcR`%Zvq#-5+OcMdM!$Q)hk6_R963E{7P}b9p?E&w5`i4Y8in1ugX-i*T0@REiHfylpdE>oK;BpeVssbPGjvs_ z*lTU3!mou_l~(rh`6E8dI}s}96*T&i9fwtHylj7rsCRbp9^ODT)dPo5VEFr4uR%sB0OH1{{6+KFnwAhT8~^w)?lJ&WP?cV;GQg=!F<&Q6`|u`mv4>wQh?T|$ zN}}<4q16C+_97b8K(FGnJHd$U-GV7{66)2N@{VBmDq|$pr6)@=!)y9204gt&a^lRy z4m8|BQ^wf=!}~}WJvq}e6U~~-Q2AYk=k*FqG#_z$e~yYNXwfWDCd_;SqIk+bO|=?k z=CT2CJ@tvQGY8i!2z@=VnkooM&T)z;sIol)8%%Er>WNGhu#SG=|E~@p3@`=w09^mC zP2buUYuZ1<9r8(26=F~t;AV@RY`6;2w8>poEXUY!IS=}h;52odag)8%qFCh@(v52n z=Xi;1W^A-G_#SMB9KCi-OCDUp9tlBcO?|WO$k`zLk7+baq=M((HUbq979C5NAR369 zV(>2vCW{*z7tbCTk`otJ7*-rc5a>#ROJ+;bU=V@*&zDbZX#)UL+pxoXasVyB{#OIQ zmq5|}&H-E{!ncV)#{QA<7Xxp*27AWGNrzufcSJ$d5^1^sIWONG2fRA_j9at)ZGeow z6nhN&>;3j%$JxEXaQNWTVKVTYU+MJC!>C8T6kJw;z3?Q`pwn#dlG}H@et%f@@lh~( zV6u@@4KpJ1bvdD(c_6$q`r;S8HZuVdpT7!RJGEA)_Gof?MaZ|KZ@y}oRjTrSYY6j6 z0jcpOommY<+zlTqJX4RN6oxvP`z=*MtT{r=LXXZ?N34F};H-D#y&Qe9t#T;^SlZH$ zoxMiX8d0|7u-J-u)6A;TkA~C3rj5Q`e%LZU2LC`$K$kf{%`1!UPeQWdrzgAwwBX_cYwbdq=GTzEKcTNix5wXA{`JsMfSM z64Xx(Z%V4A%2K+?`5u_&q`tW2*})Iw%z1mkVib^ zWC{lN#(fA}u=I1#Be*#wtRdsGn=@^jiYBl&?Yo2!`kMNtux50vZAxz?(vibdreZ4< zs{Y#L#&Z~CXS6h!sM4wff9@ZnB7^mHBFAYU`r02?HPmxSHjV@zi*PRN%7nKBKPBKf z>Np>1lg;fZC`#1YCd)oGp?7pI^LF-#jRrN=mnB~F*T1-s2u$oBso6KzkO=E&lwzJ% znG(X!%138A`2}k$h!P=Qz)i_O!~@2*Il>BWR7jTHGYtMM_uTEGvf%Hx1!_66$D0kR zXu{RD(~@bypIBr8s@_`c-~V$FY7N!CUUrzA+mN%bq*_bMSB=S0&`y4ba4 z{p8g^`c{(Wa3y*}4Okdse(U)n)qy?Uej9RXeuZD?E%`_jKT6Cop8*@LaTC8`+E*OO zTw!}Y9K1vIm0o#=SuBT*P3gq7&$nkfnRRNjnD9HW{br4gt=@nu0Nsm8oX&(#MD96WYe6-@&s_VHf-s^ps*AwO)J zMeUZoWOSp*bJ32J(mq`2H5IZtQ17imPZc}S#Gpgt$ z6n~2JKX1d=fSa=~|?7igY zhQ8j(Brf3?+XZ(s`{~cSEO4N667d+S3gh_W8MBE4-ots!$thg}_v12+7>*X}WKmn_ zl1;y?aduaB`eblUZx%1e=DC3XuRJWg9sqVBRbWo#!o7A(nr889)_hnBRX?U%wlp%Y zn2;10vzQ|QuF-$nK!8i(obzWz#jJ^*GjbZ-tZBe)j7*sq3Pdgn*`B#qSyqo^%*fGiY_Bn5h$1`CMB|% z>3@9Y?+6hdn(i<$uU{97nUNjCb?VcXTf_+ zyQ2g*(w^-~aw}3bSc*3PT$^*mq&ZUKI`gUi1AmIhg|W$IJxqNCTwaMJrknC+!9W}J zxcD^(2&Dh*SSFQn!PwL5tCl>ggc1CIBl28_#*=sq; zV2k~T`zFmByG|K|=)+c5SL>)QX~;H_Y@HKM`xJVpynLUnL!%@!pY#D3KOwTI%3rZ@ z8ehv^E5nJ8b<(po7?>#!kJnhJ$Cp1nK(YX&aqQVm}*dhvE;2$j}y*P4Pb+?pB$vXd zvbt}HBYm^=OQ}fE3~80h?-Oz8RhR(h6cm*B+BjHj{iNSF^A^&+^{_V0WX3fL|@gndwS%2CO+i>O3Ds>1$ zORe~8e|BNIJ}|~e@hI^>%1KBatx820B4aHrIArC!%>Gum+R)yY*zz75eeCpvPyk)= zOXh0wdYiq^9$YY687!?(-Pnt&9rKA#>_B1P+$E$OUbltH!@dAJncbpozG@uLysL<~CHhsgt<#OmAg>0gTE z6tT#HzfPx=O+?h_r!X$zrHkg-2^tyI6rC`k?m^5`_b3aY*x5g;KgoVLO_hoe=$T$- znyyT^!96wGyWD@?JiOrq4yXPY-KU+-n$Q>Ocq58FQxuvy=A3!YnO#ZE z@|m{JjB!-C3=hQj$o%C(>I)TwZ;?{3);DZ~B(Ou28p2w%=qC(&?){PH2%Fu@PZvlN zzz#t@W-1i#QxP26uJEAF7W_Hrm44P*C*PHj_rZoz|ApHrNrNoOa0_zZ6VC?e~g9 z_f0GJY65kWg7jS%(hKF0g>d4qr%CA|Q=X7fm7v5|AlH@>Z4(PYWc%-2YMmYuy2r^r zcBz1QMd)x?;rlScA(V~@QUn=8rz7(i z?ynx@738B9ew0uTR1cm=Bh(HR?4tFHA`geB)Kk;cE(F|<8A+_fXka{sR@8v@=Gzk> zDj$snloA#_X%U`Xk0HGBSl1mE{g#)O7u(-uT(C@nA>)weP9n&~D4bD|+8QM;d&h&d z8)@Q6Onhzw?AE9f<-E41i=-5-H-XmdKH-0_Rcnhhyooy{U{S1K>w}9Ew7Hnys5ue< z*gU=dp&z_!$m&hOQh~C5Fd++I%AQ(OXDi;r1ooe!=iO1LY0&eM3H%{tEqgkjw5o{t zD%xKtR6aEmIYK=G<~4k*IC6#VYqe`ti*i(wm06{k_7NWBg7T>)&ks>p$3D&Mr5F)= zjKJN?IR99=&(_uL}^(M|eL4p335mPKcU&82Y&V)O5VkKnP zfqrIXx{DOG*=|$=P%E!pEhbMp@gs3~oIa%w$#G@;s-h#^h*lF=w@)FOJ1(d`FQHF` za3Cv)NlYZ(2SHt>O7Rb%!>*hQ4tcjE8!93GK2N}4%;DKEWsgef{zniaeMq9dDq)^r zXihkJPZkF+;+>lII}T`DQEGBro=#Rs)u~_tXL0-ld*m@yKfWf`p5SK#eD?iEz;C{6 zv+g_wZ;7@}dhB`=dud4t?$n$*?l0L984T)eOGK_ixJa{zWPGl@!XN>0rv3^nvz~%q z7{GiNh{(~&Ip0&qh)hibwo32H2ItngFT!o5T9aT6ZV35}>wiN5FK5>C+>jtFOepC&Y7@bRPDc!ySh+f zeDoSjq2j$7c0vF|l*nP+QM@K0J3Ez)j{Hxj9G9kze3!YwH4oM;bc{o7Q!&}|o?71siW*-Q!>rRDG2-|2ooMe`V?}od>?&rOy!+Mq)$#L zKjGxMOj@!XQI;1mV^@|k{}UZ-U`?mu2@XCbb~;D<3fxA;JsKhT-bFLHuBlWoNgA0E z8gH#0|F8h=td=H2$UFE8l=V0l9fHln4=)Osa*Hym3~pluOnum*ytsH;S2yBEfO4bcVZM zUyJv$H#qgMNB2dat-6g;v+EeB-mL0S6tr2PiGFRAuP$VJfxXT#0=0W=?RXh~(1L_L zMpoG9Po#B%GwuX#!D*AlQ$3>YX zp#VKI%Fq}~ZYIhhk3%h_SW;9Sag<$S*+5q1PgjZJEJ-w%!49VLuT=+1$Z|dfSH9L* zHQie=a*JYllY{D2Fqc`ei;nbrXD-vd^CH%s7|P#rxI>ZQ7$8yEJ3B;^Vq-AH9cnhg zkZjoTuCn9}Q>hcbt+X#Ha=c{HZ>_OadsJb zY2k}fDpIO~g47yf;+o=D6$AxuN(pK@aXD%;$vH?!=cro9JLcCoTE`0dVkyGVZ z+y|fT=Xs(Fc-)f@B)xg$YeBf{xrs2o51B;H@-(NA;ixQfJQY$`vGVfPdn$R;&Wen= zPFOR?wy6n6WD{A+hgj3dUBkD?@yk$GF-2e-o>v`9t7t6RD!JeLW(DHDR7tV8_Y3vX zdT)ps_7`hCsZM_)0rrK&P0D&JL|CVQ)HSnh24_D|@aZ^3~>il7Qr_ zQ>*pxzyKR7jk9SJdN~|^S@Q7O=H}^)K7(*sXG>JUw1LR|6A;hF3K94C_$hU{{tU>P zjAcj6TC>SM=^*z}C$DfU&oIpWqefs!Bp0o@;o((v0P1@6iyR6kCSf}C`{8tm&WDmwAs{~ee0Lh~p}s^rMt$?SOms(Z_KQ}S0UT{-1lK(-1|fll-drqX@7Qvxb=Y{1Q}VGe(| z#aC6>X+WmMQ-p~Ew$ExlsyF+lI=83ZxvOFaOIVtA0x&{;vY7JS{YB*{&nmo2~RlAJ%M-`Q!8w`X5WAx@l-ER zD%xfivtGy9tJvai){#WR-{x>k5XC@qX3zl(v$RiQh_?EH8>Bb|Xk_zPEZPiA2gCc33eOqqsH#Dai~pzuC+s!79O z@|KGKFhDmo!p>MeauBEqNhHC^R%MdJnDqpNH?dI`Oib06sQ3*&`wGfNG=drj2yjOc z!wpNilMr>akUmOej30pI7kto>Upoq*AIRG-Z7r$#}28V!|1qQtz_T2Xu!Y6uB2!yJVb`tl3&T=qQce5#tQ zgi@u>R2N?%DMHjS&Ncs*y3lw|0D)?a^{6Hu9^vMI1k;;Fj&d_Ap+;ZS8ET?YG~EnNOebpEB<!v6~Ks7YK!19CP$U{I?hNS22v4f24vegij`K!G!hYS zC!l%ey;7r>gB9t82?LR|fM8wOz%a8@b!}xfS-Bbs z-zAILu_RbY5{`1jG_MM!RUf??;Rwy5=R%QeNCKG`NrF>g8>Wiw zA#Yc+eNjdgqaU!MX3FBd)#Oy9+i>y+oojWE`U0USZ=T`0T3wG8YweomR%oIg1JD8Xn+)@{_ zJ4OzUA^M?@S(Khv85gA=ooK*`iZ|UUp@e=U&7G@5i7N$?q^>ZJQh*FJUAb-iZy;x( ztIDK;cC`**Nri|$KXg2;XzFQY#Hw^_RDmdAtaVac@=b=wDPHMJ)m3Bc6CpM*(^Lj6 z>b1ls`L;g7B>uEy#9fy!RqkgxE+Nm|Q6YP(PU#^0Y1RbwdnAHFEtjfEfRrUQE%_BW zE{s;2d^4ZnSyTLthqKoW&;z#yFMmAD+hF1f_x_BNH6ngGQ`iK-@uD`@vs<0wMol8K*-UaReVWMK2b@ z6u~op$#W^3m50y3~9TP3x4 z+7)>yAu|0{DFbjGqC9i=QR{?7+`f0)X{Yb z0ST7DM^}W4s$pJx$XY3(hOZ}oAf^>(@mFW_Qd^M_>GCI>W=H{%ZNvdj<(M(z5W(c+z9C2-XL5aU}i+^J^;pj85cuRK?T%y7+AVMNd)d#VWRPlgP zn{^(kU=f@#K4}+GO=eq*vR^PZPp1|?z-UGu7HetY00v-Fc7hxiw^yhJa_eTO#6$ zX(Ndz6gkP$Dr6p&pWSZZ2Uwoqy`(ObDsBDJFh;7M8 zsY5{TQ7He_W%xvLzC@29IhU^WZxyi!(e)#U;wn+Jb|07k>tUh?dYlePP)^x`DI^JF zBNCvbPbgz;F{2cm011XseotsBw5Jab7Zl0KO|H0Jx8W8wf)^9{cV44+74bo^2UH~z zWP&p#t*9h_6=JR;5uJmeY)35Y^bqbSR7X?`&}GLjrrr#E_$9|y#g9f6Mr0TmTvF<4_KIdg)G zvKI4EL=7_u`yrHJL2ahU8DORVs2jtY6t-Oq5GY}m9KZGxL{d8SIDe6nG8cj=UWutN zR)P%E9=uT*M-ef_)tv>&dRr!A(Z`$Kv0`gPi*bRcL}e}VIX?JPMd8AQJ0(fo(i&WN zbdR%Akk^<40EW@XDUirKmINuXHg#8K8!XqC?8H=?Fr3#G71x0q7y~nHr=Q;lMrfsY z#gR*r)Du{eZ3cvb*fBIUvrJXuUw#K7JyRaycu}zmm{^)$@wgl=LlyJGZ-w!kl_oVL zxvbNnk!r_BZk0#)L?;c%Gyw<#spb#+*F}DW6Bu%Wrtzu+rkcH4hAQ|Z<+2pLBq7zM zJVY3q`#7i8L@Yu&E@pWDPBvmd+X1Kz+A2LFfpe#Th(SO7!V$bVLj)vV*HUa%v$QTH zsXLe}1_DE`q9ax^B=4wJwBkylftOFGBm^NLR61c{BM*%zmRZF~ebseX#(bFTW_E;{&Vp$sx`Z8C|oq=l3Bs zv7c9IQ@Gg@-y$nyW&ts(QEIDjjJ1eZaa8LgoQlXJUl%*yw-t(n4&yOGuI3`k@_TxM zTfk$2aML1Xp_){CN3+RQelUb5b9<~c8{^om79|l=q)(j3z0(6c z@p`6R~I})@Z~)g0zt$frIydl`=l*HbS4ddKXK0??qek zBVgDaAEW>uNnI zc!C~T9^PojHw%SucwaB|Lft`+Sw*d+(l}^gD#|(>6a<5j#7p2b<;kOa7o+RB>oZtYf zfC?oY5sTo>D=iEw-O?iB(XrqS$8sqpGz)l`3#z~XjQ|XoKnZJc2`bSCwQvat(9^2G z2qBO*3z#s3NBscW2@FLY3ANAwzfcR1a8i25gy|_6}5@5-DqV7YT#cTga44=Lt@-mKa@} zbiyY;%Q=ff9L`Ra$6#U&3{3(90{{XAh5(I-a{!0~iUo~phXMhO0+9d-h616Ti-&VK zhLekPoQH{sp=Fb(ikq^pua%gLiU@#VWC@XqjFGL0oQ=XeY>bnduMz^E$H||ioT0MF zo}`YcWx~mnzf@O@;*rEdx$;Y7+qKN^lruMJZp#YHyaDXb2IAM(@2wT+2 zkpx-C5V-3i6`4dv?*;3&0_crBDGoSQ>cpw z(h@xoq))AE(aa`&S2bV4w_2r2+@w>QLQ%uI{%slY=Gb75S}MY*u~)_gH)8qZyYuSa zZ=p2R!=%{L0(z;8&T%lwKqm(Wc8rwiGHgG6YSgLb&=Akg#nMx`FsuRHuu z4;Xv{1o8@y^K0-=ZFY$5#>xM4GDyT4GURQN4;yPF!h-?CfJRkpEJ1Y@KhSiOUm^`y z$Ja&qfw91d4D>Rh4{;4>Pbb;TXHPi-D3G5%v~UB?Pt{rY(?8;Iwh2S4_~;5%^*oo# z0Z67M0g_<2CmvZ40YJc%p%74Il>{W9z>3znRvtX^?TDayKcZyTNRIGl-8~BtwFhM` z#re{dbk=F7bP(I@PjKh2>m8cF!PvVLjuX>b!I|V zg#*yISTT!hs24KiY>Vs;6UjsI6sOg4-+c+nM(I*JmvJk7Lf1gUdYFzq;7GIKBnMza zke;v*mR+-oKuAtdpeVeqb_Xm5;37Tt9w<28=M~)R{3d4RA3&*+4ai4DF(cv%lyVgiV4HR&pQ@%&<3y1xY%v0w)}sHuvL)AWze%N9PsJH>#OfH!t+y2Q4KZsaFFtUw-yl6M#6oXR_|ITgnml*XA+ zDk#xv$nSoqi13Y1S(yS4K|xSD088vW<_3#LN05 zy11cYEZqPJS1M&53N#Kj(D+VJ2xt}}ZtY^jI~`Lp*bLf{rxY)HT?19;jk?LB8SA-B znqKF{asUhlIt$(}X-9(?%wP&fur-}oR;^y*LPEXJMX@new+cYR{_tS} zxsz2%}NDdqlNYM9Z!Adr`o)R!bO( z%Ai&;j$owN5t~IRuVr+bIY{y|0e}IdGw~%n6vI>>uJ1Yuix4sh_@lrn!fYu(Kvyq< z1v5QN93dnq*VNnUyFmq&Wk}m(1 z+_JKj$Je|uHUo7KaNd!g?Il1&BnrZb=9;GDz%GODkffMs+Y`bV2y?(o8JQrPDd;@0 z6>L~lTmdwS+3qe#w2PS%qxqchxTZO~>Dp~uawC9k#cT4b1^AN1fS61IxE^XE`>J*` z9+sCI^!Xm$yz~vOEmMEn^@~|ZM&X~~ceI~*SW#b+N3Lv*C%9SUU6OZB?rjmD^>LSC zscJIEP!XZ~s#$gD^&|%$xOKs^Ow+n%Qdc-#L^~`e0c%#vO631};ki9U zX=I8Ufg~#t)jEnGs-!jw7|~wnG~q?d2WZ5Gc7A)cvH)dhj@*te$)zznUgjFRWmXP2 zp$DKfuvA1%n2Em{z<2^+2Y#v){?N5*Tet`|Fbr7RYPzENw#KXrgRd=`NU`{UMx04u zXB%6Sv2M8o2c)9aIL=Wjyh^#Nblc!K_Ibt0+G|f^-fC3^K?VyRdytqjQ0EGoSYbc= zt4MvMhsq`0u-s-$d|_t|K7uv_l!z|rWRsVEI^_3d*)p*59DA+26phjN9#*57A9BMv zn~qXr;86^M^P*ie7Xu478xpFM2Vjjt#Rr>$>mifC;7{r9GOTkiyJi2C9<~|Vj%eK$ zj6^w$TqqX7bJ#P!zx7sP@0WbErOf*vw@AUoM~L%<<%>$#6`bMC*#wOaV6?sJPUa+E zU0*YrhRkEnC8&m=pd4p06(CV~Oe)oV_KGKbItG}nDz(gP@DNxWp#|!SJf`kZeR+=1 z;g@EV1X<0{ zHIrku?ZNJ_tF=}-V2+k)Gy6f;Tl5~LWu^@cuE%$tz;Z);w4_2j@+_4x!53iGUO5={ zEO3r^TqVr_=AIL33w>XE-KU5rjj%w!BxdEy2KY&IL+Ivyqe}nO{&F!R0vTa2UJsN; zNYQc;6b^i*Yl#IZ0HGQ{bS5~_IL6iMx zM%eNVM)F2xv?n_N2B35d^2dJ{*NnB4MfE^>U57`#_YMxyJt_!Jbthly(006|JOji+ zHb-WXad2$7i^FCu_xC+UGJ@X0Nw~&N0eBGxFkXw+d_vJK99Lk%lYg3&Q(Qqh;}Uai zbAUT>VU6}}?08xWH#yjZH*fc5Klt)Gr z6(-3vIefM{Hvy1fq)ak|N1J(d%91-YeRAF`FkLun*;ca^a=qy85%OY!x|*PgBNTWNNwyI5cA_s4YiZJ2pwctnlWoX!k9)$UHND+>TU zda_HB$Y#3J6%NoIkYGn0xk8}PEcb_UxPSl;x{!r)cxkF93h^E2wm}N@R`v2QItWr4 zHB}b4mD35XCzu-csR8-PT}uQ!!nZx(@^czU4f9&2*}zU8#cx^0ckXepS_e@sa8PL<;OUDpdqp$E5#Fucux5LLMn1SSC>*G?S3xRX8tI5Z}`Pcr_c?BMIj? zY66xuM;i@r2&|)Z95tj?mdG6N!lnGeWi7S`GtdV*^iFDU5q!H)oCpUw^tTxR1K(vf zZh|bQvye!j1g5YBI8cIFun{<51yGO$;**9s&;$<>89ku6IUu=NP+>^mji=)UXh8^H zpa-fu2DX8^8qm6VfDvOb2$R#g48Xdz`w_Kky9e-usA~bOD+N{uyT3aI4=1}H0lcuA zEU=3Jva7qb`?|IZy?`LS#*4eyOT4|yTFjfgyIZ`z`@O;o2+Lc$7ZI@m$hBCIkY-Z= z>+6l{%TDb}BJVrDGXS5zCvv|5CMOv5xWI-Nb?b{R^IOF3i^SvAjr;4wPdJqVJOd7# XzyutC23*AmTsR7xkPVE#5dZ)?wN9`S literal 0 HcmV?d00001 diff --git a/include/grid_map_core/BufferRegion.hpp b/include/grid_map_core/BufferRegion.hpp new file mode 100644 index 0000000..7821c2d --- /dev/null +++ b/include/grid_map_core/BufferRegion.hpp @@ -0,0 +1,63 @@ +/* + * BufferRegion.hpp + * + * Created on: Aug 19, 2015 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/TypeDefs.hpp" + +namespace grid_map { + +/*! + * This class holds information about a rectangular region + * of cells of the circular buffer. + */ +class BufferRegion +{ + public: + + /*! + * The definition of the buffer region positions. + */ + enum class Quadrant + { + Undefined, + TopLeft, + TopRight, + BottomLeft, + BottomRight + }; + + constexpr static unsigned int nQuadrants = 4; + + BufferRegion(); + BufferRegion(Index startIndex, Size size, BufferRegion::Quadrant quadrant); + virtual ~BufferRegion() = default; + + const Index& getStartIndex() const; + void setStartIndex(const Index& startIndex); + const Size& getSize() const; + void setSize(const Size& size); + BufferRegion::Quadrant getQuadrant() const; + void setQuadrant(BufferRegion::Quadrant type); + + private: + + //! Start index (typically top-left) of the buffer region. + Index startIndex_; + + //! Size of the buffer region. + Size size_; + + //! Quadrant type of the buffer region. + Quadrant quadrant_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} /* namespace grid_map */ diff --git a/include/grid_map_core/CubicInterpolation.hpp b/include/grid_map_core/CubicInterpolation.hpp new file mode 100644 index 0000000..360e384 --- /dev/null +++ b/include/grid_map_core/CubicInterpolation.hpp @@ -0,0 +1,345 @@ +/* + * CubicInterpolation.hpp + * + * Created on: Jan 21, 2020 + * Author: Edo Jelavic + * Institute: ETH Zurich, Robotic Systems Lab + */ + +#pragma once + +#include +#include +#include +#include "grid_map_core/TypeDefs.hpp" + +/* + * For difference between bicubic convolution interpolation (piecewise cubic) + * and bicubic interpolation see: + * + * https://en.wikipedia.org/wiki/Bicubic_interpolation + * + * R. Keys (1981). "Cubic convolution interpolation for digital image processing". + * IEEE Transactions on Acoustics, Speech, and Signal Processing. 29 (6): 1153–1160. + * +* https://web.archive.org/web/20051024202307/ +* http://www.geovista.psu.edu/sites/geocomp99/Gc99/082/gc_082.htm + */ + +namespace grid_map { + +class GridMap; + +/* + * Data structure (matrix) that contains data + * necessary for interpolation. These are either 16 + * function values in the case of bicubic convolution interpolation + * or function values and their derivatives for the case + * of standard bicubic interpolation. + */ +using FunctionValueMatrix = Eigen::Matrix4d; + +/*! + * Takes the id requested, performs checks and returns + * an id that it is within the specified bounds. + * @param[in] idReq - input index . + * @param[in] nElem - number of elements in the container + * @return index that is within [0, nElem-1]. + */ +unsigned int bindIndexToRange(unsigned int idReq, unsigned int nElem); + + +/*! + * Extract the value of the specific layer at the + * row and column requested. If row and column are out + * of bounds they will be bound to range. + * @param[in] layerMat - matrix of the layer from where + * the data is extracted + * @param[in] rowReq - row requested + * @param[in] colReq - column requested + * @return - value of the layer at rowReq and colReq + */ +double getLayerValue(const Matrix &layerMat, int rowReq, int colReq); + +namespace bicubic_conv { + +/*! + * Matrix for cubic interpolation via convolution. Taken from: + * https://en.wikipedia.org/wiki/Bicubic_interpolation + */ +static const Eigen::Matrix4d cubicInterpolationConvolutionMatrix { + (Eigen::Matrix4d() << 0.0, 2.0, 0.0, 0.0, + -1.0, 0.0, 1.0, 0.0, + 2.0, -5.0, 4.0, -1.0, + -1.0, 3.0, -3.0, 1.0).finished() }; + +/* + * Index of the middle knot for bicubic interpolation. This is + * the function value with subscripts (0,0), i.e. f00 in + * https://en.wikipedia.org/wiki/Bicubic_interpolation + * In the grid map it corresponds to the grid map point closest to the + * queried point (in terms of Euclidean distance). Queried point has + * coordinates (x,y) for at which the interpolation is requested. + * @param[in] gridMap - grid map with the data + * @param[in] queriedPosition - position for which the interpolated data is requested + * @param[out] index - indices of the middle knot for the interpolation + * @return - true if success + */ +bool getIndicesOfMiddleKnot(const GridMap &gridMap, const Position &queriedPosition, Index *index); + +/* + * Coordinates used for interpolation need to be shifted and scaled, + * since the original algorithm operates around the origin and with unit + * resolution + * @param[in] gridMap - grid map with the data + * @param[in] queriedPosition - position for which the interpolation is requested + * @param[out] position - normalized coordinates of the point for which the interpolation is requested + * @return - true if success + */ +bool getNormalizedCoordinates(const GridMap &gridMap, const Position &queriedPosition, + Position *position); + +/* + * Queries the grid map for function values at the coordinates which are necessary for + * performing the interpolation. The right function values are then assembled + * in a matrix. + * @param[in] gridMap - grid map with the data + * @param[in] layer - name of the layer that we are interpolating + * @param[in] queriedPosition - position for which the interpolation is requested + * @param[out] data - 4x4 matrix with 16 function values used for interpolation, see + * R. Keys (1981). "Cubic convolution interpolation for digital image processing". + * IEEE Transactions on Acoustics, Speech, and Signal Processing. 29 (6): 1153–1160. + * for the details. + * @return - true if success + */ +bool assembleFunctionValueMatrix(const GridMap &gridMap, const std::string &layer, + const Position &queriedPosition, FunctionValueMatrix *data); + +/* + * Performs convolution in 1D. the function requires 4 function values + * to compute the convolution. The result is interpolated data in 1D. + * @param[in] t - normalized coordinate (x or y) + * @param[in] functionValues - vector of 4 function values necessary to perform + * interpolation in 1 dimension. + * @return - interpolated value at normalized coordinate t + */ +double convolve1D(double t, const Eigen::Vector4d &functionValues); + +/* + * Performs convolution in 1D. the function requires 4 function values + * to compute the convolution. The result is interpolated data in 1D. + * @param[in] gridMap - grid map with discrete function values + * @param[in] layer - name of the layer for which we want to perform interpolation + * @param[in] queriedPosition - position for which the interpolation is requested + * @param[out] interpolatedValue - interpolated value at queried point + * @return - true if success + */ +bool evaluateBicubicConvolutionInterpolation(const GridMap &gridMap, const std::string &layer, + const Position &queriedPosition, + double *interpolatedValue); + +} /* namespace bicubic_conv */ + +namespace bicubic { + +/* + * Enum for the derivatives direction + * to perform interpolation one needs + * derivatives w.r.t. to x and y dimension. + */ +enum class Dim2D: int { + X, + Y +}; + +/*! + * Matrix for cubic interpolation. Taken from: + * https://en.wikipedia.org/wiki/Bicubic_interpolation + */ +static const Eigen::Matrix4d bicubicInterpolationMatrix { + (Eigen::Matrix4d() << 1.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + -3.0, 3.0, -2.0, -1.0, + 2.0, -2.0, 1.0, 1.0).finished() }; + +/* + * Data matrix that can hold function values + * these can be either function values at requested + * positions or their derivatives. + */ +struct DataMatrix +{ + double topLeft_ = 0.0; + double topRight_ = 0.0; + double bottomLeft_ = 0.0; + double bottomRight_ = 0.0; +}; + +/* + * Interpolation is performed on a unit square. + * Hence, we need to compute 4 corners of that unit square, + * and find their indices in the grid map. IndicesMatrix + * is a container that stores those indices. Each index + * contains two numbers (row number, column number) in the + * grid map. + */ +struct IndicesMatrix +{ + Index topLeft_ { 0, 0 }; + Index topRight_ { 0, 0 }; + Index bottomLeft_ { 0, 0 }; + Index bottomRight_ { 0, 0 }; +}; + +/* + * Makes sure that all indices in side the + * data structure IndicesMatrix are within the + * range of the grid map. + * @param[in] gridMap - input grid map with discrete function values + * @param[in/out] indices - indices that are bound to range, i.e. + * rows and columns are with ranges + */ +void bindIndicesToRange(const GridMap &gridMap, IndicesMatrix *indices); + +/* + * Performs bicubic interpolation at requested position. + * @param[in] gridMap - grid map with discrete function values + * @param[in] layer - name of the layer for which we want to perform interpolation + * @param[in] queriedPosition - position for which the interpolation is requested + * @param[out] interpolatedValue - interpolated value at queried point + * @return - true if success + */ +bool evaluateBicubicInterpolation(const GridMap &gridMap, const std::string &layer, + const Position &queriedPosition, double *interpolatedValue); + +/* + * Deduces which points in the grid map close a unit square around the + * queried point and returns their indices (row and column number) + * @param[in] gridMap - grid map with discrete function values + * @param[in] queriedPosition - position for which the interpolation is requested + * @param[out] indicesMatrix - data structure with indices forming a unit square + * around the queried point + * @return - true if success + */ +bool getUnitSquareCornerIndices(const GridMap &gridMap, const Position &queriedPosition, + IndicesMatrix *indicesMatrix); + +/* + * Get index (row and column number) of a point in grid map, which + * is closest to the queried position. + * @param[in] gridMap - grid map with discrete function values + * @param[in] queriedPosition - position for which the interpolation is requested + * @param[out] index - indices of the closest point in grid_map + * @return - true if success + */ +bool getClosestPointIndices(const GridMap &gridMap, const Position &queriedPosition, Index *index); + +/* + * Retrieve function values from the grid map at requested indices. + * @param[in] layerData - layer of a grid map with function values + * @param[in] indices - indices (row and column numbers) for which function values are requested + * @param[out] data - requested function values + * @return - true if success + */ +bool getFunctionValues(const Matrix &layerData, const IndicesMatrix &indices, DataMatrix *data); + +/* + * Retrieve function derivative values from the grid map at requested indices. Function + * derivatives are approximated using central difference. + * @param[in] layerData - layer of a grid map with function values + * @param[in] indices - indices (row and column numbers) for which function derivative + * values are requested + * @param[in] dim - dimension along which we want to evaluate partial derivatives (X or Y) + * @param[in] resolution - resolution of the grid map + * @param[out] derivatives - values of derivatives at requested indices + * @return - true if success + */ +bool getFirstOrderDerivatives(const Matrix &layerData, const IndicesMatrix &indices, Dim2D dim, + double resolution, DataMatrix *derivatives); + +/* + * Retrieve second order function derivative values from the grid map at requested indices. + * Function derivatives are approximated using central difference. We compute partial derivative + * w.r.t to one coordinate and then the other. Note that the order of differentiation + * does not matter. + * @param[in] layerData - layer of a grid map with function values + * @param[in] indices - indices (row and column numbers) for which function derivative + * values are requested + * @param[in] resolution - resolution of the grid map + * @param[out] derivatives - values of second order mixed derivatives at requested indices + * @return - true if success + */ +bool getMixedSecondOrderDerivatives(const Matrix &layerData, const IndicesMatrix &indices, + double resolution, DataMatrix *derivatives); + +/* + * First order derivative for a specific point determined by index. + * Approximated by central difference. + * See https://www.mathematik.uni-dortmund.de/~kuzmin/cfdintro/lecture4.pdf + * for details + * @param[in] layerData - layer of a grid map with function values + * @param[in] index - index (row and column number) for which function derivative + * value is requested + * @param[in] dim - dimension along which we want to evaluate partial derivative (X or Y) + * @param[in] resolution - resolution of the grid map + * @return - value of the derivative at requested index + */ +double firstOrderDerivativeAt(const Matrix &layerData, const Index &index, Dim2D dim, + double resolution); + +/* + * Second order mixed derivative for a specific point determined by index. + * See https://www.mathematik.uni-dortmund.de/~kuzmin/cfdintro/lecture4.pdf + * for details + * @param[in] layerData - layer of a grid map with function values + * @param[in] index - index (row and column number) for which function derivative + * value is requested + * @param[in] resolution - resolution of the grid map + * @return - value of the second order mixed derivative at requested index + */ +double mixedSecondOrderDerivativeAt(const Matrix &layerData, const Index &index, double resolution); + +/* + * Evaluate polynomial at requested coordinates. the function will compute the polynomial + * coefficients and then evaluate it. See + * https://en.wikipedia.org/wiki/Bicubic_interpolation + * for details. + * @param[in] functionValues - function values and derivatives required to + * compute polynomial coefficients + * @param[in] tx - normalized x coordinate for which the interpolation should be computed + * @param[in] ty - normalized y coordinate for which the interpolation should be computed + * @return - interpolated value at requested normalized coordinates. + */ +double evaluatePolynomial(const FunctionValueMatrix &functionValues, double tx, double ty); + +/* + * Assemble function value matrix from small sub-matrices containing function values + * or derivative values at the corners of the unit square. + * See https://en.wikipedia.org/wiki/Bicubic_interpolation for details. + * + * @param[in] f - Function values at the corners of the unit square + * @param[in] dfx - Partial derivative w.r.t to x at the corners of the unit square + * @param[in] dfy - Partial derivative w.r.t to y at the corners of the unit square + * @param[in] ddfxy - Second order partial derivative w.r.t to x and y at the corners of the unit square + * @param[out] functionValues - function values and derivatives required to + * compute polynomial coefficients + */ +void assembleFunctionValueMatrix(const DataMatrix &f, const DataMatrix &dfx, const DataMatrix &dfy, + const DataMatrix &ddfxy, FunctionValueMatrix *functionValues); + +/* + * Coordinates used for interpolation need to be shifter and scaled, + * since the original algorithm operates on a unit square around the origin. + * @param[in] gridMap - grid map with the data + * @param[in] originIndex - index of a bottom left corner if the unit square in the grid map + * this corner is the origin for the normalized coordinates. + * @param[in] queriedPosition - position for which the interpolation is requested + * @param[out] position - normalized coordinates of the point for which the interpolation is requested + * @return - true if success + */ +bool computeNormalizedCoordinates(const GridMap &gridMap, const Index &originIndex, + const Position &queriedPosition, Position *normalizedCoordinates); + +} /* namespace bicubic */ + +} /* namespace grid_map*/ diff --git a/include/grid_map_core/GridMap.hpp b/include/grid_map_core/GridMap.hpp new file mode 100644 index 0000000..74a62b7 --- /dev/null +++ b/include/grid_map_core/GridMap.hpp @@ -0,0 +1,589 @@ +/* + * GridMap.hpp + * + * Created on: Jul 14, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/BufferRegion.hpp" +#include "grid_map_core/SubmapGeometry.hpp" +#include "grid_map_core/TypeDefs.hpp" + +// STL +#include +#include + +// Eigen +#include +#include + +namespace grid_map { + +class SubmapGeometry; + +/*! + * Grid map managing multiple overlaying maps holding float values. + * Data structure implemented as two-dimensional circular buffer so map + * can be moved efficiently. + * + * Data is defined with string keys. Examples are: + * - "elevation" + * - "variance" + * - "color" + * - "quality" + * - "surface_normal_x", "surface_normal_y", "surface_normal_z" + * etc. + */ +class GridMap { + public: + // Type traits for use with template methods/classes using GridMap as a template parameter. + typedef grid_map::DataType DataType; + typedef grid_map::Matrix Matrix; + + /*! + * Constructor. + * @param layers a vector of strings containing the definition/description of the data layer. + */ + explicit GridMap(const std::vector& layers); + + /*! + * Emtpy constructor. + */ + GridMap(); + + /*! + * Default copy assign and copy constructors. + */ + GridMap(const GridMap&) = default; + GridMap& operator=(const GridMap&) = default; + GridMap(GridMap&&) = default; + GridMap& operator=(GridMap&&) = default; + + /*! + * Destructor. + */ + virtual ~GridMap() = default; + + /*! + * Set the geometry of the grid map. Clears all the data. + * @param length the side lengths in x, and y-direction of the grid map [m]. + * @param resolution the cell size in [m/cell]. + * @param position the 2d position of the grid map in the grid map frame [m]. + */ + void setGeometry(const Length& length, const double resolution, const Position& position = Position::Zero()); + + /*! + * Set the geometry of the grid map from submap geometry information. + * @param geometry the submap geometry information. + */ + void setGeometry(const SubmapGeometry& geometry); + + /*! + * Add a new empty data layer. + * @param layer the name of the layer. + * @value value the value to initialize the cells with. + */ + void add(const std::string& layer, const float value = NAN); + + /*! + * Add a new data layer (if the layer already exists, overwrite its data, otherwise add layer and data). + * @param layer the name of the layer. + * @param data the data to be added. + */ + void add(const std::string& layer, const Matrix& data); + + /*! + * Checks if data layer exists. + * @param layer the name of the layer. + * @return true if layer exists, false otherwise. + */ + bool exists(const std::string& layer) const; + + /*! + * Returns the grid map data for a layer as matrix. + * @param layer the name of the layer to be returned. + * @return grid map data as matrix. + * @throw std::out_of_range if no map layer with name `layer` is present. + */ + const Matrix& get(const std::string& layer) const; + + /*! + * Returns the grid map data for a layer as non-const. Use this method + * with care! + * @param layer the name of the layer to be returned. + * @return grid map data. + * @throw std::out_of_range if no map layer with name `layer` is present. + */ + Matrix& get(const std::string& layer); + + /*! + * Returns the grid map data for a layer as matrix. + * @param layer the name of the layer to be returned. + * @return grid map data as matrix. + * @throw std::out_of_range if no map layer with name `layer` is present. + */ + const Matrix& operator[](const std::string& layer) const; + + /*! + * Returns the grid map data for a layer as non-const. Use this method + * with care! + * @param layer the name of the layer to be returned. + * @return grid map data. + * @throw std::out_of_range if no map layer with name `layer` is present. + */ + Matrix& operator[](const std::string& layer); + + /*! + * Removes a layer from the grid map. + * @param layer the name of the layer to be removed. + * @return true if successful. + */ + bool erase(const std::string& layer); + + /*! + * Gets the names of the layers. + * @return the names of the layers. + */ + const std::vector& getLayers() const; + + /*! + * Set the basic layers that need to be valid for a cell to be considered as valid. + * Also, the basic layers are set to NAN when clearing the cells with `clearBasic()`. + * By default the list of basic layers is empty. + * @param basicLayers the list of layers that are the basic layers of the map. + */ + void setBasicLayers(const std::vector& basicLayers); + + /*! + * Gets the names of the basic layers. + * @return the names of the basic layers. + */ + const std::vector& getBasicLayers() const; + + /*! + * True if basic layers are defined. + * @return true if basic layers are defined, false otherwise. + */ + bool hasBasicLayers() const; + + /*! + * Checks if another grid map contains the same layers as this grid map. + * The other grid map could contain more layers than the checked ones. + * Does not check the selection of basic layers. + * @param other the other grid map. + * @return true if the other grid map has the same layers, false otherwise. + */ + bool hasSameLayers(const grid_map::GridMap& other) const; + + /*! + * Get cell data at requested position. + * @param layer the name of the layer to be accessed. + * @param position the requested position. + * @return the data of the cell. + * @throw std::out_of_range if no map layer with name `layer` is present. + */ + float& atPosition(const std::string& layer, const Position& position); + + /*! + * Get cell data at requested position. Const version form above. + * @param layer the name of the layer to be accessed. + * @param position the requested position. + * @return the data of the cell. + * @throw std::out_of_range if no map layer with name `layer` is present. + * @throw std::runtime_error if the specified interpolation method is not implemented. + */ + float atPosition(const std::string& layer, const Position& position, + InterpolationMethods interpolationMethod = InterpolationMethods::INTER_NEAREST) const; + + /*! + * Get cell data for requested index. + * @param layer the name of the layer to be accessed. + * @param index the requested index. + * @return the data of the cell. + * @throw std::out_of_range if no map layer with name `layer` is present. + */ + float& at(const std::string& layer, const Index& index); + + /*! + * Get cell data for requested index. Const version form above. + * @param layer the name of the layer to be accessed. + * @param index the requested index. + * @return the data of the cell. + * @throw std::out_of_range if no map layer with name `layer` is present. + */ + float at(const std::string& layer, const Index& index) const; + + /*! + * Gets the corresponding cell index for a position. + * @param[in] position the requested position. + * @param[out] index the corresponding index. + * @return true if successful, false if position outside of map. + */ + bool getIndex(const Position& position, Index& index) const; + + /*! + * Gets the 2d position of cell specified by the index (x, y of cell position) in + * the grid map frame. + * @param[in] index the index of the requested cell. + * @param[out] position the position of the data point in the parent frame. + * @return true if successful, false if index not within range of buffer. + */ + bool getPosition(const Index& index, Position& position) const; + + /*! + * Check if position is within the map boundaries. + * @param position the position to be checked. + * @return true if position is within map, false otherwise. + */ + bool isInside(const Position& position) const; + + /*! + * Checks if the index of all layers defined as basic types are valid, + * i.e. if all basic types are finite. Returns `false` if no basic types are defined. + * @param index the index to check. + * @return true if cell is valid, false otherwise. + */ + bool isValid(const Index& index) const; + + /*! + * Checks if cell at index is a valid (finite) for a certain layer. + * @param index the index to check. + * @param layer the name of the layer to be checked for validity. + * @return true if cell is valid, false otherwise. + */ + bool isValid(const Index& index, const std::string& layer) const; + + /*! + * Checks if cell at index is a valid (finite) for certain layers. + * @param index the index to check. + * @param layers the layers to be checked for validity. + * @return true if cell is valid, false otherwise. + */ + bool isValid(const Index& index, const std::vector& layers) const; + + /*! + * Gets the 3d position of a data point (x, y of cell position & cell value as z) in + * the grid map frame. This is useful for data layers such as elevation. + * @param layer the name of the layer to be accessed. + * @param index the index of the requested cell. + * @param position the position of the data point in the parent frame. + * @return true if successful, false if no valid data available. + */ + bool getPosition3(const std::string& layer, const Index& index, Position3& position) const; + + /*! + * Gets the 3d vector of three layers with suffixes 'x', 'y', and 'z'. + * @param layerPrefix the prefix for the layer to bet get as vector. + * @param index the index of the requested cell. + * @param vector the vector with the values of the data type. + * @return true if successful, false if no valid data available. + */ + bool getVector(const std::string& layerPrefix, const Index& index, Eigen::Vector3d& vector) const; + + /*! + * Gets a submap from the map. The requested submap is specified with the requested + * location and length. + * Note: The returned submap may not have the requested length due to the borders + * of the map and discretization. + * @param[in] position the requested position of the submap (usually the center). + * @param[in] length the requested length of the submap. + * @param[out] isSuccess true if successful, false otherwise. + * @return submap (is empty if success is false). + */ + GridMap getSubmap(const Position& position, const Length& length, bool& isSuccess) const; + + /*! + * Gets a submap from the map. The requested submap is specified with the requested + * location and length. + * Note: The returned submap may not have the requested length due to the borders + * of the map and discretization. + * @param[in] position the requested position of the submap (usually the center). + * @param[in] length the requested length of the submap. + * @param[out] indexInSubmap the index of the requested position in the submap. + * @param[out] isSuccess true if successful, false otherwise. + * @return submap (is empty if success is false). + */ + GridMap getSubmap(const Position& position, const Length& length, Index& indexInSubmap, bool& isSuccess) const; + + /*! + * Apply isometric transformation (rotation + offset) to grid map and returns the transformed map. + * Note: The returned map may not have the same length since it's geometric description contains + * Note: The transformation will only be applied to the height layer of the grid map, other layers will remain untouched. + * the original map. + * @param[in] transform the requested transformation to apply. + * @param[in] heightLayerName the height layer of the map. + * @param[in] newFrameId frame index of the new map. + * @param[in] sampleRatio if zero or negative, no in-painting is used to fill missing points due to sparsity of the map. Otherwise, + * four points are sampled around each grid cell to make sure that at least one of those points map to a new grid cell. + * A sampleRatio of 1 corresponds to the the resolution of the grid map. + * @return transformed map. + * @throw std::out_of_range if no map layer with name `heightLayerName` is present. + */ + GridMap getTransformedMap(const Eigen::Isometry3d& transform, const std::string& heightLayerName, const std::string& newFrameId, + const double sampleRatio = 0.0) const; + + /*! + * Set the position of the grid map. + * Note: This method does not change the data stored in the grid map and + * is complementary to the `move(...)` method. For a comparison between + * the `setPosition` and the `move` method, see the `move_demo_node.cpp` + * file of the `grid_map_demos` package. + * @param position the 2d position of the grid map in the grid map frame [m]. + */ + void setPosition(const Position& position); + + /*! + * Relocates the region captured by grid map w.r.t. to the static grid map frame. Use this to move the grid map boundaries + * without relocating the grid map data. Takes care of all the data handling, such that the grid map data is stationary in the grid map + * frame. + * - Data in the overlapping region before and after the position change remains stored. + * - Data that falls outside the map at its new position is discarded. + * - Cells that cover previously unknown regions are emptied (set to nan). + * The data storage is implemented as two-dimensional circular buffer to minimize computational effort. + * + * Note: Due to the circular buffer structure, neighbouring indices might not fall close in the map frame. + * This assumption only holds for indices obtained by getUnwrappedIndex(). + * + * Note: For a comparison between the `setPosition` and the `move` method, see the `move_demo_node.cpp` file of the `grid_map_demos` package. + * + * @param position the new location of the grid map in the map frame. + * @param newRegions the regions of the newly covered / previously uncovered regions of the buffer. + * @return true if map has been moved, false otherwise. + */ + bool move(const Position& position, std::vector& newRegions); + + /*! + * Move the grid map w.r.t. to the grid map frame. Use this to move the grid map + * boundaries without moving the grid map data. Takes care of all the data handling, + * such that the grid map data is stationary in the grid map frame. + * @param position the new location of the grid map in the map frame. + * @return true if map has been moved, false otherwise. + */ + bool move(const Position& position); + + /*! + * Adds data from an other grid map to this grid map + * @param other the grid map to take data from. + * @param extendMap if true the grid map is resized that the other map fits within. + * @param overwriteData if true the new data replaces the old values, else only invalid cells are updated. + * @param copyAllLayer if true all layers are used to add data. + * @param layers the layers that are copied if not all layers are used. + * @return true if successful. + */ + bool addDataFrom(const GridMap& other, bool extendMap, bool overwriteData, bool copyAllLayers, + std::vector layers = std::vector()); + + /*! + * Extends the size of the grip map such that the other grid map fits within. + * @param other the grid map to extend the size to. + * @return true if successful. + */ + bool extendToInclude(const GridMap& other); + + /*! + * Clears all cells (set to NAN) for a layer. + * @param layer the layer to be cleared. + */ + void clear(const std::string& layer); + + /*! + * Clears all cells (set to NAN) for all basic layers. + * Header information (geometry etc.) remains valid. + */ + void clearBasic(); + + /*! + * Clears all cells of all layers. + * If basic layers are used, clearBasic() is preferred as it is more efficient. + * Header information (geometry etc.) remains valid. + */ + void clearAll(); + + /*! + * Set the timestamp of the grid map. + * @param timestamp the timestamp to set (in nanoseconds). + */ + void setTimestamp(const Time timestamp); + + /*! + * Get the timestamp of the grid map. + * @return timestamp in nanoseconds. + */ + Time getTimestamp() const; + + /*! + * Resets the timestamp of the grid map (to zero). + */ + void resetTimestamp(); + + /*! + * Set the frame id of the grid map. + * @param frameId the frame id to set. + */ + void setFrameId(const std::string& frameId); + + /*! + * Get the frameId of the grid map. + * @return frameId. + */ + const std::string& getFrameId() const; + + /*! + * Get the side length of the grid map. + * @return side length of the grid map. + */ + const Length& getLength() const; + + /*! + * Get the 2d position of the grid map in the grid map frame. + * @return position of the grid map in the grid map frame. + */ + const Position& getPosition() const; + + /*! + * Get the resolution of the grid map. + * @return resolution of the grid map in the xy plane [m/cell]. + */ + double getResolution() const; + + /*! + * Get the grid map size (rows and cols of the data structure). + * @return grid map size. + */ + const Size& getSize() const; + + /*! + * Set the start index of the circular buffer. + * Use this method with caution! + * @return buffer start index. + */ + void setStartIndex(const Index& startIndex); + + /*! + * Get the start index of the circular buffer. + * @return buffer start index. + */ + const Index& getStartIndex() const; + + /*! + * Checks if the buffer is at start index (0,0). + * @return true if buffer is at default start index. + */ + bool isDefaultStartIndex() const; + + /*! + * Rearranges data such that the buffer start index is at (0,0). + */ + void convertToDefaultStartIndex(); + + /*! + * Calculates the closest point to positionOutMap that is in the grid map. + * If positionOutMap is already in the grid map, that position is returned. + * @param[in] position position that should be approached as close as possible. + * @return position in map. + */ + Position getClosestPositionInMap(const Position& position) const; + + private: + /** + * Defines data validation check + * @param value + * @return true if value is valid + */ + bool isValid(DataType value) const; + + /*! + * Clear a number of columns of the grid map. + * @param index the left index for the columns to be reset. + * @param nCols the number of columns to reset. + */ + void clearCols(unsigned int index, unsigned int nCols); + + /*! + * Clear a number of rows of the grid map. + * @param index the upper index for the rows to be reset. + * @param nRows the number of rows to reset. + */ + void clearRows(unsigned int index, unsigned int nRows); + + /*! + * Get cell data at requested position, linearly interpolated from 2x2 cells. + * @param layer the name of the layer to be accessed. + * @param position the requested position. + * @param value the data of the cell. + * @return true if linear interpolation was successful. + */ + bool atPositionLinearInterpolated(const std::string& layer, const Position& position, float& value) const; + + /*! + * Get cell data at requested position, cubic convolution + * interpolated from 4x4 cells. At the edge of the map, + * the algorithm assumes that height continues with the slope 0. + * I.e. the border cells just repeat outside of the map + * Taken from: https://en.wikipedia.org/wiki/Bicubic_interpolation + * @param[in] layer the name of the layer to be accessed. + * @param[in] position the requested position. + * @param[out] value the data of the cell. + * @return true if bicubic convolution interpolation was successful. + */ + bool atPositionBicubicConvolutionInterpolated(const std::string& layer, const Position& position, float& value) const; + + /*! + * Get cell data at requested position, cubic interpolated + * on a square. At the edge of the map, + * the algorithm assumes that height continues with the slope 0. + * I.e. the border cells just repeat outside of the map + * Taken from: https://en.wikipedia.org/wiki/Bicubic_interpolation + * @param[in] layer the name of the layer to be accessed. + * @param[in] position the requested position. + * @param[out] value the data of the cell. + * @return true if bicubic interpolation was successful. + */ + bool atPositionBicubicInterpolated(const std::string& layer, const Position& position, float& value) const; + + /*! + * Resize the buffer. + * @param bufferSize the requested buffer size. + */ + void resize(const Index& bufferSize); + + //! Frame id of the grid map. + std::string frameId_; + + //! Timestamp of the grid map (nanoseconds). + Time timestamp_; + + //! Grid map data stored as layers of matrices. + std::unordered_map data_; + + //! Names of the data layers. + std::vector layers_; + + //! List of layers from `data_` that are the basic grid map layers. + //! This means that for a cell to be valid, all basic layers need to be valid. + //! Also, the basic layers are set to NAN when clearing the map with `clear()`. + std::vector basicLayers_; + + //! Side length of the map in x- and y-direction [m]. + Length length_; + + //! Map resolution in xy plane [m/cell]. + double resolution_; + + //! Map position in the grid map frame [m]. + Position position_; + + //! Size of the buffer (rows and cols of the data structure). + Size size_; + + //! Circular buffer start indices. + Index startIndex_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace grid_map diff --git a/include/grid_map_core/GridMapMath.hpp b/include/grid_map_core/GridMapMath.hpp new file mode 100644 index 0000000..fb1a38e --- /dev/null +++ b/include/grid_map_core/GridMapMath.hpp @@ -0,0 +1,344 @@ +/* + * GridMapMath.hpp + * + * Created on: Dec 2, 2013 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/TypeDefs.hpp" +#include "grid_map_core/BufferRegion.hpp" + +#include +#include +#include + +namespace grid_map { + +union Color +{ + unsigned long longColor_; + float floatColor_; +}; + +/*! + * Gets the position of a cell specified by its index in the map frame. + * @param[out] position the position of the center of the cell in the map frame. + * @param[in] index of the cell. + * @param[in] mapLength the lengths in x and y direction. + * @param[in] mapPosition the position of the map. + * @param[in] resolution the resolution of the map. + * @param[in] bufferSize the size of the buffer (optional). + * @param[in] bufferStartIndex the index of the starting point of the circular buffer (optional). + * @return true if successful, false if index not within range of buffer. + */ +bool getPositionFromIndex(Position& position, + const Index& index, + const Length& mapLength, + const Position& mapPosition, + const double& resolution, + const Size& bufferSize, + const Index& bufferStartIndex = Index::Zero()); + +/*! + * Gets the index of the cell which contains a position in the map frame. + * @param[out] index of the cell. + * @param[in] position the position in the map frame. + * @param[in] mapLength the lengths in x and y direction. + * @param[in] mapPosition the position of the map. + * @param[in] resolution the resolution of the map. + * @param[in] bufferSize the size of the buffer (optional). + * @param[in] bufferStartIndex the index of the starting point of the circular buffer (optional). + * @return true if successful, false if position outside of map. + */ +bool getIndexFromPosition(Index& index, + const Position& position, + const Length& mapLength, + const Position& mapPosition, + const double& resolution, + const Size& bufferSize, + const Index& bufferStartIndex = Index::Zero()); + +/*! + * Checks if position is within the map boundaries. + * @param[in] position the position which is to be checked. + * @param[in] mapLength the length of the map. + * @param[in] mapPosition the position of the map. + * @return true if position is within map, false otherwise. + */ +bool checkIfPositionWithinMap(const Position& position, + const Length& mapLength, + const Position& mapPosition); + +/*! + * Gets the position of the data structure origin. + * @param[in] position the position of the map. + * @param[in] mapLength the map length. + * @param[out] positionOfOrigin the position of the data structure origin. + */ +void getPositionOfDataStructureOrigin(const Position& position, + const Length& mapLength, + Position& positionOfOrigin); + +/*! + * Computes how many cells/indices the map is moved based on a position shift in + * the grid map frame. Use this function if you are moving the grid map + * and want to ensure that the cells match before and after. + * @param[out] indexShift the corresponding shift of the indices. + * @param[in] positionShift the desired position shift. + * @param[in] resolution the resolution of the map. + * @return true if successful. + */ +bool getIndexShiftFromPositionShift(Index& indexShift, + const Vector& positionShift, + const double& resolution); + +/*! + * Computes the corresponding position shift from a index shift. Use this function + * if you are moving the grid map and want to ensure that the cells match + * before and after. + * @param[out] positionShift the corresponding shift in position in the grid map frame. + * @param[in] indexShift the desired shift of the indices. + * @param[in] resolution the resolution of the map. + * @return true if successful. + */ +bool getPositionShiftFromIndexShift(Vector& positionShift, + const Index& indexShift, + const double& resolution); + +/*! + * Checks if index is within range of the buffer. + * @param[in] index to check. + * @param[in] bufferSize the size of the buffer. + * @return true if index is within, and false if index is outside of the buffer. + */ +bool checkIfIndexInRange(const Index& index, const Size& bufferSize); + +/*! + * Bounds an index that runs out of the range of the buffer. + * This means that an index that overflows is stopped at the last valid index. + * This is the 2d version of boundIndexToRange(int&, const int&). + * @param[in/out] index the indices that will be bounded to the valid region of the buffer. + * @param[in] bufferSize the size of the buffer. + */ +void boundIndexToRange(Index& index, const Size& bufferSize); + +/*! + * Bounds an index that runs out of the range of the buffer. + * This means that an index that overflows is stopped at the last valid index. + * @param[in/out] index the index that will be bounded to the valid region of the buffer. + * @param[in] bufferSize the size of the buffer. + */ +void boundIndexToRange(int& index, const int& bufferSize); + +/*! + * Wraps an index that runs out of the range of the buffer back into allowed the region. + * This means that an index that overflows is reset to zero. + * This is the 2d version of wrapIndexToRange(int&, const int&). + * @param[in/out] index the indices that will be wrapped into the valid region of the buffer. + * @param[in] bufferSize the size of the buffer. + */ +void wrapIndexToRange(Index& index, const Size& bufferSize); + +/*! + * Wraps an index that runs out of the range of the buffer back into allowed the region. + * This means that an index that overflows is reset to zero. + * @param[in/out] index the index that will be wrapped into the valid region of the buffer. + * @param[in] bufferSize the size of the buffer. + */ +void wrapIndexToRange(int& index, int bufferSize); + +/*! + * Bound (cuts off) the position to lie inside the map. + * This means that an index that overflows is stopped at the last valid index. + * @param[in/out] position the position to be bounded. + * @param[in] mapLength the lengths in x and y direction. + * @param[in] mapPosition the position of the map. + */ +void boundPositionToRange(Position& position, const Length& mapLength, const Position& mapPosition); + +/*! + * Provides the alignment transformation from the buffer order (outer/inner storage) + * and the map frame (x/y-coordinate). + * @return the alignment transformation. + */ +Eigen::Matrix2i getBufferOrderToMapFrameAlignment(); + +/*! + * Given a map and a desired submap (defined by position and size), this function computes + * various information about the submap. The returned submap might be smaller than the requested + * size as it respects the boundaries of the map. + * @param[out] submapTopLeftIndex the top left index of the returned submap. + * @param[out] submapBufferSize the buffer size of the returned submap. + * @param[out] submapPosition the position of the submap (center) in the map frame. + * @param[out] submapLength the length of the submap. + * @param[out] requestedIndexInSubmap the index in the submap that corresponds to the requested + * position of the submap. + * @param[in] requestedSubmapPosition the requested submap position (center) in the map frame. + * @param[in] requestedSubmapLength the requested submap length. + * @param[in] mapLength the lengths in x and y direction. + * @param[in] mapPosition the position of the map. + * @param[in] resolution the resolution of the map. + * @param[in] bufferSize the buffer size of the map. + * @param[in] bufferStartIndex the index of the starting point of the circular buffer (optional). + * @return true if successful. + */ +bool getSubmapInformation(Index& submapTopLeftIndex, + Size& submapBufferSize, + Position& submapPosition, + Length& submapLength, + Index& requestedIndexInSubmap, + const Position& requestedSubmapPosition, + const Length& requestedSubmapLength, + const Length& mapLength, + const Position& mapPosition, + const double& resolution, + const Size& bufferSize, + const Index& bufferStartIndex = Index::Zero()); + +/*! + * Computes the buffer size of a submap given a top left and a lower right index. + * @param topLeftIndex the top left index in the map. + * @param bottomRightIndex the bottom right index in the map. + * @return buffer size for the submap. + */ +Size getSubmapSizeFromCornerIndices(const Index& topLeftIndex, const Index& bottomRightIndex, + const Size& bufferSize, const Index& bufferStartIndex); + +/*! + * Computes the regions in the circular buffer that make up the data for + * a requested submap. + * @param[out] submapBufferRegions the list of buffer regions that make up the submap. + * @param[in] submapIndex the index (top-left) for the requested submap. + * @param[in] submapBufferSize the size of the requested submap. + * @param[in] bufferSize the buffer size of the map. + * @param[in] bufferStartIndex the index of the starting point of the circular buffer (optional). + * @return true if successful, false if requested submap is not fully contained in the map. + */ +bool getBufferRegionsForSubmap(std::vector& submapBufferRegions, + const Index& submapIndex, + const Size& submapBufferSize, + const Size& bufferSize, + const Index& bufferStartIndex = Index::Zero()); + +/*! + * Increases the index by one to iterate through the map. + * Increments either to the neighboring index to the right or to + * the start of the lower row. Returns false if end of iterations are reached. + * @param[in/out] index the index in the map that is incremented (corrected for the circular buffer). + * @param[in] bufferSize the map buffer size. + * @param[in] bufferStartIndex the map buffer start index. + * @return true if successfully incremented indices, false if end of iteration limits are reached. + */ +bool incrementIndex(Index& index, const Size& bufferSize, + const Index& bufferStartIndex = Index::Zero()); + +/*! + * Increases the index by one to iterate through the cells of a submap. + * Increments either to the neighboring index to the right or to + * the start of the lower row. Returns false if end of iterations are reached. + * + * Note: This function does not check if submap actually fits to the map. This needs + * to be checked before separately. + * + * @param[in/out] submapIndex the index in the submap that is incremented. + * @param[out] index the index in the map that is incremented (corrected for the circular buffer). + * @param[in] submapTopLefIndex the top left index of the submap. + * @param[in] submapBufferSize the submap buffer size. + * @param[in] bufferSize the map buffer size. + * @param[in] bufferStartIndex the map buffer start index. + * @return true if successfully incremented indices, false if end of iteration limits are reached. + */ +bool incrementIndexForSubmap(Index& submapIndex, Index& index, const Index& submapTopLeftIndex, + const Size& submapBufferSize, const Size& bufferSize, + const Index& bufferStartIndex = Index::Zero()); + +/*! + * Retrieve the index as unwrapped index, i.e., as the corresponding index of a + * grid map with no circular buffer offset. + * @param bufferIndex the index in the circular buffer. + * @param bufferSize the map buffer size. + * @param bufferStartIndex the map buffer start index. + * @return the unwrapped index. + */ +Index getIndexFromBufferIndex(const Index& bufferIndex, const Size& bufferSize, + const Index& bufferStartIndex); + +/*! + * Retrieve the index of the buffer from a unwrapped index (reverse from function above). + * @param index the unwrapped index. + * @param bufferSize the map buffer size. + * @param bufferStartIndex the map buffer start index. + * @return the buffer index. + */ +Index getBufferIndexFromIndex(const Index& index, const Size& bufferSize, const Index& bufferStartIndex); + +/*! + * Returns the linear index (1-dim.) corresponding to the regular index (2-dim.) for either + * row- or column-major format. + * Note: Eigen is defaulting to column-major format. + * @param[in] index the regular 2d index. + * @param[in] bufferSize the map buffer size. + * @param[in] (optional) rowMajor if the linear index is generated for row-major format. + * @return the linear 1d index. + */ +size_t getLinearIndexFromIndex(const Index& index, const Size& bufferSize, bool rowMajor = false); + +/*! + * Returns the regular index (2-dim.) corresponding to the linear index (1-dim.) for a given buffer size. + * @param[in] linearIndex the he linear 1d index. + * @param[in] bufferSize the map buffer size. + * @param[in] (optional) rowMajor if the linear index is generated for row-major format. + * @return the regular 2d index. + */ +Index getIndexFromLinearIndex(size_t linearIndex, const Size& bufferSize, bool rowMajor = false); + +/*! + * Transforms an int color value (concatenated RGB values) to an int color vector (RGB from 0-255). + * @param [in] colorValue the concatenated RGB color value. + * @param [out] colorVector the color vector in RGB from 0-255. + * @return true if successful. + */ +bool colorValueToVector(const unsigned long& colorValue, Eigen::Vector3i& colorVector); + +/*! + * Transforms an int color value (concatenated RGB values) to a float color vector (RGB from 0.0-1.0). + * @param [in] colorValue the concatenated RGB color value. + * @param [out] colorVector the color vector in RGB from 0.0-1.0. + * @return true if successful. + */ +bool colorValueToVector(const unsigned long& colorValue, Eigen::Vector3f& colorVector); + +/*! + * Transforms a float color value (concatenated 3 single-byte value) to a float color vector (RGB from 0.0-1.0). + * @param [in] colorValue the concatenated RGB color value. + * @param [out] colorVector the color vector in RGB from 0.0-1.0. + * @return true if successful. + */ +bool colorValueToVector(const float& colorValue, Eigen::Vector3f& colorVector); + +/*! + * Transforms an int color vector (RGB from 0-255) to a concatenated RGB int color. + * @param [in] colorVector the color vector in RGB from 0-255. + * @param [out] colorValue the concatenated RGB color value. + * @return true if successful. + */ +bool colorVectorToValue(const Eigen::Vector3i& colorVector, unsigned long& colorValue); + +/*! + * Transforms a color vector (RGB from 0-255) to a concatenated 3 single-byte float value. + * @param [in] colorVector the color vector in RGB from 0-255. + * @param [out] colorValue the concatenated RGB color value. + */ +void colorVectorToValue(const Eigen::Vector3i& colorVector, float& colorValue); + +/*! + * Transforms a color vector (RGB from 0.0-1.0) to a concatenated 3 single-byte float value. + * @param [in] colorVector the color vector in RGB from 0.0-1.0. + * @param [out] colorValue the concatenated RGB color value. + */ +void colorVectorToValue(const Eigen::Vector3f& colorVector, float& colorValue); + +} // namespace grid_map diff --git a/include/grid_map_core/Polygon.hpp b/include/grid_map_core/Polygon.hpp new file mode 100644 index 0000000..d7720fb --- /dev/null +++ b/include/grid_map_core/Polygon.hpp @@ -0,0 +1,249 @@ +/* + * Polygon.hpp + * + * Created on: Nov 7, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include + +// STD +#include + +// Eigen +#include + +namespace grid_map { + +class Polygon +{ + public: + + enum class TriangulationMethods { + FAN // Fan triangulation (only for convex polygons). + }; + + /*! + * Default constructor. + */ + Polygon(); + + /*! + * Constructor with vertices. + * @param vertices the points of the polygon. + */ + Polygon(std::vector vertices); + + /*! + * Check if point is inside polygon. + * @param point the point to be checked. + * @return true if inside, false otherwise. + */ + bool isInside(const Position& point) const; + + /*! + * Add a vertex to the polygon + * @param vertex the point to be added. + */ + void addVertex(const Position& vertex); + + /*! + * Get the vertex with index. + * @param index the index of the requested vertex. + * @return the requested vertex. + */ + const Position& getVertex(size_t index) const; + + /*! + * Removes all vertices from the polygon. + */ + void removeVertices(); + + /*! + * Get vertex operator overload. + * @param index the index of the requested vertex. + * @return the requested vertex. + */ + const Position& operator [](size_t index) const; + + /*! + * Returns the vertices of the polygon. + * @return the vertices of the polygon. + */ + const std::vector& getVertices() const; + + /*! + * Returns the number of vertices. + * @return the number of vertices. + */ + size_t nVertices() const; + + /*! + * Set the timestamp of the polygon. + * @param timestamp the timestamp to set (in nanoseconds). + */ + void setTimestamp(uint64_t timestamp); + + /*! + * Get the timestamp of the polygon. + * @return timestamp in nanoseconds. + */ + uint64_t getTimestamp() const; + + /*! + * Resets the timestamp of the polygon (to zero). + */ + void resetTimestamp(); + + /*! + * Set the frame id of the polygon. + * @param frameId the frame id to set. + */ + void setFrameId(const std::string& frameId); + + /*! + * Get the frameId of the polygon. + * @return frameId. + */ + const std::string& getFrameId() const; + + /*! + * Get the area of the polygon. The polygon has to be + * "simple", i.e. not crossing itself. + * @return area of the polygon. + */ + double getArea() const; + + /*! + * Get the centroid of polygon. The polygon has to be + * "simple", i.e. not crossing itself. + * @return centroid of polygon. + */ + Position getCentroid() const; + + /*! + * Gets the bounding box of the polygon. + * @param center the center of the bounding box. + * @param length the side lengths of the bounding box. + */ + void getBoundingBox(Position& center, Length& length) const; + + /*! + * Convert polygon to inequality constraints which most tightly contain the points; i.e., + * create constraints to bound the convex hull of polygon. The inequality constraints are + * represented as A and b, a set of constraints such that A*x <= b defining the region of + * space enclosing the convex hull. + * Based on the VERT2CON MATLAB method by Michael Kleder: + * http://www.mathworks.com/matlabcentral/fileexchange/7895-vert2con-vertices-to-constraints + * @param A the A matrix in of the inequality constraint. + * @param b the b matrix in of the inequality constraint. + * @return true if conversion successful, false otherwise. + */ + bool convertToInequalityConstraints(Eigen::MatrixXd& A, + Eigen::VectorXd& b) const; + + /*! + * Offsets the polygon inward (buffering) by a margin. + * Use a negative margin to offset the polygon outward. + * @param margin the margin to offset the polygon by (in [m]). + * @return true if successful, false otherwise. + */ + bool offsetInward(double margin); + + /*! + * If only two vertices are given, this methods generates a + * `thickened` line polygon with four vertices. + * @param thickness the desired thickness of the line. + * @return true if successful, false otherwise. + */ + bool thickenLine(double thickness); + + /*! + * Return a triangulated version of the polygon. + * @return a list of triangle polygons covering the same polygon. + */ + std::vector triangulate(const TriangulationMethods& method = TriangulationMethods::FAN) const; + + /*! + * Approximates a circle with a polygon. + * @param[in] center the center position of the circle. + * @param[in] radius radius of the circle. + * @param[in] nVertices number of vertices of the approximation polygon. Default = 20. + * @return circle as polygon. + */ + static Polygon fromCircle(Position center, double radius, + int nVertices = 20); + + /*! + * Approximates two circles with a convex hull and returns it as polygon. + * @param[in] center1 the center position of the first circle. + * @param[in] center2 the center position of the second circle. + * @param[in] radius radius of the circles. + * @param[in] nVertices number of vertices of the approximation polygon. Default = 20. + * @return convex hull of the two circles as polygon. + */ + static Polygon convexHullOfTwoCircles(Position center1, + Position center2, + double radius, + int nVertices = 20); + + /*! + * Computes the convex hull of two polygons and returns it as polygon. + * @param[in] polygon1 the first input polygon. + * @param[in] polygon2 the second input polygon. + * @return convex hull as polygon. + */ + static Polygon convexHull(Polygon& polygon1, Polygon& polygon2); + + /*! + * Computes the convex hull of given points, using Andrew's monotone chain convex hull algorithm, and returns it as polygon. + * @param[in] points points to use to compute the convex hull used to create the polygon. + * @return convex hull as polygon. + */ + static Polygon monotoneChainConvexHullOfPoints(const std::vector& points); + + protected: + + /*! + * Returns true if the vector1 and vector2 are sorted lexicographically. + * @param[in] vector1 the first input vector. + * @param[in] vector2 the second input vector. + */ + static bool sortVertices(const Eigen::Vector2d& vector1, + const Eigen::Vector2d& vector2); + + /*! + * Returns the 2D cross product of vector1 and vector2. + * @param[in] vector1 the first input vector. + * @param[in] vector2 the second input vector. + */ + static double computeCrossProduct2D(const Eigen::Vector2d& vector1, + const Eigen::Vector2d& vector2); + + /*! + * Returns true if OAB makes a clockwise turn or if the OA and OB vectors are collinear. + * @param[in] pointO point of the origin O, used to compute OA and OB. + * @param[in] pointA input point A, used to compute OA. + * @param[in] pointB input point B, used to compute OB. + */ + static double vectorsMakeClockwiseTurn(const Eigen::Vector2d& pointO, + const Eigen::Vector2d& pointA, + const Eigen::Vector2d& pointB); + // NOLINTBEGIN(misc-non-private-member-variables-in-classes) + //! Frame id of the polygon. + std::string frameId_; + + //! Timestamp of the polygon (nanoseconds). + uint64_t timestamp_; + + //! Vertices of the polygon. + std::vector vertices_; + // NOLINTEND(misc-non-private-member-variables-in-classes) + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} /* namespace grid_map */ diff --git a/include/grid_map_core/SubmapGeometry.hpp b/include/grid_map_core/SubmapGeometry.hpp new file mode 100644 index 0000000..3e7b048 --- /dev/null +++ b/include/grid_map_core/SubmapGeometry.hpp @@ -0,0 +1,73 @@ +/* + * SubmapGeometry.hpp + * + * Created on: Aug 18, 2015 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include + +namespace grid_map { + +class GridMap; + +/*! + * This class holds information about the geometry of submap + * region of a grid map. Note that, this class does NOT hold + * the any data of the grid map. + */ +class SubmapGeometry +{ + public: + + /*! + * Constructor. Note that the requested position and length + * of the submap is adapted to fit the geometry of the parent + * grid map. + * @param[in] gridMap the parent grid map containing the submap. + * @param[in] position the requested submap position (center). + * @param[in] length the requested submap length. + * @param[out] isSuccess true if successful, false otherwise. + */ + SubmapGeometry(const GridMap& gridMap, const Position& position, const Length& length, + bool& isSuccess); + + virtual ~SubmapGeometry() = default; + + const GridMap& getGridMap() const; + const Length& getLength() const; + const Position& getPosition() const; + const Index& getRequestedIndexInSubmap() const; + const Size& getSize() const; + double getResolution() const; + const Index& getStartIndex() const; + + private: + + //! Parent grid map of the submap. + const GridMap& gridMap_; + + //! Start index (typically top left) index of the submap. + Index startIndex_; + + //! Size of the submap. + Size size_; + + //! Position (center) of the submap. + Position position_; + + //! Length of the submap. + Length length_; + + //! Index in the submap that corresponds to the requested + //! position of the submap. + Index requestedIndexInSubmap_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} /* namespace grid_map */ diff --git a/include/grid_map_core/TypeDefs.hpp b/include/grid_map_core/TypeDefs.hpp new file mode 100644 index 0000000..04a7a36 --- /dev/null +++ b/include/grid_map_core/TypeDefs.hpp @@ -0,0 +1,47 @@ +/* + * TypeDefs.hpp + * + * Created on: March 18, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +// Eigen +#pragma once + +#include + +namespace grid_map { + + using Matrix = Eigen::MatrixXf; + using DataType = Matrix::Scalar; + using Position = Eigen::Vector2d; + using Vector = Eigen::Vector2d; + using Position3 = Eigen::Vector3d; + using Vector3 = Eigen::Vector3d; + using Index = Eigen::Array2i; + using Size = Eigen::Array2i; + using Length = Eigen::Array2d; + using Time = uint64_t; + + /* + * Interpolations are ordered in the order + * of increasing accuracy and computational complexity. + * INTER_NEAREST - fastest, but least accurate, + * INTER_CUBIC - slowest, but the most accurate. + * see: + * https://en.wikipedia.org/wiki/Bicubic_interpolation + * https://web.archive.org/web/20051024202307/http://www.geovista.psu.edu/sites/geocomp99/Gc99/082/gc_082.htm + * for more info. Cubic convolution algorithm is also known as piecewise cubic + * interpolation and in general does not guarantee continuous + * first derivatives. + */ + enum class InterpolationMethods{ + INTER_NEAREST, // nearest neighbor interpolation + INTER_LINEAR, // bilinear interpolation + INTER_CUBIC_CONVOLUTION, //piecewise bicubic interpolation using convolution algorithm + INTER_CUBIC // standard bicubic interpolation + }; + +} // namespace grid_map + diff --git a/include/grid_map_core/eigen_plugins/DenseBasePlugin.hpp b/include/grid_map_core/eigen_plugins/DenseBasePlugin.hpp new file mode 100644 index 0000000..118a6e3 --- /dev/null +++ b/include/grid_map_core/eigen_plugins/DenseBasePlugin.hpp @@ -0,0 +1,32 @@ +#pragma once + +Scalar numberOfFinites() const +{ + if (SizeAtCompileTime==0 || (SizeAtCompileTime==Dynamic && size()==0)) { + return Scalar(0); + } + return Scalar((derived().array() == derived().array()).count()); +} + +Scalar sumOfFinites() const +{ + if (SizeAtCompileTime==0 || (SizeAtCompileTime==Dynamic && size()==0)) { + return Scalar(0); + } + return Scalar(this->redux(Eigen::internal::scalar_sum_of_finites_op())); +} + +Scalar meanOfFinites() const +{ + return Scalar(this->redux(Eigen::internal::scalar_sum_of_finites_op())) / this->numberOfFinites(); +} + +Scalar minCoeffOfFinites() const +{ + return Scalar(this->redux(Eigen::internal::scalar_min_of_finites_op())); +} + +Scalar maxCoeffOfFinites() const +{ + return Scalar(this->redux(Eigen::internal::scalar_max_of_finites_op())); +} diff --git a/include/grid_map_core/eigen_plugins/Functors.hpp b/include/grid_map_core/eigen_plugins/Functors.hpp new file mode 100644 index 0000000..1f9f665 --- /dev/null +++ b/include/grid_map_core/eigen_plugins/Functors.hpp @@ -0,0 +1,28 @@ +/* + * Functors.hpp + * + * Created on: Nov 23, 2015 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +namespace grid_map { + +template +struct Clamp +{ + Clamp(const Scalar& min, const Scalar& max) + : min_(min), + max_(max) + { + } + Scalar operator()(const Scalar& x) const + { + return x < min_ ? min_ : (x > max_ ? max_ : x); + } + Scalar min_, max_; +}; + +} // namespace grid_map diff --git a/include/grid_map_core/eigen_plugins/FunctorsPlugin.hpp b/include/grid_map_core/eigen_plugins/FunctorsPlugin.hpp new file mode 100644 index 0000000..77aa039 --- /dev/null +++ b/include/grid_map_core/eigen_plugins/FunctorsPlugin.hpp @@ -0,0 +1,59 @@ +#include + +template struct scalar_sum_of_finites_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_sum_of_finites_op) + EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { + using std::isfinite; + if (isfinite(a) && isfinite(b)) return a + b; + if (isfinite(a)) return a; + if (isfinite(b)) return b; + return a + b; + } +}; +template +struct functor_traits > { + enum { + Cost = 2 * NumTraits::ReadCost + NumTraits::AddCost, + PacketAccess = false + }; +}; + +template +struct scalar_min_of_finites_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_min_of_finites_op) + EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { + using std::min; + using std::isfinite; + if (isfinite(a) && isfinite(b)) return (min)(a, b); + if (isfinite(a)) return a; + if (isfinite(b)) return b; + return (min)(a, b); + } +}; +template +struct functor_traits > { + enum { + Cost = NumTraits::AddCost, + PacketAccess = false + }; +}; + +template +struct scalar_max_of_finites_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_max_of_finites_op) + EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { + using std::max; + using std::isfinite; + if (isfinite(a) && isfinite(b)) return (max)(a, b); + if (isfinite(a)) return a; + if (isfinite(b)) return b; + return (max)(a, b); + } +}; +template +struct functor_traits > { + enum { + Cost = NumTraits::AddCost, + PacketAccess = false + }; +}; diff --git a/include/grid_map_core/grid_map_core.hpp b/include/grid_map_core/grid_map_core.hpp new file mode 100644 index 0000000..d714311 --- /dev/null +++ b/include/grid_map_core/grid_map_core.hpp @@ -0,0 +1,18 @@ +/* + * grid_map_core.hpp + * + * Created on: Jul 14, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/TypeDefs.hpp" +#include "grid_map_core/GridMap.hpp" +#include "grid_map_core/SubmapGeometry.hpp" +#include "grid_map_core/GridMapMath.hpp" +#include "grid_map_core/BufferRegion.hpp" +#include "grid_map_core/Polygon.hpp" +#include "grid_map_core/iterators/iterators.hpp" +#include "grid_map_core/eigen_plugins/Functors.hpp" diff --git a/include/grid_map_core/gtest_eigen.hpp b/include/grid_map_core/gtest_eigen.hpp new file mode 100644 index 0000000..8872ab8 --- /dev/null +++ b/include/grid_map_core/gtest_eigen.hpp @@ -0,0 +1,165 @@ +/** + * @file gtest.hpp + * @author Paul Furgale + * @date Mon Dec 12 11:54:20 2011 + * @brief Code to simplify Eigen integration into GTest. Pretty basic but the error messages are good. + */ + +#pragma once + +#include +#include +#include +#include + +namespace grid_map { + + template + Eigen::Matrix randomCovariance() + { + Eigen::Matrix U; + U.setRandom(); + return U.transpose() * U + 5.0 * Eigen::Matrix::Identity(); + } + + inline Eigen::MatrixXd randomCovarianceXd(int N) + { + Eigen::MatrixXd U(N,N); + U.setRandom(); + return U.transpose() * U + 5.0 * Eigen::MatrixXd::Identity(N,N); + } + + template + void assertEqual(const M1 & A, const M2 & B, std::string const & message = "") + { + ASSERT_EQ((size_t)A.rows(),(size_t)B.rows()) << message << "\nMatrix A:\n" << A << "\nand matrix B\n" << B << "\nare not the same\n"; + ASSERT_EQ((size_t)A.cols(),(size_t)B.cols()) << message << "\nMatrix A:\n" << A << "\nand matrix B\n" << B << "\nare not the same\n"; + + for(int r = 0; r < A.rows(); r++) + { + for(int c = 0; c < A.cols(); c++) + { + if (std::isnan(A(r,c))) { + ASSERT_TRUE(std::isnan(B(r,c))) << message << "\nNaN check failed at (" << r << "," << c << ")\n" + << "\nMatrix A:\n" << A << "\nand matrix B\n" << B; + } else { + ASSERT_EQ(A(r,c),B(r,c)) << message << "\nEquality comparison failed at (" << r << "," << c << ")\n" + << "\nMatrix A:\n" << A << "\nand matrix B\n" << B; + } + } + } + } + + template + void assertNear(const M1 & A, const M2 & B, T tolerance, std::string const & message = "") + { + // Note: If these assertions fail, they only abort this subroutine. + // see: http://code.google.com/p/googletest/wiki/AdvancedGuide#Using_Assertions_in_Sub-routines + // \todo better handling of this + ASSERT_EQ((size_t)A.rows(),(size_t)B.rows()) << message << "\nMatrix A:\n" << A << "\nand matrix B\n" << B << "\nare not the same\n"; + ASSERT_EQ((size_t)A.cols(),(size_t)B.cols()) << message << "\nMatrix A:\n" << A << "\nand matrix B\n" << B << "\nare not the same\n"; + + for(int r = 0; r < A.rows(); r++) + { + for(int c = 0; c < A.cols(); c++) + { + if (std::isnan(A(r,c))) { + ASSERT_TRUE(std::isnan(B(r,c))) << message << "\nNaN check failed at (" << r << "," << c << ")\n" + << "\nMatrix A:\n" << A << "\nand matrix B\n" << B; + } else { + ASSERT_NEAR(A(r,c),B(r,c),tolerance) << message << "\nTolerance comparison failed at (" << r << "," << c << ")\n" + << "\nMatrix A:\n" << A << "\nand matrix B\n" << B; + } + } + } + } + + template + void expectNear(const M1 & A, const M2 & B, T tolerance, std::string const & message = "") + { + EXPECT_EQ((size_t)A.rows(),(size_t)B.rows()) << message << "\nMatrix A:\n" << A << "\nand matrix B\n" << B << "\nare not the same\n"; + EXPECT_EQ((size_t)A.cols(),(size_t)B.cols()) << message << "\nMatrix A:\n" << A << "\nand matrix B\n" << B << "\nare not the same\n"; + + for(int r = 0; r < A.rows(); r++) + { + for(int c = 0; c < A.cols(); c++) + { + if (std::isnan(A(r,c))) { + EXPECT_TRUE(std::isnan(B(r,c))) << message << "\nNaN check failed at (" << r << "," << c << ")\n" + << "\nMatrix A:\n" << A << "\nand matrix B\n" << B; + } else { + EXPECT_NEAR(A(r,c),B(r,c),tolerance) << message << "\nTolerance comparison failed at (" << r << "," << c << ")\n" + << "\nMatrix A:\n" << A << "\nand matrix B\n" << B; + } + } + } + } + + template + void assertFinite(const M1 & A, std::string const & /*message*/ = "") + { + std::cout << ("test") << std::endl; + for(int r = 0; r < A.rows(); r++) + { + for(int c = 0; c < A.cols(); c++) + { + ASSERT_TRUE(std::isfinite(A(r,c))) << std::endl << "Check for finite values failed at A(" << r << "," << c << "). Matrix A:" << std::endl << A << std::endl; + } + } + } + + inline bool compareRelative(double a, double b, double percentTolerance, double* percentError = nullptr) { + // \todo: does anyone have a better idea? + double fa = fabs(a); + double fb = fabs(b); + if ((fa < 1e-15 && fb < 1e-15) || // Both zero. + (fa == 0.0 && fb < 1e-6) || // One exactly zero and the other small + (fb == 0.0 && fa < 1e-6)) { // ditto + return true; + } + + double diff = fabs(a - b) / std::max(fa, fb); + if (diff > percentTolerance * 1e-2) { + if (percentError != nullptr) { + *percentError = diff * 100.0; + } + return false; + } + return true; + } + +#define ASSERT_DOUBLE_MX_EQ(A, B, PERCENT_TOLERANCE, MSG) \ + ASSERT_EQ((size_t)(A).rows(), (size_t)(B).rows()) << (MSG) << "\nMatrix " << #A << ":\n" << (A) << "\nand matrix " << #B << "\n" << (B) << "\nare not the same size"; \ + ASSERT_EQ((size_t)(A).cols(), (size_t)(B).cols()) << (MSG) << "\nMatrix " << #A << ":\n" << (A) << "\nand matrix " << #B << "\n" << (B) << "\nare not the same size"; \ + for(int r = 0; r < (A).rows(); r++) \ + { \ + for(int c = 0; c < (A).cols(); c++) \ + { \ + double percentError = 0.0; \ + ASSERT_TRUE(grid_map::compareRelative( (A)(r,c), (B)(r,c), PERCENT_TOLERANCE, &percentError)) \ + << (MSG) << "\nComparing:\n" \ + << #A << "(" << r << "," << c << ") = " << (A)(r,c) << std::endl \ + << #B << "(" << r << "," << c << ") = " << (B)(r,c) << std::endl \ + << "Error was " << percentError << "% > " << (PERCENT_TOLERANCE) << "%\n" \ + << "\nMatrix " << #A << ":\n" << (A) << "\nand matrix " << #B << "\n" << (B); \ + } \ + } + +#define ASSERT_DOUBLE_SPARSE_MX_EQ(A, B, PERCENT_TOLERANCE, MSG) \ + ASSERT_EQ((size_t)(A).rows(), (size_t)(B).rows()) << (MSG) << "\nMatrix " << #A << ":\n" << (A) << "\nand matrix " << #B << "\n" << (B) << "\nare not the same size"; \ + ASSERT_EQ((size_t)(A).cols(), (size_t)(B).cols()) << (MSG) << "\nMatrix " << #A << ":\n" << (A) << "\nand matrix " << #B << "\n" << (B) << "\nare not the same size"; \ + for(int r = 0; r < (A).rows(); r++) \ + { \ + for(int c = 0; c < (A).cols(); c++) \ + { \ + double percentError = 0.0; \ + ASSERT_TRUE(grid_map::compareRelative( (A).coeff(r,c), (B).coeff(r,c), PERCENT_TOLERANCE, &percentError)) \ + << (MSG) << "\nComparing:\n" \ + << #A << "(" << r << "," << c << ") = " << (A).coeff(r,c) << std::endl \ + << #B << "(" << r << "," << c << ") = " << (B).coeff(r,c) << std::endl \ + << "Error was " << percentError << "% > " << (PERCENT_TOLERANCE) << "%\n" \ + << "\nMatrix " << #A << ":\n" << (A) << "\nand matrix " << #B << "\n" << (B); \ + } \ + } + +} // namespace grid_map diff --git a/include/grid_map_core/iterators/CircleIterator.hpp b/include/grid_map_core/iterators/CircleIterator.hpp new file mode 100644 index 0000000..14f2713 --- /dev/null +++ b/include/grid_map_core/iterators/CircleIterator.hpp @@ -0,0 +1,101 @@ +/* + * CircleIterator.hpp + * + * Created on: Nov 13, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/GridMap.hpp" +#include "grid_map_core/iterators/SubmapIterator.hpp" + +#include + +#include + +namespace grid_map { + +/*! + * Iterator class to iterate through a circular area of the map. + */ +class CircleIterator +{ +public: + + /*! + * Constructor. + * @param gridMap the grid map to iterate on. + * @param center the position of the circle center. + * @param radius the radius of the circle. + */ + CircleIterator(const GridMap& gridMap, const Position& center, double radius); + + /*! + * Compare to another iterator. + * @return whether the current iterator points to a different address than the other one. + */ + bool operator !=(const CircleIterator& other) const; + + /*! + * Dereference the iterator with const. + * @return the value to which the iterator is pointing. + */ + const Index& operator *() const; + + /*! + * Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + CircleIterator& operator ++(); + + /*! + * Indicates if iterator is past end. + * @return true if iterator is out of scope, false if end has not been reached. + */ + bool isPastEnd() const; + +private: + + /*! + * Check if current index is inside the circle. + * @return true if inside, false otherwise. + */ + bool isInside() const; + + /*! + * Finds the submap that fully contains the circle and returns the parameters. + * @param[in] center the position of the circle center. + * @param[in] radius the radius of the circle. + * @param[out] startIndex the start index of the submap. + * @param[out] bufferSize the buffer size of the submap. + */ + void findSubmapParameters(const Position& center, double radius, + Index& startIndex, Size& bufferSize) const; + + //! Position of the circle center; + Position center_; + + //! Radius of the circle. + double radius_; + + //! Square of the radius (for efficiency). + double radiusSquare_; + + //! Grid submap iterator. // TODO Think of using unique_ptr instead. + std::shared_ptr internalIterator_; + + //! Map information needed to get position from iterator. + Length mapLength_; + Position mapPosition_; + double resolution_; + Size bufferSize_; + Index bufferStartIndex_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace grid_map + diff --git a/include/grid_map_core/iterators/EllipseIterator.hpp b/include/grid_map_core/iterators/EllipseIterator.hpp new file mode 100644 index 0000000..06be4d4 --- /dev/null +++ b/include/grid_map_core/iterators/EllipseIterator.hpp @@ -0,0 +1,110 @@ +/* + * EllipseIterator.hpp + * + * Created on: Dec 2, 2015 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/GridMap.hpp" +#include "grid_map_core/iterators/SubmapIterator.hpp" + +#include + +#include + +namespace grid_map { + +/*! + * Iterator class to iterate through a ellipsoid area of the map. + * The main axis of the ellipse are aligned with the map frame. + */ +class EllipseIterator +{ +public: + + /*! + * Constructor. + * @param gridMap the grid map to iterate on. + * @param center the position of the ellipse center. + * @param length the length of the main axis. + * @param angle the rotation angle of the ellipse (in [rad]). + */ + EllipseIterator(const GridMap& gridMap, const Position& center, const Length& length, double rotation = 0.0); + + /*! + * Compare to another iterator. + * @return whether the current iterator points to a different address than the other one. + */ + bool operator !=(const EllipseIterator& other) const; + + /*! + * Dereference the iterator with const. + * @return the value to which the iterator is pointing. + */ + const Index& operator *() const; + + /*! + * Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + EllipseIterator& operator ++(); + + /*! + * Indicates if iterator is past end. + * @return true if iterator is out of scope, false if end has not been reached. + */ + bool isPastEnd() const; + + /*! + * Returns the size of the submap covered by the iterator. + * @return the size of the submap covered by the iterator. + */ + const Size& getSubmapSize() const; + +private: + + /*! + * Check if current index is inside the ellipse. + * @return true if inside, false otherwise. + */ + bool isInside() const; + + /*! + * Finds the submap that fully contains the ellipse and returns the parameters. + * @param[in] center the position of the ellipse center. + * @param[in] length the length of the main axis. + * @param[in] angle the rotation angle of the ellipse (in [rad]). + * @param[out] startIndex the start index of the submap. + * @param[out] bufferSize the buffer size of the submap. + */ + void findSubmapParameters(const Position& center, const Length& length, double rotation, + Index& startIndex, Size& bufferSize) const; + + //! Position of the circle center; + Position center_; + + //! Square length of the semi axis. + Eigen::Array2d semiAxisSquare_; + + //! Sine and cosine values of the rotation angle as transformation matrix. + Eigen::Matrix2d transformMatrix_; + + //! Grid submap iterator. // TODO Think of using unique_ptr instead. + std::shared_ptr internalIterator_; + + //! Map information needed to get position from iterator. + Length mapLength_; + Position mapPosition_; + double resolution_; + Size bufferSize_; + Index bufferStartIndex_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace grid_map + diff --git a/include/grid_map_core/iterators/GridMapIterator.hpp b/include/grid_map_core/iterators/GridMapIterator.hpp new file mode 100644 index 0000000..3a3443b --- /dev/null +++ b/include/grid_map_core/iterators/GridMapIterator.hpp @@ -0,0 +1,105 @@ +/* + * GridMapIterator.hpp + * + * Created on: Sep 22, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/GridMap.hpp" + +// Eigen +#include + +namespace grid_map { + +/*! + * Iterator class to iterate trough the entire grid map. + */ +class GridMapIterator +{ +public: + + /*! + * Constructor. + * @param gridMap the grid map to iterate on. + */ + GridMapIterator(const grid_map::GridMap &gridMap); + + /*! + * Copy constructor. + * @param other the object to copy. + */ + GridMapIterator(const GridMapIterator* other); + + /*! + * Compare to another iterator. + * @return whether the current iterator points to a different address than the other one. + */ + bool operator !=(const GridMapIterator& other) const; + + /*! + * Dereference the iterator to return the regular index (2-dim.) of the cell + * to which the iterator is pointing at. + * @return the regular index (2-dim.) of the cell on which the iterator is pointing. + */ + Index operator *() const; + + /*! + * Returns the the linear (1-dim.) index of the cell the iterator is pointing at. + * Note: Use this access for improved efficiency when working with large maps. + * Example: See `runGridMapIteratorVersion3()` of `grid_map_demos/src/iterator_benchmark.cpp`. + * @return the 1d linear index. + */ + const size_t& getLinearIndex() const; + + /*! + * Retrieve the index as unwrapped index, i.e., as the corresponding index of a + * grid map with no circular buffer offset. + */ + Index getUnwrappedIndex() const; + + /*! + * Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + virtual GridMapIterator& operator ++(); + + /*! + * Return the end iterator + * @return the end iterator (useful when performing normal iterator processing with ++). + */ + GridMapIterator end() const; + + /*! + * Indicates if iterator is past end. + * @return true if iterator is out of scope, false if end has not been reached. + */ + bool isPastEnd() const; + + protected: + // NOLINTBEGIN(misc-non-private-member-variables-in-classes) + //! Size of the buffer. + Size size_; + + //! Start index of the circular buffer. + Index startIndex_; + + //! Linear size of the data. + size_t linearSize_; + + //! Linear index. + size_t linearIndex_; + + //! Is iterator out of scope. + bool isPastEnd_; + // NOLINTEND(misc-non-private-member-variables-in-classes) + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace grid_map + diff --git a/include/grid_map_core/iterators/LineIterator.hpp b/include/grid_map_core/iterators/LineIterator.hpp new file mode 100644 index 0000000..ffbdc9c --- /dev/null +++ b/include/grid_map_core/iterators/LineIterator.hpp @@ -0,0 +1,126 @@ +/* + * LineIterator.hpp + * + * Created on: Nov 13, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/GridMap.hpp" +#include "grid_map_core/iterators/SubmapIterator.hpp" + +#include + +namespace grid_map { + +/*! + * Iterator class to iterate over a line in the map. + * Based on Bresenham Line Drawing algorithm. + */ +class LineIterator +{ +public: + + /*! + * Constructor. + * @param gridMap the grid map to iterate on. + * @param start the starting point of the line. + * @param end the ending point of the line. + * @throw std::invalid_argument if start and end impose an ill conditioned line iteration. + */ + LineIterator(const grid_map::GridMap& gridMap, const Position& start, const Position& end); + + /*! + * Constructor. + * @param gridMap the grid map to iterate on. + * @param start the starting index of the line. + * @param end the ending index of the line. + */ + LineIterator(const grid_map::GridMap& gridMap, const Index& start, const Index& end); + + /*! + * Compare to another iterator. + * @return whether the current iterator points to a different address than the other one. + */ + bool operator !=(const LineIterator& other) const; + + /*! + * Dereference the iterator with const. + * @return the value to which the iterator is pointing. + */ + const Index& operator *() const; + + /*! + * Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + LineIterator& operator ++(); + + /*! + * Indicates if iterator is past end. + * @return true if iterator is out of scope, false if end has not been reached. + */ + bool isPastEnd() const; + +private: + + + /*! + * Construct function. + * @param gridMap the grid map to iterate on. + * @param start the starting index of the line. + * @param end the ending index of the line. + * @return true if successful, false otherwise. + */ + bool initialize(const grid_map::GridMap& gridMap, const Index& start, const Index& end); + + /*! + * Computes the parameters requires for the line drawing algorithm. + */ + void initializeIterationParameters(); + + /*! + * Finds the index of a position on a line within the limits of the map. + * @param[in] gridMap the grid map that defines the map boundaries. + * @param[in] start the position that will be limited to the map range. + * @param[in] end the ending position of the line. + * @param[out] index the index of the moved start position. + * @return true if successful, false otherwise. + */ + static bool getIndexLimitedToMapRange(const grid_map::GridMap& gridMap, const Position& start, + const Position& end, Index& index); + + //! Current index. + Index index_; + + //! Starting index of the line. + Index start_; + + //! Ending index of the line. + Index end_; + + //! Current cell number. + unsigned int iCell_ = 0; + + //! Number of cells in the line. + unsigned int nCells_ = 0; + + //! Helper variables for Bresenham Line Drawing algorithm. + Size increment1_, increment2_; + int denominator_{0}, numerator_{0}, numeratorAdd_{0}; + + //! Map information needed to get position from iterator. + Length mapLength_; + Position mapPosition_; + double resolution_{NAN}; + Size bufferSize_; + Index bufferStartIndex_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace grid_map + diff --git a/include/grid_map_core/iterators/PolygonIterator.hpp b/include/grid_map_core/iterators/PolygonIterator.hpp new file mode 100644 index 0000000..6027670 --- /dev/null +++ b/include/grid_map_core/iterators/PolygonIterator.hpp @@ -0,0 +1,91 @@ +/* + * PolygonIterator.hpp + * + * Created on: Sep 19, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/GridMap.hpp" +#include "grid_map_core/Polygon.hpp" +#include "grid_map_core/iterators/SubmapIterator.hpp" + +#include + +namespace grid_map { + +/*! + * Iterator class to iterate through a polygonal area of the map. + */ +class PolygonIterator +{ +public: + + /*! + * Constructor. + * @param gridMap the grid map to iterate on. + * @param polygon the polygonal area to iterate on. + */ + PolygonIterator(const grid_map::GridMap& gridMap, const grid_map::Polygon& polygon); + + /*! + * Compare to another iterator. + * @return whether the current iterator points to a different address than the other one. + */ + bool operator !=(const PolygonIterator& other) const; + + /*! + * Dereference the iterator with const. + * @return the value to which the iterator is pointing. + */ + const Index& operator *() const; + + /*! + * Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + PolygonIterator& operator ++(); + + /*! + * Indicates if iterator is past end. + * @return true if iterator is out of scope, false if end has not been reached. + */ + bool isPastEnd() const; + +private: + + /*! + * Check if current index is inside polygon. + * @return true if inside, false otherwise. + */ + bool isInside() const; + + /*! + * Finds the submap that fully contains the polygon and returns the parameters. + * @param[in] polygon the polygon to get the submap for. + * @param[out] startIndex the start index of the submap. + * @param[out] bufferSize the buffer size of the submap. + */ + void findSubmapParameters(const grid_map::Polygon& polygon, Index& startIndex,Size& bufferSize) const; + + //! Polygon to iterate on. + grid_map::Polygon polygon_; + + //! Grid submap iterator. + std::shared_ptr internalIterator_; + + //! Map information needed to get position from iterator. + Length mapLength_; + Position mapPosition_; + double resolution_; + Size bufferSize_; + Index bufferStartIndex_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace grid_map + diff --git a/include/grid_map_core/iterators/SlidingWindowIterator.hpp b/include/grid_map_core/iterators/SlidingWindowIterator.hpp new file mode 100644 index 0000000..42b2a95 --- /dev/null +++ b/include/grid_map_core/iterators/SlidingWindowIterator.hpp @@ -0,0 +1,95 @@ +/* + * SlidingWindowIterator.hpp + * + * Created on: Aug 17, 2017 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/GridMap.hpp" + +#include "grid_map_core/iterators/GridMapIterator.hpp" + +#include + +namespace grid_map { + +/*! + * Iterator class to iterate trough the entire grid map with access to a layer's + * data through a sliding window. + * Note: This iterator only works with maps with zero start index. + */ +class SlidingWindowIterator : public GridMapIterator +{ +public: + + enum class EdgeHandling { + INSIDE, // Only visit indices that are surrounded by a full window. + CROP, // Crop data matrix with missing cells at edges. + EMPTY, // Fill in missing edges with empty cells (NAN-value). + MEAN // Fill in missing edges with MEAN of valid values. + }; + + /*! + * Constructor. + * @param gridMap the grid map to iterate on. + * @param layer the layer on which the data is accessed. + * @param edgeHandling the method to handle edges of the map. + * @param windowSize the size of the moving window in number of cells (has to be an odd number!). + */ + SlidingWindowIterator(const GridMap& gridMap, const std::string& layer, + const EdgeHandling& edgeHandling = EdgeHandling::CROP, + size_t windowSize = 3); + + /*! + * Copy constructor. + * @param other the object to copy. + */ + explicit SlidingWindowIterator(const SlidingWindowIterator* other); + + /*! + * Set the side length of the moving window (in m). + * @param gridMap the grid map to iterate on. + * @param windowLength the side length of the window (in m). + */ + void setWindowLength(const GridMap& gridMap, double windowLength); + + /*! + * Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + SlidingWindowIterator& operator ++() override; + + /*! + * Return the data of the sliding window. + * @return the data of the sliding window. + */ + Matrix getData() const; + +private: + //! Setup members. + void setup(const GridMap& gridMap); + + //! Check if data for current index is fully inside map. + bool dataInsideMap() const; + + //! Edge handling method. + const EdgeHandling edgeHandling_; + + //! Data. + const Matrix& data_; + + //! Size of the sliding window. + size_t windowSize_; + + //! Size of the border of the window around the center cell. + size_t windowMargin_{0}; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace grid_map + diff --git a/include/grid_map_core/iterators/SpiralIterator.hpp b/include/grid_map_core/iterators/SpiralIterator.hpp new file mode 100644 index 0000000..f1c3966 --- /dev/null +++ b/include/grid_map_core/iterators/SpiralIterator.hpp @@ -0,0 +1,109 @@ +/* + * SpiralIterator.hpp + * + * Created on: Jul 7, 2015 + * Author: Martin Wermelinger + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/GridMap.hpp" + +#include +#include +#include + +namespace grid_map { + +/*! + * Iterator class to iterate through a circular area of the map with a spiral. + */ +class SpiralIterator +{ +public: + + /*! + * Constructor. + * @param gridMap the grid map to iterate on. + * @param center the position of the circle center. + * @param radius the radius of the circle. + */ + SpiralIterator(const grid_map::GridMap& gridMap, Eigen::Vector2d center, double radius); + + /*! + * Compare to another iterator. + * @return whether the current iterator points to a different address than the other one. + */ + bool operator !=(const SpiralIterator& other) const; + + /*! + * Dereference the iterator with const. + * @return the value to which the iterator is pointing. + */ + const Eigen::Array2i& operator *() const; + + /*! + * Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + SpiralIterator& operator ++(); + + /*! + * Indicates if iterator is past end. + * @return true if iterator is out of scope, false if end has not been reached. + */ + bool isPastEnd() const; + + /*! + * Gets the radius of current ring that is iterated through. + * @return radius of the current ring that is used for iteration. + */ + double getCurrentRadius() const; + +private: + + /*! + * Check if index is inside the circle. + * @return true if inside, false otherwise. + */ + bool isInside(const Index& index) const; + + /*! + * Uses the current distance to get the points of a ring + * around the center. + */ + void generateRing(); + + static int signum(const int val) { + return static_cast(0 < val) - static_cast(val < 0); + } + + //! Position of the circle center; + Position center_; + Index indexCenter_; + + + //! Radius of the circle. + double radius_; + + //! Square of the radius for efficiency. + double radiusSquare_; + + //! Number of rings into the circle is divided. + unsigned int nRings_; + unsigned int distance_; + std::vector pointsRing_; + + //! Map information needed to get position from iterator. + Length mapLength_; + Position mapPosition_; + double resolution_; + Size bufferSize_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace grid_map + diff --git a/include/grid_map_core/iterators/SubmapIterator.hpp b/include/grid_map_core/iterators/SubmapIterator.hpp new file mode 100644 index 0000000..3cf1a1a --- /dev/null +++ b/include/grid_map_core/iterators/SubmapIterator.hpp @@ -0,0 +1,119 @@ +/* + * SubmapIterator.hpp + * + * Created on: Sep 12, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/GridMap.hpp" +#include "grid_map_core/SubmapGeometry.hpp" +#include "grid_map_core/BufferRegion.hpp" + +#include + +namespace grid_map { + +/*! + * Iterator class to iterate through a rectangular part of the map (submap). + * Before using this iterator, make sure that the requested submap is + * actually contained in the grid map. + */ +class SubmapIterator +{ +public: + + /*! + * Constructor. + * @param submap the submap geometry to iterate over. + */ + SubmapIterator(const grid_map::SubmapGeometry& submap); + + /*! + * Constructor. + * @param submap the buffer region of a grid map to iterate over. + */ + SubmapIterator(const grid_map::GridMap& gridMap, const grid_map::BufferRegion& bufferRegion); + + /*! + * Constructor. + * @param gridMap the grid map to iterate on. + * @param submapStartIndex the start index of the submap, typically top-left index. + * @param submapSize the size of the submap to iterate on. + */ + SubmapIterator(const grid_map::GridMap& gridMap, const Index& submapStartIndex, + const Size& submapSize); + + /*! + * Copy constructor. + * @param other the object to copy. + */ + SubmapIterator(const SubmapIterator* other); + + /*! + * Compare to another iterator. + * @return whether the current iterator points to a different address than the other one. + */ + bool operator !=(const SubmapIterator& other) const; + + /*! + * Dereference the iterator with const. + * @return the value to which the iterator is pointing. + */ + const Index& operator *() const; + + /*! + * Get the current index in the submap. + * @return the current index in the submap. + */ + const Index& getSubmapIndex() const; + + /*! + * Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + SubmapIterator& operator ++(); + + /*! + * Indicates if iterator is past end. + * @return true if iterator is out of scope, false if end has not been reached. + */ + bool isPastEnd() const; + + /*! + * Returns the size of the submap covered by the iterator. + * @return the size of the submap covered by the iterator. + */ + const Size& getSubmapSize() const; + +private: + + //! Size of the buffer. + Size size_; + + //! Start index of the circular buffer. + Index startIndex_; + + //! Current index. + Index index_; + + //! Submap buffer size. + Size submapSize_; + + //! Top left index of the submap. + Index submapStartIndex_; + + //! Current index in the submap. + Index submapIndex_; + + //! Is iterator out of scope. + bool isPastEnd_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace grid_map + diff --git a/include/grid_map_core/iterators/iterators.hpp b/include/grid_map_core/iterators/iterators.hpp new file mode 100644 index 0000000..1d919aa --- /dev/null +++ b/include/grid_map_core/iterators/iterators.hpp @@ -0,0 +1,18 @@ +/* + * iterators.hpp + * + * Created on: Sep 22, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#pragma once + +#include "grid_map_core/iterators/GridMapIterator.hpp" +#include "grid_map_core/iterators/SubmapIterator.hpp" +#include "grid_map_core/iterators/CircleIterator.hpp" +#include "grid_map_core/iterators/EllipseIterator.hpp" +#include "grid_map_core/iterators/SpiralIterator.hpp" +#include "grid_map_core/iterators/LineIterator.hpp" +#include "grid_map_core/iterators/PolygonIterator.hpp" +#include "grid_map_core/iterators/SlidingWindowIterator.hpp" diff --git a/include/grid_map_core/utils/testing.hpp b/include/grid_map_core/utils/testing.hpp new file mode 100644 index 0000000..e997c2f --- /dev/null +++ b/include/grid_map_core/utils/testing.hpp @@ -0,0 +1,37 @@ +/** + * Copied from ANYbotics/eigen_utils, to avoid testing dependency. + */ + +#pragma once + +#include +#include + +#define ASSERT_MATRICES_EQ_WITH_NAN(first, second) assertMatrixesEqualWithNan((first), #first, (second), #second, __LINE__) +static void assertMatrixesEqualWithNan(Eigen::Ref first, std::string firstName, + Eigen::Ref second, std::string secondName, int line) { + ASSERT_EQ(first.rows(), second.rows()); + ASSERT_EQ(first.cols(), second.cols()); + + bool matricesAreEqual = true; + for (Eigen::Index row = 0; row < first.rows() && matricesAreEqual; ++row) { + for (Eigen::Index col = 0; col < first.cols() && matricesAreEqual; ++col) { + bool ifRealThenValid = first.block<1, 1>(row, col).isApprox(second.block<1, 1>(row, col)); + bool bothNaN = std::isnan(first(row, col)) && std::isnan(second(row, col)); + if (ifRealThenValid || bothNaN) { + continue; + } else { + matricesAreEqual = false; + } + } + } + + Eigen::IOFormat compactFormat(2, 0, ",", "\n", "[", "]"); + ASSERT_TRUE(matricesAreEqual) // NO LINT + << "L. " << std::to_string(line) << ": Matrices are not equal" // NO LINT + << "\n" // NO LINT + << firstName << "\n" // NO LINT + << first.format(compactFormat) << "\n" // NO LINT + << secondName << "\n" // NO LINT + << second.format(compactFormat) << "\n"; // NO LINT +} diff --git a/package.xml b/package.xml new file mode 100644 index 0000000..ac020f6 --- /dev/null +++ b/package.xml @@ -0,0 +1,17 @@ + + + grid_map_core + 1.7.18 + Universal grid map library to manage two-dimensional grid maps with multiple data layers. + Maximilian Wulf + Yoshua Nava + BSD + http://github.com/anybotics/grid_map + http://github.com/anybotics/grid_map/issues + Péter Fankhauser + catkin + + eigen + + gtest + diff --git a/src/BufferRegion.cpp b/src/BufferRegion.cpp new file mode 100644 index 0000000..4c1e8e6 --- /dev/null +++ b/src/BufferRegion.cpp @@ -0,0 +1,56 @@ +/* + * BufferRegion.cpp + * + * Created on: Aug 19, 2015 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ +#include + +namespace grid_map { + +BufferRegion::BufferRegion() : startIndex_(Index::Zero()), + size_(Size::Zero()), + quadrant_(BufferRegion::Quadrant::Undefined) +{ +} + +BufferRegion::BufferRegion(Index index, Size size, BufferRegion::Quadrant quadrant) : startIndex_(std::move(index)), + size_(std::move(size)), + quadrant_(std::move(quadrant)) +{ +} + +const Index& BufferRegion::getStartIndex() const +{ + return startIndex_; +} + +void BufferRegion::setStartIndex(const Index& startIndex) +{ + startIndex_ = startIndex; +} + +const Size& BufferRegion::getSize() const +{ + return size_; +} + +void BufferRegion::setSize(const Size& size) +{ + size_ = size; +} + +BufferRegion::Quadrant BufferRegion::getQuadrant() const +{ + return quadrant_; +} + +void BufferRegion::setQuadrant(BufferRegion::Quadrant type) +{ + quadrant_ = type; +} + +} /* namespace grid_map */ + + diff --git a/src/CubicInterpolation.cpp b/src/CubicInterpolation.cpp new file mode 100644 index 0000000..d9eb2fc --- /dev/null +++ b/src/CubicInterpolation.cpp @@ -0,0 +1,436 @@ +/* + * CubicInterpolation.cpp + * + * Created on: Jan 21, 2020 + * Author: Edo Jelavic + * Institute: ETH Zurich, Robotic Systems Lab + */ + +#include "grid_map_core/CubicInterpolation.hpp" + +#include "grid_map_core/GridMap.hpp" + +namespace grid_map { + +unsigned int bindIndexToRange(unsigned int idReq, unsigned int nElem) +{ + if (idReq >= nElem) { + return (nElem - 1); + } + return idReq; +} + +double getLayerValue(const Matrix &layerMat, unsigned int rowReq, unsigned int colReq) +{ + const auto numCol = static_cast(layerMat.cols()); + const auto numRow = static_cast(layerMat.rows()); + const unsigned int iBoundToRange = bindIndexToRange(rowReq, numRow); + const unsigned int jBoundToRange = bindIndexToRange(colReq, numCol); + return layerMat(iBoundToRange, jBoundToRange); +} + + +/** + * BICUBIC CONVOLUTION INTERPOLATION ALGORITHM + * also known as piecewise bicubic interpolation, + * it does not ensure continuity of the first derivatives. + * see: + * https://en.wikipedia.org/wiki/Bicubic_interpolation + * https://web.archive.org/web/20051024202307/http://www.geovista.psu.edu/sites/geocomp99/Gc99/082/gc_082.htm + */ + +namespace bicubic_conv { + +bool evaluateBicubicConvolutionInterpolation(const GridMap &gridMap, const std::string &layer, + const Position &queriedPosition, + double *interpolatedValue) +{ + FunctionValueMatrix functionValues; + if (!assembleFunctionValueMatrix(gridMap, layer, queriedPosition, &functionValues)) { + return false; + } + + Position normalizedCoordinate; + if (!getNormalizedCoordinates(gridMap, queriedPosition, &normalizedCoordinate)) { + return false; + } + + const double tx = normalizedCoordinate.x(); + const double ty = normalizedCoordinate.y(); + + //bm1 stands for b minus one, i.e. index decreased by one + //b2 stands for b plus 2, i.e. index increased by two + const double bm1 = convolve1D(tx, functionValues.row(0)); + const double b0 = convolve1D(tx, functionValues.row(1)); + const double b1 = convolve1D(tx, functionValues.row(2)); + const double b2 = convolve1D(tx, functionValues.row(3)); + const Eigen::Vector4d vectorBs(bm1, b0, b1, b2); + *interpolatedValue = convolve1D(ty, vectorBs); + return true; +} + +double convolve1D(double t, const Eigen::Vector4d &functionValues) +{ + const Eigen::Vector4d tVector(1.0, t, t * t, t * t * t); + const Eigen::Vector4d temp = cubicInterpolationConvolutionMatrix + * functionValues; + const double retVal = 0.5 * tVector.transpose() * temp; + return retVal; +} + +bool assembleFunctionValueMatrix(const GridMap &gridMap, const std::string &layer, + const Position &queriedPosition, FunctionValueMatrix *data) +{ + + Index middleKnotIndex; + if (!getIndicesOfMiddleKnot(gridMap, queriedPosition, &middleKnotIndex)) { + return false; + } + + const Matrix &layerMatrix = gridMap.get(layer); + auto f = [&layerMatrix](unsigned int rowReq, unsigned int colReq) { + double retVal = getLayerValue(layerMatrix, rowReq, colReq); + return retVal; + }; + + const unsigned int i = middleKnotIndex.x(); + const unsigned int j = middleKnotIndex.y(); + /* + * Notation taken from: https://en.wikipedia.org/wiki/Bicubic_interpolation + * increasing f's indices is flipped w.r.t. to the above since in the article + * they use a coordinate frame centered around (i,j). Therefore: + * f(i+1,j-1) in their notation corresponds to f(i-1,j+1) in ours. This is + * because our coordinate frame sits in the top left corner, see + * https://github.com/ANYbotics/grid_map + */ + *data << f(i + 1, j + 1), f(i, j + 1), f(i - 1, j + 1), f(i - 2, j + 1), f(i + 1, j), f(i, j), f( + i - 1, j), f(i - 2, j), f(i + 1, j - 1), f(i, j - 1), f(i - 1, j - 1), f(i - 2, j - 1), f( + i + 1, j - 2), f(i, j - 2), f(i - 1, j - 2), f(i - 2, j - 2); + + return true; +} + +bool getNormalizedCoordinates(const GridMap &gridMap, const Position &queriedPosition, + Position *position) +{ + Index index; + if (!getIndicesOfMiddleKnot(gridMap, queriedPosition, &index)) { + return false; + } + + Position middleKnot; + if (!gridMap.getPosition(index, middleKnot)) { + return false; + } + + position->x() = (queriedPosition.x() - middleKnot.x()) / gridMap.getResolution(); + position->y() = (queriedPosition.y() - middleKnot.y()) / gridMap.getResolution(); + + return true; +} + +bool getIndicesOfMiddleKnot(const GridMap &gridMap, const Position &queriedPosition, Index *index) +{ + return gridMap.getIndex(queriedPosition, *index); +} + +} /* namespace bicubic_conv */ + +/** + * BICUBIC INTERPOLATION ALGORITHM + * it does ensure continuity of the first derivatives. + * More expensive to compute than bicubic convolution interpolation + * see: + * https://en.wikipedia.org/wiki/Bicubic_interpolation + * https://web.archive.org/web/20051024202307/http://www.geovista.psu.edu/sites/geocomp99/Gc99/082/gc_082.htm + */ + +namespace bicubic { + +bool evaluateBicubicInterpolation(const GridMap &gridMap, const std::string &layer, + const Position &queriedPosition, double *interpolatedValue) +{ + + const Matrix& layerMat = gridMap.get(layer); + const double resolution = gridMap.getResolution(); + + // get indices of data points needed for interpolation + IndicesMatrix unitSquareCornerIndices; + if (!getUnitSquareCornerIndices(gridMap, queriedPosition, &unitSquareCornerIndices)) { + return false; + } + + // get function values + DataMatrix f; + if (!getFunctionValues(layerMat, unitSquareCornerIndices, &f)) { + return false; + } + + // get the first derivatives in x + DataMatrix dfx; + if (!getFirstOrderDerivatives(layerMat, unitSquareCornerIndices, Dim2D::X, resolution, &dfx)) { + return false; + } + + // the first derivatives in y + DataMatrix dfy; + if (!getFirstOrderDerivatives(layerMat, unitSquareCornerIndices, Dim2D::Y, resolution, &dfy)) { + return false; + } + // mixed derivatives in x y + DataMatrix ddfxy; + if (!getMixedSecondOrderDerivatives(layerMat, unitSquareCornerIndices, resolution, &ddfxy)) { + return false; + } + + // assemble function value matrix matrix + FunctionValueMatrix functionValues; + assembleFunctionValueMatrix(f, dfx, dfy, ddfxy, &functionValues); + + // get normalized coordinates + Position normalizedCoordinates; + if (!computeNormalizedCoordinates(gridMap, unitSquareCornerIndices.bottomLeft_, queriedPosition, + &normalizedCoordinates)) { + return false; + } + + // evaluate polynomial + *interpolatedValue = evaluatePolynomial(functionValues, normalizedCoordinates.x(), + normalizedCoordinates.y()); + + return true; +} + +bool getUnitSquareCornerIndices(const GridMap &gridMap, const Position &queriedPosition, + IndicesMatrix *indicesMatrix) +{ + + Index closestPointId; + if (!getClosestPointIndices(gridMap, queriedPosition, &closestPointId)) { + return false; + } + + Position closestPoint; + if (!gridMap.getPosition(closestPointId, closestPoint)) { + return false; + } + + const int idx0 = closestPointId.x(); + const int idy0 = closestPointId.y(); + const double x0 = closestPoint.x(); + const double y0 = closestPoint.y(); + const double x = queriedPosition.x(); + const double y = queriedPosition.y(); + + if (x > x0) { //first or fourth quadrant + if (y > y0) { //first quadrant + indicesMatrix->topLeft_ = Index(idx0, idy0 - 1); + indicesMatrix->topRight_ = Index(idx0 - 1, idy0 - 1); + indicesMatrix->bottomLeft_ = Index(idx0, idy0); + indicesMatrix->bottomRight_ = Index(idx0 - 1, idy0); + } else { // fourth quadrant + indicesMatrix->topLeft_ = Index(idx0, idy0); + indicesMatrix->topRight_ = Index(idx0 - 1, idy0); + indicesMatrix->bottomLeft_ = Index(idx0, idy0 + 1); + indicesMatrix->bottomRight_ = Index(idx0 - 1, idy0 + 1); + } + } else { // second or third quadrant + if (y > y0) { //second quadrant + indicesMatrix->topLeft_ = Index(idx0 + 1, idy0 - 1); + indicesMatrix->topRight_ = Index(idx0, idy0 - 1); + indicesMatrix->bottomLeft_ = Index(idx0 + 1, idy0); + indicesMatrix->bottomRight_ = Index(idx0, idy0); + } else { // third quadrant + indicesMatrix->topLeft_ = Index(idx0 + 1, idy0); + indicesMatrix->topRight_ = Index(idx0, idy0); + indicesMatrix->bottomLeft_ = Index(idx0 + 1, idy0 + 1); + indicesMatrix->bottomRight_ = Index(idx0, idy0 + 1); + } + } + + bindIndicesToRange(gridMap, indicesMatrix); + + return true; + +} + +bool getClosestPointIndices(const GridMap &gridMap, const Position &queriedPosition, Index *index) +{ + return gridMap.getIndex(queriedPosition, *index); +} + +bool computeNormalizedCoordinates(const GridMap &gridMap, const Index &originIndex, + const Position &queriedPosition, Position *normalizedCoordinates) +{ + + Position origin; + if (!gridMap.getPosition(originIndex, origin)) { + return false; + } + + normalizedCoordinates->x() = (queriedPosition.x() - origin.x()) / gridMap.getResolution(); + normalizedCoordinates->y() = (queriedPosition.y() - origin.y()) / gridMap.getResolution(); + + return true; + +} + +bool getFunctionValues(const Matrix &layerData, const IndicesMatrix &indices, DataMatrix *data) +{ + data->topLeft_ = layerData(indices.topLeft_.x(), indices.topLeft_.y()); + data->topRight_ = layerData(indices.topRight_.x(), indices.topRight_.y()); + data->bottomLeft_ = layerData(indices.bottomLeft_.x(), indices.bottomLeft_.y()); + data->bottomRight_ = layerData(indices.bottomRight_.x(), indices.bottomRight_.y()); + return true; +} + +void bindIndicesToRange(const GridMap &gridMap, IndicesMatrix *indices) +{ + const unsigned int numCol = gridMap.getSize().y(); + const unsigned int numRow = gridMap.getSize().x(); + + //top left + { + const unsigned int iBoundToRange = bindIndexToRange(indices->topLeft_.x(), numRow); + const unsigned int jBoundToRange = bindIndexToRange(indices->topLeft_.y(), numCol); + indices->topLeft_ = Index(iBoundToRange, jBoundToRange); + } + + //top right + { + const unsigned int iBoundToRange = bindIndexToRange(indices->topRight_.x(), numRow); + const unsigned int jBoundToRange = bindIndexToRange(indices->topRight_.y(), numCol); + indices->topRight_ = Index(iBoundToRange, jBoundToRange); + } + + //bottom left + { + const unsigned int iBoundToRange = bindIndexToRange(indices->bottomLeft_.x(), numRow); + const unsigned int jBoundToRange = bindIndexToRange(indices->bottomLeft_.y(), numCol); + indices->bottomLeft_ = Index(iBoundToRange, jBoundToRange); + } + + //bottom right + { + const unsigned int iBoundToRange = bindIndexToRange(indices->bottomRight_.x(), numRow); + const unsigned int jBoundToRange = bindIndexToRange(indices->bottomRight_.y(), numCol); + indices->bottomRight_ = Index(iBoundToRange, jBoundToRange); + } + +} + +bool getFirstOrderDerivatives(const Matrix &layerData, const IndicesMatrix &indices, Dim2D dim, + double resolution, DataMatrix *derivatives) +{ + derivatives->topLeft_ = firstOrderDerivativeAt(layerData, indices.topLeft_, dim, resolution); + derivatives->topRight_ = firstOrderDerivativeAt(layerData, indices.topRight_, dim, resolution); + derivatives->bottomLeft_ = firstOrderDerivativeAt(layerData, indices.bottomLeft_, dim, + resolution); + derivatives->bottomRight_ = firstOrderDerivativeAt(layerData, indices.bottomRight_, dim, + resolution); + return true; +} + +double firstOrderDerivativeAt(const Matrix &layerData, const Index &index, Dim2D dim, + double resolution) +{ + const auto numCol{static_cast(layerData.cols())}; + const auto numRow{static_cast(layerData.rows())}; + + double left; + double right; + switch (dim) { + case Dim2D::X: { + left = layerData(bindIndexToRange(index.x() + 1, numRow), index.y()); + right = layerData(bindIndexToRange(index.x() - 1, numRow), index.y()); + break; + } + case Dim2D::Y: { + left = layerData(index.x(), bindIndexToRange(index.y() + 1, numCol)); + right = layerData(index.x(), bindIndexToRange(index.y() - 1, numCol)); + break; + } + default: { + throw std::runtime_error("Unknown derivative direction"); + } + } + + const double perturbation = resolution; + // central difference approximation + // we need to multiply with resolution since we are + // operating in scaled coordinates + return (right - left) / (2.0 * perturbation) * resolution; +} + +double mixedSecondOrderDerivativeAt(const Matrix &layerData, const Index &index, double resolution) +{ + /* + * no need for dimensions since we have to differentiate w.r.t. x and y + * the order doesn't matter. Derivative values are the same. + * Taken from https://www.mathematik.uni-dortmund.de/~kuzmin/cfdintro/lecture4.pdf + */ + const auto numCol{static_cast(layerData.cols())}; + const auto numRow{static_cast(layerData.rows())}; + + const double f11 = layerData(bindIndexToRange(index.x() - 1, numRow), + bindIndexToRange(index.y() - 1, numCol)); + const double f1m1 = layerData(bindIndexToRange(index.x() - 1, numRow), + bindIndexToRange(index.y() + 1, numCol)); + const double fm11 = layerData(bindIndexToRange(index.x() + 1, numRow), + bindIndexToRange(index.y() - 1, numCol)); + const double fm1m1 = layerData(bindIndexToRange(index.x() + 1, numRow), + bindIndexToRange(index.y() + 1, numCol)); + + const double perturbation = resolution; + // central difference approximation + // we need to multiply with resolution^2 since we are + // operating in scaled coordinates. Second derivative scales + // with the square of the resolution + return (f11 - f1m1 - fm11 + fm1m1) / (4.0 * perturbation * perturbation) * resolution * resolution; + +} + +bool getMixedSecondOrderDerivatives(const Matrix &layerData, const IndicesMatrix &indices, + double resolution, DataMatrix *derivatives) +{ + derivatives->topLeft_ = mixedSecondOrderDerivativeAt(layerData, indices.topLeft_, resolution); + derivatives->topRight_ = mixedSecondOrderDerivativeAt(layerData, indices.topRight_, resolution); + derivatives->bottomLeft_ = mixedSecondOrderDerivativeAt(layerData, indices.bottomLeft_, + resolution); + derivatives->bottomRight_ = mixedSecondOrderDerivativeAt(layerData, indices.bottomRight_, + resolution); + return true; +} + +double evaluatePolynomial(const FunctionValueMatrix &functionValues, double tx, double ty) +{ + const Eigen::Vector4d xVector(1, tx, tx * tx, tx * tx * tx); + const Eigen::Vector4d yVector(1, ty, ty * ty, ty * ty * ty); + const Eigen::Matrix4d tempMat = functionValues + * bicubicInterpolationMatrix.transpose(); + const Eigen::Matrix4d polynomialCoeffMatrix = bicubicInterpolationMatrix * tempMat; + const Eigen::Vector4d tempVec = polynomialCoeffMatrix * yVector; + return xVector.transpose() * tempVec; +} + +void assembleFunctionValueMatrix(const DataMatrix &f, const DataMatrix &dfx, const DataMatrix &dfy, + const DataMatrix &ddfxy, FunctionValueMatrix *functionValues) +{ + auto toEigenMatrix = [](const DataMatrix &d)-> Eigen::Matrix2d { + Eigen::Matrix2d e; + e(0,0) = d.bottomLeft_; + e(1,0) = d.bottomRight_; + e(0,1) = d.topLeft_; + e(1,1) = d.topRight_; + return e; + }; + + functionValues->block<2, 2>(0, 0) = toEigenMatrix(f); + functionValues->block<2, 2>(2, 2) = toEigenMatrix(ddfxy); + functionValues->block<2, 2>(0, 2) = toEigenMatrix(dfy); + functionValues->block<2, 2>(2, 0) = toEigenMatrix(dfx); +} + +} /* namespace bicubic*/ + +} /* namespace grid_map */ diff --git a/src/GridMap.cpp b/src/GridMap.cpp new file mode 100644 index 0000000..b72ea4c --- /dev/null +++ b/src/GridMap.cpp @@ -0,0 +1,891 @@ +/* + * GridMap.cpp + * + * Created on: Jul 14, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/GridMap.hpp" + +#include "grid_map_core/CubicInterpolation.hpp" +#include "grid_map_core/GridMapMath.hpp" +#include "grid_map_core/SubmapGeometry.hpp" +#include "grid_map_core/iterators/GridMapIterator.hpp" + +#include +#include +#include +#include +#include + +using std::cout; +using std::endl; +using std::isfinite; + +namespace grid_map { + +GridMap::GridMap(const std::vector& layers) { + position_.setZero(); + length_.setZero(); + resolution_ = 0.0; + size_.setZero(); + startIndex_.setZero(); + timestamp_ = 0; + layers_ = layers; + + for (auto& layer : layers_) { + data_.insert(std::pair(layer, Matrix())); + } +} + +GridMap::GridMap() : GridMap(std::vector()) {} + +void GridMap::setGeometry(const Length& length, const double resolution, const Position& position) { + assert(length(0) > 0.0); + assert(length(1) > 0.0); + assert(resolution > 0.0); + + Size size; + size(0) = static_cast(round(length(0) / resolution)); // There is no round() function in Eigen. + size(1) = static_cast(round(length(1) / resolution)); + resize(size); + clearAll(); + + resolution_ = resolution; + length_ = (size_.cast() * resolution_).matrix(); + position_ = position; + startIndex_.setZero(); +} + +void GridMap::setGeometry(const SubmapGeometry& geometry) { + setGeometry(geometry.getLength(), geometry.getResolution(), geometry.getPosition()); +} + +void GridMap::setBasicLayers(const std::vector& basicLayers) { + basicLayers_ = basicLayers; +} + +const std::vector& GridMap::getBasicLayers() const { + return basicLayers_; +} + +bool GridMap::hasBasicLayers() const { + return !basicLayers_.empty(); +} + +bool GridMap::hasSameLayers(const GridMap& other) const { + return std::all_of(layers_.begin(), layers_.end(), + [&](const std::string& layer){return other.exists(layer);}); +} + +void GridMap::add(const std::string& layer, const float value) { + add(layer, Matrix::Constant(size_(0), size_(1), value)); +} + +void GridMap::add(const std::string& layer, const Matrix& data) { + assert(size_(0) == data.rows()); + assert(size_(1) == data.cols()); + + if (exists(layer)) { + // Type exists already, overwrite its data. + data_.at(layer) = data; + } else { + // Type does not exist yet, add type and data. + data_.insert(std::pair(layer, data)); + layers_.push_back(layer); + } +} + +bool GridMap::exists(const std::string& layer) const { + return !(data_.find(layer) == data_.end()); +} + +const Matrix& GridMap::get(const std::string& layer) const { + try { + return data_.at(layer); + } catch (const std::out_of_range& exception) { + throw std::out_of_range("GridMap::get(...) : No map layer '" + layer + "' available."); + } +} + +Matrix& GridMap::get(const std::string& layer) { + try { + return data_.at(layer); + } catch (const std::out_of_range& exception) { + throw std::out_of_range("GridMap::get(...) : No map layer of type '" + layer + "' available."); + } +} + +const Matrix& GridMap::operator[](const std::string& layer) const { + return get(layer); +} + +Matrix& GridMap::operator[](const std::string& layer) { + return get(layer); +} + +bool GridMap::erase(const std::string& layer) { + const auto dataIterator = data_.find(layer); + if (dataIterator == data_.end()) { + return false; + } + data_.erase(dataIterator); + + const auto layerIterator = std::find(layers_.begin(), layers_.end(), layer); + if (layerIterator == layers_.end()) { + return false; + } + layers_.erase(layerIterator); + + const auto basicLayerIterator = std::find(basicLayers_.begin(), basicLayers_.end(), layer); + if (basicLayerIterator != basicLayers_.end()) { + basicLayers_.erase(basicLayerIterator); + } + + return true; +} + +const std::vector& GridMap::getLayers() const { + return layers_; +} + +float& GridMap::atPosition(const std::string& layer, const Position& position) { + Index index; + if (getIndex(position, index)) { + return at(layer, index); + } + throw std::out_of_range("GridMap::atPosition(...) : Position is out of range."); +} + +float GridMap::atPosition(const std::string& layer, const Position& position, InterpolationMethods interpolationMethod) const { + + bool skipNextSwitchCase = false; + switch (interpolationMethod) { + case InterpolationMethods::INTER_CUBIC_CONVOLUTION: { + float value; + if (atPositionBicubicConvolutionInterpolated(layer, position, value)) { + return value; + } else { + interpolationMethod = InterpolationMethods::INTER_LINEAR; + skipNextSwitchCase = true; + } + [[fallthrough]]; + } + case InterpolationMethods::INTER_CUBIC: { + if (!skipNextSwitchCase) { + float value; + if (atPositionBicubicInterpolated(layer, position, value)) { + return value; + } else { + interpolationMethod = InterpolationMethods::INTER_LINEAR; + } + } + [[fallthrough]]; + } + case InterpolationMethods::INTER_LINEAR: { + float value; + if (atPositionLinearInterpolated(layer, position, value)){ + return value; + } + else { + interpolationMethod = InterpolationMethods::INTER_NEAREST; + } + [[fallthrough]]; + } + case InterpolationMethods::INTER_NEAREST: { + Index index; + if (getIndex(position, index)) { + return at(layer, index); + } else { + throw std::out_of_range("GridMap::atPosition(...) : Position is out of range."); + } + break; + } + default: + throw std::runtime_error( + "GridMap::atPosition(...) : Specified " + "interpolation method not implemented."); + } +} + +float& GridMap::at(const std::string& layer, const Index& index) { + try { + return data_.at(layer)(index(0), index(1)); + } catch (const std::out_of_range& exception) { + throw std::out_of_range("GridMap::at(...) : No map layer '" + layer + "' available."); + } +} + +float GridMap::at(const std::string& layer, const Index& index) const { + try { + return data_.at(layer)(index(0), index(1)); + } catch (const std::out_of_range& exception) { + throw std::out_of_range("GridMap::at(...) : No map layer '" + layer + "' available."); + } +} + +bool GridMap::getIndex(const Position& position, Index& index) const { + return getIndexFromPosition(index, position, length_, position_, resolution_, size_, startIndex_); +} + +bool GridMap::getPosition(const Index& index, Position& position) const { + return getPositionFromIndex(position, index, length_, position_, resolution_, size_, startIndex_); +} + +bool GridMap::isInside(const Position& position) const { + return checkIfPositionWithinMap(position, length_, position_); +} + +bool GridMap::isValid(DataType value) const { + return isfinite(value); +} + +bool GridMap::isValid(const Index& index) const { + return isValid(index, basicLayers_); +} + +bool GridMap::isValid(const Index& index, const std::string& layer) const { + return isValid(at(layer, index)); +} + +bool GridMap::isValid(const Index& index, const std::vector& layers) const { + if (layers.empty()) { + return false; + } + return std::all_of(layers.begin(), layers.end(), + [&](const std::string& layer){return isValid(index, layer);}); +} + +bool GridMap::getPosition3(const std::string& layer, const Index& index, Position3& position) const { + const auto value = at(layer, index); + if (!isValid(value)) { + return false; + } + Position position2d; + getPosition(index, position2d); + position.head(2) = position2d; + position.z() = value; + return true; +} + +bool GridMap::getVector(const std::string& layerPrefix, const Index& index, Eigen::Vector3d& vector) const { + Eigen::Vector3d temp{at(layerPrefix + "x", index), at(layerPrefix + "y", index), at(layerPrefix + "z", index)}; + if (!isValid(temp[0]) || !isValid(temp[1]) || !isValid(temp[2])) { // NOLINT (implicit-float-conversion) + return false; + } else { + vector = temp; + return true; + } +} + +GridMap GridMap::getSubmap(const Position& position, const Length& length, bool& isSuccess) const { + Index index; + return getSubmap(position, length, index, isSuccess); +} + +GridMap GridMap::getSubmap(const Position& position, const Length& length, Index& /*indexInSubmap*/, bool& isSuccess) const { + // Submap to generate. + GridMap submap(layers_); + submap.setBasicLayers(basicLayers_); + submap.setTimestamp(timestamp_); + submap.setFrameId(frameId_); + + // Get submap geometric information. + SubmapGeometry submapInformation(*this, position, length, isSuccess); + if (!isSuccess) { + return GridMap{layers_}; + } + submap.setGeometry(submapInformation); + submap.startIndex_.setZero(); // Because of the way we copy the data below. + + // Copy data. + std::vector bufferRegions; + + if (!getBufferRegionsForSubmap(bufferRegions, submapInformation.getStartIndex(), submap.getSize(), size_, startIndex_)) { + cout << "Cannot access submap of this size." << endl; + isSuccess = false; + return GridMap{layers_}; + } + + for (const auto& data : data_) { + for (const auto& bufferRegion : bufferRegions) { + Index index = bufferRegion.getStartIndex(); + Size size = bufferRegion.getSize(); + + if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopLeft) { + submap.data_[data.first].topLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1)); + } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopRight) { + submap.data_[data.first].topRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1)); + } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomLeft) { + submap.data_[data.first].bottomLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1)); + } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomRight) { + submap.data_[data.first].bottomRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1)); + } + } + } + + isSuccess = true; + return submap; +} + +GridMap GridMap::getTransformedMap(const Eigen::Isometry3d& transform, const std::string& heightLayerName, const std::string& newFrameId, + const double sampleRatio) const { + // Check if height layer is valid. + if (!exists(heightLayerName)) { + throw std::out_of_range("GridMap::getTransformedMap(...) : No map layer '" + heightLayerName + "' available."); + } + + // Initialization. + std::vector positionSamples; + Position3 center; + Index newIndex; + + const double sampleLength = resolution_ * sampleRatio; + + // Find edges in new coordinate frame. + const double halfLengthX = length_.x() * 0.5; + const double halfLengthY = length_.y() * 0.5; + const Position3 topLeftCorner(position_.x() + halfLengthX, position_.y() + halfLengthY, 0.0); + const Position3 topRightCorner(position_.x() + halfLengthX, position_.y() - halfLengthY, 0.0); + const Position3 bottomLeftCorner(position_.x() - halfLengthX, position_.y() + halfLengthY, 0.0); + const Position3 bottomRightCorner(position_.x() - halfLengthX, position_.y() - halfLengthY, 0.0); + + std::vector newEdges; + newEdges.reserve(4); + newEdges.push_back(transform * topLeftCorner); + newEdges.push_back(transform * topRightCorner); + newEdges.push_back(transform * bottomLeftCorner); + newEdges.push_back(transform * bottomRightCorner); + + // Find new grid center. + Position3 newCenter = Position3::Zero(); + for (const auto& newEdge : newEdges) { + newCenter += newEdge; + } + newCenter *= 0.25; + + // Find new grid length. + Length maxLengthFromCenter = Length(0.0, 0.0); + for (const auto& newEdge : newEdges) { + Position3 positionCenterToEdge = newEdge - newCenter; + maxLengthFromCenter.x() = std::fmax(std::fabs(positionCenterToEdge.x()), maxLengthFromCenter.x()); + maxLengthFromCenter.y() = std::fmax(std::fabs(positionCenterToEdge.y()), maxLengthFromCenter.y()); + } + Length newLength = 2.0 * maxLengthFromCenter; + + // Create new grid map. + GridMap newMap(layers_); + newMap.setBasicLayers(basicLayers_); + newMap.setTimestamp(timestamp_); + newMap.setFrameId(newFrameId); + newMap.setGeometry(newLength, resolution_, Position(newCenter.x(), newCenter.y())); + newMap.startIndex_.setZero(); + + for (GridMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) { + // Get position at current index. + if (!getPosition3(heightLayerName, *iterator, center)) { + continue; + } + + // Sample four points around the center cell. + positionSamples.clear(); + + if (sampleRatio > 0.0) { + positionSamples.reserve(5); + positionSamples.push_back(center); + positionSamples.emplace_back(center.x() - sampleLength, center.y(), center.z()); + positionSamples.emplace_back(center.x() + sampleLength, center.y(), center.z()); + positionSamples.emplace_back(center.x(), center.y() - sampleLength, center.z()); + positionSamples.emplace_back(center.x(), center.y() + sampleLength, center.z()); + } else { + positionSamples.push_back(center); + } + + // Transform the sampled points and register to the new map. + for (const auto& position : positionSamples) { + const Position3 transformedPosition = transform * position; + + // Get new index. + if (!newMap.getIndex(Position(transformedPosition.x(), transformedPosition.y()), newIndex)) { + continue; + } + + // Check if we have already assigned a value (preferably larger height + // values -> inpainting). + const auto newExistingValue = newMap.at(heightLayerName, newIndex); + if (!std::isnan(newExistingValue) && newExistingValue > transformedPosition.z()) { + continue; + } + + // Copy the layers. + for (const auto& layer : layers_) { + const auto currentValueInOldGrid = at(layer, *iterator); + auto& newValue = newMap.at(layer, newIndex); + if (layer == heightLayerName) { + newValue = static_cast(transformedPosition.z()); + } // adjust height + else { + newValue = currentValueInOldGrid; + } // re-assign + } + } + } + + return newMap; +} + +void GridMap::setPosition(const Position& position) { + position_ = position; +} + +bool GridMap::move(const Position& position, std::vector& newRegions) { + Index indexShift; + Position positionShift = position - position_; + getIndexShiftFromPositionShift(indexShift, positionShift, resolution_); + Position alignedPositionShift; + getPositionShiftFromIndexShift(alignedPositionShift, indexShift, resolution_); + + // Delete fields that fall out of map (and become empty cells). + for (int i = 0; i < indexShift.size(); i++) { + if (indexShift(i) != 0) { + if (abs(indexShift(i)) >= getSize()(i)) { + // Entire map is dropped. + clearAll(); + newRegions.emplace_back(Index(0, 0), getSize(), BufferRegion::Quadrant::Undefined); + } else { + // Drop cells out of map. + int sign = (indexShift(i) > 0 ? 1 : -1); + int startIndex = startIndex_(i) - (sign < 0 ? 1 : 0); + int endIndex = startIndex - sign + indexShift(i); + int nCells = abs(indexShift(i)); + int index = (sign > 0 ? startIndex : endIndex); + wrapIndexToRange(index, getSize()(i)); + + if (index + nCells <= getSize()(i)) { + // One region to drop. + if (i == 0) { + clearRows(index, nCells); + newRegions.emplace_back(Index(index, 0), Size(nCells, getSize()(1)), BufferRegion::Quadrant::Undefined); + } else if (i == 1) { + clearCols(index, nCells); + newRegions.emplace_back(Index(0, index), Size(getSize()(0), nCells), BufferRegion::Quadrant::Undefined); + } + } else { + // Two regions to drop. + int firstIndex = index; + int firstNCells = getSize()(i) - firstIndex; + if (i == 0) { + clearRows(firstIndex, firstNCells); + newRegions.emplace_back(Index(firstIndex, 0), Size(firstNCells, getSize()(1)), BufferRegion::Quadrant::Undefined); + } else if (i == 1) { + clearCols(firstIndex, firstNCells); + newRegions.emplace_back(Index(0, firstIndex), Size(getSize()(0), firstNCells), BufferRegion::Quadrant::Undefined); + } + + int secondIndex = 0; + int secondNCells = nCells - firstNCells; + if (i == 0) { + clearRows(secondIndex, secondNCells); + newRegions.emplace_back(Index(secondIndex, 0), Size(secondNCells, getSize()(1)), BufferRegion::Quadrant::Undefined); + } else if (i == 1) { + clearCols(secondIndex, secondNCells); + newRegions.emplace_back(Index(0, secondIndex), Size(getSize()(0), secondNCells), BufferRegion::Quadrant::Undefined); + } + } + } + } + } + + // Update information. + startIndex_ += indexShift; + wrapIndexToRange(startIndex_, getSize()); + position_ += alignedPositionShift; + + // Check if map has been moved at all. + return indexShift.any(); +} + +bool GridMap::move(const Position& position) { + std::vector newRegions; + return move(position, newRegions); +} + +bool GridMap::addDataFrom(const GridMap& other, bool extendMap, bool overwriteData, bool copyAllLayers, std::vector layers) { + // Set the layers to copy. + if (copyAllLayers) { + layers = other.getLayers(); + } + + // Resize map. + if (extendMap) { + extendToInclude(other); + } + + // Check if all layers to copy exist and add missing layers. + for (const auto& layer : layers) { + if (std::find(layers_.begin(), layers_.end(), layer) == layers_.end()) { + add(layer); + } + } + // Copy data. + for (GridMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) { + if (isValid(*iterator) && !overwriteData) { + continue; + } + Position position; + getPosition(*iterator, position); + Index index; + if (!other.isInside(position)) { + continue; + } + other.getIndex(position, index); + for (const auto& layer : layers) { + if (!other.isValid(index, layer)) { + continue; + } + at(layer, *iterator) = other.at(layer, index); + } + } + + return true; +} + +bool GridMap::extendToInclude(const GridMap& other) { + // Get dimension of maps. + Position topLeftCorner(position_.x() + length_.x() / 2.0, position_.y() + length_.y() / 2.0); + Position bottomRightCorner(position_.x() - length_.x() / 2.0, position_.y() - length_.y() / 2.0); + Position topLeftCornerOther(other.getPosition().x() + other.getLength().x() / 2.0, other.getPosition().y() + other.getLength().y() / 2.0); + Position bottomRightCornerOther(other.getPosition().x() - other.getLength().x() / 2.0, + other.getPosition().y() - other.getLength().y() / 2.0); + // Check if map needs to be resized. + bool resizeMap = false; + Position extendedMapPosition = position_; + Length extendedMapLength = length_; + if (topLeftCornerOther.x() > topLeftCorner.x()) { + extendedMapPosition.x() += (topLeftCornerOther.x() - topLeftCorner.x()) / 2.0; + extendedMapLength.x() += topLeftCornerOther.x() - topLeftCorner.x(); + resizeMap = true; + } + if (topLeftCornerOther.y() > topLeftCorner.y()) { + extendedMapPosition.y() += (topLeftCornerOther.y() - topLeftCorner.y()) / 2.0; + extendedMapLength.y() += topLeftCornerOther.y() - topLeftCorner.y(); + resizeMap = true; + } + if (bottomRightCornerOther.x() < bottomRightCorner.x()) { + extendedMapPosition.x() -= (bottomRightCorner.x() - bottomRightCornerOther.x()) / 2.0; + extendedMapLength.x() += bottomRightCorner.x() - bottomRightCornerOther.x(); + resizeMap = true; + } + if (bottomRightCornerOther.y() < bottomRightCorner.y()) { + extendedMapPosition.y() -= (bottomRightCorner.y() - bottomRightCornerOther.y()) / 2.0; + extendedMapLength.y() += bottomRightCorner.y() - bottomRightCornerOther.y(); + resizeMap = true; + } + // Resize map and copy data to new map. + if (resizeMap) { + GridMap mapCopy = *this; + setGeometry(extendedMapLength, resolution_, extendedMapPosition); + // Align new map with old one. + Vector shift = position_ - mapCopy.getPosition(); + shift.x() = std::fmod(shift.x(), resolution_); + shift.y() = std::fmod(shift.y(), resolution_); + if (std::abs(shift.x()) < resolution_ / 2.0) { + position_.x() -= shift.x(); + } else { + position_.x() += resolution_ - shift.x(); + } + if (size_.x() % 2 != mapCopy.getSize().x() % 2) { + position_.x() += -std::copysign(resolution_ / 2.0, shift.x()); + } + if (std::abs(shift.y()) < resolution_ / 2.0) { + position_.y() -= shift.y(); + } else { + position_.y() += resolution_ - shift.y(); + } + if (size_.y() % 2 != mapCopy.getSize().y() % 2) { + position_.y() += -std::copysign(resolution_ / 2.0, shift.y()); + } + // Copy data. + for (GridMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) { + if (isValid(*iterator)) { + continue; + } + Position position; + getPosition(*iterator, position); + Index index; + if (!mapCopy.isInside(position)) { + continue; + } + mapCopy.getIndex(position, index); + for (const auto& layer : layers_) { + at(layer, *iterator) = mapCopy.at(layer, index); + } + } + } + return true; +} + +void GridMap::setTimestamp(const Time timestamp) { + timestamp_ = timestamp; +} + +Time GridMap::getTimestamp() const { + return timestamp_; +} + +void GridMap::resetTimestamp() { + timestamp_ = 0.0; +} + +void GridMap::setFrameId(const std::string& frameId) { + frameId_ = frameId; +} + +const std::string& GridMap::getFrameId() const { + return frameId_; +} + +const Length& GridMap::getLength() const { + return length_; +} + +const Position& GridMap::getPosition() const { + return position_; +} + +double GridMap::getResolution() const { + return resolution_; +} + +const Size& GridMap::getSize() const { + return size_; +} + +void GridMap::setStartIndex(const Index& startIndex) { + startIndex_ = startIndex; +} + +const Index& GridMap::getStartIndex() const { + return startIndex_; +} + +bool GridMap::isDefaultStartIndex() const { + return (startIndex_ == 0).all(); +} + +void GridMap::convertToDefaultStartIndex() { + if (isDefaultStartIndex()) { + return; + } + + std::vector bufferRegions; + if (!getBufferRegionsForSubmap(bufferRegions, startIndex_, size_, size_, startIndex_)) { + throw std::out_of_range("Cannot access submap of this size."); + } + + for (auto& data : data_) { + auto tempData(data.second); + for (const auto& bufferRegion : bufferRegions) { + Index index = bufferRegion.getStartIndex(); + Size size = bufferRegion.getSize(); + + if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopLeft) { + tempData.topLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1)); + } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopRight) { + tempData.topRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1)); + } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomLeft) { + tempData.bottomLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1)); + } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomRight) { + tempData.bottomRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1)); + } + } + data.second = tempData; + } + + startIndex_.setZero(); +} + +Position GridMap::getClosestPositionInMap(const Position& position) const { + if (getSize().x() < 1 || getSize().y() < 1) { + return position_; + } + + if (isInside(position)) { + return position; + } + + Position positionInMap = position; + + // Find edges. + const double halfLengthX = length_.x() * 0.5; + const double halfLengthY = length_.y() * 0.5; + const Position3 topLeftCorner(position_.x() + halfLengthX, position_.y() + halfLengthY, 0.0); + const Position3 topRightCorner(position_.x() + halfLengthX, position_.y() - halfLengthY, 0.0); + const Position3 bottomLeftCorner(position_.x() - halfLengthX, position_.y() + halfLengthY, 0.0); + const Position3 bottomRightCorner(position_.x() - halfLengthX, position_.y() - halfLengthY, 0.0); + + // Find constraints. + const double maxX = topRightCorner.x(); + const double minX = bottomRightCorner.x(); + const double maxY = bottomLeftCorner.y(); + const double minY = bottomRightCorner.y(); + + // Clip to box constraints and correct for indexing precision. + // Points on the border can lead to invalid indices because the cells represent half open intervals, i.e. [...). + positionInMap.x() = std::fmin(positionInMap.x(), maxX - std::numeric_limits::epsilon()); + positionInMap.y() = std::fmin(positionInMap.y(), maxY - std::numeric_limits::epsilon()); + + positionInMap.x() = std::fmax(positionInMap.x(), minX + std::numeric_limits::epsilon()); + positionInMap.y() = std::fmax(positionInMap.y(), minY + std::numeric_limits::epsilon()); + + return positionInMap; +} + +void GridMap::clear(const std::string& layer) { + try { + data_.at(layer).setConstant(NAN); + } catch (const std::out_of_range& exception) { + throw std::out_of_range("GridMap::clear(...) : No map layer '" + layer + "' available."); + } +} + +void GridMap::clearBasic() { + for (auto& layer : basicLayers_) { + clear(layer); + } +} + +void GridMap::clearAll() { + for (auto& data : data_) { + data.second.setConstant(NAN); + } +} + +void GridMap::clearRows(unsigned int index, unsigned int nRows) { + for (auto& layer : layers_) { + data_.at(layer).block(index, 0, nRows, getSize()(1)).setConstant(NAN); + } +} + +void GridMap::clearCols(unsigned int index, unsigned int nCols) { + for (auto& layer : layers_) { + data_.at(layer).block(0, index, getSize()(0), nCols).setConstant(NAN); + } +} + +bool GridMap::atPositionLinearInterpolated(const std::string& layer, const Position& position, float& value) const { + Position point; + Index indices[4]; + bool idxTempDir; + size_t idxShift[4]; + + getIndex(position, indices[0]); + getPosition(indices[0], point); + + if (position.x() >= point.x()) { + indices[1] = indices[0] + Index(-1, 0); // Second point is above first point. + idxTempDir = true; + } else { + indices[1] = indices[0] + Index(+1, 0); + idxTempDir = false; + } + if (position.y() >= point.y()) { + indices[2] = indices[0] + Index(0, -1); // Third point is right of first point. + if (idxTempDir) { + idxShift[0] = 0; + idxShift[1] = 1; + idxShift[2] = 2; + idxShift[3] = 3; + } else { + idxShift[0] = 1; + idxShift[1] = 0; + idxShift[2] = 3; + idxShift[3] = 2; + } + + } else { + indices[2] = indices[0] + Index(0, +1); + if (idxTempDir) { + idxShift[0] = 2; + idxShift[1] = 3; + idxShift[2] = 0; + idxShift[3] = 1; + } else { + idxShift[0] = 3; + idxShift[1] = 2; + idxShift[2] = 1; + idxShift[3] = 0; + } + } + indices[3].x() = indices[1].x(); + indices[3].y() = indices[2].y(); + + const Size& mapSize = getSize(); + const size_t bufferSize = mapSize(0) * mapSize(1); + const size_t startIndexLin = getLinearIndexFromIndex(startIndex_, mapSize); + const size_t endIndexLin = startIndexLin + bufferSize; + const auto& layerMat = operator[](layer); + float f[4]; + + for (size_t i = 0; i < 4; ++i) { + const size_t indexLin = getLinearIndexFromIndex(indices[idxShift[i]], mapSize); + if ((indexLin < startIndexLin) || (indexLin > endIndexLin)) { + return false; + } + f[i] = layerMat(indexLin); + } + + getPosition(indices[idxShift[0]], point); + const Position positionRed = (position - point) / resolution_; + const Position positionRedFlip = Position(1., 1.) - positionRed; + + + value = f[0] * positionRedFlip.x() * positionRedFlip.y() + f[1] * positionRed.x() * positionRedFlip.y() + // NOLINT (implicit-float-conversion) + f[2] * positionRedFlip.x() * positionRed.y() + f[3] * positionRed.x() * positionRed.y(); // NOLINT (implicit-float-conversion) + return true; +} + +void GridMap::resize(const Index& size) { + size_ = size; + for (auto& data : data_) { + data.second.resize(size_(0), size_(1)); + } +} + + +bool GridMap::atPositionBicubicConvolutionInterpolated(const std::string& layer, const Position& position, + float& value) const +{ + double interpolatedValue = 0.0; + if (!bicubic_conv::evaluateBicubicConvolutionInterpolation(*this, layer, position, &interpolatedValue)) { + return false; + } + + if (!std::isfinite(interpolatedValue)) { + return false; + } + value = static_cast(interpolatedValue); + + return true; +} + +bool GridMap::atPositionBicubicInterpolated(const std::string& layer, const Position& position, + float& value) const +{ + double interpolatedValue = 0.0; + if (!bicubic::evaluateBicubicInterpolation(*this, layer, position, &interpolatedValue)) { + return false; + } + + if (!std::isfinite(interpolatedValue)) { + return false; + } + value = static_cast(interpolatedValue); + + return true; + +} + + +} // namespace grid_map diff --git a/src/GridMapMath.cpp b/src/GridMapMath.cpp new file mode 100644 index 0000000..b56d618 --- /dev/null +++ b/src/GridMapMath.cpp @@ -0,0 +1,600 @@ +/* + * GridMapMath.cpp + * + * Created on: Dec 2, 2013 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/GridMapMath.hpp" + +// fabs +#include + +// Limits +#include + +using std::numeric_limits; + +namespace grid_map { + +namespace internal { + +/*! + * Gets the vector from the center of the map to the origin + * of the map data structure. + * @param[out] vectorToOrigin the vector from the center of the map the origin of the map data structure. + * @param[in] mapLength the lengths in x and y direction. + * @return true if successful. + */ +inline bool getVectorToOrigin(Vector& vectorToOrigin, const Length& mapLength) +{ + vectorToOrigin = (0.5 * mapLength).matrix(); + return true; +} + +/*! + * Gets the vector from the center of the map to the center + * of the first cell of the map data. + * @param[out] vectorToFirstCell the vector from the center of the cell to the center of the map. + * @param[in] mapLength the lengths in x and y direction. + * @param[in] resolution the resolution of the map. + * @return true if successful. + */ +inline bool getVectorToFirstCell(Vector& vectorToFirstCell, + const Length& mapLength, const double& resolution) +{ + Vector vectorToOrigin; + getVectorToOrigin(vectorToOrigin, mapLength); + + // Vector to center of cell. + vectorToFirstCell = (vectorToOrigin.array() - 0.5 * resolution).matrix(); + return true; +} + +inline Eigen::Matrix2i getBufferOrderToMapFrameTransformation() +{ + return -Eigen::Matrix2i::Identity(); +} + +inline Vector transformBufferOrderToMapFrame(const Index& index) { + return {-index[0], -index[1]}; +} + +inline Eigen::Matrix2i getMapFrameToBufferOrderTransformation() +{ + return getBufferOrderToMapFrameTransformation().transpose(); +} + +inline Index transformMapFrameToBufferOrder(const Vector& vector) { + return {-vector[0], -vector[1]}; +} + +inline Index transformMapFrameToBufferOrder(const Eigen::Vector2i& vector) { + return {-vector[0], -vector[1]}; +} + +inline bool checkIfStartIndexAtDefaultPosition(const Index& bufferStartIndex) +{ + return ((bufferStartIndex == 0).all()); +} + +inline Vector getIndexVectorFromIndex( + const Index& index, + const Size& bufferSize, + const Index& bufferStartIndex) +{ + Index unwrappedIndex; + unwrappedIndex = getIndexFromBufferIndex(index, bufferSize, bufferStartIndex); + return transformBufferOrderToMapFrame(unwrappedIndex); +} + +inline Index getIndexFromIndexVector( + const Vector& indexVector, + const Size& bufferSize, + const Index& bufferStartIndex) +{ + Index index = transformMapFrameToBufferOrder(indexVector); + return getBufferIndexFromIndex(index, bufferSize, bufferStartIndex); +} + +inline BufferRegion::Quadrant getQuadrant(const Index& index, const Index& bufferStartIndex) { + if (index[0] >= bufferStartIndex[0] && index[1] >= bufferStartIndex[1]) { + return BufferRegion::Quadrant::TopLeft; + } + if (index[0] >= bufferStartIndex[0] && index[1] < bufferStartIndex[1]) { + return BufferRegion::Quadrant::TopRight; + } + if (index[0] < bufferStartIndex[0] && index[1] >= bufferStartIndex[1]) { + return BufferRegion::Quadrant::BottomLeft; + } + if (index[0] < bufferStartIndex[0] && index[1] < bufferStartIndex[1]) { + return BufferRegion::Quadrant::BottomRight; + } + return BufferRegion::Quadrant::Undefined; +} + +} // namespace internal + +using internal::checkIfStartIndexAtDefaultPosition; +using internal::getBufferOrderToMapFrameTransformation; +using internal::getIndexFromIndexVector; +using internal::getIndexVectorFromIndex; +using internal::getMapFrameToBufferOrderTransformation; +using internal::getQuadrant; +using internal::getVectorToFirstCell; +using internal::getVectorToOrigin; +using internal::transformBufferOrderToMapFrame; +using internal::transformMapFrameToBufferOrder; + +bool getPositionFromIndex(Position& position, + const Index& index, + const Length& mapLength, + const Position& mapPosition, + const double& resolution, + const Size& bufferSize, + const Index& bufferStartIndex) +{ + if (!checkIfIndexInRange(index, bufferSize)) { + return false; + } + Vector offset; + getVectorToFirstCell(offset, mapLength, resolution); + position = mapPosition + offset + resolution * getIndexVectorFromIndex(index, bufferSize, bufferStartIndex); + return true; +} + +bool getIndexFromPosition(Index& index, + const Position& position, + const Length& mapLength, + const Position& mapPosition, + const double& resolution, + const Size& bufferSize, + const Index& bufferStartIndex) +{ + Vector offset; + getVectorToOrigin(offset, mapLength); + Vector indexVector = ((position - offset - mapPosition).array() / resolution).matrix(); + index = getIndexFromIndexVector(indexVector, bufferSize, bufferStartIndex); + return checkIfPositionWithinMap(position, mapLength, mapPosition) && checkIfIndexInRange(index, bufferSize); +} + +bool checkIfPositionWithinMap(const Position& position, + const Length& mapLength, + const Position& mapPosition) +{ + Vector offset; + getVectorToOrigin(offset, mapLength); + Position positionTransformed = getMapFrameToBufferOrderTransformation().cast() * (position - mapPosition - offset); + + return positionTransformed.x() >= 0.0 && positionTransformed.y() >= 0.0 + && positionTransformed.x() < mapLength(0) && positionTransformed.y() < mapLength(1); +} + +void getPositionOfDataStructureOrigin(const Position& position, + const Length& mapLength, + Position& positionOfOrigin) +{ + Vector vectorToOrigin; + getVectorToOrigin(vectorToOrigin, mapLength); + positionOfOrigin = position + vectorToOrigin; +} + +bool getIndexShiftFromPositionShift(Index& indexShift, + const Vector& positionShift, + const double& resolution) +{ + Vector indexShiftVectorTemp = (positionShift.array() / resolution).matrix(); + Eigen::Vector2i indexShiftVector; + + for (int i = 0; i < indexShiftVector.size(); i++) { + indexShiftVector[i] = static_cast(indexShiftVectorTemp[i] + 0.5 * (indexShiftVectorTemp[i] > 0 ? 1 : -1)); + } + + indexShift = transformMapFrameToBufferOrder(indexShiftVector); + return true; +} + +bool getPositionShiftFromIndexShift(Vector& positionShift, + const Index& indexShift, + const double& resolution) +{ + positionShift = transformBufferOrderToMapFrame(indexShift) * resolution; + return true; +} + +bool checkIfIndexInRange(const Index& index, const Size& bufferSize) +{ + return index[0] >= 0 && index[1] >= 0 && index[0] < bufferSize[0] && index[1] < bufferSize[1]; +} + +void boundIndexToRange(Index& index, const Size& bufferSize) +{ + for (int i = 0; i < index.size(); i++) { + boundIndexToRange(index[i], bufferSize[i]); + } +} + +void boundIndexToRange(int& index, const int& bufferSize) +{ + if (index < 0) { + index = 0; + } else if (index >= bufferSize) { + index = bufferSize - 1; + } +} + +void wrapIndexToRange(Index& index, const Size& bufferSize) +{ + for (int i = 0; i < index.size(); i++) { + wrapIndexToRange(index[i], bufferSize[i]); + } +} + +void wrapIndexToRange(int& index, int bufferSize) +{ + // Try shortcuts before resorting to the expensive modulo operation. + if (index < bufferSize){ + if(index >= 0){ // within the wanted range + return; + } else if(index >= -bufferSize){ // Index is below range, but not more than one span of the range. + index +=bufferSize; + return; + }else{ // Index is largely below range. + index = index % bufferSize; + index += bufferSize; + } + }else if(index < bufferSize*2){ // Index is above range, but not more than one span of the range. + index -= bufferSize; + return; + } else{ // Index is largely above range. + index = index % bufferSize; + } +} + +void boundPositionToRange(Position& position, const Length& mapLength, const Position& mapPosition) +{ + Vector vectorToOrigin; + getVectorToOrigin(vectorToOrigin, mapLength); + Position positionShifted = position - mapPosition + vectorToOrigin; + + // We have to make sure to stay inside the map. + for (int i = 0; i < positionShifted.size(); i++) { + + double epsilon = 10.0 * numeric_limits::epsilon(); // TODO Why is the factor 10 necessary. + if (std::fabs(position(i)) > 1.0) { + epsilon *= std::fabs(position(i)); + } + + if (positionShifted(i) <= 0) { + positionShifted(i) = epsilon; + continue; + } + if (positionShifted(i) >= mapLength(i)) { + positionShifted(i) = mapLength(i) - epsilon; + continue; + } + } + + position = positionShifted + mapPosition - vectorToOrigin; +} + +Eigen::Matrix2i getBufferOrderToMapFrameAlignment() +{ + return getBufferOrderToMapFrameTransformation().array().abs().matrix(); +} + +bool getSubmapInformation(Index& submapTopLeftIndex, + Size& submapBufferSize, + Position& submapPosition, + Length& submapLength, + Index& requestedIndexInSubmap, + const Position& requestedSubmapPosition, + const Length& requestedSubmapLength, + const Length& mapLength, + const Position& mapPosition, + const double& resolution, + const Size& bufferSize, + const Index& bufferStartIndex) +{ + // (Top left / bottom right corresponds to the position in the matrix, not the map frame) + const Eigen::Matrix2d halfTransform = 0.5 * getMapFrameToBufferOrderTransformation().cast(); + + // Corners of submap. + Position topLeftPosition = requestedSubmapPosition - halfTransform * requestedSubmapLength.matrix(); + boundPositionToRange(topLeftPosition, mapLength, mapPosition); + if (!getIndexFromPosition(submapTopLeftIndex, topLeftPosition, mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)) { + return false; + } + Index topLeftIndex; + topLeftIndex = getIndexFromBufferIndex(submapTopLeftIndex, bufferSize, bufferStartIndex); + + Position bottomRightPosition = requestedSubmapPosition + halfTransform * requestedSubmapLength.matrix(); + boundPositionToRange(bottomRightPosition, mapLength, mapPosition); + Index bottomRightIndex; + if (!getIndexFromPosition(bottomRightIndex, bottomRightPosition, mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)) { + return false; + } + bottomRightIndex = getIndexFromBufferIndex(bottomRightIndex, bufferSize, bufferStartIndex); + + // Get the position of the top left corner of the generated submap. + Position topLeftCorner; + if (!getPositionFromIndex(topLeftCorner, submapTopLeftIndex, mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)) { + return false; + } + topLeftCorner -= halfTransform * Position::Constant(resolution); + + // Size of submap. + submapBufferSize = bottomRightIndex - topLeftIndex + Index::Ones(); + + // Length of the submap. + submapLength = submapBufferSize.cast() * resolution; + + // Position of submap. + Vector vectorToSubmapOrigin; + getVectorToOrigin(vectorToSubmapOrigin, submapLength); + submapPosition = topLeftCorner - vectorToSubmapOrigin; + + // Get the index of the cell which corresponds the requested + // position of the submap. + return getIndexFromPosition(requestedIndexInSubmap, requestedSubmapPosition, submapLength, submapPosition, resolution, submapBufferSize); +} + +Size getSubmapSizeFromCornerIndices(const Index& topLeftIndex, const Index& bottomRightIndex, + const Size& bufferSize, const Index& bufferStartIndex) +{ + const Index unwrappedTopLeftIndex = getIndexFromBufferIndex(topLeftIndex, bufferSize, bufferStartIndex); + const Index unwrappedBottomRightIndex = getIndexFromBufferIndex(bottomRightIndex, bufferSize, bufferStartIndex); + return Size(unwrappedBottomRightIndex - unwrappedTopLeftIndex + Size::Ones()); +} + +bool getBufferRegionsForSubmap(std::vector& submapBufferRegions, + const Index& submapIndex, + const Size& submapBufferSize, + const Size& bufferSize, + const Index& bufferStartIndex) +{ + if ((getIndexFromBufferIndex(submapIndex, bufferSize, bufferStartIndex) + submapBufferSize > bufferSize).any()) { + return false; + } + + submapBufferRegions.clear(); + + Index bottomRightIndex = submapIndex + submapBufferSize - Index::Ones(); + wrapIndexToRange(bottomRightIndex, bufferSize); + + BufferRegion::Quadrant quadrantOfTopLeft = getQuadrant(submapIndex, bufferStartIndex); + BufferRegion::Quadrant quadrantOfBottomRight = getQuadrant(bottomRightIndex, bufferStartIndex); + + if (quadrantOfTopLeft == BufferRegion::Quadrant::TopLeft) { + + if (quadrantOfBottomRight == BufferRegion::Quadrant::TopLeft) { + submapBufferRegions.emplace_back(submapIndex, submapBufferSize, BufferRegion::Quadrant::TopLeft); + return true; + } + + if (quadrantOfBottomRight == BufferRegion::Quadrant::TopRight) { + Size topLeftSize(submapBufferSize(0), bufferSize(1) - submapIndex(1)); + submapBufferRegions.emplace_back(submapIndex, topLeftSize, BufferRegion::Quadrant::TopLeft); + + Index topRightIndex(submapIndex(0), 0); + Size topRightSize(submapBufferSize(0), submapBufferSize(1) - topLeftSize(1)); + submapBufferRegions.emplace_back(topRightIndex, topRightSize, BufferRegion::Quadrant::TopRight); + return true; + } + + if (quadrantOfBottomRight == BufferRegion::Quadrant::BottomLeft) { + Size topLeftSize(bufferSize(0) - submapIndex(0), submapBufferSize(1)); + submapBufferRegions.emplace_back(submapIndex, topLeftSize, BufferRegion::Quadrant::TopLeft); + + Index bottomLeftIndex(0, submapIndex(1)); + Size bottomLeftSize(submapBufferSize(0) - topLeftSize(0), submapBufferSize(1)); + submapBufferRegions.emplace_back(bottomLeftIndex, bottomLeftSize, BufferRegion::Quadrant::BottomLeft); + return true; + } + + if (quadrantOfBottomRight == BufferRegion::Quadrant::BottomRight) { + Size topLeftSize(bufferSize(0) - submapIndex(0), bufferSize(1) - submapIndex(1)); + submapBufferRegions.emplace_back(submapIndex, topLeftSize, BufferRegion::Quadrant::TopLeft); + + Index topRightIndex(submapIndex(0), 0); + Size topRightSize(bufferSize(0) - submapIndex(0), submapBufferSize(1) - topLeftSize(1)); + submapBufferRegions.emplace_back(topRightIndex, topRightSize, BufferRegion::Quadrant::TopRight); + + Index bottomLeftIndex(0, submapIndex(1)); + Size bottomLeftSize(submapBufferSize(0) - topLeftSize(0), bufferSize(1) - submapIndex(1)); + submapBufferRegions.emplace_back(bottomLeftIndex, bottomLeftSize, BufferRegion::Quadrant::BottomLeft); + + Index bottomRightIndex = Index::Zero(); + Size bottomRightSize(bottomLeftSize(0), topRightSize(1)); + submapBufferRegions.emplace_back(bottomRightIndex, bottomRightSize, BufferRegion::Quadrant::BottomRight); + return true; + } + + } else if (quadrantOfTopLeft == BufferRegion::Quadrant::TopRight) { + + if (quadrantOfBottomRight == BufferRegion::Quadrant::TopRight) { + submapBufferRegions.emplace_back(submapIndex, submapBufferSize, BufferRegion::Quadrant::TopRight); + return true; + } + + if (quadrantOfBottomRight == BufferRegion::Quadrant::BottomRight) { + + Size topRightSize(bufferSize(0) - submapIndex(0), submapBufferSize(1)); + submapBufferRegions.emplace_back(submapIndex, topRightSize, BufferRegion::Quadrant::TopRight); + + Index bottomRightIndex(0, submapIndex(1)); + Size bottomRightSize(submapBufferSize(0) - topRightSize(0), submapBufferSize(1)); + submapBufferRegions.emplace_back(bottomRightIndex, bottomRightSize, BufferRegion::Quadrant::BottomRight); + return true; + } + + } else if (quadrantOfTopLeft == BufferRegion::Quadrant::BottomLeft) { + + if (quadrantOfBottomRight == BufferRegion::Quadrant::BottomLeft) { + submapBufferRegions.emplace_back(submapIndex, submapBufferSize, BufferRegion::Quadrant::BottomLeft); + return true; + } + + if (quadrantOfBottomRight == BufferRegion::Quadrant::BottomRight) { + Size bottomLeftSize(submapBufferSize(0), bufferSize(1) - submapIndex(1)); + submapBufferRegions.emplace_back(submapIndex, bottomLeftSize, BufferRegion::Quadrant::BottomLeft); + + Index bottomRightIndex(submapIndex(0), 0); + Size bottomRightSize(submapBufferSize(0), submapBufferSize(1) - bottomLeftSize(1)); + submapBufferRegions.emplace_back(bottomRightIndex, bottomRightSize, BufferRegion::Quadrant::BottomRight); + return true; + } + + } else if (quadrantOfTopLeft == BufferRegion::Quadrant::BottomRight) { + + if (quadrantOfBottomRight == BufferRegion::Quadrant::BottomRight) { + submapBufferRegions.emplace_back(submapIndex, submapBufferSize, BufferRegion::Quadrant::BottomRight); + return true; + } + + } + + return false; +} + +bool incrementIndex(Index& index, const Size& bufferSize, const Index& bufferStartIndex) +{ + Index unwrappedIndex = getIndexFromBufferIndex(index, bufferSize, bufferStartIndex); + + // Increment index. + if (unwrappedIndex(1) + 1 < bufferSize(1)) { + // Same row. + unwrappedIndex[1]++; + } else { + // Next row. + unwrappedIndex[0]++; + unwrappedIndex[1] = 0; + } + + // End of iterations reached. + if (!checkIfIndexInRange(unwrappedIndex, bufferSize)) { + return false; + } + + // Return true iterated index. + index = getBufferIndexFromIndex(unwrappedIndex, bufferSize, bufferStartIndex); + return true; +} + +bool incrementIndexForSubmap(Index& submapIndex, Index& index, const Index& submapTopLeftIndex, + const Size& submapBufferSize, const Size& bufferSize, + const Index& bufferStartIndex) +{ + // Copy the data first, only copy it back if everything is within range. + Index tempIndex = index; + Index tempSubmapIndex = submapIndex; + + // Increment submap index. + if (tempSubmapIndex[1] + 1 < submapBufferSize[1]) { + // Same row. + tempSubmapIndex[1]++; + } else { + // Next row. + tempSubmapIndex[0]++; + tempSubmapIndex[1] = 0; + } + + // End of iterations reached. + if (!checkIfIndexInRange(tempSubmapIndex, submapBufferSize)) { + return false; + } + + // Get corresponding index in map. + Index unwrappedSubmapTopLeftIndex = getIndexFromBufferIndex(submapTopLeftIndex, bufferSize, bufferStartIndex); + tempIndex = getBufferIndexFromIndex(unwrappedSubmapTopLeftIndex + tempSubmapIndex, bufferSize, bufferStartIndex); + + // Copy data back. + index = tempIndex; + submapIndex = tempSubmapIndex; + return true; +} + +Index getIndexFromBufferIndex(const Index& bufferIndex, const Size& bufferSize, const Index& bufferStartIndex) +{ + if (checkIfStartIndexAtDefaultPosition(bufferStartIndex)) { + return bufferIndex; + } + + Index index = bufferIndex - bufferStartIndex; + wrapIndexToRange(index, bufferSize); + return index; +} + +Index getBufferIndexFromIndex(const Index& index, const Size& bufferSize, const Index& bufferStartIndex) +{ + if (checkIfStartIndexAtDefaultPosition(bufferStartIndex)) { + return index; + } + + Index bufferIndex = index + bufferStartIndex; + wrapIndexToRange(bufferIndex, bufferSize); + return bufferIndex; +} + +size_t getLinearIndexFromIndex(const Index& index, const Size& bufferSize, const bool rowMajor) +{ + if (!rowMajor) { + return index(1) * bufferSize(0) + index(0); + } + return index(0) * bufferSize(1) + index(1); +} + +Index getIndexFromLinearIndex(const size_t linearIndex, const Size& bufferSize, const bool rowMajor) +{ + if (!rowMajor) { + return Index((int)linearIndex % bufferSize(0), (int)linearIndex / bufferSize(0)); + } + return Index((int)linearIndex / bufferSize(1), (int)linearIndex % bufferSize(1)); +} + +bool colorValueToVector(const unsigned long& colorValue, Eigen::Vector3i& colorVector) +{ + colorVector(0) = (colorValue >> 16) & 0x0000ff; + colorVector(1) = (colorValue >> 8) & 0x0000ff; + colorVector(2) = colorValue & 0x0000ff; + return true; +} + +bool colorValueToVector(const unsigned long& colorValue, Eigen::Vector3f& colorVector) +{ + Eigen::Vector3i tempColorVector; + colorValueToVector(colorValue, tempColorVector); + colorVector = ((tempColorVector.cast()).array() / 255.0).matrix(); + return true; +} + +bool colorValueToVector(const float& colorValue, Eigen::Vector3f& colorVector) +{ + // cppcheck-suppress invalidPointerCast + const unsigned long tempColorValue = *reinterpret_cast(&colorValue); + colorValueToVector(tempColorValue, colorVector); + return true; +} + +bool colorVectorToValue(const Eigen::Vector3i& colorVector, unsigned long& colorValue) +{ + colorValue = ((int)colorVector(0)) << 16 | ((int)colorVector(1)) << 8 | ((int)colorVector(2)); + return true; +} + +void colorVectorToValue(const Eigen::Vector3i& colorVector, float& colorValue) +{ + Color colors; + colors.longColor_ = (colorVector(0) << 16) + (colorVector(1) << 8) + colorVector(2); + colorValue = colors.floatColor_; +} + +void colorVectorToValue(const Eigen::Vector3f& colorVector, float& colorValue) +{ + Eigen::Vector3i tempColorVector = (colorVector * 255.0).cast(); + colorVectorToValue(tempColorVector, colorValue); +} + +} // namespace grid_map + diff --git a/src/Polygon.cpp b/src/Polygon.cpp new file mode 100644 index 0000000..3ab234c --- /dev/null +++ b/src/Polygon.cpp @@ -0,0 +1,352 @@ +/* + * Polygon.cpp + * + * Created on: Nov 7, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include + +#include +#include + +#include +#include + +namespace grid_map { + +Polygon::Polygon() + : timestamp_(0) +{ +} + +Polygon::Polygon(std::vector vertices) + : Polygon() +{ + vertices_ = vertices; +} + +bool Polygon::isInside(const Position& point) const +{ + int cross = 0; + for (size_t i = 0, j = vertices_.size() - 1; i < vertices_.size(); j = i++) { + if ( ((vertices_[i].y() > point.y()) != (vertices_[j].y() > point.y())) + && (point.x() < (vertices_[j].x() - vertices_[i].x()) * (point.y() - vertices_[i].y()) / + (vertices_[j].y() - vertices_[i].y()) + vertices_[i].x()) ) + { + cross++; + } + } + return bool(cross % 2); +} + +void Polygon::addVertex(const Position& vertex) +{ + vertices_.push_back(vertex); +} + +const Position& Polygon::getVertex(const size_t index) const +{ + return vertices_.at(index); +} + +void Polygon::removeVertices() +{ + vertices_.clear(); +} + +const Position& Polygon::operator [](const size_t index) const +{ + return getVertex(index); +} + +const std::vector& Polygon::getVertices() const +{ + return vertices_; +} + +size_t Polygon::nVertices() const +{ + return vertices_.size(); +} + +const std::string& Polygon::getFrameId() const +{ + return frameId_; +} + +void Polygon::setFrameId(const std::string& frameId) +{ + frameId_ = frameId; +} + +uint64_t Polygon::getTimestamp() const +{ + return timestamp_; +} + +void Polygon::setTimestamp(const uint64_t timestamp) +{ + timestamp_ = timestamp; +} + +void Polygon::resetTimestamp() +{ + timestamp_ = 0.0; +} + +double Polygon::getArea() const +{ + double area = 0.0; + int j = vertices_.size() - 1; + for (size_t i = 0; i < vertices_.size(); i++) { + area += (vertices_.at(j).x() + vertices_.at(i).x()) + * (vertices_.at(j).y() - vertices_.at(i).y()); + j = i; + } + return std::abs(area / 2.0); +} + +Position Polygon::getCentroid() const +{ + Position centroid = Position::Zero(); + std::vector vertices = getVertices(); + vertices.push_back(vertices.at(0)); + double area = 0.0; + for (size_t i = 0; i < vertices.size() - 1; i++) { + const double a = vertices[i].x() * vertices[i+1].y() - vertices[i+1].x() * vertices[i].y(); + area += a; + centroid.x() += a * (vertices[i].x() + vertices[i+1].x()); + centroid.y() += a * (vertices[i].y() + vertices[i+1].y()); + } + area *= 0.5; + centroid /= (6.0 * area); + return centroid; +} + +void Polygon::getBoundingBox(Position& center, Length& length) const +{ + double minX = std::numeric_limits::infinity(); + double maxX = -std::numeric_limits::infinity(); + double minY = std::numeric_limits::infinity(); + double maxY = -std::numeric_limits::infinity(); + for (const auto& vertex : vertices_) { + if (vertex.x() > maxX) maxX = vertex.x(); + if (vertex.y() > maxY) maxY = vertex.y(); + if (vertex.x() < minX) minX = vertex.x(); + if (vertex.y() < minY) minY = vertex.y(); + } + center.x() = (minX + maxX) / 2.0; + center.y() = (minY + maxY) / 2.0; + length.x() = (maxX - minX); + length.y() = (maxY - minY); +} + +bool Polygon::convertToInequalityConstraints(Eigen::MatrixXd& A, Eigen::VectorXd& b) const +{ + Eigen::MatrixXd V(nVertices(), 2); + for (unsigned int i = 0; i < nVertices(); ++i) + V.row(i) = vertices_[i]; + + // Create k, a list of indices from V forming the convex hull. + // TODO: Assuming counter-clockwise ordered convex polygon. + // MATLAB: k = convhulln(V); + Eigen::MatrixXi k; + k.resizeLike(V); + for (unsigned int i = 0; i < V.rows(); ++i) + k.row(i) << i, (i+1) % V.rows(); + Eigen::RowVectorXd c = V.colwise().mean(); + V.rowwise() -= c; + A = Eigen::MatrixXd::Constant(k.rows(), V.cols(), NAN); + + unsigned int rc = 0; + for (unsigned int ix = 0; ix < k.rows(); ++ix) { + Eigen::MatrixXd F(2, V.cols()); + F.row(0) << V.row(k(ix, 0)); + F.row(1) << V.row(k(ix, 1)); + Eigen::FullPivLU luDecomp(F); + if (luDecomp.rank() == F.rows()) { + A.row(rc) = F.colPivHouseholderQr().solve(Eigen::VectorXd::Ones(F.rows())); + ++rc; + } + } + + A = A.topRows(rc); + b = Eigen::VectorXd::Ones(A.rows()); + b = b + A * c.transpose(); + + return true; +} + +bool Polygon::thickenLine(const double thickness) +{ + if (vertices_.size() != 2) return false; + const Vector connection(vertices_[1] - vertices_[0]); + const Vector orthogonal = thickness * Vector(connection.y(), -connection.x()).normalized(); + std::vector newVertices; + newVertices.reserve(4); + newVertices.push_back(vertices_[0] + orthogonal); + newVertices.push_back(vertices_[0] - orthogonal); + newVertices.push_back(vertices_[1] - orthogonal); + newVertices.push_back(vertices_[1] + orthogonal); + vertices_ = newVertices; + return true; +} + +bool Polygon::offsetInward(const double margin) +{ + // Create a list of indices of the neighbours of each vertex. + // TODO: Assuming counter-clockwise ordered convex polygon. + std::vector neighbourIndices; + const unsigned int n = nVertices(); + neighbourIndices.resize(n); + for (unsigned int i = 0; i < n; ++i) { + neighbourIndices[i] << (i > 0 ? (i-1)%n : n-1), (i + 1) % n; + } + + std::vector copy(vertices_); + for (unsigned int i = 0; i < neighbourIndices.size(); ++i) { + Eigen::Vector2d v1 = vertices_[neighbourIndices[i](0)] - vertices_[i]; + Eigen::Vector2d v2 = vertices_[neighbourIndices[i](1)] - vertices_[i]; + v1.normalize(); + v2.normalize(); + const double angle = acos(v1.dot(v2)); + copy[i] += margin / sin(angle) * (v1 + v2); + } + vertices_ = copy; + return true; +} + +std::vector Polygon::triangulate(const TriangulationMethods& /*method*/) const +{ + // TODO Add more triangulation methods. + // https://en.wikipedia.org/wiki/Polygon_triangulation + std::vector polygons; + if (vertices_.size() < 3) + return polygons; + + size_t nPolygons = vertices_.size() - 2; + polygons.reserve(nPolygons); + + if (nPolygons < 1) { + // Special case. + polygons.push_back(*this); + } else { + // General case. + for (size_t i = 0; i < nPolygons; ++i) { + Polygon polygon({vertices_[0], vertices_[i + 1], vertices_[i + 2]}); + polygons.push_back((polygon)); + } + } + + return polygons; +} + +Polygon Polygon::fromCircle(const Position center, const double radius, + const int nVertices) +{ + Eigen::Vector2d centerToVertex(radius, 0.0), centerToVertexTemp; + + Polygon polygon; + for (int j = 0; j < nVertices; j++) { + double theta = j * 2 * M_PI / (nVertices - 1); + Eigen::Rotation2D rot2d(theta); + centerToVertexTemp = rot2d.toRotationMatrix() * centerToVertex; + polygon.addVertex(center + centerToVertexTemp); + } + return polygon; +} + +Polygon Polygon::convexHullOfTwoCircles(const Position center1, + const Position center2, const double radius, + const int nVertices) +{ + if (center1 == center2) return fromCircle(center1, radius, nVertices); + Eigen::Vector2d centerToVertex, centerToVertexTemp; + centerToVertex = center2 - center1; + centerToVertex.normalize(); + centerToVertex *= radius; + + grid_map::Polygon polygon; + for (int j = 0; j < ceil(nVertices / 2.0); j++) { + double theta = M_PI_2 + j * M_PI / (ceil(nVertices / 2.0) - 1); + Eigen::Rotation2D rot2d(theta); + centerToVertexTemp = rot2d.toRotationMatrix() * centerToVertex; + polygon.addVertex(center1 + centerToVertexTemp); + } + for (int j = 0; j < ceil(nVertices / 2.0); j++) { + double theta = 3 * M_PI_2 + j * M_PI / (ceil(nVertices / 2.0) - 1); + Eigen::Rotation2D rot2d(theta); + centerToVertexTemp = rot2d.toRotationMatrix() * centerToVertex; + polygon.addVertex(center2 + centerToVertexTemp); + } + return polygon; +} + +Polygon Polygon::convexHull(Polygon& polygon1, Polygon& polygon2) +{ + std::vector vertices; + vertices.reserve(polygon1.nVertices() + polygon2.nVertices()); + vertices.insert(vertices.end(), polygon1.getVertices().begin(), polygon1.getVertices().end()); + vertices.insert(vertices.end(), polygon2.getVertices().begin(), polygon2.getVertices().end()); + + return monotoneChainConvexHullOfPoints(vertices); +} + +Polygon Polygon::monotoneChainConvexHullOfPoints(const std::vector& points) +{ + // Adapted from https://en.wikibooks.org/wiki/Algorithm_Implementation/Geometry/Convex_hull/Monotone_chain + if (points.size() <= 3) { + return Polygon(points); + } + std::vector pointsConvexHull(2 * points.size()); + + // Sort points lexicographically. + auto sortedPoints(points); + std::sort(sortedPoints.begin(), sortedPoints.end(), sortVertices); + + + int k = 0; + // Build lower hull + for (size_t i = 0; i < sortedPoints.size(); ++i) { + while (k >= 2 && vectorsMakeClockwiseTurn(pointsConvexHull.at(k - 2), pointsConvexHull.at(k - 1), sortedPoints.at(i))) { + k--; + } + pointsConvexHull.at(k++) = sortedPoints.at(i); + } + + // Build upper hull. + for (int i = sortedPoints.size() - 2, t = k + 1; i >= 0; i--) { + while (k >= t && vectorsMakeClockwiseTurn(pointsConvexHull.at(k - 2), pointsConvexHull.at(k - 1), sortedPoints.at(i))) { + k--; + } + pointsConvexHull.at(k++) = sortedPoints.at(i); + } + pointsConvexHull.resize(k - 1); + + Polygon polygon(pointsConvexHull); + return polygon; +} + +bool Polygon::sortVertices(const Eigen::Vector2d& vector1, + const Eigen::Vector2d& vector2) +{ + return (vector1.x() < vector2.x() + || (vector1.x() == vector2.x() && vector1.y() < vector2.y())); +} + +double Polygon::computeCrossProduct2D(const Eigen::Vector2d& vector1, + const Eigen::Vector2d& vector2) +{ + return (vector1.x() * vector2.y() - vector1.y() * vector2.x()); +} + +double Polygon::vectorsMakeClockwiseTurn(const Eigen::Vector2d &pointOrigin, + const Eigen::Vector2d &pointA, + const Eigen::Vector2d &pointB) +{ + return computeCrossProduct2D(pointA - pointOrigin, pointB - pointOrigin) <= 0; +} + +} /* namespace grid_map */ diff --git a/src/SubmapGeometry.cpp b/src/SubmapGeometry.cpp new file mode 100644 index 0000000..065adac --- /dev/null +++ b/src/SubmapGeometry.cpp @@ -0,0 +1,59 @@ +/* + * SubmapGeometry.cpp + * + * Created on: Aug 18, 2015 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include +#include + +namespace grid_map { + +SubmapGeometry::SubmapGeometry(const GridMap& gridMap, const Position& position, + const Length& length, bool& isSuccess) + : gridMap_(gridMap) +{ + isSuccess = getSubmapInformation(startIndex_, size_, position_, length_, + requestedIndexInSubmap_, position, length, gridMap_.getLength(), + gridMap_.getPosition(), gridMap_.getResolution(), + gridMap_.getSize(), gridMap_.getStartIndex()); +} + +const GridMap& SubmapGeometry::getGridMap() const +{ + return gridMap_; +} + +const Length& SubmapGeometry::getLength() const +{ + return length_; +} + +const Position& SubmapGeometry::getPosition() const +{ + return position_; +} + +const Index& SubmapGeometry::getRequestedIndexInSubmap() const +{ + return requestedIndexInSubmap_; +} + +const Size& SubmapGeometry::getSize() const +{ + return size_; +} + +double SubmapGeometry::getResolution() const +{ + return gridMap_.getResolution(); +} + +const Index& SubmapGeometry::getStartIndex() const +{ + return startIndex_; +} + +} /* namespace grid_map */ diff --git a/src/iterators/CircleIterator.cpp b/src/iterators/CircleIterator.cpp new file mode 100644 index 0000000..b681b33 --- /dev/null +++ b/src/iterators/CircleIterator.cpp @@ -0,0 +1,88 @@ +/* + * CircleIterator.hpp + * + * Created on: Nov 13, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/CircleIterator.hpp" + +#include +#include "grid_map_core/GridMapMath.hpp" + +namespace grid_map { + +CircleIterator::CircleIterator(const GridMap& gridMap, const Position& center, const double radius) + : center_(center), + radius_(radius) +{ + radiusSquare_ = pow(radius_, 2); + mapLength_ = gridMap.getLength(); + mapPosition_ = gridMap.getPosition(); + resolution_ = gridMap.getResolution(); + bufferSize_ = gridMap.getSize(); + bufferStartIndex_ = gridMap.getStartIndex(); + Index submapStartIndex; + Index submapBufferSize; + findSubmapParameters(center, radius, submapStartIndex, submapBufferSize); + internalIterator_ = std::make_shared(gridMap, submapStartIndex, submapBufferSize); + if(!isInside()) { + ++(*this); + } +} + +bool CircleIterator::operator !=(const CircleIterator& other) const +{ + return (internalIterator_ != other.internalIterator_); +} + +const Index& CircleIterator::operator *() const +{ + return *(*internalIterator_); +} + +CircleIterator& CircleIterator::operator ++() +{ + ++(*internalIterator_); + if (internalIterator_->isPastEnd()) { + return *this; + } + + for ( ; !internalIterator_->isPastEnd(); ++(*internalIterator_)) { + if (isInside()) { + break; + } + } + + return *this; +} + +bool CircleIterator::isPastEnd() const +{ + return internalIterator_->isPastEnd(); +} + +bool CircleIterator::isInside() const +{ + Position position; + getPositionFromIndex(position, *(*internalIterator_), mapLength_, mapPosition_, resolution_, bufferSize_, bufferStartIndex_); + double squareNorm = (position - center_).array().square().sum(); + return (squareNorm <= radiusSquare_); +} + +void CircleIterator::findSubmapParameters(const Position& center, const double radius, + Index& startIndex, Size& bufferSize) const +{ + Position topLeft = center.array() + radius; + Position bottomRight = center.array() - radius; + boundPositionToRange(topLeft, mapLength_, mapPosition_); + boundPositionToRange(bottomRight, mapLength_, mapPosition_); + getIndexFromPosition(startIndex, topLeft, mapLength_, mapPosition_, resolution_, bufferSize_, bufferStartIndex_); + Index endIndex; + getIndexFromPosition(endIndex, bottomRight, mapLength_, mapPosition_, resolution_, bufferSize_, bufferStartIndex_); + bufferSize = getSubmapSizeFromCornerIndices(startIndex, endIndex, bufferSize_, bufferStartIndex_); +} + +} /* namespace grid_map */ + diff --git a/src/iterators/EllipseIterator.cpp b/src/iterators/EllipseIterator.cpp new file mode 100644 index 0000000..7fe7632 --- /dev/null +++ b/src/iterators/EllipseIterator.cpp @@ -0,0 +1,100 @@ +/* + * EllipseIterator.hpp + * + * Created on: Dec 2, 2015 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/EllipseIterator.hpp" +#include "grid_map_core/GridMapMath.hpp" + +#include +#include + +namespace grid_map { + +EllipseIterator::EllipseIterator(const GridMap& gridMap, const Position& center, const Length& length, const double rotation) + : center_(center) +{ + semiAxisSquare_ = (0.5 * length).square(); + double sinRotation = std::sin(rotation); + double cosRotation = std::cos(rotation); + transformMatrix_ << cosRotation, sinRotation, sinRotation, -cosRotation; + mapLength_ = gridMap.getLength(); + mapPosition_ = gridMap.getPosition(); + resolution_ = gridMap.getResolution(); + bufferSize_ = gridMap.getSize(); + bufferStartIndex_ = gridMap.getStartIndex(); + Index submapStartIndex; + Index submapBufferSize; + findSubmapParameters(center, length, rotation, submapStartIndex, submapBufferSize); + internalIterator_ = std::make_shared(gridMap, submapStartIndex, submapBufferSize); + if (!isInside()) { + ++(*this); + } +} + +bool EllipseIterator::operator !=(const EllipseIterator& other) const +{ + return (internalIterator_ != other.internalIterator_); +} + +const Eigen::Array2i& EllipseIterator::operator *() const +{ + return *(*internalIterator_); +} + +EllipseIterator& EllipseIterator::operator ++() +{ + ++(*internalIterator_); + if (internalIterator_->isPastEnd()) { + return *this; + } + + for ( ; !internalIterator_->isPastEnd(); ++(*internalIterator_)) { + if (isInside()) { + break; + } + } + + return *this; +} + +bool EllipseIterator::isPastEnd() const +{ + return internalIterator_->isPastEnd(); +} + +const Size& EllipseIterator::getSubmapSize() const +{ + return internalIterator_->getSubmapSize(); +} + +bool EllipseIterator::isInside() const +{ + Position position; + getPositionFromIndex(position, *(*internalIterator_), mapLength_, mapPosition_, resolution_, bufferSize_, bufferStartIndex_); + double value = ((transformMatrix_ * (position - center_)).array().square() / semiAxisSquare_).sum(); + return (value <= 1); +} + +void EllipseIterator::findSubmapParameters(const Position& center, const Length& length, const double rotation, + Index& startIndex, Size& bufferSize) const +{ + const Eigen::Rotation2Dd rotationMatrix(rotation); + Eigen::Vector2d u = rotationMatrix * Eigen::Vector2d(length(0), 0.0); + Eigen::Vector2d v = rotationMatrix * Eigen::Vector2d(0.0, length(1)); + const Length boundingBoxHalfLength = (u.cwiseAbs2() + v.cwiseAbs2()).array().sqrt(); + Position topLeft = center.array() + boundingBoxHalfLength; + Position bottomRight = center.array() - boundingBoxHalfLength; + boundPositionToRange(topLeft, mapLength_, mapPosition_); + boundPositionToRange(bottomRight, mapLength_, mapPosition_); + getIndexFromPosition(startIndex, topLeft, mapLength_, mapPosition_, resolution_, bufferSize_, bufferStartIndex_); + Index endIndex; + getIndexFromPosition(endIndex, bottomRight, mapLength_, mapPosition_, resolution_, bufferSize_, bufferStartIndex_); + bufferSize = getSubmapSizeFromCornerIndices(startIndex, endIndex, bufferSize_, bufferStartIndex_); +} + +} /* namespace grid_map */ + diff --git a/src/iterators/GridMapIterator.cpp b/src/iterators/GridMapIterator.cpp new file mode 100644 index 0000000..756c103 --- /dev/null +++ b/src/iterators/GridMapIterator.cpp @@ -0,0 +1,75 @@ +/* + * GridMapIterator.cpp + * + * Created on: Sep 22, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/GridMapIterator.hpp" +#include "grid_map_core/GridMapMath.hpp" + +namespace grid_map { + +GridMapIterator::GridMapIterator(const grid_map::GridMap& gridMap) +{ + size_ = gridMap.getSize(); + startIndex_ = gridMap.getStartIndex(); + linearSize_ = size_.prod(); + linearIndex_ = 0; + isPastEnd_ = false; +} + +GridMapIterator::GridMapIterator(const GridMapIterator* other) +{ + size_ = other->size_; + startIndex_ = other->startIndex_; + linearSize_ = other->linearSize_; + linearIndex_ = other->linearIndex_; + isPastEnd_ = other->isPastEnd_; +} + +bool GridMapIterator::operator !=(const GridMapIterator& other) const +{ + return linearIndex_ != other.linearIndex_; +} + +Index GridMapIterator::operator *() const +{ + return getIndexFromLinearIndex(linearIndex_, size_); +} + +const size_t& GridMapIterator::getLinearIndex() const +{ + return linearIndex_; +} + +Index GridMapIterator::getUnwrappedIndex() const +{ + return getIndexFromBufferIndex(*(*this), size_, startIndex_); +} + +GridMapIterator& GridMapIterator::operator ++() +{ + size_t newIndex = linearIndex_ + 1; + if (newIndex < linearSize_) { + linearIndex_ = newIndex; + } else { + isPastEnd_ = true; + } + return *this; +} + +GridMapIterator GridMapIterator::end() const +{ + GridMapIterator res(this); + res.linearIndex_ = linearSize_ - 1; + return res; +} + +bool GridMapIterator::isPastEnd() const +{ + return isPastEnd_; +} + +} /* namespace grid_map */ diff --git a/src/iterators/LineIterator.cpp b/src/iterators/LineIterator.cpp new file mode 100644 index 0000000..2c6337d --- /dev/null +++ b/src/iterators/LineIterator.cpp @@ -0,0 +1,138 @@ +/* + * LineIterator.hpp + * + * Created on: Nov 13, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/LineIterator.hpp" +#include "grid_map_core/GridMapMath.hpp" + +namespace grid_map { + +LineIterator::LineIterator(const grid_map::GridMap& gridMap, const Position& start, + const Position& end) +{ + Index startIndex; + Index endIndex; + if (getIndexLimitedToMapRange(gridMap, start, end, startIndex) + && getIndexLimitedToMapRange(gridMap, end, start, endIndex)) { + initialize(gridMap, startIndex, endIndex); + } + else { + throw std::invalid_argument("Failed to construct LineIterator."); + } +} + +LineIterator::LineIterator(const grid_map::GridMap& gridMap, const Index& start, const Index& end) +{ + initialize(gridMap, start, end); +} + +bool LineIterator::operator !=(const LineIterator& other) const +{ + return (index_ != other.index_).any(); +} + +const Index& LineIterator::operator *() const +{ + return index_; +} + +LineIterator& LineIterator::operator ++() +{ + numerator_ += numeratorAdd_; // Increase the numerator by the top of the fraction. + if (numerator_ >= denominator_) { + numerator_ -= denominator_; + const Index unwrappedIndex = getIndexFromBufferIndex(index_, bufferSize_, bufferStartIndex_) + increment1_; + index_ = getBufferIndexFromIndex(unwrappedIndex, bufferSize_, bufferStartIndex_); + } + const Index unwrappedIndex = getIndexFromBufferIndex(index_, bufferSize_, bufferStartIndex_) + increment2_; + index_ = getBufferIndexFromIndex(unwrappedIndex, bufferSize_, bufferStartIndex_); + ++iCell_; + return *this; +} + +bool LineIterator::isPastEnd() const +{ + return iCell_ >= nCells_; +} + +bool LineIterator::initialize(const grid_map::GridMap& gridMap, const Index& start, const Index& end) +{ + start_ = start; + end_ = end; + mapLength_ = gridMap.getLength(); + mapPosition_ = gridMap.getPosition(); + resolution_ = gridMap.getResolution(); + bufferSize_ = gridMap.getSize(); + bufferStartIndex_ = gridMap.getStartIndex(); + initializeIterationParameters(); + return true; +} + +bool LineIterator::getIndexLimitedToMapRange(const grid_map::GridMap& gridMap, + const Position& start, const Position& end, + Index& index) +{ + Position newStart = start; + Vector direction = (end - start).normalized(); + while (!gridMap.getIndex(newStart, index)) { + newStart += (gridMap.getResolution() - std::numeric_limits::epsilon()) * direction; + if ((end - newStart).norm() < gridMap.getResolution() - std::numeric_limits::epsilon()) { + return false; + } + } + return true; +} + +void LineIterator::initializeIterationParameters() +{ + iCell_ = 0; + index_ = start_; + + const Index unwrappedStart = getIndexFromBufferIndex(start_, bufferSize_, bufferStartIndex_); + const Index unwrappedEnd = getIndexFromBufferIndex(end_, bufferSize_, bufferStartIndex_); + const Size delta = (unwrappedEnd - unwrappedStart).abs(); + + if (unwrappedEnd.x() >= unwrappedStart.x()) { + // x-values increasing. + increment1_.x() = 1; + increment2_.x() = 1; + } else { + // x-values decreasing. + increment1_.x() = -1; + increment2_.x() = -1; + } + + if (unwrappedEnd.y() >= unwrappedStart.y()) { + // y-values increasing. + increment1_.y() = 1; + increment2_.y() = 1; + } else { + // y-values decreasing. + increment1_.y() = -1; + increment2_.y() = -1; + } + + if (delta.x() >= delta.y()) { + // There is at least one x-value for every y-value. + increment1_.x() = 0; // Do not change the x when numerator >= denominator. + increment2_.y() = 0; // Do not change the y for every iteration. + denominator_ = delta.x(); + numerator_ = delta.x() / 2; + numeratorAdd_ = delta.y(); + nCells_ = delta.x() + 1; // There are more x-values than y-values. + } else { + // There is at least one y-value for every x-value + increment2_.x() = 0; // Do not change the x for every iteration. + increment1_.y() = 0; // Do not change the y when numerator >= denominator. + denominator_ = delta.y(); + numerator_ = delta.y() / 2; + numeratorAdd_ = delta.x(); + nCells_ = delta.y() + 1; // There are more y-values than x-values. + } +} + +} /* namespace grid_map */ diff --git a/src/iterators/PolygonIterator.cpp b/src/iterators/PolygonIterator.cpp new file mode 100644 index 0000000..733a842 --- /dev/null +++ b/src/iterators/PolygonIterator.cpp @@ -0,0 +1,88 @@ +/* + * PolygonIterator.hpp + * + * Created on: Sep 19, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include + +#include "grid_map_core/iterators/PolygonIterator.hpp" +#include "grid_map_core/GridMapMath.hpp" + +namespace grid_map { + +PolygonIterator::PolygonIterator(const grid_map::GridMap& gridMap, const grid_map::Polygon& polygon) + : polygon_(polygon) +{ + mapLength_ = gridMap.getLength(); + mapPosition_ = gridMap.getPosition(); + resolution_ = gridMap.getResolution(); + bufferSize_ = gridMap.getSize(); + bufferStartIndex_ = gridMap.getStartIndex(); + Index submapStartIndex; + Size submapBufferSize; + findSubmapParameters(polygon, submapStartIndex, submapBufferSize); + internalIterator_ = std::make_shared(gridMap, submapStartIndex, submapBufferSize); + if (!isInside()) { + ++(*this); + } +} + +bool PolygonIterator::operator !=(const PolygonIterator& other) const +{ + return (internalIterator_ != other.internalIterator_); +} + +const Index& PolygonIterator::operator *() const +{ + return *(*internalIterator_); +} + +PolygonIterator& PolygonIterator::operator ++() +{ + ++(*internalIterator_); + if (internalIterator_->isPastEnd()) { + return *this; + } + + for (; !internalIterator_->isPastEnd(); ++(*internalIterator_)) { + if (isInside()) { + break; + } + } + + return *this; +} + +bool PolygonIterator::isPastEnd() const +{ + return internalIterator_->isPastEnd(); +} + +bool PolygonIterator::isInside() const +{ + Position position; + getPositionFromIndex(position, *(*internalIterator_), mapLength_, mapPosition_, resolution_, bufferSize_, bufferStartIndex_); + return polygon_.isInside(position); +} + +void PolygonIterator::findSubmapParameters(const grid_map::Polygon& /*polygon*/, Index& startIndex, Size& bufferSize) const +{ + Position topLeft = polygon_.getVertices()[0]; + Position bottomRight = topLeft; + for (const auto& vertex : polygon_.getVertices()) { + topLeft = topLeft.array().max(vertex.array()); + bottomRight = bottomRight.array().min(vertex.array()); + } + boundPositionToRange(topLeft, mapLength_, mapPosition_); + boundPositionToRange(bottomRight, mapLength_, mapPosition_); + getIndexFromPosition(startIndex, topLeft, mapLength_, mapPosition_, resolution_, bufferSize_, bufferStartIndex_); + Index endIndex; + getIndexFromPosition(endIndex, bottomRight, mapLength_, mapPosition_, resolution_, bufferSize_, bufferStartIndex_); + bufferSize = getSubmapSizeFromCornerIndices(startIndex, endIndex, bufferSize_, bufferStartIndex_); +} + +} /* namespace grid_map */ + diff --git a/src/iterators/SlidingWindowIterator.cpp b/src/iterators/SlidingWindowIterator.cpp new file mode 100644 index 0000000..c1ba2a4 --- /dev/null +++ b/src/iterators/SlidingWindowIterator.cpp @@ -0,0 +1,117 @@ +/* + * SlidingWindowIterator.cpp + * + * Created on: Aug 17, 2017 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/SlidingWindowIterator.hpp" +#include "grid_map_core/GridMapMath.hpp" + +#include + +namespace grid_map { + +SlidingWindowIterator::SlidingWindowIterator(const GridMap& gridMap, const std::string& layer, + const EdgeHandling& edgeHandling, const size_t windowSize) + : GridMapIterator(gridMap), + edgeHandling_(edgeHandling), + data_(gridMap[layer]) +{ + windowSize_ = windowSize; + setup(gridMap); +} + +SlidingWindowIterator::SlidingWindowIterator(const SlidingWindowIterator* other) + : GridMapIterator(other), + edgeHandling_(other->edgeHandling_), + data_(other->data_) +{ + windowSize_ = other->windowSize_; + windowMargin_ = other->windowMargin_; +} + +void SlidingWindowIterator::setWindowLength(const GridMap& gridMap, const double windowLength) +{ + windowSize_ = static_cast(std::round(windowLength / gridMap.getResolution())); + if (windowSize_ % 2 != 1) { + ++windowSize_; + } + setup(gridMap); +} + +SlidingWindowIterator& SlidingWindowIterator::operator ++() +{ + if (edgeHandling_ == EdgeHandling::INSIDE) { + while (!isPastEnd()) { + GridMapIterator::operator++(); + if (dataInsideMap()) { + break; + } + } + } else { + GridMapIterator::operator++(); + } + return *this; +} + +Matrix SlidingWindowIterator::getData() const +{ + const Index centerIndex(*(*this)); + const Index windowMargin(Index::Constant(static_cast(windowMargin_))); + const Index originalTopLeftIndex(centerIndex - windowMargin); + Index topLeftIndex(originalTopLeftIndex); + boundIndexToRange(topLeftIndex, size_); + Index bottomRightIndex(centerIndex + windowMargin); + boundIndexToRange(bottomRightIndex, size_); + const Size adjustedWindowSize(bottomRightIndex - topLeftIndex + Size::Ones()); + + switch (edgeHandling_) { + case EdgeHandling::INSIDE: + case EdgeHandling::CROP: + return data_.block(topLeftIndex(0), topLeftIndex(1), adjustedWindowSize(0), adjustedWindowSize(1)); + case EdgeHandling::EMPTY: + case EdgeHandling::MEAN: + const Matrix data = data_.block(topLeftIndex(0), topLeftIndex(1), adjustedWindowSize(0), adjustedWindowSize(1)); + Matrix returnData(windowSize_, windowSize_); + if (edgeHandling_ == EdgeHandling::EMPTY) { + returnData.setConstant(NAN); + } else if (edgeHandling_ == EdgeHandling::MEAN) { + returnData.setConstant(data.meanOfFinites()); + } + const Index topLeftIndexShift(topLeftIndex - originalTopLeftIndex); + returnData.block(topLeftIndexShift(0), topLeftIndexShift(1), adjustedWindowSize(0), adjustedWindowSize(1)) = + data_.block(topLeftIndex(0), topLeftIndex(1), adjustedWindowSize(0), adjustedWindowSize(1)); + return returnData; + } + return Matrix::Zero(0, 0); +} + +void SlidingWindowIterator::setup(const GridMap& gridMap) +{ + if (!gridMap.isDefaultStartIndex()) { + throw std::runtime_error("SlidingWindowIterator cannot be used with grid maps that don't have a default buffer start index."); + } + if (windowSize_ % 2 == 0) { + throw std::runtime_error("SlidingWindowIterator has a wrong window size!"); + } + windowMargin_ = (windowSize_ - 1) / 2; + + if (edgeHandling_ == EdgeHandling::INSIDE) { + if (!dataInsideMap()) { + operator++(); + } + } +} + +bool SlidingWindowIterator::dataInsideMap() const +{ + const Index centerIndex(*(*this)); + const Index windowMargin(Index::Constant(static_cast(windowMargin_))); + const Index topLeftIndex(centerIndex - windowMargin); + const Index bottomRightIndex(centerIndex + windowMargin); + return checkIfIndexInRange(topLeftIndex, size_) && checkIfIndexInRange(bottomRightIndex, size_); +} + +} /* namespace grid_map */ diff --git a/src/iterators/SpiralIterator.cpp b/src/iterators/SpiralIterator.cpp new file mode 100644 index 0000000..9ee5b3c --- /dev/null +++ b/src/iterators/SpiralIterator.cpp @@ -0,0 +1,110 @@ +/* + * SpiralIterator.hpp + * + * Created on: Jul 7, 2015 + * Author: Martin Wermelinger + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/SpiralIterator.hpp" +#include "grid_map_core/GridMapMath.hpp" + +#include +#include + + +namespace grid_map { + +SpiralIterator::SpiralIterator(const grid_map::GridMap& gridMap, Eigen::Vector2d center, + const double radius) + : center_(std::move(center)), + radius_(radius), + distance_(0) +{ + radiusSquare_ = radius_ * radius_; + mapLength_ = gridMap.getLength(); + mapPosition_ = gridMap.getPosition(); + resolution_ = gridMap.getResolution(); + bufferSize_ = gridMap.getSize(); + gridMap.getIndex(center_, indexCenter_); + nRings_ = static_cast(std::ceil(radius_ / resolution_)); + if (checkIfIndexInRange(indexCenter_, bufferSize_)) { + pointsRing_.push_back(indexCenter_); + } else { + while (pointsRing_.empty() && !isPastEnd()) { + generateRing(); + } + } +} + +bool SpiralIterator::operator !=(const SpiralIterator& /*other*/) const +{ + return (pointsRing_.back() != pointsRing_.back()).any(); +} + +const Eigen::Array2i& SpiralIterator::operator *() const +{ + return pointsRing_.back(); +} + +SpiralIterator& SpiralIterator::operator ++() +{ + pointsRing_.pop_back(); + if (pointsRing_.empty() && !isPastEnd()) { + generateRing(); + } + return *this; +} + +bool SpiralIterator::isPastEnd() const +{ + return (distance_ == nRings_ && pointsRing_.empty()); +} + +bool SpiralIterator::isInside(const Index& index) const +{ + Eigen::Vector2d position; + getPositionFromIndex(position, index, mapLength_, mapPosition_, resolution_, bufferSize_); + double squareNorm = (position - center_).array().square().sum(); + return (squareNorm <= radiusSquare_); +} + +void SpiralIterator::generateRing() +{ + distance_++; + Index point(distance_, 0); + Index pointInMap; + Index normal; + do { + pointInMap.x() = point.x() + indexCenter_.x(); + pointInMap.y() = point.y() + indexCenter_.y(); + if (checkIfIndexInRange(pointInMap, bufferSize_)) { + if (distance_ == nRings_ || distance_ == nRings_ - 1) { + if (isInside(pointInMap)) { + pointsRing_.push_back(pointInMap); + } + } else { + pointsRing_.push_back(pointInMap); + } + } + normal.x() = -signum(point.y()); + normal.y() = signum(point.x()); + if (normal.x() != 0 && static_cast(Vector(point.x() + normal.x(), point.y()).norm()) == distance_) { + point.x() += normal.x(); + } else if (normal.y() != 0 && static_cast(Vector(point.x(), point.y() + normal.y()).norm()) == distance_) { + point.y() += normal.y(); + } else { + point.x() += normal.x(); + point.y() += normal.y(); + } + } while (static_cast(point.x()) != distance_ || point.y() != 0); +} + +double SpiralIterator::getCurrentRadius() const +{ + Index radius = *(*this) - indexCenter_; + return radius.matrix().norm() * resolution_; +} + +} /* namespace grid_map */ + diff --git a/src/iterators/SubmapIterator.cpp b/src/iterators/SubmapIterator.cpp new file mode 100644 index 0000000..12fb120 --- /dev/null +++ b/src/iterators/SubmapIterator.cpp @@ -0,0 +1,84 @@ +/* + * SubmapIterator.hpp + * + * Created on: Sep 22, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/SubmapIterator.hpp" +#include "grid_map_core/GridMapMath.hpp" + + + +namespace grid_map { + +SubmapIterator::SubmapIterator(const grid_map::SubmapGeometry& submap) + : SubmapIterator(submap.getGridMap(), submap.getStartIndex(), submap.getSize()) +{ +} + +SubmapIterator::SubmapIterator(const grid_map::GridMap& gridMap, + const grid_map::BufferRegion& bufferRegion) + : SubmapIterator(gridMap, bufferRegion.getStartIndex(), bufferRegion.getSize()) +{ +} + + +SubmapIterator::SubmapIterator(const grid_map::GridMap& gridMap, const Index& submapStartIndex, + const Size& submapSize) +{ + size_ = gridMap.getSize(); + startIndex_ = gridMap.getStartIndex(); + index_ = submapStartIndex; + submapSize_ = submapSize; + submapStartIndex_ = submapStartIndex; + submapIndex_.setZero(); + isPastEnd_ = false; +} + +SubmapIterator::SubmapIterator(const SubmapIterator* other) +{ + size_ = other->size_; + startIndex_ = other->startIndex_; + submapSize_ = other->submapSize_; + submapStartIndex_ = other->submapStartIndex_; + index_ = other->index_; + submapIndex_ = other->submapIndex_; + isPastEnd_ = other->isPastEnd_; +} + +bool SubmapIterator::operator !=(const SubmapIterator& other) const +{ + return (index_ != other.index_).any(); +} + +const Index& SubmapIterator::operator *() const +{ + return index_; +} + +const Index& SubmapIterator::getSubmapIndex() const +{ + return submapIndex_; +} + +SubmapIterator& SubmapIterator::operator ++() +{ + isPastEnd_ = !incrementIndexForSubmap(submapIndex_, index_, submapStartIndex_, + submapSize_, size_, startIndex_); + return *this; +} + +bool SubmapIterator::isPastEnd() const +{ + return isPastEnd_; +} + +const Size& SubmapIterator::getSubmapSize() const +{ + return submapSize_; +} + +} /* namespace grid_map */ + diff --git a/test/CubicConvolutionInterpolationTest.cpp b/test/CubicConvolutionInterpolationTest.cpp new file mode 100644 index 0000000..4e884f2 --- /dev/null +++ b/test/CubicConvolutionInterpolationTest.cpp @@ -0,0 +1,130 @@ +/* + * CubicConvolutionInterpolationTest.cpp + * + * Created on: Mar 3, 2020 + * Author: Edo Jelavic + * Institute: ETH Zurich, Robotic Systems Lab + */ + +#include "test_helpers.hpp" + +#include "grid_map_core/GridMap.hpp" + +// gtest +#include + +namespace gm = grid_map; +namespace gmt = grid_map_test; + +TEST(CubicConvolutionInterpolation, FlatWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(2.0, 2.0), 0.1, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createFlatWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 100); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC_CONVOLUTION); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicConvolutionInterpolation, FlatWorld failed with seed: " << seed + << std::endl; + } +} + +TEST(CubicConvolutionInterpolation, RationalFunctionWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(3.0, 3.0), 0.01, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createRationalFunctionWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC_CONVOLUTION); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicConvolutionInterpolation, RationalFunctionWorld failed with seed: " + << seed << std::endl; + } +} + +TEST(CubicConvolutionInterpolation, SaddleWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(3.0, 3.0), 0.1, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createSaddleWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC_CONVOLUTION); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicConvolutionInterpolation, SaddleWorld failed with seed: " << seed + << std::endl; + } +} + +TEST(CubicConvolutionInterpolation, SecondOrderPolyWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(3.0, 3.0), 0.1, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createSecondOrderPolyWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC_CONVOLUTION); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicConvolutionInterpolation, SecondOrderPolyWorld failed with seed: " + << seed << std::endl; + } +} + +TEST(CubicConvolutionInterpolation, SineWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(3.0, 3.0), 0.01, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createSineWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC_CONVOLUTION); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicConvolutionInterpolation, SineWorld failed with seed: " << seed + << std::endl; + } +} + +TEST(CubicConvolutionInterpolation, TanhWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(2.5, 2.5), 0.02, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createTanhWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC_CONVOLUTION); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicConvolutionInterpolation, TanhWorld failed with seed: " << seed + << std::endl; + } +} + +TEST(CubicConvolutionInterpolation, GaussianWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(3.0, 3.0), 0.02, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createGaussianWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC_CONVOLUTION); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicConvolutionInterpolation, GaussianWorld failed with seed: " << seed + << std::endl; + } +} + diff --git a/test/CubicInterpolationTest.cpp b/test/CubicInterpolationTest.cpp new file mode 100644 index 0000000..eb4a9cf --- /dev/null +++ b/test/CubicInterpolationTest.cpp @@ -0,0 +1,126 @@ +/* + * CubicInterpolationTest.cpp + * + * Created on: Mar 12, 2020 + * Author: Edo Jelavic + * Institute: ETH Zurich, Robotic Systems Lab + */ + +#include "test_helpers.hpp" + +#include "grid_map_core/GridMap.hpp" + +// gtest +#include + +namespace gm = grid_map; +namespace gmt = grid_map_test; + +TEST(CubicInterpolation, FlatWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(2.0, 2.0), 0.1, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createFlatWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 100); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicInterpolation, FlatWorld failed with seed: " << seed << std::endl; + } +} + +TEST(CubicInterpolation, RationalFunctionWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(3.0, 3.0), 0.01, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createRationalFunctionWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicInterpolation, RationalFunctionWorld failed with seed: " << seed + << std::endl; + } +} + +TEST(CubicInterpolation, SaddleWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(3.0, 3.0), 0.1, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createSaddleWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicInterpolation, SaddleWorld failed with seed: " << seed << std::endl; + } +} + +TEST(CubicInterpolation, SecondOrderPolyWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(3.0, 3.0), 0.1, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createSecondOrderPolyWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicInterpolation, SecondOrderPolyWorld failed with seed: " << seed + << std::endl; + } +} + +TEST(CubicInterpolation, SineWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(3.0, 3.0), 0.01, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createSineWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicInterpolation, SineWorld failed with seed: " << seed << std::endl; + } +} + +TEST(CubicInterpolation, TanhWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(2.5, 2.5), 0.02, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createTanhWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicInterpolation, TanhWorld failed with seed: " << seed << std::endl; + } +} + +TEST(CubicInterpolation, GaussianWorld) +{ + const int seed = rand(); + gmt::rndGenerator.seed(seed); + auto map = gmt::createMap(gm::Length(3.0, 3.0), 0.02, gm::Position(0.0, 0.0)); + auto trueValues = gmt::createGaussianWorld(&map); + const auto queryPoints = gmt::uniformlyDitributedPointsWithinMap(map, 1000); + + verifyValuesAtQueryPointsAreClose(map, trueValues, queryPoints, gm::InterpolationMethods::INTER_CUBIC); + + if (::testing::Test::HasFailure()) { + std::cout << "\n Test CubicInterpolation, GaussianWorld failed with seed: " << seed + << std::endl; + } +} + diff --git a/test/EigenPluginsTest.cpp b/test/EigenPluginsTest.cpp new file mode 100644 index 0000000..cdbd1e8 --- /dev/null +++ b/test/EigenPluginsTest.cpp @@ -0,0 +1,115 @@ +/* + * EigenMatrixBaseAddonsTest.cpp + * + * Created on: Sep 23, 2015 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/grid_map_core.hpp" + +// gtest +#include + +// Eigen +#include + +using Eigen::Matrix; + +TEST(EigenMatrixBaseAddons, numberOfFinites) +{ + Eigen::Matrix3f matrix(Eigen::Matrix3f::Ones()); + matrix(0, 0) = NAN; + matrix(1, 0) = NAN; + EXPECT_EQ(7, matrix.numberOfFinites()); + + Matrix matrix2; + matrix2.setOnes(); + EXPECT_EQ(matrix2.rows() * matrix2.cols(), matrix2.numberOfFinites()); + + Matrix matrix3; + matrix3.setConstant(NAN); + matrix3.col(3).setConstant(0.0); + EXPECT_EQ(matrix3.rows(), matrix3.numberOfFinites()); +} + +TEST(EigenMatrixBaseAddons, sumOfFinites) +{ + Matrix matrix; + matrix.setRandom(); + EXPECT_NEAR(matrix.sum(), matrix.sumOfFinites(), 1e-10); + double finiteSum = matrix.sum() - matrix(0, 0) - matrix(1, 2) - matrix(3, 6) - matrix(6, 12); + matrix(0, 0) = NAN; + matrix(1, 2) = NAN; + matrix(3, 6) = NAN; + matrix(6, 12) = NAN; + EXPECT_NEAR(finiteSum, matrix.sumOfFinites(), 1e-10); + matrix.setConstant(NAN); + EXPECT_TRUE(std::isnan(matrix.sumOfFinites())); + matrix(5, 7) = 1.0; + EXPECT_NEAR(1.0, matrix.sumOfFinites(), 1e-10); +} + +TEST(EigenMatrixBaseAddons, meanOfFinites) +{ + Eigen::Matrix3f matrix(Eigen::Matrix3f::Ones()); + matrix(0, 0) = NAN; + matrix(1, 1) = NAN; + EXPECT_DOUBLE_EQ(1.0, matrix.meanOfFinites()); + + Matrix matrix2; + matrix2.setRandom(); + EXPECT_NEAR(matrix2.mean(), matrix2.meanOfFinites(), 1e-10); +} + +TEST(EigenMatrixBaseAddons, minCoeffOfFinites) +{ + Matrix matrix; + matrix.setRandom(); + double min = matrix.minCoeff(); + EXPECT_NEAR(min, matrix.minCoeffOfFinites(), 1e-10); + + int i; + int j; + matrix.maxCoeff(&i, &j); + matrix(i, j) = NAN; + EXPECT_NEAR(min, matrix.minCoeffOfFinites(), 1e-10); + + matrix.setConstant(NAN); + EXPECT_TRUE(std::isnan(matrix.minCoeffOfFinites())); + matrix(i, j) = -1.0; + EXPECT_NEAR(-1.0, matrix.minCoeffOfFinites(), 1e-10); +} + +TEST(EigenMatrixBaseAddons, maxCoeffOfFinites) +{ + Matrix matrix; + matrix.setRandom(); + double max = matrix.maxCoeff(); + EXPECT_NEAR(max, matrix.maxCoeffOfFinites(), 1e-10); + + int i; + int j; + matrix.minCoeff(&i, &j); + matrix(i, j) = NAN; + EXPECT_NEAR(max, matrix.maxCoeffOfFinites(), 1e-10); + + matrix.setConstant(NAN); + EXPECT_TRUE(std::isnan(matrix.maxCoeffOfFinites())); + matrix(i, j) = -1.0; + EXPECT_NEAR(-1.0, matrix.maxCoeffOfFinites(), 1e-10); +} + +TEST(EigenMatrixBaseAddons, clamp) +{ + Eigen::VectorXf vector(Eigen::VectorXf::LinSpaced(9, 1.0, 9.0)); + Eigen::Matrix3f matrix; + matrix << vector.segment(0, 3), vector.segment(3, 3), vector.segment(6, 3); + matrix(1, 1) = NAN; + matrix = matrix.unaryExpr(grid_map::Clamp(2.1, 7.0)); + EXPECT_NEAR(2.1, matrix(0, 0), 1e-7); + EXPECT_NEAR(2.1, matrix(1, 0), 1e-7); + EXPECT_NEAR(3.0, matrix(2, 0), 1e-7); + EXPECT_TRUE(std::isnan(matrix(1, 1))); + EXPECT_NEAR(7.0, matrix(2, 2), 1e-7); +} diff --git a/test/EllipseIteratorTest.cpp b/test/EllipseIteratorTest.cpp new file mode 100644 index 0000000..f77fee0 --- /dev/null +++ b/test/EllipseIteratorTest.cpp @@ -0,0 +1,55 @@ +/* + * EllipseIteratorTest.cpp + * + * Created on: Dec 2, 2015 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/EllipseIterator.hpp" +#include "grid_map_core/GridMap.hpp" + +// gtest +#include + +// Vector +#include + +using grid_map::GridMap; +using grid_map::Length; +using grid_map::Position; +using grid_map::EllipseIterator; + +TEST(EllipseIterator, OneCellWideEllipse) +{ + GridMap map( { "types" }); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); + + EllipseIterator iterator(map, Position(0.0, 0.0), Length(8.0, 1.0)); + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(0, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(1, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(2, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + ++iterator; + ++iterator; + ++iterator; + ++iterator; + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(7, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} diff --git a/test/GridMapIteratorTest.cpp b/test/GridMapIteratorTest.cpp new file mode 100644 index 0000000..33c1ac4 --- /dev/null +++ b/test/GridMapIteratorTest.cpp @@ -0,0 +1,59 @@ +/* + * GridMapDataIterator.cpp + * + * Created on: Feb 16, 2016 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/GridMapIterator.hpp" +#include "grid_map_core/GridMap.hpp" + +// gtest +#include + +// Vector +#include + +using grid_map::GridMap; +using grid_map::Length; +using grid_map::Position; +using grid_map::GridMapIterator; + +TEST(GridMapIterator, Simple) +{ + GridMap map; + map.setGeometry(Length(8.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + map.add("layer", 0.0); + GridMapIterator iterator(map); + + unsigned int i = 0; + for (; !iterator.isPastEnd(); ++iterator, ++i) { + map.at("layer", *iterator) = 1.0; + EXPECT_FALSE(iterator.isPastEnd()); + } + + EXPECT_EQ(40, i); + EXPECT_TRUE(iterator.isPastEnd()); + EXPECT_TRUE((map["layer"].array() == 1.0f).all()); +} + +TEST(GridMapIterator, LinearIndex) +{ + GridMap map; + map.setGeometry(Length(8.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + map.add("layer", 0.0); + GridMapIterator iterator(map); + + auto& data = map["layer"]; + unsigned int i = 0; + for (; !iterator.isPastEnd(); ++iterator, ++i) { + data(static_cast(iterator.getLinearIndex())) = 1.0; + EXPECT_EQ(i, iterator.getLinearIndex()); + EXPECT_FALSE(iterator.isPastEnd()); + } + + EXPECT_EQ(40, i); + EXPECT_TRUE(iterator.isPastEnd()); + EXPECT_TRUE((map["layer"].array() == 1.0f).all()); +} diff --git a/test/GridMapMathTest.cpp b/test/GridMapMathTest.cpp new file mode 100644 index 0000000..1382f76 --- /dev/null +++ b/test/GridMapMathTest.cpp @@ -0,0 +1,1039 @@ +/* + * GridMapMathTest.cpp + * + * Created on: Feb 10, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/GridMapMath.hpp" + +// gtest +#include + +// Limits +#include + +// Vector +#include + +using std::numeric_limits; + +namespace grid_map{ + +TEST(PositionFromIndex, Simple) +{ + Length mapLength(3.0, 2.0); + Position mapPosition(-1.0, 2.0); + double resolution = 1.0; + Size bufferSize(3, 2); + Position position; + + EXPECT_TRUE(getPositionFromIndex(position, Index(0, 0), mapLength, mapPosition, resolution, bufferSize)); + EXPECT_DOUBLE_EQ(1.0 + mapPosition.x(), position.x()); + EXPECT_DOUBLE_EQ(0.5 + mapPosition.y(), position.y()); + + EXPECT_TRUE(getPositionFromIndex(position, Index(1, 0), mapLength, mapPosition, resolution, bufferSize)); + EXPECT_DOUBLE_EQ(0.0 + mapPosition.x(), position.x()); + EXPECT_DOUBLE_EQ(0.5 + mapPosition.y(), position.y()); + + EXPECT_TRUE(getPositionFromIndex(position, Index(1, 1), mapLength, mapPosition, resolution, bufferSize)); + EXPECT_DOUBLE_EQ(0.0 + mapPosition.x(), position.x()); + EXPECT_DOUBLE_EQ(-0.5 + mapPosition.y(), position.y()); + + EXPECT_TRUE(getPositionFromIndex(position, Index(2, 1), mapLength, mapPosition, resolution, bufferSize)); + EXPECT_DOUBLE_EQ(-1.0 + mapPosition.x(), position.x()); + EXPECT_DOUBLE_EQ(-0.5 + mapPosition.y(), position.y()); + + EXPECT_FALSE(getPositionFromIndex(position, Index(3, 1), mapLength, mapPosition, resolution, bufferSize)); +} + +TEST(PositionFromIndex, CircularBuffer) +{ + Length mapLength(0.5, 0.4); + Position mapPosition(-0.1, 13.4); + double resolution = 0.1; + Size bufferSize(5, 4); + Index bufferStartIndex(3, 1); + Position position; + + EXPECT_TRUE(getPositionFromIndex(position, Index(3, 1), mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_DOUBLE_EQ(0.2 + mapPosition.x(), position.x()); + EXPECT_DOUBLE_EQ(0.15 + mapPosition.y(), position.y()); + + EXPECT_TRUE(getPositionFromIndex(position, Index(4, 2), mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_DOUBLE_EQ(0.1 + mapPosition.x(), position.x()); + EXPECT_DOUBLE_EQ(0.05 + mapPosition.y(), position.y()); + + EXPECT_TRUE(getPositionFromIndex(position, Index(2, 0), mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_DOUBLE_EQ(-0.2 + mapPosition.x(), position.x()); + EXPECT_DOUBLE_EQ(-0.15 + mapPosition.y(), position.y()); + + EXPECT_TRUE(getPositionFromIndex(position, Index(0, 0), mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_DOUBLE_EQ(0.0 + mapPosition.x(), position.x()); + EXPECT_DOUBLE_EQ(-0.15 + mapPosition.y(), position.y()); + + EXPECT_TRUE(getPositionFromIndex(position, Index(4, 3), mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_DOUBLE_EQ(0.1 + mapPosition.x(), position.x()); + EXPECT_DOUBLE_EQ(-0.05 + mapPosition.y(), position.y()); + + EXPECT_FALSE(getPositionFromIndex(position, Index(5, 3), mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); +} + +TEST(IndexFromPosition, Simple) +{ + Length mapLength(3.0, 2.0); + Position mapPosition(-12.4, -7.1); + double resolution = 1.0; + Index bufferSize(3, 2); + Index index; + + EXPECT_TRUE(getIndexFromPosition(index, Position(1.0, 0.5) + mapPosition, mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(0, index(0)); + EXPECT_EQ(0, index(1)); + + EXPECT_TRUE(getIndexFromPosition(index, Position(-1.0, -0.5) + mapPosition, mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(2, index(0)); + EXPECT_EQ(1, index(1)); + + EXPECT_TRUE(getIndexFromPosition(index, Position(0.6, 0.1) + mapPosition, mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(0, index(0)); + EXPECT_EQ(0, index(1)); + + EXPECT_TRUE(getIndexFromPosition(index, Position(0.4, -0.1) + mapPosition, mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(1, index(0)); + EXPECT_EQ(1, index(1)); + + EXPECT_TRUE(getIndexFromPosition(index, Position(0.4, 0.1) + mapPosition, mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(1, index(0)); + EXPECT_EQ(0, index(1)); + + EXPECT_FALSE(getIndexFromPosition(index, Position(4.0, 0.5) + mapPosition, mapLength, mapPosition, resolution, bufferSize)); +} + +TEST(IndexFromPosition, EdgeCases) +{ + Length mapLength(3.0, 2.0); + Position mapPosition(0.0, 0.0); + double resolution = 1.0; + Size bufferSize(3, 2); + Index index; + + EXPECT_TRUE(getIndexFromPosition(index, Position(0.0, DBL_EPSILON), mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(1, index(0)); + EXPECT_EQ(0, index(1)); + + EXPECT_TRUE(getIndexFromPosition(index, Position(0.5 - DBL_EPSILON, -DBL_EPSILON), mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(1, index(0)); + EXPECT_EQ(1, index(1)); + + EXPECT_TRUE(getIndexFromPosition(index, Position(-0.5 - DBL_EPSILON, -DBL_EPSILON), mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(2, index(0)); + EXPECT_EQ(1, index(1)); + + EXPECT_FALSE(getIndexFromPosition(index, Position(-1.5, 1.0), mapLength, mapPosition, resolution, bufferSize)); +} + +TEST(IndexFromPosition, CircularBuffer) +{ + Length mapLength(0.5, 0.4); + Position mapPosition(0.4, -0.9); + double resolution = 0.1; + Size bufferSize(5, 4); + Index bufferStartIndex(3, 1); + Index index; + + EXPECT_TRUE(getIndexFromPosition(index, Position(0.2, 0.15) + mapPosition, mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_EQ(3, index(0)); + EXPECT_EQ(1, index(1)); + + EXPECT_TRUE(getIndexFromPosition(index, Position(0.03, -0.17) + mapPosition, mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_EQ(0, index(0)); + EXPECT_EQ(0, index(1)); +} + +TEST(checkIfPositionWithinMap, Inside) +{ + Length mapLength(50.0, 25.0); + Position mapPosition(11.4, 0.0); + + EXPECT_TRUE(checkIfPositionWithinMap(Position(0.0, 0.0) + mapPosition, mapLength, mapPosition)); + EXPECT_TRUE(checkIfPositionWithinMap(Position(5.0, 5.0) + mapPosition, mapLength, mapPosition)); + EXPECT_TRUE(checkIfPositionWithinMap(Position(20.0, 10.0) + mapPosition, mapLength, mapPosition)); + EXPECT_TRUE(checkIfPositionWithinMap(Position(20.0, -10.0) + mapPosition, mapLength, mapPosition)); + EXPECT_TRUE(checkIfPositionWithinMap(Position(-20.0, 10.0) + mapPosition, mapLength, mapPosition)); + EXPECT_TRUE(checkIfPositionWithinMap(Position(-20.0, -10.0) + mapPosition, mapLength, mapPosition)); +} + +TEST(checkIfPositionWithinMap, Outside) +{ + Length mapLength(10.0, 5.0); + Position mapPosition(-3.0, 145.2); + + EXPECT_FALSE(checkIfPositionWithinMap(Position(5.5, 0.0) + mapPosition, mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(-5.5, 0.0) + mapPosition, mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(-5.5, 3.0) + mapPosition, mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(-5.5, -3.0) + mapPosition, mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(3.0, 3.0) + mapPosition, mapLength, mapPosition)); +} + +TEST(checkIfPositionWithinMap, EdgeCases) +{ + Length mapLength(2.0, 3.0); + Position mapPosition(0.0, 0.0); + + /* + * + * A (is inside) B (is not inside) + * +-----------------------+ + * | | + * | | + * | X | + * | ^ | + * | | | + * | | | + * | <-----+ | + * | Y | + * | | + * | | + * | | + * +-----------------------+ + * C (is not inside) D (is not inside) + * + * Resulting coordinates are: + * A: (1.0, 1.5) + * B: (1.0, -1.5) + * C: (-1.0, 1.5) + * D: (-1.0, -1.5) + * + */ + + // Noise around A. + EXPECT_TRUE(checkIfPositionWithinMap(Position(1.0, 1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(1.0 + DBL_EPSILON, 1.5), mapLength, mapPosition)); + EXPECT_TRUE(checkIfPositionWithinMap(Position(1.0 - DBL_EPSILON, 1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(1.0, 1.5 + DBL_EPSILON), mapLength, mapPosition)); + EXPECT_TRUE(checkIfPositionWithinMap(Position(1.0, 1.5 - DBL_EPSILON), mapLength, mapPosition)); + + // Noise around B. + EXPECT_FALSE(checkIfPositionWithinMap(Position(1.0, -1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(1.0 + DBL_EPSILON, - 1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(1.0 - DBL_EPSILON, - 1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(1.0, - 1.5 + DBL_EPSILON), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(1.0, - 1.5 - DBL_EPSILON), mapLength, mapPosition)); + + // Noise around C. + EXPECT_FALSE(checkIfPositionWithinMap(Position(-1.0, 1.5), mapLength, mapPosition)); + EXPECT_TRUE(checkIfPositionWithinMap(Position(-1.0 + DBL_EPSILON, 1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(-1.0 - DBL_EPSILON, 1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(-1.0, 1.5 + DBL_EPSILON), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(-1.0, 1.5 - DBL_EPSILON), mapLength, mapPosition)); + + // Noise around D. + EXPECT_FALSE(checkIfPositionWithinMap(Position(-1.0, -1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(-1.0 + DBL_EPSILON, -1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(-1.0 - DBL_EPSILON, -1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(-1.0, -1.5 + DBL_EPSILON), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(-1.0, -1.5 - DBL_EPSILON), mapLength, mapPosition)); + + // Extra tests. + EXPECT_FALSE(checkIfPositionWithinMap(Position(-1.0, 1.5), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(1.0 + DBL_EPSILON, 1.0), mapLength, mapPosition)); + EXPECT_TRUE(checkIfPositionWithinMap(Position((2.0 + DBL_EPSILON) / 2.0, 1.0), mapLength, mapPosition)); + EXPECT_FALSE(checkIfPositionWithinMap(Position(0.5, -1.5 - (2.0 * DBL_EPSILON)), mapLength, mapPosition)); + EXPECT_TRUE(checkIfPositionWithinMap(Position(-0.5, (3.0 + DBL_EPSILON) / 2.0), mapLength, mapPosition)); +} + +TEST(getIndexShiftFromPositionShift, All) +{ + double resolution = 1.0; + Index indexShift; + + EXPECT_TRUE(getIndexShiftFromPositionShift(indexShift, Vector(0.0, 0.0), resolution)); + EXPECT_EQ(0, indexShift(0)); + EXPECT_EQ(0, indexShift(1)); + + EXPECT_TRUE(getIndexShiftFromPositionShift(indexShift, Vector(0.35, -0.45), resolution)); + EXPECT_EQ(0, indexShift(0)); + EXPECT_EQ(0, indexShift(1)); + + EXPECT_TRUE(getIndexShiftFromPositionShift(indexShift, Vector(0.55, -0.45), resolution)); + EXPECT_EQ(-1, indexShift(0)); + EXPECT_EQ(0, indexShift(1)); + + EXPECT_TRUE(getIndexShiftFromPositionShift(indexShift, Vector(-1.3, -2.65), resolution)); + EXPECT_EQ(1, indexShift(0)); + EXPECT_EQ(3, indexShift(1)); + + EXPECT_TRUE(getIndexShiftFromPositionShift(indexShift, Vector(-0.4, 0.09), 0.2)); + EXPECT_EQ(2, indexShift(0)); + EXPECT_EQ(0, indexShift(1)); +} + +TEST(getPositionShiftFromIndexShift, All) +{ + double resolution = 0.3; + Vector positionShift; + + EXPECT_TRUE(getPositionShiftFromIndexShift(positionShift, Index(0, 0), resolution)); + EXPECT_DOUBLE_EQ(0.0, positionShift.x()); + EXPECT_DOUBLE_EQ(0.0, positionShift.y()); + + EXPECT_TRUE(getPositionShiftFromIndexShift(positionShift, Index(1, -1), resolution)); + EXPECT_DOUBLE_EQ(-0.3, positionShift.x()); + EXPECT_DOUBLE_EQ(0.3, positionShift.y()); + + EXPECT_TRUE(getPositionShiftFromIndexShift(positionShift, Index(2, 1), resolution)); + EXPECT_DOUBLE_EQ(-0.6, positionShift.x()); + EXPECT_DOUBLE_EQ(-0.3, positionShift.y()); +} + +TEST(checkIfIndexInRange, All) +{ + Size bufferSize(10, 15); + EXPECT_TRUE(checkIfIndexInRange(Index(0, 0), bufferSize)); + EXPECT_TRUE(checkIfIndexInRange(Index(9, 14), bufferSize)); + EXPECT_FALSE(checkIfIndexInRange(Index(10, 5), bufferSize)); + EXPECT_FALSE(checkIfIndexInRange(Index(5, 300), bufferSize)); + EXPECT_FALSE(checkIfIndexInRange(Index(-1, 0), bufferSize)); + EXPECT_FALSE(checkIfIndexInRange(Index(0, -300), bufferSize)); +} + +TEST(boundIndexToRange, All) +{ + int bufferSize = 10; + + int index = 0; + boundIndexToRange(index, bufferSize); + EXPECT_EQ(0, index); + + index = 1; + boundIndexToRange(index, bufferSize); + EXPECT_EQ(1, index); + + index = -1; + boundIndexToRange(index, bufferSize); + EXPECT_EQ(0, index); + + index = 9; + boundIndexToRange(index, bufferSize); + EXPECT_EQ(9, index); + + index = 10; + boundIndexToRange(index, bufferSize); + EXPECT_EQ(9, index); + + index = 35; + boundIndexToRange(index, bufferSize); + EXPECT_EQ(9, index); + + index = -19; + boundIndexToRange(index, bufferSize); + EXPECT_EQ(0, index); +} + +TEST(wrapIndexToRange, All) +{ + int bufferSize = 10; + + int index = 0; + wrapIndexToRange(index, bufferSize); + EXPECT_EQ(0, index); + + index = 1; + wrapIndexToRange(index, bufferSize); + EXPECT_EQ(1, index); + + index = -1; + wrapIndexToRange(index, bufferSize); + EXPECT_EQ(9, index); + + index = 9; + wrapIndexToRange(index, bufferSize); + EXPECT_EQ(9, index); + + index = 10; + wrapIndexToRange(index, bufferSize); + EXPECT_EQ(0, index); + + index = 11; + wrapIndexToRange(index, bufferSize); + EXPECT_EQ(1, index); + + index = 35; + wrapIndexToRange(index, bufferSize); + EXPECT_EQ(5, index); + + index = -9; + wrapIndexToRange(index, bufferSize); + EXPECT_EQ(1, index); + + index = -19; + wrapIndexToRange(index, bufferSize); + EXPECT_EQ(1, index); +} + +TEST(boundPositionToRange, Simple) +{ + double epsilon = 11.0 * numeric_limits::epsilon(); + + Length mapLength(30.0, 10.0); + Position mapPosition(0.0, 0.0); + Position position; + + position << 0.0, 0.0; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_DOUBLE_EQ(0.0, position.x()); + EXPECT_DOUBLE_EQ(0.0, position.y()); + + position << 15.0, 5.0; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(15.0, position.x(), 15.0 * epsilon); + EXPECT_GE(15.0, position.x()); + EXPECT_NEAR(5.0, position.y(), 5.0 * epsilon); + EXPECT_GE(5.0, position.y()); + + position << -15.0, -5.0; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(-15.0, position.x(), 15.0 * epsilon); + EXPECT_LE(-15.0, position.x()); + EXPECT_NEAR(-5.0, position.y(), 5.0 * epsilon); + EXPECT_LE(-5.0, position.y()); + + position << 16.0, 6.0; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(15.0, position.x(), 16.0 * epsilon); + EXPECT_GE(15.0, position.x()); + EXPECT_NEAR(5.0, position.y(), 6.0 * epsilon); + EXPECT_GE(5.0, position.y()); + + position << -16.0, -6.0; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(-15.0, position.x(), 16.0 * epsilon); + EXPECT_LE(-15.0, position.x()); + EXPECT_NEAR(-5.0, position.y(), 6.0 * epsilon); + EXPECT_LE(-5.0, position.y()); + + position << 1e6, 1e6; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(15.0, position.x(), 1e6 * epsilon); + EXPECT_GE(15.0, position.x()); + EXPECT_NEAR(5.0, position.y(), 1e6 * epsilon); + EXPECT_GE(5.0, position.y()); + + position << -1e6, -1e6; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(-15.0, position.x(), 1e6 * epsilon); + EXPECT_LE(-15.0, position.x()); + EXPECT_NEAR(-5.0, position.y(), 1e6 * epsilon); + EXPECT_LE(-5.0, position.y()); +} + +TEST(boundPositionToRange, Position) +{ + double epsilon = 11.0 * numeric_limits::epsilon(); + + Length mapLength(30.0, 10.0); + Position mapPosition(1.0, 2.0); + Position position; + + position << 0.0, 0.0; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_DOUBLE_EQ(0.0, position.x()); + EXPECT_DOUBLE_EQ(0.0, position.y()); + + position << 16.0, 7.0; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(16.0, position.x(), 16.0 * epsilon); + EXPECT_GE(16.0, position.x()); + EXPECT_NEAR(7.0, position.y(), 7.0 * epsilon); + EXPECT_GE(7.0, position.y()); + + position << -14.0, -3.0; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(-14.0, position.x(), 14.0 * epsilon); + EXPECT_LE(-14.0, position.x()); + EXPECT_NEAR(-3.0, position.y(), 3.0 * epsilon); + EXPECT_LE(-3.0, position.y()); + + position << 17.0, 8.0; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(16.0, position.x(), 17.0 * epsilon); + EXPECT_GE(16.0, position.x()); + EXPECT_NEAR(7.0, position.y(), 8.0 * epsilon); + EXPECT_GE(7.0, position.y()); + + position << -15.0, -4.0; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(-14.0, position.x(), 15.0 * epsilon); + EXPECT_LE(-14.0, position.x()); + EXPECT_NEAR(-3.0, position.y(), 4.0 * epsilon); + EXPECT_LE(-3.0, position.y()); + + position << 1e6, 1e6; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(16.0, position.x(), 1e6 * epsilon); + EXPECT_GE(16.0, position.x()); + EXPECT_NEAR(7.0, position.y(), 1e6 * epsilon); + EXPECT_GE(7.0, position.y()); + + position << -1e6, -1e6; + boundPositionToRange(position, mapLength, mapPosition); + EXPECT_NEAR(-14.0, position.x(), 1e6 * epsilon); + EXPECT_LE(-14.0, position.x()); + EXPECT_NEAR(-3.0, position.y(), 1e6 * epsilon); + EXPECT_LE(-3.0, position.y()); +} + +TEST(getSubmapInformation, Simple) +{ + // Map + Length mapLength(5.0, 4.0); + Position mapPosition(0.0, 0.0); + double resolution = 1.0; + Size bufferSize(5, 4); + + // Requested submap + Position requestedSubmapPosition; + Position requestedSubmapLength; + + // The returned submap indices + Index submapTopLeftIndex; + Index submapSize; + Position submapPosition; + Length submapLength; + Index requestedIndexInSubmap; + + requestedSubmapPosition << 0.0, 0.5; + requestedSubmapLength << 0.9, 2.9; + EXPECT_TRUE(getSubmapInformation(submapTopLeftIndex, submapSize, submapPosition, submapLength, requestedIndexInSubmap, + requestedSubmapPosition, requestedSubmapLength, mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(2, submapTopLeftIndex(0)); + EXPECT_EQ(0, submapTopLeftIndex(1)); + EXPECT_EQ(1, submapSize(0)); + EXPECT_EQ(3, submapSize(1)); + EXPECT_DOUBLE_EQ(0.0, submapPosition.x()); + EXPECT_DOUBLE_EQ(0.5, submapPosition.y()); + EXPECT_DOUBLE_EQ(1.0, submapLength(0)); + EXPECT_DOUBLE_EQ(3.0, submapLength(1)); + EXPECT_EQ(0, requestedIndexInSubmap(0)); + EXPECT_EQ(1, requestedIndexInSubmap(1)); +} + +TEST(getSubmapInformation, Zero) +{ + // Map + Length mapLength(5.0, 4.0); + Position mapPosition(0.0, 0.0); + double resolution = 1.0; + Size bufferSize(5, 4); + + // Requested submap + Position requestedSubmapPosition; + Length requestedSubmapLength; + + // The returned submap indices + Index submapTopLeftIndex; + Index submapSize; + Position submapPosition; + Length submapLength; + Index requestedIndexInSubmap; + + requestedSubmapPosition << -1.0, -0.5; + requestedSubmapLength << 0.0, 0.0; + EXPECT_TRUE(getSubmapInformation(submapTopLeftIndex, submapSize, submapPosition, submapLength, requestedIndexInSubmap, + requestedSubmapPosition, requestedSubmapLength, + mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(3, submapTopLeftIndex(0)); + EXPECT_EQ(2, submapTopLeftIndex(1)); + EXPECT_EQ(1, submapSize(0)); + EXPECT_EQ(1, submapSize(1)); + EXPECT_DOUBLE_EQ(requestedSubmapPosition.x(), submapPosition.x()); + EXPECT_DOUBLE_EQ(requestedSubmapPosition.y(), submapPosition.y()); + EXPECT_DOUBLE_EQ(resolution, submapLength(0)); + EXPECT_DOUBLE_EQ(resolution, submapLength(1)); + EXPECT_EQ(0, requestedIndexInSubmap(0)); + EXPECT_EQ(0, requestedIndexInSubmap(1)); +} + +TEST(getSubmapInformation, ExceedingBoundaries) +{ + // Map + Length mapLength(5.0, 4.0); + Position mapPosition(0.0, 0.0); + double resolution = 1.0; + Size bufferSize(5, 4); + + // Requested submap + Position requestedSubmapPosition; + Length requestedSubmapLength; + + // The returned submap indices + Index submapTopLeftIndex; + Size submapSize; + Position submapPosition; + Length submapLength; + Index requestedIndexInSubmap; + + requestedSubmapPosition << 2.0, 1.5; + requestedSubmapLength << 2.9, 2.9; + EXPECT_TRUE(getSubmapInformation(submapTopLeftIndex, submapSize, submapPosition, submapLength, requestedIndexInSubmap, + requestedSubmapPosition, requestedSubmapLength, + mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(0, submapTopLeftIndex(0)); + EXPECT_EQ(0, submapTopLeftIndex(1)); + EXPECT_EQ(2, submapSize(0)); + EXPECT_EQ(2, submapSize(1)); + EXPECT_DOUBLE_EQ(1.5, submapPosition.x()); + EXPECT_DOUBLE_EQ(1.0, submapPosition.y()); + EXPECT_DOUBLE_EQ(2.0, submapLength(0)); + EXPECT_DOUBLE_EQ(2.0, submapLength(1)); + EXPECT_EQ(0, requestedIndexInSubmap(0)); + EXPECT_EQ(0, requestedIndexInSubmap(1)); + + requestedSubmapPosition << 0.0, 0.0; + requestedSubmapLength << 1e6, 1e6; + EXPECT_TRUE(getSubmapInformation(submapTopLeftIndex, submapSize, submapPosition, submapLength, requestedIndexInSubmap, + requestedSubmapPosition, requestedSubmapLength, + mapLength, mapPosition, resolution, bufferSize)); + EXPECT_EQ(0, submapTopLeftIndex(0)); + EXPECT_EQ(0, submapTopLeftIndex(1)); + EXPECT_EQ(bufferSize(0), submapSize(0)); + EXPECT_EQ(bufferSize(1), submapSize(1)); + EXPECT_DOUBLE_EQ(0.0, submapPosition.x()); + EXPECT_DOUBLE_EQ(0.0, submapPosition.y()); + EXPECT_DOUBLE_EQ(mapLength(0), submapLength(0)); + EXPECT_DOUBLE_EQ(mapLength(1), submapLength(1)); + EXPECT_EQ(2, requestedIndexInSubmap(0)); + EXPECT_LE(1, requestedIndexInSubmap(1)); + EXPECT_GE(2, requestedIndexInSubmap(1)); +} + +TEST(getSubmapInformation, CircularBuffer) +{ + // Map + Length mapLength(5.0, 4.0); + Position mapPosition(0.0, 0.0); + double resolution = 1.0; + Size bufferSize(5, 4); + Index bufferStartIndex(2, 1); + + // Requested submap + Position requestedSubmapPosition; + Length requestedSubmapLength; + + // The returned submap indices + Index submapTopLeftIndex; + Size submapSize; + Position submapPosition; + Length submapLength; + Index requestedIndexInSubmap; + + requestedSubmapPosition << 0.0, 0.5; + requestedSubmapLength << 0.9, 2.9; + EXPECT_TRUE(getSubmapInformation(submapTopLeftIndex, submapSize, submapPosition, submapLength, requestedIndexInSubmap, + requestedSubmapPosition, requestedSubmapLength, + mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_EQ(4, submapTopLeftIndex(0)); + EXPECT_EQ(1, submapTopLeftIndex(1)); + EXPECT_EQ(1, submapSize(0)); + EXPECT_EQ(3, submapSize(1)); + EXPECT_DOUBLE_EQ(0.0, submapPosition.x()); + EXPECT_DOUBLE_EQ(0.5, submapPosition.y()); + EXPECT_DOUBLE_EQ(1.0, submapLength(0)); + EXPECT_DOUBLE_EQ(3.0, submapLength(1)); + EXPECT_EQ(0, requestedIndexInSubmap(0)); + EXPECT_EQ(1, requestedIndexInSubmap(1)); + + requestedSubmapPosition << 2.0, 1.5; + requestedSubmapLength << 2.9, 2.9; + EXPECT_TRUE(getSubmapInformation(submapTopLeftIndex, submapSize, submapPosition, submapLength, requestedIndexInSubmap, + requestedSubmapPosition, requestedSubmapLength, + mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_EQ(2, submapTopLeftIndex(0)); + EXPECT_EQ(1, submapTopLeftIndex(1)); + EXPECT_EQ(2, submapSize(0)); + EXPECT_EQ(2, submapSize(1)); + EXPECT_DOUBLE_EQ(1.5, submapPosition.x()); + EXPECT_DOUBLE_EQ(1.0, submapPosition.y()); + EXPECT_DOUBLE_EQ(2.0, submapLength(0)); + EXPECT_DOUBLE_EQ(2.0, submapLength(1)); + EXPECT_EQ(0, requestedIndexInSubmap(0)); + EXPECT_EQ(0, requestedIndexInSubmap(1)); + + requestedSubmapPosition << 0.0, 0.0; + requestedSubmapLength << 1e6, 1e6; + EXPECT_TRUE(getSubmapInformation(submapTopLeftIndex, submapSize, submapPosition, submapLength, requestedIndexInSubmap, + requestedSubmapPosition, requestedSubmapLength, + mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_EQ(2, submapTopLeftIndex(0)); + EXPECT_EQ(1, submapTopLeftIndex(1)); + EXPECT_EQ(bufferSize(0), submapSize(0)); + EXPECT_EQ(bufferSize(1), submapSize(1)); + EXPECT_DOUBLE_EQ(0.0, submapPosition.x()); + EXPECT_DOUBLE_EQ(0.0, submapPosition.y()); + EXPECT_DOUBLE_EQ(mapLength(0), submapLength(0)); + EXPECT_DOUBLE_EQ(mapLength(1), submapLength(1)); + EXPECT_EQ(2, requestedIndexInSubmap(0)); + EXPECT_LE(1, requestedIndexInSubmap(1)); + EXPECT_GE(2, requestedIndexInSubmap(1)); +} + +TEST(getSubmapInformation, Debug1) +{ + // Map + Length mapLength(4.98, 4.98); + Position mapPosition(-4.98, -5.76); + double resolution = 0.06; + Size bufferSize(83, 83); + Index bufferStartIndex(0, 13); + + // Requested submap + Position requestedSubmapPosition(-7.44, -3.42); + Length requestedSubmapLength(0.12, 0.12); + + // The returned submap indices + Index submapTopLeftIndex; + Size submapSize; + Position submapPosition; + Length submapLength; + Index requestedIndexInSubmap; + + EXPECT_TRUE(getSubmapInformation(submapTopLeftIndex, submapSize, submapPosition, submapLength, requestedIndexInSubmap, + requestedSubmapPosition, requestedSubmapLength, + mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_EQ(2, submapSize(0)); + EXPECT_EQ(3, submapSize(1)); + EXPECT_DOUBLE_EQ(0.12, submapLength(0)); + EXPECT_DOUBLE_EQ(0.18, submapLength(1)); +} + +TEST(getSubmapInformation, Debug2) +{ + // Map + Length mapLength(4.98, 4.98); + Position mapPosition(2.46, -25.26); + double resolution = 0.06; + Size bufferSize(83, 83); + Index bufferStartIndex(42, 6); + + // Requested submap + Position requestedSubmapPosition(0.24, -26.82); + Length requestedSubmapLength(0.624614, 0.462276); + + // The returned submap indices + Index submapTopLeftIndex; + Size submapSize; + Position submapPosition; + Length submapLength; + Index requestedIndexInSubmap; + + EXPECT_TRUE(getSubmapInformation(submapTopLeftIndex, submapSize, submapPosition, submapLength, requestedIndexInSubmap, + requestedSubmapPosition, requestedSubmapLength, + mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)); + EXPECT_LT(0, submapSize(0)); + EXPECT_LT(0, submapSize(1)); + EXPECT_LT(0.0, submapLength(0)); + EXPECT_LT(0.0, submapLength(1)); +} + +TEST(getBufferRegionsForSubmap, Trivial) +{ + Size bufferSize(5, 4); + Index submapIndex(0, 0); + Size submapSize(0, 0); + std::vector regions; + + EXPECT_TRUE(getBufferRegionsForSubmap(regions, submapIndex, submapSize, bufferSize)); + EXPECT_EQ(1, regions.size()); + EXPECT_EQ(BufferRegion::Quadrant::TopLeft, regions[0].getQuadrant()); + EXPECT_EQ(0, regions[0].getStartIndex()[0]); + EXPECT_EQ(0, regions[0].getStartIndex()[1]); + EXPECT_EQ(0, regions[0].getSize()[0]); + EXPECT_EQ(0, regions[0].getSize()[1]); + + submapSize << 0, 7; + EXPECT_FALSE(getBufferRegionsForSubmap(regions, submapIndex, submapSize, bufferSize)); + + submapSize << 6, 7; + EXPECT_FALSE(getBufferRegionsForSubmap(regions, submapIndex, submapSize, bufferSize)); +} + +TEST(getBufferRegionsForSubmap, Simple) +{ + Size bufferSize(5, 4); + Index submapIndex(1, 2); + Size submapSize(3, 2); + std::vector regions; + + EXPECT_TRUE(getBufferRegionsForSubmap(regions, submapIndex, submapSize, bufferSize)); + EXPECT_EQ(1, regions.size()); + EXPECT_EQ(BufferRegion::Quadrant::TopLeft, regions[0].getQuadrant()); + EXPECT_EQ(1, regions[0].getStartIndex()[0]); + EXPECT_EQ(2, regions[0].getStartIndex()[1]); + EXPECT_EQ(3, regions[0].getSize()[0]); + EXPECT_EQ(2, regions[0].getSize()[1]); +} + +TEST(getBufferRegionsForSubmap, CircularBuffer) +{ + Size bufferSize(5, 4); + Index submapIndex; + Size submapSize; + Index bufferStartIndex(3, 1); + std::vector regions; + + submapIndex << 3, 1; + submapSize << 2, 3; + EXPECT_TRUE(getBufferRegionsForSubmap(regions, submapIndex, submapSize, bufferSize, bufferStartIndex)); + EXPECT_EQ(1, regions.size()); + EXPECT_EQ(BufferRegion::Quadrant::TopLeft, regions[0].getQuadrant()); + EXPECT_EQ(3, regions[0].getStartIndex()[0]); + EXPECT_EQ(1, regions[0].getStartIndex()[1]); + EXPECT_EQ(2, regions[0].getSize()[0]); + EXPECT_EQ(3, regions[0].getSize()[1]); + + submapIndex << 4, 1; + submapSize << 2, 3; + EXPECT_TRUE(getBufferRegionsForSubmap(regions, submapIndex, submapSize, bufferSize, bufferStartIndex)); + EXPECT_EQ(2, regions.size()); + EXPECT_EQ(BufferRegion::Quadrant::TopLeft, regions[0].getQuadrant()); + EXPECT_EQ(4, regions[0].getStartIndex()[0]); + EXPECT_EQ(1, regions[0].getStartIndex()[1]); + EXPECT_EQ(1, regions[0].getSize()[0]); + EXPECT_EQ(3, regions[0].getSize()[1]); + EXPECT_EQ(BufferRegion::Quadrant::BottomLeft, regions[1].getQuadrant()); + EXPECT_EQ(0, regions[1].getStartIndex()[0]); + EXPECT_EQ(1, regions[1].getStartIndex()[1]); + EXPECT_EQ(1, regions[1].getSize()[0]); + EXPECT_EQ(3, regions[1].getSize()[1]); + + submapIndex << 1, 0; + submapSize << 2, 1; + EXPECT_TRUE(getBufferRegionsForSubmap(regions, submapIndex, submapSize, bufferSize, bufferStartIndex)); + EXPECT_EQ(1, regions.size()); + EXPECT_EQ(BufferRegion::Quadrant::BottomRight, regions[0].getQuadrant()); + EXPECT_EQ(1, regions[0].getStartIndex()[0]); + EXPECT_EQ(0, regions[0].getStartIndex()[1]); + EXPECT_EQ(2, regions[0].getSize()[0]); + EXPECT_EQ(1, regions[0].getSize()[1]); + + submapIndex << 3, 1; + submapSize << 5, 4; + EXPECT_TRUE(getBufferRegionsForSubmap(regions, submapIndex, submapSize, bufferSize, bufferStartIndex));\ + EXPECT_EQ(4, regions.size()); + EXPECT_EQ(BufferRegion::Quadrant::TopLeft, regions[0].getQuadrant()); + EXPECT_EQ(3, regions[0].getStartIndex()[0]); + EXPECT_EQ(1, regions[0].getStartIndex()[1]); + EXPECT_EQ(2, regions[0].getSize()[0]); + EXPECT_EQ(3, regions[0].getSize()[1]); + EXPECT_EQ(BufferRegion::Quadrant::TopRight, regions[1].getQuadrant()); + EXPECT_EQ(3, regions[1].getStartIndex()[0]); + EXPECT_EQ(0, regions[1].getStartIndex()[1]); + EXPECT_EQ(2, regions[1].getSize()[0]); + EXPECT_EQ(1, regions[1].getSize()[1]); + EXPECT_EQ(BufferRegion::Quadrant::BottomLeft, regions[2].getQuadrant()); + EXPECT_EQ(0, regions[2].getStartIndex()[0]); + EXPECT_EQ(1, regions[2].getStartIndex()[1]); + EXPECT_EQ(3, regions[2].getSize()[0]); + EXPECT_EQ(3, regions[2].getSize()[1]); + EXPECT_EQ(BufferRegion::Quadrant::BottomRight, regions[3].getQuadrant()); + EXPECT_EQ(0, regions[3].getStartIndex()[0]); + EXPECT_EQ(0, regions[3].getStartIndex()[1]); + EXPECT_EQ(3, regions[3].getSize()[0]); + EXPECT_EQ(1, regions[3].getSize()[1]); +} + +TEST(checkIncrementIndex, Simple) +{ + Index index(0, 0); + Size bufferSize(4, 3); + + EXPECT_TRUE(incrementIndex(index, bufferSize)); + EXPECT_EQ(0, index[0]); + EXPECT_EQ(1, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize)); + EXPECT_EQ(0, index[0]); + EXPECT_EQ(2, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize)); + EXPECT_EQ(1, index[0]); + EXPECT_EQ(0, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize)); + EXPECT_EQ(1, index[0]); + EXPECT_EQ(1, index[1]); + + for (int i = 0; i < 6; i++) { + EXPECT_TRUE(incrementIndex(index, bufferSize)); + } + EXPECT_EQ(3, index[0]); + EXPECT_EQ(1, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize)); + EXPECT_EQ(3, index[0]); + EXPECT_EQ(2, index[1]); + + EXPECT_FALSE(incrementIndex(index, bufferSize)); + EXPECT_EQ(index[0], index[0]); + EXPECT_EQ(index[1], index[1]); +} + +TEST(checkIncrementIndex, CircularBuffer) +{ + Size bufferSize(4, 3); + Index bufferStartIndex(2, 1); + Index index(bufferStartIndex); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(2, index[0]); + EXPECT_EQ(2, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(2, index[0]); + EXPECT_EQ(0, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(3, index[0]); + EXPECT_EQ(1, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(3, index[0]); + EXPECT_EQ(2, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(3, index[0]); + EXPECT_EQ(0, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(0, index[0]); + EXPECT_EQ(1, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(0, index[0]); + EXPECT_EQ(2, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(0, index[0]); + EXPECT_EQ(0, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(1, index[0]); + EXPECT_EQ(1, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(1, index[0]); + EXPECT_EQ(2, index[1]); + + EXPECT_TRUE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(1, index[0]); + EXPECT_EQ(0, index[1]); + + EXPECT_FALSE(incrementIndex(index, bufferSize, bufferStartIndex)); + EXPECT_EQ(index[0], index[0]); + EXPECT_EQ(index[1], index[1]); +} + +TEST(checkIncrementIndexForSubmap, Simple) +{ + Index submapIndex(0, 0); + Index index; + Index submapTopLeftIndex(3, 1); + Size submapBufferSize(2, 4); + Size bufferSize(8, 5); + + EXPECT_TRUE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize)); + EXPECT_EQ(0, submapIndex[0]); + EXPECT_EQ(1, submapIndex[1]); + EXPECT_EQ(3, index[0]); + EXPECT_EQ(2, index[1]); + + EXPECT_TRUE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize)); + EXPECT_EQ(0, submapIndex[0]); + EXPECT_EQ(2, submapIndex[1]); + EXPECT_EQ(3, index[0]); + EXPECT_EQ(3, index[1]); + + EXPECT_TRUE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize)); + EXPECT_EQ(0, submapIndex[0]); + EXPECT_EQ(3, submapIndex[1]); + EXPECT_EQ(3, index[0]); + EXPECT_EQ(4, index[1]); + + EXPECT_TRUE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize)); + EXPECT_EQ(1, submapIndex[0]); + EXPECT_EQ(0, submapIndex[1]); + EXPECT_EQ(4, index[0]); + EXPECT_EQ(1, index[1]); + + submapIndex << 1, 2; + EXPECT_TRUE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize)); + EXPECT_EQ(1, submapIndex[0]); + EXPECT_EQ(3, submapIndex[1]); + EXPECT_EQ(4, index[0]); + EXPECT_EQ(4, index[1]); + + EXPECT_FALSE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize)); + + submapIndex << 2, 0; + EXPECT_FALSE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize)); +} + +TEST(checkIncrementIndexForSubmap, CircularBuffer) +{ + Index submapIndex(0, 0); + Index index; + Index submapTopLeftIndex(6, 3); + Size submapBufferSize(2, 4); + Size bufferSize(8, 5); + Index bufferStartIndex(3, 2); + + EXPECT_TRUE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize, bufferStartIndex)); + EXPECT_EQ(0, submapIndex[0]); + EXPECT_EQ(1, submapIndex[1]); + EXPECT_EQ(6, index[0]); + EXPECT_EQ(4, index[1]); + + EXPECT_TRUE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize, bufferStartIndex)); + EXPECT_EQ(0, submapIndex[0]); + EXPECT_EQ(2, submapIndex[1]); + EXPECT_EQ(6, index[0]); + EXPECT_EQ(0, index[1]); + + EXPECT_TRUE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize, bufferStartIndex)); + EXPECT_EQ(0, submapIndex[0]); + EXPECT_EQ(3, submapIndex[1]); + EXPECT_EQ(6, index[0]); + EXPECT_EQ(1, index[1]); + + EXPECT_TRUE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize, bufferStartIndex)); + EXPECT_EQ(1, submapIndex[0]); + EXPECT_EQ(0, submapIndex[1]); + EXPECT_EQ(7, index[0]); + EXPECT_EQ(3, index[1]); + + submapIndex << 1, 2; + EXPECT_TRUE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize, bufferStartIndex)); + EXPECT_EQ(1, submapIndex[0]); + EXPECT_EQ(3, submapIndex[1]); + EXPECT_EQ(7, index[0]); + EXPECT_EQ(1, index[1]); + + EXPECT_FALSE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize, bufferStartIndex)); + + submapIndex << 2, 0; + EXPECT_FALSE(incrementIndexForSubmap(submapIndex, index, submapTopLeftIndex, submapBufferSize, bufferSize, bufferStartIndex)); +} + +TEST(getIndexFromLinearIndex, Simple) +{ + EXPECT_TRUE((Index(0, 0) == getIndexFromLinearIndex(0, Size(8, 5), false)).all()); + EXPECT_TRUE((Index(1, 0) == getIndexFromLinearIndex(1, Size(8, 5), false)).all()); + EXPECT_TRUE((Index(0, 1) == getIndexFromLinearIndex(1, Size(8, 5), true)).all()); + EXPECT_TRUE((Index(2, 0) == getIndexFromLinearIndex(2, Size(8, 5), false)).all()); + EXPECT_TRUE((Index(0, 1) == getIndexFromLinearIndex(8, Size(8, 5), false)).all()); + EXPECT_TRUE((Index(7, 4) == getIndexFromLinearIndex(39, Size(8, 5), false)).all()); +} + +} // namespace grid_map \ No newline at end of file diff --git a/test/GridMapTest.cpp b/test/GridMapTest.cpp new file mode 100644 index 0000000..64b15f8 --- /dev/null +++ b/test/GridMapTest.cpp @@ -0,0 +1,496 @@ +/* + * GridMapTest.cpp + * + * Created on: Aug 26, 2015 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/GridMap.hpp" + +// gtest +#include + +namespace grid_map { + +TEST(GridMap, CopyConstructor) { + GridMap map({"layer_a", "layer_b"}); + map.setGeometry(Length(1.0, 2.0), 0.1, Position(0.1, 0.2)); + map["layer_a"].setConstant(1.0); + map["layer_b"].setConstant(2.0); + GridMap mapCopy(map); + EXPECT_EQ(map.getSize()[0], mapCopy.getSize()[0]); + EXPECT_EQ(map.getSize()[1], mapCopy.getSize()[1]); + EXPECT_EQ(map.getLength().x(), mapCopy.getLength().x()); + EXPECT_EQ(map.getLength().y(), mapCopy.getLength().y()); + EXPECT_EQ(map.getPosition().x(), mapCopy.getPosition().x()); + EXPECT_EQ(map.getPosition().y(), mapCopy.getPosition().y()); + EXPECT_EQ(map.getLayers().size(), mapCopy.getLayers().size()); + EXPECT_EQ(map["layer_a"](0, 0), mapCopy["layer_a"](0, 0)); + EXPECT_EQ(map["layer_b"](0, 0), mapCopy["layer_b"](0, 0)); +} + +TEST(GridMap, CopyAssign) +{ + GridMap map({"layer_a", "layer_b"}); + map.setGeometry(Length(1.0, 2.0), 0.1, Position(0.1, 0.2)); + map["layer_a"].setConstant(1.0); + map["layer_b"].setConstant(2.0); + GridMap mapCopy; + mapCopy = map; + EXPECT_EQ(map.getSize()[0], mapCopy.getSize()[0]); + EXPECT_EQ(map.getSize()[1], mapCopy.getSize()[1]); + EXPECT_EQ(map.getLength().x(), mapCopy.getLength().x()); + EXPECT_EQ(map.getLength().y(), mapCopy.getLength().y()); + EXPECT_EQ(map.getPosition().x(), mapCopy.getPosition().x()); + EXPECT_EQ(map.getPosition().y(), mapCopy.getPosition().y()); + EXPECT_EQ(map.getLayers().size(), mapCopy.getLayers().size()); + EXPECT_EQ(map["layer_a"](0, 0), mapCopy["layer_a"](0, 0)); + EXPECT_EQ(map["layer_b"](0, 0), mapCopy["layer_b"](0, 0)); +} + +TEST(GridMap, Move) +{ + GridMap map; + map.setGeometry(Length(8.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + map.add("layer", 0.0); + map.setBasicLayers(map.getLayers()); + std::vector regions; + map.move(Position(-3.0, -2.0), regions); + Index startIndex = map.getStartIndex(); + + EXPECT_EQ(3, startIndex(0)); + EXPECT_EQ(2, startIndex(1)); + + Eigen::Matrix isValidExpected; + isValidExpected << false, false, false, false, false, // clang-format off + false, false, false, false, false, + false, false, false, false, false, + false, false, true, true, true, + false, false, true, true, true, + false, false, true, true, true, + false, false, true, true, true, + false, false, true, true, true; // clang-format on + for(int row{0}; row < 8; row++){ + for(int col{0}; col < 5; col++){ + EXPECT_EQ(map.isValid(Index(row, col)), isValidExpected(row, col)) << "Value of map.isValid at ["< stringVector; + stringVector.emplace_back("nan"); + map1.addDataFrom(map2, true, false, false, stringVector); + Index index; + map1.getIndex(Position(-2, -2), index); + + EXPECT_FALSE(map1.exists("two")); + EXPECT_TRUE(map1.isInside(Position(4.0, 4.0))); + EXPECT_DOUBLE_EQ(8.0, map1.getLength().x()); + EXPECT_DOUBLE_EQ(8.0, map1.getLength().y()); + EXPECT_DOUBLE_EQ(1.0, map1.getPosition().x()); + EXPECT_DOUBLE_EQ(1.0, map1.getPosition().y()); + EXPECT_FALSE(map1.isValid(index, "nan")); + EXPECT_DOUBLE_EQ(1.0, map1.atPosition("one", Position(0.0, 0.0))); + EXPECT_DOUBLE_EQ(1.0, map1.atPosition("nan", Position(3.0, 3.0))); +} + +TEST(AddDataFrom, CopyData) +{ + GridMap map1; + GridMap map2; + map1.setGeometry(Length(5.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(5, 5) + map1.add("zero", 0.0); + map1.add("one"); + map1.setBasicLayers(map1.getLayers()); + + map2.setGeometry(Length(3.1, 3.1), 1.0, Position(2.0, 2.0)); + map2.add("one", 1.0); + map2.add("two", 2.0); + map2.setBasicLayers(map1.getLayers()); + + map1.addDataFrom(map2, false, false, true); + Index index; + map1.getIndex(Position(-2, -2), index); + + EXPECT_TRUE(map1.exists("two")); + EXPECT_FALSE(map1.isInside(Position(3.0, 3.0))); + EXPECT_DOUBLE_EQ(5.0, map1.getLength().x()); + EXPECT_DOUBLE_EQ(5.0, map1.getLength().y()); + EXPECT_DOUBLE_EQ(0.0, map1.getPosition().x()); + EXPECT_DOUBLE_EQ(0.0, map1.getPosition().y()); + EXPECT_DOUBLE_EQ(1.0, map1.atPosition("one", Position(2, 2))); + EXPECT_FALSE(map1.isValid(index, "one")); + EXPECT_DOUBLE_EQ(0.0, map1.atPosition("zero", Position(0.0, 0.0))); +} + +TEST(ValueAtPosition, NearestNeighbor) +{ + GridMap map( { "types" }); + map.setGeometry(Length(3.0, 3.0), 1.0, Position(0.0, 0.0)); + + map.at("types", Index(0,0)) = 0.5; + map.at("types", Index(0,1)) = 3.8; + map.at("types", Index(0,2)) = 2.0; + map.at("types", Index(1,0)) = 2.1; + map.at("types", Index(1,1)) = 1.0; + map.at("types", Index(1,2)) = 2.0; + map.at("types", Index(2,0)) = 1.0; + map.at("types", Index(2,1)) = 2.0; + map.at("types", Index(2,2)) = 2.0; + + double value = map.atPosition("types", Position(1.35,-0.4)); + EXPECT_DOUBLE_EQ((float)3.8, value); + + value = map.atPosition("types", Position(-0.3,0.0)); + EXPECT_DOUBLE_EQ(1.0, value); +} + +TEST(ValueAtPosition, LinearInterpolated) +{ + GridMap map( { "types" }); + map.setGeometry(Length(3.0, 3.0), 1.0, Position(0.0, 0.0)); + + map.at("types", Index(0,0)) = 0.5; + map.at("types", Index(0,1)) = 3.8; + map.at("types", Index(0,2)) = 2.0; + map.at("types", Index(1,0)) = 2.1; + map.at("types", Index(1,1)) = 1.0; + map.at("types", Index(1,2)) = 2.0; + map.at("types", Index(2,0)) = 1.0; + map.at("types", Index(2,1)) = 2.0; + map.at("types", Index(2,2)) = 2.0; + + // Close to the border -> reverting to INTER_NEAREST. + double value = map.atPosition("types", Position(-0.5,-1.2), InterpolationMethods::INTER_LINEAR); + EXPECT_DOUBLE_EQ(2.0, value); + // In between 1.0 and 2.0 field. + value = map.atPosition("types", Position(-0.5,0.0), InterpolationMethods::INTER_LINEAR); + EXPECT_DOUBLE_EQ(1.5, value); + // Calculated "by Hand". + value = map.atPosition("types", Position(0.69,0.38), InterpolationMethods::INTER_LINEAR); + EXPECT_NEAR(2.1963200, value, 0.0000001); +} + +} // namespace grid_map \ No newline at end of file diff --git a/test/LineIteratorTest.cpp b/test/LineIteratorTest.cpp new file mode 100644 index 0000000..2086fc1 --- /dev/null +++ b/test/LineIteratorTest.cpp @@ -0,0 +1,178 @@ +/* + * LineIteratorTest.cpp + * + * Created on: Sep 14, 2016 + * Author: Dominic Jud + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/LineIterator.hpp" +#include "grid_map_core/GridMap.hpp" + +// gtest +#include + +namespace grid_map { + +TEST(LineIterator, StartOutsideMap) { + GridMap map( { "types" }); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); + + EXPECT_NO_THROW(LineIterator iterator(map, Position(2.0, 2.0), Position(0.0, 0.0))); + LineIterator iterator(map, Position(2.0, 2.0), Position(0.0, 0.0)); + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(2, (*iterator)(0)); + EXPECT_EQ(0, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(3, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(4, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} + +TEST(LineIterator, EndOutsideMap) +{ + GridMap map( { "types" }); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); + + EXPECT_NO_THROW(LineIterator iterator(map, Position(0.0, 0.0), Position(9.0, 6.0))); + LineIterator iterator(map, Position(0.0, 0.0), Position(9.0, 6.0)); + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(4, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(3, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(2, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} + +TEST(LineIterator, StartAndEndOutsideMap) +{ + GridMap map( { "types" }); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); + + EXPECT_NO_THROW(LineIterator iterator(map, Position(-7.0, -9.0), Position(8.0, 8.0))); + LineIterator iterator(map, Position(-7.0, -9.0), Position(8.0, 8.0)); + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(5, (*iterator)(0)); + EXPECT_EQ(4, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(4, (*iterator)(0)); + EXPECT_EQ(3, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(3, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + ++iterator; + ++iterator; + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} + +TEST(LineIterator, StartAndEndOutsideMapWithoutIntersectingMap) +{ + GridMap map( { "types" }); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); + + EXPECT_THROW(LineIterator iterator(map, Position(-8.0, 8.0), Position(8.0, 8.0)), std::invalid_argument); +} + +TEST(LineIterator, MovedMap) +{ + GridMap map( { "types" }); + map.setGeometry(Length(7.0, 5.0), 1.0, Position(0.0, 0.0)); + map.move(Position(2.0, 2.0)); + + EXPECT_NO_THROW(LineIterator iterator(map, Position(0.0, 0.0), Position(2.0, 2.0))); + LineIterator iterator(map, Position(0.0, 0.0), Position(2.0, 2.0)); + Position point; + + EXPECT_FALSE(iterator.isPastEnd()); + map.getPosition(*iterator, point); + EXPECT_EQ(0, point.x()); + EXPECT_EQ(0, point.y()); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + map.getPosition(*iterator, point); + EXPECT_EQ(1, point.x()); + EXPECT_EQ(1, point.y()); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + map.getPosition(*iterator, point); + EXPECT_EQ(2, point.x()); + EXPECT_EQ(2, point.y()); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} + +TEST(LineIterator, StartAndEndOutsideMovedMap) +{ + GridMap map( { "types" }); + map.setGeometry(Length(7.0, 5.0), 1.0, Position(0.0, 0.0)); + map.move(Position(2.0, 2.0)); + + EXPECT_NO_THROW(LineIterator iterator(map, Position(0.0, 0.0), Position(8.0, 8.0))); + LineIterator iterator(map, Position(0.0, 0.0), Position(8.0, 8.0)); + Position point; + + EXPECT_FALSE(iterator.isPastEnd()); + map.getPosition(*iterator, point); + EXPECT_EQ(0, point.x()); + EXPECT_EQ(0, point.y()); + + ++iterator; + map.getPosition(*iterator, point); + EXPECT_EQ(1, point.x()); + EXPECT_EQ(1, point.y()); + // + ++iterator; + map.getPosition(*iterator, point); + EXPECT_EQ(2, point.x()); + EXPECT_EQ(2, point.y()); + // + ++iterator; + map.getPosition(*iterator, point); + EXPECT_EQ(3, point.x()); + EXPECT_EQ(3, point.y()); + + ++iterator; + map.getPosition(*iterator, point); + EXPECT_EQ(4, point.x()); + EXPECT_EQ(4, point.y()); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} + +} // namespace grid_map \ No newline at end of file diff --git a/test/PolygonIteratorTest.cpp b/test/PolygonIteratorTest.cpp new file mode 100644 index 0000000..ef73ae6 --- /dev/null +++ b/test/PolygonIteratorTest.cpp @@ -0,0 +1,196 @@ +/* + * PolygonIteratorTest.cpp + * + * Created on: Sep 19, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/iterators/PolygonIterator.hpp" +#include "grid_map_core/GridMap.hpp" +#include "grid_map_core/Polygon.hpp" + +// gtest +#include + +// Vector +#include + +using grid_map::GridMap; +using grid_map::Length; +using grid_map::Polygon; +using grid_map::PolygonIterator; +using grid_map::Position; + +TEST(PolygonIterator, FullCover) { + std::vector types; + types.emplace_back("type"); + GridMap map(types); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + + Polygon polygon; + polygon.addVertex(Position(-100.0, 100.0)); + polygon.addVertex(Position(100.0, 100.0)); + polygon.addVertex(Position(100.0, -100.0)); + polygon.addVertex(Position(-100.0, -100.0)); + + PolygonIterator iterator(map, polygon); + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(0, (*iterator)(0)); + EXPECT_EQ(0, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(0, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(0, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + for (int i = 0; i < 37; ++i) { + ++iterator; + } + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(7, (*iterator)(0)); + EXPECT_EQ(4, (*iterator)(1)); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} + +TEST(PolygonIterator, Outside) +{ + GridMap map({"types"}); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + + Polygon polygon; + polygon.addVertex(Position(99.0, 101.0)); + polygon.addVertex(Position(101.0, 101.0)); + polygon.addVertex(Position(101.0, 99.0)); + polygon.addVertex(Position(99.0, 99.0)); + + PolygonIterator iterator(map, polygon); + + EXPECT_TRUE(iterator.isPastEnd()); +} + +TEST(PolygonIterator, Square) +{ + GridMap map({"types"}); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + + Polygon polygon; + polygon.addVertex(Position(-1.0, 1.5)); + polygon.addVertex(Position(1.0, 1.5)); + polygon.addVertex(Position(1.0, -1.5)); + polygon.addVertex(Position(-1.0, -1.5)); + + PolygonIterator iterator(map, polygon); + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(3, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(3, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(3, (*iterator)(0)); + EXPECT_EQ(3, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(4, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(4, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(4, (*iterator)(0)); + EXPECT_EQ(3, (*iterator)(1)); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} + +TEST(PolygonIterator, TopLeftTriangle) +{ + GridMap map({"types"}); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + + Polygon polygon; + polygon.addVertex(Position(-40.1, 20.6)); + polygon.addVertex(Position(40.1, 20.4)); + polygon.addVertex(Position(-40.1, -20.6)); + + PolygonIterator iterator(map, polygon); + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(0, (*iterator)(0)); + EXPECT_EQ(0, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(1, (*iterator)(0)); + EXPECT_EQ(0, (*iterator)(1)); + + // TODO Extend. +} + +TEST(PolygonIterator, MoveMap) +{ + GridMap map({"layer"}); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + map.move(Position(2.0, 0.0)); + + Polygon polygon; + polygon.addVertex(Position(6.1, 1.6)); + polygon.addVertex(Position(0.9, 1.6)); + polygon.addVertex(Position(0.9, -1.6)); + polygon.addVertex(Position(6.1, -1.6)); + PolygonIterator iterator(map, polygon); + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(6, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(6, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + + for (int i = 0; i < 4; ++i) { + ++iterator; + } + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(7, (*iterator)(0)); + EXPECT_EQ(3, (*iterator)(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(0, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + + for (int i = 0; i < 8; ++i) { + ++iterator; + } + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(2, (*iterator)(0)); + EXPECT_EQ(3, (*iterator)(1)); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} diff --git a/test/PolygonTest.cpp b/test/PolygonTest.cpp new file mode 100644 index 0000000..0974a05 --- /dev/null +++ b/test/PolygonTest.cpp @@ -0,0 +1,268 @@ +/* + * PolygonTest.cpp + * + * Created on: Mar 24, 2015 + * Author: Martin Wermelinger, Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/Polygon.hpp" + +// gtest +#include + +// Eigen +#include + +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::VectorXd; + +using grid_map::Length; +using grid_map::Polygon; +using grid_map::Position; + +TEST(Polygon, getCentroidTriangle) +{ + Polygon triangle; + triangle.addVertex(Vector2d(0.0, 0.0)); + triangle.addVertex(Vector2d(1.0, 0.0)); + triangle.addVertex(Vector2d(0.5, 1.0)); + + Position expectedCentroid; + expectedCentroid.x() = 1.0 / 3.0 * (1.0 + 0.5); + expectedCentroid.y() = 1.0 / 3.0; + Position centroid = triangle.getCentroid(); + EXPECT_DOUBLE_EQ(expectedCentroid.x(), centroid.x()); + EXPECT_DOUBLE_EQ(expectedCentroid.y(), centroid.y()); +} + +TEST(Polygon, getCentroidRectangle) +{ + Polygon rectangle; + rectangle.addVertex(Vector2d(-2.0, -1.0)); + rectangle.addVertex(Vector2d(-2.0, 2.0)); + rectangle.addVertex(Vector2d(1.0, 2.0)); + rectangle.addVertex(Vector2d(1.0, -1.0)); + + Position expectedCentroid(-0.5, 0.5); + Position centroid = rectangle.getCentroid(); + EXPECT_DOUBLE_EQ(expectedCentroid.x(), centroid.x()); + EXPECT_DOUBLE_EQ(expectedCentroid.y(), centroid.y()); +} + +TEST(Polygon, getBoundingBox) +{ + Polygon triangle; + triangle.addVertex(Vector2d(0.0, 0.0)); + triangle.addVertex(Vector2d(0.5, -1.2)); + triangle.addVertex(Vector2d(1.0, 0.0)); + + Position expectedCenter(0.5, -0.6); + Length expectedLength(1.0, 1.2); + Position center; + Length length; + triangle.getBoundingBox(center, length); + + EXPECT_DOUBLE_EQ(expectedCenter.x(), center.x()); + EXPECT_DOUBLE_EQ(expectedCenter.y(), center.y()); + EXPECT_DOUBLE_EQ(expectedLength.x(), length.x()); + EXPECT_DOUBLE_EQ(expectedLength.y(), length.y()); +} + +TEST(Polygon, convexHullPoints) +{ + // Test that points which already create a convex shape (square) can be used to create a convex polygon. + std::vector points1; + points1.emplace_back(0.0, 0.0); + points1.emplace_back(1.0, 0.0); + points1.emplace_back(1.0, 1.0); + points1.emplace_back(0.0, 1.0); + Polygon polygon1 = Polygon::monotoneChainConvexHullOfPoints(points1); + EXPECT_EQ(4, polygon1.nVertices()); + EXPECT_TRUE(polygon1.isInside(Vector2d(0.5, 0.5))); + EXPECT_FALSE(polygon1.isInside(Vector2d(-0.01, 0.5))); + + // Test that a random set of points can be used to create a convex polygon. + std::vector points2; + points2.emplace_back(0.0, 0.0); + points2.emplace_back(1.0, 0.0); + points2.emplace_back(2.0, 1.0); + points2.emplace_back(1.0, 2.0); + points2.emplace_back(-1.0, 2.0); + points2.emplace_back(-1.0, -2.0); + points2.emplace_back(0.0, 1.0); + points2.emplace_back(1.0, 1.0); + Polygon polygon2 = Polygon::monotoneChainConvexHullOfPoints(points2); + EXPECT_EQ(4, polygon2.nVertices()); + EXPECT_TRUE(polygon2.isInside(Vector2d(0.5, 0.5))); + EXPECT_TRUE(polygon2.isInside(Vector2d(0.0, 1.0))); + EXPECT_TRUE(polygon2.isInside(Vector2d(-0.5, -0.5))); + EXPECT_FALSE(polygon2.isInside(Vector2d(2.0, 0.0))); + EXPECT_FALSE(polygon2.isInside(Vector2d(-0.5, -2))); + EXPECT_FALSE(polygon2.isInside(Vector2d(1.75, 1.75))); +} + +TEST(Polygon, convexHullPolygon) +{ + Polygon polygon1; + polygon1.addVertex(Vector2d(0.0, 0.0)); + polygon1.addVertex(Vector2d(1.0, 1.0)); + polygon1.addVertex(Vector2d(0.0, 1.0)); + polygon1.addVertex(Vector2d(1.0, 0.0)); + + Polygon polygon2; + polygon2.addVertex(Vector2d(0.5, 0.5)); + polygon2.addVertex(Vector2d(0.5, 1.5)); + polygon2.addVertex(Vector2d(1.5, 0.5)); + polygon2.addVertex(Vector2d(1.5, 1.5)); + + Polygon hull = Polygon::convexHull(polygon1, polygon2); + + EXPECT_EQ(6, hull.nVertices()); + EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.5))); + EXPECT_FALSE(hull.isInside(Vector2d(0.01, 1.49))); +} + +TEST(Polygon, convexHullCircles) +{ + Position center1(0.0, 0.0); + Position center2(1.0, 0.0); + double radius = 0.5; + const int nVertices = 15; + + Polygon hull = Polygon::convexHullOfTwoCircles(center1, center2, radius); + EXPECT_EQ(20, hull.nVertices()); + EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0))); + EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.0))); + EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.4))); + EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.6))); + EXPECT_FALSE(hull.isInside(Vector2d(1.5, 0.2))); + + hull = Polygon::convexHullOfTwoCircles(center1, center2, radius, nVertices); + EXPECT_EQ(nVertices + 1, hull.nVertices()); + EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0))); + EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.0))); + EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.4))); + EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.6))); + EXPECT_FALSE(hull.isInside(Vector2d(1.5, 0.2))); + + hull = Polygon::convexHullOfTwoCircles(center1, center1, radius); + EXPECT_EQ(20, hull.nVertices()); + EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0))); + EXPECT_TRUE(hull.isInside(Vector2d(0.25, 0.0))); + EXPECT_TRUE(hull.isInside(Vector2d(0.0, 0.25))); + EXPECT_TRUE(hull.isInside(Vector2d(0.0, -0.25))); + EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.5))); + EXPECT_FALSE(hull.isInside(Vector2d(0.6, 0.0))); + EXPECT_FALSE(hull.isInside(Vector2d(-0.6, 0.0))); + EXPECT_FALSE(hull.isInside(Vector2d(0.0, 0.6))); + EXPECT_FALSE(hull.isInside(Vector2d(0.0, -0.6))); + + hull = Polygon::convexHullOfTwoCircles(center1, center1, radius, nVertices); + EXPECT_EQ(nVertices, hull.nVertices()); + EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0))); + EXPECT_TRUE(hull.isInside(Vector2d(0.25, 0.0))); + EXPECT_TRUE(hull.isInside(Vector2d(0.0, 0.25))); + EXPECT_TRUE(hull.isInside(Vector2d(0.0, -0.25))); + EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.5))); + EXPECT_FALSE(hull.isInside(Vector2d(0.6, 0.0))); + EXPECT_FALSE(hull.isInside(Vector2d(-0.6, 0.0))); + EXPECT_FALSE(hull.isInside(Vector2d(0.0, 0.6))); + EXPECT_FALSE(hull.isInside(Vector2d(0.0, -0.6))); +} + +TEST(Polygon, convexHullCircle) +{ + Position center(0.0, 0.0); + double radius = 0.5; + const int nVertices = 15; + + Polygon hull = Polygon::fromCircle(center, radius); + + EXPECT_EQ(20, hull.nVertices()); + EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0))); + EXPECT_TRUE(hull.isInside(Vector2d(0.49, 0.0))); + EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.4))); + EXPECT_FALSE(hull.isInside(Vector2d(1.0, 0.0))); + + hull = Polygon::fromCircle(center, radius, nVertices); + EXPECT_EQ(nVertices, hull.nVertices()); + EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0))); + EXPECT_TRUE(hull.isInside(Vector2d(0.49, 0.0))); + EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.4))); + EXPECT_FALSE(hull.isInside(Vector2d(1.0, 0.0))); +} + +TEST(convertToInequalityConstraints, triangle1) +{ + Polygon polygon({Position(1.0, 1.0), Position(0.0, 0.0), Position(1.1, -1.1)}); + MatrixXd A; + VectorXd b; + ASSERT_TRUE(polygon.convertToInequalityConstraints(A, b)); + EXPECT_NEAR(-1.3636, A(0, 0), 1e-4); + EXPECT_NEAR( 1.3636, A(0, 1), 1e-4); + EXPECT_NEAR(-1.5000, A(1, 0), 1e-4); + EXPECT_NEAR(-1.5000, A(1, 1), 1e-4); + EXPECT_NEAR( 2.8636, A(2, 0), 1e-4); + EXPECT_NEAR( 0.1364, A(2, 1), 1e-4); + EXPECT_NEAR( 0.0000, b(0), 1e-4); + EXPECT_NEAR( 0.0000, b(1), 1e-4); + EXPECT_NEAR( 3.0000, b(2), 1e-4); +} + +TEST(convertToInequalityConstraints, triangle2) +{ + Polygon polygon({Position(-1.0, 0.5), Position(-1.0, -0.5), Position(1.0, -0.5)}); + MatrixXd A; + VectorXd b; + ASSERT_TRUE(polygon.convertToInequalityConstraints(A, b)); + EXPECT_NEAR(-1.5000, A(0, 0), 1e-4); + EXPECT_NEAR( 0.0000, A(0, 1), 1e-4); + EXPECT_NEAR( 0.0000, A(1, 0), 1e-4); + EXPECT_NEAR(-3.0000, A(1, 1), 1e-4); + EXPECT_NEAR( 1.5000, A(2, 0), 1e-4); + EXPECT_NEAR( 3.0000, A(2, 1), 1e-4); + EXPECT_NEAR( 1.5000, b(0), 1e-4); + EXPECT_NEAR( 1.5000, b(1), 1e-4); + EXPECT_NEAR( 0.0000, b(2), 1e-4); +} + +TEST(offsetInward, triangle) +{ + Polygon polygon({Position(1.0, 1.0), Position(0.0, 0.0), Position(1.0, -1.0)}); + polygon.offsetInward(0.1); + EXPECT_NEAR(0.9, polygon.getVertex(0)(0), 1e-4); + EXPECT_NEAR(0.758579, polygon.getVertex(0)(1), 1e-4); + EXPECT_NEAR(0.141421, polygon.getVertex(1)(0), 1e-4); + EXPECT_NEAR(0.0, polygon.getVertex(1)(1), 1e-4); + EXPECT_NEAR(0.9, polygon.getVertex(2)(0), 1e-4); + EXPECT_NEAR(-0.758579, polygon.getVertex(2)(1), 1e-4); +} + +TEST(triangulation, triangle) +{ + Polygon polygon({Position(1.0, 1.0), Position(0.0, 0.0), Position(1.0, -1.0)}); + std::vector polygons; + polygons = polygon.triangulate(); + ASSERT_EQ(1, polygons.size()); + EXPECT_EQ(polygon.getVertex(0).x(), polygons[0].getVertex(0).x()); + EXPECT_EQ(polygon.getVertex(0).y(), polygons[0].getVertex(0).y()); + EXPECT_EQ(polygon.getVertex(1).x(), polygons[0].getVertex(1).x()); + EXPECT_EQ(polygon.getVertex(1).y(), polygons[0].getVertex(1).y()); + EXPECT_EQ(polygon.getVertex(2).x(), polygons[0].getVertex(2).x()); + EXPECT_EQ(polygon.getVertex(2).y(), polygons[0].getVertex(2).y()); +} + +TEST(triangulation, rectangle) +{ + Polygon rectangle; + rectangle.addVertex(Vector2d(-2.0, -1.0)); + rectangle.addVertex(Vector2d(-2.0, 2.0)); + rectangle.addVertex(Vector2d(1.0, 2.0)); + rectangle.addVertex(Vector2d(1.0, -1.0)); + std::vector polygons; + polygons = rectangle.triangulate(); + ASSERT_EQ(2, polygons.size()); + // TODO Extend. +} diff --git a/test/SlidingWindowIteratorTest.cpp b/test/SlidingWindowIteratorTest.cpp new file mode 100644 index 0000000..902144a --- /dev/null +++ b/test/SlidingWindowIteratorTest.cpp @@ -0,0 +1,153 @@ +/* + * SlidingWindowIteratorTest.cpp + * + * Created on: Aug 16, 2017 + * Author: Péter Fankhauser + * Institute: ETH Zurich + */ + +#include "grid_map_core/iterators/SlidingWindowIterator.hpp" +#include "grid_map_core/GridMap.hpp" + +#include +#include + +using grid_map::GridMap; +using grid_map::Index; +using grid_map::Length; +using grid_map::Position; +using grid_map::SlidingWindowIterator; + +TEST(SlidingWindowIterator, WindowSize3Cutoff) +{ + GridMap map; + map.setGeometry(Length(8.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + map.add("layer"); + map["layer"].setRandom(); + + SlidingWindowIterator iterator(map, "layer", SlidingWindowIterator::EdgeHandling::CROP, 3); + EXPECT_EQ(iterator.getData().rows(), 2); + EXPECT_EQ(iterator.getData().cols(), 2); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(0, 0, 2, 2))); + + ++iterator; + EXPECT_EQ(iterator.getData().rows(), 3); + EXPECT_EQ(iterator.getData().cols(), 2); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(0, 0, 3, 2))); + + ++iterator; + EXPECT_EQ(iterator.getData().rows(), 3); + EXPECT_EQ(iterator.getData().cols(), 2); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(1, 0, 3, 2))); + + for (; !iterator.isPastEnd(); ++iterator) { + EXPECT_FALSE(iterator.isPastEnd()); + if ((*iterator == Index(3, 2)).all()) { + break; + } + } + + EXPECT_EQ(iterator.getData().rows(), 3); + EXPECT_EQ(iterator.getData().cols(), 3); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(2, 1, 3, 3))); + + for (; !iterator.isPastEnd(); ++iterator) { + EXPECT_FALSE(iterator.isPastEnd()); + if ((*iterator == Index(7, 4)).all()) { + break; + } + } + + EXPECT_EQ(iterator.getData().rows(), 2); + EXPECT_EQ(iterator.getData().cols(), 2); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(6, 3, 2, 2))); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} + +TEST(SlidingWindowIterator, WindowSize5) +{ + GridMap map; + map.setGeometry(Length(8.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + map.add("layer"); + map["layer"].setRandom(); + + SlidingWindowIterator iterator(map, "layer", SlidingWindowIterator::EdgeHandling::CROP, 5); + EXPECT_EQ(iterator.getData().rows(), 3); + EXPECT_EQ(iterator.getData().cols(), 3); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(0, 0, 3, 3))); + + ++iterator; + EXPECT_EQ(iterator.getData().rows(), 4); + EXPECT_EQ(iterator.getData().cols(), 3); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(0, 0, 4, 3))); + + ++iterator; + EXPECT_EQ(iterator.getData().rows(), 5); + EXPECT_EQ(iterator.getData().cols(), 3); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(0, 0, 5, 3))); + + for (; !iterator.isPastEnd(); ++iterator) { + EXPECT_FALSE(iterator.isPastEnd()); + if ((*iterator == Index(3, 2)).all()) { + break; + } + } + + EXPECT_EQ(iterator.getData().rows(), 5); + EXPECT_EQ(iterator.getData().cols(), 5); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(1, 0, 5, 5))); + + for (; !iterator.isPastEnd(); ++iterator) { + EXPECT_FALSE(iterator.isPastEnd()); + if ((*iterator == Index(7, 4)).all()) { + break; + } + } + + EXPECT_EQ(iterator.getData().rows(), 3); + EXPECT_EQ(iterator.getData().cols(), 3); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(5, 2, 3, 3))); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} + +TEST(SlidingWindowIterator, WindowSize3Inside) +{ + GridMap map; + map.setGeometry(Length(8.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + map.add("layer"); + map["layer"].setRandom(); + + SlidingWindowIterator iterator(map, "layer", SlidingWindowIterator::EdgeHandling::INSIDE, 3); + EXPECT_EQ(iterator.getData().rows(), 3); + EXPECT_EQ(iterator.getData().cols(), 3); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(0, 0, 3, 3))); + + for (; !iterator.isPastEnd(); ++iterator) { + EXPECT_FALSE(iterator.isPastEnd()); + if ((*iterator == Index(3, 2)).all()) { + break; + } + } + + EXPECT_EQ(iterator.getData().rows(), 3); + EXPECT_EQ(iterator.getData().cols(), 3); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(2, 1, 3, 3))); + + for (; !iterator.isPastEnd(); ++iterator) { + EXPECT_FALSE(iterator.isPastEnd()); + if ((*iterator == Index(6, 3)).all()) { + break; + } + } + + EXPECT_EQ(iterator.getData().rows(), 3); + EXPECT_EQ(iterator.getData().cols(), 3); + EXPECT_TRUE(iterator.getData().isApprox(map["layer"].block(5, 2, 3, 3))); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); +} diff --git a/test/SpiralIteratorTest.cpp b/test/SpiralIteratorTest.cpp new file mode 100644 index 0000000..f206dfc --- /dev/null +++ b/test/SpiralIteratorTest.cpp @@ -0,0 +1,36 @@ +/* + * SpiralIteratorTest.cpp + * + * Created on: Jul 26, 2017 + * Author: Benjamin Scholz + * Institute: University of Hamburg, TAMS + */ + +#include "grid_map_core/iterators/SpiralIterator.hpp" +#include "grid_map_core/GridMap.hpp" + +// gtest +#include + +// Vector +#include + +using grid_map::GridMap; +using grid_map::Length; +using grid_map::Position; +using grid_map::SpiralIterator; + +TEST(SpiralIterator, CenterOutOfMap) +{ + GridMap map( { "types" }); + map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); + Position center(8.0, 0.0); + double radius = 5.0; + + SpiralIterator iterator(map, center, radius); + + Position iterator_position; + map.getPosition(*iterator, iterator_position); + + EXPECT_TRUE(map.isInside(iterator_position)); +} diff --git a/test/SubmapIteratorTest.cpp b/test/SubmapIteratorTest.cpp new file mode 100644 index 0000000..3c838ea --- /dev/null +++ b/test/SubmapIteratorTest.cpp @@ -0,0 +1,267 @@ +/* + * SubmapIteratorTest.cpp + * + * Created on: Sep 15, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +#include "grid_map_core/GridMap.hpp" +#include "grid_map_core/iterators/SubmapIterator.hpp" + +// Eigen +#include + +// gtest +#include + +// Vector +#include + +using std::vector; +using std::string; + +namespace grid_map{ + +TEST(SubmapIterator, Simple) { + Eigen::Array2i submapTopLeftIndex(3, 1); + Eigen::Array2i submapBufferSize(3, 2); + Eigen::Array2i index; + Eigen::Array2i submapIndex; + + vector types; + types.emplace_back("type"); + GridMap map(types); + map.setGeometry(Eigen::Array2d(8.1, 5.1), 1.0, Eigen::Vector2d(0.0, 0.0)); // bufferSize(8, 5) + + SubmapIterator iterator(map, submapTopLeftIndex, submapBufferSize); + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(submapTopLeftIndex(0), (*iterator)(0)); + EXPECT_EQ(submapTopLeftIndex(1), (*iterator)(1)); + EXPECT_EQ(0, iterator.getSubmapIndex()(0)); + EXPECT_EQ(0, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(3, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + EXPECT_EQ(0, iterator.getSubmapIndex()(0)); + EXPECT_EQ(1, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(4, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + EXPECT_EQ(1, iterator.getSubmapIndex()(0)); + EXPECT_EQ(0, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(4, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + EXPECT_EQ(1, iterator.getSubmapIndex()(0)); + EXPECT_EQ(1, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(5, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + EXPECT_EQ(2, iterator.getSubmapIndex()(0)); + EXPECT_EQ(0, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(5, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + EXPECT_EQ(2, iterator.getSubmapIndex()(0)); + EXPECT_EQ(1, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); + EXPECT_EQ(5, (*iterator)(0)); + EXPECT_EQ(2, (*iterator)(1)); + EXPECT_EQ(2, iterator.getSubmapIndex()(0)); + EXPECT_EQ(1, iterator.getSubmapIndex()(1)); +} + +TEST(SubmapIterator, CircularBuffer) { + Eigen::Array2i submapTopLeftIndex(6, 3); + Eigen::Array2i submapBufferSize(2, 4); + Eigen::Array2i index; + Eigen::Array2i submapIndex; + + vector types; + types.emplace_back("type"); + GridMap map(types); + map.setGeometry(Length(8.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + map.move(Position(-3.0, -2.0)); // bufferStartIndex(3, 2) + + SubmapIterator iterator(map, submapTopLeftIndex, submapBufferSize); + + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(submapTopLeftIndex(0), (*iterator)(0)); + EXPECT_EQ(submapTopLeftIndex(1), (*iterator)(1)); + EXPECT_EQ(0, iterator.getSubmapIndex()(0)); + EXPECT_EQ(0, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(6, (*iterator)(0)); + EXPECT_EQ(4, (*iterator)(1)); + EXPECT_EQ(0, iterator.getSubmapIndex()(0)); + EXPECT_EQ(1, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(6, (*iterator)(0)); + EXPECT_EQ(0, (*iterator)(1)); + EXPECT_EQ(0, iterator.getSubmapIndex()(0)); + EXPECT_EQ(2, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(6, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + EXPECT_EQ(0, iterator.getSubmapIndex()(0)); + EXPECT_EQ(3, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(7, (*iterator)(0)); + EXPECT_EQ(3, (*iterator)(1)); + EXPECT_EQ(1, iterator.getSubmapIndex()(0)); + EXPECT_EQ(0, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(7, (*iterator)(0)); + EXPECT_EQ(4, (*iterator)(1)); + EXPECT_EQ(1, iterator.getSubmapIndex()(0)); + EXPECT_EQ(1, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(7, (*iterator)(0)); + EXPECT_EQ(0, (*iterator)(1)); + EXPECT_EQ(1, iterator.getSubmapIndex()(0)); + EXPECT_EQ(2, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_FALSE(iterator.isPastEnd()); + EXPECT_EQ(7, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + EXPECT_EQ(1, iterator.getSubmapIndex()(0)); + EXPECT_EQ(3, iterator.getSubmapIndex()(1)); + + ++iterator; + EXPECT_TRUE(iterator.isPastEnd()); + EXPECT_EQ(7, (*iterator)(0)); + EXPECT_EQ(1, (*iterator)(1)); + EXPECT_EQ(1, iterator.getSubmapIndex()(0)); + EXPECT_EQ(3, iterator.getSubmapIndex()(1)); +} + +/** + * The submap should contain the same elements as before even after moving the underlying map. + * + * +----------------------------+ + * | | + * | | + * +----------------------------+ | | + * |0 0 0 0 0 0 0 0 0 0| | 0 0 0 0 0 0 0 0| + * | +----+ | | +----+ | + * Submap |1 1 |1 1| 1 1 1 1 1 1| | 1 1 |1 1| 1 1 1 1| + * +------> | | | | | | | + * |2 2 |2 2| 2 2 2 2 2 2| | 2 2 |2 2| 2 2 2 2| + * | +----+ | | +----+ | + * |3 3 3 3 3 3 3 3 3 3| Move | 3 3 3 3 3 3 3 3| + * | | | | + * |4 4 4 4 4 4 4 4 4 4| +---------> | 4 4 4 4 4 4 4 4| + * | | | | + * |5 5 5 5 5 5 5 5 5 5| | 5 5 5 5 5 5 5 5| + * | | | | + * |6 6 6 6 6 6 6 6 6 6| | 6 6 6 6 6 6 6 6| + * | | | | + * |7 7 7 7 7 7 7 7 7 7| | 7 7 7 7 7 7 7 7| + * | | +----------------------------+ + * |8 8 8 8 8 8 8 8 8 8| + * | | + * |9 9 9 9 9 9 9 9 9 9| + * +----------------------------+ + */ +TEST(SubmapIterator, InterleavedExecutionWithMove) { + grid_map::Index submapTopLeftIndex(3, 1); + grid_map::Size submapSize(2, 2); + + GridMap map({"layer"}); + + map.setGeometry(Length(10, 10), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5) + + auto& layer = map.get("layer"); + + // Initialize the layer as sketched. + for (long colIndex = 0; colIndex < layer.cols(); colIndex++) { + layer.col(colIndex).setConstant(static_cast(colIndex)); + } + + std::cout << "(4,7) contains " << map.at("layer", {4, 7}) << std::endl; + // Instantiate the submap iterator as sketched. + SubmapIterator iterator(map, submapTopLeftIndex, submapSize); + + // check that the submap iterator returns {1,1,2,2} + auto checkCorrectValues = [](std::array given) { + int countOnes = 0; + int countTwos = 0; + for (auto& value : given) { + if (std::abs(value - 1.0) < 1e-6) { + countOnes++; + } else if (std::abs(value - 2.0) < 1e-6) { + countTwos++; + } else { + FAIL() << "Submap iterator returned unexpected value."; + } + } + EXPECT_EQ(countOnes, 2); + EXPECT_EQ(countTwos, 2); + }; + + std::array returnedSequence{}; + returnedSequence.fill(0); + + for (size_t submapIndex = 0; submapIndex < 4; submapIndex++) { + returnedSequence.at(submapIndex) = map.at("layer", *iterator); + ++iterator; + } + + checkCorrectValues(returnedSequence); + + // Reset the iterator and now check that it still returns the same sequence when we move the map interleaved with iterating. + iterator = SubmapIterator(map, submapTopLeftIndex, submapSize); + returnedSequence.fill(0); + for (size_t submapIndex = 0; submapIndex < 4; submapIndex++) { + if (submapIndex == 2) { + // Now move the map as depicted. + map.move(Position(2.0, 2.0)); + } + returnedSequence.at(submapIndex) = map.at("layer", *iterator); + ++iterator; + } + checkCorrectValues(returnedSequence); + + // TODO (mwulf, mgaertner): This behavior is not yet implemented: + // + // // Reset the iterator and now check that the iterator throws? if the submap moved out of range. + // iterator = SubmapIterator(map, submapTopLeftIndex, submapSize); + // + // EXPECT_ANY_THROW(for (size_t submapIndex = 0; submapIndex < 4; submapIndex++) { + // if (submapIndex == 2) { + // // Now move the map so that the submap gets out of range. + // map.move(Position(20.0, 20.0)); + // } + // returnedSequence.at(submapIndex) = map.at("layer", *iterator); + // ++iterator; + // }); +} + +} // namespace grid_map diff --git a/test/test_grid_map_core.cpp b/test/test_grid_map_core.cpp new file mode 100644 index 0000000..78b7680 --- /dev/null +++ b/test/test_grid_map_core.cpp @@ -0,0 +1,18 @@ +/* + * test_grid_map.cpp + * + * Created on: Feb 10, 2014 + * Author: Péter Fankhauser + * Institute: ETH Zurich, ANYbotics + */ + +// gtest +#include + +// Run all the tests that were declared with TEST() +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + srand((int)time(nullptr)); + return RUN_ALL_TESTS(); +} diff --git a/test/test_helpers.cpp b/test/test_helpers.cpp new file mode 100644 index 0000000..96d78fa --- /dev/null +++ b/test/test_helpers.cpp @@ -0,0 +1,232 @@ +/* + * test_helpers.cpp + * + * Created on: Mar 3, 2020 + * Author: Edo Jelavic + * Institute: ETH Zurich, Robotic Systems Lab + */ + +#include "test_helpers.hpp" + +#include "grid_map_core/GridMap.hpp" +#include "grid_map_core/iterators/GridMapIterator.hpp" + +// gtest +#include + +namespace grid_map_test { + +std::mt19937 rndGenerator; + +AnalyticalFunctions createFlatWorld(grid_map::GridMap *map) +{ + + AnalyticalFunctions func; + + func.f_ = [](double /*x*/, double /*y*/) { + return 0.0; + }; + + fillGridMap(map, func); + + return func; + +} + +AnalyticalFunctions createRationalFunctionWorld(grid_map::GridMap *map) +{ + + AnalyticalFunctions func; + + std::uniform_real_distribution shift(-3.0, 3.0); + std::uniform_real_distribution scale(1.0, 20.0); + const double x0 = shift(rndGenerator); + const double y0 = shift(rndGenerator); + const double s = scale(rndGenerator); + + func.f_ = [x0, y0,s](double x, double y) { + return s / (1 + std::pow(x-x0, 2.0) + std::pow(y-y0, 2.0)); + }; + + fillGridMap(map, func); + + return func; + +} + +AnalyticalFunctions createSecondOrderPolyWorld(grid_map::GridMap *map) +{ + + AnalyticalFunctions func; + + func.f_ = [](double x,double y) { + return (-x*x -y*y +2.0*x*y +x*x*y*y); + }; + + fillGridMap(map, func); + + return func; + +} + +AnalyticalFunctions createSaddleWorld(grid_map::GridMap *map) +{ + AnalyticalFunctions func; + + func.f_ = [](double x,double y) { + return (x*x-y*y); + }; + + fillGridMap(map, func); + + return func; + +} + +AnalyticalFunctions createSineWorld(grid_map::GridMap *map) +{ + + AnalyticalFunctions func; + + std::uniform_real_distribution Uw(0.1, 4.0); + const double w1 = Uw(rndGenerator); + const double w2 = Uw(rndGenerator); + const double w3 = Uw(rndGenerator); + const double w4 = Uw(rndGenerator); + + func.f_ = [w1,w2,w3,w4](double x,double y) { + return std::cos(w1*x) + std::sin(w2*y) + std::cos(w3*x) + std::sin(w4*y); + }; + + fillGridMap(map, func); + + return func; + +} + +AnalyticalFunctions createTanhWorld(grid_map::GridMap *map) +{ + + AnalyticalFunctions func; + + std::uniform_real_distribution scaling(0.1, 2.0); + const double s = scaling(rndGenerator); + func.f_ = [s](double x,double /*y*/) { + const double expZ = std::exp(2 *s* x); + return (expZ - 1) / (expZ + 1); + }; + + fillGridMap(map, func); + + return func; +} + +AnalyticalFunctions createGaussianWorld(grid_map::GridMap *map) +{ + + struct Gaussian + { + double x0, y0; + double varX, varY; + double s; + }; + + AnalyticalFunctions func; + + std::uniform_real_distribution var(0.1, 3.0); + std::uniform_real_distribution mean(-4.0, 4.0); + std::uniform_real_distribution scale(-3.0, 3.0); + constexpr int numGaussians = 3; + std::array g; + + for (int i = 0; i < numGaussians; ++i) { + g.at(i).x0 = mean(rndGenerator); + g.at(i).y0 = mean(rndGenerator); + g.at(i).varX = var(rndGenerator); + g.at(i).varY = var(rndGenerator); + g.at(i).s = scale(rndGenerator); + } + + func.f_ = [g](double x,double y) { + double value = 0.0; + for (const auto & i : g) { + const double x0 = i.x0; + const double y0 = i.y0; + const double varX = i.varX; + const double varY = i.varY; + const double s = i.s; + value += s * std::exp(-(x-x0)*(x-x0) / (2.0*varX) - (y-y0)*(y-y0) / (2.0 * varY)); + } + + return value; + }; + + fillGridMap(map, func); + + return func; +} + +void fillGridMap(grid_map::GridMap *map, const AnalyticalFunctions &functions) +{ + using grid_map::DataType; + using grid_map::GridMapIterator; + using grid_map::Index; + using grid_map::Matrix; + using grid_map::Position; + + Matrix& data = (*map)[testLayer]; + for (GridMapIterator iterator(*map); !iterator.isPastEnd(); ++iterator) { + const Index index(*iterator); + Position pos; + map->getPosition(index, pos); + data(index(0), index(1)) = static_cast(functions.f_(pos.x(), pos.y())); + } +} + +grid_map::GridMap createMap(const grid_map::Length &length, double resolution, + const grid_map::Position &pos) +{ + grid_map::GridMap map; + + map.setGeometry(length, resolution, pos); + map.add(testLayer, 0.0); + map.setFrameId("map"); + + return map; +} + +std::vector uniformlyDitributedPointsWithinMap(const grid_map::GridMap &map, + unsigned int numPoints) +{ + + // stay away from the edges + // on the edges the cubic interp is invalid. Not enough points. + const double dimX = map.getLength().x() / 2.0 - 3.0 * map.getResolution(); + const double dimY = map.getLength().y() / 2.0 - 3.0 * map.getResolution(); + std::uniform_real_distribution Ux(-dimX, dimX); + std::uniform_real_distribution Uy(-dimY, dimY); + + std::vector points(numPoints); + for (auto &point : points) { + point.x_ = Ux(rndGenerator); + point.y_ = Uy(rndGenerator); + } + + return points; +} + +void verifyValuesAtQueryPointsAreClose(const grid_map::GridMap &map, const AnalyticalFunctions &trueValues, + const std::vector &queryPoints, + grid_map::InterpolationMethods interpolationMethod){ + for (const auto point : queryPoints) { + const grid_map::Position p(point.x_, point.y_); + const double trueValue = trueValues.f_(p.x(), p.y()); + const double interpolatedValue = map.atPosition( + grid_map_test::testLayer, p, interpolationMethod); + EXPECT_NEAR(trueValue, interpolatedValue, grid_map_test::maxAbsErrorValue); + } +} + + +} /* namespace grid_map_test */ + diff --git a/test/test_helpers.hpp b/test/test_helpers.hpp new file mode 100644 index 0000000..075963c --- /dev/null +++ b/test/test_helpers.hpp @@ -0,0 +1,96 @@ +/* + * test_helpers.hpp + * + * Created on: Mar 3, 2020 + * Author: Edo Jelavic + * Institute: ETH Zurich, Robotic Systems Lab + */ + +#pragma once +#include "grid_map_core/TypeDefs.hpp" +#include +#include +#include + +namespace grid_map { + class GridMap; +} + +namespace grid_map_test { + +/* + * Name of the layer that is used in all tests. + * It has no special meaning. + */ +static const std::string testLayer = "test"; + +/* + * Class that holds a function pointer to analytical + * functions used for evaluation. Analytical functions + * are in the form of f = f(x,y). One could also add + * derivatives to this class, e.g. for testing the + * accuracy of the normal estimation. + */ +struct AnalyticalFunctions +{ + std::function f_; +}; + +struct Point2D +{ + double x_ = 0.0; + double y_ = 0.0; +}; + +// Random generator engine. +extern std::mt19937 rndGenerator; + +// Maximal tolerance when comparing doubles in tests. +const double maxAbsErrorValue = 1e-3; + +grid_map::GridMap createMap(const grid_map::Length &length, double resolution, + const grid_map::Position &pos); + +/* + * Collections of methods that modify the grid map. + * All these methods create an analytical function that + * describes the value of the layer "testLayer" as a function + * of coordinates. That can be any mathematical function. Inside the test, + * sinusoidal, polynomial functions and exponential functions are used. + * e.g. f(x,y) = sin(x) + cos(y), f(x,y) = exp(-x*x - y*y) + * Grid map is then filled by evaluating + * that analytical function over the entire length and width of the + * grid map. Grid map thus contains spatially sampled mathematical + * function. + * Each method returns a structure containing the analytical function. + */ +AnalyticalFunctions createFlatWorld(grid_map::GridMap *map); +AnalyticalFunctions createRationalFunctionWorld(grid_map::GridMap *map); +AnalyticalFunctions createSaddleWorld(grid_map::GridMap *map); +AnalyticalFunctions createSecondOrderPolyWorld(grid_map::GridMap *map); +AnalyticalFunctions createSineWorld(grid_map::GridMap *map); +AnalyticalFunctions createTanhWorld(grid_map::GridMap *map); +AnalyticalFunctions createGaussianWorld(grid_map::GridMap *map); + +/* + * Iterates over the grid map and fill it with values. + * values are calculated by evaluating analytical function. + */ +void fillGridMap(grid_map::GridMap *map, const AnalyticalFunctions &functions); + +/* + * Create numPoints uniformly distributed random points that lie within the grid map. + */ +std::vector uniformlyDitributedPointsWithinMap(const grid_map::GridMap &map, + unsigned int numPoints); + +/* + * For each point in queryPoints, verify that the interpolated value of the grid map + * is close to the ground truth which is contained in Analytical functions structure. + * Called inside the tests. Calls macros from gtest. + */ +void verifyValuesAtQueryPointsAreClose(const grid_map::GridMap &map, const AnalyticalFunctions &trueValues, + const std::vector &queryPoints, + grid_map::InterpolationMethods interpolationMethod); + +} // namespace grid_map_test

    tua@)Fng|MZa27(Zru@Eruz8|+y$bqM;xK}RxsOi>06>+hg|KwGvT=zZ!UtnwmOG?T z>enJR$ZA~}e|8v&5AG<`cK#gkIY*@(qph~wMY@XrFMV);kW?8xIxZBZGIbMm-*)qPXDHWtF(8StEKb)udHiuZwms9#X#&P__!TpYs^6aTb z&pQ1Nh~SdTtI;d7`HBPv`>#;F^~XMJ;O7Hv{iB};4|m$vhu>b@i{(~NlCFI${19u< z8~&Ncg*$)q;%eY)r(e4H?1RLW(2iu3jtxqgi%){g&Bc3eQqm z-{OY-F-_f$v3u=p=!K;O0lYQj11)P~jGV~}N#+ekPw{MIy0C#1Hjr-$82-@T8PaHE z^xAk-yfFC&fpSV&I$s$rUAWVIz+(oN*+)rp#&X9|{xgk|+xUQbRFnv`-iuQ|R#JK; zyD?aWw(#|0OHb(al}8QzkB*3ct!!%i*I^Ov=uEV}k*Nbn<;lB`U!-6QrSx7T^BT`j z_@3DA9-9BO@2zGmtX^q5@Gka-_$hVxg-?62RIQEQ5)rE6!jE6>720n^-DYIegK*v7 zz1x_cta7h?re`D5XB!lacRlkK6tj{690i}E9;8rz>|7nNKqUPkUKY7U+2vISiEp6Vx446DSc4f9|kR^h(VIe-DGax9RlUr>KAJtac zf<_s`Rsw}M(&4V|X{X8+Wru3xadE{cF}!_E$p`pdbvNBdQ-zAI8L+G(CD(fW_|G`& zU`2;gd`kP)XQZ@#^hzVIIXG8Z*YfdUW-dJ!r58q%APywDBVFno5T81~r#CoW3)`O6 z-vJ9DO`}V-t5o=FrEqa$?217!OqLVQmj7e4zdKZ!Kc-EL5g_AYNj3dtfSuNTZZ%x}K6L?Z_?BnY zUV9~Z0d5we(u2EVZ}JOQg{IN`UZD58}M0A$r)i4-+1Q9HuLly~vwx=O1 zy1juS7M%jh6(mG_1L8Ojap*dMr;1P5lt*M+*i>vHO&H&~J_yq2%qS#G-Y^~BoeyeNIRSL%};zyG2_1~P+ z`S#_MD8kd<)$)s7XO~n6VF@ChF0%&{pXIcMU2|7o6=WY*Iuh(k*7@fWpro>zp(>5% zFgj4(Sn*h2d``9-xu9A+SkE{~T+=23gcNrWL5sU0BGxa;9+W?<&QY5uO{%-ik}TAP zHa|l(@Ab~xULN9hOlq#YpU*R@JC~MM@M7wf=DU^$2PW^^t-Kwjeang9(%@?Ph|q(N zY^Cy3P!S?9_Jw!4Q0#Z=+w0`7>!vr(f8XarocM}ptdc}!1FBhFv)i>-=5c2AWzB7e z5Gy6bl`MwBsqzautsmSocBb_=3A9ATK$=c-5g;WlBJx+dGI|?gE`(|kyG3v_h`O_lbL96J zPmV)~x6i$v6ur)sRNf?Az4Sa(tn6^OWEroWu9$Wp)k-04U>AWu^@+MRRL7Clg%cI(}L+c9Z;;l$gHZhs>aAoWA zZtF9Rk6)1j=f07v9G~Ko+qRD}Mci$Us4FyDu?s8RXQ=6J=(zp~3Hn@v5z&AU6ZF_( z9!2-=e;bXBuoZc}y=(}svoC3h4%HA&xPjk}A>DHmQTHbcf~Of0I;j?7nw~j6+)YW7 zO$+VDPYSaI4&`rGMhtr~!mIIjuD$r9Wc(#C<7oli_JP7eDMPYX?_n0igthRg*pRe3#GqdCkEJgc0-D4$<`3uwq_ljvd*mvz z%Fxw#AUK;Yt{#{s079}679-rZIu51P;$>W*v|mB6em4X9 z@>av~B5QzXV>e1gU)>ygu=`qVPQs}Bt}e9QjU6u)j`1_W$7w>w z5CA7MSVR~S@U|kVT8LPDrhehk8$0ErLLw?eV?wj5I1qRbi*`(&U}H|Q>#Ca}{O5uQ zB_2Sm5O2S=aEJ5Tb#nL|M(A<#7fQo)z3NFnc#7$ur_#!-&0lTML)<6U?Igf0>a?W) zW{~71dXQMM)B!W#&-~Sp2!Mpps}Hd^c-pg6HUu0vsBve^qMfeLJ)i|7X=XFeCr0uvwSL&Csr>6GJIO;U4b$K{f zV`H{(Tx00HXcwd)qDa6+zYR*kEDv+#>{cqS0+a~xeeBcSS>T#dM4%5_8IO&r*NL=_&%j+?bhnB&&_ z5EMB&Ohky}=RQ|!O1*r6{2^5Bn0Rw<7eI$c3Mktm1$obR)Aha;PDmsxg;*Ux9e$!@ zTJXcJHs?p`VnwQVy|BKA zSR35vwbWhjw^`5((Iqgfp4J=QnqCFEY|B0VJjW+&ETmA(SMf4p)JU$B%hwHSjdSPd z8zj>_OoZtZzPSQOTM|;@2=-6JSnP!y8LiA?YiCYfwdjbO-OAmm4)Uq8C^)zF<6uxr zF!t2dXK`mVU-^BVcyE+%vEuQA7TvxlJ+~=waM?(Gk)gT8((EK{Ckz?_vkEwahKE|A z*We@Z3ZMfTq-%Ymk^W(OW&qy*QD2tcB4FA-F0`I?++8+phmf{2{>{$o1al39gF@MB z%t(}AZ3XCSHmHJdTYJ`uP0o70xWJ_Giw$RM@IwtUr;P1$m%L89@t@&9@1CDTK!*^P zm3I-$e;bSV4bsUFw$mKc+>XcbS9*&+`Lf86rFA7gikyf7@oyJA(O|lYjfT*3+`31k zt6!E?+1^|4q&Dx6*wU5eJ1wwz>D!R|Fz+lA~2-l;DL_1=f$bf&ADQZ z`&|Z{*FaG7*(;=?aSNnof7a)o4E-xx%4x|?DUwC;h#dB+D zAgSt~oFRs|UH<*zS4l0tTb*Nf=j^vCWID%hoM{POBjleQXK8E&>;8JFp)RWXjiiMz z*X9BYw;4tpKCRj`quRlvod7;foQWHU>`)8bOFKfd23HeB60FO_c&{P)5jaOizrb}b zS&^0TFXYEJwidp=cdhy2<= zvKEk|bxAm6$uGN8w-nuaW>0e2(q$u22`>Z_;J|&pVn{VwY!kEXNe>rH`H5xmo3k!8&Wg)WQEAVRTv`6P@$`1~yt-(e-L!h3#p zDaejK_-FJ*?z0a2nGWljU&NXF7bLehGRCbk$p;b(uS{pu-5gA27#ioVKEI`~HZ`!3 z_s{Xu4X4c`JI*+;b_Tg{AcULyVgu0-~Nh8(snRLrpcr-GT z7R(k05w-M>>J|HA0_7F8*V1b%*;_-;MQ{8W|FSL$?c1vQL#swl2%16R(qhos$D}#3 zed*BeLyEv%tjQQo`r`;OAm{27ViZT?wKLBmMrCvZA^kSyrs)=yHsFfv;_pQ^Do*C5 zm=>N;A_qfxElffHiB59!ZkcnlRbB7van_)2H`*eXAb@|B5;Co%$cwfVIN>xv9r4E@ zNF191PnAut*Zvg+;@sL|9Ci-h$v8;-z~9cy3(_Yl6Q}&0r$V-u!ZYgO2>~_Vs=}%E zDePR2wv5##O96EW0n-vei#)+O=d%f!3P04%Mx$>nB)@)0$)ap#Rj#?()JJ45FMR86%=yh79S+H`m|zBa32v?1XOrt$ z>31T4)~F$Ko~0)8YO%+`C;`n(ScE0cZaj|2iGv}F95NI1tqw|yoO*@l<sJZGXh;N_;ZoQ5>mKARwT7fEMzsc4k!UdGU}jZ-^5(Jiso@4;;e`lY}o< zHcy7TA){L7)Pjb`wU=e`cvhF4&k}}1pM&FBTxea%+|Y~IF=@A7*MZ4`?sgy`n|m@6 z1UzrId`LhziwuofrRUD4SNNW3kr7Y#)OqNuK1(vY|MnHDL1#|w>wV?d1g+lKlV9X=+w$z*LCdQz88r_kPO1-GOMUa|%gBI6=QA}fLrZ-@7lYT?CK);nK8i^*c<+1c zZnSCh`cXNI>9lc~jiwV8$Etck2^o#WOdZEKf`!%sb}y;jH+_3aPs`ybbup~j4( z(7I0b-;K0iZ9~>YD2r~CqpYH+G*bkL#1uc}+kZbp&3w!QKSRijTa(S(P#24JL%8Pf z{9XI+RyLt+qe(k+>h+4?z1IovvTxYn~h@uJ+*~>L` zYP_<>hecp9mJFGjtC-KTKKQVTP)2Zlv3~@qQcB)fmD27Wj@Pl=vIq#a%RrtFyDirt zO0_!}i5PhbUXB!!I4S!wLhMHK08JuiRK}gDJ^+(ljhb0$KD#yoOn=%k?~KHTE7x3y z&_q&8>*2H@q*E?unE$-k?ZJKIGtR4|;*Y5_lw=p;k0dR#E-ka9k7|^eT$Jcn8=>Cs z$`|I}(RvvvU2k8(#=hh?JRc&xK`p%g$vAwr8w~=~x5l(1_)P9G^oxZIf&2e`|7d_x zH~q>7cyj0X6^o41jinp`zW?$O>3Hj1!nN9vFHW*%I$mi4*`x9MCqNTF*lTvJgbZ&2 zsW^^xeAbdOS@IiIw!2cCF&hsnoDSiB(8!dPu!@YyM1Poz6Pr(fxu{%rvY0C+4IMlt ztfQJ)ZWeVDY-w^{-NfVK9T}5MXPwY9=%u}*7GWCS7J7GgTACM~#NRgAzKwT&(o2xo z;*-|PQo%FOurQ1nW36S?lSop=E4}#TglI9Sc?t@UO;d||_M95d#0S(F%5NRrt4hQU zqdV{cFBEwtsLc4$h*+ukfcmDXaoV25RT|J~cp+JL=f#_|34}%ir1%fZQ?>H3l<5WX z_h^^llZ!hZUtdQQ#s^rzLQLPCPo{LaU;DcXPxjFIYT2*z7!v#7b~5}+ZZCi~L3!Bs zR?CWLwn^G*)B05sp4+MQP~yx3Mb`)MXMXpQG|&rwmKoZRbvoGGXdhs30DEuPY5w1U zd9o4O6tRE2;cV&;^C8U&%Z@9EDeLPi)?nAQA%n{|jD^jdFIWBKsp5gce*eggS`jd| zsdIt~ZsYhO$yPtt$reLJzaLMR9Y**wT{2oQQZDhv(@8uZ;vw+xojIAV*Tl}(d4cygC2TB(nP3bO2Y~E$U~%he@9vr z`&^Y22#&%PCBAr*gZ+*0n;KSF_6|Vz-y1K!^v8RX^iJ&PjobDwFgH^0sYe?fgfr2fk*c+m|*Om*#J3gyiQglEiuk{v~~U{j(vLllps;q*tjVO5$pNN`O9{c8Y`CBJ?ypPJ%$*!4Qw_jfWrCkJ` zB{xK~9a~D9dpD+$;qMjia)ZkR;0=+hagj00#UBb>d}8v3ug`vubH9%f4N}b4!CaA7 z?9w-#*N59E6i@x^!C6bZ>uQ#GR4rAO5mwq2=4L6SKs*tBVBkH=hn|YTX!or3w0mOe zaoZXdl?MK>IqwafBUTQb7bxlK@=Bx{j`iCR#MAoUPccRv)OhEbNcmLG=$mqI1jnv2 zWA9`|M(}jK`b_mgTWs}BiFc{AkPWb#_57G`$&Rjv0QK|LVW)ozm4@BqzgpzBz0ORW z`L;DhIvPOKOh`Q?dgsy$fYGayW(N)bj!+&v{P zmh@ZW>&r{J7yEW^9%3?@Jm!BlDcUrl-A>Z6dxOV%`App&+;u&6S2C{azdq(NAFYgT zb$Xpv7IEJEarTUB+Vcg_8QHJ@p1m}QC(<9outk|IG|B-N*wE|OLXex*3C;cG{CK_X z2=DYS;k7|Se_b`XokTVu(T(L221k5|Y-Dp^zeI1QJ>4!uzo0g@ZV z`LTH>_Bix6WnO_&$hO&CjC5VFFEfon4rhttZ&m@8vJXp~#JxM3y$W=@CRS9!8}uU! zJ;p^99j)P`nw zqY|r4ZEkt@M9d9@zFThbS~|5cApS13#dEdiNk{(Q)E~Z^CpVg7)t0}1d0o?edEkY~ z*}Z2mtEVqNG*SQOzyEB7QGp3f%+dfB#`3Cv(x;5_n5XSv(wV39x0Pq7bok}Z{_Ytc z6ehx)heWK^=Y~X`?VN|jkFQzf>1VLoA((6wgN2R7k@&I6@8hkoG@cHAGz)i{g1tm3 z4qIO}}ynW^n?)VDuYrD!x*`@u&V{S5i#@{%Le;z*5hvAE zGHh*IRFWnom6W%$Ck2%JTsE1HO30$(F5^lVyQ*CZn;!_y#|_>}pP(QD zg9RvK)J~`pqKa?D6ahChQbZ6#@}d;0LJQ2Q4?{fx-GWrb!qSs1owbx4sCtKS5Wnu& zN>v_YibXxhRBz)BU;PxDGW_sEHP@l{%lsF`lBQ8x$KB7ZUqFw(H-9mKdOe+#Hv3+C zQ|PMC(6#$}w=Xm)a{rEnl*QnUF{>ozGP9q|!lR z9(Xg5xElmxr|Syg1tRnb3wF?T7@ZHgt3H+{Ag0=hu@bhyyE$p4iZ7lpLKHb={w$)- zXF-@^^NxxJ_`fE?HYX1Dex!f-oBlPu!BR@qt!amctRE~r9j&e)Dasox@kLvDkqfrn z7CfMCldekQ=w_y^w0(RO{$Y^bpOfOndp@4T#DXCrR zJPs_O7CagSDxXYH*OO__4U^Xf%&;vL%0!40B+>HxtaVV&rZ^C0&PTt?6mZzjJ2f(& zu7(cek3bE~O|kWLZ}CQ2FOY-^**V{%M^Cz+V_xdeGidvp8I#I4axS32=$~HFsrLQ+ z#m$<^rkK&=?*m__G!DwW(;qEvt@WjSUKZ^8yD15=VQZ#V37*oPk=bd>IC}5`)033W zC%@FqK4v<0G$!`SwdY@zSi6B4b9tgx`nw_`*tYu^ft^GP)xs-9UvVj&4?VQ%e$u`{u`1^N%}z4w*Ud$$+56V|)jJB1>wd54Ed7M)ssUH9 zl9RHjNR*2}L6P~RhK6G*Ll@;Kl%LW*E}wL^s!`h13H|$Jk7@P6dgy+XBp+YVA}vQ{ zCkGk9({^24P~aEB*^CD>P+8HYTu{1v7t1S9Eo-4d`LwK5y(!Slau=f{gU&{@7axHZ zK))h|eAvdIm)v2ExH7>Io zwG6%5e%LYAmPi}H=wVfOEYG~}i`YOzoY>XwQH@q@Hcwac^aqo-fv*$eMDF>nV2{5l z@Okm3OOrZf-_6~&&?qdk^XFEJzaIvh;6n0a2>EjRkj!H%1uxHre7W}b+s8}1ve=7b z5fDAyxcsCo6Zs|~h*i{E;f$|*Yl_y^_Jv5O4-Ehd_exfG>W8X3nZor?fkLWj1V>p0 zB7z2p@VUZ|M>iSuH`NQ-vwq4}&%tF83TS3=KBn+MnJCA;1Wn;uS?#*8@)PRN$0^sl z_!}+%s$5dbYpS*^mo^UsHlR}AQ_0eWQmk5?>?U3~b@u85h;EvlF_!<=Nzsd?Bm@JW z?vTVFMg9$8dfhGY@ZTPYU2XH-1b8YDHstoE7!vIeY;U7>MM@d-Ze-TUzQyVxRTG_T zyA{EJ(sfDAKB}S-`r9-GsU!713im)-FT`-9V9Y1XK)BRSM)}<6xW`a%(W;l#MVqi3 zsgXr39u(JbTMDpw?sX^aCvdoJoezu(xznh_VA-${&v8>zLJ7IvzmV3?4Ip(g(6~Fg$_->Ez2~Iz^?pWo{Vv_<`G>hN-G_sJkjw^n*$FI>%5agr> zia~@y%G7=VdD>%9v5&mt3p@}H*h2(`Yxk_?I=?ZYq3rbSbFiM5mAHAj+*$4@x{|`L z%5lDxreE{QcG^O~WuB)#+X*Nl*2rT)uz2lAduKj&y;L)iMc$&(Iw<@m|CWufMCBgt zngwG^hBY>a6>a>Q#oA`8gr5f^&T5kHSVn|L>>NcBo6h6dpGkFbCsmxQpzZ+PoOdS5 z5}lB^@0so9p3F4iSe zZ+aJ}C290nR+R)h3q=i-6eCMAc;mb1@lzPNy_2V>=yC&ra%+KdQ-N|~!mmQ&z>#e7 z?<$CKeuCxO3b)Ke>G%9}TvC+PfLp7z4`D!)X1%)u*o%DQg&vB{2f3^R^ZD(@woQ8Ql&;IXZVbx?FihF-uyolK!_ zvWo6Sc1}~X&gGi5$l?0vU92TRNSNh8t+^AS;Hj?E2z>>fnbQ1IO})MiDvi)MBplyh zW+FD_5rJaXbKXj)9-rU*oWAMP1wxw8ebKzP$^m|Uyb?nSWj6!b3~re4*)ps6m&l(EK*S&P~L&;tpn8>gap zB_KcvDsPz&otPXLuQ?^BDPZ#Ye^eTjs{o;15~-19~=3$*yl7E=YUtxyKIC?`-X>`s z!UBc6R7CylXtXKFwhbNe?*IkdsPzl~%Hyf?@pB)RV`DBG2k92x1|V{R0;sqdI{`G> zi1nJ4PfeJm9SNU={dT?=_YU@y1BaZxH$}ZSvra5POYU8MsmU(2L82C?|NA*DiFZP= zcCf#uB`yW}%f@xPsStkOevazEU7(kyj}u%zW0_ef0KY^V2Gvm|kwTYlB=)uT%QXrp zd$v)QHVl}$*2SHV^k=vURLcxP;*0>KqR{4si)zX`AOmqWPFbzy0H<~nHyEG^^`yS7 zcN%h8xAjm@)u-{ze&*<}+at5l1N`;(N9$l;uy5iFY|IU8c<%f@eGXr({hv#XCYDci zeV4~#cV<@i<=(D`&7K*Q?}b&3esgWDLk&8}QS-|?JmZNeSRb#3(>Lp-l^cf)T@_bfJ!4@fLsDH{%Wt}pA44D3MJEQbKsSIExlR=d1 zpdWUEh$r-mcWp@D3RGrxQU-Zt6I_&+Hk7aGM;0etdmmVF`fy8wq&U5$;BHY0hg4MT z2H4uxeP00~Giot20QM+g$Pnbgv7@M`@?-Fk0T$wYwMI#mp*$qdmZZ+ z7r=;yMHnxsKaGwwZgabMkv-kptjh6uH;*X{wMoW*7oko{;s~c{bHYm)^5_&`|76m#Ra%FgmnwkmyXwSP}1KP!oEl!mFLzQs_yRTI-0n@tIyy4 zzNPu?D;6sGvC|=6Nl?#332956@`AfJIcu|_O|@f+=QE5rU!Y$DkGz>eAo~#rjL80! zcU)q+9o|Qbh@fGas#?C(2;Y)wUlWWdTjhBAq*+CcH>O4M+8yo-j-I?Ni{*ueS)UG;w3tthGCdi5+iu= zzf`)S%0A{7T=I84P7P)5IDblgv04O(0*qQ_VPrZmsEAUTwtgAJjC5<2^b|(+kVZ^$ z0nxqWngeBXjk5|&nof)f+wogf8$x7m*+jmrT(`Ck%d{>;fO zdkY4yfb#Je?e0bByS#Dy`O_dESYMw6P#u7O`RqFFg#CTLP($>c z(pe$bSNTFZ?LW5mpxz3bcs=`!GbfBX-n#?Q)TtTI3!urxF)6J!y)37bf8JO~{Kg!y z3rq_1Rz_AG9KM!4tUigIxx#Ez%;?(1cZZ7Rdd_ua9Pdtp<}auvJFDM9LuMVOms&9%==5g>7^Gf>us*yR`MD0z%NAcqcboOYXT2Zr8|@Bnqa`WTx?8 zdD_3HM>NsgPM=N10K#ACNC+wO9;}FPRt+H3MSpe*o_rGy`x-%26U^8kWbd5vD^>LO zilbsOTu&>yyGXjZpj3^q2C`xH*5>fqG(IPDgSB247Zlznu9J>RBFcnF%XIQe%n&yY z$;*pf4NrI*mxyxd#7vWvi)2PXv`S*dNL1XuJ!kw{2 z2UpQEugX7yzHNd8s7Fg|E0aJ(!!u`_lQw65!kG215j1zCw$^M3RzfQ|WI+Ln)P4}L zAs#{Zu5>>dO7E`gffjP0^^&V))2JL~&sjdrYRI2B;UDbm+x789|EAnIt9W8AacTFi zjEa&zQ4}Yk_DlUu8_Q-1I{0sHi((=5Sx9;$#25}v=#n+${-;y;LYOX9iatomfl+f{ zY;=aC>3}OT&H*Wa3?Z;p6hWi?fg1#~^3uauj;C&|XGec#f3IN$N?LZ9jzMM6>xI)Z z?hs{!_#18$GtZ$|nI+1ZrLtVQ>_DI_yJRfUtm#M9k@a=UR9Yfgs97euSveXKKC0UE z=WK|kU3)r+pq`AUL8lXju8*c18eKCu2Q%i*i+tgiL)yL>uHRDW6MawKZ_65_b?Dpb zIfjKPrJRAwd^}jZ?3%InJJt1Xsmy#zI4#8Q%^9hP4@ao}T1wB|;fkqsw+{eD zPhr`tx^ShKKWsEYmS`AxHp$mt`Sg>dv)(?9*^e^@y8KxgCd30#zt5*!A{F1(&rwg9 z+{Z%Ec`X&9sJ9la>K_8K=QLVZO`hj2RLm_v!HJic$T^rcE9zgINTc-NPuebh;=;vI zb^V9OZwS7c0%vIQfT36pB!K{tjyytacodm)B>v>nsFMftgh=dH!W{Kp(mGZ_9wkJM zvpIMvah^cMY-*W>@sdilgSe>z>55KX8eSmgw_T8W;Ltz!S>LdRxuxbo{i*P@It{P3 z=>A?%&4}PL!+;i_o;wnnVFn?uM(7Wkgw~AD|4#k=M?k-Ewu+o1eLP#gX}-?xn#uFG znJh#Txf#iO`fg_ak>eMWUvDg_LEFqGstFsf)Uze<9tVD2{hR3^2~~&1;|16uC_^9RPah$AOH-LH=&F$b8mdpHr$WZ6L6q z=Qhg51ZCt(=}{MHn6!~RNu$M=P95nPg})r%7^M`}S|4`N)>4Q_3uG%~fQ89Il~S+_ zu|hPKCH9$$L0Ym{=xkX=6*ikZfXTd!zzX2lvNbuH!b_VuT6c#Sw(5t8#lx)W{}YQH zVbm_SUG#^J^9@lu?JA(CgIf=|#1RMNPWMg==jb)v=Y}KT;d|*O>6~dcrcdO}O z-nRKjKSM-)kcTf<^S(r0XgbBP^JN@7X32rpyG$=UzV6{H^QU*WY zQ!JPE_WFT%TjYgnaSJ?ra4kIDh*tzrHHgTp<~>mp_C8MKZ`F&(k&V}dwEwF=7Hy+q z6-ab{y3I7qC@9FLlIhJ8EDIrH1aNZ#-A0hmi3&vIG)`a!<0u*s1_3zItk5ovJsn&OMJ?p_m$PgMD&!TK(N;kTQr~D=S^UEj5 ztM4=45umz8#L<<0#0Wz@fB=e5K@GX^jEF@L_|P2Mh(3*uprC=JB4rae*A6%brYo9E z3$5TYY->L>_I%;1)Iq)W$jgT3)I&~E_Gvq78Nl1t(=obEhVx?o3=%+PZA2dpcvOW|%gO{b35?EdfNRBon@S%|86Xh|u+{)w|jWxht=Py=We6 z_s_}BIq6mwW~b;;aX}y)ENzW}vm1(vIM?`_o9Yv1shOgr8Wvp;d%6fj8DlD&PlFph z?K6@KKc0475lwhV1If3FAf?}pU({*Q*Csh+h%K=sosCa9jyNP_n4`>(YKmlgyVLud zvtWM83+PZrBR{U&3Kf7$?PR+1x%=a#9g-dtb9hg|>{6-~V-OloZ89E>Vlp5))XM}s zGxrH)^6%qp8lSaO>BidM4h`W?#6J_`9VX7$IVzF|TkZ-UiQ%rA0)4jFXtDTo)|k?k z)E>4xk<+7lBjaNRcS_ORpY#RRO()cwNazw9u%wEfv23(Uam)dP@8viX+dqg`eUqiq zCQUg{Qi;yjQlRj^yC1A)5K%k!>e09Q7l2kIm zrd-y{fXU!H-x&r4mR9A5IW1Itq7oy5WcR9c%GYW-#)2B#cEdP-RL)aNJq9I+T zt&W?jug#_tEe!;!+LoUs`D>djC3Z`JZN;3J_!3#@rvGry<2-QQnSG7OuiWZWujTV!oshr-v z*rLzAovkgl6o=@2?aA?JwO;CIff*P;mU|Z8E4@mKR8Jl(3#QrhHJjDIjb46V{@VEY z>LplA5r;ttwed6lQnC#kWSW5i3gKGd!6G3IxCHy(+2##plb89=3M*0uDc4=Xfu4Q4RFt}uZoZv$xa_4Q zz@Fqqw)n`ygSVxP@eNY%t|aNR7il+B({TVC0-}!*17P8PGVfxtT^fgx9kdfKYfM(M z;k5$+IGB6ZkcC+Y??uXWUl-j~CfjoQcJ~)Qn?cyl+Hxg!*R3uo+%aSqW-n2NUVGnu zA%(+hn8J9 z#-$IY>R`TLb9?D~Z|p7^8(6NkH&qRZ-XEDA?KXxlQeD2i@IAe*V)C>V&2jC~ry-p8 zhOY9`Q`X^@YbINGx)OV&>Bh`DBlG;sTu_)x9oH-Pb1P~MM=T{xFxxm&!}?zX)BD%I zwO&SCOb7h7*vZZQ3nD+8R5lXs-UMNANS~KQMo85>Xmt4s!XZNGiB4i3_K5i0@H@~w zZqxr!BTDGpu<~3oAaEe0B0|E(V;O)}UrW;qTj3VIvlpV1y1g1obRvC*$$owh`~5xS(31rBsdSqikpe~v`vJaZ_Z(09*I-d>N`S+Wg)v~ zMRy=#EyZFQpQAq2TN8Z6b?vl&6~_IRBw4YO)+8kU>|Q#;p4;z&#Kzft*wUH#0%$oy z#^>X$-%73<2){oDDMbrApN~458G!+IMl|r{9|`%fb_TPFrimAC`zD@n1l+RoPvIq) zMC%XQu&pxK;(`bZ^GM2g0M=HNDW2_REix@ANupaOJW*fLKS?Y`UmTc{k{Fb_j9!Um z@##TVC868sEGmTtwC7G)i3VBAtiNYddnvh(RybU#hCf8F^zd+31adRgT?yI(%Mo07 zh#)y{Abi*;Hvx3-7Ef{wumH+S(gX4_PJyd9Wl0W`N+_QY5y(yu?6tl5!bhs%o7wev z^_b5p>-HcBMLm32*yepVX}OzURX>N!F_+Y}XjYxNLdy$KOhixq=PB0Cmh<<5)$yX*Z><&x=q`p}NJ z6+yzzPQq1Mf=fESy`2Z$Q_67I| zf~Ci*4UT4NV5-I!l`UXI;IDaxD!*{ogX0QFBPR6HI}f1L zZyKf>N>Z58>mSsG!}WF5sFElR$>S~abY%%M8;PG|o*R4T5Z?TUYo#7%%!LeU-3=*>qa&17S1hUuWpxYQhGIK2Q*kE-a%RLj8+N|J? zU#N(N%AU~s`rWMhRK>C}=c{T}Axe2V#5`~s-X%UXrqE^lHV-%0bx9g1V8Hu2Icz}+ z_;BphRfrC}J*P~w73@_4-W|L_Pq@2d?)Txl?$!CokKb+BOV#)JrRwT+KS@iqVx`1w zi1)v#?Do2S;iX+1j@;vsQj@%Zhxwfs0h=a)rHmzomoGU4mp=CMv0N!RtQUK$D%MTM zKmhPGZ?AL7UX+Ds$zb@%Vy%1&oW)l&hX8*?N0ye!bj&+EW5_-|Q}xnBdjUu}b|{ud ztP3Efs*LQ!bW7j!<{7s(e|OHpS6nmcjN<9AYw=m@f&93YAgnGyDxyOieP`lqqV2&R z6^%`tx+(x5hA50k0CUlW4+|4i0YDxM@SM@@IMdsP>WRk&(q!|CDef0-8!slGy2zx2 zN$1-6YkQ;an6sxC%e$+wQ=g-0Ih1>v?Cm0ftI=gr{)BvZHZ+}5>Ru6_i7s+Z*`Omg zi0FZ6mJM(8A{~9OnX(Q_%~G%Ilwq02pz{*%Kf3?;Er{#cS$(!Uq)MGzUIhQ#)g^ik z6kUj)Y7XTpR=UFGdX3Q-{sLZrydWwyQ2qM zG7t_pjND`cH>nE0d;g$)Dg2A8)W)0;7ghI4{M{eC^k5b9+3%qE&kvLtDiJDDAF^!r zV&Xsg_@c`sP`PKTk2VLc!-@}jDBj)v1p$H~+X3+1fTDAiMPgy_Q-z7MBp6n4l6e5% zyn<VM4NZIR6zAmV==lxhjwlHNAXMM7MIMn(^u3oFqEiy z4jXfTEv_lWIOE zN^&Iy+Su7S*=a{Z8eaF+PoPWt^jD~kH81o%N}J-x`fj}_Blebw7WUn0L8m6_7r#Zn znMK#%XMapbZ!jv9I9bL4spq#)_e>sl@}l=UAGdv&G{J^^W`{g{1s+6(_MdloX5s>` z}JPMt#w*Ntvicf0u6HWvV4${4dXQzvuR^;%9pLv5 zNh+d?_OE;6=7*=X;?H)K8b6Oyq2nGe)e1h`x`PKqEZZ|?Gu6Mmc)G2mn>^G5uk7JC zlyHxYy6Ak4cR>8_vKX;WOkY+^USF%7z`VN$KX*c6{!AK4hfA(R7j#*&e)i(%MfZyg zzto@SvqiGlc4>uZ)rrO0;$!9P#F`DD+a)Ci6zltS-uUxSfe+poNpT~6agHW&^Jt$T zu?Clv!q0^X-t6a`bfW$n5DtUuHmQy^?Mm*ZNnH*BzZ(YYV*KezI3KITgy!ddy*N8{ z>5yywH$}@*;S^ly?R>HfR<9yuzpvnhqw6SI>eN3)WUl$FXdqkPR4T|$5^APAE-Mv8 ztPjV`9uiSFPUujFuYUhGv5qz8S%&Z(@!6KXPw$nYVBbL#7&Ye=>7CEIAK2~6URNa zJ502U7C0{cZ?Pz8z2RmNTvW}Ivy@*?j@333nz=9i-sgtyf~fV zIRH4=W+myiEDHn$2clk&SiOP7p7x29D1EN$#v}hWY`1r5X$Wa|?3}~DiV|F{*Gv+} zASH(5B>2o~9vGhg8tChmYU4R+9-P|9zbCcscfk(?RG@)v6%-w9dnuy#4421}uGkkU zOGjD3a*CECZo^{a`Xs(3XcHl~r1}d4`csw>;gRFyKV>!A?DAn1>$8X)S@u#7$I_~x z+_tjPsg*SXy77L+0Wsx(j$Wp+EQ&U*(20=G^#{lt^V3t_0z{TB*mTq zXIoBugY|%XH0VV#P>ONod9Tsg{_FGGp)<0^vLddWc;nZmzy)XC;=w1IWv&Z<1ctZx zo`2_`NVxvl!*AW*@87?tpkwDuuUz5jIAJDa)JLS>@|UNdrqly@g;VwYkmkf~wokjq zHk^C$0ihp5+;%-4>v*JqouxAdhyQsvQrH`pZbuX&+goq!B1L~9Ohw>ngdy?64(JLH-yDZ%XdA_RdOvA4I$ErspR(acM+us@rt3MCgk?$?h@r43d zeC$^1Ph!sf=<&NgpWTRq4LUP%YefS;7%0ZC;(h@1~@vqQV@|+@C12t4K2QfF5>CWY(=+= z^yh?C&>o{rPwB6cBH1%=DQ}2P4SncAYQ^m&mUmQ^0|NSpo+2L;9G)>r;YN?+4{Gxt z---PB$ep#z<3*d0(Qp~}=vrP@0x-^pCvwY(izDC9aEb^7iKPMOde4^h{H00W{6W>p z4plL{$Ld_c&(H^7CL>p7B;Rl7s1W^dnGb#Vb$Jr#Og-^)MxWk(vRT{k;N0^Fuf5LE zBe|tw>x0sb2IE*{&TAKpy3Y%L(L2xJ&|!P5%?8`#%oR)fVkH1S6VoDpT!cfSynbF5 z;Y4pq!Z8^rtc(LyMARr9692kK)*T-)*ctNPD6g#DYe*Tv0sF9|c)90l{?~7l%VzG~ z(bcDUMzWJ~ZVpZ3wZ2BTXj^y^1)@8%<32Y%$&_FuY_eFdga(HH#k zj!~TP9i8s0zZM?^{j>4+%E|HG%X^pqIlcDh=eK{O{`nV<5lNoi%KCpIRQT$dg7lP= zJG>@?%Y{IKa$9TE=yN&I&frjWh>rnU6|M(HTwoAEEEhJtjab!>&OD;{GVe5A?RN~Y zfHp7iIlDP;4H;pMA*Hj+P-;NzftZ?1Cc|Vs2;W+&MJB&Ly%WakZ;E`uPyf&YB zFPaUNmFjd0m9DR#*5ag1qHTQdi@;Btvu zQO!r(lI6jNs`si}kE9pG6{@%AEvi%XbM74qA?~*}^&e(Pd=;|DelP`kA;*6RdOxcW zl02w@k2=$(K8*+H!-Xg(x$tK&?GO0b*_EjsRpmHT$As|jvb+LaSQ}i0S0IHhL^sXS zSg?$i=czMbn)=QKcuR0fF4A$kzz8my;}aHY(Wk#;s` zq_3Te9vH0$Cy_D6i)WCpQ@0M7S0y-x%&pBJm)dn78(c5zXfM3J!#*FZcqfp0|o@rh?KO3rCjV}tr|yB*bqs$tCy!gKY;g`0^CgW`R7 z*2*}RC8k7*zwRnbb+Rt+OT9_teg6Pi&!6VM7R3l4Q7XxX)(dq7M00jh5!Q4vhYkZI z?d?HP1&}eCERb{XL5N)mi7R9V%tvF(Z~R%y;!iN)!wkahq{!?TvxJsh5_}`R5iw4H zxRMzkC?<_Pt$T^#w#eIvQMx|!1G$l%vxb6{?iMh|5-cHn+%$44O*G#6Dx%4wTS{lO zW=~e#1;o)j^q>tNAZ>key2X)5DY0<$LFg2Mtb^H$o$FN_uq3ElJQn2wiN?Z~dAps}DgsOHMYCb(Ly6 z4N5#d=-(0`Y=U$E7z}>dh=Ic9r87^Daqg5WtHYGAuLm*4-}#E0r<8oZu3*RnfLSCs zbPDS~Qx(VJWm=?hF-%_Fi9>bUe^_9^+bsmP%70H!O6%KIGc!akbaqf$8{M{Bt|h#4iMm=>Sl9f7;N>0*F6iZL(ViAjzo64_(# z#SFr<@ycL*wlI+&_OYy3<6BuVK|ZK7u|FzYa*bN-(mO*uz1~~$HuLiCXFU;xL9<7v zt#oNuRZaVXWlmPvrMYvHxzcv4=Inrn5GjbO&*cLI2j&}>K31JR^!^Ab0w4ju5q!Ds zyYN2i>%gWrc9u)<3F>l_s78|hGGgk2P(R*@LjrkJqCL9$iQx9pcEMu}CTz%Sv~H(U zusSkxreZj^xmjIknZTrW769{d`ON?S_%4veKU#`^mUnNUU@OnhvR7yITjaC9f1_N4 z^?Wb(F<7VGgU^`;>&wkbWUe5mMjAFDoFcXeJB+4(<|ddGR|un({}b%hWmNIlmRVw9TDWn(59s~}cvPw!-mu!pr&%3&G<3@8D-dj!*!n5D zbbgUL zf3y)`5EW>g?mE@ca<);1Wj^cIPTyuKNRd&U33B}t8nJyrk2TVNXt136?KC=;%O zHJ}~@*c9s(UPa+PK)N6G+0RO@J^&Y{iX&JNxkAl-&)|RqeYF}{acpNFom^W0)=dD4 zLF6G7@(mV-u>+YgLg#)KE@DYyY$Sv?eyN$Rf-UA-=-8GX64ut=5G#BAx?cjL^;&zV z6NlXRT`fQ*N&Ds|=ST?_-^-Yzzxk=TGg#EWqSYm0fVJmspGAlduUj}ZUYTPfUlgl)C1b;D0Q^-j%w^Oo*Q_t3J zQ&6J~x!Id62~cZ^20hqBJn$1;ljU81e5O}JQuKf>xjl0F7xJ*ETx_1!(9?W2)N`EJ zOVNjgG36e)L{T{UWy^)I5;<`j`9N8PctTcfO@(;{|29scsU~yVmlArVZ7DWCf=YX9 z)AlQE9rq%#>)58GXXpmXW73b{F8N!{8wBT6%ICIQ<4ETn-Hmk38=61cKUsEp0l;*|jAq`0S zZGV(H&p@@!oLo?uDO+u$&AIzWSgI&u!Tr9B#_hA~i-U97g==5954{~L?Rk=U(V9Hh!_1baTJ2En*h7Jf2ydP06Ag`p0my#&X*OGcS*Gd(&=Fo1kr?-JJT& zy5jeHRGO>cPo9WB8K@dHPdR7Nb^pJvZMvj3K{8)=eVv;3u%Rrdj5pCflE3zv4!WTkGS) z)c03lp&}Q5TxDruK5aJxU98`F8po(eq_G^}nbK96;`%b3TulE~c~{Hv=&J?7mb##~1Pi=CYDGyZ{ZSQV^ib@V+jsG-%WI z2u7I;bBY*c@8@>IcR%ccIyOKnDA3tTto2;Bb39LP4v(;Yr`guD=^PK1{NzS+6B%2g z!`7;o0uTzemScaAb3lSqd2^3*cj{V)nwAe=^vrDYzT7tU=RifNp`y_Fha%0iOa`HrZfu-^rtD~5fuTH^gcV4B`TTo8^c^CSY}zs zakVhGmW`RgHZvh9bRY?NJ%`1T5Wz*|_EP7~?%+QZ?PMb}j+MHC^;>j?+eNHbk7ZA7 z1~L}hJ&RgvVfs1jxz}rSiG1gzjf79YlA(tjYV}Lv_9}kzWln5MhK5PN~_=zjf z&-qqpk-t6K22i8_=6S%8+iHmvywWpTL;&(pgFe;@mo1B8Om;ZXL*v%UzUBGZfS224 z!@O-D7MGu5@)Re5$-zusgsjA-`UC3CgW!xC35I7+heQYGcl7#q@bzt()AoJJ#c;Noq!`#DXv6^iLJUFgR)!>3cwtq1Azx2nu`CI7R2VG^6dc=oZAG~)o%rViq>ZupzuD}7u_si!_8K+f69+xv0eNo>22nR zu*0T{@s)gE(E~TC`Mz8Ao^>VLL(V5|iYFXhbk@iW8b5!KGwUCn>7VQpNX&${duQJX z{=3PPy19Z(#$?uEILE130;{9UBvv4a%XF1vS%W)Zi)+dZkfv9@)QIRS6cQo{T*t#@ zrPd1Xa3hCRx7ON>)@mI~+Tc4~5_fIh^N54APbD^QcQA6czshEi+~gFjKl_wOG=x6z z=6u|QlcbZpU}~aqx>s#;S{V1mMRLS{$UCcdtF9VVS){(D*+Z~k{jDi^*ddPSG#W&x8NI%429nUa z>+@CizIDlc>JuKknq-6db?Ljx8Edk}hfSqVY>;Z=StXa3aOe6x>*yst{L*)+%(ABU zALL};;tk-amANQpnL8e~OlXOZ7>Ox<_5Ddy>sH29<6dKbmUq$od(;sP6&5S2fkx1@ z4;<_8Gvj7c%gc{6=e~@v)4>dPT85j*DBHG7XKGD3Ub?4qSl}>Q64NZSX4R0K^KEsn z`=jR*b~VT1>J6t>+JtRYGR>( za-a19#3@XztC@emn~B~dR~1Z6#N*>=nXP;_-=^LI^PgXD_&44p>sa2@QrYG-u{UA! z-y|^8r{M7`ey{`cBglCM^iniaL3H}P;Q!vac&1W0%BX0_R;8YuI2GQ8(&KzDFZ0wqjZn_A6NhQn z2qSUaPTQ!?T4Chrmb|?h7gCKg?g9MEKP8B(Ddcb23HMg8$>m0c6-!!q85&ZfZM8ao z*)rW2l#wnG-)Q*oZ?Pt`EKk$kVU}knZTyMhhM}_0jCWxxHu>Wl=65lRvf%tJ$`6H1gZh3fm{H8t$w?g)0iiKyzz?ouCo?Wqr z9aOkb?wqdtZ>Vu8`Bzr-^`kWR3hJ{*R4(`&YBicT3(x~o$Res&0mob5tPHeD^d{8@ zeAb5&4u40)8f4uRHO@QHAVbX9SbZrNHa`gzo3b~f30pjtQODDxKU*cCSo84?S zJlkv5NzsZKO3yClF)z~M`vnS~m$>95=n0C?c91mg(K0$rXtI&8?^0&IvS{YoXqa^& z1M%%F*<^KRvszgqdqdK`-qg%a!kkOo(ciU3)Z$pq{bAr%PQrUfc@O&4zlVENyx^8Q zbyxQsycM>y9#*E{{e%+n>08)i`p0K7uRiaco!B4m^&PFvc;VFgyen{`!srD;e#D`5 z^OA1^;)e9~dna5go>t-{XLd7*ty}gX9p8#CDb5}ZfiVEUATxLO>=5+gA9@W70dQQy zVwi_Z#~4yg4cUwgZPK%4Yk_qb0~*$lO{rp~HcytNV>?G?Ex9(w@GIRwY2PJoT6@3S z&q`~bu~1+9pa;wvX{jvj9==~z=cawIx$mZJ>BQU^cH{zPE&4=1n9q@?A^ zJ{PRZQ=SqBqg8I4mQN|)_+D2~lOK!Z&)-~MZ0B}1byM%Zq^omEn*||o zbm9=RToZMOS-PG!h-kK>0ioEd7?3_vsoMr7?2RWeak$2Z!8rUy^kKc`Hu`i4iVcu? zdYyraM*SeXxa)lHRwm2LV*N0`qF$6()%3>E z{B-CB?G{>n!++R9eJ%Kl2Ywi$@@9zvS3xP2FNvb?jH}K_{OMLk5>l?HI%~tPV+xeC z?l4=s;_I{$1oi&y=+WVI)#})AGg-HglY?3E*uiaE>x8@mLIFrnoJX`C^5PLy6NAZv zi{{*YZ!^Mjv7OhSP3G2yUx5*-V;G~}`Dy!IW0!S$w*K1FG#2{NP(bmK$Ii{tPwS|c z+UAYLfnm#6e+Jw>|3g7iYafEXG_&PV7pS$x;JB&1MF*c*Q60e6YU4UzPljX!qoK0E#W<)4f7e+97y@)~+bmuNDVhz*pV;0V{Jf)L&2*!DFpeGMXz zHQL*m>nsK%NiSrM-*gg#J26R$fY_@r8B&~sNSjm9vr0TNldVV(9k|&iunv%Y^D7%2 zNiD588IkkSv>967Q;<|0l>J)!%C2HQ{a)F7X+;}^eXw^QDP+$hq?yNkMom%TPA<$Y z9dRZiN*~e{Oko*Deq{EbyHGQ}?9^e(_eKhN^l1BbA6`!Sr}_FL z1{W5N+61n3GY~qXY1~Id1F?CarY+<&UAQdR^kTm!oBrF{L>8Zf)+>cN7H{kLs@oHL zRqnCS8M#SK6a34Y>?QN{lJB2@gWy*7rLpRgp&mOHPGlxER0WG{xu02RDwFoQ4~s^I zpU@5gra>iL@Na#2>2vPgKew>BK)JMYrC?R(-lg(TY{j&cHzjO4hiUkEQ(X{=GE#0<`S3t>Od2LVkuwj*=R zw`SfsQ}#v`tZXE`e>o|g`nlDVea?1YU*RZsqdnxtr9oxu>d>2v?;#B}V>86eF4BIh zTA?MARu!k}25nei#gu75>rq!^8BAlGR1xFm)Z>|)Nlh1rt)?HFcZKYSGpGRpUbZie zj|z1k9=Tj;I=a)p6rtpRZ}hGwKs8SH6#ok$Uw-E+qAH2iyD7_)E<&>!kMV|bmkDav zVrDSM1g49Cq3qPn&6hPz)pdSzx)HlGd{1Uf?!C9oCPTD1zj+(#iVU&dWFV91V5_4e zoHos$rC`W!)O5S)%Ss1YTvJhyU4ElX^;dn8%UNk1o~5|~nNOhB@o(V|RH`~I5P+e4 zcKgL8emM)Wr+%6*+{Q{8uVQ47RU%VxOGgBM895EN3ugBor)%JWh(6ae!A+V`yyII; zBICZ;&qI_0nVq-D(M_=lhz?hN7rKR)(i=oLPi?n1=4HrcNQhmlo`no=$a==`iIN4U zU-i$cDg5r|8D41!iC=Zhj#UcxJaKbu0uzP3~I7kh=7een?e`PJt z>rhvr&`DBz03FtP@Ml!^k@3TS|LE)VSho3l%{@GR$n+%lQKeih;Q7lT+j1a#Rp5`$ zuTrf}N9FRqGeiE!5}AnQl^atY`>Di7!pSUf%)>Va;rD8VPv8l4Vn5F^rVt@`jgb^P zXew!Qv*^9Zh~Yfx%)HM^>SQ*5@2#YL3o?5%w8TPb1{dkCGK+iSXZdl{D>n;OaD)}B zkFv|s8dADhSj*XvOja&+m%&NDh<_1!S^IU*RDt!kMdC%HC1yhOK3O#y%UsGQMS-kk{^?w}LAVT6F5s^#Y_{l6x4&;1KOuPTpVarZ;v0tX%@)$PGq*{I z-V%$Q(Rqq{nRAf_Pvfqdf`fw~XI3mtI#akJQ=7_H{2B60OHVPw&#z5d9qPYra*B9l zjFR72DEmswieM0i5>@@)96GdxTE8BRPQStu+D+#770p+RIIS{3Yb7RfC+_}+u&<+_ z2Pt`}tJBv6tNuB$YD2S-X@wqzqiR22LEuE24nkA>B=iK3Md6?%v#?Rtsa4~Yl6Boj z3%Z3j3*He5R^VDsidhT+>CA(aY7SQ3;gfXMO88<)Uf5%VcR*MOlFgSzvT z+WTRI6>C%{%{`3Id#`J>^=E^F)AY%SOdYFkh5#yz~2YP1NzzGsy;X za_nlT{Bl*#a7LP}2d7SV=1a?>@~aaHyC}t~;ROIwmxRfGn)&?!=j4)MN**S%Z2n2X zW9p$<6BLtxsx0}A=kn=O$#YiF)Tz`qo-tngAYkT=zCusVQ`5~R3l2!0tKkgTlnAf{ zz*`wm9R~B&oJ{W-(l-Drah;OCLdjdtrB+S!tY`1qUzpp}E*GTKP^eeom_GnW`lZ~q zVJ#Q%$yL^z1lAJzu-X8xHhtLWk%3k{FV|C-UnJHFx*6B?MK#nL`%Z)9>Y7(1u%?KC z$nJ!a_^{F}*3xWsHDm}!s}}yXcNrvEx0nXZm;^R3%2wa#P315#a$xC%_OEZM*o0x> zvvlvJ_7Vb9GSRugkU2T>i zpdV?LN1(b;ww7&c7RkTW*Z`IKcgZ540qJ=vGRG&u7U@(Gr|jVcU{QgMxA{!rGq_Wp zWQ`}k3Rx{m_RqvK$TFJF|LNwd#}A9{O-*+jh`+J??y(rDJCX0hS!!7nxo$kS>lYPo zhle}I%A5Qb@J}ozOBaz$ zAoG|P0DcX9Q*H=~c|*JrQVg*nLQuR27Y5YkCh3@HC)4o!%`Qc+?B@LX0eqsskoSXO znKp3ZZOOW=R@r#9{S32@T6fuxbTDV<@JU{QX7JvU&)F|==G!kX752=DVV<}3EDVvT zqHvn#JMfbYe)WNrabQnL0}DsKQ=!S4l6?I&XyBd01EGB|q7{IImqN?TMYJU0_N)X40vbFk(8o7;iREJ2=mqZnAQ zkg@M(p>ML~`X9H65|qNgkh+`6inu_+$=wjD*eoY{j=p0QVQ|fyIkKBvI%O=ml^5w^ zpb6tCD-nwgNt=pJTY$e?z(S8bI_{;yZe3K`I&IkVN)7*kJ3||&nrzm!A&E~ zw1fg|`D=>KcJPh~vUD*2%}b_(%$31=mBgAK@R!HwFN@+!X7d|LYs-$p4=OdJHS)l( zn!#pmA-^^!D#t=_Rn->9d$`#x-1@d4FO+v2QPlz8d!#9BKvelZ0h~M=$M%iv|BM=r6 zfI?z~UWeX|nh6cqb3W9x=V$X9acOT8eH;0(_U-=YThPotyQ%VVR+cENTfrE5>y|vE zQjzxj+-ZdId3L)_TeSKgSnRvH`I2+LbnphZtRBLU4C3e4JG z{-#8f*0hymkXJ*=LY*JE{9^t)83ZyfAvkOG#35~}hjh8aDp$h?C)JziTsnnlLNq)@ z=rUX!8Riaz9-G|VpCeXRk=7J8Xa7-Ec_2h&aBFIm#0lRTcY7)W}xXYYVAY(Uw&H=K&#)lpS zZ^fp(Wt-;;XU6IEu=BfOVec{xAHlxi3uMC$mW-!Bo6oO@dvgiW zkD3qtt=J$<;&h4}w2A=+gaUsO^n+%|gWfaM92iuMZA&zy37`IGe2VL|d4j9v#f37% zi>l)iE*QhT%7JW6;;?-SSabYHgK&Vkw5N4-an`8e2cd?eea{4&hRSkyl`-r-w5LK% zJ3B!9Yctzprl#7sW3@J7EilGj`&+|T@cC*Y2usBZLs~^-V7#I*=pDoGS-yV|5`heO zx{ZMI;T@8rvfpF+0yPUc=e)rF4)a(e&!YzUY1$}?dp!QSzcliuK!*QiPFaEM zPh%j{x5A%&1=NS15Pi}*+kKb!zh^Lwy*j?OEb#Gps;BoG8$HD>vf;KqCw^D4m0Pws zufHSj5zu7%gJoZWfLb5uTa#I-_@Z%x%TXS)cKtsWNzC8!Cd5x|zo>8eoyouZesxCw zt^38EMikz}qr|ZXWMHgcVDzhiub{xALhXyY3WIT9Ja<#yEjMX4z&~-;5MON;)^bcI;B%Z+c%w}?MLf`u_60Kp1ol__;&vf|Fnr7CPRz)1HC<0eg()dNwibIC- z!t|9bV^$S5K1|m)U%opj{s+!JZNr0IF9^kk6(x}G4k|udJ zjS9ItnikAoSG&BCmWzh9&HI-I966+K`jl53d~ZBG6pj5jUvYWym5I5Yx1!i({QBEW zg|_nc5#pzVvCwx#xBw>g>IMETbv;hOe>MnVz9M?hZDb){?;h0L(gK6SBADcoWnTn? z70W8sssE;4DCzfFG_u8(fl3@V)W4(;7u64I+khX33d|f$EyS~nNifBHIHxE+AI8-b z>o6@{GtUqf4+`H&teU0+4JJ<9<&%3KsGWQB=ijTlZevGG2}3_QmU3MgNl;TFlO7<~ z4p25)fA7q$9Ye8d`Cw4VQSk7?_@IaF^)l+_ZojsR-6^10as^5taGo_gaeSIh!)i@n z^K%_%FB*L65+@?VY!3oh9;6j*qx3*yU;rkjc|uhb1K1tZWvs& z-<94{oB!yM+$d*=(Y*=D%LaLOz~6yUP6Bgl7ru<%Soyj9VD4=ZPF%Z6%*HoRbYJnYZuK$Yu5S@cdLZz!22=dOdj+_&)aZM4%L$_xGb`4` zmdkIPm6?^BCe-R(IPS>)*l>CHCUd$fO*91@@$IbB$JF0b8G8A79BMe3eOPu{pu_!n zlC<1$rn)@-@i^_(Rm&Y+sfCmmJXNPVP<9O#b^;@~cBJ@Up{Xp_vTKv~(ibMyg30nL zR;ku+M`+eEeb$|iCwy+Co!1yIEdCLM--r9KSZXjT|1&MG(W;8SbV)-)@ECP@Ps1|A z)Ny#3O zUOy74HDqS9H=4q*fyYq1?mml0Zo^|}0rgw6B9FzHAyO8%@V2!hZ5(}8cXZ6`dOy7x zFsrgWcLI3Kvqc%KvD0oTSO|5XJjthf$2YVl5{z zaUf&oBGn-}iYS%osIw_F3UG>af9N~clJS07-lHQFc>mjbF1*W=bhH3>o(tW(z1wGa zKY#5}#KwHX>xXTgT5+$|I?|Y4R%<8kZ+gZBDO71D9k(?EJ-=C@8MoZp5EhhQ5kI@y zs12IiGSZHEINT@@)&Hoy-?MYhSirNpaAwG>8*5zYlZwsc-KR*m-`=_YbM&@b=Rfz6U}+uM9au|GDT@lToj~wMWi8JPly{%W zg6(`JLJ32BZ*5{1u~LEw7^D5C(F`9GA^&AP)vC~C<}9J;MPQK7mzBcqicmsAw{7$| zAH1AgtGUk?gwc{L&oB%Gbm_)8=m6a9-Q z#iC9HfNAPS*-dDzBL=uZE4n2erQ9SU!)Drd*uvXgRFl~rh(wVbV+f-}vI)2LPmP=r{61N92cl0)=6{m68W&N)Q6IzZv~@f zIuxRwq@C$ZBm1|;v?4lvw6xHrl4Ay#j5E4+UxWw7>tStKIO?MM?@#WH@CkJ9ibt{j z!?NP0?VT51$v)ZFu*m>2LT6J1jJBq2k~pmC43MlMf%IbY(ZJ@E@5ctl0H1+`clow?X&Ql})T}&FQQAr=PDE5MPY{{Lx3~$@>?^u< zq6eLtCt6;hkyw)f;Qd49OAq%*%oqtU$5FPOzXnL)CJka`dmAo;N#ms>VP^^kOjvZ9 zXwE21mBHh&=8Km=eaJRX9(u-di$`+3As}8l-k-H)Vp=HS3=#M>B6PaLV8MZTePLvU9LlnHtE|=+T`jRx4g@`@WZjr zao5HhVKno=Zhb>!I?+BkF9&>+{A^zNQ=Ht9(?=~`0BTtpG*{5-+BzGo;x z24Gg7SO8F=qE^0f@$PGUeQuhY?@q4uB-rl@NbI=@c;Fq zXNGj3nZK?WG;UQoYD_rEnAZ%1^4Gxgzhxr!x zi-zV5#5y#7aCZH}?@AQ7{L#7G7?x+qCmOqz?AWZt$amF4Q=|@CmWVK8Py-^v7Q$P} z`j*Yc5VcI}HplX#(p!s#lKTZRtEp~q@6D13j&}=Oa!8KI3QEU|Xa#TA8?IY?rh>yn zYH$n1^Pt64ralOvT5sh2`UoO}H^L`OEd&~r3lg-;gYebHg170RRmxRbA-0-+dzR*! zjWTNfrg`JIa%{e1;z~n-pg*T#cZHca{o3$~Qk3Q!!8v$eKXppkw?V?AZ9rf;Mwwct zVKw2YuK%(EM;Q;uKc<_MJ?Njln62Lt9vJTYGsdF#3BTy?;R%DPbY_;;3m_LTazc1~ zuOKn%gBY79o6vK3P11y-Eh&>4Gm3@1i#NJ&4gzDdyS$?VIlPRQl14fT@^!*Co{eJ7 z&v&NzK&1eT7a1hzVyY~1FGX53qJ8X4bo9?Z&1n?=!juKY67+PbpXT#++c3S~6|=m4 znR>t88o*1n>eM)YWlLV&8NL5F@|u5jr?uE8=PbpD5e19xo%bN%OrE;|Cu`C!ypn9L znfXtl68F0mEodeqwi+mN4l?h;|95lFzU!(S3L*(HVqyOExdKUYdpK*TIzzd0G_+&VHH}S1OyT#|w4T0&r0-2pp&~tw)%U)OO6q||O``{_^T!LVDc`D3r z8?}?(#((!e^o~q?L&D`WA!HR!>yME51=*-i z*(#Kwrv(Qd0Yb^FLmRF+-zR=2?7{MMqUzdpG_Y476ZqO-H^yaGz(vX|eMiT|G>)jK zv$vrA4_-r-(#o7vhKyQ-JGM2E>a2QK^SIFd!*_WTsT|ywrG)#pOvU zyV6^`Kf>$@d1sxXE)Qqfj5J@?TpDv=fW#P}WTsK0H}Yy-1DP?iH@Q7E>F2ui-eGTs z>;e^Zn0HB5y827DMIuLxw%t-Mj;jaaiW}VWx;_zrylcyIHH#7|Z3k~1IN#%?_Q#;b z)(g?b;NV+dx`NID*fYCwI!4SOT?z^t89tXRAw9-a^b_j7ZMH|qldZSeb;KvX8t*`Y z???owpWab-Ydua)U-|cuPHv93zUxm^U5$S7)OzJ98jP5q{qEcP!*_axnZvt4)l%3y z4$TbiB336tbOOiLBaAk@Afe%rX4iH$!YSBY4g@W@xH(Pe8sb6Mg8oq2g-x)?YjNSy z&cQvC>r@-(j%{3BM z4*)dT2H%8ba=ESEMGmSN090ryVwFU1B4qK+xaU^TOQi>qG;FJ1x ztLYeKcxldH48x#tep*$TixNE;gFp^Eqa?tgS#musa>GHO5i{@QAdo2_i?bWl<9`Uc zNX=~P3I)K5_hBF3F`wX6HC~SM{Pxd*fbVif;5D1^@_1U0%%A$)SghIm_P zV}c+cu3&6dQyi@hw0lOMBTz5~;wqOvs_eMfH|2?XlR*%6Sz|G<6C8gRx;SozzBt=a z9++j#_`30~^R=1c+bQbwxcWKSZ7Ee1=9C5$tdR-9(})Oblf2NF6DP3tl_IUb)RQg% z!p#|Ep%r{Zs?aTg?zVoHBy(~tUB|uY#4^UkQKL6lQhOlG!b4f2a}G;+Qt7fw;9V_p z`_vy#5%aV8Uq_lg3)`9~euhO(e!D01waLXY+nM>^VNlD3y~V{m;~F5;#oX-7f#gf( zW|RK#ZGB`QaZpl!nBuD}|7S>CXu#RHLsG9s23t3wD-wd`myeYS0bWopO5TeL-LAS6 z7_8Z;g>6N6&sZi?YZ(RLKoCTZ0dX50EiJB78D;Y#O^&{2!yd4m$J;U|lYdy<3|~8o z?nq8A-MNHMW(L~OAy6eTw$bI5D{hE}WkK2@Hd=+!=h8UjAnfJmTDQjMZ7mjWukb+A zjWjQ)Y2-G)X1h{qr!i*tyc9EBj?oi8*jtNuqMg>m0E=>hFMO+EPuC zl(o625KM%FCCt3n-@KPp!e{j}_WDzch=5)~F7~42NMa^GEe2Q_XI8oc zh_l1S1H(>3j2{`%l7{nOg46W&HFoGV_KfQiX4l!xUhJlw zTHD(k&VM#R*+%W=m$+;*>0U--Gf( zY(t&wMDk?P*mhhFA*!Pw6##pS{l{Ti3%LtdkDjG|nGTMyIm=v}`SpIfo<&bQYH3w* zD=>1KbrA;{alBf+u%d|}_+hrzF!TJ8cd@zdjiPIu5az14Zz!n8OioWs9-!qNHJdqT zt?)t`rci$|4GvrEpccqwm$u#ZdY>)Rk6@oxA(jLnJ2emB?soYJerZ2*;+!oo8)Ws$vBzgdCkcINgUC-!U%pw zz6l6DFi0u>$NeDUQ}~*UPdY@W}}f#xA3mD4p~J(w{zt{}Om1Q7-?;W(2YuabnIr-w+TjqgtQF zr(|Q!9+))1M?OILAZL;OVpI3{!U?B0hVq_T~?4XI)Y9b^MsL< zrOv8A%n|AnDq;cZ4o!&IIBoA%9ku7NY69Acs@O;wY<7vs_NAX6bARGnv>A+G!cBeNHyNI5FhEJW0;t#4vK){>&N5TZ)CH##w$tyLaK8c!mt+jKTfLqa zMnO*W(mART7SW-V<*JkCbs)(lGSAEdO>-uOiUJ6vX7fa_MdIBewR}7TumlHy#K;hJ zA}Cn)Y?!eO!z#(6UizF9ymvP+$Ym#x2kuZlCUGF6TafIZn66tOXM}|hn6jym$8hX6 zUdbUo0EBmy7)csex6zWGCsu$~e0+-xvvh4-`w(3*Loc?$w1qG9D3uvu0zbBbjBf3& zPTj&z&;7U+QZudZFZ$6)W|>(H>Ve8Tw0&88w+Pb8zc>GNttEdVr|Y$c;!vaSN9_5- z!GvGz7;z%fK2t*`zsF-eA;ndj_i`cCxjKC3P9zwS)B8Y|xAbS*?f>=#QWD%%b<|;Z zg0FGk$#&LW^Ii`gL%z-J7NzU>Qjj#qvI}Fn?iY$gLW)ZFbV;56L-W3(U(g>GH-JxW z4!hrbC%fO#aIMPC32Etl`<^5G-87@*+_v-SXWItLO{>pXa}`%2%yiRx?9A;8qNuFs z)|D_)?lbI+iInU!T2pN5bcpY6Tw>tJm#SkoNd#?F+3h`4fn2Ls-}Zft5@P{zB|}|U zo-l`z{#`bDU~=Y69do?-GFA3wc+X|3(~d7b!!!C7$=EE&$nM>$a>9$ZGaDC<8>V&Yrhkfy zY68H){xgoDU3-L1W3Ux`dL&fEu+2cvcJiD4Q!n-mKJIwee)iHgbFy8W zG`Knw8|7NJ&2;V%Z(f^mocub-*zwMfG@L#*sQTpdw4oetbx|bnf1!e3AKJX?X*jQF ziY*8>h5sPbeAvhY6Ed5$JL=-ellWg#&(B*x82n%Gr1s!(P=y&(FY%W$Q6BZj+Pd6E z8w)q-vUm{qYNpu+H)NA}^2*f%exAqNkpz{CN}>T*eIfPhl`@!x& z1coVXStR4P8W>h0bGFqWOs}PbSIVl@vc0Dt$#=)C%aj#xT9?tCLLH6%f4yHJdV94> zYaz09$gyp?nAP&+yBGZ`^FPH-Wxk0FjLq-MgfFB=Sud@*w{&98^@smntqsaO?(*o4 zni|jeRDRd1-x7@3_~d@q>vjU-DPLZNcI5NuIMl}D>aS6o!~HfE%C)+22Y0$rGf}Vf zqPM3h0Txl-@zJ~VLLvA3Esd``vl-xfhBbPz?>jS4_wKyVOZZ6Z4G38}^&oM3aqOk` z6`|qym(5_3-s_s)$GT&F7~$y6z_iCv9I%pe_%U{qZTv%aFuU4Az%fec)LWhm)q70F zQI2vSg9qhvRcphAM^&yUok!J$v|}McZ8n1Ir=rJ^#11+L#ab*HFA`u0@44iDF{HQ* z{xQI%XH2c6(XPI~(>Pt3AvtrJ2gv%dOLNu4eFpt%ihyh{hGog(Lxyrz|R;gR^~!0_D~CofVO#nNL@1fo1V0r|cS7)#635|ER0j+~jfQ8j zREdfceOd?c6DXZgA{e7NOrJ!l3iEw&vX=w8@|-nYcfokst(5XIyjgeG!~67XxjsAh^W*o8iAbY=8-9+1THSn?T_e7o$3D9FxUTZ-Or0CUA2(%*0C zZF}_kB)@F1C`jHF3-C!in`ZL*=|?e*?}R7qy&~}oo+W)(EwaE*UVQ$QWv{;vpe|9~ z|1$r15qT-?oOb`aX&tpm$kT<#5BJ}CDXW9yyp#v1{HRC&_|5rwoHWNK0h&aBQ9d7) zHuhea#29149kh)h#oMA&ku3jI>!;J2ADX!YChhl19Sh`JnH739?fPZ+&spsqcB`f| zb18e115vX0ixkCKVaWoG6~=Gdn@K+q?Trbb@co#uHn$Wvb-_KwKR z1Xj(pRz|#?llgITXs+$n>Bf#O0DC=v&2rRzJphdRMP`#?P&i4GVCl-y_X-ZIc7iDc ze;>hKDvb#p1HcGHWA@<=;0E4z=WGc%7`J_hjFex-zLUU%RvJWp^n$OBDagH<1{p|~ z_U8xZjRG`Kly4U_%+^pmMf-T#_s;V|3%N=kjiLE=YJPkZC_fQ?tb$B8^`g<+oaxY9 z_w-=RK2oKs(_X`Qc$(Jur~{s4R2{LY#=@sAGgZhtLXasAp^eQyDllr~fah7uXK6)*HaA~Bj&|$i7z1G+qG4){4k(^=3C(--saZ~E{yRhf z!kSFH=X(e!w3-{3=R2Kt+c7T2V2$2sVaXA&PmejWXG_;D0zf!RJw7&7Z ztR+YI)p>_$wTkXMyBK5M+Mzd0<}aNNJG4LMe~R_?N%K$ZraMFx0jFSiI)%d$06sMf zu(qbT1eA$M<13Ad&fETB<4fB1s!Bc~GYbLOO>M=LG!rJ%}6I!Z{ zjut$poie&T7IUgowtTgp3ep_?@+^lJyggh5_&-BQ%BkMtd&Z^|c}Egl$e$amzd1Gy zGLwFAFz>Rq=>E$%nEneI;RZ(4JU1752%nC;G@Wnw111CnEo=Wf=8PNOp)GozeP%Fc zwQu>pxI8^DSw&YXFoK8mF;#lwk|Nz|k4rz1W?pbwi6-^gl`*rG$xGs55o?h`uiAw0 zr*;=!?wSkSqfFsLnFBZu;Dkw?pfZrY*{)sJ-FmChJ8omTaGo;%UHDUhnBM_O$*n+uMSuu6+CtIa+c75Q0NM2R59 zWgGj#f|(iP%ob|lUDwAPE@1(2sC;q_sq&H!-nrKaWP3xYBOmSoHI5GHWTvvT%}6LxU06JePG z>Oq0U11Y0l zV@eLUkV1y0Q-CU3Htss&f&FA*Wz6N zaurYg>dG=)%>F{y0v0+SojAkFiJR-R=v zsv#+_MqIrXh+jQ%zl+B^;?;{=@m)WWgFnL_ycfI<#a)#SyTO;|7=1y}MB>)A`ptLh zU)OOj@a({QzAwbY6Hjbb@1YPq9CWDI|NOMSQ!KxZ3BTOddJgo?DZXZqXm#DmYRk?0 zO@pjsfEI)9%^fE4ksp2Y?ibzz@xO zw{qNrbtmOJkslCV7f+o=d+kul+XdxR-m~3@Y0b z)^W@I(NDpf+citia|gsEcC*djgyBY(>)QP!=wj>(GdR}FdT1GS8B@5$5PMCx8C7GY zYc?-Jw1FNz2S%s1X;xm&r@Tz8N;R#R$73R2 zNE}(aoE;~e7EiTJj#evfjMdv>(yDO#ZQbk%uIIe>}? zptC_r^G7a~aAl1{5ZQuhJY;Qb1mx9Wl$dj?X!eAtmO=_{@fGWY8t}R&Nb}#@RK2a^ zF+xRMQpKeCeiZdl%=SV!2vuo3?lP;;L|0a0%M%b?Pg+**Z zh?HG31qXj-t9=|d?jNzmSN!sjb2`S_N<;LkW2Bd))B72@OUB&- z;c}%?oY_aR@7+&lrAF?mX$?a~r51!2wuQqrL@i7jO)xCfJm)ZgOH%jTUpFySWAXj& zn>?{X1CAO;&v7ELxVuE$XdA!w8n2~Vj4IJpzMDECp~s8Y6B&(htO9jT=xGju^k+#d zX7ORVOjwSA3{zI0PexxM%iw}UtIRC}P0KXNB>#?H5Drj=I|Rk1w#7-@I53Gf32{$izd~p)A+ql;dR$ZQ?-3o7Qp5&EgwZ3=Bc?=v*0fSR0z9b`& z_ukW-;ZfW0v$nbDQoY)pd;A3oJh*$AxOTNGzh8)FJr!>)^O~fih8Q}U9UL!5g^yFpgNvEijBC~3Z z2Z@@0A=>xepUCLn(u@4mud`3`%QdiWGzk4P<=mJa9t)g5CRz9cKgY*8&N}GdD~~@1 zyi-3I+2%xJVNP-~@cd`^wB*BQGlGBltF~rbkqA`a%UWDc@P6NRUZ=fO?|!iuqA>gZ zcM^NB6n}vuHe|cn3JpEW4Lx4wYVH_n&Kvqo0^P2bJU`7N2xtYli z6nGz<3o%!#wmk$XuZ7&2&AI=aw^T>b0AqI}L1N4uSKXqXr-8di zEVz4E_wt;?yFa!K++inPBO#^cO+~oH$vk?}(sqY>uleJzDYy$#Pj0T`y1H?~jkZ7m zcJNm5qcx5n)WS_N=hWCJr}w$FcivS}*Clf0roYEK>o~3u+j7Ro#QCf?9lJ4~BG>&y zHdaJzo3t}EML&;nu8|t=?uvqYF1|7o+h>po?3Cn5o%Rgzuj}f+^l^{(t36hDt=Uza z)`=pciee2^#AK;s7t3~U&o-dPe>i>Tsev9LR;NNL?9zJQgiNrtz9o;o8}qkb*cM29 zMvpTHC{LHPR{&bl*dsSL;@+NCNVs+J^XbUJ(-yLZycz7?mYK;s@~IK><&ABXJqct+ zf(GAQ;b>O67@`P(C?Y3Tg|oj$3S$&-QpUQs#pgqdyjb^aY zHy0t(1@beDM4zklT4&?0s!XG_DuW)i5aQ@Q~t?Kh;z7)T{{Y}<9>2$Wb zm4IEt_OV2j8i=G?*At2ryNWzFSlS^KwFWeq0ybbkHu5dvhpAjGaqMMr<`V0i=4FWf z*qOL@+ye&RO5dH^YL)*H^Re09;X^YojrHhd_Y9G*BFTSyx`Cg*=Q?xmy50@5_x_)I zGa_f%zfCwPuea3zf(rk^i&$4XasNs(S6L0}k$^zYD1WrLdyK0|ZV@CQ0csTuosMpA zc=+LhJD23QNx5$w%40@l1ZBN%O73OK_(Ke_8)Cez+;7P2$_r8H`~{h=s(xswN?M7& zM8UFQ?oJW%pUO9n-+T2q5cj+$TB%80>Ik({5#7>l?g&6BO6IjW9*lb&Jk1_?e!8}K zWhrFRQ>yr23yB&TePsB@{EqldVV>yc%c%R^s0VbRSM?k)Az>ho&Ii2a=X&9{S@rAD zBF|SMchH7BosI?@&r(+79b``%lxK=|(q_opo7{)n+uKY1nz$6py=V^M6b{g!sFI!y zBvtInB>6SjH?i3Zpf8lxboXnvM05<_7oJor1yKEc9_x2~_a%S>JS}mTNwGO3g!zWY zpLFL+gF7bc_7w*1pHI+x>k>L;XzjAIzZ?*5dM->$peQNz_9(l23pFOWg@->)y-?RE`S23FwkdxG%zb{y z#AEyUt%VP?^VEN%T#W|`Y>F;v3t3Us_u@8&67-+3;G(40snDn9wgO826Pf=> zY;@kZ>*Yu?%QjQA=8?B79d;;&!14s7tV_{qjV3Iu6Q0CiZT?faaK^*y0RJfjQo(-9 zb?mLFFQ0(Q{=?{0C`%Lt=L%kVYm5?=Q>y>p|}ct3E53F05|(JVdT>zcPFDej6@f!_z{lU{fvYRLX?z9IlL^CVQ%K zb*`)`p8gzG9Tolj zOCV&+yo=|4f86={P3d{bRF3k!8tHP?NCf6kjqN+sN$aX(U%9@~_jhIIMfOevOx~B? zwAcRt*}EYJxEi#qb2Yn^DU#UgUXd-I`0?hS1KxIU-4i>?YKbbDl6#(EjD6TP1*NQ@ znxtA>tmdXW=_@6q{Yjyh1PjH1hPytIJEsmwGg^z^xKn(ZB^jd)rWG0JV0nn(qZF8C zn--dx9*Ux_5dFDt1}Tdabc#Jj3UG?5b0)N>34h$A>b>sg#NLsV{({faeNl9m|4YaD z*M#lSVPL0EDA;Yx(pptTE{|iQQJ^HY@N(U)ro6Fw5Z=Ql+W-%w#f*Z*@y%@3KPX%d z07yYI8RkR+wm!5CvizIt8=t9Jt-PnE*P9nWM9kMFOygzoc~DR<=)q!;inxanT=Njf zX-fp59hSoD$Jp%-RxfnK*hPA!4ZMWR==gkkp;5yPe;)r?Yu;f=rKBh?C=?V$0YF}f zeWO~CWcA;0KXLX~TZ&mtJ>zLyQzjxHEict@`Z#->_YO()&)^J}IqQA;`~9=mnC5b# zL2?tgB|58k+aS`^>20XZpm0zbKq($0=%{+y^D(j+z73d95;MRBb|vZ07tu;@@a_E9 zmSS(YdR((Rs9@UO@-LgKeC@bJ)eMLjsE7WF&dD{e{XmJ5;8juxz2&w4;VNenX=0=F z5jZpFYW+CrFZ(;xX&_SJdewQ}@^M~vo{sBqm-9*$#&S^gskVkc8N%0rC>NkfTFWX- zsSj9sbJE&XvwdA9TB{^}u<_I(Hb8&Vk0X(u>m%3=*JV%5i#D7PvovjtzSN`~%0Ags zln`+dy?Q%@V^?escjJBmv>-Z9vfIY z$o()5Mm)~bc9`p!4ZaWB4wV@#0h(ILWRui{LgvkJa>qKYW#kC;y z0zcC2`>=>bs(Eyvq+d|IT_veA{}~Bf9S#FkSBgz)Kln|(cv=E|`uXN*g^eW9MKYc))Wd+OoeK>J{(U+~?u_ES$qeHEDQRSf(3xcR=l> z&o=JagXQe8E902DSw8-uQ0&O|+DMF-5#TIwoVSz+h7;>yWL}E9+fM*{JP9mB4^lQ9 z1)4AMKm^#vLMjH-mpx)ttX?jH7jx$q25$s2wc-|o<7FxqHmBanZVpN{Wdf0Fu^>Kz zxt99`d#HV!t}iM$vti6OlvjdVS!f}}AZh5?E25WNn$QM4Q=LYs*PmT37MT!E8=l+6=O-tHv7^yqnh$i zT!#BD@2vrc66K}lR!f9+>gS!le-Pz;>-T4Ghdm~>e21XSdM{q%j(_?e5^IDUF;0!D zDrpj}eblI@bbaVdxH5Iyjk5}gonQjY9h}}x-{kE|2fZ{O9WFXonI1Fnm2gjMc)!Tc zq8YbC7%-yUroHkge=(~$G@sMOs89+_Rg#M35BtU+L+VNs%L=e556Fh6qzDv63lx*t z@Os&gK99a}g5*xhjP{cD!=GkYB5^}SS z$!(OXdo*%xS{2ipf+h+6XFUF2mFfrySk$EYkfd9sOR4{jT3XJP-9qv050-iYzy480 z9s)iT0}#;}K@~FVv$(G3Et(N{zn=W(go3x59Q1CET|%a>6a9TMC;BCX$Y`}dLwF=1 z-}W<%HF!67VKw)nqtcOtQB=rp?Z3n_jq7_@EPMZXjYME z!>alB4;fLVn6ob*o=K_rq1J&27iCA5>CTDXyM#4+n$e8TY+lart576(@p=Bu{{A!* z(^D2V+wc8UE1ZBxPR7l_pGuV378?yY%wGgG zUf5|638ymUCD`&UZ^Vo?CIS&jR)`xUw)39ZeCk==+XB}F#iODnF;XyhJfAE36RNC*<0UY{_)P>EFs?p$YEJ!l_NO3e3wPHbyHxk>J}U! z0>=RNhtcdKq?UV&ciBQK2U+TEdW%{*Imjb301n+)PVX`@@g2{vO_O;^&|`mE^`Z^` zX0R&20lyc`=|HWvYa22_Lpo3ppHUqxpzybBWKA*B%aSXgxkABGw#TN%Ldj67t&rd3 zK?-5YjCZi(*eU!DHhaI>*d)Fg0*{m9}MH_Yc3^vb7^n{r5k zQ<s*Fr$yRn&BKdh`_oP{~cOxCD~VAOLd zoHogZRyU@~W*ePqpa@Wa^ype7X^I`rZSn`uQ!l+jYPL`}_AGAhOV{ONw&n6sEB}r! zJZ`fof0}oH8TH>#u6&=1*(*Z+&Rz83odFtvIsrf=1H-Fif;}>)Oik83GM|NVbjIXw zjM{qSPf$GQi(MxAHLc;7IJv-(j=vMO(NHOpBJlzyHkRuo^sH`4_e8r|Vq>b#1GS1q ztWq1>cHhPYSM)VHSU(!Pv!(B7piUT_WNT+*nVl!VxmY>ii@Dm{%cq0{MTD?~bL>1j zF{$EVpl^#grB$E~tl@{0TUHUK-yI5-DLLorq2BNkP0GVMkeH66XktxCiwB0?SW|bt zJ~kcNBxj*}~#sYx^#G8%4l#=c|^>>|4f{=s3wSGj`=)%w^8G~ z1iZavF4B{q&9ppxl8EewDADUQgws zPL~ghr03uPbAUsPlYKk&A$E)mA8cW!yn=o|6n26Eq75*0u4rQ29@|!Q zaB>PS#3K#R&}d>DD;3L<>h>#Bg{td*)!ThDl&$qLSJTC8n1Be`sR*a~-k#-5qdxG% zdOtY}v@|SkcT-m)r^-;%hrW4R(n5;h!2ai9tU+HN(!pCppO%;?n^v~rCwTfPfhpyh2+fIu8$F1b7N`HM{7B7`Qg zBC5VW%7M=#nXjQjbhIevD4|%243L?%&NUv~4>Y4*Cik%{uk!#-8X27oc*fy^PR{LJ zBUJ3%eX=}$BTVo{FY0gO+Hf*isV}$UB>|ZXxD|%_+H+@B4#mwM^2-07uQ=F@lmp@PF zy!EpU^y;ASdmz`Z+BX^e_SfXn-VVRfpzTZM0?q&!+l#5(j^1>*)Qc3#=PqveG&gQA z$JrOO>?|UYLOGr!F`on!OUK9xUw9%XxA~cZ+|=LH?B+d^@B3CSmZ)U$Mqd+K?&q{! z&+%u3vsm)bq|C1kdc~%bQsZZ;sHvxJ@q2p&WxcHXag$vlvmZBmQIjujxL(t>zj+y! z7SZIf@YaJHTQ#di-Rdtry!XbW%~?u;K+*D0KgzC?{r|EwlB|?#g~t z0{G#%G>6hq4Jw(Le;y)#iYxR~0Y4B+Hp9|@dBxm9`=>71eYmV8BGEvS9%YoK)^U`J zC|ahyHc8Tf)O8BZrFg{DfeS)^Ra#mA9$vd{HI0-XL*qeBEc13 zQ6H<;KRSM!Nh+1Zo}Rhpk`rUf$7%f7MZS#J_A{>mHVQw+-H4!?HsK?);)&Vuasi1< zd8GoPKpH{dzc_yBM(ue6&eoS4ixGN=o%_E}4?U|l`Cpn+C`kggHIPkh3|u)VShmFZ zu#FcxUU|;vdq2}h+^F`KXJq}+XA}(BZ(e<=Fmb42`-5bzLeX8q@ZEpb=t_WL{~fO6 zAoI5>J_RUb#n$3-(EiAmr)Dm#W4RCObN_XqLfAOISugNeCawU0EM3+|C)8IJARK#f zGSD}?L*~_IpY_niwP+5~kgIi}_T=>98XTJR=<8sSo)ntPomke$17muYj1`$5QgWEY zJ8{Lu{*X|`3efDFq&zKyf2VNPs15lnS?q7x+Y@0*Rj39&ZCA+*KE{R-V=xQKYZD(* z1lzdhFO%>Asi%r!WRrpCm5QZ_sZTJ5+7Gy1lorPoX9Pho!R)M40I#uMsnxj>j=4LI?P><%AW|7%?hlZnyIn0k#AeT6sR1hUnopFEq|*2h9WDN51ci!FK z*yPv%Py^=c{FmCcO-g!obQvH^0~p#=T&C8{KcLw zU8dRo896rPP99!GJQ+EqH7`1k@hFF%$gMV8-%yYIcp~r8_??wt?o2IzwncI}lkPQP;Yczf2t7~;hvL0Tk>@4)heV#Ac$FC=C2$k?BJNjTcgE|IsZvQ04_ zv|3WgZg*)+kGq>Ms6Zi@lF-5C z^MMNst%^e0CtH1y6C0nmbT58hsl0IS@z#T+FI!`*jeTMLk1Sa{fnlIgKzM6V!bn{) zz~pNz6EGa<^QM+)O+n+hW#S@f)6ZBq9J`$%XpXhZ= zpl%Osn;SZFAdHQ^=eH<3#m_DoN*cGNP$Mpu<{4`LnSNIt1)>ZNM^82#S;49IyJ^A5 z8dgvm%+5^_wD|Rs_l#~lejE}qg-$!CUV}*E&@3H>U~JdkP5N3Nl%->=HOG$5XBw(O zmz*sfr+8iEemL* z#fPhjL+Pa_WFdL*H~*qaP^Y1``B11~l4^hRUhP)*m|N||PO}?D7hmj4_~0LIm)mVS z4i?*KZxOyE>wI~b#Hm->)caWb1LI!4)?T~_CwW_JVo7h;#e|cvn+GmPRkKgd%UL$n zKx={`E5tuz)h~2qP3m2Cpf87l9)AIwwXx?Y8e95lsu?#iQkTeSc?3rDX--`&{=ovh zUD_Q^!rmZ@Zn{A~<}^4Ae9fs^b~BAbdkd1r@sf1;LCcVf6vdRsZ?AS>Q!!ejE=FN<0U#Pi*YAe%<@jprcps*Kc7wHR~ab18aM`)V6CSs z5K~$CR;dg^ zUdmB1s3*hY0{ui|!RwAXeu0yOF78atul&`yC*#%+_wBYbi?sbqEd=ff3dQv}YHwCJ zpX>fmurbn>yN_qn>g}H03Z1BVUf-(!O8jhcpAk2uF$?=aw@rJ9a$Cl4N4UafM!RjL zAilZj)LWZ3zW^>AhqVO>JISz5UMG2M%1;C-a*mnC%}T+hpRkj~{5I7U?5Uv=#*0Mx zOeq(Axcpr+H7~S-=gg2$LxC_u$bzDY)03=}Jhe@SnTb~w$e8sBeL`fGk(}?T4@}xv z{pzS-rCu7@UCI)KT(|*)!p&$0cg_PiJk5Zd4zxSshnSnlgfT8S5<*dDy0oIF#>|4| zon;S8k$hTmoX8(Qo_&muE|~(00^E^+OY?x#a>T>mW(}>n%H_2oe7}DboAJmzEKqw& zkuo)TECKJUDx(pplETjz8T~^>13vhW=*VZ+`3bnfhK2ICSTJ+Z|oOOzjDBB~L#UrhFW?-W5E@blW!nKaS4AugUi9!z)H@ zxY5lF>-XLqZ>veqR(J-NlPl-ARr(h>gW&<5D*Y?gb0cX*gneh?)Tn*!hKzz z`?}8aKF;F{J~KOm;Mkw5lM> zu~y)^LqhsL8^9V=s=mO^aiC;*Q7(5Va$Agkh;vLDIS>iwSwLt~xvDaJYwAs?mQ|l_i(w8j?=b7}%j= zH3q+ko8#%$lH(!R(jRFz!v}-xxs6d!4XZYW-?QL20sDI@1fV`zEsf7@)l>7Qo{f|# z9Xr;}(-xusc&Ee?Y1i&@O)RNjhvHC9DG@hJYPZUNG5(-?wkJR`vg5e7{vJYd&~@O!c11xf>yl(USF|da-FHC|hKf>n{q^ zYjS7Q!^2{G1g3Tmb>1PXHkU8VMT^*~2amV%z8&v>oXI_L7=EW&fd3)J)isr>{0Q6A z!yJa+|s0ybU%|XELhSe11K);eP8WHeEFqXq`SF zVd@0uGt6RkS2$C^dzq`k0+u)j>k&B!Jv z!%iLD8(@&Z95&HW=5GA_Pn@Ty)8bLi^Pf4Be+e<@T@$CY2syThKqtc-s9FJZ9) z@vj&0KucDEXGl0RD;oK+$1aUfe@59n#~NpI?`O|5e9IW8fgWlUybOlTL+s-j!gzzeS`1WaB4I*LiUD~@#3S!l-_==SXIo-9ZY z6Fnfy`sP@EG2nbv)1*AuN^mxk00;Qmo%O~DjGq@ z>t+LiBsqyrUO6S3-7RrmAi+jRi?cYHUsbGMZ_iJ_dhuagx8%nV*y9GRK$ zzfhDa;#FMWj+m06fC4vigO=DZ6KUZWlw_HMYSEQy(O!YQmg-GkedZnUeZ{;I6<qi-v?8PCoW9!W0t(U+llK5-WMkDsf>>uYHgt2>e9 z!t}L|rnOVZhePB;G?|n${yuRv8%55RoXM;)HubGnrtA!L?hFYadrp1s_6XiT;5p$j zvrI5nKFnj=^-v$k%T{@wOwGt;5UEenS4HWUcaqbttZ8?X|t6sL@{ndV&fYpN+^8G?R>{LU`pY9u$k+D#{T0@S!{*$6eNXsydPY9Ooe5<^p% zpn)+TvrVfYE>HBXaFWGG8=G$hS$`#8uXb~AvJtbk;e1a)ZjfzG^jT`?Tqfs!&f?m3 zaUR=2WenAF@Ynp`@m?F*7W2qxp4ze3pga7I_GwcA1US0OFz##ec7s>E)9m$}^jDJQ zIYVQi!Yu0CtJgc|6LO47P=dwiyBe8A>KrU$Ho~v0g=I&mn;*HiPMkuREUsgO)lWe& zY8L7SCPny*lDMwt1sRvVB=H<0W(|AvzYqFb>)x&`5LD3_$FirG@kpMva8@w|{KJbJ zh6j8YVn0DXW5qG|GPpcgeMe@mAX6B=$!5HFvix4-uL{Xb8y>&e@Z3Px?gr(yI*qJf ztZ7+G@l;8gOMD~smaBaM(2;24vV5m* zZ1p^pQW-(jiTvd9Y|{`3Q}!Y}c?w4~RM2=KBUz*nGHcXlAXjA&>E6aSgnSa>=&0xD zc)`LpE>L6?Z}2b#-7@v5`Fxy@syn;pE9y=&l_c?;P*|`4Cm-F*@h`2H#@l&Bbq6MI z0Y%yJGo7x#`DYZi{1@l>we7yNp@kd2*lQXB6nejR$&SrdVCknNRl*G7u3(jhkR~vz(<7K ztzPf?IyW2|(#^lDROK+tBl!W1Je!x&#b%t;WE}kxtjpa`mfa%N%)X_xshe$-H9VZ=tPXz z4{5jYa()y0b39|@#xVf+J8(D$ZF z`IVORpL)BClX^=ttr*T5jH`HD>RQW<+%F|TGSj>C-{E`g+!g;=k=4H?%S4+E_ZeKJ zC8D=iz`9*>@2>eG5qEP)AalUKs!MG%nYYy%d`#B=jUd6zedutAmlr0eOQy|)hT5YD z+Obu8U{AMPV!AT>d(<9EG3^)uz_3`+>{k!1sTHNJh`**EE=tz#IU9c(%~Q5}mSjin zcca}X8240W^HPh@$xwgMb|R0=n3SVzKwDN&l}Ss=6K?Y#bIC&(={t#^6$7Q^kCGMt zG%8v?oY~a3*I*TO_Eatcs#NMCjg_6SBs%`2Xg1sxJjJ;L&^|c_Uj;xi6mtv}<~CU6 zt;4goa#l=$tf%-FyUdm$Lc^FgBS~AO)TxIWMG>g<4C^AwuC4Si{Ev7yL|G-KlwSSo z$sYs88%`xrk^1Toed8$d(_i;fZM%yi^j{flg4*};Rek&Cp8qLMf1;MRZ=9)q6uh?< ze-J$$m(W~Dt&}B^K&6u_jN!J zyX2Ik*y!`gfVQ_>GZX+L1@PiYg0Lg3;Gqj{a1Y{$Lgo(%JPkqGqWCYL^dn z=DP+rZPocM#60Is#&+2!G$|}G5Y${wUNZCRi~m^?B`0^@cBOkiCz)UR;Ty|GCu6;C zi#?0m{e2)?FXn;b1*c2SSFbbs|4H@>F&MO)QWT3rhB2nzY#chFBGuyVaJTzKKhr@d z#N7Kg?j!kfM-rb?>g>=c%Z8ZPH+iR;Q3T*ZLG>PKk{frmD%B;2)m5|!zCmH_UU@!* zUtp-_XN4~EyK_KtIqZ@~LYjPPn1@I7mbu#%5>t9FK>yPXmq3Gm8*Vg|iG5lR^Xu81 ze6FW&QS4OGbe0_U_>b%usN^zBSQxLqf{KIZ&p$2h8UFeqF9x}Ks>2-y_o-9+Kih8% zPHWBxtKru;L(6d=y>6XMH%JL-lk|VEGgLNrYv41os%B1*VfWrT!=rwYXd`3?K9U3i z;_=Nu0c*<(tr|M*kR&B5RY`KgV)Y8c_bP9VJ`l+X{7;62LG8Hl_@I0=Gv+|#$MFjL z36A?dt83ZpGzCldQ=7570hmjITjJzlJjA607 z4h`1m8{6|3kMjbnB2>Z)7cL9ak0RY3%G$ECb2&)A==b-1_@TzP*x=5f^;kiQf0ni} zMNc*)Y^Yuvd&H)ZPtYaPBgO3o^F4KMgq&_T@B1zADA9tJO^W<7%F+5MCx|)`5QKrN z_p8jtC4DGTlokes_yUDjs+37O*QNLuNnCBlUoUJhS(37;uxk~@1+vOmcFtr;XU}yw z+j-$KeVMtsT&`VPJHPnN%q{EGpTekYCcDv12q8aSwqlJzu#)9_pe=T``c^%eN%$@o5zLH+58;yeVu?Q@?qJ>k?gec zfI;u2;eh;z!{OtJau)tbc?eA-y5a0E5ZjR?!5^P!=3f~-65-3`-gk_~awZ8&KX5Coc)HGQt>*$NV|lEL9=dCMnfW<|WlwS2N~QWY(0-+3t}vuzBC> z`rFd3TgQ#16;U*(#*>6jE2~!27nb+x4a}8)d^p#{@oez8NolP6Oy+%9nD>c7_#kZ% zIXrgL53@bI3|*gse1Har#gB?VXdzqY-kDBLqI=l+>aeMIzBe!g^Ah^1k#Do*?2tcv zrFLo}y2C`GI&LG7UNBAzmR=2?wT`JG+R)Kg9n+cv+7Wf0R@wmo*!{2H$Cz>DKlEC| z+0Erk6khy$QvWw*!}FTu)gOOc56dh|ke{_b8s_?~eyrOJi&~rnHvjU!%VWeJd12!& z9~o<)GHnn&a8~h=kdXBDj#E&ra2B7oMRKNiY{PCEug4%TjmIlPw@Ji|dsIvxcSJS0 zbn&uL);ADr`+Eg~p)^8nk-+eYqB}I?Pc4FkN6k>GXASlUZ zCEo)}<{AMoCNZQ)V$n?8S;;oFfXQ2iJ@>XdjdUu0K2Pe}hxx#eJiNn(do9Spme4f5 zVeX3O8MQKAt94vYDRi=lZ?j!~*2%aRl=p-oQ(d-`nYLUw`zZY!{*Bho2bJYcBYPZ9 ztK;r5eft7uNAmFt!NQ4dV8eNY@vUEG3?j%4uq+XB3)UdS_ytg4Z~*|LMzN`8gfWXM z$`c8n6$yRDIkqNR&XC=%B-%EMqXnQ;k&R?c6aCqYoD3e566 zRX!RD;!x&)-+Fq|b*1OkbKJG`dnSRx>6);~226j>_Oiug9lP7dV_yWUZZ^liqA|N& z`=~U-ea+QbtG21-s))o4flnA~nfcvZw%w`B2xT+5I?_doq`|27)mm=LAmOJx_!y{C z`DmeWO#@3Y3e3~80=b|$_=1j2c{Tv_eUMRzT7GA6BLyN!Y`W4a1>vqCK@J*5)ih0# zxge`x4Qva2h-#sI;{g+6J|j;aD6L=xA|d`wvf$7v?!wbBp*SMP+s8p~>4u?989)rh9myX8W_tDRY*g_+yV7+ zQM2}HE_^wwoaTHj*5)$YFUq1M{qFWEDyjfQR*|#-70siRl!F4l7;YUnSJn=U6En@+BB-A5eNlSNB3q-kHuky40%R>+$m>|A z_tlwM&6oFEJB+>QZF1%J(~5^zjo*No3ik5iPBdFdIvhGBU3S{6dLH;zTl9O>SDp&K z^fYmj}%L{{u&%>9jQ3)tij7HJ_#Oj`lM{>`7P(S@AJQ_gZ|pj z{sU171~O(iFm=UrhU8Kqt0|)+7rj!DSm77+*wZ9LKur>w(qDsFDwOc80WFjQ#R4g8 zqWomGx_I`6j@O6SK}}ong(xLc4)l>d3(p#nPRC{Ui0hfg%;*x-FXXL@wAN3qF^ZUc zs4H{%FOZvYCmr7qj@bpp%mu!`?m&!SPDz(xa)V4Qh{Ku5=6Ciu9{$ulKTFHpcn05m zY|INXNy{@JFlc9xSP~FGpc4gji9`YCVQ+Wk5j+)Jq~V0_luFSg2@9)hY#FTVe|d3F zMLsCl*LjsV#+vQ+49Z1@Psw<~^zUf@D<*quO4xn7u`0&1B512=fcwADyGz?pRfiMR z8(JULdNpr^az5xsT3&n%f2UIUhW7=YGAJCr=>t<3EBA7ofnr|$blqCg9Sl7Z7kGST zuDx}}GHbcW`+=b|t&2Zzfk$PD)hqwVLHh2STnU}WA1psz(Yj}5J!ez2_1#G9+w#wO z58F>tU;eS6mpZo`g#Qa>}dUsZ#s|Eb@qj?%`h-JP|K_n z7uhm95${xgTDRf|qGGMX;M6%lNn7*e3%u`Bbp?m+Wi;i^Mam-`z1{2)PldN z2-;*|F~J1xgMgb1)+*poPCAJ~DqRINwL|WeC|#O3&L)!KvdeVp3~W0O&8x!9Q$x?6 zW(?RG<=t6SEWVhP-^wnWzD0X z&d4rq=M;x=CVTG5cQIBYhQIG#lJxS}s`0>hi9n7;vT7JIunh7wq7dp^Ni0~D3N$qa zu|uK4Qf*;aiP$~5lV`NhC`sC}t4G81>I{pSj(yNf4pTm*IOj57r)1pF9Eh8LUN-UA zKMkmy0Ubw)$fN2NPQ=42(o|uePfa_fe8vq9Tkl%=OaLs21GQ=pf8ro?%AiB>4@-!T zJ_fp9PBHvgCmufYiTyb`b8(a{betFUe3`eIwCAH=zjd!}-DLi?# z+80kmbn-@R-^<22JioHl0ool0q2F!=G1v?uuln8ZU8%<=O2+Ha=@=Sm>n!nfj7L!; z^jP2XU?4oJX#THAK`QV@-3ew%oI83~b`j*NWL}(6$0(h~NZf?cCMGxW zPNr)HakF;!XJ}6Jhlhh=4_8{U=gtQw_Gra(_SBeP^ytvtZuyVBd4FnPhp890WraoN zsj#n&BC%AF6zTzr0KnJLNz%p{2q{V^6Gy`4*io6DbbtZ1 zOAIlTEKBy44T2&i%(;_m{kMeq#1~%M<#X*UC}Bh@z0MTE#!rd+?5#;R7C-exi=2gl z1zON*MC(aNI&Z`A31qyF(yG{X+_%kAN%WqyKvw#YZ$OPABJ0oC{ndX*Xk_&0cc6uk zaDFBKgerfnE0=zzHAg4YW4G(S&MaS9+K<_q?~%pWJSngN6icq<#Lh)r6*a9xnbze^ zYj=2S^QJU)kLy*vi?qWDjgRtoPxHg*adqO3&|c1fZl5;G7gZM|uShQm{&T2bU7Huc z+L$EVGbe1Hd#Hu|XJpP4Loo$Ria(PE4~m)%PT(;Fu}2L_X?7hMx!?m)hz@~V;bQ^% z&?!p&W5@va)>Cq90oG&Lut{v}?PfgBuIieyVXWc|6dvH;@?g8KLs5NsN58gO`9!^y zyMbjHp6{ba?<4?`o*#CweWiuLZ}L*JM?g7y#Cu)Mj=LY^rTT4n zg!i{=JleVyzKOwODI%sUqA)2C6a|p4c{@im-H>S)4qOcr-ohM8_^2x1)>F1@rTKJy zT1e7vtv=miu368H2Qso}gxzL@jqj~OJ?Y%v3iMZ%`A?AgpiaGxaV@QUZ9^P(PUNa76JPMV7}R8%mMK1v!A8SW za(%&~d7a60yuW~>sU80+Ptqm5w)&-+THZoMe!X^$?OpYOQOGP~;@CS5 zgJ>y@Lq;t_G|$S-ZHZeWpEsLKJx`4we$jso2_ThTk=hB7YjRdyKA=UWBsB`)@dR01 z5`2^*CPe}35n!_i7Q;R;z6b66MUTfUFO=%xfko6*cC(&1&@D7m+Yx8Tp-hUe(=D^?$Y8%Tg#0vv>_ET( z!DnS7nfrXy#y2jOF4EaMFbx-{H|$_ zS}c(L-!(qeeSyU=zC`k`j0@|zD?a*q*$J!YsD^PtT_b+sQf(|wz~o)@Vnkdw(pG~B zD}=KV#r2HYu@6SuTp6&LSeB&ki&2^6HL=vuqr>tu%_msuX~`@x$!W>^G#8S&{~3qe zk(8Hz$W_Qh!KO(nNl9?qNT8t5FqE-RO`9JTw}vs1S278*gD^FkLZAH;y(%)vY1VfD z?3w`ZF}!>-Vf0GPlGPZzrPg%-G3R`sILZWHz>0@i?qX_`oBTs?} z5xO%bOxu}+ZyeA??kOpoDC-;ggfu*@BQVvWq+{27y7nA%CpjndWWx{rf(#vFp=E>@ z@`63`UO1(lKulGu8jHeNB)FmjtscG48&AHGFm8ZS5Lg7BM|P-xf7tN(*Z@RNgp!j2 z>+k*nHL#UUH83{)c=%6T(GApd^1^5YHA!QBly`enkDL%GKmC)XGo#7KyzytFTUlfD z^XRYOD_5j>4ABTdy6@cCpqMg{j1~KUoTRs8$50RGHO%%CIQA>Jk+oO{WolPE8czt4 zsvW?D!@dT}|JapwaVL0XO`QpNe-4Qv@!9Ri>S?=~fSao1GZ z4M`A;lBr50Vm=e;yd?6VsyyWnT^D+$tk%Yc^W)TjZc*WbAEX{cM1#$ z6Bk5n6{E~50gQjv*?c5B{wmvmbZsLgc-%7ZA`?-C$Uga1x6a+VcNVmD`+(6$Nrd`; zRT*0W-AUNxQ2XIG)`&>A&-SRjoPlg~;*b0m11 z^P@hQYuGS`B>)_&M{lrqkfsiM?hF#e{}Rc&r!Kl&;(P%1wq^pTv~%Z^l_FQ_9NUk$v)G;+@#NXxG4~R5 z1iE(b;(gArT5e_$Eg0T=(c@}Qit7I8ng71NpC% zd8Z`+dJPht%WOE}mF;&ZdoDNB7q9}=8aP?Fvm?iyEpURu%bk4ue)* zV|c)jP_y^+6fM|q;?R`#T|r^|H009 z$%XYMl(k%3+3G{^r!Kw#u=)~^&zM&y*X`cdz^Ovj{ygo=GSl=7m%^D< z!$0~i?p)z#2@e|L63-$N$mO^0@pm?hJ?Gs4YIf~vREP*EzPnhu3tkun>Rq;qHpVr! z6wJ@y+pbNg9q4rUGY~a@Noa0{x10BjsGR=&;_dsnPQG#eyq*X=z>e%=D-z-d>!YBZ zS|?k2Tpyd0>ccZkxJsEA@lc-=#N9Z9fBAboeNeZ&gjXe2R`XNZTO4RN1&B1^?{EJH z&o7xxNpF7L5Pxa_Vx8$4IRO7Q*q}m~JVr~J1qHi3xd`ZuYmvslZ zm|yY8AOwY^^iyjq&h6Tgcz@3Fb^$-0%fA)_NPFAU+X>f!Iy?$sZLzUq&9wNpFGl;qu9*#7Xc z$-I7tj_>urYRhx?S81QNKkT-?D8CZ-J6h|Y#qy#4j*h@c^yiLH^2^uNnsFy{>8@N| zypM>~u}nTA3;sd>z4uqM59c=@{8{>~Z`*`dx&SFXphf%0Dw|3^BY{kl>q){{k~Kc( z)D)!0(QGO*vanXNoEA@?!K=nlD_LKa;g!rFU!R#olZ(~UV(!^cD)W;2FqK6~@->y8 zuZ`{{Qemx&8oS-zd76XQA7raNI;wky?VbQ}x!Q>8mO7e-G)}PMmjH(_bqWRyQ<_K6 z%&GYRGK1*Iu{a}JF-8w698G!$VT~M?|s}eWd-SA*O*m^I5MkAO{#%-RYqa0gm9j)r?~h)3qh$OAQG1M zRe+5_=_RVZL36{3W^!%te87C6wnJdc@g6mJWQN&7)GuHrB%#j?$0_G#3XlJIAuvzN zm|+G_N6zyV1|?U+44wdN%^p*kY_l;b-$3(5f@jH>@Ssb0;wV%|XXVPTlRiUpt+&Nc zURuBI3=zPNrfr$8L|up$W^xs5jT0M#`92{?!|@?Q=WGF&dmPwo3?h78BTSME+@fY# zC*AF~yqM(%sjScRSq0pgpK=0~@e1Ps^~^q-##82NJH!{}>#sw`nH3)8m*(|0gzCdp zpSZtp+4?wAlqd6<@?uN-!KgQj*69ZHhpOMTI|HhIpQofEUi?~TQ8*&{xi)vD=2mPT zH7xMyyn3vBSM_E0my0~@PaWed2_IUN4>V@%^cVBLXX;(p5jiQ=T6kbW0H=rgt zsfwG449}~ZO@)Oy?WGAkX{${eC^bfBUXo@om8@rPp(-(@jp4ub3fVqZ`mevsJMTBn zR!FHux?qIe-AoFe4KvlV4lzS0+ zxhJrYVBw@nQ&ci7Q3WE>LZUZ31?cz!EV=WsHG&vPMmz;fR$^}yrvOd=&Vmc-04&kF zOmQjW{11*_X}akSM8%JD7^6z;J!+)wXYov3rzxEoj&<~O!id@#$j7i^A%1~MDDa>pW9XN;hK_Iwkp<7t z6dKPx#nE+>N8Ii4M(IHE?vv}Nkb<0$1`+4p+YH^i;-MP)kQo9LU$+a>?=G{7B`FFc z&{C*+0E4!18`BJpnx!z6RZ$^g8fZrE**7k2SY;Wf-O}E&O*cQ?)W;BI&cq=cd)P7} zy((BFRZ4VVzAQJu=Fr*xh0A*PKyH}iGutU$dSc3piclwg^}PwcH^nNIF{hxg@L;;v zOfLoAVd$$`c3p$JcKI!w_ai=@TF7*JTlSYs@i(CZLgPo(PUjB=UOJ`6FR6=0w$xwn z;`9VGX$d*2jTZbrBhqezmW6yL@^~up1(fxYY|J$j;!OV_Bm(Hr44Xmvb@BFTA-pmy zuT}JVv#juz2EyhV#*Hg{lSwQpA|KX{u5P-z|9CIL;=h{Cf51JhK}otxO!2PrVcsvw zP%Ln?LNgI-$4X|-A@-U;Uo$5?hu#&__8AJ^&#Q)kfK6r^3B1qVL4rvB1TcjWA*>Wz zdKQirS|qVm@*IGkpD!61L>zeq^>lsm84R8`40rd?-WhLi($aALTcJPHr+1an?2rQp;ufZ3rO zk&4|*#w$$TWsWCEw_l*CL1@u@YDzGABeY3ASuv;Cx=AT3vEjxW=4;8nlHmSCvPIY) z+r2VR1|+v0GOe&jQ1mT5k{fG_m+GZ2?vTa|Cbbrxg2Xjy8Sxl1=atB(Vk((`hMQGm0(lRW6n^!}d&|5!bUn>;)gp6o(<)2!;01H)OjFi(NIK!$ zmZOQ5147uNPOMK`zr6)3C%tr1Xu9%WfI@?IvY}DE={GRZD7s;0XXrz8PCaU@Gtu!qkfY zlmt~e1u%^e*6iJH!`cgm9wF_tX3n9kW#=FUBF^5{=^223q1NbGkX~Pchh!LEhLjeV zf0W5UW~}z$t*DW+=Hi*Rn__<(j=92G1j^S>mwlArcx^bqZ)K|FES2W`{PR9l30_}t zc4#I-Jjr;Gf$aQti!5~3IkXTiUwCt)9zqH*fNH z+nKoi;w=~b+~}h;b@MR#_`2=9Ako>{BkSp^QN_HVzUj+*`G2cNCD#7Luh#$dOl$FE ze+*t8xXz&$oqjE2-Sd56R0d6!IwoYLw67j38)qlPs>zM*yo`63uhA*9S zW10-pc2(r2Vi!^r_|WnReF#2J#5-1b*@qE)igM=OaxaqMQ{9&|rqe<)#g;-g$cz=%OVwUhzHKCi5^ucRWgGN~wjTiYF;jvr_OdtM*{54GcVY4NURQ&6 zl{|ZbWtC%^S+O8Hu=p2{5+Q`ihs4A#A%>C=#(-ePPRKGKQX_O@0GQJl%6BTkT>})# z@V9HEndM^yk4AB8-PulQyqy3g*FuP%UAVynBY&hpS**^ZUYU)05!+~7S3aNH!S$70 z_&qv9nkQ=mz{46Rw@DKZTN!7a8IBVpCMYU9!Y~0x?*1C)rzCfW07S@3uN@9p>H+>S z!SF@0@doPBUus&BNjd1jrCZ%>+68PH5$V`76Py(UhbCO6fOSq4f%ybs?+o98vf5g5s;p*{J*0h|_vR9F5w{;CYSK%W7!`U%rtv-05 zv%t$9pWF4t0-HGr!789#+ny| z?>>D=K3lqXo9?jeq1AVJSUy?7;W467YW@dmLM_Td&xu0qWS9;sT#eNRuZo(b>c|$N zz8~3&*#!2k+`fy*zyCJi{+l4ntl3>I2xBhKLfV;J;;& zb}-8_faL&u<0MIR=d8+emB|>u{6*P;=t*av53wP7TAV`u6#XMp#BrfcTgH$e8xAot z7IqM#;;hU5H6*Q3chyf)uuoEuq9>36=^|L`fo|+m6Lh)rD8~A#c4}QHCATC_^8_*P z5=J3j*DH;IRpP|OZiB8G`(u)3XA(cIvz>{=*@+)qGOucX*gA>CIo1hi3Ph|}DK&K65&kEJsqad~jj(Ndu8x+`yv za!EAFiyLvjRt?@$lFQ!}ji+bcCh$}gs6GP;G>h7F;=f(G z-Udi9^&1|z+&@Q`8Ma{i1BYx-!{_0fY(eUK{;%2K&x!urz5`S%xRG$eI|}psxf=y@ zbr8cGGs=lK<@_#THZlbX{Ra9^IRp#=LsT47E5%`};^9i*h1eo?pCWcUr}(<2^i(Gv zOa@=Ro&pi}=m%_iiD{-gNYT|_f$#1EB#WDP0uTU{9?!r_U$sLqlMwm&hv@ZbZRHBs zG(~0(1?ZwOeOUGj65;>PfH(Y6>1zb+bxoF~lHm$OwS11-av!O%u2N^5DjVlMjLAxE zy|c4|%t~?c#FnHBMy+7FfZfY+Bz6)}cfLFaRs- z449vE*xL+?{NQhDbfIW+e;}7Ng02_gbr2Lg^%e117_l!bPdavQ3^1H-gnNG-_)%eA z)x-QHMW7L=PKXuYuM~CbvuEJTlj6%OpVT~D(ll*K_%E|tY=)(R+^Zd;xfCxNMb>QQ zVo8zkHJ(yCm(tV^U}62hvN4f4+^S&-y|3un!MTzu!+sO9H zVEf6dT&~i*GKL3?_Yr&cFawN(t?<*$Htkn(rs%q~QW z@hg|kMjKj1EZqoOX|CAgiAjnmfM`o$pNI4 z;>GKk+955!Rp}w$B=<`1j*u>_Sdr)c1{_%bgwDPE-=!xkFQD2~w)mfH)nBjStRV*7 ziY5_2u9~MHj5Hfo39c670yN;@{9gZEScqM0w(KH%sC8xZESngC5O8HGL=9HSG?2 zJ&m00W0ubD@tJt_ZOs(@qw1{bHJpy%`%F>XiBGwASmcx@h5tcxn!g+VidCx6%#z6P z!^;3+5fd@H<#C%e|G-YwepE$xHPxlMo3XNHBYb{CFvy^~X2U#tirV_&3SgB;%W@$YT9tY2OV&9piEI1HDZJy`A$iRDXo8q|C*bTBHmj7>+e z<6kj$fExQ{Vn;*yQ%NF_x4NREmE)&TVL(KQL!Gh%0Dm}K`RLfQ&r0E8jr+G=#M+uy zhG)cz5>-{)&~u_nOVnl4TFoU^;3ehl@6CJvFOfPC>Z~x$-Pq?cbPaL8L6T8b>XpuGR)$`D_hQs+R7^nj7=qr?Q=8$Iu zx20fb9%GRPAZ91fKlV*4?vhDkv|A&r>%ry9_8VQqn#>E>d%)-Y?(tn7-(vt!7!`iA zVki8JX&PHswvJkPU?6P&rW28DRF_Z)*8I3mguRn}M5(fzfyZ*0=SO&KQr&`z<+cjt ztjKa9tH`jpT>*NBv<5hZdbTmfy+wjgP)lv2WDjKa#4Nt3Phav`ijtJ?2q2|jT)e%; z)(OU)rkjj{uTsGh7yuxjV2%d=Y5vCqV1^-!J@io)aCqp0i~Yhzr>~D^(H(vEl^K00 z$}-B(M%mD*$h&-*=a>Y4i4gEH%w37kDHl`U8ywe$u|%rnnGLZVP&C<7*Gk`N9+TJb zhJuIr&N@0f2a1RLquEl-Ig&SWUYQ)4|798D&#NBSy#6`CF2=qi*1Gx2<+d;WuS9Bh zUIt>?w4aRIYN_@YyVvDaGv-q_ip@9sKX2r}KCZv}uj#*^Z%@_f^PMsl+PIrd4So{x z`q!VyMaa=!@TC>pbwYLoAU1f)^i;D;@^OPx^3}doh}H1J=5G)2m>7U4_Cf`V^#YOB zJUAGlNlLAb*Kwc)bKMu;0sr*U3NuMT5~PO>wF5>hS83`u$!;k}?9ZS@)Gb~Q65p?z zM>{U_7cy}aiWUfqWwAS3*Fm-pX4#tY<=9483EsBXJIPHzgiD^EHpag5IQV6lt5(fO zN2vB4mRCbj8?hhHOKA?(10h}A--p}GUt&T%Gm+2Id^Wm0Ci=c)Hv690Q@N zOZ{7Zd0W~Z)ZOsrII7}1fv67aCH}aLp{Z)(I^%S8CRNu@AX3yNy_#XobDD!uALh@` zAT`od0beLU=vB(LwHU-wuP^gf?l7hs`fPg=$Fjy+r+9rxeI|ND(PCo(;?#A+S$~9H z04f5K4mYsQ4tPXoYbdlc+(~B!~GnB(u9fOBZ&d+68sUgi5kQL zfP&rsCh>&T=w^y~1n3P)Rg~2+?MLV8aZ3BtiZQ(p&`oA?rDZ(aaSA(Y+PMs zgk@Zr=jt0)wLb}{OeQY0Y@=VGa27Z+odBrGfFf?xth_uiojNB5!tM_HfzCJMW7R# zY1YxjSl&H?)WKp{Eju#Jvyv~^8>Bh16jP7Qo*7RmX-qa++>|!64PtFQPlx%GiSQo} zrm4r*GP{4><9d*VlMU$6kg}>}ayVUMznh;T!P3r%CxVDs-;%{P2#o53N$>yyIbaRt zq7)B=`JuqvWr|Q`k}hMPJ&3iq1|q_pL~oei1t(CzeE9(OowY*wR3_g4>bc;bRaw%C z=dM!$^xs0fa=9`9P#fd1$S^VHS-NC4iCu$6l`}E(5g9}$*08Yc>~i(NC-1|f*$*o{ zTG67ud^=@g&*Dd!pPUNIZWGJZ;u#G(zNRXu+CE!OuFdwE!^wqYK3m%BE&aYE#`nl- zPQ`g(ILgXf@Gr&XLjCbCbD~9>kiW4$-^?-3a#@m!KEZ!$Wolp@Fsj-+1YnZHkcM?@ zK;RGXH^qeRUE@&=q3bNsE!ga%i80QHm_6E*2=lYuI!+1zDmw3&_j~bkC(LLi z$Jxf_k0d^$J27n?TUGj;h~qMv@RFD$ zZx_R|3(TaRycC%S;?|CZt~7|RHSjVj&DoHgm@|Y|GoBsKbmg!ON=$sehetWE7I)JE z<9DHRy+E!&D>Cm07OIY|=jjv!hb`2&zR5~rFh+E-M%REZ<$n@1%1^!FqsLZq8LF(Z z{My^D^#McAOU0AaHirx_|E|;h6xzQXE-aSGAp^uwhs}1Pj&VqOq8g|iS>6GAUfJ_b zWa6|<@vV*$RJN~L+;Xm??xfFVjo~vQV;S=c7~d$t(y?1fYx#JuT-d^F>1%IkO)g!< z|H-JAd2V9>v(`n)PH$`^B{RJ1X0?S-a_fp6Hm-L3DKK3!Z_ zPlD$RP?GBIGu)X-7SGdqK;oAVNXnk^UF3RN)`AHF4)@JW2Joj|Qg>R5ybrkEhGy0F^=FRmWOPnZ@!(POD zpSpAw|FWjxiGnaP(pa^0LWigW=06B1e4HP#?#}=r)$Xx3t1!Qu69=c3?DaF?jxq}Y zkF28S2wu$08&5a~x^H&cUQ-`E(bV<2FW`0}&ik{4HA|1JCf}}XY*i1tzQt2Xx7PmU z;ZC=BhCSb5YDYrSknr9QO_~9jEnVal74d;?$aidK;OC_L1!s;5MjqDWdvR*Kh=MY| zD~1Vk2_4Rarngno|R4&?6^s}LrXPB1qHP(RrHR9e&fKZ?%8k?H@BF0 zeIC!pbMfD5Ju|kV{Cyow7KQHAKo|XyIx)V;F-aPxzr8p$TwZTz`M}+Vp&y44WT_R6ox3CH(5f|UQ zeI$9Ya;5SnhDUl<>hA3i4`bWhx}y^TM^Nl#u<&%_+r9hu9*glAYq(%n5f?Q49Zy&D zj|fFQ;Nj0qAJdA(@N1^O&UukCwDHL&Ap2g|wIp`W@$QPZh640LiS{*Vh6Bu&!RywHB-E~-Uyaur#+Q55Q${$D)rPC}J(bNU4` zV}3h5hU{%m7VlkoiVgjPjhK-+O{L0|0?Ed;j8Fmr z3xpwnCIu9c4S?_l0EQR1+{@=aO?QMIImuJp* z$LY-aNfy4o-AT?;3EMxzQ;=#+228X}YBDx2nxJISP- z=wEc=Ex0RftT@mA+cL^7htw^pdo zABsJzqQ}#1k(M$;q)=wn>airU`fq#n4{8M!aT#ksKK{==9_7q*sE9LvK9|us_AOM& zI+gi$2$Mi&c#CSBW)_g4Iu;?v6GGF!zc7p-Vo-3po)p9?82wDG6X^;~{ zT0j%y)D|Q?3v|*|D4#_O5NTS8!>&Mu7N2OT;>DNx+OOUQF7MYY7l@}-h({aOUVb5t zTrPnV9ASr!o+iHG26yn&Kdfyte%K~gsB%09`$ zw^$A2o&KQx;pTDPuAkRxec=*mooANuCU4SjdRUzhaM@n!I!@rx9~VF?=J*=u-44!~ zLxWOMa~7bc3PC`Ac17qVszj&OBQ>G5CR)IN*uDwYuahzE+k|U^#7qiJV)Um(ggb1n zq3C(tX<3a6>HD@B0RT96!}!G3)b$z>uXw)XQs^c|UdgVd`bBfbo*5-fY08uN2Pp3u z$+S}J$zUlc1CzEHQF98vI}r1Vf&(J zeGI>BVM`c>_=Tw9``Ek&v-7eiYCO-c<=QC#?=0wc8qyVTzMXUb-U=dDMxf-u=8>>! zYWQ|dM7+4JNr#kcuY^x8l1Uvds#Tq&Y&-#tu=(84g)U#*|0%?z+C82`8LO&^d0T>@ zoj}P>opC$Ydwwke1iEDw)ILKUj?zsXh4`T?p)C5C?5A}mFfNq}tJR>)Q}2-#iao>e`KS zXtfjAV+r9>FD`c0i5@!zI&o$iViGM?wo(rnq(_nrEeXBcQaN{V(h) zWP$oO2r-{=Wka`93UppNCq1_Df_r!7-w}DhD8~}WkM0K&NB`DQS@i?+?ztzcX&d<0 zpzx;e<3gDx4p4|qjj{BdE#N*VoSj^XOO2O|Of7DuNmxyI|jUAO3pLEV9ybgnL6N68a~_PhUmD zTced#Tc9qb1bU&Vv5ksrZNsnJbuH!KW6?)MP$qMQ2H_r~0WY0%!FAbmTO7xY_k&x+ z%WgQ1k(UXxF+Dlhy@>%qam*0L;nHEUUgY-@GAL(0!_KU$Rz_ z#I0f9{@aeP0R$tKCMbwn@>O%KFk7cyYRK1wth#zlASact_-dlh2 z#W6c`d){X)cf>(&9je1&iEPUibY&eIFuOihOn2cvwqb%tmFcz=x_b%T{R$V%`LfP^ z1Lm}_gEUZxC^WK$qxX3!e4(Rty#P=s!Noi-cV(R;L-yk!r=Y@<@dJtlvrP?kN~IuN zDo7RaW5J%*mk5$B?S6+B*M`4~m~p`hbgULAoi%n8VF6@)9*l5$U2HSmBq zPVhGMQLt=$fvdRjF|sFE=27i}0)VDKq}G&Fh}r_-gwe1t&;U1umP@9oqvua%3bj4T z^#k&bs;yc>c&C7JA;fDhj2rfr@lBM@xfRAjb$a^msU#v|Nkl>Yx4x)gRTLSz`t879Lp1)+K8^-(*?cOic+8WF7PG0+Q(feKW&wEx%2O@l3 zSe=V0XSgu5MzEdMc@2T}JLB%?BA=osR+`6rJzm|7eKQ(cQxqF65x&?FyO{fJq&U{| zibqwYXu~9U#R%0@N!<51efHdGXAw_fO}j35Rp3X4x1__oGOu2%Y|$~i2iftRBipbM!-O$?Lb{{7OSW`T736uY80p z-4}bQFNta0`3cy)NHpcS{4@}KNZ58X@)LmKK0r~|D4BE$>n#(PY^_!rWmL(ya%H#e zHza8MFi0jGj7aYS@R!4Qof1|Ll-#g;F_T{;w&yVVnv8u+H8`CeGH zsH&5+k!Lq4b6DAttm&IDl%6AP5Vb^!=b`0D=|v1TA=1E^aFzYf*VH^z9=n(6Wg-ou zK6O_;wNQ3Q(mc$(TUQ&O6Bk^(O`gilwB%hGEl}yI>Cf`wmu%~>^`~0$=K9}>o9ie$ z`DyCyow&_OM%t^Xr8`MUZ(<*$Yrnm7j{EuU4NKL9TSo#vPo;cK5~?^7mG$tO$-Q=& z@H20b7l$HV>lr;8=!3lZpe1=E_D#~~!3Hh;BcpF6cS9yDXM-~&5<&ge1=j3Jsi))lITG{%)z$8-;ZAb{255I;YX>uwso?r2YI01 z3k@Pe;?TwWJx#+kVqfRA{12j6Rvok+LoM0(hfqt$L(Eb#+vqj9_I1>|%9la*8l+3!CB+o)0%UXL}atix-C;i>xj7R{yN1H?tv`Lzpp5 zo7HtNAIjECm?{&{p9K7RiA&7|J;51g9;V!@lJz!JZlJT8lvoIh@tOkCp%b9M6lqsq zVqNfAu^4%{H@tpD8m3fi5%Rf)Rk@g1m!Z-JtELOt|upPNB2OR!r!W(P#Ec=X8U6w_h2drY_|^ zM@1w}X;aj^F^mQO(Q8J`a7!nnx1@2&BR9{BS0AbDN|FjGND0jeo1YZRJ#(OR;_mCy zwKwiA>dw^io+AtBf|o2w_jp7SMa}6#i`#;v@QcXtKe z*X-H2eoFJ-$n#G%0NfpZJO`>MpgE~m>V$t?dPOP}HI;-hG^*HjJ|mZY?wQ~B&b4{w z{j`^G!WVjNZlTNSf^vy178b@bGpSuagj6l3^sN?4*M1)R!dxpll543_7La7Dvge&- ztf=?=WM+8bWE!_N!r;g8wJlv+v3k6Lx${VMy_PVm zsHCj!6s}IYo;r-di<$EyLA09%vx=^Fnw$|eqHXY%YSa8oiwS$zs%daLDZll}d|K0UJKD4ACi^1Ssnx2JF>|Mk}+!l>ej`oQd1V*?69-7wpsBB!A;G zFlhk$WOHP;4?iZUUZZ1A@@NMT%Q8k@__*b2xQscP%vqC8i1a<$mM>Hh8>;h;m~kY+ zTA!Qf8hYB`<+U(z9?3w|Ga2(CULAa4*>Hcl-Yqw$kfs&E*mb1L(V_I`+;0AdF`+U^ zx;BO%2P*EE>zBW%{1~_2mG*HwmM>8Qv_y|PvWckXyCkYAeDGUN9+4ZT%I5IMcUA$R z%O~HoSRli7`F;JrtKaE`P{819KY#HlD5ABFh60`ZDi-mPjL7l1WUt7BghrqJbL`8X6^TkEW_m0g!1@hsUwxOw2 zMQ5ZRZF>Dk(N7pDU-0w{C#{`u)`jb@CN@?tM@p4%O*ro>;i<4F(XzN=Rni{Lj*9?! z)jV0Q*YufpQnL^#M$*yR%1lS#DuSI=RBy6j?s*=BtYDE;p$wc$uRTho&a2%z9|l;B za(N1+cc83MM#hH+&p7_05w(J`2d)yGao$?^2>z49t5w}hnpjJa9~BXn1v(mV%%y|TwS@l4Vvf*l|E&bp=?q!7b)7Ppq1N{9;g%W0> z0!CmS$qBZ*uHQw0Q1zbDVGc6t*2Ll$aZ88v0;J_=LYd*aF7fjOZeh9fJAB5BbsnZ) z@J!rVgHYD8(q5SJkChsEwi%Mb)b7^P(m@paV@zuP-<#pELY zshEy))ryC0>LS^}rZ|};vJ+mq?UcZWP3i78)){Rgxp(T6Wxp=qu02`8;_QCduSvcj zOQsqv5rzN{1;o&Su<=W zwRbU?YXBq;&%;}(dcmhe861yec;ro!=msHkX0JLHnbj1ev?vWDlC}`dkCq#x$t_?N zSGNp3HWbL;Y4HK9>J1suixV6AB(JPy{LtF)5a`YgPvc4sNsdy5?AD*Y4iR@_(ll9U zh>G-jrrYGaMS<&xx(XF$7Y72DvcH?#gB6W@KqI7@H_3m+d&MZQ_#g3wSKmBwDbZeV z*$mra6D>u@h(74$U0N*9hFHMNrndV;_)_nX<}7|J%p83E0_9Q}`Yc0PIqUj^*m0iP&wS4E=?uHVR50|cA zpQ(ARRQnNP=cEC#`8{?0m}aJ(%{sz8Kb_<$HxOw3TGVED^%J~)Ve9f`divn^9-E_o zz?71^Yt8_%))UmN-jwsGdTF2e6KB65#FXf5;Q>)r{f6xnTa8vPttiJiKX>^=loH}R zu|1(iv?9YxJX9OIKO!y9cr58Mf@)|-# zpUomoV$y;E)?tzhSEWkvQj*V8h5+oe=YSih!0A(^JkKr_sC>wM@hy$d?5)h;%HkG} ztU-pC?Lp^Cqr3 zldkl)8>n1@mB-fVzy9)`VO8bh3hht#g=;MV}3VVCd$#XYi-Ta z$IsXw_7(PvRI zhV&hngzB^w@BEY&=PD;V@Tx2*vRWtq;YcUa20;If1j=m*D`h zlLDXNT)-*ZW+_q$NCBYmKS9Vt)vP-YH=tDA+wI5%Meq4&u^VPgs@VX(clpE zkMRpU(s3Rl-05dVf&=GEOXtszC2bKeFvpS+At}(QlqQY|6#%iNfIW%GrdYvWW5hV4-tIW={L%q|{X{epKon7-gUG>@z zf1wqAw{jP1R7yD->l-A(Y5O%7~%eCIszL|Bi zj_%sJr`nc0c;)W2>vx#^vx!@>mSI*rdY+aV%cnHJmKM7FnzAp<9^TL*0Y9MKkh*S> z!PmHU)*_dJW>9T!qEkeye1@$!>oM`9hYvXd{X|F@Fht1aaW7nz{k{$19U`*SL0@wT zvp`d>AxY+%#PGsjAf39=lRGp+vilR)`HZ#`XP^xkoHV67hZB~i>NB+`5EZd^BY~TY zXW7WW9{;Z~f@1r~XFy)v`vrm6Q3h$@6j(j5&T=J1>S*Q03$2g!AyIK#mgnL;mISDX z(gmRnPUbJlk@yS(5GWj@0^cL9OiJ=M5!9EdC%`%&M!zq0hIt5b0?_9=rBY>ogYMZgQnhuMbXCX6~@1W{(2i)-=rDf zw86LS75Gj1L^aEzoE@@~_m{xq)*k5JV=;Sx&;-mxJd8MfU*(P4fbEmPOP=OPPwHK! z%)Pdg(e*L{gWmVUh7Ujdhj*m?FaWhBldzSh7Bg2p42SVL-duvaaY;CzMblZ!O9UYD zKvXbFTytaabMK(;2Uq`Lh~FhC|2E6Yz9Av!7yjdpH@p{A^FIV|XVt0}N0ya6)K(y( zXDpW?qtkNM8gfz7z|v<{!D8+h>EG;>Ou?)kT46-gmyj=Jdjp}lK8c*~@^I?=pa@|~ zMoSGq7!k7K1K`K4^7sIbx)Bd$x9!*g)bvYD(zPpF89K63stL{;vg19voSIB5nh$C3^N$;{J~^O)vKuVGlLglBhvXv6CS=7HD=Yu9DSy z&TyFzzLu+$lHGq}4Ev)xfxpR|3EZ06(7i7d0&CsW$ z=~Zpq#te`*2Yck8Cobjga-&e_naiXprE>3=AIW!>sCn8Xl<|NlonLAG@K07cG!+Ex#b?Xo{y-&rpdj4yFzxxS1i9ejv$>Re z)Tb1yP^BEc|2G=8HWTYRU2+uJY(b1*=ZWAf>(fr=aC)DULSBU zUNyJiGs`20ZXP{~fL<@HzU7Sesi@Ez^Ya|-ra&8fMqw7DMyRq-s8c;#P>8>Wf@$Hb zkO7MB9KJA4?%T1;{UGu$8WB=*={*S-By5BFW9=|qp?#k)%aj1cR;4Udm<6vADwMEo;{tMc9 zBPH;Fl8xH8r)3MZkYIceaVqegX%_u^=q7 z4ZDy?`)J_oaB9LE;ZRZBY@4-5WkHJ(CvJo`{CVy|P*PA!v(yM3vuZK+*ZK0(0?%|7 z2@lEUUDov1x09Z^gCgBE&Cg445HqJo->-UGgw^>=q?aWZm-k`~< zguhT(`5cR0QB`|6xxmnycoDc~73PW&+lS~XdxRn6aQVMaO$wE#TOMUv`7C#9|7#@s zJ59RxyAf5L@TWRyFXvnN%VdOeYYhdXvI=n}Zdvd0UE+W}9WRskN68}?pyh@8P1>_) zO|oTdgynmnN5rP%(`SwJi<4`V~pK51zGxkca{bTG?X zj@43W-%PeYi6PT|Cvq|41gG}~SXr9WQ^G$Jgxoi4wC=?xsjR)?n}4>;_eEHIU%}ho zh6m7-9U!WO}-+ag2oUhEBQ0S-}Lwj!#F}oRy8ll@)4 z_@@CQ^x;Q!PRC0v0>|0{C7wK9q6Zb`@O`%wCt;%o2X$r}-eR4+Mjcl^vwUrlwL=W6 z;15SBwoIP|D<{u@xTMYg>;5>8r?Zg(y#lLuhYVdUqfc~9Ru?>tIoq7kQF~WF-Mv(0 zh1WD2nvJ$R`(ILrzTELW^Es=Cc^Fk_D_D3l=R)br3;qC;Vw)8<1v0(>r>j87L@1fU zSM-rbX+R`^E2OpgGC$JlHZfd_c|kBl+z4T5v^kh^%35v4v8O6{W#mG5h0ZmKXR)hY zAuH{_4%J=HMh=#d_$YG-ynR5f{eJ(`P>-F5XXAfH49f?n{{^gFm6-b&+nDFstLyx{ z0%tl9Rm;)O{;~30_W*oFC_4x?3HzfuGPvm~Ob!_79HYfx7Lxrw5S)GxuqY6E;ivQC zy~+Q6K0OWhwSqsr$_nhN%|E*V4fN^|_~2@4n0DM!gWVLm1+vzLrfHU4+qW@GF+3cx z@^Zo=FQ>drKiM0+?Rzo*eshYY4=JBUKl`n2@#oO7Wka+r=+>WdZwO6oiRa4~9y2BL zWmTXqm-yk`h_%sytj-ee;l?M-H|@IbkO}F^Nr8^*Zoie91p?@2k9vA%Bqkm0wLA*0 zuILjux^yBI@Wl{UsH!X~4T@^v3yfYnp;zy|_GogYjOn`s?f9DdBiiRHw-4cIgTLtU zZi6C3=R-*9C+~5DJ6jeE&n>87+d4c9TrTq35|2KlB>jmR1q(@~kaYqr@_EMt#S*VkQXPfFDs{$F4p{*-H> zEF-2qi*v0dP?6_n3ss#fjSRo_*tx6PvCwu|B;1Q?%dB2`P)~96f&~+WQLnRg^(BRk zb!aJ(HPLr6rjopRez_?<%$NUAY*0M?-Z|~adHX)QNENqA5)2}p^{Fe2>SK0PTxiKK z`kjBu(-NnXok1Mtul-+NyxRTl#f@}}MVGYsbcfkhhm2$usXwT9Y<_XkerwsK+|+Id zd|y=6z5wrA69&ssHj3e}w?l54eS35N!aq}&Pd&O=s3ej~5<^zI|FggSlpCO6res%c z`x(-9;#SZiad#&oR_5F!bxiKUGWAehI`11NcVPiGCKuhIhOdlnNwFa&O>zeigBMJH z9#W`AF{drhb)@iBCAM`n$R*#kQ?)oWWj5Z3T{LgJA$_Y^&$>6{o3~YNNIZPa zTNN#|)JeQB7^y6KzQwpfVXv(p`Bd}HQo&R0hX)A{uFNh3GqFiH3n+%^Q^=HG1g|=w zuK+Bj6tuU1E()&X6|lH#GKIm1^T9AsxYA`RA3_YBg(G({4E-XXm)kFxX0*9Li4M_jjR zQVB1ks+3hFNm~`Vrb{zUx#WMY!2 zRuUmJ-S(2e!268PK5;3DCAg+i2Hcli{p~L9${Q`haslEyVYTQYE%QUsNl>gz!-Hyh zeEXzx|HX~_rxpI`+2p&Xk(w4R8Ef%oL@dy6AbmFJorrE_oV36g39Q;ST7F*s9#+G&DKnh?~B>#-1E4@ zh9OrQ@R*x=_m*Ew^UmJ#e}wW z90}dg=?xWqk^h9ShFy2J6VTeVK*`gk2s3o&5;q<8R_m!sNr=06TInDv0)I6VtRy*l z{efwANEQHma%!i?3{~!=`wl!T6!GeH4i9mZjRMy&Cae&dA?DeSW`7?&4mBG_j^mnfBOr zxChHZ^ou@Z9o-0XMpqz9c0tm(6^O$j?8@c{uLndb{IClYubHm!Ls&}mja%b8MS2ol zhh%MO8O8?d@C%-`(pl$hXsoVYKCLOcO+gGknQPfZL$s9%5+ejPi046v7JXlKIcph3Gu7xtI zL#t>)yO?tpA@yQ@lL;_ChgD=mK%JuS%DnBOR{`_Vu(Cw39ck61Fy#Y1bE4DN^*01g z$+S>&m>BlJJrk_r3^6(-vBkT(~;M| z1mkGCcT^oQC2gKukSN*i-NrP4_ZJ0c_0S;CS{Vc1hmGo8pbFZYvDBX>H4((_v4`Ef z%rp7IQ$2pupANJFq^o#G1o%;;8Y<#bSke8DihS5DKGS93KmD&j$NmuOHOT`I zXV*t!ZOdTkrqAFAbt=qX3WR7H(FhXZ4@$l-(Ybt5Cvk>97E$Z51eNxXNokSLY8LaT zkD`rM=f6FHK4{l5sAU#9q=Emc&h@%ZDHIaj9 z=cSEgbNrRql)L2N4a&!CqaJLM?02gF2eclDC-aw*>}R{{8)gTTnVcwt)YwJc8(a&M zFwDQp&KDO&`F*BUl|7ch;!Vv(XTMMdI4&Sz+d&N_hTTg5&-aHoK{8QUItJQV_5kN@ zVq)rqiY=5IceN=B3~xQXp-#iPncjaA-tNr9pPpkDVqTDMQPH_I8);Rdf_OVfItuoC zAChUI$KSy2Rvm=l3_JwHj)~wKeTUH%% zk1oVcl^3x=EwX;)aqf_cK zh_alTzRA}i_#IfK2{Bj(TcE*al*ydU)8Q=a>+Ryp?SS~-$Ttc01OB&%5>E2^OM>)SH}5^)1=8>;Y+PU210;!PT`uxfZ) z(2*;(N8CS0`@=vDL|BNOG4FRsDTNpD9k!CDkX>C`!xsOjA%i_5;}bTF8(WhMY** zS<2GE9-2!kASr(;LWmcsvLd<@{7~-&SL0@DVO`XwTy$L? z_X7xwHGcIbLOhqj<(d#8;PB!Iu6){Dw)y71R**`4O9_^ooFoI75@!bt(Cz_(jdCGNQTApoyvMq{?*QeRmrH3z)C9>=h&S}D~6J=sMt45 z=?5{z8YXXz@*+f<*shGL@zo4v5b{+LbTiLjaS{N%~&zVAz30cy|8Xa*!_eDeejuWdKCM2BnZ{OH*o|{TT9Z zMd3`UI|V52Y-w2e@jjdDVDu#xeJi~$Ar1aB_I(YJ5cC9S`M8SYTb+C$|OJ*viS-@J`P&sYcOHTRxbD{UvJ7)TPeTzckqJ zx99RdzC@XK{(>&`DvcT#>-2efGoB+WkqaRNLTbFxuBV1F$+49 zX5Cb6b*ZBzEMW@^l?@wdHNh(H3;5EQeqkWLmiigfL;8AfR{gn39QGigX2zrvn`$)^)9fQYnlm{^!zU_wCKvvkrp;gy5PM(%(!S7HhQgJ zZ`NUeMlyIOUAF4TP+XFPnfZGR`MMxaAgOFRN@igq8^{>xjdPJ0yw z1!nhxa)(7t8}DerF(Ok;zp{U%W}qjV&!03_37sn3ll-WY^8`+f)6hn<~i!itnVk@10h-k#1NyDsBqv1MB_ATTrz1>_3z{p^jn}#I=LLdt>m( z=v|D2tTH?iV=$X-I}MbZtX9=HBP);dexyc2)otN6ti(QBc@@acudLRDaaaS&r;#=n z3RFZjEqpqN>Nb!@JFDsDLFu-HDZ5HN?X-abG34jS$ZOq3E24n{(RrmcdjrBX9Zq!_ zjxW3UZCdyz#9g!ju^wMQz1q%RXh?6b>vGa%3-;zz2j~gmo3xMN&kTb}P01vT0pNOb zU>NNURpMi2Icq?+rJDA8Z|joHuhDRf=AgdI^=YN&0r-4I0j9lxdBR0dHTR`wJjhr$ z+R)}mrVtk4N=8L@&9FwcS>fq%zqZ-o0f!??$%ttDYSP)fQ`|#Z|9~M|I2bPQQLV-z z`JWmM3*JA>cCF4keib?*_)$dDg;Zd5%5{m9mpH9y+uZLV!TT1AHFxj!x&#;wl&4&~ zbWZjBrFGdps)T+0<=r*+FWW9xff5v;M2xv%%)ou#B=L9mqkiZ0**6yfO5cMCgwY0A z=`y5)t?@8XfklBgp~V*ol83SXBCs8<_dy?s?B<$(@rU|P?~QAW_1dXKtp}g#ev>Y36nyRbuKjF_EAXvI@E8ST8pNZ*;Xx|9bqh2x ztHqzRO=d?(^iq2_ehIe&ZAeNtq`~r0;Wal0yz#g;%{lk0AAE{Fh&yacmNcp4>Z`ij zW`clSMdVCJu`aTOsJs-zc5YYx+iu7?UnMPRpRSoRh0_IAJJ|M}INF=U5VPpf;yZ$B z^mu%YsCwNuk+vEg+w_o)ke;?X*K3RYGNeS1D=8Ue_ijpvbe_+qyjhs1Ney8&654e@ zJW+pa)v&E|8@sc3+JS*m`E)R;86(M}Tt0r7#EX&SdR|q6D1@$v2d))XYQUFMqHH74 zV(v#a?-MxJU>l0p5qr#S>PiSuJn3-y;sS}DBX)=F`%Y*5Qo1(w3A}8eQ!Vf$>I*mu4qg|(Vn*S? zb9hMTZ!wwh;mylKZREs(C8({ZEo8XrGjTPhLv-wd`gr^ZFu=lM>TgVjqpoOv)44JX zBIeMrv)U!%&?z{PWOcO5&2ZYV3&r=QNDd_Go8MW4L3o4m^^e|u4>2q}*K=V|HNgcZ zp5}A)9v-QJFZm?`9(aA1md(8@c1K<1o**>^GJpVMN>kn-I>qL%o=kbRT6+GNbk4=x z@7VjdbdcFIl1GB)mpxEBR?iDD9s^o|Jm6vLk)_4GCS0cE;w^EUm7!0l;llmK2w>kw zttjZ-tDlWA4;+dcI54QIaVfn!nJ$KIuUD<#dZ&7ZA?-s?q21I17%r19 zr@cUrpQT1|6Xba5a%?bqi4l5wYUyb7$2Q-z)9nGh8JnYCx6?Ic_2O4^F)$KYw9cu( z-f+om3FrqoQnQEkQA{v1UGLIY21zNHNHFrvrAj#m9)rf zjhfE>gz8l~L`>bFjm^S>nFwio*f<_I#M>=TVm1MIKn31+Qh`sc9j|N0BtJa==C0O_ z_erp~_ix|T_BTAgKA3+};Cor`>E|_8xrg#p4RUF%+|Z=&Yu$)RwyuMbw88E0I`hUr z-c+e5rwM}`=aT)O-L7{mE4)V?%Ql{~i~ooVYDq<$o@Sl3?wBn5L4HzYer@!%@n+}~ zVtoTQ=jd#cYc(+w33(!_x?81}f>e7^TlY^Mb|SBCV;W<{*!gNRtl)+rWh&8_7=SdA zP0f@fkJDf(%pgi8swRk@zW(awRVH-j6eer-#CuFWMRG!M+wR4TZCOkKOm&@F13NQD zND~N~GX)EqUWr{3G5xe~P9KhN&oqMyiYdT%CA=k8ehV>jYyQXWx zQMboK7-C+Y<_we<>2M$FWRO2B>Ooi`9Xm3j_R0R=$z6NRTi~^vBeO9)E=RX|hnxvt zmBgnA%h{GfHB8!V9ATBtBc#`!T`Nh*)gHx#meOi-P1YzaLWFcii?ha;&fDBl6FSll zSH0PGdx|~hKQzVOgi3E1f&xN?OgGUeXAK@-4?(>t;%@=8{N>pR8>Pzy&nsuWqrcr* zXz0m1W{p^Bzjy2arH!!p!?tuk?oYAc|7tWc2$yK$fV@>*i34y<8=K0j@bkeBAITv6 z09dMsJui4>?*A%O#BQk3>!8|K#-EedUfufG$&=UClAh%l%2NO8W3WoH42V!w9Fx)? zQ+lZv$JuUJjA~TAogLG5zacaFZkOYmnEEo_oEXh(qcRagvDTGmpE-TKte(G2rR|Xmr>uewW_a%+%T^BWFd6jG;L$-+Qg6M z+GWo|pW6S1P{zc$$1a#Oxmvxs{g4kWCr4VO@9Sj{6Br2dhiNB9`$kEV)ur*hAgQr9 z$ZazV=3U^RC~I$6)qdrnc;6Odc9l=|krh}DFoHV{uyEsM7ZfG^0YGp;<_H%Ki2txu zSk0EoOJso%o2{o54g>Y$1=OA}B3LOIAP{wE<5Qwao}WqAPO4Uotz47sC-Rwe0P`*& z*5we*On?|8|C;HLl=8Xs3HDmHq`4)bJV=O48pQ_)d85|82JacAL zx}t2<;EtVOTq#E8x|9uJM9P`$++eUyNRzNV%yl;r`IUP0;BLtb%vn)8ryeM(lHh`# zE~&XIQX@)X(LXwZvHyC0N6-kvjD1D6#byrias?|5GzPU6urQyaPgA9b??psFEv25g zWU!2UX~`O+ymU0tafMvfX3t#ZvPU@^Kf%Q`jQ2w2iAX-TKMx4gX4Z4!R*;1uM!S*V2!4SM$gIq$LfZ zk($|wNVYht~cTYDe*GAc9oc-i@JQ04^TF%D(0$h#z@W+%wp)D86lmzFdVUc!oMBZlu zQBe408WQE(K9CzVye2)=$NR-X5*qRFS33rlX=@fQTp04_CA-7htZy!@3Jk%KbnW?* zJBt*|7y%^BRWHxZVo{viDNLt?kIFJoD4D1U+~t7hu^`F*!!tl4BOsM3q42HQ<(6k}#?8?;8dmgBr*U@y=&F)1;HXw;j#(AI0_aK3~C}D5wsy?vJ!9x8I3a zqAS&%F3J};O;@pgwk@ESD8lf(@{gkzi&oaeeiA0LbCk_YzBn_KneS8ih*g@0wx$Qe zxu3MoF3P&n!0`kd&8BjSVjK;afsRsvA^<`x{Q=)XTngju%h zm&N~-GE92`?#ZkoZ=QUJn>o&Y z2pYJo_uV4tQb>Twl@GZ&?L*R8I|_FdhOSJwTIco3<(~T=N9W;{bo;nrwxFnp3pXn6 zy=Ml9djv}64rgi(9F=VxD4Lpk51gr)xiTv&+`H7QG_9PaW~DY>>n-1(-``)rInQ~{ z=Q-TxzOU;_KzT`t;+X={RD}0h}P?7M)uZYNxGu5}6&Ge5IuBQo{3ap^v6I)$wZk6oGgeK zvq+*rV8(M0V?`r)8k?3xi&0ie=C?Lpq{d2g$cUbI{J!UxLneN$HvCMIu1%5{XQ($0 z_}|Z!H=xa=51s15JAX6wwYar_G46_WB)nVeQwVh1@{j7$!`iyg>)DC`HRKS zCBe%^3H-cFp7&=CdDo0kcZM)2|L7dA4{kq4&61_2qzVwN;;&tZ&%7W1cMbC+FF1YQ zB2`Wm{QY=3fv;m$)zAtho|K;0huYKT-)Hc*9VxuE`9U1FF)Tn~&hXi+p{x#~;zKG2 zlkpqRe_27(d|A*oLCAs*>>Ux}h>}FxKpdkhDs7-H5s=+F>CfyHF%D3IEFv}y>~{kR z)2{N7C$b>rwcM5e-lH+BkN-AiUReF0wi`J zhOG(N3NXf}^Aevw803($bEtZE6U2{OnvQXztOdo#*@#C_Ucg76fHP1EBUOS$UxhlX zD)4k2?sCia_^u^5Z1*8T1EPBm{Pz5uNA!*Kxv>BF83PkzpoaOTjWoQi(@TB$t9-b< zm~j@{iF-fK!UHb8Z!CQ@*^!gM%^L3H$R#Yx?NUugvZ*Qle4n+iwbq`{eRYCni!@Zk zJ;frS=TdAE$)`Tzoc+z+JIp<16*_j!XTB-;#hiC)JKygv_?L#fOXg{tMu`UU-odKX z>QajnP4kPD?KUv&P?a5{_~+By7}+$|zULiOT4t(%lL24w2Wn-m>RuAQgBZ~X;;U~| z+ucs=U_{)x;z>l&=F4_wDSqj8~hQuJ9zz5cO)0W@co{_zpt}V7xmKgCB&N8 z_*kE+L5Xn`{P{9B^mT$819B!emz+ZPBj%pW4e!>M-cB&oS2-H4>>Y9D*Bn=t< zx?G2%#O=z{%i;OJKrXT|sTAI{n9_2S_#LIRTxDwc0;aktK1()jqz!Y^k2(*d{svPE zJb7O(>%amdR`8h93Mh14nNA=7FFFzkfHMFHdV#ZIjY<7zx*%jWw` zCsd|h_$^p^Q$TF@lojqFRnB+*?V zWjcs?5A^Cl)0UdKu|<*rc;syWh1!6JzyJ}9HmJa=Rc;rgtqs=ChIn?iz9Cz@n-={_ zFSEVRx2CPU_pM5--DbA^Zem>&S}iIoFx%I)dYN)>nNa->Xy`AxVlTOx8Ji4&WPU40*U?X$+T(>@=j#@Pf<_0i&l7jW2ai zHS&<|?(!%H4#ez@*RJg-XOR23QBSnH|Mrk z>54?vo>*_tb<-q?F>P)`!Rqy;r`tcJ`~;={Gvii%6v-3n4RW+=6_6~ZZkor8MA3k7+oXy0~ z^7}eDjl&tsF_w-6Q>1#wvoZ=bCh|EBC2ZeXLE?CfI%*IVoW^%VM*ld?>n!?YiDq`( z#f)Nvd>~&GgSf^0gWCaZ-Y=+d^6{|x!thKU{Ukssw*q~@(f(pgFhC1r@~Aw+kB*>9 zd6rh6N|RVqHI)O5-8pdF2$rZ3R0_Ab?Qb{n=JYE82o8d4-aUEw&eNu z19k9(eG}u~iT8yc^#Z?}zr}_EJMyZ*~XiHhj0(hEmeXHkkWgMn=GuQoz(`|ut>Mpm;l7PX3K}Dk6 zH-gCl#Y8;Dh^k`DUTx2=UA1zvevtFBxe7D?yTO{&Ns4pEP>9(uU^ig_njgd-$)l$rM7M+VJNGlbYTtO!D5}7c3NA!2hV*z z$p_KTIcb+u9GC2)XS`c8K1_Oa6>3*awb;E_=nQ!twjX!CWkaV@J+mh8qD#42?(*<4 zsHn4)$@vvdd)df|wV^AZELkwrZr0r{S(;Ev4SVm_9r5-FQ{q(X(6wuqj+XLkBfc`` zFaWuci)|%IT>Sq$q`Td&fSj2Xvk$@75-gt~#r1;5a&-becnfw0y)Q=h4C0SYlRYatM+u?E*I9vK_W^Tup;H_Q@m{I|T`k7(1I3$=n?4OOV-YQp{3} z1Bv?=deV}QlI&>pES;3=WH^>A=zNH;J|T8QyKHcd>3^Un89R9-e2Rv{5&%h+Y zI}nNz5nTvt34dv+V2n?S01V@BeQQIMcBKg_>P{C>7V(1AFbiQ4H8qtF+=2|`uF$ri z5@(y670aWkrenB3Z;*XCJ9&GozVgaBgp%*Y^s(0^SBSw2l~???8VcCLTw*b{=#Nd& z4RSUW^fu44t(QT+wu{@{G9Xj7b7A*p6+XDH%a(#6vLDq=Xa+U$Ptm4$saM_l;i|EKEun)!aMWh? z^;XT2zb&y@C1md=W}*9_Z(B826Nj9R$craOsE8zM_rrohZFk&ZC>@lbtZbmVu)N)U zN70~`_F)p55a?hjX_stc4f&NbDqF4YGHzceIf%wphwty>s`9VcV=o5=I#?rBa5>@v zet##lCd?tbo!EszL1*1+EmY8YoMQ9Y%K@nsOUu9V#0k&)Qp6+ABVc7j!65x&+cZRj zs6RstR_ti>R!H>pmA-lrukedQA|B@6qv_XHgHHSU#H|bopKERx2`)No8mzSTK~huk zzl)i6|9KMist!jXN_wGg4!%UC(jD$#eK9T*HzMEJOp=tqprFZzndVE`pD-iKgYr1p ze*Lj5nU%29+$Vd8H|7T5_#Phq@BLtzE&wROuaD-=P82N1LRF^$P`EX4G-R1311Ahx z0CZT)VK94vab)goLua!=I_^%qApl)P91sDd4{0_MGUFO2rM_%tezlj=s~*LPk28k9 zWXB?dB?IuK)5))XCRJ1=aD@?WzqvTqsZW5_gsuw&z8KF-`zQX4*_)Lt#cL@QpLR1$ z&xJ$LbOO^|8Asv?B@4H-VUhPf6KydHZ(3+jm=zGw#er&OGa#p6HBoX`2IXfJSUO{e zwgSw63M>i;mr@|2GU$U@E&6c$0X(h%pZl?V-6YJPuhg#JJBOhU4>WCcXmov>!J)$Y zGPeY-*7_*w?sefq5|y99Q|)T{v(6qF(O+TTRXuCxU8k&(mjKE&H8vT39O9*%M60?> z6du2jFxT?^A&nZ^jkGs4R7zXFIeD~S=vl4kHei@z1&p`dnWJeBL)EeE?g9-o|PZku}3m+^b@ zJn_{>GWw2_98?N4#iI|Qo}GwwfkCVx2@neah@Z^%6JpE{Ru(7l&D}dZ@>KF7{25lS zr)f9jQLP1M8 zS-1hqRH6FGw&q*K34iBy$0h)}*ClWNl}#M6#YhNiTdqF z`vSvfsR7p(9=h4P>E`{n;OK6o(9y=$5iI@nTx>kVE&A~Ox}WTXvPE^;2?+^8Aa+1y z(KPJ#pA|w0gIKinrd4h~C&2K&iRSsHA|$2lu82DuYVzmxsS_wS-ed!aHEz{I0Z*Es z1HjU(PY^@;Chwd9SQv8@Mbn2cT`4fsfg0L(cL=!CFa9~+CUSmH;&w*Ygz}Hmk{flB zA<1&4b2Fva+s+$QZ=5mvB>7zK#Q?(UAwuZZ#<|df?uvcRmRa``=WDx3_a>ylB5eRl z<7W3b^iE8H9bFPF8SDXxCo`+X!H%YvE8Fbx`;C`{^W1Gt|B;+N&Uw;>f zbfl%pE>E7pyglHHr=`njPlfuk+cgq*pjwPWJQ~J;_<9FONE?kbMnL&~zieVq&!;@w zVJ%b)J-oRDjF@FhFoVta(iLTViW8(IDAE?}v|zz|v=ALF%jl1HKaKe$IMhlgYnC z*Y}kJkl*QA2hECClJ2VHNdDciNUKRZU4LT-}&SeQA`PRAq+CX>RDomPLiS~JS zF8$wmar4mQ3%4SaAB69wgwv%(24ViADK=?@l1^#iS`#OaM$aCm`#hn2%pw5r@S#`1 zRZgl;2s99$S`~AQK3b({#@EEdJ%4xup=!pr&Mr~V>rirq`61FTw_7hA5GfZDp4;cex<Jn?;aq{vo zBK{@)>}j!z2kKL+B^IR`)dKtnG;xBz_)&`b&hpMbfG01)@?M6C&k}Do35f5qt$w>3 zI^jX?yHE;3fT=CK*V(=1&*CApa``D_c-F&IjzjyP`_-*yUO+mr5Z%z6Be$=1wE&^` zsia-QkewpL`>v8K{_xsmEzlt3+N1Kxnfw3oj82r~{>xqQ?^^B!iM!fjl7vwOVjG7i zPRS(tm|jMD7+d=S9=5cZ=Y|m?sF>s|F~ha(to;a|sw=m09@uX|-RJW?EzpF|GhkN|FFR)5v&F=%eN)c1(&M%gXwJ* z*rvvV!u$o8#g<^4Em!z1Y<(|*c!Bd7N1B`&jg!^a=FRSGoApgsOSxpo%3)CPfcwN6R5pW)-pfzJ zJloB%gJkm2YmSh7y~Iqh;snuRpvL}fa$KTjsRDq`bZdlNU{~c}5UvtfaJsx{O>Lzg ztg8K(?LMF7?9f*l&hk4?AM4|!rq6n{@O{7Z-W;Xz-zm>%)W9n0*{ zS_z5^>ZCtBYQmb5%fzwEl#OK`RwsH$2}`#y&%`nv0gyhGy#Lh8#bR4I>!GZhr+a-0rXB~-$7je8JB zR>Sr1=Sh;e&mW)z-{kyu=-FFUh+QpvQ{n`3Na-NCRK=7;>7>$oU~lQV9xbSd@ak+~#OGcg0>Ys3n_qI?Q<1y~`Xm$qwEhMO5l4sX|5Rl(E)6shpv+R0wvf^#P zrywy32}HpGCRychGm=k}AG*iMv8 z@5S~Cngi~2+?@sP_k#cCyQ8XH5I$y38BBJM-1vQIW4b!`+cx@jyMS-l@i11Yb{vz`rA|Hc)|lt>K&8HmD0#JGOqXoD?{zrt$!C%#557m-#Ja4*UCP=`vAnY($|@RqkA70j zj0gFj2Knt#AsQMVQzLI&YV#8(CiG!4q+>FUIV23o*9=X(IqoILhwsWc%-~#+Lvk2= ztQzz#gL@S7xS65)1vA>4fGc*K-(2;GVLmuHbVG2nAr4{OEdLaWx|36P=x+U$KIQ+Y zV(s?YTz|meRDjV!vUBm0*){J)^rl&|y5U#mVZNIk%bOp|@O&i<`>P))MY*(F8OQP~)Ngft z*>dB1Y+#RrisUb+2?xm-K_Fy~{FHr)>eb}W5g{wVUo)1u#2)$y#lMk6-)?kD5W-@* zOx28!zUg9Z;cKivRJndAs!iU2!o?V5m zl{Y>gvVfLAQx0jYJxhfiO`kBc)(1IE4~&~9rfM&({=chs?$gjy@opF5Mp9ai5A6w9 z&ujgG*lu18at{u_TDGCj&vAg`ug2~~-ckHhp8LX1QL8U!PgU@FH=f8AuT*gW{eC!X z-;xdIdW)^h^7o~T`j@p)+B1RMamX=?U2L&R=(TEoWC)6&owB|{8=()B;W)9a-wZp zj6WIkRO(xCypae0>o};-LH;vdnQ1Hdx5c_0`By%fKJphdJs8Z8|YzUOF+`g2I=M$mwcRwVKHR=w7>8(NO>u?LsJhf~5muYEhZq6d&uKbFd8>>A=H z-W@E)5*bIoh(}+{vgPFt-YRU~J$1y*KOd5M`C-cW13~N5={VNs*iG1}O;|2ZJ41KO zcXyiq?R$q`Owa80yQH5iZPPeu?v0dMRY}zLEBw=nbEvy#Zc+K1=;K~@zch527N;LJ zl>(xKR}KEo^V{y$|F`pl6ZQ3CPBl-+Pr)8NVU}kmZ1u12?b|^$QB^OHm_^=f#`9vv z!)*Wpbpg#$dt9^na?^EmsYcT!QK>jlF}}>Be^*-Kk?uQ$G%w`jjjRB`GmBYupE=08 z#m5Qv0~WsrET-+fSxI)bjW;aW+pmhgb4m$+IP}($|I7qIDx>~g4b!8Ixzjm}5_=U2 zhO4?Xj>?5F?S)h!2ob9BS+^FCuHc3AAI-1sc-~_GEoU80u`N@Dgwe^3WLZnqle+%v zqm)|fg5cS%z!$*^4n^7vOBcV*DpU{>e)fi@ogvp2!lvS=W1;dkNyvNp$)ks4SrSV~ zMcmHTrNOCOKa{(`u|)SwSgqA%7@wp`;7T*o>;AI}v)Ip*^$z#%Xc;OBoHWu4d3u%qzl!h+^uHu&&LxHa)U?Gd+j;E0I$~cE)i`%I)6w)yWnylXxrUc zZr$Z%aF*9I^CT%xtCapp-D-6~mSQb#VO^P>A(yUP5(wf}qF(Z^SFViz6{J*|yfvm+ z5iZwI5?FXqQ7QS#7DDNCa7R#~dm?CDw=D#QRPPB)=F#jLMCXvu6hEj2+=D_UrjB_)!5bfIP5NrrTG4>n7wjt zc9-xa%}>30&yN)ipAh-yp0+->dO5ovVI$Mip8yM6PDm6BWD}AlNw(Eo7;j|)Ov-V3 z1&(InL1}@{8FJ~G595>2j-v;pOhY+=AwYt6fRi^qQT~};nA8ie5&hKJK;;!XvHJWP z1~I6}r&6r2fEFnhtd!j25v)`Z=pS4hlxy;_%-7}O8O8D*5YP6#UNl{Uvb=Av{y*P6 zDeYNJNDcR~(rH2`iEu;RWr?p>o&TjXk7oPfJm|7|&m3q%>+zpe?x(GQMD$O0F**22 zjiL29Y~MTT*xlZr&1w{4^?!NJCJ&;64@OAscMV!NVg>lwcx>UA_|UP$MVxTM2Y_q z=4c~GD*LS5CZ1)j-Hj>UBHU^cz>ft{>PYsiq-=w8Nlqm{{P z`;_Ry9Has>G5vz6WRY=By=q^RLpd$4Y%tJ7E&5q(!NiiHdC`PHU#LSRd$vGV0PX_; zi%3)6YS1q5Ebyv|6szW2M!rU=V*M!j{<%jTm~vB664NTahgE$vlX211VV&;dzjmUDMBN^N6P8YRH12bE z^@7v;Hc;YxH(e@`I&>*7HaC%@vBM>8xyVEGY8)RINosy|um6^`a{O7I^kAR}_A^A>mcUKKCI~Y)ncSDiNt%Hp zyz%U_5*+et9IA#thn6juO-Og4CP^&O5c=dq!TjB1rCvO@Q+DDK8~^}x$!U(FxWekc z-Cx$e=Q&}E77j40r(_gFw`NF|#5kDf_-V%8ONM-8JVF>{jyXi9yKXh-BhL!y>9x5_ zX?tI|;iZ4#JpTh9A?aC^{pYMlyfYupi5VE3c_YWY)?#(W;ssB|wPdO-`Ia4e#<{?_ zUqPn?@#nCAVPn&AzVjS;$**)9GnbZCgs*)4=CT#+`3$cw4V;|*pvf?0h5PiuC(*_- zF0ZGf{Gb-FWH==&QXN*_Xn(GGgwZ?{9-o0H3Fph?&Bul(krcXjZZP1t6-g8kVmah; zD6ekmi;U7=yBrG*_daM=1ITby7$O8GB$}f@w^bUmB$mbf)Tr}EAoB18N#Ftu0q&Xs z98rA;MK{sf%bN%p~y|DqE?a^*&^5VdMDC}fev8Y78$Yl zY4pL|JneLa$??tTCD*J(6mHD^SzznAl7HlRELdk}HyYc?oc7)ZqwfdL|6R zu4V3S0(nA}!Pj@DA*f?D7=1&Sj=MfGkPf!h>+6VcC8E`NJyrD6Bf%k72Ij}=oN9s? zW2lXd3f$t5UCztaI>DH+Kt<IkiA|qQo-uju_AZOuZvMb}aq2{%j7a#X-U0aaLMA@S0klm%aA`J4|8*cR#Axz5ghiE2t`CCMZ#L+eg@dMalklv z!n8Q4r`OV;7i=Cr0QqHgdKYBc%hMa4WEc)Mf>=5(I2c|b>HKjx)DW^PijaD~V`+g+ zGB|LGf>34zMsir_T-v)0ff1eW-p{9K&#i=KbW)!$48LbH^^}vs9S7i-a#R{!V(btl z?Jr7l*n*&!7Lt9_NT=)NoOuLX0?L9cFK~qbl1Z#raB*0&tY0V#zW&yKOKRbd4-)SN z&@mq65t))aQ4xeyu)F(tu4YP>-mQCVLa+f93?Y9gk018e=V8_N=Gd1C$eT za~ZSKKEBUGiF`T>%JW^i^hVvCiEKBr#Zw*@aWa+KppE6<8I-Ud8{Ck zIoyp>Z_dfWzI(vjonU}B(!!ppwj6M>ZCZvcv_%$K4wqESm74(w_5xPV)t|ANC6N2n zus|RRaFc5De$$$717%Yx?hzqfNKU(Zn2=Qxo~6E$8&y#m)%33QT;lf1Z0l5RYlL%o z{1_l`K2ga||EWvH z&y!K6mR{k-YJg?0ICtYK`Jl83gEq_Idd$c@OML5%N8y$Z6_Sqw2ecuU%E7~GfCZgHQ073n7E2wdZZ2oHkPclrUOTb@|U9Fz^V*h;0qB|jr8qG^`qoK+kMN^)^l z{1UVgepHc7#NiWh%T-a#(2u=idZ;`#l$SqjQjI0p<8(^MJlJYe?(>p!@RL=`NoV!p z8cjEd22RlU7g7D7KlT?$=jRc3bU+6^Kzs-?BwMO!uTgRNj;xz5--Dm{5DoqNRd#|6 z{ljkgZ`c1E#48N7*fJAkc}%uXoYGd71)wU6hfZc9#~U;B;wFrjRLvTbOj|5{Pz7nn z$iBwY54r|SdJg*`9X!y&rGTCO$EX1<{XiW&jyY^&F$y+bPocwoloznqpS;>gII5gi zL@C=LMYvpbN<4p(^=(5$XTV9<(uB_SI|je)dUdvM*AmrJat$}Nu;3y2K%gp!@haPo z9m?vv#CcnQXXQ_&QW?ndsey6X8_0Ld2I!*$SY27k40JV=P0&H$)g+TfgM|k1lP60& zRo)`vrwc#Mj1`dtwgg^l>TD`f{fn+Ooqi~dBi-2kyrZF`yuDFa)RpMOYiSZnIuSHz zth2~=Jk=q~fB$cz(OVU(y45n%MK(k6{?L}y9FcAM{Akl-(nkymNzzpRWY`75Ix=Mk z%Q%N)i{UP{2L5YHiQ5g&K1YUy8SKA!@~g~=H1yBhO*?&zEVg{ZR$zeFCf4-he-Rjy zj3hO>!?`cpHgB0G**p*H2Fx~xAor4t!oiQoU;}!R(N3aKV3MN>E*N8(_(tu@ZjyQ9 zzStIjmr!8AcNct z?F7N)6+uR!v?p*aNN~F+(c^dK*pc{|t-jjwX7!46Ibd4zhnv#Q&erFaPj>xNt5t_k zFZ!LJ&<}&9itg;{ZK8kf>UNy9b&H&)`Qnj1VV?})>7-jt64gxe_O+|_)feL^qUY{x zZHFg+M}TdN_voF%Q63QtG+5>*+^2Jb$rglyj`t%~~j*=2GZ zt6uzfTIRn=^lJY$Q^!)@k;^M^!i)W?dq>s8`{Oa)Yy)i+1abECdb?k^rT=KYVc=1E z3cG9{b$Mst7^zav-SK{6oks}qzIcuNr;qYl`!-o;>2NK&`<#w>VD?)uw)b{H7vfd5 zuxwGsC90O#9mWiqgJ1v{$#}`Dc(^|Nh*JugtVqt*sunKgV%cId;fUQsA1IZR*2_q@ zE#wWXM|+DLni9~CeTT!D#6O$&qdjk>g`@VY2QtxlE_V5WcAG4_mI}o7Jzq!^vB;YK z%u^e7N}Im5qtRaZ0h_eoIsAlllYI?l-Lh4sezO60;#Ex9KK1k0aE(q%!mAJ3*0ezt zUr045DHyW`uMZA$8PMFZRYQTULR-UsCNKH!9gkMEjZ(dJDa`KU=i|{ji8J<8)Y8L( z!M_{t3vBJ~3B4U_9LgSCLtk_UxRjeJXZs{O7_e{Hy^S_yCmH-1`uLkkGlm%jf+qwl zb-L&?tboBaK_PNnW%qrwlIP7an zQSh$(`gvH{H*jjd;Vw~|n({pkawcDUzI)Z;!izFZjhzsUO4u5&4e$k@{XV%!D-t#z zneshfP-lln2MRvoX=;9Fnm~xX2!}h=X6HYz86JC)`>v|l`oiz;yxkABe=gxnOLRp| zv}5{zgl}P(8-9HW- z!2S{-l;ri%;Oq`qQ3nyjSeLJQgZtVl`!4c+%!?eYx&g)_?+NM$gHEC1g>G+f5AxMl~ zP#-|vPCRSeHp5*!)0QAiO4oqZ>Ig7Kr3??}He{g|3I(;ZgWI8D*4i599%og#UofJa3NighcdB3a!Ro~l zf9sZ}GxU_37mXJ9k{;WpaD`eLwdI=x9=?|w9Cw))eEL}<%C}v(?EBk>#CLE0QJK4c z%dM6nobO}|<=8Rpi<7YcV$`W;o7vE*5Ku%&i6`65iej4y>jqL@p2nr2x9Q-G{_PR2Ey@JNOf3j?6|6P1dv>WIkok-5VojZ z=cSD!fnF<><4FCTOD$0TBFNzxq8f_9b?nnqTNzD2QbYJ}mEVY-1>z?fWWSDXM7iJb zvaRZhm#)fU;~5fLuCKlCSo>$8nro22%|!p5enaChHAp`}3ge0!im1F9DQ9Lk@lS)l zj@_rv*XvJrJ^jZ?zu#q=zoVR67|2QC&)qC_r$@3j)AT&M$qf?y-N8?np zSvmpMNX*fOo}sfge8?-VrK(y@u(Y#LaI!EIP+{5&t5O;V)6d;5)N*fy8JjhzOt%M4 z5}C94f^&`k>uav&r{yV~C}T-~&Tn$P)s4qLn%(YrsYkDDOANhw|Fk_^)_L-RLTdr#ipi6L zq8Kf2&KJ0sB#aV^LLTx|Ob6ay?-aWqf z-(iLQ{oQv>mqb54Ui$g@Lzl+Mu=P;^dFvD;f=IQUuC+;KC2lu`dNc+Y77&t-%Cq{> zUxtQ6ZL%bF&mFFfGI@+NmrP?nE&o5%R426}j(bT_>gDv_hw@naf#5FRgPD4RBnwiF{h-|X)5}Sy@yTT{ACAKS z^J{ZBNl4vYc2WYV$2D2NR=FCBCMnCp1W4|-5LOr)m?9p|;J_sGw~v~*`KPn@-jLYS=|dSIvU}fz zu(PrtgcpC5rl53}0ZB;1c`O)dx`_n~n4@e#2yQg%1W~}VF%c8kxKb^Se%yCdn04>} zM?ul2X7*;oXdJgnU0Y(Edx*+T>%(jmV;Ft1ZcoYmMyc?r+S2W7%^jEi3aj0I!u=`R zMo!0Vp>1$`9djxkp@_k?9Z_4|Q+`1)Q@&fwcb>jEqPVU=U0ck{)4mBe&i}2~`pV6w z9qP8aBVn2v2}4>RK%#!(bj)MyaL8eO<}4X3vA7GHYY|`(^yLis2b^NfKa^qk&II%m z_+rR8{t7ffqi0qmJw9#N;sSPN=QMLOEYfJ*5G_BDTwuTHjCc9MTaDT2C8`h~HL4PxnrU-e*A{A#2g6 zdsl@oN834g_ERP$zkBv)i#+XExoZro)qiW8YSdC)dKPQRJdRr!v=%8BkIA@o3vU%o zXQfFF(*va+4f0nf>DoBnqQ9Y#JWN**B|u%F678AhhQ^Gaq&2Y_;}qesna*gTOp8%C zm)X4RaAyiwdIyU#Z_UZlZvabe&NGc33LwKaiBUD*Z>RoDxS8BOPBI|o#Dioj$=~ZL zQjxfHxSg#Kbkzn=T-5(?aEha<<9>1hA`c<-kd|uimKuBxy-B_4Lj2-TaC>Qk$T4}= zhlsn^;<}}p4NS;iE_#eqWFyf@qKCaSxo+1FwbwpAva`!W6xtKfy3AfxcY;Xuey|WI ziHCnX5dek{PPw0R-Wyg``O+&aTRB^IE8O41MdgP3?pB43%Nw zOyBfy+J;Rj{9=;$tKud#PeNJ>u)PucX)7wGcx`=s7d^T%KOA>yu68xpu&oIqz@-Dn z3xNa@=^gF>V0!fq$$E?o%Pg<13~4!Y=Ibvp<4OUy7zSAK0GN7}Q=LV32jBSu=MsC{ z#}`iqOSQUBn>@@p6~253zIXK%*YO6~%s}>?o9gK~Cx&C65ufnpT*()>QAnsP4*_*v zdo^ug9}QOsf~uBhphGpJ!YHqkpvrCdb(azl_n;v}l2Om~t}6i%&IWfoz1@Pi04)lz zWJY>|W!6@Mclc~9}Ft6xvR2wUESD;!oJazg2{Tl$M{6GtUYe%e}sI}U-;;(p;T{Rb{4FtyAxqW{VYdA&fxv{5@H`B^EV4PuxZJl&ZW!jr@k z*btYq^6N{=XAX^r30A6c8L?G0tG6tUF>hWEm#ED}8g&pB&O!R5oU|y-tCTqT5&?Kf z-I-&bqEnt%%2sLLTnPD>qIdOR&B|nAK^z#yW%^|Y8wnXWTXT4pR_`}&kq(*(yL>WZ zP|)_?OWO|9lJCxVotv`{|7Q6RWZcj?ERuIBI`V>f*uObY*ZX*A(<@H%F?z%EXa-n< z6~tvun|M(l2@&4q5Xf4I3u6pf-jY5Z9Oz$?hS$RL@_ZZBpe98}FINTNN&8*|XKM7W zutB@s#o)rUM|TC^zD?r3JVO)?UNKYucTnre$4~daE*E*Y0EY|@BTBJQ|kG5+iV z;(o#5^zV5bs{R6K<1~X9JWd$QQ5%3EG+<$+{skNGsvFoS9e4pA;$a(*0UV@3Hfn=n zWT>Y&@aA@o=LV7kcdo}kFos0NrfP#WD&b@lugO@jeY6J*Lt$0!#z(U37^30oy6PFK zNIt}29D0x>>!WDU%09wD9n$I=$Y^R5gs$+c8|L8*<*<(S;T~!N(a@>f%I#I?PX0V( z=52uDZ5FF-(54wcO%Ctj5EMZX>T41b4?C{oCarRkRO=2cKm#fVbJm0dGJpa?FLWM& z)@ErCML+_0i`Nw5Abza^9zX?MJlS#SS<6BFw>GEfxd?E-Za4*1i%}xAse!R8?r$(tYsKL zuB6!S;@Izb-cK`NfiLLDnAL(lwn1#=a5DrC_!P6 zt|vw$l+fA+N0jm^?;+`+vO6AO5Cp*u8392_RB4?R zE(XpfbmDq~B4&ny5O8r5;z=_9W>|`4-Ym&GH0{2i(q-ri-!!2Wyy30@&cvX_96>`H zkU%vXYJXsJ<95@b?&5i@wEqMZp)kmQ>V-2xj2H}TT1adiO-z3N{v{ZAp&O_nYtDhL zw!y{1;Toy|99qE?O3*qt#vsL$AbpJIa4tN5YN!%2I7$`fUL!VAW(9pwEZoT`EOOAS z%txkf>UJi}cE&y6qX$P)9E@hnkVZf90|MjBtqR5o@hl#wutXV$9-yH{iZUo36ex=l zD3s4zMIjKt&_!eflK4zR3*jjhLB6bmI;dmtu(e*T#2#EgO!T!(LI49afb(YUMQ>>Y zJfH&BQV~l)P)Ohf6hgRY=XPq~^>ha#n4ot$qS=geQl4OAF=h8W#Z#<6N>3sRW)q|k zOj<~j7gUAH#H+k;MNFZh`qDyK@@);*&`r@NXYng%@h$!nTmi=Xjip4xGd$xhbiu$j z2wQ%^e>7uh`+_d^$1XUIpg0au5!>gNEGAXzoXTGa!&(;zd(H%c|BlFZ4nBUfR@OJhU^m*Hj*7aEQs%ebr~ zi#6-MY#gv?%!o!EkYOG2BOKgJKjh46R6`zY(q8vwAEqG?8uUR0347FO`5siU*5=VF z4M8`w$rRyD7l9F|!w?uDbVav!L1Z850ZdY01ul+9Wt^xeIq2#b(!2Bf}_GK702u~gL7hFLz zHt08f0cx@3f)W)M5DJ6s;xablDoiaqNW084xjve{Z{z&ah_D}-Wa-^D)jjS8xZ7NUTo_yUB%DHvWt8@z!R!U08; z4-`B>6xsIAaBicLZmTtK-1TpYAVxxtSZaca|ER3Q(Uu8w=#z&GtJ%m+pi*;Bb z_ZhG#>x`z%$iWrHLCw-iKg{9&9m)5pefffx4?PwFj z5+C3JYUeI1;@Ehncc3W=en*;;V0?E^+KNYctZfuk!W2t!Heum|qEQ=k!4;@s7ZS_d zGT|1Nc@uz9SHuSpy02!T@{*pinxXPtBjK}MAskvE9k8Jrf_XGaGmhS3oF!N_>q5jj zsN)PwI5%U#=6QqWSvXe{!9+|IQ}Hu&K{Y2tpND}o*KV~Ha2Zo$8_>awwgGC)K{~4; z>yW_|DhB9M)#nIO6(s(eh{s#Uj^pPf#$tTPWRfgOlFk?TOH7U8im@0YGtwDuFw5Gb zirnL?AlE(0sy?)6KUb1z0K^>PsvY8?k-fS~@F5fe!6#ou696GrX5}Zz6$}rp6!M{7 z(-4W4t~%tk5fG=rOrXwxJbDF8sJ5z*tcmz1-IVseAMjmXJleJh+I6KdtqvRK?s`ev+7XSV9<+#@7=h8%u|K4f}7);NsZ z;Tqn7YPLZhPFzcJG8B#)R#q38uN^`WjTDB&Uhil-+Lb$&YC0UD5=uPUy}BM;fOuEU zOlT`kK(7NzpmcT%P;&Iw7GfgilJ$lwNEyW_6NAh0=km(Va>F4a2+Coq__X%`KfqffUS8baRr) zkf;zAfjY8!sXS@%ftnw(pm_T=1mGm}M#pqwbWeCqP)dMdSx*Llt#)LfBJR2pyVrNR z_ed!vd_`ho1G{*Vpd^YvWNjJB*##GNd89^67hYIklCu?DAsLXOiZcPdVD?wW{1}V= z@yt`6nge(fj-eG+?i#QGLb3)PPxI-aUmF%X=RGLt@pS#5u@=mcgV2v!{KvNYp8x>@ zSg&Eihz&ESZCFBW+Ja@v#x2+`Y}~qGJLkcq(tCsCP1 zjS4ktS+Zr!$}%IX3|d-f&Y(qW`%GLkapI1Nb4FL(IC130kqf6TusL(<;HA5^PoLt& zj2kKh4Au{Bs zk#0wh2JwpxJh<@T#EU=XcSM8o5E?RY$S?szh727yZ(0CI>TipZ#A zkBWp6PB`YYLk%_CbhAq^yuhLjFWCg64K@m0ILtu81XJNKS{?+D4%HCZM&55LkX*e+?JbegEUgfZ|?5PZ@=C4;{pXAG^fFH9$?@>1|vW> z0(KRMAOd*d!C+o`FN7z94eGt{0u3H7L4y)YI3b@C`Zb|n5>u=!Ab?T~XoVF9(qaoO zvAkl7gRs=n%Y?cJlTa^7=7|k8-gxLrAe>y~NheODh$118{yY-N)Ky24ql_}zSfe5~ zX3|PHg_(m6I_I2&jYHhPlFcr}FzHZ23Mm8&EWyZG<&|e{N#@%FX?eFWRhmhrHn12} z=G@vm#JD!QaFY!$6?KF5F595v$~Nt2?v6R^h;33et_14-|s%A_zo38-0NPs zsYE~a(Hj0KaDn{WM?EOeoDg_G0|}b|bv#g=5>!Y21Tc_T3}gU<3ZSP3FW49jYG4D8 z(cnExppO!q&_a_v0cB5^;mVpIpee+R3Ra+n6=FdJn%N>2QLsfVbXE(2Txd?j$k3iP zLXB3K!xgRo1c_h;h!nXfMlr&g7i*NGLkNOLiXgNR8XA;Plh=E6gREdvqx??czn6`(+4IhDI{tjX$LW z9UmbSp{Vt&aXcd>DltV-WC9e};bc>>v(!#}G83J+?o+pG38_q_6if6*DuOr!)gD2W zO>9DbTY;agnm3l`>53V?N{g@9a;)%SFE0Lbp$j;^Hx6W|gB|No$2zQGj%)0Xf#e*{ zJv0HD&WLMVrvb%k5LixknIaL0sHamZ!JA4@!V>q0r$7H$9DZa$10nc;1Q9kJ4=l_B z)+vDqDj+c#phpHT5DyJzPy_YQpgk-U*%IW#1d}l#q&2Kz5^(6B0lmx$QQ+asY=MiI z;-VI{cu+5RhNfP`4Hik-1&4U?r*~{FsL(LgNW_dO|d*5ydoEGu>_V!w`u`1XKo534B)KUZx1I zd*Az*ePjUyAwXybBtV^pHM9gIco=wO0APv2;07c_VG3`sQ5G`cJs?dP%2>uSmsNp> z1B!wy6f}#P^9Dk4r}b<8ijfWAqWvQ;jt*GSF2hW!?>eB zJfj-!V23-}k&cc8*=UdR{sv*inhl1y6-sWU;~*JA$HO&*k5y_Dn1->Y!SxMJbLy)@ zhLPkY0(P)_k_hE6l8&QsvK`hS6g%MIjvy%)8RIAxvyy??Pigj*tm6r#UdLzAN{V*2 zv!(7V!4yC=g_nSs8mxw?mE&!uw#^gE@^*!3XYjUq)H~L&=7KD77?&K#AoV!Z5u|mj zV}0;#bv{f%iqp(WG^6u&~$@H@u;w zi=d4f=nzz6-$58dRf8R(LkXjh<&0#QZnH4)EGt*p6Pv8!b+G%h>}YqpN1-ZJx@0tt zA^|nxMcQ1osx9*_EtazA3L3`%mNKGo_v=CZ7;%ZqUi=acWN>pG@;ElG_i+!dWa7H; zD+OzcZFtup9xCQtFTU2B-p5CN^9tODJzOvW3SvM43F|<^qV3S{a4-fpsK5(mK;VpW z+dc4k!Giwf^8%AOAqh#y&q-G%g_Tty2{5aIf!>XvS;S)AzKE$W3L+s3wMkBU<;E^x z;f-!|6|o#)@sO@z4P+!E6tDtjjSunSsRW`Lm9=z*MJGTu0mk}p+Io{wW*04F@v<<1I zYS$DF(lR>8a13dISwG=AUAHM%*Mgo^6PThYuhS_r@hPQZ6sN)zjQ~Jiqf{v(Oxu-R zsZm>_5D2$rX>rF4X|Y?ZkO+csPnVZom0$@6REBZ5FY-kJ%O)KekT4E40u>-_BJdp)b1~yFU>frRHgE$F z@E%M+1Gd*fNx(5rzyvRFZv6p#l~@JuCNn`q3sg`K}Y?EWf$UQA_pY_$PfZ}SHXY{j+0~%0TD(v5tfum)^IlI zfK{E;IV52%%0+78U|GY`E0oY@Frhjx$Vx8=Xf3!(tdk0~BPx)hT9}XhYICTB>)}}6&^2;9yI_1h4^hZpadOr10OX~^05TGhcZln1pToe z5O#@CUbGn;5Lu|NyB5DQ0CZ@mzGIkku-17|n(x4K75NHAE zkC&nftH4TJ$8{~Jf}>Shqf!*7k}8cb2vSi9H9|Emq9Vm3Xh1#%$Dw|uw| z1)xY%wLlE7pbG+_5TdCI0JjUeP)Vt|ngz#ZpY%D9RSilPc!rWFJ&FwA6j|2r4uJwF zYIF^7c@9US4b)(L-q1D;p;yfqH{38s3NfRPlyi|3H?}daSqpjSRb)ibLnHMW)6Q*o6izH$j}zY5C~J(I=;Cnt00^KX{a=KkfD{Ro-!)R zi3#g92*4v1Gg37uVj{AY6|-VYng9yTQ)!{_otS18Oc;f|B~5$EETUFw;~)=^$Dgkn zUi|Ps_rw&sWC`ij2&O=Wu*$3bfL{~vpB|7f)&WrwGXo+-Q5jVOG>}5H2Qu>!QcoFD zyC;b?)C5wXGQlTd03tI65(QBZ3u4(IGX;tfLQ}s$41xm-Z}JcTSB~7k3%kH4e_|x? z&=J9Z((E zA#EfO9@r)xM%kd>wusC+GVlQb(V7I%ssz2)dso>q9{QnFAO%QZAn^u7VA&wIPz%5C z3cw%?>#Ai?h9SJr3T=4~tcVUq17z25u0A6f=aYkH>jyls5Dr0HJA#Q5Wq*VJJ1=OfB*m#c5dzm$=kTx@;+QHMqft^38~eS46@U>@j{i1RhunWyYMO0xnidF0mShp> zP&7?ibebb5aZDIu6N2M|D9<7nAxSLE6bOL8Ihac!?h9z?l_O5h$L6Eg8(GPyTy7dnY3g#-ffZdoZaETte+ zU<*SO3!sY&zwisBt8cYXC3ya%B#_yRHQEhtnGw`5yh-|IbZHJEK^RPDRn+o+)(~fl z6%K5sIh&Mb$+(QjTYnp3$Q6+!6oI8l25=6c3lxzjPL#-mB}f1FIOPa*EZq%JQZz=x zj%ao{Kn5sC2TmhlaiS9reQ}S}G)nrY44S~3N9z;9xk^UMzp7lQR?T&s6%@2YDyqd4 zPXQG;;!9{ZJi;U^#?u*^fsvr_cB3$UV(~m>ffm(c%y$=D!_~8-0}k`h&4JB6h__ly zv0k?tY`Rei{Uq4$*$)-a0n;%759Nm(1cIC_LGWtP@>PCE4kOUOg ztx-S=B-+p63W~T8A^v7*Ayx8LOoEN%xYITYkASjC9XOZnunlkKW9;BLLejgQL)`5^ z+(>t%ezHksqne48$Mu&H8&X(K;#D2n4HZF-a@5n#>#jSOA*N}_!2qQivfb=xeH+3j zfN~CqH6(!&i|=6E=70?A@Hx^#S$#K3*~1oPaSWz>)r2aX{TrNwinNCcoc{O{rqvR% z9H|e#XTr74kX;zEzT|c5TEqf zhL>jw!{*{QxexhJ0eH9_+p&5Tg>4)2ZSb*RjMzdT^+HJi0VSnw!8d$Tu$5K-{>1`Kid)h|V8(CHyG9UuHrQYdWfN3GvJG>op6~Ex?hu>r=ML*&4sfQg zL-G!>dpYu#NxWb-l(P}?+6}>gnjW{^@LI8hWl1UPu8yO!6KI;3M2kh4O4b=kYArXtQ zNW7P`SjFqm_csw2;R}zfeC;x%M#v8 zV#FdY;xta<2_rIuoxv5g)plGv7RzJ770gV!6M>^ zkK^@V0u4i;5i>C&w5&I<9^UpI5YPl8rF;1C+4i2T5yq`CgM1fe2A1!u3t7`vN9bcyx4DAuGM$0sjq z>5^Qd5Sx8#YDpCVIhI~xEuY>jy;W$FjHrnb7$LJC(O4icD5};?>aeyYIZE7vJ#Dds zx)KVRU^>M~;0V6eub$Pn?wkGy5UEn3N_FZKAWR7d0UCtJAtFT)A4PfuNs^>Zoi=Us z#7UG#QKCkH8aXPI$xxw|jY^h`nah_ip)orKO_?*C(VjgMC$679ph1NWC0f+zQKU(g zE@j%(=~JjtrRw8%&(zg>`=)N?+STjVul(wn@K8cTg&8qsz zCQ6hz!JCB1lqY}%OPM0YFqJA)tjLlTh03g1v1r+%_3GBGTE2YM>h-HvtzX1|5z{t| zm@Zw}vhBjQOPe=s)Tm*j<}DqzbnVjR-VM*UwRh&&y>sV|ow;!AteJ!Nj`%xx*5K)G zXKnX3bh^=@^MqfpldT-8Q zuRLtd;VvC?5Zq?B+~6_C8h64;PC|0jsRkT!$l>W3aH4VM8J&)~Nf~CA(L|F}R8euo z6<1Nk#Z_XIF~%2NR3$|f1yY3|gA7VVp@j^2NRdMhnMjgHBM8^G!J8)Mp=l#*=L~-QYVJCmeMG4u>2Jdjdxs4|R$L8ZsGfDH%;b0i;G4ZKPQK#ujaaQAJcZ7Dyn162fF5 zKmb8R5R?TWG7^d^Qj(C3I_V_JjyM4&q>w-X1VQ z!Dr1pqn3JVs;jp8YOIUe=LJ7SfFTAL!mfda7ib`RiMrb2%ZV47;A_&ro}jc+O*6GZ zip8jSESAS;iNdl|Gt11gT7-EO7FbH_rI%ZEDKDE@cX7|XZLr;Dmv$0-XB&7pZznk7 z+;Olt<63d&8hB1O=Ni9P)WW<{4<7DRWGuy$nT@Km@q) z#Z+dTv3?pi-niox2SNptQzYaPmKfO}5|J{MMMM!vA_O5I@j#hz!bwj8NhU;bGb>dI z6ec>!GExFGFCC2;40FaY$`p-gC<7l^V_^$j_(B-QFlzh|!2~McHLnrs1van&4HBiO zB`k_Bds)<81XHOdNFh^pOAOwqKnp9(f(oJ{RV*-ri(W+G7r#iAtAsI(VDuszV7wJ9 zyul4@aAQ5ec%FR>w2f<6V;k0MM=O8>k8oVW9oD$UaNO~n2Q5$q%!y4s^BsW@7An26~le`d5uKohFJU5ohjlRodw(3=_YMEmrcX>h*CN+g7RH{-+%#_}&U z7hD8}FnXbjVGJX2kc$;Jf-xZTP-A)aI%PYk5iDRa=N)%+jyalzEO@Y^8pv>vP(^2~ zeO1Rgh`e4p=IGP|iN`za!A>_8{uCf@smnW!#A@&YL_G9}r(WpER)V@i4Fug3LDPyI zam<072x*TU0n5-h#9`NisZS>)B-1fOm=aEWA`mIU*p2LWv5FPbVjXK{K}0r)Af*fu zg(yUk1Yx9$NP-Yc$_OWBMl(@Z@FSeKl9hV4B~5IpC0;rPO?Y|2r}0y^v!!iqZR?bJ zK%oRB2wT{0K&V170WUA8%Mu*wD7VQiqEd)dVG2Xhi^>9{9eu@QYGI2j;$l^x`HbOu zK@8IjLl?9n#(ubAEBy5598OIKHRiaW>ro>*%+cP12RKi4 zsyWbM4R2Hjt=(xwxtwbLp9I~e6$g4GZNAE#dP&b)@)FM@=anF{RxdZf3XZXm6^@_6 zQXS+72ZoSg*PS2?h3I2gm>%}aKmfv+#B>qJC?l*nnpQCu*~C*iUOm(dcSDWkPW8xu~XvBKM?Sg6y;r_nMn=Xf!ld!=DUESh38)G z7zoq>O2>tHeYyVib_X}~q8By}RO|@jD;@fB&>^j{j&-bYuchGZln zF)d0w_^@OI!b{LNh6$%pr#5F?;~VEVSoTqm8HfOEFnCK`Ua$m(GKvYrm7ClI^MocO z!BR;;LKUnKg^Na4id3-0EM8&7Sj55?t4dWZIP={vf;SkjuobOb>J44EqCb~Q$L#FG zi)&QtdcQ#`Ayem^;)KH*|JCn0s$mTXDW|{hI8Jkng*{j3D;=$vPCBk}4qm_xJG@yC zcDNJb?EatwJ5sI9^u{CjdKDW%5f=QkMhvW;o*LU`4<9(jfed7bgC{+a@t9Ibrl2Jw zC8I!hCI~?>#QK=WAL}0~nt6&M140mkK$$}daWa(sn`I5O$VD~+iGpu}W>&@-&Klmc z4yM*ifuMMekui;qM_>BWr#?~Y0jL?YWruM=xuW>;1SQ!acb9sSy=w=1M~$h*#IhrGj=cJKyk*p6P=JHJa1?6?MOVWjrj7Qwp~+Srcm z{;)c00Kx1~q@8L7V+kF1z&3#yhjG9Va_ET|!-)^638f)7h=G`8(3x~I1$LW4)mw!F zn4cSQJ$idAe5)qPf(VppG9zi3%o;f1;{-y8l5kQ(49WzZxsvzsvM(E&WMCK(k%phB zK0Vw+KD4cm!vPt9ff^tbJX-?d(hDVsIVDgoCzvR@!4xS-0>y9)S;(kZm<3vxj9VZT zTzCcTg0wAy1u{l3`voMp^sYv z7zh-zQGyr93%y{;CvbwmfSdA@s6e|Yi>gFSER|9D#G%`alEOdxgB36ehFb{+UC@R! zV#VUID%tQI?a+Bs*d-H zFJMs+_u@O*(2ZI<5D;sxbdaOUS&&wM4rKHVw)4t=AqRFCLJTQPTgv{W^PKS2pA~5=BV!0gFa$yHLdyEgL-4l+Vn`^1vWHy5&jPKS$r;mPrw?)o zzhVYyfQEY*N!z?l+{BYVtN}YS6uL;17htI5f)v1b0>VgwC6WTgn665^#GJ$~q1%ki z0EQ?isl_pk?~;}A(uVU=N>(h7=ZPKP88N$?yX!%gcR(HOF%CRJj_>gvOa2%Dga8D5>r88!tRnfh z(S(F;k_3x@1eh5(nW3_BBB#|00DTN9;!2%f=8@H$nCs=|e z;4>y@s7RTcnM=;aNDRi9qAJ3!S`fNb2}LggFYG*xm(qprOruWo23Kg8a;Y3%m?Hvp zg}ZEyKYEt}XHmHOh=x7c^S_fjxufQaS%L4}v;XHZ*k(#hWc_NV#@gUQ>N7F-y`l-Sd zrI8zfy?Pq}$YKc2Oay~;2t`1I9Az15{ZS>ch>Z}w{+U_BgL{&5!jh4AxH%LNXqbm7 zJySEKm28khmIITVB9vqh8}N2wHt$`t65f-}vi$e0CEv5Zy01?d!qUx0;L7zSX- zzf$Z4TJb;jV8sD^k4I{S>B&J}2tjdVJJfLnR?{!i`L7=g2V|hnL;V*E71`ow7FS(a zcsL~FSk>TABw-Ae8_c`Ux!Glmowu^o&WXxYWe$Atma_yMU@;Ct#Wrxbkbt=mbu_{c zNtlF*$DkRSEin;LNHj;3FsEqY^4%I4*&SWDt?sR9CAT!;cTtp!}zqAgmSl1iytu@ySC6MbXFv1OZ5e2B6FsY0(}Nh|HWl1FAi>y*+8& zH$@PHNC-`U>ro%|riYZ7i~xipwOgBc!zASy)dHGkcv8WgU<&TTkHZ3jLb<$1f`o#( zNr|ZEvXm*XNxh*&%B2NdP}5WC1zi3BhLSRz(AdAy;6KR81~hu9*La@sG!PX;OW3gv z0JBO6frt8}PnFF!vLlCe0EcymCEfKNC|-`@pwQtcMzKo=(UFd4*%w4|J7Bq^>A1mZ z!ye6%j_N?hZD@tn9aIPUXBeTD;MFgy$H!FP93zC1A=ZBE zpCVIM$T9>2Qd=RZz5eCjegj|uE<+_T;F%FVajLS9(3uM&iPWM;)oKPcsbEqr)Y+-2 zB(ZHkDxgZF2f-I$A;IWyhhTvgR?5ZX7&|BihwmXw4e3zvEtBS}3BPg)^i7FBPPcRu zWI;wOb{kfY5eP&k+b%@g$*Mg;m@IyyRz+wsinxd;Gfe{qzK)oa^ zXxQ^A4>jtKZ!woXRU|hSHL&w3JgSCkK!!wZ1xS^U|6<~R;a&>i#dQ!&br@N$RN0hW z9b_51a4?qT@XOQ7J!-6g3-JpG?Qca zwuK3kn}CMZs>hY+8OYp(k_iMs5Z3s$ANh@6g7}eW8iYzwW8-GRN%ZP%J z8l3wxDaOIS(6wP!M5Fs~kL6)62_56lK|5Bn%COt!_{3dx$hK}47;p#}??Hz9PBmos z7rI^tDMp5CMwb4%K>boRJ_?R0hCtt_2DVG*zMikL#80dj@A1VA8!LlA@ksGqN$ksWt8`Yj+wxVJ%|CP5IA z1DY&ridF?GlK-WM9(AArhM-Mg5^<{XC_y;ZG%XV$h2&;#FaL6V5(}1mn?;N$F@>(2 z%f!c+qK%5b`5UQMfMGZt4bvb>(r_s?VvStcwP3rRwtR248(#e~oykM7xTeql%8<4e zSrX@7{~B5D%{KgoVhIT(?J?Q-R2J=d<^)ev62s4+!Xtf-jzW5n)!{&3L1)qVL2$UX zZXR*+={9jFlg!?w8XHkfP=-GK87sLUd<-Wkg9OV$2-G_)Lr#cF81l0<1Vh+N-1f{b z)HnV>AQB@9O-ZQM%zCmVA>e@@z=#B2*h+y*FW=Mcbk_Y1UZb$l>IZ|+)hCD=fxQ~0P;Rk%k0=)>%y?{BIB>s$w zQjErcjL5KsPDEj&`vuK49Q&*4QX~daR1NM#BlFmWN0NLR1hEN)4(TwK{&FSUz2+9f zP!>xL%WLb)(-0wqC4d2EY@RDx0%!>dacpx1`g|p4c@{$2o(B9LcHmeA2P$&(OQHpi z)*;4qc;?Duhr)z083U1UBa?+8H=_xmc^ti*xmt0Wa!6pZ(?0Ez!34uHR{AX&$Z~{f z+DvBWOpV5EB+p-u4ozx*TW!iLlD1?sOt&jHQl06bW$1Fb?|=W76M)#auU?WSN}NoY z@?=VqBvPbQsX|4Hl_<2R(3&;N7ROk)eBG+m>sKvd!iK>TMod>PZM$4${^KT-n>TOR zyq!Zw%^SL&?XI=sWvyMicShY&Ll(~6I;Km*gF7Hxv)sR_p=MLVrYVYQngJ;g&JI34Ig|lWZ zTw}(R_qwxN&23$Bcg2Al_e>n=Xr`k%g9h!GGiIxkC0nLxS+Y^KL5%_>N|dKfnKo^L zL@3fBK!pSW3INE`06>5+4H|^Wk@V<{8ZlzzDAAxqhQ1?8glIf@M1=||LIg;WAVuyY zDS8xX{v%0`9zl|%AJV2y{XKQki6@?L!igxEj3SC{%aC%9J`Y0v7@>p{Qdpsd7h;&9 zh8uF&p@$!W7@~+Hl31dNC!&~QhWuoq#1k({(L_R1NHIkfRwQACEL30=%Pdjga?35R z;PQ(vwfrJXNyD_H%`n7dlg%!{$P~;?+MII^Ht6Kk6FNkJDH&t%XoK7$S~y&JDb^MRc7m$Q>LQuK<18^ z=DfqsHg8?S&Nb^;Q_Z7FkyR&Yr9I;eYS5&n3^d9l!;GxUEE7ttq2vY%C;kOPwK%7~&nV=ADO#Ald$==bn3qyaz}m@rg zASC_)M~Ekx7}zT)nuL-`GySNTufF^8+poX>0vxcw15enGF;^_K5RDH-Aq5ptP_bhy zw9w+CkRjm$j7Y!qk`hY8XhX~}QR-r)P1tmk(=O?pvkf}wY?Dqpn9lr8E1ALrk2}|x z2~{;%sdMLAa_Wf;Icae<4msi!ZM4#@D6KSB;Z&2AR^j{^C^GA8y$(Bw&E<79O)aJ7 zJJndz>CS=)c1>cKx`Qb@?Y?uojJKuR4Hdibvh8u$j<>BK+P-(le2R=)J0y<~ zB1wJ$2KXO=p2)kKZPO53yz$2)pS<$RGw&fk{a{hh6E!9j5sy|xOp7fQzar#EMD`+* zFf0iZGBMg{6D2phU=vI?HQ{s)HPoa-RQ)g;r88uHJ@qwRVx=V@lOE_(^v2K(m@WSC=6lWGb(%wdjoh-xsF%1dA(vzNM{ zP%RTw;Aj+xnr9$mRjGjnY-ANHTG;W&@g!|vBPQCg2`{?wzMP!H z8{2SMJIt|-b_^wFf?13?T2T#nj16mb$r?E>*ovctW-Fi>2h++zjs+eK8F|`UooYE1 zr&TR0Ra;Beq!JDcu45cu8{5}32&tx!NmQUp8)N3C%1D`TgRoqaT9APZah&rRr#S{{ zT%`g@rLdr1a9oJASnp}~YueG8rLEF=*)Tt_G>`*nZfyS(81H|0a({YjOO@IhtT0sy3 zpszE}ceXgK*B(@g+Tomcs#UEnCIWMqTW#jpvqbj@;t_%fmh95V#&t=;UBG!9@C<}c zmO?kW(w#1K^Hq;1IK=)&R&bcZD8^G<#KMuk_=U!ZK@3>Hf=Ru|1~GP_NvC#$7u(3v z%T5`Ts#=3mi**#+!T}FZDWw&4`59TBiI%h`4IF)Y#sZagj9*5B91lju0z-q=J8@+z zS=kDlssX1C6WC{e@}Ho_CYW`63Mz_wxB;v_hvlP0*KI8O_qffkOrR z&2OYR+NnfCz^;^KPh6p^00|t|Wj0WnRa4VdG>A1!E#^>jfd}5=W{nb33UAL=hbx5H zl|9|~vVx07JY^NnP$VN1K`f$fdNo?f>CUuj2I!a>TDpWDOAyb(qH7zvIq`^xSiA)z z7+?3>CC*Nxkzgab{3)P0(h(FT)ic8z?(l~fParXkLKUO{F&%|B<32_7cr~UAl{6_B z>C?q7Fo~s5qJt+dqXtoiV#3Ap<-b;8i=x!>%&NpymP^j{JrrQlbjGU6k?`S2I|h;!qW< zl+oj3#0oY>z7=kC!-;Z}HbChj#O>59h|9h1JX>U_yfuf#*9sy#-bpCxzT?n|j(NA3 zTOvh$YdQE(jy}43Bb*<{D^lOdW4Xc7ICYJG@#zLq_>IE=>(F>7@ zoEVubIW}&RCHhjMC--{{rF2#eRw`;UPM2l`r_vR!^sTK!FDs7G?&?+pefrWjEA-py zeXxubDmTX^RpOepuFmBtAw2#&2p}eFO!*lS=*Yta$&mDvNDP%Qq}O?!kH}4$H*kYCPy@=K z9G9Gu%zRy7#9w5zMPRYXThz&$^b*qyozcwNso)q6RUd<0pV0l%(18Zeja6Lr%{aJ% zSzuT#b;Z<(g#@MFU7Qf4gq>duMq6OtJbZwv?_^v5P77jXd;7>S3wg~t}TR(G5ZC=Pen4$g$u`m&P zT;6ceN4eC8M@`Nq6v(^OnGEt`FZ!aLvB*Ry(!+GbD_fRtRRkO z5!r3%2Hs^t@2m?O%?=Y?4kvmC6nO{dXbyK+*_TyIzHO1<2^6t3QJDeW617L|l%R0r zj=}W?@JxdX{$fxH2~HR6!f zifw?Vk}=nS^hYP43%P)cB0!)_4peQ4B9~pDBP1Ruwj^zO;3}4fly!@@Ji@oc2kw+h zxtJEacmg4G!aW=$Q7Y$hGH3Cio)ug{#nb{Vd_*l+CnZtRFo>MUNg7QsRZSe>C~bo^ z*caX4j60x>)sd5j{Y+Z5A<^L_4WW~1kcKm0=4jkyMBe4vsh#z;rT%EN+A-vkf&nJ< z6=;FJ$(xXaIe67tXx(A(VRCB7^T!H1fS%YJa4fP4ZzH0O~bX_D%T z!3-vJzPq!E537k_jDCzOJODrv9^>#(kfG33H4IBAg7!jXu?$4%v=IU_fC5)!%$ z%w(fExWYEDjbQxOf1wy$XvMC<)wr&sf`Q?FUT8ZyL#kXReZu9s0uF!1tE!+Ag#FUe zfW@qd##p7H0*S@_k;BiZ*r>(LJSeJ%?1N-h13F=rX}roY1OhXJg2dj+ZREyoyh~3S zr{3L8u>96>OqoMz&L^4(26Q z&$bjl7(-H4OmzZ-E^rJ>=)$B0LpET;E=cQB(N{YD@Iw8V1DGz>2eras&PCNAgDXgr zob(NaDNtL|C56qaWj(_&#WlnOJ^*Wo z@WV8uiZZwYYYa{gU1Y7?ligt~Y5E5n0Vi=R5v{ULzkS)3aapQT%a*xYZGvJ1qRxtj z(Rh>@nepgNYTkbI$0zKf&%$o(E@wU%11!9PF+P$=)Lt)eXEp=_m6TjJYy&prgqOC1 zr`3$kZ0lyI$)Dt0)%Ycjr3GBBt$;FEM6PS9Xq$bSM#I)AJI$x7q3d0ahS~|87tUH} zFc<^{ELsqoSTv@J^n*086Ee6;Yj~Rgg694xzzZl02qlshCaTeJ%*UCnPUfhhD$*uG zc?Xtp?&4ipOIAxtI?;HD#{q{~dRWxA+=qN@RPTJk!pZIkldv!LLl(qBF4V$DXbdnA zgEEGUm0$xVdD48L!zh7iRYgjsEM{O`!#EaZu8rf*{blu0SgNE7GC%`nI)mHVr>ZC- zGH9C;oE0@fyR* z4_)fTVk~bg*Sc7uKh-Sd4$DMYaLK05LA_`MciDF^!r^VM1lJZQ@>_0_s+l$NdU$Yf zqRZ=EazG2To(+UCJQ8`?-jkeEIxWeysNl%yqP#i^OJd+@H2DOc=F9{Pe1cKa# zFZuHFW$74Z{n(D-vLbGqItflY?w=IbDLbCiJL2mC=_Ocr*j*rlJeaYH@EJQD0~>ed zXA&81h^YTEm*kkJ?i8?Z{*lM5I#i8%M>`KPcMJfGCW34pUUqJfRV>?42tZQTYm?G+!O0SbdVraakO1uKySb;?WfrD6-F~IagAnX{d@DL;p z5rQZgfowwFeJZ&OheeGfzjdMns;U*mmOE?5=Wz7}CKOlGrg*gIA~zAgm3649QM$2p zb31o*;X^UpLXr%FT>ma6VZ%0*GA|HsmuO=hx$eYSi3$j=dmT?*BFfb@`(a4ImZb?*X#z(p6 z2S7jfjpKM88B8ai1e1hJ(`G|W4DTp?NmUsI{K4NGh9k}iHjbH7Thb?ns)`ghtY!|5 z!?KEMtm`poLVaV_4xO~aG8kO0#yaWWGW(odmIa=a!@>H?KFotOY_pNo3$BRP@4R;8 z`V)SP%Lt~&9t+-w)8-$)R_BI}v~(F3Ma#6vCTwyUN;VX}u@>ZM@FNp2B;-SmYx<@$ z&ovtZFr5BG$gCG8QJPkYCzxOrJEX(bn8{XPjX9}zthFVbl5G`tFKR%s!>&pdYp9RC zO53qY69aQQs{(~X{1S{n+{3HDMm;gEuIST%_=>vhN1ykm zMX}BXf@0#mTj!1rqaPG@P{-)#HUnpe7SVI5-m`i9`ESj~a7aQaxH+f$`@i=KpA|!o zo7d9H@cU3h%kaWgZNuDDM%YBt*9J|lxmwh;C2ORUoLaW66T9H_pK7qNegC?B>-v0G zv3#F~Vt*lJ1?)T^&puSUG6)&tD2Ndyb#Mr9-^oWFQyxS`HRvY#;en17X-CnEjuiPe z(f$WFm(|;C(Yu&gp5+Wj3j%!ATYbOu!@v&%$oQ^HR9bf5@MBOFL4J^+$kKsX*jC(F zfO0Wrp*%aeU1eYSX7;)}0lV8Zv4;NG!pKJUd z^lN#B);BP-3Tm(uOQYQ^yIMIYm_aU2gCl-zL?S21QJ&wTX+i=mI^d{6V5#C8{?ns- zJX1>}JPURxizDEFwDkXV0K}j{j0`a{n8=VIMt}?}az6m3yEn7Bh+OT<}whdjoZQIPT zd&iDlIBVg;v8xtt964~{kbx5??ismfU&TcecMPmqXwjTGi>6E&G`P^5K}%LwnX_Zi zf zO`Rk`f+XqDqeHSY9x8PEHljiZ4HZnpDA6E8gB&?xRNT>^MvWXTFYdhlk-_MOnh#_& zaL{iDRYEv!5|yLAhZo>Yo~P&@rbS zbFP6Ws;a`NMjds=$to<%$|4J_XY^WZt+n1-Oc}QL%4;sZ0)vJbW=JHl#JEP}D;W~^ zat5wwj&W=+8KZIRt7o3^YDalGx^JX?`UymnWR?LXlhQcZB(+XfdkwZnBB9N@iE^`Y zyF>sn=s1FkyY5Tqm{V>!7ptRwpo1(T!XPb85dFLHh!dZtMaM&3KoN>Y-Co6EoBInbNaeT~`V@7?e)mvNK zYu3YpOhA+kVI_pNXbo5c*d_wsQNl`>et;tTHlrj=KZKD%6 zhZyP&q2Cr7Xt_qntYpmQm?L)(a+w?3>okQEh#-QvZT@H?M8=cIHbqLg_usnhz8mkn z^-d{ZqPpp38*dKY#u^0Sp=zCQD6K{-WFVxh(;T7Ek<@5Rlo7qfY)WL$H}#*QHC+I>^bc-@XD&%MPTpZxO8zmK19g!=m&Zv;meL2DkZN~?>( zafKX?cRhw2vp&@e8I!AAs{$bxxa8$?2b5Kb0Ao5$tn7iNOOfZ~l0a4E#Vs>hi>HF+ zFMKou6rvc7Cv>MYC`oHd7>S#1D3YyhX=fnD{)tZXxK_P!fo*!#6I=Ae#jb<6sUZnr zp?D<0kJ+6MiAhxA5}7EHe#j#m1Z&^HtYMCH#BUwzsK&%DHjc4?V=OsBMyb*QjWOzl zE*N^utOB!_WUvf$BwApJUv$}}?LuYKI38KlX?l2+ra z);t1*hroy;tdyJZY-c#f84lKXm_zE_@P?HTWpSn_J?N+@IzD_zoa7}QKr|7Sv6SU3 z`z54rc%vKVI0yW!QN>4@V;vMzhgPzZqcE0bj1#hv=1A5m)p@RT%vc7?@<>fPw#;$mdJp6A&eTwI1jq@iywg? zMJAZ4nrFEac#)u!B3KxwZDl7oX!F`~$aOB_3}T>-7^pzPHa$^Vf|O!=PPw|YorA1$ zc)C$UJ}_EWyWSPADB%e@+Lsi{p${E{FmX|liChMl z2QI@i4`fCtm~mOohT<43TgLtZ-`JwSz|4kc zZMfH)E;-MX&MGaJ^er|eq7d6@AthRySLQ%_ z<^YE|$Z=A!cm;Mjf}Jxc*HR5(s4jMq3pHyRvuVEZzBkpWkyB%4rJKRn9lIZjok7T);YE>lr?RMMr+Oc>eQym2!)ZR84Aws6u&FG zriwHH&bFjDZ~0j8C;n7Jh)%>N5_Ni7ZV<8?ZW$+rJRFxl9pO(lyZNlh?I&2{oE%XC zw4houh;`o7!a}wf(18}TzW5=Jgnbv73tCYA#4(P_?C30xd5n#6=1iDLma?MD<7IJr zStEr4v!FJTk})eyB)be6hgr*u9Ai}S^`jY^$OIwUDXrUvnUa+JUbeRLE#z>OYiLc* zSpVryrO;CGH7dG8{7BkM?Aja-FCd=VIt+qgDAr>uk_d~ zlQz{~N|ua32&S5J%qcZ@x>F}FV-(8(b-nrRvQQLIv!4^{3?{zg5E-}$%$)wr8E?BR|d6s^>=9-9WSo7>#usM%Ke%2_UxZ4U^%hog!* z2K%5Kk#R5QILFD(@nx5t&SfnV*?!oNL@a`?EtmV;>CU%!Sn(-Tsgybzecmuy z=tdiYFJ0h5*#-KPWlJuSHk&+(eeX2ike9q?c6#)o-H~N5QU)QXPW4&$4iFF4t%MOl zVJ;DetI`|p#)*xIvzNW>aXxlIwHj@z6~YvC*ZuB!|HK2C!yJmkipIp^sj@_7Luo8o z8x5%bY0>KU=u3}0zLQ?>dq1APn+=SKlyMB!CUGC8$b_>X@!+`eRyS1}4t2Jg@i`~E z?3WW@N1kIXrAA)<{{~rKZ?uiOV@3?|eiZ3lBLu3|<-A;u2illUS%G7i! z=_1eZ>g@s}@80yyrbMSzI8TXQi>V^vwydQ}vPE02<4np%xZrI5EP?*yZxHCO{$MZv zjLnqv%n^9Q5E`N20uTs;kj3&r9tdzj*r6-J;uw%YMoNXHIwVyDLsn8v(=N-@Ch+Kv zE;R5h-$r2+K%oo6koxS683Lgh-Uu+DK^lG#iTc451mLz}<2 zj|MFP6a48C0+H`* z)S|Bfoeb2x&Z0U6w)L*Ak;X62`F zO8fY&6deyVG=UT|kQ7f5G)_?iho;j~B;}ImwG<8`3SrEm>s^jRYe>n%eo+_!kp>GA z5MdCk1d;5PEjh|$APOQMpm7=}k|N8ecBY{kGO`*j1&qF;bpVfK+5)nm3I2~Ja01QI z6v0p(lLZvi@f^Ky6jyO*N^522ftFtDP9E+`dLuiC135q}&IWS+=7UP*pD%|wYgDB(E|6hZMtIv<29a!$1}Bs)9nnwre=_AMsS5)^J{ z9gQXwNCOOwrX9V|Eip?IjLIoPa2^0*Cm)JBa#L&eF#ci?FoknQhm$aWa|Y>;T#PGh zilZ?T6i9=VKBRLia0KvhX8BZvkDd>LhQ`U<@(V#j6h>i6F;o+(6hu`sgx;~|)d~!K7uET&4F@tkI1F=opv_}0#~6HHTt9<@rf6fMIu-vU8B?COw)rw-SzAz}0&4|6yJvrR+Q zO-pr7<*a&QQ%_fwRdXUAIAtt!##9W0W^ziu?9JZ7@D!5-483qlBXvrXNH=+;q6ebrHUHH7AsN>39e^Q{@~)S~DiK8MF2%cR(N^EZvsFx`||sg*cS0bvnV zTIJ6-{|TVV>02k3VpBp$q!SsK(4`=YF!1OTNsa#Kki|)p1zsD~LwPkxMx$uH@JhF| zB{cyS@robrAvcgmh5!=&{&QMG^%RQpU<2`IX>=GX!8a>`6;8BbllEKp0Ux9xRtw`p z*sYExa1`w=Q8RR2!H^S#wKR;zXy%m@M2KG55)}0HqQcJ(d*ek}FBoeyIDhtFNA+N- zwK(52FkSExz*K4Xc5e?!WY`Oh#E~YCPQSvlQ5}yINdqlO!$TQ&UcVMZkt7gy>ie)O zA8PX<%4QFXvOn9DZUb{}FF|2}7IYbQI02DpE5Q`ZmTz0PTbWj|7Q-1bt+ObQ^6o7Y zFsoO4l}c4Mgu>Qqfmam5c3wjvNt(fkkp7mU?qPTo;yTER<9gF=iIYuxHgqu|6%-Z| zes+6F*FXJm5M0j`l-G63S4a{Ly z9pU#wy|!^nBY%N+YgsZ`Lg5}LxUTrY6p%*{isPRMk#lQwVI8=Eeb!C4SBFJcXz6c! zEtrUxHaau-v8LA4JcC_}HAx(oN{uE-IAMxOLwGa6c$0+`T)3`kham(aDC;qPxQr9Fm_he$196j; z8J?e#F2gnPZb}sK4QstHh4c4>t=U7nRuoV!+wK9J1wt5ixq&75m(lr`iJ75;mU=J2 zo8y_HpEEi;!$`L9Gon=fkA*dO8P_x*RfT(inTd^tvEGG`r2T)tTiPMM8d9!~x6;h$D;d^_l`mX8r6kr>?^IN}@=pHa3d`ow3dmFQT zJF|Zo72bQmvAc}-dcPao!S@D+ZxnQUvy!EHuIU=4EBnBGo5QagXshkPLtMni#~w_< zFc0>OQ~bKC`@k`rz~lOn&-jf;oW^T>Uk=GA)7hLC8osA`!(H6Pv6~faoXCrOU;4W@ zdzP5D8?y`iz_r`LFMPc}+sLcj%Kd~M0Moa18^IBLyQ`Y6;Ty;q`nj*%%+H)YSOJqA zI<7H1%>Lb+uFV<26&AnI+|KXZ85Ibf)`Pv&#ha%w8+!-*!Xf?1MZF)&TiBny$PdZa zuN%~LJr!yi+OvJw>GB?QJIYaLoZR2N&}Zk|Upu** z-Pz$C-}7DH_nqJS-QWKm-~(RZ2cF;y-rx@&;S*lr7oOo8-r*k};v-(-C!XRf-r_GF a6yq~q<2Rn;JKoIy!Q(^TTmK;-0028TDCs`{ literal 0 HcmV?d00001 diff --git a/doc/iterators/circle_iterator.gif b/doc/iterators/circle_iterator.gif new file mode 100644 index 0000000000000000000000000000000000000000..d1bc507174ed0047245686baa3e50cb5462315a0 GIT binary patch literal 38534 zcmdSB1#q0rayGhR23wNFwk&35CX1OFEM{hAW@ct)W@ct)W?3xnl}~a`zLVt7y-C$y zmAl$n?an(hJv04GcfW7V)54-ctZcgXAon13NC4;H0M19|sMKU-W#!R{aUc*l35sxj zaRCbzRomFGzPafd8ia_5NJ~qrZDsy(^*azw>W6~70H4ecdTLrQ5C8!1QKTX%gD0qK zulwifPt}zh^wuEysMOgo~xN2 zn?61dHy)=myR(J0g@L^;p0kCyr5(F77rw5()lUQVkMDnqY4Gv>R>j_o3!m@L1-w5p z1*~ih@R+C>sPt&*=p{vc&t-qwY^D2YW93kCFb%6fCSICI8W}r5*L(CPb}gWkKVtYfVE( zO-o~8@n>Ftt8Hg5XYg;s_)lxwDY#f0(8w9sSvlD18GKYH_ zm6lCN@b7*6XKncy7?~LvSlK>4=;-KvF!D1BFbl9Tv+)bE2?#Q>{-dp^rJcR5rJljx z<(hoR{nxgv|7BZt0b2uIdn;Q7D=YKABS6O3%HGP(*vcADK%Nu^o4A#Eb#ue!t5sh$q0n_|KDc*FKzYzC#y#DF&LUZ@c0W{{$BKf!9QRB z0sfC4|JXhTmLGe@_G5E^0Dr%~y}mp@JwE)pzq`G;zPh|PKRZ1+J~}+u-`m~U-rC$) zUt3*SURqq3pPQYTo|>E(9~&JR9vU3z@9XX9?&|DlZ)p{}N?qO7E-ATK8?BP}HJibh4%V}YHlPk^q`pa}acQOb zS*JDSl)c54bLEx$6|g(oT7(iSYB=9^#GE~Ay4YTbTx@ z!m@4ay4hW-YVGQ&-E->d73l5b>*pU37!({58WtWA85JE98yBCDn3SB7nwFlCnU$TB zo0nfuSX5k6T2@|BSyf$ATUX!E*woz8+ScCD+11_C+t)uZI5a#mIyOErIW;{q8-cj6 zxU{^oy0*TtxwXBsySIOEcyxSndUk$sd9|x`3^=+!d^mX8f7yH6{k;S5MR|(Q>2Za= zA{uY9))uh6ouqPplExqKM(>eS7_P|^hOWFv$dV@^RY)!_Iujp_`NTcgyR$dUO?&BDC2Bg`H_l?I?=4U*Q&==~ z`L#{9tlqP&Z<%Y$Q)5+I%}?cBDV?~p+n){C$#-pH|3tSRFAFGA&-mqda@c~+6V>7I zay~Lv6=e0;=6-Q{lb3as34Hzi8>09d(7XTB@r3i9N#MHA!+hu}h(AUG(mmmn<^LX`Yd6SFYIAU6ad z-qiO{KULo~asP{WCz(^u*C@}#`| zkwL>mA=~4ESl8Ybg&ZTX*5cfxpQ8uaZk}rUC8?dq8L@zV^0V^#S#s}kxc$-eR4m9k%wwBzi99Z2o_;Ox7AT?%IH*SbsQNMWFYSGj|US?4->3c>| zeR!&7(b`fuX4$gsX=Yj8RJ&H$(E?hH7khsLXKLu%x?0c;HdUNj3WZ*tQxce1N23ce zlziO}u54aCfNs=o-GvM{WYbqQi+M8$+zg=|{7s%-JBrJYPCka$_eMXU;o(v{NYNB( zH}-8RoPLT6?EGeeaE!8kEPutkengxllyQy`9oJ!!XNZ$&T2lJuK1^uWlP>}G zW%HIbIwISS0Tgx1cGOgbJ#asPX7g!3$jFoJFgt9M?Z_lZ>*X|+q_bf&(d~uhXJ}q# z>q%1`_sfaX-Fp+5{hgG{rT^q_wv%BJn)cICl&-eBvAsyi>uF_R$QTix>Cnh1XTv#YvR(>)B$mHqYa$nF;XbmO%UInxq>T66N*0 zmJR|l+zjSA<@)Zn{ko3M_asT{{b-jA`bmWskvZBMGaMJ3LZs)J%GwGy9uKA|hX=*B zni&wD1uvY;kJdUJ$W*@#Yvj!LRVy!mjZzm`AfOi+5jjBMeg|QuNf4J=HW+pl4>6*c z8%yrSAHV)5e8Vv>F;EFCSowbYi`(!IP~sVep3mNZ&(Q!-WL^+!PH!AI-XZo`*+?kw zJka%FA*L78AOp%>4e!Sc8>%vu9#{0vFWZ&QbhFXJrONnw3nF%kvuY;(ge~p{H1@dS z>YJaF8t0b>S-y5h7E2V6E4PetUebYho+}YErBF(df7VV)U!*i4qo9ra6fK3Kj}Fu4 z{S)ghd02v&&vQTsG+i#iWnb@G8Cn^KO<4Q{qX7lXw6LGQO{gFEE>r+auQuc;;fO>L z`>&pHmO}c}Y6)-c-QIC#^6eBy_k#*!)=5gxyCAvyU6zjJDS{Ui>Qjkhx|0L|ME2** zSHe8OUyGA&xpF{|>ii+z4ClcR;%SG_RpXmdjB!6DF$I83F*`Ob0ED$Z(#79E3l@t> zh#55tVp&g6{BS06mr6hQQ~}TBWlj;MM!{M3gboVe4ZeH>SYJO`*20KpVxNm#$3c)B zV)@GN8(%C9k0%#Fu9QP9TtYQb#0jCZ=oN^Dtu#OevV6)@DmPk&pBFC@0=*cQYhBKu zdICsS8)`w!1{v_*p|$ECPnxx2 zRAx_A!Z(syUsdZ^T%|}Qx^cSHN!^`n(xC_Hog_1mXeUtEajGZZrbzddBs&IzqyR9s zFhQLSf(XRp#XSg7Nq9+2=Y_SzrNg4MTTB$H%(zg0K3N}QA1w&bA_g^B^WdB*; z3Z_-;Mr9ED#O+9*uZhBr)2`Av*jRi&b{>zcq0+d?+&4^V9qLiKyHV}j9IJ?GaMh+e zahudf#BT+HDxrZf)I8(`F^-j0;{8k>Gq|;(pe6gFC8vnV%Rfjesb#+ZQ%WWK1uY^d z4Srza5(DmuiS~gWP1iS(WDIUmEGgpIAaYbiUebdsMVDfe2Hz=Ph0`Vi0^vZeCk0RA z(iWI8_NG@B?$Y@^(SlXvON7KONJgcOMOYGlpeeQ6 zuQCvo*VX08#>OHpD*d9dxSO93?Z*dZwiN0r(1x}hgA*3UDQ)ZVjkb9Q@9ZF)3`-*I z_2)0;RyPV5-HBgqN*_B8_iI&qv$>-)GuDqtS)4X?CTcBSxH^2oFn0Y5pGwx;Ba}&a z_ppUo2cIL(!r?gEA)pwC6t$KTzr7tSR6jv2VXIU66rT+W9WQA8>WCP6h#` ztV-HZYxffDN3FE%*VOg~VU1yi-{I|(u-{H8gIpGCEO*U@HG1|XS-Vs>z5)?bcEp-o z&kEP=HekScy5WgG z)a8E_Tja3@5|yf)$94W%(0=JcxIc~5y3=y>e!0W#w$~m%XZeNWPIAj-Mz5pf3-|AP z5Vc=3>Rm4rTb&OOG+2Q8O}kkV;FE#0$CO#$&4z{biNNLib=lU=<2NK-I^Z>Mn}!F- z@1R$S?sC`U`D@8@E6HWo$;G0^WqV0p9^L2F+U0i1qbSJxVaT(-zy=Y*k^9iAw8&k@ zz!8>Kb%ez8smMoE*sJKne=vFHJUG2SdXXplZXjzz$$Zgt@C88o_8oohGcbj8_Qn=* zm~6eJ~FkxcY_%=OK=E~YBt@H(XBl4)^rZU zNDicY@-{p6MECW8&~ay4c2d&8I3N~F1-Hy%6pLdtpMtaq^A{OY5}&(u&rz_P`6=GB z8067Rk+x6ea%|qJPtgl0diKTAOGMn+I3&SXBuPXCR)=!%(2P^X?=uF_d12az);Y9T z#9v@IuIj|cR4i1LCh`D zr;pUHXW4%aPfbi}i<4-8EBFX+zz zHhE>C2o$oInd8s!C(&j_kr*v8SR)K*E?!_KG0-WokeE?8P0<2{fy2D~vQEV$wOqj76MJ6;b@l83vD0Z?~r9+vVVi!@i zc=C`~iWM>`RbLL$1ToRLXQKp-<^*KY2#%3>K~?%=hlC-B7~_&K4b>!Cn1rS2u8 z1S^RQBc21z{`8_z3L}Xt-O)xNkt8lj@}iM?BM9^)K@S0jQL4#aEeLWd0NUVqr-fus z(c~c!l@L)^+m!@0lhjB);k1#IxPufs)o4f2Bqvdoaow;;msAHBKq;F;7+G2;Oj@{V z%D#w-g>G6XS^73qbbw<_5?S={bL!Yi%yvTrgR$9<6B%$`r1p`dA0tK!CY)-<;l)a+ zH8ANvRDRAj81X|Jq~7>XhNL-_s2mfeXvvE>1ykJR25rv*E$1IBr-?(h94*^-6<`NN z-(0AUe$uq*i?o5#M6gosCYpzmiodK-L7fKwE(v)O6$M?j77jHYv;K)l$ zU6DUqQ9N78-Av%?f3}-fH8T~;Tggr*A5CXC%q2?A!~34`OEi;P&1AU%VR;0JlU-F* zEuX1W!#pN4m?2MUG@oM?A^2IJ0v1QmG()3REe11R4mLntEe|d`wG>jHOH5sSwE#sR z4GFW*@gW!AMyzZklO4-gF}0AQxd=iq+loEe8LOBXOOuTV*-XsXv9u_Jy%3ea$>u4B zf27!#y+GQ@(I&Jomc2MttOSC;S@09S{a{G z+9_7#!d`ykTG(G&nYdT^Io)qVK5hhqv|&nBQ!^~!*ccODY5}p`98Vr zQ)>;dl#{;c)9PupN+>d-Vkr`~A1Zbw2}Ld9w!$DrEt*-i|Mvh{k~(3c3g)(2y0O~G zQ6<{4S^_gfdZSu)@iGp#dS0{K&-+EU-ocxVz~G55IkooGQf(qiY{3)0G+Vb>D5g0H z%~`mxIdX6f=St=ZZdsaURA?`h_dgp`SgEB%0fR6ZYbi+T%Qe$0nNuOD8<^?)(J4U# zWrgH{`^YsOqD`!0wF0YEeCo|Mq>0zhY1|Gq7pu)4XH7w4O@X4(<;nniRtQs*l1q+HV^gMN|&}~ zindmY7I)#g8nbrsXEjD_uaUFXp4XHqj@DsyL@+$fu2=Adw2pT5+6s=&fwOk~mc${m z=x+H!SU~X+MXNP>$9`K=5l2^@S=Sr~u(P|aBQvbBy{)aBsPn0;^+mlC5Z-a9{_Xs% z>%^@!iMR{wtt%G02f@92Da_ZuziVR*d@HT{TD+A^tm6^R?cS{CilV&=KfqSJnjkzK zS)vD8qYJXUok*h3h7Ew&&?7e8gBYGZ%jC^K*-ORQ|BRjZIlGrqqrcasrb)Svzr0^i zqFZQO4iT+cp}UVbyfX;1ml=LQma<10e(;1e0EV_k+dYN!RG$yNk1l=STloNn1_+|H zm=Yy~%KAX>u>wrnp!?8})cD|Ilb+Ns4du5Xc^9!x5DH^ zNrGDU%rfaXC=Gh-(PZrB+L+(d7=bB>KIKSixU)Z;f-7Z}$Qa+;+u(k9Z*VAxU;9Lydk^Ba%+Byc1W24$>)L&6>%li_n;Ddz+<=V7Q8xNwq|-Ni6178agnRW1hCuBQnv z7D#XxojFrbw-wka!KE~3JfG)yJr)%vraxKC8AdFYzqW~Q%yUI_;z%yhaV-*TOgnol z6M2w+iJpMiUSf&p)u~vr_CP?AoC}nkNeN$`3jyJn=<(7_w&hyVwOB#{nGLB}5#buZ z@Sc&pUQDr=f~dy0bV=WpnZxFrPkvv?wV1)lo{hKwucVqf5A&VI`O@t1nJHtnm20_u z0%TTkh@*Xd_6sF=9QSh^CeiZZR|tLUuC*my4MGv8Rvb~kTZ&+6w4 zDL4;lz3qD~8D08GVHrlPK`}nPOAYEOf|R-QDRZawd04!X*dlFXCa?#DZPrF_*@O+aynj)`8{Z@z043 z(2cGc$sFN+bc_%A^WUN-J4 zFZQv|&N8oNBd^{%ubV6{(2XYFY~e+?NqjGZs`Jy{> zw*WuC0&l?KCvtEnu{aPVI+IwU4sJ^BzT+JU>jWWQ?l$dP4%;?%D%FxpQ4&Pvpu1Ah zPf|*UIy7e$>7aLE)x0quDi(rt~DGvVwbvBn54oyk~pW-_tz`FRSa*%RsD;qrS#?M>-9|_@X4M1t9^fs%iJ@->}3!8 zWr-4$0{1p7E79>aE@eY*5y8-EWulx1KYXw_Xap?sJoYdQtSLRYyb>~%Ode_^DSLuP*i!a%42--s$ zZQz@)Dp8WM<gOSZx)Z|8+)SSyQw-XooQmO-W5@8J>Ozf|$f$PgiNV03747TCH*pRavEq#_ zp3>G){MR{pPC0CT_|ex`HxL=${Brx8HUSWQInEW7WlDGp`1W3Q98C$Tp9((?^2_X# z>&pZB%q2(ij|pXqRTD z#3JFlzY{Vh(qbFBW1yaPr=nS!4!d|8N&C=wWj3qz=q(kYh(ywb(jUwtLa2kji!GF3 z)Z!*SsLPjlFIGIdw}y{Siu!;$fURIAVMr(zSfk(iSEn9+4IJ+OywmB4y_bR$ z0kboe7!xT%d21U+k)v2g)mCl4zY>4Ix4XWws@?1@s*uUM>JT6IO|FP5MdR7_a3X=E zxf!e8e$F>&=?ku`705IWp&P&9gK?{m9{S31UoC z+UNIgFl3q)=Gt5TTb;VG$~rkPFd@1OalB5-9`?H?#sPKtE@rOeSTWVjc^w|8^L4AS z>z{deEho+W&@r<(h-R*a6(exhmvm#JT3KLR% zn(?vgSP6cJoF@uBAvHo=^?n28vkHnz7Oe?NDnAesCWP;I;TBlUHx__PS{xXqDl8oe z;>xGSV+l#d7V?Rerf2DiJYvT%O3Q4u2lpyw0WZg^N(KXr8oVa-=u3_n4e|5RdJ!xE z>5jJ#Yfc3lNvoElXz1z;^Bj+=gWZ}9Tj!?-3A%dX33|EiR(#DriGRa1Z*#xTJ8QMj zJEH45b9pB38~mumBXJ`h9Q+yo{tGHO37xr&)yD{OYTpKzJLM?Dp>xG3y|5(6;A`*z z+YSM@tcqqf$7Iz}k-!%$Qx~p*7t=5LIRnQy(UqyEC1g76CP_;Tshc&=Ol>9w-y;P+ zAGiO0Id9N4{2oHIdWdaNQ>TP|9e7o!dL8Rg+>g+D=D2o=dT+@IwDr4T);JyY>f|); z%@9ieJb>N>az3$T=mQB#h~&0kOt-{-y$ChMX|b$Lk`qe^0C3q4nKZqD&&hs!=a_Uc z+Hlx2;`wd88x%+gLuPlS`?&80lqA{K1Gcf8D{5;w9u(1hb-6Js(vJekj{5y_S!ZQP z^Q&jc{nyjd(O1u_l5gLDSJK7%Np~|*ldrevoyanyp6A%xZ=figAeU1p0M| zq`gq7(f%ao-;qh6VN9#9Kg*EM#zi~h;hY$UK!bjcNi@#Z1`=kA5~M~4!V>1=5FPW& zGa{qb850nlK=XekCx{3KA3)Bj2{Dz}#rQ$^gLbwiQhR(Cb!B+~cO!;3K056aHeTz+ zPIWZOa^EH`bYJgGRM02XT%=DJ{oj;qV+G>-j#NZMgjcPDP(^xAFiHf(ev<{|bLbOT z9goOy%f(U|ZwiBtj3}1g#-U{UfKn%qraQzYMAzq25U`EwV9h3dCe_w8Bw} zzMo^}c+5K{akV)p8uK_s++(6ru7h(apapk0p~se4AN={;EAx{dS?EE8lz{vN!eem;tnX((;*(G; zikYOz6=D|S5ZsbWSjk}Ld{+fO&)lCd_7uz}(<>HX50Hzel`2{cfTXifol4z#*XSXl z@sKfBtRM>qljFmZn}Kvxl!m<6XWdRKFw@;V)+g+lgM6ypI< zUq9l!wjxMzm1+XgtD$6^VzRokj!%`h=C2e65A;oC9M+pwK4vq}Pr~CnOpY~7aQ=cqY192e_mwUg$KW)r zYu09ddEY9`^%?L-Ya1OKwGnjH(pJZ+4IRp#$G{d2u~u)n8x<(7&zv8zH=YuiyQ?xT zE!?+P2yhv8`^X|Leam{@nS2iH5nr+rPCUKqZEgv?W2eQI_?2fS4FuIxt zq$_QG%G9?u8)=ghTCUxs*Y_6*d$m@9bVf0E?ML6Un5P#^jW}uEKJzC%{Rok{$d_+F zAk}6Yv-o;lXf%H$zf^(9X=xu=gtMu*ME^;Q`?^RR_gtUmbtxnAmy`DU`BkG`he_mp z1BE8oTc^wFhSp<~!21yv59^T4w0Wfy*Qr}mD`aw}Q{$`V71LGQ%5&yZxB6W#rR^auI)AiYyrz5^gMCmdD*APdT#aNzGC6A$CKMF=C-28)*u0g)AJ1~0a*zo>@`^MuxjG8fW8%hs^{{EX|y0~+4- zw%5gR+eOIM%}m}+q}t5^+cb{Sc}`EocIQ0>*0syQwZlhq(c3+7N{wmU0hi7_D^3xW zo#O=81Mkmw1lKhL)_z;Ygcz1RA3TZZn>vVX>ldEb4whWd@M_tSmPMs4R=ANK@1 zzd;Om$|t@9Q|iy_G{gMV6TTEsPvpe=e3bK5h$`(E?)-2R0w?@^l>LP0-JHan?Bs-f zEH}kq7=8>2eSkK8s=7XGcOMX1T9!9{F3M86b%8ry0SbveTE;F&T3i1@3H{XmNHTrz*b<}$%EF+l;!1R?u=;{HDQ`Yh4#J_-1K5&IwV z?R`0z-YD&zs`h*%us;Ob2iPfoki7MS*nvdN^3hNZ>g-cyG<)ls52z6esd5UEjSNWH z3u>YMFzNS}@gIzt9aO;?u+Sg;!aJyFo@0AH;FQvDb>3qQF7zW_SOFefQ$ffS=f|u1 zpqia9ZT^spgpUUQkUhAFI%U3wDW4_ykjL9lV7(yK6NI`zj}59Y#tVdO?yxiEu*vwa z=Z6R^5np=|zw>;yb)=|ys(6i|$niu7jId~T!2oyRfEBQC1!3FvkW% z(F9Hgvh`tOc(Fit5gb-+jil&{y4&Xv z1{b#b3+JHrA`BOdUUy>Run+8u#!8GD;!*btilyKAY2UMtq)SA?OYpfT5l$0@P`3Av zOE9PO`R})XdXvb*5uHxQ0=W)G>z3%{6oV=r$z31oxu2L`FWRuL%o3Dbk4Nnamt2;Z z+#H{vU>x^19o>DKxbr4nM3vaiA2{rnN*@QT5{|B=OKrlZhLua)v`bwGPK~el&A!z} z$4_3AivW0~fGdpBUX)V@oKs_T5_kaVCwIxia;ca8sW%*%8F=X_Jw6ru$$15-ksQ@CGPq?zs0kVgv zI9K(PJA$&12{VhTQ>4-3NT;$m7P0{6X%q)(y!Yw%6lt(uQ$X_>^aTbDVcexns z7OeXz;G}#!EfrY5zxcPXF<8;=hH`N(@&zmk#lCucNVWw8J8{yK1^kv6D7qR&G~QNt z0?l7B#5H;Br37H=Q!FUk zE(pj>gtskm$`*-m)V;zk*6$WUb{Pqisny)QCzsn}F_(^kk@cF1yd zEU)m-MO&!Iy(#-wsIb1H`BkVSZY;w-1u$AHCHzteLLm$nuVCXZN2KL{unR1Mbb z0CIMy#>^;XObaGwsCr+hAPEcF{l5aJk#%Rlc0!cn; zKX~M65GiUe#5@!%+&Cc9U@g|~YkwgdD@l*0T^Rk%RI6aHcrw9yQO75_<`?WXZWO>R zLB#*VWAhXA9BT#(q*TY=LF0mo7-+LMjMg{`v+layCOo7cG__hY!RDZVF1+RTX$cg# z>L#9oE^gsGl0PU&uuf@51h2<-@!dR@C1mx49HHS3>U|li)W^8}D~NWHEjRIrSOCZeAOSGt;4obt#neh#|)X#Ft`2Tj(Y`DYW#e*0#|PcXrBjU>A1? zn3?bfs81bs8T!P zkd698;j`zuWbZ3DhkK0z2l2r=5Z!yIo4RnDdnk|xD(Y&ikq6}AJ3pxPnFsedZh{3X z^#zCx8SG$1gu+C>>SInCsA(M-PGT|&sj58aBU2k{@b4Y?>53U1N_!eI-AU!(u49+w{coyTSV}#3w2Y{!74lRE-?Nft$YC{DbpmC z*(ibAR~>OJdoj}S@Fx`UDI20lRJI1m+DREAyJN6U+QmUd$mE>^!P_hC8$zs}qRu12 zHYDcuTbQDTq&AoD7Ff0sro0(2K)n7-Omm`m<8SR+@UbppK!xK$lhzq2|Kcy)T1`l; zGfmBucZ7+B5J|0~{*5{P0%J%U$>Fa@g%78ezrl(J%?&S4&3+$zeljV{(9M9fxXdum zG1$nUyCB0@+j^Io{CePjKfb)UG8J*Y8kx2BWw0{>eN)PGWs!e7(Y)Q`a`6IUPRVbb zSd&u2d(rV=M@apM`117K@^CRrU26YJ{pC87AjtLR!57Qx0#o31q4_bQmGbNnb|B3J zap_B?@$;pnrKQ!)@2hQM;;~Nix5KORz^#hLwcnmrfFsM*NGp$@CcWKe1(BBkZEC#5 zQ^CyLsfQ~l7V8s7Uv+BhjUSZYB=8SHR&LMMPl4CySF#6{LFr#^+($2=JI$RJETSV# z_BXXaXp&zB&9I!T(XRrqmrP$Ht>J?vA)#*ZgKkN(re88`en8)3wcMa8-@j0;6&AWaE6dGU zq%B)l9C-Il2OfYSs-jx%j!XJR5PcU{S%x=BgKy~W*>D`lv=v4_g#4Sh06Jusa0$lM z5t8NT#{B+<7wT?H<_^5b8bairVaPty0q*Vv%0{E-F;$-TI?E%H#M(X^ei*DnGv*nU9`%4STRnzhY$d~2F*z}y;*2$@n#l67m`TN6BBa$2N{*}D`wcF?| zTI!9v@U@=z z$fK$0G$a50F43(*+dU`JP0`E9yuxkm==tc^i;=+Zd7yi}sizJN-_$pcA+MVwC)YM@ z&zH|zUPk9F=6S73ior(&*GtGZQDV1NPa#J5z+XW;1Bgnm8BR||W7PaWBL3I$uD7%( zS7__88Plr_XT6CoaNo@31RNKol2ZWH;xL2e8cXIG2a?fmSP|WlU=lqTGPy|q@89cS z9E4=&&lus#ZJjr1Si|kOn^fu+hnNa<&$d)?ou<^S#<-RPLtcOLAgFH2Xv*%)=*sQJ zZs($6<*#S%7?irY8K>@?iHe)>=l`k7UQZCo1aS%kQbc@8C_DTmziCd z(CpG&Qm02#(i2-;liHQok)M@b(OxkU)mt>&G#K1EZP_~AJ=wW1{%Uz(*0SMf(_*fE zfokSTZm#!y;b!Kd5Vv{=oD9qNIo_n&K!TgdX_WQ(^ATqnuFoVYmfXH<9#hDs;K{ua zTqdVSsk<5)`C^%xs@lfstl4Cxc8ejA8~>?Pso_$j1$JZkTDC-5uLqn`rAnLmuTWlf zIg9mNyEsIxRCFuN&d^U=Xzt54KZlLp*}>aYZnXwe=%5PMlJ5+r(tbF7eMx479!-FP z6*Og~H=QVe$%;f!b2Of-cJMmX6;A{xOFN`h8jt44!a|Q$ex%qn#uItnH;P0WV_#s58&iJ8ZrOo(ZRIN|= z;dG;{1QATD&IFNcr_BUWTrW=q(R{FMgfTy`TnJ-D$y*5HB-x({<7LIzh!PalT!<1? zOwtekHj-Qjr9g7%x3&K60eRRK{+=@qBM@gB4p`$6BeO=~FArwYw`JF{ZpHgNqU zFrS(T&d=gku{8?xCWnOqn0nB;2hsb4N1(&0g))T1MkYqaho%H2Wq7A~WV>eOTjyF9 zSrn9MmuOaMl-G(@t2YSOwNNz0#WuHg#v80yT_LYlyBci0lOhE!@k?FexL^5C2SCN zdV?gs@ZS^KOm7FVz^SEf`Cp)f-J0tt*^JW3@Y7 zAE_&v%Hs8d#TBbBp2-u5Bi9_QFPSTn$rH;EYbaePQ>ioE7;Pw9s?zBT#T9QXU#T;m zE7crptXONZ-W$yjZ>rpAbG|#>7;CE9>hcDI`zp~~z0((rLZLO@T(dV6O(32r(NcRb zmds$bIo?utG?gt7_EoaA{$x%M+f*i^wc%{3T5l{RWA@NMlo)O`r^L<+t8nk=5`P}x)ruCg@WP|}2P7kO(a^H3Hn+-M3*`SYrvg#Dj zo6Onqho7`80EX)W4&MU(;iDbFA`_Fo#Kp(x6D4OwrW)jCWEcA6JEco!7FAl8NYw~c zR5gm#1(ZoOGY4zZksgxqVP$dVYC*eR>1Fo{xYr;BP|sfogw(_ov+{3Gl{ZPZz1l9SFl< zFkSy(NDM{cy$Xclh}Pzh#QpDrgNZz{beYz~|1CIdMXgA0LjN-!2L2-+q{8acjnyK} zDJm@~r&hYxoh#4mKNvGQ1C11y{vUW?!xRY~B=r-mP*V@-&;HJ&)wOL+4C3urv|FD_ zCPGRITIVEL^=cmB$4jiWf=Azo1&fwHw92G zOf$}Mn$n^GJ{U7Q8_RSCV1F1hr#wa+Qb>);!bn_4p3 z+LfD{yDB^T6nX{~hezalD#k^?X6NP?7N=zkmj6>q*Y(Zq-G~2reEKk0Z|}c>05Dh_ zk?QOoKWG$kjp6E?z93`*v43x{lK%G@tU!rv{eN;U@*mCx;jgjAALk-B{>QoecjO98P2&*S=mVW)+O#7$wg)6)nidQ*^LeT@(<^-^jBT6DJBgh_VmI!5d*2gkR}9oIlIN7@0a*@Ikd?la|qQ z7`reC+0rZ%r*`UPz5k#&w~?GGY7BU;jo6(p*kA2E61lj0`YU`;ObHMI!o`CKqu|3L z;(24(LShrrv{I5o;?i?zl45f5ij6W0ODb>*Qi>|;P^+`+n;Xh9TRIxO5ga-y0APQp zmLmhB6Qh02aCE)X3z)NuE27J*8{F%gJ9OK-2jBJ&Pq2$so6AZ|JNpMhdxt-dPjt@C|7V)4`Tvt9 zkrV)op#SD4bwFeQvH;q@?MENsf1*CGd;gbOqzEfUMWvFo1`GV4KAS@Mf)Slj*;T33 zy@+QcW0}#s%(2Go9r)zEi)=R$I1oE|X{aKAqQd%{`Zxw?If22T!dRO{`bBH{BLHCa zlJR|s!lMi05|Xr13eo}%vvSJwqN=n_OFZho=MxqNbQ^`1!E^LF539F=db5w3O{)bb zs0}qW2Ows{cCySGZjZ%t?#5KjFD)PTO)bNpYn(RSOtSr2X}YU=f>%al0l;H?_(?uL zP$Y6r5fEhm}&kFyC^PT5!Dr5_}NC^UJGfIF@O36yk&`U^yNzE&; zk0?gS^3E^UhV!ecsjdInn1}>Z-2z|NrqPkz)zjNQpzht=+d84`pIkcAH>VwtyF9z9 z3A?m8zO59!>2q+X5PWiaKKTJ})sFx|`El!6@pa|B6eq2TS|=9dPxR0njr5uA9se&+ z0Hy(M04f05#~LU^kBFM#G9T@<{zifHOlL9OHA#qUZ82NwRS;u1$32ysTw}~aghts6 zrq+uNild7mH@G=@la=f{qkJv14cg3mU~6=&*{##-{vgF$0o=KvD9=Cr8w6iI1kwFX zkoJe5vJXK+uXA_-0ohA2JHcwiO{S+D4Otok%oba(>klaD5>Wck+Jf6Q3FlO@6B}`; z4Uz(iD-HJ)mP{*4PIHQ1`pW3a&M85cX@6tEimjcRd=*w4+iF;s^mLsYyfTZ%Y=b^(6c(uk zSp&dvK}<>1LQ7BG&?)_GbhwFjILxAS%e>kxvNFZxp3vQe<#5i+(ZYej&A`vqC&0!i z#GlI4BhWjFJvcrxg+)3vI)fZ8i775GoDcx^hw)!tTv1(7RZ|aE*HBFd0Q_aF&LA!y zDGJa(6k+tQV{OC1_y}e9gfsK6EhrNj)E|47B$RI}R@mbn(K0Wg(xI*TcViO4sdXnd z>(CY?RTtKn4wo-O<0&V`PJAPbvYsUxgLN&|v2c*45>A}TxM%8~OufBviAe*&0)j}$ z|025v#1#PY@dp40MHc)wmE{3k0AD~@K8pYGbm(6bCMfYHXZ}mVgw3Dwj-JwR7k{Gb zVNBXc;h8uCx-arA=te8trSqe*lM^w}7rgyU&M3a0KlRauhhynMxi#@2?@ zdEW(h<*!dkW{c2iFV9V;$>z&G(|)EhMJ-cy5l(!leL*wnDbeUlq*9MISgkaxxm_y> zH`mC9p9Z+YJzma1JVDpHn=R2uMY_LY4PpiW+J~+HBAM=%HCxt+3}%UKEes)}nODAu znl_A3bNNuYi`DE7or@ScZC^>&_%Bx0E#;>p)UmEyJFtcRvd>!q(Eu6%-iIy&uWLTG z!k#Ht=A*iZ!Ovw6xt5qy2Tv;WHe>cEr(eF${f8Xb)kkHYFuT;Rlhdg}CYI~aEhK|v z2;xf$Y-Pu3%+ny^N;D}~ u;&Zcxel3!eSw`n1%0KNjenEsah!Z#=&B=jTsMO1jS zUu;}rSW-%0LTYMyMp9OGTy9=WVRk|EU(mM?a0Sc&nEwOJcK`V%?!TRvgEfTjBQM7z zi09PO9njv>+ufGN&&xN+IV98}JOVy|I@;wUF^5mGeJoWfd{lIHXl_tCWoCX*iFcV- zAw_X!R!wRZd3|byM`j~gb8@R&k8=lUS7KjM@&L(D{D|YU!?;~b?QBZJJpN?PM(Eo5 z;#O(<4&MI3-q_K%6TjuU)eGFK@(2I>UuWGs>!rl8-FMkOdt**3W6X-X(CdTUPKfSP*G4(1f+;`QR%&x5JGQ(5JK<0mq_ou zN|h>25D@Fk{O+LRo0)g!eCPen`K|RW|HHN5e(ti%wXc0`Yr!NU>U4p;t*vmr1;wVx z=L#RcH3y^Pgi=J>!?;vfc&{~?D;pUfj%Twj8hYyWGVk&;aQ%m6xmu%M$#THxzwm0)CRu&@_`poWY8(&PjU&$fsOg`&aD;y_0GkCnRJ6h z!2!(u%MXr_|3|_oS{L=~0nAguClI9gfO@>kIA_A>1=Egi$cFLfNsU&guda?x^zQaP zww_+Je%45ffIyUam_wkm>*I)LQOAIOj6T{c(Jo0h*(pUYD;?vVrknF9<9U%~L2({k zSy{=`nhJQ`140Fe@d~P{UzK$Rb-(IGw5JV16hvW^$+4-~snIjg;LX*43cI)?*V@0OHdB(qcBT{?OE?r8tcgiFn#WeXQw4>KJrEiXeK-#h*f0)wp4 zx7|d8pN7FBM52%}u_0(ocv4WZMx1b(eqx4DR#xtX{G1fuf>Nt;BGBm`uZvX=S@GslHArF~OeF`wvOgr8ow06DHoZs(~QRj=Qdg;NCW6adI z75n-lzVTn{?xv&X(tJ?az8m4Ab75*@DVx2wVM+P*gpMq;7f`=Rr&zWBMhxVCM?mgg zt`N+dsD9(+iS+RcaY2PSMMQeUM8(C&MMq*oaLE`vGA%G8GZhn?NU}UUuuuGC-y_t& zi1Se3h1`d7tetzli}Tz$0z)X8x6LvV#d)6Y&Yl zgHQ2EgzF;AQgd=`()lg<@=8jz3*bqbWi_?eDl*mU8k^J%E}U~vZ0_m~Zx!^!^$ZO& zRs>ldgN;mekMYV;c1|zO^j)B)%v#!Lp5?Wmhef^H%b}qlA~|2zc1|(7mmg+1=K1Iy zPZuHB_k`DlqYU0Bp5dA;L^)NiC>G8&hfr5NdEs4HxNr?Ede!lk_$@AcxS$%pUVCV2 zdyJT3SBdhDaSxWowrYKxF5?zl?$lwH`$cd2(;1>{%}wdDhN(1oG+sKC^4&_*tk(Wj zLL_G_-7r={+DT+%sMOq}YWT<{%bv=kF0Y%ZpnUmSCxb7Fhs3tpU-caUayRW*gI4I& z_37gdMTXGiWdYQK8_LVwpb{~%^;zL5B3&}&l#bjL|n&#PTxMUE_2S*I?RIrn%A*O*kf zZWhgVJ9~JtyV}CN`~w($Yy(jtNb8Vr|4>Wrh*-xclbATH8OAsQ-O*bVi=Vo$N zZed=AZ+20+Z2rTtirNPywl#H)TveJ4P3^2S6hsN8KB#|axMP&_I>&2{wy_z8$oxj$nems{V#n@`lW$A-_fp7B?^w-7doxBmgg-1 zbbdtrnjt(${E>CLxhtye!JYIM+WFnDC?q1ERcq$hPkvGF?iY0Eron}7CReHD>&{(~ z8t&P=u`BK_>FWK`Q$t7exerpyPb5T`h=7oXJ_-no#N3ZVV}%p&@-bI&LMd6&X=&N{ zytx_hg3>cZ8D&*$6}akp=2|SF=|n?Zb31)&0MyX|?IV-J{UhTey^|b0(^GFw&9E=b zm4!1eEw9tBoLt-3*kpRYy}Zk~$MW@KB+2KBlcfUdauOV@%Ma`F_1~<^`sMWUr=6NI z?`i@NlyDkZ#p!3^5$8m^M+XP|dAyLT^j^b{6?C$NYc@jb7XyyR_XMWuKzedSA1?0d zW+(L`@NKi@!qWUyBV+A}QNEi%d{)*~i9F%F9$SlpXL7Zq zjO{xGUsU+XM31i6NmArzFXO76Wo<(?oV6LBxjFh6-J$i?cK0&~Km=(7BTdj@HzUHM zPQ*yX#bS;pD)>hFCnRChG@`RoJ#sU1aD_L~6c7bb?W?Y;zM-C`v8Co!YvVCkHw=M3 z)qiS;X?V16jDGO-@Z{9^?943l{Ocu#w+kz4jH?q1n{?X)@Au|5j+1=pKfEJN1hdvs;>I)g*wyIo8vf?;QZh zjY)+4q)PRS^{2Snz==)!RgA#>1t51O;$-d#U4d`40LeL&T_d_G2?88-~<1tTS zwG(j3npjzUddAgM!_3^gi`fGC#U-4D7NsD1FXykWC+NROd(~W8`;s04a%Xg%9W4WH z5Cu{0Y#c?aN=-{Gt3J4pt_mT@<>nVR;vrQ^gwy)FJy5G%Lr|)H{9R`|*8QVG8@U@q zr}4`@Pd2{GALvy?8qnU24C=Io0b+#)aY6j{v{KNDC%!dYPs!EkD9!1PXdYcdW&_%^ zZXQlWi6n>O^kZQNnvxeQ#oV-LVFxB1l?!c37e!-La>+De1~TtiJ$x~MFdfOi^C0Q= z^0Az8k8@XC10BmY4l>Np!>8Vs2^>Cw5E;-nE4Mmf#=iXYWR1DJ@DtZH((pS9DuW~- zCU6)pfH_#p`a^r}&2X$?mW=9JouE{ch_wI9cRh}-e$u)Hdlb|bt@qxCM~LcP?|pvB zLQzulpq1mIVR`SnrLWDJuha^Coi9G`BnVG(TeZ&EN+hn)^v1q)wsUoGchYC4AZpJA zL#WVDi0^a+4{4g&2THt}Pz33%;92<|^x)Xenf(7Rg2x1D!HFVxc#4$tbPD;599&v% zPL^CjVM#`jY*}ViN`*{KYRy49c%3vMIlrnALER$Nme)qtE7_maQFCRqc~oI?yy5cf z^!(_XvaamqHfq{oi3I}f!7cIas-``$PbFPrYst95(#@-~dIv0+7a|K#)RAO-%qG`Y9Or1*!sjMNG+y(fg3albq^> z#69m*N?J?esl38v+^U7VE_K_{Yt?E3VJ-9eCZ8|24xq?hQ0up=-x2PH{3>1-Io>CS z-(b8nvO{yS^1ZoP57YP}%PhusbaAZu(fZ3OWm7&|Aqal?%1y5T8(KX#m1jL-ng^4q`-4Nnej2=5XHV=U_og`S!H!mc}?X#ihDpX@Og7vOMB>#nn%X={^O=U(-wNLr)?mnFnxRG1; z=qUQ+G5IDvrC9hWS+$wxbc<@D!xJCEA}!8Mjg-@>2lFfrI)q&m8tt6*5+fGRB&B;> zW%q6Nb8lZ#ROT^RB_zMUtv>s%5m@GGHwq4v;eB6YQ&;A!IwUOpdgG&Q=T%de2jYp` z+`GSWUwNeQL`o$}nA`l#l_P2cqiJ7i-qqmGUCL%pZ_*TIU|zBvzaU1jamQ_Z7oSjK zRsB`L#zEHonYGs?A0L1IKu@5t8iYpqMTCV|LKH+DMl4Md9*;&K(*QT`=Ygk!1Lyu* zz=K9LD~~^@%-Za`$qctz7p`SBzXnXE=)r9U`YKEzC|fA=eMjZFTa(6GSZ8zH>mv2k{hd)%k>`riS$9_R7}ij-H~fklw+} ze(#~Nc!+|i5IHk3J3k8>|EUo9e^s{l`8a;^A3k=y5;;NgIM5IQ+#X`U-eO(*w`!W- zRJP9!(Gk|$h1Us5TW9&17%5or?{6{(H!TZSK9`~$(6`O1;VD-VyfYqT**(V+`Pn3; z-)d?$j%L*34ng6jUr^>H8W%fz2}&6+Zzagw&Q(wOIVCDENXt3ETlrB$pt4ay9CXA2 zhoVzYbD;~*vZ9NLMM=ZrG%OXVsh>Mh5Y;s6p@!yWM=lXDh7R`bp7t}nY=cAnqa4Gm zuURIi#>Qv+IH#ExnU>$SlU#!Ws2380PJ>U202h?CTFgwk?4tsgx^BQrV@A~Dtg4v~ z4Z(X>+x%0^*hPsMWqYz7e|SV+8^|)cLI*SPzhG-j)>LxeRovaQ8~>o*IJcu=PL@At z$^GD*UwA(Q58fqT^fzi6a|)tRs2}7X6a>Lg=0u@T4p?MNSad8#Gd>}S9g9mr;8T;* zGcZ}%F}ZmW1%+`X3B{o#3!Q~3p?A>V0Ce}sy!ONC|B<4py)ZGS`%3TT>E`gv%g@Qf z-wX1w3i1j>y9T2y!oBHYBBG+>ox`w^38vVjxHLFE#UvAsi_gw+%q)m0DmKh33$Lhr zT%D0tSFiVqHm|AqQ7fXo)2O?*&tM?4V@P|Xahy=vkUXV7@n%kUp>Sz=rfqcfz6(VV z_3npV91sU`8r!@LLZu_j+-UMwUX;H+yPs5Wn%bAfO&%#`#;&Nra9+D3qwr`e%AQWf zvxLKjGa>BEVv;J=6Ru8H(jwLt*r(~g*{6k(i2uCw{IiI)ul#z6<^;f=>+5%ZcYbN$ z>h1&g_I2}o>>uEQau3oEM%zb3hUrD4<597?2?01?EKq4o4^4fT>6Q!n^72C>oeGOe zODgTlwTm4=;rafnsOpBsyUl*BHSJoRoxOeCUEPD4{ljB-UXM;{Ot(U_x8|xB76r2y z;7spmmn&CqLKH-rz?Z$RzkS^mI(L}cc=oUtWj!0bQ1EoLFDsiw7ki;XbAXnBWuO1E zBdu`OQ<9gd96VCm&Ya;(k;*h&q>SbdAvg;Pp9zf>RU{2q#L0Rg-u*XV`@=cxL+3v1 zT9ymI_c>K@@prIpjAwMLoVoFaW9CK$yC;&sa$%fKh_Ckzt#X2Pg68`0@pIcubOb#h zmfJm7`~_}b@k1V31od$_X9n5rK?y4|gQF<$7d2 zz|Mf81!d~KzYz11i1}UbgzaM8j0zANy79uIAK-mixT5_b1Be(}EQjN5vzIbLBUNrb+aOc zOMiVUHkxoMcH=302Z?wgS-xel9%G7gF#?0ib()a(J3cG zcW)nW&j-GNLC^d(kmyi7)UB|nX!VF|F_;9oxQB_!c!4CPl#EP{G^4D%e8wE{f|63& zB8#%Btcptr%Ia5Pl?Zt4%ZBzC=zEq9D}NzQ(J^MicZPacY;^pM?gZEL%-q|13miw5 zF3qmIS6gGJeAlx5`TFi@s*hV=$bXwXbeSOQaoFYPH@!X!CNIt@ac=^CyI@cu}ey?C-0M|UrLbj@~rT?k#Xyn zD;}qG98dEMrk})IPB4|{9nMBTCV&;ncb5uEyEPVAYJRZL7)$!dQlJG;^Em-F+J8&> zYId#NY^~pdUaC*hrO-+L$4jp(*AG2d?JBvb*=t|dC_T}8Y+><*(9HWNdVwIqlR^sfy1{msNqi*eY|y0R$LeUT*sPI0ZuJMD@p;; zq8_3VC@Ab1B<(`pFrEA_bY=Ftxlt}-ac_p z!e;%o(#nlj`AV^>%|hMdmt@yusNSVIQ8G4azK^+b&P#1z@Hn-agJ$1w)HyQTtK6LU zU+UZ9&x_`?6p2%eX7%g!ourUZa?5v`Q~W8H?FmD|0{7*zJx~!qE;}G9nq)Dv;7Y!O zM8Hmc{cZz(YIjo`|HtH^KUwhUj7!{m&b7r@uN`|w7guisI8nPhfFcNm@^K9b_X~~) z4}BgT5)~g5Ym*q1knErIEESmYHEIH)%K?Kk-IyK6-KK(c6gCwFd_`!Z)|HcS1hw>A)aB z^!i=xu#(^`!IS(W&qJ|85DC#skNNQ~9ZB@n5BB3%Na)|6sIoxt|J?J_`6kMbfBnGX zZm;9&;^yfU5GX<6he8F1g!u;rgocMi$M`{!fpPJ!NjS%ZL@#_wCN3@AE<3&;CNCq! zuPD3(Xu8&fROOes)u9NsP2~+fEic*{JDhU6tb3CCQU`5@ohBm2EvMjbU^7FbbIS{h zv&-{q>!a^B&EIVAn0{FKc#Qhj-+q0xt#i8^5iDmy35yfYP{qX^0K_+E2-Hjh=><$D z53}JKg$5YqyuW?2OgR+JS(~IPZozfkKtOjjkf&IY1nE~Ln}_c0XWwPtZ;u&u*?z{M zd=Zx!w~qyB6h0i;^IsOU8mN1KF6lgGLBPG`HmJkorO;L-XXVsWX=SXxEazM~nzQB@ zImhPk^pWs@O!*{yxx4;_g;U7pNU-y52U&`mf)Y7ksYR!l=uuM6u^Rjh|2Hf2v{U5;bdu9bu&vywVE(W&3}p zyKjmh>h5Pcx_Qz=UcPibeqI63k%2Es{(dO<`>bRFe|{^o%}BVYFCsIKcePINV#+$x zzV5$ncisO?_x~=nABpb2HJ2p?QTHDMB_t(*5d^7`cVJec*?bf^`S95EyO|aRIeF!x za>bgZ=Afv>UsKz{NZrU=*}>7=+DG5sT{zU!KQ=JZ)!jSZIyf~_I5R%kxcqi;Y^7@B z-CF-5mc6mx(WobP$?J)+6*V)1;rZmZ#?wQzAQbYg|4cnEuWkKhTk{ zcbrR7;D{dzr=4-94HvL9?hf&i0sbF>HgM!nWa+$T9vfhfFP=;8k}r-uT|- zOxx}}>vPj*ndd@1XhB`uvb4g8Zb8GjVs*cpI zp4O(Op|R}t(ebg7zNzWH$v53I?TbCjwJRCW=GG?S;rkEocW7b6qRg)d7*y7H%(^?? z14YV_LOfB)0_(9+|ttL=-r?SA`?lf5-c{T>5t>&@7sC>&>Y>XJ5!k^+t7dYQI;r|I17ww4Av(yB-!dbvf8 zNoH12YFR~PE`c+@p}w@Gv8k=95Let|=F~aZ-EK9^22BXS6i+BlEpRPNbG|t}#WO4N z_Ue-07AZz9Mz#my4X za+Py`DD%Qw6;k(mK^^F?tA`3QcmanLxuE!XHe&oi8_S-`ND5LGgU#>WH*(J3Eyj0m z|8G>`N7R6rRe1nR>PUuKQf%(?T)^H;5?09_NE^w~@|kk1PZY3MJrmh$a=|e{vv}s_ zCFjJ5!A*^ty1GrohO5T~cTXRF_+{TfuYe$wUq~o_FkeKNJq)H4i-|g!5KCf0^vOO0 z_5=|Lbl8#>%&I*x*j4=P56DVj#w$y3r-i4lXE!!Gw>rIo6@UEOF}o``b#WCT#a7G? zW2##0@R(+-kA;uU^ad3dqIJP~)l8(=&U8@n`1$UqF9)QftdcX0FR~fCu(N^_2@H}B z4)&yl0Yo4ylph65NSr6hYHonlJlkIl{>S#fe19ZFz@Uy0YOMJ?-Z^rfw7lrBz<`10r@@_A6Wr6q8 z`c2T;)?Lfd$a{X5LIk<{rC| z#|PXQe?@iqaaajmeM4yzV-Y>cy3x>QNa}ClwL}gyPdzQ&RLh@8ede&&v-$O@gN+;Dps;wD zg1o}lUmxTZwy1j`uP}!X=h4oO%73sB&9p58c z@a^3%E=Lg5Tc7u+Qo@st6Fd&D94@dG#5D@joJzWWd<)lnZf^QkOJWU2{rPX#}{MHuzrg&gS(edsc8BcvI~ z1;3Q=`e#bHOqX<&QjCP`mD#cc>3bl;{h2Z}CnDDGJ)z5MPq-c(Cthy2IXA_3`TR^h z%Qx~<52Fh7sXY;_>Nzoj^DXYI3QK$rLem{lJH}c_2jNi?=5`W91FG=En{Kn!E)H(G zSC@DU9TA+RF^;22N~z;GQg1FfSg!5$`E`7CUkK;PKu>}BTMp*ZG05a!J{zj|-Ff>V zy3{n`b$++mf$&J3k{G+hxZ%YM%)ch)`8=1*jBE8|K(Km10Q>SmxYPO}ebwDULeB+; zg~3R!%0JY!`oQWm_aWo#Sx0~ep#0C%ix@i9*4)QiuWz7OVwc~9PfbuaRWv5fX?Dwg$H zr0{*XVQsJAF7ABAOWxS!{6&iC9W1~W2kRn4(Eej)#@PPrQ zJ9&0dX;DQ5tfaiMt}utZz7fhLC;1xUrWWiko1_@bEck;CkAR4D_?`WPdhgw)Kpe1V zHjee26q&n>;Nm047c|`la%`{T9$8JF2N&Nrf7#Tb+ch=b%E(E*wJF@r+(ozd>o-Yf zPYZV~T?wxMLmzRZSRh&(rRV1#8hs=DdZc(v;+42KEM62NmYkBwhD*DYmCursTTsGS zlvY}KtQ-TYs;`Nxqi&+6ZE0@rXh*bkclI@3Xs2oI?eCx;>l0~`riM>+#Dn2OC+g0x zu*$CquR!vF@88q!e*ElXk4?lk=wTw=1h!;;XB6gJ~r)HX@TVS&CALiuZ z3raPLa?7feDlDq&9gEc(V1yRoS~G+stx*TQjyDCEl#l*l z%FXjOHTF$;3m=nk!)Y}KNeQg-5+ARNcF-MTEr*SzG6liD>*@h+%f=4D$`g}fWf*c@ z6{DSR_*3(ZyU$&3+u6IDd&+xX@bwE6^hcWcqeBhDQRgG0Vgh2~9z`c&@8VGS6pTNN zPt{2(H86q)Mx03{kxg4(MPG}6Ai8?GS1qj#%w|pL3|-xQ+`aun#|MYUs>dgKCZ}J| zOpd-upI^W(Ek~}bBG)(EH@6(NNpWf%85`MAh!T7y^;RyCem;2d!+~kiMlLkCGSXy! zlg~blA|&ORPo!C{3q0AM%_Su(2&krF-+l>cO5C5#CCOpafz}A=BhKcU&KZ4tVueWm z;kSoBEGE)_etQtQ=iz& zIC*Spnho9}9+RG%_b^j4`*MD1nQCESd3B9$v3yl+LnFFAtEH*E<3wc(ytA*byG^8j zq;{}=bfRXwcyczssO1$O6)l);xUvF4Z?+!6c6JaVySvPv2?#3l%J<~S4tLp=ybc{< zntXOqE=l1$rSf6%^uwS>_dYx7=(alHvdxKc1&My{%R?08tZt(8?L~*$kLDb`Z>~(& zdi|&Zr4)43*ti>e#?qC0ApfjFlG3dhB^$ZZ$FRzH+oP)^w_Pb*I?6-}IjK0(0*b!#As<^2g0@)v$d$a;86;HnH4`&Wal|cuFra zki$;ToHli$CQSH2%;i}RmZmt-8!PtW)^7(@w8?B_OuhZ z55u4SZxo@InO!|>VV*wr)TiCq{C#!(sj1yV=+Kc-Q5;A_G$w{NBmtMmKz@mWIEgKb zFFP;W8v!d0J_nT`pcBP4wS`5Os?PAq!1vpOC_1{k`Ahp1dWKrNhKKqFCYr~3MyESo zPcDeR>0O>%ToYUAeAhO=z9YCbve&Y``<43>e0FR1{YkL~RyjLzD&AeazS#!9(@b;M z4;MZ@5U|IsJ?Vd8wk71amIOPcvW;ik3#RM5QVs&C9UlCRmClvt)5>E-mdBfXg_o-m zh8@3f9uk?jiH5>>b+RHn^V924D#Kf5S;N0H29;*&76;keXf1}Z&> zf;jXpKf9o~_zWxy;m!mB8cY=}ff*`iYpUepGfC@;?Cxsz8&K#?r5H}_ADoaGOB$Vy z-{0!E+2shp0ufn_0BsKMKAhj``Lw(D?d+%R<-HFlx#w7A4uY*-*Sk5>;CJ8+89e%E zvf>fyH<~r}7w{4&Hhp1xspCb4KA~?^v%Yb@pH&IxuC3)~q?_nMi)K$z#_o)(qdqY+ zPkws-+7sWu_v@;r$I5`NBEIG5nMl@Q#NBMu+R&GLm3fUS?jIy9)&&X;H)6XBqAXrJ zTAXi+{JM9Q1aLx-agbfuXMaTcTEBrpE?7VsBhevbyiB_D< zOLB_3Hg-eQw{F~i{uJMn)*q(n+f7@G&$FwhebUbRoZdx4c6@;2A zsH8lrLYyQvks}i$`y1}RIQW9Q`(H5j;|t=;S*Oy^5rhRnj{|%}BX!l~O=98Powy)cas(a4_wqDN%Q0Won^$%& ze$3kxUgLIlbMSJKaM!gD)b>>I57G1UMujT{E1`o_qc6w0s$gUjeUM>s5$REB*qF%6 zIE}pIM^{TrApn_iiF1|Jm%{WLn)C@*TM+Gt>TZdK*8cK=q2boLk+QLIPzvvyels|? zu-FBrC9aN7%x$b~)o)Jkyx;pU`Dt&hj${v_APzEiG9oSU_nS3;s%3lr;e8UnlTT*| z-v~)J-=1XhtJ$9nd8rv6@k;^|mN*%*^iJ-Tt!Mqf`TFBkt@Cchwf4|F-@fe+G{aCpKe2OYoK0P@#JLh7i1uiSM zxP&eLPN6JRT2p(Xyu7-uv6fH?Z)obsZK-VU?8A2#_V$lN4B~+90SEPi@z{x}g;O)y zZ~W#L*IA&=wPWoQFwjN}YuNhw?Hj^ygPb?ul3xH)^44)QKKBJxI<7GMpF$EaeGaLNv9$!Y1Q67@53a*t)D<`rcWm=>4gN@Xg_9pkHP zYKrRO2vP`0LZDNi9o7qL7`We0+l%M}-0-#(S&G3oI_+GrX_?u%)!Pf4OUqI#Ydh*2 z9GhFfRA1R+|FjHDwSA-RVfSfD+J_YfPV@M{IaEB3-$-uer)QJ{Ih#^TFv~TC=}+86 z3r9gL_gXHq$Os-KU=ZfcQ@nI2?&5P(LT2$YUm%;y9zAp?qyNYu_XE-$C7xwzst4o} zzTlXIE^1|(HtSihrIF-XsgM|%!amFqNeup6IM%ww-?F{szxz~(_{Iozn|eJA=IQS& zI$!+$R+0_598YC%jiKZ!!@`lwCo%B}!C-bO)1TJFPPPhAnZINi zsFV?miDT4vgpN_L?>}xEAsy#>{vri&oU6BoZ-9^6a|+NV5*ikU3XckhA)iG?C%`d@ zQL%AWNw|pgXncxAT4qRIes+#oVP;u+ammvPTy0`?Zhm-u!YlLU==P}A(#DKlbhl|| z6F~M&hWkdxUyl~d!l$21gf5LO7`}ZoyK1zKo!eZSd%tV&{^KY8FFW7#zEx6uQq;TT zc^~4&pp}We|Hrlcx!+$_@H;#Xu@zq6z@XTV$T=?fD=sLpk;YhJz@kM#MAZ97Wxrhl!~BdZmcPe>&~^(t|Ryq;h=n@+AsAic7@G+$$v*65uh&s5qG@lI7Tg<$N#bI{)GKIf>PoMw7VS+llMtWlz2|%&YosTfCMi&XCp+ z+?`)RmQVJTe&dc-dj0%_kDAvo12ooER5pEkjM7r51#dH&<6Bhu&N%+dRoJ4n#Pq2- zuQDD4j2LZs@yJ4e=81YB%i;k>4D+~ys~8^@gNb}VvY^Lgf@BsD8@L561wUC@5tKv( zKioghTr$g&zjMoc#xQtOD($1(^m&kq%e#Akyy{|jPX?VelKKSjY}K_k^^;l0RC^pd z^$ORJOGOi}(O-6b4c2Tw*LeGVoN#pFa5M2X^6+H!H4J(ha3)wcR6oSo)-w7*WK^ti z!u@#8a2@PDoL4Fw|13Q)Gdl@Ep37WdmsxVEEUTijG(Qtoce1*=v5A1C03uJR#a$CTzO`RB`LNj@zF5+tkto3^pjGqf2tdZ z({up>TF6D=(DRD*Cj%!M1)vyhkJTZdUG>OCg2U8b z?O~%k^;+|*dqr}jm5@G26<}_}B0=3gL{WhPbWH_r6em>#w_{pPMcGPY*9(h@#@w~f z?*?mU)Xz*F2og)V<-j52(fj&>gb{i2O@4gG0(-u;)h($JA;P`w8?_hlnZ{)|@| zE;&!LY&^#w4KqL&Mx7X)tK*7GR1q)`307Cr)>NH>8X#6!9ip+lqm%VSQ}?l!zGJ9sgd#RdpY|*UhlylwbiLi&qYUpT*(%jm=R&rfJDfQgjU~D_Aw*EoBl|+ zz}@cYqx8+vnws;w0P?({GdfEDDA?{n%l$iAxdAJeG=IYh>%HHdBeVZR=I#MV2Chyp zCpXU^51;)3;b^b$sOS*)n0O4y8db?u0R@K$qDAco2OF!@Kae4H3jB9OB-y66p-gpI zsHYqX*tFxQ@(jVKAt(+r`cbn+MsjS3474~~eAj*5wA#v~?SarAM?i7Bb^=^3%v zARrCPFGwnmDJo?sN0BV`F_|JTGJIgE|KbZ_JJ0?s6Q&VBf!Ct5F?SQu_&b3{PY%4q z*3&itcZ9GMXLptKej1sF=k2?WhL@tEK2I8Xjau?!CNq}qJhw}%mHk*rj-ZsWf2Qwi z;eX#v+m70s2Wb@;6k+p>8oa4{d||p+zbNd5Bli=dj52Wnu164$Gw|6Z=5d&GpW^BW zW{xHzAmN0 zvErMmY9uxciDm_5GG=KTc^vZ^$rTRvEG1>4S3-}0n>z(|xZJu{KD+k#Z0)PBtbd^L zdKq=>N9xy?yG8OwlIp&kNrZ`o{bG>oH-Ex_{XyVjznGc~{T&?!Zs(&l5ANNIH*}_& z#}@NxNYPU3I<{EW&sS7dNZB;*sKZ~n*uC)Z@^%w9bLMh=>L?P7(v$QHk1#P+^*^I~ zOFkMXs$w-1J!sfy5fB(%f9f18r-V4Vz66n@Rd=qawjMCivuj$~JL(!b_ea+QCVHpk zNMCn9$!+#hftaR8~B5!$z6PGgXC6K(Z;~b5UCtn#*!z z2q&y?11stGtwu1y zZR94j9~b+8xY(B#3WnUIDBvIliHZt~j*AXK%f`mz;7Q4G35n7vsWI8WdPrvFh8Gp* z7l@bUR%Mr0T&hWZm0VXZ+K6k*Ymw-P>%jog!|1-K=79?%krNSP;y)qiSDT6o| zVyv4A=e@3;5Ej>9R^EQxP7iyaCne5q|K+Sb7NKUaZiIIcXc$b@+~V z-yzvcoaa%Hz+I!@{7$Qy#=Z>$l%_U zl+6ol8)prF335-&x@T}OAr~(=9!{Ps$*=B&PpeQcxns^LTq7fFUuGE=dEMqKPh$1# zUg1NFmYt98k6k@(Iv820_=>x|bO}KEpw+#Cz10IFLZeh;LgEzz6EwpxDT=YtX_u3A zv+m|en$Y439vE}uvDu|Mv?eeD!P>f_u?4~Xs<~AK2KDy!58UZ&>lz)CE+QfzGp}do zXou%VmflV+&abV!>)u>`zazadySKaYY5MEu_4mJin+gZ=pFcYw{^4;V!Csu(-;1m* z4`6@n=7O=Ts>B!|%49|Q323GZ62Pvv>>Y;8QFAf}^N%x=xnvut^E~Gay2{;%vscmY zlON_a`t2~ndSg}8g9>grGO8p+fBI!1vuVBJHro_UYe=<_GpE7}o=48qUT$W-mM(!; z+;#1^z3<-RqRO?EIV}h2rw^vI=4|U43y80oWfR zU<(LT4NW8_rw_6wd%Mpd{+EN=w=I=F_}?Q`z(MUZfI>P+89=TFfo+jEa5I0@hhhto zsMn)008gUZt5{q5aP>@FDF&0+Ik8nU?Yf-*-qAxJ&~Tr)dj_aNzD6&D4g3ScmB^{l zAu$p0%2ct=SYL3GQq)I)7EChwMQXmZ0TpeOE6y8VP$g_gPMesN8(Q5YYLrfkd|qDG z+;jd(F@oUM0I%#FXE&!k(&0BU_IjShjCx=Q^=4uHbmtTl{bFt7!{g`6^&wqJd%rPu zo9N6vxi(qv=)En?HtRlH?RAt(#8gg>oXpRS{i?aovO9z{;Sss~P>!f;dFD0-B7_CC zMW49WK$JN>8O?4D2(6dT_F~zb$)}Ey+=(s7j!b5szXjSM#9vj2tyz@M+~M|B1u{7j zDg2UkhJ5jB{EeRsdOsvC3F>B_6(Q4A)ZBi-eC|e*;qBcNO~%1{qS{>=dGI{zH<9km zGB%%`HJ!#a?HGQGxUq8Gi4Hr&`dJaML=221?wUw?ihDox4Gt89!Xv_IA)Cm!C|C?4 zNDe~8`vMF()i+5jnmU#{rC6mcTbC;pW1{K-So>#1XJ zK<|Nvd@}cy4tAa7Pg;W=72c2RfHDLRIC?YU(TnZZ+x_!Qlrqh`2-~abFA`SQ&n-&P z3chuMJG3$-#pH9<#uB?=DG&yKRD}mKH##}b1G_nv{;z%8ET}gP;63|pf@5)G#O>g@f4qF z8Bak&X&Nn+9vupD4l0_2 zP!F@@JWimd#eOK>0jri@g|HK*F5;l{O{kEpuByG5%5fyV{Z4CsuNYL!-hC>ouRnQE zvYtFPoty?cIh6yam>qdVK7Mf-H?91%9(u!dgpvwIgMcmEQaQ8|O+iLQfB40*zJ?&b zqb%Ac6$L<%q>B47Q3sbL1V>Jq39^wP$@KU0qt>4u(Y2EkWvDD*5{KfQ7i#3|Ejih% zmbY1X5}?C3w_($!ZKD?g_-U|xZ^D%0HH`Xm$_#5?*N75q`DtO*k9LPuEwQgOKOr~r z!iVligMMhOKW4bUn!q2Vr(y3qn*vG?Nz6B3hrQ}8L+ zv>VCE**R7z`Gtmg8KAGdJge#!`4#Ho1Zs*p3-FQTZpiF6L+OBRoSS7MCLe;7&ry_5r%YyXV@G=T&x|8 zQad}h>~6l94mCt|oRS8kSz6wFx$>$#HBH@d@`rbuS_WC$Zp79eI!)Z{3 zIGl=-^5pRl`6~hM#3}g;4)>9hk#U?lv-b7^s}lN%kc84%#mUy_nYi|QXs>-GY;7p8 z*d*4L4b3E)HKZ_j=|kD!1~PXfTvXQ_yF@WWhbu!42z&%K zi_;(my~@r_5`FzcAo34C#(|spH$^NoP!{3^{~$`meTx~B7x_cLiim-Jhlqdp{qr`G zN$N2ibI406YWEEWFv1zCO!$VJ^EuZi=89_g3RE!cc=rEeoKyk+ASDE9|CAhC?OcD- z+55{Mlu}V9xqWD$M8^jm2HL1e#DyNXxYo_}PVb(}eFqZJ?+9uUm|U27dmS zM5P4{S%Wrc@;{V%iMR1z2WvA%)I|i^CFT2s{fP=JvF7*W6)_cO0-*5=6;b(YkcvA3 z`t5%&75{(bV6_?K{;H~+N<7$YdCz~E3b1qC3oGaJA58^tL}&ajOa=I<-s%RC+TB!e za%9k9@FXdL-R1b#N&kc0{D&W>0(11^*Bosl{WT>2@jv_hKbQH}-~aPJ{;S_F`Tqd} C4=G6i literal 0 HcmV?d00001 diff --git a/doc/iterators/circle_iterator_preview.gif b/doc/iterators/circle_iterator_preview.gif new file mode 100644 index 0000000000000000000000000000000000000000..0b447d2c6cff19865afbcdd3b715f855d82a229c GIT binary patch literal 20228 zcmb@u1yodT`!+hnAPgZRH8b?k-5t^;ph!pwLrQlH-Q5hGLwC1?bSWjEAR;J&C<@q^ zd>i})@3+qTU*9?B6W0>Pz4v|H@jTCU$3|UKO;XCL1=Io>X9U^%c^6ldv$3&JQBf(r zk~6+zt94Uvc41yhR(1lP%-Y-CEi};9&Mr1Bh0~w?HVL$|uUAQ3EkRa+o}L~d0O#Z5 z6BQG)^Yyyp?}PGibwK-)k&#)rIa|8B2nq_Go}MzF66>lO=qoGUP!;AE#KQrBK)^@F zIyab9tbDA1e`T+tJ*;e;?R=Q5?d~|b$sv#W?;)8SZRL=+#B>C8Je2Jm95n*H?DPY5 z4Qv9PZKQ0GSLK;x(b8yF4_7-MD<-t7i<`GJS`KMt>uzl)4Saw0u>g|k{1P8$Ii%v* ze=wcNRCf2WV-n*R;jpxd}``onq7w`Y$gS`y`JnRH++IhSCdfC_km$RIS@{m^cva|AW z_cCyIclq0jHyqr3+`S##J(!gB#hEyDtZW?J&OYEeze7hyTGP$j$I8vdPE$n=2|R<} z(a}~~R7z4(O+-jiTvS9{NJv#wN>No@QczV~L`X?YNJ?1o?|W6;ZG2tr+S^X;u?n@=~Mtgk(Ow7RnVaA|R2e(u5j*_r97$%*l?(UIYMLxThTcl&yKy1P0% z+S^)NnwuIM>g#H2s;eq1%FD2&CB;RB1^IcoIoVm5%#8H3)Rg3;#Dw^`*qG?3$cXT; z(2(GuzyP$rpRbR%m#2rjo2!enlcU2OdplbjYb%tc#cgvlQxoG`MurCZH}!5@*VWO! zrlqN&uBNJ@tfZ)LRbEb3Mp{ZzLR?H#L|8~rfS-?-hntI&gPo0)1135rFaWaDnZC`5QhMAH)da1$GKxi)sOZz^7P_R9nXqhx%rh zgCP&z1s~Tfbn{X0(djVOLxUHQHeKm8<04(USnH$JWZJUU=y(5J;60R;oi=~r!hUDq zoLm3aF*@i@?Z(l`KqirngC1T3AVGPypZ71ENQ-w7g!lSqKm4-dl;bR+b1uzMqPG&B<7$xbHwV@+?%(PE1%v^Li*zgkLZ^^&AgQo`QmOeZ1?zq zt8#U?dA}?DkX&btf0wDJbI< zN+>O6w0hfKJPi@kWFC9v_G0|^!1p{-pIC2XufZN-YSVXDawVC+G)lSF%q4LViOU)J zJW)q6f2H3U?uPYuyI@9kJxJZ+dOUD!^UP@YpLGX*lP>&`>q_7e{Ytoj@N26ziStIa zvpLMfwma#Bojw7Z|H?j1-qIMP;KR05;T+%>J@N^6rR8czP80K|S8Jt0YhRKJdn%s} zD(3zU{w@-}T@e?=KNRepqEf4$#P0h2tLy3<9hduLQP2MRa9fmGli5#)l}&;D*uh`f zpY5mCZ%Mo>QY*hdLH=r!xJO{4KN0+B3l+-chZE*%r+_*&%jP=Ci%4dxWsEw}VYdoD zv3q10B9g9>e*H5HOr-#0!(Ub^lQf``H@54zAwg@ZVskwy@e(E&Z=AN@~qF^RLgFAzhdmLV@D-GW%8#L1VY+jA?Xt_b@K$ij#8_v9T9U*#wD= z)1|7IdQc4}RoYQx^d^xqvZ!-*ras%C+^qBA{4CLFSA%pAU00*=eb?p{-GjFskJTC! z@b{}}75O>|KqENEqr@WvpN43Ua6S?&4&#p1K7Ql5Xl>@!^Yo2cK?gDCkI@is9Ld~p z*KeDV+!|H@eV=Uv&02Na8L2K)iinkUrao05i2S{_ zR}Se%Rb4f=&tF;;rqWr>RIy|uH3P#ypK+lit%|d2MG3wI%Y?HdxQ8z`6fSY$>2j=l zJmKIFb!36~Je(RR&NdWfwiw1e5+@&-q9xg0I8D4Ip}B%ByaaLwp}tCgNp?T{=>5`J z_wdV79uK_(-VwnK&^}Wdng46=OvAYu$Z;s>AadxC<+@$ZaO>@CMHkPp)mz$+C#G#( z9&ZY&HMo z?9p&7)=hF7hgfnEmq7v4!wqe9GE9%eqj-F;(U)nr&CMA9?be8Cw&3^Oc*bf(PF<`X zm&T?*%;XaTV#d#jRFgLhF1<*5gBvcX!5l{+-f2bVh*qX9fZzp2SmGc+Enq?|0}&s} z2JHzU3ZvJae&y;W(d^U=oBY?CB;gdyf*q&wt}#B+-)K!0Iw!hxViIs9;g_DEsVj{= zO^j8{4EB531ZGK7HhIF|AZ~zA`AauYA0QfQoKmEeAkdK)lCjKxDrOhzfO%_u$Q{>j zR|~P!|G3Qjv2t4Mur0$UibdrqtY1xNH>>N~2F+6M_%54nmP0ZjGHIMbZSn)WaO`nd zNnF}~8!FJKA=#WDTJA_SIVcSJ5{Gad=Dy(>6h0#7kbIv%A7l|x^qBV)*J5nV!4(x%k~*qZN$+|+@R0~TnP3~v1C2BS zWC5=2Z}t2qn7pws6>Z~`C=0HRXI~gZbKQgql~gD4?G|qt*dY(A!0}VD+>YJXytpvw zA8q!MamcWfcGr99O1N-Lv~G`H@iURV{iAw@L~Hgi+f-$jJ%ySIjLxP-brmHIv|S6# z`kd^f+Q6^_Nk)yXG&Qf-q7w2~`%DjQPwrM3OlDmhws3=oeXc?YnWUIXx8)gRml!V0 zu61_5ON%kwZf3GpVJ!mAmZ$rm zX(x0~mS5>`Tz@^=KPh9Hx^QXYIR2fq{aYLO#z{a|C2@p~M>pHmz8MERVI{iv&+bt6 zbp=&58q?TF7ilz4xoLZDDg`~bR^FGIaaZ`ZG3WpXc>P_y8K!l$5qGWD@b-a;yGL{xx&`zFI-%cJ z0p*SULd?ZHu10tT7mUKEEaM~MmhXpd*{hKDktT!|YdwA5oK?dVGw$6oy7`9xD<$LZ zLp(HgQH=hbi=&H-j}JUOtHRmt$LtG>OzQhZx0kQew7Qgz__h(|+6gwxX+LiFYoN}3 zmnRZ*eC0Cr3kG#MeBSUQ+ymN|9yyW{&uBNON~w4J84f0GoK1Fqd2JcXKORC1?ZnCK z?s+N~_16;|n;UV6OK_0>OjM7r zc;&ND_Smzmtyp{}k&@EmD|PS3S%-C!dULHgl#gmSZbB2)_6I3*LHp0RmJ;=+N1@)9 zs+*UO^zOQkf^f;#S2RJz?`%JbYv70PNhNa4IS*BAmh1^y>;ybV4~h19>AVuV_h#Pv z_opc-IR{qH?-{ctB}34;K)2Fwa|?;`HsQlrMR1jAZXjYMlqDAA$n8PvE~92{&!`9#FGDe4pFZ*{opV^jDrC)bURieI()%hm)7*-j0SdxNeD^Bq?tZ+f zaZ3Aif`ud-k~x%gG3A9}u*oZ$1qq>W>-YyN!B!uFE7roPyhF0vbnxpOW32t2Wa+*? z5&h)g_0>D@E>2Jdj*EsUPepYAML-~YoBx2^1?K3~Uyajx%Sl5tgmlfRG1qx0Hjp*J zdCV_kFfOoCFKA-Yx%~s;R9GLWhm+~Anu}F>nuE^9RVe|vbE(lJdB9%B5-GoiyrxdM zLFBGm=gLate!5fb+Ac^kvq)&tm(@vr^SGK=E&+6UE0hh#LGnaDI-1<_CTlrocHdgE zkde)iLvGSXpU*frW%in~)tu9uUaqg%TB&lYPOQTXa*h0Qlk#)d_vyxsy$q{!Fw;hE zQqa8$j##dg1xfqFnMgwQ{HB+2LoE4j1bK&&q^D|md)Tb!mGLFE^M-SqiJ;3rgY(-d^b`%55(q0foe^=WBk==Qp-jyqQp$AK@Tn z?L<*@ADirLgEScd;kSZzr4SvNC2#6V-hT}bQY*fv|H>oMv_vsjoF2l|?A;o}hd zD_hYCZE^Z*l@DJ5)TM_dEWkn%K?JQ9F7cK~6$@~5oFAtGrIzBnRq2To?xb;X_B!Q* zJXX3JSdws+as}er(OUE3k_WoL1Hu`I?iNHFt^4oiKz1h~&BJIFBBkS4oJl7M{X3`#)6|7! zn2p}G;3zmnCTW_Ltv8O9Q3qAXM>)FOmReB>nY-z?xj|$^N!m}UAH%42P9%cwYIZt? zX*^CIn$BC>uVy)pBZ+H$2l2VxR&bftCqBT(_{}X7hYGdCHjCLduliQqSsg#8)P(p{ zA&E9ZAaWeM9<%~B+S+Nlr9EMdNwTtdZsw_mufY9^4= zV?UU7WtO&Pwpl>aH7STWvA@oGSK#yPn;TuX6Wngm=41=zXj-+3pq1c6^+Jv=ObISu z^&3RLS-fF(LC!d_&1CL;;1#NK1{pZB6J?Gi_DVQr?7tSM|I!U4+?HAuUmV1Wa?)hL zFqat#YNPZ_aX+G)j+vg0S&8XyJ_=Hm*C7`>BJy%-HRC~^t}-V%?8Nq0f;z`5B)y%A zStrB3Z)3;>15l9uVa=MSOk|gaVJ|e>L<{?m91FF1N>dZs!X(o^f6SdqidtFhQ?82a zEu?@RNDP@(_Q9>Gn1aV;^4t1bS(W;?WW1j@P%W7a-FY-LEJJWLe{fQ!v<}XCI_&}4 zUL4Srxkr#p_Asga73~#-Ssz_}sdqfzOI1s|{e;Gk*bjCVRI?TovRLSoQtG>L0kBc` z>9~FrPV@bH^t5?5_1u|%c(DXkDJ6Cc_K&757ReoVkB3f!yxkQ;cxJ2Q&|%i=0HQ^i9VSz zE#gjz#PJhy98JjNW!_2NBGE1%l3vaZqsB>R>B((Ed9Rey#xscXb6uNy{b^6ZY-Lek ze_+tNjKJZMh6b;o!HoKdpTi#N%~`GJx*N^#R@o%Iru^-uq;Sa7S;ELm=x7eez+1G% zw+D$et}qV}IQ@Q3gIw&}isXV|(>r22lFaKLYe`>B=LDv|dK-d&P2%IjT(Uc3?L6(- zn0kNdNHvZz6?1R5x8qiN*9=*$f0|FZ?U0Z?N>zT%{k4%l;g z?z(N{`ou^%2**zcQ$;?Ko?iYn98=g! zGl(BX_Ym7w_3r}+iBE0l(Twg&MEHxDz9UP-Jq=h2$7*{UsQ1LW>IbG zY;CMqOI*?8bjXal?|e<+e4f+HK^)xo_Q3Jmp%2ONCB8L5_5ERQ20{iFr#>zB6H;4|`JDySg?mZC@6Av*8_#I+2vP`I&_Hk-p%_Q{Cw5Z>FB&4J}p9 z9-zW2mhh6{t2eImmVGPX}vySUf8Zwd*yjfkt%)_w6nzD3QBIQ+iWJ$r9;<)~Hnk+&|lE~-UuabN6B^x-U z5Ag&#I7CQd^pk#$@<2{a6ThR#+$EE7p5CrE16`eb_xs5^tZ+1*$oGfu*C%{`#q0;KxHH$=5xD z)LYb)m=N@sNvT!qe-h7L@!h|RW}~3x%~Wo&FO=+ z&<}wkHQbi+-ms%9t`!58hW>o-;ujpY9t1~(z6*Xf9UHd4J!Fs(R+ql8uRrmOy3dK$ zrwkVTh4rPSzk`#zj)lXZGiC5^$28~QExxWVU*&C-Ne|7)pPAo#v3+_EgiG_t&aN)s zu7=BzBa^GZK9RbxW8I3zV#{2bYB;z3mr*Af=vW`dUBcDnG_2dST(bnm6g4dPVBoC=bn7m-5);O4ba7qOU@@l^1Y7`k?py=y|)z>R@n*zlShM6x^>*YbTAYqUdP_4ha zeO|5K_2Q!EaC-7M8OLeMAsUuM_$vZcp*IHi99K}bQD7n{bntm7WqO^4*nm4-izlxE z-TB#XkoFiIEMBqv{Bze_NW<=sp(6JgdBb0$UHWnHe%K&8z3s-~CU@+WSJn2Sh z`9+0ArP#9aipr|$n%cVhhQ_Amme#iRj?S*`p5DH@{R4wT_l8GC$Hpfnr>19S??0HE zUszmvxV*CZ=<(Y6lZ~gF&$hOozu39Y-*u^n`QPTlnK}yR>P-Dn$3dFlr58@c2Yx5l zEt_S0S^R_ug0XN;2aoAWhgL^va0a0b%?ejb_ssY@ol7Z{+AsN`mjvEO0EJ%q7ORNF zp!o2%M;|7%d*`F}9ZPd4O_&EE19cKLAv7_W0W2D4ix8&C2NCDxL$b2}FR1f!ckk8y z>o*5)-yI$uOMu6&j{R@Csh{h1`j>9?<%m7&@a}mZ9a_C+TEC->{8@WRN>u2yZ5@=5 z7dcVk^}W!AJ9%$3y)4ib_l4SUc<@3;D|%qmT=*DW<9UKFOy8-+N6l$O2aW{GB1xkn z0y&}7DJcw4ZU`LD8bMCuObZoGWT(MmA;p|PRgIdQ6t~72N>gIsp-fCpK#Lcw($c06 z2UFpY*7Ow&4C<4USWh@lO>0s+;~C9|Eo$OD*}$dR*dVA}laGi3(?j+m5ulx`FpMXh z2KK?@#o@Q_KYsrDeG0;Z&}p<{N1_NRxXq_q%f{l!S+t5Y+R7)AU?NUWr`sx~(wLOh zvXJeSGZ;>NwtDlK_Nx22f;O{7njO`1g_7QHp3ZdCER-rlLFi2*@g}8V%Ks7M^q{LC zOCZRr{I}lwJG^*bzAF9FBOxtj8&L67{5#H{}?*9 zaY$2?t^2qTC+=-`K;DBHHq(~dknjlk5J`A!93(n1DLExIEj=R>la-y5o0nfuSX5l{ z|2D{nz?I}x|Kan$kq`ZYeEkCQw&7E*B$S2T`}Rei`Wv01L9ctI)*hkeL-$^I!$JiNjqn&KVojp>A>g!hn)Gx?GCvHS zUw|km0OiQgVE5;X;!@wZ9^WRY)%THg?f-e&ft zKa%CrE{yOHgyP51MpaJ*>i|1W7F#v~G{@_N+jz4)=1V#hT%7P%Wv(wVGt^e=rIA&=HT!7TAVDrROq zh`_Fg8zio15no&RUP3Tl#fJRxKwc3v@mrhV!Ca113o$-kL<9vxWQ3|Or+^q8jhG;B z0u4781d+wXdqKVeh!rFUA_wGK|82EQv#ueJMu?Z|y-!U?*7K)5spJ~wR)RFTo|+FS z@o#9LB2m;-v2)c+ix7UJZ8lnC2Qw?CZY%lzhgUVeCdVFC`n=m{zP}d|EKWxd9RrS# zfg~m&gz4iMFNjqKaf7aaAb?nn?XNnvT&cUZA(3pAnC%hFNXl6C!C2=J6vXqDmN4}0 zv|YR?QbNoAeS9(`UgnOk)X0ZmvkWV3amv}9Lc$7%9vno^k1-;ge1)dM+OSLEan3Lg~fMT12FvZ3d)l>vjXa^<{aGNO_u%8`N3in^frUk2c(56q!x zl2PFURvtDgds!1Ztc1H_?uzAxHv577G48n?Ck~VjqT5Ak&hi&@IvW(g0lq+BylooX ze{CoQ$g=??g1~Km$3-(QaSEcf6Br=qW`mUq5yivZGX?G(82)FqFf;nW2~ZdfXv=7QtR97 z72HPS1mix_;h>|WRCpdcErN_vVxP}XJ}j8xb}xTQDO{p4q5Q>wJV&U{dd5Ko!uk_0 zenY5cSzv+j-H+g~fD3|j0YS{?g3#MviLAdF+G|$78Z$5PeKtj(!-q@B1 zVU^0_bPQ11Fp57wylCD0%Cy~ErbF>ejpHc{q`<6)*8Y$)V1L|agLEC`67W)F;x6%+ zxPlWWmp%F-O0SaoFw?piY4_&jp zOtW|R<@uiHP>Go2V+U6D-0|uosZW}|27B8l$>^ai2(BJZE)`-)b;RCTG;u|BMRWZq z@A|L#)0baE{4Sb2@gG6@fNyscLYLzSU6Ks=l2GNXo4qMpqn}Cd7Nc4>2tjnHB@Iek z>Dd=Iz9&Np`(AP6nSGJZ$-VQoPG#EWV_f%*bV}kajWV2g(Hh^->*epig$7-)rW7E@ z35X&Pc>kZ3;Nq-gSq%!`dxma4$bkk!qde4k5uTV4_8V)G(2@!t?qY3mT#a3LRp34T zhGo$6$OQ+?+WMjk_O)c-V7`KE&VCgeZ2FWNPfM3pJ^%@&z)iv>OirezO2efJ&mknF zVqnM=WF#l0jjW)msKC{%rT~L-!Vr))2peH^G;X(UNFN@!qq!N*+S@nY-QPWUZ@8Hb zX*SVk92GtL;4%H;)Whl3p~nv(PkNrNM1x1Sn~AB*tE;Nj$Sl^YE{bk4bE5n1snrT4+Js^x?3BC$M! zC4aFRk)wuiRXm0WUyaZ>R(dcnUzD6o7oW*UgMjBkGKi6oTzD)d^n!CN0URplIBc-T zDSzgi-rgbdNFHxneTME29^F38E_JtA-%Xv)PzO?t{CRs-OyeF_uhHA-U3;g_aV)S+ z;aUr=KiE?pI})niB!gV~!nmX%a0eijkcbF)hzkOqn3Rx|=pAQwL9PoR_sY3kJwX2# zOzHcthdMifpNoLQWTm%py1*46jnH6_c0(@H&31W!xcJhuukbH z>o%#+o+8fLbINBPV7lg!c>ergi?XGIhznAJ04d0GDG`4{?}Y)x#W}$B#{{nu@gqqC z<)e^gfW_~wlYTm^L>U!{uWdfyv!Zg*bX5i@7E>3aI9XJ+zl z;U3!8YbvQ<8<$l@Q9)5zRVG+blLZ1!&!DHv$be_3r{%$sAS47{Rt5u=mq8HKWe99F zjO7BV{}vNM09vo}h0^}-LOIZN17^-P152>P`l!=klq;4Nc8QjF90|;vmCx8JH+{#h zz122tLUe9>ByMb?$M;41k~I294xG#?muyvvdxnf;5gTU{Z@A97;i(?3eBo}jnK=AT%nk+gE1hD}g*uSKOFIxkLp`od@mpj`&zq`3_n6;m#erRM0 z3CY1Byj?gw)h?~U5`>yEpxiO--(V^>q8pbo=Jkf4uRGbK$nCFc=?6QVhk`}F_#_TV%znj~J<`X@7AHg)F zxp){H7!ihcjr6=6DjXgV6nmLKgd)bxBNz%3CLn+o7Z;Y4h`}ILRWL*~ghs!qSsNsN zK~p0@Q|5C{5q8EYz7bhVg_PVis^dz`ks<1GCThOb7a6G`h;~UWi~uE=3rk=|yvOu{ z8HiYJO8E+FF5qx<^u-R&apiH%Kd3bOq(@d9J(V!49Q0EDwX>NGhd!QPn3IRLA(D^) znhqsM%SZ=jr(^O65C{<%qznQ>l$R4%mlfB+kQXrhx8U*tu>K*8s@tzZ^raH)zcn>v z=j0qC*Chzens);E9e6CR*EXOcZpe;!0DFWkX zfvq{VyYNfg;7Zc!l&`pH_gM2mY}hp~y$UfH(xX>~;T3NuV~X{?OS~t+jPw^&I}^ll zF6h>I7^Lb;XE-5>1zm{V85njQLp%i_g;+s0N~El;rM4iaTl{=Q`;?DT(nGFB(*cCs z6W0zIPq+5xR~AiEBbV8tn3ZboANZX(dg`70LLkCI|HF(zAa%f8WI)InqrRlPlpwMT zG_hnGDEU0EWNWLs;__2md$2??%8WCT0_8!Ww~Y&}6kdDl!-V@fvknH%nQ`^*B>p|V zdEMrw<1Jpoi2mD)m1?j1hw#^a{0I#UkKl^px}caMAnXsXPyrMxRVazaHplnWmvFlH z@R5kgQLYua_iX7tzYq2vD<_TPB@a`u=OZdskcc5EAKitRZYEwTTP&L27hx~9=vaMw zVd3Zk7Bd6^gIM6;KMMyqWg1P+7EYb|#VOWj_>;CI%ns65sqQRS^FqYe-oDD1AfwEE zbNqzfrN2;-gM~V?!`>}mlWb`4l~n)l{+f>-KEZN$6b`iECUo>svQ*UCRB6=IW|_Iv zFj$H#h|8*|tgy_wqEf56M&yE~1^}Sz=YZV)1vCuQFe+AEE&z(|OVprJ8g}6?)K(GZ zTr+N2ZRl#x``vDO+*SVm`?%4kSeL`P)wf>`n>KTH?`nqNO>N(zir`?l77+>Zn~P;y);=+x-fEa;Kt_n*2z5MzL+)10%=v!fGWq5FS$n{!pvId8*lI*J@| zV*&YSbusG^iXy|L?B^XLKUB(c&uAHZk(v+NTzj0eU0dspM)(7 zAN4Po>1+Y~IgGIXc*^CVV2lSCfKJN69vHsd90tab@?BCj#@(k~$daaCKGbX)!Y-ve zoPAf`y42+V7JN+=r~Qc(%(iQJME8cth8dtk)C-MhpP zni&WJHqm(jv=k6re~z9TC_5tCgshjg0WY_QR(}Kz3%Z^qc~#mH&+Iuq;lwCc3Qcd2 za!Sr#>8l_Yr;H1?sdzzWGH$EK37dE5P*h~fB0{9RP`bxS{Yks90~CFs4yO*%1%wa* z0VK5z5Ol|q(OYNK#qxgQ>N$1k<0L6Wc`%VfLKIk*dYLCON2{*PWT~lA*bCn0l^WXi zIDuY>mFvLMbk8Y@-hmcC}OJM4Y#8XYGc;kK$6rcO>n?dnCQJ)QI>LQ z3FEg4>2nDFhpon+_uabfInWOna{C=V_UPmeb-X_unD^i8GWT*0iRQc#W=!E26qCXN zCCJDCgEKRuQd1!`MMW^;!s5Jqn+w+a7s_9|#lA$P%YCDACQRgynUgz)y(Ak76xTUU zz}KQ?Q8QUWxtIsL8iw(W1{l=XJ6(d?hvAr+f`v{&e__3}`}>l<4fg#rA7s-Ry5qJ2 zBY1-?T*J_j32f2MD5v#e6d6lccR4tMhjuX8yHG10fD<11;PQf-=B< zidj9p@S4JkiF9dIHK~@NuGZsvafdo0+1o8v*VOEoFe#>Tnk}mYIsx<1gwG1aLn-tY zPsyp!foPyr5Jny4<{lF715FA_O|v6F<0U(1Wt##ebn0>jLMW=7ngQ%pYzs%U!ib4s zt=&yw^g66MbacI@7tDASWCWr(H=`*4vs}4^1xc7;+{MY|^68ZeZq*T`e?rIHw(har;{jc3Jtf2WWWSPrz@4a^_<#}LGNBz>;{_=;>KY3R&qc=ZIUY7aSuxL*OK@kV`J1mBH)*gvOUztivM$o#rP|zdLaeRQ2lM%$MIHtfE6`#XPm(Pad zs)5PQE#rfOaj0&Vme+Gvk`mNrHMFx=k`T9IJMKcj(2OWtI>_B|5F-tejvfLVpJ#;8 zvGgsRwfz>x*6&_WK@w!~7cJM_{u+Qm6-+zo<~Wdfyq#$4ieIii8XdaTTjah>i+h!# ztYu$@Jx*mGN@VvzJ}NDoput0;w$J<>((ezJf~9E`IFxIg-+Ut5`#&i`sDo|; z*~?kwJoL{w#+gu{w4s|V*2kyRFD%Dw4eV`L>=ly0Ld`711PDeLgdXV0!00m4 z5jmMzIS_UT9E-)!mthfA<*>@Cg&PZpKtPBz41_T&O^X!{L!@Tq(3El%=OW6o0FPzU(Kk0Uwlvdm zx6>oLIeOsjjG*3@?2FZ8Nx*hG=jlP`-#`mSfsWRIDF#JM;kAKbI~_K(Q{W9`S1lKq zb_xAczJUnNHzu3zYVjC1p?ABCDz@7YhR-^e4|*LIn{5adSUqd6uF8i5qS^6+HTj~D zxUp)I6lrn@ItYl4J~x*!FPF}W1qi2{!h%A2j+$y9DW+q~ETluwK)N~+1vCZlfdR(B zff}x1IC7k0;@)5l4gCxfF@GNcuk?D%2wB_UdGd6N{h8nei+ccyaGhHmeXdBsXkByt zEgdB~vsPJV7u`wat?N{l?l#8zKA0K%K03m@2ZVch*OVmY57e~mOv=`IdK$h9k1YzV zi^3gBUvOzkN`Yf^aTww`oV4g8=po$jNP0RD4P6`@ksL`E#tLGD=kn&}(kIdvz#)i| z0(vjj3t%#Vv+UA&EuCQdL&^@-1)3xT;Pg6A9FG1rc(cofF6NAm76MBh^GZi%bIO|s zkybzAK5YA@-~mx&e4}YnWQrg0hFi_!)?PLkT4GZK{lG14_Eo32>~Wx`fu@hvUa&r)1y3$V zJ>S_Gqs3b~TG_t;b`8M@R2UdZp#l66$pn=*T5wF zwpoqI1nD#8&p`UGJ~rP0Ayj{rOA(2OM^FIWE-=J_mxhHtVSYAP1aXhw`wLGS>sHCp7A)+awy0tBjmZFcgr3VWp7#$lK8$*QL!x9GpbP6#y zJ-fo_xr)8u-GAZ#)4y(Z=|}!2{Oe4-&j{3*--|eqvDZMBxvoeS$L}^;L(%uvTY55I zQ%Z#s*Nh$7Y8PGao9nCHpr7z;fBgd-8j1&ZR|T;|!vi@JVi?^Lq{1U;F%fufngv2R zVOg|!sf87s#Ua(${K^LQ+S;|C%rtotj|4X$sBtZ~3 z$_G)bMa-D2=K0!>=2>(3my4(Ge=E_rfNX&cnFR1}z`1`@^`(kj4niXhfu6F7Z_3Ng z-S@bVw#Gou1NNOGi#;+{EUvWX{AVBFq#Vw;V zG~Y~=>XA;;CJJ}vEB>UJIZGW8ZXB?;;*qdLR#{|<%5LV0EOpbvx>~L1z4j*y<5J@~ z!%rfu=8QTXgO}KNO*#2blB{v255$ndK2aC>t`x`)=n$L*cH+N*egEtn|HO+f!5(GY z0$8lG@H#Awu+(FQ@=BV9owt^&Tv?&5?|re`Wlx&XKT?1h>Jd=kXJ$Vcyud?YN|KWS zhv!zbqCOGafUdDL;fxR}7bqk$T_`CfEhC2~**G<~h!Z!fxQvwmTV94kj!V_h08Xeb zr$=myZ0AD1sb}UeS&8&3L?q-$`(5BC>mmy4h(%Y_!Ge3RApEsjbxFu9}2>Sxmu0|1k z?tAW|5}$~sgQxMq!uL9c9Ypg^E;0DGT+77_MSr`PzupF{t$Lm_c>ZneYJDCRXWoTQ znQ0Uz_#4l{5ZkP+CHlpv5d1NH|++3>vS7wQu=opwG}+te zS`Xgb(SIvJE=&(hWFu|ctvR3JV*vIs4Jzu;^tlW75H`-w+4vP}W7A9%Y*bZq&>f`k zEN_<+zkKvn5I+pfMGT9HK}1SG5;!l2^Z~33J@=#PHb*c(7a5U_jkC>!TrNIxkA1r0 zB|~er=mhExsXYm(@NwpacuGk8gpFX$Tl!0jj+es~42CSP z;s2z9QI~?%#_Yock9)PM@-a#m3#?8+5_(p#x&x$xXEawj(CMK1El=8VmYPVSfzp;4 zwPi~r#jbYbh<#t9P%hp$haW3jDJ_TJEmiK)CpA?E6S4W!gzMk!N^*0%sQTfZ`A$+x z`meu2WkMKmNxaw)@$qNbTRe!EF(wwFe!*r^z`|5HKX=pr4wmLppkVj&u9xc+Fy6p6 zdOASo5zq41d+?bAn0*ygh8CYLZFE~(Aod}SIPHBEAi)e|F>Z-@nQcGn(7SP{!$!7j zAWlx;9uOET5K7D7;DmMyiuDQu`qatMY3W=DYFa#69O6K{ii(7M9uOTJn4Xcez7=>$ znHvW0p=0goM|56vtOm#%m@7D=jlo#KGsnJS!d3|my4#H$YhRDlVXjTFr zjJ*(9lPn&4rOy;|vwzAIM#LB}@3MFa7 zLY1PF4Wfd8DIB`gR5(pq8Vr-3nZt-+guqKm7-6NQh>8+ORdwM7tNphf-VOlzZ`aFK zDmh26so_>zgJ9sXsKMy)o7^u%h1f-QN-yDi)*e-KbQmrBr38F6j=7pHjUop3C=YbS zllVFK#HC@!egTMo|HqMd;S<@t%&CT}7o>XwQYg;JsoD81Qc^9}#EWcgxD$vci#`@L z-u=@{rvzy!TMHYH_^8}RLf3**s|)w5ArnsE`6uoQ3@-OyHdXsP@7>Dl>Gu$F6h0YH z%a~%+V>1emVvLODjJ;_7AV41HxxDi<>>H82v`(Ev)hah}4zF3HoZ)+Jk|w=f4q9#5 z$#QiGa&ite4Q9ekh{>x}k^5>`N<;A3j>!V83881yImmY1mm0V@n}% z&p}&h!xWfvh?xeaLr4NFIFX7#LQED~N?`kt=SynhwQnke?VOl+ zAM!?4UMVv$l2+S6wbz+~jSiS9;;Gx#NhM|WZ3jl*iw$sBXGd5&)ud4#eX>7W}^?Gc3yR zxTb?JRRjNnq@sDeW^#xVQh?x*!4R9VaevHQNdgUiRg zbul>^4y}?UE)rWy?)rQ&Z{|YPfp>0VVq?J2I0A4|B0*X#;2>fI4JaRkAkHhGA%+!z zXfP%DSv>Vd^-axebX@iOZ!t{*yuElW;%AtQFB8~ZqP!=^!IK!|a7wA9B zgX*Bjzk=2DEO7_c+jm2yjllQ=wO#uyjK@|6JAeP20!^~He4+x%iN(&cDP+-b1im^Km5rsv-;9PJBOyk1ZFgh1^wz~oi zle1PmC$iC{s=a~P$jr5{+m*L8{c&&U^M^lNBm1o0$E`p^v>iS;KGjYph-m=28M5_m zsy7xv@_C)6A8~4z87FF$Yj^}prEgPS$nNX`5q}E3XIUsKP$$y@7?vr(uo`(+gg+3O z9T8Jl9Ch(Gwd(qr6l=HJ$8NTi@&%;#+(Q|ymsxK zMAA0@aqA(KM0f-tF(WJ!bHH{IGmXys%Ur3*cECTXrt_Y*hl8OTA; zC%Tx(FMx~!Ktj)1sugg^+j3>?-7z_z{!uFxbd{7R3~-C@dDh(XKAnB!so+#NucXEc zuPcPw@(}1l}^tFB_x^}x7!+fDe+|ce9d@^+kPofkUR7SBch(G)$%6dlB(RmKBWwz zPy->L+VvAjM;s{8?gD~(li5sEHZxcCHfoG&kLW(9PG!A7=43j7RUuzX$<3OTK4TysYFJDXujeR_LOHe;3eUps{%22kL&n*&fhBot--O9k!L^ zE=N*_t6(Qp+?c@_nD$tK_OUEb>Y~5`W8lJ64&bN>1FHrwMCIN3u4^vK!gYet%~K}x zS0POtTLCpQGBAT(!3Hdf;fsVx^^OU!<;o5;jDb}Q=!)wevrx`anuWYd+zP0a5ggLY l3cv|BvaLjNyFytklG~9a7Et6VB$qxYZAG{gNgSUKtO1Kv{zm`+ literal 0 HcmV?d00001 diff --git a/doc/iterators/ellipse_iterator.gif b/doc/iterators/ellipse_iterator.gif new file mode 100644 index 0000000000000000000000000000000000000000..a401b30818b8c0ae6b6c25a00bf0e78ed39beee6 GIT binary patch literal 30436 zcmb@t1yCH(*6%yGO9&R65Q4iq1b2eFySux)yAxancXzko?(P;G=8<#mIp4XjzPeTS zdv9uLx_kH5wb%Zy?wFITBEI}X;F$h6MSW!VxKu(yEmL38O004X>sY=Tc3F$fN zeQde;Ty6CXEQ}n9^o>l+ta-j(wsn0aGBf1)s=^{oFKsJmWNIenZf~UEE~9ARZehS- z_?3^Bh})IZ)yme&$Wf2T)ymS^fzy@etDd2az7glg{@-M}uSEaI;%LG1Rp9RlqQ7kl z+SnTrvCuNn7|=5?5V5k-GBC5SvNBK;G14S!o!UIayda8QF;b*XQd;Yxai5 zobo~<|EsN!Bc89Oj*hmRbaXB*F0?L8v^Mr8bPOCE9DnOzWTg4XLF3?N?WpHUW9>ll zuNs7m91QHuY#q&Ptcm{CsHbn^FKPj{*LP(xg8wkjsB|}|7~suMK@a`I(Z`p8z*}MqmS$)|0?`pyZ>`Te=~mchEvww z>|;{&EQM?goUDwj9mR!szJ8pcH8eBi6cJz(VPIfmre|ZMXJuz#U}q9y5D*sTU|5|K;m8JJoBO`!NY zLH``DkdeKavyq{Qy^R&oKP=2?_TTh?o}T@~fBsJ+|7Tgl|B2P;J~~79*FFBjUH+By z;e&s7|Ly!A2mf9^M%Eu|#{Oe*fPvoMUSFP{9v|-i+}++>UtM0DpPil@9~~a-@9pkv zZ*6X@udS{uFD)+2&&|&Ko}QYV7#|xQ86FxO=F(<6Xm4w6X>Mw4sIRN7sjjL7 zR+N{OmJ}Bi7UciR%gxEo%FIYlOHD~mN=%54i;annii`*k3k?Yl3Jmb~^Y!ue^7L?b zb9Hfca&)k_v$e6dva~QaGc_?bGBnWF)78<|($r8_Q&mw`QdE%tDJLr%_sHrF^$jQEwek1uxOhib4kB5u%1se+!1N}4F zCsY(Jjns4))WDHjplPw4qtH zX<4P^X{Rmql%v(AYvrZqC8#^sR*V`aX1Kt9#F8^-y2Mces9v>H;XHQk-nCWjDn*+y zbyV*@VcoWQ)$A!#wR-v3?mcz+0`m3q4+snj4hanlkBE$lj){$nPe@EkPDxEm&&bTm z&dJUDm0wU;R9sS8R$c+Dtg5c5t*dWnY-(<4ZENr7?CS36?du;H92y=O9UGsRoSObU z6Nvz`u(-6m48F3yzP7Qwu(h+Xx4&|Dv~+U1dvScVdUJO7=N{(#;`#LT=zSj${uw(u zm%|eV(^ajzIgiaoNw#DZw$V(ZQ1@?{ceqgK!<=kpY*&>G4xOcyF; zWBlLX7r@l2HQTb!)0I!vfmT(W9XKf`YbA(Y$x!N8bh91E&zv2&O128UGDwndZ7K}% z{UKjcoTSk0 znsmDTye^?-R;e$?dPyKAH8|ZaJ8GLaeLOwy??&ef1*drHUGK*Gs{;6Fc%2^4568S? zq|+mg2love=y1B6pKEUWevx%`f%cvU*B8@3zImUPR_xEMt~Y$%troUSPLn`cl~%Rfs8iRpeWfa|981S32i3X%(6Fc*m9S8$Rzz&0$j`Sg|5YUNj&o5{ zCW27jvM*x+tQi3xJE=P?!=p6Ui_sen1?xgKW4g}%z35b)M^BTv4xBaSur0eFQx~sD8?gmQwZkiv&t^Ipk zw#@T({o(ZWdYf;P>#|Fy%Kd4toUr|6tk38CVW26x^SU*MkmqjpR;T0s0Bj4?OxE=r zWutrdnegQ%rSoOk#^?D|2NEW<<6Mc}7jj%1nx?tz02Wmcw|@(YqPY{Cayk$tQ5S-^ z`3J_%lnY(|=vl5D7YqSvFvVUPs5OZRUj{Xh1X3T41-l>MH61D=k^7{6B>4S?-kCXn z<8xtX|JQKJaIXFxl!l}JR1k%!@rL+MY@ldAvHg{oQNa#&jOzePaBQIH?G|oO=pfS| zU6e~b$)lXBATBLxh?k)rB2=2-GDVG->zct=q(@P{n>fD!^t>;mYN8SczvIK_@*nn0 zg&E?@5)9||;IO`od{4FyS92sGw{a8`!;Ft84&0|w;t*#qx=Cm#*d?_}6PL1N>P%q}`B!Ot2W zyT)9|7V5yioZR#^WPT0z?f##&Z74gF4naZeoD{$CS zF{2fE;DBNgylSbmUHWWFGO$Qywsh8)lQpOEyyzQLCi4KrwEyT$jx3J}Ti%Kyd8a~7 zXQGMndV`{^vQpI3oH_TgxRM^{pECUkWA&jg(z=szKvjGyz9vqUmS=@BXBHF2-(e~N ztV|V}PN$Tc&+{5+=;1+5WV)wi%C-0N*>b&ydOe(KeVi;cGLa|R#VaZk)}Q^ff=mp) zAS^cM-&bvLo^wvMF11-NP{BI=Kze#s@2XrV1J0kCSe!0PpS1NXK@K|fl zR_Vxkv$mhLSoKj}lwF*+cFr%?=}&LydPTZIzSJmvg;%Xv6+Sltd2Ef3J~Ryj$6eFp zv>!QBI>w@GJw&;5kY<~j2t;f`XVQ|h zanxmUz|9^=DEZ8=bW0VEGuk1a3-J(!Ep6I*(6Mm9AbrA4@mpvxY`*Zoq2(7R>*7jW zc|pp#QXq~M5PG$IGx?-_0%xAN!)eX2qe=ZCYEjLifo0qn34r~wG%Vv>i;{b0%*M4K zd&?r>7bRafdN#{&eI!|*Wo0=PxVj1LBHizm&IUrWx>Jm6|_n`NOrO(T0-m7(iizmj2xK;^Y@#9akI&;$BOcAQtO0Wv%U#m;$%qP1pc9M806Kx;wZ-?1P_teX|}s0o;o% z(;*;j0NAU>WFc*84g``Z7fgE{rO8ve4#BO{?An1KjQbRVE})XI8vxGE&ITZ|tKQVy zMML474${7>?vvURBWme7JUfW5QaceHdKo?Ub}XZMJpmu)7(~#$&Vabsx=wy*`^=aa z19NbIM%F(4Y5Gs(rs{-SOzXjE#TLEEQ-HUL3&gO@U8s-O0euzcZmE4#9Z2(Vh?r$9 zhUlSKP;Htu*?yD*g*sTr>)e8lpI5Hys;tlBkCET&>8I`}_sI>|22ky6;iem<_4~Lt zS;ur6a`RmA#v>wsXMjEBQxD-*{|hwT<)X!lcd_%^HBgoX(&ic*z)uVh>bxG`!qFS+>zNah4`No`NI$S zPwe{8m$)#d$}tan&xHiYr24uy5*f*5`Q{D+*7ZM|zr0^!I)hMEEeuAQo2f-4fe6B}I|$jlb8{GpfJ;Q9U0$@Cl_ zt;2?`HA|HI9vt)^h5d&WjZ{s2hF!deWkgDx81_vgmaNr7t)qr*Wc2`i#h?&;=HSF; zj|%oM?WC`M%~*)d4!UdGL&QWXeqKn>40-rm>K98`-@Q4!4OZ(* zRqJb54J18GygYOiVy@V_pHIO*Uyou|??3sI+41F}9jbcfHOs-bp!0+P2$gVVisV1F zD6m6WNeC+bPPX7SiZd3pLMx494~kCwrgO3^1v+C(@_=v(d2wpO zNLoRvSyX8vCRt)uSOS+gx;>nF=$E7|*YqN_G#7Dnj>F)vr}PF6^x)ET>Em>xk@TqJ zG}96cMN>dWOKRc>7Eef8HED7xdvZ5iDlp8qw$#CABx3veU za?28~aY}1RAB4-vIL<~;H{ejof_%m=ugvMN#-po}=5awSjL&yGAj z53jX=+Ppyc#9-VMpca-g^OW=GU{?~FzgL+5rdFuv9w0YN6vXb@Do~KKTv(EjGuD!A zxt#srRzzyo{kDU&9|aWndI&yG`j#j~FD ziu^}&$wo_J7m7zuvQ9pgOdl7K3i^xp0eQ{CtnKak!+<2kz`18&fI858CWYV4drYEI z8(x#uy+UH8K#DV8CcQ!h^2C3G2eq>}k1VRqcOk-WI|WEP-WVacTCQisu}YCek^+Ju~LG00xm zDxQ-DY=qn&J&{Tl4Klb5vW#(-4WchKqMQK9u?A_2CRUF| z7b+5xCA(Mk=J%B<@w^(#mqxu)KWF&dn^8{%_-cZP=0pulo)pvwghp@o;?U>(arPEj z^X7byW|_Da4K7G6ixM4onvL*AzP57TmnLtGCY8LBQYy&u)0Q3%oGRSrf>m@RxMWv^ zwmOS8MZdO;vDSl?MiB(`IE}i747ViQ_E|GP3oc~aOLKHNLziTm*eZU&Vwj3W)i|#H zQF;e|u3Vpbc?W#OC2s8Xs?{ymCy6hKn14X!HxcEJgI!muU7+$$0&$&0!leZ(ae2=Q zMb9PT193bor4`QIEI|$or154XJqVhLsE8KWncboo@<*d(aY~&q7VO^;X+Nzr=d89z zMi@hm7tLifZfUf4b9K+bHMOrs(NH^$BJ{CqbQIzC7nYaT5BFxCHj1_r@I+SpknCf! zY>~F?_(G;@M#(_5|pEQ89I>1NWH{4dx##x{=J}{dx zsQcSNq^8|qt#z%fH*s!IKXb@yt%D-4)%k3QGqZoI)lR-_i1KwPJkr?ztdAdeC=Rbv zHe&dfMgL*jaL_nkIKqgk#jyF=fRH7~!6kB}FtU%z5y0QnRJPibXxSd$E`lrCR3tTQ z=s7l8SY1)kR(aNMVcBuPIhO0$%k_%Sau|E^0k>Ae^Nht%=k_4e1y;gBV*I7RwyT%4p|z85w^aZ;TuY2y8oEgE&1K zZ`K^UU2`QNp8{D8O>`rUZDi`jj(AS1Pm;b43g*>3jYGUhO+lPbQN2#< zv8VQPkNcL7B1BA&R!q;YO?2WJkdPdY4|PP_Pi&qnuk_N*+}bi`bhFBnNL76}XqTWJxWPo9sr@gSw=A1 zK1a^lu1(La(IIiPfW6HAz@KB`MrZCQl0uwA;8_l{qK$gXj|DDsX3b*a*d+r8e&H{t zz4hPCEc1UnlDb+^+g^bL06gDj81d)A)mKcomj+&!QPC#^iB|zvSXI)1uM?|7Uab(h z#aJB>U)HBe+JD<}`73Fx9jdH#;4d{HjhAr)%nn8lJVw(!J?7TY2WVEW^;UB0;Wo`CB&Z(M`Vn~x2P zx9f{CA;T(moAp`isJvT_EY;$ztKrg^&qzB|G&^G38_3$aUuf5N zwTzK%1Ah{)F21c`6Ks8!#vprMPl;OLLRv|c#?Ya_s^VEgCR!Wm*jd$@KziTt!rX<* z+Ts5+je)%Cu;idxh1u2a?CA$!Ld@WMZN+gBpMI10}rxY$FW-L-7A z1II5Se%~twE~il)8gw2yy&vfM4R4$6droc^jBWcOZy6G7PjQWnkIKPaR3qtOum}~X zmgQW8E;Mm2K1+hSoU<14ct4?6#y(&zW*;2)mYqByoK$yqq1sJHU66@Jm3@gU{Z%%n zF)`Oc%i<6*$49zWATi&3(bFa(kIy0Bmwcw)aVh}is7}%wO?zZLIn~zSU^`s#K;si? z?Lq>kVYIPXFmWs(v-e};uq-QUX2WG&`D{1iQo0>vq~e9 z&kl9Y3NsyOE^?9pg<+U*^WanMRb=4}GT$94=!%x$)-U^y>Qo*!O0jaxoleyq_htdM z3GV&H+N1XEvvvWw&L0lG3j*0A0kGSzHY+w=4^Oo9CbSP!I`@JXH{LoIQWUqwQ#)LA zONu$l2AAjB+Sl#kGggHUUYGYNHtjdhw@y!w;(U*iI<*<^lF2boML8Fmcn{Hh53%p( zx``%|Gwba&_ncR2kWuG&=M*$=QrUEmq&Y5x>)1r+01cl?d-S&0qUZ=y6xg zgzL_r-GZ3MT%Y^JoI&iNC*RAfDU@}l?3Zam23Mcd!kFh#*~d-J=cTz9&YZ^)!Wv#e zQ4&JX^GVG6^wUH8)H4n;m<%oH`G6X5jp5G^i_bjOcVc(tiC}8Qg?Sb)gAQJY9zGo8 zfr9#Rp@VIhpLkH`0-0PiFx`L4xVE1cE$%nh>&8g{HI(i0j`(|b)7PK4I_ZQ5qMc(Z}0@0luQK@W+tj@k^k;rKU zMI}M~0u~yPPGGDpY{mCsNQ>ho(BWET9^d;C%M z)^jx4NFKb`-VU}Fb+d`4ON%MR%7bO{HCBYiz7pkdg`5DM8c*Z*`Y&AohZhBWvB7ph z!%q-f@V-C15RdKZ4?htOM`Mztqr$}*hC+STdt~}9cQ6ipjK(PywqqC)!m09$`RTJD z5u*SwuP(W+e-e==1>UMm5mEtD1Q;X$m2j}&%ZmHG;Y8LPwhSv%CWsQuqOtlQHr&dC z{-U?#X0S-iW7{{i&Dg*mDs%W$G}B2Chn6Gyq#q1?GJb+<8_3yD{bC-NC~vX@F($Pj59uXp$DGL_*7{@8C$rKQ+XSh+i|ChY$x21SD2 zJs!@9V|Wg4cIg6_8fRq*UXH@2X)k`YR+qsGc8|8{!G4?WE=J{+ z>$!T?s1Bgl_OBLj`Cf0^*RNR+JBV#1B@jsjj)&AgBP0~j|4CXCW#BWZyB@v>x8h`G zq&W$r07-=5bk|!2x?j$d;ni<$BI3`C!{m~g@)8(BSCXB>_8ME_r-OL4QjFzNH6qkJ zx>Bq+t;`o=3tQ+4lkCUbXaN`u=+bRay4+GCV~orZ;^%kmbpiZx%Qu3&FH+VsQW@V8 zN2wGLbLZ%xV~geh{@ar|zr)V0!!YNu|<=El)Ch4jneSc8)JWX2k=SMeg zQ1XF*NaghF!ROGmkZ$Y-7$s;qr8+4EaTuqW6mb|s!BbQl#>sA|>Dy7zvIksqI)|*r zwAJpXNGA>k9!q8-L!}fD+vWMnr?j`mrC1!aTBLslaDkN$B}1M391b2hlby~EWKbTb zJut2GJu--)-tg_Srn;gPyrg)1*N>4*@=A+_NWbE=8-Rf2^5eT1egQ?d5npQDbWotI z-E=V=_Sz8B&imhX*d==u#U3NL=;o3&rb?usR{CmvY1D3aPQ&HPQq#kS3V*mj_0a0$ zk;FQ>yL1%6f7*4E(e_``_U4dZEpGa9CX%YNVKT45_c$mKbSmnq9Y*)QI43@+4K5p@ zB$*oYC3>zP*SYE8=jJD1mkVCcZw%1&2u$epoM>0%ag}cuM6~S!7}NFdQ|g>AQah=E751c)rj0!Z&M0mD~Y z&%yK67kU-M)??9UJH^<)D`LHlUveP>zW;Ezp7LjH&--dG)(sEBsSancgyo|LbP*q* zL@+q!p{Wh^6U0~RFW3GW`n4o*OJU+pBUIJir4 zlzgBa(F5)tZ_Smm+o@IGH)T?&R10LQa$#NsIWIh(yhvJa~z5XXOM?HUjVvHzRDq1l}?CEV7uC z0)8q=UpE^?_$vZ2=Zs!@UEW(QISMTNj1^A(m(NCKg4Y}}zB7tBH5JG5uVFSCnyem5Q8=_O%&& zCHg5b^1kp`XyaNav>Q7B{r{Lr92db%2!PpUot}N>&48K;Q+AXj3I~^v44ReEYmmS` z-+#_snXYwitYZ0LsimQ@)aVTNdTV9#V$0qukzmydN?oyYi_?_Ly}>jxuwJpe);y+M z#QLoiv_g=lMWhMe)_)~wSM|KmCDPb#M{0qM&bsV%Ki`3uWU08Sp_T{d-$6Z6A&i8e zc1Nk4ra3XI`9!5#AI@9^v2f}^+O7Juqtbp#UC2W+E;!2D*tso9?*%&5LF#*Ghm5vC z_@WT^l1|hGzD}nu*{=5hAHx2n@ygTSRS!EPsS2N#O2s8T34?9F|3u0zRJ^Ps?+^PB zUUrR69QOigMoJ$%u!ds(amy&SY2;0bK4BdfHV|8FjJ>fYzV2*~!9cC=)uSfG>2}u? zI&ILL)giveZkb&2F;|b4DRgs9mtoeW-w^s1lwPW-N_E&WiJokiI{&i&t&V-#Is02S zkEapOr4kq@u&xLiX%23R`M12xnREcmk%;WdH1y<2tO}cwh$N?V#=%{dz`3eQllubZ z^e-SW(t-xUQ#WODm3mC(VNdwtL?Ul}u?_dGBht(7B;G%t6y8py8G|RMy`5_!JS+uG zIG1J8>PmCotiI( zLjaVvsaw9r8s< z!R}0Fd>5aVqenGI3J&4(m|*r?%wgt<0wLIJ-bJ+x8;>@(&iw!odGy%c1#`NAmcDZg zi~(`i(srngTyx>R#X$ekPDg!nf6`A-3+t*7wyN8$9C9uAqA|k7bDd}ka?8&jSIEW2_^Q=iLNa%DOFiN2;`1XAf2)AO+o{=9>mmyi+@BviTQ#!oEknp>8CbzS zDI?5-t0(R`pF1AaV-n9#tzZ0i-|wqLokx^9VzXctj;5=QM#nlmbUsVOw)nIz^>w{P ztK_U#4|T@)$-D;PcD)U|Jc_Q{ID-slyH?p%njye@eub2Ky-|m-N0acyoDkk|@h*FG z0TOx5$Iz^H8ty!r79hHTr#w&soR3`mR|u#VvrWel(YDy#NbdCabzR98(Ulo|$Q67T z?OpJZehS;zc>&%10Znj@od+2`hqKA45N(ii{8*WdMAUwp20fMLCp1uGveTjSQ*(C_CiYN5_CcZl;2y!GX%~=A=tiX$ zqiZ9Bc~qrdCEsN?ul(&_cHm!?91 z-LqSWxdcH<;D=^EvSGL7QWuC-vES;6PvVSEj+q?YvzJ>+NGY*T4v!ehmr-&}kaoM5 z-Ecrd6Q&cE<#T_Z81sM{WDP{9uv%mZ|7)qhw*jsG96_OeWpoamIYFX!U%hW4Y>Xlk zwLPY5LN8{$@^gc+{)6VP4GL~GI@E(Cnk0tQLMCfjwhDt>kfPERLe3Rc+ol2*LPO;8 zq8f;z%O!or{leFhBEEsG3L{~@j-j6Id0v^KfqMe}i9^hL9mGsxGW`{Q`nZ|ocqUhd zhrjSRjAlkx;KgM^%uqp0v~kBn0*QTlCKyKIH9J6D?ZuzkyE8`QY{SmVMv9ijv)f17 z$}8Jv#YKoj`#wwTfd_$L3mAj%MC=L>ZM*41@rJ|B`Y|iS%G!t3Er-1khkX)9otS@x zdJgHdOH>$A0WBrm*F^{UNo?V_7s5XkBU9nJ=tJf-NqjrS&&_d(Y7BT9Mq3qdGKb?=Q%_e0w!inJ+; zA?r(Y&5Z@w4%M%X4`}|-_U~y%?3{(noqLt=78)S%lnyiOk7N{M<{lGAmm1lVR<%U* zW|oOqlcX;b+h(5lNj+K0J=y3ed15HjEQPNJDbO-5{ZmMC{&oC-JJh&s@|aqBEU{4X zROT{Mim!j1byf=Wd#$q*eQM*I>^Wqj=(oPxz^?`wQ~Oc_fZHkXKNDwjB=2Xki+8b) z?X7@;Nie7Gmx8Ig*9mS$Us)mkS48q1#Yxz#uE{$oWTmMi$uh(&IZC{#BgCmo!|CV% z3V4iZk3ea3P5?T-;1RRb>NmnQ&nb+gkOj}5sQUvrETk9pok+lG&>AbOu&f5U{1?)h zCCxD${i$zCGhdXtl3qp{I7atRW<*n&WMloLjz&tJ3ViudAz6_|Iq)SI z3wsvE#Q4a0=1%>&g-1xY+Q&~(W7cL<_5!wdW+!iFg?RjhqaYZn>8M~8i60dP9p+Lk ze-o1a=K0YMVu_H)N|Hwqp6;t|B=(ZOx|4%InwL0M{PL(MttC(LCh33*cn_0MotH1f z6Cit&tM;7V9anPYmaAn?(ioVh=$I|sQ&NH&*1`X+im!|l1qSBZqrjr{eWKZ@V|NDR^zsxk1^sL(Zf`*>8U_kXqGUNu{S=R&HR)mPVetMIuy5)e@iA zN^2hIIUKjX;8Q4%!v7P}l_6$;pPzeiMtso^D67b^lwh><)5#ZndRlE>wk%w&C2cvh zVQH^G6_k#l^!eO3t5-f{LOyI_F1$kx9s|N4X(eAtUC9ER-H5GNYg#s3y&y~7e@(h( zK;6trX0Km9XI?ebL9X%hawN}W77nk96|4rCgu=C)AWEn$!U3(d3aFK^0ksx<)hgz-DXZ03CSUytwaJN5 zMbh*?W75@KpoY0lJYZ4vSAko?hw z6bmE0U;M7D?D^I=fvAluvOUK_q`JmeIK4AL+L+6eo=3B-gn_)4rA4B={^F|3U^~v? zz2j*m$NG-V=Dobw5C3&x7roM;b$YvXf7e^fuw-8g4cX9?XZuIv7Ue>edXTQ5w*g3u zVC(xI{fEdkoDD+;UPE;LpFh9v|18?cL0J8|u}gOkJLhC1?Y)hh@(ylteAb|MMtjM;rR;( z)pKxq6(&&Gr*5=oyu4>xB4^{1(UNwEEBH-yax|9>hl4UlAu`IP8>ZvRRvocNlt|s# z-J1E0CaTINax!N!lMAKymj0iSA*)wLF^A852ZoE7W-8BD+ARlU4jc)jxoLehv(KhP zLYsnTmswBeJFWMjH9{^9&hD*428?icSyNtU|{R-RH9m&rE42T1t@5Z`i7NttZA8>{vgOu=ky){vLqMYJIlG&W`6 zQr1si2Y0)juK+$qs|QC92YWDN*E)>Q%!b}uXvlY~C8S)rKNf+tv^ ztJuM#g{V)+Idr1i4V$hc+Y%ZdBHLV{Ou^ub_#STfPNRo>&sA;?o`c%7dokXD#@tqp zzWmm84cVuOMdvGkYO@q!|4ML6=>rB~3qHzg%NF7Qe_(%3V2A57)IVUb$qHb#xm9WX z0#l-7F73b)V?o_zzjd!aG%q@=WW&YASs`Z|z3;Stoac#&VN8&$u0^Ov4ItCR;MMdjLvI z01GPbi=9u3Hng2=T%273N}%OpqL0tZ9_~6G?xoGrv&}fxU3^rIeNoK(4qcQUFVP7eeS~j8Ydp;8#~^usLvxI{-(~`md)FWipNZd z7df*xtgZb_tKx)uSwokD-)1c{S$Y}OYAYRH%I?DNG*^>G-u<^gm{&0TUV=}qbEI*p zUxySdPmPcuz&~X#S4i*qkkoe|j^xB%g4&F>_Sr0snpl}OjzT`*8NSUeE>I!Pv0GH@hH5u~?mCT*glT_#&TFhG@+Q_)W; zW4KRuHCDJza6U<6L0kLF-tIQB=9p=XS^KQk)JZp6wff;<jzA?YGi16~d zMT7f*+wM7=u9>%x-Qew!&*xzesX!$bhcgfogn?sdIz^n|`SLyaI3*~v%oN=*Xc`-G zm)bd7s2AS#_cyY{T>gujl0#jga7LKaQ9#gmy7e#jWD@}zKKOevMs zs&|KiC4ex3LW#12HhbPC(!|k((*>u;)Oe%q`m*2UVn6kqo=kvL&Eu{9R!1yH>%~rS z7OSD7)tKV@g;gwZu$pQ~06OET{jpj2`7r3I#oB1viy_5!fWOwHwKH=qvxva) z{AYVP0vDuldw#HAlEXD5v&?;Ug*%jw1>*hF=(^9V=>iji=i;>TWOXT1`JV4d{6{(4 z`4A&@!|y^%K*wui4Qtbf^-svAvyPJ3dJuFc8*$(j5GyzE1*2Ctpqu+qFL28ZRyTYc zi5)AH(mr%2oY=TzGfF%ublHVA9>&09nv{Gm_$!*KVRY-4W1T2QTD7rgMjBgRa3ys& z(qt8Qexqb9Z8u+lcDUJovVl8XQJQ{o+V^DB+O++28|CAoOhbD$vMeXcSd%Qf(UIaz z?@qX*4F6hj@{Hi3u#z+wJXBIkQZY`7!XyGYilS8Qbc$k9%N4Vt9DnoUlDy=yq>ib2Zb^5O;c6JY)UJm{n{>wfgOD)R^D?=WiCV}n>x^^)yc*h$l~I#$Mr z?fL~JTFg=iS7HxO87`Pa^iZ9x|mTn?vuJ&fF{#on&Qe>yPZ`s@M3Aza+$*$GHSwaST_6IG1jA#4`v@J z+V|EtZwHh0XT%z&^I^;D)(h0Q88T<(qTt#zT)$=bnYLv+2m$zKZ5{mG{s7emnQk|M zI*V;DAtI{ISFiY;{TNtBusxoa!SH-Kl&sCMA4>Snv6yul^>Qptwh?g_KW*K1I=t9< zq2Hl%ae135s^hp=gT*&^{j^cpwr?+c$$d#vv;MYen!?9@x2@sBgSd>_(ebeDVf{Y6 z8Buk6QnFd~{B8gf!~BAFz`p-U&SS)2!wmV67fRX2Zc%WOUaAjB0uYfeF5SXU4}ra3 z6ZOaY76RjimT@5baV_)WPjdh!0E1~0#Ji+uq00{W1qV?>p?9>nnk7e4DL5Emhj_hm zOHd3kF4V?X_ft($KRsxgo+-OGufS1^jp)WGjO5o2{KxBrYU{BPJwKALT9yXXynZSf zq8ognND^WBRTHJ>x%*`syPRc4B9c0BJrS>Pi039QM&pEp=;d*U9}P_^h3|RLUeDzR{=M%pI>JZ6864Pz`2Ri)Yc|ddXiEb zP>iX~)FwB!lhQhrj%nT0rgXlN(g#qC>!H=94sw5IOeh^UVysJ>^!(18PcdO8Uzfhn z{++e1bi&HME@R{MJ9{6+q+NVn<^eYu=WOYuQ*B+=g(n&JF2$7FOkMVUI~nh7>6F(^ zUC#R}89xN&v>#f%LM}89`H#JHl#M(h2<4`u6byHu=`zHMH&;7qS6IL)C zKqx@$FK2S~FV3WRQiUc$DExynF)ztR8J~2FYIUx>KRA=`0b@su3uDS)*iq01ADqeIW!wA4MLs+<8nhn@G>l!SiEE;A^#JI$pjDTt4Xc@+x~8$9wDptI zE$11e-Oq!^cUosaz=ph1aZVR0fPpm7KsvVC4JM7+konW3pJF$n$m`FavO~}^AaedS z*a8D~TL4acg-J}bxH_?lyPI0bcRYZstw7vJ@AvFvN0CJGxPeiOY-~?PIUJ@zu>z_@ z%7LvtsdRd2(e3`3#67<%-M(-PD!mG|T20|(F<4!!T=i&ueijLr;@MWE>LnIpiGzVchJTc+7$LkEJhok(CO z?*P%ZDy`3f{fvTJs-rhgVjU+klR#56}bzfF|Dp`9flvZu!A} zFWK@(WIfsnKoue14n$Wr-44PwF4+#ob3WP*Aqpnn3H_FAx)VlTRI(FJ-FUPUK|e^o z8_B$2x*NrQP_i4%eSfqY!w*fd7fZn{Y#4HpX1W(A#d^G#ASXhxpQxy8wx6VGT)LmE z>3qDOq8m(ckZPE0c93RTRCQnD>_a|;Ufi+?4Tr2#W)N~>fl>KZJYfb}iB zZNEA?>AN#~`)CKEhlXik{<2upXtN6o6U!^BYwH`ETiZLkd;156N5?0pXXh7}SJyYU zA1Kzt)SgB00ECDR-M}u0Q;FzbNC-D7KucrSk1422y7o1S5t zC6kl;D=jzWXF*1hRCzK`vMRbpqAn)2vc##Swk@-xvCFPOyeVivY{+v&bj)KyWU5r2 z>w|+^RQ&W`Zd3%&0bqlP{BKhGPoytBdauCbA4nhbM5WXJ3+W5%Vfg=y^f|%+{vv&u zsad&M$&moWzerzcVHvP2Kcb?t4zac#2!l`^+SpXyS=rJS($QTsFxdMUrq6G(1JG$wArnvFCZ$Y4PQi`(Li_=)vo$7?56jcp2TT z{sMhZ6-r0k8wmMjhQpQqmk8A*Q-9_Z9{t%<=fBku0wo+7|LYc$CmdHBPP zjHTgN9X1002W~W5rZv_GTy3)59nF$#s$6e#y**hUYpUAp@`XSkkZP{p?hE})r9IwU zvpW<^BAMNu3u`Bzn5CL98(nE z<9(hSX*pv%-EfZY+;7B-MVO!dW2Mb}xaTt30|a009au>BBwaLjZ_*09X|0yyB9Q?BLvD09sLLZFvx|7zPcz zwzNL5F%JnEt*xxXzw1}(aQmR&7-CdS+r(r)cwhgV?-U}^=<Qwhn6dY_zF%u#PJp_uCn#YqK zp(wk2YSvhyIO1Ur%rA!EuJ)6DA1XJPc~x8ZKUTT_TlbV|soft-WwO{9Z>c++$`y8)k|L43xgGB>$0mT2DH;$=Rb_?nKcdfsqFadvA8+{|J7HJy6M;S976N_-h?2Zv>DILyOE2UAaN)M8lgTCDKZKs$IYai$(y z;{ITCI`uoOvVJf)82uj~(JB7ha6Gwaw$#YYZa^}H0Q4)rLf=q23(wa0h~;5$3XB^O z0w;3-9GYr$v{>0cqtlQ19l5{JsZD8Ow7~+dOsFFqKLU~bBRZ8@NsrxAEH&EJbw)|D zovgzCmzwK=#Q<;sL?32%xaxo?>%bmEN(Jd+Tg#JW?+B!uj+JDd_7<+qpjd=7clvbb zn3L{(is&Y}DHMWE8OOeBDd5Zyw!oxPq%oJ9IpF^Qw2k4Uu2q{iuh`dKY(p){lBNx*Ej)_NA>Df+HH&H zO?bXw^cRoq+BTan4_-e0h)w|ke!;$BJ}`tBp%JdJafk_VQJBdQ>0z0{sWFM3zud9| za?y+Y%X})lOFmbI7r4~ASEDr+);F~Om4*1uUYG8Hr2fvK(e~l-$%*>u`r)bQ(wTzA zw3T0LdB1mNmq-^j5=#z_;3G@*9%C_%|@EtH#kJkomzf`z7tARt9V1f&QeT|t_3 z>7f%sOG59xhtPZP9R#E)QY>^36;Leq4g2h~^PTVP`O4h6bI1Q+7}xW>tFPbsJ*jb- z`Oz3%`q%<|XpwGdS(Q)u9e7D~qfM>q-G-))$1T!`)Xsjb?&}ELz!)<7n*JyR*zlhl z9e-mxA*FA@v$F7kacJ_Pu;3Qo3KfL!;}-@nF{^wJ1*7!gKi2qlMUu#c=i!c!03yY>NlSSB|!4JC!*%#>lB+xk_fnKCwp%;8+rB4LUYZHq9V=BUO#mxPHQ?er%dd!Z3nwEjzxrHzjCWxuzF{H zbomL?9q_j$xDnHzYC>k{@toLO>hujF8(O6PmLAAR%K?u|QVjrc@=z-3mg?mb;nr&fD2Z!r9#TZI>Dr6U61K}laS#`Cn(1tUDJ7EhN-B_^fN>J&dH7whL_ zoYTnXtg&cKQyl#0M@-|EV>4>)jaqz8%u^!tb|{>YNfaxDcXG7dOzSFngPHHmPhkyA zcUR*^SI)D^e)eygIkEQg^m!5+1c)?1WWYZV1^KSxU*=~-mIIOmodJGaxU2HQuUYbA zQDd4hKbe|U8oz3ujYsJ2+z48&vX?w$zw~?QYv|;OIMnSW2XnP^$bt7063vPs4<5R@ zzOglUoMQKl`g(GK9i8{({9etPes9h2Ri_vIBNNj&GXvcU)7??<~k2ZO>IupK2` zJ$)n&H~62@m+kg{gVsqtv#our%|iaK(pR+Myo+0PBBvo0UblOq`Q_MB+j$wjXD{R^ z2;IHjxmPDFYS-%(s`UgX5l2yT_u2jLS3|J*_FB!1T<`CAs=Dd>iUoNq`XWOakl_K3 zgQ6@fF(J`5sCb5Ji7&A5R8cUI9wZ-LP+Z7_1L#3SuVrOc0rVi|4NX-{2^H-fjL>dq zCah0nB)u#pd8RPk?Dk_^+b$Z?_5AYX;<)x+Txhvgtu+eYiEZ*X-A|u zk$7X@??e*=I6zhH%kk<(0L6(>iEcV%Q8;;YYFG2t?Z&qbFui6WX|_*IMmO{4KY1ek zjl8YlegR=98Q=iDVx@iCJNxZgq@(%<#sa(P;z!4)wTI|zuQNfwFbGgqFE8AiS>u{p zB!9!Wh(JJGmjw9sz6l+E|Gtg_lLN8Afn1UX%C5HiIYTypbIwO$^OOA)_QdK1FD)wnP%aG=BCJeSVk2QUQ8+0l@a?z@!XHe@KWpFRJZl>~C`Fq;$aTZ* zq+S8VNu-q=Yc!AGz^XbITzX&6L#h8(!OdLF_byee$zo4h{eQl2*et1_GpuU3jC?j+ zU<(XFc}^>GNyCMQtR9pPIt^&X(5|0KarNH%QNtgVGLTOAgH~D`*lQhy%ZTJRs`Iiv zB6`;)IU~(0dTp+GhM#*bUd_Q7p6@y+rdTW{knsGGdE;u84xOd$;FD^vNT+*ST|(ZY zHcp$D75)=?P1q z;qn0nUfta6Tgf3&{d;7M|Huod9Qx~1sz`pN4xC-``0VL_ot>)4yh;-cG)p{&(D8a4MRG28VHkTSbJb$Jk@tVgP`n{%zNlyptYl=|<%ERTxYVR% zp3I>1=v<$CRN;&4D_|m7Q3XeJU0vB_2$8I)1qN>K?k)}>5xfUf527Nw_@7)*jw{gx zZS=SJ@nl#W*Sr#KKiV=hRsr%ROivV`Xz62?pOh`siqXLoEJT*2Ri-;UzfECw?f}cu z6|>L!KJM(3J54@2=)s@2;aXk*%hGv2^RQbg?jcdp(curUHy>I>#v~=%$10^kU{rD` zxp^jOx6`O#keqx%xmuxo8g)WqMMLAcDhs`MbW>*+dy8DG3wcNP@QA--wK*lsY;?N2 zS2osQXy$GCoD(ife(@t=Sx2wLZDDm6Gv2BlvBLoU^!>$pc>4$DTO4|_#LiykzQE=s zm_8F3ERL)sM&nj@5X+4(#il!H9CD(+bO;sHZHme)tOp!=Kxgkx9Nee_{S6)Vw$CpR=QII!tLVJLa9X_-%|!pE4<;#JPG_a$CJ*&F}?uxUM%aa%_ zx1htmF+Jy1@1%ClEz!qxbN0$Ii$7D$MekV~{VOT@*Tsuj_pN6m-n@xmJ|poqS=H*R z&tgX1r{xx3TCd@wn!uG_?1|=?fswx8&fI(+y``+D^Utg0AL%0n?V=rs;J0Ru9`akwmvRM$2k(=|0Wr`3!LfV@tLA`Ib@5Q-IgQLeL=vb z>jzs}`(&&~t`>7XMkMdweQAUbZ{aHYdY$P`XNLNVJDe(NiJxh5PqR$fk`9ycufbv+SqFp=$yGYW%6$Doec&R|el zPACFGOvd0|c}01iercRuDHW9n64_k=Aw`dcjQ{K6VSjq&3>;qcbIt`wix-foBLPj zZz|6@xbyf(dOCRv`zwUXAw!iPc$xY{bAgFM#>11-(u9vG*|MZ)eIZ0jHs!M7++tj8 zUTqy0q?$z59zcsfg9QG@u{~QO7ME3YqCf=o+yaUeQTG+r7a`pa0DW9YcQ!7@i%1`L z;hLCE^&%l*Cf28SwTi7vcw=Ov&TzqXW$|;9kwNXsfge)CRawV!TAvLg5a^YXTijg#memICUT4vXmLkw=rsMNzxC}9aV<*5F4h-K8-81kF?Wg?N-L)N3+z zbZ2BXx%YUC_0fJ3XR*3a=W>>YXy>4J>?89_E7Hl9Q=8fk*(DlUoxidhifk2oxOwvg zaQog1Iv=8nvbiQa z+J@%Jrk3_%5|O0H4p{%&wS$h2{rym9-6qPYu;8uX?6`A&sC;Z%AF-R_hmRn zpKxOW5i55DZjnD9O~QW5zMMDtlx`4k2dcp3GUoRwT%q04il5OCYWg6vjd}E~S!P+{ zK*#6YH3-C?E<}j+3>p+3!3G0kIfDT5!+0<(F*N}bM++6o$<2WV<>eF>mEvL9WfhgB zB~_$poDm?W!SU7p{$~yO!HC+=R3a6WjklT4v)k-&93FG^Qg{FLy@FGNmwlT@(fDQU zkeF?6Z>2ar^vSeN72AqwrI1K*Ic3PO!WVj5{_JkVA?s_|y5YSq^N47K>x*Ze0lMZu zs6e8OZK=S%{9%|tRXBZAC{90I*Or_vAtp&TB^D-_DUEe6mZ5~DXG9le%jc@Yg$k8R zlbglL$}18}s#RsdFiJ$DW^2vp#ioYJiSB7*EpIB};o6oSlemXUJiKQgzht4oKv< zE&Y+$mvk9fANK4v;`iu%nszVjxG&j+yJM?WTP5w;R4DWEge-!YlZxj4GCw(E#R;=( zZ zA_D_KV$!x2K3ZO`{?Trj5L*>nZNI3LBx#&Ej5?mqt28JtKixz+n=!QlS#U+i5a6*i z491yunD+)X!5uo1`@0xM8zx2yhWh(v$K~f|i*7t!n4exAdpn-hJ2g4IKC;@hGx=#r z{owEb{O!kg0XZ2PYIbE&%Ju-T6=~b=Z=&1?Xb@xv0+J1i-ww_HmpMJTSpiPZGVtzi zUmw2!cR3n>&NLJm?gxgz`6AF*FI231d_q*rg#>TF6zP&;Q~0w1tw*U|3h?aQ$d!e{$;7!1Sx`Io_8GE9sL$?0h<^*Sq5>Ae2KHK zuY9E^^6Xh5AG+CbC>Shww$QL&^Zf~RVY3P^fy%sr6EK^Bl9MF0pcL6RknnMB;dGL4 zTnl=>8ZhYd%X%ec9#%M?STO-<+~uuwe)Pr~-+L3a(_2YgA*V^MTLY%qO~HT zumBE-kHjaL0dgRY<#6~@4xNRwpMxGsU|1Rwi(G5yAiDNKqgtg4b&-2lxM-*ufbuCI_}Wf@WXu-?^A9H6v>6W!E@pC3bYT?9R$kz4z$OQl*Et ze*mxVJ!D`Q>P)a=Xn1rCEJ7g)6CZ#xO-R8cX{2VN(ywLZ`R54d7rPb;mJsam0_D|~ zm2^~a2xDAL>s2s_NEX{g&Ss4OwT-Ak86e<6q2bXPRxpGJPwd@V^-gu=R_;ODev?mdS^IN&I$tJlQx_jc9nYr#XJrujNz7x* z@LM6*U=XKJOgt_bl^T~Wb_oU|GV+#yO9_Os@~WcB>T($EgG&&g$Zfmc-qj5QclWpV z4h$zlA<+DZ$xAP%W~OHV6v!*+;^G1k1pdx#Z3k!GdMnZ|1KGD zav(bw`;7+M-Lq0%;mdn9pt0Q56pr(Na z3KvK3Qr5j)LlNvfI{Rr9Wts17VK2_9J2BsNja{Uv73(GIqv47a2~Y@f3Klo@43D-8 zjKaJ?3!q}X-cK|4Je08EN^mc4$4f?t`+^P+Zr_7ZiH57mJHtKP(T}Oa zViK@?@aT9S-z%Y6@sJ=T9*u&+VnGo-1qLvPNWk1!3vwxH>X3j#hy={NFfgQMV5~=S zlFyn8;sP}H?4Rzz83@IVzcWID%&lDYlI|9Hv^cmAeNmWxj@JdR{HE(X z0YY33?a4V+Xv3MR4$6Jvbv8q7RkL`=(bup0)-6g}PO43}Mk9z+anBh99s`c43M5<;hw5kEBNP+KrC zIJMjwVpcJ`zLr&ctEq9=;dSZ)Y;oz+{HqIHa-a+%eu<1-xi5MNn9f0D&@(4{Bg0u# z9N?Yh*-DoP+&y0G{rBPhSa$g=b}Nil4+(yWE407AG9ZD(;`c$^WPjxNF}wY}Ma_}{ zL*Ej$_>AWHIS0v;%=#@uPH2jJe5E73!shE;6g}#=LZ;iPddiLQLVR@|PhpO#)x8aF z$=q9ybp=-jX+5hOo%XOJ_*&(IF~mXnihRY|_E7dG84qq<&@l%$I1G)3U%PV5!41EB zMF408B*FMou&KIne{yi=Lla8N&z4n`kbK?0(O+gVZZcUA3-HnNf&5FrSaPFT52|ca5e0kW1JtyX0Ua$b--J? zTA`SvAt9D}cBzLHf(s(go6m_@mL0UZ@zwC>#p& zJi#7%H`x}geKGw87(^rxFU~J1D}jS6s{ou4V@|^Z?#33NBiGv52oS9GNym{YtU4e& z;#hW6Fczy2UU4}fq$0P=H`Q$%!3 zs4q4+F5aIs;N}7S966es?Qtj_L#M%HN{vQhvv>=; z3*KMaO#=2#X9V2Oa)wuVZ9iggi|RS2zH=1oD(TMW=^Gq!11aQ1#UB(J9m9(f08zps zBE2vvsb_F>aWG23sI>e7IF3F(CpWpU9D|~Nh%c+Ck3m+${Rs{2&aTZbT08nWr5;k# zOXc;CyGYvhjJCa;)iRzMahsW2Qqg^*KDNB71O{z_%phBz_F&gDvrS?T5gAgTwK*`$ z=E)2ZZ8@eN4u?ldz3u)S1ZL$F<>%*{Lrm2e)#`SPc_rxvj{GJF0*k!%hmv@Wu#@J> z@=U_&(URvf$|5-L6MjhU@g^l)eG(VAx45XDDz)|XOBg@@4c}VL3pa{z0)qKL)XPIE zQ*SkkW1v+ubyH@#@y1#lV;vP6+ErHfI3%r{*XPTg(=W*h#BRK4su-GkPkY*dkHY^a zyyw~Bz2)B95Q#{}YLRyl7(VVI_MR=%;nd5qrAMq)JmcS`lZS2QVAg{B?ksj*F+xe_A>n#Sp?GZIH-2ntT*SQpNv`?Ysv`0)|hVKln!Xt30C= z-{?J>SPTrxoQ_!xwd`GPd6w6sebn$JR(HQSyj5jmX_rz@ey)%Eqx1Oiuq4MFHw5B+&veA7 zOOSm7OWE}Ic60)3>1i)9E!E|TtHSh&%4!d4x-9QK?y0W%ijy#V^)2CU*(+A}iaXFj z5xa4YAHz|bCO+bR-pV2lfNd7K5~$> zlx=)#=Tb*sHlOZjapw8Xk=qMdPx=Q$Lw;rhqo%(D7&0gF3cYh=6ecN|5qF865}uHl zk{go-%A~v+l!y1l6~c;3%4&R&kRt8cW*5gmc$FBKucg=0nw}g^rPAFuZfG3mHKGFR zc{zVuGhyIivDnHvPm9w2$NAD}1IK%qLj?PHpL13GmpB8H3m@lPbDfwj9#B zwr_evS*yarab;#hZk*+Y@-r1CW0rBWI+_jdEhe9U(DH7QWj|K`IP zFVMt=h7$v;Uk>8z!bj~6Ov>}R=XbAr7^Sa`zwkBl^1kG68Dbt7BobyHX&R0ej;2F~ zVX#86@ga#x0x7X{=^1=kvAKD?1<^&t=Sm~X2wW8j&ei<2Y4r^kn*6I;&$Rn?cCq$& z^!1+}bQ>OF8hh>pnVI06as)6M>>y&Y`X2mYZ5;+)+S4MJpJ|aw=XYur1o2W z-j1ez+SM-01*TCY?MjLR7|vKS>wg0=PRm)z_~)x3si;3+4G9!R9lsg^j~W5ORm9qb zY2rxTL#tRsNC*I>T?rx=et2_o6L>YG_7xB~r5@AleEZ+N8uCcvfsh>@(ool4+1eW0 z&DaL->W2+=5RvK=ZYGmNY|4KVsXnq|A&j|##J>K5at39}!v;fdbSXGwDZ*%JjsAgD z|NZZf>Nw3$Bjt%v*01WrJ}<tb34^i0as+DqHZINEHaP_MxU-f?jF%DsV z{w9kN#$xgT+vx z&B2}1Xwb`18w|!3EQJMh2cHK+u6|iUovxZ0@)G?w+Z+mUx6EShvxk~HDv4|5prmiT zSPExUwmKK9S6B1y&uxzSM_4gT{do=3yl+OK)@Y4^yn6ACmU>&Rm&D zxjZUn@1W3f^E0czdOXzIew^uO^WxL)*PD(b;$~!3ed-?_zD{tEHV~m?cY&!ifMTM^ z{bvM?H`KE_?}p&iH(j?*Eo`j5d?KJ)aqwXKd$EzaL33U=SNu%z< z%i!vfn#rWo3~>=6@44z4Z?w)R*Pg;FrfE2;riEVv5ffm4pMc;17?>*@q8Cnl{U?SN z76FW!;^RLZX!?2plXDmJEVCf=EBm!3t#NL8?5Y zC4JQKYG4o%R#o_j8q(3*0n52HbPnjyUxvaa;8noB#^6ZK?84iD(du!*m4$ahE31N2 z?`GCUH@3!iZmn+|ZXA63F?{qBG}sMcaX8!VMT!f|1(^a>HZySYquooE3rUjCsA>-0 z@To5ylHL2xKC#DQsnav3X0|_ExG|X%VW3`6%w!S%&cFNcTyO@rx@wlAp}+-h-m{vS zmk2a|TX!jBliaJAtMB1+;!HUW-j3UQ33wLn_<1mUv8da+p9#I~@5sgkle0l;qLc%i z?!xZ5KE^7U$Da`p#iZupJQL`iGUwvb6f+{u=*7G!%THI)=SnKlsxNnIbcsyTh;6GY z&}(I2qN=$}xYp0pHNwyoHfc08-z;!Cd@#M!g1dzBCHouS$I>tmuqE_afD-Z*y#Mpp z=O4dlC?p*gkpcQR00S$(gp`ADUzR>wzT6SQEQ~+POcIFyCb#|$T$3<}1GuJ0Ah#~2 z6#v*;oj>#OdDLN0o{RLIqRj0tk`{*T`-bxjoMpmB_xQ=+yfX2h64Zpl?oMd2Fx`DI zH98gd)yC}6@HEp1TFZiIqfc3P4gO5{)zjh+aj$1!IK(2^j zP9n^XINxo3KEm$0^P4#Z+T#R@QjT-b6TFZJ$%Vv1~@84Ystx{T{x)x|Rc8-lE&t__%lG6X&mk-I%@JozR=0o}%~M zdb=U564?CW+hi+%pX`69!n4V865FPk73L*U z*2OsPr$3>Ukk$++1-acY^b_i;8gcxb8$TRpy7M1V3hS zGS&9mr>?(CdMIiWvU^HnzqDONf1|G2^OXH-4BfYy#dD>EC5x{VHyw8sFNGT{eQ`;C zy(P!qdzD%f@7^zH2~_5P4VZ>OZe&u&O@i57l|TBi$REas4(7SBJOqSkc%Ddpg)NJl zg!r_pU8>AL+g=NZ<367%Fl>FxoB9E6EEDCI?f&s3_so(QtYY zxk7$+t{;JbKS#i2!-Sq+3@e6ZWW{h1>at5>gKsu8o(~)u4Qz-58%%nm1IFgSKCewx z3zp77-@S)&4X&-P`D|=Az~bwN;2&Z8%f5)c#q%UOc>tW2>$n}6bbMO9^`C^_y(=cx_5tJa7te3g@<0q*lsbt5W zSfS)+lqScVsicN`Ivy(Dp#Z6Ee-%?c38!?ol@;?lV>} zQdIQWAX(Y5Jc3X`_>G*B(yLc;&ckTA3&ikcB^mnmS#T0@|Hk-Fl7*8|fye>lr`j!$ zif<4uHy!HGkyEC56hLB14e@IW6!z3WwC%^MC08J((Gq%CV)Y{gLcH zE3Nr$tS2=hpO#bbKVNtM`#f5!`pv-X(QlEgO62!)}j9^)cbI`=^)~-UlUz6;aCw| zNbgc}@PDy@0z8-48dCXRK9}ePg+|_vW{!@F!$^?m@iM6YPq?|m|5{@fL4Ckk|JWN* P;d}NUjNv~j+4cVeYV>^S literal 0 HcmV?d00001 diff --git a/doc/iterators/ellipse_iterator_preview.gif b/doc/iterators/ellipse_iterator_preview.gif new file mode 100644 index 0000000000000000000000000000000000000000..18908ac7b3ac3f3bcc9c499b5e08d4e3eacb3e7a GIT binary patch literal 12485 zcmb_?by$>J_x3Zy5JQ77AS&IR!w3k{DM+Vu_Y5_F(lwNH4Bg!wf;5t%(nrLgM8NTz-?+08LGkc!B_Py4<_Py7$=21~ohDljB0*yc`IpFArU}0unSzi}f zIX^s6aeIvlj+Sb(`$z)^i=+@kj7N(z< zAYElxA`ev(b~q-7b(MnMf%GHcdx(AdLRUTx+7rg=`I*x z?IkEIAaw51Ul(d={l71DcmMlp1oF21KY0JEVT695m%ZR^dxWR2kF7oSa@O;uyxXXQ=JP)`*4I{7mY1GAeX{s?VSa9QX8O_8?QN|s%}tFB^>wv1)m4=hQx;nSCwKO%<)l^lmbSm7Gm%AY=BYhn%1(TEz7ZVi`77`TT=i}w!=HldF zXJchyX1aFu3gcx4dMF+3B^qifN(yo^QW6L;5g`E>9}gD?D-X=4c=&h#IlzZi3asQb z0s!9G{G?iKKWu-d_sohb$>==&hOCy>cM7HfTlp+a11cz0(5OeA77S@dG!1UzL~WB{>MGvKtx33-Kdc8 zP;?9$6&vL2N&t{%l9G5puo1#QJV>&Li!r1HSw%oeW?3z!jFh;#yuPw7GY81)09vzp z9%ScMRCRki?CHxIBdzJGOyx8jn;NZ{D{Y@%UTc_dez?*<|E&Mv@W9{*W@c!=cd2k~ z!DTTW^Je{HWBsSfjjxj>bV-?mCOC`y3bF4tngb3rrS!Sxn8bj`nmUihJqnfFiOxVD zhCh=UvU~sG;T_4fudiTtnCY8J__0{?{-aB*U8*T+| zgNKAJcP9VjW9Z;DEy;G#$VhDCH)-q{zkP7!`*wY!LpOuL<-D3TwWsh|Mj|Q(ZH<>; z4!&3!`nSCQQljmauclAmmrjSF$@{XG8*(X)aKqA9Yo7blIJj8Xy?gSCJM^Jn_Ukk2FHDbk zYo00XS=De|X?tG5Uyb1FBwToP(9-Tew-?62p8dA#Sok`n?G6|0xyD}ZmU_>#(c*QTpJ;{xas*nTAd|rwy@`WF&4#`QUs3!` zHP1Q^S{fZD4!A*Vo1r*2PBcG($f}wJ=j0*tgO>!U`C1yZ=ceD5>Ns9^tIe*F<`t$E zv;tNXu7!SlE_ppdY1I2WpPZ{+ZNAuAp<#_h`=YGJ?I(3ftIs=$uQZ9C&ExR_0f5Qb z6**Bo-N)jzqg;ESQVp|xzwUCI%P*d6(z~{8q9E>aJ0%|rM0X1`-GKQW?mwB?%{1Fb zc^4~6t$cL4aW5Lnr6Ro(J(5!1+A9H{@U{ucbNRX?>KQud= z7(IEI>v8pM>@cY5uNIBC4A zbCk@dGS!^MQH9Sa?iI0x*)_pFt_Fzstf3<=1G{Dy=-GmBqM+;6e%B(O#t#B!Bez7& zKVzko-w@E?RN-9{2lAM37GhpBy%GqAUD7O2Ma#U3Cs%5o)P*ahK{oBU6#^$Ii5gsK zf|z+!0wJ2H) z7sJLF-{A4Lh8F(t3Hv_$e0*=b;#*Xjpz-E92p-!++(E7Bftr57VS@kaQal%L+oFtP z1dB|&PN8T^@eNKeuvM=Y4H74#1fghGb_k0I=B<_$+4<#idCqQv8cFYKsTO>NRS>1Sqrg|$1 z_EsWkU3Rs+h|@`vj`pPnvwve6HigO=NmIWHO{?6;HC@QdP4YhGS^)*)dz zqgrpnjl$MM_iG|Zo@q1|sWfOVcvxH1s4C>9ZIrZivYi>QdfmHDkqGC?HzSR|eE+&Y zGt1|=?jWAFfIYL_K`@m*KCJa1e)=zyX$Pl)_FA= zd8+F*C$UzdEv|fME9%?1!j76>poa{jGX=M8HRJ_RjTeL*!Fe2akS)a?gS;wMmx+zPthu+SGw3tkj+v~oY z^?NNVpxe!(WLprS4tZ-?41`)nhi2tHS)=cwS@{0u4B_gskRbv07+l5+^4A6W@w?)2 zqZ_ouwXR&^MOA*;c(2r$tLv?(513m3MZ6&srBj{r_+yB>NmR=7rkizP2QSocG}OEI zOlkYxm2rdembOf{0DPy!H(TnD4Bk>TP0Q8^7VsMl6Z@@JP3J?0cA@Spr#YCM51oz3 zX&d#&c{Mv!qLcMAcCsJC-$_vQF;mZoF6E>uBpuy<9>{T5k|Vbkdb|8|-uB)D<5n?C zfYuE09wneZZLX}Zp!Mk?{Riie;o-M>7+qk-gz;8LiFzWGcsr`aKHy5LFaCF~{hPT) zPtvxQDLdtz%R(PL-Ecqkzqbdz#H#z6#_BZK;_T|g&IkXHG+NaeU16tkvXE^Dq%w34 z-vtLZV_WZvYJbR0guxod1s2m-XQ@?F!5|)&z}~o^qV?&X*ylR}cTly@HLR+JwO^Q7 z+!~%yk82kUQ;MSbi`S+f*ZBrk?*3qIyC!(h$x_}_|HPi6ea5hj zcX<>J{xKk*?5|!H=Y$*MHj>VVlG~KoAlW{cvg~{}p z{Pu$Gtdff^dOIq?ed-&<;jBL|N3rL@aHGp!m<6gS-+gk@%mYF|zzt$S+wYhUl5M`TWZXs+`+%WV0f+p6RFqa67_(m!X+>4e}KWrqJO zOHfRvuTTs={fPrCoHAn!nXT-^uHaWF;+Q=jO7KwT*`oCoJsYlQ8I~>pR}R1x0=iQ| zEVrdu3}t2%tXaV}+}ZfM2pUM26*T%TmCy}05tMqgt)eY}TNEBNAFjC^sT~WTN>N|+ zBDbIDqY#90P>E9sTjdGV)d+w7DoJfvv?gH`-nO>IvS$*LuU2$a5S{5Un+|1+4mGE@ zOEl#T1b`cA!n{NS9+bCMRtPL{2+wBZrGl7capt5%-6U{*n{}r?g(zkb5C{kiyF`OT zm=o++Fzy5mv(n%{jNRLgb^N3_K6WOGQWX<0kOEhQ`P=y~cqs~~`0CjEmdE;br35Io z#$V2e%d&NXFU2jS#I#xod~PjFEjTp(%a_`fV0@&;%(u@?~G@vE`KF4!Y>mmRb?OG48-V=}t(WQs)?D9-w`D z!h}GIK$H#@KA$qE0zb@7{?Nrx(H^?WZkFMk^u{UYMtE{TVDbnjB9P9b(~w zA#>1>nJ=z$hB_IS@}3apb&n*hpBQb#szr?EjduAC9_P)f5W{vec6|KVQ8&`id@$0{yb-8{167+kK5`s~m~LTVsOy<#HMt}Q*;&~KSDQ|=UFZRB4A zQtoZKTkMp|OBdt2b9U3>*a1~dLn0)t)_gxCHY@aIOeB;Qdf&T3<&rl?_DkbiKy@}j zOg2GQO3I3-vnpYCgbDt3bY!(Bw8s;5XuGRiLc>#%$Zf0jl!0d|g6S?p9RPG$!_T2_C&ozM~K<7S`e&aUwkn%5JTm}H76|0oKjB<@zmYz1J($N7p* zbA~G2cVWq0MrT3!>NTUGNC#U~xq47_V7{qHaT@+Dtx*P?xRg!?+Y}nL8Y?gQcmmRu z+}NIw2$hg{lo3+Ax@Xt*{#Unt`cTa=gZ1p{86(Uc;u!0id{p!mu5n_29{oUg#?cCw zF@1eFZGI@Ko-?Q3y)*yRsQmdZW~--iV!pDTGVM5!7gJMy&{O|>qV_Pp()dz=v%2~H zGO^~&M!M!k@@x$8W5Dify{%LuffHspLawIC`TJhQ{EJMQrNRiVEVCn90;Qs$?)wD9 zI*yC_D^H0+=v&AxWye=FoO0JD1afegW^?Cehl7+qibbI(ZA-W`xBM918n)#!-+J-b zL%qeLYWIv@%mWZ|U2wu^(=>*b_J4YTVmN!LM8_x@?@jE!BCerohHUIaRg%of=ZmM6$xK zIlfIP>|3R(T9=n;XD63Ir5`}`t$-%ah;B_vc{DDZw-U9~{0%RQ^0ZL!HtLF6826gP z!(u6m))wc?EWhqsolJF4onR4n~t@h0s${J}^(xK%OW6+n736_A?i4>XEw2RlMV9W}L`r+4W z*Yh~STM1s)sn5)pex}Q%8&!F;!clJ62SypME8I z@-;V)csNmY_+4%{Al;0Y*Tmm9M6^CswmhhtYYAdZf3P!=hQ>72q+_Hj;VY>L=(9kwQZ-{UHJjQ}%JYndJuACxy+f+R5*fibQ>XuO$+=G7B zbZt7lCAWVC(~pmvj#EUvS|YPrX0cikvRakDTGPK;x3St#zp78M)*`dkX0g^0 zveuQq*3-Y%x3MD_avsOuk}*ih z2qFpWEll#$XUIv~7@|M{wDEN%pm_(nr(?r|_}QQ*t$|b*0uzo64E@i*$ejl!|6uP| zyRVEkMZ2hGcBjnsalE|Eb4PGZXMRlIAD%|kvdBUkL2r`sOb{T4XUx@rcCNBcL6w&f z{)0IRYm^RP$6|IpH;O;?+o)Xz9xVf0e!s=Tt0EaO)|AJH=HQgu6wLMlf)%Y>oa8uS z<)oXjw;c*?WhP>*q9<-H!oT@INMaqwanm_@7)N_H;v(T{ch{&kunAo^@ zbOIwu*oBy7W7miLbV~kEjpJ7j^PZfO@d$$P(PP!Hv~)E_=~?O#E6n_{Oz#8B1UXea zT**>*BaJN*&0K`;t1#Ml{7oA`>?TA5?;o!$uo=V*kYK$EI#he+f_r;nruRAc7)nCG zw?$ny^b*G73LnbD8);o{M9kMQ2*tW^QK`O)pit$=o4x#`n^3$co`C5qhQ(-|M|t=GMH zn=ef7tlCh(I^a{N>V2V3CdRb+87hA!>EMO8_PJgZcF|2kWr<`6!^tfQ1mRV*PpVe3 z21yJCk5eU{6rc$R#)E-uLvE1JfhB{YW8+K-$iWIRcBv+$j@h{;fMYOmp)MaUFDSj- z*I*1^AW#3}E`ngN+VG(Y5M$tH?jsd|3hf2?yGG z>7-yos<3>in2>v@Uf_+wDpWf@AE?ms{yBF zdeYE`9(MqSAb(_75CFNb?7t8gghlg9FO&`^rEo(G;dDLEEw}ZxZ3@<%9c~vjG`NT# zd$|()+{Y=Q!pENRj-<(VGsHWversf*qd|GX*5flzCZ>_{!sJ@&zL#_ z`8E4CFII_;<{fx1IH8TTY4CHWKKRXXJ?>|7uB2D5Ve$+x#od9!NDkz~v4DZ{_Km&4 z%?P9GZHy1u5>!PS(sigrif<*47d|gCce0|yh0AI zhU(7!vh+q+a}6k|?oLCOaH&gaJH&TL81m>5DI|9qLJBNAnv?>Ym`seX0#Sc-F0o(m z$sV}z7Xw03iu-k+IJU#j*0-fp=6y@zPLLUGLOJ5^1r-kanQGhHdgxJJmM3nDP(Q0|M&qr4 zp>J^IOOGb`7bOb5Nym|a>xe=W=-jrtmMl@DhzlAZGeCW8;wiQ|2P|NV5vD5 zm>cJ*)Gy-nZGFx34a`a?b263Pt+xHZIv9lM>(E?-)t&G$?K}29^${%=5)Tri)p5e5 zNW2X!*A1o2$kJX2jtUm5`Oi%~`J3<==dL@PNp`zAHG z&J-?&IAsFnBWie|&`Zi39X_LZw-mUzEFhTaXTC+Ns~pbC2NGk*fl9e*>yT?44-XPZ z<56?-BTRjrh`<`x$iSpP3D$)diWaoH5sP5mr15x4iyRDR=0|shpgK2>KMV7@e zw<|m7vXt<^j=r4_sJr7V$_EF*WCY~5+bqW(U|h==-HD0kDnSHm>l2ufFRR+cc zu+V5yW#+3vH+Vjv&}?00+GrG|_;|{||MWD~)hmx7-@$#1=$r~Rx%%|kW)$lD3~rCi*IT)k;MIle-PQ^4i5w?+&X z82*=p^2IJk@soIodF;tj`)Lw=Wt@P5%}y$_%of9CRwF>qDa5n(DSnRU-F8fo7tCCm z1p6J}sS~z8yxmHfctJEG0A;LboFAGu4x?0R`^BC1%AV!F4Bk`)LnzqJbI7Joi1gY= z(|vz3&JJ1u!dFD35A5D!BT`5@Jd8!&m>Hd^yWnzBG*qzg^sxW|JkP&GBjO}^IML48 zboS)RAXYS}*^vBW0R=PS2hg6Pl%;P($*>aA$zbk~bX@lNIzv=DAaA2uHc|Eavc~`*^IEvf86h?wh zBpLx#lY~~4$h#}n>f?(MH(7$f?>n1gFL2=Yw_$m#Ah~8|%x3p(QBXLd8G^GP!QHC^Uoyl zJ)GoLD4N^qt3((=gSQCd?RNFGw+1%%lYDM2jnh0i7BG`8oMx)RixPcR=Ldr3s57-H z7jXs67fs810W|dWUpQGAsiLR3(^Ww?`scZunb>^Dfuf=J*S`g$h(k$(AXMOhSX2UO zU=%8fJS73FO`UX+3%Q?1$gdK)pJTtqIM-ijCfl2Bq=W5B6+7gPCx<5Se3AnOI!5>X7ZoYrnB)71u{yO%J zv03O^1#?B+$s#*;mUo6H1=h&>Kuybv96&*zxJtWz=^}T*fFX8Q5@UCeP!xU;R4a`6N2XB?SFpgw!GN}gC?W5j+#=SB%w~9xbxNj z=R#5ryM+GFlRfgUO?qCv`Dj}epoJUUTsgdgtK8i^<@tF1-`|q5*lPMh?=GMJa>94Uw$oypPHUy56C~_WNGmy{nBU zYeLy`J8h^$4**CEh&XbX*Z@ZJ$(kPRUs&&7(#QU980JD4G7K&auhv5CRgI9xccoj5vTSL4;oy(=!t z8Vs=etrKBhpv6$3Da=UF&L0FE&z~?xda0^x4kUf-Ibwvxh=wRGN|i>s(Le;a05W++ zViAQQT#>Nwqyk1Gq>GTTyzy;gQ#A^Sl_r#?35?LF5DoIvH5kOKCD;NYeDs`_FId@lhdMHj1QLoBLawTWBKwQIJeGq6U%(5Sz?x!LuMK)}<6KRN zQ&AYI`@`zi%C-{`ET!Q2D_eFcsyT%^8`Uz+>J#oiUuQ}^$uDcxQ76ZPNC{(a<8|-) zvj70;U41+kDW$X+P*S`!o=6%dq983hM;tFIJ-V=@ln<}GA~Un5maV?2F@`*@wT+;E z05b4ks2|cRo&cVl1g2(YrpGQ83je~zEx--S{ki%{&3DUH*BMlx12;l%vfI(8SAY_n zd^*Awns&?{wXO7Y)enc}B#XTQ(V`=Ka?E+?cog*2@pWp^7s6!mw>6j$jIO4RpxdH(2E9d0;}-WohdJ$ukhpO|6#G%{}ZW}p+CPGfthm;xYKe*3gZ zd=M}40zw!Tq1I0+Zu?E7%+H&wQfiFj7KPn@hdj&Nxa)HhX-@HXXK)ku<}dVjhDuni zVQ`fmhqv>6c#O1q_}>^OjYU;Hhry*ZU-L4I9{7+EJR1TD$`VHA^TA%ezh>*ffI|h2 zHV8m*$D@cqq(C?<@H#ppG5LO~WN>Ckc1oTEo<_*sq@vssR#Jt8Mien=t%Qps!m+!n z8`&la05Rl4FaI4K306s2Po_yKM08lzKO501S?04~W z6~+pbCvX>=5T(BZ6mt1rpLt`!{lA`hQ^yvm|MAS*`H}GR4!$c`yK(LPm%h7m@6Vea zzxq{ofLJuPvEy+yIn^RQ4cpnt$<4#$7Zes1mz0*3S5#J2*VIyH)HOCWx3spkcXW1j z_w@Gl4?Gw&yKhQNH7tA~9u|Mc1Dh==E~K-j@f+WhPPE2ZbaT@=V!Ruwo((v=%~1Dk z9k=)L-kGxYVk9dr)7^CjkwkMM)$?(np{}-T6F%Kb7qZ3eZ=-sL-G^ACmirE0vI#hn z5AoD$?z*U3I6bO~k!bX`k&bD7-T-}(Zv5S+K{2{WgvzY?N|CRS9sJ7c!=e!hlF*o; zL1SZ=m!C?D1KPwhqRlO>|MOfx{XQ3h&x4-9Z0>UV+3bl_G89$}13i*wE7%UWL-jaJ zW@*w!EE(?w5b-)*x$G!b`g?fv=52aChbnERIUYxp z$4TK8CuyqoSl>CQXV*p=^!*`3ZjGy9si}as6M_>%sylCe9m)_Ig(Qv@p^d>E)j7Z+ z5#^Q_in~yj%K<@vAXc^kynvrsXWTRR?YaqYm?!M6?_nHJ(_Y z^8rB-t$-QXG^Wr6*}YL@Et4aq{?wFan1nNF4Jyj%BkrObkki z_@aWmoxyl2VL^__+y+A$C&JL+-EKdwrB!Cd8LeGScI z)#jAV`p?;9h_wv)X<0<5Pp&rYo#9>qxf+-H3|m1#Acq_e95|XNkY7)J!KOjXSQ%RE zO9&&IP-t{;f|C|pNXvg=#|nu1t9RIRp?CN{UrnL-4@6%ewr$(CZQHhO+nMLi@7;ZO_m4gIo^$*3IbHa& z>RVOaUG@1bCc?(9_Xzq3+JFqg^Ug|@Ni_qG7?zgo79Qde5ef$r>k}C092(&3=&WmN z1q1?hY%J;M=#Y?*{-z0m@Y2GH3WEHy!VCa9a8M8skiSK$QnCa>dX9R3pIp4Iwt5B@ zMvesfMkZ#~+(b7WJwya%hTKFd%u;kxwt_~cW}@!)MhfoIiU#f$2JD7JygUS4t{kpb zwpK=tdIYXkmevj&uG~a=hBo>}9DmdQ6w?wB{ENiVf}4o{p9+G1bPC$o8xb%A7-O68TSEe{F8qQ5l&Lo-7T5q?$?dU{qSI#vcc7B+f%HbxwSp?Zx*ad{x1%;T{{)<=4+QCuJ+Q8`Fdd>do{ZC$@|0^$t zpuLfvqm8|yjg95MBS6;F#?i*X)W()TP=SSjTuRTt%=(`KihnxjKl~LkvNv-!G8D15 zu_E|a3v-zLFBXUh{J%W^4_?FnpH`#&YYgo_;qgDh<=;hrWALBke+B>F%zq6ZBkR9o z#{Tc%00sW}`uuo*dwqF+dVILQyS=%-y1Y0)J3To*Iy~6l+uhmT+T2)QTU}XRT3nc) zo1K}Snw%IP8yy)Q8XV~F>+R|8>g;H5Yi((6YHX;ltF5W7s;nq4D=jH5DlEv)%gxEo z%FIYlOHD~mN=%54i;annii`*k3k?Yl3Jmb~^Y!ue^7L?bb9Hfca&)k_v$e6dva~Qa zGc_?bGBnWF)78<|($r8_Q&mw`QdE$ala-N{l9Uh^6a6hBEF>tv&&SKd&Be*V&c@2Z z%*4n*Pe%)&p{AmwASWaJMM6wONPv%r`x6Hn3lrl9`gb%`lyAsLhzRg-urSb2kPzTt zf2SD2HwZ`w5M&VQzq1X&tN$eAs56t7aRS*>)QxN`5=t#y?IWXzm4x=&em?A*3`O4n@M zymore+*^aCo0?l%+uA!iySjUN`}zk4hlWQ+$Hpfnr}Pov=jIm{mzGyn*VZ>Sx3+h7 z_x2ACkB(1H&(1IQ5Y#Vk@9rNSpPpY{-`+QF;1Ll(z~O$1*5>m2!68v1q}uNF1|y*h zM2_kb2?t_;s!xu_9*BhF1KGoWhQ$?*B@hedD`HmRgG199jAybZ6#9dcAd|0-HI&R` zp<|tXianA^Cqda9Q;##9$`(t;xDQe=5GuvVGg9J~C0I=7s@K?GhA$aTP|s=4Yf3DT zg2qF{;(2nSg04ouT}DS<#QAB*IUk`;X2gSP^}6u?Ia1}b?Hl+B?xC4kccAUJdW{Z{v#w?=qs&RN9x`3gKv6gl4653z$jduFE_2m+Dh8BU=u0vqS zRc&QUYRh~6;-ilh4`|Q^$+l(%8J(Doeo?ogEPlTQjn9XIC$z&4ZXAd&`c6oi>jOC! zyyZunRI(RZLI{)TpN80y7GTk4vK?;|#6^G-gMsWElt}$SaB0(%d#EdL%bk8ln_$R=f zLO2X?NKumOEiRX-Fu6uj)S~8oSaCRqSuW6kr)Uux${|ir>2|N4R-I9gSyo6_r=DMN z24 zn>cO?7bwRviO1HsE;!cjxM>9enrC%_pk!L~JP}RecIB^M5Oq7APo%bj6=%6I{iEGrhw?E}|FC-8UI;o=*EkW1GZO1e(4Q2th# zlR?9mA@C@j7#dwpBWLT)BS(gbZ3QIhr?5K7FIzs)S`0oA(7FkpkE;d@IuJ0J-RqAV zh+7`Mt3eDMPS63I8qcc^j9Jdx*^6n;$65HE&U+X(UXZ6v;+(ICtsMaO>mGEC*IO^E zjQ8t70dL3C3Wf~l{q;w+_t#Yivd?GtM7P&h8>jDiZg0C}pNZn9xNgmN%t}a(TfbC& zT?oS0mfW>Te?shCG&q>lKDk*b=Z;(mDmH;{`mttYn;Nia&HceevIHUWzED}ceWR|m zer%b#NMf)2Kb~iUXd`7{sLyk%v z#0FZ;g=;15H5Vq=lgr;lsAuLQFTn^g70*Rl1RCJ1jSf+x(u)~rYGM_Uk8rf3ggHYT z;@7c>VrtLDY6g9g^5 zM*O^Cv1AdMVA-S$YC`&Cqycl?+N8DlLWaZUabE7-CQgPvNiR2%L1>!Jed=l;RY0-;WELLXHPU7{ zD)dj*RfYj9wI1A-280sz_Ncau(7Rd2B`e%dR?iK&Q`^^U7u|bHHy%Ln+?UK2wdbNA zzQs#BZ;BGU8*MT!jZgSi7VvzV^DNCRMLRYpAw4V0$gQUfRp#&nd=u8TjKV-U#WOya z)Df}YtW@W)uJZov*U~R!-hHS?sSjE?fiD)CIJBU2E(M)IONHtBX}OJ`mPy^71ui~ zFB{IevX5J4*C(8SpZKG)DDX|oqzyeA&^Td@dyQ#k*d&%P&Ajn?K-mE^6$-T07qMb+ zNbU2UK98Ew*CxZf>vNAJPtmZ}r+lxOPS!KC9`mImY*B0qm z9ZQ{XtaUUKHH4jADjob!dmj&~r4cdhrs4Wy z>kB~bL@f;wN&ItTeAzii4(`IAcw-Mirmd<1%-*!3b02i(sP_nn_+YzZwZU}rTqhX) z5S+wSNrwN_=7V&rh?coCs`;AC9bJ)qBX)QeyuNUQ{nVpYT}*|{AsTW`8r6_~FmC2P z8L;of@AtK{AI#Qvk^S9=OnFP0tbHm7(FJpS>lB%y^VrruJ_9!U!tsNJ>2Qq;!0Oh_d01KcAcO4yxn7q5m zdEL>Bj5+676L$~QqmO2AcODR%Jn7HknT=TW_z=Q#k;URVOmp=TUZM6y2-3E9vGwB8 z(Xnfn)3}#YWj@i1)EgPmDH>W0)>Co zbnSqVp~0cX0giRSmZz?UZ1&hFfsU_%pmm;nv+ltufp)DS9z!F{0gI#JfzT zdrpHwL?f=q!#7iv|A@xyx`ywhM$W?crjN!fzeb0Ck1-A+ya*Ngh7|{^5QnrD(oP=z zKoZK!7wQET$!8Rq>K|wOJ09II9^5T9044V2RPN~1;>6Vop)4A!EE1wE3Wq`!u;$9u zlE4!dgLei_AVye~DnM=~KLN~;7mo(3A9`P;Au_+U8S!lZO^ZWIHyBM8yYnr2OM~%qtOLy;W=rIr^~{6xdUnw`a#4SGQ9p;)*jZ4&W>xQn z_1;?Wc^XmQa>+bR@qTRa9(v2%6!iMU$b3lgIz{uEgXLPq@?KZ-8gSD9h6J{ZFj&9o z4E_f2x_S=$)(v{d?jp;HzR!jT(7R#>0$$fB$4!zjLXv1xvfb2Ds$bk_&r%QA;-Dzg zk}%Q`!oRhSfeVkNLA)tP9p*^nt?c*gSp*ah#+xwPVi=ynC{u?4kcg};dl_{Iwp!*Y36 z3S_VaMZ>|x-SfV^=R+A3YPbJ}NJepGC#UW$Y?qcv>;11_%a&GNRSwbyXMhsUP zrC!wXTq2w9?6{tqP+qK+UKVo>EG;T8vlTB7GcN#Hw+AbC3&Jjz8jmjyFUu4!Bxo-& zH!s!RtKJc>vcrhjhC@9R2S3IRWBG1M9Gt#gRD(WR z6C`JFIh3wBk4@KHBcY6;N>n?nQo|^l7lc-EN92Jup8ecb__U^jvQb$#hxsv9XXZ{% z*7^;J3fwF%ndvO0B+Wlx&dh|7t-cI{lJi&UL%pD@7WIW`5LiPrVM8(2w_@W4-U@t1 zc+yoP6T?H#oS}^Ax2zsCVD{cf*5*Lw;#%XY39mF~lRS>kQJI&r2G3|2@9J;wrL-nh zkEW%DrX|MaskX+>u;w0OE)WuLa|!NArFweb{H^wu{q>gF^A?rm^3<2|QuDI*_o`*_ zB;Sk5lJ!pl!4SZN(Z@ z1r=>@<1G~$t#of?c^mCTA1$w@9eCIs(I5HAZ<@O2?Ku@4O*ow`5v_v}u{{&k!yO&1 zADuNGZT%8$U}5cm-1b?{&f1BNgeMHh`Puxr$!XD1_ktfKpFBI0!d?A@b#^P=sGv#ao;^J7D_(V`o6vKMNz z8d|caexe(^6Abca->pU;5WW|0vd2HEkFvH8ezR}eqn~`Umryf}BopkVyq_SmAC7w9 zsiT^PI&p8p^8hEFU2@SW)y z$RWm`)iRo0oLr$9gkF;HEnkf4hMt`Fzq1#_GIijyjB#2H#(cCkvWz5#Z(6bpH-=Zt zhPO*H6*xz9HAbq9vi8qLG&_cm-3G~Q>xnb!hgG!d-Ei&0_=F?G1gXZX#l{5T$Hwx; z>c_@}UIT8;fnyn&0nf=}R;}Ua8g<`03V&48VWrnyHr3@()?-u@u{lsjO)Ber#&KIF z#%+dRV*2B}YLOiKai#bXh5C|)PW}g<<|Y~*R4HZ3;sR!?OQF?*=2I*uH8&2$lQo{29XVm$B7q;gd) zVWwpp=h2+acbjcAbAJDvIqRJLgAkGxG3&QFA@nx!qkOiit?ZF&`uTG1-%{8#4u_p4d@uUSUix!3Y}0;^dxso5J2=`BsLoy-|#t$7ZqMMA3u z9vUZ2OW?eI$h`QLvyb^4Ec>i{ms{xag38n!>e%e5=8Tlr;%DZfh}Qy@R&2&bg}&6h zp_Chb)FKznf`rt9_0{48)RGbRisWT3P1QK<*P^i2iUs0=74EWe*TR+M3Q5R{zt^gY zWw=>ZRRH2@P}XXK*NUIjsypIx^3|#V?uuMj>;l{(W>yAvR=y?Tx?9&0xyl;*)mqus zT1M0=F7CP$+-yVIc=zj4nt_xx&$iG97jDyCCwv#D$SMr!xYYF906Nhf6I%W4bk z&#px0j^9Twlc1gws9wFMcEgK@)Sj*@;Xa;6U9o}(d9)c7(nJ_aD(!Y1%#VWx>Tqft zEoJ~7Xt4>~c5RVVo?d50R+Crv+i)-1$h=z1q64p(_i*dL;RNicfv0zW*r+zuQ5#zG zyTRy^!O`z)E>&-J-R?tu>y{Jt?R(|12DhnI$*CoTsg6$HG>VhvFkh$b_%*H*cO>mu zs1sxu9WJ@a1*J(m=P}aIbyDk7KdeQP-cerwA#tmJy%`JhYG4e)cfp7=K5(+UH zDh>p!_Byld8Y~tBKI$5KdVb(KQDOLM39ubMWxA(*a{#yj$-YX3x`o)ghV8|;0DzqE zT!Ek8JbFh;1>b<*Tv_t$f&y>vrf+MpuQJ4LA>wX1;%?Dwt`?{7CQGkC$?xEEc2nAR zSF-nj)pvK4*Ync%;BmLt**E08H>Oti52H7fId{~^odBKtRqco8(FZbK;JsMQH(1~` z2XEvjV&FY@5Q@x{Bvzq9r?Zme*3;A@r_UWX?W2^>x9jR#IpjNSnWrh~I2B|aHT(-f z@B9+4M5diP2A#jJehEf4-(-+)bZMU~Y~~cbLTq$0?2rrU0bqh(_X|?bdcdt1-e5eP zTbY<=s+|`RqwQyxxEH7z5Tcy7xSQ9X-j5EhH>xq0 zf-{}MJGVT@u`E4zjWaKGJ`Xo|7*NO`{xaL3T`#;nS1mhNZ8zN=$e)=pFFiW%T|MtB zwD+ENpNTmyuvuSIRnL6DPqQ492z;=pp0|XZrKFjUzMIRQoQEIp!1rt9KLul-6FHyL z$e@za;z>kGD$Ea16-H*_4?+q~Mj9@-f@(zVZWT6&3uGB@kK{Qzv}B35fjtDMsg8Ia zk|ogLiGYlC$}7rBbeoi`$aSMgZ42iOuW+ry`whG5328Ap$D;Ym=N?3SrByQM6 zeP1k^QWEetXsvCAQ;-MR1zuObGVY~yp)EIlazy&^?F)rL0I9VHP3=JZ!M>vyLWt$| z4#)nYCBl^LH582|SE=4yjoX)qBQY};D!VTpN(OiKk375k)deAp{F6M_!DuE2D`47_ z{oX(Uj6H*)sJ!miVv>Bxbz6+azv|USl<%X{8}{3Ed)a4-oxObB&nwl)(8N_4#ygP+L*Ua;g62crsQ&o3fS3 zp1wQKRY2~Y_3nJx*ksZo?fs-Tcx08snuFKnv3cv{2n1&HcDmnvy#aGAE-PfZAy7JN8a_#x^m;%+J!5+j=sjopkmBfMIS_dRYxyDF3~c$4ZF*w__NX^+ z1+WYX;|5Wrs8IsH$vn~se^*hA8$tA5@D)W=cbsFyv^xAYf)g-#_nR=nGnyMEBk*2~ zqTmu`l%@#*bc|$4eO`>ZhpSKQW zeRmz)#tClbN)IK?Nn9VJDzAKpt*Fd4=Pr-x29u~<9~&2^O0%yCcY+WQ+9i*S*Uxs_ zDC_Sc+A6Bqa;f!2=5gPaz^16E)h#)DE1sR_bYdNE-oN&5$1B|?TRaK*;+j15HUD|6 z&%q(vs|?}IcpRhit6G@NcC^NVkxKY&as=wptDL5b3*D{C9jNuWnBe_9tyLx+Rtxih!U+5}rq6nKG?hj3vsfM&jH6}*whYK_T< z4Hp~2pqaN9-&zmT_D${A1wJY*IRzL{oh}5kF$b!=GywmaAk-H#AEM?J22I>9awa?l zt>Y+}X1_L65rG(@BsCV(d?Z+)q5*B( z8Mvu>ZpH=J9t$J?r0!*0;v1(dbrAXVeB1)Uf+I0al^QkVH3Q^2brF}^4>1!Fg`^=v z<9BZnu{9a7r{izSbqu{4I9MT#Z$u%zfJ_-%;vRLIXzw zE;RY?PH2^$(=BV0NK%zO@QB755n3ZfJ}Hd4oJPflO07FvF?agO1kxAYcNr&2jW1hK;Mx4Y7L`*QnZB{eHxV|g4D%ap}-ri=VZPG_6@u18qDP5URr1f8=>*0O;?_U zn!n^Z2J<|=okvHy#VGD2dbeAM89)a-Wwq*j-@u<=1-PV;A~1!v5L|m>cg$EZdoI*e zWqGjlBZtF=Y|#CkY$^Az5fwu58@CWnTA9B09-3EbfI*#%tbDhI5Brb|LEdqhsCc%I z2#MN$Zfv131p)?xUN{{YWbe`CquO9|KYb`~T4xNS17ckW&y+OUe`HKMWEf~dvcIsC zKYra+k_ll;;3MV=FH3*S%(d&xb7!5& zoscmz^gWxjcA1*qw6irMy|k*BcF%0L?(wfaG+%Uqkv8}4Qt-a1y=tBN;`cAEbh}w< z{JB!H={z{Wb6fcB|9EEo6%RWBIz_zwlojK)-K6c@pW^+ZSkqts68tm{#EY!)ak&hT z`}-+p5;(iI6VZG_&wHveXzbiZG zzA5qX1a7zh-wgV5z8*S7_gT*rxSlF_->CY33V~fUq#-x*;YIeL2=zY}@YRX;A!M@u z5F*5w6u=w|LW<-hYvd>Y>?c<2CGqSgfFOIR5MYGhXF}kkHf(>6=)dIbl{Ig!Tj1*{ z?I2=m+dLR3)?j6J{NXPORdU8J;K^t8P{$+L!w(_UZaWzMA!yY$An@Ke!7fPoy;D@E z7$`f^!B5SSa&(F8CYx-*~~uWy%B97@~3@^Xa;`WC9_ImA9G z%;)YOq%w~<{!ka*eO?vHq`iHuTcBes@s&Xw6~ zprazhIat(wxF295o#4Z^qLQr)j1%?2LiKWonJjgn)Cw74Yoo1g%@Kyf6RD!0U}MA& z^wE>hbP7L7e_{nY=Ct+Ur0NMmMW&@DW@Ii>rf6cO7K$MzjAaz^W_Xt7Qj2GOjsZ#K zMRPpUiZjI`Pd)()XbOe09mR8Ee? zPa5P&j!0r{2oY>DjdL&!buCUcK29wNm0?v%?Rie_SWew*NFH8F^bbm&1WIitN^DS0 zoiI(U2u-anPBV~8;kUB-^Y|@;$Fq~n2lm=cV&fEv~ zJWNU-J5IfFP2U<$9S6>UG);pF%e-I8bTG)Y5X?MEPQP^K92v@j{F?oYl!a3e#a5Jk zQk42qlz!Qqg+r7Ehm=7HDxF)T|Fk5fifEG_6w!0w!*9&|iW5;H#-?qDE{SN?_LNg> ztS_9vMz>=90Xd*9G&fY5w|qH@p(VRT$9`uhL}nyEE-R0?RM2iV`gSPusy^Nvirp8M zqkxlz%hu<(kO@%wsmGK~IM{3{vA_VSFuvBp+9i^gHrLIV<&Y|+dMA>nI#NY|mtfnt z-N%#=%fyl};-!fv;n7&fHnL&XAhLlg1Q{l9wIEm&#`kN4p9WUE=r>Rz3r{RdalI{D zq$oUaQ@$piuD-r>+Me$7O$Mo=u*yJ5wF%@nold<<=Cpklz5;;tAoFNWHZ@P~rXcx* zt*j=sghWh?-Jyg-Ja?8@P2^OeELEc&3(z)NyYFBQ8gQPHDF6JoQ6E+mpU-FC^$V!EksFeZgI_R zYuQ+sKRHT0FG#jbi<(D3&1`+m+(_MZY(ZjgsoZMSscX5&iqfiTrINd(Du}L%TfJtg zsP-wLPD`V{YBh;lqi|~Zx^n~aVqF(;9amPpJ8C1uX+1P(y{D?KY)hlfXk)umtpZ)G zMQeG;YBTwlifL1=!KkoWi)KV|x+GG~}uWhr8O5l-41Q#$uJyx)b#rvo`Xh z=4RDaB8}#3kd_L!)+vqp#nsvo!%pAS#-P;fNup^ zC$$c3tvfiSHdM5WLc0AFwKD>_*S)pd%DoG@yn_rFLo3z;!<)C(%wn!kl%0Z+M9kre zXbdQ9_+8cLj-W4P1WTmN#4D^H3$iasyyVBUpAouW^i7}Qd4%X1hSNizT6tg0XkUVP z2?B9}o|%rHb({{t5{ zSuukjz?dj0R-z#05sN8;v_NHnBP>!M+j%%ydI-c5gb1ZzlyYVPK@yx1ZVE2Qu$dR3 zJ8IGyWX6>r?u$DxZ5PJrI&dX7;)cloo*bxt3@)2kphn87b&aFl4bCSWFKI}v#kU(8 zL8np=nyO(OlaNDjg>O{c?O<`7&T|9MNT*EOC4iU~Czk zU$ADZ#jIzcVPb#1i{7;xXmMhzz2;baVs30g{AnWZf8r3l`s{RKgLGOE)b1YL>-DT* z_I&ck!4z$Am805p`*7tZ}Yru)5PtIJnf5-=Zi3Si`HWc zIa2u=JPZ1+lfmT6p=iNj=iCXrvvDNLQRR!uW4;Bzikq|9lJVIj68DI<)nf43%yxev zo>dpXsxsO#iqyLL+Hx-0ykq-vQQ2~rhigC@e{0yRxB6-f&+-&-v7da>_T&1H^y3YrDdZPJy8PB@P*$OzltT*$+rXI;^=h^y%#bhJ;`pNm?4a(~N+U6Eu zei?0bEpoG?Yy&2dyEI#OFqE(T0Zk_KFRs8uEy)VU+gaR?XGW zwH7Cd>dxU5UT_$K27V8@MpROI3{Tjwoz56zO`)0&R=h!97=5v#^|#}tzUY^}z?8lK zu7TjuLiO$4t=K)@vp)WC81c>`fy*KxuRg^Hj9d~Ul}iId_L;YX!V@AV8a`@y`dGyBjQGc(2z{nJn79|Fu$ZD0ID zy1`wVfpdZ}M?-f#vIOlM(GS4ciAQ1bN70>YI$m1_VN#|bEA!7msgp-IA1itcGRfbL zQaO(DDz|YY&^pWH+1n~>#g@_7Pw&bnDj22O(6>rtrUJP&3=WITF#KXQCN>Q&z5d*(-9K5l~D>_$Frz}sqDJcuwq zx0BtYO;}=j-X~^0eQrDlXF4NnKF54ImTF#RYCK_QZsvY}EVOtvDBrHfxVMzt&hX}n zv=~r1e2pc1O|gDJjDO_;y^dTwC&d12@CujMSf2gqJUbawqxG&G`BLCMNY{Tb5jrYF zcGQO#(OVWS7kmaP78H17KNhT$Y6TiZSv<_f5kBym%3^@Q@P*Hr+b9XyU1F6;RH1Y&&N%)u=@l+CXvWOPd?vL<(y+{HFYo%kn#KF-@QPM-(j^HD1ER zF=P9t5yAR33n3t91Ue9mJBJqG+k4N?eh@reJOMvlJw5#WjD4-0g1uZrf_$xCT89}q zL^>wNxS+q)|WllF|s z%P@}&f_{&1PY;MJLC;If&f_mAjjj^YZD4M(ZEP_7O)c&)9Wfp)O`XhMBXkVCzMx5C z4e~VF{BGF5XF{&gTfP2J)D-4I7`wIpFcnH`#nHQQUO%GW>4dJf;;}Il+}e$$ccJ3= z^j4FFYxM^bznHZyN#-5~W-$1<14+ylOU1&;jkY5h9{UyG<)|c!WRv=qDpWJ7C(Vcp z1Z!9-{Hl~6$=ChhpY^mjSg409HPgbA2wkomTG?ptJ>O&^oRltqA)|j?hOX*9E=dqZqnL_m9 zixD(L4yt?5b)Yyhp6$xU;;38Jxm;uW+Dcegv+7&!_60I*mZCQ~6`PxMI(QJZ-`tKr z3Kd3xR$8Rbi!&qewD=p|+Mk0VDM*u9e^gqUSa&^`hF)-eQomYs-KXhOb)D;(S8)S3 zs!rB?7tu{u{Pvh(w7d_SNQuIp&Q^9pNjaW&!{D@2^*nIy7YW_biB|Ok*~VG(ltF?^ ziDF-h$PL5h^k51+^3jEem8g;4h~xML*ncIF|4=Kk;n;pX^ftx~J2YWOF)-%@K!lSrjFLSU)r``kP4{Kls@mJumuN z51$*No6qi(XqwKI6{;EEJ71~wEKYTE;Xv&j2x|5pBcf^&hR=!MRO3~?x%S!v1w#rF+3R-Z+aSBEZsYiflNd6-wB+LW-D41}?W-ojK1z4t* z%X<^QoFqZYDv56vWo~p)6xNzYewD>q^Vk;kvKn}!Q-V#3Y>R>mv4qQ}7oL+HXrI=Pn+!aky97=duKQ;y-tOfim%%^R?It}DbF@D9 z9ok>1x!ezXHSXY<+Mu|vC0}}@Q!C3GR`guw2U zViBf@3E&K1GEx3i2mU?kiEhfqg_Fz|!m_7(P}$P;JzdtX{{a+UgFF}mC?Fe*s_2i5 z4lZN**EE0Pd6$xNEK)QHkrJueD7v|dihL|=$EKVO2uz7%mUN%CxKNVy2T?P%2e3Xqr zJ|fzZ_!mm47`gL(gsmYiq41lKm~&ks)n&o21kh1@Z+i!}%RH((SMjYPhPZ-9UBHTp zgrWdLY$e1mB0Y==Cc3!jk;z`%pf-t9^n~PvO(jB~ws9;dMy~0_Vwes$KN9u&w1Gn- zW*l~@$D)OVmB?b&8L=tZcl(TIgcHmZwRp91hlJ+KBkV6RNq4A6VA||=lbypcY5#7y z+*3nx{3kIUN$-d3h(;ndWHIqb^~e0R%TtnsHQ4|j#X^*%Qyz-)*=Nv%0&GWe7NxiO zC~wDNtf3+aX7Tyd@qkQkrV|de@u|$>xNy>_Ln%9Tg)GvhBq2l!$vt*y)pG?y;tw@E zOM2#ls!QXJ*1`G4bB5~o{)!kFbsFh9rP3_)N)Ck!)irnJ2C%6rfdGqNp2~1#dy~}) z9oXUu=5?V_;dr1PA?3q~VxCwm*z>+4rawC9o%o!UPd-wZkTxntwU_mymjsNiP9bvQ z>)aOJsZn0%kX@g2aZfmC%x};EPPNYR4cyR{J9Zn^tXx0WQe^4IbpYJo;tvdNTTOFv9d$+*MYr(kCo^SR2q3p_U zvM#5K5Gn^Swg+frDK0t0e+-lL+yQ6B zREGQm7v$ii_i(Aw4`o~%jNhW0JV{k+5NgX$kFYQ;bSqWx1*M6FO~B@J~*(P2?dF+1se~1btod-7Z|d>(~V9ePq?A9h|^p~j!C+pM^0+Zjbs(r=)wS``{x-1N>Q&F_E*)WzzWE7f; zZ1wk&)a1khR>U*u6!-ap;-+MkD07N(_2I(lr;@tJV_tA|E|&%LQuHiyuAKK3$K|Gm z7t0IdgZH(*<42U@$sT42jpf8Yc2!+o77QNh`s2sU4S8Bu);b=`Yt~L?I#zr36*Oxd z%lb7_UN)O;I6QUMFD;O`*1jVl{5|yBIPe?q+$bY`4@HK(IS}YIA5E5d1po5Xjt;OkXYJglD*@UaT(#ZzVylH+{FxO8;<#7pCjXWbZY%JTcZ7#D(KlQRx>@4hEn4-_G~es zRMk3+x8dKH3~NGrgESepiF+&9YFbjY&cE?Yo|)A;AIr(4(Bbmy@k{eNSF6%*Wrj|1 zftn`MH5IfwWuZ#+itt7;d)sK_~n+KLiWVTPf3Rgv|SXtl4Gt^Sz1yWqvn$P7_K!XtNV3m^ts8 z`d&VpBo^w{mEj0lbzV^5P>C!7Ml$BU7oq3dZhGY27d--Aa~O{IZ=64QArM5^%D6wx z^VaC{;E#1KN%DHjX38$}*3EDWV8nj_rS%BYb@8$D7L@Y(Y6+@h^@<4daJT1);qswH zAPB*BlQr|Pvh}d#^-0@D36b=OruR@tvxuMZDed)Nt@6pM#i@C+9)!b?E+GLA}S;zI(@wlngVEweaL=YieN(5LVcR;h`*g6qdz8U_P$08uBu3cK|#hdw-Wy&h|_ICHxJqIm%wcD}?QAvr1mPkerzTn+{5 zc*&OmC$=H4{sEu*p|EiQhd2qk{UMq49(Ocx%$)XnRsn7MKK;0XxOahwdm$Q>;dg%$ z&(S?mXFXh=L$P#N4$?x&epoIbDltiZ2s7Rx;vBKfDv4lxVVIWA)f9{n-Ug>E34!=7 zh`%gPCo#A=fvoi}%zF$|Ld)P2>@qr`}$g~Mcjyu!blUfY>9qdh-rE8nB;OU;_7NGwDe>Lc;SpHn$v+LuHVs!Vjp#1rYc8c3f(=tX_2w`QEia7;Hx1h- z_a`!ouQ!eUQ>w~Q7S(+UpL`g(O`ZTK3uY;c12aoDr-<_&jdm}K$1{uNIf#v>NVz`^ zwWbJaHcLD=jUy$`oIaWKBj+urNOL|*_oj#vILiqyVOPV&zsXxnM zFpn9eNaral5HL>zuA4ETmS+T0BdUL!&q|ultLu@9{+J6UpBEjUSNyoBpQfx*r=StA zXjm>U`g53nU)D%j(QI8&BW*zjXHjfFlE`9|zf4|DITFsYwBw28DnF6YQ2=sCc^iptQd|*OZa1t;usm(uy*Ea>l zKkbcQ+gmvS{6npFS&0Z!h48Hk9+L)^;0l_l1jE_y@9D@zk*Y;$nkD6`C2g8zpl=;HuSVnziJrwd}vytdU%rjpnM2Zko;Es?BMdt>vmMX&P|PtnF)>o#(2Z zKQy~g)w@W5y&u(kcz}J<>U{v(#blC3T((~peGDjBkC$>xEU_jqr=&)4ge?W&VpIoW! z!*=pSB>n{*R!4_w@!DpU=hyiMI?O{0{p@CEkL`%-@h|8wo{wl0lAle0Q^Y^eVYQez zt4zIwptOIW!xf-G?WaS0-m#7uOGuink(NT2CLJY%luv@322j z_j7R6AkZic3&(e3zQYq!1`7Ni?!G!K%YECHkB(13T1up)1(8-zly0O1q#Fc8N|~?AL>! zNv@xH5#E@Y--EEg0?Pw5Irlh&|Sboc8HX5V*VhLwVYMt$f!a?TMbPr+lwHaeKP7`86`^hJt|Lv zh0$;pTD3iW)rtL7ip_N`t?rS(tlZjWoKj=LtRbP-;Ex;kIkpsMn}8*Q(3b-dbh z{Sg{RZ_W{sGJVbo{Adi?5w#Is-6dB{P~8AW)mq67Kde>VJ;@GHLyy$&Owp6l(oMrF zDyLmThoRP5(T7>?g{E)tv`3N_r;fC;KUZN1nkg^5{`0`c_!&zwCvoL^|q5*@PA9 zM%x7)=*BquF{j^m#}R&>=tP68ZDPWqdv)-%P1l9J zFKD-mhvf`&^n7L_bEqdrCg>?=d+~EA7F(5eNLOnkO-MIOCwA`b=Hl-XAEqk3i5#6U zWhB0goX8`(4#LmJhw)Zo!bf-;nIC&Tl5ctkjSK(59Ri;LCKOWMuFowG9F%&SU7dVf z+wFpkTstfhtEtIunaKZO|uNr zQ>#22qGOMFI7}-z{qQr50uk#7m7WUgD5Z4_>lm4b*vUB1o1RP;GA>0`on&KJVMZ5cojEXul!w}lL;$EkYI!bTrK{%)e}3EdqQS*ZL?8t9>uiw zsXn_puu}cVd^9^-{YmPWVUhh+^qaaXb6nBF#MYX<_;MaJby@#jmY!deUF8bq@I1 z9wm|7$`BL~9)#%`GI6`oxh5$2nZ%A9^HH{Q1a;jpCKKyx?Grc~6=G49#a3 zWY$FHo^-)yGy@@>EUA@88Ir!4vT4GfGnI}r6?!t|_GN_JElUz!YwIcCa>}`eu_ov~ z*Hc2PlyfdEiGM?(r<}!6i#d!PhE`6?bQmeGL8%c@iglNh>JVn!U??Bpgdtm~k-IsJA!_I}J!n!M*X?a~3p6E6j$4+moK*idqkpgl?@eWL z!wzY2)#n}C)2g{!dDd+rGY65U)oWsTwxeA$CzYo)d%k%eRz+qnCQfV5dh+Z~yJo*$ zj0%gh`k}!PMuX4-*%ADtZ{My~gS#8pfTsEa_8%Txqdy*8_RSpZKCe?LA1Xgm7IE!z z>4b~0K90^ezk78oQRDjyl9P34F+}w*uuMct2ajw%$YP~*`^~H4u8NUT#Z0O1l!-Fe zC~+^ut7Ek$G>;?0HvV zBtfmnuPTINt;OdoU$-s2i}&P#jl1^XCyBhZZcX#GTY2iItTFgWMnYNdi^I72%23ei zo>)A}wQe+A=*A}76|0drKpT~sD$TDs@UEL?(V9iCtvtWC$eN5>@>ulpaBs0IPNJ^% z%jMbO=4@YG-SssTJoVhQ1MH0lcWurY{RQ>B3znSTyepng`n(&V<=VVEi5vBT2YHy@ zf+uxq`hpi->Dq!fQ!DkN&%+VDMPK%n^hH1JleI;EUikY<0sJ`nOM!xvz=JFLXniSI z^2Pn-5Lr3>SWEDr%v?+Kd9<;X6kx#nEEx)icReLSCv!bD+Hzw(E&k?% zYd{y6GO>|qRznk-o!_gZn!`HawJBA(v$2_14^O+5-;86pRnShEwN=>tXmjhjsQ>$e zOJ9I|WV>BDWhs(W%Hz1XUA`1%xKpu~nzd88Rl2!Twbx3!TYWTQxLb3!lC@iVb+Wlz z2ZcblR}YJ8wAX+Ld}f=lmH4Mk=seXhFz5mrp~={Xr2D9MP6r=Q!syaf-wwGz^_%_n;BKGJIv_Bd z&AH&3oXw*i3KXECjn;@RvKVoHUXbCD40Quv#%=WA(sUoW=GcE4WkwJ}~_9gV)Z{&Kboi~v`s zyVrMSFXJ+yJsy@L?J16P#zW(_*TVx|9q2ysuvCH#$ZjqUINkB^Z0!xGwtLPbVD%tN zDprgaJuZ^Z=7(h09^yReaTRr*AJj^Jh)>z$CfGDzJEO@#?3Vz=3r|A&t(!~Zp8UP$n}N$b9-lqxe>Of zfI)BwuXg}oZln{W9QGtOJQ^@J5(jLdGP6)4(g1TKq71_v)RNpHz}yI}qP{Gzwz zA*Z6LwY%qCdsb)f(6D)b{NU$_N!ih`@u~R*_L-2m#kF;^W#h(;-M!+ntvCB8r&vce zjcR9K*Dp@WF9pz5cquwBu$2Y3QJme;$%K8@OcS4bVlx^H^E)I6Fn3*Z)^qR`CU*p( zp?^>wrz1xQCwLJX?I}&s6~&;p!5!Fe3c|zIR%*ufF z`E2R)=Y%rOwA35_`~#|3Wz*VV`h#fk9^1x^k?hw^FX-PtTAwK8TkP$zVSCe4`%x2> zp}Ks3u|1gfb#HaWTj}OFOg{z{rsEBVJk8TAJFeNCnPVq3e=BaAs+GPWu{>3V%M;Vt zCM(*Hk0&q8_a@7dK7K2h<=)qtHz$<8D42$~5g`Rrut|&ZpB7A?Bl)BNZFG*LKuwZ6 zNkP2-ykNEpLV=M(&k>=iGm(S@(7r6JkeQ}(q>%*kS?H3zYpqx%v70!jB639aN=xu7 z_WZqIzMxr84v{nX%YylRLSe@y+01@E@_;sn#UYJ4UTVrKORw|-dGn`&x%5ZD+%6e= z+NlK;%+2kxIXBv!f1zN?KJdWvu1`gec5b*sqU_b!d9h)NJ?XS(n%lh<>D;vV{Hme( z+Hz~Zjl`Yqpq)J2=%9l-E&HI8u1qw$m7$I9u>0Yt(P0n!YW86-_vzMQ-x@RcsGlF# z_@5Tc?c-6kp9|*i6Uuw_546}!Lp@}|W5_vHYRbnL?C!U3BtAEg__iSb8=cbcu4aCn zP4V|%mFj*^e36@puj#JO^eypANJ1N1vALG;(PVYsL0rv3az+zW?oRXV$@=6@?pg;; zOuAj4sG3V#*Z{6(Rt^ew_NZP8PEsx&fU6mozmSjpC!s*e;BWw%xEJ$0$~5hHoJ2wj zkoZ}A879SM>V;L+DdkT}4eOrdi00L_cf4yd>h|+}+``q?`FTXTyFs;gkaKu+ZvN4D z?^NZ&+B)k}e_#JJ$Lz-85&l;H%3A=MAUO3shd(9|3_y5jtPCwo({4KZM0^{yUQe(f z(Z_tdT&%dgU=hLR?3&b;P-yUVYw#|y5nadNA_)GQtJxt%Pt-%>g{g`KUPowp=SqH% zgmd$4L|Gc_&SG^bFmkL0I}NG6SEyJ~Sc8`UpLDV^n}SMa$re&9vz1*AzFgB-sqTnd zfQaV~LY3&=%1fY#&DNRntSvJsILl+WPK)2mZ!~JE=Qy)<$i~Z9{3SGzrP@;ofhIJ& zV#TUTwnmF-S@=CFPht1dS)!a(dMu&=H-TJl-5DGMw$LsXE=A zYx2G;QCod}xHgpay05n8^7P;8l-ydCU0szu<_$ZI|D{gJmT2c+?3BDx=YwBc{#B>s z#(O82$LkrCKXytq zdQNUI!J!$kH=v2lobr{-&D`pfKRP91q56XM6-6VVPKGYN>!Mx*DC1&0QIQJsqHm70AH8pq3X&4NQHtl%Yr2nRz3;U*XB>1nwa8`)jB%Jn&I z43}HQqb8Tz<*T`uJJqKquDkUJj8}WjxNolZ+o|%dZgxuH6JyAFDJf^1<9VIV{o2_R zHD_8LPip7qn#miH^ZZ!`PiAqq?A-LbUk5hs`3HSGhIC5TP~dnd1i^Y}{5=Om(fIo( zX+LyIL5=oQO(YEu*_luuc{-*+Ct#7@C}Pw=5laT8{-THh){Lsim^A*E4Tj&X8S}vI zfHfnIb8GVL3?okAzPNArYRFp1x~O@TKt6^SJz&jv^qlsKm+Ov|vZx#cU-kMD<@`m( zLHwO9#G3KLV<#~mVLu@k55SsH&Wk5NtF)}?X&r#C;x(|hqW1N54Gq`!unklUex91HFK(Hrm|0r39ep%D zU$(NnqqD}kQ8KxEa>}#MyRcbub`52`Ci8&tWsL(OrW;;FVtkr2GMTXGVgP2dCmxH* zyuh32R)3Of8`+RWsbiH8n5ah7^)&;8Rz8oco`%^iX(~X|xST3m?wm5Ye8l zjTc*Q*Q?c^xW7s?Z5T;;Rkk)=y<*-17KET{n6=&aH{Om*aI#%>SFASAC zbDVe%r8_j(L3)-rfcNFj-0tmwJ)UYCbHv^(D>nO@_ituqyV7tz*4k+u?{4~seysZ_ z_2moI+%-7}RWF_xjyOFYABka2?ar;o)c3Hr#eN$1BA`Lv#yxDWbPX_VDW20?#)|)V z+!MHOU!fYI5i6kcX+Fl2(#jxLNF~aI89_I?y+`P8$Gu;5FAMrN2h5Ol>l)^u)9(t!&E-*@SD+3t6$kDpAC*(yVaOx5}{5aI^X-a!$I2CkC0U7P-Ni zu@3Qk5~Ci3B5KMDJ!-pGwGcaLnv2Fl`Q{U*gv@?8E^V+`IKd+B0}Y}#cMckFb}v5_ zvEREF-cuLa-e+V#LNK6qzzEi=!=cJpO4>W@VXux9+Bh<#WRrH|t~?0s!&afF4X_T_j)1~Tqh?SA=J z$GvMqd@z)Hcs}U2BKGsRr?lsU2O0OqxW-v~oqb^D7x>fJF(`XoJf6+Z%eFV*RPMPl z`6PgK1)K0E_T1RJ6Hu+%n}{#=+#%zhyCA=}ukk};7HNzp4mFfIXxd=JD6Z(Fnsx1Z z&e|f4+Yo%!{wBV<@1rN0gg@He`lxc>*VHG8aCIyLnxPM9?8t~#Q`&eg_Wd2e$s`Cu z?N4>QXq60QrAeFxMd=S7_*M^--N6(R5yN=!I%}BXFi1$`9R~f_0M=`~jFuO^7(ppo z!}srh>U^FP^dLu8mhKs|2><6G!k_y}pBt3d?{2xt$szxtTW;j40^pXb$OX9N@*P&$ z*YzD;7)I@`?d_lB92u*gt(Y$=p_*EKG_x_hn7_QX zXTG&LxLt|1vVTE;)P7Ptv$su9o;b_w+yjfDEC{Xs$bAlrIrj zUMF58IKFiZa5WzYRDV~TiJcI7f4Ybg_U&+KL#|+b#BB-5EjFMe2Y&J6-E%0^YDi^? zz`W%Inn%l!fb^9pn-k@ph*dE_UpZUvjB;1}kAad~bZh0$zS1$;ItJ(~m#6By@9su1 z{#{?GcC7(Jd0UkT0q5+Q)0@52e-(k#K(XflQv5$c;8Nhh_BPKWH01bnKFLIT>R=h< zp7TeUJOb%Pi*yT7VKk1}P~ArCE?JG^SW|S1clb&YX~>VE^oxPgD@Es-iM&T*WTD!O zT*3y)VnEs;$iO=*>{or|gl48yv2deq^j9{6Ta62Q(RozAV-6kUudL4<>;c*y* zS1kN4f1yhAxq>FRmozud5#^rEJ(QlDha2K}AF#EZm_N7j6`B(P7KbGY0eWm+K^e_5KrM7gJ zP3|Z0XIS}cQe1dt?;Ys5wGallQ0f?|7598WeUzPo^&DKAKOu0-7#|IH#){JIZj@y7 zyC!)T$Ax*Vr}&NjkK?-*6`mXjbUuL~aMvkci=pRSVIy1+Z?ub$nK$s4GjA-Z^PhD5 zf4`Hr6%siDc^FwlNQ^2f#K}7eoSc@Hnw}M(nVn7(Yf+$`mz7(ZQjt-WTwG{Yr&&|k zoKW7}Uej1_(yiXwHjp!f+F3=@*P}o2`txYTT0W|QYPg_cWQjUUU8 zs-%;l%AWJdjNvH?oykx#Ax}b%bvCl^(`$>zFxyBUj-%;GCc*_0Kdh8aXH8p;Ko(WY z1=s-v2s;o;Gn%(j?X>L0YanDT$AyL0;82eUXClVW8s+EUgkbfgKE_+#aTdY&&{oZ~ zYzraF1bZ)KvYTNJ9TxF2M%3oOrP`3z5a+|G$x?yxT^3^cdpoxpl4Y_~>02LajpXZ> ztI$on+xlbX{i!znHuFAvO0QC}z45QjyuszUbsw$1TKBKa{tvPP#P{6*cHrWkT6mH^ z(qFLy6-(ikongOb2N-fo5Mn8y&)|}+A7rK{3ro^ar-uClJMa@7|Bo~859~nQpI}#! z-$LiQ>u_j=G0rSBCWAF>2-i-@zswH&O>O!K?D~s#@dG|iVn31<%1>a|JKxnrrQ_l6 z?7;6}mx=+W0qmdd{M=C7P~M>TKaGHhoPaw&m2+-(XKgY{k^cb`JK4_f?)(=zjCU|n zl*1y$1-8Rjeskxaej)SPl>HGUwh@Pl)i-y3sXO>7jN9#Rm59E%^WW1(wH9<^@?bSdlf)c=;pRc^4 zQM|eyaOcNs7O&LMZ0#Hzs_nKKVHp^noQfY~>7|^fn3!H!b(;0upj%$s-80@wF6)1^ ze|D~NNV}+&dU}LJDClw*)0uMWwsLzu%u_QoA!;MRf&~|kYkqBHy@DhGAJ=Op@gqUz z*G@dtG7IeSh1&RG46kB+G7dmaQ50_(EcjV^V4w}K5SQbf`5cLPq`qd~vqCJahfN)(trc+h1vF@yH; ziRtsoB)!=tkL&n~!199nDiU}rMZ&RyWs{I1;gz8C!XG3ye}!ZHmeW_$0}JgRi6j63 z`(MYgu60=c4aP55UeT?BzU{x2@f*0!>)@{Z&lx{e-MhhRD}TlKeH#JAN7Hb^Go|ZO zqvd{P{BGv7n2zw@&t zuB*4Np8!1YSI0QEwsT;2_DS{*jtP!V&T-BzF0Q_Oh1$5+FFN?p(F&CmNcV&$2wxQq zz}79^cq|4}?FC6~0OA8E>VyEkDwulcinf?}nZ=bMhQvdt=tWm#lgR>IBk$_nI4;*C z3)qL$0SUfd_{WYG8TqN=j(olwhBPl#E3; zK)?Ms70$-W<`wQ?xegp|5n>kO%a~eT4)uKck%g(S#;W@( zFlHF+PM>(Gt@&J7OY4DmoPm8RP69TQ>aGhXVtVLr1phA(pN1o(zf{!yL%J*V@N30T zdT}NcetD1;S5wsdo!|%fs_*Ik3%)AKFCLBBa4l|#@4deZ8lJaP4f$Raj0r7q<{QFx z11VE}1ew76S13cKsn|$t03Sgv=;Pd?H-iM*vhx#P_14L((=4a^pi2vTo%tqTMZgW5 zT7bG0-fwue88T2tDi%5@&Sdvc>Jvwg%kT@S9GA~r>c%c3tY%^^qcl%_?~FaZsgb3I zqJl~R>HPkHzkBpwJg=iiO$j{UX`5vq#Bp0U0gbHXEO1_j#0~%q93gRLc0Th?6J)LKZLn-|dD(bqcA zJk;>HcC==^va2U%vazFTp=GIPZgHh>tz>%U(^m2R>c-}A-Ra@U@$MIbi?a<7VMHFu zlaGk^(XsR-r=Pl?VhDfO>sNkmj@tr?j$k4ycEh>m)9`5@h!fB!Wlg=Z&R?nu9+peg z5|oMQvS-Ta@KI#Z>Wa!U*O<>5XTx6+rs@!XjNNR4~|0$u|4`P#T@FFvW9L!jVtt zbr_SKpAB9XJa5Wm6_CqN%ro?Fb;TBn}onaGW|q?EQ(MS19Xns?@toP_uG=>`IvntS?GRjJ7&n$BHo)v621(Sk`+Io|3@ggMwpuIOWKInvGZ6rR{Q7+u9GQ(^rLv#6As+z57BlG zarW=11><3x>8W6~NiD`4-xej{&U=m`h1_-Xqo!Iw*!lvcfyl@ppM;pJ-=27np_I+h zl>Lg043Vu-A(;ePtbCD_$5!xm0GpA9q6bB}ZX>TSLq-Ux!bW-u)dP&dPJ>kM#Z_@K@2mUNzn;<*J_jY%zR~?3KRG1eLYM^TaL8^UM#P*#AmRbYe~Eh z6~;jbSZeo^BOWIxnSHXfedZeLX4?{&7T2MqT+U=Z>%U=Tsz1rSkX zI~SYzKNC?uW4J#MQGZHy{v8bW1`(xSG@MeL!b@#@5Blb$K?(H)qz5Tfk~QD&fN87# z@3;fThe%aHS;bjHUdP@*+QimU_S+pWp!N96J76Jj8{0d(H|~I40*%M@_d8$>&WM;a z|3d2_ld0TM2qBw*J77XZsXbBbZ#SkOcfjI!oso%zivhApFqlTAvp8cY4Y*$uBMi|N zDij$^ca~(0LXgdWPb%|owH|hNVE<&ye~BLar;ItegWT;s2V)I94>e5Wpaiua#!*Qq zZ4e0*WaFb+D63@MfW9nloXU?d!&T=Z!CuD+z& zrOB_hp}ix#C7?T~t#e?|wm0^(LjTajq~>T*bn(=}qU?;yT=e+T=GOg{*Sk+PwvUc+ z_PGmJQx8wRZl7JnFP`S9H8?oHw{Ga>&p&i=BC$6YG>hi<#AY!Ufl7t+r(PURgh&Ta z9l=D;6UjXt97KGXQa%e6XeA=S!{N!TovAH%AaQCU-)d3QK~CZ^HekwZrILUXd_9cB zSxi%yh#ha>8p*mjlJ}a*6iy^8`*YDz`eP4U8M=wGmj#g#p3bmD<<^>=6o5<3M70C$ zPL4TS{=AcO2G-+lcH>!UZvqkGaBJbEjtIu*KOlfiP!^!qzc(8<#|Mo+5I~|#%WwK% z-dhacZuu=4r9(cCp8tKwEk8QfOyHKE8UY(b_44!=<3pRhqm!Y7vzxoBtB1Fbq?hl% zcgs%@$+zAN;c;VuzYZ$omR}FJcVM7@@N?(z$RHRE*&2CvZq{*r-eUao*lOR#&{ppx z7(A^$8G7Kpvw7aNe*R@=Z{@S6K!94j6Wm=A+9LngO@?ShSDNyD@Sf7^P}{fr;F|D#5{jpK@8R zm_j;4gy+Nv8CEYmounW$8NWFbCx;~=aY^Y|Uo@Y)E$Dcj6=lLwLo=8D_(Ww|_pQ*h zb}44=RCVGBr%x89saoT++qkS?VJ7|-tO_Kp==-3?u82jV_U=#d%e~Q0oLhYy0I5v~ zM}tVYBcEd^k#f@rxr=mD>KuLw2}s%%6y-1eTm zHOE{@s71|fT*4Sg5kZcduX3|N$|2OM{e=$D%pbx%@761!5|1duMs1I)V1zPZn@!`*A zqYBBUom7&b7%k z-$1PgQ-co<4+coK*MJk9bHLNQH4Mki7BI#2{`nOLwV>ZToBJ}>Q$hsEc}H6+EWN4p zeb7S}jB9KLuwnsuo#%w4Y8B${ou{beVjD6QyIS3!a2~Xt>FrXAe>&6CI2;$JW(^Zj zH6c+7xzCq&E5Yk+sZ0iXJYUM=Vf@=!oS974FBT_0r;euSCSAZ>J~d)0#Omq%!ojvV zfp22hAXZUEIbCOYUhpokO#XG9BZy6mws)<#fgbsglRIQzu1g#HV~Zgx%<{W90S&*b zb3!egAS+iK6)Q7C#{>zh)Pjizn}Y_gld!oj1-AQ3o!fS{7f#mP=blRu;V<1aQRyG^vb@t&u+ z*DC1o*SA45Y9IkbOA8PTTye1!!sWVrtT+N?Iuth;kKNG~@o~MH2+0TPd2S3XJPl`( zFexY;TAhS@@Pwsn_gwGj$wIjk%EhZWu|D35N5EH2e=Wf56))vQNbSIj%7`(V97wQm zwh%1z)mj}<#EEGcf&QL;ayUM4uRHccl8Ww(C2^TQ+{8LU~`gz8Y_FfV3FpTIiq`^q8iS8rgS3NFOcyt87im)YG|f2`|5>`aA5Bw+(qLv%=EM96zJSN|6J!Yw$B>ir2^NH%9h>bpXu!4N z$aL2kVU(BI1;Co!|1Tqi)u{E%bYr3IsR|tE`33!V)&F0O5Z6DC5P+7glIVlXOyy=m zU&X}_TDET^gum%bBQDyBmjl6%TDF@b#OdbD&#M1E_OrlKs>^{xE7ZEnKUDvJYT5EF zj*DhNKdJsFHtl^-2-leOzN`Kd5CsGqF(UU|s6`Wy<=Y!^o+d&u4aeWXSaZYc%tv}; zF+VfI&+P)6;VyV~58<6)Gb#SQhoER8MtFNOCFj1UGal*q8T@1Xr-7Q%qElXl9_0i` z2EE>&V8~W}6v;^f01NN0s-s?}Qpd*k`^D_t>;OYjM`VhKh2ifP{q26SWZ-R%XlZA8 z4GYNqVl^MuE`s2m@qEbrVu3ZoXikAz$o=A1Pfk2PK0|&FxnE4__*~1|=drT~aKG5Y zOTmvP>~RPHuowcDo)eRV;(+_b90}SfsM)ER0Knpzo1b3-+%MKBt4pbAY$`6V2mEt8 zV_H)xfF)#?o+QW;a(r6^WC>Yvc&ZFoLe84>D+iX4IoEw4OUUF48%xI*mjtK#xmVE0 z$pH?Ikhz7DE4~fGG5^CC?a4x)42UeUHiq-m z7?)50iN8yM&XD-?tWtWBQjpE>GqQNX*8*s z28Xu-jfQBU$YLuQQO=X6NcRVkI)X&S6J-<4DT2ZneCvILv?#^yJ$eJ(kuikO7t6s7 z{Y720(J$dI0E5u=fm}5Xw_gDUr%j`kzuv9+3&6m8cLDnrWcxqMrSj!;80)K1L-nlC zn6O7mliFlIjEhoGT7Ne#{&4!;P4*kxR2t9=O!Hz-vw+j@mrKCuchhAWU|f^~#>JVy z$-VOEqgY^?7vkyL%{m3fMP{_N1!z?)t{o0lLnv;k*&l-rAy)!5Q+giRy)lrGm!k z*^RsN+aoKvYnz8eJHvaG^WgQPFE}TidmV#qeQ^y4P*D^gN_XR*x$NSY44w8TG@Ide z36aR%h7ovl_gYtrn~iy<)$fb&iuc(Ld8Z8xLSgmlK}uyroeq4q{t!X0+7pTWtvmG8 z_Z>O(A0rACM+_KnMk%UISPTsrO2zR|D;$q}HhS$YwOx7NajZzMFH)>aZp*RM^iH;K z6b=Xk4M#pjfnu=bCN8r6lxts(NeQ<2Y^Ia;DF_6o%wj={uE@NE0gHv%(~VZR+J(va zkyy;uFsF}%*|0R@;+ZyD9!Ih2bYRgYMuGOww%}^duuf}g5lO?>R2v#Hx`c( zd>E#XhjQu{!H9C{Hnv;9g^H3%{Gp z36;X0lu7wUo|Gx67dNu}36vC+H0a6ib^0bK6!*vYcr(k7(!JUNPFa){!0bY-q9GCz z8K6N*`wVc(C$3#<#g*?=t7c8b0Lg0J>PdC2H^4wi+BrD8JaYm#Wv?HyToi#Tk}R4u z_8t;NVuTke&>&@Ig0pgSbMgw)3X1YdO0&uG^Xs_?vnfK`M`Jsc$0z6Ak<$nKmm$-ybd1$# zoDpE4H&4+#8}-n#*1aQ8)JqY*;=?Bh`XzDr-@T?%(o7!+5Y)jLkHIQu&=wA&V9Wgg zFFh?9$!62wbDp%47maQAl@8B@s*m_7Qle;Nz&fi@yk8_}BG5oEQCuH8lm;_vG(~Qp zq#EW2w?~&xNoM8< z%rQkmxNQoU#gLhwxG5_b>V}3m+cWelIIZ-skiL?;Vmo?i?CQ~;8yGads52AeR%0{?6CWrLC*lm&Sy%Ga~OtGwIL#FxuJw z^`-Gg+z2b-H{pyYP`prnAn{+tBOswpYW%%n-(LBxZ-^Mb?GK5^<~vak44LOKgnU_=f!57ZqK5$uINL{kxrpu zs;>B_y4YXzACeCy7lajtY+!A4r{ZKNeK7b8tm?eJewTt>N+Rc_+?Gr8elJ_0L~1%x zdxM!?S=I=%vqtwcH=}w7s%&#JJY>$(!XM|PQvS_CrZ?c-CJ13fgBcB5t1DQRyJOj& zQ13bLYDpqXXNmK0x}+i_L%Z!<)w`xrJ&^F0=B+O^V8k#4rJ#()cu#41b`oh} zSr?27`Te)nw)eJo_m5ELSB4Ic_bx7XzV7cKRrjN*RXV}nh9+z`b$a>{?eux}X#PCE zE$*VWi&Y+Jk?+Ad*bS>9H%UO7nQ1=tg!w0@zX4ZbOEL*>Nb}UwDPg z{dVnM2J;FyOve3DXZ@0{bfUiz6VIKJjZQwyx|tW3E!(pp&aE?ca==nT^Roi+T5FEO z^4_>OUxpgm;|-ZSO^Hmq%f6kN*G_1=X58m)D}88MJjy&5#oN;?qKtQ`m+F_0vC?-R z{6NF<0wQjyzla9PKeFNX>e&808@7JShL^u(!!%lZ53$S4F@@_XQ^&=|9SmW2V+BPG`N+qDh(rA&A zT;-a_AQ(GSmb}>-Cs#_!$}zo(Mk6$YFmUk$=`OOnD9v=Cg&KW6d|a)<)&d8syE(G|qtcnm-7_TNI zM72JSjB;@Pw;bqFAnmL8EWrsyWX};l;Wxic!nUGux!}f`}j%FU%CY3!bD-9t&QSxgHwc z3_oBhP3V$v{43}k5;qD@3Q%~ce;sN`PT%(hB86vxeSs_E z)B1Q*!H_SI#!!))8E6cPmw?7lL7x?946P=C#_-X%#?TxHwV6jB#N9gqY0_Tq?xp?* zKx|0u2oxS-Hz3p?ZbJW&*zg}7;vWld6Vi$g>bC(NynAr4e|WNqfCk3CH2qS43O#}% z=s#Bt1ID0iKHLp&uz|T-=uJJ);P`x9OV&a_N~6vFJQ`mIwyEvtY=H>CY~A#diN31bT)zJ~5*y=4s`{nI(WN>gU)32r=82ku z+G{)H_X(Rx`M^Vrd|P8inFF-icZrA|A*r_SHIT}3Q%lATe6Ya3d@24vsttnq@q7xA zsDCZdK>tG>DsvzhkD+)YsyRRgP$7Wm4hr`C&vs(2)dkW{*!ltzh2Njk-M@mR6owm$ zm)|9U-2sV0I3S_DlVid)wsVAw>>szi!Ks=(Yo#b|XYFL^V&-P@%E9ryp|6#{riU>C z*jp^vCNL=KLk#L$iBI}TelaQ92|j6Y=~}s(nGrd~*)fHp`LU%@mGLsQ4JA?KB8}C7 zwJpMJHBEtCLOmUQ{sV$T{^P!*0+a7&t*2kiyMCUkU!B`nSZ|-$vRr(=?7nY?fGmA% zautGn5l^1apC8}g41-3)U!H%j!37ofF|{O#_j8m(kDDPw4P^;57o30bocwKb5kr{? zX|`h?5JH;muR(oUEVkPYmOyh6ov0JHd16k?1MCmTSie_ua&~?101SV;?lyjw0Y*N6 zV1q8m@RMGYZaC0f5XR^`r=)6t6SK18lWo)0^D=TuNs>|9eO1~*S-2XqD_GR};!{jf#W>pm1Dtn&0ZwJ>#z?+;wVxPQ%hp86 zk02c-R4tU(4_{Ch&}A*bhW&>drx1Pv_=13i5kztWw1K6_74`0j&Pt~!ZG1_xDLBkFPv)|*pa)zM{ zd++c%mgfq)M}P@es?OD^?jE{>lZOKZx*#;@m{oTU5yh)t&Ed;SD3XsCJoT!GB+BiM zA8;t!@44SqD3A5Pi=9ibAwP&$zeOwU@zk589xoA%SxIuytuw`x435j7UlZd=s>0I% zTy#agfEUF2a6ud!YfC;lpR)T4^)*7byoGceLPV({Nw zL{p*b3C8ZbIdvssMT;6ie`)l+AmFbRMn6$% zI$!H663*vT`Hq%kj9_`&xrBUp2WrYO3bsLX1moXD=cTnnBVcVFl1kF&|?p&&> zQgFB~^~SNJVW@Cyu2;N2-0_LI1olhsox{SxLZLy?*#h4h1pI-5g${WB=U+d83IO0m z`XB1kwHlxsl zkp=Oj?6uI>O_nazvFifrld5pj)>bLm%$(v9tvvVg!qVy*^-AMCVOO`PK1B){TcFYrDl;2Kk;ld#5SOLq{2BUrP^m z)|%9J`6;ZXy+QS~MlR5DH%>H<<2FC4PR?2>!&0-WGU0~=FPLUNj> z)8JvYT7{S0Qpq#9IQ6znIN7i!#R&b;&d?#trdP3Ms~bcz@=eoO?@o|cvK%sAvwuXO zMU}QFSo8<@*FR05uiBU(8*1)4bBf zo}QPQ17LAf`7!Ab@*KA;ssbR-3+wzF0P;Mn)wLZU&+U7hA>_Hvuu1_yo~uoYj{xNP z(*^x$fIR13H-wPqqO*32mOKW#;^@0e{T#g>&ev~OS+W( zGaf9S&SI58RFNoQxKj)A+zf@jm(%F1S)i@|%|o;F zpBwwsix2Q~q-t4~tZ=cZ~n;l-QtxgF~cL@YE*K&SA|LPnr*NH2b zb%-qd6s#^3N9{_ZeO{o4heUZtaNDzZY#0!03yZ~<(2l^UHZjl9l+unDDmEnc*jjE6 zmzvxmq~42nn69$QvgZnTnmdePFQELA;51JT%|62%5v*Z4pMgl+-W@Ek`>^pN+-%f^ zy4pNt9L1a7sfM>xIDyaamKrJUYt)P9KYB5b|I8RY^M zt>ft`O6N8oiyP0f_bz>?JFTB!TqA?lCU#wrioavilqMeOElngxQwVsy=RMt{r=@t( z(@LKPeSYUbc(;(W)|(@VqgrKt~|U!Z%CjK4-G zZut980SVq@@$!*T5z%U~I3lV^$yvoYsTjuDMOEn`loch_vKfz>S#$9VYbu*+sXBYQ zwR0$oQzvyk6fo3C5dwNbt=AbllU`%IdK(6;^uvu{wcUoATX)qJy4we|gr3qr z6_Ua+kj#Ho=oLN8&4kC-Jzu*nwm$@au$WQd(vy*ftO$k_drk%>!m^nMzSy8#GyFS*F{Xf*bbwici+U`x4l(ck9iF7C^DcusHAR!?k z2uOFsq`R4P!=$^rySuv^RQ5H!@3kJ+TK9VPdY`@bAMaNfM?^-zuP7lxtR||e!>=W5Xhd&rLvO7^ z>!@tZ=4DC>bBX85*7~n(tYh9vki=L|d8Mtggx!lR*FNOJV?yu}oN& zfBceuecI6Lr~7Z(t(*RT)ozW1{jS|w0sW@k692n)>y_p&?UobtZ3C5V1%h7r0iSkg zfJU%jR7eEyw$Y7?jRB`gB?F@%zEpz@%>2w;U=&1GTv=ESjDqwEt1{|aT1%VKircz- z5;|hKdWVLc`hy2YCZ|lsKoipoiwd(w)l2Ied5zo6n|u2&b~@J%PS0po-p!xi+!9?{ zolv3P!D+s10RwM!l*javJz-R>zSxhha3n|HJz_*B|8!w_qTAt%8^9ch(6y4@fT z^4{G5q= z4QuVeKGlt>Vx3DD3>luKnKI+vWV!yUIiP$@ZVZ;;omr@}|0?w@q53&X9vV3V%0V?- zegF~%Gf!vPDl9@6p^UAs(8)%B1odx&V*!|27(-aXzwZuk$vD0Kuj2mY3!sz2DY{%8 zd<+>{5Atgh|Ks3cyghUt(&XaJLi8Dc4kjF#RX_6~VZ;^$QC;;zU!GevygAdu;}v4R z*aP(6FzuCmUJK%_#1sB;*wJ2DZeb`iL0UYa659a{6q)xwN9~?DmfELhT3l))gu#-)buQ$Da$UG(FhK!W>vm8X7YYy>fqV zHl*H9rR)5`#C%WuFC=l2dLkKA@?`<`fJ_XlexNtwI2{}u0-9vYyE3Cvcp4e^TvgmG z?=*UM0`mZ!(BYiU-xre&Sj;5Y>%T81aA-Qor6Br#nhiG0FE+cU{H2z%mM=aQ7`_l% zc`iAC0TM=9|I;}WC`wj$Cz1?sc83g1*y_H}060 zn%49VeoX#KAjM$kuy86*Z;fcRSV>>HQ1WEbRM|A%jEL+Utf+kVc=1HqtS6;}<(!oq z)wy-X1+GP6%~Cie_0Xv&aidwQNK|_-V6Up{x0w1m0)QMA^=EumV&;~BDHr=%++M;4 z0CG4bIw-zqIRX}Q>*`(8FqZ!zi6r*B*G7dfXe>aPoayzR@~&kYk}j@|%K1}Y{4~8g zROx}X>hW$C4X~I-Vd$CRvut$I%6&<-dYhDqAC31G-oZVUj}!1h!-s{k{G>4fmLC`F zcn*4!h?e6@Cp?@6D*9r6xlkOkPFo<^OJUQNJfV_&N_PTA4OIPhtN)Hf{BP7!V9w`R zIy^SMC7p^Ni3Ei&*{6;xSTk2&czg2eWo?M5u4o+NS6Zxu$f(VkKSgL6_!9n-&#$C5 z!#lvWuaBp6V5GuYDnJe$|! z^7eE!^}*3Z%bmjY=d4}3D?4f2*UW%T3yCyk3QAnBfn(^<@?f;~;`Dbv{e+Fmy1LQzs`@TxNp3QWOm1XqVI0t1g zRgS4LM(8A_ZgBS0wxw3sw1MYg@XUSKv+UW6XD*dSW{nrjyPtoBw;&<3Fl@;^M_Pf$1_oQ|hnj zvKVsC|2MV8KMr|->3USs?g7#M;r}meosoT#a5O%%FEoI2N531LTqcFop=`4=`nkfZ zlj1_d{`l9gF`p%{?~Y;eRf}W9e>0tq(|sUyNzD!-|kcL)OzoPowCkLZ2|`jaJ;wihPN` zMo)I@I^&`-B=~neLs~UJ37J~8{uxZ9{~0fVjw*mNP%XoVZ|mkAD1@v9HVAnsCOvep z2&@K&&IOH(5b4#5dMncVE?R@9_fw3(I6Fc>ZIEyn4JWwSe&VQ=<42%~*hvlBr!Yz(LhUmT6mBp|guc^0xS zd~$=G(M%#=v$->&W#^lC6+WLJMktg>y6wyb!hN8T5%oLixzsW(Wdn0;rVpsy#LPvd zSS&JP72}2lW{-#Kz|SgiSOO7Cas8eAYpOU*j!-BH9~DIiRouhXiLkAF!M>1=v}m~Y zq%5gE=^{RAfbE_;#<~}YgkW8zpIAJ4bbi8y_E^Rlf`!i+S&E4f%XV5H+x3#Ih3ee2 zqpJ_x(9uns>%8BCO_=1{-#rq9&`&c%3O_`>bKo=F4%3J_fY;B$K1!K$Up_jBB8V_d z#dpXy_KefqccNM6Sy?PX>;T&&|9dUpsm8D$+|#toKj0=PssU(X9PjP@bkny z&wQ4uPh5BxsdnlvJI&_>eV5-;7Nac5v;7QS3*Z~_-dGfBLRnQ%914Ee4AfcTTUoRG z;=d&oRvf(JliSF#vkI2?-;<6@3EuZ=(SEVNo;w6vV1h2yf0PI}dWeS(Q}4Zv5BdCz zqz`LY`dk>BlC@Tq?{)38;CxEWRRUg1WBcbjY4L7Dd!{B7RUEg1g3!2O=K3(==bgxg zRt5E|dfsP^ba%*S9^bE2-apK+wP@gtU_F3DZWJwBxVT2}u@*$((jYB3Vk78;AH28hK%R13u93_}DxK4Os92`_%fy~D} zxjn?W?kd5gaIi#Aq$1vxM7#vk()0HA$~&G#g3+@WB&7P36V9S?WwV$%IeNtJ9w}?} zL?LxVHOcsbl@CC4EUhgsWrJZNnm&Os+)?4At%lzwn6>^~8|mk5dhU>T@|Hv=y4VO) zE}k4>fJ9q4pnmrlcR(bX=j)1qo(H4Fa(c?+F4RGrd|Y@G$sB~4cd%x)=gDGVBcvn7 zLe|{!==&sU^qy`c&vY!i7bi;-BLw9ZOBmo7p=9Anwoxt)n+FuMOCpiyluG_;=^1&R zxd(b-N{Z$aaFkl&(m9M{kxSsr11m;EHAl3$WLfa^g>lIzP1Yp(p&WI169TjRQIMK$ zrdVT)VsF^nAXZhKH)IqF5>tbWT$8Bkozp7A*(x-Y-wG_?nTg8K5Xzdq=4*==ykn=I zdR|zGY!MBs2|7{r3#2NRXfYL;?<=j{sxVbuB>DJ*UxQ(XJ3vYGqu##ZG#jZ}Uhrjy z*ur*%r2bL-zq;>i7%9;lk^VPU}l|3Hy)UwT-*OmPU zuC}VE*=MY;PQ$XMChkb9}?e0(cy-$rO?=}Xw4i)hE!O7X_hA4@OQK?1Av zFK>GlL&~CZWH*`K-}c$u9WhlFO0(vS^%H(Qi3|DOC-x&BhnrO@VV<()(@KrXxicp< zxsda2askS~sDI#(5$k%_z9MAxISKW&smgOybiE5?h+FY)CM_egUzr#|?Y7Ga_7 zJ058k)F9brsB3-hESsBdeWh7qbZ0t8Utc|Zv|r{#d`L>kJJs%bSyZ0Z5?^BQrtJqDiZSKsCEHBbUlptHr6DmCc?KJ|)v(Sh(y?{)$B)uOZ($)%CT|c8`O5lUt!c2J35m z&8TX`+_vu+Z`})Iy_?RxKW<0SzgDQiiW(@7YKSXk`#4b!3a@<72AQuk>J?w_r7$ z_$ho}BYC*#QD{1g9d=ImPKqMMBf-!>>cVfV{m91;Iko$d=fU*qd3U4V24Oz(yn6Wg z@UXbJTP@tEb&!m|x9HtBc3M_kvao5ALjmXN+ts4hS1VR*ZnZ6LFF8Ly#C|=icB`>< z+cH3dGdBNl;{HC1%keE54vPEXH^h5U59bOrLVx#=91j{JVX|B_3O>&##)u@6o;f}e znUJJeJJv5p0zAp8Ikd&CLGXuN(7YKnl4?)duVxP4j8gRBi zYC0NY3XBZy>=lEcvWHrpsZve7rRfyt(EN#=h_|DYfUmPBFqF~@6bugl@;@+{fw4vs zXXN`>$+XlsEc9eRV@#4+l#zyvo>Nd!nOhuN6J1(f)zs`!=ilZ8#U@&IIP`0F^^S}x z4jPuk4v)>wrA$RnsLsrFNq^(0{X_i6f9Py+ntG?w;LwjS zRuJltqV?NQngON;(7f>d#pXi=#lLA@{!jp6w_6g0_IxVKHDih&%3bF!1Pl*m*i7bD z^)e8ZU$L}9>SiCx7uPBP#l-cBjtSiiUWtTx2M-Pgy&A%w?BX0XO5H+QnxmH zb>gsT01!PD__&#f=N~K#XPJ4k`1|LTar|y zClH(PacQ78a(yU8=*JIqX}qP8bjfZqxxTmaW7&#{g2B@GGeB3-LTj+^+a%CcWCyy6 zF{40N5!RtSuBvE8*KDzmdp^?x2z@%_Na|Nt>KbYQU`cCnCr5LAQ%_}o?O;Vm*BIOIz+`FPmH zgjy-SaRs6F3D{w4D(_L!7YIG?2UVo!QSyV{2dw~?sM;0iLqn6hM(HI1 zWdWc}>@N;}MA!;nulJ3El3A~03cXMS+a8;zLqP~XYD(WB~Mp2*B-B)GmBVF@I4Pp%DHgSg)D zjwS~pP+RfaJc|vc1%?w=|F3p7cQVuLmq72LY6^;}ZeDHzWTz}!?!R1z)KLG&oTD#ME4aRr%jM4T@whYINj?Ys}HO*xAEv!>6RjeeeZS0e5RUg$JoDrRLUJjh!;$07Y zAGw41VSsCl27cwaTb#$qfVIlxGfgyPJrlS_6M#YGTHYf`()F42!R@oa_UU?QSnHc5 z4k^q{w%B5x(kP^HJugixJpTj-mey=2XiAW>!dNNwP2?Am{0RoQlyS6!38~6_RaA8U zkP)=DaoAjeM>>a^U|QsIq7hF-hAWRbH1xg*`$u->Go=)3V~r3yk&pEUKkK4NL@ab$ z1Q1DBW%-`3#RrmXM=uDUteb~Fdv5D|t8e%?QBdP3=zvqdGm|}m9`u5{eKPWWy)Bhf z#}00#FhvS9n(040oBy+DCc=LSu}s0IqWt|H7X-c)R#>6G`c~5Z=3N8-k|;Y{{E{e7 z{E{g5I+H@b6%**U!ZHa38odHefsn6&ca7K@kSMPM66NKoV|yppVTrzb8)O<(dT)0> zhhN`H5MD@l2zo>`C@Llz89gbP3mpfHmVxGP6CV+l8(9z@R}|!#UCs*$#jT13%tDxD z6)kLy`L!jTjZLk6tnD@RT~#BH=Ke{#L7c|1qWOY}sTJ<}j?tdQ+~w6hk{S8ot)AWe zbArRUlg6`)`=iQgl?`_iP24|or} ztota~sc*tBB&|46aSZzWFxmSmDgz?>Et%9Y3M*71C>431wH<7;>-Q`2cu~KIz*SXH zKP9(Gkp8ykrGzN`8IsQ>G=ye)H zG8LEqC|FKLxX9~r6&q|;KJx56${}fk)cVvy4R6$Pk~$Wat7q*gSr3T!I_dju#7=$= z$nxjR-M6(#Im=YGl)7u$8KbCbi0hA&b4hIXSk@)ytE!XV15YXbQ~$~ioIh!*|hU;AZk%cggw;%*Hm-Slo}gSWQr zoNQb?-8AfERK284Yy-vpo`zut*?Y$X_*loqhJJN7PZEuYi1JT%O%uur4@ob|cLXPv z=O~t1=2jHPd(;VKuwnrIvbIPxN;(?CzJ6SZq2W8KFM7!0k|GNtjUvOHv_05@_5TA&yfHS5< zAxI-^#XqQDR>*b6zeK+|^s%@t<>xRU6!NSl@4L>Kt{gh&^EZ*ZWhtJCgjR4ty<-^) z;B#dh9}S%4;aIp>v_W^9PpV(ZM=q=71X;`p%0x4;#SnLq=p_E*0>HEO`U4HxqI5X0E*NX z-nJm?V3PpAH^313ImR%~07~2-N-%Oy&(Hyg8E4roXS)jfm*(`!;im?u|08R1Q zdB)}S_sLtY)}RX#zC(%>7X)18GMeKAeoHhO9x2E=j29GAJYfu2RDw~jUIljCP{wye zvLXCbY=M#jpQEv@z^K4_B#`07iS=6h^wGaD^i^~RcMPRSg2YgnJad)Iq%vYCVSIK+ z(rH7a7xz4vqT)rYr6IQyq|@bO4XXF`4nVt`f&rw-yIrJU9*i$D9y*URvEeEgg2NNQtkP6=S zzv-~6I`mPLTV5*K=009_24bm>d`rHp^<<$a3^_}eLAn!Vo?3yS*?Og~Ay(j)3m{w1 zqUe^x#^!XVpi6#usdw}0B(^wIA+_iG-HpQU@^S%~6~K`|^>03fzdI6uyS!oPd$5Ee z91F2Wl%7SeSw0c!_O?*E^yevnSM9>zv;xr>AW9tEEWbJEG{OuJki~e%B>`SezLeBV&tf;o7gmS- zs-W!Z=YE#7K4LWm3E~h> zik3RJj=0x1kEwUE_8Je)@7Pc8DKATo%t`2qlAFDr6;pM zXAoC=a|x+l38s~P9;Drsx{>w#wl{C124c~|BEj=<20U3w%yY9I*aue zPg8GAJv&!mzlmIe_1!HZRHLk7F#W?4lN>{nW#W9*Gu~!t-~@n!@(W~AizU*_V{**$ zN(*acA@u?kQB_LmHBC-MU4o6hd@T`e&qh4ZCI;*$5vTg*1c%(mA}c3)7G!5Oop)X= z*&KMS@9Aux^7LO&9r@h)om|UI{xq3+B$+<-N;&=Ru>hQAW7SxHsWROK z<4kH2V2T|G#2>Nvybc@Hlr?@VBu=lV)f1jn+q)qc<)I;M+@iPHuZjC`wD}90V}5|LWYD$ znO&EmS#C;)fP#aapXR6I3@Ce^}7>Pd-g{og4{RPc%EUY$GXlO=WT<$*CUJ9PA8|MPgex~ z-F^Ju1dxmLP?CYzws3xX<_W;810J-0Rsh|Q>Aj;f%um>WDuCPoE!mCSrt{E+(EM{0 z0k)7HWc}<2qT ztWvlDQdh5>nVsNP+tA+eyeYofq7BfPaG96Cs}>p;?Dra){nYK+Yd)<|G`B9h5Zuxy zk?--(c-u{;a!J+!QT8PHokK&3ikJW46@lmxeP(eBhxzP#f+LhUB|Kcshw*E z$LT+4Na;kMb0=zy<*5qxm6N>Kn>R*YUvhcL`M-Y*{P3AMTG9Xg!Vm)XTlru18!Be> z?PjF^!<|*p%LiN-_k#}t6qY;KIBv+k5lW`Oe(#LiAEh&s%s$-!0&D9js9RS^Lo|b@K7pSI)bj)d1%M#EO z5zHHpj02jYr8SccC#jv|-2=@%2|z7Acp-KtdUf;AaI<^s(@)ysm5V?OkO7I?{KD|4 zMb!EzJ3zs-np8vw9&kaFbre}6HehJL0R^a1p#RUSu4J)p6~5!%@6u>v7a8KtKd2!x;A}`R_Ouqiht%a1o|) zEr$EdC$63<)qfN0z;EpUWW8Qz#Rimd?Mv7$w@ZivHT!F5CgP;Fa}&GkU2($LVI2JB z+w#e;LF95!XizSYQS{fjyvtU+@D#7;|3N>#3fu?J|IPgmZMC8E+KA367ai9f09~3u zi9*!pB^g$|(qTyhxi(CmYEsDgP>EQxlCM7SmLFUzzf01tCzFCe%}MVLt6!8zTu<9U zyEJyrZu)-yfo?ufZR)Eamng>=3#foEnJDfH*fiZF1zCTb)mDR+>_T{zh9V$MVjhZb$ zB1X6`eOPjQc6)juaa9CFPN5}j3{a$dpx~}C_CVs={IDg6zQeNtc@_BdYHhwiJWX)y zJ)a}#Y(Oe@m_-x21^|tgiG3&8H-V$l=K+OA58UeHD5MIyp*6;XR|Yba@Yw8y+@(B_ zS-A_HPdq(50Ufe-RtrvRf5}G*ybpmDW?{4_5rK*)Hc$FdKT8n>>sNgN(VABpFV^Gl z&DGF!&5=2)i)hn3<6hG}5`oou?1?J##=~wzxr;Pn#OJ_#Z{v9=JU71byXcREI6Qv- zvX9DS({Ye^NVCUC11N`DUA?;I_)2>!&B7g#%4>v>GBFeI>iwly*;7%J~Ff3Y`{ zr8PYCWBTf7#mEIqLEFw~a&tTf=iptV(_2v=sMGM`{=N_U!(edp1NgVzjsQ>}e1c{D z{d;h-1+TwL$4lAa|I<>eVB%*3sNC!>pqAqQ1FiCVI=?`WTtHB0m}p2iln?z6X0-@y zRCFlYqcFD!QiNPukzZa}@ftC!frYo33caPJ4WNj3F#`R&#xLlDDB8U|Jrk|d3{$gt zgF|NhSP0{@GnrMeMsLJsOuz;>!hk-O{i~Je zZg_^A?2Ac6gKlfF!PIBERwRKXxqcavjO>%Vs^D=<#SD>rX~n!cmp3jZ!5x#jv-&!M z3=Cl=2Wlk;LuxYfy5{ezgEpAP3oz#TFl-;z=sK=D+D#CD==o0;CU(SoJ>c6-A6el�*0jJ0gS{CM{n5-joT0xq{JwA^wL=zW?|Xs{b}NVc+Y5nh$yb^T9L3 z0~(rV!TP`^2M1*+$A37Y@6j=oqT?y(FNhcudLaZ1S4LZvE4QfUB>9WSLsGDhvI+`5 z1D@G=Bp!a6zy2Dk;Qf*iEMqavN7jif_gzVmyIW*wCYPR|HL z&sGV{D=jJ^D$6ZTM5`pIPHwVgsfW~bHb=Bq)pmEaV)YWX*rXKJHQ1Q|+-|B3Yz6_3ag-0Fgh&G4bdQp5x92RR<4 z&PQQAM>Zp zKVw2qItFaar+bU`Z;ysc!-PdyUJ!NBBIU`FzX_J95H8Zp>(7qJqqC}yhsQ>^iW%HC zyE}7c>)F@;ekM5Ge>n18d&};Jrh}!ayQa^3YflO%Ypbt*@)nMv!C`M=#Pz6ylDq>V zygtW?XAo!Uf8XhYkfN^%ktv0?#g%2HHRXBa)s0oAdd;M*E5U_UX4)<|(kuL#>Jl4(q_shEChIyFD?hpxM-Gt_DQ#q({TQjnrQ)Mz6RqWm>B zP6pc7O2v&aNRUoXgl6s8XJ=&=m#7s0U@G+@t5QtB%Lss}=o{MWS^p{EZiKMegn7V?P*}GT2e=VTc5FHUH$wIHWhvlBcztBJcJ}}yesT~09B?C$ zAR#eji%NLHqtHaW6gn010Qy>bg*RY8qD@)PXp1g2rtfKuPMhC=bSm6VgooFYB&D+D z1OMEdfe(Px_oWKCom4yl5-@N?Lz%Spr~t3LBI8MrG=Bbgz6J>DM%V=Ah8V7Z8(|rk z8_oi51lt9`jZg%2Bg_JB1dqkR{#XL(R2O(;(OqST?t5=6<`nL4rTTB_Xhb(|YBISblK%U}BFfQHi zIck!)b%W9`PMv=wOdIgj3cktd*pollfg2R8IC`WVKFQCg%+g%>?pQ$Uqrq~plZT75 zf~(tGPakg$3qL%NX4r?|5S$3@Sfi-u_|M6vi6N<9Gpt>rV*-Nm!)tZ?B`< z*X|vyM?ieXi9;I~OeUAlLVc#%8!e{TcxBPwC3x4qiw^33`Lr+Kh6al9V|Nc#2bcFg@7#d# zJC1{F2&SJ}Kv1+@ScFWxdQ7r=95^H@CG%sNcU)G!ZqC=d0*FeHbxCQJK)G{ebpu7M zYkgxIakFo0dk=o6e|PUtf8^j$&qzWZ8akRn#yDhBy+nZ!1K@dWEDDAMr!Na{$<5)+ zU94dt-{9Qb^6r}4BOk$%N@9asJW;L%DO-T?I~@Mq;?A~(Y9li5-sc7l4-&*+Ty37f z4UN$!UU1~RnGKM#Oc~Ut@Abl@Jho)q*d1oP9m=1|M7^+Do7v@zA4wDPBhb2A*+I@B z^XE830FyT)lR;a2h0Gc;|wf z6v1!tJ)i9dwfSRv^7_W@YceZ&8wcRzB5?ySA8sBpUVh;b-T@&pF_HmcKuV}uG$`&( zx@aQss^$k5xMYezJMv_OMU`gIS2b?6S+T22Z9_+ClSTLY_RfLi-mk-+p9Uv#N99{S zCX7!mMo!1BC@d^(`mDtV&wtxGwA;xzDcLx>G&&Qz5mLPRalLmJXU4o*0*-QrgGDRQ zhXb|x5fe)Sv4Pa$;sl)9HX|+goo1wij|6nEJt@Szkd?`aEZt!|P+9f+q8QJFh*WS_e`&9_M;<04G;E4mN{e??ihA+^2NuwD!w#4Oq0EOfKC;@Rj@q0m6N~Sn_S;$Z8rb1au+fF{1qHpy45C@V+- z`eY5n)y-8Eg^eAZke2+O-1e@)p@_bO(cppMsp*W?-nstTndKGjanQQi((2A`>B88- z#P;6l8Re$^5oq%K?w;V%@p=p9ltglbg2LVK?D2=(AxeBd6=?1}MtZt=zOCXy+|U}G z_ooL%l#Mv~UU*epE-6dwwhezxA|;0pV_=wGA7m>aoymIJD}|qXrXm0g*oW{@@H9-U z;m31i+~5}9xo>-=sgxs4noNqw=jx;#={T0_2eR-DX^)KM=b<2&y)=Hp*p{t{g^t$o ztUoqx9^3Nu0JpB)bH4`PdnVUQLNT2NtQ}tlS%u@Zeh9IfJqs^~E=_>TyDr%mQHHfi zSWa7yHEs6CAc)DYk{sK0rl_#HmoPp9G|wirMEhW2-s5!-=X*G9DSOm4Qwf?>atQ~z zt&y@K$Fe&?@p=XE*JC9hWfY2`P%0-na?t_8BZh|>eHiNGlYag9;w1>^tT zkz)Y9tSnfLfBmw4Apns7UiA!-n*JfQVIgKl_XC7BJds1WxJ*Sah`Rp}+A!vGGm*a@ zRQ|=!Ury!FWK5kNJ%RFN{I*rxjXY&sp?n!jJHsIT5Vb%k1xzqZHBLD}DF%uk#7*+> zw#k-;A^@B+y|PPW0e(Z3W|>TFPHr_&^)S?{=XNv#kxqSt?Sq{F0-$9mw;ezL6ik#3 z0|Q}Xjkb>&&Iq_n13E$PEA?Jb zpJ_-w{s4=L3?&2sWbNQ(oCXzz(V^ zVyYCIsY~8RJ;JWFIhQVDMle!nbl<~h-<|I5k+#IBuL5$vm_KAD*H`B*HhGP&xv1J}uXROQ z2mE#;2*6Oodc%_c^{%Q7YO(_Y$a7(+chj=%yorL9A#*p7J5x#7l0S7sic>n8AUmVI zy%jhwJ|fu*5JV1t;7lmg_L~3lTp%U8x!}ebwcyz8K-b;MQ_I@M_pASxK+_;&bl30* z0_VsWJnwJuAx24N@t7$F;B>p#9Ea%K$jqX|V(%=ElEi{4#r$d)h-aBsMQMY3lTTe2 zV{Nx;n{7uzYfIyRU*9B6@07xLz&vO%csX=-oor@x}-`;<|j~ zeysBH;o@g-&owBu-gXd$0GHu8r6@L9>Lq6!_9~S!);j;d43!>3=+MI}&5ffci-|xk;z9$5MHA9U91iUC}Pngsxupo z7hI-D2Wx)a8_L&cPZ^(!HkB_C(|?BFul8iN+%UY$Ja5WmzP@^?Z?Ui1?4yb8DcYNF zV908_KgMgxfw)s(S0B9&S+M8W?1*_zF;w{O3>FS73M#hTMDrQ-QVC^-34p_#2EkiH zG=)5XUA5je`~m)kw5aK98aFB?iHL}9vaiibVz^I~pK&kDA#5LxD{XiY6V_N~x=u^^ zEk`H1_ToGzVtfYM>)P*%LkL2!B;0tl%C_KSj79y*?gC~{dEu>-Y#0n4;$81FiOm5% zgNPL!7vYL`BzjG%7d0sZq6;}5vZxEuRn95`jB_2eS=`r)zE36Ucy>dS{W zVq@$hlOFIW*yyAhU|nBN9L!hlMC;(r09uAGH8)^g4?F@5?sRZBIv%{l556##-Q7gASZ>FY2C%7!Jt_U?Khhkjz2yS&<30j%b(RZ{^<>@YK~Y z7EFnK;CA@I6ve^$cTNS_n16^#Tzy7O>3%ma&iY)#gE%raNz^F0*Pl%0N zsNH>zn1jG#k6?kuN2dnyrsr_yrY0vBr^j(tM>jUdws$5#`!lA)Dr*ZzQpaz4X^>yu z)7(-&h#;W1{^6G=m+XP8wgGG`zSpARZc-?4i~>Ncb@Br7=1Xxv1=RA;e_{IU#gE8lCGo4;?o#8#jAknFa&X;4`$x~$`| zxY$@VGq+MehY2rZ7G+i2osVW6_PxJMeRz@0Zb~|q*|?!!*$dt|;p?CeK3754JqGM<^htN7NSy_5uDKfx?Bbp~2l_QF zPG09$JH*5$rtDk??>lI9@HIF6xW70xovC^3@$dkHLrM7nOXxzo0uS?(H`NW?2VAm6Ip*n?@H2(Gz7e0e`-X=;y68V!3N_I1j-0LkUv6z z@fs4+*O^vfKF=2S5Y9PckRO?=#zyEXPxntKB$LLpEDA63GNbU(r9`5iB=Z@tYG`8{ z#If+iKaR&2W0Vm7XyQSSXtGtanTX~14&EVZg#S?r!AV}*8`p$gSU75(r-3PDH+k=| zJtBk{gacoB<|@;RC5U9u2ry-4dD@OJBBy@A-b0UU)63HcqL2Tamh@$J4<(~dagRAC z#nH2fr$So1kbPiJEh`uBkSm~#NF5-{B%3gxbo-7JEUNaAf+{JE9=qQ zZ!K53$tQ%=geaPq4mlQhRMA=97uC(S&3o5)hu^o?PDgaJq8{189Mx~G2|fQr_Zz@T#Oj%*uNj?635!kmOV!Qvw!Mkset%t*q%gj81P-!``YYTBy*U0?26(X4J* zrG`rRhs#NJOBBv$D(9v-Xj&lT2-}Wqt%YG`l)Woom%799uy0Ewhf{Jwjk5pn$5Z}i z$17CJE)<`^ae!|wK}OR9Xsrt2^#MRr(OAJ%!i;0y>@g2ZQ$+tHrz4s<082+}7Y68m z*Zi)b)8`MEuI^5rUJky_KK?c`Ux5J|Umz&bKiW6eE8acPEjb_@fI~k`^#-}*`sIJi z&MORp1Z4u%8DVh&q}H~fsLZ3K35e+EN^5T|>m6tt>hB&M`!d)+Tt8hnFut((dU9rJ zZFOUAX?urfWo|Zq|EO*E?40>H_bTe}`t;(*PpTW1-G1H>vI;j8Ts;*3&%mqtoqh4x>UyF#vCVZRYC-h5(;t?@zB zM^)hB816yDid`)?I+vX=gRwW*1|Ni@xXz>^ErUE&>{XDceD9@(nDDwB zw$=UO5ItMm4!pKd1?Q^iW9s&d>J}MkHrj2ep~1`K@wT|m@=yw*`C~LZY)V*1=grXz z85oOUn#O@^st(@N2m75>0#CP_B3o=X^q8?ll(W&NWUjagv8kT*0@&JKAxZQi)^u-g z7X1Y$)K}~oLa>K@NncQ}Aw5qZq(SCXQ(Q-U=nH916eK@dxQ~f+)xDwVmtH) z3fX?k^roWj^@^xMiEIg#s}eT&LPsQ(76l{dP8mlY^m!HY-r&hbB(2%3VU(d2_BN8W ziJ}pboncsZ!UTlhGtsTBHY0=)XHMVOxo&4Wodc%NAU16ypfx4n)oOM|=#)ESw%(ik zWzXoVCx%gbVK0pRQmKjaa|hyE7~>)IC;^#-D7ee{njCW`c@`qXs6_;dYUIUKm?SF* zr;B|aYH7RKX`VI)VtjD08mzRiuvLq^iKKdx%y53` zwa9oj?A@`6S6;T+FB_84f`rRp;LXf?@dlCh z(dxblY3T|{CMlA>=sFpNMXXuo5Q}`P;vz)(8vQc22LFnx);igCyQrqXyaK?bz&(`N zJ(k>8IgmEOIV;x_v>4Mey~a)th#{9#$Fo=0k61S4cJ@mz%KMLR8BRNxc5|{lue>>@n66wZr;M$#og}hz>+(-)S&Gz@8=*5=AT7N*ECz^%Pl8 zo==ey8kTIZwNQHwJDken0{7z<3d=QRK7vB&lV{FU7X~dzV1{}U)D41T#fk{S&d-Vdo*$ZBUYfi*805!6#zEF z2lgN4k>+{;;$U4kB`2U5+?Ve6*58y&8Sp7eFGd9f)s&=gN5m9E2~yyrH7G<#m;9jZqzMlTL3dpdo5^7;)n7*Pa}j znZ+FoT!@}U$I)-I4lRcUs+gaM_1QLX9m@f%bN$7hn@aQw8xF^D7aNm zj0;zaywGT*JK7*2qI%d*O%~!Z*2qFliaD%Er8wYwM8BioG53~jdPPR+sJ-i5MT13s zE?Kj1yXy{3u10c!8Vb_iMBa%dRJf1lC_o!y;4Zm5RnxbFcRIe4s2>~xf2>{#qoAXW zWgnWT0U|`MCwMj4ws2lV_4FeHlp@G4G2FVppvs!E%42hFapYFVTD)Uc-IzOhI!&=q z$<5jvjeT9X;^rdwxC&(dVPhF>He~? zon!n@pw0ie+lK%d&IX*E$efC2rsM{!|aQ|6=UbLMFy&ys8Tz&}+O zl0o`_cPcq3$A&mrGj@_$)pXD*?PDHqg8(g%DB(ExGpzM^D^37wy4miFc71cg{I53| z!B<%q^?>(&m>|92knm6iHy@}9<4bUqLW)&ndUA$eOd{|@cxCy4{fjJ0G)h0^0C_)k zqLns{_RWs1n$`8dAPc|UxnFBAs5rc{cVaSsc;st&MCRgX@c7i)dg0RY_S{VBp8V>@ z@rluazlpXK3+wgIG3L|Oam}s1i~*ds?9}fAbOp?3+Ql8HA*yu z_yiB4fl2O4dL5A~L_r@M!u7jtSmQh2(#p~GC;pI5zhH>Wp-ANOiWuh~e>ZA&rHrP< z6q2iup%6|Gq_W}xm#q=b@ACwIOsOQ>-H;4qYC2ZD-;@o|pNq2LEeAUQ))4Cgvh8_S zk)~?NBAomEUD5j$g_YKCbd*&fyRUlPmRPT04yvrO^RYU#6k%jk(HUd1 zF(rkqc)^LIQ;IS$nAh4;f)VI%AhmT!`&8L>uPH~Ixc67e%&&~e8ZM7bI?QE0>QkSe zQjp81>RRG^U@y^$XivUs{Qmf4=H**;tPQ4<{f+xhUWL~^&KSG1Aj=1>oga5FhSSS- zC~@Co!#rT=k z6K(vFo>>`}2E;X`(GkS6m7C%I@{RwKkh<^wxM70Dw3*?Rf3$%?EKS0fx^AhHK+$G!Xk-rpT3a(%LOapX$p!CA0ppTIsqTh!D ze|AEwmSZYdEeS|Bu}-l_SIx`F0n&c>iwX-Wt8~kN#&tvuW`$ET(75jU+}zsI-aR-} z-#0oiJTaLxR?{~%zYsE0HMh97ZnIpl3Zw)oZKdz*pPcd@f{)LxZe(NzShh({)0NgAk~hD8Lw1TCq$@9d0c^JHiXKK)JACj_Gi3>yH+4}$r>C;{^S zS9fO_7iGJ)dq7$Qr6r^#MM7zj5Gg@I6cCV3X_Ss(VCe21y1To(LqL%3P(Vb$z|Scz;2q9F zP+|Xm_cF%kzfp@=eSnUP_ zjJ>k{VXtf({xNNL|M(>5Q^8l=&!9BA?j#7ES+d|{lM|&$3`iEu5@muGpu+xhg{ z(Q((LdmC0wG^AnGKE-XHQx(G<8Nc#|Cq|d(BIHz}#~WsEZ9Iodl9ip}ldmY1@y5hZ5#|BQtDg!;cEEdZxrt6d;7LapCIy#>y(!bBD#MNikO z&z>-{%sqp{4Er_p5oNJsc^aLxLBC>+cFyoi5oy*rlo7fX89*6req-O&>rMu`{wF}m4KHutlXheCAPXA*r91O zI`_D?fyv%5Z(qn*`~cu*znw^&O$Gq6JP+;jW*q05BjGK8ff%aReCf#t$wYe5|cj%upt|HfpKx zjFh{~dN$M?`yQZ_uw8e7mm57!7KYBCvP>94(g`tv8c#WEJcOS8Tbz>w9Q7Jc&g%kE z6bNem<8~QiYyz??JiJ5lh1SH9&r7W;LkA~ec|L`d`-VaN&pxQsy_lLOYCtZSX!7+Q z=ro-6)VdPH`au5CY1^_{1mm5dZ?_Cj`AVkmf!?KhkztDx~xad>+s@yR4G}5k~*?al^8D{mfNk@$`Ci$`8yF zM_w;i66#nP_cP6-B-<}om=7S7LVR-`6CBfU1?;EVsSc!`A~astvKWJ5O z%c!?yIB3Z^g%ws9n6i45f^HR&EMssNDXs*0ujZ^s2}S$9^O87IrL@0ygE{f4;^c-t zhG-t=s$ajfqjD6fN8DnRSojv5yQWiadMxob!y5^jZOpCFRyH>oZ$8LV8%)~U&lO3& zDU-7SC;!q*lj;l8H&*btxov#kC477{J#wfw2a06Kk(d~UTb7IY(vYPmo2KSrrlZNz z6A!br%Dg#-q}S>u>_wA#i3K9lraOkBi+z!~Av$99G0s?Q9cZ>A1 z$&YmZ>T^ zX<5MjlD{B7ucA_?6l}DIRpXXBH-Qb9PLrmV=C-bZ!MffN1f3*dw7M5;&jw9ZA{=?_ z=JOVT%u;bJ6|p_byPJY=mXd3b`hTfhsu+Jx=&_e%FgdrrFZ;6PyG{S2ziXRHwVfHr0 zM7!_JvS#?{5;TiCoIOe4%C>0!jSQtZb(|eoHbaFCC6JV(mk5_0QTOx2yu~q=^fi~Y zpP0R4&plAsPokuC*;-=vy=?5r0yacE#|5dPL{HR*nLao#`e3CWLMSxCMr-5U87toY z@ey)`aU1GHobVv;D*=51GAdO1S?1swrTsgtnq9B3=Hp(jpP37y?O*P0#>H3?Z|hI! zdnK#p%y^m}mBCoRv-VZR9wy!7e$^8D^~+89QL4mTVf>ZP6glFI&4yiHBT$1v`? zZcB@!Dg~4rskDT*@jvPYa;)>D8_;^xh?=rAS*>_{b!J=C+FK|Qowwf7#WJlguDz6BuR%ptqRm~4&{c{vaJrdzohq(8 zN;}&|nx%9@&0+p}dep5Fe#3Z`uC1)Z1M5>p4amdn%|wa$ePgmP6oJinbEWOvD>1Y& z%o)!o`SWskw;fru^L0%P^TS)oSYr%de_=?A?%Sp+3W|3!&NMw^p~Ous>)WB|q|MqX zs=ekU%2Za~B%Pht7R|p^I5x9hfHu-qRbZfJ(T`Giw}G17>`{j?JKIk9MJkLT=xnec zOM!={b-zLS7j5CW*$6_c@>}2ak7Vgz+AsOHnjsaSPJm?TSFcbTH2oF43)PMgk}lw( z{36yUk>@cy?!_3eE znkW7lWQ_fW;}}7&pFP#(^EHUB8s6ipuB!CzOFsP6_=eJQ&XsFp@=(&t&)F9c z-eC-WrXiYg-mYQF(JFyKvCk59??u`s>!-hj2l@Di=7q<@GA&BPilPc)s^W5jYmypt z>+18{!l9{YO&L8eW$MbD`YZ-=h9K?AE;(p;7zhW{x!J{)#pTrv`pr$e8PuSe7WqhW zCb%pB>K`9`lSlpftzszvqnHZn`F*+edH9Gb9Sn;K?njEJ+YHH}KuM5NjFE7oqNaMi zI(?A(FpNkt8r9JTx6R|4bkQfpMZy8!+eX`L*Djo+_dqBpB1>O9M|ZYYJEbetK2?ZE&58L04IU2QVS>;2QTx%aH+&9dgN)lZSl9r z4Bsu6u09N*kyID#9b1&NVpcKb+zP)b8pu^XJy9L;Vj%IE(-(sHeZ~=%2P8KOjX!Nh zW|E|qnQhcZylx5(i#X${m^uV4hzNy6A_%XIsq$z`E1B|J^%m9 z2SMf)&>*O<{VNmc-wy(WwtFp6^|UuosFf%rR?%U-#**|I4@kSh9hgdS2Vj7zGo zVhb?70)&IMBUvVLpGFxP_`fn6y+lB^`Y|tRceF@r)Iud8s!*l+$OoEzlaS*UtyvXP(qHCjH3 z-*CI7^u_na7{Mnyl?|3t^CXUThfiC_@n0l!f6XXeDK}J@s{DE!x|crOk&@OELY*xksYZ`CQKpkBQsMr^VgCWY^}8ZJc)r;m^&=Ae&! z;;F(A`B=+QKU$r*H!~E?i+Md($CKzL3f>86zYHGJ2n5Bd%h4l&rbW#|flaaHCI+h1 z)p4{>oQta%b}Sx9$uv65i$beiTERG%ot&5(#%*;9vM2eSkIX( z%rO6wEsT7pMP^KkCey8KJYNC1#9WI|R?NcJBdi!@P9?0xS(EYWIm0b#Mp(@jBLy<( ztxYCv<=4HOb_;X3o)=(_+6b7JR*8wL#eTh4GZ~T)w22Ng5Yp;*aiqosW7C${+De_FgOGf|U@7akrlYhKt&mXV9 z^5l-kIlD=zErNKwFfeE}d=+TgeUL86=!&GJbzUXBZQ4;|O?Mds|HrZZuCX<}H2%%U z{wJhLk7c58welhzxpc8ZZyk)#*Ou!&4q>%guQ*iJ8x4@WRR(|$H)XQv!k=pNMFvk~ zEASf|77VCedV>jTHZW{~P=nZ5*+c$&$^|ICSMewm z8YO@zw2EO7JXN2e^DVX*cxUk2m(VH(2i%ap!UNWE0{Z3L&>{XPQ_#LjY0bbR!f8bg z%n&ii!3X`ObZSf8hSzQHM%@+NJ-=fd2UhnVCu=si5^TK3KsR^2`E3f>jdzQ2kp%Tq z^}MrxXEmJoisuG3wks#E4&!y1np6f#w;E|*T0=2iznDZ{T?UpSKIs7VhbVf1Ap=r+ zbUgDlJytFE01cdI`vlVtO%C3Ij7{&C7@9^Mm*Mls0$(3nHd)ailJa5%3L@Dfn*@j;y*`Zop^o0+p~12K z39#}w-HFjE_t$=%IC$*yQYVK$`p_zPIo{oK!PsGl@7}5@k3l}B352sH2hHbCMW;Z%$6{=OLZ05V^jkPjCyAY07%sw|GMO;Uw{t zU=4v+o0G-d!$q3>#~%o;3NdNBphHnK7}&}cJnYfk-V^ntJZ=_t{j_~|nsNBe_et2s z_u~N>w1c-s+OC)#Yi*FVRF4IhHs6tJPP3%q$!KqKvf=JT86>H~L}cZ7K39@OL@s}H z6rn}G5iOG9Pgk^g4T~{)(=U)GIZQXW>Ed&NXuv5UgHKT3a5Vl8sDL;y`w@EEvGJcz zW(eBq+Ujy7&Zgfs&WFA29Uttm1Kqukv=<(vWpDxn|EjT(1}6aT(%{`66Ud%Q=e1tJ z)-N7+3+EnpRCp3*Qf$dCbvJCXG}_|jF-D{c^V06TeA>U#lr>rMX2;{gVqetm^Z~9p|Z-F51HgqhwjyurRnu zrf^!iXSQ(EbB)|Q#{#>G`>|!^&iV#bzBRQLO*}=MogAgDy6w^RTD^UGL*we*FGd;S zQIjU#3~+|#&Aba*c&{kC{{KAqvIg%M_=E zc(nWAax=$DS<|AR#WLZ?<&4N6YqaqDa_B2q`)1j(@jYTPSzW=z#pY}**hdoW(IzFx zs<|rF(_u%|&hg|pqEnhRmi;N4QyN`gwnF>GxcLU|X5?>*B}CkqImiCcCVj2T9B$YL zH?3_1%a91uHu(*grel%r+rXYjzlZ*%)Wluq0i#z-<55GL5y-H zs=I>v_tm~eufKVFI3qYT{4U8+4B`oKcJ(22w}blg1UdPJ`2|KoLU3W>t}%&Gj+F6X zNzuu+@Km34$Gj|@oZL+F0`u%*>vFRi6@bPqt!=JvY|7}&hgP<$)oHXo?(H)i(i(p- zGAcbV(N#Fz|3-9XvSD6kd1+B(YK;`*!w0-QkTCBb9UmT?eEsru4-E-f_-YSsFDU_u zFrmW;3aU6dHdiOpq6~8Fb&|_X)cax(NjenZzZkb zvJ8?pV7_sjFxdnSD0bAvz5}q)2KkV{UmWVc3$OpBrrm$U6dMiXL%3hhJ_!Q%Cb0+2 zgw&!oiz4j-gDj>la75FNXqn%W;;kaRbU0qk9l$wRlMx}+yHS3ky&Q^i*Zj=EgIl|b zgu?*)E{~#^f)@eILF%=gaZs{+!pTUBILgFTv`8C;mOIR%$pNF9D|5 zPrwwr%L`1gMZpyN3z%YC3V|th#3eAr<^fY|LGgkbPR_1ix_(bkY%=#nbDOml)Rw2~ zCyO@=IEJU2jOL_pA|=#S@)nY}l)aXFP7Fz`v~8#5cwTL()Zl)3gV3esKng#E)iTnh z_E2OnMK*=NweE=PO|h9zxNH3}!(4Mf^)?KI;3SU?Mo zl??WK^5o|+^!;GC6)7ryh!h50FClxv03%_q15?p7+vje?)?JAMTk_4!bs7Omjq-f# zvR}Nnu@g4sj|bhAN%6@XVRwN&LO>vovuTKYn0bVZUyv?pY(gR*rhN=Y6ht9IE=w^r z36P|V3?g!j($n*b5%$Jx6{U?~(0YK9Ol%G*dr}E#MMJjT&b^Z3E>**z%DgjbIp;P7 zFygZd9_yY6jClKI=3X|SQymo?D4rM{e*S*u^Cj}szZ1}@p!z6E%Enhx+kHmRQS@@M z0Ii7BOd*o~T3lx!^^ExT7L&PNLI|z0;hkJB1CA&TJ+e5dvF8P>$(Fvoeuj`p3XSxB?D3+Tu%-FbVJIVs%WN_hEomBR@aKRPyX`5KXZ=jBDk$dDHB^1U*3M<`-?eamfQ`<2?=1FQ!F5+` z=sZ{**|}vun%H@`Io&I_G4sX#^PUe_5C7fR@;*2t8UCC$tNm|mD&XTF002H1z5xOL zfgxU4p`qasfl<)`v2n2AL>L~LCpj)q9pvQTOqZdG+&T~R|WK6Yzc zI$=|NS5|FPU&BD%&~Q)hSSAK`$Mp%^k&1Vv^CgRwGqW?x1sHfZ(-)-z@rMi6CWd0^ua-APiR&o6SU#d=pcMo-Rxr6M=J%6GfoF7-F zgY>1t(1;2yown%n#jGf>L;d6#`lGpSa}B&bpc#BZrFQly#(GmEeLM#Z&F>EFaD-rr zTZFN4&P2>Jy@zuGN+v2Y2*m3$MQ*Az0 zul)UNkky=BtkD-u5Dll_s;MKe5bjK;5k9j3Xy0 zWUqhy9!;1MJH)qLW|w-(6ayOKF{ z98~cZOzcmRDKcoZ4neLrm`WBge@OU3Ja`pJ#XPAzrrYm+jkAYep&vWe!liIqN_Am0 zq^8AVb|a;`a`$NsE$%I+16|+yebaOyf=;1}q1>y++F?w=*Yq*C*`-m!1%j^{L@E2j zSFb!VJ;?B5F;o+aA=6;ajAe=L8H&M&^}@0Av2z&`ZS(xDBp7r_Lz2nIOc+v}zr-0D zJM^6*!-=WmnXn9P;Kpbn7Jdq;q<7+5(+RZWnbX6totPp{6`UZMu4$+1DYn6CjH$8V zPLQllM{K>ktZic>WpQL71$or??BG1*o zf=*A2Wub=NGB0ruE|tMPkHTSoiqR71>R-)B{a9RhOj>+05IfRlNEDi+rI%&{eOa|s zX>nOveML=6Ye;=ZUAa_SZ=YLdV^>yB|Jb49G+TuI|`&iG}C^Y-ZSg( zKM-vj9~kWJeO^DbU-COTKAS!Lxci(JfZ{zatubUg+lPxAAZI`D8rw_lR42H`5AE7a zlhnBWiSZT%6a_0Kgy|kpivk?bXxSMkVx`No2IKK8wkP6jvxnpEDPtc+dOv`q+0t_; zSm9#@6R}<|j6KxNQIS$pw^D#F=3t^>2Fhgae-fR>kSfmmK0YcgiDI&$&(ErxsYFEC zR;Af*uQFRhPKu1q8GFgI(fBLN`X>@EZ36EICEtb`uEZ`K{1|uvGN(~Le9i^NDe&Xg9e&zWB0cLJ9ym+FxRcfzoi7 zlIzhF(B#jxA|MExVT@0zSGps>66fX# zWjYkTDz-!5TdF8aUq{r{TULXCKu)c1qeVwkTVMZxTTge_$f(mG=vi?NM~>spOiV8> zEwjIypGWX(*4N&F!RqAh_y!oPRv(TYfx&9Zm%xLsk|osX9*yW^8a-EW+BC7rWfGZI zQW@+CxlJ{6t`T$vQU4H!Z8B}AgB1RDD1E0~Yd8b1Qr|awI6{+eF5J@_u>ou!%!HYa zX~zfB3ET-e>S%h#VkBW>5iNwdDlbKZnL3G9A)Y7THdbW>0LfbeBZjeiI3l zJK$+m9CWcSMKb@UxdWHpFbZ;U^7mZ3@ge$-vH5%bRj~0Ag1&XRhOj-H7Tf3SLk;5x z^)-@_W?G3z?OU(Jl^1T{30`{tu05R*?F%y`3weOEee|Zr zW#ee2LFCOq_gAzKeqBz-Ur5$}Ds&t~oE?Cw0Jf|CcAwG@b@z{Pcq2jJ%TKvT|^G8q^igY;q>tL_1_&F;vO009G{pRogTvJ zdNDD!z%|pq(z7PJA+goF^ad|u?)iJ%oq@w6zLVkOZ|}ht!Lq>?i9FR6=;F6)-(U(9 zybyI_t%%s5WuAc58)6-vqZ*QSR6pK$KkB-*_>h(EJ+p=yhe4Aw!{apl-jOxocmiv~ z0Okn)LFj#gstLzYs^MfMPk&|gAm)47`;TaYP%2pzZ4>}CQ1?~NRQ$7hWN0-}rmCSv z5?Kb-(Q%VyQZr4F&WC35^@6=^uf~Yj=F{9uzeK>TEkm2^zq7~>@R94Z%UykzaXGR~ z0Tx0-Rn-t_t33Qzlp9l3)%J3)2gzexwkmCt@ob57;sLV49s80Ogh;R92rB}2G%De5 z$OkJ;L3H@QZhE$r&lNU`YW zK!rktj5S}K-?NZfe|oh(>MC^*7Ftes3Oe!`Mw)dPo?S5}uEMOQNO3`%CpR@LWm(3=k2@)My2@bU{yI%t_V3KTP zj?MIJJ^D<+;806@!sXqX`+7G2tmtl$gUd&^($$K1(`3!5ee2mfeWa*7Yo1 zJ*C`lL!iF5ykX9M!7Kr|J|U6xVG&Vrcrj}6$q4~EDe;Nv$(dPkF+sV(iD`wd7!>7r z<)8vVqr$6iLMyexZttMLPQvTx>&M1y?`du8KglPk9wb3PLCxn`hg39t0hFH{@ZuCKb9UCJ4Bo2->`7e>gJpWSL@OY zyiBa5^sk0U(%E2nF%vc+I5tn?R2g_`C2qhc0UeguK5WL8qwuv0^CF_&Ql1g7Qg^SC zUPi1{2|I|nX!<^P^8(K!HOwp=*IzX-G%h|qGAc6qQ7q8LyiS74=4fRCnrL=PWLi;0 z<^9s|JjwE^#-@j80GC5N|iiZb~&#v9-BItqb$t_~E`TUX714!m?(+@JUs zZ74?=oi8u8rnp53@<=-Y6PLb%$S5*$AK{G}zeK5q#$aMaw9x6K2g-WTjiV7 zNi?B03Z@mgq*)Il1d`OzO)>IGOO)pF#PiXMiCSzZ6S#e*v5b22D#KqF&b}~Tx|rV~ z?zqa|-*FIM7qX{_iOSqxypn>K&ef-!y#Us#(9PY)hIuaaCX&mQu{vaB5AXLWasnry zppi9&Q1)c{RyCl19DY#n&@+(tk}|QR!(krAnBxV{L0 zJ3ZVmL#e1BGX{u}st8MKONz1p{Ug3Eqb;ow7-cziMD)WDMp;Sq?Gv5lz$okfpx2x+ z!YE5?a$tQ3QQ?v<*lc&2_uoi0ZUUpMdxAe&aM*ejW?Gr>QrTXP zl+c#=LQ%BJdk%EPyvWiS2REgZRN^l&;i)nsSpJcY+I@*whsc8oT;|K~PCeGVTp6HT zN}=5-SFo^e&>xjd+{7hwBrMnr&0RWAgTz zo-E&eZ{oJ=xl1itSsO}tatFrE>+nf<7qW)?GtsApQRZ*s>NHSj^UQV)u=s8 z7`QL;VtTjs&izs1aD0xzcw!@-pOYOpNOt~~n~mTopL<;W|Fc$MKugjB-Tq~*q8$tS z+IJ-n)LzIXJZ_8n9z;V5uUpuk@VZS#Zvb96rvkimjWe2!^^8yF!TO^pJk`2)wX&_q zXab^yq^a6WScyUreM%xoObU2xK`6pqpTjPD+{ z@29IFeV$hR5O$v`t3zUzuN6?uEADr5cJr%CC~Hk+QHMAjN|(Cju8ON@aLiur4&`0} zc~SBDur8nE0Zv_o&{&powpl^lUH-`;Jxf``r&Z>r6<7=Na)CU13!UNoL{}P4sFyl| zSVN*fLyG_6Z!3gUg{+1|3{Jspj#3~8+AzIUo$_{rlD?M@h@5tMn+h%u2R~|#Xxlt~ zd7MXem4QOZPC~n^y5X)#jLxH(H1xt;rmCtnixgp55*)gfuG(IQ?-F|x@A)PvW@+Bq zHr%z3**kjTV&&)tF~)ZF@^^pn8X6b?3-S#K4^y(c6&&}>JJ!c9G%eaW!6PO4VZxPM zne03wV6O4VH?r(ejeH~y1|=;CO-pM#Sz9L|hSbFqJPdqyt@H0*7}_gsc8|xXpnf&^ zb)ddZygcAk^;d9w>#`G=D$U@K*<-?b-0t0~TN9ZpCyvv&QyVFE{4USjm25nqgg!9uCw>G0Pr_b=;791i z7(_uNgI+ib*}J8Cz@K_$1m*^(x@IQFzD$TSs<05s_AfE05)-Tqt*>mWZlUR>?k4FY zA0P(n#uw_zRd59w=U0$^e)m6`CRH1CA77C);X+(NKoz)x3hpT@how)0_4n0EGRtuw z-BFe`IK-^dD%^Z)D%Ou>?!4-J<@{XoHU61rwV|r0GVbim>=EvJ`Rd&QPAxSb$s;#K zXC)mEJBTEd8RqHgQznOu#t7Vie(&-HAyG4i3*|>4+LKbxgTi7gN-nNDeDKV_&=F@A_QN5rAYZlf-e_dS-lITfgzFtk`b5% z|MtL7Cl8zp$up{>{*P&4sd4@V^3uQ{_Tb-7g8!8}^6oqZ0R4`02^_FePzDk>gbfpi zUSA@j@r7XTzw1RXn52VN{yVC~&%r4MZlUZja(`)3}fhGZtCE8U@VvdNEX%hvj1xy|MWYRfl<0pjb% zE&SVBWB-MfLJRaVm3%|Z!3siXFw{_cxG|D0n;Qwlm)9?;;?F~@b0h9XTwKtQB}R6!6yI*N#ji1gljC!x2{d+)t>2vvFqL3$Gq zP^4H8tlS+eC-3*4^WAUUd;c>W<7kqdHQSnN&SyR=x8-Dngmub+a-bRx7&+NrWVm!= zK{UG{U)?~rwewjo^z7ricUc{og>Q&Ig(0*o%}7W{o?4l6b8{abA745qQkGV`Cnb4D znwOIs9}fTk@TG@Jcj#~F*z17*zkb8nT1U^!z@A>$z{tc>jA0Mc#z1ePFUIiTni98? zwUmLeiL9%w!97=HH9c1|Jz;%@8{+iWokg52tSt=eb?BWf%q{IioW&S)^sRIaM8Lme zU*=+UMno?G_2K3iB`8f2rd3fjr1UPy4uL%h7u+#H$^YC(UgMS1# zc=$!G35f6t(*OF80bI>i-%v#LmdvlUz<-G`7~9)hi*Ru{IXQ7U@o`$&8gcOm3kzev zgO`^B`~-)ci>1AeGl!)e{YD*KD+hZq22j$UDp*+m`C3am z&J%Sw^{gzooOP_ZcsRMSD*gVTlG1#0ND+gOW z1MuUF*rlvRq-+gz?5%9otgOs`Tk(#umA#dnv6VHw)I9-uRwW%h6HDw1S5BT#QWBA~ zw6oW-)H9H~CB^`L2d9aNz6dY(Eg>FmK|TR~J^>ycX?|fzX#pW_X#qZ-o7Z@Rc_n{8 zd&^4C!NS1O{`a%`e?QCrug_wG!NM9``IdpLiKBtOjIEUg{fW{dCjTxA&%b`(uV?lD zT^8PdeU=Lph70Rj99RE-35*}?U;hLy_>VuKZ(s?=yDb>lc*j4!fBX97^U>j_gO4BH zzuVv2-FdtH=JnR*#;f(U)t4*FON$HhbF(wkQ!gebo{x`>jtmbC4)pi+_H=i3KI>?2 zYi()9G&MHV*VWckS5;P&mz9fbjJ=ME+RFstz73Ae)Z_7yElDa7=aYJ0}x~Pb-kf6Xdem-6vZZ1v^_N#1HSXr1a zGcht;qQ6LYftH4vit;=KITJ+$HtTz5CMjL0FmKPZ~xe+!MJ{(@r3@1$>GTXU{>$t^z+5J4cPkB$`<5wTSQb> z_ww>f*xLN-w<8BehhMrfJB_TgTfIld3TdiK7Dcr$`wr`An_swTImT)Fp`K*rM)<2^ zgduUzI72_r?#k(C!Ey#E514e)TjPi|g@{S(CH{i5%xzIz*DPHrttczi)1sIa-UMB^ z=dPHXr}rktbkgi@ri?*cZ1IayEisc^k^3eyhDMdDV#x@GAX$=vv%u~8vPF#Zhc}CZ z_2tWLNc@Q>5+84&klv(MwT2pO^q#RP(f)99cs*AZI~c4q_=sK=- zQ^PrmZk;qnlL2B^)s$fmkV<4wCt$8e_hw!!ezuKZ)$I(o*}?#o2)xw?nO==AoY$4U==3c|O~lr}JhNxB zNg8=q{Plzl-lh61s9P z+qE}7%1`%+D!i1YmNzpSA~$UOC_AN);EHi>WVf+t-jgqn@`^8C%RO@;nDtFTj<;-9 zP?=nUjt`l5!<%?14OzP4^F3dRqR$QdRa`8dl*p1~K4N0z;%yrQ%g|t$H*`>C_>1j0 zU6Z8vm4zLh0&AT2O}G4VHB$xl>WQ@Y^`zNTk2&2vKDp}FxBmz#t6XKHF|3)cOWs8; zh|dq@q$J%hR3(1*H8xk&G%hY1ue?F8O)1r{A}`(ltZ5gy zmD=x#IF;2hI10wp$tx}NBB7kCg%&;*RT@7y6|D#Rn%^25M-DWz4s)k#@|r#Mx?_Kg zzDu(xT$cVpiE~|Z9)CkOs4)CueObdN zbp32|tJUF``X(!{Z|~=i-J!`+i{IXLXDRP#8a2JL88Q00CUM;K2{W;yh*aWT*(xGv zmV%91?+si4>LDFzcdea@zp9)PtdN)^w|X?`Jpo7>mmS|9vzm#dJJL61N-zRvUv^6bH7_{l}q0 z(lH-&UUd~@;R8rO_b6@McB^9d`#$OF+S4Q#lp zL`7H~Jr)>=I1ni<1zO=JSX&?WD+pfb@v2j#)n;6U@raGA^WBb&t;NvF05bT+>c0K z6w}7l3lIJElT;(C?UwkQsFXG?bJ75%06? z?7Q8BofLY3-k^4iG&_B^?Mxb)D)L=}%i+Nak0_yRcLZd*Qz%z1bCc`!1*O4{?|11e ze_to4e>{%xs^MSf5EfDWO0M}?297IeW)IE+3QALv{4c~BQD*rHJ69}I=0=l5Y;$!LSO5r; z81EsMj$DUnOHC7T*_ZL+kC3ZOF7-fll0(UL#vRH&>prmHCUmai4r+P2n%7xAqh zq*uujS)U#;M7F8W5}W&d34QAdzZc@h_zCfi%I9T8h8YIK z9&g9^j$YGRbnB63?67fAx#q;-b;thv)OR8iTz$pL4kI7(O*QLWv#A$9-&s0t(RHC| z;d#bS-0*_Kkicy8^+JozC(1c{$F_4b&zSRjuW)`?(^z=UvDuI$_}!c||N4Y>cxKjg z+5GwB)M=WFuEQMHKfp{W)#u7Ep_N)Ila$1z?bjaC1j+AvbKG7KNuFFb2~Euw6|c%0 zF<#PN{E#vD0CY}V_vnw$!6Y*F|0QA787+x-+sQBU*O)55=pO6`3T+sH+B5J+KBcA%pp==C(f*1*UMZ^p#E-ldYsK4J5&_-)krKs&NNr=>&G9Woal zHEvC2snZV}reDyouepzBSYPh5Ry(}&CEnpWf!)Eh$>Fp^XpMOnv)3~tb7+HwTOP8S z#gXf_*JT2fJS&PXf$3VHZ!3Y52&J#xh8vTU8qDyVm@SF$O+)P*=c^4;$Z3P84|%y0 zs6(KcZ)7kdKac*^fp^GY5#=Mit4JDN(wM$-3Q5@KK|5!Z-HK*hFSIIgTIr z<{Np`^?2z!1*%d8z84H67IF+YLJCo$7>xX03VMtSda4*XhfI; ze^eX%wL4gK@~Nke)e(Vq^1;)Oej#7(pPxT}Dm3FvJ7wrIq0p{}p-5{$IU@8%1TZiY zI&u^`Mu~ndgr0neo^nRdB%tRS&c|E*}3_J#iiwym#b^*uQoQfUccFXyR*Bu|L*;Vj|ZO)k3N6- z`tAFVV?YX^q%>Gz@`0F9)}SJMYY_O1I5uDgZD4a^gX4WU;UaABaqtb>d&m*|w1GLz zAQxY;Z{eQ%>&dnUD?MlGXzMRk^ceHIjurG5WIYR<(nSo~%eQIE2^71d>j#qrhj!6s zuNco-?26AHU7;Nz=l#k>yRkwG~{CDklFEgg{! z&&Hm%sdP&AYO0;10Ms7Je)3b^#2Gb$VefuqmbHwtn07PNB0ay2gFa zsrvD1&zTux-=5uG^Do{tFNb9nIa6oYq14gO3j~WD70ax3mgack*fITPGmVr+HOtOM z&-&nRzv7XQAn{->0ZOpo5O_!^I?O*XS}Zau5|I$|f3!LNM@rWby*}Lfy!mzG`#Nqm zAO?tmcpw(rh5uFB_`&m< zTRRP#ZanMif6#NiU|>`Z@_ZtDZ0a^p5sCv*m!W&FJpUb4?L&|`Ok1$HM? z<@86h-YY6GGRqx|=hhoYk*m%dP8PCzv(R6iKbkJ#^VbFWNdjcHbTr$OfttdJ{5#q5 zsq(c&FNz;ln=TI27EhOJcLrZjs4JPRHl8SYGFVqSUvE9(kisp9?ZQ9T4h_a{Xz}5C zfE+jnTmnKt50s6yfcdy#Ul)4=@yB4s`<1Ch? zQlQTtDWMm^eC=k4oMElgfn2SenKls_Vg!qWFtf9v8@}O1^s;>FDZ#raw&eK-2MNXo zTzEueR5WfrcFthDne`9(xHPBXAM-J-I~tVwH#wUMkwSd87Lgy-6|&Z(blLn(Al zpqzJ*G2{Bny8=2C->$I+ zs`uXBDHh|Cgncc$&3HI};3$z4vBk?wH9CJMFZn`o+vQs0TMSoyD-tRwlSel?pFKCm zTtq4~qwpH$lbW@v198p?tZza9cW|{1Zme&9VpKwMy8kI=mPE=JY1QsMjuqw37q zy>y)}Wn%BB+4Da!s(<#)Kb)0Rqy-k0vk8&lAjZRMl8H{*%&r(|!jOjoVWj&j-%LLAFTmFf!jj4|hNF05x=Y zc%*e)Oq9R2G9jE$B%cJDqyqU}0aO*ia^mknfZ{ta7->s;S4RtJ2fQ2BN!HT^^!ES& z5u#BW(%-s3KgBwuF}Jub@bbaht2aEGYOlBV*>^DW?>@2Q5PtbexO{lbT0nT6ph7$F z%-^wd6`%#K10V(o`O6yX&G&DHcY^qdR&5)5+FO~!9p=mkC8HR^RO)+>%a_}?T=6xnrZ4UK4-&P*57_wHEp4e@ zYw=I<2)fhVaNBX_cJ?JjV#b^V#U!)Rd4ao03wB{5Yp-zx<}6I#>gRR*x36x2Jz# zXke6ZWN>V(ixQZbg=33IU}*udytWQjk~5?@su6=R5)XO+fRy}J4Rie9XAsB{;BSGb zH0E~@)K`P3bo07>FU@E#K#@Mi%3_ku8z&A{$9@{64^zSFxU+R=-$K(SVR>I}RB*b` zE2h0aGVtpl^olnj%E#ZE1Rv(14)F@t1frth*nCWc@Nf`>z#=lU$Ws*4vkNkF#q$fx zY>Gun%WL#2(=uwC9*16U#S6ncdrSoD>FMmh1N8O{j7s7tKmiy4ga9w7z(p{M@lK+6 z8BJlxsP6eUtiG5^CNBMVyXRNEt${P+7E=a5!EFnpizZfC!ch3rtB4geRqErDrC{fF(dtNe;XS zR`B1p1pkoc{dVG%y_c&mY;jD zGz}lpt&|Hc9Oz!UjqK1TpdDuBAGo8MK50s!kScROW2Xv3ZqzdV?(mzj@6dYLoUl<= zs*^?i_tvR{rw({tE}CX;mO7qBM&7=UT_W8tdijJtuntJDc?!_0_++ZcXWixfsDr&>Uj&a);oK+5x!r;Q5xHy$(TIYg1VqMtbY7KZxol;1 zgGOyuSYxXaMzX%GOQb_0yL&(c0v#D092bTGFJ3&KVa8FA9AE<*0qkJ_#>i(x3+4RK zS9@%VBTq42&B(8=l04PR^`?(|q-bC4Vs1vnb8GG}S;qIy8g#LP$mntVn~~2=99;n7 zw%qM|7$xQI$@eowWwtFV4N$aWa_Rbq#!^H3S4b**7iYh_9`^3{yijO_kFukgf%C03i3c{p3<}KCFJ6`-*L9R=JG_AZ)I6Bv(e) ziwPW)Fc)?PG54)!zEVj_YKBODqz&(X$-CkH!@KzP4qPTqI!eK~xQ^b8c`jr2x&`Jv!2M^kYK z;1Q_-1N$c!JT5jNIEe@mY79w<%FQFq49m$c@hB9{F0FDe7XqVCzgDomvGuMap$l7j zTaQLkZ112nj__mv44(@H9y#e3F| zmact$$!g|$OA!Jigo^SChVTos38T4#LL-4cuuLipM+~K1RF3k#!D?an zN5zPEypsWKH4V-R{~9nnV89TAe$)W>o_Ds;8h7;945;U7LQDo3L~&bWm!^Juh+RUg z6I0sj+oLj-413(c=yP7LDMn7c@^$nnzp4CTxj_b+{76Q2@r<5L$mw=Ng}EI;O}gos ziy;`#@J&51YyR$Dh(SH$Pm)&I-(f?6j~zs_CjPX1T}K26bf}Q59k--&ojv=-9Ft?4 zNcdOkjjTwNzDBu7fy!V6b@5DvbJr_Zzm-Z?k1HypZT8(AWluw7n$LRXKv+o#9ew2a zIQ>z9;GyrW3Gs~-0b*hiu`%%pLrJt*bCM9wwZJvLmP34_KUxC#>f#q0d>8xQ6ViN`F{2_vY=xH_iG>JkjeWw6J ztLacjT29XSQFUR#(FcdI_Ii#6wyxHGR$gK#AICsX4cVYbWo?KzTJWZ(n|R8N-P=6vrY| zxhHIzI&0>*Y8xW$JG7JvZ#@qdVu{$0C&<0U2n{jiEtewuNNLDwrf%w@DDrwKOt6a0 z>BVrhD?T!s{fCzz66x(j1oxMQ`D=KyM-TKD3W~Ou~DVTwK+jZBdWPvwh{;_ zp(q{}pk8Fx{>C8)Y;Xyq(KxA;7K?;V`zWW_nAjP5WM*prN(jQiUt}O8jUmzuSnTRmc`0dZhe) zpsEB?lEe#n8|=e;Zb4uk5dz^vF|qL2SQspU2olT(He!)EY)Sdy@Pfi(M3A$1SZ=jh zd1hfvqk5f8Ra2Wn^Uc=wZlPzD**$}T5a{UG&~rf;Ff}zX`=7BX@hknSa_2~FmrM#P zaxH}!SzHVXdeSL`#Ss;{IcP=O<+nd7&X?0x)O}cV6k4i0FTvoaZ1|C2hdjA$6J@>S z+PK7tN6YMmw?!b*qE(Ey=SWKuj$^TNfCLZ$+y=M6Paw;g;P9qW?6k?Flcu(qw7ERG zeP0n8q##PP4bn-t+F7Ze%49P>V&bI|%e0sOE*3dtFqNpuUj(-5wy)UI%krIuEb#}8 zYZ@CI=l3o z9M7&3wS#CsW!J#)h)Icm$&T)}lX7{Xx1vohsnYZ1sfG=;9;puKEU(a@4iUqOxy=zt!cpB*Wr+INFP2=XV4-`|(gpli#`EtGawasz6!9cdl~C7G|HSv2G=oFU?^Hv@ zvT_^iv>#VmuMMOQekk?Dff~+&X7>P?eb5?b$Uq4QG!z|z4h@fhM4^M?xnMwYGCV0oD<#=8Jtg6PJY@OPQ8fdz z4min<7*ysbUex|~GJ1fxBdLmp|Al30l`#_VrwU!$S#jZR2bo%dHYc^P>|;8wt^)hH zyPTzcd8G0?uK6>137Jo9+qUe7`YGchjcVP?s4)0%g*--kMfY6b%z~nRQ1`$mzm$Q5 zqnTmMo(d2kDCI5;$N)>M%#3V!dL|Jf-W-yjTA5O+TwYZlSd&=M&|=agTi4q8wEZ@S z5v%%$5{?iS4?Mq@n>;aXJU%mjYi?ngdue42w^%#}=87vP8T=urRC=+{Xt9B<_K}}9 zZ&dz_90|5nAwa$D;hlb2F+3)|1gk*shDs!lOD>%D=+~?$e00-n;Pqcu*IKj0F5f>T z5h-sJa3%HB1$BKS*f>qU4sR4A#ThH`0=EDKaI^qG?0;DhO$v6Ls$j=y6eJ?~B8&Ug zkbTtHHSy&pyDkZTYsxdk0b$u=1^VoO#KY z|5D&;|3F)vn(44Wok87rqc(EM>ZtF!-EF~yte&FTZ-i`sk1wgOyj(zFFdKsnI)Xer zGA23(7v!=4t^czpP~?Wl6c>X%!K_jcW7td9IA-JE-VT%V3oSFJ#u7_jl8x`DDHG#= z#0wB!y``tA8$rgJePpLzGENou@?PnkoY+pHQ+Ow!x4Phe6m_z{in?N)nEii-<4Cw4 zixsz9L6I@`MM#>DmvJgy%cxrpN^GC&28IjQKJz-s4m>NO!vi+nkj zF#W`o{1{`!6@pOww$h1K_7Pu$y<<3yo)8(rs#lkn01!!+(Y4>wP)-~z*>f#rZd59L z*!9FUe5F!DRXHtpYF}gFT4(FK&(1bmUkM?e9$>ZO2PJYf1wzqq>|8)8+BR4tC_YIS zM-~!L7TpuPB>lveM~&P*Zkpus3sW9R*;&RLt=1){6}6|8E#^NfTZw37T)IjfPT_Cs z@|ewTL_@8So}qkZsOGh=qsh3bqoSvI$Kn-ka}EsJs8;#4Bv<#IJ3HM@;tfXyh$|riQR2u<4$A!aWPAJm@;|j<{4%K!1G($tqO!tH$o^MWtLsyh_=)f5_dq!lqQC zTzEJc-wj#c3e|5{EELH!tpG0T&2OT&9ZN}J%N+TPOTGg1w%vN~jWN3x#w zrKu+7^kwTM5stE^wWDv0N^NroNE=U8A00orD}*E=p-@yf4bcVAX>swf@o_Opaquev zkcezSATJ+|J&2+*KqNP(+NS(rWlf`D-Tj89Hsxkju#6OWcDJi%kS8cKG-~L1E-*1A zR0W64PcPzb3anE-PCB)O6LqFeKln^U7KjErHJ#vpq6{~?X!T~<##jrb59jlpi&f85 zxNvDh+qrGAT=48!x6W04M-EA!VPf6|4}yw4xQG;&;PwSaXEQHr4--3-w}P*szm;cD zu(Sc%FD4*@JTgk`!M!v!Rb^-v2{h$VWHKC8TvT8NtAde&NM&_HRfPgh1o8svzmPd2 zP}r+V@JHKCDnW-1b8Fi3T_xscD@r;I6*rfZ@n!ele5##QAYkHmZh0CWC{aRNzO;G- zu<6_~Clionh5HnUhaq;fSv#~pbq|Liv)yz_4IqE!0a<0Ds?w;IC78}9FWg$QSD zl|O5P9kiU8^|kG{WnZ73@?PCyx`!w!>1^IV-MKrYt*X6@F`wpB)T_ns3FTVf;hFsI zI=~uzRP)(edZROFhrBxK`IfdwkfieP(l9K7N2ZXEwEn()WS!aba1`?p_W{)E{f z3AyJ#Qn?v2&c<0&hIeQ46e@CucNQ?6)qYqWc2(Uh*OrRt_1NHWT$?^e=3Ti!hu1ra zH1%ckdzz^_Q=iJ+oX9L)1l_#U1Bp@Ql70ei_w6)7$)Vu_%JL*h$HTHix7$ZEhyf<2>Oe2&JDG7QRPjiW3f-7x?3I#aTE>0 zsjrDaOaBB9D*k-qAH>t}1o32kM?-8@w)btFyM2WVi+D1#N0b6TFP|TYuOB{m+T8Gxfp|xY0Az9G z2?^wAcVY-ECQA&Kn@I}pvDEt++2!UXvSk&ukE(9f)M0$!X-&-?!e}i>^0U6HM1@8D zBdoyC=)`}vXiq?l4htXH?l)qGs%ErJ@mhj@9nlfFQp#~nSz$D3mly-$LHJ-~FLin3 zknslvI@pF)AL6I*m=CEYkUhHUppkp462%dd{4v;TcB!U+i=b8K<9iS3)6~f8r)Rgg z=sZwfaCek13g$yY9_T@a4iAisLi*!+=N#ClNS)+t>l0hf_z#nAhJQG%Y?!vS&YgY8 zvr5TtVsV2edvCi8+Ij)yc-0Wuk)}eX&mP#rdb-h^*GHvL{pPDjn5MTB_lwq}lqxLy z7DM?uA`Z6a*#S6G>$r~phZhk-1Hh^@}uA z=NRFWQ9aUQHh*hln!iG1BJaxXZ> zZFwfxCg0K7#}9!H4fl@<0M929$EE}mrsr^xNiuMX=6Pc2XZ!sUJ}DntO>J6ZdmK`Z zOird~dCCZ(8d4@lvB7J@+YM9}EG6IlB~$grorTk*PV>L8=PrAA^^^RpR_#18e*D0@ za<$Ta!1BiEvW*Lo(d6cArP8AP*JEl2Clh;DTVEH$zz2%RFi-CQf5WJlVE6FEdy!hs zHgP&3j;>kgqHzjKW93 z4i1=nK0WbbY98@oXyqlF+3G80oB)CY`an2900#G?lK>I~1L#g0VQ?q9{Zf^X!8n*g)b+X#@%ahf3W2KZgKXZ3z6cy)HaT=)VbE`-$-)Ox! z%5o`~ojB@B;&plBSc>w#3E3+T=xdE@^>e4y8CF>1NjG?1Qb;o935nV#GWd6$@;yfn zc@q`9*u9BSNRL1o>Y&i`V!r-z`VkRu2k_QYLUOowBzt;hTyjosV5(PobXshDUU>yw z0n)d)u(YzV$+M(3CM_HDtPuk3>FovwsohQ`ZlGnC(LwBE8GY3rrwU~k~;>H$&-oc)Ny!>j{*9tDLam`9;BV*OLJ z(_E;z6Z81845OX0N@EP}62cX4LG$Y`K%kiBre;iQ8>FM9t-S}@*;56p%7QeEQ~%U_ zW)d+6OwTRPEX)ugMhqaZ=iArb@V!#qeERzB!6(Z1nvkW#?}wisZGEO`Afcx~K}gf0 zq(h+B{m!bq3rXm>AWcomQDD|SzSapB= zR5nZ8NQVvB@k{Qv?hFZ4wUnd`ceTzDZ$9RCro1@Dob$?1W?lMo>T^f|{E!t&rXw z$X7=Xz*D>weqz- z*?}?8OOtahQ=$@F_sxjvuGyx)hpRa?!Y zCEkOZ$U9b6mUb}Ss~kbxSGlf)goM+Q0(96J5CWE(nvw=1%~Z(9%1$dNglCc$C;v^& zt<5FJ(Tf-q_9sM*GdB4RQU9Fv{;GVM|FiPZ{Zsk8RsLQ15d5lq!okW%NXm9T)mGQD zNkusniRa{_bd8&r&!0q)5FUcUgZM_rAkZFQ%@dn)1qM{)8iWZ`Ei?6PYh$3O(F9&x#r83U;i*5wh)7J>vFGW4qzn1ac zz)Mr_NH|4~V(Vjeq>Lb)1^;zrlbJnu`y%IT+q9 z4;Y>trI{z8%4@u{w6t_y|7idgwSBM>xOJYVv=yE1U1y9Eg?L8|^%k7Z~W7U59`Fk%jiJn{|pa7h_Sz$!}{z3r( z@L+$qU$BEuG{}FAk4GgWgeMEdC8J_kh_dsXa`TJy3yV)U+GN2>V4u_2hAt_&xdD*}QG$(VDzCIhq9>Es^VY2hX3Xqpr}6w9Ii9s8z|+wzv%LN*oP$nb&Og^#t5&^$9#;j(C-4s*`rA&Qts ziW=n@7Pa{pWpHFT(`67xrN!zzWT`i@X>YevhIx6&C0CXpx{7VL%{(B!ct7e>R2ic3i|UBdHgEGx5X8};h%R5!KBH7h}i z+j~TwDR!MF8j7bHChaCqeO^d2PF_ShE4+wUPKdn#eYFAYeSI5vyK{Tu%?XG8C2q?6 zmkmM=xB(YW2DF-3^@}r~lchLGzIVAKD6&c^{s%jK@7F0Hb%>#%@1y@=eyjKFjOYeZ zLBE<=`cwh$+rdUZ1j)+2pd#nRo|h2GQy>X*SMWMXLN5yp?KwL7;n*F=-aH@&^U?`} zL7AKBwu$v?_2$&KlU3Y!dTEj_Nh793yU)2xlbiT=U)oxB=Fgd)PbR!85y#oTb>Zm{ z3wl;B%3kPdrVTx9>x$*k_J#OfMl6|AX(vs3+VDU>x6{daJzQ-Mz( z5r;?LJ|FyG`t}*2PcKO^FLUcZnpkYP!V2pC@W&%o(3y-*N(z}!c~4>#r`k4 z|Dm})9;j8GM&Jc3oRb}TYB$3jpiC=T)!f7bFwQf0Q^Mj-N2RwcX}vsRDcba8q<8BxvQ;8Gj(9gzWp!Wn))xvG z>qvjGd}AA10_w$F-d)oPH`@5Nw>8%0oJ}-(_JV{Dh=RcLjaT9_9(w>Io^JqQ5GzZF zL@m&B1%H_ z!aQ13zCwgL?onqZNUZ4lkxR{BlgSh;js zah@P-yN8#w;-G4ZnB!|1P59W^DI`Y@jD?Zf>-wvSSNbDa%_hZ3-BUHhtDSg!u{ZF@ zKHLA`7us(~d0x==`qS6Wu>J=)@Dnk(TpU0SIuZxv{GE;e-&7)B=wxJ^e3S|Cc=4`r z2Kfi#6T(Skcp<)V@rVd)F_Mse1(ubD$j%|nPDI{M%_uWSD#j%cQ-E>${TmgM*#!_8Yk=i9GUQLNz{AN z30kB=ld`FF&CUE!Ywd*B19)M*t_cn83P?$I(_m?6l#nJ}{J`bxpip(6hru5o#g3#* zu1~S~i&H;(E1<|!KfA!oyK#^<(cy66FC)H%dq{65XHM5Uj{}|r1sWRru|Ku*^tSfa zb9)fMNd!qtgTd0%;n^9f*+f}+xp_pT*%j&G$?SkpCak_O6VcoPv|$=r+M2o=Nt*|1 zhet+m>}Cd1^?yY_E^ovPREy!{urk}1qcTnS)asr(Pw~lFGa`oNwk?c;8#@7)>U=SL zmZM-^ke-y0o>BNj2}&Y!iy^ONLya);n|bc)MSG@~GG;fy2O zCVToVD%aI5^&bZzIMNt-+<21fnDw|zG|JhadV?=)>&y4zf;o~$$@d-%!$SJE8m{*) zO;PP~xsU9*?K-(=x_SEflOc7T@q(?zcmpDhgLJ+1ZYs({h@w&-Kr%AnM41^dSZ)R! z#u2Iu0n)12V8!|Mi2D4-CeqSiNcFS(we)S}-JJt0{dB!gA;W_c7oO9OYK~9N8_qnQ zTX^{ZD*K9XYW4LMuvT~j-nV<1^8Ns~Bq9UN>~z8jU;LwH{RoSeq=~X2GVNtwDrc^U zPEpT)`8kg&=Lvq{(p-MYVv&NWt5Z#-jwV5S*F>4Q=t8PLu4y+c@6=EIl|gJLf_| zeqnHRZ3Zf~f-A7jtEIi(*_9a5grR~$bcP5a&|yO8*!bZ1#PsCw)bPw=A04o|2FJ39 zeO|u-sRmmcyYE&m^nN^K_=F`Ikbj{D>w`bMF%=*ROsZH~CBy#Z+a^NWr+dEQbxhej z6^hCbiYtN|vqU%F)?J?c0JxXm{`)a?AQHT2fMu4-fkZ#EgxJ-$-pb0XA}g{}*i$db$cTYI} z<4}tP%NXpWIsCU9+~BlZ;D|(b7%CmP^ilkW4v2mK+8DTVea}vlW)Q4Ds6(&_%Vx{th%ebEi#Y^3gt&b zAs})YNf;7C7?gM!NJ)jKre&lcvXl@)Nrg!TMcBI?q$Rj*7cppopXdkJ4MqaJ*d;4x z2uXYz^M}N~hxi$0^f}#*W_~9Zgu26`scY2p=l2{~aeT@PF7op@eGC>Vr&=fZi9JhdlSOS@CX^E1_az9sK;Ys)6ie23Ck zvvk^ysc)T6*QYt{=FXHDtFtC5s3nbX#JOLJ_Ih(NR zIzYTr!=;#Qy|@gUF7KWAPS=qVY%D53C$AcQ4*eZS_cfy#v%RZj>Ad|p0sG559C8iI z`_9cUL6D&JX9HRM(Mtm)0f5Xf9X7#axsw_F236YHC9Sx+{)hD(Nc1@QXb1UCsp$_# z;u66T2|TU|;AIt?>o;>%HaF&+<(R^{4zJQdWi}-6?-+x>0Mzj90?DlO;eEQci@5aU zU~oCA6JII(X4u}g`-wiiqIB-?YmDvTN#pOF?Rn8K+>i0!yN0jpT%Wbes;Lpf2bYzC zF%?mtb3D!J3|6^EZf7z_3~Q)4f^pROmuBhz&zF6{rUf531%}`0F~4|yoO^Oi;5&K% o2l$TKpF98y1^EMVA}GE8lal_|uPZgUm#K|k!3mcCk$R&43tC$PvH$=8 literal 0 HcmV?d00001 diff --git a/doc/iterators/line_iterator.gif b/doc/iterators/line_iterator.gif new file mode 100644 index 0000000000000000000000000000000000000000..1a664ab5d9f83bd6ed10bb5fed472285f23ba278 GIT binary patch literal 38873 zcmbTd18^o!yEmL{E4+CvYexrOlE0SzmkX9QGBW=WY-LaXFNf$2tSuQ_^lTWI=ouL-E&uWB zU)1&v3V{E|jQ^3^Udh!4z@PxIw|2BM0Q@B<{WtU9zWd)5{X_WI8g4l|)4zkFXCZ8D z;Ajc3a*z<_CHdPzZ)j@BEh@+%%EZLM%E-aY$j-^c#K|JeBq$=n#l$Ae$;c%t{BIfm z6R#i(D?2L-r|{nk6BCmN>n~Ozb|Efyu3y4jLc*+^|KXLevUkw4G64KrujyaC|II7( zzw&Ym*#Yz%tnHMntu6i?0l!VG9jxt5tZj&d6xoR=W%LY8t^TQ?`e%Ut%U@xDov9PR zP}I)alIUMO%x(HVSRnfA|I73L;x+vL(`yWWjbZpFJpQk6`FGXd82qRBpWy%d@SpSn zSpCfzyT8c+3jF%~cz=6+d476)xWBu-xxTu*I6pf*IX*f(*x%dT+1}dRSYKORSzcOP zn4g=SnVy=Q7#|xQ86FxO=F(<6Xm4w6X>Mw4sIRN7sjjN5C@(85DK083$j{5o z$mNlr>kh>weniH?el2oDPl2@VPj@b~le@%HlcaCdWcadvWau(z|dv9_|b zFgG(bF*X7i8tCik>S$|e{?SlZQ&mw`QdE%tEhj4@EhQ--E+#4>Ec8oIfS-?-=O;H8 zCkHzlD+@CdBLh7hEe$mlB?URz4^k3hB0>UuJX{=XEKCe^G*lF1Bt!&wI9M2HC`gF! z;NQUhPBFx<;NQVP5J71F&Nd+bOk5z~z?xBs@=nh4$#$SFWt5?5mPuKa#d((v?X-jC zwoBEu$2G7g$3~nMCwip7Zq$N1d#1!evQndZrNU|a(ye=^#zmSwefp%qZPKcJ`=-T1 zwtD^grNe9b`W@)w>*pU37!({58WtWA85JE98yBCDn3SB7nwFlCnU$TBo0nfuSX5k6 zT2@|BSyf$ATUX!E*woz8+ScCD+11_C+t)uZI5a#mIyOErIW;{qI~NIp01L9Ry0*Ro zi?F@DvA4a2uy?$;v~zxOd3bbkvUPa7cCh>SbawgidGoqPu~LOI5Q2E_>n>)S-5ahA1ffM*i3J^wBOpsMn6cdlOQP#djd+bb91Wr|jS7&k zH=0gB(}}{9Y$%b>X0pW5l3egrC=%g7@R4-v^>I{A*Y2c>H6G4n?GJ=IPbeR#)alle z`4fM!P-Eg>X8Ag0KHki_Kc|(xTp`p+ecb1G-b}om68xvt-#rL4~^E@cDpxl zHBsuKhF))in@e#ZT&=Eq(u)6BW^##Ybx4b`DPRNH#&`^sw|{bD`pFP7Pi|aEE3LVG z$2hY2o(_-me7qd8xoI7l9dnf|vEE<{@zG%~w$Z)%!j0o3MWuI{eG}i=@P2mxm|$wf zR_^k=C+SR1&Za~Aoe>3ukBxQVeMFPt8*hy3y< z5SY2V?f(r&4cBjqN<5FhAn4i z2C9agr!ko(W~F+W9&>=btmxRn;waCrg98h_P9+o5$H6AbJl{7i%FI}tF^sG)-L>eV zbiOc!!UzpX%;L+KwoP-TU({t~iK%T-<-#gdR2AMRXH+@mUTZ~_C$rpC0g>9yG}U$5 z+_Z(Q7$@g-e$24c!18Od^0@l;zSOd+L8EoT#x?!+%UWl4SSz6o(RE9!!#Zrm47CaD ztNJbKB>Jl3FLs97N0RjG_QkuOXDzgOXOtZezi1eGGEpoT`aWLXXjL_N%E zurxl(hPbFIs(Z)G@XouC+%KwIiR5VP(v}cD=6TeS56hFE8DZ@wbn&^fCzp0I>Zjbd zBJL-+>0a!n`50hxI9UDruh6fO;C6zjEgO~G5slLdgQ!U&?JE;xJ6XrC!|>CVnf@5W zO*32L7x`5o9G=gs2xn4BtnLo8x|uD9axA-Xq$cG>e^%~`8)JGM6@?Uw-1EpR8**m4 zp~{l06EiXP0FN@9uUwD8ZKiro3X-kbj&c!g-p-0pd)kh&{R!SLvWlzT&WjOaxUVYO zr`k_5)@9!>ntUuf zR?0Phtl?U^)a4m{KJ9ZLXvBL!VQl>H!FM6!9eRTVVqj2y=s_u`bRp9h2M|mUL29`$ z;T%B*kt7g9Ag?g%Ro(>h(?ZSqxd@R!Km~Ih>>}WD3Xx&V1c?n`Ma4h~<2u2G8M@~o zG@c041DS0@;o$ZmdO1ZI_-wpoKJu_JjRt6kYQiOy_HpJZMY)r1Bkdv#@bT^Xs0wPr z{tOt5tWolF)-lGoZS3QXnhc9F-^GSU6!5=M2J$Z<#Rh*6V!);jOFN;&q<|k%Fqn$V zQ!B(cUqF)O>yDCG-P!8;|DeXF8Wo_i$0y`F04Q@yrHr-|5=}IVSQ@E>sTJ;1=V%W(detXPgILlI(T=&w)nhH*>@qes zhLIvAMqUP^<1Ye^e=bYNa**F=_c|0aKc`OlFV3fbbQH0nx5@au+2#j>)ZF75%DGqQ)$-pj)Oz1k+SU@w z{CLgvSBWPmKtP-(?X!+*D7sFSmt4vWv<>}>+phGU>c+m&T{E|@uCz|o=Vo5Ku>M(_ z@x5-yeAhDS9qybPyK3BlC43S$|1%paSDh~y>jQztl}}b^D-b7Tdr7q+jQuPi1*~8D z4fCUDisxAv3a3gcnT9f(-J*?&1akJ!nPu*CO<(8xR=37g3wQ0PY6o(2c5kz| zj)e8vQai$R7h^l~=AWFrcFqDA7q(gSHLue$jy1zU95u5sq)A-eue`;)ITR|rMceA= z-1sgUnsFwIj{;96>?LG|Cesq(np3?nXzh%ra6d!X}R#_?*8 z<*>|`eeSo&T|va9N;cSA9=(dwTCz3?*&!HE+5TfnG1D=e&pY9j4R8+cw?R85hkk0> za|PG83C(>mFz^_ks|1{7)bFg}>xcRp=4&hDq|240mnTk00w7=@@ukYlmTb9hC1q77 zXz`m%bw+=Nbf4~u6NgMh1J`h7t{SU}d5;L>+*W?muxFY_9=bZWZFpHdaXZn0bSvRf z03ntdjd_}BtShQAj-GNAd9Av4-xu7xnm`E9ZmyI(e7<2i_xfMx#kjTa!gN10OF3l+ zr%#W<`aG4`-kBTar&{A;I*hSKm?99aZxJ^)j#kPXX;BcdU^ZZt@o7}M)n-k-94zecHhR6BgLlrai=8i-`Ev-?YesJB|{IcX2n_CSvT|XOe|&h)KCb`*`4wJgKajG7pu3 z>usoJrXi{ywz06Bl!`K(*2U8{yP5u?ls9V1kT=VPzcd0s-YnfJuBfuCZQ;|;kqTE z2`wR+wjS+j!GkWQyJ8_hy}mIk5s@yD>mgxGf|2T2L7O2_b7B#tB_X!TQEKuo0qCKt zP*Jxl5!pu|XIQ>Vl#v-PQMD`Hv{+&95SA2zVYh|R#Vh{rFYv$@_Y168PpD|b(ZCRq zXfxs{kH#RV(8yz`*wd51jh6`D-LOoxn7gHzq8Go8qeyTluPL=iY^vyQtH`z|q4Kj~ z^(js>j%vrvn1Umkp8^4Cf`)ufTD^e=tkC9uCcrq9ZysLpUiOf}MVKTElk<&v(=pwP zp51EuK}^+Bd_&c@>ovSqQwoBA)smEw=(PdJFx;?>*pCXv& z8$2ZYdZ;F$?J@e71YWiv8yUx%V({a%L{+=Wq8L*&nnqEZ1ow#}SGuNihLTf5N3I{n zG-1bv#@aDKGgXBK4y$EwQzep7W`w#V{xHqB!oq4e^;VfSAT}gyN2$WGtEbcE4uXqyV$}YqL5eGG4jja7MGvu){rSoxpShpIW0| zM&oKvqCZwKzCu&K?PY;+XUvLoK}aI(mFB{Q`GJS!QmDsu9p~Pw8?SKX08?`@$D-R^ zBh2Nq_g%Az+VV(o@^+9i>OwscV6x;xV$XeZV7T)M&9Xq<{K+H>D8`IyTMNX>*aUDi zpRlqy*K+u9^pVmEV9yG8+zNTA)8%o<^Cev4V!}9vu%16V><5vvOO(l5{sdc+;Vz86`8I^b(KYq zv6oZ5Mfxp=Chk|iGx=Dyf>#;UM4)mGl6g&yB|y?3Nnux9&&MmzBk#FtBl*?#_12=A zCnWppv=Y~@kyA7}yTv`L)1+&-k0wVitNX0hwNbd%h}5(FOzE$8Wm@NL&aaCdv@XrB zZ-`H+YfSMwO(`>O$S?f4j|$|CUvNR)THTjpfMEz+oDK8EPvhiwDuzGKadB-G3ZE*{4T@q=^I!|?8*D{3-Fv4kBNDB;* zvh3a~Cu?cTYj1YJZCf2_d7)@!K5e!I#0)nz_N+B_>zA@fw9^{5Gkj}r{Mpw0v(X;V z7WGyZx!x)mYgxu!;2_meVASCs+%Z_*p*Pz+<*wQ>9@iz6)`~Q-|9LQqiq8++1khJ-ZsGJJyL&OwkHm2#41V z%A=U*Le4>l)!<~JipK2ozTT^ZKPwS#&@6QVqHj@0a_kN;^PQsG`ijDqcm!4m# zJ-Cux3L7j$eHlwX6aQ4O|E_40;29L;>88Wz_cpH#V{51RXw{z0Wz!tm==~GH$WxMINSVzdr!xPWGi?Ku_~E_*EO$CFvz zKK2NaQ;XrpC<;$!j?@Ik#OR6Xc#G!1bNjD(N8Ri22@W{V6rPECy!Iiy@lws9q>c{G zxVqTK=*E)Z1=!VbIs`t$oi(i z=`5ktY_q;poLYchA_gZHr>$=d7rKnEW1B|fWFZmP1PSIP#YQ8!L7rwP3O{uD-%Me1 z#>6p@N=K;l3p7b`7A@A=jScQEvwW+3gP8A|4PH$i8f~%q*6ttqGX>~=PHQPjrN(4ZEOB+|z}=}7YdMu_i8Iz}%5Hg0a!Jc{ zY5wQp&&s7~_r{S_bDPUNt9f*xl9*7-l~?fvyG)Lu{nf}tqwGOR5zs%TxOvbQI!dZ%S4Vm>x-;KfGb$UMzO<>Af8qfNfg zjV2P{R<2C;e%%4n`xb>|xVA2u}aVZi!qS!pojSC?7jVZMj|n z*O1*u*ey@XEH5tJbo_|<>PVMw`?d^QLgp}Z^Rh7NU>CpI zqw`X&HoiP-zV-`KtAF7JvJR4_Zcq@dX$0*|mHb@Do9b75mjxDPr^hv6csrR5kwRvCR`5xzk+h zvwXRzSloL9{(Ek@dtucgzA&OR{)dX}XK}sSz!XXu^# zq=Uy{#HZ2j`*{BSnC)k8{x2tvY>VsH58W3qffr(i_jS4VP3y-Jxo3A;;3dygbQ%Ar zR2hCMA}D!iL4>@l^%my&FL{Hc+aLI-hbl4X{4TV|H;r68s?J-c;DJK=vo6BqiBdh* z`{RO^bJ*zYGZlGL1j~AWMGMS8ff_Y6xXIKAnlIl5M$F~Qfcu`3&yy=n7&N>eJo^3j zXZaEjeF~xVifFMNsY3EBq%Iw5=J^*R>vh7V_HXmJmHMoo7nB}>k@(yJ9)Cm*?4%FF zJ0jO3nWSP2WWbMjpTw!Wq_i6VM{$`&Mt6(tTVs=Dhl1vw%u}i2F}4U?k=)&`4OE{J z*&2|OPY+;aQ_F~XB8{2e;8jxetSuRE0`b3h`vRyjIJsM*e6RzMfV=7kzBcQ>xDgoJ z-c5w|1%u($Q=lX$4kJA2N*__b%k5wWv7tkt8OP^GX>TR%&ZXK26nzK50`ZYJGp@{G zGfm>blsipUmci!hlqg>ODL~)Z#mp^mp;iYNMPW>5r&|Ms+vp0!P4-o5u)FNSA6L2D z0(E>XBePMx+351WY`T1RuGa29*r4{Q@Tu9WPgss(!{e}BpK#&$Qw7J(dOT&nn&c#< z`d~6^-`z!!poGrqzv+c+u^d#^Y&`^%l|l&u3nH88@ND(;2cM_3AT5}w6oJUj8NnFL zCsQlb0*j?{Ib91keR^|G1P(oC)E9^OsMzNkfj`1SyTMy`8JN`#_5AuY+>SWi1T3SG z6L1Jv_2GpBiJ0cM#JWK2d;7ry%Ku4k;nNKb?=jtrK;=OWSp|Wn=f{FVOaBew+mG8` zbX;&-lsD=DBq4aYmnk6(EsI+rF#7^xR0K4o+F^W8R+J%3QcXJ{0@@1sc3dF~lws^r z={Si^7->6D@L*{sQ6~o_W+@6+VboE)oCuUAD!>oLan|U9`iZEPjCoL0I${NBw>=(3 z8Nu@e``=hA7Wd^G!w>Nk0+k+U<3D{bh&Uuz6ql`n$GeIX^lz$ zW(iarP?~>;14Cw1R-Tu$Y_wODv+q<6keApTRuYpRR0J+7n_E5(yFF#FNvmLcJ}sC8 zXR>FAdwyScRS#2g+wcokba@EOK&&pcKaV}Odh#(<~tBbhL8lLH%PMc<*aK6Xa)BiYZ?&fPV zuif3+;o`rlV&F8M8p1ux>?V-E?&#Of&})0FO$TCG8)=+^qf%~j!`hVi8=hiAiRIqS zwBCx5yTB0&CXa&7Z4{4ps_oo*kW6cSr?t4-f3&QE7kt3_7-Cuiw*dJB-!|3d4Lr?4 ziM^kr2p%i*V~6w#XayktxH~A-_;NukD*Zb^}o;&fIVv6k3M>0Z@g&R38#U=+ZDEB1px zo5lEJT}Y7=so^1d4fz%bP8t!dBq3DQ_`(Sjn}PZFwwcs05;(|!$uB_>Tuo_5`fMXk zVRG<884wIgX(3AN37s%8kxHWFVOA9j{Q$05hTygALDYq`-LR2zkd$s_MXA-}S!>zHHHHLl-$fiF zMLxQ5e~ajmyo2wpme+5<5QoeZk$uiKKIoti4P649%Lyfc|6`cq)re#iIXWV1!Vp)+ z6=h9uS2{{wc9+zIr$y-~5u(7&l2#%d zz({;lEq(+Ns?}h`kb4@e5p*AQG_b~6e=KD~J#V=^OMcC~B%}H@n;C+4%$4psZJbx{ z9IAB8eZMMev<7FR5@sA>Bsy)dRu9andoYGN#4?#xl{ZLz6>LHtvQb!J)70hN5OGaDFjE^%F4!c-j?n~l1w>VtYR#Hbr1m9+rtew62(?|EY@x;O7ml)@n{a*7Oa-Z= zE-D1lcb`sm!B^4s<+;1WymFv2ol5VT24@#WeW)kJ523g}v{ovB0KmxQS#kU>cT(`kPwsbSS5{QV^Axn5xAMZ_PGRt7?~1P4d|#-E8bBJDD7wa0{= z&B4_!>rvB(Qpz7X3HM+Ibt!-grZIcGNPJn+aX62kf;cJ_{M*ib zoruJBI$QfT9QpS_yuhQ}mqAt}g>oWj&|df0Sb2)XDegR-b@MweR2hLj449}`SF@$B z$e7CROU&Dkc55JdbLV%wKbPt-{GJp}sih#3GBo)>!x-9r!*>s_ zc$k-41oKQF;iAn!FF3J#&Ry!*p>KGp)ith^UAfQT);vyuwbQ|lIvX%-#ne2?klJ3~ zr?eFJM^*KmuW0i_X^wyoKUH*6T3bnJlEWQW^egJ>IHYqooH|vHe!IH$)%m#(IV{>o z5p`!B4?Rkp8Xl7c)BvP?(>&xqeodyjvd;~t-mgc394_CtUUTbN6qB@#acR3xMf*Hf zX?B}Q^|~v^)O2EumKZihcql%W+#n@-o%f4+tVG1ex4eGsKGd$uH~x7FmCZ383vox4 z0*a?`)x1?o?=s}rdG*oaK5@_YRFRBt9ng63v?A*=#7uA%#Lu%b+4Kg(7PlbWne<6$gllR|Dds^fK6?0I$>diXe8*|m~E@p*Pe$+Pawci85g zx=?uT#ij};M^U{^`A*N6q2z}QKZ!g+!8`|$~H5c$G z`3VA7TJamE2luBTssOTDNlrQ?OIa;$J1Hz}^VoY8C`>QBkT1|6K;k|U>{riW&$oAC zm<%5XB^JJ>QDnRTLY;a%IPfr)^IkL9>H*teAS&yaOD;1iY)ef9jwA~^4J*>GdLb#e zex#tEEW}u5zo0aJkz3T$OV?9Rz)@Mi3&j&ph!ZnM)YE|riQs}@Oz_{~3cQK8@156S zsr4wf!_PB)kJQb?gc6p12dBH~o^Tg{aQG>*(O-5}`Jg)x*Z1@DC!ZwjfUrf+^EaHe zRH3*0eqh&Y9K-n?L$#`KVT5Sr??=}c0UL}6OjhT9SIi>TH`T}7&O12GCvTRNEa~K7{Ws1 zrAiqruNS#}7dfIC(iI+FaOblAA?7@QYPT*Tp~Pe9F>EO`WMe31VJ_l$&@7uU&{>W5fe|D8)?FyF%FI!S|boh*QZRkHv^Rt5{IPh;%}~-#|ZC!thuAh~|NKV7hoX zPnWVoikI++<3zXTxOi5|2-wGPEbD0U#h_J%M9hQ)=W6M0XjRI_sOg1xnqg(+fOuws z1hDK)!a!*#A8jP}gEAojGtpu!@qi=QLOkb(WHFkgOTw5%uB0cNq&%Fs*Sutv$58FS zkUQ;IV8dA0!H6yRXuXG2x}j8qrc}kdq;4!}EQ%nYr6VVvw-%O>m^zVTXTuj^n3X{K4?Btl=w_|hu5H-%EHAN#AP{-r;9Q)*LGb#$`xZL$a+Y3o zl;k)T!PsBII%a&EO88q`)2%5xi9m>AU5w>2pRrm+5( zaO^uGR$BP;gCmO923>8iQ~vGE9Bybl763~!l9F@-8t^aNt`wiLgeO$-yc7kQUl6e`{b8U=M1D~2?5`UEalNXXE)rZge4fh z@@A{>N&?O1^xYMXL*|Gx6*k6aY1rmB!)HGRYTu=$?DfkT(Yu)%@dzThetrs4U&^z2 z@-DK@(TmV?PD;TEL54{6ek~}@1Qd&W%JEGq@)wekG-k2OD9}63Lv}J1Moa+1@28vd znR(dcB?|di9TgNd6$Jn@cr1*kWIxJMZ5BWpm9@1Lm8BE`pNj183(}vzO&=AEVLJ6iN(?q9m_3*Nd`^FRRQau}y!c+D z0_aF|8CX46QeRx^LS8gVRM3)Ia)DnqotR@^o#Wu0<8-9>l3vKRP<_~4l9=pq)lxBb z#JQd})~R8Kw}wu@X{dnNoGAglnz?9{n> z+PhM`DFb3BkQJz*xw!%@{cDhsg#k^7WfYainREgDJN6zV4BYzDS{{$_b5h4yAFn`3;bYOmJ#c`DM6Kte441DD;5= z__z}S#TfyYn6)1ot6iq+>@S-E4?OF>$_(v|WF%KG&o3gx8^T{ULQ=CknMx*HD3m_2sjORO8U%HT0Z8#9CC{?1kNTd{B zVw6vMRP<`ZP5LB5dtX}HNP%NyqQ1R&-Semhf}gw0Rr;qfdSJP`Y)eY?d?WEAean`< zFPG7OzqYu$wr{bvX|i@{kM@E1qmC_nf}`@%~>KoQY>Q5A#pM}u-l1B8MQ z-;N%ztsN%vVX7l)mLUVtB?B=CKyas?8!JI3&2V?^fzr@{a+3j;*P(3Gp8&BheMh70@h<#-nX=(45<4DYpX24dmQ4*wmX0OiBHcQbF$=1F)hPDO) zfR0+*3PM`R$p|N0`w}o~n`OjZVno_?1Ttl$yQ7`5AZ>I7t^0LUKdJq&`n`os`4xZ9 zPS${7#h5JXhtAgbxOr|Rsog7^E&d;)JX^EjL&H~qs59lx&diM~>0BCV(;?-)-WXoy z^1dN0mZYOUY>^ z7W*<7ld0n-Cn=nyc(}w1+m$oNVpRb#O}eVLJw#_d>KSHoI60wt&}a`m6S<)QyOej0dKU(cTdf901{VjfD}yCB)VzecOw#$#Rxu6x!83!eQU;HOlY}`0~y7V&g&bqwAz=tZ4t| zLK`rC+cmyx!+A@H>uW-5>wBY)UbwqmKD*~GMRZkYjO7c&>l!4EySVh*m#W*#_N&_= zOENiY@@-6dLPiEmOC{nv(+C;l!^X8PoAe2r*cF@gSvze5`_8-`UHwa6a&mm5%pKm) z_NmMYMF&ykpt~yLR}7d3m8;glOs-`nAXYPA9(Nzt8WeoCXdT~_e|WR(r?&CE15Wom zIwKvS|AMkTmlvyPm-yKr(b>d|=}pCB9V0UPfa62M#tpbx#!-&$@)X^KtVZ>QuAEsb zmS+0asU8Dt$I9b)Pwvx!Y+sK35F#Z!J#96=USbt;fd}BLVvgg3WH>AW@67Tz> z;j?rG1s6ntisctc_eIbk*Ro8NqjEQvY`d7HH_1U4XN0{#c5Q`{om%6SGP>tn!dF)% zcS>uiDohF2?N`O7t{H-b9DesUe!e`4w@wb%I0(DUp-5#og?r4Obk)n5MKpaeYWEF(zKLy*hRcso z3YP@y&onvbSoDY0=J!oZ*Cn~je8{g-e$ZX9ujX=3#1wZoaaT`{ljUVLUj0Ms5BpSo zw;qbmQ#y@4p!+DIn~-BVaBEuNn(*=lvE)`2*c0uJka81I{CTK9SOq3=!M8CYg0U`0=PHcL50=^S62dp5bk%fU^GAEqO>JNv4lW9Mg%n^!3l1ioh zaAne!3ILboQz~I5mQ10uFZ(b?GMx6oGa%O#Z^#|Yha&b`7-1k>DESo@n!DUv22rt< zqa?XwgiFYqJ`m|j>QupOB-u4r5C-k@;IyhN#r-R$eRp_=-aUi?J{ModZ6s zj|9p2R}uwddh_BA0fajQqprI<2jT z%hgoF=UNbJez@vZj-D8Kl(94A=pcY}c!d>pVH8mr z(OyVKBBx$BbD594sUWjSK`4_~up!j5i~=ciiTFuxx00eD&ooowoa5cmz3k?Z({IrZ zl8uMy08vRWQK|rSvh374=)+iZdTf(~6sI(Ugz%t~62D+4ND9OP-c-uenm6dP;sUEP z)A)!|GvIQSjc_ovRgBwc*>{c8*Rsl5@}KA7&12jpaji{Mr!@;@Nuv2Zca1dKHY(h` zg&Rd&X7!CQYrUxfLDW?x#VKw1O}%yQdnVeNj109QbJUhy&!Vt&_MdmuHPtIa=cHW# z`k6&kX#St4T_Atfm%2~RsBM~2lW*vuR|)VUYMk|X=*hHrP_9NU@4{*71C!izdO^)Q z&L)mO-fWeKG0$&UtJpJ`rw^+>ZuGqdG=I^n<4x+#q_yD|4Rhk=)ps3Zbi&x+vdUD= z3nh=$*8OU)J7$)ZRJR`z))~)Qh-NR87bd0xBq)3cfP-wg9#>{=xj{bu-f+YeZdRaO z)B?&&@`j?#?lOQnBbEz-Afqm8&IbM5CuJX>)ZSevX&ID@=h|fE65D{)xmkl2>$N^VAW+0Rtabs%8eX$^y9Hp8HuS>|s zc{CQEKbk3II?MMTAs5EQ`WR{Ov92XZAn>GDqcb;GhI1U@^n*3bV|%rJuH)N3|mN{UMw{4M^TT? zSt?TiAzi*GRX-hDY8hLsve7Do?roFC$YZI#L8c}2VOfNOSSSzStm{acuW zqgUpK!v>p{OcHZz?7#t8VY>Cv!TRRdC3rVSDwLahA7?AFNT*mTv^zG6ZZRBDJ794K zfYmm>30>ogzNTB9RNm->#SuU?KsPt{E2!3{8sYB>8)TQ*4F}bY(lIPDW|o9 zvm2o796rsuNQG?6V!L?X(CeL?8YqCJ$ID4MQ_fR;*?@CMR^+uA88d^#)!=4s*0lQM zpaxo6y5GlDzvrbD!E+3#P2e4H$}E*m;8fAtNr6iJC0lA1o0?|J%&&BhijIpOzt5?* zYxux&cJk5%|7d5U4Mr5Q>&Vc-n%8r#4+N#4Cec~o7%(ohlCwFuN7nK9W3O&|H6XNj zUKIRFoy=latnc*cH4!sitEy@$SdYAH9$H`V)PBYu@VueYc-@GQeb(rAyYzO)ZDnU} zX&VgGa$iqt`OqG!p_9FF4v*OE<#Wk7jJ%7r{O?6Xq{i)Maezw7w5c=4NqP&DR>-^h!GBvPT2*P|2z^sPMa61a?~+zKiBr=F6@o^ zyXidj96jevqmpmGkV4Cn2eW-@7vVZLfEh$fAZ5}GC(pW(NtXZDfDKY# zIi@ZFJCG0xq33?CKJ^^hwBz#7g9$6k#n3DJZT;D+zh>q0)@GXB-P+k6wkX6MS{iK* zU)FxhvwHt(yroZl`*j6!)bshg^%}ROdz~=zWm?J$_$7JuF@OEFoz>@(5N|EGP2$gW}U;$oFmWN1`?RJ1l}-d-LUDN@e+Z3MS(#~8;lU( z3+tl8VS_8=#HbT}v%=B$NrVgngVNTe2jmc1?tJVD!q{bjkL5sl5kbr5K!at&U+I2d z(zTl)iayN2veB)ABF3uFg+9yr2DTfxnFCR`6UMd+c1DEyrHhWC2M0lnHb*o@tQSA9 zhC)t+XqSr^m4iB^jft?^(ufyfi-J{$U^qzJ7Ltn|M~s}di=L;4aYjsVr&ryY>)*SJ zL%xfLp^rtdhyApRN}mUFq(^#1jL?*ej4&1l+{Gpm#lx@iA(7Naiz0?l*rnLgqtw?U zQqfP_-TuC!hv=4vX|zGko{X0D>wHnOIZ>Y+CyU5vd0cPrhZix)ST5bro>t=?;TH)l zgaQ8CBK?^PgJ>G1Sst_99;0kNt)D)uX#Vai7Cp(n1e<{=uR&Ss4*Qlqds-eV_a5xj z-iqn|LFztQUOs)^-iB)`PZuc@A1KY69!FFj)6+gpQ9ezbUbb((K`5z3EGeHx{;A_0 z(;F#&mH|C|0XND4mDTP}DM`zP!4Ez|fg}Syus={L1;i?(667Rg`i4uU2aq-eI9UaZ zV5HJftKtZT5@Q82d4_^>26Q=F!b$iXK*<6Qzk*cWbAB&f(Firh4*$TW-GtfZr)- ziro6C$oh-i2BO#ofx;G}*p`68j=b28p2D8J*q)EVLA2OGmcmh`*ioCp$*9=Lio)5c z*x8H1C8*dXio!Li*fop7t*F?Iw~E5Oso1@X!egk|V~WCasn~Oi!t1Em>x#nrso49A z!Uv+n2Z7QTqr{hh(vQ5vkDk(>y~Ll7GN4Ng{Qp8!DuO72xPb!xK~&!SzY&#wQTG2q zR7y=${tHpLBS!WwL}i_r=0Awahn0+fAu1I&{~{_GYiRyKR3dTxMN|%+H+#tH44uDp zY&mWJMO2b_`u;^!BKima?}$ol*pl+{vWn`0s+#)jx`yVork3`^wvO(YuActzzJcL@ zp^^y@TVE)3d*b%B$;}+q?UR$EW9)*SGhN z&o3azHyAwenw(yLC{$|Ak(%88U?ft>4Ds5$!Eh`VvyGA3{NZRKpimf|L|wsXJf&ip z=4f5vcrv5GScXJ>(PTQO{n^H7Jq4sapFa$~BrWo6zIZ&f)>uR7eDUvm$xO+{vc+<> zdb7IBBu+L9KdIeOt~@LA0Df1(fD^t`b`d}YnAzNN(LQPFQ5^s2PNY! zV-TXVVn&2*&i7D!sU)0K3jdn;N36+-*81b=9HDRmnYM=0`4Yu)?a4Ma?vWZj=MeZ+ z=*#s`+w-bV5K913yQ9<%FOLiLT91N7?}S19cU#yD(%7gHZfFogQl{q|4>3*E_56=1 z)C^|>xPAVELca7rE{LbKa4B-$U;dydXXo41$9Djj_wV95K%_5plO1267Ll$e4Xp{G z4=U71ue;LVu?9SbHm6V!&QOnDFoOq_J}gO8%db%KG#~x29~C2cQ1sLR+ssVltfb6r zT~OIkhc}d2(Z3I%45@|IR1Q#n5vU8sNwS{~M9O0HY9}a-3F;+sYlarWYgkDLC2P0! z6vP{_s~5!?6Qml&nj@@|$5_8%QAFFHsU3$q2bCUYc|4sSXZt`q$}hRog`q>{9!MQ8Rs+1So7khuSJGc$ey_`?Y%Vjd^1C-=A;N z)>lXu{=H!}V^Mv)j6CQAJmS*oJs^MdZI#fjYnYVq&u?xOiMJW+6v@_Y>=db%YnT=3 z=5Ov4n5G%)+c}rh@Bc!&F7BrVAn6`vgfT52X2mHg8$ut>cqAs_0k9zpQq$m%CaU2{ zjwXNnmmZCE+%cSt4eV8%jEv=ynhedacLWOYSv^bZiaO|^WRw*3pCRgc!=5P{|L&QQ z7CzX7vMXzm1h)zq@r;GB+y>#=?m+%O&3$D+m20#1T9h;hibx}!0xAM35=tr|NC-%G zBhn(d=&nU~cQ+y+T?XCVA&64S_kf~+u($ht_c`DB%RgOn&ogt?fX#)_?}_m4Wh_1H zEEe(>t^t_=j>_%1kZ`BaG0|(7)eAWdjOB}<-Z*x~j4u=@viV{CU>o2MnbTvHgm97i?;@zMGq~# zO7VZ8xFi=%yhhxn_~2`O`W_c(bKUhDUj5w>^<*$8unB}BQQc>meKQ+Hi62MHb-hm% zra^*a6A$;6GzpUfo?7$<5u#nMpfA}4dM9{~o8W$DCL99PYEKRG8m|PV%LL@4Xo`p> zdl!9d;5G>{c>PGQxP&Q`wWac}1ku?vE!z{Lg0e>&kZIlBU_b&2qC7LMt&d45SQ2Sb z6?`QMS;9VgYCVX@>uIcKE&J$Yaiz9E;OY$%VV~Cc9&*7Zp(iXt^7kZ)UMO#|bwN z^7~SqGMe@+A&fND5rPs(ZDCjl1tm?-?BSvxTMbKsC8;}6*vM$%NqJ_R{Dslbp!1*X z9a79BRfdp7>7+TIzFJ12W5wvpGjET}j5k|~C^DF+_VR#_b}u!}>}_i)&K`MX2a7`V zpd@Fk))kxXX=_RDM1wDxaMXj+yr~xGHQnLUI&I-XPmXF!)Wh;3eKu>uXtw6pV8fy6 z*PBreH%mTFGzQQqwpWy{&veEMM~hUJZ7lTW>yBi3aX(%jt@R)lt=g>}A9$-P9UXbc z>`Tv>T!>;M=kuNSABB5}BVVn9$qV2E_F!S_E)c?Qf?`G;P+{JH9FgY(kDkgQX zg^DMOEnrqV7krRqM)rJ~Ynn5pA$K27!puR1ktl5e3F2mMwKZVky>X zbeyuyu~4lnOK1eU%q&I3wKTVT&RjPvHKGFFy77VxU_diL+6ZNu5PTxM zOvmL}`@oW(u@OTLJHgw&9Ei4?gn92MyZ1ZL5%ZS}M#?8@!q00Mkzj7-c z0dL(1L10s~Nid_qdB;pw) zH&#h<$GNK9Dx*!-AV{=#mk*g{?R=BJmq?s^f(Zo#%UDTAYc6jZC6twlxwlD)NA&t# z6!49l-GN;naPw;Ay6*BsOFm#nVgqd~%&gBw5bZttx&sfw-m{r+IyZ_6?wwJz zJvWYNr;ozY8-sTDKJ}Or?&gNw1GsI?7?wOgo*GwAeYV&7INw~x;K>C>xhwVuFBzHu+q zQ(`dfJ*@}}e|scer>~ZMaiR3|n?#mmd3}_&$XUfn5j2}U(UD}Mmy@hw&uhg;6QxKe zTRRoS5IH4Ka8Mau)S011M!7CMXjbx2C^fNwnKm_vM6wzG`H(#xZE{qlTSO|cYZ~6O zkGcJ{X_a54Vls$I+-Hq*$NRx)^$d2zAUr-7HJ?U4R**k26TaG>Zy~jths6WVo7C`3 zq`@sAg<>s}g}t90p|F!U>EXpUIE@}D^NhPOhEUP7f{N*+(yt({z4M5z9DU@Q9sfCQ z)iACLZ$|fAmy{V(jTECibp`(Xg0B0Rd$04K}%0;W}jpJC&J zq_qA6M;0`3kP^rS zEOWed97NuDx2GO1Xbg#F2az{i=NS(oZ`2G^&WgP01p|>cH@lWgYz!RVuWar%W&x2m zST=T!P6iInu5KzW?q1&7K7Rg>Jp+P6xPzeK5jVmjV`Ax|;}VmI6Oz-?FQ#T>Cj$#w z46va6MdZz&wvK;qLBoD5DqdtuiA-C7`8Lkc`^wjNQ|;&^k##OFD^1!icB$<8rnEw| zo-ExehdX3udZBq54KakUF?0b1c19V_!Z(*3%AEVh2@}j$qN{9oK$t>4Gn}b`F+FOJ3Bif=~+o3P1f69bUS>Z(9?pB=##)kN;m?yjo*Vqj1 znpBq;8xEI(5Q#<-U$aqYeQ_7Oy4jz;k1sl7M>ZZ+KC`9>x5 zbI7=3PK#3^qp%=TDpJUG5Mrzg39BD50UDf49M-yiud>~Ira+wyFj;^sh?_SZtefs| z5rNX)q{Q1#=|h2UPy*GYFGqp&gx6ilCN<2d$Pg}TF3!=xKvE*XaoDG~h(Z9lV>Y}6HrHR9qjIL^=$(lnD488~$kF=J5#Yg6 zrbg|}iI9>>Uw%|PM8&K zW@&#JT~=CMT1RH;622iys?ET0bHbOO zu~Y6MJh)6zGA2%XmE1eINX2u>Gd|hxtNo!!=St&MeftqQpK0$ot5fyS9e$I zE)n0FbG>4?yEaU{qPa}Uf26ZK1sMSg3F+^hC6z(rFifk!srzrkwCFqr%>SJ*Eq3M1 zKM2$M_c}`$evBVxgSX=zfgRF1azZ4S;wqbrAa{b`O;i;XT&`y|4Iz36aJ>NZ(}9m> zHm*03uVsgT1zOdc@edG>Mk2zTZTj$DB8vEh)RO6j)}zeDFoSu#=d``gRck8S5vX89Itnq7LPt17hJ3=MQyLbTSDO1i3U zGkyAX1c5{_lPvY@LvQXooE0)51ZTW$Brpu4aO z6;!>ykRbaXSxDOVJIkoFE0QQt@8;U<`*g*Qs>+=&s}n8JqOYpH?rg3vjC8zuwYLXC zpdM|sgTn!!A4JL&U?E|h9d*Ry1LlznQourjtC2DWAuyXAa~W1jdTks}dM*y0IWcA2 zz4oElpc_*?^@Qj3ZmkI~w&|1!@7teeCw#aNXeNE{;b>3#2~eg^`afWun+y=+qnQen zl+vCGlF>+=3YIsUn+j2a&`d+sf)6@N>U5Z1(cE;nQ9aE}glV_-Or*v1nb6PtY`m|D zc>ttFym~+xis!Yyr=Ll2>oQTM-;?5k z+AbX6n*KKraLo&EloHaqQh}s6giD@w`$=(?KvEnU9&}^{!CEBS9BfeXG$IGUHSb$k zTfx}_NpVb;PU;|cASn*t(@PZ#l`SAV!Zlb8f&>nWOia>?R`J0=i%-tZQAjnxKv7A^ zEiDsB#a1mTe_eAcnk?g0ZBz5L-~y0Zb<4Z=M8Q>^ANu<7z1T8)2gb%RoZ2|!VVGJ%MM#dw8kY8BoKiZGYsR7ORR3+ z__3467Hbb7cuoLI9LfS&d`s7~=0k?`?NdR7tP3iGoR`+TJQ*a|N%WSZ)p=ghB;Hto zWH=_KvCEwaV$n>MpRcDqrb=~vI^+&GM6;CaOIq+qGGvL>TA~!fYeBL_MvvKIs_lXY zvW?f1Ft6Q69|ok-Uo((Pav%i`XmnL}G7Bn|C|B?UMn}oV8(vaKFm?A{oGy`pQ%dvA zHLX8~fA^}CQrQM=SB~n{Q2KIKg#Myu9-VF0=7z&1FI&(V30OalNBfYy%&;jPpKeFt z^@$2CGhRqbR&_~#v0vQgY*75FimmlCiaVNP>)U>DkN!z`5uLeR6AAC3Z1y=HQ%fKovDVJcmYC!=mW@3a799jJ-;YP6v$R*hKy$Fc zlDW_43B)6YdRwDm!3G3A=7&ZA@raM2tZXsj6M_}ffp|ogOke+8tDvM3ARdt{D&~Hr zH3lfS4v0s*7=_)`-1@e+uf`i%(bdw{KRyv=*^t>ZI=QguYKaBc71*=1@!7&CXRUke z%eTF|OtCwB7yy{hF}^h6k`v2|V~4|HBanLq(GaUkcChiI!@Wm@d%O^Wl5EMle$;3z zBsAHQ7wKqJVbr$JS_DJc`rbY$Qmbi;;JR3Pxw#(B5e)GMzGs$GT zwn9TX9<(^=RphOXO@(?)*)3_$@zc991|Dc-MxnrEEe({rj#CP+a*@ha*xi`(3Q~PE z1RynNQP-tA$Lf3+=yB?Lt}1Alk?9(+g!)9gLYNJS2$S-oRB^8cP_*^C&4F~R?if70 z=+;@tEb&KD$g21}zmQ#xK)0Avhoifg3mE$r z^IBOK7WMKw`RJAkK1k^<74~YRp9SVGESIm=)2&o|>egMU+?-BdsoMR#u<{CYj()Wo z?vmc>YecGy)f&{Bi>tMm{PZ8|E=cQre1of*@v)x3P(!hSgbXny@947j6eI>R0CWHL z025dR9yBv!$Q|aB65Zk&-K$pWOr-msPulv)No)+%nX%8N1=o96z4Uowwm(w6nYoF_ z2jr8o$yeeOO#%6&(eXX@<~IBJq&T)OIqe}pKB=awn}-jOPb%Q|G9U!VCnXOB$AZJ7 zfqYWzP&kICiK#icfqrOMXjv+GW#wLe)QZ^^HMIt=8A!UX>snf6Y$Y*@t4rIuy04*s zAT%vhe%{n0npq^?LGE zy@^nmq^SFgjcuD%b-Q^KN-RP~7mKR-2P*8mg#1@03`c7nB&WkPadTB~6K{dFcT4hm z)SReB3R`7Y@LYJP&50t_11Cw$k^P@4s7pSAVSj_G_E1ic`VyUH&#*qZM6qScB`)2j z@=Z^0BgKQa0s&imQ;h-m(NXI5!t=et`KG>=<*1Lgi>!%#1aEJxzi5sBtC8x*1Dw!< zDAB)rqx{a{V5AB%;wQDlc{-~A!P96^cKPrEG0ymkccYveWj92{JtMR6iZ)|audFA_ z6FyZhpCMN=6^`W-Bb6Jsj}XoqwSRx4`t<;D`0pi|=rzw>MzDNB=5^gTu|L_sMn)X= z;H$$O+dS=m;5X9jH07&ISJ$jq5>2Addod;ZuK0=8h+YBcO+|gv~J@3&#YlF)Ld*J zYgiNlOpq)&N3w>e!TqajI}F(aZ$6dVuC%W2*>T$f%=k@5h?_f|tB1D_sh4j+AeMg+ z)FUJ`!YMp5#yUDS!6ZI0MK?M1)U08W^w%e{hX1|w=m#^7xktzbVnUq^x=PssggV~m zvD;_HQGKzHo5Q{{H%U-(t4zgu+D`efg(iwvT1irUq$9|Bth^ z<ZnwLM_H{)KGq|GwS@Nd86%q5@IDi6aZ>Z26%C`B&aKuZoBE*yF=cg6I#7cA%k@sIWA}CEvlp(xllRx2 z?|p)&9%VWMax*5SDnZ_J1#;KPI_3@D$omK0%}uo;)3RpZT5SKGHM^WQvWAtn@K1 zk0uP{gU^eNKs*r`v&EvA=fz)-=N>YwkXzEt|OSz zueE#lp>(J_^%-loP2(M-A)k{Qh^@J@-r5_SBkfrelnkN)gO68VOuf_p_45G#RrQ@B zW35C7Q6Kq2OZc@fg$VP zI_U8I7vp`MwRFv%74c82`^iF%Rb%7wn~L>+3nfwU-i#{iZp~ z2DDbt(BWWRVJv~q*&SONHf zG{Be6E`Yze=rJ$U{m(9X*uZ)oUi7d|g!Yc?bpoMJn!#~=jx?Cp zNTywr0R5@Hd%br1cm3(H55~_aTLHf@NLZP1@IV>yqX4XtNPbgAwHk9hauDz{Yu5A3 z!$^Zb1TEQZDC)rRJg5<-}ENS zjyl%E2ml0G+yao;!u4|7j&svHz@Zw3myW=p8a!t=PcKIgZ$JO%z5r{l zzR%jr?z8p+`>g%#eb$}{VC{3R&}8Kn7UAX>mz5KiR=ldlt^$_F+vxj;YSiiv4%NK> z@I<<#>!;WcqiuZ3d~$luXm)-{b8-2j((2lV+^5f5;+xxFg?7Ke;DD)fVlW&Ku&23F z{!>{s(AUf`^LRUGy?=bobKO9-R&9SOKJP( zJ5kK+M-pGg)~g_1!WpY^$HbmUhhk6ELy35c$Sv~{nu7_I+gr7+Y2J&vi;v9k1at14 zok;w2yj5XTch(Y6)|#xq9CU4ar{NB%|d`% zTQ-t8om=a_sRnRsTVp}jOj1v9YZ?$-Nau8zQJ0HTgwZM7+8r#bx^Okp=Gx~F+Jsp< zA7or@y8sxOxtAf^A=)p)*Lvn`qvtQ_*v4nc>cpow%uM*FCjn+q(|1q@*yO5xB=!gp zbb!Q$FJRhJ?1bdb)1>R&@yg7bSIfu~(bW(5&<@S?9H{SQ@Eoba&GMKil410i$$~QG zFBYAG#JbO`9g)zffiwVagX8xXHTP>h?HByNclznn4}}xz?7|`m>(VMd=;L1*6_U-- z$sXCy+N+%NAYk(DEU}+}_qn{sC3L1yf!VFKDSsvx%vsFVd-*?rW1>iD4<&T}U{YAY zU7PTL;)k-Hf3(dZBzp>RM5CJ4@^59t+ZH&N_I45ni!fFl1 zn%QcPus1Rjo-FU6p zHbzFdu;^aod-NPz0^+R|7*yHz^ryLFevGH{ZruEFXSiby+BiNT8XX1285rOnjHk($ zf!L|$_7m=y??uP?snm3-?>7wariKsyWJbl7>~v)8tzVk$0}PPV|JHd?m)n~sS!7PR z_0Q}0fmw$|r}LxeI85abb}x4;IXpPeH0a>Wuu9_eOCoXD#^VrC695*OCe4gg8D|>{ zkVr^TzH{TP6bSVW_(&b<;|E3x_4PSF2lewJZG!rHFsDKT+_>GKfiB`Sd`HSp1EdDh z1mFIx{Cs#%%7!Zzcey-L`S-V@$=2(V`{u0cJp_-F_os+R`Eme)t{?}@S*A1Tz_~kF zR^Z&-%H-z?+w2+ug0{b8>);HrbOOv-+HSybEbr|X7$g!9{M)%ZIoPy6J9l@Y=NZ6G zPE7`7jE6!a7x9)QJ66Ni9VIr(H-ok>?5ekaBY~$k7L7``hgBv|C=@$i;{d|Q)9Q6l zq4#hm5_-Mqu1ex1zIVF_YwH~O1^-mBW#+AWQ#2v2lstL}@6lU?5%`-2p%PsWDQ*bD zC$3*>5)KpaT3xoHcuVA&L zOXH4IReyu|Oku&4T?2VeS_LMN@2MLha`fG`&pX#b$n*>s)L}o37ELOL#Nt{o%k0J8 z=jFeB-KQ%nyIu;xnl-+^h;W({Vr|Yh^2Q4G9Jvi!^mzRSiKszA0h?~uLc!(#;RFo zPn9}>crTXm%{XuRHG!iF9dZqq1S}!OQxrPyK1`u~d!fw>RmoEl3DxrVjr7reQpy#6 z!x!lcg-&pv+Mzk?=Wx6XM-xt?;vSboXsM2r928e0dnrB(o8(4!Vj68q>}QkNxNKTH z-MIWKPjq98vBDN&%8~nZV_w1FEk@UF%j!iptc5N{wZt{hLfkrv`WxNf);!jC?QwuE zxeQqKGPsNw;ATN4G-MbdGf$ye&I>{dS>?&w+shT7hA(GhZcGo%Jl{Tr&%GQrVf5I) zXopxkJqdX>9P1i^Vm+1#L2Lu2!){C?y8mEI6KY&VOfzy`L`(}}jZI7|!aMnxHjH~m z_Es^_BhU-5>WQa`$f9z@%`?U`66N*XHz`7OpfCEbE>Wt3?Cuf!dz+(@6F`H)BQQ{+ z10RG${-aBjy0HZB--0130-z4wTa~>BA zXRC2tRJ}d9_lC#Lr`k^<_+X2Drfa}*Y+{dpq@;6c8Ncz*(DIRrR-GDq>1_GLv|VOa z`k*}S&ak73{^hrsW=LagbXr#xxor2gk?5fqV>MRjWJIMU#xYQ>3%8e+>A>kJTB%d(C)C`H-3kKbby#gFwyl&gT~RO{CT9YJYpDXqKu>b0BCwz9H7O zQukEx9NWD;Qmu9fA z#Nqlzj`nbncFxv%4wlrSv%@F$j^FG1O8uL7j?1|Cy$1_Hy`2xE%sH6g2GbdYpmT8~ zNFma8_w7UBoT(Bym8P-D0?!c7X));6h-qQDpwDB3GBKq&n0r%R&_)SJi;+oeYl5UY zh9mcC+eOo+-Sdq*)ECJmWbNyV+-rp6a)U9`NQ%2TAVGK6`s1>xVCdp9H{5*oi)n6Y>*(|efBSbnyP)@}pNTg= z{h?r<4MA*=tNs~RUP8l}j^^((TVias;M-V2?<=P{nh$0+VrplwiC!0G+-JR8tRAcP=>b94*2YT=WQ|M)Of^t`%aU!X4_pTp>noY zClNSJ)=GKJFk@%k||4vd62eMZ8b3@wFVZrL!a{k>@T8i#C8d|CjQq!86R>2yY zx+dKk8ir4BX4IZZoshLQD@Hotl)=YBGVgvIw! zQ3i(ZrjH+Yj!uKH206(ju$kKjHnr+s#8R6T0zAwU$3v2q` z^+=M?1X&TfY_eAy=0+WB_r>o=r8Orz0P4hUaJA6OWY)|#Ue+j>yv;=gepU{q;M zGM*>|*x+<~RCayxCM`-)qBV+^C?SI}`6_vAT_9XSLT&td(le^uC{AZE8nPa>crbtd z<%eauH1Fj_qKDmSgD!TZC1j~wOngq4l=YOx9t}mCzAry41A4zjjRCP(FQED%zI6K_ zy7|HZyQ9db^A~&^SxZa!WhBRTl}IB&q+j6@$1$4)jry(C{^1h)b<8U^#UHP~@i|$> z`mclSFHjlV?Ls`@A}(219~wtFUA zm2-+6J!*GT;Is=p?~y~Uc*gtr-Ndnk3uLHExELf3I1Dgk#(SoMk2wr96c-{T_`{8A zQk^jo-jrfQ)`z;l2a&UAH(70eC?>xMdx3*m_Rb4g9t$}NymRp~?8xU59t& zr{cR4#nYfh+Rk<*Uv+9$PMEUao=r&&F4Kw6EK^F0PC-wePsr$>r_IWlr(H-dv@%&p zEJZG-%dN!Qq04?fo})dFpO1iqklJ#Ej)E;$3P~@qFDqv$OwlHos$}*>_=Au;pHoRo ze@8(LRo*V|4AOj!GS>3qi33+_e@zl}t>OH_-DEoryj2D|nM;uMN+!4z`X~W+>NA z`UyGQq3w}3#PlrN<4sk?Ytmm%TArOQG0MiS9VJ10K^&kvV5t+&pW0hZTSPc5YtiIT z4g1}L@vot0{sxQy2?7nh5EK?E5)l~&2^-J8aY zh7!~^)TUZm?2i1Fnh%}#QBb=Tdi!JthU7;^rN_0WrXSC0%`ZqSX|Ak_uW5YR5dEUQ zwf%6nadRhGhlE=K0mEG=r4w*HhY|7AksHS)y5mqNw>IWZxEeF>McIF1gM{S=P>a^| zZpNrwqo>bKcp#Xk;Rhufm~?W@?`VhI+1f2ARo23bzjq>AhCM-QMXBwHCS4EvQ?Ejj z!W;B17Ze+EN|cKp%VDYV*S{fc<4c6*uZmbA@u;_;UQ=DmjFVRC|AWMXwz9JoMUbFL zA&Y^Vs}GQHQT8qm+FM?zXdbI4+_`zxZI(D^L5wrf3UdjCE#lF1qJB3RSzfwhby-Wmr948-6c|~Q_t7^c<@wc$^ zz2vD`x0$)y3#XCdtk0yKVyYd*Q9nN_aTtSlLHs?G=`k;*DVINf9Rx=pO+NKe!f&BW zC&s@sSC~WGPgA7d{RoVc0P+Owflerfl&BexEQ`ghdLt45jI+m5P11RQuqOOhFpl@3 z`~YZCVc~#aKRV{bvY3UQbuC7x+RFxFIZB@e@-Bo?`)p-r~KepFvIad`;1VQ%fenq#I?S_ zGDLsU0pAS*J|l-HxDC6B{xRlHzrbY{QJ5uKOvB`|0(*MzqCwh2h4N7*4?4;hEwcq2 z(`?xzt0l>R5PRhUhi!-G0>Gs|ehHx9Jo_j(+dc}eYTy_66iX6VhVa$GqoT1RW8y>O z5|R&J1G|1+eu1}He$Jhe(oEdb{iRb6(aX}dX)#j6qyT5 zk#vv?=S&iE{3-2YAI#}e9KMEW;g@3a{r3{{eHa+-Jcsit%>TRaj9(fdecALS(F?pi zW^QyhQHIJKSBc8fzaWiN@qdG1ykc=IIEVK>aQMqkJtD*y`5o%>5cm#lHi>BvhY!6I z55G@pazEZew~=D)Q+W$BkN%>}$*6LCEyMCxxufV+UKW94_1q+)oGzsoEX#x62Xe|> zM_s_pxg~x7h3uDUj4DGQIOhbH9&I?V6kpsd+L8mkx7*#1`g{g%Pb=}`WU#GK;e9*@ zDuTvQR&)*?Ui);lX)iNsC2AboPd8>2EeXsJV_hHmZq~Svgw4XZPv){kc?`Usjqs#B z;ZtSJ2YGSt`&2PW`+WUzF|{KC>bNgQ1iljQ3lAz+4h;|9VD3u@QF1>|%Ag!vnsCZ8 zlz_lUBeDEJ>(`Tp!Pa_9HY2+CVWEE43)SxrQ#gE4>WKeL>TRm| znj{r?Q65Xd11lCNcRE%YzS!D3sM-PQ6j^6i4^L5dKxG7kx0)qusl7UAz9<}}H{Jx0tSu7U)5>6l~L`sj%*M-ea z#?ckz$EM=K7AoNAj=jyKD3??Th4YYX>K*^h`MnLtbB6P~6jqrPrzi3FUUs(gn>&w< zBn1{5aeGEwk?0`w@8^pO4$v|RkxHYX30*s>|Gfp?`)zKTocN^?`H$zO6~KPi0c558 z(cF{>*zbV3NsJ0mUFGKGU(EVn&Pqx8`87Wy%<{0VKfpQybiG;5l#@1YvT)GRFw4KJ z>+dm3fAlp!CCsuAIYmNQ_^1$A3}k&O)!lLw@jU*K_xW#8`@bE;P9UCgsHm_0e&jtl zi2c(X(r3T|V9G)*;W!wec_lc5G9F9VTw2xDzVr9ts#=(UdzpEb(W^?lvyK;+_?yha) zm4E=-(*qOPd+nN`T}r1#(}tmr^2qO4Sq_!`AaZ^;;MuC=FSj(rl9}6vD;Ok?)k6U#(yi+Kf;CT?ud zEm*vG9D^b1lDaZjYt?M zQp!t#EvF$<6LeciTR23>m&P&Z5+pSd$_l*<8}>An{Su0H4tp#=fmxz=q}SXWYNX9D z&GBg3pI@mXb6?s0n21aeC?zU5tr=!S`AvK()6^W5L6$=xerm=^GcBN@tcBw`;${cn h0|>7!;AU^ZPwPJ7W)E*E7%$>AD4kAXmxlx0`hU9K0L1_R literal 0 HcmV?d00001 diff --git a/doc/iterators/line_iterator_preview.gif b/doc/iterators/line_iterator_preview.gif new file mode 100644 index 0000000000000000000000000000000000000000..18e70a8208eb07fed60ccd05276bc5c54bab9483 GIT binary patch literal 10436 zcmb7q1z1$u_x6E-nV~U2B)kKNgmi}@4N}q|CCv;lFbo3>-7pN@-QC?OD3T_Pg(8Zm zU;&ECe?YzBjo)`a;CUDh=j^@Swcq`&wbweT7gZ#stQ&v^poIpYq@--??owG%vaq*p zWj}jS=aNTQfE~u&-V<$wLOOb5;8;&fSLZ8kE`oxBdwYAVdlcHr2KtKfI?BTQf*>LQ z00@^%v~*xf));HT?{gQhC~I41dkoCR-Vxz?o^7LNfDMMQJI`h;rX{F_QnZI7)O^wQ z`o7u*w!Y4`Qg&Tw#xKHWD<~uc6Bp+f5)~5{7vhBp3knGf2oiq8`GiEJ#l)qBC15|k z*a)+s?Hr`_lvIAqMfmGH8ytf{Nec*gdwcVHi}1Ul9R-A>q@?!85EkYm+`;GJ;qG3VI`mVSqTMEyCes|Wu99DZ9jqyW|$B_PBv zxDV;)japj&`&K0K&$~S^diKBU{l|el417@b0($lyZk}jcd&2GP`%|H$718$A7&o+m zo14o|FY3VEFm4`jHxx`!UmV7zWo?Ua-M_$n@Pw9@^hH+>jJ2z+{Y9noY=klR5ePeJ zQ7K7D6%iptaZwR*At7Z^DS2gaNkL_C5g`RJAt_<`pU*0}*?J=FT`@nOwfps~(!V~t zPX;84Ftd_98sTMcr-F7v!VW-7BmUhM`F|bn$Fp|-Zi~XdJ}W>lMqqzw4=wf2O9cMx zfBciUgg^eIzP&4f?`Q(CiT1vI{j&S{)6VwR#}Dt{z1`e+^ZM2L%e5EJSD&pseX{)c z(ZdJ#mlhZ1=VoW7@7=v~`_|2=$%*l?(HkSzuMH1f9USQI>+R|8>g;H5Yi((6YHX;l ztF5W7s;nq4D=jH5DlEv)%gxEo%FIYlOHD~mN=%54i;clYo>g zhga9TtoNgMZ()#+u=N}M8+(I=C^cTjgway;n2U75?Mh5Hw@Jf%t=GhB-+{-CSj}(E z)Gt0*C+Tp~LqBHoRa88B+cT7JIrq;yLGp&-5Bbgx>|GxGC9*fS9!PbQ_C)co$V~& zbqSN@4>LK2)XQC#lrz!z=M*eb(W8-5GRjAm`t+Ihi1=5w?-aEq)vDv4Y$5DwQ#K}} z!*JEhmGM3BZ=n@$A6@hMYV_GZQkaX|k?0PsxivmSUw>t#-^t8(P*aj zQiqqPVVl7WiCtN!XSXKLVs(|yMZ=d~$ouu%_vw}Hs81CcEj$q<=bgWlZF#XA^PO%k^Q!y&9vSmxg?v^{)41+jh6keq7g{ zsEK=%`bPib(*?7cB|Qh_RPhA-aKe#_o|toEPxbdy#w$t2b%;(XQ|axT98H$s=MbHc zJhJ@mZh(;cbi6Vh_?~|7mI=;E7t9YmCPm%sFeJaO)=3dW-ABd#+DlCeE;10qABBrL!Ap|VLq!XN$hSI6F31&krjnD{RdL9ev9U*|Q`v#W(}yr? zsu|Z~t2me(0<$=T$Sbora?I*kpEH?7hHB^8hhBW1WAl!iQ`jdmIyjf69Hqt)%h(7h zA!itbbNES0uMwv!@T`@l$u7PqOA5tTRiwH2BFYQUJls_!`8+)A70pgOWv$xPHe_1X zj_Ib4-J_B$mfAQ^8OVL);Wd{G5q>4|PC2@E&;L!COXVV8vc#>#-4Bh~==>}kT@t)mI>9US>WoQo>RU^M zPWbcF3r`exKi{y{S|!%J6ar$PmGdL5*nJaC7MA)N`f*(CwYKW&@wbuBLOZ8Yl#A$s ziOOq_H1-&TPA2rS$0XKZ1{r1k@RCm;HNNA)*R$?7F;c|>A|eq4cqr0I>)JN8JU?DO zABDmZTX|Q%tZ9y<5+`mMs`jeR7Pj%KNs)H)D!ZDMCqA#M4-&thTFb3RR3K}hXo;WYxgo>Ici@#*;~Ym#DSZ>2u1Svkk= zKsbgq++%5Xckd-X{IFzG@opaP>fovC9;9V9W~e^2h+m)DcD@rh#jlg3)S|XdO@#-O(qWr$*yk z*;*Lx-FLu6T#P@;m%_|#8Ho?inxZok5((X-t3VmM#5=}&!;GO&yDjM^{I_N$+#y16A)NXPpXr1$2#d}5G$9<>%P%K zbek9TpTwik{OADR5um4)0rN20JyOA-;33H+R|kY8r-{LRHM(kzw{-?zG@0Zq#Kg6~ z9@GC8Zbn?ZdMj`QUzn)=;sT55StBy^9;gMj2-@Y!E7RhLx0lLp%RX|q-hka!&!fPo zaaGp=;b_vt6>}SGGxWI*t@0%2nQ+?0c+LP^K$#$ei1h4vi`a(jrOryQO-DiQY<&=K zOT;B2uoy^Fs}jaqO&rI=URtkIb<)bI<3p6(w;Duw!jlP*XYiG*0x5$$Fd%QI+=@tbA2#E7gFXI@DNt z=mPqKDJ&c|JBSZyh(H>6ykA1hfpuDnrjRva=9OC`&>4QPeskIq;shg5OG(|{LCXI? zkHUPgZ%Vkn?R7EbHZ!l3Hac@}XP5)pBrT!YL6a)^V0HF1WGgQ|7mHI`>&&U}s^;&0 zhE#f{<`>e_d^bhfGymGqvpMIl)b+Pd*9y=X%;(J*no)|J**PjTUb!`GKdVR@828Qy zk>6Yk951&)l3Q!4TxxhHCa5@#zuUn(FaLE)Abg3jxs)v-do$qW6}fTsnwU9&)b1RoKJsonc<}v{m?i^{KO&*89bjUttmw- z)Z5I6%EbA>V;O>)nvYybc_wtBc(RY|TFO}+%3D@Kg2}{FNH$VtLD|)4H=`-!D;H)E z;N<{c_7G?0c&>1zDcT#XwU>V<5`I3+Vd}WmE0sErw2@O2ap_xc6CsVk7M3vyxm34W zQgiLp=P)T-9z1Vuj>j8r8`6`(1_5YelXEFS+>Y~ff~~@mU|g?MB0xV4gDvK z-eZOv)COxoasV+_W`u^`yCuZpNkjhpgR8xxGJk}gxlCVu-PY!hDe}y5ffIZ|K2IBvqo*#AB;?DBrC7C%m)%KnfKgLsW>Dr?lFMP%u zVY|f)2kninEADw3)hRMBlpulwmjm9LHFugbr%K!^a+L+M$G)Pgmy`{v^E4b_dOq)< z49ex+t~krYC8zpoAu7R##T=#)Fz%wm<3%i*$!*NUb>(fTqLQDD9Q{!xZzATx+ zRzJlzk5bJ#pEAB_t4H=dSOxD6yrn;xRV9IP*SJ4Vk+JP{mcPur;Qph%haYrRuAROQ z!$~U<(|UKhW(W}}RU$R1v?0YG$}|JsvW4!(z{B5{O!&VY82KQ2Vd33k{Ri(Fk%e`r z%!8nBB>~STUm8VkosIj(wm0y;?dz8ms}XVUs1E0yNN>d! zm}RF0!LgG@8aHi%)=}P{qCAg#U8FHVwqlMos89t4lgq4Fzf}!B`9ci}XFGDjRTztz zxr=2@3^d#Jc0FN0Oe;-{;sWUyf^LHqcaFa^4!&m)cBDQ0RA(@Z3rXD>w&%zXf&t** z2zW|_NSKS|P6UY#AiC^j8XRAS$#_W`+D3)*_SVd8xm4+4)rso|j+KJ1$7OdRi zC4M4g70ri*lk0lyg%@n`PKHN&Nx0rD_kM9BNUS5U7)n#R6UJ3$72JW>ox?NZY>v`L z>_YIZqn={Kry!^+I@e=7Gq8@G*qscMq50rJ2A8%MxNZ#I?_+4+i`ee=@Z5PfdI(FV zI3k|ICskSXLZn`@&Siykc{Iju6E0Q?_I-|Z`ZNv4cqxY^!K(}%{lp#7?;UgW;Cpa* zn!I0Vq*;_hVnvy+qayrrtK+C6(=B5q-(ZLA;3PW-CUti_vya26F@=YYOd{b79G4-S zCmqDY$#R1OC1>?`lzm*M^?D!2YqL^viG@o@oq&;?IBkFVxwT#iz0(G3$`rAFlUgh- zJeK)wpuYUx6$|g^2cxKsHs@umr!zxn?+C74RK4HU5FwUk2fwJ_;WEP&@3$Qt;25V( zMzJWFUZj*Z1y6I>#;>kMJI$r5-3a@1Rd#VR%~mzz1H{vt41c#XjVsZA;ky5$3V+s< z@c2PGP%BjKIGlY=F{>-dY*~@}WZ>zGfqh5F@*0UNCCqC${ZVrMRcn5s_W<1#^14qF zgA$S+Vc7%EvTL()T0i;Gb}`g;WLMbxCa1@5SL%-VASi?N(ofh)k);-{`s67m6mjy6 z9`)H#i^C~J#KG}k!K3IdweTwSbv@fCx;R9XD`+I|3K=DHs>h~yhOBBniETbEE1#_} z%o4GOoLJM`%tG2#MN^8~MxhHNp~Rop(gWAX$1+{^J~_SPE_^s29%*0bTa_;%777A; zyMHRQmkRnIRiJENbkBqsiPMR~6}xx3Qh2QGtYLL1eNb(g*B@onW|~Z!)X!SWwsg7^_jvb-@-N285Pyf#`Zsaj5xLg;5yrU#`iu5_dp_C~Vxf`QCDfX#rNAh03^_lj`)o$M- zMyfEz&^sRUIl0?et+*)b2QbI9Ct|^g%}zBni-}#I8LAfH6KTqH+z#P#_UEUQhk3{Z z%afwz?9IV}EZnsLjmhJt_P2a%5$*PZm*cO5FTOHZ>++F@p1eiV`O&5g{X4N&@afJ{Wr#7an~ikaGhv8qO=o;Ck}*u=%xT-t z4Mm;gy`<+zcGKa?nfB0PlZ6UBe34ys;S}clL}%f4b;vRD^4mLcE~ZJ<@1W zTI*$HHwNJ4EYoZu+u>5T+n^~a(gHow&t|fwBP`ACO0U~z_f(i2LHLIp6Yu@F2X^sly_d0N{4UX(NMeZT7GGk))yHw?J8TK6O$h7UyP zacX20QM1e0L>sf3MX*ocQ#A@SC1WTj(#|{;bX*KNsnT={)MHWI#8Med#T&tvd0K8p zu+A)$?re8Vb;BQF`M4z_vPIS_jxb5Ft88bxPCKWaagG$nb}_AE7uBmSg2*?x>mR>t zACszImQKjy$$L>PramiL8pT)svc`_&y5{qO9&6>xO3X%In9$`)_NB_+BiC(|810Ua zR9pK7>()sbK&SzLnie1>R4xV)JO~GFB`D|R+W83koRdnvwF-0ikqPx1Q)$H4PgYqs zjfjG70I*0!=4(?6?HL@s&&NfvGNQ9mz7xCk*IR%XW&qziD!tsT%egmBr#Td^Q4~3W zZHp-kb)rD_j^KGCkH0DcPsDjfH)&%#YnUqwp<=rLSs&JVgR~v0Lqrq|fEsUonM4djay6N7h7|q*ie?XMc--D|Y3(LfclDuhIJ@0S zIS=}Q+ROvj_D-|fc&p}QN39FFOP3Q@IkgKb-P8#F)!yBc(o^z$_pWPBpR75@ z<*hFP|&6Hoy;w6@$>)=^iZi{Jo?`GqLXo;!&eHO8IzI5qv7f|#x z+^rj*`${zbq2JPGA+=7cBw(R9uOH4fAiXs3x{k9DIgrmHMP7=0xMJ5|YU^vT`3N}m zm{|5PiREK(;A3e1WAgsTln)^k|T$zX{>-Y;0LG> zs%gWU->Yd_Oh2k=^lVk|L)En2st z4ZO9nyB8c18WtWA85M}Y#l*(NCnR#5qM?AKr}HKq1Ci$CQ)bhUky8WZ6@^&|r4@w;ln`SsLT}SB)=>>NEsAz znz|?&Vh5sbY@`8$(Cu!gZJ>cTQW|QcYm7rr(!e0L7ibNtbGi=X_>JBQOu!{LQv_z* z3w0(12av8{oI5MYAE92oezURp_T76)%0noHfJ?v`fRli7-~i=L-sE3vp(z?Rm!Q3r z{_l8W=ZXO?Mrt5xC;~=I9$EZ!MpKqqkLRrrmuXhS)!|)>2k9%qh>|hgT+3%;I;i>A z;QFZ%lfvUB?lh!+;#7g06d}rCq^`VpORz4fOJWGA?WOdyNr16(S`ehPG)dL6n1e!* zw7!8furZgNj1r-YBZKzRP@QS-Ea1P2$hy{Hr;p>kZfOpZof=an)4jt-4)rqff@tvT zi_jdx#0hW%R{%Q#rcXZ@Io0s;Ki7BnSFVHR&-yN5<%$(;rd0H)VX!p!D_aRsGw+6up!w|Fm+7K6*_2qQgTXaT6#uiR(4KqUVcGgQE_HqnCAdVfCJzsm>+*&KKHsu zPsPMg?8;`|2|d7Ny>Js#%g6M{gNk7!@qUGQ%_bliD3@@16%b7vo4A{3CB%5=rp+K* zGjpy>)Gj)ch1}h7rp981erUMRZ%AM&`>W+0sUm+G0ncD>^FTksip9o}vf__HA*m2( z(joIpO3TVCDyyn%YU}D7@YeZ|KqVSOQfHh^ka%!>f|((iLP}bqm{DAgwb%vCfismI|oyeUjoSvFaZXD2Lblp57=>Y3hI@-=7cuNGddSDEP{7p47e{jc-mvb znM{ScWA|i20_>*z3TuHVYoQffp@ECz@zq|sCaW1%d2Qx!aE{pI7UjcDqA~f3;dyH% zYbZ+XC^Uo|i-q_p(h$*~4!4R_1hK@$M@a-yLsC)_Bxy*gW3waDC=98?im?n(`lehO&y(wiB;TvLv3taWpYaP)@_ly_h!|S=6=CmdA9l|Y!2g3Eitd0NZwYBq2q#weh zP1tikux?f!y6y;w0?dS20TNl-zW>tSV?L#Mqxffk@4MnrT}@LuB%&IC44?|=5{7j8 z0YmE~0fw&)B73Fk?=8cNtiQDk)jdyEA8HvMBm>{wM=d#1cH{RXCs64Mg$*PY!gk1u z`wA0y5Yg&>Oh2{#J)$|O`sNZkmh=i^sC_nhP_*pH840NIdPR*ETA`wM@EA)(95jjdkO^!A32+BY36OJtE}D#yC70z5c)me2 zfitp@_ct*X*S+c+cHZpeocc?fSvpy_fsWQ|B7(nLh3_!re@=`KOxRD1O~{gd3%ss2 zMTinYQ+YpfX_nU!7R~WW%R%6EYs-QRoH=ALGr$f604RdNT|W%&p8fV8^QIS*?7!B? zYNeY5;RFGF%7M-43gecz+wfihn zg8pDxpGZQ$eC+ z0sQI;;c8fO2qiKuA>Ji1CD|n=;zxcaamBgVsnjZ+uAJeJ3uOQn!190)83(3qKmO~B z5?|oxDSoeCFG^(75@hFxc&pb{qh?Qt|9ny6hiS5`OI3Uan-*JsZvSWpqq-2vPZ{JF zyuXR|8GIl+j-u(mQpewNuV1Mn7w(X)Dg-wQ5Hdx8MCiL4FO>cDAoC9!UU(GB7IV3noq*>xs1zQG`dm#b;3C_hohKnehGTb zRFGrrFVXzh8YLiHc1-Kb3mCWF@no;|?4NOs0>fw`B7Zuu*Q%KNX0ue#Yc9P#UU;L#F&oy21&>{`7a^A%C+Fq|+O)A{d^3V7T7$Uy1j>-q1O0 zIAKqKoiWdw|0P@5uPGcDu0lmal_XD@lpISLmzAx75Xs9aWPubNO8P6HgtW5Z;LH-9 P&`mhAFty^305bmvhx{M; literal 0 HcmV?d00001 diff --git a/doc/iterators/polygon_iterator.gif b/doc/iterators/polygon_iterator.gif new file mode 100644 index 0000000000000000000000000000000000000000..96f20c409af93633dfec32e900abdf0b4d9b9a12 GIT binary patch literal 88369 zcmb@t1CS)&y6)Y!X4;&#ZQHhOcTZc>wx?}R+qP}nwypa5zje;O`^32sH@=FBsLYj% zS?~JAQ$84_t=`#Qnq?la`{YrsfeAJP85^005?DXFGa(cK7$;pkhm_ ztMqNH5fBjQ>FM?CtiP@j0AOWBl$C@8kfPlV=)Me!Hg$<#Q$3rCo3L8fxj-`|23wNor4KJ3oR3k z5j_I~J}WCN12YRND+4t?BRvBn9sSpvm4<z(*A8hv_^I|bZ!RrbPTlgbT&4Bt?O^K z9i0?S{%aclV{J!ecY6~$MH5FmX9pvbuj)kqZ2Wca{`Z0Ys`xbGTG-CW z*~Y}yNkW*1@aqb#v4t_Gr~sQN0|Of~JsTrED?0-NJCiVjfQSeO1B);_J%_09Kl}Kf z+Omt%i!w5Dh_EsaI~)AJ-C<6P|6vC7^z2{p^S`b9?`@6$U+x;+*JSAa3XlI5F8?h0iow4Q{}udS zC;!?$CbnOD#^Gyo00TZh-rrtdo}V5c?(c4IuCFdH&d*Lyj*kux_V;#owzoDn*4I{7 zmX{V6=I3T-rl%$+#>YlShKB|R`ulo&y1P0%+S^)NnwuIM>g#H2s;eq1%F9Yiii-;W z6y)dS=45AOW~8U3rX(jNCd9}6j*W?qii`*k3k?Yl3Jmb~^Y!um<>l$&?&j*^?BwY1 z)85Y3#@fo#!raW%#MsEtKwnQ+M_Wr%LtRZ(MOjHvL0(Q)Mp{ZzLR?H#L|8~rfS-?- zhntI&gPo0)g_((wfu4?*hMJ0!f}D($gqVns0RIObE)F&pCI&hhDhl%VZ%Bv;@Nlp& z&`^*N;9#I2Ux*=i0RsmELIk4zq7Ber-~s{zRF6oMb+DgJv;p+Vqm3=H%u6e+&pPd? zr<`oI+$yiUt^nOR_Tto7F~bE8Bi5YR)5T7b6`EDcR;@QBE$=$P2waq$U>Ny#axY3Ui6S=l+cdHDr@ z3X6(MO3TVCDyyn%YU}D78k?G1THD$?I=i}idi(kZ28V`6M#sh{Ca0!nW}{#i7MGS+ zR@c@yHn+BScK7xV4v&scPS4ISF0XcVk3kU*L64pupWj|T4qgCD{56I=cK7!>V6NYG8>8?547S?r3ff`;i-Im=81}}^0nggJ)GxJZlD2G3 zHPY;{Mv_k7X<%?If8)*Mi~OeKX+|lTDHO^Ul;KnQTIhNwij~ zlbWGaIa9V)tyu8)H}OoMRcKS#*lj3ns#@+)2E1l+sZ(uN`y(SmU^hvz3-U32`QCCRqsVYZ8ad_#XVWe4plkYfi6 zeoG1RgYRt02_Oo`F!Un(9`wT-i&Bj+e4J8V4HRij(tTh)PP*ILj(H@+5TZ7A+_b3mr$( z&J>r5iRY6w6e#D!QZ->H02NJ1lr|No7o)mWldKUG)jwgRzOfE2DwzR8NZ%`G#r%p# zOsx^*DsRf@#iq_(L<_xW>^dB~tOG@(LhuG&R{s8ngy!t3 z@>E1wF9K-kY0nnaOFYZ5H)wqSoT${r2x-x~?EvB!Q}-DC5Ov)+@VIr|1j|PHrjKl zzIDrWJ4v|ui^nxvI{E!IkZ#-^5c{Kz$5ykaOq7 z_tcu!;+3L*?AzacGyyuj(<`i2Fd--1cJt|?Z+C?JBHY&<=Q5u*%C2l=j&kp`JesJ> zbZCxSBD_8J!uRmnFLBYZxj^IkbXpF;aS)L%I@Uh9PUg}(8Ls-?DjBbvkh^#u2G&s8 z)?xNL+Sk4)*>ZHgv}u2pr3ifXw3x5kalK(>=kp8;hva!XI+qSaTh!URG3EIth5v+5 z+y$;%#hI~&vq}hsdSejn1rn(JitmaD(~4+6oB!i8_Inq_xSZd%kiiE|aqqYAYN9ew zeIRggegv%RAb4p4Sl8k{yvk~~$~svufxPH#v@}=PvjvfWD%*Uw_;k_IBAe9M>mh*WQrXZKb79dAe-e~9BM&fZu!WV zBgAa7t2W_!KlEhd!d%uqAsHu=hAh{mXlAzI5lzjCoS>~zR?^)eTg(v9&(>KR--3K$ z1`F9)>u-Rp%Zy{lqP;HrXyjBl+#KK}4f)6@Kct(m6=8k1)V(C^IlEQaI2& zt&stQS{tTo%`EUr>l092vNNWypVG25b>miucuH+-ye3t()7Et;%no~wf(k>)G8f& zX`^7Jf8#<~{aqF+ut7iz+_Sl_Te{>IpVamiW#0(E?A`lxOm9NIwd*r2t&DA@Imp)6Xk_CAR**;6WRBWSvZ__AAb-KRYZ|E*qG? zFY8&{huS7o#$0DFH|#uMxwk(TSN}{^Tn58Bcz2mL2h`&LS*tBCqtiLXbVQgd@~L&B z__^c>?2&+~udiT;wG5`OUnX@i?S4o9Ho!q^rQ7DYGePS(F+_CxTdriES*~R=2v9i? z#ie~9(8NA&6rGo9#(g5s=h0zF*&bi^x$G@VWRKgVgU zT<2qP{PhOU1#4Z|Cvm+#&spfI$6A~1Srr)<^jPETB&Jc)pO{Qu%d59-@a)OzDV_6X z=CO?%Udj%ttm9-e&lwF`iyW-bOGw7|9fLa3A|Je4jwg@o&*;Ez*U!ELwU>RPs{|IC zkNcP@o;GzKuq7X!h-S0)V=+1FxC!p(s-<5gxKq#GGrA85DIa%N4&*sRfTtWXu5|*c zr$efrudaB!Hx)YU;d(wdBU>Mj`D-8dun6yANxbhuI_zgt*(cLWUcWeEJ^<92Kkm#3 zz4wyQstvuLl08z7ToC(xj*o}{MLuSPvXD8x4QBi#Av7zHzL3R+aK(P0&-B>jm}W!H zr@#&fv2K`9egy2gxW)cI$c?C$F~1-CyR-5oCHteK_;59NW2)ML9tA*|*+Y{B3PaKB zf(8mSGieqAJ+lTr1_$bc1{o3s85=nfhdK?!qZBn5n4tfX+4mDEaAhBMH7~LmKk{Dq z9+2xt&AiMHyX|D;7UVg^-);uhx#VkC6r68BRtw>!g&v|#9x|aEB4Qt+59Ngs>LJ<_ zY!e!K2pQ^#5sE$-V7Tc0ku2-+jOw)<;-Uc04;jWO9^51xDy$!BBMwjwKL(0i4$Wl$ zCYlmH`lOvuY@HMuat{)&P!pB`HXL3}#wG$1v6;-* zOAgjg9$x4a*~JzR7aS@Ip+6ZKT*emRs}>Ow8a|#BIT{*<0!&|H9${)86o(NexgUXA z69z(J^TQOk{5H}*#aF?Z<}8JQmB3|O9P=?W`lQ)plRdh?IXKzP>Xx0Bv?&O`AZj-* z20k_RV%dLy-3R!@_;lDBg#+!!NHq3~fBI3(>$4!Pg`rC=`d%SC`K>0*y*pY-EFk4K zdD!p1x;R`?3Px2UjGk{Qg0}Z@C`9hz8{`pi5^;7%5nkpfU^@VKS;2%WbhIS3xaXl5 zC#dKOvS{%U1q&nEWh4qkA*oM8Z3d1c+}+@?;&6YHcnVCZ84R$w=9ob@Ekg>%vfH3V za`x>(zWC*E&?jOh%z8k)LBY0G)pq0nUneDlh;$jdTYb8 zMhwQ)f6j#YcDbdrza&zWM9e}<&n0G#VP=tHMowykPLBXGo?5aX-BAx#Oh#HVuhp|1 zQnUXwXFpf8hxs%&f+^>eLq0w@A1*EbVyqr>*!3C0>1s~>g#-rKggZX+`G9|(J zMp(&Y7KQef`9w!KT9yTA1i7SQMXIfZI4SX+BMGFp!5QvFw;bZ2uZ6)cE&{6sXXZZ2 zFom}JdB~%Gg3}5B^Tp<)DMKelVXh_Ct5PE+#eS;*H>S~|o0XI-$HW{g?1`kz0?J}o zsNz~l;nGpV?A9cOS6tlHqMC4Pb;)GS@X`!P*Vr`9hw3sA#rQ7HJZ@5zW{$KO&9wT| zz=jt_DfaXV_lkwm3a&k7@T0U1te`oV^gS%*wD7$BP*&ug(wk6^lA=8C(}M1_%HNz- z;lInSVB!QHeos&qNQ;(rXp~{*xdu6w9l7Cl#Kizki-D<%B1$X0f7{AHS4IAbhHoqJ zfvNd(TCOKxqi9;w-Ajo{RYOf)jmK48FHl3mZa@>4&+A@D`d0mosP4&w1Ye4r6snYC zHR3+4mMWwc2)o9)r`lXfs06|W74!3pPpSkwD zW&*4n7mabBx|yEa2%-2pA%VI)1zT6tb3w;DpWC|RS13|E9CI})?VT%IIP773fv6+9 zsHHnQVVPSw`l{S}$*C*Yq$@;(x@WDr8_T*5&nng_E7#JP@6PI>hixSadBdL0?MrL=plBC^;a2HM11RBJj_-g_9{>nx~R9xZ538PI_F zyOGCx@x7Wp(>t}w7;x8ncO$xYYg-CW2dk}69jRq$;rcMRTaw#)thqUr&-)r+hds&$ z0=-I#q=v%addFbv7iLF7iGaZ90izlOqhR?s3WTDB(X&uJl!4hOx-a2#Ode# z#>$vIYd?*t=?bZVL>WfGd^?n3hFpIRTf7hH^rE48^m7Rg(8Bdcytnwwj@8G(_j)1r zwo7Sf=W{EK#c_``b9-zf6@2d-owpiNqaGkPohZzM@3kIX8XWG8!1#qT`K-_>EiPE6 zIH@&Gw{_lgQa)@xGhw(tIamAD)#x4daMn3KM(FtSy71om)E53X@rcP`*gs(}@|~Ct#z{@KZPI(?RV+aernm z$7V0UT^4`|1wZ;&WhP3z0N;ml;fZ)gd86hiwQROB#)aU!j4a@3iDq`oCLM9KTD)du zqNd5>;S0+r6enbV{F*+g9|>HN)>+^hS-RX=D#-YD8!2w1({61{tE-$nO?=ImarLo}dL(!4 zd|lfsX{vf0bP;Kdv?6m*$CaQW3CMcT{lbx-!=wv$gKJv;d0}w*_w*PI?g1=8+N35hdoaUFDJ)0&bA)vEb*y0q#le$8zJw zF?Q#E_$8(r9-uxXy4;$VAbWBw(zYx*dM^ggKbQ72vGYjQ=!k7Ip@r*+Sm$Ux(~zIn zj7f73x%tfYbL5Lcsov-5t7o0wBSPLMS+s}gm8Y3m2eFr_Rh{Qn-YANbr|Y(7YsTk6 z8>cEB7t6e-@_xhFG?x;b3peWLbGC;?-e|CREi1a{Yj`_YW0xh!7nGlu{<>!_(3^6w z2V>4xKy-o>x#;<8C5`@z+tF7@Rk?1w*B+Oc5PBEuao0Y%8ye4)ZZFpXvKLe6rzl;r z;XiLgb-U(zu3L9z%S}+#B1rLlt_iw4oNi7@02FtsTOgBLJa*gA-dmtqTT*q?&zWjM zG55SafOLteG`_lRNjny}uvl;}Qb;JP8solWYM-krhQ?w@sy4{-d#3%2kf#gSq&N|=A ztJCNcOtR;I9|ddC&-+7{oi&eQ{%2l*=Pu5ZzOnNj#k~`Rm($Ukt>khoJpu3RTS7jU zIG;ahlKV+=zV6u%X?hbCh|fEdKXbM+1L-!xC0>25ii)>xTC#iE>|R*_8eNF*k7>vC zyvjp>+tRI<)0+2&so|O*uMeF<^Bo_kp)ZTS-?=WIH#XmB7d|%aE<=&mOuMWWV%{PV z0TQcxAGUHB=UbmO2*9$koMHniiFvjVC3J9NwVG&m<*JL4MvRHduc$vQ2|NsEH2hm~ z`-8YT;F%BNOgx=crbX$>-<8IPS|qJ$lNVD0goNXf~LctaVJ@wE}S+ zGU_`9CL~Q1`;?y@4+3FXL7jp42l*lFt4mT3&XJ+u4}LYYixLKl#vKfnOrZXNTvMUp z+k)c;%3q8mN)IQB$E;`wz!iN@kc+y$R+F1jY@u% zM9}7_IpQdg$t<9dq&k!?ZN~8@4@dr^l&Jk%f1I6=Jns(y7S6&;b@^(6)*O}w%EHEc zsWXwz1d<9BN`&;*A$S{{`B2Xo+z-(V^&10lIH!h(wTG&%26Zj896=}ts2~>}pB^cV zZQZd%h3&giFlw<}ED`EpTx=JRRcOn@gbeH_+dt_lZt+y-ch?RIkw3(;xcMCp$CH1^ zg|xKX9L*J}HC=MQJzPxG5Q#OeZ{7gaPGm#Ma|yT}oUgT!A@X&;lW%RTnE_(5+XePt zo8G3PX?G#!4_G(X9enH2URNawCM1E%;5`T9ka%EGm3$kgL*1(D5$+6QE85#bo(~o?Yb6^+)wNSn&^3Yz}A)?kvtrJJ{Y*&)T z>e^S3o0KP>qh(6ZP!M2|OMM@J(%s~A>)E6wLVuB;^A16;3E3W3Wa;C#D&Ur*T*r~-)2Rs5xbpd0@y zZkaxSrcqUkN`_ob$3(M{vBCp2Y0Z#~ojSmPfQ4{P9hwAvLxU&5MN`tO`cX6OTsaOb zqdjvQ*TW<;uG-8l=yA;%9HDu|iO+mVM>QzEiPkYQ3Tg{0ctvf)-w*tG*8}o1Su;jT zLfzo^Kva{#PrS<+^sw~Y=k-LkMU2BpKHU_ffCngdWB)Ri7Rm&hM`v-a2j^6cNQ+7i z(+D$fwi9%eZ&>E3L+9>=*(|2D7IAuq$reSw7h8-f+PKw`zIPz34VTvFIG<`>b^eXU%Rp7UW0Nc3QFc`O9e|2s7D;*D)K`#euVG zU2K&Cfb1rlKQ5Q;sVfhQI~? zv@c|aJ_Jp(z$-qICB$(I1ecotaOITyR;boHka%r4b+~bZ(#GjMTi3LKFGRfLG7N`` zpq75sFR-yR1heM&%Ma*aA?nRkS^<#GxMn1JynN!|y0o&%uP3!eLs* zd8iG;%^6V)dWso@=w9T5NCnVdYQ`DgCY}e_!>^*mp4V_Rl0+rS86w4*=W)T^1+QqL zqeIr0x3)uvuP>qy&gh408AKJ=-y+D zidxpjXBiVynNXn1Pk#5xq#!|s#w@qd_#R&&d_c9*EQQ5elGM14PU~1QC=S7tWZRrf z2g@O2c`4^QBy3uq&>~Hf;gFCQnZo=BV%#pSE@K5n^rSjW*1;w|9satIKA?p0r{-N; zmoeD`PSd2<;CSYGe9=uk_)|6=47I(84PO5tfv)RkEUd+=B$Vte0j-zxLl`8 zz0i@AwcZ}(5(vdYG_pLBAq{L$-Q`0L!K zRix2J-o^<;+Yu&3q{)zmuBZxN3a+K_(YYFJz)FOvfuu@c_+qp3c&;O+h9)nXOR}cI zr5u~pz#y+{v33K6^2e%|Np8=UFo9PbD(f3EY)5<9R>7}7DI-`8u2EZ|HK0c?8T z@r#4i!VVlc=6f$mXt1EiOgW9dBL|4r0is8|%+Mn5bKMs6{fdrFgrEF7#}k=ih-6@k z6Wyngb?g4DQNuvn15L+2QWuBN&jKAEj|n5_Ccoeu!;pgj=QT3;8f^@M5IZmWPu_)M z!k-Xe;3KD9GUb|7K+3^lSGK6KRI8B^t7>5`G);~{An=?kDakFB1+&1;?)X`&t*x~~ zKtM+FNSA19t%xGK)(ydJ>GQd*O}jiwP?WC$rrZ3kB_N?J&epa;TpJ%d*(?Dx*K2|{ z+n=2@JsU>0Y~rRk`5y66Ci--gxIx3&#l@L6Z6f16@$r3JMk_MU zgNZm0IuW{6ab<5sv$3HDD&5EA0Dad#r`{Pg{LKXH_+RLl41qvX}r1On@zI@u1^Lc7& zbqA*P{#a(y`!!|eQ)UJK3vj!%^|=UG+LQ75>|sOwlyGw z!#19;+*dK0MQf$6lW;@*$fadIlxfLL+XA97(@DAt= z$VbfT<1vH+2P*(&P45|6=|u)=M+WOaDX&DG=SK(PcsvoTm+YgO=EI5PZw=_6Y!3z^ z?%@pVX2antxT%Lr=ZA~z1AcFB?h|4w;N@@UuP^DoaO69)=)P+0`Dhd3itLxrCPXe5 zXx0?ovFMko6P66@2MFN^$f1xPC?qM7d5gO3ik7X?oQKjzU4isT?Yga4~G$Ll=v>u!|6EU?W%m@(G z(iSz28^Bo?v4xBo1&K_O=E#rXFTYsOJqN zk8Kl&7#IK950gU0pmM^&M)4y_x|U@gSpQx;Oi;`suu4*DWCvCxsU9TRnl_di4tv(`QaBY2YhfQvCy?zOR`3cZqRL zX*(#i`cQO#JuXhKhn3VBR4<8>R0|w?D@t!u`xv=2d)s|92tQE!xj=_DyDhh5mZYCy zKyB4~ceQpxmQ!vvv-r3~*F&9zaoI=(7^Iq`gqwmiqOmk)f+Q~-OU`%}e09UA*~xKuXhq33R8?sd9)RVkvG|QCA#a zcz&F5?Xh6u3Ap9Ps{X{ugg7viv7qlVgN$QLePWvl)LZK~+u8+AOkhaNBNt#Lm(s}x zfnsCwl7R38wtVIhcdR(M?onq0IYI}yQep9NCGl77?l8uw5Lmw70kI!&NuS2K0O~QI zDDqTgsc%H%Z|lVUb5s4)sE|>4`vsKG{S!DTwJ!m(upQ&Q#6>{s(~0F1HG%R6?~|L$ z6W<=FZgDa|FCcaz=pO2M5K)sb;Ab#JppUo}_~3?9=Nt9XNq!v2;2#hYG*A-qgxH}> zIrPpn%*>$E_n>vKkn<2BWhz4BGFz?>VXMf@7|CoJcPI>xoNy~yM=Civu%I?bzm-qJ z4Rf)POmp)na^d>j*ZB)eDIICeanAGcipVe~Djlu|=Z;TQQO-Yc&5IX^ihL-+$#8v( zng^soPpxHCN|^LZE{IUs1ngwYVeTu-Z(tC0%sP+FmafbqZSzZmD~tXT!>-^~x==Ql zAJw7(uG|Yza#j=znp3`DWx80{L{X8E?j=hQ#7{sl-;nAt7VH)l?1URPuTZu95csj~ z+qJ%EOS04>tsn!R!E?`lraf=OvN$|H7wWa7%%#TX?924d?=qq6DY7KWBP_0?GE%mr z#*;QSrly>^#CxFTpP42{GOu^BRQatxfM)TzUR`Hm!32E3*=rg0Va_H(;1{@R6KoK_ z%4|G%RiKChx5;wlw?$`><%or4J4HWGeSDgJ6&4A}hxirwpk?j~etD#oP@M&!YZd^) z_1F=PMnYm&Y`TWJ&EgjE0tWJY8q#XYfI2yr?{NwUI7UgOrX~pLe0fk!NnK#BIK_%3rz5h zgXU!SwUQpRa%I-iO7q%HA}oEi0-CiVFn#kY8XmYNGvL1=M6MGDHFiY-$LgpL4N&(T zG_q0sUh4*PUWS_0fu-WnIk9f(!VQzd)qZ(hZ@ySpTV0>F(el~gTTSksA2U>yAe+;6>MwXRvvpatOO&}|7? zN;2BIBN@4`2=G+*WrADNTGu@ZO?)~40+U~TY*1h9(*sS^CCSr0jA}U>&><^cTYe}9 zde#Ic)l9pEDrcd!A+A=xz8}-ZUZS_3kW643sA$^yFFVf@ zyQ+e_xf|(YMuwRli>p|$dHAs|)(*i2{hc#1`0l)wlbfJ0Wo_b7P6qFEpD;L6kbC2lWlc3q2fa zm-OFQG4INm3pY>(ShT4{c~lt>KwWgC1^18+jcGCugi_>8Ow(?`bzU>;lCMoDM2U4( z6pU;!?!Y!J8lhEe*CiL}wMvcAO^<%UtcQx2xdY4k9+mH-QPu1}Fhw&z7Cz+NjN%R?J>p;9)loIx!$u92-HadHQHfLv zT1=F|p|JSe3N#0e-`tMzicKTY{rzd)yggHXukNoReq*&nS*!)fB-J{~vk0olu4mr2 zN?NeS^FNJjO~XG{!Lw|`KKc~|;;3s;glAAp%DN-PltHVH2y`}6&ZN?~?M;dc*?d&U zx@OGWN>g@#)BDn}3n2kuq#!SKuEg5V7c32%Zub037NBX?_+ZWGUP_Dx+{Jv+ zIBC_9G}B#r2766c=wegFYbuv?0iDCc6K=}Zd`^^aK2vz%2yy9TyN!J-y>c-cmsq)0 zX+c0+S1>r<^l76*W#pZXz>H?ck~IdgyE=_(%#^j)YP<&!DBODk(g9_)drA_Vi@bWB zL>P7<&AU;Unj_E~)LlOWceUL|9z7oVv}idAJShYMR9vvO8bM-S4@AS9vmRqBoy2=z z5J4A1Ovxq?&kRuaoAX-w!7VdkUNl78!Xo>+Tm@EV>{s@Z~6Hq9p`A>pfzQvS*;+5#T}D6AoYt4t=OFM{)CsldFR+rtf}pS~fKxVTcWbUk+%B0aafJ;oQ)SsD`w8@Y`L9$@PVgtn`~`r{a#RMT*f zWX@_C(x}AC7Q`03C6vsgwqQ;{hs;#u>xq}Rcc1|f5xZe#wvTaK)*`$MDs*c0y%o~F z!9Tn)3m*AVs0Y5UE`N08CN)OgbH7`0E%PA@dPNt3F)fbxkc9V8N!+9)c7HCq(?515 zfl0yb{{SAs>y2hMJ>k^I`v?c1Gt5SbhI6_Pio@&z7G}*b6}`munF7w<(nH$9z%f0O zEz|>8QK~6-@={v3I$15C@mzMOiN0Q-Svf}~J6Xi~*<=6$MH;VrgU;Pn#`2`EXj))oI zmiOwA+3jO`kKfzw@o}$o>8kzQ1rE~202l7pq*Gn9y1C#6P1^eiXTg^S%=sG$yr{DDQ+TPh#x zK$DV6(i(THALqy0N(`eH^RG=dm#g`A(Ykjp4HtX?f$eWX)U-h|W{Q|Bve`UT z@Yr(*q@00*ML|(KxoDgfx<$G(wPZQzeLL7(w>%FQH<(?@+4>7PcsmAi%QzxCGnm-M z1;k-m-*d)s20^Ate&m_#DI6VV741+Q7nvUq6$WHPgHTQH6#m5Wa(R1Xgwwrx{V{7upG535)lo7c3yml-xrH<7gbKC zm_HInp#Z`yL23w}B9v2dXI>{$l}JZ*IldfEJQhT$g|9=~A6t^wlTN`}6J5T$LSw_w)Vr>F(+Zz~>7L!;bFoCIYHal8!Y3vq&iBnL^Nil#eBl7?jqNwSW| ziVoO+rKnQ_u>!>cNB@vK^Ji5}_UO7FtBUp|IH@Mz- z+_1d8d&#x%eW~WOZtdad;_8k02C?nn6cw4hES1+AO7B^TKW3Z9s~v$fqqsMl+y9Wh zGY=^$PwYDyAd_R>JbG^^9zR5*?^zz78kyY4|C-E!Si-l)_;eqix?3cQ23&Go!pWa6 z4)ZqxjimB{T#|S;1J6il=|Y(-C`gn?(E2C-f^3xTmb#;&jL%!OPbh*fYd$E|A=7Hd71@--PK1P2$|H@C+kcB0A+v7)EeF4qsm zr=8nPfXfHL(w5I7kBXG{!GtS@#}=#pg;(o z2S{EJdfYQwAZ|_yAsK!+`>rO5VY6Q(lcgX*1kLVqo-0G?5)lc?s#`ud$L;X%-(r%4 zc(DSD+r|lrp+);~%-UfG#LLi2K%C_~=6%VOl&syLz{N_3PBi>sro@>9Vw&cT-X_~1 za1`>H4h(LoWJI=@4@ChE2$EXCN0?@Lc?=S{8Tp)ouUhJ%aY7|INiL@+MLEHgr^N+H zmZv4fg{7yZ<&CGOWz~a}XXW*amQ;w81FWK|O^>H%;Jsi}=hbK*mM}HL5LV~4s*C!0RjZ4JWz({Y#&wsoi>B>hs>|m6B&*AoYIKPHR~I$Z+hi7gE+3|H$(U# z)VIUL$=0_cEcv#X8p?O?3PPTbmF)ylkT(xfcN>R5TqIp_( zTC#cCa677a+Vpz5c-r!Xqt1-i>6teBQfufPdLfQ1fn@N;0eD*rrIa zyL>sy388&GE=ab0Jt;1#d_661x_mvW9-@6auV1o#yJ$YDe7kIax_rCphNOGH?nk$K zzZoX`;czs{cJ+QYEk^foKd)x@@qou9SN6EboKdm zJwyk1zhANgd^{gj0Y2ZKt^fcaxEvrz@otbwW93t(91!&3ZV1k6KO{I&FfwrgR^n=Z zjCUCbwiKkipVt9;E&AKS&1~O0Cj#-MbD6n|d(m32gXkl3;o1gcT}Y;ZXZUyET!;Jc zUav#=;qs7_iiL7T{+lm{9*7wz1~}?JptmLPAHJL|I>a2i|L)7lBl?>!XNmbQU(O=U zfB15g`XAf9s}8<=IrxHpfkA$-0m0!BCZxbPp^OZKjAw;SeED+b=5Y|*7FHsc zRyWp`H+Q_(cMtZq5C7rIxxTr*yMK6ms)l)fd;jX>k(ip+TU;~80aU}fwM&ikp3Q=-u|47AsXpeG_d_CdBr@vWA&~P-9 z%HX(ov0iZ`m&_43!PIGCCYdcb#nUjCj6WSIlHbuVk*}v%EWd1Y(RoFs=Bm-cOkgQP zxLCxWT7Cp^@2OaT{&}!UDAr4>((Vy(gS)d-7TE4*1dpbWa=z2=c%o`BV-xv{MOLwchdZ z_I!7?HPzMi6>$*c+W=oMH1lmgsLI4`f4IvYod6_Jc409TRq~x64AbJBU>uj@oe=zB z^4(D4B=g-c^1|ZXaO%e6-3aih~4YRSOd7s)D_mlrLX23-)RN(ud^RipGIDZMw; zq9}*cK&!X_g3+>sDD*Jzh-t}NvVDjyv)m6vyVVNEL!sXdj7Z4=%7xdyOt$Luy%CCFj z*v_x}ki`B0y#Wlf{}p;e)OY_4dfZRvb>SbM)c4cE=r;E=;$-kbK)Vz)#cBOG=ehIo zoHh>&>Sh%Wi`svOUIp2L;lDwT%eae%jpZlgf(6$*ArG;7MsUxOLxH_ckaoSj>Sn$p(p{9>oxR=dFJE5WPTfZTs+jTd zoOz_D_qO>rk;M!Y4;=d+yvY~*58hnqMQ{HbZ~pH-K(_|^sjIaoZ$Ez>Qdk_{fUt1G z(1_?5^{CkR1lhR6lvLs5w9G8FjO@I8n%sh-VuHewa(76UvWnWen!3i~hNjl+mbT86 zj;`KVguZ|C0nW|;hYwI6`0zv~`1C^JSOoTqH+Pp$Y+p9d=MUyv2ElN@C!ECVlC6@EzATz*;3cbv&Z`b7Q<#MDewv$?VPQqbs$86)3zza z&#zjTtf&k}!?Cbll9I`Gb?%OBCL|&ajg8;;Y^mBn%KXB^8Q+DX3W9&F)(Ig77dW`y z1`>Z1;yc!L;|Zvn=niJs6vHI{lS6usEQ-*vHmTFr>=uUDC;y8x1W0ZC^5ooJ(9X^Q zMw2%lkEc3tn-skQiuXHvaDmAtz@6=53I5jus<}QJ=y#}1|M_#(ACe&4P`S+ToNflJ z-(^Fyg0MN`bAt&q_i|q_w-L@hI``zNBxHs7YW7zX@jbgYV zQi&qKzeDfGh}P!rMWW6x7tjL}mJmltHnWqU*Epa2v68ZNmv;R`%`ZsldVa#=GiOEC zfv{`*-*^*BTKX4nPLK0rMJZ1T5>zcu{-l_eo)l*Mm&lsj)=BxZ>sQJOs-1XRW^4}q zH<5K#F*_V?g>6vTdREm9@g=hQ(X7sEhDpo*U1T}rTK!XGy+u@Q26K%!>?W;2Hy;+h zL37KOdV;rJk^WpC||AROGtH{#Jb^14vRe7^XOVpXW8~m5ZiWQ@6>0hJJ zKiogf>vNhRNuQ!nI_lT|KSb6f({bg07g?U6)mN8od682nUImH>{w5^@d#i6(<9`!b z`3&!s9Dwpo6ewZ2^ZOKSQS*mE`zjuqVQRk57tHF2&(~gbn$F=XEgZhLd&hjwr9_kU%q*L0XVQ-vma15hX({$(Q+Lc!>Q& ztYXrzFuJp3rcDVjcc%D<8K7+CO`+FQBh=MFubi)gVRH={3I9!1(F3IeC;SKHW)0Iw zoO#X8Dvkf;c8;ki-m=2D$Nan78PAV;%uvvafayx5#Q`p&i2?zY;cE(5e9T%rBqE8v~m)jXVK3*XtIYc4z%kAuxonvVG zr{v4+%!`0oR`(CLb8%ePm)n`KXW+~2j9NZ6In^;S{XbCdzueCMR8`L}uYXfjK%g)< z;?+4l0Z_=4+QZekeIZChk{RMPc>@s`OqT1zHTgp^_c z{8cDis7Gr}W%6XC9B8zD=Q(wPV>V4|$2c3T50nXB>PEXqyl-GEUu=icC*dt(h~Df* z7~vsT61LPHh=E|3Z;rP(npLRz9(Qn0)LG2sWTKFKoY$XCXrlKETQZeIE|e#Cc;kAq zUZe}zsZGG!G@WgB{|2e@OJ`@?D*|V4R9LRMGoDtEE859v-8h@7^V!TILU7yI<&bLf z?t44F>z^$n;}fzoe%?7?QU~BdmPnrO97O=U({7%0Js(-f@ae!V#kOob?-#cG;l7*a z=zrD_82F-`&Ta<dc~JV>G6WMUc-*yt6)w1O%1uB~v#x5W>m{hd?0Zaq({ZH-01L@bFWJ_*cSk0-R1ut0I|Nw=$}^ zXNK-@h09XG^4d;D!-_Ts$}-*TMvqcJ^;)}GY3($rQD)_Ws-sQWO7Na~b=&tc3KUTn zsf*^J;Qx=iw_vC{%d)pG8k_`o5AF~=XdpNQ2=4Cg?he7--QC??g9ixi?h@g>q%5hb z?yBzTng7iD5#XM)fBUSx*0U=q8_Ge0!%($wEDwcGy_HU?MHdbN+5$>KELgAg@3(3| z^06yAW`{aY!ppXsEr~QiKhd#5?C@FkK)w#8XT0GaDeL*nzw~5aS5ADom)L;oysy_5 z=e(cj(_3L3Dlt_?J*?mi>rV1mmW~5Z$tDLUblb%?Xcnr<3XsPD zz49d!*3nvZ6o%+8jWS;uAF>o`LO%6bN|0x~bqjECQF!<$RK1@w5?_wP)`4*|k-DP= z%1yT{CGW@NtE+=VHfn5OV=0FO{{BB% z1#i_#nLCUqk|ExmYsq@xL+1+Z!kseoTN%xVvI8>zxRsIq&Xg<q*x%y2l}hmGo8bJ2%qps(>+@&Upxz8}OXwzEp8QjAu7?|)mXh!=4;1< z?^n&_3esG&SsFme)6#Za%d;t7(qVCw+7m@QyWC%(CwW_$WaqUqxS=#N!K+#N)-y8# zlV?SFvcdZ}Jt!&dZGLc2{=IOyiyL}D&l8%AI6GA#DiTdZu{r$0^2*SJxAKIrP*qs5 zRVER$5)9Z=+h%dqrnSQcd?Ef{!Q*P4KSv*wb_rP9@~bTsG*Httc`^r+S6Jf)s$(;} zc!Y{t-wI!586dW_j&;*8AW>!=KfJWfanm^Q5LRZJFSfj|eA6^PT4rBAynO6@)4U2_ z?$|H(@w_jF=9t04NwWAUMUh}t_S+N0vb@=IWtO&c2pl)BPik;(Fzt70Z+vO7S3w2N zvjA}esx)2o6!Tt)_4gQFIb*zYg-Ki2 zN`sRmnVV;PSzRS3TDV2)ayP7rP@T{(zRj3?H)1GRoiz7(iS^KtZl#EkEATKTB`#r9 z>#Ig%3mnR`k&9GV13m0S(=Gt%Fie>~Tt=_k=F>>55k6Yo+?M4F zBjKEV?JrI08j=Rf-nj2n;zzVz*PUy|zeI3oHO?}pvX}K7;%+&USk%~}tnJiMtY(Oq z7;Y+;8HDH8qX7iV@Hx;iQ(=7u#DUF9^1XF{F_$c`U)l_(3Y?6m(t3?1#Mp{Zkh#pm zQ;n3d<3G;$5>9I_@^}Tb{*8A)5skia^@^+&)}*)*=gSn@4~J={^ln2OjU*{-TeQU! z=IcFoG+-0t3b%Z{tK2>hYjy{-FA_T*p6wPWt5$%V-x0(}j`vz0$GQ(w4iG0RX31iv zFx?1Uj1ZZCIp7Xzpx+nwhVN8(%x~*Taf*$UUGs<~c3N08FYSDluTxN+7N6^%*^;Yuoef zqfTo-4jez}Ig0VSuMyLnl+v*$uV=-w6p}{TXu?mp)~)d0Sc_BD;3&8ebS6!wfTsn- za=g$!2oUC67rlcQ1iwJ;HZrB1xw|mGG(J=BKRBV@Aqr!y!Y5hS?6*MgNjKUd9nD|b z;4pDZ#|lfnJ-5(LzCuC=y&bRfu=`a0HCiy=Mxu)|dk!3+Er5seG7FstWEbbUlL1PI z3B%sC4%H?3g7-bK`FmCktI4;1J7i*SJfG{y@+sIYMX?ZJSXb#m_r(d#I`B{kk;V3K z^jW`zhqCF9_Eukg2`kKYOXfL%?h!)ftAU2xkz*1X0RHT|PP7?d3FrlU27Eu%h#%ez z-8A_2-Zt?^QfdNncN*Y%&J%##9ci+Ccwi@rBo{-IKCx>&XCqv$xXY)rg;~9N$~0XX zJZ_joD4UwQVyUo*UcN|o(Cj|A`^en^_40)yeBv%4FX<9S;TPfI6X{_R9jp+3nzr+WkUJW%efG zDz$r;V**nk3}FR~ygj|?WU$H}V(F5tO;-o=)g~)rt<5(ltKA{^Qf)1F7rRr%8slxP zpKeY!hSR0m+kU6-(f+LOkrn{;J(k^7puR`G=8Gb4_(y$@g^m9^$)*kv0r&s_JU(VD z2d@%ZG1|$@$2A9_RK7zuT{6AVX5oUl-eT_zlc9PsPs5cY9(S0#16UMsUvU}x__Fbd^~+|k|H@a0#g zuoP9c2>8G@GF{WtPyJ6bsJ!5ggV+rxP1Q^_BNxXg?^HVfsYye!mT(}`@QcZ;zYx|!oMXE|EXm2v6lC{ zGhGV^2P^`BgtG5uz5T;vzv9U9);Jk~WwG89=)rjC5TR~Z!!&8yIIA?Y_7})v#z<9; z=_9f4x8-h~ttg?4Gj;e-T`ES~oNHFe!P;KA;%LI9`uf_$!O5G~McxC>$WF~Cl-o}> zAjn2MESC12Ok@CDOk5hhPf|c?dM-)At1OS4yi(i(z9P4hvRZ;nk0|4sx>o)Mw8%N6!3&14!7i;*q( zo$2u1?~heIz!xwG*#7Zr+x6SA`fJLaVz_4~aGJK#-&IBauG(-0Z3Hspxj`kn1W)Or zqrWQx-P{AQgOjO?m5XN}uD6etzK)fDP!w87sG477WOQFoBgH1YT(zF z*9Qhyw5DJ(TR56h4XFG4pFCD8V{&|W$RNMjNNRy+AO!I8hcl2rLKZ#^oNzQH8gsIn zf7AXjLViy=G)9})71$|>Dww368JfXSt}uVwK^}moTkZTZRj7MizsXdlJ5cNR&aQehh3}`m4+&@7(+X{%oY| z6!X~f1n=VL)Vg}X>Z+2Kytek>rjYKk-j~%`j-@y%BQ#?mi1y93J=1(+<35YS%d9H{ zHA;vZo6IY#Ir|9b^aqEG#{)#4R5+ULm$3Qi!dOcdGbb~NtqIEM&R>6>$g$sK7FP&ggke7lzmer4wMBgu$GK0 zyU@}E*J2`}r^#ZHQSizfCmBQEr%M=d`xRBIL*&S~Fpg4cnsimr(HwqmVo57`LRxJM zF9Ls5RVNqie^4@HA{+dIucL{XrSdHIsZXKtG>^RxBPP4xN=vSD~o+#hwfjAvXh~wLBCwC(SoV>pE;@1cCu`myBsm0qxyf&i5>b*u5SC zZ75%fUwzkv^8yS3rvT$0j>IGUlB6+3@85-A9X?Eg;BoXE*IT%dwKj-Z1#IB`YOVS%A%zv3;xb-ntrH&jf*YySUvdfFp;7%S` z6J<{QGV)$+9PDpRxKIS$gIL@T%&Vi(9O%=UVB8ASL_> z%9r3SoJuGT(CB8A>K9*l<7Ev_C`%b@Sj_uBUGWECGdkMK=d~UvsO(&Kj9$9BW%V8G zF*>}pL2^NI^AYuUWB=BQ+Qt(#P?kT^D_oxq)!)@SHqAtj_jpt2Gx z3Z=TH!5OD6xT!g^2HO?^5uvwi5H}UMZfJbM&v0^j(DvDH)rlI=0gwkE1OJRyznI*P zl+}P7*6Y|`O>VYk`8%ZncgM*Y=@ZB}Sop2k6$)}#$zug5+X?I3^P8~7rB==lmION@3pW2ULh^fK#~4!Ys3m&NiiF$bcr7HYLx~TW#>1qEPY4NKnm}V39W|5~Q9N|f{CS#go>&B&J-TH!R_Dk9~+V!jQH)ajX+WPnq>bYFB!&9 z<~LrlDSZATFL|Hvk(XQt_@Ch=KVGK-)j1$9nQviv6&Gx66Gvj}7hdw;ogl84TA}?i zL8O1c@Wc`MWrBEPwp9>Et20E+P@OlL%w{7gopCYMnD*~+6BAuOD@rJ???x z`T{j*x5ZOjYIORQY>%5RE`fxKwU$6wsW$>*Rlfa>^Ufd(7QY6acbVb$pFcyWixQ}(HmpV!p^ z92S%`H;5Mq1Q;5Wp=ax7I}jA%gP4zkoI>!B2;dkM%Pnr7b{lte>Adda!B&G_t3Nn_ zE*Y#k?XlOVIZvsbsR2Oo0@b{bJ_e}UlrQ(JfPH=QCesgpJs?pV^FxhRfUK_}o*yL< zxpI(DCb?h;^7}x|w~Rts*>=?L9SPsEb7w4rf`QWuJ>z7Y&1ikN(<=>T;>?%o8c3*nPMWgpNd@dEa?$@BpUfdFW^ z{HJDAY3#BC{^nzE&*bVe_YUmVt0dWCh|}#~eOc%wGR1M2)Ll}*2yagy!aD*p^6DX$ zvnJGjOe<^D;U@RFXpP{-3s@aR z1o~}gq->&B5}!*22D@az&IP<8S1t*bl_Nrnefr(QiWlGsPy-SDL9_X(i~h}@|3`$p zjEyp|BpO;x#sCrW)Wt=>lBh}hqg54$Jng>`As=n`9&dW4Wp2Ld!(ufMB9BNWv9%T^ zhqOv5ceHV^<9$lCM}Bcue05unfO3y^a}AB-7~u72svt$lsL&DsN&V{P-O!!c>jOup zj6x7eKoo}kz{jzPVfp5@E)jm7oUql@pah(Ai7FeimY4)x*i28u)as}>d&re;gcVs& z6y6OSjq-)zdqJ`IaF-%-W2t;O9(AA~S&UmOl<)ikysmJ*(syXAC)hsXL#*i{q;oQ3 z*%FVf;D^>lGP;3Q*I4sbXBNwqPOWAvdE$&mDVq>6P(1P6v-kXi(Z`lM+@0}bQu0{_ ztcxcT1yi|@X3kPOGX*c(rfS~#vRw?+)`nR$}uHg7jp9&ks3SXOanafLOFVSXoN z`%g*zWK~5>0{eSb)&E%?@^{v;KlkS!ls0S^9h9{I{rSII$Ef|V@gA*X-VvsvfAHrU zpPJSqxfgF&uSZQtH5%dpj?H!{i$8*GD7P&tC298A? zb-oq)u7Q^Z=mI1`)PB5Pt98Er+cz})g9iSm4Gn*{o{+DjO3 zh+l^yJczk2?ON#yMq`L&`C`cQ3`Ns%_Qe!f>mec?>GPKaMHxt?!kIUL?OzaiLBlb# zMDS|rO}<0443GFA13DT18lQP0aGGMG00T|B)cI-)JVdQ^Ka^75^ew#JC}St_Z;23nC`7Y?D*00c|IPFehq?l_b(vV7u^mS8a$sW5+E>E z9}L0dBN9EKkm6RoNtkcb!QqI6HGR=v?I!twdS4Ovz5_0ILUgiA==8%5C)EDan84=< z(hy#@Z!v*Ct-Xc5;WF#IdOys72K!>QfiZ#q+6?I5uD##ccCG$Ud;d{3>a>sQq~-Ek zOu$`KzwO|3;Fp*Hy6JwK^SueswhPwi+2zf@bZUY$1zib7A{Uz97h-*w+mA{>&%jCW zpk$r&{VkLMxB?_Vgnzt+7+}9nt^Rtv@QcRsxI_mXceloAbT)71r~&6*X#B)ccRBLp zlZT6kw-1Y#Z$Kc8UC=K}bXZ}4VV!?}iOvtV&=G8PV>8cns}dG=w-gFx=U}HF;b7eL z{P6BxVgC!F{U@2bPpiDDygZPvq1XmQ06vel(wJS#tll8FFLEsdk)3_vXb<=W!;U+^ zsTCQWOu_4@u)!EajV{%Ns<4q5R;l0;3NkX`bX2M+?1R9%5?WqXj_#`Le znu4AjnSA9i;Va|m5}hXNWteAF^A)-}d8lVs)EJdd*SMJvu8))(O=D+|ywT~FTU}4e zzQ8()t#q2fny{zDRcKR(4sy7gK0luwjPcn0Qo-x_ILr^gBWSYS8_}4(QW;IMdp}#D zhS*zAT6Yv#Z-K2+lkafiVL=b>@g(Bb5)Tk!vKr-JzTA=h z8rJz6!~Fkslh{AIh4%^4z=Wc+fF~EE=cYn(qw()MAlzCQCDYjcHbp7zZhgBFc;lCh zi-$Fl)X62`-`@~bplo9C2ic^79oWQZ|0bKHHW>Xpe2E)=w7Xajilc>%KE_K}(%Fh1 z*GzFLPCEc)lYnrM+mXMwW{TxGFkZs{7%z!S&&;AV0>;_!9^-5%z&Kled1Xy{b!|gJ zJ>!$cHrwX*uF%fzzJT8TA@9NAF}GgO@hPX#>A8;i$2C)$A6Knr*EW?mwsvK9_6|jh zV2;jY56-W+FR$-j+}?ko|NIrS3_$*i@p_&d@Ylxcf1!!_z1_tf>QiyI8GKBSLu- zKVuh<9Ezow^9hXr`d-r52a%)cFAY%go=;T?HQ6LhDamlwNqY(z&zIYn%#zx#dE3=% z>C6&J*VeD5&`qWz=9TpjI^cm~1ma7jxq^Yff|Ao$Xmx;s zzz;Fqwh^^_{&c>UjbDN1g5 zdCi`B6J+|Kdk3a_;<}$^2Exe&5;-C1Dy&12Wnp9of(8q&hM>NYC8#r-)4u1h)!&}$qqT_+PJf@zwIiO zhN+uGX>Oz+Cu2^bo+37e8IUa1*_fB6bZ?aJ=;_Z+o<=2ks>32vdPkOED+-iAzr{=9 zC4=|!5`>cYk~3(r_6xvho5<27Be9ASi?a6je$DXy{)YTMULsn?{Wmhai{5s}zkR2+ zi%;4%kmew$Ve(#^cBrKqZk6x8;5#4`3 zO!BYRw733XWyY~W=D>$pqGW*zZy5E0h2e8vSS_H1uPn1CkN8st%?AtP*DcFp#z#w4 z`X`jbRN5ztZHK!bP*b{3o^+dcs)M=4RjT&m5!A=x2v}(jPtZF|n4-zZyE+`mr~^1^ z)ZbgOqbtF?fF90QiBYRiHG$SGCO=;qlTeKSKt5Xd+CH-ZBf5Ukv~AiTmj{EXIss)( z%vZ2*%HTkUS*QKxhjF@-vP5UcXE1mK6HhgHowoO8$P5q{+=4b9XDSbXCzkXbpkN94 z>DHeyxACFxo};gN!eCT%dfk}iCz&O$T`xa*rp~$sI2(=cbi_PXkXJ+WB%TW(@-0ZS z0f|y1aLaevAqss;JD(B=3dc(TrG3?x4at}mziEREskt6WPaTvRGsi~(7CWJJw*+CG zs{cHYn=)U|mK0@SJsvOgPA6f&$|x^Vy_MBFNxN!6Ke0JgDJ6yB!yq8_(;DB97Qgrq{qYiNQ;E`g|VL0+D+u|8dvkceqF z$edRGD_4&265MrVW!=}#`FtKt$5@BKb>V$;6*UqHKSt*MnoICq@BJUHY2Ua6zl+TM zYc=hWOR#KOAW-&21a=<5mJ_P9!geNtRb%ucO+x_9XE(*l04Mt!X4eBVs)`oLyoQZ* ze!P^;K_MVD%_l(TW5#x(^0A3Q7}!^~os4!($9;|9kM%o4X=x@t%q8yZONgcOcT0ne z$qlyk7v}fd0VfDP0dDWYKm8^JD_BZCSYOQ!zjD0hnrS^LOSizc&^_7{YrDBkle%l& zM;vcED$hr3zdfz9XlcE!mbCcVxxw>r^T4D5kVX1VktGL^0dhdHf2mArEZ;Bn)SusP zJ9*!=bf|>@zpkAYz_omI26iXPA~QiQGK;Xx0|Ox6EG~AnM!kg*Kd^xjQDX# z^*hN32`2n!yA#qN-*4t(QT^wS=Het@vbqx7D*dTGzT!F>>^jSqCOep$u%$-vgY{)> zA-a`z{?DLzhy3(w-DGgY>Ps86I{7j)Z0_Ptnp>rj8(FfhN*mkb(Y>Ca%l8G1Hljz82nVwwhe0CbF33k8E21qYV^u8&anb2{%k zi7Or}d#UCyvrLvl?ZfHN%8*xHtRY3-nlW)0-}vCq<=%PcuDcKr*#55M?9-bmjR*W` zh=wswR}{kxR;c65RqrL{27dr20E&MUKi?p5ILHB zmKb$ifp_qoGh6-ZZn$;pl-gZk{2!Sg{WHr`4*Ru0=n`nV5{ z-udbBhlTtmDW1aQk^Xs}yQIOi_qy5ST$Ca?QQEIxXCz`VZ$r=9I^*YNFp?B;rzd43 zljX!EQX=)GCXE-1_D~*pm3DEEd)1fmn(!uECykWz0Op7xnqgp}D|e`GLLRCcAp_Ix zaBl%eG#@C6X#%F5CphAJ)RZ*8PXy^SKteEfhwY=9p@o*K2)Ys^bT7;$3kV6Vk`%~xO_le2Z0eJz&ezx zu9Bzog|@k9a$h}{Ver?ZE?;#`Oz68CABZkUzb>pbJU{^nO8BW8ru15bE`~Q?^;E*R zSry;Wks*DMDv()KD^B?qj;7Yc@nEBqqn0TTpMAx9RCtU?f) zxkE_R)EDsvl7kKpQDeYzk!5HXggNgSqL3->CmgN0JISBxMq+fbxNuWC}>;c1+A z7MsNGzQEO?0gW`M$Y#ZU#&%fCM0it@&i-;R zkp4X~zFq`bLsf#*{g*Pw9nYSMx94q2g3F?rN{ENtmqH4lQ%%n(omt>2&s%1Jh5 zY?lD`Cw(R9Jh4zII61Jg+*oY0$!DO&*lXCZ4@GmcjWt9-w9^FEnDdu=VDgD%gI;J= zv-7}bN~$z9qNT)m6>q9ay9vnTB^h&21QH8If5^;zA7iOVleki4AD^hcTQtS6U+J2k zP~?7v^f^V5RyMLnO}JCKv@)AFlY-~fRZTh1{pg(Nrld9hTPPT}{SBB}%!`K8io4|L zkoQ-`Z)7US`)@-fgsqfRv7#w(BT3vQr04bd>|L$iQcJ+WjMUhpK|UlG;faVX7&4QT zNogHf_Hl&tcg+@4l^z)hE}$$oQKPGt%8OT%sam=dHNrh`;;Aa^DbMs(xq0f+&O7ok z9~^^69Uuqt_oCn|jAhpNL(pQj6eE+lN&yo|bVX==YAh9VnG>*bu2iqlc0oZ~^WL6d z9CIQ!@NbxY!o?R*BgMbxw}c1x$3^3qo68DUAO~#gIDBzo^q%2uM@JC#KY-Oj!0#z> z_pt~R)LD-jH0?pmi!!r&yR;=!k4YsYaJet75IXbDT3fetw}5FVHzuH@=1b)*hDu4m z^XppfN+UmFt`aA`1TThTuXF2Yy#f+PIl8hWmB~9^4@)U2b^HBz8|My431Zw}aJ<+> zPCfE;wvm^!Rw4K@YC)1)LzW2_BGfqT(AAdf*ZOaI0zy+}t(llo{YqrS8?*f?B5| z*y%qt*v~I(3JUF3$}+*l*crZ_>*VIFe9g7{^&)2h#O5-Y!2HOAL83ok{UG>S=-AA{ zae2=lF)VXvpM=21Gg~dR`=2kNXMxB4P_+V{l>#5L!uRZ zs>FULNk@YD+A7dv%EA44!cC{Uh1V!){Y`UTNW~w=+!@GVP`4ZL4(7V0Zsb9V%iJE` zqjb+*8L_-|FEmF3Bg4IV+4;dGz*lpVXX~h5L+a{m+vr*k|At|i`_hT%pn6EAebzzr zE}!J@Ab`5!VpBGYGgwg#8=!g0g zlVUp2*G5OsokhxHM1d$do6TY%i73!PLp$#pQbR}HV??JApiWLjf`hu+-U@CGL~?p@ zAw;~c2~Z_ss?TGHKCz29@g1~rF#MT8yE?fEfW&)-p14(eG$tgi0F9Z|CZ^>IQ;Vu#a>MxU8uMxRr16%J{_t+vc zoRStI#fmV=k{4cyU|RGPL{S(y#4{zqB*qU7a4!WZw(r58qf@LU!fUg|&N}%H7lz&4 zB=79Wt^}ntE~Mqv`8aN%p4~kNUpR&Bu%!)RQughsf-5I~3G!P8BxOnmA3C`%)dMiB z5EB|X0WeX*^8xyM8R8d!asixAn0!x$LZDz$+|g3aq|=^0iP%g`6ZDHCrA!?rM!Kc2 z$5+PK?GtJ6MPn;42h)Wiev{o6l|@sH1bL-($*VYPsIVW!K0~DYDgtxjSwN7Maha3$ zo~|&)z18If9XEgC}?ZlN|8eg@l;@OFjob}MwSv^XGmH|B<-Fs;owq;kT+j9 zE@x3ccV_|=6xcM$$d&v=F356{=SLS zRp;E(>^F+uJf{YEce)}N%As+<4KSH6#kL)fr3*>VGm$t_%)F%*3o*uc`O@yut|m+Q zDW9bor~5@1+8Dv=|KDkUGEtG~c&S;#CmUU7huq}Ie=aSo~M{Eq4<^D~&mcyIp zQ0HV~;`6Ux6%&GEKZK?iicK`t^jv#6Jgup-N+G67N8qSsgsDQ{_aIft+~Kn)+_J?< zwss{=d4eshY6GSymXzKP3hq^9`y`X`;0d-&mQ^u~XF;{uv*3VLuAYu$6>P&^7F{(? zbg_c!mZ|yyIa7mV4`G#Lr4Np!Q#QfY4Hl~=BarX7uv5QqBue)+n)5ooo5_;qD{8Q8 zw4`WEhHczUOd=p^F6d|~-fz;vc5ZZmEikD^%fWDAfcds(kdU#T9G~KA0srsnRy{3H~i$LcT?)uvq1xHeFC~ zZnvMH-!>0gykf>#QVqdAXlqD3Zwj$PerNH=vB_)2kuQ|6t zEx(mpG`R`73I0sRsRjM*i$=?q6gFten#3MauK1br0m>oEP*_z|sy_FW&{sTLxp0#tW)Z*o2|Abe|>mNQ7ug&DEPrFw>QDDjGTa(So`l94>R`)+YU(qR}WdZMFKDebDfewepzt_-Aw4rQ6fT~6>pODE8odMza@ zMBFbzRuOjp>3VG!QU|dCrtB=WO&?BMr`EHuAc<9JKb8ytQ>!XM3k^Ol8@eM%-eGpm z?(0TZR|dgSbQ|)?S_0UvPh2AhldNXb@9E7*N}-CM<_9Q`tE-K1Q_s4|bn731NUK79 z?RZ6zI?L^kGXgiqYt&|&YOUZlN0lS#aEZ@Rw%J z^(bAc4OKQmt%13sOnd5x=Gzm=C!e zV&_~>fN6J2;TAS~WQei>(?{1d^NR$aMX=;?{MWwvI3R!IF8w3d^jqM7JSg~)yYwz1 zGAcSIHtySioY6leJtH$K`&&q(u&B7Cw5%M+T>>I}>*_1W8k$>L+uA!if!w9uzoN_i zOWdW6-C*HLqD-(~UDH2umwpqZ{?fxVn?hb|%o8gA$FzH+w1mkxGBE8fOQ_`dihsEX z5@ETuncAYe)n=m#i=&wEIi!%iUQC^{I~%*q17hnzk2s2(GoM02r?jd+b+iXUlbaprI5~p%7Sv34)IaxZ4&inL7%*gj+#PI>2S~Sn74!rF#cCis{`7fi5phC6 z;{nE9E29GdyGf?vaSku+YyK^h0D}_92T;6INb-3Z`Xt#M7EYQF6wh>E4Gs?hozRAi zF>>9825Nr&3EjCtyvN08Ab(i5M21#4M|cOZ1kK=xGjsE z>#qc1{V}Lp)s=D8AU#ObF;S)oDmWF~PdS1tJ%sWDd1}O0%fhro|Di%nR&pz1q_Di; zy@DV@FY>%1?;%Q6Y0;;}Nm<-jN@_MomQ?YL2+r%}ClH)Q#ftL0)J}aYb?OhApVpeF z9l~Ln6KSPn=u7QJ<&)&Akl+9Z4ORO?SaqBUO@M+$ZiS;t@63>oO&xV&OU+|-q!xAl zfhr}f-D?Lls!jA0C+(Z-`${1dxZ*S&Ezn$+s+H`A$94C5C6z8nAu?2)dPzkci3Y(U z=YzUQq346t`}6Z2q`datIZ+>ks*Up{aLV=Xkc=-z6F^!|OUSbN=g0YFDQl|550;Xk zS*3H=`Zdp2@pbLxC460X^-61>${qlY=QO2Q0D6L05_O2O?|>X%`Fb_X8OwHpoB3(B z(y?X7xuY8r+XtE-5WccH#*cKlM}+UsuIY#GT+?}xY5c2s`P|+gi+)A;Mr25SIzp}p zcR6S}8IwL~>o#{e&2*7?MEI6}{!J?X3E}(bn!aB88R7f&b~E1M>)mdC`S%FlU_^_1 z(Cg%5-r@QksiucZ*bIOIXa~rCfhVMR#^;ZDKOuZWGk^%+PMEkXgEm+IBn<`$I4G?X z-VzQNyD)#IVu3HY_!>3~23N^b3y%T}La}4(E@{^wQci$6k?wqyDIuM&?}Qe`eO{Lt zRAr!^72(;KKNlPBvmohE?H8Wpy_8tK=5k#Ah|7_JRHDw45CeBv82!S1jPG+p^u@EW z<_7v$n$E&3L$h&qg!?&;Y3ZbO&3haG4t{>+n*e)PZrM z3QM^- zBkUJ4?7-^s3!xH#FcGswF!O_130nJDH(4K9R7spl3##6HZsD@eY-k%}{}d*&vtjcx z9_(n@CWx*b=F9!9tlt=q9*+k(%xALIuYWr=zjXWhFJZxd>H_?Z1fhp{^UNsg9fE7) zRswpk$Uk)fI_bp=fWqWtxIe;zfg}j>XYtR1brM2;gm=DApzz910TR*`Tf@E)()TqB zi@qnMA2^49+{Z0w`sTnU9iVzQ0bz1T+Wn!SLz3Y8XfFdG17HOL%zu9el6VXy=o-m) z{W_fgcdrDQPxB8~!tP1nA3Ba7uLP@8(RUpOFT$U699~U7@w1cR=H?eZd;nei_>p2J zdu4Ned216Cc0Fr%?|5bZkQnwL&sx!kg#9zC>q{wwQY)BQeY-Rj(3lo{z-6 zBwL6HWHQXo#0bIqaudBH^J;;F0QZhL%JY%0GsB@-tWaK3L{wBC{>axkcqu%5T{2&( zKUbGZrDeWY|9AO1)UQB(;_JLz!~7rP>*W4;B{XeBU;f0`$wbLh1M;)8bO-*x&yHYU zB@Cel#n1|6K4;az4xYEq#?qRs(+T5!yb^dV!kdvHUjjFySTP2Ha1_xU-A8`*uW%Hl zgedi&_}Pt1F{oKae}JPju8O23A)goKYq)=9md8b{50DrB47l%XFU(Zf%qyy+VMz+%Jc(M zEm-p#qgj1CxfoffMBW1+2+u_2*Mmu`b~A0>V(rC4iLj~e=XpT z;LqaC3A;6#NHP%=jnMrL>qEsA^efh94)jMrK zOE+K7K}qXnlCSBnRymY5c_ivzt#VwFb=v$mc|GbJe3jim^1GENqy=!@h4gb#f$s=J z+yHWbIY`LwuivAWJKg6OSJ&VDaL5a>LvX|)zbGcYWpW3bZslVA&IO=HHz;K zF&lsZ;0)sZheP~M;J0tc&#|Dk%SXNC?^zQqXXqX|*Z-jh!T*Uv{71dz7rJ08#sH8m zNUH{7f3e+LTwku*=6-b#SAtHz*5r>kE>V)ux!M;(xDtz#Shc}!W3H@Ul5n9l?u)NG z*0{h3HsST=6Y6Mnjmc2ar>c*4%GQTnc?Jh1@ORfAm$I$S%?}sN&zhP?*@tF|_~ z;t@~aT52y3>WZiOJ|;I_FE0hTc;KnpIPOm&3cRb%XsNmMO;*TjX$${ka4P#Q-y>b$ zz5VwjtvzTXq;5cY;nhGv4icf6l&nod|v;CE_pvBqa?AUaY-r8d9#Q z90n=wZbH>x&~T%%&2ovOKI&<_`n1|{{{=MMp9K>BurldS?AD8-NslS@Z!443{vsA6 zNDx9Rv|k2Xne;cTiJ$6*f7u>FbzlkieZYYoFb=Q>S^6Vp#VGAvM~Ue{(>_%@h4If% z@Z@>Zfu~4%9l(GCP~jxsc*c_Y5^eqvbm*JH`AS(Wa(M1Q{#(F7^Ukg;Z|)5E1eco4 z_jv8#_V@(H^?DU7;1dW`IGsY7VuV#3qkv?2@i+VE7M!uckXCOu0jAE_Vsm+zMnE3AAp;j{;()HJ5aCOAi2J@)iO7+ zro4T4MEbFIb^rMC3g@)&eC_)4qWvus78DLSy=Rl%7o-o^1R0NA8zEz;FvGeJ0EWpp z$FhPL%?ke^eUL`j7|5XP7***t@4_Udva|F82r z>AWdC_`iN3Tebb^vmvJGyXp;GKLz}3DDPC0ORdObupc&Cz68j%nr@&mi|WniQxUnI5&Epw1ej;I&DeND*?<43SW49PLL$^VbNw{VMc`}>8N zAtZ*7lv0rH6iF2WX%P%WO1cH4ySux)ySux)ySqb5<-JFD;MN_#c+NS`b-n+=%(~b5 z<|pD(dt-cFT)z++O3jL)c+V|e@nI1L1QnL$KBgJYd=aTtjgg~0dQHC3W4OF{T{>5> z*N36g1bMuKK%XNR1u87dx3(}%x5)5|uf-=%@y$wc$V#7^-VjT5HRZs-i)WA@VaLwc^MlM&|2U?xT2s~}vtHBrA zGCP7Ke<*hXu9Q1-4}S^16yKFQcv$~^hsf{OOaH5C_CGIozKSX1wb)gd`6DXUl>%bQ zwucsDC}qrw$Y_{UxT5xX^Q{mJx{!ubd*wD~3c4KndDfLWEXof%pT?ONt_5*fGIqZ{ zSVPKu6Kf+DaYq9s9ln+Ea~*=xY_O?qNnYLKrMZ&#p>5sLoGZvE9&D|fpA2A;>l9uy zS;;wgZzYyqZr_XN+@8p)ytbyRZ1G`ogY42_aJ9162-avaADu)d zN@%l#AuCW)Vu<8#okw9w5L~npW#D*YU-*P&$sYe`ZQhrMmV(?fKAvOR|FKORxwGgD z=TIP*#RH0f8?xcDA^Z_A%Z8E!=1YhiZGvhqwKKSq5S1oAuDp1mv_}znc_vLpD|S$j z8l~RiRj?%wg+j^k}?_Z zt>U>eQq99BGT;*K3DByy952(VyirSAHm@_;%QUSiSk;cp%%E+~XF_=Us3^aYyK>&G z9~?DaHDN{P5gtt?6*G}lFL*zdwcm6}Ow5#StKVf3@J7Bv4|6}5Ur{`X%aQvcPS_{!{y;F@0`a^SZ;@%K~P-yd=)YSDkG`5q(v0{+pT zXTV_Y!2+en0*s7k;`67i-n#wwS}>3fuD1txizmn?8LB3PFrwFceXn&Ppa%XIby`E5 z`$~jo8ipxM|IewS+oUjRZHiuXVUhs4Q)Q6YAH%g|&y@-1|9a7if8B-Y-x#s{O}H-I znS`aeu?9>y-z$J@V6P$2m*vSfxWJS;la49mF zPVMHT!h7sKKJ{y2pDmiVbLvNTc6cjJCkxwo(tWnA^iCRw@4mA|tx>)h3~!{1hrL`{ ztbd;Be`yB$PGVp914jzZU;krng!g$h6C?Bqq65lHVI5 z?qY$sIa=I`z!<}Gn7`1Ps;)S5F><_AOcksDh0siRZ{9ck7KiQm+4P;0TbEWUadUOn zf@iPg?LXNk$5{oGEaS+;m^^;Z2|<^x7bH z#dqi@p;>l*5y8o?Bl4xhCsaWkiBK=5nSlKwb@%yxsy4AZgoeQNKhCJK9IKBcl*Z(#}-ZLYylz4tC7w>k*B->N&lQDr_ zPFTL39ytuYoc@c03zq`1)vBUCovpV=0{l|jE}=~Gf``4Y)rWGb747(n$4+}XKP0|W zW;dx(EhN4(qDf}$Jbr&r*SJ=54)yMYW#`-CDHT|GhFN%*`O*ozYF*Rr?=dpsS1>YP zZLT9ddG2nY%E@smC=oKJ&QrNQBfdLR(HL{FY1xfdCEswl&9mFM`jU6CwUl#X z(Tr=C?Wp6~Gwbh$R4gzLVf;Zxe@whSOND=>)c3zkE$Y9Sc$e4ef*liBe9(R-gZ~nH z;QQUiH`5t8EAQ`3XQ+IU5vm^LNfJUZ0n?cI%f_{`2J!?Foj~zCq=`uwn&`2 zB%;jh>fI@Xt;lipdvnU^FQ2*Tnh&{Sk;~rV5U|`|p7Fs$e9!&~Ru8Ko@YZ{8WiFaI zfAvRCcVq_*mfQH&VniSnt388(wiWlPEI4*+Ev0VV2k|&BRwTxUqFGf_9W>7}jWODC zTOTh>r_Nr&H#T4Ewn`huQ>5y=BRyk-aL;gegsA6W$BTpIRG z<7|<@8uOIH(Vg#_~JyUyZP;4q$l|EvvMVQ zaowhI3tA_qd;lx)Wo?P%#TT{-FA~Ny!BEhXv$l|={G>WJ@{({l!72Rf>gZ*~>uM1+ zoa(7APS(ytCd|Tilrd$fAF1Mq?nwkio2e7XHusBwMgf-!0VatL{GH zFeSi1`SQC~=qrF_oaPFqi{TGK!~bJ%m4@>wfaNb|8j)zj0DuKh%$b>;n_pO50@Nki zvewEsHg|qkm*Cz09nKh&# z?(rWTpMgxzj$xrpdd)A4tdFCk?CkEmL)%|rTifhEIo;mdJ$61HffsGfRVcT0MDUP0 z%~rhcgtY%sd99n2*Uf=iZIH8vgwMXt<^l2>*-d4#D+ASvrm--I3M<>hU7gAEhOX#~6j=xcN{POpTSJ|v zT~dUhbpMw;z-<1NQSE;W+xrdaL9-H;>VKecr3nGZ89$Xbhc+R_^qQOhBLkSLK>fdI zLjI?K`hR1P{GUXf)cmsY+gX7HIIR(Xw57vO@BYq~ju{Q@n=PHP<*isZ`tNP&no$L5 z?d+kjxm3pN3gZogEV)iK3`-O3s-H~!zwmJqYQ-i@8-$=AC7yJuNPr?sF z^mxh*H%e|v;Cfh_n2wJ4+L~rt^Yrc41+yV45LIs+Je?-I-y>gUHMHD)QDqx(X>nPU zes}5;`TQ6z&i42-f})K8ahkltAX1y65%~66oCOx9F{w4-%}@n<9%E`ErwRr^kQ4AScIuaJRLbr z^kzD5TMCk`nhp6kh6sG<$xO4z#q0H_bJ%1Eg-6N-gZbTQM25w)5%Q^HJqnpMU7 zjG^Eo1llzy_~Tj6IAZh~3P0^qWOFG33$=QSkvZ?^8+9 zpWZNR6%1m2Zu6pFvb8geQ@e*e9;>xGirF+_&3uunFX*AU2QL9zx@4%RBR3BJkV}8s zO9sIxZc;k$%;)7Ud)%<}Qu!op9n6;4+t-R&#=yp#AVx?z7Y)6%(5S;So|!U7SYE(; z1!P+}I03HHJ(ng1+(?~Iin(x&KDQpIk%p@*!UQuZn^c)US?wi7dE4{p5$nc~)qttun9!U<_$>3N!sEF9v(gL|b(#EFSBN^+OJ&Ws3084>@Efs*ty5 z3pV+fmL}CBTo$V&HdVswD?-S2F*b=O$Ahs_wwFBj9M6uronkK$LWEMmR{J20xVM`) zYca@EXQ^{GH&NFdKVW`&b<2=#FF4+rXu$8C8>h5UwE3aG*`p`dDG?JqFbX*9VHiuU zkwI7q1jtNaJWLi*=nYTme5A$7=6$K)xDw$Wv#Kt63R=V^!9j@bs`!Hh${+gOeATY< z;+a-?ve%0M71cmaF=|Q_m5|p1;ZL2*SE3aC+GA`6RE1V8%_MJ3AV}=QNB9n7Bc?gq zZ?LR=u;kcSOZ595%l#+&yPwqPKYxMd|KbZApjD|pT|x1Fe6li;TT}4~Wv>qI_c6dO zn`$G*Q~LcT?AJQ`%>evwzlF#Yfd7%W(jT;uhw2=(Q>S|Qxz`p0m4+LeWb1Q<$O3x*8|4~O-OeguIM*Al@=si|Oew3zIhn2c!!@hOD`894%Z zE+wVaX<(Gf@+S7$^wy;M#^!FO_T;{V&aR#jnt`J6xS`P*+DS<9`1I@w#r)#H^6ECp z`g+6g&e4s%$*tpaypyGa3mAr@wk zd!kES^G_NKOIiNpk>OP@nE{(trd3tHr-dnb*El|`G?`;j@VKPk~v3?u0?SrBa0)O5O+201zLS=g~jg=wW(<(a5~RkSrq#T<2+4GB%?3EsMc| zjfB_1HpZOLbRUOqrE-lbvEG~L^33c=onV9~w9 z)rV5CoOxY_1_#I&pQL)tDcq?)AE+rKVko1~#Fe;?6x>gth_AR&V z3~2(WT#ev?;l6gm$_bj0>9(1XF-(-D$rbXs;i2_@@cY$0immO#(ft#$f6HT`L(dqF;mOK54C2F%+aWM;`!WnSR>GAM3alc96lf)r;7V^2E3Z? zc)4DA{Tb7qD1J$1x{g|~m~7`O?TP;-zR<6(UKtrb38*i0yoH9C#ymtV$awynnFfiA zTdd3Ne~2R+_rGy9x3R-Cz=VPjf2cISE}Rm&Hh#Ej|6!%chUWPzDcc4m!I$4KVuDkn=t)oWmN!%vIf5(zz}gt+{%S( z!K76oQH+12gi9nCq_H>L=!we2n8lp0-295*l2{F*xdoyYwU)4{;+LFn3uzQ}k)c6J z$q!{#%}CPhr(}s@Fh1~FK2-0=r8?Xq(psc$Onew#VTc@*)WrvzRKP29XX#}&N%_NQ zBwU=~e34EQ?zclp6EAeEE3A2FbGplo_{O`#Io_vK^Ix22!;R67*V{Ii@Og#hDV0;H zQ|gMA7hro}iwU`Pg%|ep#F0HM&Z1#o>rHuvG7`b{sC6{&jlUkw7X`0Tv7uG|0~`C@#n>LkB~kf(Esfb&Yl9nGH?t zkhYFSEEJTMl&d^lw$Z4o1Q8ESB3ysw<%M=BCg zhZMnR-e>2cNK6{N;g3)7y@Li-OOhoL)dmELwT4Y! z6-rvaG7@;5u2$r+Olv}qovg_6(DMqnnH^>nu)pE?f90eJV8PHRm6w%Yl%Ej=hExC( zsp|5Y`WjGaL|sE0q_w@ixuvVEv#$yrWn=_vtjA|yuwr^ zsoCt>o|xG4IBLIW`?zy<;~0x0Z=BN(bliSX>_^bx1SZ^}T@xW{dWwxNtfIKDROO8? zMI3QhM!nSJO|MFT#n9UjQ&@9 zGD@4e|BqTnKdy|xw&YmKQ zie;3MUqFy`FDJOLyaKzJxAa+FWkY&3q!d)w*pXk|>MYmUpH$q_J1`oPHQZZ2HshKy z`S#&-72_%+?CfTU(|z#PKIhU0ybpctm}uu{7nnQu=7IyCGB@#Q7-1|__T|psx8sGQ zmzB=DeS;K(Oq@s~Kk>R3{tCX}(Zl{kA#xHnAFJm5q)vPq(wwf7f|aUkq)+sU+6M(h z?bynXh-ep6E8{5KX^H)@G&_?e4CW#0>=`dHVAFQ0I*P&AOm9^6wuN8KJLNrX4OrHC zH4R&2nUS-t6=MIkOl_%$!Xi)JFWnRgej25isV2yNQINbV?4fUy48mQ&3zs#*5qsy2 zpcYrge5xdmC5Kmh{C%603-=X~i1)Uq;g?TDmL}VGvS$y!5L+G3jJ8MS;$K1CeSm=hk$}j6 zPw(}s_iW`aZA#={v?+hThtMU3vV~H}{!BhV2lShL38rOi!p-=^SX5vSk%o?zoZ^1P z99JLa5{3-K@{_w66ZI=6Z}h>xp>Ocy0q_G)KsL3bhnGe+c2*pQE~F5se2f>^+t1I} zKgc~W*dL5S>l#fM78DxilNgZf9f6X85+k3*n3|ODk&s`Unx2_miB(us6H*5$O)k%< zlFnsrXiDsk>kVt^Xp8O|t?LgiM;{t?8LOFy@2Z%YHJC443}0?tU3&ZoT>lcJrZ$ED~O6pn`VPV6|C#30FL5aObPt;#Lx3G%0RJgLXjk!@1p1X5|z1Mtje7-v~aCULLqk3_z zFZ#i=t%-IrMA4!82dD&Nw_oM~c4c%23{!0eiJ3km1b2EG1;td_{BAunA$npsDTqsp zUy}9FP|fGc4p1L>dt@NipBo{g;V^#zq&pmJ99IM8C)um$OBn=!MSem&x$77EI2T*)V0_2lO`0 z-dQ=ju-l2azjZWs_4QNJ;PaI5miG^jzzYrvXcn< znXj2vP*_rJP$pKvm7!PDqFh(kq}ba1qP+pq>C-bT(AO{+HZt{StYV^QdXZ%o2#W+L zOIyq%~(mEAdd7V>^3UD_>{mJN+o4x6N>m@KM*=ksrRFc|*`oCYaI|H4wE|H1a}N(LX}U<4)wOG`VEV ztS3TStOcr(9gibRG$P-JWYu_GXm9p~XVWfpPae=JNZU|!dC3&%HX}Hr-im>YjEn0B z1u|HJ&I*>g0*`m#qu&@k8we76FJLWwM|&VgL287mvZOH>!#BG`&O~2trmi~2m?-LG zy`))TcDkD9>|Ixn{UdckV&lV&f?VZm#8>J7Zy?DYzz_o;`V3kJB;VfbK3gNH5X zy4T)iq&wM=z4>tKt4dqamQNAU!5AHM_B2$a^2)S39Z;S~$>H5&*kp+8ea0d#N0tas z-#wy}df`yYZF+6T@P&=c01l(Pt-X$;iYDkhpN>+NolYFMo+?2wKq6eiOd6o72#f&vtX5|eX?^~4GnmYTXx)p&EPy^wj#SsjVfs@zFO3-{$SIcBW_0YE& z*R6Vc=kXPEEr8P?v$fX-PQ%&F4aGaa+Skl8Fib5N5Y&zlHV*Ogk4+YdbWlmjjtZwe8kgMwG)v8a|?*l}Y4Bk&nqEF7epKc$^ z@}FHB8)z$CVCN|VJFvixC34nUMhbkLqm*(0QN|rZB zC&Q;%L7RZykRpE$cJ{g3`R9xEW3W=)-FgLLM?~H0*aZ?KB-b#AdHtyO9r%%uu*9FQ zFvC41y>3Dy4#CG9srR{kuZLR5U*&Po(Tfg6t^w6%9@KX|e)x_lVs6~a`w(Fx^_~O* zpWAZ64`~KdZ$&+fjtI&a4tiZ^;g@ktJDT&N*1;K=3=9I^8yRw)z>?ML%RxQ-*vH{} zULS&&iDgQ2$(>$)&LBkKgq2CVN(+R>vqc!DAMW%ZNt8xL3d+~SRYd)J;xhRqaYf+( zi7Rn9OD1B~8L zc#^xSN_qJQ5c#|f3=P8xejXkj8mV>zEfFmyMJG-GjHQX0l$@IXE?pM$Lrzjb#p@!$ zlI+~d2GMH1tlav>j)%<#t!;^&1NXbR{L1=D1}9a_Td?~2vFMhTV5ioEW_U8!CpGr= z_ir(5a&M27@5CH@)*%0AIA`gnt3YM@1qMNdWG=Sem2`k!Wep?Y2^uCIN0o8@qO%uB z_HN06;6Ou@H-(fuXZ!PH;Se&p5GNWb%I*lJJFlA7ud9i~U|6@nX-TBVK_mysoi-agD7(+R0qoPa~w*1V1z`3^1a zq$I_@mz>oK?ftFog1gbTXD^sEwaf%fENrc9-9^nHPP#5OZXSX6y?nI&ECYg~7(+r- zqZ1OTV;$p@(lb~b<1%y8Q=HTCiaiQ^i%Keu%EBtD>XmBb!y8(qn`B$sy2UzPboC56 zIOhzFJ?xVl7>8mO84c?wRNgHwY~ZA=t}oHAZXVv>+532UwtnMSp7rfOy~L*IhmKcG<1N-xoK1l{Ame6LIU456~sGIK-MH<6VCp1$roRfYv!dB z(7Ptb(ydo&u~TLR7dyEdqDI`ix_e<~XlwsXe2)dy3l-bj&)?7E7j08UpU4=&=-34Q z_{0>h-`Q0@{&>E1GW1UFv>3}xyw1T9We=WQ!{=tBIU*MA)InZU zqbtI7@g!;g`X?^Y#^8`!Bl#LQ0QDGVM1+M;g=0)i4}v;Edbr!@JwQudt?5(N`+E`to^T=3t~jhR|>FG5=?wrAqZ@c;)7!ptc3{U`mFBm8;&h_WGtGlj`-F3LRx>AjV4d~N; z-_=)D2DJTAqWI=rj8mWhvbT0{cCfq;hCl@aeLQ>veBJK(2ZljH!vli(BBT7`17mpO z5w+qsz;IrI>eb(7+(` zXu_~p)&$$s$jofRJkz4rhUeVcv>bj}Zi^Ls#kAL!#WKSoqkVOO{R((4;=qsw@bLOZ*xX3`z%5g&_w2w*+0Nbu)6vS+0^3x~-N?tl8Qo7m$l5tXD_kecUOiF` z3k^*wPBld(AxSdLAtoL(F*!H2C_O*ZtR$y0qp&g?Qj=9_*qoqPUmwuX8eP|8(_P(L z(it!&iUMHTCrxJN=S{>Grm##`rsp;mmnOUzwr6&kS40kvSg+L6`Y^O043NMduM_ZB zJ$kO{Pxdfa{0A_;S15oaE3b_YH)1;zyPdGA`!fflD%(dB zN?b<*r$@odD_{^h^6C~Cc6)CRc2RGE7Z~Y4Fj3FHK)_#+u&M3jBPB19Z{7%FB58Dm zN1Zt{owI-Bf_DpZ3YI~*mEy}KfnXn^-%_0$nq-D(yZW;5ZARq^xCN$Zm;ih+jv-0| zpIU!TW6Gs*HlG@Ekmw3Ft(`{y-Sbl#oQ>S|)>IvWd(xc28{!7i{Y#l;M@gf(jSUg? zR0p8J!qbS6grpKkjSUWIwZjfx-n)>2RC74rOQ zsgF9O7gZa>OZ}E1cyY>l@zv6dpU(_7=)Lp;W-KFQAgQ_Uw^XZz5O${O9Bogd>)&K% ze$Z_sVYEUxygrdOY%??EbF>63R}DCb%T2ha@+~iG_#{maEE*gI?mw;8{y5j|>1x}` zr**!Zo7<}J?2FA8oiTMHI6MBUZKX8~6$ln2^plGr+4=2aKvE2$`f}>*&~iba^UbLn z&{hhu-t+1DMXMKw9guhAn!GCSDCb>jmE$qEYv#+>yDRn4#@@`%!TG(D3v`w(=?0Vw zP(+!PZ%DXc7&lr(EM^o}Ok6}l@?U`drNGc~p$)dZs|&W#3<7}uhljx<WPqa5C_eQ|)?xUTYo}J-d;9Vr$IQonwC@}|XN4irlVfSd}j_c4` zu_Y{v>=R8)s*>`y2eQpx1SPX_M~K%|+SrMNxY^AQL_30xWjxHeSW`rq*zZqNwNt3K zNAu>N$|A9+1;-yq6Et&Su1K;9&eK>&P-Il3zu<>EeTPF_nI%`@bAeo<^TruR@+eR- zDSHz8{bC1$76+n?)iv}D9?nsr*;=DbQEp%jcG2{s}!D-R{r^?gfL0GMfc-P9j`XT`gBuGy=O?@U zx2@~H2Y28R+>z|{-`r%^`2^` zyRvk5Hje=DJxo>E{vs*bmRcU#-GkLDw(pHHa$!90b{(Uy;qKy9eJsrD4z-U8_;dz< z13P1%{SFR9w5-28ULC$v0-ZlmR7$&JqNs?3DNQ1a#*L`xgaj6N=WHu?s;Gk}E*S56 z-GMsZjy!}D=|d-co-91!jPn8Yf^ zp5g@v-3+()=MuOgySyC2ia56%s_25h0;3f2W(7u(B@U`FJDvig*Mgr4quHUE8lgX< zNfmvmQAR>&v4fu$1s;=7=CM&qYl-{7x}g@2?4!}^>Ms+QfbUZiP7~=T$*t)YT#~;Y zVeT_QlNRf9x=N6^Fis1bDlCJZoXI$$l^)q5v&maT8_|+krk0VJdvIithF1sHPRsg? zVJT2pP|8@jd9O#wBD26>Jo8zx>I3bJqNy3Iof|VN$UFIaUUUNG4Kaj%74Pyk*YegP z0yV1NwslfhpH6MM)Hvc!kn(FxXk`?@zJ=G116y`1vk7|`ym!UY4r8bie@T>3iyOC+ z_X@XiPEQ8YP_*9uR_IH^1Y%1sT377F%#c`Q0u6%>qkgYLS?*e$*S%dM@I@ttsNVaH zzsimnL0IowOAUQEqrM~Y;?Y{Urjag91FBwkl!u?2PDLjB!Upw;c?kN${SeUO9%lC`(hg=ygMdH7u3euk zkK>R$$4<`~mE#fd()CsIh%~xY&N5|C^JKw?+F>!vld!3({*M*abbZu{I=W{y$ChT1 zbM@AXUv#&8^yk}y#^0z#l^1@~iWaLV`nR;AEpBv;@Vx8osjfWPoon=j!Zgng*Ph-N z@4cx31^IsWj%zP3VGyXlD(-5`eFuaJL!_oyBO$$xEotB6{76Nk!G(we+~Ml(Z06{S z8*vKjL6R{B>q$|;3G21lPTlNAGobYUxL$&a94|z6}DS))^|8li+Zpf zFrFMMv*8}fRbPtm^`jrf=XYnbl-&wGHZ24vP-zG*9jf zny91-YOVNmOs$PnA)1Vh%)}OgbjM8aM236$Z7sT#qJnen)cTE$P#MyXTIt!fS?gJs z7$Nvr*)kJecVyqoVFbS%ukAmKJB4qC1CwbR7@L6k%02^Vfx&sV9M)xjPX zbQ0#q8|Oa1Q8W*SJ^54y066aPbGm5&=S69q&!TVMt@o@J81DG+O643?*)SEnKC`p8 zvr*Inc3&z^tS-Rr>$#_gtfdN4g+&m`?)0IY(Y8VnpfU=m~8TckdnhBxa35)GP zmRa6BiWlLfH+}i8GD;8~(}=8DJ-9KP&Nbvy9h*i^;PVTH&u@0uT5@p;?`2mAZZ#Fk zjh0jsx@k^VzQ^jBes!w282uJ+*ZUKbK}q*#fznTw=6f@}qvEU8Je3pMk(IAqdx$Q~ zwwIgfsBGmvpYN_~Th@wRx;dTT@d6l03m`O{AGe0+qM#q2#M;A9p1!fuoMypt_(VfJ z@30#DQcfKCAt$M$j@+1(H9e;WrW>u>DTzBxm^6t8bsFL|Plk_k*S#pq1mV4@#!kUL zcRDzg=uYOXU8mn%*xdo`OdD$rb#Y0SrF~9mMuyzp(yyiKLLorbU(VwFgyQh~u%E=0-41`4o6%>_} zw>+q+g0zRBH)58QwhnT4WsUfO3d5R;hh{m)5<4KMm{WbtbDL}n*-MaczryvItrMo5 zpq-?Y!|8!NB+>X>%qlZ&&7$qiPGxt@!0&x@S?(KrKOk$_q{x}*%|Up z(XzaG0b}%UjLcR)GLbKe?+X?>`smqe(tzZY6m@^n`^tyXhj{?h5KsW!qJF#3Xd=^9 z)Abx3nd-ee#ott|D7SiV#C+9Uj-P!-$q(J079}3BFbo2r!uX}aXpWiaj7@z#fZQL6 zrkgLZ5@)JrS+B5pRtu|cW$&PBBWCC5<}T%o>k0tq9-FcT0RTEKmaxdEXCl%-s34Pm z4}^*r_~t)_Q~y(sD;2c$t?h4weL}IL_KzpOg^Hw*_av@Y5G;DY|HcG8`0;{{-}z;8 z=oKG82HhN137MXPP%E>(aa5i)%a~ zmaEO91TYpHUoV+keKntXgW~#ia|kHky11hRy9b2%1cii0dqxJwBsj-~CZ<{>r)3&v zWaX;nk+(bY@e(>F+wV`rW+G(k3sK0Z0e zcnu7lf3Ls-^Y4wV-KCwqE!cU<=^0E^$X6IS927=QQt$W)a+{pGPCiI41^4C)>it{I z9-kSNfW1rPBl6QrN}VE3R>gKNDlCgng5*g~K}7Ggnm7xUo`#6X-t%i`Qx$W+Ye4y2 zD)C`&;C(#GCpTVbTu;!ZCSoWzO6Up}w_J?}dHYz>TN_Jzme3Ydi#-+0EYawyP}YsrmM_^UO8Qif#oPgv zB`lluUZ(jWa%qg`4iQ7B@w-7TiA;oT0u2q98ETx+s&_rMG{~_Q>S13;3Uw{(Sig0!`y+gJ3PiNG9)(9B0e}N%`hc8JzF6& zCtp6Vp!hWq$O3{ADr&^aY8xKaH@4hsZtb|+-r2+4-8(?nKR7}@JPH-JAOl0iEf!&y zR##zXN+8g;vIpKjI&#@8I6mJwyf}BslAdo|+Eu8x0AmE>b8f`(x$eUlDxD%F@Oti& ze@qa>P_DGOIf`ZYczIu02;ufq4tgX^W#Ql$@sgrbOtn@&*6ZV5QRLU@@ zMPi9|v8|cepZEDyahOPD_|YV$GA72zjJ{YOPNXkJo^laL9epCL=|QaVszEYU@e$)3 zdq@^>sTh2+GqvIEni7;l@Wdu_{2Z^VE$zqWA0df%{mAZyOx?*#XyT{5=5pAcAB$|X ziP->fTcvtpcyTD zOr%tf%d|f#O6avT_2HX7?!6Kppm7lu#1F)WgT8j5=|9HBx7DLV-%6;=_c$VzU&UF) z_#i9LrJ#g_WQiBhUD0bJXKB^W>4#|VdjQ>)&!@t)**#A6e2o0=gQ|PBq1%^sTGo2@ z&Mr@kNgZ7QREZFaKY%I$y#HLK@Bm;jjcm-Hc>n!;7sKw<(|@yX0BTM(Ff?8_In}AE z>o*IH4}aEOT`i%omvu=Wx%v=Huv}deemjP*Ve)6`;om-n(-sD$$mLVs8OFhjOD!uS zJ11vpXp;$?fsg0cxu1&^UT}B>jcnxKdvslq>=*%B?J#aj{$aUa&ls7c4%g9 zYCs+G^%%gLJ3HIE2dn#syUR)+50B3`K7C&M0#dPK>Uv;uZ4e2rEKh--83{)q>8?Nj zBWv{97e&(h34FeX=QmZo3a%&d2JT8!U~wggMhcJ#1#Jm_xZTMe*7n$Q{oTsrU_@Oo z&AcR4@AZ3R;N#c(YHkTSJ}!b0`st73dG0^hCdYvrc6S#@HQNf_E56KqM^A6cSL&Iik?1S zx|^@?R`N;&oC97(+}Evf%de{t0CTO%!!#@zflq_vlof&Sa_m9H>68(6+Z!rB9c5Uyj((ta!O;O~Q!f#9A!koi%jo*!Tm zj0H?b;4c@JL=pny6d4)sxIvS?Adti{2w^pb+ z4JLAMOzgXGwFFZfzqqt?o+Ozp*+_IyMqv?4js$<(wDU_svDa~>K)1}{IB^p z_w)d0qL)~yBxobO6W0CxH+1o6{l>>9R}`iP8}e?UjO`Blt{y&H-+*A!k}NEBA6?$t zO7Els%k!GUU~OP*0!VD zXrz$>YFJuSb;C@2HO~yn&-uZ0zPTcIt*7UPvqBIs1yFHdLb8Y7*_w}hu6!~Au0A=< zF(yo4z$%jm@7|D|*OPDBz>ZacARD5zb5lR6E?}#}FOKArIv^Tnd4uD}<`$EOu(n=p z{gO)Q^LR1**t=#MI_-H6nDj9H!WxjwNjaTHAk|9u6xS0vvs-=qavXOdvm?cCSgPdC z=9*_CU2Rjm{LjW%>vEZ1B^O<+cP?he_HJU|nOvS;lc@TZf|BbV?(-8GOtQeW2)oXG)3&Hz`#h9TpOJHU(Xk#R1onA$-APH{*-ar4SshNAhe47#tx2SGL&nQm4XW!` zS&qJdo6q470AOI}n9ksNbrJW?PU|~uaHySDG*Zr3)+?Sdi)zOVvo7k$UX3D>ZZ(va zJxxnJ`N7rQvKjN%lgang)Rs;HwtB9bU>axdC+=E)>Yfe`KB2q;#u2JP!CqnU98nOH zh?wAn4ECgyfV7az0;cTje8<9ay5gu9%(9AlvZ_=EG_<;gj+;%nEp2g~0|ecEHR$bw z6F9@}qvMnF)2_4q^9$7_Wpk^8i?(^&2k5)j`-iK?rYEP9=SH8-k%$EMoRb}6B`HK- z+P~wszm`uCRFdpqq`_DXO@oQ97VLTk=~|q6KRDqebkO zR1E+U^ohJ!oeogbm)a;4T6C{CJ1&%1-Fr4D<^Topqo3Q^!J0ZLYB=BiiU#zCq5;8f z!6X_6A@~7No_+u>9h)|ZE}v{cHc3fvuv&o4t|@L^rdjIR+G~D z(3xoS%T1S@y8#n<$k(%KZ6Ay8NQjhRyq1$IwV-~50y|k^rc7Vwp^BGTWp{UM0cCM} zwvO}amPrA~6l5UDU%!PBr}jzF=ihLsz_(bTG{uMFi*~IpI|vC{oGG3K`cPps!?ftcl74Mo^FXANl}{@YOjjpua+&&$qUBu(UOFbam5lcK7m@ z6J`IUehRzwia0zvhC?Ct=ibRbub=*W1SROQ)`5?wTHEjY)~Zx^r5}=aqe$yfZkh*BJ@>!AD2U;)r6H6`7C4b*H;DJb4;33uLqE9Q zF(X9_A(?w9-3}HTLT`8eGGvTYm&R`SNfAE`GBWOsu)JUmS?Tvw%zP>Ur76uR%NmPE*At<9T9;U~SaKCjzoJ8R=W)eL{A7L=JU zAEM7guJbm@T~{xfP;GwDo&QS?j#ZdCk~PZc^k>BfF#Y>WxJ^45Aoy0b_?XYbveHL; zukr624ZSqB%-tj`X3Al!`IK`+I{A$K5*XjRl05F>1jFG<&%H)4Z1r+DBR7k4#O)%% z<7wwSRdmouiubZ}zY+Ej!>$R0AS;L=ElNP@Qrr&5mUJq1rRp4-3Um51|h`X#nrYECd=2r|;3N`+ZsdLJveOGM+Y69ozH)~*!wbY4tlYo7sqCgfb|ixE)TG&LBIAOiu3t98W4n4 zYpTtkti^}qlE>z@(!O$AAVf3)j;mnqK`&{9b5#3Y z4Nh7aB&K9Xt}|9w5rUo_SGwg@!GC}+yc6YS0BeE_N0&l}jkRcwfI$~6+O9_Fa*YyB zL&8W;y*Kn8M;#UEp>R*|^VbgLb#@v9B<~bLrqx$Bkgl;`;~%<0R>*1#@=$q!c?xv#)2lvW3VrjJ^rE)AIN(BJ9oW~C8JHxnJvsnlrU>i+D|xmRY?Ju*_MmkMCu`*&a3+L>d% zvvzf3bTIWac0zY?4+tdp)(O!B_;*p!YIbkJH2eTUU}`c>WK32}f?Td{T482(Np^mG z+-p>Hl+wC-qH>eUmjJ}EqqFICcWX`OKz*-$OCOLtb4Eu-+a~9uhP9^WZWk|Xa4ZeC zjr(pM+}U2K*~3eBKK!&by*#^P%n6?!%a4ByW~@^O4cEIeVG>y0^&@HWq$S@;aLZ3@ zg{*truy88ddkw@MDaNYQf@MU9bxJp)cI6QCK!y)FL+J;}G#C)|fi0{{{%0N zB2D;s{a4)4!a}savy%W&6fk`Jilh5pz=ZL6CDcXr0+;sxEAK1(vdq7238h161*97k zq!EymmXvOkQbJO?ySuv^q!Ezr?(Pl&K_wLK^MX3);EeM-b3W(Xd;fzMzWdp+_S$QG zHIo6r$3{=oKfuR$QC7bDZ^H~OW5cRo#^8+LJl~$@@^&I>QB;4kYQXzqwB9M|sI9{? zI;S}*iD-gB;k`};2}tS`w$?@YsRErgR+O8GT_5OXHvl92y7J6^6=3sr+dgQJ%oxem z8laxyKwjv}!23f$B11t00(8UZm}m$DkneMHd4zJip?*0o|avV@H*KTyg0Y8 zx<dl?-U}+u;awy65&++Djaf8>-O@_ zF2-ufDg-ig`u6DF=f(ZveQ&RU(E{~K#a@~2Mn?TnJeM0q1ft|ywuT-=*coI|j5 z<5_=(hCiujM`0FjrhL8N_R3!JK#oGA)VOz#R@)Q3rtCbP@OXi6-TM5v2dOl5q0l3C zY3FKv_VP!!*jXUw8(p^BzH}Zo;WP!p!-tF3dtfs7(Wkt^8P9T~_h$6DbLHYPrn$^? z^MZg-=K^Sjfd~j~AyjHT)s_1I0fBy>x~A&FtI$7;4Om=ec&KgL0gFqh&Xk=~=ug(3 zmuar5K$~_SobRglpLzYYO*5Nj1M%s43vxW*GBxK({ZouU1QZ@2Ntn=?&_19wz!mf1 zlYH;I9o@U8v-`j|*?+mj_OVAES)&b*%^!S_k|xu#2lRyqxIrez+2Eb@}*|~`|6yn}^%Inm$n5b?%q$HL%AU8tv`cn8QZW`RzbCM31Ce|SqabG+P@(EnM?@U~LE`tU%F{wKr!YSZC-noY}uxthl(7$am} z4fBnzm?1v<@hcVPK^ymh;=QT#5%9}L#VKsJy97rZJOGMCw@Hgk<)zGj10C&CZ$F0#SW z+NvgF7^t@Au_e$&ngc-m+uH=RP}e{-2Ba3V_MvZdq(J<@pIqR*Y<&X)?GS@P!%X2W z^jv-qVTwX%X>CD4=xA?Bg74`c;02;#)WRqfet2v~a%y%#cz$t(e|dF-ZGH0{BY-fG zPw#&u`Eap-SUQ8yY$KCUuXa8|GRbVoOXBr_aiN&1+fCwkzG*Io<0(1R;)}1qd*|rT zE43{MSG>wpU22&noI)kug<}6scl5sDf^CNBYE?X^P8k9vBDv(tM*-F%*=Ca%>0%k& ze)_`Len~PUEnUJ0RB~#nrmkPubg2Q-^Yy6GA|`|QOR%O9m@jbW{Ktr7?%Dn3(*&74 zr1k~*i*ueFevi7ArDch7@vKf=0-qY=dNptr$#>IFVwPTChBbN&4V`ToiNxR7LR8zm zH#GlKhU!j-akvc&G$Gzvg}o7*51GMpCsj&#TP^b!UQ+4~9sxG)81ODiVUj@E3yz74 z3zYXkh>(PEw@S?N2u)6X6cv+gotKy4|GGlR-XYf~pT96W*tn!NCbP1g)gGnB>n%@x zhi7f+;HXG!AI~J$z?f)r@7$8`w1v;?GW&wL<>oG?9LB1**T&x6?dOQ#Xs1VW1Ti-f z>x<2zAr{62o;f+eL83qArQhW$w?^0%8j>;)c?%15M$Q;rzBh4Km4p<5Ru^`@Fc=3p zoQ;+nyz{|LjSe=}9WSu!j6xbinfnmDcz7hPpPg4_`{T$+%=7}K8ia{>Q8_v4CBVdB z;UMPCs?cR*vIJ^5VLH2?DWEQ7N>zB9FDYeq_0>Wgs%O=(@$C#8-x><03AQANvzya* zns820t`+@^k1G*IjmXR|8r7?*D|7-CIHgd4-GD+}b&{%Qq9@oh!a^Kr)x9}cVY+$H zG+8<_Qsd&Fi7Ucoa7BhV|{zACxDh z84}E1)R>|!_Rfm+#@ZZ?Je^HgvsXE_;@vxv1Ak1`9SN;$3?VC^?rdzDj8y zUP*>)j-oBEXo2=F8L(;gm(lPfh9iIEW)+s1Y)Fx6P>6sDU;K(lwQePL}$hvEeXtrDkE28@!(M z)C8P8t(U*j<%S9|nq2o_z9&|msB&rHV4W|1_pmvRY>`x3h$K_;?W|3rj)+Gx@tR(+ z>D@&4AM{t76|V-y5{sxF2n|8?i9VpI>VkwH$?@P%AuW{+u9wb~EJj&MLnoGn7h8A5 zeejWDFkkmxsA-kYi_B6(E4yY|W&=gRH9)OwASHh~-^OT;X5rI4$=b(o*zfezi!PkN zeR=4XJMUAU4fs|T>lk{{V0{)nzP>t;$>I9AyQ*|^v{0+_owaq@=EN1{-KK0lI@ZE; zBqu?)Uu;Pir`*Tr8wUjT6%1=l*)+D6s5rdAENmbNaXPTbz^0Wk<*DKG+u3^xinHaj=m zKe&Vr-G_z%T-^Zq`;_O!RXf4#EDQ2#%tqTMzzK0> zzMHBy$E4^%?bDlrv%hgh?<7OG2hNWU#iXCxy2srfsDmX;A+$FO5k|$#grl&K#A`>( z+>i6hMYSdNqeaW^k+imi2=AsJoH|+-H_v0Gr`^X4$#qUU*^14cVXK~b+HZKgv!%g1 zi=G}Ce`%A+3n<|mD=R+4xC`lTvgZtTte!u8+u3bR#lvJyGS%^f_#@ZYu7;4$@VMF5 zCnE){Ffui!c{(9&C{)%HKX#%6UBYCYr}5E+rXsiV)zmt0WIv2SO_-Hac2mUFJD29c z!Q8Fhl(Vo6DNt5VJeptKxGinVUQqv#$srHAxkr89!gYwEu2?|%Gu;+Hqsgbo^V)CJ z-vQ&8+H8XeLT6}t+Y<-3<`y;Tj*`^@=z6f?Ij2E0zQpT96fjBV;X-|_u9&K?;5=|Q zRzqoV6tOfVh?pXsyvV{AB{XicRe<}@^aRV2oz$%b`+|Lx)4IoS8kyk4<9~Vmqy|J9 zFF5-Zk*3)74F**ezL?}dwDX@YqH14^0IlM=KkZ=%im#Oq5NXN}O!*g-;o*a=OLwVHL!oz2v6T;}~RwF%)-t47+`ijeCE zX5}3h2ps$7`iJnQP{t-W;UQN0U&B{h-zoaY{@#2YXZ)RSpLgp$Bo0RzxX193&k}i9 zpl=FW9k$FqG#neDs}6F3axg;EiGqHMA z4Y&z>0q~5cNpDVcuJcMk4JKCUi@y z;g)cn&#U)SRcI_J((J4z&&tNks7{+Tp2RonF8b-t>Eb&*1m=$K*HcMgp#V#X z`g?fw&i?@vSVLWwtz_%GD!jfXGF41KJ!+mN#(YWO7-WBJeD4*#c<S3_^_ILSzHKR|IxtDjiux;v9U z5*EL_x-vz)kv5VH`EG1?Z@s19=!lqMl38>H#yY!Srkx>M>l%S$rtj~q2IdFOf6huP{nnb;sC>QT%KjbM8lgmhz%h(i z1-v(aBLb}nfIM7z`hcqD_Cq@1PzZ~RipGinw%Jnfafzvde|g0MXh*gXd$e}^pdE>c zbZJ`&qN31)+nz^mrBF`D!TKMOd;XVXkZ7S^!0S6U_u;qSpCh8dn7IfM7l*Nx`s0eIa7-+|B7)63S~+t1%f3@bR`ViC(EhY}s1zz?h# z{w+lG8*S_0!$;sA=R0i+NAPdR-^9-`sKLJbtV9_RiwJwDcEorLQtfx|r} zB9*j%6c8_z4Z8blh#bk5l%SNkD_fx7o*f1^Dgwb`zkT}|^*D)k?~LRo35^nw;Veej zH%}yk6%(W2OLLSs@c)+pcle$;%-6d|7v;~J+^-PhXN!aK_OC4vYM$2MwTqiTDR=xp zQ&0;eye8%iDone4&zAstNXc!1kCCIm)T-(_vVK^7XR>w&paOB)838SjCyDDLFCcTE z_}l>)whk80LI8$s95A&iL;{Gk%+vJWGC}$EdgCX0$fED3aXxcqtmxxA%f$^wZ60*u zU{HKZ0f}fX1WfI`$O{!~ zQ`<9@CUprRlJ!34bdZIoG`roO-0x3lmu~ipyUVK~#tX~OG;GtIj9Pn0c!1xy%jW2a z_zhxIBKF78y}v9Has9SdAnVQ5oqj>G`oc zR}>N|XhE2)Rb)c~S`dQ1AX(DE*Ui8e^mn=Vihnzhi~sny|F(_L=Kdy4zz}t{>h_UgQ2ncl$Tx=;wcd6Fe$>R9K99RCH{jLVQG0noLA|dbVUr zYEFSjUSTnRen~kmz(IWga8Q{64(hka6Keo2ctB1{Aad1DW?A2o$Yfr^Zrb~vgTo`$ zkH?9hzr<`!L$B6nR*751>D@6brW;f3#Tge#T(~6j&ouofZVUzX?b)T5y)z93VME=*Jts;@ zCOhIlNgM@dXM-lxvOvkh-s%7m=PB*{9e3nU5VOycX;Vo=Y7JceTQktmu7v z;#C}xegMLGU@oT&F|d2!a^Ox^J>1&jj}P~so=KQ)C#rZ3W4%@&QtRoArSK*CUXwNJc#L6FaN*pzIE&0vY_)z)z~B4ilEf#_7}sp zFc>e>8*?_thBS;VH(gx#B0TD&Qeu8~_ek^O)?A&H(}9F^#h&{cf4f9KKp=d%Gm`!n z{$x*}^R=X9@ZXeegCNck7#rZe^{Vv}uwMAKUi#@S?%clMOUg{b<*yTT{p1M9Cj!?` z#(%zkda+rCUMj!;{3~cs2=@bMp!=AqvP&Oy{j@!k$pgAokEoYd90N^tEDWFk5Yp`+ zvIC|%RjVfeXVqQInddn`-Sxlg#pna-jd6qYf&EfUl#MN*=i`tN0%!sorYB{CRIV?> zQ~#zVF)F3DzURNq8uN-7pJtG@uG)m7d&&Ny&HN;Bj?r`2!kUn)sx^+x9p z(IUC>uPeIT`E540B#y>lP zuQ?eSLtyAaI6)~osyoBq9#c2#sM*CgyIDm$Z;D=KoMd|Ib)kkSZvHNTDM2>vf(c2w zF`)@Xa^b>Dn)qEpW4Z=8BD>S>3RQnt)jF*JR=m770JOD8e6j%hiD)yqA{fR^XS?co~Bw$uoNw3q5!)fD= zaO=RmCtbP#%TKXkVIWJvLDr6&X$v|}Y%*PCl4)Zy(QY-J#`fcj>1GwkR^`}(_nqBg zIsX19mCrU>t)9>B%D9GCvCZ@-TO zK(a{4UIN|$zMlR8etwTa!-69sJ%Zw5V&i=hBa=gt!uez4qEkcT1#^7zvU3VEyo0LT zZfA;?VO$zCSimO11i{RKADsH_2N!Gt-(s)8A9@!*O-Fyo_x!l6_}y>uF+8xXKnWHL zi9ik$jR=Vf3Xe^Q7D-A@h)E00NX?25Oias1$t=prEiEWa$_F%0h2IoZ`eT(!a zv|v+!GTnI{+ij=7yv&pNPGe%&KBu!@beX9%{%u+>fkm26M{4tX;D%Bj z+yp(}l+5I`=&Zc(oQ(Ycfh1D-Z#6Q%pfO#YM1G(#U0KHfS4*IdeO;u*i+ycmX1a@R z>~t|-gHE_CS5FJHrM_4D){s}`ZXK5xPYE09f9*;*#urGak-X|IY;z^N19e0D{rk^X z83uzJXh(od?Pct-vvC11wgtKpc6pFogZpjg?+1q<1)aYd(*NtPX^eDmj@YRnot~W? z!rIOS;Bz@cqC$zb70z=yLX(UYukPYDxuLJBPz!=R{QW1qBK7r;jIQKZ}uIVZ9Xz@y4ieSjEB(r}>O8d87^CK*g6w3Hr>1WRG zrqvn_q4Kp6_Ly2c@R&nv+jf>8I6rco5l`bz8A=iS6v+W7d``#Nj@~+LKYXv)lQL>( zcWk}4UH?}6y&Y%h@yGdy>Ugz>d#OZNQ@xC<)q9^s!kW*_HK`7-LXLK!M@PaM270bVR1>19!>yIC$|4|W<_Cx87B`C=5Hw?)-)X+x1cd6B@z-A!g1nxUHvwK8XZNgBKn*mF zGrBdpB2Pz{6g+|9{hWh}D%5w28F3B00BB>A3v+@hLb8MmtOUoEuN0yXV z*N|7{)iyK|)V*oCK*TOXGe4Sm1Gt1q>tz$~e*i9@bGN^P%fGhM4O^|N?=#^K2&O*= zm#-3)y9{p1l2NGCPcT{A2)!e&O4z#JfGuZ4P`mwE_Wd>H!np^I$U7v;a(ikmcDSGB zsm5`S(g*GQKof1w@ zQ4T+RnuUS^CuO|M#0Je)EP&$R)yfjovXVWh|>dkbJ3G11Jv38{HnjMNqP_xB#+sn4nt98#Nrcf`HHoz6U1#kub z61akY0U(e%00OBAAdt%W4NYyb)UEB^5}iH$a!6eRBZ8d(O=pU$Z)kd6czkkUg?R!A z9$<2;?mT?A4Uc@V`-x-g5YP}(-9IMoD_$*_gK>O^K*`_~m{{iuPo%9&UbNuhzP+I^ zB@eE}1rX~utxBNjo;C#$<3`JPzMmKNqT#P)XB}7;4QG5d^AiI33=3bS081|y?uG403{VI@Tp%Ul@~d(q5Exy7dZHiX-L9lz@|mMk1&NBgxJ9c z%T@rZfZPMcEHyxb!qBn?kgK`FEUgX5)x0ec2jps;S?$&I01XQ7J8ldfz>%?wpKfq? zgiR>DPGnrXR&)T6R3wsO(|&uIR_HJ=Y?VAR{$gxm8YIB{D@(uMUuOPgz1g7|tHdX} z7tdk00YPa--kV(Jc!ytDWc_ivSR7B>GQ-+X4rz|2ABp*9PQI#=6Jn<@#dv{8Z@8FJ zb|0ys{>{o7RJj3VeRK3_w;0SmRT;bMUl6NxY3KRek;UKd%hGAKyu#fdr?M)FYYBsl z8gF7P*0GHMcc`_n`bSDuN3i`p03o;sj_raF{>QY;nKt}>?Xux$zyKRSd*9hKvaomX zI6XB0Q)hR)g&;V09qP^@mowaNPRsDit%TMH8<%NApn!S?-U14!s}R6W*`fE}1Ip&d zfa>@jP*fKI)%8O_ab5(}>_tF5_!?077XjsU9#D=K0i}N)Q1ZVYP@+f!eM3G-!(+~) z<5Sj?)Bj39o&0r`YDaA?kFU=Ea;@q)dB5_bfEnTJ5{$w09~+ntT1jHbRY=Fy0$YTy z9l8j4uw`lR$}*>FKR`0&D{~m{_@^n!8j;o-d>H|MAyLMOA&g0?n@5jU6E!zHmUvq;9 zI7U3**U*3KTKfMc9)4Q1-JvKE3LOx&k50B0_E^Www#_}Qha2{n$+szCyRJmG@#M8> z(_{WOkEkcJwOeaR7A*{8t1LQ&$D5c7)QnU|PjOMr|8x-aZIbpC2mh~0xN8bZydAV z9sXnKb*glxxEALLnd~S25(N#K*&iqd^7AX4#XjtBj>+=(<_m+$h@?I$P)3*srXHS` z5oS;s`EqOp&qAB<)_oZ%Jx0E7rp5CPuSIp_&Jt_zJv?{Fl){zX^{qK@nlXfbDv0>u zmH%UvfrE`PI=PNN%E-AO;typchf*S5a$PC0YWCE&_;j6Y?h(+;z$iLGy^ENGVj+l3 zbb$x11pgj%B@}|Z@oHKZh3&njHT_Qor5p?m9QF!4Kl%q z8J9k-C`&b1AU>aMV1q$3UG&tvKF5YJ|9-Vm%m-YMoY_woh2IiL*VS5^JQz6P29XvT zlZEFeYnCumE>0(Rem+_ItAeshP;F!r@^gnO0hSA-mYqKu3PpYzWLN-0)*L(+2bmjF zOcmP6QrY8*5cfE_9uP%fa&${dxJ$QPFZ6EK+iY_WM!oW4!p{$k-jPXtB(b9$`=!2dsw{`%<4?3?GlH2ZwtxY!XL+6tx404l_gOP$b1 zo*hL1Xul}$M{ZjiDZy=u+@)`PTx`w3k6F1@fw?W(xg&4g>A&;vgORA6XIaNb?85UqqX5NC)toJuN!|tk;DWm*=XM)BFyHa^^$V%<4f+uZm6aWy{&#sJ>=0h;Rcb1zjasCx-kEm&H zftb5~JsqHXQ>F2)eZUtoPhlO{s^JZWMgq)fmwAvd$>?0EqMfsgfx~?#K*UekUBU_g z8wCC60ssV)J=F8J5llR!*5>x7NFCkET|NEMfUuk35I~IjE!phL!fyY79dhMre)}i` zB_m1HyMR`Y*AUW@FHZbdEK4x><;Q6?>Z)#hCOY91f*Pau>8 zSlf?D0+34nf1$*`ga_Rr=N^Tf9oNHPQQ&b4LQ&wN{fae&_$^61y)Ex`>3V_`Fr~`? z5BpOSyrdQSeIIT1g=JOqYZE-yk7(9(u@)k4)xr-0eA0joCOT_o+c~jLk1dD67IZ!F zk*C`q5S;&PBqnq&e@USC!W0D4IkK4}`}qJ3fF`_ucqqWw=OPqiRaMl!4Jmq4(pcBh`l<%IqpiC~r{PY2@6fPfS7-Ccv zQ3$u7i<0TQK0_%^3BoP%`Qe=L>c5YaOl_AWei*OJ8cg^gf?5j+MV$)_A)4vg23qKS zzTP;l*3Sp9^qG?Myie|^c$et82>Ic3Xa4^zo_Iahal5E#i;X@ui04dbVl(HuO* zS2FaTD1U%~MSe2mNL2Akp)KwCh~dmz8ecGObIihdWU0Pmu4l`IT1^42hgPCikO}x9 zRL}Fl;7pgg6NxZa`dJSaJNblTn0&1TH-{ach@2u|?}AB-8dBx^eR_^CTm1~efsXyK zeW5Atc7*p7|Nb(1!UH*^>CA(Sp`4v+&bR`L5Rf@c51p;$dx35r0X&&6Rv+1>3q0_o zPi>A{iysyR;N3bq`C@P|du9u+$bj#7{jM3l6D(y3zBA(SKEBJ%6&LBphI2CW4^eq4 zG}sZt`sY2oeb)%QmR!e%UXiP&;@u)GI~4Gx%_P^NXCQ4|@GD!AUo>RrY{bCVxvtO+ z!3$;L8q~YR2m@(PH;#bxAXr0AOX@UOp3wIhY!?9+oQY>dMO#Z7;?o)Dc3npn$7j*0 zPt!ePjs2yrlNgTNB8v{0%F-eCsJ?_ii5L+XJsAr)phmPsCT?>*XjO1o$WYD%cL zt{y(8wlHr7AIru%cH-mG^-S9MW8(BoO-cRC>@sVy+?_*pd_GYnxn2%t|(1<3@>q+gCm|`FGoZO0Pi%lB0w}H=d z+`Dn`!Q5Am;S6c_Ti!TVbw)qmfjMOAzn6A)oU>C)qJX-a01YonTk^p$*f<*b1bd}{ zp155s2yI9GC9{aOZ;SFeS9^LZB}rtv--x3^!o_Z1upHK*8S;^iNaGwP4TeS zVjuT#CQz*rajn{l_dimaBTX9WsrJ5RNa$zA9Zqe)7@h+rrZ*5vu+G&ZB1a=V^u%Qk zc9c1p!)YiShi?DLi`g`D$80S1I&h0gyAHr9LQG-ScGbWU!s?_u=I#OhU9bgTiegD?3uD&e24gexVon8wA>g0Cit2pwM&m%b~t7_muMxsl0qYQ5S1h?wm-uTOeXR!>WIO9dL(cJd*`*?FQK6o{`+eT-*W?RD_x*zuWkV!fX8 zBEc?m67Sv@`@liNnw`Z58HY!mXA%csA8lvtQx@dv94GG=N| z4fgfgaQb7|LV+sdNt~s0rsOySL*!KVVQ-5vsMtCETkN+dQv)F(-ER*i>}xchZv~T}vyJ(PCkVyqs_Sk? zukp!pNnT^gNv6+dfgnB8-@{TSc0zjV=|dZ??)_9IBtiJ2CwV#@s#S6_6x`k;sivDy zy17JT)}8`H8CZ%UyGbJHB45&n+^&jpHFBmm z3|Amx{RGB{?`o=D7VF45s^EgIxe|xsnZZ6RB+g(w7l)T7{IQ@oX6f+1$?iq@f9 z$HKwt53wz}$QLMbjyJVTTxwdn4 z?4t8hy)8=oaGyvWnFSD(Nn|5)YeT(U@f^J4mCb;iV^Aq67uNlRpr(7w2opuw8SxWA zv)|}Tg5aqaH06ZdXHP~tu&i6B}a4gWXNF_MV$i?>u&xNv=?|pN*oHqbSh$~ z2HYXjaOj$~l3B*i=_i zW(oF%D-3qxJ}G$(^J6_nK6j0d$XqV(?SNP7Es}@SM=f*HqN-tCie$`Ijr^zZhI_@! zb6ll7YNX;3m9ft%e4{w^+o?f-zPc zJZT&JP>wdi?orTLqPeE7+e#%rwwOrD&i!Q!8aC39@P$|!1IhfS$1hZ?4um;Xn(oU9 z47s(CCr;|=Zo2egl)~a#z=A{jk%_b*8k1TA;;u4(e==#BzG<@PF-`u` z(jmAN?UjR~%%n+$Z0wV|hE=ziSPT zLB3Ur-ZF!|XZ41kn#Vqz^v!*+>$>^!5G-}g&rF``lPFM%%VLnEec5~EM?u-0FWrOw z+7#B3joi{uG5OY6+@>an^$UKvk?zWv1I;JVB;udm6}1v*?I3+2mb5e+WJS>n_z>%% zu-^hE2W{d>@<0UZQ!EvqcSl9|@8p$U>uLfo^I)wC^)g zsAN?S>Fq!55*ph@5In;bpzvPk{a!(+>Iz*4pfiY zV&YjMchLJ|>fhH2IBgPP-rOYWJkjjqUo9nbsziJEc{SnYVPzsh=VYDvK=0NuL6|-H z)Sc;15pP{rjLyzhiR@2K>m9qJ20_^E`+5);zM)B*|B$sp13Xo${37D~v4m;lTEPNpzj1*Fw`?tAhg$;D$A$$~y!cTK;}1;faV1&tkn#8Ckw+Q{Ht=*s`fnXz1+Ku6G(kja>VR1^zAlF*HG z?4bsiv+x*}f;^!T3lfb73<964xF@s-uWQJz$T_!C- zIX`fBV=mQ&K=afFI|g?-lsS8y*X}WimO_aL#=3~)=nf8GUcrtYsRy>Zj&^;}*9COs z&C9PJLEmT{J@ZIegEMWlN0z@aIqHU!=pr5Lz1HZ}-|uLA!`qDCXTZdpK+@Z!&L>IT zQ@-Du8r-(9jh-1sssZa-jf>+Rw>6oiRCgq7q#({hx!QKU)wreTFbgcs;Wcz!W^iLC zDmpN536>S|YxA$*y9S&)$$2P=J%b{B3r*}zc>`FO1CHhGJ__3QFgWj3+^`=D7&bvj z3=V+wvJeb(KcRC8g0WWC3e^7S1}`LYwiX}?7BDR725<&%jYE<`IBdJ#F&gB!c`F!t z9kGVii-_uT|7oT;x?90p2}dxxex^t zhay+!jMM{;78tq;EMZF6VEVdH2&hnns8EqC>9h<#C033>T?{!ZLXurpRV%FRPhJ^j z;cLO+!7veFgI1Htj?I#xRnlP;Ty}LyVQ7tE6XoH$3dp$v>;h5YuI&&SE8vTs*xRPq z7#040tguE*%+X_@-deF~X82!o3@v#_2*ZfeH8A%lQ>FHgI)&xRtc+2i{o6ERp z6pJN|U)R15En4hPmWri@%9|4jjSv>_nvdKdQxB6B+Z`-=gxFm{(ATn$w@FC6CCV*M z56bd>5Yck%_$^o#t?TVk+%30cUFx)E$wd$=NkoU?{OV)0Z^S=6@L&S?aS#3vvgslR literal 0 HcmV?d00001 diff --git a/doc/iterators/polygon_iterator_preview.gif b/doc/iterators/polygon_iterator_preview.gif new file mode 100644 index 0000000000000000000000000000000000000000..33e8d3764caa777838d1409f607a276bcd83d50b GIT binary patch literal 20229 zcmb`v1z416+dq5{ISey&3pj+dNSA2HfV?&-&Kc*1E%KYL#nZ+{mrPvriIwsu|t{z}{+r9W8k@c!diPe0KEc0}#H zJWil&y-$dXitV#>_(gsFfB&k7#~;G+Piq}e;|19gucFlwx^%Jt*5=C z_Gu+<@C;EG7Y7A7Nlhs=X?0B*DM=Y|aSbVXRSg+AF%20>aW!dic?s3SXHR?C2Y5Jo z`X4^)@W->K#eVthzA|`tgEyac^mPezbkOwm@<1Lit>E$xv`ERz$!SW8Yy9%OpU*n{ zk{0z}KYIcs=ES~e2}FJP5vV`=fBZvn!N2^W`i`EUzWaiT4cYtsx9{J+e%bx}>Enm@ z@80gbdA*eOgi|5atuCF~=ef((U;e+M-OZV>HxxKhBf9vLrx!IZNsmY1!<71;E z!$X7Dt`79~_4agkb#}D3wYD@jH8#}O)z(y3RaTUjm6jA26&B>@<>q8(WoD$OrQ%a? z$w`R`@o}*+*yyN83_2qGN?2$}Fe)f8z~9f;$J@)(!`;o*#rd+6ql3Mjt<9y27p$!; zEzHeK&zqbxHZnYGps%N^qpfvDQ{%L{nyShvWhKRv3i5KYGSX6#65?VfM30LI3keGF z^Bv>m;pRdf<>X*L!p6$N%*4n*Pe)5bO@)9{!YH8RWTYg-M4)@%`a(iV0#E}Ypr-&` zPBQ?I?A@BuuD>d`HP^pqBY<;oDRQoBa^JefC_SUCm&U@?Myu%~HBcn0i zVNhX2QZfPt$H8GZ1l&0lhfi})bIVQ6C;*D`aX?8@ab{U^ItXJ@dS-S@UTsHFcU^)| zW>Q;LV|z|RZ(&n?Ugy;K2%K~PF;hCXcxSZpdQZWFrE7viDU*+DpO#m?7#ppaZiAB( zQPkc~x%ctbtFEnQ{U4tgCM{lmZQd8O)l}=Jfkp!spFXuty*PVc%D?H8&sJw7W+LV3 zo^nV9Z(8vro?AO%%!JNZS6A5RO2z~lxSCRInI%QB;HZ-$=lJPit%S2S06Dt>@h-W= zuBcC|?Lq&s_O_ffz1Wo=a(rH0z^+OFn<@3uN$<2g^N_%sx0@a2jg$MyRMGuVD2X@C z>JX+s^!~!fysG22-F}bzjI8YVr&BbP+StFot1+BBjluc1l=wl&D2bx^ZuR={7G~)x zbJpfoPu%G+Zg$YKvl+Kz{@5FuwPPc2gOVLjwbJXdiP^PV>FN+)@(r(cPHEZRE*?(m z&!y~tagt@{W}!xkGL;^;Oyu2uN0BAyX4$)&`Su0R^g_K}HONt(I37L>AuZ&Rh3#qF zvABH}(*ybNDBwdYGfd+Cg|@=rFJH(lQQr~#$Uu^&>_<^h3Gy3}vn^>H(yzR$r{di* z%pS$Vb~065#xer|=OZyAb_t5FH|&l%1A>K69|qQm2u&fhLz*tr{imtgYEupwXNBTb zh)8XQ(OE=Dn#wejaEoU-b}?TZGt^^NbI#&BW$wGVxA9r&4eV|^VQStRaa|P z;9Ka4Bwbpz{d2b3ZeW)SLWLSEs!RB3Up{x_N#05=IxQc_U+6bd+vKn@Vp>zYT4ne= z!--AXY0!X3JGt7+FEJ^6Z6gMWj1%wH6WTYXc*H_0T!kjs zF0)UMD_M&0#v?@&8XB52*pk$;(u|Me@qk-VSG#Y2ecK61VX7L@M3ha%z?X!_6$@+D z?~BLFmTKFn?oRu5Ya}j9)LymwHod4X9JGC7I+)Vq?qi*YkR~PaWa)d_p-QyE z*D#-NzFXngt#hUR$G>ytJsEG>ggj%CKi=_J66EG;}iEc&r}$#*Gyxs4&*Dy8Siq$n4f z82!p#?no@@R#aK?ra;`6bEJt*IT)gIEu6%z_!Gzzg$ zWO<-9d&#S3IV1(=0fe9mB&;V*`9gE>hMEv`wO65cw$z#&S#R+eW+oy{ifZI>-ce*W zAEuLO@;jzsNM_lG<}-y@7pj;QbXYtICKcv~yIW9LE%kD5COe}RoW2cN%4oT?$8K}m znLcHnP-fCi#ZD3q5VPN2G7)R)I9ZIyed>#|3jEf=OK-O{A){4oca zhi*U-*1SqXDaO%N_Ys_4rHLtK%UXNk30~s-7@6q_ML61mWJuQaKFg-SjPuEf-!(`{ z4Id^Squ^38(9JZI^a+a!nc>(Kye0HK2^(KX!#F+0*BOg&5Nx^!Upu#B4M38339`A>T^Md5}ucv;G zRp*s-R_hk4FF)Pel|-e)PBVod1Se!y+``^w|@HWw#|z{9-hhHqWj}o$STsyMzfr5qWf_Z6kSc!L z(Qs;$)mu*>r?iPj&XLkn5-TyFLD4x@!NobB77~5$TDY{{Teus{Q{gu2rJIe5PCmND zlcR&4f>>TT_Y}&H3mu>QG(C@xrqPGoVbqt8Bc`C&;Llkq4*bxXzW2;&BW)ndYerV_ zWl|RfV;l7*Wm}|Up&)*SoiAPV@qBES$Yrd! z(`Jt#7xQEX?hJU!e!i=1m+>tuc+S6PJB%s4IQs2FZz?iBiRYe!oymSzyQpvIY|h+y zxp{*2i<57^zG$)Qod-ql8xogYwNgIJ5j#8TX>xyLf8&U=HF&lz$-Q;{^(uvTo>xJN z!mH01cs2H@zx_$NEsT?`zVOO-i=DpTsxOCsz`P83c`8pSHp2c>>P`1O_ivAQF7lsP zxNa?MSIoqIB~UIo?Ds%;b8af{;E$Xl}_IXd?Q|qb^03 zY)uk@aIp=<3`^bU-I4IempOD~5%150TWuJ-@%z7p1gUqsb5?|w(M1JK zV3p5AEXLZAlLSpO2TjSwWZiXJ53+003_zG($s~&P=`rb;fasi8;bl-IH;o9&(e`i- zm?HC>xzMNJM|yyp#zrCPJYHCrx?Cv17Z57`anj zm#^gGvGFYK(Cabr&trTu!UJPnmhUOev-mng-CZ`YaV)L?`pQazRr=nYw7KLQ&iH{7!;S_^oqaQDNV6AW`O*r6u>$QChf=-H zIph2%j!4qKhZWG|V+O zJnBMO!@^r!lP7cA(6hxm%{)(@H-SVafjlH(&q)&Aogg%nN)we{Yn;YWo5neFva^B4!7}E)7eMK zDj#lEonk2bZHm2`IMvd%u(!9I3{_$>87-J<7M?(l`5JvfK^~%w4X#9S)ruiqPv&>m z2wRr5?Ru7|1JA2GOJ!qE(4Dq#uRRu}emYv*A>njM-JZIXJT2fYSf&%9TT$?Qs6c_V zitbAw41EkaTx7agM5d}9Gf-)d>u*h1f$ ziwY@CL+qXbX}`xe)bmx(C16in=ZD=-fBz-DVko;@v%y-D{$YrI7RuDJG(t1){DOZ~ zkamGxK*@w$`HgbTHwx4nL;~ciG!))Eqd7@&LUjDWIZ7d3efCUYcn4~$lNF0hwb+IQ zB#V1$Bl5mH%{QjZX{P##QXl)S`@!qeua7c<;+VF#!Zjz~wZu^RrobM>cSSsdbK&Nn&7Drt3yuQjd zyriM9-l99JgSUOprY%D~6VlDRnfw%nv&42^JW@XusNf&Uc9XSwv$N4_tMhJlom_U- zWtF-!Pm8&9`eghYh}*J_*XPG2YLm*-`zPdr~+Pr)3Ot`OYM-!8$ymUg~^v0V#B zENuUlp%&lgWPKVT{mt&q$C@W&`u%Z=yOxq6n=JDxEh}sV-(5RSDirX)ZC1O_78BgL zGIPOYrXGZZos#~NP^Im1k+RVMiA{^elwiEWUUt)Rmh6HSr|RIRZ=LO~TC-n`^@QzT z&j>mS^)0+a+z&mIwgY7swxA6zKF8*2dy;yk&JJ5Uh!FAp>I(O?8uX?dBo?{yh|O7NI%QJ6qv$PX7}DJ=78kJN}f*n_GCm@rLIOVk^AH`v((`4DY(R{ zFa}(_`9x;eguO^rt9$w<9nvB8*%8IrG3(juVY8D3v(p2!vkzx)e4o9=KDVGaciVdI zZrI#X!QAq|+%0y zACvE(+DdMv+q`1xyMRWzE2L;`3~MJtO0*pVj`-S?Ci3BRApn~*1y`c|I)j6R{f(V@ z_FYBpn@1<|FIy;4!eLIa)UmPN5hl(aB(ed?85{_?sA%QPf)uUPwETjMqTIalOoXQH zNq9JGQjM4yIk^!8+m@+Z=ik@n%-K3PHhz6#ataBbp1W~#(&g6T?K^kxE!|&!@NnhP zrbCOf3dOoa_iOh>o+@Z-@X6v@zdwsFJHfX|LylZfEdQE)lxDX1*I3Vo@^-{ zjiuqyDbQ*y8&71BbbUD4T0W72gsUg8YqwQQ!6=qB2)a=m05jkN#DM^P{sGWdeb>Ks zqYC^*aAn5y&I%j`FX&jz&6{ys(zoRFg3oVri+F|w>Ay9 z{}GFy%CbfI?^uLMWLdD?5awnyE5_cleb;l zpN8+;_x-Jr@#bey2sag_4HXH*8qEg-VyR3`;Yh#;4y7gqE+q0GpyV)13%Ea<7BzXH zU|cz6WxWDPSyM}^>^bl9u5Q_;3McKWk{z8@qv8N`W;SF}CK*`Bzxn^SvK;%VEa?L0 z>a3^QjwNV|+D{i~xAW=bu)>xePPJDHMGzuK3(x~e0On6Kb6Z*7e#G}b>}l#WS|0Q? zb-WLHnxgqPp95?!p*@e|0wh{$9?-&i=RF3AKWKzqp@c@D)g!N9W8?gz5|h+$2{EZE z(41T-JWCxYE}`RMEibI92DPZZq47YAE)_Ubw)gZZ25WcnkTPD=j2JoAnW;Z{eq3y} zZ|>%S79E-y`o<%s=_mVU)(9Wkc(tv(`uac3EQ8eRrr{O{ z^UYsXfXt?c0a$B1+cL1THli8{xXVsRL_96JpeGQzie`C~h*GRh5ZxO?yJdpB~-L&F3!6`x0@>e5vwlaHzj$X{C(vuS6&r1%2*r&~Sy$Jw$w zQ-U0swtYk2UKe1GJFsR5?05?Vcj+#+Y(JQmaxLF|J<@s|_MAsN8dtG^F&AQ_zvBqI za+<*EE&-wdKVSsH;I=chS#{VCPcX14nuL<+ZdKJy^c`OqThZeIZfrIeoh5Fdh|O7x zjGdJ$G9w|6K2r-;LYwp_{}%p_RyHfsAz0VY+QUo zVp4Jt1?``_sDSsM02smhBM&^_E;bBu-~laQbR~HrHbC{@N^bSCPZfz5W% zQU3rc3@c{@I)<4vKq-+$KN`>Ei%ZC$hrtU9gL4@WW#!bxxddc!0`kB~05mcZ>jSb_ zVy_;1VZev0=q`8>Qx<1@&AX-ST@v7}e7D|py{`m&hNsALJX(1=v`}c+_oM0XD-SVjT~2?msc*2ebiV0GxV| z5VuSb=nX9(2V4ZT5+LdS8Exji`CSyiJ!LG=oku%vT}yADO;neIHN3f?ax<3LORHfw z98;Et`p%eTXr6vO!Sc+aMVhZ6YH+3bGcD((pteiLWo_jid6R^_mMdh3KDmF#W_J%@ z0HCgv7Sd2SjFcjoB=iI#EnOZ#7v&0p#*^bHNXg;8%22#fDS1+IaZ~_S3W}-Hp(rhn z!3wyxwrk|%_QnoeRUg!99%&m>EX&`IHd!;LfxGvp@7=q&eD}5j0cNz|IL8aP1oHFv zCqLEy9x(`JIRa2*qoomIsMPzTAua!P8F4ONDmcl=6B{kI3wKyss6<{R4irHK`_7|6 zf+9n&_>jVEj$uNQus#eNiP2FRVR$+!eq3gBHa?B7pnwu?k|W>>`aNiA4L{J<&febE z-14u{^T6*NtA4-`@#tUEi+9#fsNnGg_R0aMfLz;vJjWjJ{CRSS_;=(pe*^iz0{SM? zmVp+^K_NH4_rfudC2@Rtg?zkCSLlcY77I#f^S6(^4k8$?ROalXS8MEMPjy?yndz2gsw~ubc?3|dk~t+AL?LM`K!@hGr7uY^m{Fu zFvc@t8_qHq9N9cGm`vT-%EV+ibgDFF&ToXbzVKnqy%;_2(7v>SYk#qgU5VWQUD-J; zAR0>z!$wD5NJ{=CG=yRBpOUE(@_Yi|gunpqaF7PB|DgQb_0E4y0|^wl#{V#Y?++z+ znvj1HYPh~0;2Fz_v0k_wQ9Fh@~A;V24{P(;$@lO9n~7%wP{ltd{jn-Wu+AIn^lU7ih%k&25iEo-e* zi~!T$Q%aWtuKHgMr0%=$pXu*E^1achN+4A#kh>HB2Xc3q&^Gcu_|H+ZN$fw4nnCXP z(OaVR+tV}`d1Unnq`JG#Gm*SCd-7uKW1er}=V4Kb3K$;J*!|E-ppT3Q?R?k5BNVx1 zsxd6ZB+kW>9R9~^;&D-xq9HA5HpseiX>#($ejcKs(>(jjKH(MV+`Eb0&ePH_j{xjcq2m_Rcv^x?? z|GP@{e)W^WqE=B7yE>L=_`&w!q)+4+4w-h$9Nv4HXG(yNu}ZJ!or9VMd2NTkcDvJ6 zVwndb`N56UK#>&sIlB&m(Fm!QB6MN8Ly)o@2TSsYZ9lnfE3TeFgwL!qJ2B$AVVC27 z;lB6fLD7MGj0RSGUh!cjC+(X^t(cpL+>k~mXv+g-$*Qby&Xyx_^wh((OF4CgbjY*# zhLpBMgEStip#h5mMJH-*0*}f7C;_oxnR+NDmZ;euZbS9Yjes1x$No(-25)#8M?D27 zMR1dV&(wEh(j@j>DIn8)kAy2#z@%}>dy&N(3B*Q&P5w6}^Js)rzytN2r|UcL-QScV z&{UD(L9tBGgv10HsL`3=)HF&cEG~x{$S=r7q~J5c@tH?*s~N&7$}%q3G}D#%)HhbO zkjtX!iRBf&*-=qcnE+J0@DXIfE5Jl!VfRyR`|tEpbCM=p6B@!0%oY=kM8yBJpwz^4CIT`T0UE#$2m;BN|4GJg z42NX661o1DosmN~^>b&0z>p7KH2KsSXmMw}9%z7_)K8Hk}Ci|WY z($Fy7^!mY7x2SpDhij5^QVJ|7%+}u%w76f(Rd6NhT|O5hDWkH~z*M?z2gxIs6UjLFWU6sh+dpg%WsTEnn1j^aaWrGGC2nbtxHVPbOxL;wROQ2@!( zpOVQY+Lui3I*G^@yEC}6)bbF8TnKw}S?1yK9bvXmRj#*_?rCZA)&6yuM>Z;TUC!re z1RAr(T95lpGJH5aPQ?y&pdDqi0cLlXejA}#V?hK*BH>4_ga=@v5<|i%z;z&?^E+2n>g&(1m2{^sawlLUarb%+Uq%X?yEQFzrA>&)+3(T= z9**Yc{SXZW&A3UauIL#npXigSDfNOMd+o(&R(E9Koat8`cBn|4`;Wfv=B7f=-%BA# zN;m)mAQW^vhiE@}3EBbjMN)-SWQBc|Yo?Mad#u05smZ4dLE9ojB|J1FWGq)J(iY4Y z;>Jm(rUAL;B@suqr(~@9jVSl`I^`;2!E?`P>^0w)EjK-|U6@cic5`LV!4N?OSBJ*N zg`*QK;IXz)t)z4}0I;>q$g|6(E6o3yVgEgi%rEY)?d|(zPwwB*?jZm0d3TMXNR|NY z{RSi&^y&b~z)#isFHN^!W}aYf{?D$B!06>E10cybx@05{f=|!LV#~^)&e5Qvhmh+~ zQC3!FS5hr_CPk{D)tWdOhj^mBaj>p;|R>R+WCLEa7F)EJ%Ev`LcrLk_7sp ztM`mi$I6q|mFW2$qv%9ya&0LC{4`H{Tr`=qzW(#;<20=BXcRkV;*3*^MT4_2;Eg)T z8L8a zSwH|d6-a0Z7^eY}8k&KB%i$M?U*}VuvC)Fl#ZrxV3Bp8*4EY(R4aJ%{Hcd`~S-~p& zvwV2S=!Q=3fL!(Bmf**4niJ1FLO7D3U(+MP0n<<$a#&n^Yb1YfuWsW^ zs-o=UJ#8a~{vxM+Gi9Ts#G7+~nGA!FAS`7ue^GRjL?Je)-YE(Ox$Z`L!I^dEp z@Vn2gE$Se8coZC?L?DXeU<7gjI6!V<4zCS80rq!(wcF}U!9qOt$8M{RnsLxX`Dm&% zcazA3o!&)~Y5QoR28HrDFA{X2Z~3-^JO`HlGjm8NUxc?aCi1)&)-g7Y#|m!+O|^pK z_+YttF!KCda#chb;$(RRT~)OT0clQu0IdkxPE^G?h0EVwXGI~IoovsQXE2@=Pwp=e z5LwJgzR`x8rev{GXJCwnjdM+z$m9bW_6m*yfLL7up?w4ZW}xKu+qd#R12%Kk-pUJ? zf(>k0c?RFt+J+6Bj^v4M*L=C7?$E?rwCr?86Qb;@N{pd=H7$a%j!cQiz%vf1-Wo3sb^~ zPo!~UolTNGyBrNWqTngo9L0=l87OnsyPdB2?Ikd~cf{Sy8;xZRRrZNVq}PXpCB?wg zsYyvvq!UtOU{IADZ&W@S1xqh0M+eq6FoidsC%{h>Fb5l5)F6T4hXj5j`8Uz}kl?6k z#Dla%1ODTb{RUv>AE%i7?G#I!$0>e~zjDe^AN61|f0#tIF4}9gkueU~?+S@FnH^zr zTM6t=BJ2D(mzDg${VN-1`;BF(u&d7f=XZJwJO|6)xrMk~3Fp3`>U&w+<*cPC(6m|8=%QZ&8o<4QtTNu1o3@!p32Ps~*no%6Qph9+Up>Drz1#xMGiU zR$uC20)W1g*X7T62rMJoDd$2*kM8skS}Q+@trHj>021#*RQk#OhKm1+f@;%x$m=DQ z6#IFr9sld<-nkU}9_+)Wp(4xdtJ4b4)asXaM!)eMXrot-4CtNMJ7q~FZT$+Zl`9rI!;x-y?!9T44%57dqc(>nF^)Wrhtp~($H&G$zpgHU z0!dZ#;OM82(S^86?*hWv5O5S65r^=LjSpqOQsXVPamfkPS%lS&I7rF)16#=bNl9bW z9@y-32$nDImW$oI*1{m-&v6~~=uX$`Jqga^fXJHDh-r+oyCq(ll&c*HV@|2BOqgdg z>Qo;o1*F&nQ=)u4WjSAyjg9~|YlxHhQvA)M0n~wTGfIqsftMEpj6T}TJuZz6hD}We zSE3Vh3#kpIvx{;_vI@%6p>_4p7?5FG_5Ji%MNDq9V= z8}}3UAS?$9u41#aRLJ-#lUq{(Hwq{DwMhV7LL&edBIuNBflt!{`%fPSpRR3S#I*EX zdf4s!$f-JXZQ)tdp1fZ&1L4#r4V80orhd=XrF@ud6XAx=GWNr=~J)<)E6(aerZlJ9wSs+q{_W;C4p z%^I*8WCEs+<-3GqBuVgi{ez;y>8CI}vaLD!aryKGHTGrvi-xm{V-6l?AvGtyP)PvO zTbdmo1Nk41oOh>7>8nWDY`~QuH*v1pPA!UJ_jIe!!{Dm(Z#KwBJ1FbnrlY{_clFeX z#Vv3=6R8>%!+?#AB|ugj#AZKf0!aLRUj17ErA-`Q4ZbPS((o$ons-B+Fx}%_nZ>}@ zdnp`SfXJihdNnnAF$KX%QuPIVv>L8D3$qbYO;46QZs=Ty?#N4{NvXWkKCs3qx%NJ+ zF!1KL&km??O9Wc@O4MZ-z?sYmIK}(IGBVTr2(;IZzDdjCYxMAE2h!H};*RdTl@r)c-B2jP5=sliQTiaA`q8^M@pPznl&}|P2D$0~ zn_OY+3y7UP2J1b^N=2Jce9YOJAs>ov8XZ2OM*~ zQ8ZfGP8t0zyhL{?oQHtyA714s2w&h&_~!ae|L#@(e9>g*E(=>q;kf;lJ0L@%A9woHfD6N9e=q-=c_yy6;x=8x2e`(yd2l5tcp zk3_!I%(V350AcXG1R_Xtpyfgb$uAXl9Gn;Wg@Nlt2~+#Ut>}JnJDO1bhP9ao43b(5 zbSVU!cmVD{L#?b>w8mCL2E~ht7e%p9I?W3#X&HQ$TtH$k!^mV-@6c}T`#w?+@>Q1P zIG)&2If0^EP9K87q~y;sP6%wI&>iSASjO=ktC2Gqr;*oVNqQP1V$jw=wP`#=(WI;L zSg#xj@p;gF-r$K1d$_7CPZrQrAg5DG6TRS@ws@1x#+tLVrJIY>j?MW4G2Ybv(ayB2 zLGj{~Y=SaQ9&iJ127Nz?`=R>M?b+-?>v-(dux32>%y93LFN^;!YHTgCM}<8AgZ1yL z(4j?FAEQjP#N6dGJIUHVVA8^<`#biIiA=6)cIl#RZ`XXzaAkxU%tIPL_{SlDxHxde z8kR~8OHE7p+oXmYMnD%62ulPQTmh0={2xvC)qv<V%9+QTRwai|SuZHWV-tsO?)-d0UOr~s(x7Y{W3Frd#hm(AS+3piudI&OHBBKblA z*haWfR`sO~iN&sKintP8t1!sbicd1+G49nPVt|Z`On2&MUbQyPl=wIHz;O&57I{28mI;xNNDU-Po{a+sb(-+Z9KwM9i;|ch2>h8+V*hYZ z2Px$wsGq(sUS4ydyeUPF&Pjh6aETUEa_b2V85sK{hTh9l?>AQ)jq4NLIyYZ&wODu? z!k-7aTxtmH!*ww~mlW|}9DMB4o2cBG-WnVthzRqvv30eJl!}J_==UXxQqTjiJQ%V- zRu)EGTuh#uFPAC!7w7^(==O*2UWb%@I|sVXihCeso*-q;l>2Spo(&SkH?Nd9)v|;y z5+zpnVys1JkmVf<*6#|=4*3h$3N;%@k(o1`Ip$4xLR9y^g3HxNE}`5`~4 z94smdtmosfMiEx0!;^eY;~5EP_yuStU~7oyAl#q#*5==W-EMMMzqRyC{$hM8Ush4= zsMwwA3+)f*D2c~<=Ax7-%HI;-aUEtiN~>VSwA;S@^oqA~_ED=VEBC=HlS!BX-BAXS z>!07;g>aslxU)szzpQ|m!#Gp)J{LXdaH9t)3ibsSHvIuU*wFd5%n(@RRQeQRdfw4S2w@y$Tv~W$5l1eC!g&F{V&h;a z>B;oU>WdK4lmZFU=59uK8P&i58)*=D65B!8P_g-n}zruH?O zyYlquQXA5cYeo1MDq2XQ*4J+;SB>ai%01VLCx}^GAh{|BO#-Jsr<7UrNflZ+s+y+t zwQIwa#M7>RjqCvKl}uXxPMQ@G7EeS+`;9dA))e=U7B9^rc3nm81Ix_~noaC*owkqE z@Q&jZLFwCEWe?tbKu7uD&oH9VE0;Ht|uO$DcxXANjYi|rw-r^ zSr^Hy<;u;|(iFm+1`7qdH%X72Dm`yAuG~pX*ZzI&{C+mH?s@NKFai-lu=ImVj!Yr! zRfHYrz<%dNZ)fVuLlK0)ruA-d6mmk6JHNfbeTeV%2q4}cR$tbjcdoltCGtgkqjx=# znyC~wGtTx+kQ5X9RovZ03V#Ucbso zROICg!Rq044CM8Vhz>eL|3H(R#XvtbqLDi8$i%g2RsznrLE7C8Y{T^rlo2LtV3Z3{ z%`@H{Dex9?!<5&3;-H}x+fzAbqbkysKna|fba#rG9G_nbm2Wl>@U^tI8&qvH(o;m= zJk@66q0z68+pxSrbM*};V1Ls~YBvmqied-CV-YY|9736z;QAxr(uD7Ukh2c2?+@5d zvU`8zSjxk?k-mQ>+1@$l000pmImr%TzooLa2{mtys|xgW7Gtt;VbQyY1RgYI!wp3m z9Cv!#_15pMo?gA0a#KDaPzD7hwY}m9CHIe%MNv@2`cP3M>$y?IIK)9INJ%kSs;~@l zDrgN9PD(;u0WZ@_)NEqVMU=J@>VObPsy#R$0!WGuNp;z`x%+4K$IP!fI%+8XGRqVI zJ2+Y-tuZRx94zBJEj5{Slmu@`c)T%@{nW#r}DL+!O&biBW{PcjN{)zKN;3WtJmTg=uVcuQ^`cK#Gk=n1oHFs;>+H~>Fd1?1YhvH zN0Ckt?0yk##el5C7>NH%48(%1FlLZ0)8TTZTMbAC>sYYuLUQci z8q}hZ`)e3XYJZ6@$>7Y12z(NDATkr_*--G4!=Dlm2VI!i!8{yX!~D_te!HLG|63w` z_)`MT3`mW?E`o=GK<`&8jNn;T0Q?`_c}qBf!S2(;aX^p!pRx3Rh?#&%sfsvn z#(!6vf5GA>a)jEnPtuQhU%>yGq`xj-{r7t4=LYOS9()0wo|T?8te_4%$kCG%{20_}vK;EM(dbS~xblug{Ymm7$ zR8&Jw)U{7JXJY9yS{7>0Y=nvBgZZ*W#o>4n2}fKJh?Hz~80;vNJg1nIG@6x?G_$0J z?hKb?ZAliX^wBd}O*yAKk>untU9l0|SFXj4a1V`QCWfz0`i=8U&w0+zEcoB#y?xg! znI8gyQ$BEV6J1%iUgovfutLC}h(UqgZ5{IRmXud>M=rHj|RfJhYR_f*PhJ7F= zdQD|OD-+f8eX6!RO_e_0b*THl7ms{g`FmjRmbCGY{){n;GX7Y}bj$7X+Q}H{x(z zx!I8OwhJ?Ql0MAzId_cYW%9>NhMirjRxXQyn%yklY~CSJ)kgKE%gccd4=o+e+!-2* zDts_#|K|F%s`Rs`EALFbTPR=KPS51_8*&VNvK)*%%DWWM+W6^6aq_FLA%TyHmtXjq zv{@1Z$wO}|m$Hvx$lAZZ>-?;;XSU5qj-<&)`VU_r|Gnig8BE4mJ(^XnGcTH7Zm5{- zjhr`E3=f(|4|02JRF$B$Gvi5`Pij2+eJN1r(72X*xT`AIGEq#eU*UN{5S~a3+ymMNKw5SOD4N=_lBj?%Ro|u3g;~ zsjITUdmoM+6-b!fLyg>*xY&@wtAI-$?T`R}Sfy$K=w8PMyQjYyEiMvYyISfTbc!`kT08EE;|oXm zG{}vX=NZC`*63Wko_J9eiVX#_(1i^rIv+2rdr`FK9*{$R#L95$qOg=9iekl>i-St8 z&XG7}xygF?hW?8F$d~YSLC-HF#oNc`BltyzW?pcKt-hk946_;<7P-xhg5)LIyrUCH zH(Xwm6+q_RKEk3szRg`>y3FX5{{gt`lP<=SPkrk<L$tjDfd)=vPbh zN0U~>R{T18M)x8`9zSMJTa3}Lq=e+TQ{9yoUO_3<}P3U!vMudzaRM1;_fQ?L2) NIw%^cfjyj){~xafC-eXS literal 0 HcmV?d00001 diff --git a/doc/iterators/spiral_iterator.gif b/doc/iterators/spiral_iterator.gif new file mode 100644 index 0000000000000000000000000000000000000000..ff287dc499ab22d531fae9af1d0c5133b5e4115f GIT binary patch literal 44166 zcmbSyWpErzmu0twmSo8mGc!vTGcz+Yv&GDe7Be$5Gcz+YGg_7`^~!JNn|(hf_Q!Tq zL|0`coO|=$lNlLxM8!qe*!3TP55Rf^Ky-4Fs;Vm05%K%``^5D0%qO_Y`a196po62M z&yaZ@VIg`pR`Brf^z`()wpJhzhyVmDBdnw-$S)_%NJ|d}1ONaZMQYM=_(J-Q`XB#X zysmcohL*;T_y)$N<~H1f*X`Ye_~u63gsRNa^wM^M#%AVX?)Jut?lMY-?v{q^MufaP z_*||WuGV(e#*X^_FAYin;x$H30c{0I^g=oo0}>8!2) z+VxLu2S)|t{|n=Pt?i)XW@k*NVC-P)WN&EvQJv^NjX!+%{~qXX#Sb(bvi9a5lcH}W zWNYYTZEWKxF2qgv@rKsO+=xSjpH+l`ft87#m64u>je&vfyAT7vurNCVvk)6SyNJ+# z`uN}4eiz~wW@BOH7h)3-U|y8$;v&jBEZe z?tiys|9`gS5VSYeceJ%vvbDAPPXx%B**e-fnAzIl3o5eUlS}Ixn%n#>p!hpM|7EX` zvAwyov5|*?{~{_ghX`s(uH{Ot7P_~`Ipe{XkZduwxJ zeQkARd1-NBer|SVdTMfFd~9@NcxZ5-zpuBayQ{OKy{)ySxv8>a~ zULI~PP7Zc9Ru*Qa?~DxebhI?oRFo9tWTYg-M1%zRc(^#&SeO{-Xs9U2NQmFQBEWxv zgN6AF4Fw4S4)*DTVhDbNLx2Mi0Ms9B1Nci^0B}&vsCaoN+xcWWNRK?)$UMuetjg-V z%Z_^5(R$mp>e}-f)RSW;MvWOWQeZ!7#gRQz;wVw6QN2>(Jbvlky;I{VMVmf-(%?R6 z)4qMv;we+Te*N6xJ$?NO^7Zo%2n-4i2@MO6h>VJk`57A*pOBc8oRXTBo{^cAos*lF zUr<<7TvA$AUQt<9T~k|E-_Y39+|t_C-qG3B-P7CGKQK5nJTf{qJ~25pJu^EO2@AEf zyt29qSlis(*xFs%+1oleTsuBlIXmCKI=xxHyLfnfg1WqVIsbF=eh3IhLXXa2_k==q zRqv_E?GO2i!k57&PdFF>M`KV>^21Ol1{=h$g8VzSpg)>azKF>!&R8&!P~Sh{H1VXPf&aTFgTP-gtPgAXykljOeM2LqKN{=FOFq$r7B@6lV<=b)neXmXKhN< z64hGG`mDFKr8A8x>*B6SOtdqtR+x5r>hm0%`F6!OMhG}%dWAmeFQO!xDh%=i0T}sT zUQrkohQ&$h3nv!u28L3 zi5`7fr?xBWL%@rXaE~}0H8w_|;Yo768(hk#19`sPI$y62O3fXf+(3!4pKos4;PWDh8zixfD z3~$uF#_S)L1SvuOxXvwUVbxx0I3ZsxO0aG3#7hh!QJO~ff>_tk_B_6TKRLglp>i(yXh~EFwyqH|<{yO7_<@Y)X&M z(rgL}rPGL88}qQL+wKV^FFWTsEULT4?yzXOeAFc&nzqBoaVqNxDzf^X{n~B1e+p!r zcYOn$S8IQg<+p2@vRVJpi|0UHIZPx=eOpDwYxQIBcOAA}HgbAL-2~0N6k`v5a^&3v z=kmt=BpTRdT{SFDPS30uS*7C~fco-b?l%_=^W26MjnljeZU2MG|Ps|xOJ2)EyZHXF4%{TNRGPs0dXJg(zZp~F~>I)-Fz?HN2Cwntw*ot8&G zqyugB)x#a`{d7sTx7xXU2d&3d6H$!ENDUS5_T_u;`Rh@RGtb*`mSH6O({e~w=L`!J zulxOk51sdOQH+o0?*`6olv_FUZJyWB`Rffge^z4j2PlA3)+~Ac2tnLxpPRW@C*D z-Ji^pP*RH1!JqCIwfgYtErMuIGhPXG+xNcDw769_O6&Ky5J0nDq%`^fZ0x+R{003) zeK#SDOn6A9Y#qd)mzW4NPlM0t(8Aw}LPL?9l=}_xsOOg-r z&M^3TjV_@eQ5TnBL`0g{GDc?+%bu~ZN0s?J^nD32#$2Uim}Q8P#$rumI$#bd$f+DJ$lrrY$PNAEF}RzF6=Aujovq@?V*rL7$EUkPXUbS z5^z0FzQeaR`*Z5Rc1TNr`9OrV7Uj{>^?TU{vYk>DGqa^^qlQv3%VO~=jjb3r1yJc_ zuFCzfTo0mLLf&GoEIO)0lDT|-0fwa$M=$3d&P;2OLb7#fzUo&)F+0xBnE1Mfa>GJ% z^;(lCTn$4Tl0`~YAeEYpm}A;hWUL3G_+&8Rx4QQYOAbHrvM!s&a>GgrncQKe?st?T zCZ`MDa|u^*Dp=3f=R#Txr1iT}##5djx_X>2if`_kMa;AiU%l+y(se`}ih zfo6hswlRL^(9b7MFLgY=eageuxl&v8gW^I5EIYa569jz-4woj`kHfs0t07uskH)Bs3l6i|WOeOT1lo?-IU zm^h?$fQ`i=bsdv#0N%3>`y*$ zWk5)m#|^2^g5ffKF? z`aRj{g+?CpbaTvkT-anJ=Nr4cxC!~1G}IVNTNS9K0+5U3s`18Up|Cj@6j_*fd}s>w z(6E;KgBxq*Ck=wPG}8Q>A2M?%kC>C)C!~(*3zH|elqJ6cN|GX*m*1@A(IBSww;U5@ zH!W_*o;Iwje&tC=S-d2@?qoze_w`1K${wfh&UstQCHhVTnYwQSi+{Q8cpWR*rft4B z|02WT0f3`p95fd?msM0=S_Y)gV$-z_FGko08ERz^v$FS0(yWG&BrMfN_Kc=G}8=EgHQ4UWoJ?v{UXu-8u%5z z$Lon5(HH(TXZrn4FOogU2Z3lOglmc8?5h8>*Ug;n`2(HoTMw@@0K(S$F6;WwpvScs zE|T7<@OA4!7|8ar8&?W&;`*Fu{U?_QB-cpB`UHFV$B$q4an6M!yiC^!L}A+fmhj7a ze9vn~)LV|xyDQmu!<6up%)va^?ug6-CY10t#C)>YL$t@^Q>YIOEAsR=K{{1YK1Zurlo*fO)&cJyHE5Ws#z6kcHX@N!(K z7&7IlH#SDp{EE@I7%~I9H4z3lNm!gyXdLHgyw5@W;&W^iBPgL+ESAkJo_1Jac{m|& zATIYg><6I%BZf7TxF}0$A{|8pyl-MtZz9@h99e1tBBHK-n7`6$q=|W`MOf0Na$?jo3Zf+?r2MOMv6D}ZA98)8eMv|jXwZckMz6z%bt)y&$rTVKU zTc^g?IH#tl%cYe@7Jrue85a2lnOL=&9ABFtmYN!QnyCF*kYO|p<0+xWE!~bFz1}>n z@ie`2RgxjqBgZYt#!apVBZG-Gqgp)`o-`4PJT(G3bI=^cJ~c|EHF1R^vt!i=+r?vX zHEs2CR)(7yO<}Basa>gCCa=0~{z#^zN!E#Z`m8w0`6wuI3nRPacP0u;_$fouuu>9G zEz#ZyaL(?>eVQHrIS0fZ-eeZjo|=VlmLuqw2pO6^Mv;cImI)wC&SXg8l}jl+&4oxv zhFeQOfAQrH%Q@OjMK;b(AI<%>io8A=bRCvA^*PTLgM7bKS_RGJi@DM#iddnup9cOl+i`>xg@~q~(3HuPgQQJ<+l5Y2`cn#kX3yEBJ zf3cOUw1Lu!rHbFbOFB}$IiSiKH7X9uN`~B}vC%BRDU~4IEB?4q!*BrlEGp^7@@gon zk~k_v339z*tbR$9N3)e~NmLwZRF#yKA`{n4ycC1O)+|C-ZLn8*uvb05R6m5HpSIP! zuhpPwrr&Z@!;jatzT`Gr)JP6gSHx%VTGY`L)PS9rLvz+qY1Zf+)SXNGxNM7EX%qPB zk-zC)wTzhtg~f;QDwB;_NB>%8PEmdQyW%@1sDb*tsv)m}!lMBvy*lWuPNuz)fvS=I ztg)4-hV|8f9jk#DD}Uv=zE&fa3AWMtRfop-8)bT#UO7?kSp{8ty~%3>iKNsRM^n3M z(<5cW7O*P+R~1r3V^VPo2ZuW~1c3MqjIU5JfwL&29}ycW)TzzY!J^m=CMNqlI+v3z z-=j61^BaF|h0YnasD!drbBuU+q3QQhwdFR|`+_>n0u7DAH}v-Q^!A?DcJ=S24(p8^ zuxRG#4VJHs!yZje9-?2+0V?IyADerP@+Oq=CY$z7uX5Fa^RjWxPL`#5Ld}x3_0AKj z`on=AvF%`_n2nR1D3}(t3z98omK`3NAQ@P@5O6@(YI%pbNY`O|OBQ(-$g)Rl9ix&B zaG4Hv{o3>^0=ZYB_On&@^my|(u6Wp=-f!bI0Igm&@G6o17Ob-7fb)*q@^09#fZN3$ z)|;M<^xgoNP-M?Wh{#U-i+br-M(m4TXsdo|;=V`zep##pIjNutz*S<6HK_Bf~gI9N?vBKaiB z@0R$DNf6mc9M=S<6%ZyIP_8wW9!a$$F{(_Ru_HC;Bb9(Q(+6hQu5sTcWISyd)Goe1 zB1cpxRXA;Z*xo5QBR4n=QQ7`^vK`8LMkQd_Yd zVL4k8)f{r?EM8?X?re1l7hu#gd`&9k4_5!)pNwm(zMKks7wB1|-*a=rlNZ?2QmXT) zestuXUVyXci*c@Q(4J)^7@MSuU zdy=pe7{Ud}iRzcNBKOx`>p@>~u3QVxoT{s=UCJ1ttQq0GR!@WrZ`*C$M=iDd_ZNX@zFO{mXLXdC=CEEnruk z)Z{94;Hu7#9hj~~IG%AkbX}UL`nAsR7O4@;tE?BA9k=!Mx65s?kCU~j?T#q2TjA_) zD`>*JZb*`vVfw_QKYxuWw~g)UcY&soK- zSrzzVApKk<(wz3xEdG}xSIQ&!+&MJ6kRIz#f{BIdU_TW|W{me^-Zzc_nM!@_Guo8P zc07eJn=@8d$6nC|KC~yG6X5Cb9t7qdAKSi!&05JD0bBF|whR|{*2&Emo5P6>QMK*Q zS=-_=dy-oqV5!yVw=UoP&duO~)6&eX!mNF%6Ck_v8GY9_3FBT=*J%vxX)^rTMJ6zW z_MBJdoUHGpS;nvo{*s%AHT2SYJ0~f1x>a0F`uYfBL?`ExMY6a?o zpg8(0-tnSs>+E>y67Ockul(fFMEGRZcw&eihO=@rlR z;stPevI>mXk@^uQb_)YoeVQ$Eb#?{xidw)RZ%NBM{gi!%fOkFfevNbu%$I5UZ0oR3 zdz;F9jWvBug?ES3b43|?JBm9`lYNIXeLgz1Cj16`*}B4`lfSvT1;p$=z+bUXG{&3U z+_izOSF?Nv;BW7|@5yZ+>TxcZPA|}O?}o<|=5;Q0wow!i?jEZy6gMwPh93+OJdofY zv14|TfxZ2myM|mzMA?tL)jCR=57H)Awz4-GpvT;>O}Z6pHUM{e?a z;*OisD_J=GKkhLPzhoY}I)Pr+Q#{kpP>TvxI;&KX8>yN1$39C$JInjozdZ_W*QY_A z;oHyV+wUV3pPUeY(lQ#CgBaC^f1m{APKA)P5**&do}{)FF}|ut+RiR^ci1MnM+ns7 zFTDA})N5WnwSXu$?{-h$n#iq-(!wwJVo8QtmE&xCH?Fgx$U{w%5!RVP-Vn z9sq;vcz%y{!LPL%uOBGCamSGkonJArkRdis>G{LckLj~ELry*CA1Nj67b=Y?E2qSR zh(u+q!BVddlEcUT3NG#yrm2g8`^`+JPb@g}Vw2kN6xy@G3>EoT;`40@6@<+=1!@dC?I-Y43bQNMC_8B&sX==WtDlI5v4q zWpO1!S?=QrYF7-!Gbv3e4|U^QB&vusWS`)YR(xNvLhj~w&UCxN)kbMneiD4AvjJA? z>NR6OJwB00+yLp^aOV*%Ck zj!`VCSH{DGLcjlb+aePNzi~=3LIh+uR^S#`n`q6quUbNOKxBRgHX9D+v&l4GT}5|XO2(NcSkep<wMGiHr6DP|KoD+u# zkHs&Ej3byFLu4oS>xPgG{MPp?xaAra=*AT+$-Hb7FNwGos5r^GAL$^&vEFbm!wj*2 zG{yBQ1TVAq6IN!596|VD1{_ryFvAQ2e*lQKGTA6FlQc5TNYzgu&+%|CA}Mh@3C*WK zz{}w)E2|niDFZZu8W+KIq8gW!fP9NfYUYcL%0Q1GClx*Y!$#2JJu-CkvO1D+lR6Mx zT2D{Z}Shy~K1SJ$Z@i!QI_ZQxiUuG=iapkZ|>h6n28qjgBB!jW2cK@`Pn_SN23>9)VWhV?UH<6Kt>5bvsQW!D7>Mh9X6g+( zt7YKHc2V$b?s>hYL-+QaT3+5beNy0sVmfsLaOuSwka4y%$muUBVm%R_@XiBiSQ1w8 zp1+Pnekrs4tnn=yH7$wn*(%1t+`ieZH2DWy5M&D4<0V%9%XpCSuJ{*&T&zQF$ z&v~lD>^wCQI2W+Q)_tPVOyEC}Pjr!cp9OI;^58=j4AF^N_#jyr^<4sq2#;2giMuCrRN9%~q z<@X>7woH}?(=ivyDUS%`eQf#x8N+6%lr%UkD0@=tjv@ znr}@_$1b^!HbKysotR_s=%l`Cyp-|{bV*>x(6+j!vX>QsVrqlruGKjQ?$(z{WAC;O zy@JRRx0P9--+VqMaYC0=&{$%Rk|X$7rINEqOpa!F-glvr>>*ovCU|^4*eBo@CFe-T zr%9!NKZe#(g;MQ2zN$f@;vYE^b>&Tx0Wtc?HTw<6*agXI`vCsA+JGs*><8!Wm+z{` zEmGAXV3E5tW@`0qmp88JRQuSVa?8N{^Yyt=ZZ8I;Xt?O%Shb!B^*|K(Jp&395BT%*fOe2mMs> zo;|A$p4JX)Bl^$U;s~eCz4Z;;#UbhIa&wivpG##CuPD}PQB{5QbqM?*ru%&E(qUdN zjoJ7aX8l4JOGS3&rP43^6{D}U@vUP^;;o6&PdZ4QI6)M6q7qfnea#u~U+k(Nou!kp z&Xu9wOM^lv6?NDJ<9jp83(J_ws`6YLX>Dkg2bHvCAX+8Ih3C^=kW0xBEF>jq?-H9k z_Nc3u+C$%rZKqe);)0v}l0cI-n)lethonEd-Zn#JJ=r!{uOG9TwIL;!{;aV5avL4U zyw{7tI&ntFrT=8;SVGmg**COJ!HCml`#t^qf#1}%WXsA5>g9~x7j;qkd z=z+sO4+WeaTn$gJ%avCr#rnqQR7DM|-w-qydkPmL4>>o%WUDh}-;Xn<8aMhiFDLOj z@3osdrc$;pRg%3fO+hiXP~Gk(rl}h#P|P*kUmzK{wiYu)>93rqvvn!5#RPjY4d?2^7b_Fwa? zFLpY9*=TuSf$BO~uNnhw72`cF;MJTP%6fB0Y(Hb9MB>zTuHSPVfpz{4_JDL&pj|qy;NNFr|W%01$@K_-IPXLaCY670lW;3e5Balcs~hZX|d8Tbdw$k zAUpQGLi15%^f6HPvcU;N(G!!v@w0gL9IkUyUi6bx2)eY#kS7S>BMYHN4iGAJ@>+do z59H(U?8l_;B5ME#NzDt25er@u33aZ7i8u5~Q}YUD2og02DGLS|2ny0Y2r313!C(#2 za|!V*^a(Evs1ERh?gt=4n}J*u$?>Rh^DU8r$v=ruf$V6;Rw60$Y!M!%33)^2LL%0l zt=39tCVyID^W$Kk0iEB6g4^SL9grL+C^>$Yc^D2?Dzvy247ZdGyGINMB2{=b3`@5H zwB`gy6nQkX`XrqY2rEd9Ab0qF=Mwc75>wU!DozNqDG5m#4F)0i>ROGE z2^ISyiy>YNMu88F2m}Qr3`A!1sQeKNb`-}g@HP0;%d|1b>?wwD)1au-PbVcFbTN`! zFp^{>-mwo30`?Zm4Tz@@4p3_#7jhU4CDlkq*avrA`j+E30GM8VfOf!flHP> zj1*@`lm`w%k`J#DjdCxDH^PY=6O9Ki3=Xr8H&9Eqf^)(EMw$a9a~dS0D#UKe{ccLe zQxm%UjHKfKjA~#H>RXQ2wii@!jrL(r7>AY)3yn@_4dzkzr65moX83l4ON}2$O(;!l zaZF?&Pb^Mw&HRy=zUcm05D54wR+J!(b1;syGBNNVv8Bbg(;<~lJvAdVPGm(t&ox;z zF}}qF+>T2)-WcC4kXh@HxWH!G02l6|7T+YAT3{MWfstJfoY+B@Jy?*ugcDh}0vuUQ zZ90m9P9mrJJ7iX{`ENR8A3Db0xMVVSWyTh&hZbZf@7eN*-W|w+q^4IRC%|T4fjDw-mota+5n7D$2$M5sM$?dmGcpgv*KowY zFQyOc<*-O5&=N<{-#QT<0RVJ)%)~+uVm2ZOWTyq>>O3&wOQc+nInRY*?*au+M}?5~ zImd)K=FebhL<&DXi8|McB*DzX8{Su^KTITS4^=F=&Y z74639zD(Tzk=;Fzmpf7TEIhymG56b19`bUQ?^1!+m=xzwi0$hfUxu7er#yAs0-m)z zX#bDg0--#%raZW|{I*0Sj*W!=HBkFyyq2>Ev|c}weQH0lL& zFUf@k6@F{wxmINj8dc%OaT}7QWk;11{z}FNMSG`Z3uYXF`dDp=OW3N?l>!p-U7=Ph0_dzw=L#*J%8P`eKsL7Qu<&_FG@!5a{5bvdW zTBiEZzFIQL>LBupZ=yy{P_S(KDxL634$kVPrTXH7df&W;6N-B6Aw)V(RKBoAwep&& za2u^Mr?!(?J=}UQ_cDZV8`zF|e$Yb2qB^>SYD=Z2vhr$ymqrsrmzyzf#^w6#L5<<1 zn!}q$uGYqZ)cq2|<=O$9s6 zo~R9hjE#Ac&BLDcJZY_p&5e@6wQIS}S%}p_6zx>zjg8lhqq1eLNeWXf%A-pP4rayg z%8HTkI^3N)7m4$ylUpa7I+xapHV29sajl)3bE53Je&ch_3-M+UzD`=YAh&~IO76Me zmAWs|a}Pn=UXHqa{Oe1P+PRB<)7-+lC|k9K>#K!Y@Dkd=jN5C>n{ATvDD-+hnVQ8k zTR#hT4xID`owQfAHLJvDcQe;)mG#yqcWicc;E%LF&hGaQR$$&I5Vn@Svg~@(tADlB z#|+lODxw}{-dZ`(cmA@0#uGY@QwoJ^fcU8rehK+G7|3>jZ3KRVmY6 zZ6KRyas+4UaaV5*?lToZ^4RP{Zz-ciYl^}v@C0KER!Irj>R-kY*Tw7T!cl90pzNMi=b5CfURFUlsGs3ulwyFw60a21DKD*M%vvm&TQ1i|}q z@W=RIzSc)3rYuBeQwOdxj3O*1+EYh#I$|8CA}%(Bu0ux-@67I1CN`ZWc1!ABTc#S( z+Z2rouanzB-c)Qq03yMnp;cxPBD#?(x*;ZPQCqsSv!=hD5(@`NiH<6k1y@G1+Q%54=XueV<&Y;?D6^QpdpHU{PoZ>2ZG3 z@wALd$JM#niI8^@fe(*$KIEm6pZU1XPKU_Rkch9+srAT^_1Eaj@uts(EP(l@%Vlxv z*(@tgPTy)115{Fl9aO8`sms}_^R=a`byC}tEgRkSOOO`krcKu1$kw@smohk;)gq5c zgNP}e(iLZ@?e-M@ZS?*LkBueKan{X)iQO08V(<{VgWsA74mTUvnG-;3Ys~oT4txFbkoHI1&{~2`S*)cw z|M6+2PGW`$nqYF-kKK7r1YNeo2fGJzA(zBL1q%?BkB+2l;@zNnjE=&eOS9-91%>6g z5Jd~7Ze4jgCly{NMbm9reTQnhN44n$e1t0kyek~pM5St*(MIEt7UC3j@IQLQ-?I0yHL?0v@W$Mg+{A<<9vOhR8 zY1;u*=fHsv9U$wLgy8xmsokCR_uSzbiJB?M2lVuUd+VwDtSWPH_u%?x$N_BI1t;Y> z4dj;7?b@T`7KGqZnEc7U7%Vl;rsTMmX8OVO*nN4(HF4QB^Vm5CT(#FZyLz83D00KnROWSr#;zaq52gQ;5j<|qS5eY zq55q-#%tg@BV+kx+thV>+Ur}5=OXB(hxJ`?-5$)>lcUDc4DWrP*SSLX^=$h6h}ElQ z^=+;BZJpJ+aNBF^+6$~FksZpu4Du0FWpSc`cKRzBq+ARNsT$r?eaA%i0^9L{X0w^K zuvK=|bn(^y3eA{8CV<}a!yH?xlYwKz=yC9(r;Zs~0ws~Mguo#=v0Tb^CNo;2Njd>qJH*+%P8@k-NC&PC%@ z?$zQ4W#6XiUv zEHrE>1S@zdkLEQN^HmiT`ys*F5i@2R&|@VI(jH4SL+vIdq9kK4sM-lF6;R5T548&Y z{2pnjR`%r@!?|lo#D8t<7X;qc{TYw1n;eOUNid53)!h|k)x58w8d-j8L<)P7|4Bb99q7>#hjH4{~y_6&W2liyLEEi{C z!(2vO3*5X2%oo($Xi69gbKk6{qZsR#pgeaq=Q8so={xhI5}EKd<4l_@%7j897)t$u z1R0Ct3KwQds*>!YHc)AC;*T@SYO}^N)S|Mi*26M;Qpw}G)GHXZiiU7?%DUmawF*jk zcuASsjw6_h=Eoq;ll(cJa;m1SEZD2Iy(+4UCSe-=Fw6%?gHhDyIn8R4Uv071-LDD? zLEXT4PI?rGbf6t3biizNzbSpLZFlN`r4j zb#uqqIDNNg-4MfkWWXf*uqVS%_4}DkTdoGI>C6c{&1r*onmbdy6sP6`_}bluc(Z__ zN9FvGj><<+}8;HEpSbp;z;gyTc@F zsHNosOS^777Ko+6lq~w$cw#gB*PQQorrBHq5xJ{KAQ(>bx_3W~+i}t{4aad%au@qa zQE_zJaa~E&?{8^%I_z^^aWXFFve{W#XRW`yUbnhDv^hFzz8^VMSAc<l5L-VMbeSI?;Qx@PCsqH?!HaW3;K8;tp4)m zeqU0>;{rK0bG+t?dk-7xKKC^9K=@C3nJDUltqb#k9ua&&hB|B%o-7AOuG}B+F+ZGLc$ex&`oW#%e;CN3wxa=LCpeCxbH#w-NdayXg7O!cBv6 z{#pe)7|GBg>_fHTb{TodmnD51Y2RX0vabH2s14S##TiQ)$*w%|Cy z6;x1&*cB)sia8nPJd=;l3`8IX3+sUp_!=KHkqF1AK2$=Y5V=Z7g1jy&to}}sAQGB7 zq2c^JaZ<{(?cs3D`Ls^=(|6;(2|kAJ&J#*cb*TfMsWi5u;8Jq+X-gHPuvMj#mL?AA zTYq|3yH_Xe?Bg@mv5VPD!=@bl<1<$rk2!ZsW!wx5GEYA~vb`0T@d}R5-YYQWJUo@P z&@q@u6Nn@gKq{LFVrqQ}DNI9Q6*HFaLNg?A$s6UaFc|1sm-q>*ua+ zX8xjH);1n$VambeR!$MRfg({pKjT$W9F1aSGS$hk{rt0Kb2Cy3#nZLQ+|!CHOKW1# z^4+R}YMWXE;ww7pyW0`qH9J%L2N8!*M@E==_~wCg3%rOh=$d4kcoQ32dw80=`^Tt9 zC+8O@_>-6C*YMx|uZTzH!$$OfY;?V86)o>fnVPu2(rb(~GLKuh!{$HlqSu0uvfgI% zmUFy14w1hWH3CQL&!c-5qjaJ?o*zn(iJGONFYi=t*P%sU$6k(JqF9R*u3I*FR)a5c zxm??%96GM1Ci5eq`ruVcN_-+z7(4>(s2KcUc=E8Ah!FBPqJM#r23`X&K3om}FZ%27 z%&W7^=Hks?L4>N&#iB)vAA5pAF`(hLYnEc;)p-cSrDz94i16O+tmF%PjMRK;fJCV* z0TS$jOl#y}G8N?hmUGC>JS~$d}1hh*wG0 z@Yjhpa5o9Iu(k1aeDC7uq3L5DpdO+hiT5wg!3_(pp23+5%JNyI@Lj}S4hmeSbM`p$ zaFT>d?O$EF-t{2}9}nbB!+-c4aAo^~HuX~Z+q8Ez-5DGqFZ5rDG6@(5XaF2Pj0fFR zegx6~zY>gog<$I^RkVZKKT5C(Ax0NG^3w)UZF#iUW!2EEu=Rb^OxhahUQiZhHG7C3RF3L^l zw8O67|A&z{zd%NQNbZOwRFH_pz^FMQy1v|tqlnPtnLN4;N;Pj>5yQeq;2khNT)3Mp zs<5nmVIAv!%<+7$y1sSuaddNc2?+G}vI`3gvhwu~4!7_?j5kgU@k?ao%Hl%&SJ=Y= zCq4k-eE`b2sU%D8WHT)DI6`&`G%^qWIB)nM#}5tQz2r6%JA~9Vh!3Am3=WqxZn$Q| zh&p|M=;SksO2i!Tx3xs)kz{wuAcxCfKY(LKbi2~n#kWTdgT6d zW@*O7RaWD;Rp7%8R@<)5;2)aEZX7#k&jtGtBdQ)Vj%+#d?-EgcsACl>-z(iQHt8N) zXp;L4%-bYb+T%~0K2*@%*DNm@*-iT(Do+D{U2oqIEqnPuo#47O67PSs^)TdHIFq#WI!B1?8^QdZjgWSq%-fEjDdUa2=hdJ?%K~Bcmhztldo= zV`CF;gFSuo5>utiD`IPT8=J`jLWjV;6U3p@&2uDpH6&R0i=>9f%cbY}tJjvdcePX4 zXIp%JziIffPbD*1y}`-o0z$+;2y?}HhW9H{UAs)jn(U;Da;^6h z%DX$lu0!hJ!dQtIi?ovbeiD|d5H9_;vd37bbFEWT8Z;FDO%3m}snzn`I1BsJ zhhVkahp(R3UJ=1b-ppTB=SR3hWB|K$bl6YZIE^H~6pqm3gov!DoEUC1G~e{Vf>;z6 z&nizW;}5}Vg9SP+HbzTpYkMcozoJPWh!4d1C%fGL0xta6fV4LQi9P}qSC*7U(yZ&K zR;~he8&0B`txER0CY{P>c>V50L04=NyrHAgmIN7d@X$L%>L;$`Jy;}>cl?idLh=N(LzNXj1< zg&b%Qo0i7Lp2?j|lA05bP!{9vhXGHE1O)~BD@Sf^Z0l^p6DaNLk7FGeW-lqt!=L0R z84QO%|IT^h#~$cXLsQHv4=O1+K6d)JtICy2)O!0_8|Q;j zd-NhusWHj8^5;UdIMQWEm^3mJ{FbN`;}+iQbZS&QNfamLAL7pk>((_z(W-RHLT|E! zZvWW>`8z4tx&?{`JBC|_Do5)7G>kJ&FikQ~v2+bdlZ+O~3d)Emh{_YicPK{muc{U! z$0DO|Y$8J^Z~8a;|6PtS{z<6V53J{!Y;@!0Q`$97MkL-PsE{8-S~)o3XuZ7ec>N1e zu46}v^x#`WGf`cU7Ce=V<~+N$N^JB7k;eF^)@izD4Pw|y{)TTbCM7PYDcDak3W(Ot zwADV?&v5YmKA!&Yfo@2l*5STU|A)M{jEXbc)<&xWp$MAb1Sdd(TS)Mb5C|S25J-SP zg1fsH6k51z;qLD4?(Xgc2oU9ai|*b{@6-F7-RJbV_q*e!|7B#1u6ND3rabeR&vFd( z!SnkV8W0f_72+Hj7o89rrs9q;f+fGi!@#x3V@stk!ow*p`ooD<0Kbs~IMF)fiPlBs zhu3TjFa&5ax+U0Lmbl-^^?snrjLz^o^&w*Gr$beiHE4fg-^Q zG{p4Lw0P3?HU#meq@1aoi9}X>8H8C_IRtqb;KHl|{GxK)%JQ0mx}1iLro5x5(>*mb7@!U?oSbi1lWx45 zu4^>$3~}JNuu+dV5NCm1^9R%cG-+c8*PA5r%!w1d7Yu)gN0>&pXQ?|k_w48oe!pl-rO!_}6^ zJiOKdBcyy1M{V{&%=;i)H%>x>q62%9xzq>iun5{7dM{5<;zl3>m5Ee6f`I1uNnbRT zvErZ)KJ*$Mj(t19t^1;=zqgsTK(73~T_c2;S>5dI|UJ1!Kk2P3>7G z$QF84Rw|9B1WEUZ{l73ZCT~edGFgbO$`cyNJ?|Z|QXVr-sxeVqejPxymTcTanGW4~ z@CB2>x8~Tv)|1j9z+A%c5M?NAt?s;HRI^HL9J+Veh%gnpdGM{yAl3io%4nhkHUbyG)Ahv_h$8Ubkz^G4%dt}jaN?APnXTs%$F`!E*GwrtyhU`H}_|5 z)*iI&9`EIRDm-iWeDH1HN8Ar6anO{A{UaPyrOv`6Q7;TCDMym0k73s_8PsPhKQ*ER zP!o%Oh+E|J_JH8LN|0gXT6q>k^&pv)6#V;Hp@C(=B0x(4LajaQ;zOz7H884JfY1kw z9$CKcMr0GS1(fuj$ix`-Y%OSnh};O+=(96G%K0q_ZoXv-ks-(zs6WS+TU{Kto!8k8)gp)S2ss~XEtwLUsiwW028Px%w8&p zDdcvvbcAM9*gKy4Nd_tD5A<>};uSrF^Pi;R0_6u%38k*8zNub=vyBsv#*Lt>yHljY zA%FP6qmhxaoU)jVzV6)Ns~yrjs0IWBg&~dqOYrVV`=hiA1?2xdX%_}eaxN~KI_GMF z2FjMuCKv=M?b7SkgbBeK866uR2fGdqPs~kBIdxRe&aYuDIxY{buWwGT?k+%gKF#gB zoP3@I|fGIOA!l6X-p^A?1VP zYj3d)O=Hf%!LVm#mM)-Z5+>LQ%oQ&AJlHPZ6OdP>LtgpT;+^phG}`tUV|i_KD=FSE zNRjvE6}OrPRRC6q`rQi8GcK(#%*CpkozJ*cZ@Np-fjA@oMs{pNmYng|&fh=&;I(nVf$e1D>d6N6 zfca9pd;0}ad0PgB5r*OhgvUJ5!qst#i4}E-LL>!|`=n?1Wrc|52C0S=y=JLkvMMMG zEGVp%5@;4|gkhHCw7GQDbi4MJ_V;vJ50CVXn-4}$nax1wrbkVd=2vvr3>Lb!-tCO- zX&kJ6Qa|4OyuYFL#+gj4dV z7sZ8><0{Fk)%JVz4*pN0x!R@ZSXC1|NRQj3@9=2Mo`lM`_CFPJ>Te~rY#n$nCQ4ox zcHg@>odR~`5!2KvpG}(op$=j7YcomKK`dU38^OgZt;jl4WIU7}{&qEQvQqa`d75;q zu~MDs7o1O+M2D(P25Yx}`b8a1w0V+kc!aKP9PhY`YZNIpd+mYWs@LSy) zdHfy{>{N4hu-M{9^}N3J%kkz&&ijG-x^HKPD?N$N8|r_2J3ro87-(p?xB#KuTSRw7 z{kq|L?P@bS4`K(yE`eKp)2`2(HNRnQbPr!DW&!F;Av&M?Esbo<><=7q*Xt1+=;XHp z3uw)|uoz>ns4uDV)h`xK4zW74>lXfkx&2G^B`r+ImHfC4N(3o_68_EDVML;!oBk^Mz-F zMG2JZMKQr@UR|Qx=sSuPJ1UiNPdgkAoU!a3EOg!8d)aAu5Igx82EK**69xFVI){dl z!h)l0V`2s30~4(P*v~87I5RfeE!RLZIXpEo*xjt`VMR_=X)S)CbFqF?b6xv~9+R4~ zR@=Uh16lP&jbjB9ZBtzWm?Pf7`N_*F8}GyycK7xV4nG|o1KLk#=U={l`~KtS1qcO$ zT%r)s1VzVZQUTHfApUemDo&y(xy_G+TYt8*D5WEiT29oLT(UT|EA*axwn|rVS`RWp z#7UN<_r>yBY|s9CK!?F7wGe^(S`x>#-?IuYI1y-Pkzn5kWCqSNP_V1%i@hti7#^=1 z6B5c5@XQJo(APS{e-2&&Izf(fyAuxyn&3#opWZPk+&6gSVimTm&Ov$=1I7fo1n;^U zS@?~9hD2`gpzNcKtknysv2PUo&~-JrYvw|5#jr? z_fZiBECZ#G<~wQ!j*r*?Sugakn}N>~&8uE=@KtAoS)(fzOd6JF@9Af#Yq>rKWW6>x z?cu_LL?(2CG7Fhgw(UX<)-7umR_;U&j(RXdXEUfjxu>^gV34mEJc2mHI~ryjnLrZj zm}D29n2w)fo8^;{hnr(iXq2B(>=mSwRvKBZU8hxD18)eftZGhZwQtvM>U8h!?jNum z>TMitnP{6CnUWu$TYxT2%&*9-^=@o_nCY2w+k3U$Zv682(y~J5Kd)hob{H>Kx}*Ik zmJRqjEc+KAESbu}rHUgQX0_hRqLq%IJJJas1Xs_Au55~u;xa@9mY zVknpBA-Pmun~5+6l-KGgQ}YfS2bSyqs`8pOBtdoi+XWp1gM$_Xj8tCp_0R=lA(huc zMc|r&VKHG4XrxATY%*4S;>VTVy0UtD<@-|xhhB~pB#ie}$GJ?;$W6w^yDm-4g>!7YUdi6seYHQo_(}FS9CzW{ z0^ceBIbBxa39fIF7&@^KwbG$l_1mwvg>R7DcqZiY?B2ewcd(E6EAk5grZ2iLSMfq< zWVIcYIMcdm@3GgP+_G4gilEk-o_%R?H#kAq6ND{=uOpZI1RnA9Ey2dCbV1mYG8!u; zc($UJdf)c4dUFA|Qe1(FhCkV$- zgF^!YhAS7ee@kHA$-@(*ydVKX$)=E}``uz77 zaMqeK{fYvyp0OVhXKxpD-69FuB6ueP%QRMG>YHp8HxwUQXt&m)wQLif>v?(A{e{FJ z?utsJyXdCNhgfvSdXNdR#}Tijb|+BOUGgN+&Rl|#TW>CTQNuc+*JvYjmwoP~XD<7) zly5HkakSrC@xQNK{@l4TiSSCzffV%v1OI_guN{j09*h3PU(bWmKpmjQe{w`yK21qq zph7X+aqicQG5KGS02Idv{~t&IBI`sz0&sd}c5Z%Q(GPP8cVz){b8&Nhc4v2QXB8JR zd$QjF#zJO+AH)Y9Ysb$96YI24Fqt$>UnncTyT|wgqleukT%3MP-d`UntZxrsd3S91IzxUT2Hx`^W2RbY3pV;L#6+t4 z{^HkCV%z;ibI+M;Y&4$_-CM1R6L02*0C|Uj_4xx8Wj4;7ccLbJX{YZovdg6kQWx{f z3@mJwv*x4n4;H6gOgiN3i6~ZUt6hlq_QKESXWBCM*YgDVj#k1W{dkN8sx5W~xuu^= z3)yUBC%1g0|1sLUGa=K{=D=fIE_|c;;q1qYMxobQdvnVL1&@?}R(_lEx-H3dK|!SM zf_el&xM1AwM7Z`4oXUH)rYNW$A<)79hYW z*Lz*}IIQO3l~cFg10&Vnoo*h0LOnsIzj)V1`mbX}62%XIz@$EZF0#fbN;O=ld^TZs zuu_v~sw;mpP~rtgm!Yw3|NmHE(hf5!HttPKJXIp%p9Cg_!B|Lv$;#5I+A7x?WCPk< z+tAk3+F8-jQ`Oy%)i+c=*grDbGF3h~I^Hukw9vWKztXnWv(dcOxzn`Qc2M`J`MBNX zY+$DBbJzFbBk-tK&wFyd0T1tk^8&} zyp0nq7D@rWl zZ=-AwZh6? zSArh|pQfj}J4_NA?7;_HUptas@w+vm!&)|2mFr+Pn1{bDzDO!`BxmRLMVY#}C>q#$ z?=$~WR$31V+ec$}Ms5ZlcV3Ir(DafFVI^TJVOxllXT2I3?G>;57oji}d=m@?WKlt= z*9W^K4Xzw|ABYOf3R3#Tjm08s&&PXf3S!SZkZ$~y96-tQxA`DQRs)3V*^UTxL5A}6 zzzP~O&8L*%Po?`vJx)_cx6Oxp_W^)|SSMVgL-UZ-h&gB6&;}zQBB#}?5cU0p&9S}X zM{7oRHII8RW$(Mbul*SUdip1l_LyfzU%qAkXei&rtkk5gaQ}JFNdo;)od9-JAE=Hw)Xb>R>DXWpGqb})P(oDq>zmh$AxMce34OYcW zg#{jiH1#UJEd1QhAvVkGyiRIwr?G6dRTrksg&9BkQ9qW0!`Xr|=5m;!){Q{_Np>2evC^bUTn3 zsV})K#g`Du$WmX{J`z8(LpJX_8Zb6uU^X&SR3-?ytlnLxJ_FVJr&eix7irbwEq_J- zQGK%*1>?ZErH8v(?p?yn*Zp7tGg}W;gfs@$jH+7`I#NF4I=VP(y5i|TwN1^4A#4wW zg81NmSgr!N;V=~^U%$vWpI6?V9vX<$jC9q^m>lK2#DdrM_ma{QY^vhP@=0#j6H~F{ z;k2~3w*n9fSxevG5Z%D=DEl8iqXHQ6-226Of#J!>(vSPUiTqZ|Nbl4iGPjiqW*|j= z8z{V*(S6!P!mU?K(ad6c!XL=h>f*+fZo`=8*m?$S9Wr`UA%Rt zwUfyat=C=ps&+|^A2ZMKevWwsf8ARe#Lo&I1Yu`A|-^+b7^UPP3s?* zIo1`^a}6+a3=Vc%W=eKG8pFq&P$-IUE4j}7z3pvLJCcUo9^-_(i5cVd(2ca>6uzK%T4G~z$J{VsTxb8=i^PTw zI}1H~mj_N(9y~B@Zyh&(Ya3t9K&%j@u!vV-q%WZMq(oOPNgpTxR0R6?535~bF;kyd zfLYg?1%d^$9)S+Pr4)~W*c5oym|z54l1E?|poIM(v_DhcI`?e>N2X=Zpn1w`JnI#b zScCZkc~)%p{zG2QKE>gkz+%UNf$?}7LpvuA&)aVL-tS+-;Ba4+pm+WO;f^7%qSPbe zB3%p;rNiP=-^92kC8y;mWgxOra*K7dtjn;9N~)>zW$LnPnw-lTq^g=biQ7~wI=Tk% zdV2Z?yN3J5rU)m>XmRYP2WJcI7MI2=dNy`EFm?~jv=$Ce-W-2E7d=}4@`L&t&@%tm zV94{ot7R@b+ToA5nnh26GmZgG{qc;aFV8rwR0d-cP#cFnQwOr>05J262O+^wI4#1w z%koCx;EINreQC_(?h)x8SNe3}dB^7`O)I6hUq86>W~cJ|ur>bBac!;fMe}D@Jx6O> zH<&Wi*wf2j%17G|9wHd1791MI9?EH)Cx9@g8f9`dO%c(zd-^9|tk@@206Km|2Tqwz{o+{t!5cSzk zPRzCduS#KeEIRYlgb;@R0pRo(VTl%R{C|QadZM@u=6kD3HUw&z9w@6=e1@>o{7Kd#ok2CYk%$QqDnnVfoN95_~ zeXY_i4>rj>>miYPTU_h^ivAHfj+3^<2M=d4OGy~i+s91SPd8XU)G*vQ(lpu}ZW$;a z@0q0e^ihCIx+R_~BRNJM_0ua?IvE&WlV7IqqQfrwoVwwqs_F~GL)B;M3A!=H;1%E( zQU!jL&dcqAXsy*yr`UiotXda1qjE_i3mI^HPx!I~cL>PFgcFpuB4=1b-hbfWak4I& zIk1Qm+!$|B;|UXg_2mbPk*J-!je&>hC6&ZFz*gHQ#4ijU5f~LL6&e?w5Q&IRj(roK zo=D^fK@!_?$%;#|OUsFb6)7reacg+$YHv4{x3reDcaU{;6ZiHJ4h%MqT%BSfCkTt6 zJmjSrtU6=(9}qJO|0fdtybv%_qCYeFB^V1S(O;DFBCoij7(#+qDp6k9hy}qUuB{Vq zXsT%GknZX(>g|&p7%Uhbc{VoQ+&VQqTQ$ERHZwlCD!M+nx%GIbdvE{IVbjsE(C5ap zbAhjw-@mS%R~W`MIxZ!X3U0E~NRS6N+8(vLc!D=nUM zdQr77uC;bQl6Tb}MO^DLWIQ!V0oNFi+f4Yk;9MpQ20^Q}id#fnKG~fDD|JIEaW_-H~*(x_7_P(U4f)fB(|3 z$=XyLEHpwfspM)aKdp3zGQaPytvb%F`+SuRnhbD`$w7L6bz304Qtd4mEYsUyDEl2WbWMMB4(m7|)ooreR=>4B%Om%q;wcu=4*^fo4@B{yHB zwn2h{5ip}pjs&cm9+8?$&m*6gR8W*#Qkqg;QJho#=MOOa5q()&URhns!)U*9`TT*) z$8|aQ`gU16Pv-Yt4!%|^!!Kc_zwc!UD=-%FWeGno|3H5TaX?TwR#-$}2vJltJRvBS zFdpHZnwCtEfyhb7!q1B?iYUM<39m>BP4lmcxtm>^*z5yoENu0u5AG=MN*};#j~nXo z8%Y@(nrs>v_nqyWpXtM0=w2ON8CdGy>DpVL-o?E8`RJgv3>N}M4j0gN?-n9Na5}ab zRXSf>1BMF})9)75-JyPjk2N)KT><56f%!7q<$T%m($GiS4haMAI$e{kS$aexNNTJ$ zx8;to*vn!|&eXmp&+lHtYI@zG7-G(19GCtKLrR4!O=3r)N7p=ysDMc2*1N6=ASQju zE!*3T-V0_Q3gvai?ASkh2mvEs+JL!x`FdI5n!$sDDFZ{oL+$}ETXaBdLIUMIcydHq zx>f2`md`0D9E1REBLmD|=32%D*Y~MAwM8Z5qPEP zegOUeI35#VUc_NnV|E?MNN-7;s;<$8Ga=3BG(aZb=z51q?X(g+uqN%SWZZ=KHMUvX z@K6K+>&L#q5<(uQZ1UWV=};?D`S1rFdjYCiiw{-!zYVwYkTXX9!kBG1zHq#YhlzaR z1qQ+O_J>*H;9$CkhC!hreo^6neBvcKE5jovJug4Cu;`CZyx?J^Ux^;rU>h*s#PYqhv8z4QSpWuodF2aMKp()ImwjUWp%6f{eb@=StOH^2oz_VhzzbkeNIpz2-y>_`7Mebb z-XT#tI7WHv(IPjrDU}={lPZ6WM=C>MaV&bwC{%UYh9qBBR%^U6az5UNSzF7=AatJ6 z;pTx)52>ZlFZUhdNRIg$6Zx`E0Isu(Z(x`UkuRfvxOp5|qD&HAig;Rd3_(_gNM25E zT0VbaQF%^fOm##_5mp*b>HVe_*0zSuiu#_&?5ZRmuaVKbEXRcaP`f=*1tt6asz%vPFi(!>+3F+NkwAXnMFp0Ine>jF{-2IyR{mb@T&d_t}MtZbR$<4N)C3er7?{~fL z1^;0(F7V%K25F#SxmQ^*IAbnD*jK#A2ub9LUtLEZZzZ||omF)BQ%(r)l)?Zj;NtywFu zeIh41p;%!z9^tih$|!u{F|p?C=;Yw;=59mhVhp?|=4gQDWh3CL7Zk2#ASxLbCmI%_ zW9F3{rJk0gkglJdrIG?K$WhKr%_}d?|5&YCSyNwE)X>}%SkYS8u7X=)@rY}1kY?yA z64D8D>0F@QUz}eu$H_nzUUGprBY&f(_&7VCMLOXS$q1i$?5I6scF_?wWT7Kk)hd8_ZcAtHoW*Luh1!O)zdVx#SQ7&@oBS4!BH`sb3Ku9$v@I~7BITe8* z2M!J%skpwR2O0TYZ(sLkDn3@>3c57$)OX^h!^B!gVF{G=4l+iCh` zG9~Fnd6g#hWVKbzzO7B|6$OReofhpR12#iF1=Rv04r9|UvyFrOi=)fEldtBUFRYKn zJRZW|J^bsm5c&U>^Z)t&iv#{hlO*m{B=Hnv12Ec=j6+vsg&e=HUl*|ppvw!oA)`fk zh6dMxy{nVQ3uh^EmxCN?2|7xy+T`JfDolZR9Zgk+ub_ioCvQv5os{R^@c!JR8{v|l z6Y!hDI+%>t?rE^JB~S2LsB*G)WVCmABgvL=TBPxx(s$=@#2!OQh1jI12^>g5ONtz zY*qAzmT->9){5_EvzlpkMU}Zv)laxaYsGNqrhKdUbc%Px9be;IYy~(^i9G?APLu?IF>SF&Oj z?^LU>49wgDSadt5`v+0K07uO!MEHu#g5Xa#|n7r=O5}D6cHTm6Nwe)l7MhZ zj*gE_PYS-e>|uTR+mNdXor6_(w;Ykc;TdMR|LS?z(k*Ah9qo>9l#hY!TegPF6MIqi z5ji9%+T>$M^rsJ9@t{qUmmT9*(JGszJN-5Zb6P3*64#&KvbPmWrqiGId6^<+VK32% z%jJWbrk0MBrzZ4`ufDe`jMU#Jgd{9DB1(kwUP2;sfIJ|-%!do%42gY|9TOCHx1dm$ zIH$BM!mBdBqPDuGv<{Z5+t~K9qq3{Iv&FAxAh4ltsC%@ed187DpxKrWR+11l%44i= zZL>08322o7jfeoe_**Ra9ehw`)c*7L0o91w|E>1{DXlY!B&wbDo-dubzISo+cxnr< zRJ`#dpq_z`0w^It;g29-ow6lP@Qm2wpnRRS#HTGooH z!kW4khK9z>oYrod_Kwu%o*|09{_3vbNs`h2!KrxyAQdhwEH$oB;5gCjtm>{;ZIW-_ z+1uAXtUMw+p*=m*JZhWHNTL#OJ;?5=UT>oIc0q4J$7<)GXtlfbiSeo80d0f7)&&FG zt`e?hBRmaV`%w1?E}>~hN9ZV$MIRr@NOf;IdJ~Kh+rwdXd-{g%{kT-6+dn)2-L|yw z7%p3k&%v*=6>doOO&c&zyj5!`$6zKRm@1CwPxef;HcBctMrnfA=&;Sj-jkfuinSS4 z%W)$8?nGu=INl5cPs#4CyCR81&$P+CGqmWG7$0@#M&I1%cNKE$p?T-deblc2*i`BhMr~^gSC%y8A~4B?fmL%BXdWtHgo|a6gFfvKTcu z^ZQTjpO3B3nal8`RWx4ZOJj1Vrf2D<+MCMk-eP#ZbZ6l?FCS_E z@N%XkDvz50ZRy=O#az)Xi<~{hs`mxBHTt(BH`i8*bZZt&&tm2hW)4oTu=vY>H3s6# zPQo~-h&rcEX}I^({vrWvAu4>`6WFNtEx6rd@owg!V+~8$u zx9;z~=9|F3zcXcTp)$QMfEJpzc@Hz_>4OF7M)e}z!GrVfbC07Yws4SdbfTf4<6vT7 zdcdI==qR8oAL|cby{rHV`74*)X?wfRZeQJ&F+ev#&JGx9{e580e|#oX5sZc89K>@) zCnP5zQqp4~oJkoe5KNAo+=TqX;=BU(B4F~(R$YTtTGbfeT;Cek&e~AZ&C*-m&pcQ> ze0MZ=oMAF!nszpQo@TM4tTSerdNp~AVyC2z6#_;wMbGdL+Ssyizje{^Dv2POqLpgk zr)k^d)i9hN*na2K^Y^`)nB)ZSej*XGAeWIvU%-b;N zt}sPk14sM{bpG2BBO@&?Fr)?6!V@yBSoC&$F~0#^;Q#wxVg*nbdoUJ~hBZ4mw>T%l zvaqy{wYIUyEWEnCzI8COE3|(!_vsAlMDXF;)-GyTLuErjvJmP>HcAeTRF4}K z6yBZQkC9u)c>BwFiyGT)wayocK1r~{TP?&Wf%3c8%x-mPQ%45Nz>cD>TtFTGjNrUn zgYylNBucMS8t>gZRh96Wdl*d@^F@8~U;B*abS54TjM zH$G*Zyi6O);_MMpEvq9Bl_zv*DKJZq`-wL1h5|g2+pu=}oxEX_9mg5CfKIL+UT!cq z3>+M9Z{I)<45)tqCLBnD0bx$?#JE_@h{)9B%-FE3tcO0HL;B#Y(K` zxFcqZSe7~xGKp-qS9tdXEDrleS$+C#w)R|`Xo^0>(O870rI9+o!laqHF`Dtp=<}JG zc*0$B7h85vLR+5{kIG8lU7O-|gkNm$y|5H?(WipwxRW|iqd~yfMjoEHsMP4VAWU^1 z5(jo{FbM52C?H5I#Pco!0t#nEg=0c8q#^nbaUlWVy8613H{hRrn@1Ha8rJfbT(u9Zx(rVn2QtN?c6b00vBebrWi4?-&^tMB$G} zN{KU1Pr}Md^Ush?!Ntx?0XfI}qZ6Qd6y{@Nq7pz$9_C_!(FoAdFxwbAxVrIs>!^pQ zu)7FR%iAV}LGIzU1;&t(qIJ&c<^1f$dVimj&qXokUqZvKd}}Z0J(%or!?ojA{f#=p zi*R{PVE(M*n#7XxYGkN?jhU58Xa+O?Abhf*&0!Umg}CLzL>WzYca$z(Jp8%tSarO0 znbHnnIe|;GPAWV^>>W;^E8t`kORMGlhWU-3MGdr6n4O4S`Nar8*lJRQXkc|a?8nA- zbZCC?NAExc!SRlC;f6jb^f9_$u#`EWlXM`v9 zeaKKfB)-iM7^`(c-w3=iebAy=x|R^CSL>OTfB2cmN|^s0)Z+s`9xB-T5h|{qHa}fp zuR>9gk#na znwkXSg3S0a2UA8yiBhO1@u#RTW&n!m(qi*69@&-8N&``Xi7uIVZkH3#2k&yfsl;XQ z$yvqeW+x9fAyExCfdvcrL1F(v{Q~Q~)G1$a&HYTrTd~iz2>4hPJty8rR9xpudaoDt z6+LQT)AH-6zm?g+(jMoSQTh%M1nu<9hiAX!+rSLPGT;4XCJr ztVm6oNJ~SDxZ1&`0o;Eu*yCyM{LNvLBKn_r5AKdF_DZa|9rH^nb^b-v12e zPd{CeTU(de+>+YamDoQJ|8(^DExz%xtk|c8(1VwIjgps&v zV0htk%jN18p^C$)vq?>Nd6z$S`rna+aoB|>zNnYac9V33x53i z-G@fEC+R6GiIC5IM$a^wSpIMjVd`j>f|lG|5aF64;^9N*zCnfENlY!(1clp*d(#<4 zchurz3XSJHO_ti*qTd|MS4oa^?+HBSc-r_B`-OvI z7^vxdJXqHkI8-n~I1xIPwNSa#IzCpnZoer#7ui;FAXcWZ8?(~0HhkKDKK*s_`y%jA zyF`BkKlO>=ty&$9g=Q!0Z$jURIn~?Th%x&G&`~J`?RGeMze+^4C06*{<>s2*d_n&- z0#Egohh8v4yCthx`>1k>uLRX22h=joQt=@Yx&;EiE3=St0NP>)(Ez6yb`xANTFqFBcUT}ef$(7Jj2{HjeLA>B!3+}o}K<@xa z*;}nZPET{&%S>51HUJHpHye(R4(btwsK91e6tEfQ$SXClendTmT;Sp95fV$2*?tKY ze}%GHYF{T@xL{)Tr89Hpz}As^U<0x);pA@Z0Cjh9eS!mldBL5$eT4l2ox|;dLxlVz zZ9L~0=*+pD=@tM^Xsbyt#yj77ktxdTN1?3&gE#Ykg zz1;nQgJZ*$UFkiO^rP_c#W{`z*wXq6>l$=pcZ+2wp!ua*|;&z!shQ>@yj&O zd(d4l`#;PL6#qG~J;SmK$bGHL{;D?ox$UqyKp6xim~hyTTcVwG`kBBc-XPt`efZmg z$z6%pn05{7g>*6ufn@*-z$OTF9%yErqh|I3PwfW|FzF#!K#S)I1H*iL?498O0dBq_ zQ18$XBbC6ISmodd-|$43e_UF+BqmNmvS(5*G&Q5RM2I%0z&*dRsI;!0ExR(Wxv-(V zgQ=;tst2pKb8v{DyQjKfV0fxyv~@gpa(bz*qH;cYad|6!wO~DQbNf@^Zti}>;n5ez zljPIT^RL&Em(IEt=-trCZk1}jxYg)!GoB@G)bwSmA4)7|CND-x2Q&T!y%~!o^+-qP zGebRc$xWK>NWLfT`s;YeO}yv#{@ap6d&;54e=0cym^&s0c8gYyypV1s?g8a5`&$2! z7-colnU5q!y_;E{_Av~6;(rTfxuH%drH%IPk1)$xgo^dnTBJIRaXm^i zLT^1l*!?G}WtcwE550N7equIl&)wvLqhxUKQy>9=Z2rt2cI72Qb=@So1=^jc2k1 zGA+z zX795%B0(o!0l7dbI;k=>?t*WmPA--<4xaRG?&dyL9PXupN zWSo1lOM)FjF4Z~P|4wE=u4R#Ret~C+Z-{9^Ijqv8!ML{0p((VwrZuUvvA4N9u-&!a zsAW)PczApwYjk9EW>$P^erfs9>f(m|RzKv$&bz(d^-m9vI}@%Xz;xhC3BVjzBVv(- zD$==(7m=&cum$D;%gA=5a~)iS5SSt(A`cBf$K{7hO+#r}WFQmFcIr zhD?AQVGD=njEz77Jhul?AAGyOv$TWSf?d75-?)4DWBCLIN&CT}5RKrdXo1i$+lUys zNW|;7cEtZAv~;Y@T=AUZkOI4+GSSj%@%;3vy5{PJ_@wU@MA8BQ$0nU1;T%xZ(Q}~^+Y{G&MTA5Y`P5Em7r3l-+ zi!<>x92E}ge}nbLfL`2@Ta|oE&h;>C{+C&hdO6uI~7Q2$qk@s{A#PW;x z0{j8wJ^gj#;*IBjg_nk{M!hY_VFEVm?HlM>ZF>nr2jsc!_g7Ja>kIg*()#l3n^}o#Le?oNrd%f4_Z}i@Oj7>C+;rAj} zgRhKDvMcD!1FrH)ksde!i2ooP2qfh4y9cU`BID=pi2e7t(?-P2bFx220XY2%&dDfa z%hpP&W7KN?+yjy8<$g#xSLAwm7?P`l9NfhxBq9J_DKNOpKuZ7QCK_QD78Mue$w9!C zAavY{%KC=-G8r&d8x{l)yS=BkS-Q0cgx5QY)h{*J4#-!bjrB}OPPK#aKnrb45-aUm z-3!~#cH4(>H$RCVx6RBQog(?AaZ`y*?Ie*D`aZ)koTB97KK@ zC4S51zeI_*|70UUq>T#C{@g~^6!V27ENmuS>!pNw04(;WQR3gT5x`FeY*g|`W?pkk zYg>CqCsLuOuYUk3x%-FB>r3wMUn5@r2mOtUzoUTKDMVSm#z6uUP|C$<%?YaS$~zwx z8BRQ)KBN}mtu*VqW-H>_G*_#QLTx+P$j)2qN|wsQamv0}q)ruNg*9nB*X2dUt)voR zu2P7O@zMF6^0f~wsmJNzhU3S|gUJFq+6G@NSEh6bAF0=l^Gwy{I;%s9pWJ&DG=E%gWozB<3gx<0jR6 z2%hh5x{6*iojS`tcN9z1KxFmfv^-0!Bp;OT;n)&+B=+&bjW7qbXx^PziK<#R-a^cU zj3|gu+HVR4edNJ;-6f9Bc#bX$Jo_?rRoU&AbS3&ry4srkYw5}oD7FeFbFIl#O&i{_ z+o}NR>IJv`rS|imrK|rRIO4zF%Xt$SQ+?+e$0VS5`@UiB8SJJG?#XB!ywNcwrUE-hs+@V^C39 z)aU$McnV#?{CF9Yjzfd@X2BA2>L5LtCn*{zoXeYUL7&Vz`vUPN?<$9nl9;;sXg=ZA ziaer-OxCz5_c7UQn%s2V*>?X-B&OH<(_*5F)Xfdzs~iBN-x`C&|EbK1Qb2BH|2aDa zXc8di(J#3Yaqn6(#$Wm^vdjV&TV(*58=y(}|DfOADFR^?J^=)bLg;|SR%sYtbTK_j z1l!Ae|0z6%zF=;Xh|;Xk$NdSkcH7@?oM^oae(Hu%7hSsXDn`~y7*6_m{dJ^*o|;iK z&-!?ns;YDN4ej0j6q=Utr#mGq?@I2VWXkfDKXyeyYj1=zTZ3I8=)Jqx{KNZh4Ww8g z^g+a4WRo>`ksjgZs@YE0LXO^8^~4j!>*99jj+^T;3MOxk8ta?Djfp}@LEge%Hxx`S z!b%b&xRe2g;<9)64Y`N8o zko`kyiO3xkZ=(wwThuPJ#!h|)o)DFfi*yv%*m|-`@$nNqU^m_*)7Xf_4VYQ;tBu;F z!#a~J^h=*IWuVEVA2IYAO5togO4cSK=QwOk7R}Wvy*7wOxZrk^v4LTaF=>}94|`e; zRa%@G<(le7z7~g~Zhzg(FkY%ayRl&1YtmLRb*lw6G?h9vCxE}R*s&X-7D0OE_LhI) z@bvqQ`$bjVF0w9;2xTe_PU}7^W0k|As?OLoW$l~170SNPRc9XDeazLkqA1~~z}$yvvXYFI>Y4{9>z~!UeDd-uSB@*fTSScy9-AI7k1g@2 zQPuO6PIf(hTa1p*vWU-TPOT(?J^5O+iN{v61c8H3`vmSuV4m`uRt{d0I!*tVh_H7i zg<>Gv<31WZHFw$d1(I)4AAZSpss5gB^oFy$81H zAH>ERn;V_z8^D@Cn_pkFn8E@zuFr3pZ?}W@=MK%LX3()ek53LPe*J>kK}`a3Tlkqb z<7qlA#5;v9h?p>)Z7{-Rdg5^2t}Fs4_nhN3Fu%F_$alWg*GURQMJ1lM=XYqs@LP~219?g;K6RMK16p=fWBe+hP0L3 z%M@!OCBp7?J!L-Qp>dy?puLzZlafjSd4W12F#o5MT!SkpTvoNODQa0Vwk-`NsPOt9R!rXV++L%c@7|gJmPm9b zxciJt#`i1ZP!nek!~lhatmEJM_5YOuXxw>LdwyX#4|8pOV+~JjMQeTc4H&6}cLX_* z2V)_X@Vwu&yCnR&BzHrw}aha(a+0!M}J~lg!^C!%W3b5I8As&8TC? z;e4}ny^}Se5{Px=EbRbZO;iZIC)X$eVy@t(xY@}jkwb=_-h#fZo=ppN;bGF5T0!`? zZac=V!Q9X2&(hdu7H+ASF-Yvj&nS)jZ^_rAV}(Zupu`DUf>a@gmI!Ua4aKfMzX;>{ z&N9bO^moIT?r~4uGE3qD3YEOGKGWZ^^MdjGCABG5!GEHFu#P!Vn6znfqKIOxE1;(x z^cNIoqM3q{3t^LjQW{=&l0m2XPnI!Cn3K%%+R4d_mF>Dy7KpISB4$(}$yZGuwW5^TrJaEiG6XRokHKp8Ij1}+LGIRBX8i89Ndywl=xzu~&?~9Ee7@(O3kWao6Ju9McKV715F ze^TD`Ahf#M9l}6C0rPF z(Mf5x)XaZnJME{yML?NKu;cy117rY5T&4zF!as9 z4pwKEb`*1KL4U!(J?-*_ic!f&!-~B?OZWJMJZ*~q1ePJMGP~{fvC*URaxd-(aylwf znontuuyr}(s;!bgT)iD4E@PJfC7>H`hPaeuam$3>NgB{doYc(?d=yVr9+ z1L)?D2pLVVJ^%o66?5Oi;nDrpF&lLI!>S(``t|t z&pl<&p7V`0!Q$)_>4K&CN0$8^X4l}5`dNCr;6s$<*(5w4hsMsDx+Q5bX%)BI+|DV#;&wqz> z^%shP>w&C}ADD*fGkkweU4>24>g6>9WZ<+bf?3Nf_xn4Bey==C#BTqG)li-H zF-w5hgW08|$VC#@roKq;jS>zuKKmwVF`CR(&5**Mww0!EClKY`z!GH9qk`2mg&&`Y zVBvu~hC^s?DM!%Cou?&Zu-L8Zq5y?gGszDOjTe`PB$E7+4blLGSC&eO6N6lE%J)H) zRA0t1SYBXQxg4k#Qw6|7U7PCAaiCE5yymtZuGLKz!x54L&%J%;;jf!}^KVK)2fDpm z1}6k6k4V!}7iC4Dvy;!~m8P*T>&3cY_ZEbP9-a~$%-SI&%hMp>)v_QzXcUGpI)<}C z;E0|=B)&*-t@=ASEP2`6GrPrD(pe*d}v}6P^2FcBLAj>|1oa z0KT{Uxvn>u{+;%8haa`w5`T#yUesH|Na{K;0N3>lIjORTIGSAQ(+5$fbPQ`;2@crc zfNt@+TYoyi00SE4H8q3_+f3DWTRhx~6V-!wB@8tOC9K>tKM;H`rmb>afP&Msn2<-x zW}>v(28$!diuUz+p5g~%?p7L%AvS<OJ#lYCSVlvhjszd<{v@Tsn2( zw{f^>6MiF4^EuywwVGR@f?SySR*kVIzPX>5Rvs<@<`H1GH5v`mm3Y_&<~*0TX~0G5k%y_`qeFc$)O> z6mEF$9diGvdv`z3NdHN=nLWe%^36{Pgsc>y*q;!`w_w)mTGP3{C(7008&M z+Q67o-7(k^_qWoeFn>psmrF3GlZ%^&uQK=hk=xvy9?r_#Rx$=~1AjFacMt7|Ko_$J zLvvJw7fRll`;rQ$QkX)RkH3#gup?)fkGF4-LYOkQqqCorivsTZv&Z7xoae6udnt3P zp8W&o*`8{Cfi9dfVp5_gxP%0!tgM)Xw2Z8*gb1f3TtZSDj{7YuDj}^PBdZ`O$NASU zZrpBx&aMik>Y9J;h5JdF+dVkgUqM{_`t|E#*QLb#0^P(VogYUG<>w~>f`gz+d;vmF8|8={|X#r9`5fVZt4=`7ZQka!M)CNww1qvTA+(# zuwS6LpP%>NS~Pa|3-$|g_w(meGn3_n891Ume9s;Tp06-4P|)!W3U>5Gx#*}XbK@|? zJUpBgE=y}jOQ_1pt0OL7mXOepQN{g<(9}>@RacXghHJq8UaRhh3h{CA4gPzr^S^6V z|8wmb8GQV4JFB|{dW5<-YXw-@7}&SdVP5C>g9{) z`_G;}dHiT^cW3+IgRRYt^|kw}E6ewm78mB{W@o0S?oQsB7{7gMY;%_sHrF^$jL~dB*YLRLIN-@JaBy{Bq9W;01;fIz=fO+03bYFnbT<*LmVxQoI1d= zoINVtvF+YRxBNwxgMA){wZD&ge>z^}uPwrwJzEzz=dEyar70Mz1EaQXeTLZx?c06x zC7mRF>5=&GsPDj>FM?g!a(N@woYN8b_6rhy109c!yAhiRB&TGgXJsd*#^)Dg6=vq; zlogkym83&KutE^Q62y;=F==mZE; zG?}kZ30!?9c!_oyQX)8=IvWO4}Zto1uyfO z6x~Z>U6N0w4+vOHTrOw+vcKBKWiB4ef{R<<2z671-oi{%0*U(;tz9bCL$j7y^_+2 zetIu^BUTs$b4*n?#vW{$ zguR=Ke{4YPI8zl1+<7&R<|^Q}v&2fj+Og;Xop7bvWX@XH-fe?13R}~2qCg~z+C1PM z=S2Gen5wVEXvFDI}s)n=61ED;1}+uJl30<+fBHK{*f+|7YwnoNktpOZNgNj(qpQduia z_v?bMLeUMiw0sxrD2|6o>cI)yZY{(@>zUZ}t{*o~6Fc4!x2bKdVk%{&NgW!ytafW2 zCtfI}<7pofGDb>1HH@st>C~}u3}45t8|yO2yBmTi-0eJ?UM2m}7EZ(M>^R2Mp%QSZm9S}-wD1DW_3 zEnSR$f1%T=>CB&!m8N&t`#wom$WY$$51w@m6FuD%&>JCtM34}1?d7SfG{QzSB3f_YY1B{~Ua{ zCWnN-@D;X;>Y4TKBC>qs=cxDXRw7l*xBc43V_%=xbpS8ENir0DKZ?9f`s;bI-;G~t zA39FI?v*8G95|1e{}i`)+^M%Q_@!|&rPWk3fNq2LK?C$cW^B?bIk?xQr+$b(_9j5* zLC+;q-}O=~j1HK{QolpnO&!l=P6xG6O9lJqIFx;3BUV~(sw>x(=Zl!})h@V`H|2s@ zfa+28Ik9takXkH&AdeIV87&U{31Stm94QTqx}7SmxC%5si1&wFDF2)l@#(`JJ@n;p z6}w+(x87#RCJBv%SXM^w6OK2=#nWF`Opw=v*X9YgG>Y$1GHjVS#=j}iQqn!RZktdy zXZvA>f+*0qi>1ac_@v3y=cD?>Wn?|=lUkl`SgLjuw?J%f0mnnl{9D+}&%Gf;d)^(6 z;`C4Rg?L!$Fw+qQYcArV`@D`tFLfAq>z(ycm)R%*E%aawB;%zjkO;|fg^={!rRHlit}j^H=nf@%T0&dd=}klD=#hQB|0LCl`ce1Q zubpavzADj9JEVgA!h3}Qmm@Rm)j^UPhRt-R1UBW*iVw|9%0)_n_a;&ps2ak>AU=N+$RqN}7@VuorAq%Ng>HJ@h> z4p-}F6Ft$0DOqCsZg*j_g*UPdCbnVbxl9ssrhP(G`8kDkNB-1C41ty@e3PY?L|jCZ z&@^9#XR!e-Rad8mtVRM)FibyPud#ek0pRGW0JbujPA<8Tif1jY>1^BVBi8oPvYf>( ztwxewHd9}g819VW(|`1W1~-Cnkl9H~A5d;gWvcx!f(_mw}RLXJ?n(X@c*UQy(bOp`uM z>EPk5gj@rLcOh=VJNuFw43yL_0=ER|f98ruf00U#UcKJY`ZWE4wP#+?<)!=wABMzbb!kECm%b``$C_U)@Zb`*U84D4hy=U?%W6 zwTUmXd(O)BUam(zF~r(qsw8SZG?VmUst@tlO9UFTw~2V5+c$PE`h7RJQ}43`Z7jpd;%K8njucs zg9A1z=Lr5VtX?)yBJW?C z8(c26H&%63cwGSPXJ(W?+nM#EHCu{}4KkWP1z+E8b_z<6+AXw&hE8tOTz5Fhzd|oA zlfD}5OBxYYb|fY-N+H%gB=l!TLdSqMxXQk>Fur>QQ|4?J5Vjy0+FiV?xiv=o2;=eWo!Yz4r=Q3SMm}Dbr|%31)r9@wa_J+F1MxQ`6sAJRFG+|72$8_N zF$e!d7^SNNaF^zB0GguT;U}Hr*B1^XpWF#y+I-W}V!eRP8cXF0KoOG`1tX-YP#?yiCF5ectb=iB^*Uh?+Y?cv`F!`M3Ab? zqR6G0R1pb{^yww{<3J!H83a!bg+-DQt0ze&={!vo zV0L91&|tcJW8dM1h<2<2jkjj5SzC@_C@k6HTS~z|#Gg!Pp9Jq4DHb1QVlJqqG)$37 zxYJVxYGtI5X2DKVL)??|n_@(_f*6it&=1m1h=F?oF+Uih3tt*%T01tuQZrow4PK?u zbw)cdM-Fd!i9d_FBXGT|5#}Mm5&%oho(1wB=-x_-oPl{ye+?=Uh$yd*XtGjFrOPVQ z%EDaF!Z4Apm84;{ZAz|Zm3+;5H!Bw09|&toIDn8Q&%~cthF#51jI0tY?T(L?vA*=p zy^#2Z!-QYjAiJ*>@Lk&9tI59yl)R>$koZ(R>YG27o|l^@%vI}JnR`f(GavO(l$+(1 z<-oMiS>mJOE8-6|2txd>xrWCMnuv9&E*FHX420B`*onv|i+MzEpi2Mc{ag{ulCt2IX%&J+|M0G-U~mdzpWQIW84v$p#5hS_w{he_&CbU7mbbBZ3B zU=oE5H$a^0QJhSds>{HV8F~On2t=_p8&M~_Ofe-h$c6n3E4k4Lyw>!~k@J&9fijaz z;u!phJp2L+++(Y7Xa0{G~n#0hhx2t$$=rAXJu8cW0xY}UxVjwM#Fl~8ab zhB%UhUSmiqy~}cQ`a7xJlc<+3@-x>fmuxB&zXpSz0#G;*U{Pm`DUazj)f=w7^zg>} z?>8g_Q`%RqtfkgZkVFgT*7XnA4L;ylJgf-#Qm)xdc7e})I@$BOT+|SY5xCcMiOXw= zBFaiG4 z(hR|BmS8OHb4MsPH6<-_*oOWBE8+$Tjuqni} z_CeidVbJ5|qGWpG*+yc$)ad;_$^uu9In33)xz-@k%4Bu3FkR4|Rzs4s_{2vO1IdlExF=3DW!Vr6_XH1wGf;f;6K^ z>TG_V@x{g^@<%awsdF$mm(Z)E+SX5zxh4~e-7moMV6iDx`I?TUZ)<$!r1kH8@o9+V zd9lIlB2Tx5?HX5p~WAdQqDF`q;JuriQz(+xw(i zY*HJP8XF{8gth}^{N^kCjyjIR1HmoYAxA~0>Rn%gi^0{R)nM{8vMxQ|uG7@c?goWR z1MDo3+4?oS;xAEBb^WsYd}+lf>7pJ+UHyU_be>)#p^P%6cDki@Qt{IG!nMWp(E%xX#qE*(wEUI& zu|wYG6OvZ*RWTwu?_Z7D+#GzxRYWxb=bgbbFr$Yk6^Uz6Ip+F@NLo!df32iOrmB9 zHvFbb^GykPu!9&T&8Do>T0mb%VJJZOu2xJ>_4Uo_)M6}m#AH06z?Tu$M>ayEAg`lQ zbJ4kvbE2TU-y)OOvY1gR_2il>->o}UmWe231$%ix7uwQ=LYuU{UuAhq<9ETvt-fj# z`*s&>tHjx61pibFRrju=+?}##V@xp%(_dYHr-u+kCgBd^J$U zI(|BYo$OcI%qpkgk7rQ=;r)qv6?r1FuO1F?#1egX5{Tv$3i#NU3(k$SKNYN|@Bbk@ z`AmpDS#M~FsTjZxV)De@TlplIcq;87CEP-G)FgME;BvLenv4N985TE%?zY=aHeprE zP5H9Rg|B~H48J@x5_f}!w7VKTACB#gnCe!E^fB&cRbk_+?p+L{U5aqxi_RhHtLj!f zT3St5Qg6A=fB$BeZdCV|!BIxYK*qvQ#)5h5^}LqciMa_1@43meIl8EsVBK3lS^s2| zr&apE+p_j6Bke>Y4MbP^eMYBfm1nQouP)e5K%xe~55ypBi`GS*58aDDy_u(62u+FX zyi-~IlQqR%kh>owUgP-&kUwm-VK^wwv+m--_oW5JJ?Z|OOR*^aKJ zqvaJgE?Xi>vPGn-_>18KbuXc2?NltUrvLqtc&6bKG~ya1Z}AQ<=6N zF!%aHcCYoVa5v^MtQsL%63Eac2mVRmSa1-3cMJYc>T+Ex3YPUXgfK`GE zySMk~*B%o!=--)_GhhhN17x_Fm;SM`nsC(st6-+C1~a!)3Fqz$xHntxI|8N5t~-nA z#KC3)gXLnIRV?Tcu5_!PL~Y9=R**K;>5|5%w>EpdVVbCtK$vTf^Zv< zoo@iAX6AWCh~+dNF4m`pJEt-~wa#-J?r!=f+4ghuwJi|4U)NnkumWQhxoN+rTQ>N0G2eHT+zhZsqa~-{Ta_@K$gB>*$6g65rZZ&p@_R^Y=XSwA<3UBji0zxsCc^H%j3BX&wRuYvHiE3`xg2hlAtX@w^FcII@Y_) z^7D6dgMW{TUF<1@t8VCm?SrWU2?)_YE5aPin^Sv z>b)U^aZNS=nD#$2&M@0MaQO2+@aFjOtf{x}-gk!bt?M6RBK4zV8L!$UGPx$C(s_E5 zr)1KT02j%e@)=3^fl3ZcbxmzueM4hYGq$C*t-YhOtGlPSuOGwJgm>IXzzTO<8l0qx z$3sX#y_aL-!`C0a3@@3^vqh<_fvO;5XJal z*89@!TT^1-f7KTOxZv>4EGv3EhioZGJ*-%ide|U;0p_{Kl-3*`n*Ow$yjjv>ypF0< zdOQitY4ZutuH(f+@CKZ5wmozCOF2ZEUL}S1a&~`ZeI+uK3@?3NS68HKopi<9+e7x} zJ^7{K5l({7EbW?g<6yvAx{|cvnGTT>#iDoo&=R;4@03>nZye^CRF|lMnYg}pk3@Px zA5HOUuEE`Hn_*CC&`7tK$V~5tXF@kORm}bC2xeV{ib1(BL`6!YR5ct1D8w_CZA7r) zVOrvR^S9Hhbe8J8iiFfJEyzH5vKE>0^c`vr)36V8?r`ccskSSM9Uk{t`KjmAB-hj! zxWMXy$ty{#+^yS+MI080?79C{o(0Y=$j{wf`FPF^TOnCEMiZkCgHZBkJ!XM4&tuvN zwT0+L@3-YYjwu#Vs|n2~NzF$sBJ52u0_7i{!*obh9yJQ!2M}xE59Xns8RU7vt? zjUwmAe76B|yu8WD+aUfH$+*nRg}Xr%3-rhxIh)oOYt_`k1mokJUZN%NZt zE7Hj3=FcAJ0xPoPa1sY4%37@IFm{e*RAdR!t-SW3=k{$2aqImT?sv;nb4d{uS&jLt z>AEua(U6h15hHk*ap&$$hhu`)@to#P-Z#*soM9?Y8k7<4KCiSySME7J>@PIXF~8e; z?^T!0fkv!x`2)nixh*dD;OqMl8qOY;?4u;8MX#4T2BN^ zFFwHqP?RzVRk^s9!-s9VI6vB|Khypr>vzWA zpWtiW8}RzenzDcS;FH~7d&F0(tub~Djx3?g;-hz3Wd`~h*08<%V>%!c7%PoBDwhP# zj4_0*>ty1E!Ye?~Ur<`q=y6Yqd$vMXzTM16JH$y-)JtHCn32QXCu{?D6br&vA1Y;L zf4IElE=)|GqKh!ca_ddQsK~Gx?NQ({U3KFn#919b+VaacPoE0W-f# zQoE5X&CaZ&_;!?#=lxp+^PSrC@2(SuJ01K%L50U2!*iCya2wX(><~L9t%ol7iq>S% z_kh$S@V-oKFkKks{zxcE@oN3PG?zLTTG4Lg4WseepF-$qPZ;S z*tBZ}WjBj8xpks_N?F5fDWQTz>3r3l<;gW&H~M=qLj@g`p;)8Vah3vnvCnP}LAWn~ z5PYohZ@9Sv$o*v+RpT+8mNrPql47HVX$CiUR&}0?{*mOw4!@VkjyQ$%;LfrPi+jh@wQ^>YB9D&xulW`)46##|NaomsbM>svpc#1Fi#s zyXjauI4_IwP3fW+`}GsH5Z@nnMbvIzy!TG_@f(mk^R@J3?PN0MN@FzxmKFuttX4~| z#24C$?Q%^0d$(S2+V0wwxzq>inrCu7V43;)XK2e@7-tMhB+v)#8XOWOn`V)r?C%iE zlt-S#QdAO`awD-oDE=Y|QGEkYMQ+5{%F@f9bF(8QXp~01J zRntBfQI&}jc>>sWixrF@`?9`|(Z|;J*;kJSPS7eTOe?W^V7|*+QYk#!HPSCA%hvAb zs`v?v2f?$+8~GemxDP+t&~gs7;9 zn;nXPLI6nBO&&;@RE1Gpxl?VuXd|+@p@kiyFGbnI1|jlxy+C9}TQylT5g0%=fp<>t ze?q{eoT0N2@QD3BIp>!|!^5qo1-y543XDKM!C|ov9^ufWym{ z-GYVzfc1eUL+7kh2Og#+4wD7PUVzXa7i$T|z7>v-EIdK+>U-F7$zt5Fc_Q({Yplz? zBs~b9ld%HFwWkPn4RczVf)HjcH{{D4L%QJ-GsR3k^4n&`jlYug*nL?>=~~9T-+k*< z@e8;3Mu0Z{_6q=R#8AY=lK>Ff*bIO>F%yy*ON%GOe^}~29&4RPD^{GyH_oD!jHFj{ z&ex>|77|pYDyJ?o9P|1|ueiwaJGPGCv2^9Vr7CR}f~*-zL9PpClrvJSBsE}}qxqlX%DKRin(PFIfBWSrE6f#ZE17_b*G=V4xh71Oo-GMA zDT0QpMaKYgtYj3`T=*x@!j*rdxC#Lv6zd$*@lX>vItDgbUd1|ojeRzxoP?40rdyO& z$`hP>KG=K$ySB_(yW~)qHc5lmHfZ58D(Sf;5XZQJ+0K;JLE(nxeulFomp--u7?zy) ze&-|Gz{%V80Op@aV)w=$PrYTXb|V&bQktz@F%!m8cpBCEr;N}zRz`YA^_VIZ{~)~_ zd+h|4bf?vuy0cY^>-hDi7JO@wLT?1~o+*LC3JDl|^L#-mxU=;1V9!1;(TlArFk~D~ zEnI}3LjS`kh5#I3#pPCjFahUPWqo?>JL6{N-@@n|nCqOCGMl(#c@$Oi?)I#;w&%jf ztBg~$6Qk5LIdepYFU&se_NY@&T&wQ+nlIT`m;Y^jDkhN=%5CBiW19YewF5Y(-;pWQ0Fiz?G>#kr}f)* zGT}&3A2)FpMB!=I3Wq6nUQk)!4%;#oglkJ)S;H(LNESvkBT7%+h!!DTu^wz(zO@r$zS_XDia`2kE-vRIl~kUE*po-j<8PEsqz9kyRUHw<+ zP0S0u*17$LcSk1Q$aY?$8=5**OTmiA@?0D-$XBX%;)v-;N$Zu6tS)CBt0cjmnnU5~C;R5~CysLMTRpk0GId=U@M^(i z5l&L$Ch!ST39$AS#cQB)|7}c;hmJiBWD}PHDD+_p(*jv92r9`vy4&ab4+dME`8z!ZYE-08%3o^)LQ^gAcZ9VcqFjENmoTz7zemf)2y z%0Ov1J#09#nXjAgmyW6(8h$>;P=geqOixURa{`zvSKQZD!tk-;{>cU!zq7$r*7Izj zY67oHG8J-a^~5rEct2#M@CvK{syuC^vB<&>%|@k~OLCABjC0moc37&RK!EhEop<1$ zL?U?YQv?u!v(VX8K<_L=lF1zW+TElqgkRjxW&O^4G&|}?+JaP^naGssuUsCva7?@- zN}k20GZ%JD-u@6u(xeQewKA@(xQ6FV_36syEHkEYE8{m)-Z=cX^ga z{-E^>el#`&B5^u6Ba_7$V2I=qaR!Pp#mDA^P#+6%4##>4m%_;BseB%P{J1T`;sCC* z7Gp&_4Mou-XG|c-dRE#I(s!6C(~e>}UY&--^$67G z9$|bub~Y|TO)iaWqv&H%3aYeel>4_PJbA@M)@10CgW4b8s%R)CBaur}cbt<}(5o@j zqOk{2Z>-3)JY;Np&>>r%FJmaMp-Y(4&Igde@VJb`art+0k*6-vF+ky(Y&|$7PZp>s zqb@bAKA`<=`n2#`gleTgmYw27n|We0hEyrkedEqUFtWky)dAE7zqCZ+`s?3l8powN znR!BmOD;|h%!IhfQS9}a*O;P=eR%9i%-kgXu=z@MIgi`7w-?fQ$UlACLn<+fxI_%w z3LMRCvWF8uwT@NA@_GI(rIEPs@EcjKGgc?I3uqowmBI}J41p}vcsZ=L`+%)K@TlFf zs-@oK%}4@4(Vd5$(x^PxPnV`3iGDKdFUa02>eRNJs#wqrVucQ%|NfSSH7TU7KlsisE_Ym~$f}67x z{S`>h#$YMvPtu_I9UrE>`SaDn(RvwyjwqRy~Li?klzJI&>9LzvkhwA(CSRXr=rV0xT?o2xRJmo zkIZ4>^eq|NzeWN|Edx%zsIXKIIM{g=7GcrKbwOyEVHoOhVN+4am+-EO5nn} zf62h;PR18NI%{lIj0w&xxtxsRZBeF;J(R9W`4L#KIyAwNQIw%BN!V^osPkC&60nH z9G8yAIEC9J-G7#^RjnD|Cb_ktk_AnbZ|Pe~7hbh{PM2s-fO!(&Ma@b`>c2{%c)Lw+xDZ0`hw8+TbH))CdzM&xCTOtfp3v22w} zE%tD;z`u;NWiXV?e$sZXgua|awwYeY^!^{?<`P^v{Cj?O87E{*h?x6ZPghRu5L=jv zvxDS*9mWS*yGE)D>JM^}c)5T7~T&$dErzMC^0~)dYD+SM(kwENUPJ^5E=y+9e9lZ(; zrOgSu_9`|z_v~T<4m82bHmub4#mnE{s?-AqLw&MKYo`(YDYzhLtIdfeN}fbYgx!{k zzs%KypC7&dNeOar1e0gQrs+_~7Kl!g*QW4ASdFk(mSFjPZTA*4 zITg%1-4vFR29l8u?g?Rn#7|aXg2j5}&x-2+Qlce?syPwX%s_cORU6_Y{pWUq$+Lu6 z(KSBEs^3`OBgsY$!^$aD0^hV zO$~%?iL0%CW^6aMoamH!qayc`5e@1b$c&1i$1A|JaLM;KU5t&P@NaLwm=7;(}oE>1f+)L%$SMt?!l6OQFC7(4KS+P2+zNZ<%r;XDFu zUeZ*+sRqgVXznu)-ia>Z$n$%XvkBgw2-lIb0WLvkUxnq}oXaq3?rw)RcGo%BPV3ym zN>DPs{Y0$<7N6%Cg2Ux{@BQo7Bw zx=h2(!oj)IKG1R)V|X#WF<8T|wnhR;?#TN;LhXOFObFcAi0*t4k$hHW*@t45u5ap^ zW@yAk<(*N#DtmjlQ%OqPbNTzg8a=L$Mt!~jB$`64i7Jhf_gBLReL=+Z3e8u$VB%k_ zX-;P8d&u_s9{I!26S0xc8sKj?b4f-fE_!Nu)5e9wT=PmnrK4dH#!&$`#KKsT{9_B^ zGt)4s*0@53kPbj~eQRe5PgXb~29969ZCDHi)sCAws&hI1q$rI5;)4N`T zm)Db}GrtLr&z!ZSUQg=$e{O;@ANyymlQXTzJ?|sGy|>ayGJKUX`Gmy)QP~c&EFxh{ z#uL*L;KupoS=oo6F4Ylif{4`SooalDF2GYDsWvcF z`M%#y-};C}i&D#*MO(6r=f2r+a0d6kbxa5ji~3wJ=@me&rLCiGEd3?hM?!s%Jl8{J z_iYTctjLdLi#%po{`T@;g%5CM3rH&yn>ToUHI^8ET*!X)0LH|~A3 zDnKTLXhuV4RwSs~TRJ6Kt9D;L7`QmiuG|9yc%dXDK%^@La07<7a|AAkvz}Ka!Drq~ z&b%{r_Mhw~;~)PLp*BBV{c z49?;1k6^ELRI=n9YXbnmfEa=|sS}Q*Fv2h{HZ<^@jo&K(3?UJv)I!LFP+l+yAWgLo zpra@%F2EDS8<(qoyRODr+gkr+SRtOu@T*VuOnGB!gG;C6Yu%~lKkmuu*1oN%O`JI@ zGG->s27{~30YEF(+yR**86P{9LvG2KmNBT>j_<+$5yvEOL6Zi@8-Q>OH@HF*X}gY!X8;bJoz&l6>0J zt5uKtA=)IQ`%L4GE0u$+YG8*vQ>~=9$&omt6}M|)B;-DE?2rW4WVTcRu%42qd!lU& zRTg==u&4|L84)cJAWv6EOTtoreo5P5CLa zo@XDIRPmFCQfiifpf=1pZ5JEyXGRj|b>A6_^p2HzueC4|ps<3O)Cgy8mV48!Erh(_ zJCd>KB=_tu&GRfuLtiwukdu$^r82rJz=@umbcH=nqe8>Nx1FNLs}fQeeqs(91FzsW zz!JEbjsRef!|%m$IXDQtezQYK!=fvW1G0jfq*38!{S4JB;5&JB<1xm zG<_r_!6S*@j652V5liAp=|S$FMS^N8@chQOKqcPZ|QJ4kGO2`kzhY?^DJc?W)P4Xz4T;rqea z_y=oXK==C$rQwP;t(_12nMu>uJh4bx;+BoT2ehC=wVY^UJK7gwAKbGFK$Xy_FOr0V zhb^&xK$A<7?(nre71Z_D^j5xhMVTj=1#j#BAfpz}3AxVQuni|si#KASaOf8!5|qTn zKm=~jHX$@*hpXnKT)r2hdFSWt1TL$~yx^4SEGPdJK!E^EqMlMjYihVsV$y8+Mjbf* z)AO39wTOSr>a~^{3!zjX9$HhJWcCUIK;xkjv|tj-cp@#CEXgc5t*JSsyow*A3=HlV;pUWYMo9&hia}P?1C-npZLV$gR6Np6pxj;UJQn~PGk~aoi)kE-P>RrR72V)7KVlCCXG&JMf_fkY#VIc|L%RO z=xJ_>JOOlV&7|6uw@qIbFN6GtqJnXX;yhOr?xPi&Y+-%#OOaX{A7GDy3Y&OaU1lUNpJ`Og1bAx-GaNj1{!yFcXxMpcXxO9;4b}|wf5S3o%hZ= z=j?m$cl+aOx@Xs%vuak=s4@Qf{~;(Wz|5j`1#tyYg#^$yF$RzU>;rr`ADBQO&=}Oa zz=T+eR7wQ}1$fvj>KPgdIa=w-I7-Os zIGX6N=;Cp4;fHH?afThty%3k@U(O-wDnlQpI;AC;o<&K1Zcv6$Nl;P z?(02yEv)o#87S!}bf{@)a2XjXY3Lak8EMFIX{l*wsi?t!j1)BVtPG5-v`o1Fc;SKX zW~Hmo`jb!KANK-(as0nd20y$1`bMt>!L?zP zv@!yBik2y#g^rDxo;gsMj{^_<3#G1+E~@}HlK>436FoH(Ej1%E4Gl9L9}PD@KMM^5 zA2T(J0N-EN_|MMerlV)1r()#yK|fdJ2c*YZEl)%{<2YE&Jf%e(;xnP9HsU@SL#%PYwvs%k$IY!~Nau&Gpsg#rfIk?~~)B!-M_3-JR{N&5iZ7 z)s^L?#fAB~*_r97$%*l?(UIYy!GZq1-k$ER&W`rB)|Td`#)kU3+M4RB%8K%`(vsq$ z!h-y~+??#J%#8H3)Rg3;#Dw^`*qG?3$cXT;(2(GuzyNhZN1!Hj529# zzuIxcylL&M-dUn->GZDIb?o#Jd`uc=z;jegATgKy3N7 z!}Asq?@hf_TBk1(szCHSwHCkACj|Y^#OvBEp*SFH_pADIjRD8SZ3tMF3+{{!~r$r3hDAzn;LBh#WOSm z1kCzp)EB~(3?MBrP>fXybS!#DSZ)o}LhV9!`5WyF7Q;=Nik(Gk%ecD~;bdfk&&ZW~ zZF_in*_14VN^T&n(a9UCR3iPGT<#j29YX*_2649P_1h%%2@> zx0VW=%1X_y%LGSMm=WAgRPfK1d*h}EQ|npuj$$h=ecmh9Uad`2_%d;%YB?7BI>ze@_vU2l#RE>Nx6gbQdwEGiH7ct zB8Pf~X_N2<fD8()PDUu^4!7;d5WB=M#qvIe#*p?(in{S;x7PL z&EF0Cxk;rEdz9fMKa`G^&Qa8GiXs5VctFk7Q{rSP^!dFHG28WW>_fnDRj5UVX$?_q zh8a1h$Le{lD2|#LK?7fgFUnpm*UPD)Beo0lOJ+9<#z!f3i*}dTcZ*^z9Q@0MQz`Z< z?x!bAd7f-9cZK%65_fBXw<~ub4!$T8;Lf_I`N>YKBq!@Zv|wn%axvBK#$8@aO6bk< zI(4@4+^jwv;Bk%L!$DFUj`LyL5zgUI&tocET_)yQ^F7gG6HCFm6Ivy{8@JK&D<|;l z2NwS(tkpAr2~%y9xcu&Spr5~j)UPyAu|Mz=H%kU<{~_!N&BPU9XkgPZE&3I78*r@ zkXU0#m}xRW^@EVGaIS%0&UOaL5dl&#gqX$+p3)EsHEq!LhImyJl^#ULmRl7sj%zGj5#8kiSjYu|3Ndcc*qcr|1Fa}rdAX{9bM(ULq9>9;+*3MRinUR>Eh$yCn+Em10 z|CWF&QdnxGt``T%m1+eADF&&_7G%$qnCiS$+=geY2`M?UDoI-Ep0%xdqecScCR=fm zzjeqP+0v|NQodwG4LtHOb21Y740(6k20$!#e=D{QiFwx!D^c!=I=l{@mea5wV#(8S z6gEfrt@cA|xgf^y2BOnl7cSy2&jSRx8I-Y3Az}qanOVv(n|FFw@Jd~k2WzNJ^J)-e zioqO=TVLYdC48*<-tBz6rUtpt-@Z%}?3X<9Rdl!)8J{prsd>}E#x8rq=E&i6V-1>m zeMl3rD!wP!-I#!(iBHYlZA?{z@iG>Nn3KnJi%g6BGHXa@)H-!YY=slmZp6^`^4E#; z8b@c%h=(~WDD`@HpXyR+Jn`B*76Q_cPvv2x3Hyo&DdgZpf^`Z~37B;q>`tG=Iui4n zKIOZbAc+x5Ea+~nAd>~U$JlmVi7*;F-cadEC!s4ODn#3(JP=oe#W@|qfj zeq0j7*lJB-Npy^j0p{|F#BKS?h=>FN<}?V=j^kMEx3k8>`XmZ7=aaZ4(8OsSIn3_k zZpo2j*yE~h?rp2Inwbl)^9=lLtxi+OFU=zM^+!$nDr`=xAPwiu?{3UZ8l#u7YpPp( z>-8ftpx=OmwZvT_)P_P5%5(p<jrLkjjo!9we&VucF5~C{?mh9)j_r?laa^a` zIZuMkw28DjZ0wxFwvwdr{2Iscb8O4HOWAGODkp41*>jRZo55xf&RyI+`1tj`T3=zhrL4(YE8JEb$RO-U~3y6Y#+FR!)o!zGKz z0T<0PgbBDq`b0H#f zp}q4!GxVe}bVL>M7EyGh>?h_j^dcnoW|((qvvU!?^QM^h5>)h7&G!~1_7Q;f-m3F< z`(m%-?^DENt|H{?eeJWE=Q!BsS?lL=QR^#~@2d^#_hHXhs^8be-xFB>%XXejjnUr$ z&B@KsU-XMVcb>nJzwfVoTW2Ak9y@KX!4u3rOFSWSut8-^LHcMxyY>d-#G!KYzS_6G zTSCEy{boCNp(~2OgZiL7d%N}ipljkldFHSqMfFbmun&S-5F|={hN>I$Mld8{a)PP^ z@*kF&WpA#5Rx#m=GvOHWmPi3%bv-U`4s0yJqSJc5>XW+klPQ178`+?>+_`{f~-15-AFs3Mq=3CNmmI+fkhc;BuD-$ z7=2gV!ANQ|(%Wf4McydZJS25u;Xz_}%iLR(j&=|Uo0 zPORd6LZkzOYd{h*NqpNt(&~1S4P3HXLPD2tA|NLzoh7M-Brzr+wyz<{{62a5KEAgh zx!*`?5Itc8E_I0{X5J|E1vjN*A!XAjW*+~EDI=gSU72%L@F-< zs=z2s%{%P{Jq^7lZG$8YBpd?~2nAJ`3jL7skdSJ-pfOhvcUh1kdm99+9AluBjtC@nmg%|M!QU+{z9F>sXFG?)}raBmn99vE52T!3(% z&g33=wg0Qgu`shPtXd>8q|i2?uuzYssAAEm_Ms@3v{-$wkP%Q6`VicjSnL#Ecs?Jv z$n20o8kLQu!{13sGXlEqry4V|hMY6(mz7n@ZKwZWX;~rGyH|^m9<~wLK|WWz1^4_?nxC8ex-iCed1c|7!WB8pWmxcD7o>q9W<0V${7_AX{Cq zL9OaiwGl#1(nJnozpIl--ZQEjnLre|Lp^J)yEI{x`eMBVT=ZM!2Cu_VP44TX<>|`#J$kYi*}mXEtwFvg)Fv#y79`wAcum-I+7$3x}+urCoev-^t`0H zI)o-ol_IO6>W?ZFt!RV;WHmvo%{T~kdQQzfDory%Wo-x<9ZPnOCM_O8$j~2JV<7<> zM~>NbO)W*u&%{l%KbqBOg$v4zJ%Oz{c45NU{#Q8AOre5?WarvW6FUJ7gys*`by z_Y?E>_`_UX;TX^xR^(kJ~V zPh)f;-anqFYlUX;SNa9s57T20ZyC&xxX)apO+u?pe;1!sd7j$Dn$@J3)*m5Oqp*K) znzlVrCUGft;RxqdqX1IOXq1ds1|$2Fl=)$gMXeONx%hgN%$63Z<{K?BXd1?r}%%!`(VFCk+!R zE1&!+_uh~CW7G%-F3B1f$S0x?jDVCX;WU&*dTW=nxaDHcN0iI4x$fUbTtBbXm`;5; z6mOzgOC(*tO_6|JT~0MlU_@A3oLP?-$x36T|M)xc6Q`QeV$E|(fn31`#7i0!j>xy) z>Lh_nBIL{Xhnr9do3M?WYcrcq*P9(`n^@)>fYvon@2$J{y`>b}URVp{LEEvWTW?3l zv&}eJC6?JGHsOD-xd&{DAxiO4ZV0$8EB;o1`%Nt8+AE>Hk$k!FiE-yE%jUo4+<8>qZT?E8d=~NC=btM(^acA`$*Oz8@oL!sNT|3HfNy^(P{Y za>(d$fjZJ)>7nY#Avxs<9_K-~`a!Sj0Z!aO4kz*mCGy)3rx%>3SL&xXuBVr)fX&pc zZHcYj)X3<>{VR&&4E>`NWu)QJBgFO-eUC##(AkHt=g42rVW=S_pwmF5;asWHm8-4Q z5)%oOfQFZodd_n~w~J3{0Max7DpEE&=p3~b-F_0p||VNqfvgB95kH%nM73%6b&}g>g+kcE!v^!x~1@Y`TQ--ZLZQ z+j8oeipP~9*Evl31;N~Wz)B%Ds4eEXx$5vt*5lMZ?bel&~`!BU= z5O;UygLO|+Jd>k++jm-?B~A16Y&XLqKuz#%RT*7e43Err%37_Hog6vN2)&o<_o1=Br^H*;duyS4 zeJ~hd4ERO~*HZQI`nTELHW8&Y%Jjz^b7y@^k?s-q3^19-Zhyki5t5Q@#=`eX>$?vKEOCjZgkP9PLPqSgvrnAjeS_^LliK0re# z5lW%;!bcKCG?4Ja1D?9UdVeH?mW%#6o?cHTO+W+Q2ZNz#HcBSWwx%%JNG2M6#8|Z- zuLOc6BdH9J30DBNIWuIsghF8oY3-TrMbn{geT z)7ch-y&Wj6jnnD;@-d1TiNkXGQIhKcvAdo1r9aC&{BD~UvhDdDxg`(6N8Pgz5G*>w z+#BpbZfs`^0 z6#|qN{GbLKE+A(rhAjL|H2Vi1Ru((0D0vNmrx2wFInpqU%W;J;k+g@^;HMeWUyx)m z1a$r1`+`4J;%vcLOFYgu|LmnpJ1Uo8g?5k;p}A#`9;9drekaZGMI1OHw3OUF%=Jas zdXketu5z5}Ys_a^5f+M$A%5X!St&s|A6ZCIDl>c;X{MAK8JrzmhG|v7lA37&m6e!T z&5dqr(6EA*8t<&u`;%)KNl7!5MLn66n^p}Q3fmb|j}`ejod|K>1#<`NxLJdH0^5qO z(ls{{HY@L|RS{dEQA=!!_~RC=7e?Y1?N%6SG>mriP&8bTY;AfSd(O2fNw9n&H`#Af zerThTt3zygW32LReR=~M4;dzmrlj~*BsOTv=|F8h#9n$Apl@J-&7=R$v=w0B{e4_X zmzt+kQO~|)KVk2OlDX2`UqPHohAbqEiH3P5sfos!9-$8#aYdud>ON7SHe?C1@JB>Y zgD{83SwcUJ$Wu)ZVa?*EW1W6C<|((I62D*(hd7qF&EX!d>NU7j?uXAZ_CT+rc@5#vSXk=wq;-4X{Xk2#5&d-2F`#ul^X6 zVb`iTSyk6KJmXV``W)2eCvSUel(u$rbu{*@ymd~*^mMDB{`Jw(o#TAs)M%OP>)m=> z6*TRc@q>ywRMyUq7yb|Kkiju;B<b-xEd81I@ZL+>SNZN(`aTzJOt`{!3xN23 z1;Em2!=^EJQY4-QezD&CSkc2vnK^&;r{&|%0-%Rc<1$RB>qJlg%c4)toZYjcLLvC^Fu7jxA19%`*}R6f)lau zab5QNaQ%OV)?#FTV;kV(U_|z_;mgLe+Z_}yj10>*T_Z(x5OMh?73=V{1H-K};O`O{ zDK(9MD&{dH7jG56dyzxw5-Wx}N$b{8O-Nf&Fx*CM?LNv*NH2pfY6Mx8yjz?=V@u^VC^)L#Q^qjm$ z3x(0`fn4SFB}Iq%W8-*I!Bi&Dc#l$nd7^{3^t)z6lI-?uRM$11silsph|N!?*wy#H z9JdC9;h3gkL?|s`><1;Jm1`3xr*pXYlcmfW>vIStOr!A+Xg06QPNZ$5WLCVj1q|fO ze#NLH`0Gv*3QI+>9!7qhA?6)m9np29&sv5jQ4vI!D_9NEe2Ijd{>@5VrfpIdjG?TF zzM$Z86%n|JS3IzvFb~wSDO9m3))c>;6G2Du_YXOSKsRX}`3Vl*+>6!Nh7?F9Yf2+q zNIze(Dtpw}#-_P&8%i(D4ATx&l6Myy>Iha%kH)H$w|JVqRash9-mXOh4VPH()+ldI z-c*zml$hrrNHr4L)%WR~kXNyB&v~LWuJq{Gdo-<_`PS&orX1TQu&o>g%GV#5{Z{y{ zymF^)QgQtq)uE@!=hPUrEs&zbXhLPV@TIQ87W>o*u32->ajPB@%hHR%M02#4tmApd z-1k;=LpH%q>tigHEeqBPo0?+7JvNO!hbq;FCA+!@p9-Ivz>W7+sI91n#z zsGV$w)CK6gJZiKpYtVY|MlX^)p6H088itHv#=REmK4#xI6v%ljgQUR$F&E~SalS8C z@|J<0Vqg{vw4q2ZK95ZO_{vJI=us_95@IN-0zIW99bg1P+xw=0KFE-2O*tsG$;SJ0 ztkc@MfJn@kkZ!WOq?Wd{<@ylpx((*$*2K%KgtI;_j@D&g6m~o+eLqqj1(4a6pOc;- zl%p$El-hU{w3t4xvW^JB+$K7N2x#??Vk9ywnQE|z=VRzJENdwddIKXSG0@L)0*zED{mC1g&)d9m;}Se|(_ zXDZ~~wy+&z8^oky>8(=R&L>QsS!8VJCkndoXJTLNhp8I00Hx|i&NXi#a#f9dDZNCL zQ7uOCW0}w>Jx>QY?@3Ux_UpVHMbKd#LS;4dv9#K_5UCt2kD83tq+TR2r5tf`J$C23 z*f=U+AMo79HBPl&6g>_cA?G=fccV_$qM&1mYvKK_>HcoV073#uJ*GkDt;J+y{&_Z!6ctfSBd zI0igDetItAx@G(Ez}5iTVuLVkhahN1I%>Q2YQDd0g9EnbeX85wZSU#&0iaK~JNl7; z$vuzPPDk?t$(svix*dL*t5$~laI^KxQ~TTM4ooc8$Dj_XB<`22j<3Z`*aY0rSe>7k zxru~3@Uq*#5C5Pm>Oe8&F=FAt5a#(vz(WS?nA7gSBImwH?0jF)Nm2cS@J$D;HxJ!* zXP8MF+2=0Q&phj$Jha^%H1zebx)nrXUF6Fhm0i57e7q#pU5rP(OvgMLL0!ZIe2mFu zINsdf`MTdscX5#O;cjzB!gq0d^RdvU@ji9&1@nPEz3VpV%9n^HbH3;vb0VuBWOqAc zAJFM$GVKy`?uPE>6PE2JDJq>S;*d0n&MBQ?Je7<(|&@> z`w1^#Ef8N{pqpK=+SMY_1RwT6K*cN*4C3F?u@0u-iP|@!lJmBL! zkVG%&6U-j7+|IDv=X;!za4eM4+#dlHO5z&?r9Ac9y~~dq9!QiO^xPKCBp*yu?J4jU z`SC`uNNgZStS@9+q_}$^n?SI_xnGKpIpd9}+m%R`X@3^GP$8Cx=aYzYaaT$7P|fh5 z9`8V{s&EU|Q2p|d(xGUsH&GseXkxKYmDq3t7#(sJ>v10Jxf)7MX0K}=92^#H3Kr`- z7Hdx)9`9!F4Q5SS7OO87sf`vH!4exY6&rUJkCYv{;2C;K5})24S|T5w*&Z2K6puv^ zo_!KqAQ+i86(7ZtSO$vsM-ObuRxFbLSkdiS?H-nY7-@S`dQ?5EP&_IR9NnQG-PXm} z@fP0=9yx9nFZY!A96j1?BDwK-?8;dZ)OAJJO+WTXE_%m4RyRF5^=|M~ci@_jM?8pR zX{p-usbvK}FgvitXt{Ukvf6x_1EvJiG+1gqX&jOQ6M-QxQ@LQ-3qHkooJ(|k;3MZ$ zGQS`JzseJzL~@smnDjcb6lwBUBZ1`h^4L=I1op|;*0%I}W8uAeJ`rzz-e7)|nQr!B zy5`^se7OnKnNDTrNji2>LbVAJxkaG{woZBydukBS<)G-|+Lu|akr^2VN-};KI-6--xfwaVS^gYJecBoA zoLLkfdF>EBg%N+F7&+yT34Q1}6KDxdAFlLd3CtPxt|2jjLP0YZM9pNW`OB8BUoHCC zEi;cvQBvc{;R*?rbM`$7x=(W-IL6 zo0JCsoW20)$v~R{O$K?>lUc=*nLR#v)|#0ZHTf7lB{3IyA!wy|lr$KWC`J|>5*Dbh=Rp}9lFZi&NgHG>( zF^lmwif=`gim*q@#Ffi-79(O5x!#Xf_lz>{%p(*p#@WoyJ1<(U%g+!fea%s>`o7fm zUNRF~rSZE&+k4eGGo^NM)y|fQChYK%m8AmyrGDt8BbDyjoaHJC1$;H-jQ50n48F}d zqBSl{1K(HDMigtmD|E$(b(<-VrY!ZusGU`_sq(93d8^Fpsm0rYk4##O}WQ1i#+m+2JeWnF!uVp z-AP24^@E+YF4c|AkoDGU&9Rk*&%3hFr5otETBxNO407sNu39j)8+bTc8dDoTueI>a zwLUSfGpTMW^|T_aNN&WZd@>*!Py-_tD??wcYpg-S>~(56ImQtlbal-4CAK582%h zz1a_gIS5BNh#)+OWITuxIEa=%h|xcYwLOUQJ&2DzNXR`%tOWz+2g$PsDZ2-$HwS4j zhv_JX8H9%?cyy{_>12zYq8#$wC#G zJwa%6#>@Q`S$%K@AkIK6;mYiRDB=n@p@GVrp*U)t!DQj8+>s<^>%--Ns=TqZA71d- zBGvg5Swc~yYJ=4UQ+ZNZA}Jy@g)>EpRmLlWHAQn}nq7g|qP4{fRfbcAYD2XpOLdl8 zgDIkQr7KPLmxn7ub!BU9?obFgV)f-4UH+fQ)Q9UUw)(>HMN`EZDtCtB=}f>NXVu!a0?rn=L$b}xjl63zAJTm4aF8l%k( zmwV$`qG=K>jn_x>RVHhrElszl>s>)#C0oJ1-u_gZ_K0%J+|E?<w^IChWBTA!wnxa{rnAIEZhAJKU`npO@D$| z!_5HV-2BZz^4k5)AnIP?tzi0D!>thJ-TbXk_M82!upclBpPh>M|2ELl0a^elz&8Nk z&B56pG*y%L50^;<-nt}-Ki@i&9lp|3=~+cYOOF&@VB04*X_nE$`n3W&z%*6KH$c{y zpJig>$WAp@MH-};HSYySq^J^E1WHm4ZLn4tTav7;IaR6JZZ+IhT?p(Ft<5(DbS{&&PnAK(f*VCh4-Jq3neGNzzR@ zhZQAd7Y$wn`ci{Qx^38&%%1`D-MW(bVi*zPcy#d2`uSZXwFW(=UTYe+$m+2TeMd@< z*j%IUZf4)d=^U6aLuu5?+-tc?yK8ugd#m`0_$vlV7^yp02Fr%>MN7x>hwDZfASGL* z>H#ufUrD-!kVU0s4464!l5UMaZ9^>@?l*Ee@@8D*whk(ccCvxN{*EEivEE6{i7Dcb z|7u1!KnIWspaORy=+91kY2-=)a?O=VuTw@eBu(d#@XAK$3 zuby#MMxQE_nI*&cB1qtJFw4bNj`nNQFryEbXV~5BlVH@ z4<-zh42i%E(};}4jFyT^LQT+5PDf7V%gD(x%}LMW!GTnQEx;e{=FO^R)d-L->5vSW-r zo-?mY+0k^INbeC?;beA4DW?A#@Dk(V1z5&iWELoL{|}&7C)|R}*_;Tt`-B4~rN!RzZ6hXzn)6U5E9C zsbbGw<2ki&4&B+s%FV;m%-h%3Kfom@*wrb_AvDqq0rr){orD}?#YRDp7MuNVak&3& zE9`GJozMC4Z!I4OI05JYDBzacgbxUt@G}~Cr-D)mCFY6oeiS;oJ2YYxjv_TL#Iolx zNW^dkn16wX58=Us9RR@Sr6Wxp@bc#fk&Zf^pw}?|wqb<^wv1gQBs178XxuUvxlSz| zIkAIE#vbi$-JR61UfJuA0l~qLNC*azQ4vvWbTMjw8{6yPnur2W!8P%F9or@3;3;~D zYac>@p1S0hs&`bH4{sM_qG3(Er|bekP8F;_hp_0DrL}%TNynyjd8^CkAhUg$IJ8)} zoN!y?5~`wkxge`vx-dk2%puZrfZ~LlW^sD|*^$rP!xSopjpw+b4+)s#uZYI*%JGk+0CW5?dv>cGOY|z%&g@|+%9b{+np}}aFG21< zT|K;g49tB40{OjyLc=IS!vA+U{{Qy)_vhn5#zBWKHS$Bw#1(U915#Lm=^$UTGF@K$P*fKDX$s(df=~)Eg zSg!o@o7YvkS+QNPO9D#<@Z)ur4qqeh$4aQe7)Tv*N953_KcLE$v=c62ML3#OQ12?m zbNV+{=~gjhyZ5VYICq_}f zU?*19_FyMY)0bp7UN_cgH^DHsU^mgU_Fy;3vX^8p88~aSmtwzLu$SsAkOSo{Lx@Uj z<%Oe=|H}_0j`&v);#|IE7z`?jWz>s&fkoU+EQv+Z&A~xlx-aQres-+!VL^Uw;bCEM z?crfjc`xZvarLb6QAz!7;ZbSx&EZj5I}BN|^JhnbjEawV2!<8I68XnpyvA73%)F*( z6;C|pNaM{sm+KM!t)m*xl3Wi88$E_@_>m}sF2>7F1G4DDhx!>qnAT@XNZ z3U>0_KqS0mCVRfsPJ1jRs3W++f^fu%(PDC_;1kYR>ai;%KM|0)Ayc61oA{y`$&{%? znsN}S9L7xHXsNc|>@Tt&V|9Gv_d%xQN;>*u$f8B^XiK&2tDV>1?I_C{ZEZG2f=sA1 zR9r!m@Z^dp8=d8d__jIrG)29ka@@JZR>ry?V)DdWO$(2x%9G=0(8L?7jiz8FisVCZ zt3CnBMfniabZg8e3oModemuthUTIUf{H;dDY_gT-_bJT>%jR-&Fs{!rH0fb~e^Nuq zAUuin=D4KR&g}*JiS&GPq>IO*rP)#TxTVeROWM=Z*~!!zS6bV%>&xoF?N^ZV^8gdB z2gHNjI>|M|-l}IBz5lY;2XnlPUtp&;016iP>d$)C|L`Y>giZ9tWKG}1DX-br4nk@M z`?IAP_3$C(Bl`HXM6Tmop=D3=9^pSKdA4B$Q4&NV(WwivNhH)i>_laWDS5=mdV21> zQPFP@jze-k$oZ}r$nsy!l$(RSGJK)07uA}(o0J02lzU5CFFqVIcez5CRv=>q z6<7AqvK51>I(UwXs+)f%71h*glNHsLSq&A|6?g^}8uZ7q1=Z(eniMwXREichWp$Dj zHfKyC6t<*o9u>5vTnrVoB|#P!v?m}37j(qonHF@$M4Fg?so@+B@BXY{dftO(P<-Bt zWp{kuhwDdv(N7Q;{G}^8)AXXZy7b9wFtQV?U^sm8DSsq%b2)!B_@X&~ED$m!f7~D0 zC4a&fPc47ao0cPg%995>f7+e(_~QLXjg`XLPu3|=Gj5(IdGjujBY6u>nI(CP4wWH! zOLmxEHD`6{4{c3ruzzdGNH7n(i+jV6CPTqz$QR&@gFw^h5t#Cog`|W52^ZT86 zs^t5P*(9%UhHd{g^v0yDIwjVmyt0JG#GBn3|UJ%hMb z;1Sgv=daVLS*weytPfmfw{vBnm#5oPa7gto9q?AD9TMZr9ky8sg6p>a=~u5uoQI|^ z!9E&1Wv{1yho%-iF&g4akC!uqmO7syD)MNLw%~lBltg`C|G-bZX|0UWS>o%!(H*Ox&;PR;!2f}NQ2OpQihqQC0)ajVS+4(pbO%TAIMHv*wK&}nG4TLDJThAlK7QAK z!+ehC7XnereQ~re?bYu}bR9t+@NI`T?oPh48W07+7e{OGGv9$uPa*}`{-PQdNHm;E zUa%TyFZ_;7bh^2IDWiX2EU^3vxGwI z`5MK~kZG1_v_TTU!oG_pp6~kg5x;p*3j(eWAD51hTaj;PAeKaDmVNVL7b%t7ZFJcI z=s%7ll{A{3$a^${qHYrY-U-s|UER^&l}YdAnW3m=!zeb>FMtF!ST+7=4`FrogKbZ%J2h5C-yrT zK2x;gjL-lg>Yv?uG=9CvUp<&A5B>4CVWaSbBaZuM^(td1r6R5GBXh+`sVxq5Bdqhr zoVmOX_erYv-((5|;fZ4aNo3L_(hh@3uXBeBr7Da$8g0mCN@f>aL)ZgZ*!U5S}$GiEj ziS>oip!jd%+Tvf74c8kH zsz=6W#wJ~-XO}wW{TG)vYFB;5H}~qd!^PM4f5*VS!edv6*LQbVr%$O^#{j5AsBcp1 zt*)>n*vHh=8C}K*8GOz{AIG}Cp^_P^M$riMh2Vl(oS$fDU*R#CLe>8vJSOA)K2>Dq zgH7QKoLrgmNTD3*T&YBxryi+o@nofbM5ee2kU}NXd<{N?43&7Lk@IwOr@*dkwAJ;0 z2#wN2%G~Xg^V_RE45Y*PjB|7PH+W3*e+?eXq_`JG)A6R`QQY!kVvX1FVxyhk^5h~# z)Ai)VQ{46t#E94R5JjH<@i!lK1Y#Tj0X7GKH=m@yk*MPzitdE(5}HP-^UMPOvihZ9 z)IbLy@YmpMkz4;ip#1hi2P?lh1;0v)0_-rnf~Hw&|A7!bC@tyavXm;d>wYuayz;0 zesu)cNO&Z&OsjSH`hggX-D>edAmR&n6IW#N1fq~}Dz2x4eO>Gy4iIRs*zH?FnL?}p zs~pi-Dh(Wx1=`%fL?R{Cqwp}{F$6Z2rzh%ZUg@l_p61M?({HA7aiX>DS!WL5-v1qt z2nXZ6`Lb*U= zYfe$=Lfgj*b(iIG#jR)kzJ1GkM~SAqBZEhA$=;C5Mozoa6OgS2k-PT~7xqs8pCAf9 z+JN8)l2DrP$T+NMFXX`ZRJ26mMdcObc`=o> zb?7A;W%VtEjcU!UU1{yIo!tX*y+8X0$AX3hM#pD7U|&-YEI}@>t)a|rIUw%tAz}l- zsRxiw&dz^tziu9wzrTAN0|#5J;9!eb6dY_7yu(x77yj1e7m3A_oG*me6XZy)y?iHt z4-U5U**&om_z4E0B*ZdR;rPA}#j&Y&CKvD!jwD5*tS=An61{F7gq{m~=8vZc@Dp%| zSd+l!iD~d$Q!|hb7GjkvV;9Kr&Xr)bX@5WftBTBmu;FkNwEt#uIsuIUXoyz;@)ckrX<{}Bsl65Y z{;wnwXOAO_f@506uK?4JmG?|fxPX3L%hx0l&3HnMEQAr`;B6r2pDfdz-dZP#WBXV8 zNfp99VFF6xWlM3#7*1Br;3N{{4yfj`9$**_#mmPxFf1JCrR!xG5f?8N74kD7HH|yT zAvQfHmm*W+Ju(Y;oihn`LV_+SuPZA^LDsErEp6nr^ls}(@6f329SZB0bs3%r82vdo zIcGP`KRdr-1pAsqVheJ6Zx8SZ5_0vo>LIei<(0_wt;p$v=-oM`0@B0%lHh;64HSm! z!TZ-XkP7)<+d%rJME{qzf#9I|{sxYQgL{SfpS|*DY7aLtaB7c$XyS*Ge{?cO-ktq! z{mCC-M)A2-laA3hi2tX#s}5_jecNM#0t1Gl1SvrT0g+Y_5gP;qQBny71qB2tQF=5Z z2BW(fJvv9%sDX6J=q?4Z{hndr?|41l_xpYM?{+-L_T1NXUv-}MdDHJ!A8KjA>IdIU zrVyn)B4Cf@D78$(^4S1s4?96|t*k<`awmMa*pjUYw<93!af=KFr+TLD1q?GJs1g3x zgMqOy3&JnfIXW>ZI0PPcEjc68Jv2Tm4|6Yp(>0b(C%?Qxmg*tY_))G>Wn+`*5uYOU zbm`J&d^bCn%k_>kT|L7ihVcXE8b&93;^RsPQwxnVuZ|BbuIDe;-`&{GBi{w*z(83q zBzWj_H+wwUctu?;*?t!yI7ev=JD60b28P*Qq|Hpa=E?Lm{!uo4fgw65O;^!6-}1Tw zs#0a-raY=mA)?$cEn|4<7=8R{y~VqXMd-xDen0+Mw=MFPRFz5b*-i0GHLb%8y5ma^ z_+h#Fsdh~_C9<`S805w196ox&x4?9oy}jaK%2=h~SQG|Pdh!7FDDB3!!aJ}&n;S$x z-7wYF;5sim5u9@+G)0^Mjm6+O<~vW2fkL^Y-sJiSoPUvm^xD@*=A$%i_SwC}w7$fA znI_o2be#ozigZx;Q|a*3AtXdR;G>5n1Rr_FziXs?tGbWZFdXywMb8=mJ3+mkRB0D6 zb0^|FzWR^g+|7Tl`uGDl2lLk6v-gRigr7wH_l%cN@(t91e~;qS-=g?(ae~P)DlVs8 z2w2tksxkFbD?mWTRQ)=)rQWsgQCxhe<4I-b(!DAMC!ofih?!Iyd;`?D9QKaJ&Tc-w zJ{}&3K;(0OEAODN@H-&^5izk!sHdTE$teN}PCyjrOZNi2j4ekmDZd0$c(=H;Dz#j- z5?dcrqf*zlg6on$NoNIZ7oi@c?!=GUkrM@ECc#s)vtVxSv1J*WHQu##8W@NO z0dGU!e|o#}6+wD;!3+8W0`5lDdeZ8h^ZN|~4&;3DbMOE28u#CVfY*n~T)6ja^f(Y6 zWW5Uyc7BiMN(Vpc^Lh3e2S7m6}Tc6HmclGW(b96Fuv9WVA^)RyZ z*74Qy^H&e_3J$RKgokN_L`5sdK8?S6G?9ZEosmIBZJex5PSo%zWGgN!f7#CmDRl7JqX4= z5&|GrL<%?=E%1iC=pmVA`-woLKOVNHoIr5i zT^DyBUwhBn-UwvSBY(L-pq|hSxfTXwq07-mF#d$J^b1L9Dd?PBvCOmCc}2w>`FhaQ zk}51i8Bc6=Lr(3{`o?tX_6}-jmqSOXc|iqkFb_;llrnn71eux|x(De4inL|-O37s+ z838hD30~k?dMmR1$@IP4%E$S7jyiFYYgE!@^_&eN6wHDS3w1}X2p{Ct9n*hm5azem zB>ixK?>aA8WC_1PPi#|}nH^7M5ulNxo!N;}3VpheI(xi0NvJlD2$ z?WKc4^!3zDdY!%uO}*Qxwh~zyw09<~KVJ_^#upf$ahDL2%o(LHnrO@6BwQHxw0fh8 zKAUGQhjrl{qgIT-5$gYjjPRf6wgh+u63PkWzgm?9&=iQ9chsr zi&TAinJJqqB;N8FOsQJ8ydEqFiN<#y)2!*Sii2`{6^ zVn+z0$aAjJ2Vic~R+B5CIg~KUf(4HygVlGwWwUp-wj(=VQ}`9)Iozz6_LFH6Tb2FP z2T#YyZI09;^sSo&Hf7n_d^vO3WXR=V$?_*z7UfUN&ZV?lR1kPBqwDGp%bc{T&_v!R z!Rwy4p=7Ij=;M+khvGVyS=7m%eu+pk>DTCX0B1hd39-2{n4|CLxD5s}*+~QZKctyN zH1#+CHO=I&Een-l+FOi#1kC{03M*j3u#J2GA62FIbn)5;~b+uT9IiHcl(Fh1L6rwOK3q-)v@J8DGlG@|gGX_vJV~d&>UC`N6rT z0RpC|McI$6y5U)7`o~^4i@9>U$$+6?KxgbS@-hU467iP-5p~9l0c7P#P+VeE@;9Ba zOy8Vz8Vp-rVM$PNsmPvSg9N<;rZ#{w+Fy{Gq_}`^ng_xca-zTWC2?d1fFzo~ce1Jv zXjc-AUt8M;m&HJ`V4FddM0;giI?uCnhbW15H|os!T#`*d5-q(i$oY!NZr$Xn>2t}= z3xIO@5L8+|Nu{tkpKPxGr3~RVTi$uIEv2|48wm(eNlCV_f_0fzW7jaCovJ zCq2}Ii6t~8=W1Fy6J-_&QDm=74wUPR;W|uS-q4VZZQ;iN;RAzdZtdY|%k1pp?0z}Y z&zZqNJ~&i0I>XM<4lNv*%$lAZ;mAM_t<;w`>UBIc#A>DY+ zdiPdFQDeD{BaOPS;~xs`^3|ICNWPxc{ZNKXZVlqO5VsXkVAvWOBq!xS@g}IlSKLIh zqFf}s>na3Zq1k-|t#a_H4~*eRLPl?zPS_XHsf0|o0~#ElA%G^Q5zkk9Z6V<|B!7|6~EL!S4k8s@(v=Eto7Qlf*2x=Xk zZR-&-_)e2Ek)!_W`1SA5|8zi~ z2@0kuyX3lm&P5-7O0ZR*nnvdIrG0xRNO;gT=;H1KsgYRBg|6(9d4R6%DlylwPE}h_ z74jQQ*u_Ci2w!XUX%hulfNsL#xFM~7_b7Ly@6~v9ZUK`JM1US#O*j zR~2_S@g#jw&z>3Ik9e=;r01dzzw3TeTEfag(pSyTKakJgTLr}%>Q5EH6J!y~9Tf~q zWCBa4aTr02=yMO}9H)U|xD!EuAY%nIL%fzVv#znasfDqj^@kv1Z%bPr$G{-l@W|n@ z@pJ;;#1#F^EbOS>!2-w0 z72myZ2}dQBI<$h&#>!icVBR&XcI8eNMX5@j8r*o-cP?bK#Z2r&*ZH|hdq=pmvzn`$ z_X!V0FP{KTgo1xy$a!mBsD5ZPThK*ROd>2!T`wtJI9xmd9hzbjnNwhuDT;y=2INIV z3G>$Qa@96)*EiOJV{jah&Q7MTvd&`BO7Q_P@)%H=9Jr5asGl%Wer{%=Z+7nNV)4}E ziu79M#`0^St?;++q&`@G`Y?NI2j6+lm7g+-!rQ{5UWn>&nw=(3QX`Z;QnPC4$aJtj zYtSh>da$UWXV8V~QB^K4J=;PVvXS9gyhP{J?b;xt7d&*dkl%L}GT!!!)%Dxc@yW8CY07!VB!JBjM| zQY#Bfzu0Ndq3|vOKu|5GK9Asjquq8+)Lvy&i1PDI&n{q;vl>RP z{a9_R@CBd;`hlz~*l|7PIWWrUF*CYbTGP1>v~wcQl^j*QB%IxVJWcPR>~qTt5f~m} z6Qtln72+5cnUs7d`g&}j#!#J8m*aITw;0;Rajbu<-^Dopo*%Snrp@CLmQhr zOItqZc-Xb?U+x2ClqG-ZDN+WOAi8^dkccVBF% z!IV^T_c$SrlKW}4jwVjjcr`Q10gT@JO%z~JfYEz%+Rc`>_0q^wg1+lMilbOTT3j$w zYnZS>nBDQhhe}bBRt1e2h4bg*WZWwD@fV>blC;%XbVkS?F{UaeOFdm8&FssPM@#1W z77J8L+{OO)F?z?j*cT(xluH$Jw2v+i(CRgO;kB2n9x0ia>@s_D%G|u#`3^*AjCpga z1vx66TgCKd4!<`KVL(v8xcq=|o4+@To%S~Rd~n@g#s$P)8#;4{DY%q%SL{{n2yxj5Bx=SAvOgJyHq#@85R79%pI;M zm4(ZFKHA~A+Rk zs`Bc(dMp%t6w=yS*?6d&7Xs>e+1uCG#XiV0%st9H&N(qOc6^d;mSLV{v2&VlnQ0xm z$@qqTbNlVuD*gju<}=5J5-p#3JOw~o+EZO1L0lxFAa>x@lfIGgO%N4dIr-d=mV++x zD?+BLEm*lNb+~2Yl;Nv2Me)$|-gEAkQv5Yz_{^1=d+q${;p&6*vN$kyglmwZ`C;j} zXoTxA`_2K|ZEV=!@{~9>#<{4^LCNWv>uqOyb4M>DJ2>L0zo)xT0LsYG%Fp90y@0^s zL$Cw}ND@;#{r$`<;H=xpDVW3p0CQkQmsYTpS5`A%YijE1D;xJ%3zOlIpg#g_LaXbkeX_xxi zWymb2q5zy7n8oyVuPZhjgPtJuLs<~qeIR0wsSb)qihcnoW~4%JNF;sO1M8@G zrWjMGUP2mO(xtfcv!&##`jdF_xJwgG>H%i-?z2%$;2K)bi7~F-}Yb=j@_%2EtI_OFu`4|Ps=B` zpx2hW{AXDTZ_ zn;Z5-rEHk1n@)f>Qr-grC}nH-M>z*yRfqtTvPGjEWAFHTCTC?QrJAQ-&&Vk%4$ZSH zv(7BRRzIq6uM4bcYSwHB!l7C^yH2&o_1wYt51fhVEr=N$f8{qkndUz++drZ|g_&Dv zS-8J`e)UcDrgZ*d+SbRSw@yoz?my( zY!#*Jsr&cVCNqHdE`iPg7Qp;SU%O6!^mxc#3w&$L|I1qCJiI=C)GC)nq#9A8A7y3% zojK+~PJuyD@x9VAy^2a5Z1tVmI<1CAjpi0LT-&XV&YSpdWdOJQDY%XVFi)8usOOI| zm@xnI5JdG1`8UCJlh?ZxQ@f>uM8Wk)QBeSu5nqTQ&dbr604L;@ke%WhB`xvDluY5o zN`V8-!y&+p*b~=xc<)=o-7YzK+BtZ6y8HRd`Fi;vUj&4PokckXM?MRWix-ZuPqG81 zl)Ne4nYQTMJl1U6=p=v>LRUal6hj9pt4*t@ima|{32!K9Zte7I%kJpvwd&4%**9!c z(1;ouA!rSxOia$HP8Y*!=2sWS+LzbfC@*4PZ@mxP=y~_y>xC7DHwS2Oa0@W@pr9RT zK!f-b_WFaIwZm`((@Fit*6tRtQ)UIN{?l4A7a}Kwl8BYzEZJPiLGqLr6!=`FZhvxt zJ?!8RzcOsNQ@DWG4~1J6JSxh7q+AyhvAHfmc3XX%Qz@q{w6PyK=55P1I%(30G3>Pz z7NE}=DPeFaJQ)6H9NTZ-{(&)Wzrg@%%BN5piL`DY0tl zHW|5*K{=ShG+my8;!F)oSm~LXS{N9j4I#?vPj}6RBbj~j= z*X?m(DiThTdeEhBkq|gSMNK@v-3kK=uOaqg^>*RJwNwA#&HypXaGS^|tC(2x_ym)rWTVtH19XO7 zR`%W8Jnj5~N5ytUrK;r>LSS;@odFF@;FeabEIAeN&VX*Zsy2a+o}r%Je)+-S392zU zO1f8sp{Z*#u(|n{iSS-W?%Ms52>qrO#D35$kc5MT+V` z&}6L-!-<0EAwdHgADUz5ra+M@Gt|MPN+YrqDm>I-+jpnlG2NQ;Bco$n08afGDMyR# zt<^e7R7glbw7}AlVSocGh+iJF=NlEE@Av)nO*iP%4;Mr3aj`#m9v>(W(=fqPf^4@+|#DtshLBosd$Im5m85hBZK*O346$RB>Z0^|pJ0vZMEvi8$1>0QL}C*0_7FWR`x z67?l>fL*e3)Y9tJ`U$~5T(q%i==_f^+K_hj%<#xcf1KlnffqOz<(6s$lsHy8VC`#O z)Rq0qMH~MGyI7z=*Y@V`IbgK)Jyr@|{s2SI251M3mm0ssI2 literal 0 HcmV?d00001 diff --git a/doc/iterators/submap_iterator_preview.gif b/doc/iterators/submap_iterator_preview.gif new file mode 100644 index 0000000000000000000000000000000000000000..49784d3d6fa451da1d54087ef922c47f4d0e1ddc GIT binary patch literal 10235 zcmeHtbySqy*Y*t}3`0tX;4st>(k&?6B^}Zs9W#RrAr9Rj-9vYGr$~dSCob!<6mNcHm#xYZxCp2X`kl%--pytCt-7eeWO~=ISU1Hx<_r((zGpa&c7; zL^>G;>KZu&x;sca!mnM0$zo(Mo<5#VXge6j)58lTgOP*VIeObW$$;-qh6UlU({f7qAnVO5R8(n7DxGWd|W)VVH!3fUuajgoH3ZOhianL{JF)mAEV{CL=B(BO(d= z^9K$}LpnOk7$~d$DGU502X{fEePjd${r&v~{6z)4kv9c}rKP1$FhoQygEKCp0=&?6 zn9E)$_P-F6olp))S0A*iw-@XL(azr64=o1=HT}Z`PoKYGy-)(D<_I`=dkSLgd<2CB zgicKQYod_8MhWR;hxSGq zd3$^O;2?&8tE;1o zh>)_Bu#kkRgqWy=u&|1lw1SF+l#q&qsIa2Au(XK6Uu%`U9sE3v zJt2dq4=7pL3F&&v$x#*Q?Fl1OV0{M;viH&#s``6DO-@hGw{qp(n)5i}7@Au#B?e1)EZNA-jv%dEF z)yo&pS67ywEiFEMvheuP!}$kuvoq6ElM~}(_ebxI3=a(s^!N4lba!=jw70dkG&eOi z)YsM4R9972l$Vv36c-iZ3i9)EbF#BCGt$#iQ|=}wB__nj#l}QOMMi{&g<|i7+zt*3 z48Zu`@^1KmqWBnF35XjQ~J!JU^*X+b^{{+k0$_NOE+= zxzsdx><;+wKR|oF#5BAQet$evoUcOnu$eV3)!mwY7dZH;38PKe z2yBVj7OM)9zdL{Bh4sBBaorY$A)TN6f?bHh+(V(B5uu@BacJK#C;=aYEHe{ALYhTJ z3eCtOB_hhp$|=vp6;%Ue`D7%GI3S<2zACf15rB3zwfJ;F`rAor3ra^ui^tk0^MN$p zak9$x!nuZu+{N*Z<*c6KnD)-bwXD8@tqEYNi*&a5LB(|S$Lhn(hv|(^XI>l{uS+DE zAW->Bv%EwCi?xJ1b9gACS!?d#38vq@^i6DouD_2V$QdqeM{Xn$^Y0$#yBV6dC@(kU zs|gp}$FOLP+(S&2w$T(YK%OtSSIz6G4sv?xFKpovXn1pa${e~H85pLC$YY-%jEjd8 zkWXr0F2?@$gMlJ^G&&1~2-QiJ`_2Mvy%8^#>iPT=!}1h?4Q!B%9Y{ zV_DR^NHKz|)EL_9baiH*>?ZSwnYmWGMIDBVHWbNqIu9M^GEJK}Yo63xuU5)=8Wq^P ztKZ%cz4p7_&*N#CT{P2InJeA%8-q7{`)@xZXiwxuAx9eGUdxyxtU_LL8rn6zlMH}f z>@W=K+2L%++q<3Q_uo1D76DgF{g5qsvU1yAd&G${pjJ^3>~0+v`~h){JG@ zav|x8tjIR=>^zSV9<_YWM;e>?n4ap*yug-#O`IP-FLz=1Tj{OBTl?FUIGH%1Jg