From 679d6bd3dbd4858e985edb25bb66be4bb28d9851 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 6 Dec 2021 16:05:16 +0900 Subject: [PATCH] feat: add freespace_planning_algorithms package (#33) * Master sync for parking (#1693) * Reedsshepp distance as a heuristic function in hybrid A star (#1297) * Use reeds sheep distance * Use average radius * Add standalone toy problem * Cleanup standalone node * Add plotter * Add rostest * Arrange directory * Better test and plot settings * Following PEP & small fix cpp * Avoid repeted heap allocation * Standalone reeds-shepp * Licence notice * Use struct instead of raw array * Update license * Removed comment * Add how to use python visualizer * Remove useless methods * Apply clang-format * Do not fully expose StateXYT * Remove StateXYT->q[3] conversion * Use StateXYZ & remove useless functions * Add license in test * Update planning/scenario_planning/parking/astar_search/include/astar_search/astar_search.h Co-authored-by: Takamasa Horibe * Update planning/scenario_planning/parking/astar_search/src/astar_search.cpp Co-authored-by: Takamasa Horibe * Install reeds-shepp * Apply markdownlint Co-authored-by: Takamasa Horibe Signed-off-by: wep21 * Boost collision checking by pre-caching the collision indexes for all yaw angles (#1298) * Precompute collision index for all theta to accelearte collision * Add test condition that checks solution's feasibility * Fix in response to the review * Update planning/scenario_planning/parking/astar_search/include/astar_search/astar_search.h Co-authored-by: tkimura4 * Use inline (#1572) * Modular planner (#1492) * Update * Check working (NOTE somehow 2x faster than the original... why???) * Split header and impl * AstarWaypoint => PlannerWaypoint * AstarParam => PlannerParam * Change package name : astar_search => planning_algorithms * Add override keyword for readability * Apply clang-format & Add License * Remove useless executable * Rearange some functions and members * Add include guard * Remove unused node status * Add virtual destructor * Rename test names * Removed duplicate transformPose * Do not expose transformPose * Compatible planning_algorithms * Pointer to AbstractAlgorithm * Apply clang-format * Removed needless method declaration * Renamed planning_algorithms => parking_planning_algorithms * Add explicit * Apply clang-format * Split parameter into PlannerCommonParam and AstarParam * Tweak * Remove unused line * Split rosparam into common_param and astar_param * Fix package stuff reflect to the chagne of planning_algorithm pkg name * Change class name * Small fix (complied! and check running on Autoware) * Add rosparam : planning_algorithm * Fix comment and ros_info message * Remove useless ; * Add note * Add namespace * Fix typo * Apply clang-format 10 * Remove array3d * Avoid using std * Rename: parking => freespace * Avoid using namespace hoge * Update readme of freesapce planner * Apply clang-format * Update readme for freesplace_planning_algorithms * [freespace_planning_algorithms] apply aedd8626762121ad7 Signed-off-by: Takamasa Horibe * fix inline definition Signed-off-by: Takamasa Horibe * rename directory Signed-off-by: Takamasa Horibe * rename function Signed-off-by: Takamasa Horibe * Fix bug yaw => index conversion * modify package.xml: fix license, add author Signed-off-by: Takamasa Horibe * fix license Signed-off-by: Takamasa Horibe Co-authored-by: Takamasa Horibe * Fix bug nearest_index must not be greater than the current target_index_ (#1571) * Fixbug * Apply clang-format * Compute neareset index in the partial trajectory * extract partial_trajectory from current target trajectory Signed-off-by: Takamasa Horibe * add explicit guard Signed-off-by: Takamasa Horibe Co-authored-by: Takamasa Horibe * Cleanup & modify readme freespace planner (#1607) * apply clang format Signed-off-by: Takamasa Horibe * align indent Signed-off-by: Takamasa Horibe * rename robot_shape -> vehicle_shape Signed-off-by: Takamasa Horibe * rename step -> distance for TODO Signed-off-by: Takamasa Horibe * modify include guard Signed-off-by: Takamasa Horibe * fix comparison warning Signed-off-by: Takamasa Horibe * update readme Signed-off-by: Takamasa Horibe * add namespace on ros-parameters Signed-off-by: Takamasa Horibe * use autoware_utils Signed-off-by: Takamasa Horibe * align indent Signed-off-by: Takamasa Horibe * fix comparison warning Signed-off-by: Takamasa Horibe Signed-off-by: wep21 * Rename files Signed-off-by: wep21 * Remove boost constants Signed-off-by: wep21 * Apply lint Signed-off-by: wep21 * Add missing geometry2 apis Signed-off-by: wep21 * Porting test code to ros2 Signed-off-by: wep21 * Apply lint Signed-off-by: wep21 * Install test script Signed-off-by: wep21 * Change file mode of test script Signed-off-by: wep21 * Fix map info data type in test script Signed-off-by: wep21 * Add namespace and message abbreviation Signed-off-by: wep21 * Fix typo Signed-off-by: wep21 * Fix lint Signed-off-by: wep21 * Fix for pre-commit Signed-off-by: Kenji Miyake * Fix tf initialization Signed-off-by: wep21 Co-authored-by: Hirokazu Ishida <38597814+HiroIshida@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: tkimura4 Co-authored-by: Kenji Miyake * Fix compile warnings (#1852) Fix -Wunused-parameter Signed-off-by: Kenji Miyake Fix -Wunused-private-field Signed-off-by: Kenji Miyake Fix -Wunused-lambda-capture Signed-off-by: Kenji Miyake Fix -Wdelete-non-abstract-non-virtual-dtor Signed-off-by: Kenji Miyake Fix -Wrange-loop-construct Signed-off-by: Kenji Miyake Ignore lint error Signed-off-by: Kenji Miyake * fix for createQuaternionFromRPY/Yaw (#2154) * Change formatter to clang-format and black (#2332) * Revert "Temporarily comment out pre-commit hooks" This reverts commit 748e9cdb145ce12f8b520bcbd97f5ff899fc28a3. * Replace ament_lint_common with autoware_lint_common Signed-off-by: Kenji Miyake * Remove ament_cmake_uncrustify and ament_clang_format Signed-off-by: Kenji Miyake * Apply Black Signed-off-by: Kenji Miyake * Apply clang-format Signed-off-by: Kenji Miyake * Fix build errors Signed-off-by: Kenji Miyake * Fix for cpplint * Fix include double quotes to angle brackets Signed-off-by: Kenji Miyake * Apply clang-format Signed-off-by: Kenji Miyake * Fix build errors Signed-off-by: Kenji Miyake * Add COLCON_IGNORE (#500) Signed-off-by: Kenji Miyake * Port parking planner packages from .Auto (#600) * Copy code of 'vehicle_constants_manager' * Fix vehicle_constants_manager for ROS galactic * Rm .iv costmap_generator freespace_planner freespace_planning_aglorihtms * Add astar_search (from .Auto) * Copy freespace_planner from .Auto * Update freespace_planner for .IV * Copy costmap_generator from .Auto * Copy and update had_map_utils from .Auto * Update costmap_generator * Copy costmap_generator_nodes * Update costmap_generator_nodes * Comment out all tests * Move vehicle_constant_managers to tmp_autoware_auto_dependencies * ignore pre-commit for back-ported packages Signed-off-by: Takamasa Horibe * ignore testing Signed-off-by: Takamasa Horibe Co-authored-by: Takamasa Horibe * Port parking modules (#738) * Port costmap_generator * Port freespace_planner * fix readme Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Hirokazu Ishida <38597814+HiroIshida@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: Kenji Miyake Co-authored-by: Takayuki Murooka Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Co-authored-by: Fumiya Watanabe Co-authored-by: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> --- .../CMakeLists.txt | 49 ++ .../freespace_planning_algorithms/README.md | 53 ++ ...planning_algorithms_astar_test_results.png | Bin 0 -> 256070 bytes .../figs/result_multi2.png | Bin 0 -> 52894 bytes .../abstract_algorithm.hpp | 185 +++++ .../astar_search.hpp | 144 ++++ .../reeds_shepp.hpp | 145 ++++ .../freespace_planning_algorithms/package.xml | 28 + .../src/abstract_algorithm.cpp | 184 +++++ .../src/astar_search.cpp | 362 +++++++++ .../src/reeds_shepp.cpp | 720 ++++++++++++++++++ .../test/debug_plot.py | 134 ++++ .../test_freespace_planning_algorithms.cpp | 176 +++++ 13 files changed, 2180 insertions(+) create mode 100644 planning/freespace_planning_algorithms/CMakeLists.txt create mode 100644 planning/freespace_planning_algorithms/README.md create mode 100644 planning/freespace_planning_algorithms/figs/freespace_planning_algorithms_astar_test_results.png create mode 100644 planning/freespace_planning_algorithms/figs/result_multi2.png create mode 100644 planning/freespace_planning_algorithms/include/freespace_planning_algorithms/abstract_algorithm.hpp create mode 100644 planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp create mode 100644 planning/freespace_planning_algorithms/include/freespace_planning_algorithms/reeds_shepp.hpp create mode 100644 planning/freespace_planning_algorithms/package.xml create mode 100644 planning/freespace_planning_algorithms/src/abstract_algorithm.cpp create mode 100644 planning/freespace_planning_algorithms/src/astar_search.cpp create mode 100644 planning/freespace_planning_algorithms/src/reeds_shepp.cpp create mode 100755 planning/freespace_planning_algorithms/test/debug_plot.py create mode 100644 planning/freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp diff --git a/planning/freespace_planning_algorithms/CMakeLists.txt b/planning/freespace_planning_algorithms/CMakeLists.txt new file mode 100644 index 0000000000000..65afd3c3b8552 --- /dev/null +++ b/planning/freespace_planning_algorithms/CMakeLists.txt @@ -0,0 +1,49 @@ +cmake_minimum_required(VERSION 3.5) +project(freespace_planning_algorithms) + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_EXTENSIONS OFF) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +ament_auto_add_library(reeds_shepp SHARED + src/reeds_shepp.cpp +) + +ament_auto_add_library(freespace_planning_algorithms SHARED + src/abstract_algorithm.cpp + src/astar_search.cpp +) + +target_link_libraries(freespace_planning_algorithms + reeds_shepp +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + + find_package(ament_cmake_gtest REQUIRED) + ament_add_gtest(freespace_planning_algorithms-test + test/src/test_freespace_planning_algorithms.cpp + ) + target_link_libraries(freespace_planning_algorithms-test + freespace_planning_algorithms + ) +endif() + +ament_auto_package( + INSTALL_TO_SHARE +) + +install(PROGRAMS + test/debug_plot.py + DESTINATION lib/${PROJECT_NAME} +) diff --git a/planning/freespace_planning_algorithms/README.md b/planning/freespace_planning_algorithms/README.md new file mode 100644 index 0000000000000..5394ad54b6e60 --- /dev/null +++ b/planning/freespace_planning_algorithms/README.md @@ -0,0 +1,53 @@ +# `freespace planning algorithms` + +## Role + +This package is for development of path planning algorithms in free space. + +### Implemented algorithms + +- Hybrid A\* + +## Guide to implement a new algorithm + +- All planning algorithm class in this package must inherit `AbstractPlanningAlgorithm` + class. If necessary, please overwrite the virtual functions. +- All algorithms must use `nav_msgs::OccupancyGrid`-typed costmap. + Thus, `AbstractPlanningAlgorithm` class mainly implements the collision checking + using the costmap, grid-based indexing, and coordinate transformation related to + costmap. +- All algorithms must take both `PlannerCommonParam`-typed and algorithm-specific- + type structs as inputs of the constructor. For example, `AstarSearch` class's + constructor takes both `PlannerCommonParam` and `AstarParam`. + +## Running the standalone tests and visualization + +Building the package with ros-test and run tests: + +```sh +colcon build --packages-select freespace_planning_algorithms +colcon test --packages-select freespace_planning_algorithms +``` + +Inside the test, simulation results are stored in `/tmp/result_*.txt`. + +Note that the postfix corresponds to the testing scenario (multiple curvatures and single curvature cases). +Loading these resulting files, by using [test/debug_plot.py](test/debug_plot.py), +one can create plots visualizing the path and obstacles as shown +in the figures below. + +The created figures are then again saved in `/tmp` with the name like `/tmp/result_multi0.png`. + +![sample output figure](figs/freespace_planning_algorithms_astar_test_results.png) + +The black cells, green box, and red box, respectively, indicate obstacles, +start configuration, and goal configuration. +The sequence of the blue boxes indicate the solution path. + +## License notice + +Files `src/reeds_shepp.cpp` and `include/astar_search/reeds_shepp.h` +are fetched from [pyReedsShepp](https://github.com/ghliu/pyReedsShepp). +Note that the implementation in `pyReedsShepp` is also heavily based on +the code in [ompl](https://github.com/ompl/ompl). +Both `pyReedsShepp` and `ompl` are distributed under 3-clause BSD license. diff --git a/planning/freespace_planning_algorithms/figs/freespace_planning_algorithms_astar_test_results.png b/planning/freespace_planning_algorithms/figs/freespace_planning_algorithms_astar_test_results.png new file mode 100644 index 0000000000000000000000000000000000000000..98338f8c8c4b239f459b94180664ba1247ba3b8c GIT binary patch literal 256070 zcmeFZ^;ef$)IExNEDVl;l!5^&NJt3M*n*(a4GIF%-Dwv{C?KGqf^>JIA|<7yv`Tk_ z^qu?oe%~?fKXC6DcU*rsM-ZOR^X$FXT64`g*Yo81)k`}l=_x5FD0WC*J}*Z>v8kMb zV#A9qoA908(hqI$zkjUHN-Au@AD1n+9^-2|n+qy7^5*(B_BXBcC=ATZP4zgeb*=RD z%&c#l+l+505~H9vNFjOtjDo}Kkq&!@y}hfelfqv6jMl%~c=q_F4YU$!5%W8(&I?{D z={_Udu;K3BGror{t`Eut-;KV!>z@b#R?53JFWDZyW8pirb+BS=+}nk>=*`U6yGw4G zG=ai-@}Y0uyy3PU?{|D1uN0?nL^(w&z%@<=G|R&I>};|95*H8fPUoiG0C#_OYwH<<>2|T^YbJXSS2# zbi@H+yW4XkE%X9ruXS{FM?3caeV(56%FY55gG;MR;~6%Ca*}>gQBh(mGxEY&$LC$< zS`1nXUGtb@E_%_^pE7#+Mtx=?h}YnGQ=;Yx$)``Brdk^_x+y1WeD^tY&U3Kh#j&`v z4=C+Sc6k)t+sz_%*>7&FBW_^ewikoIRZdP$J2UFPpJ{cMGWC(h`SbV3+H-W5mxOcN z*9s>K$2#&1#`{EUl#;Ye@9VBxw~k)iEuVbiGjDGJSMA^3-J>1M6z&^p#n>4xD2&hvd| zPB3vg&yOkAhKkNs@z&lhdwyWf>}q63wq@~*>I#-uP^&-Pu-N7Qd7y5zEz3Gxt8LyqPur?8_>}S9y?dD@joLC3j2dJ8hubc5E-aNlo8L&`EyTse zH9OKG@3(i~zDR6C`~NPy-7cR)@|}+T2O47)ubeV!_%`vYc(miSw4hbbW3$eDL#G;@ zl-q5Yrh;lorV;^dH*aF|131)=vZkp0dO)L9-Z&f8TSB9)&|T`Kn4orQcDVUkXJ;qX ztvrf}=)v#dk1WT!a&3)6Z8Nt0eUkhO5)Y+g6ypLSWkMq9c=c&@lSM{M^5nN~*>Y0U zJVT9FL+t3$i}I1u-zU4vWTvAO&+Mb2i4t|58^DbT8d*CyWHZNDc9&AIN3*G>MwC83 z5SL@!Pv5wU!sF#r8m`2-(Y7m6%il|~y4;NW_pSTyLk|jXDWAyNOHUuWvNV51D*lVp ze20DS;2^6c<<6Z=Pxc(+(J1>KeksFoTA!>wSN_D^eOy}camq=N(FcXC`#dABg(ZfH zIvcfTTdEZ}*=Dw_tju>Yc(-L32ae8CP)uFLS@bFswjWc#>Ksu2n|?e-EHdmjteUa! zd*(Dd^dZlFT*_~#DIxBf*aCBhUZQ4Rr2E=ZSEPjQdH($T^vuE{v)gc-7<60Xx zZe$e^(I|OJE#LdqzcE$s3JHvw8bgCHqy^qmnHaT~-c`RiJ3L#-RWyL#va+(0i;?@FkY%Q6JKQ8geL_jv ze&IFA7YJ1r7Pn1WT3SZ+kzP2ohgehO;_OCS2NRF5-gpraB4BPbSoc9K*CyuaJ`N+1 zuBdBFngvdc>FwAp>H`N7)^DV|6;s_`^QImrfkkp`Y%Es0$SpEZ6gQY@-j$eUP&-uf zMp)|d;X-5n z%39xxR%f|NN=gien-W^n47~5&y-W5KsUl9wpUtQvH={MvG-NF0_VAAs-PTmSXKpLA z${hvH${Q*7UJv5YYlxOTf*95;c}CNm?>L=q)W{|&hiuZAq+KLE9-iKgA7$V-`F3Z+ zW}Dux)c7QF7qJ>Ssp~gvXnc3>kp|O?(Qoh0wWjDkLJkOT%QCMt%7{JxWcSqcv^-Kl zW4vk_-+UW>l27N$7F{Pi44X!_MR1#t{n+bHr(q6VrwTt7HtoWEL&mmRe#0V0Q6~lL zU=vQT4U$V^wCp)v{i<)tH;Zj%24p4WUL2L-)3189z017FZN=u-=Z%tbQCHv0)CiA9 zv@~_(*^>v&wH*!^>nch@{*KYev5M8q%gnVIe4naU8L481L>7GV=GoZcWmE~7Ptznn zTCSjqG{(pu>&{5gEsI4g4HgD+YUUmn5>k`XX->s5y6z|14Z+4Zi#3wvil*9(1&}QsfKV0DR=BpM8;HzRbX9MT8eXBnu}FU(~oSM>ko4`LK+croQgPm z_UvA2>JQl3%CXnM z3SDo}qt~uo>&UUb#Ldl(g3Bas^f!+?eEHX>m&d@sAmjG;v&K#FzAtG5?mu`Cbk@Je z6C8$R^PWQ2La@Nc&_f`hlE==hqXcu+v-O{(QZH)Rw?q{Q}!h&5sqaAt5 zNI%yER2;g!1Qd$gTvwK-YZrS1wQ-2qBq_ITjeA@E;^8>;GL&okavw=Gg2t_0nt*V`SxLr20L~e5czw2IcU?gaBN8eqzA=`RHI#~qs(HLB*lEmRV~vb=;HJJF#r)g4k*7J`)~@lUsId1DG|Ld@~r!x>({(CT-?dL z6`xOz|5&?Vf?9@@>*9=Tl2$?LV&=%^jt_=*BP=gMR&@~F+o4{jhP=`NRPuT4~pugx6x;&~DC#we()H7k>o zla!Q{a@Vi>@SAtWqm&s<{QNY?D6ndur&F@$ZeDIYO{$sg*y8_0#^oW!bE6UW#6BVoxX7X{B7LD#nXMr-dtQsdk@v( zbNFlqu6GoO5@KRvv8X?Tebc0F z88t*JY2@QZ6=+|OMBffQpEBv)5gBgcOxsAut+{5bhW$d>I= zTb|QwY^Te#jQr^Uad$UlB2_mxH!FL4fzTqGLBCDgY2RK6 z!&m3p?V$W=rATQylERR7ORc|u z{~pY(`%qRgNE4Zdo?GWW>wa<+P@Q|n$IV->-Mo2|UeqZ))3hyMDEIg8-&nZg2^u+d zr|0u>bHA3AU9uf&kbOW&EiF#}1Hhuxn<>m}>8SLp8F;Rzu!PeIaJ72%DiaBF7opqA=@EZ?`yA5 zA9_~e_lxK6addFFekNdZta4JKRqt22GfluZayG^O%zS(eHr)l}0}=&raXi-4?5tv# zm}^7w&2!-lnOLCPtIG=)RjiQcT+wIHpSHM>YbukwRVDex8Kml~*g7_)_*W=OVS|a2 zej2$p6*e#GIyy9w>J>xyO+6WW4jnqAmSNn2y=}rFTbqHzE38I=K^k#{{eT4Z^MDEZg25KWi7`G zXjy=X{7Q5P=saau$J~)?d&Q67Y!Vr`0fnct@#tFnc%D65<@*<7Vo?}?u&@_zVo z(Bk)(C%H(Yh|g)VGz3J}RswG0S4lJ;K5~S5*RFRc(nhGfEtDE*CzzSf`}Oqpen1I` zmHQyYcKxl#E{p8Eyb~u+UPp5Ff2raX)ah8sf6y2`&(rCz_qXoxG~LIha5<@9F1R(r z*kGt>YNRDCSjaYZaz#DgAqBhe!H?yNl;865vUJxc1Q1Xx&6^&T}vyCpnuD> zv4ur4j^W!^uV^Kobj1N3#R6`XiUe|LHvvz~3?~&y`R(J>h{h><)mQNpp&YWlAHCGz zhd?d4$=@Yj{RD_%=}V$tB9dd5S5|sQM@`k5@xe9&-wx^K8q|g^_KU9>sx@QxXOT1M z%c}7?>GtED3MV4*U(>2%l5d3Vn~K&}%;goEe-%GEM8RS=nG8GMt*ZgMf(FltZI4++)eIgMm_UGq4oB4N1NlBBZ4<9~@ZZNX{ zZ%9m7gx_WN{-NZH`oUhU9gd`5Tgug{siDz;2eoM)9v@Fa(ma0hcr{ODtmgp_Q+KN}_~jMG?5DF+siAp<^!X zw8O-WU}`x6!SM9*npdT^7Xo+dN*B#{IuF%-xbl>{i{vjfaP&)LgPrF_Dpna>Jb0|# z-r$B(s8&{1P9dxA{iKX6JUdy&#IR2K?Ag00`T+_2Z^YfT0KWMn5jY9!Hf(yeo4P0vYcWLZF~R=#Wa1w+rQ2<{QTq_|rZegx^nDkT_+1U99ZE{Sg2vgO;`Gxy|d z996K{GGSsJ3Nrdj-H(}%U48uxXxD2H$ZRmDKa}?XDU41)1gB8fyK^Eesq4ED29!xJ z);#{QAQV&rkEqH?5#~2-y)~%aRp`pAVLoNHubz^{BrHii%Pd#dKPNZW=tuHR!{_}y zzkk0!b8i!!z(~B3airM*6_c2TUS&YFMd3_)zGJ<@nTdAm+89K*VNDm3hz0{yWfQ0x zYHDg0))acyg>2ae+i3W0Ut}BBM@lEyldcMNC*li3CdqKzJL`b7PwAF=?$2nm+n_849r2~xW#HR8L${=<-bw=@ zEq8RwKw-CXWXO?ldnNns?8bsWzn>Y_sK={t&koj?z3K!MXRY#n@gWF5R&u3~(k@o}?xgwib27z`BMUVh(bGxIFCcY{ZgeV32NxpvbMn+u!vKZr$ zzv+h2Y$uaXuYZrgJ^47h$4{Po_dRmSa}b9!GOq^E?ZZGTTMm+ZkQvXh4hNZMp!bkD z>)#yXeZF5%r`^I9-~xRckH*m$=k)el3=Sx4oQ;kq#g7nuZ2bKE9kz(f#^}>u1G&No z!y{RDg{$C}3nO@nDmzpC8z056MNbLY zTF%ooP-9`L*Q-qO&P$FqT|lim($eP+pSb>3B6yve67$A4ayr*TWal4T6P`Muatw#yV)Iiu9eYbU!yn1-CQpa61+>rgytt44pssAG(&Qu~ei2MBr2XDV}TXzcjM>-{Mv4x%&7iZ-Wk+MOrR4Yyh3EK?Z z5DJVaoeSPgO|2)SP0glI{%1Str}1KEROuYA^k}}13u7B)aYO!ODMM)vdR4>7=CRHK zWBO^Xf(gziqw}J?-8+wNERoYGVg8?OIj~cFlPcJWRF`^DKwWuFnoP3}wW77vJm$fH z@8P6Vd%*OFiizJWGcPCS!&2p3d^GZgY>ux#=Rek;=Z=~Z%r`i=AdzW2jN=vgHrli; zGp1%9&;GT(ULFZe7CaFMnlhWbadp7=?<*~2YuYL7tgY*Re!55CrDWY}LF)!2P`(q( zb=F`9x>H7XG^d{y7DloE7R|Ycbpjd@Lw;jz?5&U6^z}rh=Bp3;*jQWzBEEbaJ+o!U zjz;vOUW3O%9S#@knQVA=|NcLO8@NBEVI$%9N}JUru$?rT)H%jqYxR( z)0X%L=!_@cO%zllATyy%J_ts(boq{QFMxX;c*a#&UN*mUO8n zE;T9uW_$sB{ec+0UiL*@##=QOgIwwFlp~5T#WO~yMOl zQ>C4BSk=_jR2@JnL3k_R$^CYpc>SD7JP{4BF`>^?lHUgNo5lj+_ed!R=dkkd)Hy7_ zeNNZ*HE1N&)L#F`L(!HU*O@K?bQ!gze)x~XoLtst@M(GerU?a}uUR)mh0ma7Kh}wJ zoPNpY>GS7G=Xit@~??fbU}uDVe!+g};Aa*Kuj%wtakzWhEuO4$glU(7|F$`IO3EGKAz1 zDk^1U7#qZ{?)Eq6d*Xl+ax$wCq4hKO#-3I&QeQ#edeT-t+hJ12b)h$Kkh8m|=hjF_ zb%;RRwJ8Ewyz-%Q2GXS;15GNXbv zpLwUof8Ai|Y3F}YiM(`Y&m7>bxOW-knV_Jcp5X!29n&V}?FP2$RC$0OwCh^1w|hb8 zxhzbPHI81jM8SEskE2eb3=~Yp&EieELI)2@AhjvZ4mF}jV#T(8`|*f0If#epu^pl} zD!eZ-F@kh(1CYZ0{6(@*LLRBI^ods@D1Ox18-40!V4>@gn z^I%_JBvEB9c{8@=SVzr`cO~%})X*M!iDQRKY131_3(dPC5m~^I%M2%X6oKe1murre z>u_l<^AWs)&E%hz=Pcz{GK!}pn#?T>P)(MmzeFqw@(cPIv{H(_a65#Zc9(- z^Rr4idr&m9t=vm{)SwafB3&#aVe!)=Zb% zm^MlN(w6g?{=AJVLftfw!EbXu#3eyWI~^SzK7@{LE?8C25a$ygTwsxUd7Tj5X$IH8 zY7Zi~2nK@2XS_`N6Ko;9h(j{rdaH8I#nhQ`^ZzX3_&7Ih z&ABQx@}PoFM$V749H|glRWY+mIxYz*k(-f*UFD>5aaQ_|=kxw9ucPwqmgY51L<~hLLQOqk{vjciJAG7I5RqpcNysI-Rbd@oYpIyPa>hy6jl5VmhagYh#Ft z#~l&~hWBQ$+rMobkb5RiGc)(xQMTzj)i$~0S7R=z=_WO3pLAP&hZ5Ms&5X}m^4`~0 zR8-hVi#_hPa-8;x&ayqlhavL84yn*VjfB=qLJYwUs182;zurp|mGS4!}4xhdZV2U`E6rIu; z6)QIsvp&ZN>&-`IazO`;u)a&FOAKg%sA3SS$CK2zz$NG z?@Y4(KVEbZ~3aBbxiJ^!^KG#K??hGut!D90qmMt>GHztQrzDI8Wfu?@{ z9q$Zm;KfkA@7V?LIaL-x!_7(k4tdc1)iX`FBh^7AeK6Y%p;%Yss@U_EdkQH!7rIkQ zbSf;m*tH8a5Nb_Giy1dQ-QC_iK0ItJay51?S)lF4AFQO1+bHQU>KRuPIpv9~hR5(F1DOpBcHaFX2n)T|Ktji?d0|Mh5Ila6pzsyj>CsP^KFVka*C0&1r0=3s4NNWruMMSf4BJNwlNo1 z7Z)B4V(q{mDk^fS0ke>ixg$-@O)_tPKU_cj1RVY)CfApJwAzFh=Qj*MKFgKllwon2F^4Y!Wxi(;X8PDua>rX`ZMZbkgZiuPUyeC~8#b1hh19Hx8d5QEB8SAR|1RNDMU@}Z8m$3T;Hxh*Ad zcL2xL598DdJXe(*WK07C6hwL5`s>8D}TA_<$x21}T%2Nq}CyhppV8Nt2 z%v&F-O0HkO-m?tpUkxNk?s&;u9!bSH+1anO#?jJF{vpc8NLp>3rZ&_I;vCqq|Mbb? z6!sUJ4d!ER$BeYp2GB?Azn%Calrs(6INp1EUkfn5-d7n|yH~3< zF609E9LSyZuf*)fG;*iyM}B-C_*w<{`)A@8x&5ahOT=A*<1o84Uc^w_JNL@IrFUp3 z7RpfLE69JTn|AJxMqma%AC-@~iU#o}#2foWlPq++ks*CVQ2cmjgN)`2sV4&C^P_E1 zZYzs}!1}rNq25J)J1;dN)|4s4b}F+>M_SsG^vk22 z1#PsC#ybm~Ta$0z({f+21wHmH-NZ?Ew&fvz(el)@81>4Yb%CZdgwH1SoEWu}$bU%w z;fwR*VF@05N6^WDAAig3IzOhlgZ88ZG~;WNu42$iI$h^A6I9bKBEAT^NHcm2r0daFA=Sh#0c;_FFN}8fzuWe&{mtU zw0detz?>H@_dx-mtRMyfTq1HHQ-Gaa`bq#h_k;T}Z`y!aBT#o~>rW^rHauc-dv*A} z=i|rU?7Li}NGT>79}<_Gjd}3vQ7S65BaFdJOn=kGL2C`((2Y6o(2h?{Oq}efGC@QA zH00~x%R8(Gp!Fz{IjRE8&7{jcq&@?vNcenXLgS~1Zmk$Wppb9?n zjD7L;?Lo-Y(g5oy7$r8?q9ZqK?d$>wIbl)#pE7`q(Fz_b;>*FGZ|pmLA3b`69ybnD zI7!?{v?`^Ql~)Lqlbd&yY;SKTq7JBB6{609zbDWSi2WKY7B6vCERPQ5Islq?Yb)dK zF`-97-B%q)ThhvY&}h5P`Uh}nCn6gRt*$IZPTvU$QIE`hR`~>idNgRh)*|)Oh^-|phYW^H#( zaCBIn?`SDy-l^d1WT2fPQkGu?cElJa6trD(E-v}R%thG<#Yrx~aD+9xI^5@8GZ8buNnK_1EgKU*>o*$1L3`?D#^p(zIC z$02W<2tfyOGOM|{dA$>ur}xcT&N4vdFJIEy0HgFTg1DAn*$y~px;R4gWpu{DeRSYl zNxp#GOImEuD?|Z?AHdMj$!Q1y3NwH#?mfjbD=W)se(cR}*Idw~FnrJp*+hT8Fo_=_ zwi?icajvvRRQS^*O!PEr+5ptU*v7x)4;nc|XxoLkF(O(C8Qbu@%gvAFBg5qMQ=t^`pOf>aL2QsHZu)$ zt*vIUepvucB|WBQw#BEt&rg}PtDsk{wxc~H38L&9+$z$)j1?4K67~Z1vU=}xLRX~e zSM%7OxlN20OfC~=o{piFB4_-gVXX4VGBIc7ct>Ei*IBaJPVffY$+G{tK6_L2eK$!^P7|Zza~@aSm74 zGDn3v_R)FK@s`?fKK1l$K>o4mtD=)X-Phe64mB`@Eg>})y73|?w1yPjOGjohRM;1> zA%vlV5DQ>IQX;V{+G-M-1`i&pvwW$o_8X3At=LjLjAF*YWto&GB%kbNL4&DKKL=wL z%G@lZ;6YHvkrweNF~MT4xiQ1C>d0P*E~Tf&V_H)5nXP+Mn| zF@z#jnr=Ekyt5P(9+x&y-=eyXj5Gt0T~aDO6m}fDfB-IJAy7E!z*fX9Bfc{8f|!>W z857@Mct+GTVqQ|qGJ7-TRge!ikOA2TkOlRCb|h{jpL7=^XI{d^6w&KufY{n^TE<^K zH9uc#=kOam1Y9V__!qwj;*?9s>Xe$+H`XFa8O@{Z@*hjp1SOO+b+S43L1j$t8YuJi zgcbtjD@p8H=s-T8mQZtQsKCERxn;|B^ds^LZX)a&=$lZ4GECc)kc{gfip0Xp#^%1d z%m#@ZSUDOgBhF#+H;G-ZUMnY0VL`zdh<2cuUSyiIyvI2i#sU-019*^N8XyOGEQD`S zk^9vy=${{r7H0;9946kv<{Az-KzB$Q{5a_RX1x&=sJ zCu=qm(wWr!6V&!WyJ%^n;e!HQAqO_Tw!ztFcb*_gf{i#cWaUXjxvm1bB5C9S&qtz> z2+3tCK(k@E%&Cq}unq}lrkG0nI4~p<8y-<3b{Yvy3sCZ>%^AGY7ze7Xnwu zg6B3yMrvt06Z8#aD%@n+sPfHVPiC;tq^m%``2yjNYsKUCV{R5dRE-t8dIczm4-(hx z!1r^+oP)Ya_WHtw3l+u1=isR!CQbsqZ=U*@Rx1_$TxBqXxo8=W6@%gnt=AD0T_JmO+zD-b62iitCeON|C=No98RmI@xI-es)y4= zYI(#L?RF~KlOJn1J{RkQ%O_frDBK3ywr4r`{x`7oEMC*Mzv zlRg(J`uG3!q$+(c`Mn|Cb;+*V(n#~^I4xzcMInTw#93bad5;QK+kie7q{1fDbWf6E42)hMq$rnxXj6xi#3czHma!!esj})k-Qht1Z+{AQQ!|{~?`P?6T z81zw`J8?jXOTd$*!|04b{xx{4+aRr|k2O!ZWWDZmGUD5dNn8tEG!*e>_-SDl)fw0S zACqhdG1517di@a|YR^f7LFHD8igfKf486!H>GE+C#|80}54Y33$1(FqL_n^60YFp` z;va_!_SU}B@sh8vZ>cp*pTy&cykU#_x7S~94Px93cq);B$n_RCh&zT?-xJ<7W=VQ6 zmuw(N-F~J2xrt-Z2P==nJkZ6tZse^M(T&>oOST(%fJ*F-1duJ!AV}lqEWp}K$UpeQ zlnEZ}hn2_%%+VV$*H(CxKrfHyPw)Ii>#^AkS?J+{s)q%4>@VydL(P;2O{-uTnQ#nrVJ3?_u-Xryc6LvWeKB35!l#K2W@E ze}CDE&RrdWZk|8+kYt|m$n_LH#B(tKxTA<3$&zDwV&WT&G=x=>lmq^s{j%rUkDLz_ z6cJ;@A;BhnFY*kN#8n(a%zZ2O#o0f5W+}rgj_{9e83GdkwKbr^eHL! zyz3|~6AIKMH-OMG=C0@<<;o-AzjekV} zB~GBxjOOgJEfnSZ0x?kISuyI5@~a3-0pis+Ffb6VNzlMXhM;bVuNI!JBp}GIXkPI% zIR%as6jt$Y!JrVnC!+;OdxW0{JR){`l;cRO>~K_=n;Zmb(4dCneOTnPfMJj_Hr8jv z!z}_gW*s1+V)(@!rY)%#fG9L7!Mc4Q5DdtY#QW>luWc4*48hr6E%Rm~#hBQJ5>!&o zevtAfxoMPrgoXi zlG0K(F)=N_y?gc?0r(aa=2f7l=s6YF7@M7ant1+E4Cl;h&i%q76B^(+W<F$hBy@NyTe%&9-^#oFQk8i+une(~&Cp^JiD}Gj3T661Go_ln&C- zs3b}ah*gH>R5<5uIdD9C`cw{%!G*l-6pTJtLjG}6AzsUne zfg@r=;{>bYAbO#pA1UF6IcT@TQ`uog#1ZRO+eAU-(P*TIb`K*6i{G>>r`Qh~w`Zro z{`3}};{iO%H{cty+%2Hajj;ok-K)4a{p(4+$qQtbqcV`I8Q1NF z?(?ifCm&tqLFML`?)$F35mH2Z8Nf_>b2e0+ss7rvkF9Uyac-Dd6=Pq-%^u% zo2FZ~Gf{6X3gv|m&hTo5hqn0Jei4WL)ZFRA^X!QfsIaW3{DJ*|IPFn+% zjJ=gat|$ICW(fE)a@aklm@%>Zf`ZYGe<-M)fNLDaInA=?o>|F?bV=tt0KrT)(+kW4~8;lk6svQSn%jaxtnCy-{6|zk| z#@@iQlU6wzW)|;;E+MkMWMBzUSD&meC}!}Zr5RNZfpNfX%#<>i58zx84-;`M9+A$+ z?FRE1`sw6g(u{O4sjxVM?1L>X76ggNK%YTdxJ}1KpR7>$WG@Y=?L)(dkq?pG&8Z@W zzrf0pe0g`{wjn5AKKK;0hy($mZ;k_~Sj3Fce>`AiYv(IlTU#CN{!ykAiVO z4Gj*|vVSYr*!~ubfi&hjTBE7I3`7(d78Zt6@*b8~4yYe63li8wP_j--#M-)KwFImO zccOteWuhL1Uv_r3h+KaX;?h~**E=4&5tR&+7C8bCac6K69}^cB2O5*XfmJp!iT_+& zoD;C_k2>63ZV@%w8kJQr zu;^$7k2H4drTCcAfcB9LTOsX&TQ_SLd5v8FdBzEUK6pP-xekgA6#K8hr--JNAGXGB zH9|EIh5$rj0JAHIrvK7#28d%)e~|T?jFSqE+S}WMgCNsqzF_P6YQwJCzohUmsd(WL zk5hvBp#8Kz%;EP|*Xe2j#}rA_2Le*V4MH7{mQ2HpPWqh#YX4A3G)35Q#HptB9clCu zrTAzGmXW=&AJSDk+E($OO%xQXW{huqS^ol3z&Z~N35owvWC+&7DCqxUz5mC)_-!=4 z>EH(*y|2-r;OERX{rt9b|LGfuHE%v9CMHpgEdKXRbo4spo9W0ou}BpEeKR{?ogmDN z9H8}_1vXgRZr63mh7NI`go1|$#ed%;j01jWq+|O}-BaVWA!*kFbWt&-En;i?+6f~x1ke&^vD8ce#CFxCrx^L{7#*O#GKDo za2DuQd%C-I$0I3rCcwf@d;`Sng|EF|<37kkEX(amPCFLnA_p?DS8da+a}p9B#6^l^ z+(tf<5UZHoc#96xSzx0>58+)9k^O3$en3#KPRBe{q8=4%>B0XUGWIxk=>H2}SYL;C zQV~pqEeJYifeU_oXgJ~8W>K$vh^g0}a$n*b0xnDfy!#-$MqKrf5u!n75Pf7YgY;;? zCyD^B=@_M~H-@dA41)Y;WMz>A8U=qOhc%q}q3b<}^41JxPTph*1r(E&DTK`yf%!AT zvil-xOWG*T*pa3&-@a9H=0V1pjvi1h+;ew&3+)r7u;nOBD`ED z<+4;hBN;tI>AH?<5b(SMrd(t%GEE1&wgPbA!k<6U!!Owq(;L5RhfcNNA;(F zgh~U3OMoC%qL#pr9X8xX;n7a!P6)5QYuBzhv!~31*gR6IQZq&n!sIsq<&4314b})l z+Q%T>WuidfT$548`e7`IEYgGm=6Ge^2sO^A)wzB-Dia(H7M7q*WC$wBIy77I?d~EL zKRqJ87?aV@hD1$a(YYVG5ljlJ8v51jDXnysCbS0zn zkT?UNbdYll$G#z4_v9(@&H)Z|q=eW;KVt>01oI$-?nNvO!}PH@?!FcW{2BumnM@rc zApmp730n8PYBh!r5L_A|hDj)+7bE&5&QfG97i7;F45Gjxqvn{J6b5yIz#>tnnerF2 z8$7~Ezi7!Ji~|CY7zz9knH>Pf=83+w6#ITl{^qr{HS;9irNSWYIlU2M&w|5#|L&?2 zzMvK_dwci7?OT$3rG=GB$K^EtJ*?+-_(DLuF4M!7s=_zTY419liT=p(JDLkO%#nzUsk;e2p5MHkA$d!m_YKLVq za0yQ7iKl0TNlWUN($d|uv|BvF!k9n^Y{E%B#KQ6biyHz0fEQv27;09v^y46m%W7-A zk<2FGGf34bp#WX>(G{Rc+X>X^ihr-oSar4B)z{E7)XN( ze}s)~=vvsZXOEXPrR$kFI7S1SV^_@v2M2HI>8-?+m6nuz#~4{^TAI5(14MIAjItu^ zQ(?w~VqS|0;HzkQf8^Spz=jy$>i=xo!~;ncJT%OuA5U(_c9ei{cf<(oam`#l@cExh zN;Z1De!U;1=nDcSq5o^`XMkW{cz&JcMkK)wlFM-w{y7}xI!A}3%9ZSHmv;b?Gr@Q0 z1=bpdC!KL#FG)yHzVL;h{2Ds5p>`v>gwt+9=8sB%||{NFce~t zGanZfiG$hEhtrh29fWKugxU_LwCB&B9T5@=MqJbZFp0amI66AUYvu)@&DhPzcom!l zCKI?+GK{Ek`zI{A($o1moySFq7m?9v;LwPjFchXeh;BXjWhtt{#F>guI$%D-+#ykW zb2X-A??*))gN8`)6Q%bhr)DtF`OmSj=Qti|&)eHI;v_Pms-~u<4m2e&VBogeyznRv*E{@N({P$e3lI3BYf4J{ zz-{!wL{?f|?S-8}w*3NCgjFtL3#LCPkySD?(~$Onx+KiZIDz+%gCZ)euYZ9qs@?a6 z#4cZTGT#@3DNt5cR$RRI;k>=a$cPCre+`i1WhtrmI2cV2vf|^}iBAJLqJl&KPWTmI z4q73b<6v}{j~(N6TXq;;$v{qOdLoT;z2~U(4Ui?61E0jEsNG|$2^Fn`lj<}AdzNw4 zpr@}d)v*33KIbYD2j=T}z*^{`!UmUK+8GJ=HwJO{ z!leSI%D?~qD}ibm#I3t2CMM?3;^NfzOH7kZ>gKYb6i@&^q4uig+OSfI&iuPHKYr}c zp*y>dT>RP7V^i$bM@6|VS|MgP5^~eyRfIW-cx=`e#0;g#7&^$RP|*-1$S~;iH)%Ja z0nF|l{xvcp4UrS?>Y>;#-bSJv`RR9G-$k^`w3uxB`O0w~&1^D)4yEM+Y#X!F6*VUcmWvgzFvb-KVm$%^@;gd(Zcb-^^;my6pglVBz5K0#DJwSINW6y8sSA zCDVis!GIzef&zq*=B+sIv~YfMsAt|nYIXrkN538bsQ3%^JG~a1bFZ7Ue8x?lK=*rq zd|+Co<<;Mg1t>BMAcbYWu$?DR`qVWhj7@REQhO6;St$Sw?Q*1Q-}rbfn#K6}U%-XL zd{wx%>O8#6#?9@EwL1xaK7){#bO^r}*msqFU&68%D#xp&tiO0fg_9LQ?`vO-=cU0q4WotSEa~J)X>ln=Q+~sjOdc7cw|Wpg4NVz>XaQ{k zWbF6AKItYcyTL_#eaUJal9X6pAgR1*wFJ6f3HVEC{Q5v+91Y3J<^{7&JE&KXXyoMN z{y^6(2HBI`Vj{9MlE%!!f@3UbH$n>t_!$`n#*j34Bf*{BGYp1X?ifJQYkZRzy$=+e zimEDR0f9hhxw~;cV1BkxQX=;Dy%u+8tmi{@?Lo=ezW=lj);|p>L!Ge<%x)Ff3zzym z_rP14@H61YH-0QBc>o_=7^+&A#cT8f%*@OdU9R(pS)djakratfgIO21thQqO3#er? zNM;JM77YywFgH{{iTa3d8@8siVmCMJr!CZE~J29=|tjZ=nO=So|v9K zf-Hh20&gi2V?w3&51HLHhc(j1MK3f$O_!>k34%W910zL12YxR z^7BOyNOUJ}P(Y-I-|-O;ZavT(B-|&4!P^=5w}Tvpzw3;e8a*rvvmD;t_o&2v;;9P_ zwu?H{l_zeUku;0MMgq@C#4(}VO2yP+FJZS$NBqifq>7e#vu=_du zCUtm~4OsrGxG?hG{f7_NKd;(GMb(d{A|fhk8s*C`Fc9*xXf}8Y$ANc`{-7jntD+UN z8Tc3P17X1!&{1HQ_ehLQnP&d)(9s-2K0*eZ0JmBXX8=4pu5BDKIBUh2Uw9?z%ugs# z{{(;-GROInP4Owvh8(=hz(Us$@kptdJAQ~`1n!nj)QJx*an`KM;lu73&<@m9`BBYI zRIV<$um}h=e@(?+sf{+i@bja*r3w(7z#f7ZFWg}d0hIUGv&(z)<;!_M7zuFuL3qWE zzn($O>y*^0uC6Y&&K0cyOy{mfs@g$1f`YW|mMYS=ASTszlm&%pFTf#04h5ygehriW zEN$-1FV6bJc;1g5|T?7Hl%8*#$qD}RDss&CNv)QB!!m~UR8g%E-;VEO7r*DF@5Sje4XJ(}31xgpU<5Ukr zXBu+sqE3JLo3OHYJ z;XEJ%qybk;*Y^MhY}{Y@smH+kCar^`qi<;FRUi^_Z20*DP_gCWlsKR&Rlr$gP)%!R zWu*h8q7Z%k4ki`wLaM7cAQZ?gA7E%Zf9cXRsOc%7ie3Bm&4q0E*WDBY{G?3a24U%- z+FlIY`J7Qy3g&|?+qd^LDr@)R&bFhK1$u<2co8>^cYbZb{rAJUeVChDmbbJ=`y6li z>IX#jKwB19t?2xIGy)&>(|!#NNr9R$e|4b`%K;GDlJCfis6kq{z?+lc=9WQUNpZU_ zVk_)ILJx2LyLY+MQAG#xDTRQ}A8~QXZjCP@Q($hpr_Y#huTz^(A?e z#>Y9B!r(_fgrud9TKiheH8@bqX>0Mx@|qg`V=R;ARy501d<02MsgqnsKS$5hUdQBlFC8>RpigP+7pMTl=1oz zUAzE>45^BMWoUX331XqcM-Q@V)4({m0w3faoDP&hGGIa>GF5(LW~gyn@kt9iJAG)Q z=PzFLd+`E;91Q#+UT}ANBOEs*gGs{*k+MuOnc2-ZVrS*H)7{}rwy@lQYKBp`7DTX6xVq7NB8er zU=C~eRwQ)PAES1FeHK<$Y(7EQi=Lhya@RUKhcU_a6D2VMt?5WxmN$WjU|)+s3)jPm0welaWNuEPBDgg zj={X_f=j?R#GtIKjOtVYI`kqSD&A+b*1>*4EB}v78aoTiM#wblgYdeGYIL3{ZKGMQ zGeVHrAlN{4rUqgFP&@$+qZ+5md{G3Lsi(J>8?Uk;O;uNsIB<;)ve*w3eysP89P4B7 zqa6|uph5d8UC(aueH!>9AMTc!;bw0fE49&2m{tCYG3Kb}5!q zr~FYy<S9Bj z@_0ZQ3}m7}WC^PIYjLOs1jGZ!N+9au@7_cSB~3Yqr;@U=N8m4R1Rq7s*T}Q;Lc``8 z9Q+lq%p~E`fq(z~h)L`7K!2pFAbs`%RsmLcqMHSZy8r0WW^jvS%x=GsO}Sd-Omn|O zQ7>8o(&(ce?16gRJBQ%H>vsgsQRav>2p;ae4FAvkC3OBxg!#om$zRgM~snQ5f(z*?2g7+rn z7Z-)I_ZU($dJS1{*}!PUDCMuvheHa>qO?Uf{^!r1WYjY-*?&+55&WnezIZ)N9Y7m_ zm5|Ac$#HaY5&{c^e%jB^PpA6i5(gMRU7Ryg`mrpN08@MD=p>QjR8>_sYR%8g*nCVW zR5LRhJD^@B-4k}0m$yFm$FJYN@8ad{OAdJdwC zK((NUeeM>t|0a_J7eYvYgfDJxra@!%(U)65or_&tMdgP~b7_@$=*Y;(dR04^Ss)Ud zmGj{3bHl&23tzt68>ey#WG`N+sEU>fnVeJ-oUw_I8>p@qxw#taYZL;KVQ9d@((+SR zR~VXc)q97f0@w{R*ebYuFvVMvJ1~#-`oFXdhNx>Qds>?TlQ*PqLKEt37>xI4{Sdmj zEDCaz^zSeMtw%n>d(WiN4GKEXu_N~;tHt#QMJ$r2_DN2-+0>c27 zW5;OzNV|iLJyA)_czUXKcA2(eYc;7jH|tgB(2)B1`(J>86P4sAY=dAFdmmsK}(y@h*R=8cIb!DOJapfswz?Y)H;NI|?ig!KK4hRg5Gn`#(z z(I=N+QSm@{L83|ZaWVj~fagrG`;3Xz8_0Ve-FLf?DrC{FSghCvY?xzsd3=-h2PB6RM8X z7H@AZi$spYR$RGgOJTe*0Jll%uSYk%E|@@|8AOTtyw{T_B;jFPI24W_pubNbmQ)Wi zF~S-@?3x7IGg`SDw3`T%g^~8RNI^{!C1}F$;01wqz^ABgVEy>rl-NICpSHXUzQULZ z+_IVDj$H>uM3%V@cz(lMPf$Jes)IuWt&g62w6ho5Rv+?uyZhP-4CnQkrs~^^lWPu% zii!?`X9I#kpTPz(YwafR2?4hN#d5G!Qy9CZLaIa;#I%!9q#SOC62KFb@uSC%JwkdX zO^9*bXLD6Bkx)-yM_&)>g^W7k$I7tCr1uBsvUOsu$v@AkmlEtGDeP>|D~g&9u=;?k z4}i$LcA;RTKZ%}HUlhqeJOlB@z|U8f_! z$HyZsj&Qr1_aEcI5^s!@BrjQNiq4COU~cc|;NE@@*!$?U&?-!{v=lfC5Z)GzMQKfoM;I1n>rqG8NZGZbA$C9%RtQ=j4@|_wV2TIXL(PXamI(HX*;4 zFVEv}qig8KE3MY=r?EsVd_{$G03>~ak3&IKdevY1vQqnJLrY6bt_Lj*%_TGg1Tky7 zOqPs~B>|b?c-#O~8)?sZfkpzF3=6Q<)2u83_h%iCyUe%`iPfRRz8DpR1g0zoD;X+oNqDV2ZY_0 z-YFv`br`R66S|pa@#}7em{K7Q=XVHX+lznVI5sV1gYbnliWBbz;K$I~5zGUK0NAv{ zl|`sIuwDC(mo6+WlIX|NAdCp0_4M2h1xy_fI-6HC6-&;b~JoSS2~w7GN-oP1S&dq^youiT2dH63(A1sK-Gx? zRcP`f`4jzM82X}%7cbt~)9Dgv_fejFt6?kB?8Alk1dt zcs|rn{N5cXRv>{TG5#8(nsyY4{KU7rKagVqF#biU2Hi)w{q`_g@n!S{}+4T;n#E9zE21ZqDd5? zp`oeLqC}*PwzNxW?}=zqQ9c?fqD4Dx4Jt*YMMJwZC~YdO-|@bm=l*_wf5g}8xnGa_ zepR1$*ZaE8^Ei*=IM3@>MIMiDwt)``=pz`MQxJrU`0cD-;dnc(>Dodl*D1ZGntXSw zC@ZrgJ;8dwT|a03bA1ok@f>nv5~zMGBXEN}R2y5JRf57J2m}B^Q%r^1_BjK3S|tIG zF$)$!m0&XNvq;4t`?i*Qdt#uMBK&X88^C4YYn|I#=CM<;<8|*1p)%$Nd9`2I;vX2d zA}%4JfvrZoGG*mma79AES%3cfc&v!k2gC$yUsF&-_nAdM-!K#hB|!Eo3y#E@xj8m5 zu_!!~KhF4T1$GBYA}eCx-3Ju!bad6IZn!iv4PyVmZK0;h0H)_)9dho*+vd{FJqneW>_A5jkN}1CG?p$I7!B~!%S#gDcJLPq z3rQ55WcrUhVh2apOZ0# zvR%Oo*+1sw%}>Y(ghph6A|u%neE1%y>BP?mXJQN(hgar@UT#Lt&b2}Wg&b%czzkkh z)+Z2t2u2WHnL!9y=nCT{awAaOrUT**cku{X_e$_a_)*T{2^20}GQmsX!Qg~%ec)~J zwD6ifAxI90?cn=v#$lRl!2|45?ISXCn1y!--%JA$Yk4l=q_DxiUVxE|_&LnSjO5br z2RPPQj6)_w{mp*-IK?fTDM1ij_yvd!2NTtsbLUS&S;JY;t^r}MnTt*l99%EmjopNV zq^`afwHn8fBU{>pLGca2<9C#Y=RWoxK_sFc76W64uSfx^MRQybtidy%xU*C-PzgnW1-NOeiYV_7kB{} zruq;J3WhjGkuCoI^M@Vp5(A8)5CFgfI91)tB~BE&H8h~o;%A-5;t{+PYKH2ru4s6U z5c`Q}i5N+!hu}o=fM+ld>RfBS|Xx=I3w!UPcj+FVGl4Ixm&a~%V!R1kGCi|?vEScgtv1ss|r9CXxh1bhGb zpgFp9axYOFH0|mgo1AO_@mLQFj*nfh7Yi$yA1_#)P4MD z2p5s4Ni^yO45BdvUkZE2mrrGw#zGXQAj!`_Q3?e4kFkEnpav^qO`$Rp!aTkU(F0g0 zH`f}p*vq6OZS4YV&(Y6u^@LCf-VuXjz$c^D`G}XhxwhmuA%nBZ^qtxW3JHPa%K|cw zsFXJmB=F_SbXZ})f;ceL7;$#5v{VAgj5uS+;EvFu2;mp4=a*ofBa#S;^>^Lfu^`YK z(f5hs1{-B*dAS8i19CSZnz`Z45@IBPVns&6JPxfkW`cpHuCA)`gA0^M*GT2#J;g%c zOiX}^356IN1|>D5V`2QhFHkWdMK)t}BL*`mqYub7>L9Or6kMRh76y(Z5GJ;^F|?&y z#($JS15~nJ%hR_>2nnGCZcEq64<-nKHx_Cb0z?S0=uzUbGl0(!|K5Oufk{Rts6|Ar zZ9y-?NA(zcKmg6unDDNM5w2WWd=*T|FMuP6 z(j7G+cK=!Ymo8*fYClDvn|N%3jY2%?aXK`BmqCbixV`}a8B^+65Z!j{+GU0km5_xl zMe*N;^_x&0z!%Q`{yhQ*)d2pv4yVzr;T~fkaUyy_3AhJD3aZ(}O4X~-rk9}kp*=s9 za1BKpDik?0NW0Z|a8NyjPL8-A06LUr-@YIqV_^FcFhPi?fdq*Ma25)^RXgvMFWfD= zFy9B8o7fzXFH!y0@KXVu*KlXOl?C0Js+q+C(eSCHJ5dJS0i=&0kv?p!^>4JGjRc(7 z$4{RKd+c8-t_=#;qf&DzuVRve;1#A<$LbMFfdWSz#2l92wd%wS4q%47udkG#-g*&~ z*hg4GG=vmkk$|2?;Rb=a90H67w7{v6Ooey@s!5`#w3K$w9#BQsZa+i0NbtAV&}}$3 zXwgdl)etA~1jzuBW&_Tm8)OtHa}7}fegK=TuQg9#?_~Ta_cxruz7{}{0arCDqJwUu z(dIT?KZ%kOJCQCbbj=DCuNij8TckO3#K#krRvw*(y1JOhLaKBB>Qz6SzbZguNG&=y zUu;6t`A6U>+3VL2A;g)(=S09nY(nG0ZlchDohBK3Y}+4#aUzs2tQ1I{^I(HA`hK6j z9j!%#c$}uIAs<1P4^2&dMkdD8kZ1TV2vxQF#pfmpxG}wk5PF|Id)B|&HP-Y8qgG9D zG_if&?YI1mFu5fg1SKW|5E2)pKVggJTcCsqW)VLwFf?=&&AVg=SQX|Axz)A4k40F< zz_y?}t%mk}LK27delO4$bc!?tlH0XtU~9tO+GUsC6)97Ce!U1$6$Y{QP}Ty&!cw3O zKtUq6dvm7*dkI_S7(g9-;ehSI2qgewM)(D{=}??McaA^_gsy;{obkI36=n^1n`$Ij zjJ7dCX1v-R28Ah?D6bK7@S@TTDx|SVpvz!9a3ww`O4xEQ%v8@YpX@64{f*Jd$<^3j z^^gHW^74dWwIG5K_Is_41h;RbdpSZrY}WNS3$rsb*CC6w%U2N~nh?}MDG|9G_!^PD z@av6i90Lf3I2*9}UdJoF?rp&p^OL zOM9O}^#TbnXeTW@jFYA)UW2dzghvJkm`AUO2AK-&D-QMT9LbhC2L6VsDar>4bCvY^ zk}p0_}ki9Dwo-)DGd!;nGOvM}&eP@BT9_CH+?j9Yf(KLDa(B z^(e={WfvW;Cmhue?noo8^p_5A2qLysA)O&$JPZ#%jeU~AgTYV3F7pI}%*C8Ki24_l zl=9oPfSyd@MDco2>E1UKCD>%jDAW~q&O(& zu)R}ZFc(Sv*+EdnP$H5o8KT^e`}Uxp8siCf1BnoR8;}b`SzKvf4ub5CArp~rK*i3& zSPN5oBm6*7Lgvc1$;{54-Ac%c$O!~+1gJ4$A_t=dJV(pStcbFOz*UepnEc=2IJk|) zxoW`(fmjHtg_t^wFDJBa_}U0H5xNGBp5GO64MW#%dfjBFdmL zB%&^Ay)B_5*RhuZfir+r8=i`{{k?|75e3&89^3?4IO^(0fJ3XJf?Uh)rg>d<;D3)F z4@SCGM?H-5aR)X(AP4hzceWAHo-jWF+XA27!VyOvBShKzD2fTCbZm@pOi)@LIZ%kS60_O*ZS_0xPgN5z_w$LnOKHV_zg?|%nXgU@4*pxog zP17$u2~hnE6J2~;Sk`O_kARrnAq4$0!$GCuMM(^X1#5%C!somWC0I#+0(HYR5svfT zjJ;5?Dn3OI>n|Y*7fLCu5vijJMbi5FvXVUDM~j{!0nmJ986r~@A;=St(AZ|y6t4s% z2u>PCMryQ75l9v@pO#={rSRI+UvQHdqt0?zWPl1}9}}$dbqHvSmr2BJ5yTV4oLTsX z=_O2*$b%W1_xmOh5*30Qq0%6Hq^Z65V6c8*G5CFyDbO*Yfdj>+ZEMIPTnX4$y4nn^ ztb`W;3Kx;EfNvoS!ucQqD6=K|bMN|vJe~Dmo>)*nQfsn zW4o)7);@vIj}o(ILu1Tg97aM?iH{EjRwt}(*plCIp1AorZ{p+Os4ErS(P10%>ML^gyJyI14EEItIN&jk(RGSzbd zKWk%dY)O>!zBcL6BUw}(%V79zzmcz8bEuUz#FZwIpo`+bTB_rRRJLqL_>L-K*Dwhf zZAJNhVutb?G!yL1O_e|zQ(vZnR=KGUo{EILsFl~Yegjkk;a7ugbTug?Cb;J{L74&@ zLU@XER^LNIbA2t8=yOGRL&MChJCJAu$;kr4?nI0X&f4@N!Gf2`H9NTa6+#OXZ*MoW z_+{)HW7{wz+-f-EUic4JNoys{XW$xvX<><4yB$Vt3=Ft!8PlF_vB!S=OByY5*_NUs zjNWLM|Iz$>3-&Cbg|^JmsgGk~M=XdeqT$`jg_sMNF^%a8x4IzZAdUDw31CvpI6cYjE|m(NZ)gN|@PiYIt+6s$yveB#9J*hVPC zPrnM^@evll}gQR5bXt4I)!x=y*N+lBsrj3 zu&{&h6#~Cwdjk38VJIkaUB(}02U}dsVGhXT>M8pDWbcoC`k17&b^G@ImNA-QO>0mB zIAFvt#$AtJT-^C5hM}+^w_v)^e$y_QTbSdMJIUgZl2;9S4j80A=U2#T1YwhX3t)UH zMmPxGP{_*xhD&k{OCgu>NGXz#GZO|2*XkV)a zO$&uE3B$cV3GUfbY%T?J3M4V&_yI+`VIVY){BELf0y2n74nnX6+HkcdVLsQYXYWI@ zE*wM~4^Nml##@u>Op+4HahpeP0Z5v&#p__6*{As}tv_ZhkApkWuL`!{U+nDJ#Y zeC+I_$%U|O#KPaU(dc=Ejcwy(L4O5CBLDB7x{3e_6MX;w{83L$J>e|>)MV7m_>2HNN`Flm{ho)uF%s&B>dj-=0lA*HZfvCeg`P=B{hO9nRy5EA zhk8=u*=bTlgdBLyP3Wk1by!5E^?3ppE_^jW;Pkh^!VuE^CeU>|C@F_gCvM|AK58Cq z8S~E`nDB`+1zyGld$$RHmfh1QT=n10g6aL@rRJyV3i9#>+f?H47y0k~ABB~0`QT?f zI6@&mePY{*I-l3!8I2V(-vwQ+AlL|n4-%7hKRiz$ z$5See(bReoSRbW6+E@N4PsL+Vr*Wmuaa7JPkOFQUA#z&AG%g3|waX=3)^G;QfY1W= z^qpA8Y>(AKY<(171~Y%lcqY)~_}CP2-gl9&UaGQc%bhz@4Vu>viKR)iv-ws6)? zgEQI%?HYrg!-08-1`y~&z}jw}o`fDwjN!ycN06$znAq?Pn!q-e33!Mfm|=oKF>NUa z7Pb_XKqJsAlZ=mKGCIvk{z%L~S~7%qisBvTm=~X}n{ju3WGw2x+tZ5pCQv*3Fc)hO%v01Ym43X&f7FK?Hsqby4F4k z*zV>Ik5o`f%5aXhc6j`*A3w+~EyJTN!ylVIdTbj0cw}k)oge-a`O0Fqm{;fZzfSp5 zv=4P-1x+d7Esqn?IwDg~h(T~&e#W{GT?K@t3IpA@vBb($HP{q#6R$6MO5qg2IKo7O zP`#a~<|=_HEL#${VHU_Ultt)|$pN&JoR_%(w9q4mnfhm7A0g!JO)8SJTS4g(9YLr< z1;M-%%L#@)I3S=_zfTt%i+RLc8&v46jVGoMn~p)RMPCLe_hg<3vfMmCWl6IJJG#<7 z5ALuYz4Nyl_-$Od&EEO0Z3s2y<_*3Gvv!&=GoR863|XmnH8{I&nyeg0aT*1|X2P$B zB0mvZov8T`UJ0oaLtgJ-8b@!>l|6fwx0f8*mW$%DZ@~qpm*CW4jG3-(BTk_yW)R!A zbw4)6J65rO&4ZZ+S4kgvM;PBtx}1Mqt@z}64FyLqoj}I)$`ZQ7FI;~%+;nS`os0i> z6NO8{3JSOGZuOh!IPBYHA4_dy{MH#e}Sje@6RDM>*>R{3a`&{Lbkf{OcST7O>>zx8&AY)_v|` z@Vgvi?5dNkt=Idd{cdfFs0q0#xey+gYdZbuFo6~o4kwdE{}(gP)SoyxRobMSXXc{( zl%La}@2D6PRh3CS1IO{JPCX|MRaVzed>CR9)8X=P7dMMfdRe(VPtKvtB)MJ`=Q#H4 zGFJqP)Z|ksE7by?@1v*8o`EOBo9VrL2rTkHe?C1Cot?2u7cz?>pPFKyogEl6Z%)%- zx$-*Zz$ue#pRxxDz9$uwoZnobqS_kUc=TA!p<^|bU(pGbt&x}f(Qh{_Qq~TGWOwhL z_9(gCJLMKSa6RJ7<(c1Q-RJp;H*xRb|KM3z7}(R&V7n&|3bOn0=-upa=pD_Zi|mXi zVv0&mQCMDi6~#o3Mv96=9hZ|PX8Ug$Q|C=upXaVA67!4Tphl7x`mpQZo%>WYp%Me=`~G5%1Fc!t~~M-6*;}955ygxrs{RQ zR6Z!NTk?8q{_BG$;8xUjqI-X-P0gg#VVld;8-bfK56V1mMzNci$r`aem9Y(fWP}J? zT#SeKQ|dBF>=F}jM5zfhT&x6J~ z`BY|i#j26rWYi16(ZS6lpTygbOZfI3I{Yq2sSVl@=e3^ik2M{{efuhf2Z!XD`+aTg zmIc!dY=;~6DJbUU7;SrV!<2(_e5!2MKc8OoKZTciV4S3-YH2}Gsl=BwV~5|zvG*cR z*glG(C@;rz4-AoE+);{?WswJcfpt!fO9u3ID(jON&}{kbi*oEqmrqYz8~8#3?UJvR zNw&5g5Nf^A{w5;srrlb}nPLa_zCP7gkstfY$QxsNe`(78v&yvpyMb~rlzK1iL7}Q( zM$w=k`!{FrhX`?A`2;Fqi>+eo+eu*e#^KD8lHWs_DNM5T)u@g~yt|s3{9(aftCzoLiaq{ zSbKaz>Y$M^HJ`qN9+RYR-!siD$%~Oio+~_v_Czyy%N5PV^^F8iU**y8hv8ev_8l^$ z5+W1yOXc)XQ?*aM_S!i;qd+I)SJ};*YE}ookriH+PjZ$$lS8&EwNA20ZpQ^Cvco$! z3pS1AEiQ)X&yHmk6fRy9xZD?(uk{I<#z*tw&n~`w(`z0ZLNPIVw{NVt)R1_Cw``Yu z_3D|o=c0M*(fSyX;E7D3x68?9i#Cl-J`B}N*uYP&QDonE9DAM=Z5b`yJ675+ayOtV zQ9kBc8I|qZ!ImV-@1r{YyG42Qf7*ZF!E-I0i^r+IBmedD99T(uErk!?r7=&q-W*4c zY$`QXE}>w$%3;XX2iZpN_uecri=Jp8dY>%c6hDV&iBYX{yWFFIAmmTL;aTZu6s1HPkTRvihTLvh7Vxt_!u!2 zxnSOS7{4Uj5#GgK#?w|s-}feLqm)$F;4SQBc&U=m)bU>0n<_>5T~9F!CF2dgvM)0e z2A-EM7wt3Y|4V9W&&Vtqb!V{BH@>KMpvNoE@P|6;;BI|NETHe}w4G+37Xm~4xHD%E z#vc|rJI{0)v;6ATZO{CADRwl^I3U^A*Fd`d9?gc}%hT*whCoN<%XE648BI&G8>M8V ze47_q1{+j;%Vsw(f)<( zc6Hs?oO~{xoK}WCV%!gQV})Yq>hKzO*eeT?Co5Ca?3n4$HV$sTswn4|nA6hB^QN7? z?Uc(K6H{%E1^)Z{hD*L18y#XN|CT@ObooeSoGW?Jx(930K+==91%H1N`(fj%+MXUy z+gp)zrn%q0A9y=YwY(g>lh!NV`($P4!Qk_( z)Q@7j+cnQ&38dOf*x!pg3SUe+(Qw!L<~J-+b1OHPo4Mu zI}Snj00+1;+*Xm>bPPAxj!Ez{uUmmS5_vW{~b}Lh#H-baA zz~-xoiPkO_r-W(zn1VcgJ zIA%YSL_5FTvtu;3-uY2i1?ZCazV^5#s3=md4(?`&J!y$pwr9^w?=<<3?vAo@0Y0PI zRz>f*d66yKb#}4beJdFlqVe?9wtf3ZYb*3s0j2)*(Y;)EX$-P5bm?*1G$KN@Sc{0b z*JxUbYN?k-;^i0^sH%R+KPgbo>Bk1#7wdlQ#}<%%irYe5Mahn^9Xh=EYF2x?{%Zwg7X#ZH4lQgV zA_9Ri7zbyz}Bby=&i(*=9Lu z{nCQL6TJAbs|Ss1_v4}rS{56Xrf=4k_S^Eln^@TRudnecJ}HTPdhD30Uiwna3CWmP zdeOe|`2jy^ovPX4nV+v&e3$%;=1d@VifrG-nOXGSeEQmWcLxpC@%_y7rlurJ7ySOc zC?BH+@m6fS8Sq-o_H7B+UB!`Lp`$bKJYcnrn&S8GY_kWD7bMB4b61y}GR~eY@@|Qj z3YOW>ZY$0+?LJvE-r{dq<%M~gn5I77-!DR$sgsnJX20jYZF$-Sl>inguM6#19p`^z z|HVQZ5*{h;ly>3^{hV~U?TRKZxr1w}wOZRS3xsC>&r_Tck9dA{&%4ggb05Dxd`{jh zInmaj>Zv$OnTK|82>n5ck_aN#S9h5KegxCU+#!=+`GYe~6~A4#ph$M#Y0EUWBUO9% z3@S&(N&Zkac=DL5#6@KC+ekSJ%P!pli^$xUN$)cCW4`Hdo`4-nQc#eJLj}xJ@Ti%q z2d~sYaw`4o z-2C8FDYc)uF4lfN62*2sL2A`5V@ai?a zd8#PkteC3wS zb92J<^sq}lE7ms5sA1ydYI*7!|2&cGL#Xq;li2mLZijEEY~vwsoN7yKaqKC^jhmTSr$-0k*MGL4hxZmyubyEtc(f=VHR z(9WGC6`9}TJze}pcP%IC+3wQxcMmY0QG!ceXpvj;}MbQ-e_Nd{}5 z=(BZnuH$gcjl>w&(uK+NeM(hh$QW!s>^3c>Ie1aozt|BWo8LOhu#Toa$CxkrMLEm4 z&^PJVGA=0GTJ;ibOE*`k=Pj%=FT)BR`ga8%J>t1=K~>E#=jxt=H@UbqZXvo-^6_g; zj6UKum}+Sylk(8=-z9RCqjYR5nT@eU2KQ4D;nT?Kngk;d^Xj;gTT!e`dwCgvguL3r zL=BF5Bx6BcdF(vxBga40Y%hFsT8X+Lf%Ong_SthfH>~J`f=EbsS=UIrWxilu@6z~@ z#-CqfsF{08{zfD$nV9QF-kG$nZ-{1b9Cf2&wMl)Y{-)slSIrgF0Q)36vuzVbm+W0- z8+89TM$`6AKKrnRrbs;-#HC?W(Ay@7)W&-aNND&$qq2NNW~9bzyw)kA%ED zE~MU!nV>xmAx${K)zw8EoyD|fO@Ayb)qs@7d%Nw%!-v{bq}GRJ?(pc1Ka9DNmgTzg ze7CeJK#{n|Wyi5N>5L4xwOK@aO?K4jTjG~IEgg)Qyus6zpx`@*R@U9gxWchcsL2fnVY%Kw_#;m9YY7Jd0vBKjp-e8tt^&k_|G6~{hrcvY9-={&RqI(S@Bvt z8xNJNERUff>BBkKZ|TKdzn1Qt5lz=2%0b<9gRBdRdBAL79iJW$wfZoxC#P^TLxQW! z=$_dpx&&Y+0lmvFnNEFaZr=2(yEMX}Hk7Ni^;wd<{ra*EscU9X+K>F*>N3m7NcPRx z*v&szn!izuj5KF3FZ>)~+gE7YA-VB()U_hQ+6W&IjZLw&BALmfdD-EQf9Df(j z=$NPY6@Uhoi^=|J<=Yv$DaA9gRd3xhs%zzpkF3syvGkTQXO?^t+0K6KUAHZ6b;$WX zTGI5lDxmk{0A5O*gs#gkhnm90zWE(n2RbTT?89Vtv|Rl+ZQK!<2{G8JO5w94m!NrV zmg!`Jy2fzg3)pE8j*1qqZ8*KvxUlo>pBS@sudrPQc@Q~2;EIZ_)_y6}_@PuxFdg7OGlS}<&WiuFwwW`CAH%%Q_1PT#6rev9v$P^ct`KICZOc`O4J30 zqYayon1q~CM`jF*hC?e2m^bJMtbWNUOHFh8ZYjF!)jJludNX2=3AN=qzwTBX87Xe7 zEuRjyn;-K;;%?7c9RKpM^@~ZASW9!xi;*@Jk+$TIW92l7zy7V?wq_W<-zujao%non z;tSp@S26>)sb1NJB#4Rlj~@rmImlnSKavE#FTrfb4ES zX@pq_gFF6z*QZ>;n$_i)GEaJ$jpEuSUq1a=qN3lWUvm0d{LoxI+)kVfJTskn=l4(@ zXJg|*9&@l7SCt$4><`Gw>cezMyz5cKmgwm0>$lBncPS}RV}01A4icf`kIts1yf0tR zXzz3Sbz>(v@9kS5r!q5~AJ#NBqSWkg+Dj#?qoZp;fB5dw=+EwsxFL_F!9xJes3sBH z+$M82RV>Me-yy4+Z?f`Yt0G>EPOgSnaXO~mKQGFB{66fG&CNV z=<7wAO!D=uYtq#7NDG^;y0w{vyMev`YDL~zTQU4Zw}o>TE9sUufj)Ly9Twlm;wyQ& z(8eEm^2ND*!17PUo(BfsiKNpiRyV$%2z=QTPx4u#iaT{?V;%ckE4NxzZE(LD-`nOI z`hIWMTiA+A<)-aCVUyO1H#4})i)lOgbOfY&1f_@3p1)i>Wcp8h+0kl zNRbLP&6YP#XmnDpc?kM>ZGdmh-+A@@uPL8iOe{P>Z9fd%Ch1autxPm%GX zt1bKySy~#<(2m`OTCY>nZsYjP&f5HewZi}Q7GB$mjN(5!35)$5C~=lPyLufzPUODl zazG=4qp{w*4yaCcrxeXAC)9+9(9=&j6-<}@&UtgWrL6SukuAx}zqPX~hf5}8m+B34 zy8pJ~lSLn?hsRpEPl?yWOHJLiQ-7pbt(ALrc!iXb@CT@=wOmSa{(eYHU84wYDw`^* zqS-sNe|x{Trkd(ACdp2IV}EoL2Y-&EMpU~`RsUQrMmY{eKVN%J`lXg{H{1ueg)O-O zKd_5-@S6sApI=_@PjcrHV86N-E7|7y zzA~G0aAdO}Z5NLxUhlp}hePkL`&KI=-Xv*NAK?+QGRex>Q&JX z_5@^Q5s~0n+mlPuK#f`jmo#)KjX!7&4G%t2q(YIjm-e~7M12q~5RKxQ+lj9(qEt;} z)I};fRs8aS=hRMzxuZ=0utoPp z{V;#>)J%U+Hrb9TY?3{ui~T;OXmVxN|0ld;<>v7UnR|ec49h1yxi$xmh<1mTtQ@_z zHlKPOg-J0SWxAWDvBl}<)(=`gC+II+ z;QJ=VU9YY-XcNi6a05>%7ckesoZp-hCLBR*6=9#ZgI_hb;Ij^&`u58hv!`hp$cI1d zyXIaqJXPukW`u!nVZ5uY`Sp{Lmh)Ta=()ZX7G6r261ow&^47-UR!aOF=4>Qn^Dp&I z3vb_jA#2%sR|n-+L>L|J~RZF40BsrPa~2 z%#^z&2l8CAVz(sccW)eJFZmvFA;Rm=v}QvbGqO2RKpWQ%{Cw?w(pnX=Ti_nP8$KO; zHMA;j$PQql8$ZVdC$eE)1gYCrl#Zcf`7x+0oXs>1JX$*mwNRmZ?JjV=>?c&_7ur~| z%D}qm=^7k6TwN?{)AXN2MZ-Exp^=mn9Kk^k24ShHNDTLiHFu^m30BVx1`xDw$ccgj zk`^DE7NK>6`3-#FY=8gVp#xGBuQjdku$M1$mN?lv>flv)Ej(mD^-WznZIh;+5IMHN z0jXDTAwM|bk5I5VU3bjJL}#L8Ie=Q|?Mfyh*VIH~BldTq@p*WimLemIk{^M9ZHU@a zxj0xd;dSw%ux{avlQvHFI$&&lR*hNv1Ay}Z9`M3(4dSfiVu?;^>`P~7JmX1WQSRf% z2R?F0`OMK)+&pm~nnM*XitH+AY%~cCy!GeT;p3mw)f1Uy`uMF#=PgoAt9Qs<*s16A zaHPvz1iecou7!x|S|wjzJUb25QYDOq6u1M16BfVirQRBc2F#uul=?ZUe#cmUtTg+vf?%| zXLfMpMHDeI=Do=E#zlYT@ncj6=rP>XBuP7Phmxv)y}JC^VgiRdbA@6HDL1$0K$P!_s9bHR4U3i%^_Q<)KYzkL(Xk}pl&U){D|<-fYpzoo zyF|AGs#5HWKCd?8G3CZg{r$$+z|^}XX`Ut3&{qu&@%;YHC(AAJRb4;B!t(Zllb=91 z$qYd7VXRg3Nu^+8*}x`@9(@|ZR}zT!DGY3)_9`dAgss?~yOAUp0AfHiY&kK6Cnv{- zMf(bUkBjcD9AoMTj+M!tG%=6Mn7Me~_=VM@rKXLA&RqFDR61sjH%4Ntr~n5TugxsA z7g81W+oZnMxU7j5C<~YAt31~xa~xA7(w>sYL4mrPAc7`}(%8+05R7x)*!`YN2HC(9 z&gYcFiLOgxc2en7$pmE>OfEv`&%xZYW*zBCf&?wYw37-a-U)aC;nEaDdu=XhjZ%$5 zdbxVIw4Zt}Q}bO z%TpNlP&ckj&F|cKyWvuTQmilvV4L!;vD@3d-nh&+#(TF9S8lHP{&8y5((rj~ZCYgM zo)VXg(YNzFrLI=VDvMkvG+!p=|Gu&Zd>%2M6$a~KTp3<5gJDajVCQGUr8anh_fk2> zzt)4AG6c2hC}iEAnfBVR+h!i*gJbMiQ-?2a%rc7B;x(6qPZvS=gt4wSbBOOtzgO%i zwRbO|Rt+kBl!Q_qMZZnQRRNFfR*Pbu z-#&lo{;?xff*x-GEm>Do@hZs_QpIE!i{n^{*oSZ$#%+7| zQ$WI#Y-+r@bL%recI8kBZNg(N>Bv)(RFD-9;3k* zVbLmP+oCQZ-L;d=|9Sy@m*lvil3u)cy@jnY*ECq|1y#ke5_eWvGUyrFgFw>^{o9QX z3AE7n;+`h(TSi8Q1aog@1%YFGgdTHDNG*5bWk&CXOc^Qv%^Rdy9z90jKyZ^ctPK05pM08a5Mtrhybp$;>;vnQ(e%>@GHXjOD za;ic^gfTF={H22u$q)ltzfoAV6S5C#Pj+Qt+)W&w&A+Ilk<3(ZQ{(M#l35jb7(kCp z!CJ|hbXZXE5y148E`muVaXheFps$+}1G=j5h-z=wN8Cb(&V=;~DL$d#BX@`Lx3Xi{{&2;9zdO7Z?o_ z^U^lca@(}mc}M_;&)H;HBXgm_SoE_P8Jmv3p-H^Cm25LQ#?N64EO8M#{J{n#B=2d@ zeu**?Zq~@B?n_%b#kr09s)bE)4MtMcBS`-F)w}bAmHu$u%-|IHxYXj-wAYT*?A--i z(89)kr0D)=Z#25^>0|t2NV9^%q5I|;Svh@^;emG~$Z)--x_|#Ta}>#d;!kw7Rm2zl z>GqCv5UK~U!MbxR84*L#Pw5B@^C&u+utBeny7w=Cb|n_`MA^b##3x%nR}U8nyG?U* zdS0tFj4Sw!6fQZb1wtGB5c*r(NdcCGkaqpN4)ksXc zMMhfqtUHEPtjcR#+XWdrQ@_{T7r}GME&-%@|giHdTzpVcCMER-3 zFy+y^VjNH5AQA8kR-xL(Ie)|?I;1B17j;?N6W@d7F`u)hr$cp7_O`sFWu(Tg( zApfJvUDUQE1+*u~C$nUBxBu%BJ`4fnI{~Rs(ju!#%uM zsfOyyjf4fDGcJtX9oZTR`= zRnW*>T>L(7C;o1Hk7ye6HZx}qJ-8w%I5A_0tJTZ&Sii@+B5V zyM8_A%jFJE0qdye*{Uexj-60Z(@Gt0Z-gG2e13P;Xrs;Uwu%bRbVu|0T2`yk#`(aI zJjt~;wfP<7OMQ!EpiTD)ytkWglz#p^n8bkHF8X>-qJP%1pGEnpT_aPwtWjdp+XH_l z?NdIrw(){jBk{CALS0()-JR|2scXOmVx((dkQUGJ<3nhY7Kh(|7_)MXFlm68;Mn86 z*o#J%w$@fz^j{FZ`sgKsV65KgLaVSFrbuAs;B|D_Vj8?3&{_yF;sFgQKY#utEbMnE z`79<1kFW29w7$M{UNimY*Lr^2_>hoqx$^dtQHg0gJr@1vn?zr}g#NPV+P-{q?m7CBs%!N}wv7ouQ@}H84RZA~;gx7qV80H;&(D8q9M@O7?WE zhsQQnITGJ3vyP8k?J~W%>G5^~#7@JJ{^={NtxqpPX1E^uFG=>mEw#j|kRF%2Nj< zjG-YMXY4fDbd0+DnR}alOLB5+T)x5u^qpts-s7GU)>FkGyXuPuyfDnkP}S3GFbMeirnsgqh8`?C2tIhz-L7)MFr3XU?PLD|O2+a!sp z9ebH4*j_?Xf_;OEjYx+%w;H>J9q5a!zcanZI8VC*DpoxCISKj?xc7r zP%T~GcOL$nenPh%E#Smv6!sMlnoV95u#&0{omhttK;XTv&w&(Ir8a^ ztLde4@;IsKY*JGrfu=}R^DpxhvFbQ(Q!H=RxZ`j+CkMwE@(lhm&qS)QrNz2p_({dVmMpFzT7^u}vr>*CU^= z){}}8uXbeGur!Q333w)Q_pVlOh=`QOlGDVfvd^#X6eg)}V=BI_oZIS2`GUUXW^*Qs zPjUR)QdU59`TXV%gGmQb7|Q|>f{%HTR3q=<&EUG)az6O592M?h2i+^|+J7^A{m9{J za~$z`3W_g3-1IVf8|uJ=PqbTtKS}v`?!KM;>ksEZ^+F1)`y>bhrJ8zT=UeSrM4w;X z^dCQF7LlTVJQ6y0KbvabkcL54YMMPqt*qQ(8oO=Ta4KE7qIxZJysb9Z>Iv8>b$#l= zLDE~v#)n5B_gHzs-k0_0jpje353?<-nA}-z5c$WuHTUeZ*cHO{i%aL zoRf1YF#W>W@oQIjgfWtJOXm)lb0CqNniRd+`gY+F+i{Bf_WFMyO&Q*4dUXXf5reUq zl+`hre(Ewlq8Nn3Wn?RioPhf*TnwUtsdiZ@_9)(wi zo}13zKAc2e>aq>IJpBZWp9IGc6l&9^i18i0kl-q>KtncwznrFf1tCydwE2AXa?36ujm>O{;M&ur0We#jILT*T#Qz2CK+?1siJCWP|C* ze$}zY=<`k{MMXXmj2RS!uN4~jT+1u8U-ZP)xD%wRrj#$3fRT<{=J^C zf_GW{U|~D;3*7nqFxnD{jV$J{+)*>N9f!|$Q|>NI*BQxiND64T`8DTV=)*u)^m+ZT z98Z}iGy5e7^Y0LZ#T_Nj-RHj)cLTDS!>@elthYk~&acoA)!bu^^y=N`t?9Uw%_iEB z?csbY^dK){pO`DgJ5T9_b>;bKO|Z~{diY&3cd=?B%L=w9DyD(apvRF#iC53uW(SpX zk&0=?z2w7q3!lId={`Zvg7a5Nh9ei16e$UPCAXdmF(oFZQm0TeM!NUBRiWsdw<0Xz za0fgGzh4`MGOSHlRQKsn4b zpxaL|^MZAo+X#J_rom(W>xBN8GCQpAvleT61Ntp5Z}5F8*WmPgdgv`o#*nkZssi-i z49yJsPg+-jkbx)LYc(giL`Ur^c|FN;*MVD zQ|ZSd?^1RNX0pwAs2WjxR$@jOEcKvk6)Eoq$jRQ(WtD2m(A>VO@;s~MXwzbpm_Q_` z4`V=V_%5gpSnQzAhh__W!Met&V4q_&_njtLi4x-c<^tOe;GjP5jw+_?_P7J+)KClU zxHd6A%(^`_(`JI3*yPC{&fyBawzP;5EM$9$hT-5K-^KE@k0NyKUn(W0Es`$@K+B4W z>CsWsea$4eHCagr%o>YNXARH#Qte?LgDE4%>9UR#4Gz&#_nGTJg?wLM6fk%!*m01W zB$^zCwhD`A8yV@@XPT=hYDB~y0|{&(B7TNFyWO;|C9y7;lYw!I1 zJM(cCXd#ah(3oDQTp(R8o>EepX_lKy_{Tx3qC~wq6TlL`eX(yM&$|>A8zg)(y8Qep z@@MTfx0sPP}dY6rn;6kF!t>tleGtih0)2 zwc&?}GB7PoRp&-f;H^&=#oSaMM!w`fC*W1||7bezc&yv^jX#wpC9)}zJXouixKKFAw+q`CQj|9_RZw&gPSNG;JNr zrnu}~`J+Q_sWb{Za*UgG-k&`}eUoM^r&Nrf`io~bG#0qex-k(w`hq#Q_z+x_F@o&g zJ)m}&&h`ku1mMvx1n<}4?f-@~rKGef93G*uA*ON`ThlElPB zk&1u86~0SaF;MY6L~K@DeBk>?OK|@}7^m)qFHnFozH)^ELxu8{ zp_i$e2brn`R9i&qX-4P2ksep2poTO?@!{q4KL6lS7M4qT@o_QG?er_JTz$&K_Q@e& z^KBWim3~ro{@nDI2SG^il975mpr!9w9y}{~`sYZp|33=yC*fR{B!LoSqcXSo05P@PUcgF zeWxX*p9J2{&QOt(#ud@Tf9|%05Bj%uA63=CUuJ1~?&#{zd)ODH65%ylTez5<{5>OHLl(A=&@AH4S%GyG+jjO&Wl?l4ODoY( zQ6E2Kd%=-ICMcrMkm>PlZk-zIQraQs8jqWI`;+CAgq>el{o&@<#EERCwr}?vt7xm$ zjlYsO#&rKT#Kh1~Y<;8Cr+B`51WHo6gx(L9tp zPcu*mQA*Fh3p!>e>7LWPvvG$n7PqQ8B2|KD1y~+q{BzNbZhc7*aya+nEy0JEslD2} z#wsKmn+#DFfYigNgST{*X3vu+AZ6+oHopaOc8$rqb*^cq(UYIZ) zJf&nR9RBp3sdJg61-h)JcB$>fpAE0|&XWxdK=7FONsWxY`_Q|SlVijIr@{#WJ%Ryp zT3W8IfI!Dvo0H#rTGH8|PMI#R{4y>dIh43GT})ArXP~GYFw1l=w^$oYq?n@_*X!-^ zD-P(+`nDNU&q&&l;>&urrzK0fKx*L;BN22iVYmBJV-wFVE~$mAI!B9l^xe*Q{ROZn z8_oS^9HF7$gN+#I>Gc`rCR$FL$mtpYzZY?O;`6b%m+nth=QqA1#P$p9n%Vc1j^Sx` zXAC-SZ@UQfab!gA{>8GG7UOyync$MeU!%(x+r&Dt6^KUR!?Sby)@JS=R-hH%*2*{W zuU9&^wmHrp>woMp1oUKGtE`F7WYP}BMk_YbTF+&Hy`aC4^sO+H4M{)5RI4d@$Yk=l zVGR$Co?~QlD~Y2Ux%S(AXGHGH-O!jgKRG@1GWny!z5iHPwQ=(wXS(S6K3(Zh8Y1Za zqc-?0Xc5Mvf$ygE#PRc&Oj6U*W%6%_%GL)(wI=W~dSzSOxv#$fP5Ro4`;=M0avdDd z`}$mew^cGRCJ!4=liRGtpLY`PUtZ=Dd}l1H2dsoBR^HBS=LT=rSOd)NSPNnLlTSu3djamJoz;yPo1x&x|@~NW>8V;=+~2Ge&-vmoD{Pp~XU`UnS+M9HUGV@f^&_gD?Rhl%qc30_Do^aE~Uq+Q;6sg1enx z1Zv)~M4=#Qk@0EaB-^L3=vSPaw)t9Fnw49LljSi8-6|3=zvi9HT$d8O@64z9t{b}m zY1XWKYw7VjfLVBM()>@AI!IFpL`>60bdn%H( zoXY}(XM5YgLjp_buhfK!r&up1pAXh$S&fsEDo1~vU|aiMFL4Ctzta#c3yqpq7F>Q3 zJN?E}YKdDL-|iG(Ac^@|genW0PGh6q;$74{({o#{BV7c1DOgQEHoJ?kO|~Q zdK}4(^ws9LN%WZLuA2B3)_y5_6#4Agk2!&Oo5ZY&<|~kb@J%S)FS25p^N^PDVWN4A zUboQPNj zfmQCousADGJEDjJ5;~&D$kRqddR}jp;fW{{0h);8n*Lk`vz}4%cupyV*)J)+Y1z#k zDf^)e67G^}kF9qXHVBwT3?=Qs(jiN&vg^m_tyUKjFRm{O6YU25C#QUlg5oyBRb#`; z4~*cD7>}kuazYJQHFsW_TrCcfo-5ih6RbW9+@Xps%P98O)-F%AT=f4`|Fk?FI`L?pK)TPj9;H=Wk7Z>b2 zmb%4{Z!@~h9#1oMDfZZDU8qPG@YuI+9}SJ`tWu`;Zsz2C;}18D&at)ENtXHdRlnC-{}De_O_Q57rSUPON&k5I?a+$Di(y9k&kNPVD^=5OiBj?(*L0g$Ya-kx z%yQh?hBo@@+oycjIgcOlt@*J!3w*BTcYiF}j{2a6w8aVsqrJP29y>+F4200}PZz2& zBO|Fx0`_K?+{N^q4KHyJ;Xk+!7ucpiy&5D zCib*zks)gLmN?wU3VpG(A0DTW_)>9ZQW&$w`KA` zg1ERS_Uyl^*?Bzd9qmc=vDjXgn8B?RoFZXvxKG+WP#34JYqb+<#th@qP}C zdP2;bpKp{=W*s+DLn;g)zV*A{=sl6`Z}*4`3W>D6Ic=&%zb~{2ySS)U+1XL-KY|iI zIbG&jBscdDR9o#Sb~5?~{7Q;h8p;1HirsF%5*l&~R)tk(&U>$_rY<<0H8FQ9vbK7i zb)i$DyynL}5r&78{-$zv0%DtQWI0lA4-a*GIoaskRwyL=0koUEJY+^nj}1DAmxX5j zzSYG6CDy#b;#1)v|KaeR(0tbceXnd~$QvpZ5Y^mrncwuCorhgq3btU{y&A{%s2)sc zclVcf@0gfJNF>e>o(mC3lVKHQHVH;8bPXPJVp@eV`x4-Z04n;%*q6ZU&Q_&hmRsoR z;Flu%;q5;dOC`iU|UiMD4cc@VF(gzsBmD81r}hp_%p+qswGt(%bRb*FjQo*=M%zi zeb9=4^n}|5ng@u{`jNU5dGB(;kV}@@P+9GXjr;M5{?xU~8;9vwG|d(!H)`v&uf>0P zToVNepMrv8WHc#L!7L~#WMroFB5>cMhy0bcGwR~-L2oMC;u}1`DKu|x#dJY8|863O z@F8O9A1|ICz(n#|0#E0wz;8yb6=OkLnsoHz3#1GobzjG$_u~kkpJ(wCJxdi9=DC{K zPWZ}#c8&p_zv+D0e#iwT-h*D^_vNUxo;?%bxzpQf*D8vGRp^u4sS>+1vn~!i3O;%7 zqTc1@QaOxztn4M)g;vIKrbEx&_I(&DWG6+Ja%RzfIOdIN_9@vFurfr^t!;0>)h4-0 zB5~^9_cd_9_eaY)VV#-+Q@B&42TFX3gya;%ueScaBW+)ZbqL7&J+ZXZA=w)LOVH@C zDadZ4WYdXe?fIvfNLOxYkxT!^S_#RDz;~!pJY}v^>(M9;;Gkn~*uQ_aU0x;owx7ed=xV}FQI{ zIU^tp{Byopdq?LHS2QUYt9n5*}|JRq-{ zE?F0$8dqvr@TkJOFSdE_dGpn^uaS|=0&7co9#0=&(Ek3vnke1^??C?t^L8z(bGz&( z8@t-N74WXz+x!v{;Wy&B;n)(!N|$z0SbbmUDH*Nv_e1pZfi+I|xRB72zwvt4cWY)a zgOdxlrO8^$-H(_@8K*$2y9oF}Z0r6dI{^|piZ97eOozmRPkN)6g#-ot1&$PXr6(Xq z7yeYnLa@uyY#OI|4JqyTUIxDuV={%o21ND0u`g4t%Fyl8nORqSzdl@J)57 zHZTdwkTLQLvrvQ$-EN|)3-;o<%WsgIk*C=lGn%m7cj6)ma@kf#89k6s(hSUHP_M3A zbAPs0lJ=WRkLhHC1FY{#JudSSI*T_2Pz$xzFMMB~gzw96@|sq$0=(+!R+@^Ind2Rb zd(JyW?aL@oRngxn4L&DB;ePlqc~O-^7Mp}YZjDUv*&<6;#W$Ets71WqiFi0~M=P$w z?P8*?PQEVYSrzx+dBQEzENBzY#I!4lPn~9uex=Ux%nk3pE3B-9F>N+a(=lbgNu;#x z@9O0aIv%d$_%r17==8MV@}0!#JW`ymc4L0b?6S67OFnB0FpS;~2<-m#wC%H80~fKc z;m_+$Zw!3^k2#NpdjI?>xDt=6#&`7httKjITzlt+{(|}_FeiO{#jf9B%F z*!U#A`6b0v@pYD9SC4|DmUaxu6=GuHy?djost(9JJ!+K=BPhrgjCj~Dek(BcWfoAK z`t8f;iZ|0gh^l?O%ywSXs@L*_8xP##kb!v=F54A!4SylC=_s1|^OQ6F6E^A-dOzcZ?=5fuvxjM4jhquU!>L)lid(AyD+H`iB|4leo z1=~Q;PA0CAY*?9+YGC6h1#Tl!HHfmzSG?+tcL!eMC z-fzm)pI`3F--S}4t?W)rx;i(AynT22PA&-?plE4{`tXPs$mUJH9zErYh;ww;s@`URNl* z%eXkjy70c@ylr9!-98cwdT|*>#n~L9Ij=@U(W^g+=m|Zx-rkx=q&|SFk!7$tL9Y}@ z^`){jNr~R}?_UqHWp)-h56kwCBQC05>DQi(`LkaU`|HglFn?7-7mv3A+2oW*RLFCV z#-%>3a+0RcZ*VAg8k2wuLgNw)hZFKM{{E>n^jymFw&>)+1%S8!3}CQKkDSspM#4bQ zt%QWi_ef-5(Q}$|ib5)MnkdC!@uA{vT~waMcYDMaHNT_}%?r=3uZ(4zVAapn9~a2Z zCllY%<4YeX%Eu}9{HxCM3%w~2H8+-{es%6SbZCsLd4&nDjBSb;ZnJm>r02UlzH;xI z!!9&k%*+%^O9dybELC}Q*&boPEicl$&bStB8Pu{9uFZSyjACo4ZMei2XNb|0Xc{aX zd_s|t5jH!&G3<+N)80^KUcU};pJGoW8Fjg?&f1h6OUJ22u&7lDAUQx%ErOYw*ru}O zUK6iRdkXI<85*5ZD#h%>^b|ch*_7O)E(>BX%%fI;l?RTU8b$uSo6DuU4j&G1oVjM& z%VB3vsiYJTM*ccOv_|#7o9kr9>@8!`o#*9)tHf--0?NQ=2;=`v=MTo+TrB~VEq8{8nxP2IFC@J= zI^-_+xThn})Wq-h8P>Y6D6{L0*fLHAW50MpG>&A3opWU$#e%!f0r&-(; zgL;aUcCAQyc`31k@tQ&h zLjEl}Kk?S%NvfIKQqd>$rX8I>2JKm8WjF&>1+ueqBDtsVXEA!D`ag^0E=b&DX-4!; z@683AMz?a91aIWuOY$u?64p~mLV(8H_eX}wDR4WCd*DUGm;A=?5r#4ixj|1ULgkLW z_aoZ{2b1`kRA*kI>BQBBt>zX=`g;7d+nt|Ob-6Wy47{w%=VS=ZVD#)5LJ!&p+b(tD zXz{$neCkKPc^!Fa_EnfGKl~C+nrtARe{nJP=WVhUQd*;HlM1Wf65K16EGeDo2DOGgF#qRz3(utTD zJIdokQKI(ljz01v9<5`A&|4YtW&c%Hvh87ED6!QwB2QE;F4H~n%_+bl;rrJ=d#_YiLn6R^G_p_+|ZH)!c4 zcgVap{SMUR>Yu14ovj*e|MH)4eLykRMvKqBrDkTW1E>FMfSOI|5W$?IZrYbG8IU-s zjX!jW<~Z-31{koQ9MCWRYcLtx%o8ne2BI<{qhu}dlb3&UKO;R=s;u71o&(R{Ut(|}-N|@lx-fZwKK?g#CX7W0W7QY7j zL*laJHX0T$gPAvgvg32v_;Y;wBCSG*Alup61tlwqqUbJGU|!nJj?fYrpHPr=tfLH* zID7xKkQa_qL?khsX9?KIxN&%61##zRH<$7VGH6%EE~i1m)BDyJ5B}_u&$kHI3#L64 zb&8c01~%3MFP-i>Nu%~>2=Ze1jA2A@rLrGXOEA;I6vC$AtX=lN{)4SZ5AlL@C=T0)|z zCaO2aR4a?rRJ4)&QCehUO)K(c9w++ZA_i!f4lKnG&M3*Fv48uabP}{)mYF6` z>gqn=a!-*JhUFcFmuL0J_seA3aN7LrYoDJfrE7cS%eah(hW#v+=lTsvlhhwE<~(SL zwF})r&!NA9;9Jklqo$_G{WPC~@&o)H>RD1(Lu0wN)S%c`oL9PW3=u;_ac5~yxUgI` zn~3q8zym39!RE4K)V)?wfo$DEncd-}CnA{iZTRl=V{ZlY?R{tr>QQIh7a zaO#wo2mHR%K%bQrUZH+t&yP1oXhmU+OAg#^WNi55WYdE^v9(ebB<8IoQ1vA>H2l!( zCxvKf=V<+~{qD`mr9fra-ycvbm7gCFP=JmCRtfl@^q%WGsIOj?_@AnEZsh$g1S}{u zMIl^pXD#u>)`qU@61m$)WpT3NoxRjVpr(u-6kCKRXC8vl2O(El6>9bkth>$)-9{s4 z*{{gI=6r&M)t}c3J#Rsilu&$=~z>Un)OvWF(u1n15#Z$bxHd&{`eZa(Tity;p zQs?}5NSyitRI{ijLqUO*nuOU?!!1{`k=gzfIk}MLi5C~^thw0sVe~Jy6rrpTU}CUd z-S@4@RG>MLpYOPA(Cv}YJ(zvG%v9Lk28<@+PV>UG@f8Lrrh(}WR%_?oRsx>fb+78$ zlg5J{0$3g4a>I~Y&;Hp5i6-{%YinN$SZhBu4pcfmP@O8eRaiz7bo`O$*4Wl3Iiky| zjx#Y`sgQz_7US=+$)+#&;Imy{ z>S(_I^A^H;>Ir?94u~`?sT_o@aLzC!x9N^qM3cDgs<^YgoVt`_*g_ZlNv5wty)!G? zgilk03yO#PTH2yoqC5Ggh3~Mq@#+vPJ>~$KLzu`nRMk>{w$~JRy&GAZ^k}`<3mrkk z_yNz9PDv3Ybk~(Ax*MA8A2)y0KsRLWnuR={aM)?^2Q&rr$ThWfb9c4*A6^={S2R&H zJ}yb>0(=twExt{Fk`Mc|n*RQX0(|kkhV){QPk$jL_&BtzIQEEk4cf{+@5zC^kC||D z96m<`WCn>c_R~4LAUBGUPEC)`F*6U6x6I`|qi>4e8xiroHKE{dV}r_VUiOyGSNo9x z)Y#PhYp=#p4&2HRneNe4I2I2&8-qz7uWO~@;El8@!0F7w`k{$`1A#ZPLGS&KMd4Ie zcrcq4exeR3IjfuYh#gFGx?9R?Pq>_8j3=(vaOc6u_yDuF!-o$IN9$39NNZqt#HvsNM8ZUmXZI&RV4_lN~w*~ycf2Rk~YW4snQgw6(B+&MSQQQ=Tn zwVo*pg&uYq9361!TuLY!E`Y_+u!-u?Y~AKL$D09$rP|GEC}N@fNFI$o+IYDi%US62%*rr zt-{jXJ#xok$i?R=iDFY!!M(s|k?u_$s$`5ojCX-f#TPlKp%y|Q{^h2ghr9k{iVh2kSBc;Edg--qo)s+pdyC1 zpVwnuPTUE^x}>k*7Ktdsj#Js*e(m=?IRQ1kto*-60uLvJ#5b_9>t<$|)-e+O{jfha zuNt{9Z2cU_U;J9MHqdKv+nc{Sq^=K&8=7Q%m9MiN9Xy8Vt?JnNa-?2lk(^NPagq)|TYEIn_Ma6SknO&T81%kxiRj zryu^We)f`b5k<&=?5k@==hXFiKYoIPxX1!ev<1QGCFM7@^TMt6S4uVszCf5P{em=j zw37+MWUYVH!DG82s5QM&&l18k#&f;%w5Vt-La27!Ycvh~pQtxQowkYpvD90`W57pi zf?FI?00V$rLRJoZtv6q!SLrcav#C_tmv+I4i;A~H&pC->XR>t(h$dX$CSE-~bjvg0 zbq4B@izPjc#@plkCm^%`DQCYmdlM$7X<=OdqZ?-5FEtPou#@GP@tsq$`_$B3x_X=H z{kEzWFVWJzj2L^O?`lCL8_b1~iEe4*$oNCzTB<&srYUS}*yRH)14EtHnPH!w!$u73 zHs2{v#08?O#qf~o%_GB}S+F+}j;%qx3}J!1i1S5Gc_T6AViRrXLOkB@A>EuVa{=Je zCN?VQdLR2;qds2AkGy&fKNy#Ka5A&)S=8p_hy2ygK!%NtXTXaL)2qMV^=#c&2rljF z#pXpA#gQ0ss4aZD%6dQur^A2^F)#`gKn$u^6KybgG5g4^sgOAE?i~z-br1@X1eBQx zm6@zABC=t{v$3T8$Ex|b!C2b+xfOhNz!gMYj-TWE-sZLZt4}4$7=J$Q_>*7sob;bJ z@sr}Jhv^51*qciV7^aE*E7%e=flFB|;=#1)IcM@IKQHq*4{Z zJ0&mwXQGEt+nK+3aZ&o9rXJ6W>EdE!1+r7C2W-rehKDgf3`R94G~}kN7OE^pW;P}# zX_MRag_2tc82wYS${%6`poPHhTa!+nPZnqy8q`T|J~$|$J# z&!69*#8kB}y`#dT&lSB#N0F+f%+@FF?h)jA;g=PiWXRXOzeE_9R7w49c|*r#K2-7X_U(t`seZS5QKTXzAkk3qyI5-CU~@bp3&E7(0re7+H>T1 zSX1Ubt!m#6)jH$gHL)GBs(A%JCdutJz88&+$e@?D%&hYGdlKBj6{d_wS(?+Gy>7g^ zji%qee<vZ>D=;u(SwxdqA*ckTfWju6Fy ziu2D!1-~O@$a+Ab2Zt~7by^q)fU+YB^eL?mYJ4a^I>iFNhx202NJd$DZ5Q(NGoMPz zZWeGa>k~xS!H2-2X)!tKLO-zdM7+f%?Tv7EX$QcGiVK054eSVGS0Y$D^a=nWimI1Ok8*-r8+ z+i$OhwZ$az-&_e6BTq+$(BB&IgbM@VmY#%h!H5xAe7xm8JA3J8z2F$&0s@9#zCi1) z`cJFk_bn!T6wrhr{F(I&kXb`tG4TAQa^n=&HjqBJMWJ01#%G1*Zg6GFD@TjH@jY>f zgYyAI0k;*d6Rw{}WqX3 z3)1?;S=n{b4u2mBWUX9pV6Oor@4T#?*r(;Pi6kSZAq({QL+&?tHbzIKYgIM&6`DPP zhKp=Oad>@D4P1SGvRnw22j=b`>ohOCZr%xDbU%Ia{Ce~Dz`qytLcw2e2+$(;F8y|V zw{eY(n*FW1DJ!U7&KR(IKF%D;iKR_OaU#KIE&IOM3jOA?XgqLp}e|6d-gXzfVBbXu{_nJIl6(* zyfF1dd1jbo)XCPca#gYLm7rw(GeL|*-i`tK|0DxR1}bG!w1I23UPil4cDTL$xRsRD zrAkMmnkv`gbVPpG7xtaI7Hjf4Pm`cBWvkKbkqy3*r2+4$5c*_M$Hmv1L-~e}((fAB zvJvlY8n_!+qW}-%-&>f7s~V81sO-EbzZc}i`)@Ax{=cUEj2t(enXtJ%^|bIg?##?u zpHs|NqRf(xQc%2K>fIRhbbG(GvVUhlGmN?(p@N9pn5dZE4e56hF3v*3M{L|pr_Fi#xw#ljwol-2duaWIX}jqB1rSbyTo^@tk9KNEmsOVB0E&yXE6i zr;#IkyZ4Ap(9_hHmy#kzx-})66KBaN_sYv7!2~NyFjJ0|*ko!3D6ze+89ZS&H}r0E z-uw6kifLyL$y#jQdZ z#F{mSuy#G6-dD8{Bx}h9Oj0&W;|&HcMHI=&Jd^RpxZw7=wq2w~gSPg<$_gbgnGqG` zWgR-P9e2SO`wcufHQ*1YMUjJ!%g}W>qHUl;U2P`eJZ(YYMLT=p9NqmzcQU@{45}b~ zGxw`mD~X_06sBdHvv0HiHI$*KkZVZy4>}nTY3ft{ElhlZFaf!#>7?9i0&nP0J|HbJ z*=hDPPz`k8BJNtbzD~1IyM7!#Cxo4_vB+#e(NOwr0!~<-Y9LG)D!Gi2CBnV!UM1$~ zQqJ?;bx8og7yOmV1OFM=`J0%-5QBIN5!19+O}pV6L4F?I6=WY^+~cl?SEWsyxV?Id zbVCe5w4A(@m(A28%fi&uJ~KTm4oTppb_)#^Fu&-@Ku!+$8V~m`V??n)Q8{#|w!v!2 zQc3AqABQDxeAM!R|7QVqBBQv@+Ni0i`&%i9@X#g}7aPgOgzlZ=*JyDK)wg6aDISCb?!Lp)ZTnD{!27nQ_q4636{M_!irsPGRzSZt$dIvy02f zl@g3`{tO-s4VCz9|L5MOCgD}M)x$IAdbeAFE)pc2Vw4}9BWj5Mj9(z{f&~-d; z@eCNYqj;pn3YUg?&NZ>FP#egVG`+kW1^6M+ z>kq+{`|DK=VF1c;ot?j(;1Qlm{rBj&H8!P1<>(zm$2&j&9cmIpBS~MWG<`J|8zyA= z{cV>Ox1acI_dDL6PB_^YZVbV?q(EFci8c;uVYMKR?lRw$a+2rv$bupF}Ut(`yPf|K_shT5)v6162`ogZ>`&e z-VOM*g$2R@c7=u-5$kDj6e<`~K96x%bNqq>nE@WS*eKo#GWm=XN>XBWe z6K0=VqpGfjn07;`x~G*phvMTc(MdKLzLLPeI#D3?zn)O@FTc^)<}F5mp{aP4*|W08 zIX8LNZ2kS`%Tc}|!5agi{sL(bHw-4|qG%<=!4I?mzs}ZWcS+h>B}8jaNAKSM$1MiX^2 z9tq5NawjsgNM^p$1~I4*9^)TZ00$AU7&N$|j?KFf6nF5kjm<<+jB)7hS=B11~0dS*Be4iHOI;6wcaEpQ~EtKPGZ2yLu|rK*sS z7Mu}KBr`Kj$f6=xTzG_qnZ+&Iul$w;90u```Bd7EUtiTNr#h842p(I3I{fbbL5_zX z{CgAH5YN_C5O9cATv}Sbx^bk=NH#Jq3&ic<{TuI}(lTFfZjIXYRoRpL!^_J)s4spF z9j~~5@N=6lx}>{rSv4&Xj148UIa0In)|+gSBPS@D(lFGeImd^3HuzdXZ9!(zWxh8l zDRsOoD7B4!c(Sl-&rS|5p3T*I!?1AaT|1b`I8XBi1QZ3KdW1t6=zRNfwX`YOwin z@~4XSCIWDurzx7MAel#EE2FJB#^>hS-8WquM&Yhmo{gT)ln?)SXNc#DWE#>?kEBGH zJX6=WGTjq({DRQ<_;oFgz&OwdKWdCf`|?v*_)pzEy%>KRrFZ3Mo0?qmqZz%Cf6r+KPa2lxP%4BZqrf{1TK@FL{V5Z8y(y?Z4!sRf&k{p2_pk?hprAv?U6&8Lf7zpM42|bm4pdPI`}Ni| zu~tH#SRUSMm=DYs`my#{O7!o-suMY0g;jCEJ2<1jy% z&E6E15AqLXwx8Pjbs<$-RpE-@DQ2n5-~Wkrq)IO3o5}C2q7jHvvpgdp)!azFvu<3U z+JKUmjA%r8xP%u2*%Qau{2Fa0uhIS|BcsE`o%X?PW9BqrAOQ~`LE}X6jIZ*7wLSy2 zxrJqz8IsPDd_N*X&2{lQ(sX5wlBGGN6%H{-*!TxNg6T9x#(ycLkQKbmk$TQ+-39oP zC4Gpxy8ND}SnG1|L?mfAmUPAa`6m7SjM3u*ly1w9anSeb8Kbxl#srUDu+wg1W*05( zY3tY@rSF!s%T;X`S`169J8AZ4>KWppbooq0$jPXn`7Tli_yW$b5)nGniHL0uEb?+Q`e&(9kT zAg0Q+ecfGt-6MIP1sB{&^mz!H39>pSw2vY;t0wA%%kO9cP#{U?Ktu<8T7M(Iv?I8Q13WUaG z!7p_Yd2|@!c-z(;YB+L3VIrs}pxYym3U98WS_GIP0FC1{q#ighPKwgPxHwxqZQrS6 zD5gAR;#e}~^k<0o+6i9WfH*m`^f9AiD|2{L!{fNg1cp87{Z+rDKl`yffQChEX+fu> zgXQMLyDUKrw-69GxXX8Zb*MvLZ7egI2%|2K!GnW^c#yTfk| zqX_uKfvm$`#q&2Toc9>J&hji`)=87&FZ1IgAa^3%X@3i2aWiNzE-L$Y>nIvxxs2Lh3ky5)3uaHje2GrZ3=e}WN-LoP zo7CCI@vJY{(*zMn1x|TJ+wN!-#TwaJNbE5&w<0H(N@_37<2X&|gnz6im0{Tm zWRz#m2m`ji9vP2-$~1)UftJi5#&IR|q&NNDrvPsZUeM*s$-}5}=Kj>Rf6vrZqZFoKZyzn6?C7T31Z!1`SMrq{=$nG0bRY5O(KYB*KD$lB|)(zwdeIG7O=WU zKqcrzH>!M#fgZbl(_JYt4UtYRqBsf7rZoVs`ry}Se?`iple)IncCo~U((Mz1U_U+? zvIyL%_TbIY@z1QT(1~*V_gQ=X{IUzE1~R_ts$61E60FB6D$GN#vndq6Z*2%Cdgb<4 z>z}brW);=8ODZOaR~Y*?=Re#{HcrZLdu@t4f601y2tn$8vw{L+wpgVCeG}=kGXqV= zZ#N6t-WYaRsjI!m2myA}*f=H%Rdj;o)4AS#S_q+KX6Vtouj2g=X5zdtwh{D9cx;k8 zEDXCq_zlt-rRCh+c#j4fPD+P+ z5Dx@1;p|&;<(noAla0M$ruqs22t>xXIh@TuVGi+Py#}NUfd;F!pI*4~wXym^fm@`jOP= zGx_3?+iWB^A!Gq;;nrN`tSb@_VLfhWjtDFvgxV=fHRICxMJ!pSvYkpFka@eUy$T0Wd4kjh_4?dsF2lQzSAAN(%5 zA<48IiU+iGm!$0MhzCP6rEZ|w>1|F!b-omLcAh3jM;o-xD>o+#BQd<0XU=>{dSp7) z8JH|sWo=A*(Ejn`|1s0F7-PAtY_EOMvcMFRA?eU`8%>xy9ESI`+zI5aW<&x zWWLcr{tdtwt)kDT*k$j;+mta~O%x{&8|*uJY;V8^*(3{~v)VxVHT^mLo!|A!G;x})%rc*jZciKMPPip!1 z1LJz!QMi6z6{unoIMFUEiRthOLN&Aa2EiTBfy`O zoF9DV%|Ad?n1fw*n`9&?GL|dwO)@im*s6|9v(od*e$6^^5@YjYl z@!nl?!F7O`cB`s>FKF8R@V|8BbFUsz#>J*KWM+0er7?Uie(@y)SBQOOBAhhSy@7Oj zFE1VX5XRb)n(8_{_Y^|kPpK1M#_?&lke`A7_*IWKf;@wUpFVjJu7nG$bAF#qb1=1Zx(PezZK z>ZeKcpf2TX=gxs)ZtSTKR@}NzxU2g8iTwx=J zjh7c&bc65FU?G8?NAYE=rflsKkZATDiO9+qwI^_J*xLtVcA9K+^W(GDQXyx&s_P|5 zpMZp%pOkP*O_LucfIUk+-V)pGuaxM?B7XNV9a_bp6j}#X6t7mB)YaBCgv^cx6E+xO z@XgM)?}YP7q?f{0r$UB6YizN?SRIy^1#LkWn@IbSo?~XJSXzW zHz01#FUDmh4$(;5oQryey`fnoW1&+dSk`u?Q47u?gogb zfux9Nn*;104L`SZLoE9*zwNlFz%4jr62(=T<7vOUe94UDsVgdZd<76S37V|X=vOqN zs`Dv~far5d3CoJ0_^L&)GVMC=AOIW$y)$R%FHAE`-1Z_-{1zO|hVa-Fl_YHNQ#^&dFcxH7{;na+o%QGXk?`KmX9RDV*k? z<;W~S7D^FmW&Nk95HRM3H7V#pkn4lZiU_#|`9&C&U^65EBpf3Pme}IFDzgu{IhGpOLEX!w%b`(@mf9S{ zUM8ts{b(7i2O24lf9{RNRK>XGBQi1oJh8AV=IN^u=~wtA6uMXOob;LtJPlj_pE60l z_8`V+;eJgc!W-!g3(N2Ic8ED2FE~ZD{M0P3+eKnmYxPa zuWX)e+46fw>b?HGj!>okZVbDYYyBh8YBVYNI@@Uoi2G4mmls{+Or%?048-^E9az@p~_m(q+_K zVq(I~kxg75sktvAD&V@wS0OinG0|F3MSzq0`#Tm9S9kl4+SNEJXnj7lQmgZdEl5y| zrOWRJT@AZ2p@2hGH~C@#X+8HqD@bfL)GQ!k>>DfLh=_lN?&nnSD)33(3l1^G?&aWZ zDrbcd3kQkH-=E+dShdB(AJHk75%#&i$Z9{V_&8$=O#>mZUtC`#yFBWD%*f*YfVELV znR#$>nU;#)9aPzNpV+P*@biD5Us+4XO)-+%p_`jl=_s77&;5s0RMaPxg*NONJ$v!& z`(0Sv2m?fV_04<`JptUi@zxvuEV0IApr5|9y8s$3os~B zL2wm1FR3R61l;ItwtKr7H@pf%Vvnb=@CfsKhoT_{fG^({m1R=Md;|Lu|(g0x8rfIqJ)Zq1EaUAY7v{F=XJ7A-!1zP63N7sRN^{*E!mfSnCke4VF#FQ5OssGSs|^MFT*{0JPKB>=p; z#Yj=UK!I}^Jsb=d!sU~VtJmdP6Cg((8XXP37#7A-wFcP~BrUYJl2uZP-=WVr9{3|4 z9%$%{Q_bOB+S>E*&z#T_cAH=9?q+D~N@OML^Hz zrepL{84^*A3MyT1H|?Hpy4S5QC7Wbrsye^eG&*s}|H^CwyGOb*DZ(BJ677Up-K#{O zYk@LQtozM9kh86(E^qI&`1&IaoSz)So-36{xiwu0ZOkv#at-3$bxXbbt2PV9ak(Jr z_l8<3XwKj!erg9jiwq&Dt&PBdxrmu3gae@U1bS6H2lY#y5DvfUkU8O2pIZM+hS(1x zV14g1)dOInLm`D%byr%NQKVP5IvIh10__|@K_jd{WvXAXDe?QQlY69k$iHBUd-9U~(Z5fl&ARODaoUp4aiz zy9O@$0fB~p^gMnH>!&N(i+Jko%hv1gqB2MNHd!61gvn#1^MlL+?UH#1JM@ASHi4EZSW){J=tTKTwqse_eg|AUKGsN=FHNpl^#pt~w8*IPOcoE{;FRtT z%d^qfzS{ko$>_1)fpY6kHp2FvFW1*-`}>U={^$FExzy)tF{|VSQEmO}x3saw#XDJB z(EfvwYI{K%28X@@hnzR8ee;c3-{q*LEqC2Gfi_Uoo?AoikJibPdDFl9lZ&jrs3C0Ez;PJ_1ltp`f>o5(6YMSA!Szwv*9I;sMACN0SHIvNP2{cZ~k49!%y18 zJK>QV98+++}2l6Es%;t=5_Z{^)e9ZCfw8F{7T7Ral9PYC; z1|F2(oA}4YHzmX0)l-B0 z+j~2C#fQj`of`V1qgahRJ)h5Vb&;A1Hyh(cjkre$zxWOZ^7*x~{r%Oogpnv+nK_D|LP)}&Tfg}02(PZI zluYA)0%C*6bTR8>!_G0EDltP>#`CEb9kuhH==t*V!$?O(<}U_P?FIhEDq)as85!>e zB(uNJ$X-wH4ky<`P%}ZNe*abEr))A#t4+83qX)ikF%HIGphVY8|J3!G{J2urUl@Re zu1NlYGRq)-r=jVQQXIvTC$VrsUT_KsAndT-T34+!4VfaNTR-;h1K#}AN;!FX!w(Pl znwXi{&AwgfsB*E-E@r`w1GnWndcCHDWw!UHx_-S9&kQDheN&(6f-h-Paha_#@PgR6 z(Zd&<8U;ATZ{E2_Og!EuXf7o!hM>$%=iuiwYoZ|Rk&#U7jP#e-;}=rBxcQ@5{GHr;cPC=3DY6rr(86l^di25(Sv0xX7WR|N3wUt%-LT%o?BKip^bJjuKCE2 zSX=v#oC#wLlO1>^rhC4;d{7@Fc*MBg6&*D~3nsEomdCZk(H}ZwVwe)KIa!gso0$06 z{yejmR5LDzcDB>piq-5wYOS$}{5$Ezuj~0LudaXi^sKH&L_n3o%D`&|1rncyMS)&( zg9-rotB&8!w>%;}WU=`DGGQ63t#L*MfS41`m*i5`)(X5UCQk%Ya^L!PK3@krj!aD6 zBkb3#g)iVZ6<f_OIE&#}gUF4A8uS2j-mR=z8$bAe7GTO0 zr7;rOt~f7s|HppKFXu_|M=DP4V=|r#6H%X@@fv@kNluaW`Tg&dfDF$X8W~wfZQy=c zM@Of7CRk!yq(>+AtaT%{E^zYkZT~v*Yt#$r7#Qp>)9*jx_iE$WIajD~!dyaX4-*s> z>(Y~4?1A5$zZy>i2*h{Qxv9#9lKNv>8b?p|!EkoBuGdV>W!T1poY}5Y_zux{Aw&*~ zqh87!He5C}k<*&TohxWY1gaum`_4d*5ifdF8ga45FvkP-*NYVjm3igqq4K6XkKaEn(-eDpvbB#ug1WB3_H;%e?uTVJMC_WyU&&t;az%U32LB21eL z+bXb!G&7rOXOSJDDSPiR)SU`;#_nycv&YY;KEHSYnZuty{=pVlZ1Y5Tsi2w2plg=N zm$Fa5e+FvE>sU0w0~ zE{r{iJl~vGdiCG@cJXFDBcc>G3?^1l!B>W?4%ROEegAP*mt2H9KFe!*dMw|1wh*x0 z!hE5s`Urx=V)lh;3dCv$&LS7XbHA8CP!1)Qa^po9tVJZEuks+n4hMiRv$}fwH_ikodC}9(7GohC}dxkU^7)YaVHqd$W zJ{X6Qv{F!M*di7^<^1jHr~+BKm730|#PbgJ&1pV~i_^4Mi9Aa85bxiOD+dPZ!k>7u zUFW|080A)4M%ah<9tVrtW#%%jR_c$2^DMxc;tYdE1Qwvm#tjVJGwaBMFm1r2NO1VmxFo!brskbF(7?{tRYbx^}mVgp)rP<+kjnKzZ=EC5lEa z*Pe-07+4;MZqm|d@7Y3sPMOxYD?X_Wr*4w0z9XjP+kASBo+dhRNFe6?QhCd6e==ysk&i6~H71vYK{aY36IIxag^< zV7Iom$|noPuZ`qg4;sQJi?~}5IBPrxWeMQa&*gOamk;SBM=y)MPmT2IX#NIJGxm(j6`5-9&dZEM8?tGZtPd? zf~7a~E5pZq!UD7dNJ+&U%?3$?GG^x`1X9s7P7v@84H)LpPuS7;BzAqN>m$}l-ikyOvjV5vDMJcTY0le`z&Hsbl5 z%}4C``1qbnO0q)%Dd55PmU|ZV`b1U=Yqw5Aw+oWkPRlpi!Nu~Tp!?3yAef48tLM=! z{(yR}9v)PPd$OB_z{=|(Bun;IDEW1VP2p;oev^X5c=<2r2Hb#`>ejjQwc9OiS~i^x zYvTj#roruyT89A6)g@NV8v+4nJp+FexLsKQ9s>5D?q4g(xV7y^GaRtMif5NdGkvz4 z@w9<{!Z_$*=U$GQ)TN;J`TXv+6W{BoI!UC66$L!xum4hUO%djZ!@mcJR-mPyD1J$^ z#@E%RcOP#H&dnFSo%8LRlDPKg;VcoY2#pXd#y%Wq?GrO~$Hx#`>D@gus4R?-0|)56 zjUXR5_3GW(hn^&@2-@ZrMVXAf6mP4hys!md}yME z9x}UsmwR2btNK$VALs;+6f&8Wl)4E2oA$VS49`U4|h^N zkZ-Br^m=B90q_k%o7_`7Cx#iX3b^!aeaE-+4fDB3dh046?b#v z)rCbf&Un4&kT`>G$jK3aX>xuIM`)jU4Xj5RrHF`gomW2DqMC6%^i{Rf4vX$7wv_2 zgT>P&0c{IGsJr*>`1=o5l`KJ27J>nTLuQWLCjN7|dA^)BvWc_q!afygQZT zH#K!83=11Q6E1P)#zuCj$diK!Q*VnkN5*vb^AJ`bPM+OE}smGjHIE%pFzPvCi=Jc!p%mX3VAvi4fwevuD-|Z6<`_qD^Bm4Vx z^jxpN6?ba6BB|Tl-MBJ~+t+A2X1ueEZh7N|BEtg6x&t8x82HTaxj{_n3;%}@k3O;z zBkKV%lvsf`x#(Vb^HBfF?;6ttP`={d&CSesct35!!|(+<;MAX^)#tPnn+nwMY#lX? zoci{UY|sq>sCaAw3m9G0T04&Bn%f&u!$<`r_4P^KKf6)DMauvB&yV-FeOwyH3_U-Y zbs>!lXlQ5xz9oCC(eZ9R#RTu$Gj?)6(dtpf&o5w!g=7wh!G6qm=zVg6g>6j4C2PCW z)kVo5!(o>I!`F4^e0ugh#V=7w`8GudK&Jb|rfwz{hYS&VQD)8xj|#v`{d)yP$AA*V zAiWRUkli2=-s>Jp13ix%$Q1%F9{5lI$S?H~NfLS5g4O2-9AEHu-bY`$%*ja`%{4x&iaY|l`DX52yE&bNx}trr-C-A z`SQpYW@a}kWEGHLjB27-$xJK(fbr1Sd~=ETE{tiBMQS zIEhYCx^M!Hjds<>evs25Yx-JuI51$+hcWo%4MgNZ{q|p%xHar4h66bc->cMe-WIbjINfhiGk;CjSXkVXU7Bhrfr17SFAV74~u+cwi~a! zw;ImuZ_IeC7mzR6Ha=1>dI;&#-HRiW6731~=aS%OJM>*CIPNkxm%R;p!vIiWdZ6mI zClL?4h5$`!-FpOi+O^U0*PDzL_;YhV1N(IaH-(g7udO-*4#(iP%kj{P0o#g@l9w0g zvDfcouRk>`y6d?fS>>0B)+%-*?4)GrlLYAUv;<%ZD;c(!f&hE z35s;w~`n#TntB<**nC0yu1{(&)R(`ACueWMy0#1o|qHNIvta-O7Mq6?m)O z{p%(&t|uU1g0TrqI;(>cw?c4nX`EZ>60gUklz{ab-mtwlHWM)nYR~{KP&~T(6aDG= zc>B3TdYUhK7j=%=hYv7I2{v3#f_HTT&!RUUdI982(&!6jyorJK4&r;&97?#=(5)ol zO*Yfu@f&p1ZlEFqVFyB}1}u%!FAuDP;4|Kw)PXiNV`xJyc^NCt4~iN77#Cy;;dJV^ z5NziN2fm}(H+j3Nmvk|{v0q6!b1&_#z4DHOUTfH60jZUSUpLT)PVom6RDz!Kko3jRJD3Hq6CzD^`!Y3TMhQDHdwMU~W)0wpdCv5&()^VpO>@AEb_g7VN)>QoiG*||nF`RhX zZ%KqoX8!4?RM=Z4Ym*jK*0bF6_~oO_%)r10%(bp)1GHEX=aq1VmX^iAyGRvJ^G8Rk zuHxLETkx5e(u*j!|D6EJW=Lo#8X6iU1H%Uv5bH-Se*XMK z`0H1O%u8``W;jPFei`)lS7%2Rdd!0~{teGOE}NgADgtAKY#(5;#hM#wNQC2OE;;Ul zfdQ(QGbQ5i)}Vf#QN(2vQdyw->R==}B^89ia36v1)*~Txb%JoNbtDN|Tr{23vKP3- zn46n}(y5pKJAIIVQ@c%<$d^=rwx<=G2CJ4kCPiwfGoF2!R%(E?TP&02<$Qbe1xiMx zafb`P^GU%PPgEK?pA@s~AswmjQp}+#k`L35&k_YX63m zNVy%jf$u~v20Bc*56F%c)B*yvxkyqWkNxdY_Qt1YjytF8QJL8ID2Y5wF{SXN$x&&B zlTeltIg||0atx(QVRmgyh=OMwtduzJU^8nEgYW@Kg>4C#5^uM2SUfWFS^{|fa{ZAn zoWkJ$yZ=f;!sM@BK>~eFbQCP0L0IAhQ4;Wirl!)&9xGq2y!Z}Rz#MuVSe&%sf?8jQ z#?g#se83Q2m|v7%>0<)7Iz(<^*$EF8aB>>3bF|)HuiYlmEOLePcQ7{D*_e4 z98V$fF^q)mVWNI0IGDINw}`nr2Gaq^?aCYzdl$OI!yOt_-X6y98@sIQN`^f;n*%po zPeP|jZXF5uoj@1{U@oWJ*`bU9Gn3kIu9=K{4AD~k5sFUrAQTpSNZ|7^M4F-F|Cn+> z%~oq4{QBN(R=Bmw5t%918ofz1L)T7 zYC22hESZ?}JxG5>oa_Z?OjMO*g47lQ@nc-7u=0p_1|f6lVEPdNj2qPGf9$rJ7~E|_ zedy4T1DS)Dqlh@RmtwqLy2(TECUi@tAAU%#34P9p23gq_lU<(1NZbDJobGl8S{t!E z_Ay6}FgjE_v%2PMnGsdHm1r~0x}}>YG3(K$I6@zb)5QUc&v|duSEFkh>HoZaE~$J_hfCJx>dAA6$_R-~5aWe`x50M}&-m0_?%#@tJk8NJ*ho zwG1K_G{ijirm(;lX=y$?_5mqyCtOK70{z9onv?XE*+CY8dW z*9(v?cAO<;WYC~gR>LPND+^{ZwHw!4kc-oU36REPW7EP@P+^Y;lQ<oB?h8 z3kC+|qU7O4Xb*-&2AT7^rcTGfh7}~6P&~_Rh(S&Pj~t=M%q!!q9#Dw(U+W|@8|H(( zH5y5)+4bi45;i{Vp)$V zQ&Lv;{?5)$OMAQ4Na??Sude%H1-9$8(#;9 zM6Fk=Iw>g0MW1;c{>OqBeNSIL3!)WxbKc)(h7;DL+e+{K-ee81PMAjNmYZ5tLLohk z#K1QtdN5D{k;&}gGiyd@Varpuwi)F;KOJLv{|-?;Kfj2;!z=C2)9=4?t283|ZhV@d zQ1x%v(X8}=?~hw^_)XJSUcXO-*kXps^INq-*CH!uTVn=fFwePe#UM(X{3L!a)x5em z802wXH?P{271tq>Pu_6sq`5|DKtfY?6Z;85MuzM*s_Ydp0V>aLYLO#|BN@G=bblcp zq+41_jqU<&I(XiJqNgl;IsWQo$?0lPRp(M6arxSSbL{4>Xwe(2u@5~Xy~(jF9sm=A zeDlJpibSJ#X^iK&Bjx8XV!AFio4NFG5@5{&X>B_ zbRErx<`!!(iMv%TmKW-zLld(|Xn(uW0;*2L7h$gip4qq2hnrJnzy#?{;%j#96KaPp z;Gag)`{}ZMAtt_+~o4Ykt1UHvEzsdZEB`O;}e~5B5b+-^o%UkoyGF z9?$HCQOvb^u_vLc`&dcn0HWzTprE|V$e=cKU&6coXU2VnG$bU%ZM~o}Td#6U$xEG_ z00Nx~%5GI4^L360x+!CmJ^%_5oWQ~IJyNuOpM!-`^lg{TaD?*eXF?bd2g~!?gUC^U zjw5Pvaf*daXZVNWO=uXIW?7?9wg4j z%%VBYyi>yE2?W()}=j!q-28m?%I(^-Uy!fcB(`7yC|GPF530sJNf;x|W zdsTu&4k8fHtvUMcRKfTO2abMaK&Rtdfat+#bqf{*z8fX&w_tf8Wn#hytNe0EI}Mj_ z{Wkmjh>V4g>WS3jh6~O7!te0-;j-w1gVLRN_NA0OKG`Nniz1nsE2nXOu8s8P#VwWf zk-$daJWA9L1G?8nv`R_PACvrp?gF%oHxd?J=0EvpL1rL~d0 ze|0xJkN8bZEv-kt0~EFE^G6I7mrrEOio|UlPD^l?%gR!~@x-+NT-!q2wh@RjFj74m zDSQBRbWu2v*MlCcjE6HWTJO5$f!LCbZRE-P!*lyCuUm0a%%dJCvD0bL4~F`KkfO%X z=~sTK-ybb^M|Su86oba7mx0axXk=hq6<*C&5onqIi4m_)e$nmVDA`R7w$~ zwPJvKD&*;rk--bJr~Xtju)_Z;bTASJ)wT(h2^_-e*0{88aC(K+^9E@+shZ$X5{&?{ z@Wmt0H`f<|5DyK@^StU4q^^IdibRbmr@bm8>;b{mI`!pE$o)KbXUAv2|2(ssqAgpT zy)qn16(>xW^89W|33xK}fh?-@IPT-(3ENpW=uY+y4%**QdI6UdQ<48*T0r#=6m@`Ou8qZI zS@w}h{H}SpxBNlF1X%Gf(h7P0%u;wLApx8&+uhL6YOJqld76CS-9d!GL7@fB<-KU? zD+4GAEv9J;KLW20F75*6{{J2;Vq&-UR{E~;rl!7IHG_V5gqzgSeudt4?@7Jq8z>~i zsP#CA!ideFMnl$1yB?{1=uXV2k!!eB6Eyp*=;{l^65Z?@-6AT zXE1ds`8dJrfDO2Q@a{i$%V`?Q;)6jj)!9NPjM;#3G<0VNuwu|y24Ogfpoi>tfYxd} zDkT|GQx|oxb-f?KoUE`rxZ*eT8ul0(bB?8jS~4$&h1@TRoNh1}%G0{bz!0+C zIQI6cKFirc#n?SL$-R%Pr^q|=?`VPVusQ&Xf$S*W94Iz??~ZBVWNvIyp1DGa)Z3+4 zinBv29GsS{V%1m!{e0k|0g5bp_}4GfIkN&R_P%5d@CuxyL9+2pVT6^*%O$Qv!3iup zGa0!dSTf`qYK`GZ%)nPlV1$8l?+21O#HMh^?b4kxgO*ww(pJ(z55-3L-aJIXWc0z88dnV4ILL}0affa$mSj%PXZ5TIY&0|uQh`||L@Rm#`R7J zAXiskQ=qx+5argQ;behvhECu>fudwkUt(f9JX2DNz%fyho6OOkYN6CTQ%~SL3wPw3 z%*JP61&Xqr6(;)eMG#F#=O;Zq(-5bfH54UBL{RY2Q&KvqxR8K(IwE?ZKPNg>lX=G( z?@A9Xr@L2kIG^Em6O^HT;g3jh;PcdEDf~pN2a%AB4E-2=SkM1wb@FkXFoW_v_H#zW zBc?yw4bl2N%|T1+=Ahwf6(nezaoW<82TO(HCk8@|uk$i5tj`g<_P<+fK)JaMj1ySJ ztQR`NUK5whUPcag{oA1G&KEe5c($TExNf?Xm0k3^`trsDZmf8rDN4>qNapAOE!8M+ z&2@!7t$_z?U$e_n9n=W@Ta4cIf=#ybM1{h@cLunrPb_L(Ww?7_|Ar}oFw0W6Ci`G*VhE$S2(B~05Xt;|z zmqk!}1YlLjU_+FZR@iX(mb*JpPL>iKND??pzS}X4hC%`*SECH<1~;9Y14g!a(`bn~ zJHQ}xGudY*-9Uio&hjF#8Tet$w3-~`mwlb(; zcn$oYI-mcIipq5S?@A1ay5RB)H*OY#p{!AE=CjGNe2~jJ$z(YPc$&HQxU4%|e(QER z_jaiP*H3P&5PC&nQt@Ld#L^grb?4rS4UkSICSW;{Cxx$25;RE$|aMWW#tdKzPWC6Sf z`x^`vuxj3_=`w4%2Z~$v&$E3t7zd3P+HM@I%aQ59iXV6ZX4AakaLtb7h4S|iLQ?yB zLjCe)8ok=;AshmC$6wy0RoKne(^5$fjL_zGz`wPT=uiW9r?1nDU{89u2L`b@Fj}v} zs6vcH=1f{}Ay;DRmg6`|!wpX=@ER|^&GC|ZVp#VCLqnI5Itg%&gK|DGSD)UVcl;wT zZB!OK%kTQrLXtrUPlAD0^JaggBChrS`^s&Lfg`EpB89}a*AOl5Lj-Snkm@LK zgkl2P`R`UN)zwin&TBCka+UV68=pb;wVX9X@x>JU16wz4{msdfU$*~kHs45IT?X>I zfTL<)APUdx&pXyWak1>upwmqUpgKfOYJLkd>n02@YIFtaEZmFZYIprY2#jKE!=E<1 z+7X0Z3GFlJsDu|cytSH(n}g;+1(~X3`iT9r{R8gL=T~ca6j%2Nde=q(hZ+YiFUZmX zAogd})uA5Xn@u{6%CfYbxvXw^9tL~ZK|u>J=a+lTf)6KcpnKkt*FzmR45DDchp?38 zcz>yTS<=wryPSR=o}Gah!-If$l`tV12*p^ zw?=h?PoasxPO~7PRX0Zqpl(op#lp(2icb!9{3k6)|sz25jd513CR zGjL8jOYMK&=_)ldL9cSk1TK}DS?hRXBYXrwljTsxrQ;7yzhA#H+Q1>{erz1>yaE*M zE+7{HHK6Cxwk87F%-;0yJ1q;6(->o;kEeiuoc!xNWiW z+N?)RFQ*C;wK5}5Z z!q_}fwp7-?*h%K-xO?^j16T;o{GOW2OHid=%-RYz-g=L_7k#K#@Bh2EfsXm5r91v% z8~v@DU4MtJ$uVB1+Ta8s;iHl(24Tk1trd^#U`@2v)mR&SDCa4U^ef|72|3(*#(~gew7arU75ZpVvE%d)T-6tr5l>*TXuHoZoa>49-n3XZH zA6(`ODnl$hBm#Iu2!l`0Hb3MU5#-F-ZYfL@wZ->lY z&1AaTseJIcsz-EeHB2cNBnaBu7cQ0y?FP$j&p=+YAJ{zkyUcno&fPjioehYpKCI0d z9o7A3T8n$&`}k*QOCxjaCBrhr|1rw+QUOLjWm(_BC+TN(4RuP zvLfd&TvxpWA}L9`Q=bs!yDI-j1n7>ANA{G&-dA4tK(7Fj>gk)mnNjXbHUBP-#2E9t zlNnh88@$Zo)f$C?B9&ukkW^_s2K;3+qSsqV^V58ev(}>@b8X9%gdGWadi9H0W8zl_ zGt<1!;Bl8Osao{>J$1!7Hg*(%3z5UmZ30MeNFTt4`n%?EwsA+dy2hQ3{nz7_O4#H@ z**dt;!t#VorNku#MKTe-zWIFI>Z4 zwj-eY4c5A_=8a5o05mP&IK{!^rNN}4BPFQ|9AHid`wwBrBlkbgn$?uhuvaqUZoS?@ z6dfR$#Z;LQ-=V}|Tukcu4-G9Mhz^01tpzWMpGM@Whe!MxYWCXdZc#mLXdR4eXR4}; z)377Eew#u=8brKC0kUNBS2d_l1QUmd!9rFhGC<2Rd+8I;Eg(Nx3)4w?9LGGWI<*dm zlx1qwIIPOapk^mV73Rw970*LX$c=*>sAu-(FR#y#l%~+ z2r{I(EMMdezl8AAU`D5rw-U^^b^0uS;KptH6y3HC)2Sp1c(U-BRRLmzaiXu)(6`s} zvck(#B}(YLSWf%%@g)dg{|)3?5R(}VG&VLtue1LG2~)q7&LFLV%)gx-5k>2x80bMAOPd?EMT#TLaQPoRYKTu~DXAC2+?ts&gVca?!FkegW$qy=H-vw31emfCa-- zg4q*pyOxkNRZ(Qb3z+6W#sNoP)KRHNc`Kpu4=*@&Wjr594+2kjzyJY0ZOHrWh9Q`v zwIsNqaM~B5#$fOU?o2h%ZXRK3|elylp~zS z!()F`x5W6MbL*qjWS$fbM=Fu+<251+QF`WdkF?Ful8$cM}IU;HHuCSAY$n zL>1NJ!wo2IPW#=~N=D`yY1Is}uJ5&OVpka(jm#nx;EwS)$f(d-w%VTh_L;MDp#@EX zm437p0MH5C<&ZJEwr81zw4ZIueQE^B`r+NaXy|J>?Irvt zh<=Z#7)pFkB&`AYgSeJ?p_2=)m6F?a3t`6e3^#qHkF9+}Phrf6ySll2RKw2nCHM>Jz0(iIw>4%@8@>QOT7M`-3r!XzO5{U8d*nS zP%4UrIy^xrj9_8V8IO&_TeWWP2?(}`VrXH82 zATgq$OmUJ1s2wO!4Xyt*{m-G%g-~d6q48?U>^FaF{n2B^qzJPWfNr*vzsZ~KhUZ|P zfR0YuKCw`ZFRU8jQQ%Z3Cl_G3|KoNlEHx~r$9D&$9tH%22y9_Zb+>)G+C8d?;*17O zguDA?9~mW^MlO!mxy28ohznnpzkHa=>eOUMVA3-5RA{*T<99J{giO4Ko=Qc_aBga$D=Mo>7{Z&oEv2mzANy1^T&_IHDG#h)`vxriJys)0zAM^rf zF#>NDtP4uw00)VUO{oy03a8jmXzVqEknG z?0 zUrI(8)^A{%2Z@;YXL_AcKnC+?gV%iQ%Rss3`2_ty2xo#t8w$I(GSyBC7?e*Z?cD}6B{>@`c&o>BH z8u(|F>uc!q`Cqd_D{Ffc4SUe}p`Olbb#o zbwC!m7C@Dw3ni|?-e%>^)BPP@7ulG%urGY@QYSv?0yb!t*>$MkR8UNg;fRgv^28#t z0s}&1B6@4XvB7+o;_aPF&yrn-!Qcn&UyI&4#j z@jxl<++5nP^@$-Y@@xHy%_$?*SR8Ub*2t%rP$)Nl8I|(%ez}k*Czs9r_vH>oU2r|R z?{SiQub#^8T~QpPmm0C=YN&z6MCmswmdK5~dAo(_xU@^~XY<_OZ?~Zs{a07O7bBt@ z?x)}9>yK_>kXT-i0lQAstfPg@1eBQ>U%v=4$V=Op?ahAA!C=HB!O~o;c7~3c+;f-z zUVPvg0S3r!>iM9Y&}h*cFqnhOk?I;4=8rZCyuNNCD|&Wz{{UF$iYtbhnz(MzW7MEL z$WX~sxeW{xIA)EPN@OHbqH$k0&W^U7n_yk7H$65wUjw@dR zQOSp4fV^D>c`-kfsBiP`yVK`)|2uu2d%~4>kM!a!5&gb#^GXW3n%6XM^N^A!!LT|c zr10L%l2Qm8-Xo9AEi1Dyo)fD&cM>nR{wb^^tNQledu=>YP&&xa(2$ig_gO6?z$hPe zQSM!jXa%;STn5j~E1&))Z5q&;);o3<#37pw2;Wr52Z6XAIGlU8E3WItUP-$?On*SF zLc`>_wga-U!Jh>6jNoojfgbO2J(sQ9sHPtdPuJ7#S8Ae!LYXL=B%6g|MC23kiE1@y zlr&q{G;R$Q6E(SK-upU7Z6(Ny^!h!$Aab+Z`UAf$G}C>zisBgor*-I4U;ls)QHUqv zkw{wfvTpg#Y)1MB{nGQdozeF(A-bzm>hG^jMKyf4HF{s@cMTCf;uY^3Me9G4Lb^thn+-g^v#KV<7FiJw8p)|?KKyJ1H zhdJW&Dp>sB-2kN}YOy28$W+UbTv(eAl%zjjH8r<>%*hJPO@E;dFu4#aV>xZ_feDJ= z1p`jSC=YgdJvg8Fp_nv|XNCfMgwhdQwfK|CLQcz*sK!5}( z96V)9$)3;ME5JVd7jD#|+@#)LT}v0*HN)4zIUudh@Ug2RUmCql1)|{IkJ~J;b^g74 z{p-LD>2ZL7I_jM^VhFNZ>Q->ZAjM#R3k7W8FNe4cn22B+%a^^6ZWeD<5G+LX#0;C) z{NtM@+DH7Z=V+Hwdpmyrdv~i+9ja0gnMg=bQ7S4TH>=jghO&^DB6Z`YNg|k}0)YUr zRhIos0=@$HvuYclcwRs+qctZ-wVx3i;}@7prLhG)H9?sg*Sa_zGsLTHf?d+JJR_xI z$YNU+ft4fhfcRI?BDB}SJ_y#U@3mfY>N|aaXmDtcv_t^w+R^3^+-0HtgsnD3cO4Br z3ut`~2A;FWKGu?^Nm^RI{P^nTAQV|n zsA})T>6_$k@R;|ga#~Z%Ri#l`F^Y+&nk#fE@O1v*z>2_Jh3-HY;342Xya|A%CsH-} zx-!w6qt%@kM|sKSmXrHemfWTnIL2_VKs-D&a7Ii#&EOaj|h* zCW<5CAb}y`K(ovozfbL&A3M%U`H7y!zq{o*wAwU7BpM)rSYVz}0A#LgPr|>AvZx|( zvcS%}RUEVW`kZqKmmc^P0r}hb7Bm}(2gEXw{_29l6%*swgxuBX377;cWG{WYufL8< zVL>JJeo9LAz1y8sdR59=X5R1jIRMr-t_>Dwk4m5s0b~%6Y%Dypw)arXBz2U(0!XHz zARj|e398hguEATgKv(r?B4>%Zx-^Oo#B|}ISZOa7Wji8EQn)r!mXX;RmG9%z1N#7Y znPHIIcl6+;$$sHypT)q8Bil@{c^>d30Ep4TIooQAh}meIXH0Wv}tmMWVjKc0wYk0L%m`Do!boJq2rjDGQHQWK`M-EFmv{ zb;oeDw|4I3Yd-K5l~BcjEsJ&W+Q<^uug*wsK3d7%h$O_8VP@uh6xAB1ibX8)ekU!L z#z1)w;s|)^-CG)&=5u8YQwL*5zRm>&kacl|`Q|vtiw$ekQi; zo_sW8wp?I&xquX~|3sF;fF^_DEV( z)Gp<&g~)K1+DskP1Y-MQRtzB7Wt6DQY#nu>r1#MgdyR%W zgiG)(oB%iJX1pK#G|%=7qz}^DSVo|pHwT$XmwQ$Mq`u<9dlxrU)Q^*ySy`76Kh(@D z#HOg6kXPAyDuy9JCK>@cez@R#(-KbC$GoBnLLuF~HewVrGnAd3QqK9EacJi2IhegZ6twl?uaYn}acjM&#QQI?G_EvYCxgx%xBfp$J~(GNl;R{b z*S|}1j(l9Slom4+B1X5u`I~9@#r`+^y=9%c-H^@zf=N^JUtV4<_f&+Q8d&%DQ;dd` zl%#n#Yzy<)^T5JO7?Ox63w=KJrDmZ`=O=^z9`mU_ekYu=7+s~GX70U+9eTD^cDd9` z24-ar_tGBsm1>v-=A2|$rn=*~V`EYN{^j;LjsDJZ?hUFvir3AXsz(w+UrP|+Z1%I8 z!T=w?cwh&uw@I39ZsSpMlhBbiHJ#0^+nJH^QE3xZ0~8cDBtMn1N$f+hi2ll?ZfCyZ zEBHC?>+HqXfY!(1Qr}xdQPuiU=-dv;^f{LcDTTT(r=qsYZ3sS+6%cW)O&#f<9F1yf zH%x!6&>YsUU_Nl}!0KrwnEGD92)5I-Vk~fjtEi=e#GpQaq**BfosAIM&1m1hhe*e8 zzsS`DwIB&T%YJlZDg#3#qFkrUHX#x3D+EFFkDZ(~j!b0V*46#|_o{O@K|m{z<~EAu zLvnoLMIc#kEG;v(g_T=b5Hhu}=;IJm_(TOD zf~fcJ6Nc44_0jQZdpBaZ)i^cXN6)OB8cega!amTH3i`Pn_c*s)Uu4zsd<}=kvY@6Q zU~g|^rzv8fK3hkNF2x8DjCXNn10N``#>;k3Ogq65CSd_fMlsuT;>R8h7MXwc`W}F~ z*T>OU<+e&G;!tPIYL@_;cUq`keZsG+Zmgn`knor&;kQ$0BC{TbdEa5FQ|9n#7t0>o z+p6r<(2(Jso2g0h>FINGK^IlOo$P#eb&LO2{J$3fm!LV&N`44FXBDk)(ux((^8$RR z=Uj17X;6k6+D^s+_9+4=1bunp6b;s?2U%aAIkpk)a?I3Ce84z;^OGpzOQ7w9$%_Q4 zs|OFasT^l;BUp?Sf{~A@4Oo*|SR*+et7-kL%u#ntc?WX zl~sn_H2svJgoINzm?_F$rMka`Laj&CJ;ldvJ-A983w{1*INijg%+2iXFYph>qG)JS z-lo-JGC}8DonVe0xtHnS1VcqI#67#^Ll0f8%xP(V*0_}Rz}+V5SVF=GX@GX4OOwID zG-;){v1*Ub;>`OgdiMX8GHV$X zNy`kFnh{|TXIVMK1sZu>$Xwp!Oyx+b)RgM}(4JNF#+LKlTrgSb^kE&HvcEr}X%r z_{ov)tqGFGMVwGb+>T+kzguwCfEL~GlfB;nG3n^&2Us4kqVF~p8kA->ym+r5`d(D~ zGx-1iY*rdTnV0j$0ltjPVD{eG+pdUn>V8cVQ_-ZY?}1E@ubbt7`0iRGD7i&NUv1ap*S=v| z?u)xQGF^>-c0~M<_}fHr69rY8lqfRM=HI$e=p=&TYr8!=_47bk;PTDXOFVF03|26u z&iEF}-?=^ZyZLEX)SQM})t2G-y?YTI#Bp-T=#x`iG&E@){I2p~-niWwR#K`uFief# zWNZw-G&*NfQ_Wd|r{L}hr2a`r$a)?1!PjgzyJ|5qxjUX`$0@^;C=6jfU!$aMg#hI01;o<*H(88lg?WhB{SA+|o7)afl}P zu0d?qEaC>ojZbB)x%|iMWs(LT-rJ=^7zImN0$w$?mEj}|GxZcaz&Jc`M9c5^ETKcI zI>G1MV!Z%=9vyujKJzYMs@#UBDvqxX*Xei;$F=#sp1gHxF35`}w$MaUi5R7p4>0e1 z;bj$0olTUE}FR}JiL&v6n+`h3eX3;s={}CF^B05rB_-; zn-I5$5~B@UzY1<>F$;~t;j=ux5SpMf^0valz18b(W*N$1G*71 zM(xL6{Ml=&bJwgqI)_)}*-@>P9bQ*K$oTwTq>jj7`-C1z*NQ0jG29Ekquubpr>fZA}C8+*j~J&6*1bmJfnrbSn%TeaOt6I zXZiU+c>clz5fyE_NmIDQ6tW?02W^j^2@~m(|GlXVOhVw`&c$k-gO(+uiR2_-UzcDO za>>=UchTY1P^YgmY#q_k(|6DOG>f_2VDoQKj^);^KU$5uL*Fp-^%-=SfTV$q`-IWI zh96FZ)I3_fjSwnM8Ox7+{Fu;E+3+EtC3W@ipcuC^1g|05(~$&z6h*%yorjY6xPu;k z&>Jo_Ly3(o)$cbWnC5z3Vi#aFC`9dC{k2Y?{d-gt=a`YhzyyQld$RE1MlPF2D@jlA z-53~PEfU=S+VvNexcVc(lMIY+=iY$1*Fjj>#bV^ONd|uk5cRVaBqN%K!aOytZ^d>J zUiApo(~JIbdcUf#6jeKt1T1mE=ulq~AJ0x$v%#+NG{v(psk&y^R#enU0U@_RV!%?( zjfyF&si_=6%R>+nB5z`13y;ex{l_UvkulUJey1J*eRN$!FafSv1LDJ9z}^3SyYlLRfsWth3ye&rd|*cS512*&DIrUy`4XVUZ7kE8E9j7}4Mrj9E= zZnkbrnAG#a&{ex#1HV5(DE^82o`PSUAhh519E^2UU*r{G9B#QdHr>S+PC;P)c1=v` zN>6K%b^P@xv8a(7M$ViIn^D5wjp8^d6v)qsJjDJ%UE8fK9}?<4&FJ~vOMhRSMJBT} zrs!3MsQ#Wi3*w*<_*7i}$!^MWGb`iKG}))AC*ll4!^an}bPd;g{;BexD`R2pjFKi2 zW>gdqsM^;9L>eFVFr!eWLVG9pMrm0TD@NsHAK~HsTTQ368Ka+^l<-*Jd*99+u+R@W z9zLASxT9%xTiS^b2KKI2Z~M{>XB%2iciXe5YHy@NV+2Zix)6W22U4cAso z+<2O|)7;7`vQDm9dD^G3(R0dSnztu_;3rejXZY`-GSRjWFqJAY1QV9)!;4dy>}}8` z-`}>IahKx$P4%QT4OW-Yk(5Mi7AXZM8yu}#Mnv#7W3xeKm22$wX%=$ALE+U3h{c(% zoisJI!}U9X?`MnL=FxnPj{fd7Irnu2UfEUZ(77GmZfTJ&-W^DHqPMmS@V?+28BsJ0 z`ELqW9Qz44y5Z7dR(Kb{TTg*#Di9*)t<9KcX!jx{=e}DdSPiwD($PwCSgD3DnLsr* zorvS!0{NNyJQ{kD7LXX^ke~hif3$oUtV?2RUXIn0XXmi1uw}Ed_H}63A+40+uO>wK zNM58<{!7WJG|>X+yC$?>U8iOuQi6A9A{#3v|?wfPli z^cZYSE^Y_bR&N6WWTI`(-AXQG6-W0snOGP=!ZDxZOkA~8&`lVB84zRx-6QF_b5#u2 z&)U~7ZHOB)Z%P(b`VDPuuL<77TiHq_lL!Z8q^R41!WDI=J*=^5mK|4guB8w zZ#t3U;F?)cbB!#ciX1l@L|~vr21Ly@r*<7WHQlN{1O#w52Q9ge?cg94{>RqVd2M_g zD(ku*&pN*`F~_FHt0uq)PxZv^a5I{tvg__tg-q`e`Q;xfLH*uxclWei&wUklpK83cSrYmLP(<%Lio&y0)GlPfyJtR3nu#f^KQzg#^Gw=6KQaPc6 zlU~rA-A42Vu4GU|jH&30+uYntqY2{!DAnb!nnrG7NUu|~@jj^3tJqvvfQtf6MkYb0 z3=u{W8Duhn*qFfb+~OlAC1q(iY5TFM3Ax~)LXO_zlP)9q!6B}dFBU_Mjfl*5=G&7V z6%AFz^)d<*uv!?PbT6pT|jDJ^TcxQv*{rp8ALFyAbE-3*K zL_k17TDrSaQcyvV5(z;-K)Sn2q`O->1nKTNll@)Czx&z>@B2J!%^2ezZy*gOFgUUm zE#HQjnXa%TUye19O$MKWwL30XturNX93Uq>LIpvQ<7L*dQWZJ5t?Wa8xoTCladB~Q zXtwEXY;=4DKUs9$HF2wA6~dxm+;Q4#C93xbe8oode!H$z`NOU~0P@+W-l=fS3ty>} zl*O>~PL|6=**$(7(YbZf?ZU>Sh=lS=-dx-dqx;1R{bea!JxIphu5Mq+uav!u$P0_- z=s|Fj)_fP5G;KnPZ}jC&PltZos0f-X*^sskRqF|T$L(r9N=iHlxI%$cuBej5*t?uqv{3nwU*tdsHn)RREJaQd5jMEhx^PjZcaK_ z#Bvn!GN}Q-#CRo7+V5~0DiPL>BQIq7E~Iu_SUck5*hVI#nimXH2XX@ZH1M07EfWEbE!Cz z#rMjxiG;5v_6r;P<`UxL@e~Plk<-S`I+g$W!c4~6FMs#i3FAs7F)}JT<RH5FUwL1+ zSC~>#d06Yyji98#v``Nba(hTA_pNL`u@sh7pDrdgOKbm_U`vGPUI-MP zC0cp{-5bUA4IbG{|#G;!1Qq!e?{&Gbba z$F-19E#d@)tXV>g#?tP3b7n^mJg4s0-B@k6lcQ-ImVTe<8|WKWB>W_C79rG`K!YcG zGr7<%iJQg=hFtug{^ghq2Vf@Gj7q>SEGmkG$?H7M<@$nG3{SsyA>#<=gl7u`?D4|k$IK6X$h0^H;r3Mm#R1JcWT4Pc4-e5`FsPK#tOno z)_Eew-;?I&BR!v8a}N!-o}c=YPlIKG|H2y9UWWN@TjfNQlt8c|oT?y&hz_S_Oc;nh ztB98r{+yDCh!na_ml4y%NzncFO4MccLEWRh9OU?e2As~g+_q2K3 zA%rA3+X6GAu1!wN{*J*yoLqoMB-w`PX=1}qZmyz)+lgzlh5TD-VV^10p0WpGYvxY4 zPl^JA7CEhzNA!AoQ8s>EZr>dqN!zVtv1Hc2is7T6{z}PW)oS#TE3Y!pCYaXx#v5$# z6XThgRzt%Lo{dYJr8e}hw-pg~AVM~12nm%XF79W#gbMs+`Tl67fMPl0>^6OJEj^bI42i`>@l>g zvXN272k~>C+3cN4)majq|fI-_CX$X}~WCEMJeW~fB%9~&%+cQVsu2iFQt2^PK1WY_>gu{k(E zGmEbG3S$pD-1D;5#jN!?Nt4;=#9am^DCFy(#?2Jql(@FqmlZ#mG(a$qiEqj;4xt)& z?yW)NiH*$V@=C9)`_tZ_B(N|TF4`A%MOt7o_tFp9507G`CFDWu<`hF?dm&}g3Tg$m z@jsf@#Aj5;Ubv#q->Ykk5HdxaTLwKt>Aw_=kOgWQ8q`tc%|;2+Y7XDK}#G(0ta`t#rHM8$wDqh+T5ujiZB)RYs z1NVAwvC&v|L^jSCpWO4(o`-nd_C4-H|M??;+If-+sVgg9J@zblces^nVXFqoS1=V1 zF5;B)tX)n3>(2X)AQsjaFFbVPl_35vnD_#u4No*QP;4t!H8K}I%0BYwt#3V{jNB#()jf3nU$m}MDPEcIJ0@y!`zY&V1ypB|fm)fVm zoL8OT58}4y14e28LaR0|ujr)f_EAT|y&!I%tg{>&!L2O?E%b|HQXak+f27=!DdH9z z@9~@-+6%^$4F!Jj&-vnPcwyPq8;J3_oRn|n>r(kY`0eh9qrAkS%n|VHPYa!!%z3&OHq+8>F6_|@>h8;{db`VSi$1cj!n^1k5@ zB}854-!mec^_9V}5MKUtRY+E-7 z?w@#(dShHF!p7~W;Ox+T{Z2f5ZY0MNUMCJE>q$H*X;qr!nkQ@-rt|8(MRamTMn3GX z#?mq@`RuUFTJFW0bjxyalyu(wrrE1g-$ZZwDMOx|Ogz)jf;C6}17XtQ*^wy^Lki;o+=4MlSgF&Pqm6oLwS%neobV&;Sk6| zLJgiV@csqcWQo2+q|0qQ48;5Bw?kaDr~ps*27i=Eaf)Z>A|iD_+phjc8{99<9m^*d z89{rd4+Abtat!c9Ka{kD$2nt@_l!cTlDVWbbSd%JaE64K!Fv_nVbIvBbyYq=bKO(` zmK_X~Vcqn5qkOWWmxfi=-xCpKLSDz^_8OKLZ0F90e;fiMHnXz+Wt))mk-%gL<^?X0 zlySQe1X7k=y$P61;QDalY(gykU_n==0_5^6K7a`&BQk!>%teSA?YV6J5~ zCWSKD@8i9W+S#!CQ9|__4AfDePuaA#kT1}-z@y9uL9op=41P*VF}F$7pX>WC`U{Xo zMKc56yVWFSvgZd=uY8zfUc&wR7_f(@)!VH!6mekf6^+s@A{y|M8n=8``#HlvUH|bKkb7a5dr(j{m2AN@+V|4Xb#?Y z1e}TQshgZx<_{h8`vhocWMPutDBaPd5DOq7@d;zZAA1}^y@H`I17QL&w(vg&Ho0?z z)r8es&#Y_+y^uCOUP{%qNAPH_9Q+NePdd-sx&S_;iKe&990) zaX(VU?~WLuj*%Jh#Kbh*i;c^fEJr`y=7kAs30G&El?`F}1NqH~6C&u9YaHrgU>N6J z-P^0AefKUbzX2};9}O4K5uKoX;8eJ@Z*CG7_JU8b*{MQt%!gj9+r-N7%uzxzfL3rc zn57D_K`-M5W@|8hnK4*bi8pBGad+RJ3lDcZxQ9N>!^^a|$RkWG|FHkRTkUCaSQ3l_ zf7WPLoV2_Yb=t0u>yr;QOMI+RjR$Q5Ek6nP7<^^H+U^tYl zEJY}7AMmIQ583YLmQWAYJ_l795lnlBra{`>jLso-=V-=Ni-Cf@Jep?t_w(NRlRrN^ z3wkGt5v*q{ft48hSWH=$JwV7V^B`&)j&^%yLuxzbii)5FWw}sws<)#hU$BB15;-+0 zFo0JBpBPyfx2ZY3eA#I$hjv<~44fy9< zRj1vb7#{E*U+XTnx3@N8J~^GN85Q&XWxYH;F6PLEK}u`ZnL$tL0S}v#x4N*K(1@`m z#LW@I7J`nUS%UaX@xEFf=k30EHA!Spb7&`E?s{ywjhqb%vrkiOW9l%&1$XFJe$K^N z^X+#aTEv!ZvbCkuE~`Av(bP2mq~S3d`UV-n;4{wk^V$K0FLPD~{|&?h=3GYUyUiB2 z2u2l*QZZOygqtQ#w8tQKzRH+iP`BR_?`e{r73PmM3Omf$r{jwu+&s+zG7ZjqhLND7 zCKk|tUv~v(L`upv6UXWtQM!K1J(9;wE5}pyaI-XmftKG{3YQSM_AM#w5iG4*TOlvO z7x$sHrPW_naLpa2Nrn#Psl)OpSKvT4bZoZ;pMI%rl0wKFj}RFFAqWkh)#Jn;0nxgo zWd4s8+x2Ngr_8sQh(DW)Lo#eIe(_J$Y>sA2DNEv#fb>)L7h(%N+`OsSF!pSr#iye*LK0+V&afRz;A+$xh} z{b<(5q|g3jq_sR}l28oyx}H#XJCLJpIQBp0f=&;T^TT`~B-}$y0d_u3z1Cf^yv8y2R8lM1Zsl9t6 zI56B_S25gh?OJ6UJ;=WI_7<50W6YTL;2_5< z0d-aAG$xw){A3&nIdIj-oN>hC=4^cKzjvKF)9N{j(rtR1Sitc}$?xX?M9MZPY_J7e zot$aLNXb_m*qez26USpvlKnp2m;An?^7a*)5qW*#HY*x<4 zW#f2cboqBj>cnq!(lu&E4FA6J-I|h6of&)(KW#Nm26IDB$Fz)kO2K>jTgSSaIZt8* zRij4X!u)u5qHdCg|2C62Y{QKqtzL&<67*qxB6^!-A~(~f7jJ!c?a3?2&0T})aSx&0d0*k!l`QxF*8=njNNT4D3XbggbS1UD^!LHHFdU0upkT9$j_UpJacS-*b|hu2vq*qW|D-C(zw`WPdsEo3k)J+OXJh9edR z$&a10c<9Af2T1$KP4vPrNw!cx1{7phNxG$%JX*i^w$nBTlP=`%NW)%#?s z?lc8FU=@Sf?33QzJtNlB<~W4NX2(x^{JO+WzoJYBbHu?9MRB70q==Qg`Mu3li=km3 zMf{XqWo_l`l{YZ2AVYR#DU1-E$1 zWaP>xYEN1;QA$2h63~^e_ddb2t!|~KxwANYup8x}UhhG1bY#Ez{YNJxdI&59GI)u< zOsw0v@(EJfJ>T$#6or8?`d8q3w*GbA1+6}$^d=o`$dQrFx9X&lgd6M)Cuxq1y~58; zMFiN?aufQa%rqGUT`hEg&beO-S>sc&`}njH^5v?<0)MgZX+Jnw7xv88Hxf+bZ!1_k zBMtp2Lsc!+bZ`f+YrYCHRzSN^R2n{*qof2u?&XQgxHRUl=K9ijdAqq{V+gg#mrE}V zENQts3ch*c<#`8#3d0v=@+RH$bMp;W`tl#)-S@2@k%`82R-s>jge{bJ=bxuu zK>!=ynCa5XNH~lBZTem8xQ0gH3T=!RMh!?rVE$a7dQvy}n8im*`x*m`C(=*}&+!*Sceq zQLPdA!&+I5KK^5C>-<|52rE3VZTcyS;+EvI{g8VYtcjv#nR4PtfD~ZO`r-4d^~)An z;g)Ip+g8v}*h41+I2Cnr?zW5?GRR&1T_P?$P@cSY^gTE9=QcdXCq) zWR?__TX&PF&7QB^zKQn@ryP^MgjF)J6Oqq_0iRoerhK!co6aY%JKAzx1&Su6Za%v) zsGmkk5K#r8J%(Z#3fjffXMSb8RK?>flmybR)5`p)fJU z+5LK)l^1oOF7CIjE35Jf#r(quE*129IH;jtacTnaUv<7nHTYw0Gd!6sEnAkI^{=Gn zo7X=dLY-BPfE)6tj|hm6%1I5a(eBh-4I|^%9)a$UWtTwU^-k0VwoNp?;hXUY!Pt2 z?YcmzRS}IG`ullSZe(3S8XY8qtt@271!0Tud=3jJ?ZYcqwdZ8jHU|;A+o2*c6*iP# z5<9bwRW;|9@j>^iF4lBMsJ=XWA`j=*W5q00HD>Q?ClLSvi5$pENxhHdwtz2jY{1ROzAo6eU%n%Gx5{y=AEw} z()Y*B^qfVR(OWYt%|!zWo!KFwqhLNzQoe$vQe$$jh1=7x!Rfr)ISY&~A%S(_pflt6 z~5o;GM<3O#TW%H9YBW}kuKnbI?wxY1H87i+GeH=czJwN_6mZV1`BL|w~k1e)1 z9Q39fgJ902t%A=zer(^HjV&mes5M6wg_k!d{Gmy>0@LS^sJfN?hs9-M3h-dTP@lIu4(+;6{kw$f(m^_j0SEr+E$u%$Jvlh`hRmhV59bKy|}? z$OHA6iYgOa_nmo{st_U%E-Te39YIeWx zso>q(3i^DnYMnWEO6|S}-&%Y;AvCw3P|}JQ)rkGjkE)zf>DVXMj227qwy9mbPPrq< z<%o`6ww;F;P)e8HFh9_kc8;8R7K%#RCzrsS*x3Gs>HH|NKu@y0VN>aU&+O}B8*}ro zaf;e`5ZFZ(96GNL`rYA4ro?5DtL$LUoukM&X1mw2Bb&1}P=Xtt*tW*oos)2h&yHnc z(}gk8755v(PDyX7=B#T9k*3Sl60*XJPkt~0E`SX?*Cnznd3JB>VUni%Yz>cN!JX?fkAQYR8WM<%_$(%pA%CDTi)74`>bm z?g-%Y;7x19P{XqrQLkTffW^NE3;|Q8;QutuC0wnPuIhdPClfbXV7!PEb>fE4T0$Ht zgzPWFvl%h9Xz{yM+KW|-&h@vOZ;v9jwZ|UykaAn>85S}ESDAoB_KhG*Ub5&x$3xqo z;MTi4EAecX-Wn*ZOp0z(FU(mnSBGEA2|i6Xjs7NDsO!8cC3xwXOn^a#6eeT{yX&w| z=sE;MujtKzq1yrcyW0$>a}Px)N};T(tGB_B1dmIZkA^mggkq`dHQ3wly~4mCsWK1J zlIa^G@^26O_2Ik*7$+a(mWSf z4(~Fu)A(Y6+4rWBABd+XxU12QaSsr=&`1li-tXG)85icKYt3#tN=I&Wa}Z8WM%3fs zBc@8qNbR{3YN6e$EAV8}v0`NP3wnsA@>in7xV~|scu3s2I&AFw-H3H#~O)&is1B0LY`Cxf=#E9Z&N?uVg*tWV^jBnniW0WC)DEjM*` zdhxBnS2Mnk^OMU|^2)oq*D4so8{V{BM;6xqCtngl&4-bx;hP;tQNXIEhGC#!U*A}P zO=YA6lRPatlq$da!dArdSW4Nv86{FK-osKuK^(n!i7))yXc8EOc=&i5C5SChu!JV( z&P3Xv1KC^R1(~Wgy9V9bup}s!SErwxgwQ$K)A*c*Vo;R(uUocWozza$jLy3@9N-ht zA61tV^4V~~R3T0upZ<`?QCUfR@D1n%cskljT4qTk%WwOMflwPUodiZ_D@%gnVlLLx zskxTwE=~gf2UowKsCfJsn4!(3pYK6XjHLXR##pniegE!9-8g7yam&w;RVtCW*&XQy z2jhNF0He4O*-qgX^x3ZZ@l~}Li3*s4`d=fBz9!lZuUMrgr~0?u zm#{Ai9nS?cFJ=eq3d!xhx3pV{bu+^Xbi?aCgkdJ(rfbdNDb*yZ>DYwDLODaoDjt1+9uRmkC+kun6a(OTV zZgu-=@#^SUi&CS2AJypSCeK$KpCXp*u-v+o(n^&F2WT)WG)j3+W=?J{1}?64m#E_b zmM#rj=Uw~QXksE}+t0SN4E+*1#nPH_rn5q~V)SFVVkFOp_d?& zyCN@ct|KHWzy!tCivk%AMg8Mph4+aZ0m7M35H->P_x$DvY&&gpatLIiPd|r_nzMD& zp<*%4y0=5GZ9~LbRC~|~yNmwa1q2FVYaFusWX*vO{!=+fSXh9WpBzRMVD}vK06F>+>0Hx%A0#Bk(p9~Esaqg^w01zhZ z!lS0$9R5z@r>Rvl4(6CFY9!!CfOVI5AuGD@)yPj!|JS*vSce4ro*mc#B45I#oR)jo z@W#7X=g^~-{VAW?@ZcIo$FIU$;XO__o`kwSjh~;nrk2FtBO5*a7@2*U>wRL-wD3H! zveu$syz*s@$pP67jtwI4Q-(ToII=0`MTpmD#hC@5$7+Ngb(a|nc1C*3sqv$Yu z0igw>;eu^FXWZK(h2qyZ50BJC872#LWTcKcRMh5oCzHVR{X&TsM^25+Z9378m_le^ zP~v`iG;Vn22?8f3CU7jr+AmN=dy~jH_qh84dhfpj7g6q8yi+0t1~msL6d*UhzJ|Ba2%i_c{1@gujqy zo~^U^MiW6JlWk(ub~sX!qUnIS_D=!Qxo>`GzGcS2MIhF_ttx_H+G9-0`FwafkI^#J zz)X#RxoI9MxAVjBFblf?UMtyIuVESije}K@lL^8LFW^g~JbE;QPsQcH@zL)Y;9zjCdicc_#p<4(eZmhgr2u2d47|H1~g?Vn=&A>(2*L8)-QD z*KTrY5nYr`hmn(|*_qpN@3|rk4L-nS3k?mb;+IPjhV#dHdArtTXvm9IeSWPk)yg)y zaU@5TUMwIe#p>EC9%ed8*T#!`zrR1`Lq>)-DGri199*w1gc|-)d3!SD>2aK;#%R;} za^^1-`taVv@<->`?6hWMg&1vk?7aD`IVVe6X&&RA9}QDH%Q3gYAN7{WZ7NA9JvqU> zm7BtIGZu)5+I7=`P8`R>E4{bxW~>E)r*h_uNJ!>nWZ(ca2Q1FVk2IyuB5FU03oBPS z-zeRE8WWmsSW9j9N%Z-h?-@XFi=WqLa%5xMZ6l`#r(^BTF(CY@=ccVojRU1MVtJ1K zd+;cJq38d7eRIuMIkRHecsDqf`)H5TTuRpO*E<`*r+_$WeeJ!t*hYQ@nWE|NGiXzU zP_cP01QW$V6JLF9Nj|*vP$)T~MIUhJMAH5kXR9Oh7P^+ea>JltoC<3`FJH32>CTNK zgIPT>x2d|eQ)p;AVr;B1gkEf)Mr$o!)U7jj9$y|C${0Nab3!Ljn2L|b8{*!#Il2!V z`&@hc_hZVlYf|ey-?Ve;W@Cq5)A0N-Q4^BAx(fT`C(71ZG@~O@)<)4`r#dp$wAiZD zT~M8o8GVH5m+&+_8k78Z$E6Pvk>gRR6x`|^>tU6iffiQSIbW<5{LjZEtVWOl6n1)&eh0c`rYl7(0u|Y2&(zhF#SorOh&Z_#l%z)|KJV<} znyBpmS*nbpF8PJz^y+J5D#?#^hK{XFy_8#<7;Nxh21K2{?7r!Xjo~E>$^?PuQ+yQ9 z?l)ZJ2TKHBPP-7((Z?B^k*8&7Mn!!tH!sv}FI6DNy!1AEe*ErMwPb2OCA5u*flqG^ zw`TCX9Wv&HSHy@2 zBAH;O+`2Ug9=wRVh^Xt^Jt076Nqs5J2JXEupTo!RYDP+`suDFT%)>jwgYd01-uVA* zzz19KrkOXSf&tB*i(+F~@?c&=17n}ZfRyX!}n+2$dc4c=DKGXX?KyFTIEjRvu?3$8R+fA*jW`zZ;p9 z^lP{QB3}iji3vbyL|^)&Hc(T!{hoV9$1O+7bGVUNyVLn+XXU2Yb#_m6^yJ3JyRZ78 z=g#x@e)T6`{}Le+|NNMuW|f~hrf9WwDyUVinp<(5qn7USuGOaazWj4V1ccafB)WQ(WR%u%s8%cwgg(5zezV`r2GTvRqC)mfL9ZrzKW48LEnh}oc}~p z7uI!^GxX=z+qFcx96gCM9-;Z#*$|Vm*YOY+ayiT(1bHD^ONdq18gkj_+JF~el$w$8 zht^QA<5%Q&Bn<{J$-0rTpk0b})aj6M5Pj|6k!$ddJ3G*sefI{>cx^4NLs-4^S>lq} z^SNK_-VG`buh+KjzomMAX~5O~h=OQtOruo$WeASlrC9DvclSc9nKdo$-cVs-OzY=H zeNGaLoBIsQsTnVsn^ zAa1(6svkA-wkvU*I4|lBl9FGL8J2hI?6Z9r3LwqR23wntUNv;#lgHXp#Y zuosP?%6WqxIZm^g!y9)cJ5va-D*OvbG1Jo(RwD^d4Q7RIN9=HQ$@4cZ1TqMzsC^vI zMMG)`uuFr_@iLQN7v$tk*CE_#EM`-D!G1`+r+e(+`+#&er?HZsGQ?7^T|2vnqhfM> zxszLk`6>J%y<6nQqS!2~wPe&NE4$)zm@+WsrR35dNgMo|249c+Y62%d{pm!V29O#- z<8Si&&Kd!=@N{~G+F*UHX)}t1N>opyR^>}YsVBPLg{Xsrj?X%;qCPGCMkX$!Z;xhI z%~OBywl_f6^}~BwKDC$RNO!ruWM#ZGoGvH4KTh|*2h8l@VrsIe-y?{@Z5R3D_d*Fb zCj3FPa%^neggS2FKl9>f%_;>}A$YKT@z7(PmTdDD0@-Ru$rkaNs*?HdB9JQmJCRv= zcWOUVBBx3Sduf1)wgP7Jpx?ElA2pvB_WqCX&b&2zNH9=*7p547mQz#ive$GZmnhx! z*DX{bgiNGnk4$+Nw=96zKqh*zj$Sf zEDd1z-8;`6jwkynJvL)w4cUN_x;Xrrt?iMjgG-y0_{q(KFNmmE9Y5zoLHAM5`@)f{ zCw_I2pX;gfk!9=f>nVUMId-$jcW?53y?=7NLzsq5A#W}QcmrBoiENq5+|GWwW$C>RV?>&1>OebIST5RPdh9nHP^e=UGdy{}F8m6`<;h%kCT(9zNH6p^0y53$pE8u_o!b?9g>I9Pmru9dm= zb!y7;mk|L?7E`+&fz1J5BPYrAqXO&(y}XZe?vj3V&)^|)krq;~HPGO+itdgzs{u?T z@M|-TgrE`>?LlD_rwj7XT8Vq%A3;@?AcwzqO(0p1q@H{E)IAk>Z- zQHlA%I`C=eafNZ9b3P_jUiD_lSoFGC66V2rE?uEfLd+H%WI0;mPnI1gOr|-83lxF*=k^r6Z}b9vr5nBDr#PlWn|>o!4dcWIwvXa6{xmCDznH6V9PyJyn%uZv~)_Q1y!hntVf za#n6d2)^)kr&sr7V^d5+M{?h{1!upDLzJKzxbn4 zh+LOb!GmX{m95e(Fz|zxt%H<|uloV(r8j(mnSbM0*&%bRh<^zq=GQykSB);?0+(m~ ze7c47c;WtETkHni+XjB!-jK~`p4mAc7n;-WK71g`wc{SPX9tZCJo&8iw~K7*!tAW~#CD|OXKltm1Y0sM8I7Yo4hLFV%qwim zNk}$U3)6=uZ$5*O_o=Z-IXf1F0#m5hO@IqH+i+v*O=T=)jVs6HUKn3zry=jRMD`iy zTG!^GbfSx{tA9w5RNN#O{$F0Eb%uRmH0_IGU(m-H%eNXW0q(=wLVYAP`85FjV!3-g3@pR^ywIrd+F zkN+tTBDb~g=plGV$wk++If<2?4)S~|IK>TCWMjUQV0k7Haj5mgn>np#8&;1DKpu!3 zYAn2bJovUDFP;V^UA8Qot+D|!7{VrdAI0z=?r==G2@T}O6Re~9?v5xE?KId$Mx+RA z@x*|sZ6&vmb^kyIHex21ZZrGt6qfsndJoX5ysr*VH2X1bJfkAqm$WL7)+UEv+vL+T zq3!R_7q?sY2@OBOQP`Y9-5A$8+@gGt%zW=Ryuu)i{XwCj$MC38`Sm2sZ%zBG%QdIV zWwv{%-ti1&)OrD}6wXh0s@&X-QfbGgX}!!Iqm{_}lLyiM!R9u52?_DcqxHJQP&h+yVrxti zO=U4cND!I>Bqx4R0>hNK`uuowdBxJ>@GGeaL^}bCv01~c8U|@lOa=j^Xr?xJ%ifg! z@TtS2?l+jUDhYkf*a2U<_D;5PWBCXFriQUb=e=I~;g_#{bD<^^FjH%=q1JkSMD*}w zmC%{7-)ds1+Y)BHvV3?@mCe*hqoq5HfS)cem%R&x8q)g;);7VSC!8$Ox3{CYICIS~ zujF0MUQNEYtRbWiHIIj6_`Dn73zi!%i2JWl%gLpX7oPkJ`LoxTX05+J?0b3tqJLVO zA3ftbcjDOrhs^S_IW#)33|;g`BC_dO9`>|>q7tG-Y?y?y3;Z$336kEK?$yq@!_Zb} zPuy=p-CdaABY^j7-!|5`5S^XDJNp@j7}a$;*`&fOD$tu0YDMmaAlv2DYC5{l+#|f> zRhx6zEN?Wu&Y9Sp5*L>w`W+q9vR<#42~xQJ06__AK4n)IL_5VcSZEX(nP6K652KBB z#IZeGQcucHPL246{92fFF(AoFkvOgSan;^9`pQk?g1AiU;{!hJ+=kn^H|qtWMq)quZU4C z{}ugrgjq-dE-j|CZwM?IW&Uk1r4^9x8a{x~irbk+!qZ3Si3ym*dYhbfiNF=Qe@P`z zN=@SuF%@wb^u_;Q6;ATGThoKRkAU;Q)-80q|HO_s@OOzx5Hu)j!|f)E;&59{nnJ=T zj6^>~sV_F15!@bV1Dy`*k$VglYWYfR-wtR9jq5!``xCJU35%RE4YxFd$90vLSFLp2 z9>^+1Si4@Iu^%0Q)X{L1xiy$W^T*pbmAwE{>+DH}Qr1aHE78)^ z$Tz>ev4-g>+y*d#wW!7g$PDn~wTalv08>c9`JDS*jc3cJ#p5k-K87jtjk^%B&er0d6vbttr!~AH*cF(-=zPF{3L{;>j)Gd_(fLo8 zl(8WbKDc++GHZLjBlJI8O|H?bAxGaQFtAZ#o0I6d(PVh2lptrxygBipLfOH=u=IO0 z{ejjUFmzD()Ty)C&S6C|TokiHOO=uGqL|eIXE1(=u>+wSukhrxh$`!~nO#xSM8)Uv z*?Mp*DPdN7R;p~U=~zBC|GH8!MQcMuL1U=?2DOz*gI?71_JFc$n`*JhtcFq_avOQ1_9` zWeI*_7m%zx+-SkqN%ZIvGf4=m@gvdo9s;t)8cKIhluewOU-Y*|{MQpg*Hr=ENz}`k zCk%IfmLna16g^#MX^njS$9XLU{8^9)QD)A%m)vm1dHYb?=k4-2^a-$QRWMTdOq(8> z_g1e8(mg7-)bJ1lR?n@bg@22OIvHo$Rqy-Su#TZo`adwy_hu=kn1Eh>Z^0_XWTxir z7p@g1WuE9qtw~o(ufC7C5QnQXA?Z}eTH~$uK$>)}D(-jz=3-5eJ2${r0v?EI!&J}0 z$SAK|=%eUa104ICd9p$%X6EpLQ4&1u>4{~Bdr0r*PllZy#OS8s2=l7u;o{>bd%E^^ zgkxEaeU84`3!^ga3jx8d=|6?F=Q8pct=nU(h ztf;Pb-o1dovoyj~UEQJv;o8)Tl4b-csR!of?}_!wz60fboIS=Lr5fet_zCE$ddn;v z=jLmadd>&LsMvo^7))@^a25P(L=^)CEcR6N_qXpSe4Nt!zkHVd>O!mC{^AK;c-(zL z!o@~S)%2{KyX~;Fsl}jVCQ|PGMw7G4^sYaE`0b9jowC>pDbbf?EWlQfB2F1 zL3N=0JHBE?PHU2BAD{2Y=+-N}rGQ?X3R9MM*uB6OsTfk4s8JQ{QF|OQy9MlZ_}&(3 zKW;EOi*a>!+7C*wmzq{@&SEC{*bYuGqUZP_kqB%1KVv}#F^|52x3FW{%GC*5lfhmy zwa`SmonA4)^PMWysXI`Gq z$ord8o5xDy zRgemOf9z6;5h}C{63UV0Z$QUJvJeqFnP*aFJ_+?BGCC`TdTot0*w!@rIPmi9MZC)677t>az+&fb%Fc!87KUR4tuS- z@**=f_}IW$G+dQG9W8_<;UmrF991yT1|uM9^VyUza=aOdjSkzP+lr%ky86TEv|Z#H z;klt9?da&}*4chS;`*XW)G^e5rbB5f>jGzF7+rVg!+gp>hHW_iob=0NLxbsH3J%=w zF?toB#R+@_?Gc)Vr50A6KD61)jMM$ox9IBlPhNlSY-ivtzQDR$N2kc>u&G1?tSn9qYWRT65&)sz~3LUe3J#eKUe z|BrV&`d!gJVZEg#hDg{+n8iTv0oy*_!e3-5X0PRJ*}>S1hD6tRczr0tKPhvjHv&JD6P{m(&`<-3}d@_Q!@S{S4$OdK)4qv!0(2{P}%3Zk_C&*mRw zvm`czk`{4*sT_=H5lM{hJwN^aBehZAJUu%*kV!eC3^F+)BeV1JgxVxWtFst;TGaRy z74tQtV;DZ6(Ih;D2E{0B5_YbT3+gh-kmUDoRAy-pQWEJ!sN;+xlW{-{&}!#xRBGN! z_d?YIgJQzHtY_CJ)9kg|ekUhfT1+g;jOp1qN=SFVMy6XZh9xJ97IbeEx=Klh&#|!h zid=OzLlyY$!gAX8tXPt&c+X=22zh_Jymvpeu8;2K>IqEnL6ZyX(UiVWtD8u^%Os0& zBn?MLEz7fjsPsrA`xa^e>8h^X4a*Xl4>!{|74OJj3h6z^>b2~&}1<9tBT(prV%nU z^CkKpZk1?W)oIwTv`)Pw8`iJmtZ1j5Vq&)BbQrIdKoShbnO0Zo{Op&|L;0YcQ! zVVSE#ca}+&j>i&znKQT7b+v?21QZx8ZTqGD1l`fqFw2#3DerNx+U^owrHHXA7__-- z06Qy~prcl_<0cbv-*4CFKQ=ZtR!~t9_wuS6EHQen>TsWG3eqkOLy(cf==|4COt+%Ifs;dVw!)#-BkPIVTK?Tc@wCT9E!>3eMfJzm%M#Fu%L-LHw zw(3C>6p6P3ttbLOaR5!S_~B4O!>`EpGZ9B=`RFfg-&hDCkPDLvsO171tN|rl-$mvO z2WVoH4Ff$w7ZI0#!?jw^pYxAp^~416f+ zdJ`>um^rP23+8Z(R$U&mV~54`&UXo}opyCu%6W{AHU>~@f&mM3qJ1aj@?7;^4n6i#uKj%;d3u^*4t=h50Z*L&G6{zE4C)@d&Z&zZA z-d37xyn3~&p>njH4{L}Kie3Ds?iI|S+xN545tLBnPZZoTqz@;>Xixm}N0a^6sUa6PcQugDNx4mXiiOkUC0^MI zbarxj*U31RtZY@X@!3R(PeRJtOl_qt#G_{>ZAV0=T3CKee8vmFL~voj6eHucofgeK zh2nDJy}iX61I|l3&@slkS2}0Qy{(|9N9kfFu=0IZ^>-OD?WkXjNki<7Y9qGKKOAZf z3CUbFCIAM5_r}K2iI*Xfq^%;o%5+UB7^d+5#`2H6;gRU*9|yJ!p7ES2JdAI*%Eu$3 zqua*vwW>jNdz(PbbQ%{h2&w2yOt``IGqtXjs|)XTvZv#}jNf{;hlcd$pJy{dxNEWg zhhDww6cVl$lVvG6r3jVB1?sr4UcBq@%;WiZfr1(u*3ipm_CG)W(X!LXn;ZiHl62M9 z9{^)9fx|}(0=_?>HVN(iULXw7ltFh<{Wbw@Q&HyQgrN5lmYxlww`Zcrd>2b09RmZz zVva$)%9w9V*?>1VYgCN!hrtqWBV>9b_j!YFJb)-AM$n%jG19I zl_BROB^$Nc5_2BbTEXpz;r{Bds$E$($EU=MHhIi- z%t9|0HlzSqI{2QmuRAaOC8AHR-2_iJD+l0e#l@$4mBX z8)NwgNQ9sTi5-tWaWy&~MhhvZgbu8l`2CoRnGIXr!I##>RwBK3=@VdPTgz+?Ass%~ ztuDxu$<1BpePRP~RkHCb|Hs&0M^(Lc;Q}aP1A;+G8XyhQC7^_KcT0D7TY!Ls2rRm! zQ@TM#a)ESrcX!{p_Br3Vwo79-8Gub!2a^Lg^qb0Rj1s9~a&V)vPr}%?>buOGL4j z$)Jf_SZ7?~)8NSwN|q08TQHUIOqlvcTU#%m^J;c6qsN8Qh<7iA^wlMccX~BfO>oMWwG?Udbj$i32FFPWB6tqznSc7$9eSM*No zFNS#5KPd5? zIR|Zw4ZK+setdaek|fglkDqJmZ~4jZJhbZ>rJGsh_>3pt2rH~7a zu7nc9>Q3#e<4zlrk8fb4gV`ogg!+buvnIt0`+k$K503In&I7g1)50=ZnXrahUh(;d zsz);2S`N}c7pa~;3mP-{uvSh#`SdRAv}8@4!W52l3O zu*{SVwcV`J5qt`33y;c6aR&<#8>_3roK({GRjaf#{4}&5Ir(MNg*{q%nwKnIIy%21 z!)YP+d4&e}ZT8}5Y6+HP&u0o;n8m@8#j)m7m;(H`uG#FAl0k7ZNwxy_8CzdwD5NF* z#Xf&(+QSbH&S!p$?1kn<8A(ePCLHU^-)44az_z15#m^6E}oPTP0wD5eT1(4q>LHCv-! zAJ4Iv$XGnEa$-N9BgdEc?MuMpxPi*8*B+hIz-w(Wzp`n(N(50Qm5`RcH!?Eff8p64 zK_eBzvOq}Ea}?)yi+X}U8XAgDv!Fei*J?E3jfM~=Mso7&%ju&nfAXv0+hT9W*9O){ z)9;Ar-{E4^Kt6+Jtw@aXgt0mb3e$qh)Pw5=zdycgY6^>^Lq9!Pf_18;*?FI#0#r4P zUJ*RCZ4g?ewDsi&KjH7M>}-&vNXW>@cz!z370Vu^USgb5wus|%+{nyTyhRlpEGPd^ zNctY^;A^7Etn_Dywyfd)m4(CD4xL=C@)8(amc%lzpG7BTpGwtJB#=RTJ-;x~%Nzm>U&|XpDnO2dYTLO-6@-!G;tF{4pMG z-5M&OQoH>Tk}xb?FBpRHH~NVZ-ClGQ8v(t^;;04R{DK*j1qpeS@~#?m=G_L>8GTNy zUik9-hVq>s_UFOa)m8Iz-K!rrGh`Cl`?D48v=OPPsRp)=Q?jdTDXCmhFzyUo;E<8> zFGRi~TOPtn_+}x%G_(9nprh()$&(QExLzBG z4gA5#!2;ugs=9Ad-lqt%ao12-B&bd?H24SB(*QXv$?1MiyayvR$~F?{s=*=K4JgaR zt=S$~SFSPQG@L4bPUO?{@m`FHB}m+ABE2e1oZ{=RUotyx=qb2c9A{k}u)e;Izm`o0 zQp2ZPuLudskqPwUAFtx=F;LY}SOcIR8=C_*{&%yRn|_1oSXksufh)J@9NH$YBXPVl zBZQmlQoiY?=dkFiBpE#>Ow%sZ?r9a&syxE_vRzd`(FK-!T5C@*%|sS4W)tc;XNmZT z-kDlf6w&Xu;x;dh%Kt>$pKVn1Wy+EV1_ln-d2k+0dTi;9sogHY*RWuHc?uTp7E5*i zBZ4KP*88p(PLQ$@fl|lH^QfRyi&QhRP}dKToRL%f0Sl9!LDOMT^TpAauxQYPErJo& zZ3ubf(puIoH!g;f+RV8_-oLM0gL**%*Qt=w~NGU=j>-DHM@v7nI9b(~k*XnY=rhD-kv zA`l2xlYjAz<*XXcj$eYH2IqY-4FvVBFL^clYARmvU4SbeQDlWRZeDe!>O$9nHyfrl zH2*dSMlH;LiBeW6FN|`cfYi=H6_u5adUR`e9kk|~lDSdzKJ4$+$a^FyA#7q(+k*;y zhjhuIb?Yk$^PRP77VP9aDS1uId%}u?rsFbLeg@L;$ttG2d1GQ?BBD^t_XJwDzl-?u zWP}9K(_He?bN)2$v^0v6tM~U)!!Q)ge-5kJHNf%}M`@avKF2=kVzRSF^7*w`_CS-w zq9QBlw|%co(XAOdD2TOE>0fif|kmtJyGQp=PxPn9k4IIEnP*R~K^XBR`E;n=I&eO$t_u#Ii ziMvS+&KYAL2&p7v)n@?OpjiMSZfENriL#KeYY}|Br$b*TbajajRR*o2cLSm~`-kXg zX{S3m84fpKK{Cu1F(Py~!xHZCC!Ons!sX5IVwYrcvTP~=MRe*D17&GK|J$BWvN3<$qm4>Qx-(3u6u zW%$a=x4dqX%=AJEv>mSjg6Hm=R%Nna;@_=ipo=TTmeTnpv-tGXv$6-%ESU z`hV}x($PKUvV8*4Q+7|W^Sm4bF?%~?y>Aai{%W7B%hyoR!FF;=H4^fx9CuRv9D&tThBbza+%(BXCdd(LWbAN^JZoi-~)mI9e&wBCX^h*m=I7e?cOm(e~lw{}TK7aAT z@BG{|yna*Dg3G*;@y2!UT5tak*BNeMM>wf#C;TP6eoe%ThF+I3=|@b=Ljx#(KZoLY z0kS!C2+DVAHxW^SPG$Og#!aar_{w-36V;CV46LxtA#TxrDS@SCK=jM``Yk~{*K@m| zuUM53*;RhxFoy6Qs0v8qALY_8s!&sEujHy~c0|u~*Kjg8v}zH+7Gj7v@K@UOW>aUr zGo^Cd{-Q*d#`&0-4&4~(P7xa0Tfp)M3bgdwmJt;X@(tuAXuBRg4A=Gl|H7LsQ zpG0mtIfX~(=KJ0wHsrE5_@UoHh=6G!y%vIN)tR@h^@&=&B;+CMbkM}wkoDqIQXQd| zy`TR>vy`3zW~^g#F*S3sFfnKRh+n~YvBPWtBXptIj@vP|wLQEa6!Zu)cX5iCk7!ck zo!-e9)AmBebG8`+Xb6w94g_hpj?)icG(Qr%QEsIOYi&E@Y}$iQgmAnZL^;GbHA>CX zeh26S+N-q7K<|6^vUNNvTQQStt#P@uzn?@M$-?sF`CO}p^FpK!(96w!ek2Tc$7WfssfHY7+Hg}-U(+=u>L+!yWPf`-6lXJPXkr1it`yPG!3`?eC_6OR zPZge=iq3!D4QuC7rHikRv4INy!?-cYn55HisSz<&3lWf1!bYzm{;x8UM(L)Hb^9Pw ziT#h_kv7i?#fgU69Ri)@1tb##1cK4reJM7&(w?<{Ddy(5xo*8>b79RY=;?Kr z`dAt(WMS^}VoOhkr%g0QCNs^Gm+4%6F))~%X~@)x9d_~nWgJXwk<{v_)$#m=s1~|4 zVFaMbs)C#0?5ps6wfEdTn9>J+BNAtyf!3t(3(HCT##E69#$C=0D`8lqUkx}ub#&K% z7L-#pc!c#9wu$9&Rl5w~;(ke=9pbG~P+ZVcS6E=SjF!|(G3q?OxrlwfCkizZh35&~ZYkR;OQfLvQ#u(^K>Jl&MUBCEUmY#^n zP)AZJLdkn!(R_CgNNEGxF+?i%-A65+M$KEG;WYsa1#)`Mr2@LhHK?t@jKv2uHug8} zJg|1zNM&ud1aByEdJ-n_i&;dd(`d#YJe~eK%O&b+2XWBLQeGz~t1|i*x9siNs;Xi? ze|~PE?pT_aA6sS#H{AU8#LcnPR9z;-bma1)vwc z+L%!d$UW|?Wa5j6ynOe*!-1Gb$zjI#foJ{mEdiPrt*d47@yv6}NkQE7tqZT@s$L=_cbpt870yJV5(Ax;m(4eInrU=9t^7SCkd3DN!1CvkI_1wM1 zg}n;UEi(I{FSEvRi*d+P#{5gEa8Ml{)a{KR^YT>cW8U|$s9Ss(T7#Q8?*{V-X=&db zm;(buDK)J^TE?GfX2!YZD(FKU_<|!qGLtFb1SxZRD(L$#&9B;JX`&?Xjp0z-SwIBh z@c&e+8+~@)Ry-h=@?o3d1dr<$U)(+7zsP|te_4ThWjCJlB|i5kYHk)3>K3w6JZlgI zXYg)$I4x5M@d^=sssVi}DdqSa)}_$&5hD^6{!D~e$iI4iu|0XoWAiSYEB+7B8bCy? z-|`R1%gTx?$I7K4_hYIe^r`ugCQfPSgqn&JJ6Ytva;rc-kLd{)254l03JOs7D9Sz2 zM(=#nHy7f-ePT$Xwc`$%%7ZmLAk>vt%YugRy{*0$N*rK@`sG-?Z18q; zG6GJc*3d-AxcpOKuKr*iH4q0uz7rbIBqTH#@LImwLBh0%fvKJl=u3KX5zSi!9-8^= zGd~^YJ`4WT_nn>euo^5VGd0JU3Al@9)^h52Z|YG&Z7<|n7>NGx!+`z40kMr5s!R?= z>g7*W!|f848yq+yA}knpo=}P;!p=K5&;Q$Fv%wO|75K$Mj}A(<2KP?2|4_8@-2MIJ z209U4P6%Ysgcla7;vGT^o7Ps}ojEt{F5ufV|r{CKCv#kSIVm=DO zMB+0>nH*kEeiX_c+z4DPHihjbKwrXY5hdgpVQl;6GY`Gso1ln@a`O8#FQM}@Y<|`J zLDQGqESzYZhyN)oC5fM{+FVd>x+o6wJ{e0|*`M4TiExpEsp}td4EO@6P6IyD6xZG|zT&&O|6`c^@~5#Sw2T zIuz!8o_&VM>0GE)jFxf>4sCu5?XbE}<_P9<#(fmE$@O$*J6GPwr>P^T20k??$MDu?@CArpo5YOZh9_551 zZ0o7>z*`%lTU~>uj?M&^c28NVRJW`8vd==X)^49{wMQ~)Nx=RUj1A`Rp2fr{$nkJD zgo!J+tiqN3KnsF(CN<&4PLF9`hLSo0i<;O@#VL7{jWtu;je=NJ}Al#Kt-c55RY-Gb8xsPK@o{1>i_LiY&09spY!zWuO9M!-LH{Y zETN+MbL2jGC@i;^BudS6y{nwm@Mbw{&e}^dpI1TgB*%^9B+{BRHgnS2< zF9yb4t#Dy$f}+w5J<*-1LbV7b&Hc3{7W0VarBCm~z7Lsj3Y>@|qR73Uus6BQ+L zs-fYLLB;oW`zI~efW;D#7|VF|P9uV5IZX?B?R&qIpYiMTlk4G#j%ggwe zCDnXK6T8u`3J4rz;%=yl+_W4{hDHy}eD;7H#=Rwx=qq`~rFf-A-NkAOlXHuFsiVQ< zZp-mIR7su@vdyU0xvQwr(W~sJ0M5-1yH8AH{mXO>e;y`B4fKDB@)ZQmzn)^9I$>l^ z&ZsVu=i#Rs+Ia^gjCI_BvznV9%59!CCF1HwjF zi8!qGe~RwCeVUkZmoW;B8PXZi0EHZ_%`KkZms86Y9W0(VgdKpa?ob##jN|}#r{ioX zlU`I5Pu?N%Zb2f5&jXgFeM3#(nBT&2Zfg&J9RB;saF74i)VpKZfPlfjEy7uOA;xVF z5t`Nk01b!MC+oJ)_h3Ov6}0kvMPH2_Z2c8)&woyja48HlI1b?0TlCee?ps?!&2_vY z>x2!8tj%oOlWTz!?A}DrZKu3o1lF^}sw8FZKM?^3+At(4B%%tVxu}vhf>A%gR6RU; z_hepAJuH6OX!?tS^TxLQxp*)MCnH9BTJg@ev9+q>RMWR#4?w+|rmn2z6|ZZE{`^5? zYX0yn(3X&hxNjtp^#h*Mh1+JxtJ#Ob`_N$>!z!wC^zzSBqDJP8vs<9S(AK4>Q!rfj zJP^$dpcXy^wBXbjRPN|fF*HdUS3Ha$ZT$O)i2GvS6gCoAFig%s5w-R-2l7J_v`>Yk zhc6HJPNWYxr^}x8_lpgj!nyq8MHO11gAlr;tB&>kE4jKg`qb2rW8_UN$&&2iW-+4U zCi36nhoDKeMu1q{ipy_!*qN6SC9da~fk7}tGGYR|5+dgZ8+waNYcI0c>z|ve|3~`N zgk%be8W^f*04Q=g-#=4ign!5hV@<&DeZH4ZKbbQo{B_`O_@lc0H5rkrTtw zxzJ3Uz~P`cAB~5Yiv81;8F^p4!|((n==JOB8FTZrUKU&hh>zh+;+-{aY)Ni0FAilw zrb(hE;XB9zVSNk)C}ozv-m^JxM#OYpNgy|CX%KM**?PzC8_VcfQBdr@ls#zTu&qF+cm{Z^9-5DSwABrZtkFy4g)I*pF;L8gG`v5hcw&>C;|-R0$
    y{{Tgk?-UcZDbU9k>A`TPcN2_s0?mI@6GkCHxEFTzr8|*Vz&^E{ zTe&>VTTCYRDVsutJv>G8j`7&E!e}g+#dwI(x~Yp zZUAa;?g_k!$*1L-@{FJC7S7$th-qbmxi=G-LUu(WX7aS5|M3)- z*%)U~gh5jyF77h^mF;8f{Gw62r^YnFq9V|^v~aqX@Z4Di5%mYgHV1MU+L3$|lt!f_ zKHl}sYXc0ES2{Lh+=d~fe^eNKeP2YQVk6QIkk^1=k1r3dbdZNz6~n3#e|9OMdnF-% zWkhjbYEcl$|MB;K2s3Z$>BB)Sk9Ckj+^@_0CCPRwX?v|Mjf}KNA5Ai4)SY3ZMLXR)ZTmgG^XN(CCs)Q{rt}s5o^9%N< zn2?3O$S~%$8>!mg+<=j(&e^6M>G40^%&2~MLB&UGH`s>#gMy6O8XZ~(V9xjQ=*Qc# z@((;ArQw^N`c&@1WY6E0IwwTJPOgpVU~9_EBcYJzzYC!- zo8+AXgwJudYJP&E&+gl4$8z7M_V+rIdeQ}I&4YgL-c(2w9zo;bMj&MQ!R_R03=R)pY7Bn+ z8PROPTf1}1e?*1D!r;l1P%&XLs83INkEIsKe2b)vJ^P--l}3_sQcY3i$BD`QU*{_i z>%DslU*C8h|6GbS`09^;+0-nkLG+b)3H_moBT13Uc%3F>1)wCA9yhv$5Wd+i;)Xrd z@O#_mDZE1O&PP5S&_I)vWtsx+NDt^k+ws=c-~N20)yg3;4QE3Q45QKe1CRYEPh$7#7{z){#)VpLO|)7Ta!kxlJalJ zA;ThZsjoMdpxPmEqpB*yyz{@?gF>CgVMT+w zDFaN(W3{z`W=1%=s@k$DI59;Y=?)b;tpWE4%0=VSlho4w87(6N22^+}m`>BK!G%oP z=lwIIPK&Xyuw;lyA-dRnFqEO&V!|D<>4G-rst+QWw_l@LNW*z|V4{tlR zbwm)RPF;0sL`70Ew-p&^E`1Yu_R}eMHXlcezQ(~kW@h=D$XzmG{YQrPE=rQz#HIR$ zpTXt4wV>hRv3*@+K>$4Fjmd8wj#<}-5ED&TEz!fuYzPCzq=BhF7!w;YIxlClV>zFrE3>Cf(2zv`uZVMji-dZg6gPvLM0`=#UOVE`IKiDVAYWSt`ryleum3A^gi5QNlf-{KpMK+%q{N6X+zp z{~zdTgEcH(IYkFNo7K6upJg)mkq0|qS(GL>?* zwJFevmVD;pQLQ#&sYGKBEmkvLK!I^=>Mf*Q3Tld3TvsTAY}M?JCa`;YinY~aJQFy( zW_<~OJcsgHd`vd%69KRAzTL)8CdpZ~nKhxT|J6v{k>tspi$_#x?2nr;@||a?f(#fD z9zW(-w^lA$1+F?QoO8a#_PU~>{cBt(73auY@)rKwUz*)tYUbw6`+cchv@eNgK__GG z?_Hs>iW-EtZG4%AsA-l*-PyQScJg$Ghc10e`NM_9*wNx9?O{6lS0yUofR*Iloo`2{ ze7U1oW*)QJ*OGp=$x4TN%6NX6&f^x&*NXN_GoA^-Zt;TM!g)r^c{hzWDS=DRbWJ6$ zw-+n&;^oiDiJj$tMwv3|-;uSxPZ5IXq^H|L{^kSK+h1QIkbLj<`)O!+$Go&x?W+nu zU}B`5d(QbA5l(p259FEAGWRG2FFwv0D)LL)4mzzu`!!Y>&++)0$*wXyTV;{Q^yJAY zp`>KjK64_!6*cEj#`W9dk_-}?9F?`5|JqrU6jmFmuzV6<;!$(8rfb?bttPmv^LUMh z>50X}^akQ_L`H~p#>HV^bFiC)NN37C=5dvSr_cB+taz{*iC2#Wi@&acM0@G^$l)5ZbW@QctZY&10fEd(|NJ$W`E`Br^G07fRj!g2wCN$P5{bw&=Xx#USd&wN1eujRwnOqpawe&p7{xV8 z`LWVv7IC9Bs?`^Vue%0cWBV&9=x3Go*WK9r{b|!;KZcbwFxV-HAi{ww&1I_0Y*DI4 zi*Y5EZtpy`+~i=kpC#;shpA?3xuM_kQd#Kq7f(wF#cCc!!@kE zfQ{wYg-+LyQ1|a*gaCbWsG9g=pK-+HS$fJt|CB$1M_Gr(EM`c*J9tXw={GUg0|S`x zVDka@NcylE4a+XVWnH-}p|{QQZPj(Oe+%}bjkeJS zTC2EQUXF*3Y%DeSeqQ!JsyRNPda)g$9~)D>QNHI=8Clq*tF=z%rmnHd|Ja3VyelT7 zrqX5ha|$T#cPc9$w_ZN3rjF$_(i7!~_FW3pb%-gQN%D+UwA2++Ii?|B4kf01TP;ClN33vK<45l?yk2UrB2Fp%kLO>R(Caz=C= z{olTL;)zF7z36n;{R}~63}^F&_9q|%?Ohew#?p!jym9tC6W@7eXQlA)s*aB8k0x0L za$Odue6H$BopMw59fdIQE2*6KSLT$~1~cqK#p2q-mDDU1brMUx>pVt!XqBZ%d2r1; zZ#OduexDO1DxWHlun1j+zHN7&K@#kv;s+*|1rCF6op`z&+qp@4e8;ay<50yKu_nuM7gzTz~)VeW*X0a zznjlvX_yl5LnIpL=D0PNd`y(c8;^@5Z?wI?{ltDQ(Sok4D2ksU-L@ zyEE<{gW5Y&P)UCrVjl1Dx(hk5+9wOs@64JoYE%lNQeiDR-4{jMuaa?`V|XAl-d@=r zE}8sid9ACVAxW=4bcEix!E1;~f1%g*x8$Pwf!`TjzMSz#A)HroI}&qB>$Lf5Ta)ig z^42@@YaO~)9Bs^xFOE2jjJksU&it;fwPB1q8jSi2^a*n?Wale74 zrDm%ZfG!lIJmyfgKj&#@eM#LwO_yY~P;aABsp~zab{dRLa0{*1r# zK;BB?hlGgv$i&S(>C8hbq&U1a7`uVd%607tP|5JY)Nq_9eJhs2O!IEGXrjnoLk4v(~<*4`7F}&`K-K30a zKN|Tr{!=?Yb|7*eljGXW_mXOIrrGEpJEtaETvL2X7;LixccYy?38+xw(NYP#1~ye# zX2^kuUyZ3Vq)m`@?0VFT%vG)FB4|HyXP|fNqOVzFM7SS0)6ll_5e^tT962p5N{EI^ zI81%l`uE)2ZO_c9rYi8^!{xC}CRcA$c?;-lR&Pww|$$Py{!Cs4Xt5<5`nD!G9jOq+>7q@>bWT8O&L4_ zE@g$~2;|CU8pd5`CMTt`*lcI^wEo46)E^V9MNC=q{&8tv!sl4pC9d|nuAxm9^sDDQ z%iME0V%8Cp5f51}NETSAo5_??2N2iLE zdC&?p1P&zOH=yI)5wJh*ry-ph7o4yjIjfn>+&jWCKifgCtKR&Ao{(M~w~4NnNTewbp{g=VPj*VWLR}n{D?KuU03?WxE zTV6UXp>(ts2nq6&xUUk#%E>Pm=*AuB1XaocQovqiEj<%bAO*Q{nmf)v&3~Walitdx3qsB|_-=f#& zOl9owu+(;c)* zHa_Qxd(}&;j{-6HyGF%*-V2JRpl>u-F?CM;aY8cCmK^mU_Y4kn@G_tMkrMe_gZp?! zLAX-#fgYoXaCFY&O$Ecx+1oD>sn6nba94F=k4^9hYK9_m_V$==qG^#JG#K}2Lto`3 z-+)Dc$a#BlY=qM853kXGlNB2+T8!Dr-5KZTLMOf)c(_Eg)Wsf~HOEO< zXtnJP*2KwF)*bR{?-~UbE`pGOc=Lq-4@0(XxsAJ2S_9A)^6m~4VW-p5hmU$`h~MVF zHyE39y+1`d`&I@na%MeE#MgNNZ@APWNxSCoMk~Ils_SQ5@}+)dCnT=s28MEwGi^q! zB6AO;@2#4&kLcO%lr&)rcwTqmj346TX8cT^YEW@^&Zp%$O_0_+ilL=vQ<9t32`&36 zM@#+km6zQD@lBkM@2qheSa=QixWQw3(dh znP9eyDD{E0_$ehG6WaU2ntA&e0_IdYI@Yd&BmB7Hv99$AGs4|*m#sCkc4O9mBgnp& z<3s7ce`kC&NQ-`wt@0BW*N~QL_(F?Xa~AFWvyablA9PGRAK#CY4h;I<8OE_ymdnP zBuFpQ_sGa}A%E;_^MM={fBQF)wBjxkPBTlGm`pnKzmklgsgIVHwwMR&7uCZ2{4z9o z1_lL{@ZkO`G%_-3o3T|Ry*2&a-rhbUAz@=+$cU?nix$II$OU(@6M|C}*OHx@&%hHMPz3ga}Lncftq&aVls*_?&4^2WPf8pwZ zs^fd||NcofF)xZiQv>x+#vRcqf^TQg8`={2JocdxosK)EuJ(P>ti5L3j^vq06(pzxI0cNohl9GxV8nFW@XlUDU(HYrIK?D{% zvrQ`g=xD!e^kXwr@-@tfbaYm0t5~iOI@+`v$1k3A`Z)F3{1>?Y)rIi1IAUX;xdaNS{fR09KQW93bU2obd4f?Uj;=) zzCybyEf(p%Jr@L$GPBQ(x$#`P-QYG_ADdUs#csM<{{DcfZZ^z(p=669Tf4?tqry6Y z$7yxmP1=o-i;jRNsC!$8UswS)f^Ltbk9wd4E>Q-A6CPo*}MP?w=^c zO-mMOG_grDXq1XULw;}Tx961N@N&v;-})&iD7-49+cJ1{CaYV$xuAw7_iyNwP@54k z@bp}tpzO8t@wQ%>^~9({gCv4+w86*6cc>$tTM@p9q_CQ(R;E)eP+Dk@WHOF!z+|08 zi_nB;yM;yg&WW%=O^TBD28IKy;znO1W8+IpMonO( zU}0gQ5YL6SWwTg*C+)Y4*X0=b_!6|71DK^1&w$2ys6d-9l#+^S4b&4)=V;WT(ClP) zfkj#orgZvxU|A_XzVo*q7aPk4H{`5AN%#j^mTkG_9eEZUdGH7cO`W&|R#Nd>NwEF@ zG&b@b0bjhbii*k%JGAT8oE~j4wRy>duH|Uj)G5QLs_&3bjGLPqkKOF&NuMjPn>V!f zHzvHxxE&U$Sy&X{*o%20k`7MS3Uk2}@ISCHGs~_9as*1CX8s$X>g`<*LlH}?4Mmq1 zXJ^8B;Wih|&`tm2%a=QK$Fo5>O4;E9Gp=Rf;o%rn^lWTO*#1BMSb(4{yGh4!SShKf zWE2^+td5u@MNU{ZWbIsP`1<;q_oVvD{-qV)TkKTS(uyyD7MEP16Lt8q&j_KNF+XpJ z`V!k;NXQSXXMd#+@8Lszc;?)nKjmZvE=pxdD(Z1_=j-p6jBW5A5XbR*Rm;Xxsev3t zMn%CDNQ#NUkY@zN$}W-#(YLantu7!kW@F^G=7?gRPId@%Hjg_w~#@Q5X$98wi$$kv_`c+9sClMVT9ry9$l>@5VetOg| zU&?*^_DyH%j@af_wL-cCf6>zlrX~#y4ceNC0@Nc?hmBZrB%KDINWi_4R-~k)fO*)< zR+mu;2ni{8d3FK{i5ImKHh!}h=ycpSmlhUicz86xHSM3ChsDLMu@*@vfUd5BThn{- zxuU(bRSs^^>)Bv<_(Qnpl|Z_J?Eo#6OX9WelutuTw{^{ND30<*va+aA$LnJNuT;u| zTWCz^2ZFR)Qk5tF<1N^TZ%g%XMdRaIO@IGp8MK7(_sq;lp6E3N;z`KJ90sUK0zV`P zNgg&S&#`c3D$~M$uRC=b9NBU@$MG2Nv0uvYu$qyfVU|f(V)*zHy+GoMr!%<$2!*|a z1K)*neHghX&0tvAeP4fn53ehK(9=h`^Z$%E;-ulg_`e}3PL!r9nJ${!&o(?~D(~IB zD-Sq9-@qUrdx4-Tt8qo6%sjn||4b@~fN2oMU~^#<>+J7c3^cR_aJ4^R`asrVs9+#f zB&gJSf~U-Upndfx8rrc4R-;@?2<2H~#Qp#GxFT$z%B!qqD;ye3xj$J={J!;;A$0XfRKQ6QUDp$E|acJlYm zjmDRrtDK8;MH2M~#Cu@bRcf5AeEs}Z6FoM2!YL(T_iUbSDch$BYgK#uVp)lDE#m>01zxL+!hr~g_!3&(u0ol3@^`JgZ zM-wh!ETv(>p_alSrZApWqTXqJFk7+3M89mrvU)a<&XX2#(reS9svqgO#<>X2AscW( zj%GyxY7%c_tU|UBR&Il|?R~#$eu*U_D!K+!hkK_6L!h>4KYzaLDl4wQ#KAd=QA3(Y zmYeqcp(=3jT&X-rSEF>9a_x*|$9wQV53~`97`-meBGt#1kNy9U23nhg@o``p!64Mq_1 zMakTRxw*N+(_|8O%*HG2qMB*NZ5l4h`7ibrBO@ZR;CqO89JA1`U;htwz&op0TIMBs z9jb$Fs*&c%#B-$}biLK5ywCD!RSWVOpveR-=sW6zd%sXV6Fka0%zMayVv#poq!H4&^@;Bj&J_yEr{?Y9V!TZ6ccW#~~lA zb=xcTx$>TH8qzkOtgWIj1LYirzFmrJ`-S#Xm;}oK6F?_4Q0=r<>bRl+_&n>)r(4wv zQJT099y~=LQGnF!^86%6AwBRGHc1v36-fi_I`^{P-rk7s-+wd*6X*I|U4qT*1I)*6 z(2NB@OFSH996nsXtwEGa!Jzi@H2?tx@E<&YEG!DD-umg8g0nx}^0~@IUCZ|LZ=E7t zBN-Tz2d@g)hvwBQtsz~XIv~e5_2`zZhnHX`(^KV79m8L=FVvK;t~vv?k!39sA~92Prz z>Y)<(_;EI|O|3j=3m+8%buT(DozrVz%6`CbtyuWSk01BfOS)FUaaX{H21AkwqgnIS)E|T4S-?Y$_z~O;!e%7f8PgN|O%zgQ3*NH0N5tK5~ zHAc)^+X$R4KZj?Nuo^Ax$&&wpi-!jpm2_Fy(FuW$07K2+@&4{z^C3P8pDz0OP?p+SX$NcY?2eCX(IoKpz$uO=b4pB>#OUHRM za-sLzb5S;jMJbdMT(}hq_Xy5!b*iC(|LWW!CWEGr?O-*x5H!av_LW<)@xSwO^bgu5%ZYSbVhDCQLcUz(Lhgq9UMAfVc;6 zR3IFmJ~0ICSi(^MK&9OrE-r2wRidjPyq!GUSq3nU20WrNhZ95r`7*u6Tapc`;uv@C zbVIC?4{E&vep)e!->cMlLt_KhhJmUL!06qRwzJU@$=`o`F(bpnXII|s`Z>>7qK>p zWOq;jcDG$a)csM(CicV7sVY*S5st|5bl(hIrL@Q4`i>*5H%c(~{_%ndvKZNLzIpSe zI#DKt*M5&EN?cJPB&N7BI#N;ZrE?$^|=c9hrG zPerK`04B5jo!d88Vt_ZWQRCiLpf2K^&{zQZgN*HM+gzdC4Cx_%35J4fpfY<;d~ zg*9NFtT1v8o5?)*l3*_Z;fhP#PN{(H>Q9% zFGFNE0Ea+P6=X06gsGqh`{NE>C^v*U302&;V3s4|@CTF0v?o<$6<9`8 zU{APP$A=FeR$=-bWzE2*WgM)xb%>6mt%w z6f|^jx#P@YHA;+wH!J6`L1Cpo-MXg$Dvv_Lxk9{!yFGyb0{cNS^RSml~;&`(14)@f-V#cb6W0x3h^K<0Bw{kLOKD3E~>N`yG&{63^pMC^HoE(w^NAU z#wO{;WU5W>g4NZ#m^=0;P3p^#R<5wtW;gAA4ab9e5|sak_}Hv9>}g_4o=TOyk<;e5 zI?DQhD?kM!fBp!HZ$3y>%#;~ukEE;Hoj+9g>2YM8uT`Z0y0aIE9c!OqX5JP~NyM!G z*}8h=Met+Rw}9z&>^c%d8)v%VhajE7BRe)NJv%!KIZ2#cFpP;UAm1ot!ME4JiqZ)k zj}3OK;h%4+s;cncu11B2r(T^kTq#0;2-$LowgFw40)%QuB0(!$KxC?cq9YPyY^5*L z;%IZio{I$aI4HB6TUf6FUa1HEh3`jUK8w?;l58HzF#k*7U9jb%s1hv!B1EaN3Y!Yg zY2hkkSLnc*)w_l8HR^1RLtQ5u1=_JCE@KtP~m2S&oTg%sPL z14aM7A*-d9Z0_rtTsN3MME94fZnTV`S>EzSR1D6-hi%3sTM>&VRYOTRMb=ES= z5d}a*8ddh`WM2F7vW&=%j?#0F$TT8$b60zHa0_@OB(jpS{|NJ)<=V5xcK<(55CG}l7WI$i91n`L6^VoJ_X~_a`aa1!87#7()5R^SgPJsLAf#@I$ zfTM@B$5@qv3A^>U+QHh8D!{`?1R@g!eE~U`_hkf=c^~T;nV5J4)~n>G;zqdP++s6=Uq6nFp|y(78q%F#iveY#y7axVYT)bxU@uQKfJX3{P9z zpP&c~A?trok_+fM2hcAnpE*SFvdya_gp5xEOuC|}X%-5Q!1qYn`&0n>8H8`859!@l zSNrtwBkrR|zzgf2t6Hdo_qJFgzp_#dWtafsM#jWsgM2T;p(YyL2c!Y6cbR=^4Zd5s z#8?_76DY3>xs8EzNrGTPW^&^x&2k@yn=^|yO!_q%gjDbQ~a6_7y1dOHs=ZWWA zAEc+Hxsq9oR~8i)7t?=TJqMW|_#ukZ)oTNuFLZZrFCTl&WMOe}b-wL8Bsikx$r2zV zqUuPiBL?LIJOYAD04vby^G(O;-@Dk17c%i#fH>(Oy#qq1Jl7mdS%sL8l8``Uo*6=V zJ0aDSz%%g30yL@GWvgIzR=+cvSqLRq15YLFaZ*vx9)igfz->B^UFwG)<6ElK)6+}j z=pZ&UGD2BVP^|&Dwn9iu(E_^|4Gj$nPoR7Og6B$&3{1tdG9%nH}l&WnI80uqG~tN7`;F1(AhhbM!IL_8`Z z{^0prS8YaKUV-?DMU@<-w%pP25`(g_jYKUKIXU*1Ot1gf3y=(x=xuBE>JV~3;xhw^ z66O%@;DxB$R8R83r-T%?6F9#$8z9T0LZFhw-;wxCI+jk+h#pUC>kYQd0dOQUB+P z_^!_PP};TbT(dfukJ8_4uw17Q{;-*LKgkt}nBU|Tla^M_*C+$CkpY#RRe&>zYZDN& zf?xV&acTia50!^PAYak~cZy09I(4!SnF9Vn8EI5N(+Nul;jUUOGW1A!9K}FXa(@bI zS3$r&Qu5iKLb*^!`#Y8FAduj!vmj}@j&hRwQC_3<> zAT9MM@Dud>%nTG2Fh1*QwdaV44dI2$(*@***opkSb_gRK{4>z zFB)Is5)!J-q?T7!4%5Ar2K;UcF+H9>IFStNnhg%|O`4W_L~PvvHv7}WA4wYA!^R#2 zg*foJI`VN}h*aH&XqfuRlV5ZVs%;Y?1-cD7C?lo|yXa7vuBd0<(jalncQ|Z-0@Msi z1sjs(Hd6&2V18>$92(AdCA-3P!#$ofL0UW=M8>_-PA~TV!`_>R^}K)YzhN7;VQ*80 zOd&I&Ql`vBW*Vh3REEeJy-2I{%67S+q-w|a!N^$ic%9+_baJ)%(hR< zF&Fh9ZtVna~G9nf3{hD?PAqo8!f>v4ph-=Dbc=qd@ujL zq-V~8%3Efd%xusrn_tqhkL$yAc1!g1_JYhz`%a!!kW+lb*Y_<q_UF}|B@Yb^GOOjDR>az>_gHTo85r=B_ zm5+ler?fF7L2W5Hxz+i=vW*|w4D*gn`VKe;F%KO*dXW!o``H%llm>$}2lgY(2L~jq-(UHAStJ!JT?HTmOD30cHRQs zSw>P8Mxw+iQ=`Z(J}LB4b#w6XS2SF0{pyS_uiZAC2?_#dAuc6j-5=E!a(5l~l)!v* zmH49%$GhyEve7C!hY(b(IH#;JfSZDLU58SIj;+tqLgL#y;04U~x!Hb6E8m2!J>kqV zi(Q@3+pXfxpi>PU-)DuDEO8Dd*$R^U_HXeA6KHw2f-Tw8r%$(z&Y3tT-}KI^=pmY# zMv;+`q>L;kH9ZM8pYV}W^^DE8_%YLmq9e}!h+o`nUY$fs7&{@r0cqB|ny6DiP{@qi z=#GwN1J<5U zY(2o}_GpM(!*H`D)S6$u#R*YT+C~@%0#Wj-gb%Kfr^>e!JWO4~8|&5U(%ZLdVr_Gc zDoZkq_jef)!#bBgA_fWzn*Bx%83*ixur2A~B~tva8o`7%kDb(*t2u8rgN5?l+y zP4R3DOia!T&i{Qlw#wXj5MSQNrK_3Ph13${>RjwlA) z_ElbvN#n37yn81}|unG<#0?AbrGFd_mNKr_kdq_;&zMn{Z` zqX5D}a=s(>Lp_Tit=&+SX|%_1D#Y>^l8*4k6DBO}-n~13G?)N*HYCv96htS?AJs(i zO8rj+AK|?Q%@24;hKaSO36kg}K7ujXW4oZ()qA*)bE|sy4hI`7ReFC`?{F2O)>`@Lp+kN6X)CLPW7D5#pLhn<8OP;fNcKI{_A($mBjt~heERjpU8B&GG>LHJurs69VfGO1< z$CR2I(X+_W&80luggz}oquZL1&)ZFDLZ7}j^2xJnMslC>DiVQ<8;KR zav%fqL~aOAs+ipX3!jNLA#vS=)ya?W_LuE46B%rQ>i)m}dI$ocdj6nTqFxj~e8Pm> z!|9>M5#d`4oMwUuA5tmDZhAS*t+B4eXpgLMNyYN;hP~MXS<73WOS;PBVI`fpKf-$p z%kz{;(3vwac15%0*}y1>hk`ok$@xY7=UDnZcoT)}Dg2Vq1f-lXRF*WyNsP_LAQ)<4`cB_y^93=5@mq zLT=Dg!rYHX#E?>S6o}0#zLM8uaU^5sk+UVIT;@~0NHk&c<3+w}DCGwwOCYH)mMNdq z%-4s7_m$b4uvejQ#m}#94ifNq^X3e%K9em79Y&<&+unU5fay-Qs_Jt$j>tcGE+)nx z{piT-t%YtO+qWxF*9ri((3)*a0Fx`Djs!-H1ZC%=XuaGtR%2_KS+B|NdFq+BdbroF z9tM%jehURvZR`EMAUTmYI?+ET`~0HmBKn({9NTp$;pEuO)1p^re94O-^@m?;bf)s0 z#U_?~>&wc3N({P65$d?6f< z_NRZEkysbQqEBk9wG==@(R3tme*+OA;&Q4U0Z4co8~)dsmEso|D21>Mg`>rxbXmPZ z;ZL19RdoBWat7h3m~Ed|N{q(LmGxJL{vyDWmN4^FLjsrL+LE|Nl`5P*oWWX3F)@$v z@T63A(MfGM_v(XL7Z`a}^Mq}-s{W)Xqz}0YXa0l$1GVsC$+RTbYt|bNLC_Em3l*P7 zuDG#VR^2Hxfc;tC8$a9wH;TxwQt<&V5=w*prLs-8&)HQmec{4`l)@LqyujZHWi(== zeMZ;!QtOkhOC|pzvhs9;*$7UCs%SEsKHP1B0x!MN9!B8j%$WWs_ z4hM*T_X8&{OZDz!jC0}%q6C<9DbbmKPH1gBwR-Yma7%A(=kv%>Qe-$HV?#)thYYb8 zeV&wU=}cbGuCZLX@(IygK1}utDM?bhV)M+30Sf6t?PhZ{WZN5`s&)b3E-VO~bfjii za$T{%;+Iq*Yn;D)5Nn%QvxcG=5F@jaUA9Ja8{CMSsT8J2HW;w#Nu2FcXl2Zfq@OKP z?uI9pjgLr6l&%(e)?{yiY$B2(--yQFYvQ(r;s<z5jDA)BkyN|MTc%@5?{`&v~2wXVvkz|8Lo_-vg8D zfAc<*_x=0#y94_+Z*_2C|5+V=`NQDc&fk7b-e&Oa?=!t;EZV2x=eVY+oxxa#%iH_C z?Qr1P;Mr$u`YE4jHEU4&R=-T|IBVMTvc|?Vt;*ba3uc+Tn$#z|sOVmquglieTho$? z-3ouK7HsGSt^OCs`~MIBu)W`MYRKn_TO)$}n<#9$tT@c*EoIz+4L>^trW~3%r9~bp zZJ4<1L{yvHP<1%SznQ|OzmFa3=2lm9RB7V2%LjUnd-b;X=QHcPcEf=U3Q+)^@$%O` zDw8KqmMZMG4U4X099|HE_d-w1(n83#yz;g&8oVd^r;kI)gI+DK1b>oZ350V{C3elD zY4E9boAy_fmsgo8ioKp&3zH^RWp{V`2Ts8-27*(R#5$Bdo*3cr^55o`4KH3Shwck&Z|dZc z1BV3-9V8SF4w%gj_I4jp(i{V`pv%jg{VBx8#BBu*HCQ zw4Cfhb7T_>ry@l-$T@%`I|qA(7vToy7fz+B^WDFHzm&8H&A8tuBrN&)>~#+4x3Ee} z#LQ&EP4C;g_tC3c`+MaFn9Z5I!FblJH1mzoCXp*|$0R1!n{OPM49hPp?xCFZM^r>Z z$EZI1Q$uI#{<@x{rrmAcri)eL2dbHKRLt+F&qeKi5IEVx+w|AfTM^?Dw@(^4@b;s5 z{}#@m4_f*2jxx@sF>M_|N-rZk2X$*sfl!6Z8)>!l0 z?2Yv)oqa_+!!P~AH+g~MBATcCzS^fzeW+(fTZOV%ag3y=&-qcG@7l9x!d0FB+-jR9 z-R+9Jv_d1;p9XdFAFB#s2!n!m(Ze5RqiVh~-5dV;3^?c0C z%$}fMH_cB`cZO|%ff^<(l<1dqIrPd`QMkH}Ct={-TU$ksa#!k4%O1b{_}Yax+aK&} z3|SZvZ(m}Ap;6?aApgU|;_`=}l0Pil9F}$B_1C?e{f#n>Heqwc)kx8blXAr5LPv_L zu`L#-IF$=r%Fc1k|6ZRHCB%{#<&bStAKh=Vy=f)8oo>lY1%rQ@D)vD21xt1;xjczkT}i&!zvlXNRlf5}J5ub=j{& zc?8|$t8xK;26OeQxc6r9b~@j`l}z@kqkJl5V`SLXv8;CO+_?tD9!fY1M-F81kSt1Z z$|xyaH_vohC0qr@UjrWlL}77hiS<*~+KoNG4`cIoyOy4nW$2^90vD>yN6M~w$JGX; zW()T!sGoOiw|VoTc)KDIxvG(eAXAsey)V23w>b=KdV?s|s$dU+E@%i)U-hHrb{`>F0AD&L2`0CiP{8SW2 zTI5}Qd)$v*kiIfDphDfQUxKe3zD6bYOSnbybCcT{85t&8TEd%fkdf8b zJV^Qvf81ipJ@?9uTXkPahzp-LuU`k1r_`(7&_pp>ZP4h2a*yNY5k!gTFuf+Zn(&O^ zQhfpg1C=z^{LL3C-hH+SZwXJ+-vJ&fKgmh|)TvWLm&RQbVi#p}RqeMjBVI8UVuw#J zrt*1uRHzkSz8txB?V6I-hKnfNVbgZCUK0KtM&Lb8A72&i&x{Nl@31DW-kzc>+w%2}L zDSQWy|KojgEk#i?vSgg70Z2>Wd-PfV{jsgShoeggN6b z^`}gk5*}wAY2v_OrH}cE#=;Y`CWWsc&dV(db0-82(YeINMNdzU+SUKdhnygu2j@gB zRXaYnqPjXuy3z;%Ve-YNTr#gcQE zQ54m6q{S1+S})}R^QiO@0K^I-oFkHCde*Hm(K#1U=WSq=u@I(huFEsQbBbrM|LcF( zpTNPxlAdFF%{|#%*`(Y0MB@)|?VrEL>`zN{{P_6tiW>%JX6zk)Wi-05SW@WX%BD+C zu~Vo1dMxuJk)9uSZCbW$8QuZ$;HOpn>oosMS^m1YTI-*UTJYLmR5h64<3_*l+_h^6 z^rHY0q3J~_fGsh_!=GR8I}q^`jv!2N zU;a;EB)oc#Q_JppGrAM*7M$PK=hu5eHQ}kC<$_gfTK)FXbe7Ix|J?lV4jVCm(|58E z<3|2#_Q-g*uQBrjCtVUDb|goc5P*%9Bh(|p&En7SVX(myZ`czW^mnyZbZGdxMNiCO z_HEO6?Ur-3pyM((t%u4oO>npXo2ovsD-0plXNi713wa?$<>i6dM~m8XmnYb0P?Wx} zIrB%Sk9+ND^n$~uCp?cS|A&`vKsqE?>ZGKkY|T%>N4J(fg6;{e=IZHa7NSL% zrkqB{KuA%MKd~?Ior;R*kR^MKvzvii>M{I}eNy+AH}`fD>P}tzw@mkuTXB5jNh`&N zdsJH1K7Ns##sjXDy5R(n5W(#&*ZP&{Abi~g!e`EgIkVfPvF`>AsjeL7^5vqiHLsn2 zF3$%CwqI=jOY`R4n;gHj@)7We7g00(=z>0;5S0Tni^RbP2dy;KD=aMR+qZ9>VI}Dv zu#A`6!kdc#F*UAhhjUMse+1PHxxDFv@bhe}kG<{f?GF=gAI)dMVt_1q7WYkB_js8D z&Ka#dXUNfjFa8YG4>{2It#SeJL8RCmqjyd&E@6<8nBp%D@3LPqClNK*&4Tb`gl8=) z$;n9{`M$Zhw&2n0G?{%xNa2Y(cMln8sbq3WmA!UW17krlPip77 zfBQUBT6^dq%gWx8!#Hva&;KX85APp9G)@#1!uXS}kk-;3Q z-x&hnCuF{hpqYFvCPBwsf~g<*>)xtp@~ch2^q`<1@sy(i&A~%5E7*2|Q^i?b@7}gu zRqAVN&y(L0>`M-StGo(#5t7#+DakrJa=jEdTK!-``7_&ymACfsu^eg?v$=8(S6`eF z7;*FF&7P_At12t?L6lyV1(4Ri{-=Jl+rc`=IytkkvGMksgq#q!=DFWdu3E>k4ic$H=TNV&GF+2S65dJ ztZ4WUA8or2;VhZmyk?#B@>)fjSg9Sax~HCT9>96~*2kSYe-VvK0@WhzYD_asgPH%^ z1?AcLsDp_$&*E|uDa)R3N#At;K*JaVUc7aZ8N!o?L_FeTnZ?E zbg=LA4?}NK-3!#z+25rU?163a>9@K{schTYMw?y|6xCss--x9~?81cx*q4n+lyUQ?}GV8H2r5Aj^86g z<+n=1wtC9){7NNZ%UVWG-QP@owO8epp|ghZp#)!8la={H(*(jU514r z@gM2gaz@gjZ&LkrBoAh^v0^j!mb6yLL-_k|WpS`!EO29T4Dy^!o?iLOm#3vzd6yF% zl5b)L*YO14Zm}k7Fez2w<> zg>kr9WbRWIv!|_-v$G92se8f#2Ov2J_~V1AT~*D}s?0Xg1VoW?=U5+FqRh9A(4%sH zf}$iogl^sd8I?@?a!xt&dY6c>jEQs5^iS0<{`~#9+o1caqNzgtRxB;e=^b`_%ZQ(N zdAn!8B;|T6H*_KdgnXx2;n-_O+h%I}Z>`K85jY|@)n8++kFAy=?df9vO-fEycPpS& zg{M+$svMRTO4u%W_LTA?r+Je)g20OG0omUh3cpML?GjZeCoO2LSK(idAE(XqEzjKN zY|Gx;rhp8iT~cQ3?WlWn|6&_0r}#*kP^7{HR-^d5sm#&|S-OSGvWAbG8Y zDH@)bbMG!__N47m+XWLp@67);{daAvZ0i-yJeJ7BRslzqBhQOR+`OA#ffN)3yY7{+ z0zjb|r)tO_y?(^2Z}{MRKGuAqrA{*?7k7c9xn1#7st>OXTJr`TW~PbP@Kkm6<8wt~ z-rRG>j2X`i#}&}+@oCzD*VA(vpO!t39hPbR_et?t$c?Ebh+#9h~zJ(ah5^NTeNtdKlk90^S>RI#t2C4JuT9@)Tl9wK>7_d4=NOZNV?usUYdr@J z=ws6}_lEYsmR8OF>Q)JDk>==6jE+hid+azDkz;u1ocY1@ebm)V35YTusO4T))HNvK z=B--;az722=h$^xWxD34yP*@t=7vT=GCub*JbWA)QCwP!-|b45c3hvTSNlgQ1*Q^m z?G<%b6;U^+1y`ycSwL@ov|9?WhQK$b*dLwtV?{whfn(RBz?RCq;4?$DURuE*d{Es` zQl*`Kj~aZvL2qYg=T%D2pFw6s_83$OVo0l;WP9VUnSIAo7Ud7mZtd`cFrSl z+f=c$yH`Tq-rej^CzD37ZDQ*OBXUQ-+}CyFDNEyX0}tO(9X0R!5-QB+wQcQfuHCVU z>d{g?I^#0w#IX{p^PZgxK>8`wk=OUfEfd#jnao-&9Ph=B?yx{!SeRTT`_`r ztqsev=~@1>Qb;?I={?mb%IeNU?_Uq&?+6QTLnnem@xAUO7FCi?y6U&FOoi_7;A&#x zYL_eS7SMc!SECy(3>%+WB)Pyr)4{QI!IyRKDNr5#CL$x>b%^H)8MwQ-6Atw_ z?seZ`@(^KQG}bKNIe{Yi?!qC~xydW}k`D=K_vX_iu4;DmZ+6d+Ns|iR&K~Wy+%+Qc z)bO@(sX>W}VtMy}JwC2)#;!J9E0PxEzK#S`EHN_3k!Ewo*qnIprb2@^_*ia{PFr(p z!{;W;7Z(Sv;F)>Z?@|#P7)g&@b4l$|QdLF8-Kbu1F3d=XO{D15A5S zW|JD629fpIC+V9f|EGw%SK2I!-kFln^chPfFlUWt(>w&o4d(?qe9j{3y>`kiJ1u4i zuB7BbuO*R})Tl4OSS!O-QwrPVwmzS9Akc6jIMh?3L>No?G&@SgW7Xr} zxh=aCm6SrU`aCa-XAMbXmxvcMavY1;G&kzn!llmw6MqafNh&F3)#i96ffnf#7kI}gzRABJurT&Z$Nd` zJre@A`|XYQ^jIOoyUd9**AJ#VUop39)#t00slQ1V8D7@=HQhFo5fO=1B`*#+jM?P+83(DKoJK@;@@5LsH3v*zSBHzCn6;`I0$$q=l zDvc9^wP4Lxk83=9^ypEsT~RwHZfKpEM4O{{3Dq4^{kqmAZ*P+t`SH{UO-;>=_az#^ z3+F$+{XG3r%+NHAx_0*EGbx9&{%GDt8Z1Q%z{RG!(Bs{cA^rb?m%9^Je-nrxMP^)^ z4FNjt2VPdux^Ot8hxU5!mw$}!jeDeup3_{z_4!_;bI30zX-p*b4bsys+H7ilhCnL4 zP&iSnoO|odnsxR4=E>`Y1YCj zG09eWWqNLIefY?-=Z@L8PJY*!{_ zoP?6~)14PASRl~YsX*5vG*zYEUT11gZ`PMA8_&Cw58pYZb&!c~(+W?o)narRo1Gl07# zrxrx{WR_3=TB*AsA?zouzsd0zt6lfvqOPykTnDWo{wwpEeN;a2y*mxkdTbor*&y31 zCo+HLRD*tRvVhbdiYrZZXbRnf0(L8(zDt!@$q2Bb4)YYcVMMU+oRMM_~k}c zxjlDp+4|MCZ}i7_Zn}tCB|}_#JH0uSSP<^3^kU4~$2YsR9Nw?rG|)mO#9=JS9KYZY z2!EN-L^%0DH=Bhk8=ke|`2F}&yD7Gn<)hr*y&ZhvDT z4#?qTf`j?PW`D8lL0O%DxQ%t(Yqy*Ov34WB32Wh6`^nt4KhGHQeE8p8icZ2SjW#!E z8g)&-`C@l70ibaW-|W&Id*#|HcIn!+YogokJ$t&QX_j{d6_1*BihGl>62!()?%sEg zjtsOmv4eeSU_Qg`Zx~F=oW>Tvt$FWsS$x?ed<=Q(;)$_2N>+XK|=ZyxmQ?#m?0u|rkFQN2!V(O|b zoLyXUo3Cm9l0rc%cpZWA@7xEoSys|ftaqVn2)oq)V$UV2oWfFRYjHipAk@-@|2mFs1V z=P;`6X_00UuFLCssj1oNfcwa1O`Cd_ihjuhlosyOWzp15y63Ce=y%s^mORrb$DZm? z@kS4Dph%N@-nIvt+Y)l^1G8+hP~bf4U_`=D-;S#;O>kH{@7SoRGKc1K4iD;PSz^cb z?Uy^$#AAqVT7IUIMDs&4)t>PEXK?OpZE!HZ8GA+7`p=y8G9AUU1X9%Ry|T){fdf-# zAEv;|HJm05=zT^!NCaX$X>|@V5k4-pXLdXafO&bgP3$}Jm|F1!#}CIsHgsh6m{)1l z>tp$Iq$yyuZKO%-H_1cR1C}&{ait%5t<&)E;lrl6TUQw6z6t(gBhiRbU9&hd!90CG zd8S81fA#%t(udo>&bj81>pv2*%Rg+NH5%&s40%Df9jIe_J~bcpV?9q<^sl0? z%Rl+~=0IxAV%w41WY|Do6`lidTOT_+(r(3d@`7{w--%P(=7%=IsZ zyzs1}(pZOSH77h8z>xg)U6|;nDGC2Dxh`nY65#9^ zqTK=t`nc`(??iP)=bA7&`$mPjawF>;?6GwkB5L+eum0B1@Ub{MVp(8O6j%2Uo#{jG z^mp2G3zKafcX;-{wqPx_*t)raOpu{VOfN2d&+gqa&qQgQoz3*4g`Umy(bbgL*pr*8Xd;6hiQy-fy z&yAaPp-?-wbqrh8+NJ+aIDLBO{+2op6Q|pe^mCC7TX*#zs{FI&+SjjXl#5FAi(soe zKF%bz%9xWtiFMB|uMkw1-#nSMBlDIVEjL5t8@)!J^>gbEoKCECU4?=ScC zk+CF>sYTG&F*w*6GZH_grh!)LZkZyK@=`qO@(hySSTP`jw-$l^uyNw5SkvmtjLGk@ zA6yRm4g0+@Tn#4QJE^Iu&l(XfV)*8^eQWVuOH)HKZIn?a!$piTHx7+2Dk}@eY^_u& zZ))eSoz#AbqTUvsO&sR0BL$qCccgF-= zG5t*z;b!AlTN%fg9FifdVh`Q3Ps$5u(DkZAifY$q(!}XwLVcg-zd>@S##@~Z z*)P+$Sa0edvY(6VtMA4aCP6HTEC8EG0<>uGCdn zi!c@*9uB{o36yiF|6-eHP1FqMsdqN1w-2Je7m9<6l~~?2*4(S_7!NFSiLR^GoFvxvRC#pfgb(Ym(YIy?piR z4C29io~)m*a|ag|!%&N)tFU>@LbA@D7m%3fl9IS`&PYO4w@O*w^0-~y+(b6kDsQY1c%^N-UT~>;yV>~lQ@@eREM)GOG`HjZ#|GmD&=<%+ z-7$3I#*I3y4gx&=|Z<+Cl;%mse!%mRdYUkNMv|B`VWT+5~#`Chsd()z;WSS}g zSLtOom7PpiiBC-AJ?19&Q5)d9) zE-nrRMXW>e(;c(i)Yy*=YlJxO0E%LeSk{I@)EsFGsEo}ZFRf$n+lkSZyODgr4jQZO zb@Lmdugj(TkgoyrA2-CDXO!K-|5cfUpSFZ}B zc58>#U0KX3K4+0xr0H5pkfBBw2ZP#4`K!lzx9hHUGd%sC2B`0$(2xX}*|RUXyJ4f3 zND#F2CYo+y_=5brJPii+pk1u0>mA&nd-e{&$meqj|7rlIGqiX zwb8SarKUea_YU>#*@jt6_l~Q3ZO$k=N7c;$vPF*OFJufVNJV#SF-r}I6G}wb8XF<> zlldoNsAWoACb@!i*uC;VXus%>8-y4gci^=ByveZ>%w)*hK>S zs9KD7Mf&koFE@~~HKy;n&EAXt*mT4dhSgpYgBGd@YGg@9U^YZN7x*5gn<-nHv+LK9 zBbaTpCi~VY24sHe(YyDCotDre4-u8Cnc$P3HK`@yec$Q3pKWQf4e3s1?+Hr&SDBS6 z;~|9RJCduUW;JW~WmR|wDAk|0DCRnLa7vhCi7xNnkX&dviLUl=wPC|#5U9u;L1#wJ z!^Ma6LrLaF4j;Pc%+AlpY^&!xb3<`qNplz^0M1o2IH-4^eo~G^1?D%Y2L!Te9MCLS z{7Tmn2Oidg&d$W`Q*LuF42At2eU{NZnvGzdnz%cNk)E6G-MXdoy*72SK%D0%EgyFt zX<^1ho5#Y()?B@{GIE0PM7m|9@xuI^p;6!pMrdi^;R;%}ct~}zw^%>W2OVFU(7HE< z1zY_gM?F3J>l6J2rBYf?D7l%MDzlBoqg9%ZHR5(zWV7H!pwt%IWFKBD?Yu-U>%@sa z7t-QIQyqT?B3VdR`PnCT|DZdyXl+Bs0kfrBPG-@`U>9^}#A1Uh8w-!1Gsvg|iVWr{ zzYSM4D!3%gA&|K;RZNUM)SATEO&_Z+?jjk|L^UX}QElsKFLc36;=%Z1YnVTDe z%gJmDh)5zk(O6p0G`}200dLh%qMMih^5GH_>!n8U&O8&3NuDI z@`!{j!y{1s!oVu>qrf`R2-Xhp#Id5=>f49WHH zKvgB}Z_+9$&G;f2W3WpMZ)-d5UAr$C;3^BKCeZ15Srj*P)kYZU00k=x2uv{o&E_R8&%CN#x*#eUMP-3BqE>1 zVG9_oQudckn zLP^pyfB270w7uUB)h^|y33xp+Tcwp90*t+-&_3$>JnKb&?}@MEvfdD$xk;tUwfQ%jC@gsA?GzOBzB1nkkT6(J#*|&? z{c{X^TK}d|)2uZ8w_r_fpdxz;{i34Bij;v~z4FxZ%4Glz(L&Ehyr*E7aX4$Y*WV(~ zpCtzW7!sI;O(<2f)sF}9cPl%4hh~l8(o#*`4XQ{?MV}psRjXxeYn@%J1et+zSeJIOlk=BNFAOGLR=Z=trPQ>@3($XR9MzP}2HvWkI z!EP>Xov_87=QS*wG-;BoydVB`Wjrf<1b=qM+tI}E*3Y21_4+NFSkqqltrT+h@7uQ+ zcOMpj;6OJcAr0YvgBMMs6*QZ? zT=ec;s5EnvN$ni;n<(fU+@EC=+oekPT7B6B(cbxPEIl}t17&Yg1j~>#9B+>RGiO0N zcdgF+)lOm4_a%^CC^mFY_ru^19UF#BAqa7M7XZ&Y{LjDs5^N2 zWhw(WznZb!?;%-@xf$k$Zz;N~=mrV$&Af%e)sZqPhqx$t^uNrz_$kD|p?jd`1yYst z&`$pTEgHbkE8k3EN(cSHidN#n#Y!i)$=~Ud+%Ot_tYR#tR86>j}3~H#a5o_(P zM-bv=vxT>(#hht?YlYB3u*i}*GGtJ?A`XEwWJ2VYkIxNd`d5&D8-*z?L~mE=uC>LL z@hn1>$ao(pzxafNP!hKoN~C%F#Z&Hk5rVDCxl`%#IK>VgvLMiis!jS}38gYUK_4oE zM%hyN@qH(z{hCG=l0?{mX;+#Dc&g#NRO#{-qYw8hUUS=mq;b=ytkU$yZ|u4D@SU3{ z>l8M5AG^Pb6#gl37=*-3(ECCf;DPRE`F6QE87cgqss&86j%CulDF%l#F->jv-|7c@ zU7)XUb>`y)r;@E&(y~*E{TgI}HxtRfwKK3X`VC3{EM*;%Y2V}4+8Ns9L z*Igm68OsMIj@28G-WZ55Bb~ouXa-u#2uf{ym(*8&JXD!QK<#PWDvezr%SdmZxA)PI zkU=GC3Rhb`ZrnXsKlq-Thw3oj?Q>^0{E4e_F)Wuc)EHA)Mj(v@<>ln&E@iQHe=3dM zb*+jXg>d8A@Wg;Y{m7 zHpxQe&ehUC?RgA6ytTg^L*7pLL!j_Ojn;beR~H$;}U*VDCe!J?8 zsSH#n)WyduJ|B?SF9a(V%fMG!vE(EH?6R5E%LEzgSW`ji3>_VE!&xSG(rZ6}9l+qc zH8S2EUPZn@>a_zKnr^SZDZ?QNgX0sr$9L(`BMfCbX_lGgaNp>U;Re%0#Iy-~EnXy76df~#*cFJCGKZm|Hyb9msBB4w? zhgw=%(!jwF3jUXg(R6*K-M>H2?3=sd3fO3|WHB`*7`}wtvV#>!k;)i*!W@crW?nB2wv6k{)i1WGK8D)Q(qcsH zmWXB3QZ^4)m<8`*bk_aaK}AjtpVx?LR)GInQyOwVF?i_FDahh)q~6F&6G zH4l&cc>9^e-9;q1HkLIC3VE?yzl<4&x?IG2LL5T5Y#6Gb zaGWt!GPeZ;oE2p~M-KmBiwfp1aH}zozj{>$855DVNcKxJ;1O{NgV=ySNQLoRd_qD( zs5e3&aHS84$2hp7VQcX5g44fPQK>(Heo>!T0KLe*2_NP7tHP8WU|jcL?;3`0VqT3; zz0^cOxg2bNbZvw@Y)L>pANEsFs3?{$sjAO0r_B`UnUp)zw?Jz z#cx|E2N80@emu$+FP_M#kGBIAbW9=J42Xy`wVG|R@o20I3G!FyyjI5c5@CAgxBce= zO`LQCD(s6P=7r%cr-}5%6G7@TwVLE8D<}RgGrVPHAFZZiW1%qLq0HMmsBiCgf#s^i ztPOU~E1>rLk7Alf-Q;8co+arTN?pc+&(vzZ$p$ze#WNq$Sr2|7``Bnpu}uH?yZC&}VzU5Euy=9tk)4PQLn*WbR}a ztr9imKFH1;00{FakhjY3c4^;UnW-qU!XM3RvM+$xa-JDX8v8))?I+qHz3J8x(;Go+B* z58r>(2P|K!>k{yOFzQAbx)v6!b8X3nNE3YX!$3V)DP7%;@WQsM>oNb8)kzn|nE3c{ zjTx2y!K-L;>6Hmu8w(5|sK{kxmvcR@z(-1-j$9yJ97GwPvyfhcaVVe=$dkcH4*XHS z7>LHl;u2PaEPc@TtGh*t>k|C!hwwp>^f4F??e5WMAZ7+8M?G_-Psjk6pLi|#aR6ge z#*f-ZF2u zGN}yrjY#5*c)ZKCO1efmS0BC=6R5OI+;|N}ScnFX$OhUy1<(uoGe_=6p| zaijl@C`mlf+MrH3=n7tYEkAg>PY|ywixA{x3mHEHs>kQ7O!%Q2`jD?ulyHp9!GDM_ zCY>Vq(id?fe&i*U(hDJ{7IUW{Q8|8rGAxaEMW=wo2L{*QjrhZM!OsO$0?HkDYpQ zTAc86l5{OBETp=!*!HqHJCnIudU77kr1}r)WX1iwZ-p8e;SD``mq)p!rpPiSf zeL800;1LTQkDt4!HluxegN03|o>gwuZ*c2Y&8_~NyJ(74nnlyrP5TWVI{i!g^J&2! z9zA}XuQJch!=oy@en5=!dBxa_`s#P-D#`KVv=}v4Ik9BioTH1Awtb%bX~X1WkJebB z*sRaHdI)HFWaP2~`}e0W`>Hgp)o0^)r^bQw9Z_gGc`MCx zJ++;E;qo3*AOfCFw(RW!dZg=c2Kz^E-aN?tQ5y>;_UzTG4t@4n%-T*gv>%&0kheK~ z?%cNI!q^F^FmSk$Tk_0Tv4Rxv_UuP+efj$JpLeWY0o{p+Ug+eC{`YU=wX4P0LZST| ztalM8Vs60LLu`-YwU!i;ty;DEn?>8aqjLJmg`5fGeSDIe7%pqmmrZZgxA8Y{9bNc7 zAk)VFO|1~72KDRr>i6bpbk8mzW__xvvI76hN22|flm_);4Ext}_#PqXbl3o2pJ4>J z$&Oq=EQrim&wTkgz5FrH?*WS+K6GfRqobzi4xN;laBPWKA25E)K3r?X_1Z7FMR~+5 zUhOZjlR~MhDsiVr(l7Aq!M)#A_%DxScJ@PDoffX2b=Yg?%@Z|gMk?l%l63nI@C>-e zRw0jCSy?^A^iJ1g>Dh(s57ak`y~8Z=1mS< zg*@4?Dh0~gQvcjmYRw58T*b{dW0sv#Mc^1?I4v04IkbX9KYp{ zNN7kJTAPg9F@EyoYp(UzfnSR-d_e+?b^OqcopyHaaWw|9ZH68ZW|azLE@wFTzild>4;FoXbtHT@BbSC%Yp>+J#e8e3j6+K_j3G(A}> zQie5c96o5!paL8k47Ffz*T%+*$~Jv>rWJBN%tM>lwn`drw|akM^@5~VAg!Ja4z8fP zll0yin5K(7^ENMD{h+?BCAC%(gMxdCVzGX`+^Fkuhgv@(f^e<0qGjQJAgT_MUhQGC?t|ZddzP z5oZUtCIP$zh;!B&SAAjO>1n54Uo;wq`RNVI&SZEO9$u^8e^1TH>AwHgzqH~Eu}B&V z8}fqk-FNsBAATt8R~NFhii(Ot`}XapkZ~Wrujbx5_UOUEc&#z>$~A#nlm{KGq8H%c zp+lcTIw?)6ebKDik$^GSIJ_sn|E}90@#ddc`1@ss^%4ajS+o`8IGUZDjNSS*K z6CJzdU1v@Ic9fGiBLS;X`J0z4Su)%_!I##H?uYN}q?;7)QV1#+j}bO#&;I>w=mtP* zw2U>CT?0q>3b&~><=)_Zf9M8X&&cowGcQ8#mkA13X?EROiHWq5dJgYSpSCTUVO1}p z2l3yWoa3Ybdyrn@@ck}~W!X$C8dIw`IXcGGoAZF7azgOUjU7K8hCYpIAe~pk`Kp)9 zzv#HSPNdwk1UcGtzX5R-$$BB*=3L#}AN^RFjWcuROg=2_?%h`e4II}uRhu;;0!r(5 zFO#YBjlKhfMs;gT;GW-ba(+m(zXF|^H&_ipk6OL)EdweU87DEu_XrPex!UnsILL8s zUp4x;erkeXHb%*7H$+!xFZT^YZhSLJFPa&a_1rv_R-Cc+#cfS5b>Zs)1#`(0wdk|Q z#%~$Q*pFxHHR&(zKE|dqi8L?8&3}k~u=FTZIcxJTSOIfJ*j~u8i8Q_B{iJu_oweGl zqK~8NMKj8dIn~?P9No1xn4L1btQ&NQmMDxH%MPA6L7#mqwr#(O6MIJI%q8#VrT#T=e45LfBVM2QwE}k&M0-H&Y7`N$#0>kNxd5r^bYY`&-_tlPEKJOx6!qx-0dSHij zKr?L4mVbk6hMQeI$Q%YJ$-i>e2Lpp^>*`(>73shwnL5{ElKhu7M?gGu{Pi(uc!RONTDa1hE~yNJ(V>0&e-N9prsR=8O;TLPaU?MImfeJK4g_3uZ@Gfnb z3oM_AZn;A3_}iT5K|1?7_f=Ov3;^ZWgKq2>63ZKyAJ1MBxByzIZvn6Ab4A4~cA)Soh3{qK!nK^^tLu*Fdpzk_CXoxE z#=R~Y@n<*Ae`}FeHqsh1*#_ewH`ZuW&@_F1*xw$AU=t$_Ep2RI>;2NAMd<5U2wfn> zsnqYY=FcC<#ctoeeddo2vhEYNjbbJ9DE<9=z>MB{^ym=5I@-0)4ia>>`G+dn4ev2N8E4k9Z=ddW$?^Vsu`Y+`#(+;(vLb_D|X zUwikygtMbz^dzMKY}9QAJ^Zm}PfJsuKaBMTL>8{}X;F|M4lCo?4JByQPiYY&ZeH{IC9Uy>V6K%b`{By`wZ)%1c-@kxaa#^b zd`-|mj5$r6_SS(jXRcm{rPQ&qQX&2+EJxqCXr9=G#}(g1D%;C&&A-$vy+GqVR$-aG{%;RV&6qp8?EE zg~6{E=}o&MhcGcQu@HcN*zbh78$DTGW18A3C@- z63&hFnw=CCo4-+6pO-sx{MfMz&(7+=xHJGwRe50`ahtqEsiG5+ok?52@}TKz0|xBk z)%QTbC+p7S>^3Kk8}Qh=;N-=N!+~)(sI4VVk=3ro#~(U*@;+ejFE1}^-upIZXEhFp z97sPO7g#_r_Z_+H6fN~lmmC_nv%QD(5|S%c)A7R!mN19siI3frzZrrk ziGlv_N>=e2S>Xe)Qngd+HFnc>3~Ohy-!H+J&K6(AlI7?WE!w;fQ;_sY(;KyU>(&y4 zBuN_3Qk?(}R54DR4*A5U3uv}4Vg(Q&K=MKN?s{r!q5Oy8#xUO zr2pq=%iGH%P2OgP{GKtf@?QT~7v3~w%Vj3mE?}Q2d z%wgJ$GZd}%2L1%1WwVH+iq_*#9$>t!-mCW0zJ(3mH;o6i1{4W3q7(FJA-*A~g~O|@ zAu1+F(FVWK%}bY{o53UA>+PMIp58`*N&-jCKHZ?c8XCTcT#p!S#<+snU`!{xAz4G` z9?YzPu%16}ww96?hvRJL4;2{9A~|o1qXlMz=V#5H?fl|cTV<~E;>C-5j3zNEzYVhS z%%Df3(2hv{eZDpVk)v3Na=K-8By_lhPbAuV6!*1I`n0fj$M*A2W@hE-k_oU>re7OT zoqyN<;tqR;dAPr453K{RrMdTmSb9fkd3nT``VUY&YyO;wYe89RWhLV^lu@ z`|t6efbw!XfEB!;!6zwD_$;})sV`>^yxG&oeK{uece>A_j>oh= z^Y@z;vl!Yqjo;fIP_Y9E;x#MTvHBy`{u96DT=_q%q8AY)NGzw_f7{C0g7>%c*n7Yx zjXzlFbah>}Dx%2hD;a4N$gSG8J&X5<8naX9&NKMTXID1%f$U_pf1;0hF{7yP0o2lK z*LxcisvS;KbJjIJVD8kgP4?Z}wzz2YetOFdn8VJnFFlpUyo)?M5FWRi=6W#GJsE>% zGoh@{#c^ZDE|1Px*m)QA$O=t=_>p$h2&>sDHgCXJi^qMCXI(@blOmU zeo5?J5kKs-co%?>vq)N5J~t8B`vCTvoCNH2Cg20(DGE%yOu|isu&OS1{&ZK+? z+pU+UZvR5p%62rozJk7(^5D%&Kv2AULqdM&%AiMS$fAVwKND7RF3us+%$O-pDN(EI zw<3HTQ(yfXv0jvbFkja1bP^;}Rk)w#WM*33&d-mcL){J=*1pa|{s;>jMv$ix+J*H> z+rjM1<&+Pb-+b9x^JTN9|A>s%F)UvppI~XWarVKE0KZ?sS0OlgSue5Pkgdc~r~^h` z3(G=k2NvIAL)9T`JS=sfH2;%p8N~pf4TUN9fvV@}bI5P~z9l?_kUpM_+<*jF7`ajh zR#0*apabRyqI^d{c^BEWRBe1NR)o5=VIOw3e-${efB!!TppsC=T%Ry$(kZ|$G3?xf z6;tQieFbpCmIz{h`*xO{of?d>c5%VJ1?HW;K2d`5#-z_JIJb*a7WVP@qZuef z7P&#Zcv8Z_wVRlS#ao;0QwN1NoM@^aOX`h zABO(vFzZ>Vl$=O3AsY)*d zEzx@R!iDX@iNe@)9=NN9jmxW+LJJN!C#c@-Ew zrKuI;5t|9r8Zp8P0iENL2Z8!1+^xYPHowXcmdB)#Kh{h;y*kzu0`2DQ+dd~xUYaxs z|2QD!fW)bQ>G~V_Sl#8aZ`?&c} zco$;^XE8E{cnTu@MdMsOKU zxWx5_U70>@+OsI@HXPhR&F$msyEA9~1ARM7fDyg&%kI10SpchXY|OeYG^E;`EaXf# zAM(g(&a6s&z)pKw`}M0G-db?YF^#ny*@@FbGO5&dv91A>v57KusPS~odkgAMlCwQU z6GJZrBa~7rvGjEob(S-u!&eC|K`I?_&al19v0pzgut%4`eY*eA8kMnQj{$wa0Pzl` z9cg|vn%tkq_5B~k%davP2+cohw0yZTW!>9q=fsQ~c}lh3 zB1e&26FYiIkW5W2+0kIRe*JJ%18KsyIaxpR^x)ReK2`6s_T!ETE$Y@}w(sE619hi7 zu(DpBu zPZ;~`=;(X%+TJ^9(6&vR*Cb+Bj@_0_O-@@GYfACbmy@O3HUO#4^R`od{lnX5RPAb< z4{f(YGKc9Y5v#BGo6Max>jkset}h>T-et`62Sfh=-W~GuJLf(!{iLUKLhu--M`U;E z(nXhO$wnRsmq5ON3co?SkkF4$8ehY#a@$3Rnp&YT3yDUq-%Saqj?_gA@H{h^cLcZ! z?!6SDj*~L_x~RAL-1XSl&HZF7pK%t*M~N6LNSY}>;qHZfsCKD5od3Plu+h%J;pX-0 zJA`FLSFYZiY_R~_eOAYR6>y~WC&tkf5b6yszhCBB^Tn-Z;8-M~zo^v?oj7q9BK~bb z@&p!T>he+0j?JZc{fl+H^)K+{b0~@OOKf#@ZwDq={BP{N`CpIk_63|NNf8wh5lXY9 z&`hZ$mF8KK=FqG;LbIZHqj{d^q=^QNB&k%Iq@vP1Xp;1-+vjt>&pH3X^Ll=yi=F#rTy_0_5~!zmAUw z#R5D{p6&mud&Dgy(Umr)a8-kv<_5Im&ib8-fvlV+1hZb!!QJdUz? zS3V0eI#H30U5Evl2TC1cM{0d|lPN+g-tUEkmRvCS2>K?s%JJ%3pe6y}!h>Ad-+xF- z2?-l$j+Ti@0qwfxpL3Z(%o9ZoDkL8i@4)C3-yB?ngM*R9@F3`;B0?^*3}V4brL|N+ zS5TLA9j2!!c0|GZ1lM4ip{NCDY#h~KD`jUpWP@ZO-)%* z115keIj2D02$G$M-k5GP@#Qt+-6{i(qGkM<_2=9>$ml)t+QX&}NT4_sxJ9M1v-2sq zt<GgYzrdmb_CQ#(*hzF=mT7d${ z7H(SRX?|K7`{Pl^RAX7F44w&$rW7b`Tsdh1EP@{PjUa*`URv~(f>e}Vdt<@NfV8|D zNQj_!5Q&ZQG(nDeH5zF9RX|_}OVugj!7MAHI0t#~5jGPdisG)xw_pIaG;qB0hM|(U za1UH5Hc7r%FV|lnp2vK?ty)_$bP-PU}Q^`i)-i0tIoiG4SXzbfFP`tp$ z$?)ABJARy~1`B=GfUFu(!cMB2fA?I35a^5LN2384BU5x|IBlwvQNve5vssDz3Lgd= z91{?DLNv~x`gIrALF$!9#o~-kNRVPFdUeCo1eJMUrzl!2$AKx`US0J%9 z>|;lPk{0t9+s~Ssnx-#ts-@T9nNWSasjuIf&~g!f8f_Q46MbYg1j2ZJnM?bHA6_nO zAy!DzE`;;!$)*zQPrwR-TpJx76^}GOTI1D6d=)tQFCwlJgwxx%{_u%n3@5?!2|Z#P z%J&|^>LGoyLnVT5?#e1nLW^Hc&dq393DEBNF(5iHff?=R>@b!09)b*#Q5V`H!h1>2 zpUc7#0wrBgy#+zD#6UwVV4o3>B>7p zqoWl-gdp^;u)fDcMa1=X(Ny~|S)v^AXoDn-nmGk|*ZRw==h#e-K;@%kB|^@_wu&Hz zlN&*6;AlaZ0ip#-gk5Hg_%dddty2_?z9vGN8JL<Y{S@#t+MiVCR4APG(~P!SX-rmP_`Nhj>m(9i%nB$NomRl+}s zgpta!hvml=KbfJ)$tF-Cs8kH_3&BUJue~BfPB4WV9%db)d>9r+i@f<2TQ?3>9%zHm z$Vj4PRQm_>(<+0*08l_SU%!2;!Ond9?p?mHDS8PB(FLpoG+G7h82}sti-CbEDmnv> z4>JN_CUYLRzjqnhJ9Z2#1XNfN@CJxOz}0ET2gB0|Xura`1zhA+@;+00GnoK~gx4;LFjXNpu)A zViFdMcrh?9rfr)?Qp9u}+odVJ0|ySA1#g8yunMFb_Hz0VF*0!;(`O2BM;Y2={*-xT z0EOA3tqjX->*$ySCO-14?Z(@1odv*4J5Ri~$w_%j%k*%rb`&>&hjH0XataD{ot>T8 zn=5G6)wb|O@S1%%u;7FgKn%QaUB~(pwE!CU!%triA1T2^*fpBsTf3!2$}zz16!_I& zOVc5~zP_dD6X3q`gn7UaqNbU{t#n`UX~aq6lfo&YV&ElvAYBcfs}8_Cx67IUo;bpT zu=Qdq;m{`{UlPh0P6W0@!j4!l;z%>#_V*Kd79k5E8(wB@+jPd8oPZe6i_PG8UFlf! z08Rh=q%k?7^$;q6S3g_jETw;gW&6=zQ4!vB2DdR{)>;D=_yJM@oFm+{yAK?=43-mA z0vFUj4B7A}2AVf%YtY?CG)Gc-W)}7iN=Pn{7P2hCw4sY_7~Zi;yaC)(M^LLk`2^{Y z(~iJTsI?a^YzBjAj9Lhg3MB-#JAmBwEOj}sA0U8zeg z7^NI5!KR5|;orW0e+}&3M1MsLw!zTIhzuYNB1xrDUh2YkoHhl#D)a}(;z&D8cB6SM zJr_I`v4VIM{6-?`;*;kZFGeH{Ok2HXi z_#E0Ch}T3^u*Cd?Mj^u1f#2}4z)TSzw+$^O$4|k9Y!Asp9*oF@`sokPPi+N|EvtEl z++qg_*KuwRwgNM}Jm5Km0M;;n%q+Q$2n1wBpiFEf$izDV>#&koMUTXaA&8GnfU=(| zNhrq6!X3vnbnALxhpCZOc%f)6&L$8!Z;4>$>NFg*}2&CB_F3C(?Z!0YxN zqyVRFePAlSLbyo;CUx?^S^`vwR2R`?s-Y(^S5TrE0pd*J6jbQ~k z&a|};pxfTzU{7wm2HRjFlBCP9QXm2kX*ufj_5CR6VR_M>?5rU4F|Y+V_&9q=V>58p z5>gQu!1npXloXg$C@3ji6YnL1zE{uGtil2yhGRBC#`0ZaS4`gl%tDC-gi(UNT9GJgKZpwJxV=;1tkmWVn^8*s18tG zkBw!47YKdwT5hY>1t$WrFP*akGZ)$?JfxHeWP$rVxwnUMa&pS) z;jY~us6RB8mh-!;b&=bekCo))oWPd>2wQlC;>H=1l_qyRT`dKhfP;aQ1fzrcDcWg$ z=7EWc$mw-3w99cqWDYhqm6nBs$RMCo1BVi{s0CNtP)_J|rUgg=vvAG|4`FGr|A2mA zC?dwdJuxMSw19YCqZ&Vv>&s^drWh*YR}@%Y%LlL{;I3iuGR&aFU6th6@81!DLp^To zlu~j=?nToJD|p!fxCTs-3{f_wX9P{fXcFu(5ey!xq}u|W-cLV)yIKvPk$Y+BJAqlj zlXE&uTX2uq{j0>24Eiw|%wykJ#e_%6dwrJ$e?Dee^w{def=*K-iH2mu?wlxTP8 zD|-(CAI-f)Mu%U5s8zty{RT9`#wEZwf;&-HVP}KXAnc>Kls*_+1sqZe`~ZM_VW_*& zHCqhgpI}hU`3DCE3^n$g>4Y(cz+I?CJ}mV=?Xn&Q{)F2Jw$1af=?d98!F~cjcLA)$ zMMXt3WO5hQ3}WDi!j2n|im|QA`irjj?16X!s~KseFhey>0;ZSSk*{wcHpl?^pdJN- zC8HPhBs%&7q)|-3sswp})QL%6Ig3ptEbQ3&f#^#OUvQ})&StxY{w!?%8L|u*BJ&Nu zX6)Px93#sZdn~DdYz-1GB|S&#ssZbY-Z0+xVwSrwFtbW#H-U5JZ>xG=KhBdaZ4 zT{#z2XDEGyW>iKWdOs?j?S)lmFkU;p3*!zZkp=`Z>`XIs=sf1p6KXEbgvf7$X$C4BtMvXB`{Vx1W-KqN49;b= zgDV1*e`8sQs;NDlVdq!|lWNx{ySfWYq&eTnJpZt;FxR!E#qD?k{F19yQx{A;NA5)4 zOIp?Myv7HiF^lBWoOL)_IOW2&>U9fXaNWdIZ9o zWc0Umul%1s9blMyii@;YI>2+N$6BbdA2Xt*xDdq2z7KVDobb+yoGYiUATS_1sm0 z2qNTS)KaKDf;YN6STB9^`6=#wB@{bPbZFP7yUrh@(-aNIgf7gbe}Hjw;g2-alvx0R zHWR0dV*7T2wRNI32lzI^{~|;8QC4iYhIw&u@i$@iZ@7)BsE9;Vyr~TyOtDkGFa*p^ zK0D;_r?<0M+-?0!|M#N(T;d3(PUkaMzmq?hYc%3#pmHgvKx!1>P3UWBIjK0q`BXX~ zk2BBlgqhjMR#Q9k!fui0F-vxKcJB(BwLEho`mGqLd}N|;@1UeKLiCyFDGEW2j;dnq zW5pfBYFI8;{_s>(faw$=G%E0*UT=r{B!1HpEUtV+9TtxP!{EpW2&KBTuL1M{X{P$%02N`fqOnayZ7(^RoOqj;0i`&zOOkOmW460R)7&80MVa? zOs7A;s!$zRLl!txyfZK&LZ^IMp9kFmTS?zbpCTj?)-d8f=+8TR?ASeU{bDoATi4c@ zkDr?Vvxs7<6-cTaZG-)NWIBFt4ntc;$k>gM?SCTt(2v*X2S)ZeAetSl(Pdl%L}7s8 zNeOI}&{*7$Twl+@DICRSKVDj>oz-{tJ*aq|vySWc;JwQe7VEtGVW;3)|J^zjp(vjI z`R^l!IU9B!q7@Vp8ZOxb#_K7=GTTT=|JpR3wOUfcRCMBXu|C3?CiHadWi<_7QFCwb z;vzP>k&I-o*28h5S2NB8;SDV1zC&}w3(PiA%n=uJ%Zt2Pa$85R|0EhS73Jju?sgx) zISuG9z@F8cH;ZVta34A1jROROk&?lNe7Lv(vt>|lZ2$IKLc{_VWfi*nXc{17dT>`y zrk{T4y_~*!Dt3CUbxkpZXAimS>uAJvG2Saj{)iGU9(T~Jeyr+=85kLmOR!aS+OM0qE~=UI7i&?jb()M0g;9Eg-XQb*qhyO)PLGZbuuCJtOrn?5!&h+*j0| z!*G8-$2dYG{{1NQ@{2;*KH)dv=mXG$zw30bNa(VD=`Oc%gegMj$9WMgz&fz-vyYY< zcYA$-qyY71%S#PS81R7dpUj5QR15)!gO|UDr$)r3b!^8wXBCPsHur! z6%8#Qgc}Jpyd}PN)2WxW;sg%j;+l{>Bl&yFRCD(4jJ}vPj+%--K+m)8%e;``RnO2b zf{B5cfP@L;RE-!0K){v*#ch=&A8sFhm<|6Y2|#&g_F& z+as_fr)nAMks3PPKJe4Rl|vvrJTfeOBR1gKN+I@gRu_D zoq!dDt`3l&kIQmEzXvF!3_(|;Iw(X3Q}gjYUFLf<>wMS~8OlkNV4VL^Tge|lDg;a| zz$8!LGXLP7%2%GlLAi4 zQ)rM5?y_bT6Jt8pM@w|kLUqGycflnAenCNxZJ*Of_<1FwuKP0OIrYU0_3GgLy;sTX zb`RPu+0ntT%_MVYa|5*a=;-FX9g>-VoE$r-y)h z6Tt&{*<0PiFRx#UZOz}J$09?)d|}|Qg*Sc_fBb*{6@TRs8J^+){y*`**i?_5gHh&x z{*aP>+rw@D^OF*O5>gwl{m(zTNAv&xy8myiT`eNkx&PY~>sPmJ<8@3AzVw7HGODU} zOJo$iu5M*5%g9Mzchf^Jv_Jls`}1w7SUPO}=-+KqqyOJKW4XGu_3*LH;rw}qrzM?U zk{9fIZ`#oC(PoL~v$ac%S)q6B#yx>P6V_WY)a;v$*H>i~IzFa8deCt3`*g+GzguoL zhGhfa|82hCh87lAGM`E08I@$beq66RnbfB<9-CA6B*Vos(Ot`q@`(q_{Rd)6(FU+f6=>7dEx~sbn)Ba~? z*BHym-#=;W5GjhO+nGX{v`GHx)E=N8ndvDy?$5CI`;{Cn=8Bwl?Dx6MepCT zkGxcmP>DauuUgf7!tBtgf1do$rT_V*Z9ih2uHWZS%RGDbcFJ*RVhNoRs&p3>eeZ3) zc=6-!^_|C9hbN>+(K|*yR6RPXjd2O)-JdS0s&2UY@bAfFQ>8q1?j=llgmV-n8Sb=V zLb9pt>qApa9h^9rge8C)0k;y7BhGo7d*jDuQwT>NVmf3iqD=sdC6tJ5_yOb%qNU@@ zmoK2%$u%@O{|SsoLf{d;gWo7Np_VqCzyD;!awBbg-&p~1S z17ev8s%gKMj?+r~E|Q1XjKPKvLqjFtJK87e%8z~rFq|0H_YVGP00KTl^lG@R@o_}Z zyNvLNn_ea0KSy0=hGr_la0P}i7b8s}MOI@02uj`=)%!A<3XpKOv{2!d4DO5o^NW%c z_guw*&y@Z=D>nP9)yrZ)(B?3nFhD71cE$TxS=T z7BFYf)GI;3tl(d-phwCDH#n}qB+)Xypji5LP`}0+C1hlN0B(Z&>B@MTF)`7cLFDtB zC}Er7AfG}j$4K!U7H;aFuJG{E{a&;8w$SEIOtETs=bf1uX&-)h|9exvz_yvGvONx^ zk^O?glIJSJ$}O2|`kO#0gE<`<7^or~k7Z8WaA^^m6qHgzXTu~hd5E8cnQhElHJqG*jCxag_5y~0aS@?tZ z?|%moWHOp4I#HmK0q-7;I8N*Y9w{Y4O+b-A_7${)!`P>74cj6y5{mG^m61J%VqlaP z%NEd`LPRA+U`Apj%PU+!hBAX_G1JUDLIz|q=Hx2YU`2rP=iE6VAd&(F|rDh3aw- zZ61AcFRz1+Tc?6keBn1XNj*4M)uUhf^|8ZlkMsL z#7>cfatQzJWn5C#4cgiE>#@4J<GD(4jX9dB+VfZjlPk|3rn7(#6!J0R>71nfUDZS`VV!^W|RJrj~6s03zSgB0|KR zTkHXE&xiZqZwiXMzq0?#8Z!k0Z>y9MStu zJR4B!W3vU$*9En(N3;m;s-F{Gv{Fh8V(!bdr5k4z zhX>;yhNssyD>8F#=ehcx-9NQ+WJ1K7hk zwVYYfNL8tah;sVUV>qA-&k9Lshm&h`Muur}*^HAwwjC<}b(vzepP&tWsP?^q?bo6; zaU0qzwr<^unyVh#){nljGYI8F;G1BCdoxvn-Gn;FsGtjBry0+Nby>d#{2dq^JdD}^ zfsC-M@7leaxMtfNu3aJ=qw@%93*S53ta(q?qF0we_$x;S97Df~+W)uKIL67jy@5UL zGddoK5f7+bmO?{h?MF zx<6{OBOgOGB7@5W`WrFmSSdx}AVT=WMkC^siAyOf??%C3j08!Bj?EVIj}Uj#g2!os zbcg0$0|*VfHv{&}h7h-#lqm<4+{wmXgF(I-nKccW7e^HTB7}vF0=GEjJ7oo@vca=r zo~G7V7bmHmu2E#WknYn}a1f#AO?!sTLOQAJmca5a4h+3i%}lkKXVooD9B5^so}JyF z*%9f{dgwMK1~mFMPI=zgSBuwx z#BsmNS~{bBaBPgjgD9Tr)eoO?#oKFMvV9;eiT4v*`(q&nR?huU=MM*hm_&2e zS`+tf`~{OD0K~k9ZbmyXN{K@?b>>Xb#orpE3+p{@TpH?o&I+>YmS-}v%SujmpH5d- zyC~Plp5r`BbwDK5u!}EhKUaoMr*zLtL2(`)!PU^$E6JP4H*Ma+UR=uYm?w*dfnwJ# z%Gi%dfe(U$jywIp_SBkUGG1yk=O=W7iHYC%FuV>g|HM~lW&Nkd8hpe~d5l#;In)Qc zq%+&%bD>Xc-Qo;m{c%zLezRB`W=YJn%BlDE+I<)rCRfYg z7Y&*jT97{R;o$O5m90Atb)XZ~-r6YM=Qi2>3=Mnrzj+V)$xQaY(0E9q zkrXQ2T!VtD)};Nv*H*+Ar-aML#yo#7k4H8)MQ`57e2jVGbqa;wZ3^#HRZ6K`O|$D+ zFZ#93G77tYwWqi1A9Pfgx~_KN!WE@`0TZvQ8(6o=9$q!=YZj~!4>rm==y_crb$Vpz zkxWC=!I)K-nd0Ly^H(1~)d@bN@xsb%*26Eb;DF%9Y9Fn-2e_}3ts_T6_m&V zN`*+9Ck6@9`xJzmY+9s9CXM`;&a2T!db(0%iIzH{|0`9qT(>R3*Q8%e>cTx1mfA}! z|J2UQA^%-)#K?s(k={s1xxZR1De2l$D#5Jroqmt$+jq*Zep%jDh&p^?C*P?!eeuSR zabk}iP1!Ci*i0}?e93ZNP;2^HMM~!YHk|9w3IBHO7C z>$}W+wI>ezEmZt&lK=Nx?dKzJZR5sBqVAXXyR~cYY?>Oc*;ae#&)1U%w@tpD(-1gq z8f5tWlDu;<^C{ZUP%iMEe3F^^;tb+nl$AC#k}SS>=@)p3)6ti#e(IFuP4)9zKC4N7 zy<2l|h*{*7l;Zur`*oT8;eSyEf3lYPam8fT=L&r#H4~+Gg{qh3?#4+{ySM}h+PhR{RwL+h2Z2=3K7Le;g)RNj;HDd2MwC`H?52?3OVMB{3({Xksbd^ zH_xSD`+JsSl_c(f9S6BUEYJA=b5i;#{=0^%P*X{GCe*Ix%ffPA^)U-8`F=({GESP? zxVTv+4rwbjNa0_lvx5Bb?fW-eZ;; zD{4C9e-2Vvq{0Yfa z3tKTe>iejYylZJv;$}+9!)H2=3hnnke|F?RVS<)z${Q;FnwflWd~s^Uo{q z4*Tbo*NEE=Jz&DSt$aGOH>~hR!YoP0-N@+AYV!#K5*O{;B*vX9ChT_h%qJ9$ zvseV^anNe&bwb19QZMe>L%wNiY0UAL>q#Zey_f+W5R&5QxLJ=Bj@SZ_Z!dqw4iPxXR1+6k;&lyrZe#)7i(dVB3 z@;Wyr>wggMSBv@nP4m~%)349|*>Z#bl902v7N<2{%>^XKOYEZ1WQ@1?GsV#rp z;wCn!)xf~VtO%1XzS>;FY!f4=m+@)a`1lN3kHu8ojk~Txai8k>bJF>{TvnYN(jhN@ zPF?@e)zUt?37M8%yekV;uPg#~X zm5uXmo8lS$cR^SF=J?r3W-kSxHGFu~j17`%xd$~hb$~(?Rkg3z?!#^SAOHHTHQq6& zWJ48{ckLS6rAxX_?zVZ`6N$nxCI5{?!&{{TLf;-eO-aq}K+YN*)TMXy-9fs$RX`=> z*F=BLbMbz&p3_b9%~m3cwllFwD#!QoZoeO!t#HyYJwkkOK4$CLNq))e+y{gbpYc|q zPD+le67{m=4@R#HMf>im;dy5G`jAkLRR zEiI;ZWQe*Xm)9@QesXW2)A`&wX{qa3Rw)!b=N9w4H;#6thm-szK<_O_5`(L>|8s1>O>qAL7k%zwN9 zH(ie%)5JX&#_t&#AG0SXDL(jTH-(4(8^HSggYKnsY|*r|>Z{Ygmbl%Vp6=X@>|}%{ zD(`8X$KKBvW<-ko_fnOfdp^RBBa)W(F#1Nrdxs?}>ldnO7DmQ>^D;6;KZQ{XGXE)* z4dapt(WcxkAnBv|#ktxffd35Vn>SpJjsa7B+%7KJly0*|P4~8;*`L~L`EGqnLcl;Z z_4d7|3oOEny7-y|M;MMA?GxHZ#i6WBb>_=xf%zlTYI6C*WR8y6g|;fRIBEMtKH~vg z);)0F>h1&ou#)=3-}sWbT(y%*UOpg~_oBj$9|ag{fW<5S@Sg*I zW^l-G*`~22f!CwduurHdQ%g*{I_A%}N2FnI&4WV4S{!<%nysz6<0&Bm0#z*uHp{t3 zgmr9xroPecG#wku@Yr!sIa4Qv;pCgS;fQd5TIxrSxPST(0jrt)G`x|8*8SPC3V1rM zrlx>lQw^op*CU1-cGZ5Z^3f`wk_l!5?3o`;V4j;F_%*)ia>Ove0iq<1Ok=JgDe{2x z%=w+hbZ$$o*RB;8o)+rfGN7!&%(BI4;>z!p<_$u(PV2fP^}jL0l%w*f`~rlKB33~B z&Zz&qBx&cf7o3i=qT`W+{|TBD+KHCRDY`N)8>Q1ZzOl#2XdW%e=5A@!kL21awde-%hA@K z%k}05eD^1DnV1CBNt@qrYX3}4Jrk&ZPxIC1gxrr=6~=W8u0PHHzOnutRfk1Z66Nj{ zj~>DHYFz`cUpW460#iQ2jE;kmqfFTxUm#CpA(0eIWdVwPQ_>DemETsJGSp7SM{G-GOndz;pH zcHoXf>ReYdOTKQbe&ymLzV_C*k}PIsh9o9|V!QcYls|a1=*w81=j-H>u0qL)cDY@Q zR{MlIt|)J`umBGvpsfSMLv_${-O!-1&?g_TrtU$&QvXtFYVPI8QEfigXv2Q75Uhhj z@Ze(4CWawx`952jQBJRZ;^kJT=u!plajB`PEbR0FFu)rupWbLT*~18|xiBseCCr%V zcqgkiQ1pXv^T=?-Cc3?xu+i7lRvo;xeC$}|cn;@OS@Y4;dpJ1b?9Fhh!lOmG%Xb3e zy%M=7n>W#y!N6DZ@zZ91e^^cAV(9U`OnXY&3Vo(~yX+g$faVk zmX)>W8lsc%JMkZ2ap*@!6QAj2zjTh;?I)b64&69wE1{yY36;C+Pu^p!`*G#;x9{v% zJ+)LcQ&ThSukX_-%m?oFK7Zy+lH}ICG!f$BHCqpv$H#MFvwTvOvgSG-v+lj!J@dZ7 zmBOFwL}>UEw>XJbvY6>mnM;>?-Ff?cuQaG>)z@kNS~!Jud2^r1-=D{s^mud8m;FZ= zR7HO0$~YJ697j_guJ3sJLH+mFtzs4H9=Fetk?%ZxKzzrY+ec_@s&e!B&WukaJrzNX zgsYRNpeQX9FK2DZZCUL1&lItfC#RgO21q(0KGdgxKI@;I^jZ3%((9IUY-JmBdGvq6 z)uRtl+*@}PQ;RK}$xBb?kkZ;0bm(SR?s*lB5!>b5GD*{9L^C@VMFbUNVu*ns_kPg|#pnYOxw>ViZQy5QZRyTW16_`GdW?%kr z%bmotpjo6a;6mAdD~moXj9a^Uq6=n7Is$Fp5C~#4OM3kjNMx^?YUR5p;k3sM##Cee zto2RG%R^xZXOZKdoh9AhE_$Q5ie(Rp^yWhpufe%SrZOUr{|6RaOi>_pUTs4>yVb5ctJ^Hgs-b0pR0c@ThU$Q7z=KY)7`UHU+Q%K&L$6q$SbO9Re&hU%DS~( z!%YFbx^lAqgAKdRq#$o8UENV&TG;FMmzaxE&*HMR%}y`1(vVaL-fsQm@ww|+$vS5w zEz$;i?LFM}Tap3|>vtee?i7h-=f3aDWY;aKcz7vOBYOe2yw)N3fB|;;*RE<{}^+m{c z@E;J2@2b!@4vN37(^z>2tYYo&6)`EPfT4Q5EsH=NW-$w+pWa?kPu@^;HJIu8w(SL| zJVlqBm&=pVw$07cD=B418GF1QUbd|b7hsy~@g42!$@QvWWq-@(ReqxCB-Uo9*7nsU zPO;^4afO4!5t7Gy*qOw45Nv^mMq5e2_fR=^z~^!G+N!&}PMKC^s|km;_=ViU+@_Uq zgOA6BN=^E)-`xMBsa7s@iLbj$Iu^#?x+&-IqG!g+(z{z5hCWi1F#W&)uj>nD?xrSM zVb5MQ@7mh)*AnAOyPLSSZ?`|ygj#E;o-rVx_ctU2IlZXW=tyh-kfP=CBiz*G^9Qk4 zHvWALgP&Bi({TnKJ=!qdSw^Z#O3K!=k*AKd^#S{#ak8VV=zHHSfjFAq!)KWJPGLA- z>?_@q*Tb7XLJ7HV*@T|usCE_K{*#mw=J&(PbjaZl5a6h=@<4im86 zT+%VZ@+cz0c>O7mu}n9ayCzv59P=C3=G02=bon`9Q8Fb2HwbXY%uF>?Ufz^YYC0u2 z5wJPT0F3}hCyl8Pna|(-<|>VRdiY{L8UIN1c!A{;RyyUx4cKVWrELHrt4lNHj%*V)ojzj3zA5dh#&#<*|kQ>p~$cuIh~){&x68}3gicZ zP|?kFo)Qds8%C{hb)PibW)qWK^IgCg%e5!mfvrF!ntnViIr1Uk>D9T5mmLZk-Su}- zYGM7hG!fDF?APHTNXo5d7XXj0BFNJ$PTZ*t+@$N_=odt_By1e}>cF2RuT9s?IHxKq zp1;4m^emrmxh+P-XXlwupNfxF4VyOZ^!$pakiD4un8aaedH954%cpA==2wCauKwuy zAVFc9{;!8+^T*@|CQbXLqP!> zTb9g7#CWb5EZx9V12Qm1K(LRFQWuypa&XXLohm#@DbcMcWR4s)tf7$e5T)8@)bOsA z>d;it&$NHi)Qvu_C}ABYPtCU1Wh~h>bbI~5NHrA#{L7?K| zX|a%wEN-053G1e8Jxnf(cOKjpV$nurVsb-ovc1t}CN@5mBKV+v^Ua`)H%uqr&@gUK ziJ6-3=_fCqF25odvm3juJ9keFoxa|>`7UMB;gc=A*Zi#HM691xEzviUT!Ic*q-Hyfn}U(6+8A@@ z%ST;XDZj^bXL1U3&cyg0T1?Hj`^&YKGpD%3gj3!8^mXrH)4d0*dOAdx{;ci4^7~gO zQ8xKCg9Phmn3_6N#bbXDUM2OCd-2uE8E9~IPmV0 z^EfwlML=JfK!Mq+!<6;gcdcG+rzsKh?%YO=RvmbPBflVNE0|C}6%|(@7%U>FNlzBu zy5f$H`1E(J1t~fscqOv3xuy?>>%|wBhYm%!%*%(!FwM@0d@dD;{Pc+xEYMCdhS@RmdM+{gx~pFQrLKQrUnv|nE7knn4Y1`_A?226@xuT5VJVlRbL$PR_-k z^Rq0XN4(8rM_>P3s#ahU zh%EN>@<#Ap1D{Vy=|+B^trsm{)w7V{xhW;#1rcid^_eZF|^ z5|}19HKuN10)WfJ$tEo`EzeaQjmZo;6#OXE(5s4ib{jdhas4llo>SwyH}yFxD+I@@ zablN9N!=gJZv?e|CFlTq0qH)@?!O|ySB^SME4{-Lqe``T##fXEc&18k6%il}^P}jE z>y{_FlQ49KChnotiMiGOj4=9ZL-l2M+Gl5H<{HBf{rPBCP2NeGy}x(k=8dEY>!)wE zv?=>a&l@sdj%v+oV0|haX>WvqJq!%6F;>ouG+S% z`J5x;DSQ7gnrU#rR{%i$EAEhud%1@Q^162Z&8TWL%hXXZ*pK|`^;kOIL$9TEjXe$j1sO+RYF%0ouT0jt|tEFdht?zuTzAgU4Df4OWTCO=Vl^g zOzylFmZqj=3kv~3he2iCCD%$%=MrC$^}E&I&ZV=*VEA&(>eM_@^Q7$jy^zC1P5tnh zIm$IYn^;AqM;ZK#C(#?!0RlvUer_c3FEg=_o{p^0DV>-}1t#-2t8`e*P9>!q(w9~j zb8QonZ{3t!n!?8omW+s~XDMTKmdEuy-c-ls?YioG-o8m-gLE)IKR?^>2Z2njp{of1 zu6FqueDfYyrI*(S7CJ>2Cm`-yJUhE9?bzSlxR19Iom1fh)r5HS*sh&SQGD`IKg&qukp21^Q?*aYvBxM(P!cGs zP;cE?+SH92JobFR6HbA>S4Z2*ib4ru)m>qJgfZIrO+qXg0EYOlN6o29q`&#LSGPV( zhkmGTAFI6Gsb?Pjg{Hd2ACC&Oqa+mDv{ifK2Inz$1W#&}6dxjMB_3-`R|_vbJKED( zs2=p-{+MNIro+M0LAGyq6c+M2q^gE)V^%m=nzZw;i!eT^4_6iB{+=*n2BqpSNeRNC zR0!42x9?!oxK|h1v73L7%52!b-(dRcGr_jwr`mQ?m5xx7#~I6@((yr5q^Gy3rN2@B z4wVBIaa1WaQx))7?a2|rE!5Oi$wjvU!&XGeFb#L2(f zclC1kw_%ILQNxnaBQYMUbQ-z?1NRr@2Z4N~p{N|F4rsXeG!r^p z_CZ^VwD{P{C;QB)K>{Q46f`etm36SdWK@1oB92BtKtNSpefO`_>GZfl;V2*8soP_cgndCoUuZNqAyWrnXR@{7F5^t&El0|GHUAV08Xy=YMRGcOG~anek-&RfPw^* z1|~9?CSN`Y`3aFw*EvpcY0Afkym)PqERLqv%gb-ecB%qXf*X>RFT~t>zn~ZQe0AQv z%fH>G7}s&Z)!W(Sf^bOM4tJ6X+Z8*ez? zK@vTLcUV;ZIC(Sr;fG;(`R>-g`X%LtqJqNk%bptv=;UFu5aI;Nq8oN$!c2?-nEDZz zB43H3KLR%Khmny%BeGAL&q#rDgk-6zUOIv6!NKBPQ730-2k*5ebX#M*r;iXeWxC^!qec1_x{PeqG`jh1YA`i&xMoL)` zSlzguPE9SKDT2N#7Rp^=OLvLNNtb-XT1xrDU%O8&PL6l90+=c((a;*F<@iPk_k~j; ze;ZC}%d>q8y_o5kRSxEnYX3LSF9k9uulc~7n48tKcTx8?E zUp6)OIZtxFQQv2@vw8Qf4NH9^ctU2@x;bC*&1aW%H3n7(e8W@O7=$~Z(wxb$d$YMZ zSw0*gfc=E8SqwF=wPtFPVjztKnZELEE{t=-=rgo!i#e7}uj;zb)}jNH58df7v(7)? zo{#AvXv^Gq?#7L&r?$?28AAbddJzVpO*=(q(t0>KIF`Sk@WNCjAvAaq1IS`rtW{KK z87o8fSxlpF=JyP1&2^?evG@Dg!dGcWo}NEL^oZL^Gvko z`dm}Ybj*9xLxQbl(^r?*rZ+vt1n|OqY(+u$&(w81>`D%!2HWoICVN1n%xfvUA>u$W zHpZVIQzmE@s(1_qGUoBY8gky*c{$}qb91v92Gu zd9xWp*K7lzD}c)nxVu%)@o5L8G33(Rn=#2RJGK;q1P!2Uf-}HrlB-!{XkZmyn}N5- zH!*CAqXCNo`Sy`atQu$06m*>srfkPNuZlj!h}Loxb$>wYw2UUjC(OF6`i-5R)Ux|pyAq^vb*^%aXU04{V)P9*3ehD0rhj3jWb$PX z;bz;Anw~z0aZES;CFx^SJjHbFAbD7XTiVfy4y13ly_hD-NEhQbdRQ=AAPSPi=T~&*$4<#b3=#LpH=)>$U#%wca-3{ zWYu6<=j>{CdX0uXN%9Z0@05z(3K`yeqm)UKT&ADDZKo=jmH60mc_xANLHm?tS?`%^ z>08{+#E1~G7ynFx&&5Q)=FJVnXj{x7sCZXR)aqhIA)TqX#F=Qi&%>xFB0!|A_Ij>P z_PUN|k^TO&RI&apMCo_`wQJ{M#Ne(D94TR1@%W_)u=VNFIn)#Bm)eSQP)=3f-arzt z;$Qn!!q9#OLq6>eV-t93er)aJZdZ!o9~L3#Li( zSd4PR)#;D0{XALEoi?Z>Bd21xebNU#Rd|wUK3G5i+{M6Zg8T_PzKZg?9y&vowib$X zF5T3Ug$|lKWDvmWzdv0~Og!gOvOQ9C;c@+^G%@>OhS0EqzFU3Pc|3Yt=tHS=>}zP& z_|#cl>d4fg9iI@Va=h^&vrps!DWmx9FV$3wH>2f}Bql83ceCIG%eju;-peK?-``Ht z)6-)h9x=8SH*{V+e|`hTBN_hry`o>&NO<`4g^Z~j9Ua$sX;0En&`@m7?RXcNpR*y! zV9`3}dJoPR3ADLPaOGHgxDWZ$EisQbcW`_VYBXDQ0%xfMajxu^)$ZM2eZ{Giw9=e^ zS%mnI*Y=i(K>;&wt5eq4D(Q>%I5pU{ntv@Y+1h^m_|-HrOD|(a1j@tI8$P~PyB|pq z)B|Y-87r4O#>U4_)?LxpSL9_l#>EvhH)n@7Id*PtmJ=sJFjxvf{ZLU_e#g7t=C;Zf zX&J9xs<-4NoVS8iO3MObtYJ0Pj~^tkH_J1UwSd5HB;@6(QAjcfyrbDeUQz-Cu(Upw zT_z&rFhMpp~%^Phdp6R3_QJ@=J4T>%>>DB8TNq zEp+|I3ovZ@?%g{!PR^s4GPn-;ycCWYjdV4U= zccZErJ4(L#CB4vUyl4c(ai2#I$&d;C{cY7uSy*O96Pg^x$wBB228NHCH$FGhUYt^! z=uJ~}>La7r=_?!NZfO~tdj)z%#2G7am?Ep0^&l2K*QgZ5euQpDyJoW^^M%G`<&D>f zp){C?_8q3@-!s1A*I?{@HTRB_=wI>n-iYq|5?m{}53MCnXXl7K@5Lo99wWZK(){iF z_gP}TOhiQEt%_B>8ztZOz}1f{(O6HPCZSES@Mm1W`W3cs-Ubn82$#+KyrFtHIyIz* zU0|yaf9L(_fN=7RNFxkrC`u65+?cFjbYPBlsT-PW+;rhW@d(q|kG#e{%|jt>Y)Nb! zb`kFM^fY^tN5Ax`#n;wUf++tGWjJ`D)9&QVla628naeF;@2*$$oTEh>HXwNfF>Su$ zS9?w|zJi6d^)WuazcV{AEQBPcIx7GsjP*=s*4>4L8&Q^h-O8Gy-g;o^A9Q@qBaNEN zO@AR3eX*N2gS&=cvmn0^WPyz&!^xAFJ*T^!CyU<1Bs<@&eh0<&0(0ug9-Z_IJ$hJZ zpdMJqQ_fz`_gr)RATocM3?Ep9yQSV@l5q{ahVFTF^*!j4`i=r45#1@=?ujWcQB4j8 zdJvw!%RwM6e4e1w7E}} z)Ej>hkwo}6i=L$*H~i&Lt)@|O=My-*Ozotu7qX{d37t2Exde_?(55$>v@pVn*XUkS zDg`9kr7w&`csXhO%}9x2wif+jA?V-n7+!=Uyr{Cp@22-ou`6szP?*%b3$4t$@~YJs zZ}g6GP~m1baNlZAMX~)i?Yzgv<8$jvORs~9-zyQR`e2)He%k{?=Pvqb=(k(*JQHxtXHu<3}f1Uf)Vz`xz*B2L` z4V&Cw-cZBGGMuVI;W-?1iV8J!p;e!CJ}fN`895rrDx)VxPB$Vnnf2D4{RglA`1Cd(3}}3yJ7S@AFGWfeE1}KNqy!t#?BSk+fAqzTN$n#{ z!pV3Sp%L3-aa0SpXJ@DY6GPB}Q3duXQdfZo3{2fiHMDqShOu#alq!!N849jiSLb-r zf1NA>Uk7(h&x@w!TlODmJN&!5-q_*2tOToS3Ky z>z)A>95xM2_q{iQf|UyZCj@pZLe6RUIq4i(em*FjT18JI3i5%k=W93ZbT*$1rBYGh z7Io9+;1C%ce=pQ8Sb_sfb9@W6BczLXWmCyfzi%)FEQ=N(VbwOlx#hV|7 z?!GARXk}`gaD=7SZuFs*@3U~qo3E4DIqypP@^_S4{y5X`P+dDVe9j{T- z*cTdh-s*D+t$HTKaWN)P^3>E*g_6wR7J5By-Ok9lVcA7Xq;nPV75@QbIG-H?*qddi zUDg~!5Zp4V;l0&*J{T;#5du=lcM?sr_;mU^3_b{pzJc_ptUQ?ggvq&*ko^zda;Bp@ z$CkL<5<&%2?hAhO*ACAZcD|d1WmNSstkm#Xw8yUl|(zIpovaU_l zajjse`vWa9kb+44zga6`VFTL_ePm8JL`xlP)wXWm zv;6z}38vSs`z)>K-4@xTgKlqSq8Q35;zCk@+Yet!Rin(QT21ZaX9~!1!3Xcs9*6mi zr;-%e`;YGE`NF4>XWnI23d6cc@H;~lJ96~@;pw~MvHah++bMe!5oKm%g)$2(Xdr!WR#Go>`}G~Ss^k~MmDKrll2_;=ll9Se;4=dy58eFk9G2ckci=6(bD={ zoaM-7Zjz&{d|P%~tN6z27y5!~u7%0fCMG!s1@E}{+hQIQVbn6C5TqLS(!q0~d+*i( zd9AkVnw?8C*~CP_&D>k2p0fIk0~sNiz=yrdeLvz>G=gAar~5{qcU)Xq32Ej)LUOF7 zin7b_*ccnzdp}R}Kc0sUQP2im^&`mdCakR?o9S<3p8aw#m~_$mw^+i2GYQJbKZ8kC zQrOQ?@skG(Jb&5sR~vWcr#ddjMeR~cI1SPfYH{ErOyWNE^<^vU$1jwf)`Gkg4F*^Z z3QhE;5H$q`m9O02+Ng}sCtNi;S8|g%Uc@C!#wSb}d5E2sw|T)KJ*aI=OiLTDo@|nN z?ndb(SUJ`A`2oMbyrLyxwkzBIw=2PPaxubu4f?1<_S2n)mx+9$VZjtZlLCC=W)O^2w$MZk+>IYLI z-n^P`SwQ#kcI0_@_YCVpApo5dgn19n4eJx+Mo?fv;KFCPr_W@Jn&d;GZLk$d)ux+B zEEf|y`;V_eUQ1e$;=|o*G9^y4MeJ&7rn>|<8oD4vc(=QueCnUn#+}6N96>>Z z#wR=>6|8;^#+$&cTr7cJB=n))(x2axp+P|yR`vsG4fq>cT1X;gj>vKEqc>;1gm=xp z2U#=TBl{yW)do%4*BAZH+;Hm$lz593kJ0ngg$YriU1v1xjYe ze1ti(fQD;np+T*wm){Ej6B0d;h6KIRXiQU5UGq)-b6KBYTbc8W zbiC%_XmRy9j5n#c*6Kf2cw3j2=5_rm?HiCvf)T*!dqsWpVh8zr`&pJqDXL=v?UwhA zZOsErMJ(B zr=i?XN)T{X z|5|Na=#*@;>MXuor=|USRx;*xs-$(e$NgEU7kjF?2=B){QLNSFyAw+YnLR*5 zJZoWLlaq?MgMIB!k`hJy4inRANR4y?Y;ER}z7TnO;D&x^i)sV<4jTGOUZLAt8?^Z~ zuYi+56EJ~Fja-`Mnd#ZpBOlKldnVzst7cU?Rrj@2g{L?G*%Dexd7@5XnM>Dn4(sLV zNbUIU%H)Ik<%%ZYSPj=goB2_jyei>y)|sOfv+@J(8n^$tpn_Mw`uw}s69BwjYNXKo zVZy=`SlLQG#lw*sq3@PX{yWhfld*%eKne5d9U2=2__ z-+RCS&+YOH27&^swpL9U`po>h` ze{P+>N1P*e+JEzU(2kZZcZYlbI%@~l>pW2Me3X=3R8X=hv_g-SmD&p?T5`+dJWdr} z)i2%Sy)Q$FlvUjh9h<8f)6yE@O)D;<;o(`yFxwCq^P9Y=zjdSEdUxDi03dy)Q?ZYU z5)*@g(M)&NMLj0!?9|jwZ|?An94=`leM1%`qau$N#a83c-(TQU3iVK{M!*pqyilAV z*iS)$0Z(Mn;^*whOxAf5Hcf^9z zkw&}@Z?0)U*>+iDe|G*sM}kL2TYKOilE{JCLlNJ4cYm<>unx=vW zKx>Ynn-dSX`h;Gnr#lA9Er5=OK422Fun>@Vb3K(^k};V4Z55PKn_hhm^B;&wjp`=b zV1KlP6s*7^cq+9IrV0qD19Ws>^p|P5kM1M*x4;mj_`R|Ce!2m@|E6ynuJFeU;`$4p z*_LAmwtB3rlfOnCgO z8#-EYiZm1^7b*L11y;)|AKOhu#I{&dJGHsJMkKTCkUF(mX{7dg>V|1`UJ|ExdF@g~ zWa^?f`G*h3j@P;UdYta4U-$BIOhspU(8e`S31(RtXSvBWrail7tim1ym57Fh36)$I zq`zmhxO3D>ON;GQ6pCyJdyXrKVmAN{Q;WAl7n!9*?l~>VOcpXWN^$sol30@Y&KU)3 zj!&s`_{A1IywMr@dSJ$qe3qXZR5+Wu-hCp)vv&YwX_t2P<%1U@$@cyr4Jca>NU zLDiQMU|Jb`Svx)SVLWly@9zz|dbKt6?pveuZUQSaR)%GtyPnO^&Snf-j`Eu_BSKa%2Zk}KNlQ>DU1Ps^?Nnz0xxkTI#6fpJe&FOsp zLf-6YdQlhEVF2pkvw5+S(88vbrrBQ(8@qw$z)Jk~nEU3jGz!p?hY$Z4kZdUK;7t-; zcb251-Cyd^{QhywLY=Coe?J%>sXEG_4f!EQ8LMz1yg)>t-L20wSVN}M#IMx#$yLHz-Dx5g416qk zS;VJA;-2_*z52%U29GD|54lF?n&%hNeY`(!SY;6VnEM05jrqkK44^s()jgROB7cIb z_2`d*auyVMv2pvhHa2{hq7{&hSom=@t&HK)ldiy!2xWPm8R@g`AG-?DtRek-c^SuV zwyv7Y;%v8Tx(_~nY=rLWLskX4tMGk7(egY?&7(U}BwWOHd^R;8uc`G54UMvSqIUSS zo$J$v2E$jnv1%W_8mt>#yuaxSmFyMG;3PoFCMlO&&i=O@W8ygze6+NnOc|ZlY92Zm zrXuBM)R_@t(aRTkpQJ7$GPtSv4wPv@LFq98qhZJ9s;4YSKBeXpoJFx2xcyz%CuFp= z0QV`Gq?C2Ew2Uvew(tQ{Lz(EeaU`dKzY(8PH!qk`Kw%bON=?bOXngNLJQU@Ul2mtk z3Ntu(4&_w})Hkx;3JfwlK)PV~=3;CzF~L{qFIhj{%+eUyDxVAY9vx!z8wkecSgw)x z2mOwmj%(WLGuH=uNJM;ZV~$)?kCTV9_d}I8%Z*v1Z>1tRh8Z(oDdAQsv9rJh5S9Ge z>+kzr@LVE&fQA-P!kRj$?C3Y_&tRzq8~|+PQ!-Msu?Mks-st1ui6Z;}d-5t;04{Y$^BWmF^^stWrecgIB#)O(TEyWG47DQ?)fk2cJ7v zaovBtb=NWZm?mXPQ#!g2p_IV~Na3(_Ah@%>zeto2Qcw-wY*$oVxYd@FDS4BmsHlFo z>yO*)r}az@IDhoOQMmKOp$9iwfnR013bmTei-El#KORB7(4BKA`7~_13V|*wd@0f! zrY&d&m9Rk71jU%o?0ay8r{ut}zJh{*|GJtQ48>drKR$dU`RdY9*XW*?#~+UB=~7SPbv1FL`KvyGO#=+fs0%^N4m0Ba1VL$nmL&g>BE;doM5hm24-}ni8I_ zguv%lk0zi3%d0VBS7;{>;JU<3#?lS9z+~H(6seaGS(vy6Spc*=cEzr%UifBChxo8E ztKr;GaPsvP!y<)Zi+h~xA2eUnp)j54X}yx`;kG9(&W?<^z~p9Pee!*V5%W)tKM2=o z>TX=&F|mqivM$eH1XjFwU!um$uje>}PKmSA^k+HCWj}M&-WDH8)M0`TVOikejj4GI z^-O;CWM@Gd$LU_}N;uGFNQO`HnznV z&d9ra5C=X}ZBJ^$kUOoINCi}qJnGvg&u$F{1{}oTpAy0{9>XCy$U&LsOC3VcNj)Lv(2y> zR~exA9f?t6-}P8RsJ^uCh*XE$+9}_yQcj@w)s-Ibr#o@;XyG_LqU2wb!i69MnH`f@ z93yB=!Ecw?$CJyFP`bSRim#yb&aXtGCZxCPo?FemUsXmKWd`w|w={I}r-;D1n@;1HXxB90 z{*ynvGi0^u+4*|I+}ER3=)c4A>@ymOISHDw!osOq zhnLx!%n}$l!E^ZVb5?6aOXcLfig9cgu<7W97~T8Fow-q3 zx%!0fZ`Js$w*LL_j#m>9!ao?6s%pKCR}ia^5yrz<8@B(v>%zmOM9D8!$VjnyG4Y8J zl?qx&*KwkfYllGYqqS;`Jo&S?RMg>WQ@h@;0UnX|Z8-0;Lii!C~eP^5Hx z#LK3i9+piJFeTwPZn+a5J+e0m0x`I3oCir>>pP;_L@4skL;X#QAhT24-VHEY@|nJZ z++Nh)Qd8B$rm%43y5*6h_-!L)23{<%e8EFT9z_;=MRPPMCKlIul2(QG<{=S!+!!jBt>*~Om`>)5S z)D(YzyR`m?a7qUVP;(t<`V`mRdf@>{pBd9=tcFy2Mgvc^TPCLr%L{el&NsPypKs0u zt0#*hkODV(7PJl*f;*aHNBPSBRGjiz5gl-k?0|N3aWulMu-qjrz09D{;Sprwd{_+j z17ExHob!7n5o7*12ohB=-ntE2vZmENi#xlSHwJ41;XT{+cL_Vh zrQxFJ%wS22s#n_fJmy1-URaA@cb3%#|VL@OlF zPT!3H9zn|nO)g}M#kRNb5VADXET*t1fA&^;%?%SyF0$Kb1%iU8D4AIVOu4c&A}SUh zh~MQicsA27k}|v_Q-7l`EV)8oun(UcXe5uGt(bUB*y`KmxVqBqFN0lx9i+86HeBDFG%DUE^nRe2;|Uf_ z1PuEgc|Xp%T`$-7=5Os!i5cE2{kuSAU0w1^)0FMRg8LA5c?@2Ml|RdN z-)K%>)2y#YW(3Jx4b%8)EjcvAN?ZR3dY{IJVG+;FWzRdj;ti_w!6_AL&Kh~YSyVQ{>JOWIX*5>jb zr|B<^nw4)Re#j}B4SD997r)?Ef2B`<&=5&WOVLWcxShz~{rBRJvAyrgj)tF1a?#hk zd$IAM$~8=IDEkBsA`+DL^DJXkHCjlHHI*UAgEI2296=)4{hI6E6~!PTC12K?zoMKH z6=;pMVK%QC5wgAXS&{s|#x3=Na~@wMonSAa+fa?!e*Ej2gf~_D)1DmD*P)@en`6(T zNLydJ+}6l?(z&WL%k-=(m8ktFL}UgPIzq0Nw<(YN29wdIDG`ECng?ot-k6 zS&B&2UR8Dcg9vX+dK`R5S{cD zDb6EE0%+;CQvUzwvGbcNZ+FKFJmSuCpQ5?^VqbH6@6vBa;H7vCo5b?8guBl-wM4XR zSua&3c8^Iwbw~AT_*j|g*;W`yB_#`NBcWa{!ZP=Ee|)y@xTN9a<25frvcUO+t+{Vo z28X&|j;h`ok3NOGAZR;6@9b3!EQE<8LQoX41Iv|bk%9XtPsGO|tQI+37HN}9_P93L zU#v<+2<2II0o7P^B^EyT{umag>H|>K*tX2wFrO`Xz|0#PcQsMkI6VU~M|%(cyJ}-( zX}LD^%p#Y@+j;O6SiLbYq;5rWjy%&+F6X*$^~%fb7Io%3Xu^F$&z|t7NeG;_ZRcM3 z9qT?@r3N|yp870BVzsN!iBxiEb;olIS>|eHDQP*#inq7;tv&|sg~L;>s7OJ~d+dP> zF`eC|r#iqDJWAO4)#HAn1B6nrP~LUoQLpLfe<&L3C3g7+Kcb@%78L1^vp**@t2%L4R6V%pA!V9F1+t?F`0eSoyfhAvibBE z4%c_?dT*RO^GuSE(BI)_h+r4EeR+M+>0qkN9t%KQ8` zR_t+CrAQMm|1@lWa?hr1y!5m)&D;KUfysLZIXI59@3Co%5tzcl#Up+?@Jc^TF`21*Be&8VFrg24tVWD-AIz7 zuU^hyZr+&p)4vQGmS%)6mO433cPUoXugry*R*Hs@tL>=zR&fYv<#YkfmJj}$cHV9N zakRzDS1~CT|1E>EVf8>ohJ_jQ=(c|SGzlxv(Nd5aFQj|z&0h(09v zawRn5Vgarpea&-t`LQs^y9eU`@aWya0)&TSJh<}n?wK#)FrO|Y)b3+A%{MLZm(beJ zlWXbjhad-P->5$G)yJYd=Pc99^5XdyC2rB_<;5j`JUh4aGA9t`POHzy>Z}tCfA$7x z$dWG1Hzs|*PX4*P7!epGJUpWel{1`mUkfcfelffcJj8a!GoB_oNz8BPmd2N&Ol#om z`sR%B{9gj)i*kJaNMi7nTV8OG%97q-MSPir*KaZPSWbAOFp~$t04$NxbkEJC36j<| zFT)RhfA4G#6&AW|{FdS2p;})aaAz4AiF(8#eI_U<<|-B4f&AJ(T3WlwWq(zQ^b#&J zGOkO=P|GYcV0U=ytXp5-eR|Ai!qRzC^Il8F1&_9<^-vJ0b(N9YJ#tuM!k|5rTZ6)TrqX ziVqxXFQPa53$^1eh&%IYhq&0}Cg0rrO`NB6V_dA1ihdD zSGtxnF(9d4Y!f_S(opV>#4kQv4Ja7?YfwiJ&R9o|@DUUMpTD_{hXU5ndd0YxZFe9xX)ze#aUHd1#RaF;Kkf@@#9&D<$$eRAK0k@@swy*<54*nk{nWHVSx1 zVN;R!>AP7txwTqXHb$08dy?0Fz@XyHFw{qh_7Wb-g?^QA_?GjvbtKdzp#&TmDS8|c z4iMW|FMkD2u7fn{NeF4<7awM3=OZ~l8e`WWKD>nRDF|Ra2WcxP@+UT+Fhl>7DChZG z8>i;_rh5adgxTCPT*Y*R-chK|YFwF+AJvvr&TU0_X>693^@){N?z||X0z?K?6wy8f zK63**ASAF*Q6F`Z^fgEyPxWa*X{*qFeJF=PNIsAVk_;r$V3}WlNsysrY1%?CbcRW+ z2-z7(HP+4u2F%hH!$Ec49LA=LaRO7+TngPOZ9t4()ksgF}${{6jGj)BBTRrSjI zJ(xtBl*7kZ-_rWtNb%S)Xx8Xkb| zp9a!iL`Hsnqu!a5SRbBa%GBOpeCo<=4TV6GNCa{?SBu?;0kgBtr0n@g-n+TR6Qg9~ zR3fM2iKm8bQ@!uA&cSGplt>|$XP3+Wt2lR_Agtwl$PpOHhF4S_&zVk7e|xJzNz$_C z=k|tQyr4b;!RYv+bRtjY6~Iu~L95ST)7B-mb_IF*BpFH(vDdzEHlXqWV0q!ef<5-3 zL)^$@GU>+3`xHs4*SZ-8e)S)Btp^pyZ>-?;vQ(n(A#-PUo|FCObFSZ=*t9QObD9<@ z6uM<9hzb~{qvO7qNcCKuNs`>pJjMC79uIPmX=u37_j&xXV-UGO=Yb8Ul|ceBa;TaV z&?9ifYeP9g7tD_TaF!>u90$W9L!dE%52&*^3kkW27N{HQ>(3cHwqA8sm%j@zP9Rhe zCHc>juzImqt*u$9TW5k1J-_^upfiqS>C!UP&20K43cU;8Fz!aFWu4oP8Pt#x$*cN@ zNKJM8Pl4Rt^A>5AV;36wi&@SGE8D&x>~Rs79i!tDNm|;ck6KMFiobEE$+eXN@ShRun;z%y?ZyGk&SxOxY zjYq_IR`JUN6rH0_HId6MS_QG;SxMm zzd?;1I`($J689tlljTw>^p_s+d94B5usPN*UO*Shl19XTAqAH7h{3lvrRZb+N>R$n ztQg$x%dh z&QNEnqc^t$vD*cBdf{s1%5PGL*pKpev`aP<7SDA_PclTlb*XX4uU2u(@U~D986YF} z*ARc0&VwT=;K-k$x3Aa6`dLYai*^_CWl&})O+9paOYD7HyUSzbI{>UY2`o@XXrKdS@PF-y-Y z!@F{dCd}R0Yy$Z>1@`Yp$lfF(?JlLpuQlA5JyDb4@2BQgggS~KnMWv(WuV0$6T}1u zL*D0{7kBf;i|`^Dfp)@={g7K*8{37x|A^RvihA`|je0@{D@%{Zj0TOtDl9UA1AbcJ z$I|nGz}dq+henJ!YAiR`C=?Zum6`nwgMse0oRDjs9tWY3*TryU!!n7TBxLlX3(d}@!!tc^jbDkUNDwoHQizpL;R!bx7| z`}`U_`6L0sWthQI-{438Bw+Hs#|3d`zQNC+jgb2RrM5)7KzY4w+Y!mir@q2iWx?3^ z5IGsWC39^&YJuLT{q}Ad!D^c4PR3zPMpXuvi(gnzU22$YqZ-SO!}z`J3Z=e0URTiE0X+&z5my$&xa7fYHI~?qY65*ZA97-)*4=h}(WbpyLE&At7FEJ8!qGiPO?{j= z52`*K9v!p!2SL_oYOzVjbapP3pYbh2WKc}(UeJu-j}d^Ts(Qj~KG9a5`RoC~DhjMr zO4>|lU*RE97hflQ8f;>fb7VNkCaPCO(J7I!2Fu;^wfRJZfYAcI3Nb6IwCDQ}$ui&( zJGwq~{yx)GJm~B();g@H5(kc!D42kvqq~mk>2lC}fI$U*gJ44NNCd?ExY8cxGbe=T zkh22k_=yuK`ok*q7yM;>|Gl(nI2`uy@PU!P7GZI(vZD+l0{5vIC4n@kYmVJ*^d{~h z0og@GuM3p4d`TN%GnJ68&T~l4y;v~oyI!^@*YTy<(e|ghFnsS;Ri!~x9TL!xW_XWgxzrV2?Y>u%?W2R7Ce2dB38?T9koGaU=K(AZ~ zo&d)687UntC;edS-9^p0h8R0WiO*Au9b$sDIZ%9z_1oTi{#?0ZGQr#jWoq^60fN2= z3mov~L)H-VR4&k=0$K)L^rfuOx+RVRgcyO0F?g&%%Ef84uqcM5h|*IOO ztqk1##5L?!u={Z|t!?5V(U0xyzjaSFQHEXn)u*ArY+8BY$A-&XHCtY_Uc3o@-;=X! zLRvP0nd8fVQX%)vJreiG5T1Ty(DAanjjD@5Z1&#%+H{QkUY`cM*($LrKB@exOTwGts_Tl6&!?1fTO;L~Q<7mp(Z5Ev< zi#;AX4RGg`Oxrd43i3ZPXc%jpNEhNGd8J?5L{3;!%(BGT7KdGjq{7@QCg?D7yN-zb zt;cWPy1t=mx0^@LoKWM><=53cWg#Ex&_e?WBc}#g^kX9RWK~w%xgnYJAs?tU_HpwC zzRq7MpJGWhD&lxo%4MUI&bY9_G8x5VzEM!o}5Kt9sYltKWkq1xC#CtD_ z`u%INw$_W6XvJzri1T9+rNvqEgUC-qS=6yMFLUS+L6Z@yAzJ%S_cpdN4!Ew8m-R%A z^#=aSCsVP`-wx9KSh5dma`>t_dY_#6GXX@45cKi*2~~V4BpNTXZ^I%7$}c+ZDv|^M z`-izNNj(-*b6?747wgg1<8&WO-KN=OnpZY^T2|BA3JW2@1_OKal1Cl>g7)8D9JBp90&}O+gJ&PvHs8@?e|oaY+B*v@TT|B2sjGL`AmbunjOAJ=?N+WG`s@7ng#d%*?vfY&hZ#fm6xLO-3rKe4swIfbBww zzyv@X9LizSar#pd?ej}dBGyar*#W%Haw{TP>GE_}2!V1N7pYkV4@OVPX~%Gj9ywi- zW0uP(raDTFX2X5s_b7v7cN1Lrnc2!U+lb!V9Hp1}{XIgy;Fc$5Ivnq$CK>2|>>#3yrc zDa9r^%zS=d;QYiR+0-qJ`#8D^&nkZzLiq#7;8SmTrWa^Nr^oR!aj_hg$8_!mmXrSMB^8Y5X3U| z5Kx3lJ@+r_GEdGlcg+?yN|7Bc`t&px;`w7+|Kt(`;vv<=%~~}d+<0s5{R8pfueHOl zViY(fzc7!tw)hKyK{iDGJy(v`ssyEvs!pshn#4x=o3zX}OK zWVcRhQ?$&jRfqPcr6mp%|2xTKDH(af=yQ#k!0$tRW8Vilp+pGAGv?;NAL&IRPa;>fVWmoIwWHR=g3^eXnaAeAE3%%|$CsFe*C%_kDA1OaQ)<_r<#VI;u}~Mkh;Nz2UmtqQr-xVl;(hA@iPTNsun;M4Dv)AO2471=MzbPLT7aK3eRGwDMF9Z_ z-;sfG@C2ukLvP?y>CBLe>0DxCAGdyAn!9 z2tsJ2KH~dhIoTh|dMMZI;PM6o4yJJUrWHirphMToZ~Zw0eNiY8255g+{L!hj7x8xz z?gx-IQ1R?Mn<8)=zYWob2F?7ZnFX5v_##MVGxz;q8%+aDx05*x^TuNk>7In`h zB>6}{8`-@AMD5u30d08ulgn}O;g0-L%zJiAe!5Rc+%T*eK;cIy7RD@cQ;eq$zO-&V zVe}JG4M)V^40vT|;B14EK3$QDjhV^u5P1k<*UbGU(6QN!$cK5qGVT)ww1!k#N=o)M zq!?U&9nZmck@*{1Ho)1CM&L7_XEIt^Dp)Ym?tiUk4^$^ZDWs|OG9erHQ(_V>01YWh zsPWY-(>-z^)+?m*Oq?QI>Q?vfl)Fn4@J2y$I({$?KYQ3^KDFyTf8OMaE^qUquN1O4 zLf03q)8gW;_7|R~W+7`$P$L;3Bp7b@PUQ!b4tU!#07sC!cOt3K{xW986BZf4sx4ru zK(z4wAPeb{rY;1Xxf<54Bw=a@J4FG=%CZ$B1aQ)2{+Ms{WAWA0GUTaEHo3|BO7|Z8 z<^lg=8=*%&w<}4k7-y`;)f3mgozS`uwaPK+!7k_}*WJ{o+KUDpJ4ZJj?skML);j>} zRINz*R=v|3q&*{*PAj^bSVyPn*DbTpGyknPqJ8y}DbW_#cw>JmN!QmQma*RUB_E#p zUP3D2Nd{yR9XfJ3tssE~>8iv^s#Pm?(|LPR|hp$@Y*tlJdtjI{D18Q5$`DsG_iu^CqmBNaG#FPr=8TMf(CMx|5-jjTCn zXq(@?5Cgzt|M}e%7He-VwZ0)J7(oq0P9%v6DO@n>`jQ5Z9ayTZjgeMCY0wwZiS~%D zhWCb-_xZj`btcLf^de#5qjwkE{;MKooh$jzai3^eS5HQACnoYPC!X!AGXl6FY9nq%gl87`K2#xPyNrl`!m=T={|qSttk z?4aix<3b_rhIs6<)8uBO~3}7GV*WMeW)5gwUQG|5>3zeI8VeU~OF40E;w) zHL5u-NL$3M3UbLbiWdrg!go7POG|Yt08(p^!Gg6*;7+ev?XtRsYNPt7%c?Uf!WM9}cCVJ=i8Hecdt{`!^QqgQGcR9!;`y)rufj=kVy^&Ag&qOS5>Q=a_8_}NV(<1@)%W-@`!9TI@yh!B zi6ZRv%pxDT7~+OX(2f9TB^*%IXQ0T#$T3%R#Bf`}Nai)Pn%V|7r!EAcI4>@d`pu35 z!&H25L{oDYtM3oj)j?czF;@u`27qLOOOrse;A&b0rCsEA77SZid;;J6bkD5swOj%% zN1dw+00SE%-PHF65iS)8>34{F$U+W5RlKL zB@dNRqJ3*OciV(LC><7<AjJm<&OrINyQ|-XUTy=I95_Ufg7+Tm|l=E4w z`KmF`YBhFY*(vgk#729uPpN|8$}HEz-;Wsx-PC3or*M}rI1nZBh^hBms}U#j&1FHf z_7mIAbY*H6e#wsBEEZZ=O^mBwZ8r`X%L)ZE0Mr<{A3P^x>oQ7cVE#l7|3l_N(dz=N zDW;VGfo_A44o0)IAG;=B{6qIar9o7jddae*V&gwk?bil_D_deG~ z9YQRY!3vd<3t5*SYX6VY$!Y@8fFzune7nJKpDV<`85)*rw^zSV=Z9OW!sC!1Q~7hq zHo5l$@WBI&d!#}$T4eoqJa#u4DhT0~l?xP<2#K>_vNGvk*r=-+q32hj8GGYI=h#r* zTk;Zl1cB^F&xTv^aUL*wBMPrJ(LVT9AIqAf$4rNDO5fZYbJGyua6Sa1Un8~@{zHlL zQDnR7>*~Ir`GSg525A&j)TAP|KDRCFLn+`LfUgrO+thBI$5N8@nBoAvDR^XAj-vlmM#yq@c#N)NDS-T>_7ZYQB>_QtloJ zBzM#-0uO(0`htfPAaZvfNwnRA`3zW_1S& z-#PIyu-YL7jO(;s=d(MXxH>yW=>+(LAmj}S zVlk~)yZH1M@SmxV{BPH!R!wdf+h)Gb$yNqXqSW{>7__XU2N8k7$$EMiuJTZBg5Gv0 z$MDUk3^VET+A#_;dU{82-5I-euz;8Edca6&fsX9}>DuWetr*0IgdxKy6>&)R{arCp zf9FQhc?G9F^xxcGH3Te=YUPIGdCPRZY^We|-=64Q+ghF2bo~4d>S6^>TN@)Xmbh-p zj#%#%c&nwz;hp0%_(6Hp>E)}tuk#4HUxX}qJ0~WxUknSSC`P(>aNs_#dBsRh^{bQW zYQ=DFQGP^~ZB!D)xHde(c!qh0n^1IcaUFzdWVY|*&0kPm+%m&!9+$h}rE1o+yw zaUrLqvZi+A>{>2OyP#26nwyJ#k~`gbeqVx8qyrQfRcn@^MZ$mpFlunLcDr@z-z+IK zsULs!Lq(e@ewOC0U~M;sjbNr2qC1cuT--z06D*i6cG&RSTl@v`cehr^H2-YEnia5i zepg2^01W%?rXqJP6VE3^dv7f-cq4E9OV%wkS7pCX@7%5HUp(=l2J;Yma~Gzd%K(rT z8+EKO90$A1x3gXNDEjqDCTt6eqfW4@Amet}Hv^jIfnHS3 zk42knr<<7}MbRpr^xR>lwU+eJ8M-caC;hp?eWIz1t?#A9UQfHnm?e&-x8v~XGo@!2 z(xN0Gq+ijS40S0vynI!Jtq1|fuVHc_p{U2)5hW-h6oWoJNuxj)`_QE$_EI?>(wmE; zv0u9Q&U*6d<ulQik=_yhFCVw)Gs~#|3h72*kK|z)7LZn6r~?Obp}Q({5Ljsq)q%DPWzm{>rL74 zG1IqK6r2j9!2oj#U0oDkuy7h_c6LIqJP{#CQy08WLmPHh-AAhS^1dU-_cnb9 z(tZ8{fu(wSAMkQE)@xF7(azqQTlOB0-W5XDyh{|t%BPEx5gRMC4bKUXuKzzmV7U7Q z0kYIv0vK@^e&N9hH_ur;Ma=pr?Yqm(u_po;7r_5$H8>{0c4R(RNVx)=3IvM_u1j`x z`sO@CJ|}U7ivIqtmP*hRLtvL*E8v$>Ue3O!d{$uQOlvb`UvC(-+ry`lbwSy=Tu=Yj zdVbu}AcUiesio6UQ^Sn{ZF8NG>u$hu$oN&dct0f#(a1>7=QH81?tTBv61V&n*=$^>U~bMsQMwKlRkZZFW2XZ~oS#0BCDdqaPXDT)T0&9%>ws|keG zPnMvULvA(;_yuMuZrg^LFPhaAq1@pSitoVJkA!h4Jc~{xe>*_+@u_rDu`Szay&BK& zry<7>7FSQC`q8BZA^G25#d0gZFT-Q9ThXHgyaDA>N2=iHdpK}$x`Lei=BRkP3?dg? zZAHZmPX?;W`F{E=qpmZ&`KKGPwFb3ARzG#Z2CH}cQ=60xx3?G!hy|<1v6wBbCaN17 znvc#v5NW>6y3&5O>Xq>Kom9^`cWq^5d2;(GW%)zuKCzspihRdhv<`aw66vEPzS$6L zxw}>3s|y9Cq9VmUnke>aqC30T_7UBQin^pMZCg7x7peH+RQr?RPt_Tx#od!$B*+${3n3?NF2Td za_5fxzWw?ye*@g_C_2{K+-xyeabtXPQrK-=IZ4d%z&i}4Hz>5+KQS?}gorCl8Qx;P zJ~x{BZf!mZEv0`g$vFFQ#hBSu008OfA1G+|o8{X~UJS8nyfSZ@tZ$|TMHAJ}yL+Iv zK64W_)D#7^d!7(3Q_rD7c%mYHIvfh&6VO}RvTQUEAp*q3tOPUR?8cuDLB#X|+c&9s%cp%a4L`w-NE#KTGzE5&}k7FW1Vz;#B~J+DDRP z7-Riw4P>9lkWzD<8J{w?HN1g>O8NxHA!Av#_n^TbjQnL}e1F>Raw`QsSms|7L|kr~ z0_6%v9{X(s>Hzr2bJB#shW(YrdAlK#pSI3_f~4OHn3R>RY3b>G45Q}C&dxr@#&)OT z#;oQ2kxz*t%(DK>jjo|#VQiy<6OsY~ybODpP8;AV=5s*_djII`-yZ$bFJFdV&ie85 z^-+A1Lq7yE&?aGqCa4mH3#z0WgLCzT$4|Bb3X`}&2%-F{H!*(BBqdFq2{1`8b~F;- z{UKyJ!P(+|MD(`!(BG)X*(#Ufb7uTD#}nVD zSVXj;E%H7ucxCIFfn0nLNfOE>$MX|;l%Wq zS~dXzGAk0LNEYkPbVZ4Wbr?l%H(0S8B-3q9Xx=WS{+UX?&Ucu2LdfdsJg7wOk9Y4r z*F$BXj)bS8R+4)M*1_<>CN@(DHX5U*5=<)t*C>uSOn=kuwhtliixRDO%XoGUgQY0s z@+wrnyiVZj!Noc<64P1k@zQ|$f)Z0OS&tnlj51x^r#@3K+M`(g{^8fP=1(a?by%ax zclL^*sW`o4oshUFT(fNm=j>DI!&c*8k1D0efy0BiV_`AKPFt7bMDyF>6;0Tl_7*B! z8#YV1746E` zzdB_WCKhPvZp@CSym91eDSE&pjf|?Pc4Xr=t-iHVnu*Q2w0z}z`cLD6cbo#392Pn= zFpH(L^!3#)r(tKbFL z8;RoAS@@0LVO6ootN~&0SQ(FpG zD%mT4zk9>^O`m9HUxu*0k#xU+T*^rdux++kT%dWaZ_H=P`=C)*Us6G-wRZmj`C5P2 z+}bwR=>Rx7($jEjUxvZf)R7jr*C`6qGMAB2OW3Psy~ZAh8$*N==y z8Bl*Ra*l9TN_+h(Z2Y@v{^zObCLcHdqv4Y$6$^batZL1rdEnZh5&F-sCrh14K@YPX z+a*wI60h@s>HN-iFy--0X6eJj{*ITm*@<75yH|fby)-?7cA-stnCN)@ERt`wV4uZ% zX+Lce{AZ99cO3h1jz;%s%{F~=!yLooYNbQf9CdtRx{o7GE9{V}1%oNv9nn!&n%cz1 zCz|C2Wm%E<|Fxn*&7>{xv-`B|KmZ1v@KGH*S7qh`mGou5Q6CN z;nDgq>Z+aXjeYy~n@-o=nAZnI`FKH2E-Lo;`4TMkPFhL}OpHirHNM^hE^LrnP#*#f zb%$3-(Fj@j&2fGF9{Dwt6(LN{pRd{+R@-Ty59&rOU|?eE{=jD0p`XO*+f~XVymaB` zgYEp+-lsp?CB+idcar#d6h+<2Z#p(MlrJ>_4w477&+g3DGQ$E^eL~74&hqR{Zl9&k zIR+N)V-J!Zo#dBdX+BfF?W3+8L-M7i<;sk9L=dr4dIqVk?g34YxxBD&Dm_29qVeKu z_&EBknITg*+XLh)p9?c=#x6vtC-Z%bOi1ZSXIECa^YG}-@~{TZfXz8VLaVB(s@Kle zDx-wUF;`btbBUNK`(JKhn8Mi%^t*Bq8VEIOPyG`68Ja8mGKQcwZ5$;62OF+S&Pc z=?gSF^9wUsr~PZ;D*(0`386WXmrcGG7vtz-i$O4R^zp-yjhZ?q)}N>+9}c_v<6Ir& zAJ2}x%xFu(1Y_+SL#xF>&!WJ?hwruuxIaGK1_SN(y1UhP`M|0%vYDR1`xby2c3FUZm9w93weY3sgu8@`Ju&(vuho$QEie%|p!s1BssxtTk}3smdZuZz~HAFK30GV8Q8}f&(hE! zC5}!}k=^=XSakk_&{O|SE+%D(WaGOC)S-Yhl2sp88M2_DmQn)`>>kB?Z=Aj($2I?y z^FZ0R#`{9P|7Nm2rAWpi#FJA!ss5GjYlbr()BB~g=>v$tN;k}p(Rq8L8~(blvA*fS zRy_ZQqU19@BNelvl9C^eZLSzcaHyR)@okPie*N8@q~z=IA34u5$?Q}m(VjdJ!FR?e zHvYx*z`6;Uq0I~S<9jjD2+3WDojsVVm{{$ZKi*h!jVF;OEKD=&p(ssSS{D(&p=Iau zury=wL+4qfkJM~ja-YpLlb64m_Qtn-yr#Q==f7hu-~&{j45zN_n(fVf?Uz$h61TME zVbk$c-Oi3X*Q0s6Zsht_?a+vgX4=G32oAoBTqZ zG}Ui%4Biu|wP&dSEU&dz{&7Q+>i?tZtiz&S+pcXOA*FOlgCIkPA_z)IiL}y4cT1Pj zFenYuf`oK~w9+ZvB`qP{`CaVid-;=NAMRmhe)oOFTIWiDRS)#~s-%aj-&~eS6C^0_ zx8Zhq`=GIcP-1(+T!;u!baHBr3(kU-vn@hg!FPM-d!F9j@8(1j3bc5UL~7^9-^6W- z=Jrj&nN7=#5yO@*#4fy)@(XhC;JE<2M=VR>`|H~3U!^64H>Iku^dwkMpxpT-uyuU$ zm#((05!^XDw-SPI^b)G<#{mO{Y8+rNX&!69TJpCSDyD&CG zCU&>uVG86cS0)~n^K!Sw>#$vxqody&aG$KWrbBq1E5xu24~K!mmF}+D&n9Q~SdOqzW07FPft^r#LPE!Cf zX?G}_4|v|&v6+@?YW_7_ha8siq6vKdmXl(?hBJ_XjPbnq0TG}aJv+iYS zN{K?)tm-7LM?|?<0-M_r;i-^QP4#$&ss7;eZ5Nj`g4{fwJRNH#^+$PryLP5VA|i`* zu7^Y2iL3BoX%;$N*Or3cbsB`=JZn26W*mp`d0GhRFzSiFfA8M&t(iKt3X5?$B7=vo z6Tfcfjf%Z~{hQr&ip{qcD#MoMAROo=PuD2{JgnnR^QtxvQ5+^I9nt#LR4Fi+>;39H zXfB!_rnGZd_EF192e%~h2Y+X33ZsdKop7D&2?oZ;QSDNfHRc2#G(wPR!q~kp%`a1d zu4y2HXtF{Ln0{c!0_ltH0DVBa*W+^u zSFz_^Ol}f7M7Qffvp{{$-NQ}4cF7&2(_Et;(hCI*hl2X)Q{Ww}y_@9Is&O#OQNg0L8%ffywiYZM=iI9OIErboB4C7Vf zaV}(T!2pjrqfZ%dcR}Tl=H=A`7ORUh@sopYZocX2Acg^m0S0u+hDY0HhbJ~a^?uz# zR#;;9BnZIGOPQ9IzLiUJ&CP?DVcX@9Yx}L+*2&dqS1}pD?*WY;a5PhD+Al(2-4&~0 zF>9qzS&(Y2Bm4Zr_f?RO`Jf4acLRdJ^3v4HI6wxP>0<9vw`)hrw>is>(tYzb4>U%{ z?jjTCb7%^-Xedl;qoZY(EQc+u>gaLHgL0NXAEejV*mBabvVLlBm#o!hk1^~|6-9I0 znz@KvsXLxWA~Y(n^kFVdD!AKDNBqa+%Kknn2H1TPd)%DL1FyuYx?|PD-iTpltZ5dzdVz-1sBR!p|v+G%Ns~MC(K|wIgn;VpCX@NOA zHVNb#z~CH`4aS}l5&Q(bF6bx%##Gfl=WCimdRfH3r6&;0-BNdSih+JFT0`~Az71@S zdrT+aSPJwK%kzk7{z~=LUJQhaLeo8MscB___61K`GaI%t)z|aWmfq)s~>mevt`b#p5 zHdJky!0k~|9vO-4cBl%g)qD4-gA2cZ-)oQqF;DU{A}J{@Cv2>!Ugy&?gH&ECizn`5 zx3J>kh%U~^6&2r2@X!QP3SAoofLbn`nyP4wc^5E$69h!T(+e|oTuK#|E_D@_yfU$! zBKftNyCcEKB}x#c7AybmeOr$FHD3Bm@E|HBLxwdXvSqr(524UB!e?TPahlXI_hP8C@4(sLd9<>IDSGtIA|1hF`smK zzeQ-8L?#!YV@HpoW88PFQ*0yxx=?roZEDxa$-Ga4et_zeyY{{Jh!}}CZ=|bu)vU~eFq_sdxF%rHhe3sze1~(rhQ~c&L@lSpRG)oOA8UiM*?7!zk_@|}aBICIy zcl1EO*Hl&0;ywvew`dBkAfcz%?$pt2Wl#{Om;^aU3i##3lajD=-y+SZ z5wFIsN{uI>XS_T?5>LX@i4y6H($s`o^9BiHh2u7Pb#-aDAlEGZh(fh&XlN+xq7CO= zAQE}omwJ9aR{S*%P=?xjqG`syE8rlBk!BWWjwfeB*`Dw}@xtv90%us?Nah8>Y&*P`RO?N+%m$PZLu1A%qH)f_y$`kbr=-Wl3`H|Fi&> zlhU8N8~uoag3`!x^9ahHOQOTFAEwP$PJX&J93hnditMvsN`cv>2$D9Cx`n+S7%;F= z&BAGJCV_bkEcL;yHRVw$YE!iT73dhxw4tq~ejbG}T|*wv%k3M0DR3$0RYJlghW=G1 zh6&0LBxgiE=o-avqGB#x*z2; zv0oHKj3fS>oUp#|v+UB31xaAT3~cceY!}=?Y#qm+oiz zvMPk27a;P2H4bRL(rA&}HZ*6kQRp8BO2m2`IvB_biE$o8)Waa{@mnIz2p{Iso5kot z!asqC@SCc}>onWXu!CPon#k!B87bLgqFWM`R`Ymx6p+NC4L~()B(VmFWygNpr;xa* zm+{1@pa*1t)eiV>2Kr)EZ~!G6b-IDz}5(Z63J9xYCppwJs4&|9091U7(BeMN#5%-(%Zd((rG`PB zc44NWj4mQQQ<`LdrjGCABzQ`bnHD~^lO`%G0HZ-=D=CA2=*tN*_r`U?ls_GjS_fZX z6v*Z&_VT5ow)W?RC(eSD&}5qIKi(XIz%g)sH)(3*V1Agc@e71b8RXlv4s*Re`xTL&oly2h(ihTlluvw0-H7_qnla6R8>{m@YX$i z-EMAVAc^m|n&JQ9hRa3pU2!t5O}Ur#fy(B~Hxn3LE*{bAu>DnB^~*hanApNs*$4)zQ0$`Oyze7} zfY1pZTqH59L$Mx6e0~qnXAo@GtX}-}ImI)u3H3a_0AzsbJmOdJ-0s z3FU)cCjnaFThxH6s`>XNj`OfXT2!#KJum zjxO&{*{!yPog$|#ZOE-Vi(DD*CN3XY;rID* zJW9tiB(Hc&yO35$8*YHWPlSrKoPA~4Ph4POVK~MSkVt`yW`WpOVR+_G55zAh?$gkp zw@Y51=HDdFU}lIblmZi*|7ea+qM}rJtSpXC%@f3th}S7Zw2L_^!GY*dcI$4a_GnnE z85nCoNvwGm`XJI30tZ@GBC%k(xQ$PNK$iYB5$%d8d2UBhToF6L+|NT9dYUQl;vuf|xGf&o4C-mDOLuk*q3DO}Oo5VN167ZO#`k;1TJz$YG@#mKhJp)7k*B7@TMM)G%#Hw0p^?;nu;+TJCrbRet+otLs zp9K?=Q@SsJ}arbA2=zew+QGx00w_=z*jK{@YU$-nFSar9d>xEBdj{ zhC4h=tIPNDi<@*1-oGJc@vF;tK1;Sg7;u;SAscR{^h&@0>ED*PxOj70n-W}&($aUa z$#~v@-sV-((*qHz9Av}KC}wT-N}>d0PXcQ^PrtTu*Ss!kqXxQ*G$7p*B)}~G4MnLBe7{{^yDZ= zOgLV~XhL0OF?Iu*$i3b(xEQEB<)P#WNT>f~+4Xa4h*`~@f#Fx+eVkZLy}+Q4bP|w| ziZm|>?^~!9ET#p4`kJj_M$yGo@+=$zUY|NUrC%otN;x<{g_le(Adv9o3&~wf%#+Kr zt)RfbcM!JK4N*4#`{N*IsoHUvp3w|c&iC-HZG{TzIZRCQ;O|c<)_1U^9My8-cdi4H zFw}3xzbO)EL@B(z31DV2Zs-qYe4v^QW!o-Lz~m1q7{o92NK(f74|;7-TGGNpf5cr)81IL z&b6_k@GUMLo-bnHNAW!=*a`IauW0WLF~fK|VI*JN@^Cag;%v*w`Oi&UQ&S>8KYu!j zbfT3d=Cx5LG+XHCu%5uu9V(l&v@~xRp3u_K0gEyfCMkC?iS7{)H2+Q#h~qUMx!xA= zMnw2dJ?x}L`eV=itGuY)_Wtn>B1&v1Y{yl9^xbYhT=}aI(EX~VFSR=63t&4T-P!UQ zC-x=)C!SH30P3uvY<-9y42yqM{&U4gHbIOmIwI|Q_E9lOF;Ym(JDMp=1XK{{>u4UL z0n7v>2Tu%)8mk?MAkf{p_*3sgmlPk=pi+tJRL!lv@?56M(ZZv!BvzRpaLB{|g@_f4 z~{U zML`O8CvH|p|AGm3tm1obPOjlNAvp{87%bHj_(ZTiAtO)nRACDICGs2Ct^KsI<4Ucx zezUa`$izOHao@|j1u5Tn7Fd2V}6s5Zn*D{RA?Z zcYsR)>k%DyU3>!i*9I{1^!8c$qESI`*3MGE@hZh?Z?{Wmx%UVXG@AsrR9}7hY6{{% zlkk?~ol~#;eLhr}hHa!3){T_gz2D(xZQtG9J>G7@g-{;&giV!|m9GQifVaZV<+Q2E zXF1UfEo=6=Vlw+()ffZsa;tn0Gkeo~f~har<`2<$*0%5!26}*{=(XJ^px>SIzQv3Z zfRnwK$K>q;8duq_7}|W#CBlRdEOCeOc0YT&uSyRWmNT!n3Ta|+4!|V&Aqxv~_UiIT z({bFeJK-@TpH=z6)e;L27~`ui&qoWi*!NSbpCC)PI__0%aAD{b6vVttHI#vJm&mgL zg{EOQIG~85`19J36hJ#+e>wIM;H0W5u&x{9(z5j<*8k&!>#nT)^W$wI7}$ai@#Al( zS6V-{++82zG#Qfzst4TqAM(KlUE>%Zf!E;$IU3|`3V9mFN#&akFpNfk!WAbhd zlnGwd%6@wZwnZMTYRL+9vm6xq(L(DVn@>UI6MP%Z*JJCtMDPlNG%gO;eUlrM5DIaf zsOo(O6I`bOAS#f6ye_ckrCcQ3(Th_%dsG&eC%`*7t}pR9aM$9`^PV5Jr`C_YUJ=UQWqfr{MmOV6s29P~BuinS z`l%l=Mg7$b?Nc%`J{}WR#}@rIGf0Vml?PHl|7(u4e=(A19D0WoRP5hg?D>A01GQDD zR$4#`5OFWIRCo@#HlRZ5M71E@{8*?Eyq4XiV19cGq2r&| zV+hE)1^*G>ze)32?GCb#boF$)fI)z*Z%rC#JkR}IV8IUxIzWX zyI-lDAN_V=*a3gEd~zhwS}K5N7}zp zV>T;_SIgnt?Rq+!9UeuX=AMz2GKt>OESdh?`AKt2#}0HL`!Rbflkh3^vM}B2YA@oD zb>yRG=&0p;Ha(x6mENir<9?Z2=;&GUexgjuBHH}ru@IHu;giR7kn-t!8`Y9#2*>SZ9fnD3u|ZHM5i7muKJ1?=tO&_h=k<_(-mT6yHNtE_AK0#A zEUj(kF^Kzj{yJxI54Un>S9Tvy_^M2K_8^=qs!q-VWOH09U0sfuVu>Tt- z?pTrbgT$(Cc&?<2!f~qt*2@b=GWLf%Z36_&tz@WJVZRopo!m?YUlN(Wc%e9ohexkE zUP4dp+E0s_f(yJE`zCBkJ3HU(tsO}Z_dhoSzDcmguvcPW^X_kClk#DGrYh`EEC%w~ zg{Ip-{zDB|53f~N;%^;FMN+_wZIg&l>b1I60mKk64S)y-N=m?m3;;NOO}W7wV+krD z_3K2~ZxW%Gi#y5B+;(A~bG3`MIKS0MqCnuZ&SD-Ajk_{F~%{KzdPeGDluDslR_B0DH>oA2c|Tl z0IYX`Aw$53lLb2$-2LC*%GI+yl168N7@O2G0`R=dWyGE6)BZqbw^Ml!pH4dK zn*>8)j*hUb^AjlP0L5Yfgd6CP=FYZY3dL*uTNQ)~eAYy{&8veC?Ciy}hb!`#Tp!9E zLN9}kQ-Oib0md$=}4#j`*<`fp>$?gM??Fg0Rh_7$E;${=BC43b?1q-VtNMkHH zu3lx#F7`olgNr7D8Fc zc)8xM(FY?s*zj*j!5W5EDGAsqLN z)HpV0tw%340&qmqF)+diLSR&f=-2FzTRK?fYwh-^>^MuNeIg$PFSSrsqkBT>5jaKLlJgI14+c? zwmH3d;j>;aIFyf>^whNexN$y4Lz8g4@IiwrY8(Yyh1E-^*TlM`+jgNL`*ybP&y?1IIJ;El=U+i znz3(FhK})SyXEg4;r79keLW?+f*fND7%?j-G``8piCB8`?kmTko*ovUowBU7NO;<5 zcvXslll1k5Rl{_u6h0Gzz~6nk8sLfnFvRyk<%c^0l8{EdfPzN`gu4{)0ES>=w;2(A-rar9c!fLMXj=O;O=RUAekvA!r!{$c}T zMYj6FG21jt&Ytf`d~ZZUPn3ir5B3>}5s(w1l;x`+>zf- zA)1k{Ne{fA>SQGPwxe3{x=pYn`Fxwb!2W@XtCX%0(Jb%RYhT_S)@D%nc?a4|O!0Hvdl(u|&YzDa%2hmXmpmxhCKhUThGn(L` zN=@DM6h5aO-4NIs3Zc{z2M^8myX@?NKJXmO1na(D+-!Of zQ@i8V2ts?Kt>jM|)!d>~N49puOq#xgQq6Ik@a*-z;)VjJpI^s<#Ait%;`Wm7vg93X zx%|S?K^dtdyUz_X_T5@q6l2Zhzdf3)o1FhGkg+`cy$AY8m>V$NdGP`-9Argd{Gy_U zH;M3W!PpP9bTQE?Dl4B0^Ijzx&yD@y6fTyVDS82yp%P0X6AQjw#{;Lo6TR1?x$yxQ zEp~rqVOhFdSj%0)7$4ug#$dNDgeR7P`t4-v>af(Krlm-C_ZbOyX1wr4hu#PRx2kGa z=wMCCQRCao?GX*WI#<*BQ|Ty=0Nk##fPf~#x6rH833K1MQxbxSO~}1_6WpPJ#>k1MMDucJ^2XJ*lAcJO+j;zV0h28|wp2=nFwl)&qck zLKei`yNJdn?5>z`IPNiUVlXvdf7X<5Y{Zh1(j$#dVGjwZbJJav4Ddy9>0#5t(yDH6 zY1|5M*%MK%`68b z&;G6{URDZ)ln8B$@Q5^+P!E=6kI{J^r>2aTvV!m)1~eWcfT0~yMz$bxuhAbH&QkfJOkEv2$VwJMtcXCqK-%+A5>FF zEHeK6lj_RkJ{~Qv&7M)v-N4YtAeDUhbOJ(kabCRGbye>Qv)j=t*7Q6v^s=OysO8^Z zT`1BINE|$NR)_*&I1^J?p4H?f74GnVAA-&1Q&LJCDXDnS?19<w5Ar95$Yib`w03 z&r3)coQF86hE%ooaBa})&V37A^vjgRuW9-7j)d=(l5+Z3iFgc^!#dRSQT4e+eTn4- z#3G<2ffAbN@$AMua+XKmD`zXzs+HH87edd}K(z|8s{U^!-vvB1V{ z)hRL-R#It?XWiXjC;YV2WXl%t#v< zcuV!{Q32;?I%M6Dvf7^!1P2`*4ZWCh*kERrUg#D556luBeh_=pt{-%^WE!CpeAcKN3+RH70CZ-sqDU+fPm9>NXqw4N6@at^p8V#?%1x3^r@4 zlW!wa*s+cVv#x_18a#1sqXjc4LlIDz;`Un(Ms3F+qug#G<~y2&i-+!|N&RW3-jye& zezTTAE0%D>$*0SN^3|1>k&KYOhSPACByN^dRIaa&{Z=#8WnTeTUFJ$%KlJ@lbo|HL zel$AV+qtWjNF-#&Bzz$O8EbqiOoURRVj*JmNeHFo4)j&Dbl6ZWgC4fRI(BX&PtA%b z?)vXJht`rTii>~{gI~W1HDPDr!DfSwfiMI7-=u`l_<5F zH%kb({MB2=`oBdyjE~C(a?bDs#~bD67pL$PRu&}I0G>uI*QH_C4k&;tusUwt$jmLdY^qha~HbfOw>r#>gs5q(DlV1}Ye# zl{~+U+O~R+63N=NN3yy!&8;F9c}DQnf*}=@1p%GXs--V?8*bksfPcvYhD^5q%5hRW z*XI5z6eokt7ar@D^+IHi-C(BOImA~2q&-s#-)Dh|(yhDq<82W#GX4QbEa&_9F?iQb zA<$tx6EeeB1a$*Ai}d`SZfRB>9|hDo!5U`Ad##YP8hS;8;% z+x85<@e5*aL)hwr8r0-G3FyBRbqmP6_s$c zX7+bbVs9ao2n|Q|Ror}*0v$~RJ^h!4)i^dRmxM+U(i!oWonP%w>}XOzsRnHQYo6of zMF~m>(*7Uie<#W;MgT5Ecj-A8OyZHvmS!T!jWBZ#a7H$^ zT;YVkcnHW__Ik*;i*?tRK)hN3cnpY`yI{>frQD^6Wro&_nt0p93483!w!!Bo8GbXm{oPe53(c+wr z4jb$v&yG(1v=CdufJbNx@@2+LEdd!^TNr}XGLW&|jE|#TxafFs{0+e(mnaXOuFrI0 zzd7|2)%{f899l^g{+|{g2CVqK<4--|D%hIIeDlfi{D*;&@YQ+M9(?8hy)>WupflBT*~K-mPNB=*`r zEeo6m#*@l#%wV_!PFW`Q*khkvJGE16lCLiRcoPEA6! z=?rDqKQcov@BhXCBQ0d>||jnWoA|YGKl9MdB7)fKhu%Q!c2XM z7U=83!y8-WUh}PRF07CELDD=--^=qv(RA6Dmx3-@H>ZOK6k$)lw-n0nzjB>qsv4CRzUc)Lt!-Ds_@l#}Ei@I$uB`9@i1vFsu z&G<+f@wlYK;Okp?>X?YG7-qo5K$=kRbQOLKn;(QuMt*VDt$+Bx(jW!wWNMHf(Wmac z478TT#lYRMl}MV&wPB*31Z1#F8xG_ffRI-bi7QAg`VBnoN1O4)I{Q#{iVtSu087#8 z#|!9R^oAcHsk{ih#XaliKcbyO#C58Jxz8+nXE`+6kEg!6Z2!XC8fS5Qnf%6ESp`i#(BKDY!cL{uW zxZ9U!M9|@<7Rl#5#HI2FT^F5}^?jmCpZO5^@t@Indr4YkqE= zGCt+HUWGh_2+Sm0^f2}K@YKJfa(gpwo*)F3iWEda?c^jRZYt8f$;5EjXg;FqEV$y@ zA}1976pGg_a{cDDLI7}eM$a?O?{zH1Fz_Ov$Y~)7v|GjTK*~dW>8%a)r ziTt;1ZT)4~!h4I{t6)R&BoUDK%Y8KM?L{O4d>;(EaKhIDbNZ=quk!UI4XJPK*67ByFf3>%dfWA$&x(bXK0j} z=49RUpTw2fH}3IF(KT$>qq?cW5(a<#Xy99k-|i-j^V*upKi(8j>*F(L+(G?(8)i*3 zjICe--jr?hx;1rYypY7RLH;_RP4|Dw=E6G0MI?TYCFow=xM*Higp>J(N?2CR%$}L4kPN z;D67vmkaPca*kb)}^6sFYILUd5Pg%)w>(j2XR8?WerwiSe;@W%z~x4{N;aS7uDezjX+ z)O(2cfHfTp)EhQ{DUD%O0`*tjk2zEY;fAw87Pv0q}ajQgRtK08v~9 zhH5;PW?y*MDS{S6=s50Cy7$T1*-?9(Jp}_bY?yp{vq%J0f4_CCnD--2ELG##UQXcC zX1}H`cKN)?$C6Fx>?^5O_t%1Cs2(81m`qZ{KUI>fZ1o$1${2GmqtZ0~U zNNM>Ec!P@}(Yn81Q5DAiz)djT-7_S8c(9iE$qtOra&k!}uwv?kb5vZsud-0o6FiCc zA@AVnb=`qYj(GIw>(}QN(X5y+L&8))0D=exrI2^Y#LBzBmQe*tuukcY$*Br#e=OVY zN)m`mB}D|N{y7YTYmFx>$QpF=@XBL^xM4)O7zijv@C@Dlo~LXvt_WyDqRQ#zue=B~ z+DCb0PQ@_VDX4jkk4M|Nxn|ZOUV_Jz~cuJuSg{W1*7}e>;uCti0?hw&iD4I`sRX=zh0lK5&uI4ORpN(DMEIosWz3RuxULgwFeZEqolw$8PfP2rE;d8*9+H zPnKiuvG;$Eb_~8V z6hDrC(vR##gJavQgA6|4M4@~br(K|+!ACQ8CoA(2cqq$Ezd?=zod3YRtVdd5M1@gz zAN2}Xg0>Nc&A{&*S{zdqovsc`W=r9QoIogHOqC>MB3&cgvL~9xQvW_ELlK!0c31GLqmV98icg8K}SRa3#tCEUnS0D zoFbzW7a8eHuwBL?q25}30-wWtYQVY0ESrl0(Bb!2>CANRk)MHh-BXyyjQ;MXN^VX^ zmk&tz+3Ww((4%rwfZe+le z?Aj@s^*SB{pQ6H|n1p|zYpP0!i<@w(-n`U4D-$&I8rCil{G|;EBjWcR7e0ZxiAw?- z$G=^YpO}WG$j*=#CWql+Hz0N4da?$o!7!-IGM1x)_4`mZ-6j(+sX<1@_VEG^28LY< zj4vr+T^;fuHzq#6*ek-^v%%{q31%bl@cC}L&gJBScrDBargDIH z15B{bNE+7pV2TBVV#saH>?VWnWa;P4AXP{sfHx7;m_T2EGk4{54lMypi8W<#SlSQ~ zccrZZcyOWBA6hTyHCq5zygGQ{Tt|Cj$8||tw*wCe;%Sf(SX~}@-D4}!&>?O>0Z2L& zE0Cwvy8${I%211~aw30M(`@HDBjctYwv@q02GJJV@7T1;(qkxq%Am9|8S4X)4c1Na z$9xDKtMG(eXsUI`jx{^e3HPrV1)qqzdAUGs)mi2Fk)^w%D z5J}4*4ii4eW5{Nq48y$ za=!ilA9f_Xlva|vcYVj;NT=l)Dssqefl$holp}7ls4&VI_dy6mYAPS?{K?FWF+a~! zYBatvX$(FFS*f703G&2N3*mv+HPrMatNM&H_*}! zao&>^MiSkT*TMz^I?e;0Subl_`2G?SZlBG%eb*p<>KLV&kca5N#lVh!RRIqn*yVH^ zefRRC&Ho&MBxtO;jT~Gw&@lc23NJeDC_N)tnWNjA|29G9c{=QG%AgRRL_rP4p1Zuz zd!VV_IsQr(Ii=YVum+=v)AyftCBhReV8si~4pHu#;U8X-FNaj#20ef+L?d-~2PYOO ztyxO70|TDXBwq(_?rON>)*Ha#nYrbBlgMxkA^ipu1vAU_$jFRPE>t`Fmfa#*a>$qG z>VsZP&IgsltG*@r?bD4h8h(|Baw3J=*U68o`fWJKMv?4atE+dr@SH;FB*Z*a)XhK$ zI|qux%`5$_+NQjm--jNB<-Kt;ELcrHJ7r$MlaKtb?O(hd_8nVHE(w_pCxi{l#ia(_wGe? z{Jc)FIClqCNqjgRwsG<*wC-TqXj<&>&t!yvVt#&017oB}ZjSVQN-M||<#PY=jK=*# zftEO-aXybd4%LW>WncARMRAe5!rM_(q^c^@R;1$lA@`%Lw+2SiKGuyWU1{R+K&ylZ zNmh*sKor8aM^7ue{6|JqOe3Ut5OY{3Q<)QflOP8^#^R!h=fyfTbr0`7miFqW9XU$U zpFs;Q`_eye6_AdPu~7bedd%ZAvkJ_wrARr0z99!t$~FzZMRp22lHS1gx^fG6C%-l^ zJgg^5N@V1+Crg!|pGI>2myQ%Yrx1FVu38s1w?oM{t8h3Z3Gjk@ps(S~iVAo@AWS(~ z#1E*P9Xa0)cmXtY&xYEq^78jTzF(9VH7^YPG7n3FgtqU1iH6M?Wc}u8u~Y=Y{X!t3 z9&dQ%8P1AJ@@{o{64=g{oBw|GtIKe}n*HoG!NVm)SQI@zUgb0+mqv;lpC{mPP;ttJ zhMt?{q?RcwDe04PHug>BwRfFG%o5bl=Si_4s12 zL14@`30zE7$m06Jrs-~*b>!Te%oUd$`3(>|0Qz-ozBsEH8g0_B=BIe_)p@`F#xvK% z^J)Mnyh@=IIobqT5*9=)H{p7b{57ffh>5^E-U(gOYbcVpsEml9XJ_RdX8Ggd?Ck75 z46(Qb(vy{4VQo}bfA5h!qB#l=*PGk_`;F@z37MH1#4ebGhw3(o(GcR@@;K{swZFQ+ zF-~IOkMV3ENb)@74p=XYomX(LRei#y!5E`l<0Jq?FKE!Fgspziw2wAiF0FjNU_JNz z@@x`-om3!x1->cdf$4HSy1V>4+FQr%Hs`&t+IVv7eI?C2=hciG#>px{jj5G z;vLK)uitynmB=pyk)SFn@oBUjpb!iXdjH=$9|>lq_^1Dxym)yBcwm%IAoZC}Gzc^n zI(Ay7uRoE{IPR>j#Fh&1z9{ z(6;sl+@fJ}!h{D0(QnC&e)Dw4Ewnkzd0jsI`7q@=M19J}2Z+reu4JHEuRrr{Ztbk* zvDOaToMu?*T=CJcvaQ+{Q3$%&jeP++F?cn{C%ryVv0Zy_R9+lyRy66R7rfT2dVbgd z{!+-)KFBwJYYNs(=4waYhs=rb2^pzM^3>zn<|Bc6k9d?lH=ocNjX|>WR^4t|S7*A~ z6Zan!)*MXh%lVbnfQW*CbqjQ_gIsFZz1}bt@t!J7eW9!e4A>t}j(3LFjw*q*1R0dq~_tC_sr@rD4bbD9Z96vvanxKuCp zWK16?_l;D&xeRjAyRBJLiIr1gx@08jm(=e21`NBL;~H$Vp%a_|aF z?*0}?>MUM1YQbcG4v6ASP5TJUkhW~UQEGu6lN5T$I~vG9w%deK++T0nwTrt;!r2J1 zhoT;Jddsh3w{7C0QUogPcb}WDMl>A6Ks<6rl^T5)%y&xOeT2;(r7-v4yL_HDP}l$Z zI-ggHg-P7WBcex(;$zpivwi(@Y+UpvstaPW_3}k$>(kU~1dC{SNWU@lq`i`vE&57|A*}R|G4<5=A~A<789eQHs(xeALm=^K-M6 zg-h|~uPds}%<&nHlb=NhIJP}_ak!}hwN}al0RVJ&O_T>yJ|kdYh{0sz(BaQTTt5l8 z{3{aTK^a>GTJb>Q+iEBTo?Q7}o*LWiRlO=o1u_2Zo1}rTcZ>_9N86`98c06Ho)H9dy0fm^GqkXCNjuxLrx4^D8Uiirc?Lpy4*I7YbmJ8Fc*S>rNauZ4h*;m|Kb! z532O2Szb;stk&E>*4?~5J3}4wq8Y(K$7H2R{4(T&&PC@%<7Bnf%3JDpq{7-{iW?s7te^>{-AQ)Rv%IO@k?u4WL_)bki^by()}x73^U2duI8 z=@5nWIf0)u>6&_M7gQ;3s z@kYPCKB=PMPdn}p^-fR!*~QM17d=(VAj4x_moZ*0qok1f<9wG|N-FJCyW$nN(Orx_ ze$XTqdl`)14Op#w4MNC>Vf*oOskn`T@l}!FQKG0yva zmI8DxuX-aO>9r8o0B)ETzLPmqL&C&hh(F&iViVxjh}d=H}B8EbXMFR3H)>F=>bFmrlDcX!<4ec z2R>^H!F4q>%xVPY)77MWRzpmNJ7-wo_k(j_0sl^N%ZQ2f5Z}av&>@~Y%ohD0Z;#;h zkC5CMYU&Twn-Nt@d*IUue>YFc?VXohP&tmr*RTauDJx;)ZWB_~CGJ#Q82Y~>7S=ApalQ7z)bg7sG>&x@9vA$G1G57uN zix#hw%+Rq_K#;tB#xQBH@><3+KP_9z3IHUc&Oessky=rTuyh2{hJ%&5x_YxG3*Vce z>Fn%?N<2~wUESa{vvEXBOz^=FM7pdF?vNQ!!jBH8<^tY(?3jC>m(=9_`#40MeX*V& zyT>d>QHKiBDy^+fV_)9e4tU;hx&6;&yPF$li7;4(%@!E02(9Jqxx3=x88BJL(r>L! z&pIRJAK2Y)!nrtAGczNAth~FJV3T0FdzVLDW5!b>bFyJA(f%`Vcmk$t2=O0E-)99D z|A<<|$6MP84+)F=*+K;=#F)Q08ig&i8RFGu-`vII>54I%`f4~cZP_g5wT$t4$UXpz zXK~p-BGG`EO>tk+X}s)aJXyZ-B!u3~ZWoJ{23xK0X0p^1l5K4kfF`=;8Nv@~>fpI3Zv-?!;kln342`tu@a zNJ=W)!@`mkW<-^*XL5x+#D3MAgd43Xi*lHN>SfLw6RUuwEfHGOziGcS=hMWK)=C}- z@a!#DnP3BVV9H+T<)?_cP0(58A!Jg7(onm*eFe7O^V>YPJ^RPDw<7TV-(6r?fS~46 z<(5aUIP+@*H*+p-!!HbUqO{%=60~Tbs?#0kQuyWPrv{acq^Qr(O$f9=sHMTC+rI4q zTSi9Om+ORL2+GC7XSMD3k7faH$g!l9<9O{a4j1Y1ko`UlYP1Y)Yf?KZ zN&|RpQyX;WA{SvoLBlAQ#}eQ_)7ceRo`atq6@90E1)Pne;stpg2^m(H>++C_<~p>q zhqMywNwy>2jb|kt#o66IUvruZnfPNY>Bw@dF5qc|Z85ebue`NA`BoG?s2q!Y*jsTL zR+H4LtAjo;l?`1s8aE&$U;;ru(@C+Fu>8k$J@f zHV#qAqWf-tnO+~*)<3I@-Y@VEl$3d&&OqCkRz^Fz|7TE+w<;xSXWM}_-NE+6+-tVVkeyqj|5krDserO8C?~J>Td)=w8j|j>u^O@;WjNF;^&VHXc#6`2b zGa`}o3_E&>W^sw(U6K(Q?NM=q{NCZ?G!kw^d{{G{{6h`uP3^gri)g9+jlu4$$u*9S z_(ph)eZmtt+2Zr|4Pb_rrq0|IK=l+Fb*SJO7!)mP&+R%!pAw>D`@soza#-mBjD{!g z+rg>_3{QUDJ%baeE#dz4_ACy$U_T-1WSbbCWGOX!9xbQ*`E?KT4oRoEkL;ew2+U_> zo9Pt{L470Yw3Kds70>WZk=c!vR@j?8kM&DSudeEBu1keNYGKb6-WgXrgeqHR4WRQ&`(_ys zk7Zy9y#*?sk|I6d@|6A3@uNp#x+BTGY8qWq{4uh!X?<1?`Nth=aYi#l4M&FPiNaGJ zXbzDzHVKeBogD_LEE=m-yaKiAd}Tv)>+tqm40mrCJ-sT3M|5X}t`lJS$0MQ*$E%cf zYGzL)WlCXbKhpH^#`%7h-l(8ygkj6wE~u^PzC;^hpt3?i7YbF*_AhEcS3)W^SJ5^4 z=%@yd9at?@ra-Sx6=h&QXeHMoBl{EdkfQz|pBi}1vU8cT@z$P$86^=ou`%@?td%ol z^fWKXeB6#60fL`O9gJ!ykcI@YXI$m{ zJWF}0|0y$*F=B{vxVB=S=~-#ci3M@?5y5vW3&wC{i1QYhezV80^-h#Pkugk!rhCwBSUB`L$(xt@#^C?y;xjFDNx88 zPmsP$O)lf9+ECSyI67t|tE6D4=1=}CSi;p(W}0eXDCP4P`u(Ay_V}H-0Pulnnwc#YLoBhBR1$U>XzWKI zWvL^&v%~hsQq1qXym+!=WfW60LL%wq|3}kVM^(A5U)w-bQjwAdMY=;mKtQCsTM&@$ zl2njR>5`Q0ZcsX;yBnlSy1tuze&6}$jIsAQ!{u7<`#g8dIWIQf`lV3PAGzXS6J3Ad zUYPrgyT#sv|IE0rlJ$L@1&xv+6t8Rjx6=lY6d4+Oz;uk*jk5OzkJB$WV1NJ!`K(3y z0hhGYNarWfE@d;dt-+3fqj>(Q!$hM@L|!eY>MvQbYyzM55=UGBy*12%Ae;em1G@n^ znJ#`65rtRKFuAgxNhl}xF0$M{e?!K)@jRzFOE!w7w+N=dA)?_ZeY~5n-%;xO`eiF% z&Pg0B@1!ix&;aw4sa|7W9*Cz8jrt;of4unt7;#opd^{k884~YdUb?bf$yPbHQ(~73 zI4Yy9GZ(--@DsUDr(}ylp7;VF2pk$WneB2Qw#fyu2e600k_;I-&62OH^R5G4ofMJP znGoRXt}*90U=hDYS@HCi$@s^hD=15wM6`{x5H(KO{3`;_c&cRlhZ`{)oz7NA(2`@{ zp|5{g-W*|1a9K6M8|?Qsg+^PwmrUleRE^UPRP3)-wXfY*_E-KpOaxq0PVFAKK0B9l zRbkRAS}D>F*G^@;+j`36?QFiq&p7Vc#DvDskmZLOl*S}Lo6PI>`uoq9;_u(liGF&= ze7aabAsXOb@&TEKkEgeaDI6w9EFVH4sX@qvp}!m{9aDC_xK5MNyAC_(*u++V7K^m_ z<&l^7PVxBD_r136W*ED-HOj)>mqKmfp&IQg;ld>jg%YUrTC_OlvQPbI@RuNckLu+e zoCFKs0PfFt1Jidb8nQunVl`t&kE2b{w7&%TwCbW#-p(UarhXkSIGr%yD}*HwFd`x7 z%sYWVQaxUU%s^kYmv_o`T=$Z$m%9(Ltdi+ywu-$FA4sW2k}$>LPtUzZl#| z+ds{pTE#Gue%mkxKCD?F9(jCrAJ^Gy)?W~QtgJl}SUqZeBjo*JjC*+nRez7ud#N++ zu|snDOLVln(-XHx|0_-?QUy|d|2=Q}83cJRoy55lnN$UGKkdARCl6yVEks1WH({t+ z&b&OG_k7N(*fgB&Z9cR7>F8*$-a!z8`Tz9GN>umvQ(X74zI@1GkxPFC*Upk;_aWuv0r_B zeAkkIzWXTYsWw$b07 zsahpUTIvQF>DMjOVvLV?ob4O<6cxkl9>~b2iHNSdBy@>orxySz&QJzGgHRolQuOWh0^kQ1w1nvz|bQ$m3k|lAH>#%kbw~X@bd6XPoi5FKE^N z{Uwd^aX#@UU#haYjS;V|)@{YbMl3J)=W+h`RA?M%go{B?+f%DfMbcvdxPS*3>& zIb!yvv~%Iq3am;J>_0R7qsOpB}e- z&;sDRG_knePl?nSr(AK7M=qP{7>JkG7jgYERj0Z`vUi5@3aXky|6p9~yFW}6Ig)4bEz z$_iWT34i|&oftDZ^#epQ(^eWv?DFtKYA9nuMioPde!hwUMB&CmR7mTWyHTS`w+;TA z1`pg9CUX3DQSe^M@4=w$Vi%oR&vymg-4ayCz=SXjU0l?=>gtQ0zp&|x%rO!90IV(Qru~ zjDY;+g)km9O?_L;?YsTSN>jBPOf+iZGrKbmLIao>_l%6fx~KEw^_y;iy(qYN_Zv^W znqh=iV=J5BkeKy_PyDi-O<~L@JdDh_-0vCcZX?6mWxX?7dAar6mZ_i|1|ZWq`;>== zDQj%Mw!9NB)ba)}F9C1fZLt>mWFkHY|5LFNo(d#rSG!KJx28wq;o<$1Qq|1Q%3jxa zy|M9Abf~@-aNCgPqG2Tzx?zl}LQTUR?>s6X=(#b@urv7p3o9;%y7OgjP6+^aGi-Nf z0Z-Zt<6l3&0|G!bfq{q?wy><=%^OybEm6(&4J-pPi^?4$ZbQz$WGjM zd3<2FeTz$L?PP+9$}Ju7WOj3@W>W(|w$fZS84J#Hhx?wy2!I79rD$jVT#{acr{y}b z0QC_H?j5jE2->k-ZYc9R9Y>r18%xM6Uw7zL>&K8Y$IX29yvQt1?HjJQ;0SERAsj7; zJUYwHe1}zKnPRXa=95D$B3%h42yh<#T&;I+BzrZu;_;6#E7s?<=in{@cLq>(RZBHI z__JMiC(~gh8PHYth7;gSxB1zeHlVqU0=m}6_L@Ac?f%BblvIJwr7W2oTAo|1Y4vyY z1HTEgvw`|mAEO~hY`+P)#Fy>0dTJW^)_@(Hf7KtAqDU|5aV7{lGN@R-p3I>?Awo+} zw`}gSm)$dBdHi_Bl0du9C2HD+u`1u>7wZwFWTBy5*>+=o(aWYMrG94_6^_}*G9_F`NQ!&XR z87l{Ky|Zt8FERQhdNuq$OEk&)SA}YdV}|<;YQN)nU5u z?_}M6&~<;SbQrT!ngchW7wO-=LdeD-ID zNmwAtPLO%c@7BPYJvc;HYEZ49=tteXs|L3vs@&ul1xyYJc9vtX#q^IzE(`mUX+8j>+y{nU%hE@S0kw9+1ISLpQSe}}Q>ZGt9 z&AQ0vNqD1ty>v0UE~^kwjn#88o1qq@;dbyR`-5v}B0oIpf2C`j!@By`TY&H(9-f}` zGyWSqx64j0_AD53fk@LyXRnn#(Sq`#ZMLaEqI!-7p)xe2#PGeEWBDvznOI9cF0 zxP;Ci*1S8)C@c)~>H;5LQ`pVGi@4D7G#cLLc=qgPQQt9yLc?^yF!>ap#xoCa@vtoe z;qb0{G=1uFZcbQ2Rnq0lj`8BuKk79KplMvaJk+$`J{X#&MJ>;kM-9FYd^PBP;EWp_ zLKXB;t1$Ci=_d5xha?>U${2+a@zDpfz;M}q+gc=;Wh<}q!^U5y-Xxq4qqKamSDpRb z4z^IwIS_Rt=3_m0fYko=8^T$g^9i=1#?3Vb6(&Zip;;vV&wTZi>WODDNnMVpB}0M7 zh_P}QcT{CaZrB|PfbZVvSJyzKlpmH2=WEpZMIefxVHP>rJtqpq!^|5a(yOM5V4*^B z9FZL@pVCZ!z`&_j8bh%VgB$&Wn-DM{eiR-M(_di$^KSj$MrK&+mJ)$0dpdT52#vQ- zzE3;Oz$}S81g(y2O}vPDDxZ;{F@12+N(6%)R4^xX+dA4;u=XkyDrvZVeiR!U^?J^9 z2`;+7L+vu^FE(h~7h0B+B_6Z0iT(@efBINv^RP! zX-vZ=C<#h78s&^tQcV_ZWaM|n zi%;^}nP($PK6P&-H3sX(dKtorHs#>PCr!f`a_OTcij_^!LgE{=QW3EM$e zWZX9dqw#7Am%WqiXX)&3<->1<=l|9ZPT(~zPJE*p_tyQ?6KqUCV%>VJuFeLBGZZ6s zb_akaB$p`+ z6(%k0>6{VJ(11b~Z`NHKFR(k>WT*ah$LofLr9p9_Gd8!nR;!lk^a>?J#Z1XkiP%91 zP4z{R#GFB^wdV{ZSidC;gJDhBC|h^_EhL2ZxSl-l^ZUA%XyfZ&0wG<3g<7d)wM)Sy z&XqM9^X9*{*(1>_jNPtnaK_4S9~UedJ#^O*MTp_T41ZM(D=b*K*Ab(l`lkuAfiMNw zb}IF1M771Tc%JF$S`J$ZZ6L-mP@$2(v%jyqCaaR=8xoDGav{pdh1bg^UgyGhtr8Aw zSGF$weO;euEo(=MzL~swPS5HSF2JuoWnvv3R2v8y?#HF3UPfqiEZzxKQ%AP5^Y=#* zuQZ2JRvZ*B#Mk}8CbSNFG(*;E6`CP`;G4SePMj(zH{)9%bab7M1z)Vj zYr?UPC<4;ey5qQJN_Q+9`PsJELo&=vlPpxU{X^4(UbyBxQ+Etoj0h8H3@js z{1wxL)k{ifjf|o`C0ao=di1cu=ga=TuMB>Cf*e4fbaBG-qf(eIeOXkuc)(?vETw4B zgTYPTI5$|HD`B}i<9uM2hc&{lpS~rTFMJ6;X=!TBTIiYk3hM zH*#9^;YVhP)Kjo)fph`scf8?z_KQgRY}iK>*~@A0&7+GZ*OlY z=V^Z=Sv=x5Sy?$@h#G2f=@#045k?kT<>&&Cm({%Mw)TRoiP<)bjEAtoob8*}@AIS7 zcT*LTHVa-qJYS8BJR!CK1xuU=s3>3&4bPtEroW`SWRUKWvG~U{)>Qi)%oPX2EY_Aw zH`TQ6Zt~!a95F;TJiK?ZO0uK_cSuQL4cOh{7X^|gwz2$pa`Kg3ccsqG15FLZ29CKl zTqA$8Nw8$9%WD-Fns~yYS*t`#W@EkeSU-}CO>ubp=;$DJWwpz>7C;Rz-|=qt%M^c> zlBxj5lZx(@QxDr%6&MPdfmnF9M9ijr5eLzUVABBCcj!V2Fvw#^>$&TWqM)sU)<*|U z{n9=z03F+CyVoaW%eQhJ9#6T#-D2;%)b@P!j}_#05icw}!9(O%9+-Y4Born}g#Btv z$YFW`U^V;K7t9K^=08}OY;3U3&Y%J4{=5c*Ey^S_Nz{LTbwC>xVIU-Q;JhRB@JHP3 zg^6OM;1^rH?SkcY?riGL+r24V+ z*}~fL@mI4cRz)Gv;g!syA;Z)(I!Q^nx-uoHP`Ey<2TICEpbL;EnyTnTkBhGtNc``v zoXd2*M^7#^+}_gz3jRf*>un2efX=JXxs0+G&rF`=21Q zFg7%eu&H5UHdRr}0eMRtKevN1XvbUa(q+r_{0y291jPf$UMmmlHv6dOi&-JcdAVNfMFSCINWD7PhNrqt+Xha(?TZJW2 z^$gUYQ=O?*@9J8106Bmr9GbWvRm;WTcuO)fjLA9}-3?0Du2{!?OUOCMY!sIMv!z7G zbKK5;oovE1_{D`qBXJbnP#~cR(A!ybzqPztUNtT$O)uCv<(e^nBSlw-IAP>nUQ(q( zLopxvq-q5_no3?TTt=4k$K|KQ@8J!76vuv=wF00rmz}P2C!KRTcM)i_-*lXIyF$5` zkov5El}-2h4p|zH^}FT9^>y86`hlhzUEM;6gv1PT3!nf&TgY z5**;QL2v@*1%2amg5HVaYOEY43c@mvwc1^aa$pEfW(cqA zZ3*^Nj}9Wc#cj)`kD(^(>9Oo2cZ1@&?w=g~P=+cqOKTW7PFuqnq<)g?;*X5LY=SCP zQCXbya5etMnff&tx=>4+1h@|J)J-W1-9wvvIC*!fn)Q!OW6#I%0N=)~fYR3S?Gl-R z18l+&gcm(N9)8G^A8DW}AFh|-h{Sw**@i!jMiqjGo>c*HB_QCY`hs3<_&p$u>n;P_ zXJrUQ#WgvqtC@?kB6y4p_e$Rhbt-e$+KV2Kp!Rrw`!ak<41wGc@|%rew=HJf;qOlgpyFcMc9%QBffvfwJF&zj)Ovd<>(ABEt4Z zVXInkONejitH~mrRHBm$AyZ3`{(imR=)x&iJEUUET1L~?7E%eTRs1&JnZ?U9;P*jA zs2e%Kn>AUOqz@Aj7#|Ayfb1{zmq~~Sl=oK6sPxc`t`DK^Hf%n5_EEK@MF-Y52P{!IQogrZbYOmqBdMDNQfkmKE22a_7L*pTnLxH#v z)jKbKE5=wM_1gVz?iCgzGcSNWRP8p9Xx283HLQLF&Fh!D){;-~O+>{#7j=z>M~5lz z-4(JfsVWc>>fC+L|CNka;VEm^lv|R=f47ZEI;nnsdYOWq3Jp7(Uj!%TbNae|%LOmy z^}XK@(Sm~f^VL^cDvTpDY7SmGnThBt+y;Zh2UV~eau5kgx=|vJaYKMwTdx`?la^zO zxLx`9x6`ZsLSk4f{hby z<~f)(tt^FL&0Q6QKFhn1h=M~E$B0=~myv3L+Wspe( zHF)&Z1ti)L03t%rN9=nqZgEy&LDc;DhB0j1yaQ2ixrUin7lZ09thpdK>ih(!HrwM~ z5A53amu{T#^sKDHDoZ~47_3S4>@V%bhj=sUTeFN^k(^dfjg9!VS{Y?Sh_yEdvHKgx z)W0XKdY`)ET)`ef`ny!>;8y=iTk!pEAm~*1v2ZA=dv5mJ3YOVj?L+qqv#G_B(_ekN z|4=WBky=ba0ab ze)9k2(ET($Jxydp(v@Gu(Y-Sh2Xjf7ev(28vg+*3u!6XtXPq{@HXvD%c1hgxBtCtN zC}idE`@!#LpUp~E1FnARU)cAA(zYV!+no053-4bDc~n}Z>0UYxrAQ_4@pWuX@QxOa zaRgWW`sS_X!Qc4+9Rc%G(l%hQ0snnaJ3L6%RXyC`pPakr?w91(-slY?X4Iz_k74|` zxDtIIvH}}!TqR9u6PycJ^U25{T>%>cB)m4e%A6fJG-_-(yAS$wX5Ty(99DZp*zNIr zJj%MMiG*_k7OnPJY44vG)b@r(41Y%1cH8UhEP2bu+EMo2^(y+L;lHIo0-g#DesL7` z^MByugeE1!VONSA_ZJkrTU#VF%Es(wgRn1-Wp0IlUH%I5kp%aKad*g0$SR+8RW7v< zl%5_XgR;P_QNmLdIqm&KqtW_)Bg}4*nVl<=jyBn!oKy;SYU9f|Ji8|dD`A%4Fl%LK4zCA!t==?8C;dh0 z*JmH+`$=0DTjSc^`}#dK$%w!d|7BR{y9j&Mf#Aq;(>Y#Au!ihRhnu)-zhiu~)b1mr zmebK`bQSNMM=tar;`O^H#IK%f!JqU#xglQ#ggJAy- z8{Ku^omj@-2Ma!s%}bxFL*g75FxG%FtqzXi6Il9FM&gVVG^ z9k5CyWkGBcHehs<2u0pO3JWC>s+-nm9oik0X{Zh=<6T^Gn*Wk;$N4Bs^wQ&AEJ{ar zI4xGAHv7x_h`6JL4pPf$p9K{DJ3ied%<>&$Pqs~Nh0!s%u`e&$UK2pxs{XQwtSaQq zD5$&gfM-jm|MeWfa%uoqK!_NB5^v~topBBM)?;NvYZApR-w>k6@~spfUOvC;Ld)X` zY#EMVa`w?MEKR|8S~T0ML6VY1AHEuNW5@dAzwWghRn^trKXF;jk3^k?ng9~eaMsDm zXX7^Dx!G6Ds8PFRX^t~?2R`>6S2_JBe+%Q%a7N)Z!btG{EdxwR4W{VlsVa7ix_3)y}Sog8jOiW;6?FA>ik}iuUIy9 zd_@Nb0JPWMD8)C}UXf7o=cWrm%v$w`TEJTpdZ}Z@!unMRPW`M4-;Re6W-1>g?dKO7MMPJ|C-kRJCjn&RfE<0KcL%{mH}e)IuG9O1pYvhzplAJ<1E z-7F&HhDQY)tKfVUSB$*e0ms%OM99N=l~YpMS5a0W_R$2!ZRQ1wT{N0t;KRi9on(9x zT2q>Zw&Ijrj)g|(aVUs>hlL3-(N&4XJYl_PZMt54A7(oZ7n(4=d@3|4h<;Y2bRgc` z+)7m9V1dg$3dLDQgO>Hg9RUGFpVo~3*-TI$Bc{*e;M1tS0^iyht(Dc{3zK{vD}nFH zO^1CaL;d{?mcJ)FdE1U_v8ObN7?|a1R_kp7CR9O{A8GmqJo|U2%S5e)Bza+81L=aj zeA*F)5Y6_JsmQ5ZP!ct&Cy2eU5$krU;wZ;zu$1x!1Ls<9`EamHqa3dSgbqL zfCd1b6u5dG%p&&uSHp`-24OzVlw^S+<*d=*%kC;GdI;KtbEM=AXhT9{sZRWYBI}1h z1A2M6c2`br9)?wKAqk#tVuId*C-LpkSKHur-^h=y^@}FjHjj}nthIODJ)ogxVhS5t zuZcQAMuoRU`R4n4lPwI!ZT z&DjI+Ag2V?Ow04n?MEy{xF1O_aQa) zUl~eG#}xQ0SENO)pL9pJ^SyfYo>|6|AG}zapt7`q;r3{ua!addgMAY3af=fQc&njA zKi(cphA6S-q?;`WRalt##0C+2%%(9bk;?D*mE_a*E`+X*I$qq3i^BvefQ&}oL`f^N zal{)f<5bdDVtE-h){y-GnXH#Ytn5ub#MBKZJe5l}KcH&0$pEs9q%G^ujHa*m4_r3K z0I8I0qAc##5Jt!6y$!6>=F0H(SL@i*P zJeER1e_d6u_|a`F?kO`GL& zNrz^D|FC=H%I!l73%}rVr&wNAZ?sy(P^wbc)4|NKY(kttw0}2JIW8Dg+Bjzg#OnYM znRRT2ICNA`M7vcdBXXj>l@*Wy^z^x3@BXN|X?v{!k}_%ac>VQ(y989#Vf#mN%NLVl zyt_OWbTG~b&R0vR`@U{Z6dki@Y@~kmB9bf-<%9C_C}@b>Bg$kg~giqVF&_ninw&!jnETp0AarllQn>7&3rx?PEHzjJF+55c#HXwtN1wk3|} zo5hH3%5SEki)_Ey54ouw{c6+;Cybr8;i7Pr2~obJkox<0kCqPV$&3l|RRof#gX@y2IK z(gk)fu(6!6GpoBSG3dnT0TbczcKB^iy8=EdFybJhu>!MVqD++Ob4fS++g@IE=6P)T zVTt%x5FA2KtO@cB;GAAIoVujq(a?k&n7Q)6_~LQi_qoy;A2x`Nvmd?#TPpZx+;Ja+ zg1`|42?!nuR^GSqVZ&qHmS+54QAU4es09-|Rqv_d5Vr|{DpnCJD4EYksi|r7Z5SO2 zB&JY_cLs-F#+Rg$wOY7u$|yg?(K5tk5|9#sn`dBPu~thisin8)`^#ZYNbRGfA0^=W zNyW7Au0^?@TgYYp{#_W1#xzb4n3#Ei!^>pM_|lD%HsZs7eG+;|V?gAq?|Pokck0L5 zCqC6e$tNljioAR3Sbc|xdsH6~YmiGL5pUqQ;Klwv7?UQ5h=&%=!8d0=fx!3+qz?ti zD#T){V&ZIoEeZ^D-<^zzp~TOJKj|d6cgg&S`S_2?&Fc18q4J+NECKrph&9l#wtiW4 z+HiqFsx6Zl5EMDqXp`Awt9~_e}ywsh{6aIW2ZlYOdXv=H)U zCiF(Hv@Pv1q}|?rI~Msh7QE>kqx~eiMq>Wy&JLZWXP=M?z?<3jUdZ!!`QEKeU>i3V zM(2Fc)`crrm!QzOeV?Rx@}-@~CWdcr0e{Z&Y^2a5srY*(g{!u#Tg=8=f*Jf0PV09E zX*cdv6(uEggv0K5jg9rP24HsIzoqpg6{;2s0IgkC?0fiq*9$x~HJ~gI=s6vi5%AGB zr<;r#;^BRme|uJEZOuAUqiVl1tYIS=YPZR{zi+t}qx%O}&?t5|N7-CdujA!VO5R+Z zDriVnkEd2PNS}NWCbBv`AJdeRhp(5mr-y&F=MerVBcrDj(W?fQnnLRFmkqC3jSKnh z{TD$(_1eSDgZ~k_58st2#1-g;+O6Mv{ygCkmu+@obaIPO0BdXOVv3p~x%J?~p~TkD zB*^hIM)XfnYFu`!sb?KIf4I{5FSTQd`Hi`%$0yX~U4BOlxzI zBML`rZy>!p`egL~Iwo9Yd374zmC9LT#g5~tlh(WS z^WKCXH3X395W?r5kd(<_JgWcp?c4E-vX|d5#O^#3%Syq$S3$*&i2rap*K{I^u5&{_ zedb5?$w|9Vn3oyJ+=tGJor^aYBC|gWLJnqGCl}jc=xNK_juXJrb zz5?WEjYaEGRW!(I*1iO;E))mqs`+PG=mT-aak^?|?9LU_yYqi3~D*~@<%UU2o`_zsbKtfX8Zf+%1M-paI4Gku;E=jtwbs{!eGaG zxI^Jl^uf3ImRooX<0WkMN+cLgX(c9}u)8;SEdg5HKZp8vlh>r=%6>Z?;QQvDH)`WF zLmUf_Gc`QabERx12#2c^3Q@>%LelJ}9m}J+<(_|bW+2ZK8zN0Ag6}%5U=I1+{sqYtFMnlcib?T8#NhnZ37swzA;FsgM+}ynrOvq}8y+H&KY3)? z&U8Gff)jPmy-~i?YEVKT5PIpKZg~VxM)QQlZ_jLt#!@NICi-5U%oXPTgKzQ!qYI%_ z%Pm@HBVEnxnQ)*C0761Bu<0=VByKMV^MxfirqV~GXBg{GjOMF-z5#UW042E76FUbR z8!M~qc4UG0XGn3RPLkdTB=RVv%a_Gede36mxu`lIRvbetp z2lm^vC>3A=Uj_gVPV`FM5qpyFI3_{89xcj>~hgo2Y!!cux=($m9r zouBn2B6@Qod7-Gnc(NQBZz-@f6~3vm6^kI({^Uf4Eu$?Ermow z#?}jN^*-8wcL+T_YSUxWFuT4t<~2f${!{lOMr0&*1?v9(t1QlGD#|a_HiW!a3VR{$ zDwkKgw-KK(kpDX%*uJ7(xv?wEf4A)-zfXTszj%{#RRCQKW{PN zC+&9cMq<|W*b;HNK8uP(`~^w02{uykBM087P7%$g``e9u<>gNT9z)hbbY@b8k@;w9 zMgoBlE0Vr`C^j>po)2}#+tF6bG+twq1%DbCAlj00uBEp9npcO( zd!qqaTd;Z*^asM*d&aD}XGrBYfitzRK&^Lmtw(!HAt3`ZGbse`X3O6XWRy0Az5Ynn zzz<1aO4%L|78;)mImH3bq(XmYZjOEXk|KyD=v{@010<%_XVNMV*9JWdDTVNq^3`AA zu>W#?_bv~y;STGf!sxd5>&t7&9_=N~OayDZ4%)*E>1g=jy!iS%`hq6~{w{W2%#2nn z%-apg%ib*l#MprU$APapR=*H1=$9HsRc$$bE9 zz=awvN0qv9@Nfhy>!o86l69PZ?};E61<{S}zHU|lwo4s5IQRTMy!irA4b{?p3s>Jm zle2O!=z*vX=Yr3Rt`SXH2%wVFM0LMRla#}_JZ(2OnSY58NL&cR`Sd&#qR%a>sR5=^ zT%9X5o3=PMAw*7hY(7^fjvdv`O_Ko$BN1+n?J zH~!&L8v>+9fKf2969ehDD23?3Vfj^r{<>XOkqomw(&cd_`&tt5{2vy=+bLNYE6;{Dz`bCc9wGK&7 z)t%?S_9jf4cL0?jS6LmwGYoFB?r7wDcX?P?p8)RkfywA2P#l0$(ZNeunVNYq-pKHa z&u;POBSlD*3?%*5@cQ&(&g}Z~Q>Nlir1Oi*Hhhn}_c2vf&#OT*z;R{kcx4w4DWgP0roORc=f>e+R-m?g^O}Xr+~ul!bl-G_4o1owey7TtGrPHK^FL z>wThmC24&&!8VgM8xu4{$#E#L)`;PB`C1}26)OU@N2{R2CGHQ6^rT6=2!fdSQP0)J zh===SbA~i=EAjRG7R%cR3}fSe$0MM6NFATS6`=Y`_5Hs`$4fp*Ohe|A?D?@50A0bY z!qD&}Pb)t>kjII#ElB>G02hB+L_-|S1Gpw&>?MXo;9B;Q^sYC$&)xe3ZdRGm(%sg+ z?;k{K&$7MQT3SkJATn-prja0cSYi6LkGIs&bog=QY(3VP<{G1Yp5FOCi;83dUXAaN zsHgP9@=Ne9c%{&IbbELeFkz1H;4hmbm6~u_i|&(v^{UJgxv5b!+~lmh2uvIxe>j3U zVd@b&E=gxs>daA9_HW^jFQ7We=CW11ceiR!pfkknW%ZSPJgiNS{bB0tF`$CNdm-^8 z!04iPQTKN+p+}b(E~^Mg=J&I&s8iWIurN@*gZ8LXFN*hF?^Ur(Cpw%6>7(n&~>lG3Dlv3IA5-Mn4b!u zzm|~p0R?f@DxQyOsqJQ&w$Qku!FL!3Bd0K+X*GJT1d*iAZdCDJ%U@eI%UfMmIPv(xc6D6q4$ z2TUM76uXay;_s9)lS$MvBr_nQ0r;MFeMTK@yB`h>0;07?`6rp$4NVqy(nc3u`^3wr zeE=6&Td8dNdvm0-?h6*VUgeA^%>!=xUjTv~9z%A5;l?WU`(Oo_vbBbh?*(XAy?j;i zAepXIpwa>d(w&iz%U71+Y{}7L$3}-wX32;_vnzCyvYn64!lH9-`$I1R1DhUG!}4qN zK$<3~?>c*4b3?SyU}DG*iEJzRZ}$mMRn2=e&uKkPmL|@J zR0?C7P_sz{o3+VXevpob-mz(PLc-0|+9!jJ)6e2oNd5n2w#sg=(8a8n=!l5pzQ=cY ziJg0_db{LMaFaRC4S`{bL;5c-lTN)Xau1ndTtVS)IUN9ztQ4j3XylB{y_c7RxnDK^ z7B!{@b{5f!&4fN=@I3%1!Fa_>3Sn7=pND=u1SGhww76s}QkX!_t@omDvpTk1caNhxcyBQuf5d^&E)O0CRjuu8c z-vV!nrchFUAk(b&Vxc@wedhD{;%U?NEGmxXGGrZ4pySY&{hd+>r27bYyU&7*r7seB zj<877;svZr$S58rI@61Bpd7BL=c$p4Nc(_Ynv;`J&-ZwIj-@&_4vCG;qfN&5CmILV z?c>71Dk}?3+0A)$YvA*mqLo9Vavd@M<6p#VVtr!}RQCI9%^C1AR{O2=qM}aQuwDiT z4BT~&Cz`*d-4+-A4UtRgp!Z;Lj#rSe9sMF|hvSK^TP|A~b$+;sBI(ifnKb0&wQ{ai zZEq23D$~q&b(dHD{E2W|W7nV1);K69IOTM2O>ARDfA{VF(bxLosY{TJAN**zT=y3+ zh|zCOeE=mu#zzbfT>fLBZjZEJIf+;dAPoF=J(&PMP7ISEPMw-RxQ1zn+~2h2DDGwQ zO)M`{R^)e+Xhca<4%?Nm-hW69I8XesPs|RY7G0_A>+82}RV3t@8yn%O&5anx3wwSJ z+AO3CrU%UMrSw-Vykus^f_-9lEl>XXv5@Fv@aTe;{N?MJWek+2Utbw5Kg7ofQq7DU zw%*sLy&-9|8!h{NhtV!)QTxWbfN@a`WjTb3FhBsm7hf<6bS4hl!nvO z*L8XYey#R+0DflAaXurSpsNeP&qy+m;HkkhquKp~KP=cIBiQ&KsaSV=^{3x;iZiIz z-88hq|D&|mIR50o?$pJ9QY{OeJm%i*U5$Gj@&yXef18<(YlO({113uL6}tZnNATW# zu0KcQqU%`!6Ab+2iFWE(-n-OEQNnrr>^qAAWrn1UN`-{XKPTyg4376`JbR+8hkXv5 zC(VvpIdNiL@iqN+yY*;*FRskZA7L51Z3R>$kflBNfeH#?v!#8X^^+eW;=KN}NI8Ys zfr99{@S%C1#Vk&@4MkKD3m)@Zc+!IhYXAC~<%cSC{>nh;z#_W)-X5UF-7h}|f>28L z+_rN-nC8+AmmS3$&2FL|e^zZ<=zYCJ;s9Gs``f}ZUSd|ZHV%UpsYM2>#sT)?^wY@L z39SzpXq&M~#IAa>isXQOhrB_M5c$#a7Paf#mUkFpqTXnVfRMN?j5A*GhY-nL}~q> zB#T?3#Rupv=m{Ot2Q4azP*)naN zt(iI3LnlLPG7rTE!2ADzp-{4x0-jsHiaRS)O$!gg)h} z#t!bKgYOYPRT|!$2Z6E^)xKZY$cC8*{c-^p#ar;3A!}FA>)DPNrjH_GVq{Mq!T9W9 z>Cxfrc#|OGIPdx=)&5Eb@c4-f-Zvd58LvQ%qA$N~zF!Cefl$h%awzb5SX%I40kL{z z6U;3KDDyNJAN>^4&=@OLLBQo!Dmnj5tg|?-d`d+Q=9t=&v4V0?cF)&1DcRr3Nk}-4 z6plAtAaGzgNh~?gHSBl)dR0L;5Fx5}YBnEv35-`zX*nR~Q2Fsl*XytA@*8C6wmc#% ztftTRDuKV4to(hJPt^3ae*|qx?T>L^OEDY#nZ*t=mnV4soX}aqTks+2e8&qc2#|)E z4CF7f&(v-%nwaHlO$-b%zRC3vgyBsklhec2HsmmgVYD;8aL&59 z6o$|@Y|wpIa8;R3+-tnbzb%ddSuX5a-AZe$Kfsz|*&E0Ho$UPU_6cKBwG>{L=DbGc z*GWlau^*P*l9x4tzOkam?Nj#f$hxXQlB|G*aR*v_r28_6q&rlG-|L^wB+?@Wa z#ZZ{>DFhB^eA7Q#ZpER48O7r161gxD)nkM*-+_v9OUq%(9|>S*2Yt0x1PtqNdDQlo zh->xq{+8!y^FaXi9gws+p3U*s5d~CL-EWK{lz^6LIZ>NJHm_!YCF5C10W!ou!y*Q( z03bV=90k6dCVl;IdKsp*^?Yu%UHatgZjBRBZ-tr147Dd=m$23v0SqI@?~mE3R$G%( zQBegF@zj($WQyz3@U^x=6GcMxSWXU_>d=_1C2Z0%#<``h=T76rg7X}f=j&lxrhXBV zi{>zXp-Ai}{ItLC-|}v}m>nnKPLw`Z2a2||z&%Lk7c`~@ItS!)PHwQg5R{eE{T@SU zWcY+6nH^i&$}c+SJzbpHQ^KR&Lb&QEfj!3hy7_4AwyF(_%HTfdyB=RGsGZ!3AItar zd`JtUrVx?S>l00&o;Gt!tSzkRCO9ar{XmBw-v_%Rn0to<d%eYz=05iVo^5=5J2uyD?BC7kQ{V;V*r4nzZWqIN zMoRUV_mWY-wf;jtiIC=x>!e2Q{a5Vy8(^_;sbjf~XJek2u&hWK^_FI;!nEQqJvG{C@$I?zkQBl7 z{NDmF%ri1FyiZRZ%^R=mJ+!}@wd)p-9{sVaRZ3ZTD__nNzN`nE2m)r7qswCV8+8gq zehRFMBY70OpLAbrtmlKd3Gnb2U~?%ZW?QM!{p9TJ9dA^5*bSRD+9#dI?pyh(|6 z8;=-zx-cVAy?fhAX#e~DF)&Uq5BsV&3u+ygf?kV^%eMygGI0faMwGCP8J?QUAPo-E zzLK^F0Z_3?^oJ{_077nrm6dZYU;_|lod1)BU)1qpoAUc3J^l5*B3eRpEbIzZR`%DM zE-ShC8~Yc>bOfxp4PqpB9Okwmy1o^jR+Vxw&@w|mQEU{R>|h~e7L-gI)izUjyinsz z?wnx-7gHSG51b^{PM@VmZ;`F~IGR_Y)F-)41N`SFKAFMMZFc20>yShr>h*ZP*M~`p zR~^{_)d!JKjU=AOnf(ql`zNZE=7hl2V^r20Y4~{#2AP9Vb&I=2MnkWpc+ZxDr(2t` z(~}L9sVipKzj2WA^TBROm|%g793*4l^v56bBI2=KpuzKM5&+ROTEzwrm4<`P1IepH z)uOlXBmv~Y9~Iy9-d$JO^MCUEl0g+!KuCtH&7KhVE$dEl^UYr^t_vs4{(GUpJe*K0 z?rB5jQ{@vRudJ-B`9X1p^iO?>5=p%EGwjlD_7QgLPl)d1Di^L+Ed_4|YVy!d)U)9? z5(9f@rkC$BW!Z-ha$II&>x{yWAI#OOqc0J%yx*^EY&A3or_6itHAN5RuNl)FvwCa4sS_(&S(8O`l)p9qw3R*naye21-eE zyeRSlBdy8@P|-V?{)%JskWKr4guQiGR$KHg`hgOHAPv&pA&5vwmwW(L^STn|}9a$dE zx|+S(+A&d(HmCpndy+(q3kUpiiK!ZfjEbU}B1ssqG+({S`R^|cc7qWNF=FIV8OTrQ zeSnoxSlO8Dot`1-X(`IamMR?(9@Kn;Zocj>qhVn)&O=uiqWV6mFsooRyvn@Ms`te0 zPk<>O(Drj$hPctQF$~TIjP~5#EP`!2^eUijeN+fQ3`xDo@osYOnaUCt|1WZ*SCWeskQP zmsy?3w57-WBuLxrXkY2alF{wTZuo%KS1G=Cj!zPVbtl?EKU#K4OSLBU!77S zfAngo=X?76HRV8-W&~&&R#snmnn(!Z8V@p_<$L;iaXSt|H6UDtaIPou+VgWku@;TJ^a*_OsK@hV=NG2WvsJ{EDWk2#!zMzDsbGY_cUj2zT90pvLlP* z#0MwnseN&>hf6Dj%prKIUB+4yPc{5gOq{6jv?`|o84L*048UvgVskk<^CTi6DS18g zqrRf{XjHEnG{-Z={e-#8A89Usio?OJ*QlN=goov$LU9E&&@8j2O-;+{eFdk&s&uw0B_<)<-Kwos;7f?`)Hw z=w_gb0zPgI`@2322v94F&&Xn)ZW?_rG|)=;dbp}k7*FmZF5P(>T{@FCfR^m`;P`me znAO8M&-)K&oCp=!xNEmcl*enE<2!A1Tpw+@aF>`%%Av#bSY~An*eK~B*N|4H#>Q3u z9Ck^2d!^OS$v=O#ZYvgTq&0%4cCzzB;^pb?Da4kmt9iZ8lLcrR1eK2F%Y3QkkP3fxf z)7%V~fjx1;+fs6dWQAk$Zv`HmCO_5rlB~tk8gT0)Xw@kTef)$-lYedc-mV7Zq1CXiWziSlrj~V+kr*lqW%QU9*Xi>(%~deD|3b8~SfR3xMBMeV z1_E8~C(Ht@ao&`3a}x?D<@ux4a6V!H15-bI(5Md>-gH;W4utzS)aMZ8JDB4WLWDvx!zY!eghQ?0fdav;ta2I zUSA7gVA1_5A<9i~FR_e;0nU<+r6lD6&F)FySpo8YpNI?C05D6!M*>M{{|c#pKl&;I z7n?iZU7r7s;i){ls@Lv#!r{r5 z@tfDXJ;wI;k2-z(vlVJ`@-pe?b3enpuOI`Q6+q2fuKO{cJ|^25DX4!+_VM{yRykFA zI`R{*!c_~0__-%Xaed?7^OwCEm)o|u?KHbgl%q4phK0W-(unAppbDaOJ+qdGsH|QK z69%2|gp=y|!g9ky|_WXFeYhxr=;qhYt4M|K7A67D4d&bKthVY*kd2$o7fP&28BJS!sx?N)4 z#hI%5{e8Gx`Kzm6?>+`ohk^HttuOV9xBaoEcmJ<57A?~wb|7C^{*D%s#>9=^L{;9L zvwjl;y-%j2yiKh{*Gl~o=Pjp3)+HXj*x9j$i;pYKm@3*z0AUH53byqQ@jWl6)Z;=N2p{7M%ZI7p$v@TN%*R<5#B~+!c?hv5$|sN6+!g{!p_!rH+Gsw-9kEl|=HNTK zTQeJc;{vocsC2(WSvFQpdBO36PIHiXSAJF6;KGe5fsxu zjYnHa+vb1AvQ<)@aBC9q&N?OJFwc%I4cLF{!yq+CZ#{tqD!_Tom}h5i=UeM#v9sT# z6OpO15PbASP<4M)PqkO5z3Wep`{<_dIf{rKrR%XyI82g@XO{FOSrPji(F)`6_#b+F ze%P0qeG8ZsORgvs>&ct8btd~$bHXs01b$*VMG~KEbg({o^JVvY=)46ZD|DbVq^1M+ ztuX&{hmGvax64WQw(M* zRllSKSbc&3srO%VLc)hyGiGYbiOpEkW9Pqo5k4ahSJ2GEyWBJ)Stxp{Xc-e#Ba1c3 zi|2R0FJ><5@Wj=4t^atlTx~Ka{RjHSX1R*H&Ry#%W=Kxl+i(AvOvOO(U&tXD$k9h< z%b&j2Qy4%mB@2rp{6x&;+QT|SFE1Kljg*-59IUXgn=m}H#k9yNJF!s6GG-a5P+-UW zB)>o5TS1xnr%>3o*Nfft(dK*{&?spmeD=BqJ>l*AwMBbg{)I393r1{07H<5xJL?aTBL8^963FTA{+cmKY_eOc(&tF^KyiQh6EBPv zTRh*a2gTM?K4!T;@Z;%TWy3@SWp))nq1B{asCex1a`Ar__R)Y^?S7fv$wIJA&}|5Z z_)|H)8k4oK@I6rDQEgu+ALE3@c?KC}j7-~92(bH}brP8Q%3DM7`@24R{QMF+W{*_5 zyO>I4v?e`{)M8?9bt-a6-92hCmF(;^UR7>n%X|z8Mgh%x!|KAnN;z$8d0$0!m5IB2|O?k4T2b5!23Y> z7kjop<>Lp2a;~&7s6S(a0=rTk?eTZ+^LiB)SJ8~F2^MX0mP!Xts|t2%4C{3vM?;no zRY75rnNQTfi%t0*o%CVR7E$I`Edg1~K-^1kq9GcRFj0J?!ulX3PcHp%*O5y}$-j*M zyRo%}ugA_ljK~d~+r`6DfW#4I0{kZle;goi{Ec$v3#c$~MBl5;-x3%k#(p7spW<`n z@8+GE8tv0Y4A3W>C8fx&_)(A4rnDR>~ro}^SHvTRMvoMcoYjA$4}B<7wfg~TdOxg5L+M3_k*1u z*P(ndUxcnJ^AElGIyNm@bK0k&na5{6rDC)Xql@sha?mFg&3vJC3nD{r9hW7Quj$xz z2@kO$KjRJ%(>N4mc;#7-_kP_Ffb=f2U6|rAUQGzY3Mj-)V4kxg`_gBjp_Q^B#&&9} z{Yfiq4P2TFX_hFZ$MHZLncu_`e%3vDKom;nR`X9I!8P;0sO%a}7 z)#$Mc-38rdJ;^AzFZ25r%i25#Wsq$6&68=fQjbdG4m>ZyI#X%>j*K7)0Wh&mbypI~_0ci^_1Z#%DN;KHb37=^$MN7Va(P=OH@ zkP~FZg_G(1Q7AM7T(7kpyz$Of=SV1`<8cIDBqqdjQvt5_JXBIso4zV|Hz)V4geAL? zIjr(uU+rsTtc>5y?fv(qlG2
    A&OL+)DKI+{N@0$oS?S|}fBfBc?5mWe?fQvBw- z@xii}%g{~K{=%e0{CY>0%OjIeo($BrioR`}pzEL^m3SEjUMRKhitM{RAL~}~y}9%9 zjKtpFZrZ*^P*daPnEsMU7YPb0Sgn;nQfo--u-mByWWcJXR(50Re&0AqzI1HxpR7Qe z##C7n2#7cOA3Y8U2ryoytXj}BfvlbY?c1rUfh-#G(bSVNUgP)bS=lo3zi1YcAkkKV zfu97z+9-zg0V6Yun$GJ_G3n5P?=!=xwat5j9ujkN)Gj~B>&zXkNynM(*siSXx%W(M ze_+$OB{eLYg@ulj>Wg4hMS!J+Z=0MXe@+s(N0V|q=FWztH_2g#Qm7hf8JU&%+++6p zr6rq8X7csb=wVXXyUmSMHOEqJ&OoVqZed-gY!9AL5~_rY%Ii};Nhm3|6som@<{&;X(vnjht^a&Vxru|X?# zgQyD=Ch1@%6kVIO6RV5)M*s2vy`ckRP~ zW?{UmpoK)Wji}I>Nc+5t>3@?pIH1Pt+U+ISW%V6I{V`r4U`AC!zNwoKl3Y490Ux10 zZpAsA;Bj6?w$PU_tZ)g5_D2=3&Fb}%XtfFkSSiYLpeJ$7m!^6J4 z{n{JOqss`vXQ(%sl(JuvtJ)R213goUY@P-jI>{P1`(~I6Ko5cWzw4gOKK~dXbui%@ z<=z<)nnKTVhHrTA^IV81oI*tE{6y=Ut0_tW1!6;Z|2EliFl6=MlanXs=o+7Gp1427 zv|;0Y{n65fAwMtFVbc2dVxW$vw-gR(63sFUQtj-LRE$qGW2{A+v;kE_j&<^(zKP(a$plo>!vDO27e<3TzrpG z7@VAb%s3;`BG5Fk8oRT}F*`pUD7{MAnPTEOxa(`)wfh zi9#isOC8DKv|h0Tn-#xmnE;ml6I#ci@Na4LK&_yIXB)IxmDp_Q&sT zb$v2Yw2`lVn?IjM%oZd25lSf_eluyMhkOzzPG{%yfs#14`kEynp=xvN?X3Z+*I&BW zUhx-SE^)RgW8OE*iQkza4h)=RpW6*?k-74C!wprOt@MfWv-U<>v~+lBu2T=Sk&-^^emQ zshw~e-%4@xXs6Bj;xo{zvrKQrb8yIbB(L+pVE|rxxoGNca zYJJc1p*HFxslnl!Fx(chG@vsdw56Tj$Ti@^7O)NSxt>~dX>c4b(cydG@xV5JE2@a= z56`~oR1M~33n2-l8>MG*0Eh)Fx&J_E*0WjKY`jU;Pss6`X8h-$UQ0TqKg25xW+yTm zi|#ymmlqC&Lrha%0UUp!{ckv=w?UIqiNRNIH~&{IfCS58o#8h2*57rXOh)&+{3YK~ zpNjqHv0lu|MhWPTJ<5DD-kTmeQ^eVLbuvXnd~0J9?delha!b@lS7q?r&@*jb_={7Q zRTIP4yJBLG=TNxq?Tu{z#;{u1O_$*c-~TV{t^qZ0GZ_M^3noL%-?J1I2Ll=DCLitS zJ?;rvtii*@W>zU&*--ijy{C#SKD6c*V$~Vi7{z|egH{AH!jgUjlP>r zlTO?<{P@>}R^a@z^OKlQ%9f=%8d!=-3(a@95*?%?{!Vp!>n7BgFVt*4f|P&g;_lYb73-PPR)U>ikei&vDg~Wght)-`XDs(K z#akg#IOjM#{7c0r@mB?3eA6Xat(BL)(}#HTu2kqPfRR-AIVPqr`##PK3??LCSsS>) zOgSMlF&G&^m7t_^m(##B~?^2n)Phw$(gfL!*1H;ud%}1{p>VItGL+ z=@L9MmFBr02>IB42DLY%Zrr*h%(^+H#c}7;CpzBcrGMg0@})|jA20>B$N)Gh&#BVg z@}{6TdNvDf2UP5ey#{baeh8}EE?j}pti~Ph1@u0KVT}Vb{Q46z(XdT!&)w#Lus3t6 z{C-E$p#KgUHK)?TU&(t}x;Bc(L@Cy~&;2#rsNOz8p4wA)^xIJ4G1IcxV=hA<2(9}_ zNafOM@PZc9jym%r*+@n zGr^8;)BQb|!DW?IVH!sOfeYYW&W}D(dhxfkU*M1F=h$L?yxel5K9TPrO*5@r?*O0L zAYq}IxVfFbgh96@S@Jaz@oW6lC5wGi&pLWB!*JX>!@zbk$6Z^jtooWbRsTb$5*jw^r3Pq^x69|)8z3F*k_M%%}W-AbVy!QT|NtjhYl6+#WE zx;oNRmZtLoo;2Ep%%4c#OAqPGT8>elyyH@kKZ2G4ffUG>SJi`LRicRr0W>s}uy9)a zLfzVK)OS3uzA{xz=#Gqdy{;X9r_kz4)y$v|lX_py2+QhxkzfPrq4lRpGb2k9XK1wT zE&8Q*baUr_{WXcQIn#$ziT^V-+-iOtblla6I;D)IFU#vmaHVy=B-TS$lH_U~Pqvq3 zzLbiio7PS1l}4-oTYer@aqUl-jHZrS!uiuNNQR+ddZ8F zh!`Gqc@-K7pw$6KIqyr%Qvp@}gamKel zTT)+RTL&{pV2(t88V0A)?1cQAQ(>e<=^wrs8Hu%3PfFTlncy-g#R@45_g+5HLoG4C zw{H`j|LW+g$)mp!PdR_gX&K;P-b%zQFL$r~N^TGsPmroQkTYm&fmcBqe@tiITRTX;rRzQvA1# zBu}5>MgI0`Gq<;&JcAjqvf-aqvnwXPdi>*L8%TW*@ppkY!&DZ(f4g7&2x-|!&GEoi zkaLK5J+%DLwmW_`S3!@<2H2BgX>sWAyw9;_f78t^Y+B#W(l6o>JL*=ud^fn`HHgSa zyvS{l_O<=Bs5Pi!>^s>UtEhNq*acqw-LrfCNBe@eES~)NM=^-ipgP0!%sLlDG*C4uZZ+HZov5YxC`RQ8m>J2BmxUV@h_3qnK zVOUNMc|YW))R;0laG$fE+h8Qwb#!Z7JEJINS8(qY{===2sLB_XDcywDaQ}CHB`sx8 zjc$US7Zx_j+UNGA0fm@TSIofScyZ@$Mi~z}GwjgNN$$NC!lQ=RL93+_bHCOu0~yli zGuVu^Z#P&K=&Q7=DY5ozhuRiC{KR}sUf z^znQ}Q@)V!-yT}BA5y5bW4*csX{9_87_TxiprRJZ6unB)0s83c*Kv+#k5$Irs=(NA zW@6~W%h@YB*6fQ?b7SkXnSPw-tc1muX+cd+U*&8eiR=sh9GYS>!A|BsU;ih;c5>-N znw2q|rxSvxPQ-ak_E|LWPR3K);V*zOxX(c+3FSpL#PzckeZ;8X&Bl96rOIeiW$qD3 z^oIdZwyis9u}@Ax+1N}0@z%<`rV3qqpw_3VE*PbZ+Gc7qgO=>yn@;8Z(aWTyRAlQt zQl0NTU}TYg>rL1?wb{|p-zQ72o29DH2~BQ>hu5rrF0GB-K(WdE9Gig_$t8ZngP-?S z3bysx**x~+fVHoVCDx2-7{LmUE%Y{R^yZ{buS%Q^Gw0?seUT1ivyZ$c3DI$GV_a_a z`Npj8+Z_;G7eOAqm&G;-iKH_h%_72wP_HgMWeus9mmeP-Oorp@wnQ277+3!xw>j-q zNb^fJ`tU8Iw!Qa}IyClaohn@`>XjX}%B`68FZ)@jyR1qPDbh-hcWPy~LjyioT>Ck6FeahKKt@@;vRD zSN1wp@Y{-z$Vg~x81h(LTu_zo%%bvnXyw~{S+h@FT2#}qgQ4}EidVCpiUXDnYc*V< zPe;hpPp`1rN#*@`!p_{0QfQ(gMfbQX>^;4J!|?I6qZA(&y@gG4a@8 z;oxw<>4erx`B@TES1|YjI)fBoAK_5>oNN&C!U)5~rD&7Y-s3ps^>v$D16$UzeTmR3 z)XPq)e==ixzwENWzcbEwFwACQ#br@JX>+gnKWHu1?|6^t-7-7+oqv}2R=cU1;b`*( z2FO2iEq2xdqi8}}b%p!OvUs_kw!isa97n}DUKMe7xFZDL$cWZ@z3$DI=K4&pm7mmH zC&VI~1ejGXvogWQd)zMNIyssESWgfS9e3I#ikEyO?zp^Mm_=LFr1&*q{>)Fciq?A> z8353?lNorOm<;1aCvAI<*YLI*aQtt7weNv;c zRNV*3hN2WXS{NTcZEsKU@@ndfnY9I}zuXedkUZK}gkcf>6P{O;e)^;wc!@HIrXPL- z7UFBuTNqXUTq4_Mn+L=ghmP`fvPHvUo?#2W)o6Tq0}JaW01eEk9LYZm7<-)@miqOU zb11At5*ArrRjuwv)>(R5$+FlN{ZS7o*l!~I426AZXNFw7?D6nFP!ROi*T*V)n5CIX zttMm}&Dr11b$@BekLuGc71^C}sH<(>$N>g1Ij_<=5m!s)* z@7aOPpC;1nc8$-Y&7-0s-9?{iq)QCG?W6jrh!Fge^X^O@t+Q*}g`4a)*7}=A?GB`i z?kt4z7=)`d?FQ>j*?&V*^KKszlcE%@-ohXFuEx6cebH*T=z9EQ^m({N6x~w3rg1ZO zpJ?2`%o2vEH3`OPS8dwAv_Bi& zHI`-OYj+FoC^?%EUucrPR?Jx1;l8Ld*ZEU3UTGAH>W?KRc5FgsHF{IS@MXYAz3<)o zlTCBiKDN_Clbt3N#ah((_|Ko~?D#KYrXRY&L86lU%Uz;xqZ`%73bf)j_Q&NwhB$tx$- ztUU%gaxvXTpTBe?Zfbr9Ng*lrk$jY2JPAaIsnWrTz%rf_tFW&X-f?*JSSG=7Z^jGF z>)h$1yZN|vZ$1AT0q&eu)1<;Dh0r62=o!1U#pHNU$77WGS#PVul`aXB;=BJM4>2)M z9fj)iiSId%W6{&sg#MX{TAGjL3kbXw6Eogk#l!VHIj>vHNJ;05SBO;m{#F|{uei88 z@3y;S&%eyHe)P32;=TIzIRzY!yipNbOeT8zlhN}~e?eXSFreqr{UzUZDz@JX!}=y} z+pzijMUFcs;o|uvq}qL@{QHKTXe_C(3qy)w<-*(HK>qHcE}4lP@IRHPNB$>QkKO1t=s zyOKq1*}OKO35gca4DR*&xE~U`v#9>)IuPOe*X|&l zK&xm>W$CL2WV8l? zv*XE@_gK@%ZU=2HopKQQni>(6a7bsEM2Chv_MY^`a$RTdPro(qNm+Zu+cWU%bdHLO zDl+<^ScB*VUIEc;kFA7^Orr9VO^_l39_8g+;Uy0hQO>`F+YL7NVy?2$pQN%ou?F|B z+bss5T9$jIm(@6<9lF1Zq=*d(!4q_l2|bz9N`n`FV6|1RU0-*zsTmC_zc_R&NtD0G zcXs;vq0SG!esHW=Cc7g<^GI|sXdtcd+K{9}p91>@b&CaWlf{EYiQ{+TM?xm(q7G3z z5?_CGth?DC@JaDpNZHT#Ldx;;lV4Dxfu2ZNkFs_osVck%JB9#D#ImFrHY ze+v2AIv!10^1*&TQT7HRM%Qb9BiB-!Q{wgO5jQo&#mpN?$+6%C2kMVXwDe8?1X(-8 ztkeAm-O1B9#Qb#jN9wQCWMrI_G!xKXCZJWHPdDsH$6lYI82@DpcLU_)dT-oFbnrMALfFiBE=b zvLXl@{v^3Jw?NJ(OS^$_YmF0Y>*>CHWe6vKuGTy3pnCy1;RBl{qEdAz>8Nt01oHR& z><&z6JvrS^^{`Z%Yl+N;yNXJsG5Br&u>@>ni?g7#?~_OMX%)4>76H{nHxUR(duff^nOnc|`;j>1c$Ex_VMck-Q z8k$tB-r3r0?%pZ4IPL4Bs<>cN{*D?Je(jemBXg)#t)?H6r~V-%>5%kxgFPWB4+cYt z+rajmt9XsmtsE}BbFN_-j7> zcG|T65fajoc4Rw;&-Lmq-ri~(_Rox+d~#aaJ!V3OS*D6$YN^QRON5WldUeC0Q;qzc z)rn#d#J4=+0~mdW9rDR8^RTj5j%fVsebXm;bFMc=W zIFn9nO}KH?pTn@zxtfs2oE6)%+xhBK@WDy2_JvOe8F|D}^AZZek^-;3^G+?7`ksXg z1G=p4d#g><+-LLCC^P}+x_b(Ss82|kq;fg%$+9G#B@;(mq8;FcGa-g8B{sR{mu&pw z2O|s@D9MLsiX{F>){V^WX?o24i>yqs%96eg@{vr|`-eJXaA`+R@9?UpnSS8WlN}P8C!*{9`(Pqnw|NNn{WIGDcL`s5cp_(K9{?HDSod#6i2f+I|?yN`y84qtZ7E z;rbGT$)z1B=l}a-X3TQzt@q{Wk^p32l5^=|Lh}pA_>jm{7T`3rw*NYpuw%sezWVb} zrpnUVK-%8XQLG5o2l=TA8wy25#pNi;<+wae4)|wX;qg#|4*$8iKmuJr)fGi(R#;P$ z)bi>o10$o%4yz0`mxu_(%Tk>kGMP7Q3=B8c*Vp^))0tD}ps79qF)?bi7&{(07Aui& zqw)0_2O|qhT59TI;n}_Ou40Klrrj^^|LI8xrtv2p zwmM678lGF3irCrB*49>sc3KCeyLaz?erQXbnwGW_CAB;tcCmGz>|YLvBK@6D-@ivr zl)g%XBuxi-x&sTyA$%`_dW8!r^cf^bm6Vjgi-G)!7f)E9o^KZJ_dJ~IpbG3rD{dDZ zxK_q|XHfgrWURmdE~ckHPs+&1pyT3t3U4OE9gYS7i2l55!dd{g__56Y{lTro=7NCl z|L>1fkI?^q@qd5gfE8)A{-2Kz@+R*hLjI4BM_AY|{@3l0pO;m&X&L_aI{uIALBxtA#Ldmkp&hv#&2M+6L-85p<{>Rx#@)SU+8&xmMy&C&ekFk+5-R->HX9=RPD%F)8T)VU4oLZFc0#j97y z(?|Bm^ zV}S$|L~Lwq|K<@Z7gv2e?=?|E53|cndIx;wPrvhzjW`dczZm&k5yPKpNmuxUKp50G zH7+y<57c|OtcwaH;7DO&(ixXdz`yB@sMmA>)A%7BvY2$!me;M0`%{Ec#vnn^8~;^5 zRQVxbCg+sh{4bQ2wl>Ax`w2aR``xC+zh3Y)LZKV+#hs<%h!Dy=&0M|hhH183{Q$i2 zS{I(Sh`auuKa(LK9o@?A{P6W~fq|a8k-0e&CkeK-00jsPJ3D*w*yc*uRq%dYPzYuB z%TnYGvLp8sNjf?^JMqZL*+p@2aPkjmE@oWjO!^W<5s2_sKiDXXO)+Zl?ziA~ zXs_lfors|Exg4;m;C1aHQ76fFx& z`?~gMsw}pCz5B?z7f<~m!Dyb&jbF3Bs+`u@t-VWt?2{wTn@qyde%Qhs)U6 zv0j$mH8eDIXt!68!XzRlPVu@p9&~(QHJax@b>HWor}b>zUElg=!jK^N;>C+(g-^`S zScy*f|I(NjYbR^4&(L!iHz?!Yy7f*u^OH!YO|?350hX6vl-W#?u*WLy2v))`PFqqq z#^)jSx_BCZ9;23$kno*WebZGO+1k=lC7W^$`*3-A`7LONm7P6j(C*v&_r3uEHxb7- z5)BL6K|d86H=@S#2&^5s-zMkBr13h$AKvh&vAAY|$CNZSrgcBwVsnX^(k*#$3-U}? zNpyN%-ap=%35WAu+uEpEIL7ec!N~t?K-HMQpAK?T(pAk!BZnew&b{N~IBF~Yuk1L* z{up=Kd{J&7#&;tGzC0llb?1jATsmMWH#djL+N^frdA{|HY0BS)T`%|BSE3yBI5hJl z!b!Nkk!Kjh{(d1<`DUibW=i1n{JfKDwc^lSG|}r=C(p2ca;2}4QfJ1TLJuloP*G8* zUs8mJg-Im{*vv02F}P61|4_>|=KGS~&ipC6v!WEJSN%0H!#aw zs9p4J4X$ps5fA6-5N4_*#Zf1TdXRuUa(0h~k6}RyJUri$627bv%hQXCT3H4^5%Z({ z{da|hg?fjn4w-p!Y5451SpWY0dowU0o$~DQW`3?qausi`h_#t+{;18U9t{o6nv?Kw zma6m)EBDisXUT77Y6Lw`@1ftJzKsxcKV(gW1_7BTGp@Y3BbKVVx>&J_X!)9(2b%>G z)^Q~@&DD`|Y42c(_4qwOEZUu;G;^K9>!8wGer18TXB96;WpP8Cq7ROl@BhjL$ncX(vkzb5wu{Dou{~KX{p87QO#gyAz_8 zEn{t+*F}R#IcQm7={`XO6e)>$JPQ`B8CicEg~{=2H3;_}%V^!M&P+aYu59vd6uA{RkOWDZq7 z)eMw+2LfH&b5t#rVwY>vZBT-`QyvMcSuMKXLO5RMcE2r(D*WKU0Sw0MaTIO2ZX_JU z+E#DL3^lkMk)>6bsOOY-W11sZD&^PQzvG9MuQ41mZMwggph~#9R!x1Is~HkNM_@Jn zeu*^B@4t(4Tl3;X%`J*#(jhX0Ejv1|poiIAu98s-xAtQvCPRMtV6Uu+ErYXGNK8nBq4!!l-F zU0r{*7i zOvms%Fsj+v*%q^P)p}dDGylgXj1UV3Av9Tu0GrltyXE4cf^H{|Y+D&KaOuR-PrBbT za#AUUshzJ`*?~3wmpoF=)x)E<)qP%hGhf6UZTb}jtP{tt{||T~J7Hb=f6y3wbtS9s z)BWvwywa9taBwiaeWun$UPdOs^WB@pXk2xA40s_x5A+WolKOfLsTXfmL`Yu=n&e#^1f2Dx90@|7+^J4kYd&zWiehvhcE^# z)Y03EZcHP8`I{vvM$}eL4jpM~!4d=n1|om2-?AJ}3TmKmAg3-+Ggmg6TJ#0Ym;m7F zOy%!VZf@1;qkz7VxC-Rm*Gqp2ptJU99>VVO)c%{0Bf4fTaU}TzDF7iUYT56MJZv844pM`}u zb{nF0okxLR1jy6T(<2K@0fM2LsZ519UN{02{!Cy0Hr#4BUvG>lD6TLo>sKs?)-yxH zC~%juZFV3*9{?Hx$W+Ivv*VpWKR?vvm6b-oD|2%+&Ktw;bn}Doq;!4i>+10C-etR( z4m&$LL!Pb)YdJ8VP0h_Inz^9C!n(Vkj9UvJBpyG;1i53e(nJ6n!NS7ErVEfLw;Xwv ztI35)XSY51K)?1a&g|@LNJK<{T-pZ__6Ru!lZK!*Zl9ooU1`^usJbn(lzcpTb<5lmsMi4BMa$OXJ_|+jHv+_4g03WU4q-Ohz zt%JBvlu5buk%$s$G2yln?%oq6=J49`psVnxsd2%;m?_pi&(&PGJo}3jdHA%yo|)A2 zvUFiELx~KEssK6``CNN5GBbDnwARYk4Fp-8<==$G$?%ed6?xIKZg;$;!y2n-QLbBe zbvz~Lw1x*_0qswDnvCxmgRvzOcFNl7B1QmSw_hJ*x_R^F{J~1s+C(XfgM&j6xDi`Z zl`6Uw1<$%`=NK6oCBPJk!@2(?qDI^m&x4eh{yd%gl%nn$JAx0N>+47CKvr-UFVdNO z{2bg$v%z$QEY&o0xhP6DQJ#Qb&~!cc*Dnb$vI~>tR(wC|c24(~)bOt_b{paoqa!0@ z;~e4r(}QjbUCmuz(I8JA^yE#po%=b+SEie<4IoNNN~*uc*(x*Yxr0uzX<*C)Iyw|M zF$iA(0JN;Ek98|<-MYocQl22@CEV21ghxaakgcBC1n14N9EOsJ%fR`8za0$E-$g}; zcn@CYY`q5qEiD3vLZHQE&Iv>cmrt`k1Ox6GqZgtf?U{JXtoRdLIGY@7{Ez5JX7o1B&4LlQB)%I+}yaKp`nnU#P_4@V&4Bw ze}j+D;m!=j)y0Xtg9Bdx9zfA1Q2%%o6wtLmFi)>i`PkeeH_zjEOS1H3PrCCdxC*fk zGMh1IJbg10-LdN3kD9P~>U`_!9w9dc4(Oo6)xV2fbE5)ZFFkURx16BW0}bolp&j}c z_`9$GM5(E%cHVDTTnzsu_f;JTxGws z2PMO%2g|?5p`0{=tx&{%@g|Z=fTaPSLf+jQex&`=Q|RNzk4PAMm(Z}%Zb6FE=qDx8 zBMrDkSY+Nsf=T!O%a_o2L-$)8S_LiQ*Jmo-iK2SPUPu*`kw?g)+)`jrOB?VD?B%_e z-DIz+#JpkXnh+K8rf+7TXs4Fs6Z2CkWo2Bx`}cX@ZfWP~mSX{>(hk@Ew^9@r8@Yvh z+m&;s1F5oPyr$4fP>I)hLjx+bsT33x#>-w4g4iraxmz_og{}{}b^p#cO|So5!SJuY zAh*A%6iiDeS~_DnpvI9feHAJanLz_Eo8=@x5>6_3Wv1{pi*Pbhi;AA@Jg#(FXhOrM zq2YPL{0VeTD%66TUY#FFVbUG^{R_jx>Oq4Qce52HKz{1!K^IR(`~Lp^B2?rNVBDc5 zf_@#`<-J&REuf8Ce!aU9Xjn)JwI89NKeIv$7sPx;h-9=ipExA|(y~_>ll)NmXB;)BAj#({2R&&VUhT}&h5vhxj^&Jg&c;}FbwoqRvMOqTR-0T+Uv>y?&Z zoY&Ea)*?vpA}G?u?=G|WOKp*azYDq zhv{V5YtSX(04&0RNl?1*1GA#zC=9&BlNT>vhUMjP^1ALB7n?Mr7dx&hLv4>r7#yK+ z9;j0o&eiH;>ZJjnMOINUtmF4@eB?f*q@(~KeI7w6q*izKCtf!tFva$Ny6^G=tHIu00-oG+-QEH_P9+5e z{E3MP$;q@p53D%oaFK+M*LzeViIQ~Z zapF-Fx&Y+MLBAU0K1Pr~Q1skyB{c;*y9jI(5m0i37`T*pHUe#D8b8R3rGC&~! z8}M=O<)(fHIr1fM%XaS=e;pI-|>NA@WC=DBq-q%WpPQL zdtfukUksM}zbjt#Qql!neQTeaGfL0Q?D|%aGe2((Jv+RSvI|ZHtIIc$MFE%h@WQx_ zjg8|lEHns*BFM=53^tX3?j{nPfTn)t4(jPGV4ARq>^I8U8mUV0+>cdM+L7Gd2L}0? z2*%*^OW-yQUl-PSm7b=r)^ z>(^|^1%lT=O2&@h^PA}CNIUC7ZknE&3bkPh(7ud-{NbC3)kF_m9UUERdo9i8ARJ^f zE^vvP*UvyGpCkz2Fvvw9wY`37u&$@)BVngCUwAZnF)?b`-l7R>u+fO~!*&0xEY`!_ zIhuFx-YL7h?J_ytTTmN?%M^7`Xko&kis%v1totTcymkQsi9Ci2jcA}YI~W{j<;>=H zH!$uwtv%znouvfa0gTPt&|0Odt1EoK3qbnO3ks4U=C`+T5Za|Lalku|Kx%^CkP|K= zBO~O2UYjiEc-i}HU2Tj2d?#oZM8@|5({dyy@W<1HROpG;(b4f*PDUr704Jf-yxdj^k?Y|5(ZQ;Hn_E zpbxZ2^|ZkoL^3!5m2V6ps6aB`A4b zO>YOe1S5;)ez>+ku+)rtY~uBX@&~bnx8yga2!my=kdfVHO&mQ(2kDBNHl}!ue3Eno@ukT2+0>O((`miEFU0c5@;q9 zFgb$G8$@8*hx)%3l<1>e+?p5Jt@8)w*Q_&!jZDblKl8kP1VjUoncRx=B&P2wls)Z=`Q^7b$Sj{Y@t!k`=Ez!w_JK&mVPVt9)o+pZ{PsUvzT;! z$pU_^FZ0u{9aPwe_X!E%$cw=w2FJ&f9vmF>*SR?&j^%1WDb#f1#Q|b+JzI(AHEFu( z>gJXLzk7N(q@tRy`v7UbkoE7N9B+Ww={Q2-8&bb`ob1Q~3qJr_!Fsw%bt8HC^NqCR zWQoylxI#igA<@zDpvwO3NBht|dPE7!(+)@%&@nQ65)&J{FrsA?sJ1R}g=!uTUI>#? z+;o}iHAJ$^HionN*PXKR@>-AxK3eP?v#|d7s}iRfxRBtKXVO(&U0&*!sDDpNq9Nhb z_63(pzse2;$el-^I#!0)2Z^D3wKgZoYh|ML>)KqRbK5`lC$s(y4bX`m>mC>{e#>D@ zAksdFkRXuO?K3z_V5u-8<@|vlfM9__p;oSDk9k=C#mR1bNsb14nZ*DqoVZ|6dBE=W z!|8^tlsZ0>rTne|yaw=#fuKfW;^Renc!((}xA?ls^YU&dc^%*FO%jiWV}rCngv?K% z=gdzm2w<3Z#hENL1tM*Y($=e)R#5iuKYtDZ_msVGd$yj!w*Dw?_)Vqt1mESw+;v;` zm-_~$mbVjn&_DfNF6(s%5B!N}k^LPI417B5E~*FIq;v=&Gh zPLWD^R`r5nCvw*F?^EC=H8eD!)bjUujWY-I0bPzl`!y?M1CBS6tpmm{LN0B{IWj3J zsf&nqEKkSZ_U9S;oX@o={0OjC^k}}GbcWgjphIbEYtEXt+qxM`YxTg8_ZOK+17Qgv zgk*SWxwL_7!uLRjeOcLnC=8Ma2df1%a1dx=tHOHb?N?*@dcm*)3r5g|7+(K6!Ac_@ z!Ee!zXaJYtsmtRi!xUT?MhGV$Z!n986sSh9s|(O*gY2F$0x=K#&f08!ZC&FVX&@&- z%Y!{b676sf0)m1-Nf5d&e~^ch2BbCH1!J@eECVeq?JuUdQan_^Z&2wnRs5=tdcCQ_ zq&Y|}nhoNI0CgbB*712b@dz3qJ;bFE+lo1o1FGa%w#Gxz_4+Yb1f)MrLJ|au%nYOv zK-CS{uYQQ8X=rLL!b6qtXkh@&35p^W?u)c|0ydKY&;dxHa4hFJHpJ?<2bxE}L!vCW ziE>}lPvvYT%j|`@Idw{If{6bD@6W*0@M)kF3P@Szc6MrN6BBkia5=7PDZz;GKAN{% znS+3$p5>I zeuIR^Fajdi>75Q-+}v+Ny-19C7HucXZo%3kkq$(#2TEV5tRKmSlb9fBkGwpmQ0GPi zh>;-!ZV$O;FD@=bW}Y5`52^Tfq`GNeDnsr6YVTabYEIWMz9zeLa)=tNs7Vf^vQ{ZG zie!l}jfk)$$(bBeG<29jGNEWfM8r%vm)a3q4RR=jQ4SL&HDxm6lqBsj*uSTlYk%0^ z_P5#Bwfk7>TCMf}zwh(h_wRnzyEF%GI={+N+u8>2T;Ajn7wn+WZ_{Qt2ps?Pyg|1g zA^~QF1^SlzU;65dZAjDUZTPEJ$DcdOibOD;9=6&JqBuV7^Yffg(%#HW_grK|@XR0= zwfcuc0lgBZ%xGwB8^{_c}(wx>r`#CAwNIAE1k8WvLxhr2*)z#I7#7)s^ zA9W};JDwAo_u{fS85C^%5|0#(^UEs|w&@k8g822~l6TcMAcEuE++80&Um#Uydl>=$ zQ8GMYgr3U96Ku@bo`NmmXdfKktf;Yh{3MphBqYvEsocPmc6W3fUpY3Em8qb{C#t83 ze8KGA9NjLx&|yR_Rr=RE$2L07ykB=$nkAgQ#z2(sDKuP@;m7g3Q89BJ}%l8pc>(^V`+8WVu z@zzAGL+8yq2n;|_(|uQ4xULEy6e>HpXxGg_<>cxGRK3F$Bdcs`GgNQa`yS(^7LJ}~ z+qdr}39re__aV*cmgf;jH61!l|LX0GmN=0@A-Z$ZCS%mcou2B&tfV{XQ#Vo(t8wLG z1}eX(X>)p}bEfYxp^_kbW;T{K)Q)01a+Jot9WKjlIE=2Noo}{25qi8=;X@y?sK&++ zncLtkzy*eDwVlN-f~TzbjcjqKQ=d>DJOA9yT%C)PrbXx`T#4GhzdKs`vkNn_mprgQ zbwH>~V|MJGJn5)*HLTHjwksLZhK(Cb4tiVLX^$(AbP1}`+Qy78-x{Gk?Uk`|3}6X7 zYS@SoEpa{Rm{by`V{#0kzQUNXI4C2%E*9_(DxisT2IflM(2aM)qOLoeuUpAAxw|z!*!&FO<;~k)JTo*9@gh zd_We|E5U$9%SBpSk-7ViEdPYBRn%9v1BVY8BC{OFG2zDDT*Ud34XZMfof}-Te2+~$ z^m;G)orkd+kmm{iY1snG;k*tw4e5B7hi^-(V*Ol!K65~dT4tspP%?&{hNOt10wHer@y z@yhfSYViWX#ZWUhQZ%igIii<9M_NK;jDuh}K*(JquehVgqu?Uw;sl}{bcGD$UtRyt^EKOK9n*$_2;DOvwfm$H?OO=q-!_RvzFFZ zX~^Wh#iBhb&&eq6dy5-Bo%biNiLsv&R)T;hCuQmjPi7xtaK_zTTzpx61QqpEkmC92 zY0`tKPJ$~l86c5pnXa@oqFGOID*T^WPPLW+mM_Eqq`ibo?eSxSBYsOEP0QMQ>-*Q0 zVFQAH-qd)Cz1i7uj&XQIMCO7Y`GEad3ynrYD3W{YrMv3WVwc4g19r2k0KvnM;4~`4 zrS_p}yt7nM;HGTVy6ed$losla+$pGnzJbAcwA0l6p(9un+tt(JB>l9rGj644JcMq- z$i-UB=g?ylYdDzgqLi^T>-@JV2M_AQsz!jYZkYtIoJ*6(rdL6rWYmC}3dzF6=YkGZ zITixou|8DZk8N$&l5AsUo;w-GRIqkLVr<=NDmENzK{)eqh)cIQ*OJ!pWY)xd>fCxA zi!Xl#6>kETEbuAqBz*s4A6(@cmm&mOl^RZ(t(rXc2$;ysbjl1iuGHYy*aS- zI|Jq|ytUe|cRJ36a6#zwWy^^yeVo+|_Hc5^1J!IaaZjQ8EX)9EE?C2Zj8GbxLC0Q& z-&=4HwI-=`Z#Oqfbccqno#vHH-QEaM%!YFD%XrrXbTa8%paldU&R{0|w8c?Po@@a1 zVrY!~WPeh%NuxrcH*3@|jSoX8S#^2S81>;KBmWEg+}DFnVj)vP(zEt*nmDl)m>0IY zCMV}p|CJBT8h^d*+4Qph{dR&DfUI04N<_gHD|h>aW%h~lQ*@uae*gy>^4Vt`C$&LJ z&OwUgd_THZf?1peF!2raA09_NP-WDw&2DQ)lv=lZ|Rz_>CwL7mMJUpBPey;dpqIo$JUs4ZA=eXq_EZ69#TiAnPG!6p4>|4!Fj+OJ4ZL=qhoxGL=<057YidZBzH5H5n{H6+SdUix7YH>Q zN#DvZ(Dh@rIz}Z|fbSNrfnjF-~}bahQk(jl=KzAU|*HAp?Ja*$y1JotW%iuRSe z9@1HdoEX0FDP3HM#Gk^~h3-{92Kc)34C4j-_1^FMh|u8R;6Mr-arn8Y8ySfE@G6Pn zO@tJ@{Nw}X7kE`B_$A^d`eQi%&zt{WS+InMyohibp}5XZ4`UvxvpdXpwme2@H1;51KQ3t1tq`ornOBhw9;j`Ra~mNA{w}bEF$JyU)ou zbiF!Obx`Mn^n6ZBFH$`>D(ek%A)0si#!AhIq(X0YY#11aMUG+(mszODeR?3Z_~)}l zUnYKAI1Q4EKqE`;mQBretNi;Ky+4TT%*+>M<}VM{MkEWhD=&7oFZ*LzHMy#T=ouI; z->r|8n;qULX$c`^mXVQ}I@+F{`}0|-Iw*#%aEY=(&p{_1Hu23s?%SS4ql>d+rFRxI^g zLT9&c9()9?uv=uIPPM~S1BS!mAI163Pl-aV?A=L^v8D#q^;%Z<`|?zn|D=k@$1o{U zi1`T9MldH!v!mAwbu~}K&-WK8^Ycg{R~uzz9vM?|n8h&ZSPo$gl$MY26P z-?Y6FCHNnnIE4RyhZKC(c=S7#xYwy-|4H5;?jSokX7**o5kGFD;xWHbpjG~7!yq`= z`1U*Td48w@fh)G3TDZD1;ko&;+(zf>&HLihP46s*zEkRXZMSUJ zp+-v0@>KIkqN1W|PFC{Cy}ZYMS&uvRh{Up}yoc0QhIBpIUv2Bnkmjgxfi!X27*F)a zA%F#wTpcRV{P|`O2lbiX-v2EYo^qZtJYtcW)K|0z7^8jD(U>_Vi$#W0&UG5~6&Oj+>15*pmej+MYJ^j$HSP zbOi0dcg+|UmF%rQLYp^eX`jPSCki+&Y*wM*PTQ9Ib2v_ZHU|;)7aK^{ogZl75>mH! zC2}th72MvezZ8Z2Z?#WhMe$nn1;YRD3~AYN+Rr>yR#CC&{fd*!XZy!t5|AsAZ^A90 zdb2JWP-<%?jHAS~n~Li3o8OQ?Tt#CQ_IE$t<}*Fq`1gT=(;qI`|HDZ7{WZ#_&#n{h znv;5i-_+3Q38;Lkvx!Wz9U>&Om%p^YIE! z#P!>}_e4ZKV_@MH!wr6WRdBT-zo@P=>aO(BN`BG(SKlcR&Z|RNhApAOmuI^QDg4Bb zxI>{7WcglR2pru^EOk4Y4#GIvY9^9ZR5a;~WdVRA@q6}>Dk?Vi zcZL0|%=70=wi7k=Cn5`7i7|rCE80V++v;)(3fT0ltgOk>05g2uh){%9xy?LmO{RJ8 zS3tq!Z)*AIMLu8H{bfDYibW(WZfIz@P%_=kH`!I?yjr4NZrnkF4plCbtLG>C8L$F# z-O2H$-AO;7?6IOYhJOUWs-t5D4O>49Tg(T)-9jg4+^Xow(p@TED;dDlkdTn+_qS~- zrgRacObTD1geFd+GG${f8ie-7yhQ0L0V{Vjo<0S{A`T1+(i;-#>+g5pYQ#ea#^W~w z6?3bIIjFzLS;`_BsB*`{Ya^u=1Gz6vkC1M<)h_D^+-8Jt#Sw@ilxMH!LPyM^zvsp1 z>e#Pyy?1%A>p@W5NFfibtXS2)sTwr+VQ3c0%E^5->q(7$pcblK>0m#orq1cMHPyAr zC<*0F^8K~+H-q1xkOeipBk2DsMF7z{CMGOOT}dNQGqWR98-NUHIk~IuWJuW+A-Oes`cqFO5j-ED|2GH($MoRel;c2#@(+zvJD--2oLPPRk+IjjC1lXCEk{ z=0ymxF#%k|(C;a9^Y;tUGxFm7 z-wvC@Y54m}>j%na0N#-rcka8-K1@MMb$d-5BXc|t)}{d%ryB9-=02(Gc6imu#xSXV zQw?bhz~csFqi!>RwN}l4wf?n8GxtUMq?fJLSnKSz{#gCFZHsQL2QeV-=0vUgQhE@g zJ)VOu&1(lAK;yi7@$zUkqGqS_q1R3a^HV7)`?>b0Fx_~d06?v}3d$#vOyY{YPY-Gi zCp;6=n3G~|3`Z#%VG0W?8y&O`48JT9$O5*w+o&iniUKMJ~!aKN&LV|;*I+)Yu zdZp>IypDGil6gP2gpqTbc2R89oo;k3mfQS0A&O9XTF9D&5gQqol+>xN=Pdf#4lktEnIGl2m_v3?^a=39hLl~V`TL~!tx6;x3VO3(Lt!$Nnm zfZbFBqu#EA({kTCh*2FUjtLHL036|qqgmmjsQ@TSL5bXEeVMYPf-YCHIu>5IOb^-dQkTAw2W z(?2O4Thq;nV!on~iw%pry(K0{)*x|E11*5I3c&Fbgx$Gz7khfH{iAF=jL22XCu@tK zTMQT4n1T$dHAkcZ$f0YBsHiA1%{z>Y4Z(G}w%DC4{q*T?6FNEKsJ|JM;`kO&gc)J& zpft6H(|C4RvS;bl`_uq@p;;&puSjMkTC1^a&%=!r5zhnv)!CUD_LE^iNDNXLC?3rK z8t(gp>dTY$V#ho4834_~hvSZOP*x;^2r-Nk-G%j9t#n!|IQEkkgOV;^IXG}Z)+`iO zZ*)48`~)e&V>^)oq5A_;R$laSAEjpoYy`?%)NES>RyHd^Lah}%7&9;nH(^>`pJS7u z@0!g@V&|~}VVdNkyvIwqI@f`izoVG6i_l*9=RPEu!ETm_P zJvC7N#xD{9<{&B%L4-6jyFFs)dm^uuZcRG|EV!?l``4sPqpt|}!0w^AJ=4N* ze3qw@0{}{%>U(j_8bK%EFz1g&jKCwJtywanl)&z~rqhZM%ck{f3vvj}YGw{k-Ou+? z9U!mt<5;=lFgTcItK@4J(kwuY!PdnkJ+{={`nfWgzYA;ZxH7=qKZB*?veT0Mb$HuFt-1Vvj@_cJB*yqa_CwS3VEr+ou$%5$jc3!sjhz1hJZh))wr#Ol4=oft1iHADns$E$ z%udYlot>TKZu7kenTEO!_do`uHFn;!o8Qa9=S%JI>LqvxFQH!h@9jAOh5Oz5@iw9V1>p!%mJhjzCeJumZ|Z|?)b?EenHaIy z9wjODLUO!4>MmL}Lxr1ui%0uKS2OaUCg+oA@2gSzT)b-ky0=c;~R?dO2L>11XK^~qxmR%>QxcCv=*l$1( z_p|Lb3~ot&{RRX8&2P9jw0?mMo(Ecl_CIoS@27enXj+Y-DTeUgU&+KGcPJsaM6_PL zCevYwJQgJXs+?!n%O@`ez5M`7vUI9lKHTODhikn4WhD#L41{hM>#)~_PxaE0If%x{ z5yng)aO6%*9U5QRUw(ZWcWGAbyxI!-1OVtd1P?#B2?oGkYxer&f48*QBiYK0b;qh* zZJCr(6+oc4AB>pc6A_s~1%>Lf)5YCmtcxnt5rRZ@r*)qrhPaUi^~7&Cg~)jJaRy>) zZ*7EocQjSR6RpZ$m)j^7>DC5^gctx`qBRG|C$o*V)7mQ6&F4UB(H6|RtG5_fSV90+ zqJ>;Hx<*>e(!Ar|5s>#)*c+jLY^1~lP3+;aUCDeAC|%Ew3{s(g;nPKrrm%o&w?NIZ z7%sjOKD!0F1Jt4b1jt@c>wO0GaEO8nZJ=fEd_{sJOUiU?BmWpSn2R?5Wv+ih(&bAFsC%r)854k-4{uiYThTNMe+aJ6rIa z^-|`Q*PtNUg<_4t<2|^dHNwjtBg^oJlH5~Hyu^e9uQe3-O5aGy13ld;+OP80l;-ripHo8xso zLR=@k;~}!6_-u7Svvop6FTH7P1EB;u9Otfdc&6=S9T4&tnKHy1wTHSV2kWOntB9d| z^$1|#kGxNuqGMvvpbaTM52TTimzV5OX~gAmk1y9@@WxnqM2di;a*f+|m+uw7JWGDZ z1qI-)jo|&c&3@!-Pvm9><$cmE$;&`O#fozNw?_M0uiIG%vP;^*!C`?#z|Z%5RS$sL z9~5f|m{h4=JF;@|?A{%uVF9?;tCsZESXfxdZ@#;Z1Bh^h+|U8944rguP=)95wXKsD zp!xx1X8a{_Njw02!&j@oU?3m<^|`=v&%cqra8>z-q11y{-`jyOlv=Yoq|YPccbf<} zv|nIf^u*fdvJRwxjWAy67_>Gyd4s`3-{WAd1By`smx)|l8$gjy60fzKp&>*0xB~&5 z?-?fn8S7LKolnJ*H~L<|qT&)$eWCXBA~;JvKAPL?IT}$5X3<(3tO8>Y?jwSP#K)&P z+wu*y9{Yws-B~qD0wE#JR(=AvYg^p?0pR&fy~w8#)!f|7QJwWExV;7Jz}obp1 z?A0IW#DFgSIlJ2m%C`tIq^eLJk~D$S2p5P`C+p#sGDSCf(blVac}ENx9$`XHPl~|dzDiElCQVyl$A{C;95?(rKhdQ6 zin>jQg#`!lL!;+d<+FfM)ZI2)Ju}T4v^JtU^H}_1jg|3kL-Y1J8Wn#{2Oq4~S4Dth zCFhBdnp1KwQUxLr_o~Qi^4)y1#FLR&4=U|ktI`X=4 zdzIui0nXKm->p@@TM~PWjC6JuM9O1N7eC%T4af~{7yATG@fl0@^PhQt)^l`kZta?!O5uH9J0TJ`-hQTdi$szQaYrz|bXeW7jkIgHy-{?1;s_ z+2Lx`SIm1tY@Y`dC)0FZ%V24xx;P>E} z#X4B~v2|LSdM`Z0z9Vgt(btFHi(;rKXtpig!NjpUO{Drh!%qE1=yks^a*k}YbNNjz zOq{*}w3Z?e?2%#vEMQ{@v_wX06Cm%=V!l4;1P2YEQR%>#s+VkdBZ?sKU1BqJ;}@y7 znCwEXuT=}zcG@mQ<}YSYVe*RaB!i~548od&*oF#!9xpQ|D<-qXaRia;?SZp_QRQ;( zEus2!PR^wTw*f3L)8jL!?K$Axf7h;zwk)cR1KtH3unlb}j+U_?pz_`WLk5R{3=E^N zHHu&Dmo@!4=`Ze(wqLzzMd7#ZA^L2Wd{&Yz&y8WbeL8=`@)1 zGlfw-roK40CE}Z)n466d8OTk~(kG7E)%k(36%V+KXg6C?EOwZeJM$6iPUh>WVGy`fXAkd3T$AIQn=5m zdp2Gq;CLZ08yw128t~%>x)HfZ5Q12$Vvi6xpaA2HnUj;)4>)yGQ&T(Gx^b2uLS^LS zs+PQgsmKV~mY+bk=Aud>>?}gidz3+NbgdDYOdd}A)4aE-Ww!EBAP(lj-_}2$$%I@q zzH1niI_9+GshDo+KE?jsRxOrB4TiWPdE~$VL724duzr6&s&c~7>`wx{$6CU^<7WwC z;*J|67{Jj}(fS6e(8a>f!c{{Z!?q)|`rW8pyjYtKIa3mHz8X%$%{Ha1%=*jb-D67y zyaWbd=L5AOBD1>Sz_0V@GVNn@@yQL!Xq!8gr~MpxCoq%A*S3C@PBm)5GfTIs|N5 zf^*%Tg=x0Nb97?qtNf9%*g`G|en;JWyqh(%^9>kbl-yR38I;1q$U+^m-Gz~-($xd` zIS>ZK75-RXR;%__2H|H+i_Lo(ZbcXu!m;UlM`p z3(WZv*~Y$8pDA}MUf7-5&`9S`>N^|);k_kdBRexAcEuak-KdeMqHW_q8vws%E zIiALIuDeOxVF$Me?NQ9X;1IAz)C1!jcSh+T(9IjST3uMnSj{UQV8njIxW6Mb*Ny?; zXgsh=fO|(^Bn2^1+5gqeK7N1I`oSyV^0OpnqJjKHYTE@lCE7K}gkk*Cy(S%f&vz z6H!(%SbRQQKgmSFGhJvsMvu~-RsJ?m)I*XgfMwLGk;oloZ~vmUs@ZjNM73z+Z%rk% z6LdGKIb_OhL_PLT_Or~1qh5T0`su5&K5B52Wv0X-s~Z-THo^kKbtiMV`!>xw2{|6$ zznhsFobfK}tQ!@xD6E9lCP;N;oaP70S%XuTu;NF#FPm9!qjIN>EpEl%4Z@FHG-c4~ z>%SwM(&ge5hx6${C6IxW00xHi=jhcfW{}d(RyyoY4~T&Da9Ft3l`wsWwdl3q9p5I-}F%SpwXeWH&i%syv-GtPa*qx*o7=neHBpi7G48tFyZJV&S!U?n>i#VM)4ew8KzgFE}J;wP0xM$>-ioJmf1bj9iJDw z{871CN6%4j^)mZ|d{3(A%&bm0O~B5)P7;rOuHIw^7k7M|X;laWu!+mbaAiM3#x2+M zC)qt)W@#fe`($31wcYFGr^7WP3{0(ob<_e=OD|QZvSo-N#n>La8j!d_O#A|UWq<4B zDqqUJzOF8<*Gc#`^T_J1M5Cqzl;vpoeAhArMq1`Qjk0#r71dT4`7o4k0emR@{MNZb~hEYuNwPk6o9ECPV*!~*rFt1bc40ujrR(iS zl^g}L$iaLah;CFw8PC!XTl>K}nPRe_wqtjT*$nIf70(q!w$6AoBX3dthQSzbSRi)% zYN4a~K>Ho0R&BknfytVyn_JV4_?(Xi85o)da6g2+4WhmJNZ&8MBj&u!W?hAnf*9W& zok`Uqdy!zGu~Oqvx3w-h=IM;3J6ZJO9j$4GK~7Qex!CC>aJK>bB6OWxpY31{7`F?E z06t?=H&W(WJ-nuyD*X3Xfn@$GLakpKtgnqZEuw=i&b?FkF+M#M;<19J!1Pe*f=Guf?&RpWM&kwCI|ZOSyu{}=*1&l#7x7Q=?f zeWJ#_e)UCRiooCPjcVF(x**vY;kiznEI9#cF`JFFq&H2vR;+7dW*(&EY;RK4)BO)H zLW9u}vH9w2AhO1t*Lk(-yOtR-B#L`~U)ME#kA zHv+@I@LkM$nmRv`IW8RWdk)3MS@gFWwBNX7JX}`Goq|W%-a%qO{YMwpQqz&Mt$>!J zZCX|Wxj3H3SdE?65|Qy^19=%S4Gawb?a3{UjS{0E#cCG}Lb_iep$@W&BIJkw2~v`n zXjTB{0BbZt?abLzKJM&lGTA$_9vw(Ge@Q;Zdk7WG@W3j0``W{d>g+0Om8Ob8>tk#X+!{5*rn{zLccq0PEQ)<}TN9)eD{^mF#A|paJK6uc-saABn~$K&9;ea!G`0LM zuYVG3>eN&qn~Ct;kEZE^2oui(h=ix^vR&_twIBI`m92npY#|ZP8J>GzCG19*g5lsd z!m;vX#`)kYj=6Jh@x10B=?$JtZF)AtjTroQBO~>bU482l*4r~-x(i*~kq_hLQ-#S2 z33_{>_ZsGaVaFqCqHzs;`8ALQ3+53X?HY3=c)Udi zs-8`$;k)IB)WjIl;SCXDqh(ghcNs9rSc|!Lf&EFD zl-$)=w$+{U!(z7|inFcRG~?I#u#b<7hyw8NfL9xAXeZN(cu@;rzPnnPnGN>5sjvQL zLBjJB99bEDlrsnh>*p!O!`0*yUj5AgXIQvy0zTAo@l4zZ+yF8bmh3ovjf7<~&Y=FJQ*ySI zQ0z?qWkC{>Ic*rq?e?&d?u2JgKo6c`692t>38y#N*BoX)N3HolR??9Q|&#BKF~8iB+NiqQov;F@_1knPe1A8S3Q?ze3W! zG9@5HKfp&|4R8-OCV0Bh=L~F6v!_zR$d9`Qsfz0S67MadXn!tIFSE<)@q2t6dra4pDlW z%)CR*B__Q4D~Siz?+B75??HOFAL??)lQaKfoNbjIM$w-(cYQkbjG(FbO5{K>PQ1AEI80HLvPx3ix9ALOfjBf%t=`aF$%xxDE z!oG?cn?vFe6SFfbB_Wm$o0t2u_c~!8<>L}~?U|oz@DmE}tNLx(?WXkS+~MT>;B)Tp zv`li3VP<^QP1x>ypAa^@7=+?fBQ01Q$-oW=@{BNbmiyQNXa3y1PE~Pq9?2ZBOjhE_ z=O&zeU1wvQiT_WsS!aD$>Uz5MnEpX+2+WHjUSpC)AzzhdH;3M0LL@0aBFxLn-rT73 zHeIkqk^xGvHZ|)&F2Q&bz4s~Za9KyTN)CO0PO{0A{cKHF$}%(SwbAlJPKV5(*qgh8 zK4M<`pSm+5JfM-p@s1$IJ#wzJ#|roQj`H^e|D`0!UAwK|97z8M5bh%68Bd3(>YUI??QEm!bZ8Pa7zE3hNKN|8N$H4Nz}SALIK%W0izs-3vM^bm{(Qs%Cmg4HJ) z3G%fb>;&YatQu3t$7MzFIcbEC-oyq;)8gB$QFv{?>rN4%?dzWo7ovt$KH8GxsCG>r zslBFKWO1w9EW(2Hu!#U;qq+w~E|P%5ZR;46A$P$Xbz2JNFIE-2tx-!wyr{>Pth#P@ z8bBH?FDK!kgC9gwyvYzNk-a@T>{>@M>fD`WaQdHXcLXsKvwpH^^_@{0y)bp?P5X)s z!T!y|g7Pzkq`B$e`0+*czeZ}u7+CPDT#2By>$9^Ua`>9>-<;V$!LWGUo#<3TA~EVO z&#uScwy`@}<0eAskQ?_hBn!Jw)t&mEoleq{v6mfz_t&4(ILnz67M8EE0w0R$e zhjwA^MjTbnlhM(6P4#5EDnGqQ62E~S(7xKyGHdv6P*;~6`*|DVj9sS zpu^!b-T=A!Z}XN92i1821yTfzeptk4@)o{qzN07FA7``wrj-1LDod$04f!GoDKrqp z>%6jM%7SHbl>tML%IW^d){kT+ofS~oq7s%$3<8!XrneJBJPHY>(Bj&y0ts4xNMx>g zGw7}~46gKtgmH`bP5O*AOVb^LU(o}EmPY90=;D;Xv+UNx1(;yMXbs;74%AH~rqPvb z7MEg);;r@V@1y7H)3()IIQ;ph^2iHKa|yF+F6;87pix3=Qz@0>Cv~sP0$<}PdzguY z6)P}?gV|5)>oCJ(`U)gj**gMk{Y~Al%zNCsFkcc`pk-a<;yhg3c+(Pwk?7NWZB{T% zSx*URsbL6?LUbIt)Jt}LiYKEWTrRx{rH`jWa-@V13r~<$*Q(SarX^l))M{9tloB5( zH#qnH1C3vhc`7&Ph=@dP8l%|5@>E2=YfL*#`APMpE|2W7hX$W5+?qlF9EiI*WL=un1;$M^(moC0#q{L(R3H!1~MC5%qp*jdh@ZE8}u zE$A0~MTNox9Ep#&*iO ztJGi>!B)0z;@NQ{f6jGa0oCgIygEJMi6wkl6Hg?z*Z(6UV$Z2!l|7kVhkB#xA&|32 zrXPYnJ?#Ga6f|&+`!bpe&qk0b2~Xb@oydB5H)y2PI*HdAP28c7y= zGU{$NY4D`2fu`NUwR?<>D}%hW5vPu0d_=C}#KxUBljo6aV2@UuyU-1Ot7Ls0`z%Y2 zz0}Mz;Zb8x(qjwwhw#J2{SW|LD&D=9bv4NEnmz!c?t3rkz;PP*zFchcdBpe1!WX$m z=7f1SIX09_GLhhKt&Ll7dX%v|JHI%k-KbId-`OnRpG{akxnXqXCI*<8q4qFn&Nys+ zta~~_yaD@B8qrm97g?opG|-B8;s!^QS1i)fCG%Gc48V;!IZH>{TGwe|0$I0}tKua`v#}{t99Kt3+=%(X>SOQr7mw zer@%-n&y#GI{;(o^nq^!$}fiLc=_KLWQC^X1zJw)zwIuwfZ?Df(9F$Cy*|%AUfudD zX}XysLTL|L|yk}oQk7ve{-y-v_=Xb!>){^)Em{I_H1 z5XzYl`gDMa#fyIzLdMdTp8`5jwX7n5`wz)VW|8y{=zIO#1RdOjeTr;Ki0 z)f{IB-I2spNSMme76_tx++;p*|3it14#VAUZ-+TM_v3j4x~gr@iU=QliC^drP)J#7 zbWWEiFTJN-TP5G<&whHSHTUPbx{gU|S~TYB(1_Kf%>n*G&nA~|UEZCeeH0YGs^6`q zV`E?;ucK9c$$Yov!60}fC2l{uw`aGY$Q*3)iOIp`SkyYZ4t|;w-xK-Qg^L@&4lqRV zr~#>>gd;2a_AOQ|$inGFGt7ZPYtuzu8wI0-HK&7hc@XhHzxgJvz^rJbsCU;zt&-T! zJl%h>K^Ff6VaA&m`Z9_2`j3oKOy6$-5GZ_JNq000%2QD!sNkF2`&;Wte|u7jIBG3N zk{(zxA>I2eJM#(Q53x5Zpnl~jX@R5u!{)O9PD(VUCF*r%&KR0(E$4WTdssrXV+*H! z7a{fwEOW`t2?^Zm4#lh$`>%o+fVFd;yqlDc4mIWn?O`0BU!3bodB+;>* zju=XJ)ovxW<(nFrRA>cufZa}}=97ctFS4YizlF@g@q>RrQAm~o@PIQ$`-JE^hjt%K zjxRhb7E>R291>3Lx`QrcE$}(X>n_w;By_s@a6$QtA5uwd#OtCGZ_EX(z3Cw>Z*9+l zu*prZm-0x>&(F%l5#XD*fo_fvT`}ss83axu^cZP#^T}fGPxt-Ix0rQV z|49hlB*&e5)B=Wu_B#9yzneD8%_l|M!6Xh0(h}YdjK4U?+S{a~7Z@?z7;ff@Vd#+aG?Qsk!* zQvSz-=q?7GZ<)myFVr70B{7;zpo#9g!r(?Cvt3_4ol8TvFW9w8O$qgUEL7_2Eb4zb z=L-~g&IBfQI#P$V%N(sd49iK~F&KMf9Gn)2U2$p?IB5 z4ZDyqA=d|oV3i(D5a?@WUv2_R1AKI!y-xJ*szjkSI|PjIsg>UYHR^1I?GpFWW&Y^& zr}${U^;OX?I0Qrwdc$p}1EH2*1?l}95%xb81#&1)1-xM4GHXk@{F@Kvlz)A>CHaKxgo~R9g2bu=^4rD`rNtUE`io9|(zF*@P7R0}@yyl#= zQEl&^%@^m{`g`CFfzKiM_WyQJkYwa$Zw^{o5=VYM`=}ryez=%T+ejbFYT>cTYqeDD zl$Tdu4)&$o)iR4&V_iOz(C+JeNB1>u@Y+7V%X*E3R40zTd-N*1D6L$)3m98hg&G*ryx!$bU#VFnIQe#m{~EhI zVOrw>+CtYEEhpmgt_p%yoap7a>3D^sMd$2Wm{%AoDqrevyXn0#z|tOhhc@Xkf%4Bc z6q~g${_ruvsEyUMd&lu~UE=kxYes7t9FWn%`>~)sc*T;y`uPgBfcs7ZG`wS&PdlQT zvlMUB9gdR%A*^-Upq|?@=-1+V8~@_yGe;x>sdYYLXy)`5&;J_Dicxzc;{5b>h!Tq!mP0NBf5pLX27p&^M5?DJBLcT_oi`{#bmx&-cp9VuXrdCQJVmID zVdP_T?e;cIea_R{ZRfvRD#xAGDbVn~{eGFzYBeV{I2guDv{S(;Rbpnhs*Mn;G}QbpYNKy&F|gqs2w#jo?YjD zs9uoN+?B|SN2oFGsu#(o)rGI;H)c!3Wfm^rJYH(%$7|gs+Bj6ujJ6}5ymRFCY^0|a zG={S&k$^Q|-h;1+OqcZC^kib#QTk6YGCsZqlnpE+F%b`bucLIu5O6e&E1HD%vPRse`B^w!_9weH^lbO1^=f2_ zmHpfm9&>#{Hy#@+(|@dCT>-a%tAoM&fp$Hk^Rm=+$l%o{?=jKMTb>kDnG#Q`=+^Lx#Cwy2rk!YP<27|}rwAHt-&?_q-P<>{otXTiq{hi}EFimF6D zF3`y)^U}_?Y3;2oE9XX*sABwdnieJ;uJG1M6c2jel&y%H%!?C3x>&wg<#7x88w~b_ zX(mVoaqCUfo(;#d3W<$z(ft+o@%G7?5C3Zxpc>EfkV?Du0R?9hgRO3wK{M;OSNn;4 zJztzGz$E#Q_q6p7hFoX-A*DbcgRZb_Te!!CQbwejd@;X~D2IE;n`69TPtw4@{? zPrj+<8T#B)Oxok9k^H!jCOuLjD&%tI>(?(5SP@zBpX_3ktr1vz8|!v^xs5X|OvJ=9 zeAcKXb0`xruL`V^9`7cIi~-M8lT}DkEwRyw#KQYJQYRwg#N&0GCAB_EJN65wBU&n2 zsQmY@JDx6Sy%{=O#(sr5I^y`fZrcOSC;O$ciG7R1oD%-n{)R30s6IZ+cqv?txg};W z+xij4ul!*?5>Bqj7oKyF&cM(t3~q_;OJ=x7-N2;cJ4g^5yr)^Bfn`1!aZ48qS3@T6 zfnEM9oaMibhW$)fEC$C80pHZD`?5c=zMgwgQT)3E#zJG4k_EVBn%_g(UKuSf*C=kd z$J&)HcPs50<-PgN<4i>Y$sj?emCTv(gEeB+?@QC}D;KG%i2j^IO0K6_!CpHde=Y~j zd6M*Y#(();@;y+^6<;6y*%5gM3r;9x!yslXoIZzxE;mR>cB+feBhN4jej2u^n&JNI zzWSe>ry&RfgCFwb_Om2+ac#%_b{Ex7p2f5C#^HRV(yS|Xu)6??f~K9oEjjUp|fqBKG)l;W_uZ^<0n^CfwMV4AOt`^8<$-uS_y;phDt3 z`5@UB!~P^;dS8Wq<0Ur)uE}@6Cs9cw1D9_ zzXR>_mRm?>CFP)SYh}h(HCV#1ERY~GS{Hw;XpAj#3?ScCO zonc>ari^SRYC7PkpzLSC{YmeKRNdV2ZQ-;A2Do@ctrsI1($IfsJU_)m`sd!iHA!}* zA)1jeORnW=(aFBI=t+B)uE_0X`qml&Z;!NjB+brT6z8s=kPG(mNdH~dE{KQ#Y5^~s zeDo$1^)GbAf!|mt=quo>K{J5>{S%29Wg`w}9!NE5;x&4c3nE-IIl;Jc|2csqG znd6aNBs050TvngN^E9#w_L`m0OasY?iCVV4%qZ5^H;w<&haIeo005Yes)kg-ZHs===adb8 z>%kr8l>vA;4$f_m+>_aI{a5mAH{#24nl#gH)m2^#$6j&6;RZP?tttLutHj3KmsKY@P$}vc zDsTD0$p(o|vD9Ntm@n6JDrYQeq3pnE=n+`-f9upyjg`Z|7%o=|X-E<9CS!epe>agk zzhE-*hD^+}68j9ngU(wLqh-;-R|3SvDOHl0YK~3)i0@KQxJmXP-tbU$lcs86UWlgdgvJdg#v}<+Xx3Tpm&k;qr@Pv+n$~+Yu>YeLySn0AvfjqiI^EY`Tt6vQb;C zUA3>?4H`B9J8{jnOqn|))#^J-QS=5+(zwmAGo-cLXcMyUNnqaB9XGr53Aihbt^BRi zVCcIjs_6Dy&t?o`Sm({~P?Ai=Rh60wGGBCR%a%EJDHPp+Y*2A#m{)?yLt4zW0Pcc7 zvt*rDv_j&Xil`qVDyma-VSpvAN0htLLoKAiAIF=FjcaM3V|q41(va2Y|>vNnevNAIRziTq4r$@4X&U}jBvD8Zl^I9@jv?~qmj!PP=oSB4Nsm81E zknzcDW6TwDUvlVvoq$2gAAKjTlGIvBtI!ya}1ZtAO zXisl-xg@F(<6@s9;%HlK(6-S(Cu4~RUH5Rlzzq;BPfpHFOEP8$`fb)ZLVXJ%cAK7N zilAkQs9Q4sbjxdAj%O8xC*ULlnpuC_Fve=+37pdnRM*9a5h?xFYXO~~tQAO`nrX;b z?I`&FGWcE~j(6Tc1W&OL-)H=A+pI4?z9j(f#uf1rW0FZYb2`XskSgrcRqJ#3*~ZBn zLZhe`6VU7|0`xu{&hk%}G%`0&g?h(={wbfHCKJUR!^v2yTv&m@MAgDraji zI$R=`EnzkLYq&VaJF-h1BmJ#ey(0JYTf7Mzk z{C5naMZc--0!kPGjCkx@`AaN~p_+IYgNO)pJ!Bm&>-0NF0zCF(sXp8$Z;fzGsD^)KI+_vms}{^|{L^`$wqr5S{^SbW zOZOejn-7^Z>nDEyn%*&ad*hAh*3!%N#NACdyvI}@VVG4N@tCT6bLRAK_D99gntu&0y!neh?aNIC!csA+depi|V+3uvR$B+g;WH@}+2S*`#z#HL~C4 zrO>V~d|ebqE_98~X6Ja3z0@>sFM@zP79UQT@w#p_$aA#(GJ;byNfWi!40myEJvbV# zz)&x`TBt{^UCmVCLsO_j3ayD7w-~QnSM%|Ga>Zd`uOmgX#Jd_uT=bK7Ug6Z7Fl)Pb zWWRqRACH~!Ou%Wg(3BwUie!3qBLq6u(p7Y%)9_kz!Fb%%fi=Kb9{dJ@dvE>ZcEHnw z^V=~6S^-a=UWsN_|MUyurrb7Pm9XtCqx?08`5ijxxpx*T3)zYM1$mQR7{Gvb$sssECFgDk8WX<$myzzF$oOc7UK==m@N70&;{LUy)F8V;9<+Fiejbdrf=)iv^K>K zS@_Tm6O{`4CKbCja^ALRcVAnBgqbi?frXP+Y@X_I$#S0*p9p{l?tcJU-{3qrt_MI> z@#U9GTBen1{(`~Si?4xm`9<2iHrE_xakZ=NL1$26cY*Bmkicg0m7~}HMb%eDRrPN1 z3V%RJ5u{t$D2+5oNC}&e?o=9Sq@U@>s#}i^H=j4jZo@nNm0#fQ~#6#EaMt`c!A6^VK43H>7j;u9V%2>y+gjnlz94- zr8iE=;IlI*U{;3c$hOI;QEV@-?Jdca8gOam-&ap&3L*iQDN1KIRe&Xb3}9p!z9MZ_iNFI10bL}{{XDU4*j9xgRhoWaGA z3B|IVmjGmUBbi+n%d$@aG?zBBqK}3%xKjA8{M*AEItJ4M+e7@Idf?)!e{|T?X-gHr z`S1D^G@?>3K8s2atC2rQ7oD^iWb2LZEr9nNNu_Nx6T`&P5vt!Ae%HlV>IHvru)_IC zE#-qn-9IDf_Z^tc{t6x?F#bVrZa{Y%c(kb!tTtA2{U+AQjttC`Ige95h|@G8zvo5t z?=AJEu5{u8eZc}UtditthoH5h;Ao*aHNF5s>IvmED~amJ2LUZoK{yz5{?i37-81`> zuqP`+)UpFrnqLZP=Ia5Yc_$bc8pezs^8l&Lmq%jCnuyntbepk~t;;YG!I_4~TkFWR zx5Vzkibea7rOr#;`LtpV2mP4~{_isvc2`6n{}-QudPGD)=^OkmV7KhDl?)ay3EL3` zoST9o0VZlqb*c$$65>7$Z~^gpRmgONV!&Nr=b;kAUo>?-7}FO0Ai)1rjmM{^O=v!t zm^%Zti%`B_q}6**)POS;+Q~ZzP}Zt{E(B(yPjR&qHzqebB!p zaY@a$2)ZmO<}14>WEkmBmKYZc#uCbCQxbL*IGIND#?g^;@!O2ZI)y@0M{$$$nm{VW z2cHwLSaOKnBw`>>W?@Dy-pylFp-%Yyo-18`XReR<<)O`(#B7ZUk9lbC>;D4p$`c&# zPymnsk}~L=?sU(W%Un-OGKrmOV*MK5YrSt#{q=!g1Bj`(JpbJAztpd`(aej@Rme8@ z#;Wno!~ND(-Z3mF?_Qhl|;U7DNwd$);Nt zeUABUBk-`!yDIg8@4?`;eAXhJ!Fw)?t(&vs@Na0nK8yL&#>A}5Gz{+FUvuKZ{zhlp zB1F&>LBS30@Y>VrcmHxN$*7(gaJPe9rg%046>n$PNw$?r((`dFx7B1?QD&(4(LN{f zH<|)WomZ9luM^2u`FO^Fw%c)rcp&+f#oCh~B08}|F8ALvlS@N%Qb!vYc(-q~@gq$A z*EK4#R6okXP@=89f9%lK>|>{H*+Ucrll$=eTQZy^E?k%psKlq9e!qjpjvkoPZuOXa z^ZZlDfQ(Z-KR%*-ARWL^^4-Qn>@ZF>$6IPotk6j0QMR;1qbH4U)D))U+>GUlVjS=T ztXf~!a-!{nUl~-3ZH(^0!!CG2m$tV=H&PHr#YdYeP_;fjyfX112*}XWMf`|dq&Bk= zPhp9ruj$IEpzY%K@=Uu%tKLQQMG0qmeWa}~0Vjdo=kxP5m*qDGmq4#FYP0puHg2@Y zNXLI`bdy)h356qo{^CFNR_zp1J^G>5Q>gza=xGNn5&dmivHNg-wQ14Uu$&ZJ!>JVU zM06bV;u>cS8P{t{BQpa2erJ@!gZwD^QiC(l$?*8rb*%IUin`ka8Eo)**XznJjqV{9 ztETjH4ZY6^3IS~+^Vz|L@4xDUi6B)@_ojayuPQD56cgU2*DGbxTMfPVJ@GyNrF$AM z<-1}wlOy>70TInUgm1|-SHER-rY(JG_6giYk0hJ1i2j`jN!F)hY(Z?=_Cp_T5zwr5 zCQF9}E5P4f<0xP=(rNiy?O$`n;~ei#-&6r9!nW9Z76hdS3pZZ7f3w^N&{SkJJ(o&5!OJ6`E)$Pg|2LEjM>soqjac_k+-(#K01aSn{=w{tf|RyQrFT zffmiX<{PwXtJqI}Ngu8FA9H|cP!7riOa$*}&@#mR@ACA&e&K}R`+N{Zc%2wWT)*k> zlVLx}>~~&QVz9#Fn%i->PVT*r^)*#{1uKbjv&!oeGL%4qiRn|7&+Atf3y&hwgtC3T z6Rs`}hS{cT0k6R&rL`N|r+WDFEpq4D>7gd#+hXVIZ)(U8Jo;+8E}dJ(6i_OZlg%`m z8vrt3I{f3HnG@QRWZE#0xdWP%jxVpdeiZmHD>Co-RdB4}-p2wj-2<aI%p++F2KLcGFh`E5l1w=_ak>dgK17)Rk63G194%dmoNgF>uw|>uOeM8_m zDy2y|C8Mm43MZcR?qt=yuM?kG@X0A}V8Hbu`xp;?GQh$2*zk_G`4m#MT=y;bcUqnw zY}c}Mgf#*YzvNwE9)@D07rUEl$ZNk;=c36nw zVNvA@e?tt{9Dr`3EaA)JH!xQEl~#u-PFohX^pO$dZ0^wbg4oJzf+u3EIEY#Cu)tpt zI)+szIed6uB5SKEl!5~mvki=6D1D-dg57GLhvtg74sHX6ywz{1Ey>7MLj+j>2N-3@@DbR8mg~ zC>KUP7Y!zIZU|&tzxz1(vy)Stcq6lXl-_@~^FVxlG_MRkSUu9OA2EX=MOD(BO7ilg zYksU4c#F1+9Ya7~`JM(M0alxBZ0rornHnj0f*Zvk1a~L8tbckIyV5_V^BIlel-t0t zE@mxEben^cQEbL+Ratu-pD@J#pS`asZmCp|k>i}!#}b$_phbTC&Q-5rbYa$W%wvbt z&R(V+r7HY>I*8PWI@iaFjd}UfHTLH z{%{(^9hwcFbCs!*@F~m&C?nc}uywZ@?QLp(eHyrX0CCZ8ggKyFjcfNZbBm98*2}f^2zx9`Ep#1q)K(2xQFukQD zr}$IX-T*QMA3DFyg4=P4+13Q3Wk1fFsL&jF?F6SSy$E~?t%2!_9Uo@ZvQAy-CzH6@ z+2greoKwUm!5P~2aA#s5qjajyvi}@Zg}dtohdJ zD>TT|0CPOKOlTdY&?1bw5mg?2q4o&z%jrUaN7 zt0u%VIzJ$&^P}lYB#e=09{wl?ri7yVb&Fl%i`^k2ZpvJyIvbphMqWqSnUCLz0sOYT z^!~1j>#~~Fk84omM$5K)EN)8v`o<&`K`!WbJ^?nZ2TmCv@RPXrKbyRN0OWJwXXzH19&u~(*!XvF_7=?#EzSu z)Vt#o(egkqkS8Av7?&Cp3&4FrXaKkeq__G3esK%)XSpY|RAz8*#v=TnHrq7= z7$RQJeylIY+buc-pU`f+hE;#0z|A`89Svc7$Jo9+;AttmNDln&NSAsa3acUhPY%dR z3m%8m5X-g@d^AXiuIWFO!|Tj@u-J7|bDxwZ@;;KQg>gZ@TG1OHG#F5^KQZ_uu%U6^ z2jjl`{ybnf0lld0r#Q% z#wmy4s#@-wTuY@i?P3C}K|GL3tM1G>MiT!A5YS}D*2FKh!kA7TX83kra+{LF010*h zMqZLs!D?Yw*$VgK*YO($GGPt0lJpkmFTz+wt-jQN;P^EhQ7Kgy!uk1Zwn5l&j{u=K#315L3B zs_0^%D`XJ)E9ybX_^_K#7iHr-w#9IWKI7uM!Ebz)8VfNESV3U&Gpv#Q(c0QI+juQD zk_v%OE)1h6Sd_?5{uCV)$r2!T-;y2d`9UrGXssGy#&g^tU0B})vj`lYy*VEYUd#Oy z(XoYtVQtwN?pv7os-9nyR7t2&s2A45ct6VoZ02Sl_mdcqI(@dh*j6y3HjGg zAI&yMu6emN16MQp(TY{=Dj-M4gQs~Z0$WhF1UKJGsj@-8u zhP7BN+`zR|+_^)bOsbI^Gg^Ei8PV!X9Qun; zcIic2#kL8()`%jh%r%N)2amVm)}u}2bQ5-aOiY3~+aN+KQ6h$slY@x*&wKwglJaRR zAXq@6)Xw37n#BJF)WHD3bJlz~@Nh|+eZLduIrj-1e_8hWnNV^->v9HE>`0!U)sU8( z|6O^}tx0p|tz@%7>L9zZQL*WJnO<-Kpr_}pNgVSYQNYW-LDQ1J{%O3@!DedIeDf#c zSg{X!)VV29vHPz;{0fia7!<;5;GAC_#E*qGDBzO#ag-MRJ=OaLT5xHqZj8o00&@w1 z-dIPtw`FT`2|nRzUJB>RE#XlsW&MQh%c0k9={?8JHXB#l?siqE`1UrMe@TIE-xI zlu8lNzOh>BHXGP7P2~q-0hEy6q0xj?j#nvs=9&T^??z^tRGS4!9l2RB*Kskcph^q@ zf`Onu)qpJ;!5fN6H4tn_9K}EZ2nyh69ql1Qn$m|!-d)l3Z6*44Zl{eq$`a=a4*a^s ztCH3Hm6j3Ev{MQy|9g6MNhIWi2gK>Y+L*Kgpc&FPcr9Xpck^m4q_0nx|9@J5!m9(- zPw0=t@&@Y)LzuPQr95QpA>;4g^4yt2z)%-(vi)}jc=Scphn^6OyFOM-0V!wyew6L0 znzv)c)wv*2_>^EKrRLuS0rg@Znf5=8KsmVdEV|w@I!sS353s@wvGxU{+U#j6n`f=& zy`(yqG4H(Kt_VUFWghPs$%O*l7{=K{_ ztGF^=YoCI&DMVcg*e<&4eS~Z3KVc%u(9RR=MC>AsB8OiN(}4=Ojh^@{s)G8>Q;brW zr@!w;cfV^+)_QL`KOX0>0HY-7z0|FF?m~Ud6xp7Llf&mvJ`fM2T7sZ2%gY5IV0u9R zf!_(Ip-AM`P3R>-_&&+F&8&!J`$G}9Rm(HixS4tc+_mRN0Rp>lg)mgQtvx}f_5nY7 z_4&CGUJgFLpxV#cVW7G%ARq#dzsH$@TZIXh*0pgJF)x}D!{^aSR^_>ydZGW&W zS+hQE3uI*Q&1%~Dn3D}KpM;-SceHK~IPAwzlffZH?+lqnAK+7n0-i1CBxnP7ul&sj zCK+W~`S226OU&hd3TSNveU1wU=RLOV?S6iS+?KsG9}4NS8${I0jKOaUiw(!~{e0M2 zS_V(XHo@Fi?9>FIxC?S3m{)#^qCQ7X_h zC9ru1hdtzXpk}{xoO!jkG)T$a#%n1i>b@@=Ko9imn<#Qnv%(FJ9*Enr_Elfd9!(vt zBP1_vh;K2W!Kn~@6_~!7eKtJ+t~gr*nDh#p``nYb0rPYXT=s%BrBf-;`v!;N-MOoM zvA2?>ji^wjf(HSx-s9Ktf6`!)}s#bCGFSXEo6(nv-?R$UC4v%!G=wJq7jm8JOoUBwHlM%K=(o0eS%ZnJ}FKj0iBq zh5Za==Yd%lUeMV=f9zXDiyixG+N^2Ta_b zo`pa!6bsL$>+RXryi*0tpN3A}@M3k!Ufdx3clDR~Ie);bvTK*#O~0=Kg35qt9p(rl z!mYH7gCPVcQ@z@uTu-MsP?~^*=YwRqLHxgSePJTs6JyBI#}cqRg&Ih5;}Kj-MD&s3 z1;pO~60e;XooT$Mkn{uy98eSK3}7luedc)@s1$?)h>G1OixtJ7+pO^w7b_*Ro8=(W za(Tx4q7@WQ+Uya0)){3t@)fb2nz9EngQVIz!p!tlQLhw}J+^+kT+}c+nILEC0@H-F z8_&iSa6$NEQ1kh0S0)XtKO-?i9ev@}IEZ(@i)dEUx(#;G$aFNKHaCj^9g#G) zWd7S^(Q1-}B26XH7tTex!{!}0K}<6Cl~xJhzuX=-_ zHhga~wC}IrOjaVHZ3c!eve;O6!5c0UgHcLJ1LF*cMzH@%#IetE1eB`tnt7J8rSX+>iI^IHQoD4mbSpQM{oJEPH-c=4b zWcaG6mIsPtCo;tC>LH_0TY#Hc7L+%s-}~c{t_S%fQBW!)=^c1&HDa7vaQ9c!=t0bd z)@kra4IXKi{O%bb{xgN}+7U;1N&fw2zN#FyHHqM}rf#|@17o?MZrKg10q3vD>d#Wq z=+681iZ=O*D|`;A$m6Y8CzMoREw-l^y$`xGb`EW&G9}0p5%n*S=r0*CfoM|x+buWK z9~uG^mn_hqt#Av_Sweb=Wfu+HnO5$J27y$1@vWY-W*pBQX@C>}X4;x9?sTZKqNm`x zAGhkY$4p3bE-T*w;Q7HSYh$WGbyLqei(T2yJ0ahVu>)k9jzl#b2LkdNc>J4s*~=Bc z3VaJQkyDc|I6GVI)5o6HtL-@Ea8dtB-XPG7aT${=50}rKfV#!RM}^9?)_xt3m#LvB z22=2)BLQcz?EBq=T5Xjd{{N~P0o>GVI)_yJ3JA>?>(8Jvw!NdV`voSN2v8{3xnf%l z^5PPPj1|*?o9c8=J|W2vG&D61ob+O++h-9JN%m8>bJduj3B=iHGUxNDd3`eBRuBKf zw`{Jpp)P9nfa4Uoo+$EK$0BoH%UIuwQpFn&2%rm8D^48jjr)Yh!-fZpQ6$3-5Q=b+ z?^w-oQ);z4ez_L*J!eeNZMK14;Q7no(Dq*)I7&&>dgK7$?TI0dfw@Q){{GSUA(-mz zxlGAl?EC?8Y@;G>(~nkgDl2Lup~#o#Lp^7WCT zXxnarFwkp}+|$`U0(oH+ou=W}D(i>P$#2z^LT28Siik$K<6?kaz<8L7zunP$mTcfDm>YmnM|i^7!v5k4FhjT$RuAn=BY9yCM=0$~E?%a2en` zeoKA?-j5vhyFk$lCJS1p@Jc8piN?&3HF0f2432lNM zNLU&k%LcdonZ=R3D)~53X?+6FHLq=K2hh~ej>3^v&in(G=PMegFVnT4++pO`3SYv) z)oL=DZRn%f1;!rQkj&JCnOaq~@(e(;SeCj)4!1WKFDh)_OEr3s!!OKLD)@ViUH2H7 zG_m1uKVT`3`{)kD0mX|ngyv~2mz|2 z@5H!9nd)W|8{z>$_!=$=v)c9~aA=UeUy4yBS`J$uh+1yySDm8=D^x<)_nc2X1>&9t zBJe>^CBrg;+l-nly{eK_a8XG_(Fny)aA+x5Vp#Vb_Fo)92tb7InQv}zm36{>nHePB z`<(+QFQ|moaQgs3L1|ZkAb1t%Q5c3fj5nZk%f~X?;qd5kky+N-#z7MpXIPu%>kWcu z6%)TP>+!Prt0uG(swxl-xXjC1Fhj*X+6?^F!P(wHXf>>ZGuV~|VgGSJ1wl`(U5wQe zMYTN04*CzoQ)x(tf;t!nKa!l|&ET{j)bUvF16q$Q9*Bi3FqgMvh5Ves8VAKJFZy_{ zZ9r?3#>)gnTu;G%2Esv5jtcsm;A!N(LdMbdB_7#MjpiGPWI{h8=*VC90vCRPLCxXm z`SS?v;=sR$aSO{xP&DD>DP4ds(|J2}ijkiG_lc4@Lh-&~!ekYlV&Wla)IjeAJ-BQ* zBQgB3%8+wn4%KOY#SgIhI$x>=Pa)We@F)b2$zu3Vm8DV)Ljb`@eN|8EC7I#6oAK$H zb#YYu`Iz*}s74%}syg{is=h@Q=#*dSR&xLJX0 z84}>^>hmm++Uqm*nlTS+hm#+$sH7PX&=zV+qn~m3Q7gkoXaos>VJOnl(^_vU8E*sTr z#rmkgVvp{k1I)I=5>@b&!mi&$gOA)T#6Ua>yGSFfON?nOeyf2IQ#q8#9Rf;$hIkxF z{9=0p-2fnz&R=ZX0o&Ggye%bhIk9>$Yz!l*_dj<~WnqCF%h$BpL>0zL<@>mV+6OL0 z8vibRp6Y`LgCwj!sSz*$D=Y>HAf6ya0&Hk;&<%{S#ewv};B&>EpZm;AJ&|0*<=*Oc z-2FzlbV-Jgw|t9^5E^07hkR?S1#{uXUu{%j=lhfS6YzC{ zf*s^2H1Ln%Q2}0WaV--YbO6NU`Dpo|x8Qd)3+wa@)NgFsf0K`Q&W~`QyU{8s)VRlG zq^3j-lmfFVSCO7Nr}8zl8iB7nPn*5EXsV%l>J_JEcaF7c+R0qi+2zGV$-GXfn5f5# zBGdWRDFN7Azy+fk>mB?FS^cqcuIHcIa^%76I2Ul(5*+*m5CYwDR98~rePU@6YBuoe z-%+7Pe*xA*_unT-w&ptjnx_Z=9cLdnrXO0dF3*Xt?9}=p$yF>#W_h&$BA<_PkCip#^OfzgpTT5M??xD` z_TBzRz6b%;A{4+Zfa@NZgNo$!9XVz`Yf)&eyOw+HY=8B3JDnd&0Q&*_ZLCl^uVKc+ z@hn3jL>;fS4nD)haS^#4sB%Dv0m5QdQ;A279$ebRI10&Xu4_?dzuF^)LL0A`NIWxxn7pbeziYW5k0N8ZN1;OY*Ve z>Cg7Ie73Q@)z9t7Nwnf;8F0Hh!T|A}pcQ5W_dAn=LGPPeEWkf&Ha83c&mB#V3yd5x z?(zPlH4zgNR1-#9jRX|fu-Z1uFM!4u%NYNAb(RF*D}Ml219r*xzad)XWjZ=4q$u5! zWUnke&kDg8nIZUN(qBnk%HcTnkO<_4I63X1zPl?<%?YrbO3FcZyUrZCP2tbC6Gd( zSw~h`9c!vPC1PtApAV$1K|}?;fF0I-HO62-T~JzkFqB4#3{`45Q@@IB?_`(Be)0|_ zZ)dJq+qJWUFk&iJxH?wiRJB-~^^$oLxD0>ZlftwdH7-pB6>w|?5Bzl-V{!0D*9VwR zb}kPVlbgcq3{6zN3LkyX;d)Og)IE>?sZY3{O$)X?F9&Rf8}zrCnApDPpKl+!fN#*T*Mn z?6ff@_M%m-`&?Ln?Jb(>l+4~DhT~j32yp;xmjPrM zIDpYIx`jW+_o1vxWA`rivNU=~4W{<(ueAP}sb@sSg~GdLWK*;xovyJsuv#IV_>={@PRH%cAVH?3|QEQS0q|ur}#=MM;4SH+SFIXWI@MG4_1S^q4UAtDl3JnxPDq`*< z4DIR$AKmbF=$ezbBYIf6(JqF^?bdQ=4Gzx&X2}gxp&lpCp+wI{FZOg;2-qiFV+_U6Y711!3BII zn3*^YCSGhTkK~3Ac7&lcgluAZz&r;C2edLdN=a99g!(rq`MR0zNFzeTyt2gb;f@AZ z|M1Z!NPT+qRqXTus4~_l(5dffe#zRO2JaY1@I60-T^Nxz%{Ypr5NmI)*$#Jg9P&$G z$owZ9J&ABMqQCbc8LfP*$``$=a}nfjW_F>q+|>MBs2WY*=PU|$RkhvaPKGJCe=fPe zQb9>ZCI>J(gt;l0k3YqvW$90BrdVY`%%-HqC%VNdLM#QQjH#E;55-^<{RN zR)cIJ9?H0{fv_WG(Ywu2D7FHl9w3aw)OgmzIFQ@GM69+3At1S0Mb~24%u~+YBrV&ELN57*9nh?Cr$p*T2%cX9{wPBg{5e#w;p8Hw~ zpr2Xz$tm^rb}T5@DlOg{HRdOZ(u*bgA-Jm-MU}f9IRR z01b+}6Ji0aGKl1E(ieK1ml@-L1_PRjv%hW>;~}7l1DX87j7VGh!$6Q`k#l=cij1tJ zd!j|q>p$cXX`tGaK)lHukirC=QT6j_7=eKjgvgILcp0fewUFKgQWVfEfnAE|N5RA7 z{9F%*6_NXSZ{I=-dg%ksBxWEX(~02r$zaWxCU=GQ7Q^)Im;dbe z1gxKA#v%}e)PFr#@2cNXc#j!+)6)yoqIVyoeYT1}eoyOGzijkG+p)8uzXCJq<0yXb z-A6o@Z)FOe2*One(Q;r(J7_#PoZp@GB)Yovyfz;OQuRd6Kz>_hGWM4sO+yRfx+Cpc zxbH}Rt1Ta{v}A!^>#TF9g)c>XdSNL#LFAAWRNj?7wF`6NZ6G=W;29Ku3qWbryV6_s zEAB7v^(H8haL+mIZ1#4$fVwA75ecOfQV^Xlo9wu+V}dq$IEs$#&d#wz^}kZ|9WOLo zdhKtfFzoe(WoW-(%iG(tDlpx_`VXMb4X@O$J(iaz{TGp8U}3SG>0b_9C3s`N*v;!% z1|2OIe8;&;_a-aamU|coUDtH_2`^5H>pw-&83T0FQ$VrVO8Mp-0;R!+S07Ly$Z5UC} zXK>JftU<(0(bv>b5vB#P21!zq;k0rqjkvDetzeB4`y zJK{Vb^V>~B;-|rUEv$r^8M16;fE1aYUmc(s0FU^_0fVoZWWC`A^anVZ)Z& z)!4VzHi5OL<6Khz&SS6s%71I9?mKQ=#OwW`It`4LaXp9yDm}|Vi40o<5`Yus^KXjY zY2`j$(*Ja4AhW!3jaI&SzN%nKYC0#Z>-TpFof5U@zhJRzv1X6?qAbJFrV@xAAfP1; zzMFBQoRVT#_y=zEaBLgi7a zvcjHTNfQDt=aYi67N(G>fi~&pPfjnx;UEeV9*AWDE1r?ZwuW0wPc(bgTg#%^E=WdF zPR)&?Ai3jW44Kk!2GWG)b|I`&-nH`D#hciu zKx-08N`-|Tee0|>o^ubtC7dmX-y2HE_H#MObQCAL`gv9O zn^%SRDV%!;f(4!vWcdADuI$IGTf{?-m(iy`T&pH3Zyd^z`Y#$%@}W=zZIVM;Yl6j;{*;q!+^+-py6E%r?-Ej%_Lw1C;qdaeuVOf5^G(~yd983nX~ z7G0?9XZE{zIgp&~al>hzYajQ^;R^_Y>w)?w;`aA&r~DX8=z0FsLIedn6D060EJz(0 zY)?D|S{AL})43(KvH%0qwO)|VFgOPt7Rgrwz?2$ogaq9mp0>Nv!-5FsjdHI`rB37CA9Gkp8^dZ z=Q%GhStY++m(JHCZ86gw zo_o(MIlx|T1>;;esh@>qTZVX_i$QY(Uex6l9~^)R(Ae!rz={wtm|>U&bxQT7TTMm$ zZqjK;-xD)}HKP*nen1M0pubM^V)8R`o7|+DEv-n?53Rhd_?1`wtoigKtRTT`HHCO8 zdF4pEqC_@C{Sr|$m`(|4V5!JNqptJW3Y+;Yt?9o@(S!{zKJ9{-P_0Zq?o zE5Ue)bgj&CG4E|YX@FeR2;$wNaR^5{grcSd{ZFZ(5}Vfj`*J36SuU-H9NnQYjxFwdG~$A{#JCbm!B#iAN-!3wgj(&Q;Ryr zShU!p^97`?rz*g<#PTAukl-&l(I`brj~Wv9&}`Xpls3-m*UnvJ^pLNiN3K=Q1qR@X zmjZ|DqzV?fxu%jy=SO2d6W-iF7HN3*c+yt$mic+IUJ`}hy8YZ zqJI~Lv=SU(nvwgNn~&GtfhZ~p)GUa9B<5$(7zk<~(~fzaYmVSchsAzt{vY@nJukLv z4}OI)@H);2^YZaQsJIV$;UVnJ@r9k{!6tqFiK|ZX_9au@w@7oQVxZvjI%oA?XGk{k z&VwDFfz{8kH-A!rF2DCHF(uB-%VIg8AOKho4x`#nM;e)B5mh$0GNFIoW*yT_{ zHy2uge%RN?!pe%O{0ulqr6mr;3a{uC<_6O})Nye=*aWKm%* zZ`lAOEh&MW5Hfintx?LO#vtzacMca=utrO~ak=f706T)1W#>st`kp9U5QZoy#%h&u z*v{x_&;Be?Z}iQ{!QR^o1TAW+ptkndM`zmKqsZzY85zXE+Qs_l`d{s#Q7uZzIeDA= zO-G4?MVf&=e_SYqh86)0Udv32=jLWL)WOza5W5fe=pC*n6_ycK&rCp5np4ksS%X;t zF%Mtcb?*HQB@Voo=^G3G*&j)dUv(NjKe7wh0U{bC)B_)EU3Z#^l1#bKik!Q5o&GqT zI7((`qewnKPeNZ+FLvl-8i#AN*`o{ZN3RYd5Q>kg?buu`I&Z+jp0;$)hF4QI-}B$) z%HfA)1_-)#^&bqU!BB>pc}G`lb(G5gerqy^O+8Hzx2)A9_B|7@Udxl#Do|b#cRS2} za>UtuLSLlZahsq;e#xl8|!2bsr#lc6GyQ zl*O__#H(v$-(82re~Lsm`qZ8}Skl1hLg{F`@FJ0cxy(nfM)&F>JREk}0FGpLZ}(vM z;s*Xwt#}v7I9YITVR{$Di4rq#pRP~@!GXXb6g@cuHbBK?ua*qxfIJH@Ss!mBB(Lm& zenUZ-b~2}AftssPmCr0f1u#Nq&C~8kv9*$?Uo4Z5a5&JSYmi2Q_CeTN16-YL{oFLC z|N5@oB3s!T)f9x(LEsA*H1n55g8d}O>_04tLbiuMgv~S%MBotBp1e5J)K2i-5oaJ} znV9j+?E3nih`Z&tIoQ;=jF|`1iU*np(+Jsg6FKxhTHUys2G{s%)I%*xr&-Y;f#+Hu zo;*<=^4VcMPy{Pfqi3;Q@h01evsM1rds`lVZbNS*t|U#u9>m?h(lUsSFi1oKrZGXa4!pjDsj;VC>KrL(udEvr+Mr;B1jOCh%k`UhA9D!l{U^{S*;2!Vw8LfO*8!jmN5xE@!fdZzo&k#=?F60Lu~zUBHBuh_ zEEj@1lK~24k5-eN4Nai$OslF>sXXy#QuFYJ9S3t zkb_Mf=(Zl~%oO;fASfC*}BAM~6>iIK^YNn%MFVv8$ zPbjZzhqT8rdZ$r^t~RY=7Nl}8jT1qZk7xBWE)L}s-s3-H5Mq;wL&zv$Qtuwo_uovj zAuK$Xz`3at8q@x@FVOEI-i`=QqyE)&4OMPFDzcmQ?wfe*cjyos&6&RxmzgFxXY+SB zRsKn3g4D#%CmP^M$L6tLztsh{0yb{j&)lD=kos3=>{qQ6O;0Xo8KqlZ_MsVluKb&B zPU~Q1n~3*1)Ydm$Hh^+aFoOI{#E<%MtQ%~ zpHjrTKUEzEmKWEHZ7#PpYQ4l!nUP`Qf_x_mY$zXpAf@3I&|O=Hn}2sT>|b8qZbQB8hf5 zXrPVN2lpmHMNyHBhH*FzUxMAOw|e{~7WV5+JcDWtKEE=2IPCD(s^^3=zgtOfbQAry~h$B9tZ;dzIgQ^t&UflCJHSVj z>5qyeuOWn_yBs-%8~lzXvh&$8cWU=_K7F(pq7Aybkc_yO;S93U!SThR2SKn*R-xbt zhH%tdPbx@WU{`W5D>7+bsQ(~}eKNPXR5h%;I#j(r*1r@&@nME-ey$lM4la=ld5u`E zD_j0lrD(JPCLnfunvkp2sM5cAp^shM#H&rdSf`HwR2iu5u5Og%akOL^+hg&UUa&$B zQtZqRZNjn`5de(nT=>z+SHGnZ*oV{*%U!bwc?S3O5k&c7eANc$y)UN+!zxDOmfsko zvGJMHA1YZ5@Bj$An(hffaFr1M8<8!;2_c{>|4vk3jUecHq8+A3qozQt&&nDo=pZ)d zSL=0rPJSI`w`b4((u!goZC)pVFUe3B*I_sg@&L>zp?_$@go=aa%H_HnJG)j=q`>44 zKFc@=Bk;QPw)`zZGac%EFuDzmo$a?r)!9FOXxBW00SQ=%l|E$4l?fz@_x_o+`)?p$ z1;H`5t6Lh_CWd*$g^G@|P*a}QJ~?{93{FK3k`zseM^Ib<0;gT0 z^&~SIp1-ezw#(tg*w2WOyr=6LLDP;0uq*_4;+1{l&tJ2E%iL2`P?Lsx4GiCPpJ^nx za3mOl!`85DXwc|kO^Li!KBPQrdq+g+NPVlFU4^iKsqelU@n77T?gkmPB_`%a@_{A} z^FKs+vz10c)N=T}eSgc}@*L zC=!RZHb|{WTmRt)bhz`ZJ3T^iS?IY}#!GQvLLk-S%Da4$Z}8qR|ujB7T~FmA#niEDHw#oTin_ z3r?=qnWe^^QTvZiAy|eb{h<#)Blc~P1RxVz9yitYRn&@KUQN5I^&G{)x^Mm_UePA6 zpyOw0AHm3{9QjAEj-I&(2 zkht++NCF!If~{9K%L%(9q0xTm$))#H38~%_89}O-xSXHHu`#NiaEB>AoKeh(glhd3 zMS-9jh-VJYH(6xD4B()=b11$M7k}G*pn``?1ifYq07bY)>t72w@=rABhsQuDNG@Ox zl@AEGZ05JGFflNkm)?PYIxU$63S~@U{!|J4E@)+-1{i!+%Z$?qc^q((-j?PxbvAWm zT^{DM$(a^T+U!Pc5gThZ!pso$pHqu12u06*z3P}BsHX%@)r0^=C-{EXSru%&kKK^} z^T_-!H-aP95gPmcu3seWIz*@X-_k?H z8~pg08=kAn?X`fB1X+TA8v0jKpNk3Ft33|sOF$UbP=1i$Loqm~t2s#H zGpG)fkr_KGR+kZR{pT;R>3Lf5*0X*Q4}lsk`|U8B+PXiL8_uEe_v{~-wOC-h6oXBO z;Jr5N7?ya>=WKRua+1wnR9FvJSsUZ_m#aTpd7$Z>mqr_zJ$ay_|92gPIIOz1zD;AH4ccjA_86|S%T;Mn;RhV7F_DN&}%ip4gMhDXswxzIgtJw;-Dp9?vQ`> zF?GqXeq?x|&3n;hU1O={gI5^(DKlW4%lzd!4V135hK2qC4quR^UVA0?eG z!C7}^1uBTkTI23y%TY;q*9pG|oIil4oh_3#e)CEK>m5*{x!^{f zZ5(?}Or^i;q0wGDPYpE*;yL#TB3^H26;Oj|4r3y#HUR zCkhN2qo1cR*##X}N5@S=ENp;d>A!!+Y4j+%Pd2Q{0x|tsk6-gz#_wf4lOrP|p>x%eQc*}P(h}L*Dq{_-rl|i z2uXtcBG5(=LWDe|cichzJuk+4O>{G9;KSKT@)`SE2(oYQ_|L`IT^!VVki>j3Sj~9@ zPvbq0bwsO77+f!7p;sI1G@0Bx2AR$Dj%!caNL5d5Mip@X#>9LamcIe_aX2zl)%kbK z7ydJcE9VDB*WgQL#YBrV<^jfn-w!rB@Xz8s_b{$orH*!8fkhA6tEQlUpZ6~gz0A|1 zxdT@t61hS7{=MDtRyWOmh1yE6oJX{UxR1=}(?^nsm3|1Sp$8puJO}G7>D6hv#(>r= znd>WubmCLM&O%Bi7Ze&u5vaz_^>%}?(v|MwAL__fAEv`gH)_gDBCWz}?wc<=yQy;v ziqHBGO3KhY+kATjBqc0v@up}y09SS#bRv*`0_owZlo_l|Ql%a~t5on51J^P=3-u3X zwx?lcZ~>(P^f-z!c-gC5oJuKP|Lcjf(LM3Queh5>Vu%*#X6)xm1YNG3`jQaCwk89l zmHtMw?_?$P7I12W-G-j`-L5+^spdPrywJum(;;WR*8w@EziomZn1i5m57rVlcn|{c zDFzt`TQlpB#8y2oC}9Ej6vxctEa3Wk}#pp%FH2ZWtik`iZ`zL(o^$PUk^ zVlA04mH)Ly9y1jcX2+|Myacr}HL0%7-28Tst-;sxqhLA&$0LX&fYT5M4G?(M_53Wo zbZf|ui~AKqF*@-3bdQMBVA=QpZtjPkcqF6=kA{aHgG-ls5P?oq$iMN#GW|}+5aWby zEO1`g-uPji9V`rkgYDQYhO6J}id2d!F=!Qez=Yg>un>oR58%j=y1X_SbLskX1IeJB zucFrWU$Yvsq(~Wrj=6h(XpY>!wN=R~N{snbQ<;Uv{O@N6+Q%z>Xx?Y38w2Vpn>vDp zZ4E8-DmCjjofuq3b{Umos4jUy&Ck4eOVu?qT43p~^%iMvxJgOH zavF{b#@K3(r0@vis`FxL;2n3JFz|SpNh23MrsJ8@;`U-H?xsyuy;!hUG74#>}p#RsOXg8>DX!*N(#!mc5#DK&T(iUHHaFstlU*^GBVkKaiV@oFq0VOQyi z;0=Ocol@riY9vG4*CMe0Bt5>Nneycc^)6ntTIQ^`seRH_%{mre`h_0yUia=DO})2z zI;Uqd1T$}g{6y1BtITb__*NFlg$q4qdcF1Gg(JFnv7m>Qw^>plI9n2*(t6Y9mg7nj z)&o3E$y2jO9cNO%FeWijglK#+PuoHU&_IL@QuiLd;R%phw*_39t2NdzbE;U*=jFEp4DykTCe80j*v32+lh*xX5bAQ? z&o4sdml_ru4^?_NT>I^|b9NmSNkAvXLN8ZNJZWr9IA9GxsMe{R^Vn|Q;n6i&c^V7rj=RwlT4hE}*nFdTEyv56E`j0MPngH-Vg9kzuZ~jknUlmn# z+rGJJkOl#f6bWf1MH=alknTphR7zTqlon|aP(ndaxT|5}UkIE+DP^yQZ)mW9Z)?^d%wlB!T z$@zKDLwdecaaGyS@zL0H4lvHT)e0qz@wdD5(EWJq1BOKYR}-_Fb-vW%#@qJ;1A(yJ zrXuLIzh+bBWYl8p&^unntbz(24;@s_qYmjpFD=q065=ES_rk(r-!cOq8w&82G7C0t z7uaOs1Px*BFTA=eVlG76GW`k3*zWMkTfeV;4G>d&I)|IVe7L67Xt34su|)y^otq6K z?d8{KSp)=}dEp3$$=$Sm*CkuWvcN+fCQNF(@+0!a_Y_c!KKOxj^$ph)@_FePq*I+k1RJFy#O_GTjgFOIYlxH z7k~qw9VK7w49brUM?pgn(kjP!4FFuZ@`GYV5wSUCf7kqFTUP=YbZf~@#ob0_HCvGV z#Nh_Ocgx-o!SqY?q#vub+mp%3u7b|If3JQaSx_7wXMOWu!cI)<*(?ViqXwcD_0s7r zcg>FP*C5ENHPZLF%tQ8kg!aLTKYov(;vR^qpX zE(zIBe2oK1FezQ>;Q{S^we7c7-OWB*V|-7t=gkk-)vXFT?S%eb^Dd~dE+VAyA&rDpiALK2ux5yuV zIKA;;$O?iqJLQuoDCw>UpDx4eX}T_oRxptMYX7OEeAxJ+T2W%rZ{Wm1w|0W+Wq?gq z4>vV9JVZZ6=_M3<0$tb+(W7dN@s|+AV(1#uadBh-4WxTc=|8%YE~Q3Z^E+{bhq=I$ zmFr0*&}e;469lI;SY5_ywK9}kK7XqO39ob0MPK9#A&O8Gts?o?)WnQTINiy~L&YqA zV1qOxSqGN#;QK;;XNZ7J(J_V8hjhjZj71KjQ? zHZ9F(uDh0z+uIWH@k1BA{tmmeF~mfL)uUR*Avh~>v6tUib>aK z7uNN9s_#F$`p8kCR1J2l-=te0=R)LAcaAqCTNdS|TF~yXtK=J#D@7>Lk})qPWOIcG zi%<)u#a$#Q+4D5LTu@LzYh^htlJ@&kQr*#@Dz2bEP;Y)WRyY90U0j^a z_yKYP;GCSk{`3Vek0$&09yG3l0bB(-isuRq9qh^Pa%D>H7=4k|xr&g&=D)I;2x^wF zDhgM?UgDZw2pM?@21IiQBN+@jt&%MxA7N$y9Tz-9&@qcB`+c^aMMj+pf#<^Ra}@t3 z;avt%B^W9~f=H#y%B>F=ctyJjscfU=GAZItje0$!I4IyV0P`0Nv$A2BL{s59|Cw?L z?l?aIOq~*sZgU~o1pUXGrIc$@QksU!SC@)vv=drKQG4`9BG6RP{B$k)rWeFll91;1 z7OGIGQi=Dr_2(4fr^lh(yN9Xz)4uhI@mzz>BaIKeC+r`@=sp_$u{qgAE_o0K7Kw?^ zsPtwO?`EFcjXt@jU)|8oUi=lm-qO;)QC=Ony^gH?&yfXE`m1zm2{m_pcsj3XwL&8) zOn!==lMx|u5DW|y3HGO%+sfyDAUMcYrHcevS)$2-+h1q(zf!gyYgD zjQDz9k*A+HBx%IP`I-e{L;ujJX==V^<;D5TRShE}b|@asogr*D=AE7GZ=_Moa`Fqqd*? zR^Dx=5FjRwhjo~ovpbDY#OL+;$qJ2ZOr_@nKIzfN{WqTrmZ0eDSnLu5l0f2hvO6z! z^Gwg4ODaa#33BVY5Rkp=0^Ef*6U(p3Qcmg*gL85M+9;T`qzf@8FpmL$ij-P8M>dvP zgzya)KQ!zkS+c%XAL;{N!~rBKIQTtv8D@9x*-diJYJ4|5;?X+*S~rO5k;K zS_VXk>j3B#{&MWtZ_iW^IPDB*WwIERF zzsudjjUZt%otJ(EKZ6UFsLxR2Y=e*1sylQG0|S%iBhEzu8p>5+=o#*Eui=M<^WUJotAe*s~SS=3t>+0ZkUXz}_y zYwEd348fvCnJ<35vsCB;F-lL`O3x)_=s5Ajr!+|0HjtKG9w+BSrMycY0J$2=eLA7B?%_?h2octsD?SG#; zveMxS$YTWKJjH-O{XK2S$7wE5S43Z*WQD$w`N?jO)V4BOXG<{V)u|5RM>55^>-s=j zZd-No{l-F4;K>tEtC6t{zWm4`DI5AAtF-agaFe)H5*tZh@Zyj}Wq;I=aUU*W3bwP<%btV+#TQuXJJ{_g!;Q6K_|i8o_LuQ#lY8-aU8Zr#s#KLC_XjBab82 zW)VE{mq8r4qO*n}VFIsMlK2FzVlDi2B`~Xiw2^Nn($j8T@z8t!0e;ou7nX3+Zy&Gl zLNm4Li}8hqEg3r!p=S^fxXOM@maed2U;?%rU6VDSN-IqH23(kPzXRR42ja(st{WAK zo;ZvicOy4PtjQ>s=4+8=QlRqf6LRNZc-~6vBzr9cM~7<<@~9*3_^ObZws`aL$~psPbE10GlP8vc*xOu zOsC9@r94dG*V%O$Jd|T;_%am*745)-kc@Tsbq~O~4a?9^S&I zDu?dmzO&QrB)|FjU1Pa`w>QAR(Agtptk@8|f6ajmC4 zC|?`2jn;sg19@wm-5R9_4++OYw6T1}v<9ZC)jyjBBRMw!VK~*aTm8y=m(gTHdIS5z zMc{hk!DuzHepRDq-(%Q)dS#I~Fe;D?zVZbE^}@#TAe9+<5(CA_9e`Cw-Lz5%cF6u} zE4!Fq6G#d3u|bhp4a~{H#~G+q8{@;d!1;kmqunT!xjWJ*moJed38~O=x9v){yV-HG zWQGiHNEP^xRZ5Zv)*tv`PY}F?q-Dus?Rb{V&+Zl`*KYHY0+k%r%1E$u1FHy!(b>K! zYIm{cTjWrEKt{X9n-crGqerZt3}$?YGc%y2c|96A#DzL-+uOfkJ5aG{vDHVjywsoi z4N4I1CTu7cZ=p~6H-R~t*HKr>#l+XHY%8T0K-Fk{e#)Kf#=9<17isqhzwZP8$?A_> zdk^fzRwb?9LF2;h_;csfgPj(v2gfIU0KhS_x6xoBWKz7U)c! z^QXpoP#A|xIaj%VNL`z#R_{58rdk1Rwz((tB6)R&vK-ON9FaD6b5dl}Q}s1S3lWyg z*c1J3l{7_xbB@k;=&Y=ZX;)CBr$+w!;J3?z@2P|@6f_NG`ES}l=L*!Vkfja9dA?#& z>y|iAo1n2wk#1utOTea_Y;&$uei(nW|gF zpNNc20-O_IX^PF@Tpdx>x#Gff9G5qLej`1b+Ju|4Wy)f=@l7H+gkd6k2>@A_Y!!ak z?K>c2{>#f_3eF7ekt*@=vqi-sP-f-(UA&8?2R0rfrqwrF=qdn1MRcNY;7P+kp35;Z4KSf%OPTt3DQ)}thG15A2_Rm*@>@NZqRiup|BjXK7Nre>V zCW+2%EgglD`d`-2)$2)g|BG+5+~ZibQiwjQc4cc#DI0fsMAnUMB{oM4|CTYj3U$Zg^tQb-nly z+zQxv_}U}?8St@}rjOFq_WaGvyoRZ6WxLzN^k#^Xkj!2j`6_3yt&R;YyfK)Rn(zQ> z957dzcA8P({6GlRd-By;(>XDZR5Nfz02l9Q4Z$o`@xsnE#~T|SVkVi;-Y}VBsK5W! z{)6!dpA_pF@{kNu15R=(HEt`7&Qho_6?gXs#lU1mTG|twhq;GvjIV1Hnf`%AQ-pO? znU~Gp5oCE0l*kIpefA{yzKg_ct>QMB?7`pd;{^ggaj*(O5~qiYm7qAQIp2MUPp_1G zda_KV^~e6VGVsm_fKE@NgS~Y3Qc-#7LyD+w`8RrYC7e*FsjpJix|+rB%dZ%N5;a@C zM_;8)r`?V8k*ru4o_(>n^U$i|&n`WSa3xN+Sz2{1gLgA1M5%%=ABmu(9v)3UU z+2irEpN1^K+07 z-=@!={is`NOe^Z+4dU?@-y=QELWY_vKf$cH=DSQe73NQ9)^`p@>_$fS`qoaGB10mA z;_m;FlmCqLA^*YkqwX>ji%O7fWfQb1-Uo~g-d?~%kM8@>+G5kkHI9zT#$~;s&vabr zNSet0;qu`gn~*)jXS7&)g=dXOg4U%82O=v5%vG$CP3SC$p(VcS1T=$&!Uo6 z)Zy|)3Br})*d_X|0$tcX*BJ@Npr9FM`stI`IQ80iTYBDt6Q9eViZ?RZ={ns%XN2Y+0_LUa=9R~? z1bs-F%i#MIuy3!P!;FDM?8tO7aOBN-XcUU)3W2Ku(3w+zAGH`v=m4z}c6xN^N&ugd zl!66JLl18J;k-F-i2<$U-K(cotMd!Iq9QsjyNNA7Q;&7>(iyWCe`px zI4{9ob>CON#=GwM0i3PhOV4%jV8mE>R%?I>)ifFee?(CHJ78%en_aUN$(T^_(8jBh zzdCQlrr>~m4a9gSt&v}hG}TK@y@T)v;OEXs^e-;=-S?ZEJ5KdO z;L(*B1XHAGvX!3kVv zb@jWdz{S{wOQR-Z_&P~w6pKzY%iXOyc*gCSkq)!zocOW~6`Xyu77IUQb|2M%G{$wY zGp=bhitj4=cp;6RX@Apqv&f)50yed7EU+{Hmq$3o6-E=IVX;{>kGY#8fSd)Kf54X@ zjwj(mCJFLROS6>J)TVd7ydG}e)5O@7ng~zD{ooLmb-Rn1)i#LE?=D#BQ2JFm>kNl14+w)Go`Jqx$i`P!eAX+FwQ#q zO7(HMD?`yM;yQ#S^M>E{v5d-*TBAyP#K&3BsIe^-~vZr3-w$yaW$9I)~1Je|X z0UZvmJ-{|Etv4s3V0kj7zv1rq`{VWoozT%%e@iY*SpphVpom0{81I2EUx$idjiHB8 zi&x96=?#%lpumBvEszAA%U>+ydio6;uMa$o44Th=!73gkA*JN~bZy>k?Gx8B97L_9u602 z;o#u`H!%V@{c6S9pPEj;@?9~>;~2~8aVS}x8@Wf1_s)4i{W=TGKjuf*0WWr&8?V^A z_Gz=domCytjo`6MZ2KOK2_A4mMfuAZ6JJ^HFd9_Ef3;icziOa7_xZ_-0MLg#pj|Sg zpMxF|p1L8Ne7q+z`bAFb=yxdvBV)nY*C%u8z#p6Taa4SBZn2^+a0izTwTaGwieoK? zMh;mPcZh2vWMyRT`5Zd@9WL$|$dyYG@#2BVLW{G*4bY=D_MchW*d%0RWSqGwDt6~T zFzPXBE<;O-Es^5E{(+K^P<`FW%VCdHG%_wS6F3k$n- zk!eUzzXA!c!s@-76@YH>-exTK%ef=Zm=lNQA&>Jq`;{(=r@*aSxA>eUA;b0Xx>p(w zDf1%fD^^xk76y#ire}mIEqlZy^Kt2TW@al*s-B*iRL7(DprpuiU625;sh6*O zz`ppyXXli3uNKG&;o;G2oCUF)7#*XN9ZHF0%{6_Z>lFDx)GzL%V<{B9^g+i`qV@Wg z?|pz=}x;89+9< ztj1pv=h5ry4(8_OPi7i@T=V|hxhnV zS{jbVhe}IBuX1y>xF#o@4de^m=D>FA2`o4lB{n*t%RkHFNTB+jjTTfs+|=^1_BniN zJMb=>m{EkfTs0Xb5l7~+$V>DGH>#^M0sCvg7rb8IGqy2tai#@M$6CXUj#K(PmSHL( z*Zk*2P#qY9_V>m8@Q^(YBG_^6-ns?J?pSW?qxV`{Tc1o+a<2XUlxy9S>VHsZd#QB4 zniDl(ykfW`H0Q7m!c=yf(YW;V?0CQFn6Q$9L4_T!^hk;EX5;jiy*an#tJ>#URj^D{ ztAlL;v#LnW@^|lp-Ri$=OLxRPi9|ZE3Th-&c8D}unGoWY_&{F&_RUjT4j1_P&o?zU zCgPd;rWzY=B;svb%)9*^Y8NemeKEZUmJyKQ9F>Y;^!N+?VRE8gLA)IWBGI^=8ISKC~HXs}YFZs%^WRIe$ojY;@aF7fv_ z=bI0OC_!j6sM`x(K}L0nIE%YKL_yqX+dtbnUPTeHCMAWsK2r+0xUNO1Z{J|DRGLWE z<7K_>ryS+L+#UM7F4K0(; zX5GZpWJ~HpcWi?(<1z6Kzel?Zc@jZ7`P?}9tSyDhJra^t)45si_$<$%=OyAax9gD|4wOSnHb`7%4eBQ zfTHZwI0lyDAdNZbI6ZoK{=I{J_)R|jJtFr%w0r06ip#l*93yG_%Iml&h{2-+jR+Ry_imG17Sz6|L(NNu@(!(MuUh2??17 zq^xjQr?}f#g9I2ocfHDEzDZkQLIRmZ&&|M<)VG0@5}hV)oR>JdV&R0ZzCLZSh&h35 z83kQk#bM{^kLM?4b&BGIqJB5~9>)yNXJ%`bZ2bkHN{Rs! z9zN%}u9QTBcf9w3A=n?D*FGdtJ4JU1v}fh>50fZ|79m!K!0U$+A0BTa4hEP%ib-fi3R?4K zd`CcKN<@U{Nn@8B{g@(WSA;+bT-sODb-f+CKEAf_J`InWWor)w$l_ zv1w^+C9`3)@?)>=U;qAI#go%u-oHZp_)-^F$LHj<2vE)kBP3pcRe9W1STGV_(033d0X8YhP>a&C_H z;;dM&^&b*F#7J*8T*|V zhwNJ$&5akovFnW5LU1<^ILM#kzOv}J#_?wD%+H#)B;9Dej>-#!5ibs{Sfa?C$gWjZ zZ8I=lvEV5QwAwwRi=q5k=SM{RCmi`?PraLOEC;pBe=AUjmQs+<)&af^qJMII+Q^~G z{&<1#XiC`5eu^b94B_f(G}li`w6JhS$MGn=-xPZ-pyelLK#Krn(>tql+_2#~5{7>t z7|<4u?gjW_l!jr`^AG!$&De)m2QTg{Yz9>ORH38^*xq;l?#mN4fE`6ML53$PIp94^ zGn1N%2reU)RkF`EU}RtjxrZP*aXtKawip?hj{eTJIgEHS5@W{8<|trvn&AB8gD~~@ z#-{z%*v8G&Qp?^>`Pm^>{O_L$o`m)~WvNO_Kg~ss!-A6E{o|G>z3*pDuH3MM5?DXa zv{?pu{Kyig;6i}=Mzc@aINDisc$mBw@+pJjluxDq#eJ$`omVY${V$vd$!TA+S7ENz zioRVr>5SX_B8laVDyfV|M7AV`85i#JZA$ReS2LfXV9x(f3)uZ%%`b_(&heS zT?7pQzD=Lq@x@WeN_4c*+D$wOhmW2fSSB>r<)Vnbwb#U8?RU)eo8Eg}5ak!y5U0rqoJ^aA8)(+hqs(zK0K?NCqmq7 zDGm-WYnvowV31ioF6JVJAAewx3JVL9zX$gRKO*Mt1?(q3-JX?n7%Ru<>gw`NmXgkk z`1I>-2zmJMyc?Jj@Q)1bcadL9%o_T?erq$t|E>R;NEom-QYxpY2qOQsxVX5$ zsXC7}Bjoo~S7W6?2s%$kou9w>s9T1bl$7-Lo&~0xo12<}L9vG|@)=0xK1Dz{11H!K z*oy4^H5igR5uL$t%8vM!d@$tbGEJ{NZ z&F=7%c^~3TyU>};2XknBV$j{uk&{p5p@v5MG}9m1F~kiD3as3LQAhi%wz<_xt^PLi zvS#zLV-6|-hqoS&cl&c5CY{JF=9u>dr1}<*@-{bWz5D0)a&mI)BYPEzqB!3i1a9BH zjmE^pB=$o|QSq+t>C=oNtkim5`J~$@HAZv9z{kU}wjr^W7)5v$rqv+%a!Z zx{ds*n-*ZO5H~He+HU>jmVf}cbNvqHwD%e(pP-<{;CmH$C8fH}QY*fj_w0XjfT}H_ zP-~r1?F;gLMynK&*OYBN!*;kH!_1b2rh*)H^j7~Fm1O^iQP~W!#7@+FDtlgrK239K zpZzYp^YZfOMMS76DJe%Ae5$6IFjU~8s#2I48CQ+8n*q+kB^2E!ijR-aw!PVS`jUyp=>$ZLujyLNzc=K=8?>&;1kud|L z*YkMp6+{s=oqQY|ACF*CdPC2}MW9_w<_@;xS^nUt(~dThm1)zHI_&rxmx61kaK0JF zAR2fl{cRX^*VZO)yf`%2I?EBTiD^6~XxB60#%!kdJQ&t-J>9q6T3AXp`CXS6FkbJ) zySuknX5M~HQ(N2odlY47SC^!tnz7c`(#rQxKv{YEAnwhZ&}VDEPkgVk zuFhG0ml#FDpK|K!sc~>{V86iXA055lnS`lr;)~WCOenU>d*$4CVok)3SO4pmhRD&R z`)Hj9x1yqA|G+>X%!vCLkG3A1oSckSI#NYMMwZ$1(Hb_spmbmU8Te!ASJ^HV+#ZVQ zz&jbSFPGbGgwKlZ-<6G_jpn!iZ3=kLXq7Xabzf$**WR+1zZY(Wkk9_GAd&Z%Mkgth zr1W$SAc9s-TcHmdc}y`yQg9#Yy-7`F`;p8&QuuCGzs4;;FF*f}(f4drknuY1Aty-U z%a`bSU#z1&^pun$rRC(nt>Z~VTSdd z>dMRs*C{A`MueXIO}v4Jc>?cppN%)WWJ6Eda`|UU`O`ldG{rZm@7=ps?z$k$wETi! zb%x>Z&sxDr)EnsVc$m#CEL_1%WZ_`MM9#n<4aSqQfdLg8D9tl6Hok}m3sYHHSv}Aq zd%@4oj~qj=bdhrzhFNsH{$unjyL@5;xh|yCwVOlBhWDZOCati?=C{tc+xN^`(IGw# z8!mS%9`*09d?iG{T-z%&1blS=^zfUMcB@e{G{pNb82<4i2h%d%)2)fyi8fPob|#p@*x=R^vA_TH+qZAC$tHf1W@fk6 zp9>2(O%{0AqNx9G3)f&_(QK-K<4v)%bzbGScTsG5)8SCj5c+5ELvC&D&9bsG?_|L{ zB3}*!k4RY_t*ZaZh7G1AH%2UCanW*g<9R(KI|4K*0M~9>rn}GO+$@cbfq_wdH0@*d zWeich;wX?t46NiYP6g+}MPh=ex49ra0U|-t<-@@upvL|qbTlMLRQsio7BApJO;htFSoR&%KJxMs0*9BKR$Ok+ zWR;8uWbi6I7vtpW4KN;tytfrAmC2hZSBpzXSnw6I>b`DiWo34LymP!isH(1}mTh4b zteRirgLEG{n}kJ+mzNaoY_!o=c)2gD)WRw-E;;!Xti@)1nWDZWRBU^jg)0z?e!}6rvn!3+-garqGSJh*L5N-1PXGLA&CA2X zQ|rjg&B}@sPIu#C09HcerC3^z(`6bl>GU!#gcmJGPn5=OJ3!X(4QGa4dV`JJ% zr>Tf6zf&9lvBkD*EG?TYc}{+wfg$7l7suNw!ds2rhaX_*ZES1^9(=qYCWdV}bTQp$ z;m<^tTE?@|{Rd}^*P#aJ8n3X=FE7`4O(P6^CFeIVX;OqeN?>)=bagFztIT|Iyb!Yl z^DRCri(9)`>ouKtiHEIZnZp>*SdIG!YT@Sq(oV6%q83+BP!PLTRaU0X#?FrXNQCDV zR~8t7OH2R$sCRo{V4(cjns#APQG5rjk1`1IANDk>}JplN7pGe560 zdcHn-OHWUa2OK8TYPW2%e6`=@=31@vX1F02_T0k4uDag&_DHM!)d7%TiFd>Ju{vBI zi+}TmnTCeufwtem>E9C=5#@HnY^>be6m?Tv6IIU1LqnQ1z)f@-&y9Phqsu<()k@rN=rHS(l#8>6n$wl#tT5vR9C+RJ8uG%AUK4C$>F3d-C*R} z{^#jmBmL%vtIM-^Sc +#include + +#include +#include + +#include + +// TODO(wep21): Remove these apis +// after they are implemented in ros2 geometry2. +namespace tf2 +{ +inline void fromMsg(const geometry_msgs::msg::Point & in, tf2::Vector3 & out) +{ + out = tf2::Vector3(in.x, in.y, in.z); +} + +template <> +inline void doTransform( + const geometry_msgs::msg::Pose & t_in, geometry_msgs::msg::Pose & t_out, + const geometry_msgs::msg::TransformStamped & transform) +{ + tf2::Vector3 v; + fromMsg(t_in.position, v); + tf2::Quaternion r; + fromMsg(t_in.orientation, r); + + tf2::Transform t; + fromMsg(transform.transform, t); + tf2::Transform v_out = t * tf2::Transform(r, v); + toMsg(v_out, t_out); +} +} // namespace tf2 + +namespace freespace_planning_algorithms +{ +int discretizeAngle(const double theta, const int theta_size); + +struct IndexXYT +{ + int x; + int y; + int theta; +}; + +struct IndexXY +{ + int x; + int y; +}; + +IndexXYT pose2index( + const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local, + const int theta_size); + +geometry_msgs::msg::Pose index2pose( + const nav_msgs::msg::OccupancyGrid & costmap, const IndexXYT & index, const int theta_size); + +geometry_msgs::msg::Pose global2local( + const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_global); + +geometry_msgs::msg::Pose local2global( + const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local); + +struct VehicleShape +{ + double length; // X [m] + double width; // Y [m] + double base2back; // base_link to rear [m] +}; + +struct PlannerCommonParam +{ + // base configs + double time_limit; // planning time limit [msec] + + // robot configs + VehicleShape vehicle_shape; + double minimum_turning_radius; // [m] + double maximum_turning_radius; // [m] + int turning_radius_size; // discretized turning radius table size [-] + + // search configs + int theta_size; // discretized angle table size [-] + double curve_weight; // curve moving cost [-] + double reverse_weight; // backward moving cost [-] + double lateral_goal_range; // reaching threshold, lateral error [m] + double longitudinal_goal_range; // reaching threshold, longitudinal error [m] + double angle_goal_range; // reaching threshold, angle error [deg] + + // costmap configs + int obstacle_threshold; // obstacle threshold on grid [-] +}; + +struct PlannerWaypoint +{ + geometry_msgs::msg::PoseStamped pose; + bool is_back = false; +}; + +struct PlannerWaypoints +{ + std_msgs::msg::Header header; + std::vector waypoints; +}; + +class AbstractPlanningAlgorithm +{ +public: + explicit AbstractPlanningAlgorithm(const PlannerCommonParam & planner_common_param) + : planner_common_param_(planner_common_param) + { + } + virtual void setMap(const nav_msgs::msg::OccupancyGrid & costmap); + virtual bool makePlan( + const geometry_msgs::msg::Pose & start_pose, const geometry_msgs::msg::Pose & goal_pose) = 0; + virtual bool hasFeasibleSolution() = 0; // currently used only in testing + void setVehicleShape(const VehicleShape & vehicle_shape) + { + planner_common_param_.vehicle_shape = vehicle_shape; + } + bool hasObstacleOnTrajectory(const geometry_msgs::msg::PoseArray & trajectory); + const PlannerWaypoints & getWaypoints() const { return waypoints_; } + virtual ~AbstractPlanningAlgorithm() {} + +protected: + void computeCollisionIndexes(int theta_index, std::vector & indexes); + bool detectCollision(const IndexXYT & base_index); + inline bool isOutOfRange(const IndexXYT & index) + { + if (index.x < 0 || static_cast(costmap_.info.width) <= index.x) { + return true; + } + if (index.y < 0 || static_cast(costmap_.info.height) <= index.y) { + return true; + } + return false; + } + inline bool isObs(const IndexXYT & index) + { + // NOTE: Accessing by .at() instead makes 1.2 times slower here. + // Also, boundary check is already done in isOutOfRange before calling this function. + // So, basically .at() is not necessary. + return is_obstacle_table_[index.y][index.x]; + } + + PlannerCommonParam planner_common_param_; + + // costmap as occupancy grid + nav_msgs::msg::OccupancyGrid costmap_; + + // collision indexes cache + std::vector> coll_indexes_table_; + + // is_obstacle's table + std::vector> is_obstacle_table_; + + // pose in costmap frame + geometry_msgs::msg::Pose start_pose_; + geometry_msgs::msg::Pose goal_pose_; + + // result path + PlannerWaypoints waypoints_; +}; + +} // namespace freespace_planning_algorithms + +#endif // FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ diff --git a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp b/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp new file mode 100644 index 0000000000000..8b7c803a605ac --- /dev/null +++ b/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp @@ -0,0 +1,144 @@ +// Copyright 2015-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef FREESPACE_PLANNING_ALGORITHMS__ASTAR_SEARCH_HPP_ +#define FREESPACE_PLANNING_ALGORITHMS__ASTAR_SEARCH_HPP_ + +#include "freespace_planning_algorithms/abstract_algorithm.hpp" +#include "freespace_planning_algorithms/reeds_shepp.hpp" + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace freespace_planning_algorithms +{ +enum class NodeStatus : uint8_t { None, Open, Closed }; + +struct AstarParam +{ + // base configs + bool only_behind_solutions; // solutions should be behind the goal + bool use_back; // backward search + + // search configs + double distance_heuristic_weight; // obstacle threshold on grid [0,255] +}; + +struct AstarNode +{ + NodeStatus status = NodeStatus::None; // node status + double x; // x + double y; // y + double theta; // theta + double gc = 0; // actual cost + double hc = 0; // heuristic cost + bool is_back; // true if the current direction of the vehicle is back + AstarNode * parent = nullptr; // parent node + + double cost() const { return gc + hc; } +}; + +struct NodeComparison +{ + bool operator()(const AstarNode * lhs, const AstarNode * rhs) + { + return lhs->cost() > rhs->cost(); + } +}; + +struct NodeUpdate +{ + double shift_x; + double shift_y; + double shift_theta; + double distance; + bool is_curve; + bool is_back; + + NodeUpdate rotated(const double theta) const + { + NodeUpdate result = *this; + result.shift_x = std::cos(theta) * this->shift_x - std::sin(theta) * this->shift_y; + result.shift_y = std::sin(theta) * this->shift_x + std::cos(theta) * this->shift_y; + return result; + } + + NodeUpdate flipped() const + { + NodeUpdate result = *this; + result.shift_y = -result.shift_y; + result.shift_theta = -result.shift_theta; + return result; + } + + NodeUpdate reversed() const + { + NodeUpdate result = *this; + result.shift_x = -result.shift_x; + result.shift_theta = -result.shift_theta; + result.is_back = !result.is_back; + return result; + } +}; + +class AstarSearch : public AbstractPlanningAlgorithm +{ +public: + using TransitionTable = std::vector>; + + AstarSearch(const PlannerCommonParam & planner_common_param, const AstarParam & astar_param); + + void setMap(const nav_msgs::msg::OccupancyGrid & costmap) override; + bool makePlan( + const geometry_msgs::msg::Pose & start_pose, + const geometry_msgs::msg::Pose & goal_pose) override; + bool hasFeasibleSolution() override; // currently used only in testing + + const PlannerWaypoints & getWaypoints() const { return waypoints_; } + +private: + bool search(); + void setPath(const AstarNode & goal); + bool setStartNode(); + bool setGoalNode(); + double estimateCost(const geometry_msgs::msg::Pose & pose); + bool isGoal(const AstarNode & node); + + AstarNode * getNodeRef(const IndexXYT & index) { return &nodes_[index.y][index.x][index.theta]; } + + // Algorithm specific param + AstarParam astar_param_; + + // hybrid astar variables + TransitionTable transition_table_; + std::vector>> nodes_; + std::priority_queue, NodeComparison> openlist_; + + // goal node, which may helpful in testing and debugging + AstarNode * goal_node_; + + // distance metric option (removed when the reeds_shepp gets stable) + bool use_reeds_shepp_; +}; +} // namespace freespace_planning_algorithms + +#endif // FREESPACE_PLANNING_ALGORITHMS__ASTAR_SEARCH_HPP_ diff --git a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/reeds_shepp.hpp b/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/reeds_shepp.hpp new file mode 100644 index 0000000000000..a0390e11b8f65 --- /dev/null +++ b/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/reeds_shepp.hpp @@ -0,0 +1,145 @@ +// Copyright 2021 Tier IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, Guan-Horng Liu. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Guan-Horng Liu + */ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Rice University + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Rice University nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#ifndef FREESPACE_PLANNING_ALGORITHMS__REEDS_SHEPP_HPP_ +#define FREESPACE_PLANNING_ALGORITHMS__REEDS_SHEPP_HPP_ + +#include +#include +#include + +namespace freespace_planning_algorithms +{ +using ReedsSheppPathSamplingCallback = std::function; +using ReedsSheppPathTypeCallback = std::function; + +class ReedsSheppStateSpace +{ +public: + /** \brief The Reeds-Shepp path segment types */ + enum ReedsSheppPathSegmentType { RS_NOP = 0, RS_LEFT = 1, RS_STRAIGHT = 2, RS_RIGHT = 3 }; + + /** \brief Reeds-Shepp path types */ + static const ReedsSheppPathSegmentType reedsSheppPathType[18][5]; + + /** \brief Complete description of a ReedsShepp path */ + class ReedsSheppPath + { + public: + ReedsSheppPath( + const ReedsSheppPathSegmentType * type = reedsSheppPathType[0], + double t = std::numeric_limits::max(), double u = 0., double v = 0., double w = 0., + double x = 0.); + + double length() const { return totalLength_; } + + /** Path segment types */ + const ReedsSheppPathSegmentType * type_; + /** Path segment lengths */ + double length_[5]; + /** Total length */ + double totalLength_; + }; + + struct StateXYT + { + double x; + double y; + double yaw; + }; + + explicit ReedsSheppStateSpace(double turningRadius) : rho_(turningRadius) {} + + double distance(const StateXYT & s0, const StateXYT & s1); + + /** \brief Return the shortest Reeds-Shepp path from SE(2) state state1 to SE(2) state state2 */ + ReedsSheppPath reedsShepp(const StateXYT & s0, const StateXYT & s1); + +protected: + void interpolate(const StateXYT & s0, ReedsSheppPath & path, double seg, StateXYT & s_out); + + /** \brief Turning radius */ + double rho_; +}; +} // namespace freespace_planning_algorithms + +#endif // FREESPACE_PLANNING_ALGORITHMS__REEDS_SHEPP_HPP_ diff --git a/planning/freespace_planning_algorithms/package.xml b/planning/freespace_planning_algorithms/package.xml new file mode 100644 index 0000000000000..2475e2f54b631 --- /dev/null +++ b/planning/freespace_planning_algorithms/package.xml @@ -0,0 +1,28 @@ + + + + freespace_planning_algorithms + 0.1.0 + The freespace_planning_algorithms package + Akihito Ohsato + Apache License 2.0 + Akihito Ohsato + Hirokazu Ishida + + ament_cmake_auto + + autoware_utils + geometry_msgs + nav_msgs + std_msgs + tf2 + tf2_geometry_msgs + + ament_cmake_gtest + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/freespace_planning_algorithms/src/abstract_algorithm.cpp b/planning/freespace_planning_algorithms/src/abstract_algorithm.cpp new file mode 100644 index 0000000000000..9a75506b5eefe --- /dev/null +++ b/planning/freespace_planning_algorithms/src/abstract_algorithm.cpp @@ -0,0 +1,184 @@ +// Copyright 2021 Tier IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "freespace_planning_algorithms/abstract_algorithm.hpp" + +#include + +#include + +namespace freespace_planning_algorithms +{ +using autoware_utils::createQuaternionFromYaw; +using autoware_utils::normalizeRadian; + +geometry_msgs::msg::Pose transformPose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::TransformStamped & transform) +{ + geometry_msgs::msg::Pose transformed_pose; + tf2::doTransform(pose, transformed_pose, transform); + + return transformed_pose; +} + +int discretizeAngle(const double theta, const int theta_size) +{ + const double one_angle_range = 2.0 * M_PI / theta_size; + return static_cast(std::rint(normalizeRadian(theta, 0.0) / one_angle_range)) % theta_size; +} + +IndexXYT pose2index( + const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local, + const int theta_size) +{ + const int index_x = pose_local.position.x / costmap.info.resolution; + const int index_y = pose_local.position.y / costmap.info.resolution; + const int index_theta = discretizeAngle(tf2::getYaw(pose_local.orientation), theta_size); + return {index_x, index_y, index_theta}; +} + +geometry_msgs::msg::Pose index2pose( + const nav_msgs::msg::OccupancyGrid & costmap, const IndexXYT & index, const int theta_size) +{ + geometry_msgs::msg::Pose pose_local; + + pose_local.position.x = index.x * costmap.info.resolution; + pose_local.position.y = index.y * costmap.info.resolution; + + const double one_angle_range = 2.0 * M_PI / theta_size; + const double yaw = index.theta * one_angle_range; + pose_local.orientation = createQuaternionFromYaw(yaw); + + return pose_local; +} + +geometry_msgs::msg::Pose global2local( + const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_global) +{ + tf2::Transform tf_origin; + tf2::convert(costmap.info.origin, tf_origin); + + geometry_msgs::msg::TransformStamped transform; + transform.transform = tf2::toMsg(tf_origin.inverse()); + + return transformPose(pose_global, transform); +} + +geometry_msgs::msg::Pose local2global( + const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local) +{ + tf2::Transform tf_origin; + tf2::convert(costmap.info.origin, tf_origin); + + geometry_msgs::msg::TransformStamped transform; + transform.transform = tf2::toMsg(tf_origin); + + return transformPose(pose_local, transform); +} + +void AbstractPlanningAlgorithm::setMap(const nav_msgs::msg::OccupancyGrid & costmap) +{ + costmap_ = costmap; + const auto height = costmap_.info.height; + const auto width = costmap_.info.width; + + // Initialize status + std::vector> is_obstacle_table; + is_obstacle_table.resize(height); + for (uint32_t i = 0; i < height; i++) { + is_obstacle_table.at(i).resize(width); + for (uint32_t j = 0; j < width; j++) { + const int cost = costmap_.data[i * width + j]; + + if (cost < 0 || planner_common_param_.obstacle_threshold <= cost) { + is_obstacle_table[i][j] = true; + } + } + } + is_obstacle_table_ = is_obstacle_table; + + // construct collision indexes table + for (int i = 0; i < planner_common_param_.theta_size; i++) { + std::vector indexes_2d; + computeCollisionIndexes(i, indexes_2d); + coll_indexes_table_.push_back(indexes_2d); + } +} + +void AbstractPlanningAlgorithm::computeCollisionIndexes( + int theta_index, std::vector & indexes_2d) +{ + IndexXYT base_index{0, 0, theta_index}; + const VehicleShape & vehicle_shape = planner_common_param_.vehicle_shape; + + // Define the robot as rectangle + const double back = -1.0 * vehicle_shape.base2back; + const double front = vehicle_shape.length - vehicle_shape.base2back; + const double right = -1.0 * vehicle_shape.width / 2.0; + const double left = vehicle_shape.width / 2.0; + + const auto base_pose = index2pose(costmap_, base_index, planner_common_param_.theta_size); + const auto base_theta = tf2::getYaw(base_pose.orientation); + + // Convert each point to index and check if the node is Obstacle + for (double x = back; x <= front; x += costmap_.info.resolution) { + for (double y = right; y <= left; y += costmap_.info.resolution) { + // Calculate offset in rotated frame + const double offset_x = std::cos(base_theta) * x - std::sin(base_theta) * y; + const double offset_y = std::sin(base_theta) * x + std::cos(base_theta) * y; + + geometry_msgs::msg::Pose pose_local; + pose_local.position.x = base_pose.position.x + offset_x; + pose_local.position.y = base_pose.position.y + offset_y; + + const auto index = pose2index(costmap_, pose_local, planner_common_param_.theta_size); + const auto index_2d = IndexXY{index.x, index.y}; + indexes_2d.push_back(index_2d); + } + } +} + +bool AbstractPlanningAlgorithm::detectCollision(const IndexXYT & base_index) +{ + const auto & coll_indexes_2d = coll_indexes_table_[base_index.theta]; + for (const auto & coll_index_2d : coll_indexes_2d) { + int idx_theta = 0; // whatever. Yaw is nothing to do with collision detection between grids. + IndexXYT coll_index{coll_index_2d.x, coll_index_2d.y, idx_theta}; + // must slide to current base position + coll_index.x += base_index.x; + coll_index.y += base_index.y; + + if (isOutOfRange(coll_index) || isObs(coll_index)) { + return true; + } + } + return false; +} + +bool AbstractPlanningAlgorithm::hasObstacleOnTrajectory( + const geometry_msgs::msg::PoseArray & trajectory) +{ + for (const auto & pose : trajectory.poses) { + const auto pose_local = global2local(costmap_, pose); + const auto index = pose2index(costmap_, pose_local, planner_common_param_.theta_size); + + if (detectCollision(index)) { + return true; + } + } + + return false; +} + +} // namespace freespace_planning_algorithms diff --git a/planning/freespace_planning_algorithms/src/astar_search.cpp b/planning/freespace_planning_algorithms/src/astar_search.cpp new file mode 100644 index 0000000000000..94397adc89275 --- /dev/null +++ b/planning/freespace_planning_algorithms/src/astar_search.cpp @@ -0,0 +1,362 @@ +// Copyright 2015-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "freespace_planning_algorithms/astar_search.hpp" + +#include + +#include +#include + +#include + +namespace freespace_planning_algorithms +{ +double calcReedsSheppDistance( + const geometry_msgs::msg::Pose & p1, const geometry_msgs::msg::Pose & p2, double radius) +{ + auto rs_space = ReedsSheppStateSpace(radius); + ReedsSheppStateSpace::StateXYT pose0{p1.position.x, p1.position.y, tf2::getYaw(p1.orientation)}; + ReedsSheppStateSpace::StateXYT pose1{p2.position.x, p2.position.y, tf2::getYaw(p2.orientation)}; + return rs_space.distance(pose0, pose1); +} + +void setYaw(geometry_msgs::msg::Quaternion * orientation, const double yaw) +{ + *orientation = autoware_utils::createQuaternionFromYaw(yaw); +} + +geometry_msgs::msg::Pose calcRelativePose( + const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & pose) +{ + tf2::Transform tf_transform; + tf2::convert(base_pose, tf_transform); + + geometry_msgs::msg::TransformStamped transform; + transform.transform = tf2::toMsg(tf_transform.inverse()); + + geometry_msgs::msg::PoseStamped transformed; + geometry_msgs::msg::PoseStamped pose_orig; + pose_orig.pose = pose; + tf2::doTransform(pose_orig, transformed, transform); + + return transformed.pose; +} + +geometry_msgs::msg::Pose node2pose(const AstarNode & node) +{ + geometry_msgs::msg::Pose pose_local; + + pose_local.position.x = node.x; + pose_local.position.y = node.y; + pose_local.position.z = 0; + pose_local.orientation = autoware_utils::createQuaternionFromYaw(node.theta); + + return pose_local; +} + +AstarSearch::TransitionTable createTransitionTable( + const double minimum_turning_radius, const double maximum_turning_radius, + const int turning_radius_size, const double theta_size, const bool use_back) +{ + // Vehicle moving for each angle + AstarSearch::TransitionTable transition_table; + transition_table.resize(theta_size); + + const double dtheta = 2.0 * M_PI / theta_size; + + // Minimum moving distance with one state update + // arc = r * theta + const auto & R_min = minimum_turning_radius; + const auto & R_max = maximum_turning_radius; + const double step_min = R_min * dtheta; + const double dR = (R_max - R_min) / turning_radius_size; + + // NodeUpdate actions + std::vector forward_node_candidates; + const NodeUpdate forward_straight{step_min, 0.0, 0.0, step_min, false, false}; + forward_node_candidates.push_back(forward_straight); + for (int i = 0; i < turning_radius_size + 1; ++i) { + double R = R_min + i * dR; + double step = R * dtheta; + NodeUpdate forward_left{R * sin(dtheta), R * (1 - cos(dtheta)), dtheta, step, true, false}; + NodeUpdate forward_right = forward_left.flipped(); + forward_node_candidates.push_back(forward_left); + forward_node_candidates.push_back(forward_right); + } + + for (int i = 0; i < theta_size; i++) { + const double theta = dtheta * i; + + for (const auto & nu : forward_node_candidates) { + transition_table[i].push_back(nu.rotated(theta)); + } + + if (use_back) { + for (const auto & nu : forward_node_candidates) { + transition_table[i].push_back(nu.reversed().rotated(theta)); + } + } + } + + return transition_table; +} + +AstarSearch::AstarSearch( + const PlannerCommonParam & planner_common_param, const AstarParam & astar_param) +: AbstractPlanningAlgorithm(planner_common_param), + astar_param_(astar_param), + goal_node_(nullptr), + use_reeds_shepp_(true) +{ + transition_table_ = createTransitionTable( + planner_common_param_.minimum_turning_radius, planner_common_param_.maximum_turning_radius, + planner_common_param_.turning_radius_size, planner_common_param_.theta_size, + astar_param_.use_back); +} + +void AstarSearch::setMap(const nav_msgs::msg::OccupancyGrid & costmap) +{ + AbstractPlanningAlgorithm::setMap(costmap); + + const auto height = costmap_.info.height; + const auto width = costmap_.info.width; + + // Initialize nodes + nodes_.clear(); + nodes_.resize(height); + for (uint32_t i = 0; i < height; i++) { + nodes_[i].resize(width); + for (uint32_t j = 0; j < width; j++) { + nodes_[i][j].resize(planner_common_param_.theta_size); + } + } +} + +bool AstarSearch::makePlan( + const geometry_msgs::msg::Pose & start_pose, const geometry_msgs::msg::Pose & goal_pose) +{ + start_pose_ = global2local(costmap_, start_pose); + goal_pose_ = global2local(costmap_, goal_pose); + + if (!setStartNode()) { + return false; + } + + if (!setGoalNode()) { + return false; + } + + return search(); +} + +bool AstarSearch::setStartNode() +{ + const auto index = pose2index(costmap_, start_pose_, planner_common_param_.theta_size); + + if (detectCollision(index)) { + return false; + } + + // Set start node + AstarNode * start_node = getNodeRef(index); + start_node->x = start_pose_.position.x; + start_node->y = start_pose_.position.y; + start_node->theta = 2.0 * M_PI / planner_common_param_.theta_size * index.theta; + start_node->gc = 0; + start_node->hc = estimateCost(start_pose_); + start_node->is_back = false; + start_node->status = NodeStatus::Open; + start_node->parent = nullptr; + + // Push start node to openlist + openlist_.push(start_node); + + return true; +} + +bool AstarSearch::setGoalNode() +{ + const auto index = pose2index(costmap_, goal_pose_, planner_common_param_.theta_size); + + if (detectCollision(index)) { + return false; + } + + return true; +} + +double AstarSearch::estimateCost(const geometry_msgs::msg::Pose & pose) +{ + double total_cost = 0.0; + // Temporarily, until reeds_shepp gets stable. + if (use_reeds_shepp_) { + double radius = (planner_common_param_.minimum_turning_radius + + planner_common_param_.maximum_turning_radius) * + 0.5; + total_cost += + calcReedsSheppDistance(pose, goal_pose_, radius) * astar_param_.distance_heuristic_weight; + } else { + total_cost += + autoware_utils::calcDistance2d(pose, goal_pose_) * astar_param_.distance_heuristic_weight; + } + return total_cost; +} + +bool AstarSearch::search() +{ + const rclcpp::Time begin = rclcpp::Clock(RCL_ROS_TIME).now(); + + // Start A* search + while (!openlist_.empty()) { + // Check time and terminate if the search reaches the time limit + const rclcpp::Time now = rclcpp::Clock(RCL_ROS_TIME).now(); + const double msec = (now - begin).seconds() * 1000.0; + if (msec > planner_common_param_.time_limit) { + return false; + } + + // Expand minimum cost node + AstarNode * current_node = openlist_.top(); + openlist_.pop(); + current_node->status = NodeStatus::Closed; + + if (isGoal(*current_node)) { + goal_node_ = current_node; + setPath(*current_node); + return true; + } + + // Transit + const auto index_theta = discretizeAngle(current_node->theta, planner_common_param_.theta_size); + for (const auto & transition : transition_table_[index_theta]) { + const bool is_turning_point = transition.is_back != current_node->is_back; + + const double move_cost = is_turning_point + ? planner_common_param_.reverse_weight * transition.distance + : transition.distance; + + // Calculate index of the next state + geometry_msgs::msg::Pose next_pose; + next_pose.position.x = current_node->x + transition.shift_x; + next_pose.position.y = current_node->y + transition.shift_y; + setYaw(&next_pose.orientation, current_node->theta + transition.shift_theta); + const auto next_index = pose2index(costmap_, next_pose, planner_common_param_.theta_size); + + if (detectCollision(next_index)) { + continue; + } + + // Compare cost + AstarNode * next_node = getNodeRef(next_index); + const double next_gc = current_node->gc + move_cost; + if (next_node->status == NodeStatus::None || next_gc < next_node->gc) { + next_node->status = NodeStatus::Open; + next_node->x = next_pose.position.x; + next_node->y = next_pose.position.y; + next_node->theta = tf2::getYaw(next_pose.orientation); + next_node->gc = next_gc; + next_node->hc = estimateCost(next_pose); + next_node->is_back = transition.is_back; + next_node->parent = current_node; + openlist_.push(next_node); + continue; + } + } + } + + // Failed to find path + return false; +} + +void AstarSearch::setPath(const AstarNode & goal_node) +{ + std_msgs::msg::Header header; + header.stamp = rclcpp::Clock(RCL_ROS_TIME).now(); + header.frame_id = costmap_.header.frame_id; + + waypoints_.header = header; + waypoints_.waypoints.clear(); + + // From the goal node to the start node + const AstarNode * node = &goal_node; + + while (node != nullptr) { + geometry_msgs::msg::PoseStamped pose; + pose.header = header; + pose.pose = local2global(costmap_, node2pose(*node)); + + // PlannerWaypoint + PlannerWaypoint pw; + pw.pose = pose; + pw.is_back = node->is_back; + waypoints_.waypoints.push_back(pw); + + // To the next node + node = node->parent; + } + + // Reverse the vector to be start to goal order + std::reverse(waypoints_.waypoints.begin(), waypoints_.waypoints.end()); + + // Update first point direction + if (waypoints_.waypoints.size() > 1) { + waypoints_.waypoints.at(0).is_back = waypoints_.waypoints.at(1).is_back; + } +} + +bool AstarSearch::hasFeasibleSolution() +{ + if (goal_node_ == nullptr) { + return false; + } + const AstarNode * node = goal_node_; + while (node != nullptr) { + auto index = pose2index(costmap_, node2pose(*node), planner_common_param_.theta_size); + if (isOutOfRange(index) || detectCollision(index)) { + return false; + } + node = node->parent; + } + return true; +} + +bool AstarSearch::isGoal(const AstarNode & node) +{ + const double lateral_goal_range = planner_common_param_.lateral_goal_range / 2.0; + const double longitudinal_goal_range = planner_common_param_.longitudinal_goal_range / 2.0; + const double goal_angle = autoware_utils::deg2rad(planner_common_param_.angle_goal_range / 2.0); + + const auto relative_pose = calcRelativePose(goal_pose_, node2pose(node)); + + // Check conditions + if (astar_param_.only_behind_solutions && relative_pose.position.x > 0) { + return false; + } + + if ( + std::fabs(relative_pose.position.x) > longitudinal_goal_range || + std::fabs(relative_pose.position.y) > lateral_goal_range) { + return false; + } + + const auto angle_diff = autoware_utils::normalizeRadian(tf2::getYaw(relative_pose.orientation)); + if (std::abs(angle_diff) > goal_angle) { + return false; + } + + return true; +} + +} // namespace freespace_planning_algorithms diff --git a/planning/freespace_planning_algorithms/src/reeds_shepp.cpp b/planning/freespace_planning_algorithms/src/reeds_shepp.cpp new file mode 100644 index 0000000000000..ff91267611745 --- /dev/null +++ b/planning/freespace_planning_algorithms/src/reeds_shepp.cpp @@ -0,0 +1,720 @@ +// Copyright 2021 Tier IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, Guan-Horng Liu. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Guan-Horng Liu + */ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Rice University + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Rice University nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "freespace_planning_algorithms/reeds_shepp.hpp" + +#include +#include +#include + +namespace +{ +// The comments, variable names, etc. use the nomenclature from the Reeds & Shepp paper. +using freespace_planning_algorithms::ReedsSheppStateSpace; + +const double pi = M_PI; +const double twopi = 2. * pi; +const double RS_EPS = 1e-6; +const double ZERO = 10 * std::numeric_limits::epsilon(); + +inline double mod2pi(double x) +{ + double v = std::fmod(x, twopi); + if (v < -pi) { + v += twopi; + } else if (v > pi) { + v -= twopi; + } + return v; +} +inline void polar(double x, double y, double & r, double & theta) +{ + r = std::sqrt(x * x + y * y); + theta = std::atan2(y, x); +} +inline void tauOmega( + double u, double v, double xi, double eta, double phi, double & tau, double & omega) +{ + double delta = mod2pi(u - v); + double A = std::sin(u) - std::sin(delta); + double B = std::cos(u) - std::cos(delta) - 1.; + double t1 = std::atan2(eta * A - xi * B, xi * A + eta * B); + double t2 = 2. * (std::cos(delta) - std::cos(v) - std::cos(u)) + 3; + tau = (t2 < 0) ? mod2pi(t1 + pi) : mod2pi(t1); + omega = mod2pi(tau - u + v - phi); +} + +// formula 8.1 in Reeds-Shepp paper +inline bool LpSpLp(double x, double y, double phi, double & t, double & u, double & v) +{ + polar(x - std::sin(phi), y - 1. + std::cos(phi), u, t); + if (t >= -ZERO) { + v = mod2pi(phi - t); + if (v >= -ZERO) { + assert(std::abs(u * std::cos(t) + std::sin(phi) - x) < RS_EPS); + assert(std::abs(u * std::sin(t) - std::cos(phi) + 1 - y) < RS_EPS); + assert(std::abs(mod2pi(t + v - phi)) < RS_EPS); + return true; + } + } + return false; +} +// formula 8.2 +inline bool LpSpRp(double x, double y, double phi, double & t, double & u, double & v) +{ + double t1, u1; + polar(x + std::sin(phi), y - 1. - std::cos(phi), u1, t1); + u1 = u1 * u1; + if (u1 >= 4.) { + double theta; + u = sqrt(u1 - 4.); + theta = std::atan2(2., u); + t = mod2pi(t1 + theta); + v = mod2pi(t - phi); + assert(std::abs(2 * std::sin(t) + u * std::cos(t) - std::sin(phi) - x) < RS_EPS); + assert(std::abs(-2 * std::cos(t) + u * std::sin(t) + std::cos(phi) + 1 - y) < RS_EPS); + assert(std::abs(mod2pi(t - v - phi)) < RS_EPS); + return t >= -ZERO && v >= -ZERO; + } + return false; +} +void CSC(double x, double y, double phi, ReedsSheppStateSpace::ReedsSheppPath & path) +{ + double t, u, v, L_min = path.length(), L; + if (LpSpLp(x, y, phi, t, u, v) && L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[14], t, u, v); + L_min = L; + } + if ( + LpSpLp(-x, y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[14], -t, -u, -v); + L_min = L; + } + if ( + LpSpLp(x, -y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // reflect + { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[15], t, u, v); + L_min = L; + } + if ( + LpSpLp(-x, -y, phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[15], -t, -u, -v); + L_min = L; + } + if (LpSpRp(x, y, phi, t, u, v) && L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[12], t, u, v); + L_min = L; + } + if ( + LpSpRp(-x, y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[12], -t, -u, -v); + L_min = L; + } + if ( + LpSpRp(x, -y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // reflect + { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[13], t, u, v); + L_min = L; + } + if ( + LpSpRp(-x, -y, phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[13], -t, -u, -v); + } +} +// formula 8.3 / 8.4 *** TYPO IN PAPER *** +inline bool LpRmL(double x, double y, double phi, double & t, double & u, double & v) +{ + double xi = x - std::sin(phi), eta = y - 1. + std::cos(phi), u1, theta; + polar(xi, eta, u1, theta); + if (u1 <= 4.) { + u = -2. * std::asin(.25 * u1); + t = mod2pi(theta + .5 * u + pi); + v = mod2pi(phi - t + u); + assert(std::abs(2 * (sin(t) - std::sin(t - u)) + std::sin(phi) - x) < RS_EPS); + assert(std::abs(2 * (-cos(t) + std::cos(t - u)) - std::cos(phi) + 1 - y) < RS_EPS); + assert(std::abs(mod2pi(t - u + v - phi)) < RS_EPS); + return t >= -ZERO && u <= ZERO; + } + return false; +} +void CCC(double x, double y, double phi, ReedsSheppStateSpace::ReedsSheppPath & path) +{ + double t, u, v, L_min = path.length(), L; + if (LpRmL(x, y, phi, t, u, v) && L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[0], t, u, v); + L_min = L; + } + if (LpRmL(-x, y, -phi, t, u, v) && L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) { + // time flip + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[0], -t, -u, -v); + L_min = L; + } + if ( + LpRmL(x, -y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // reflect + { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[1], t, u, v); + L_min = L; + } + if ( + LpRmL(-x, -y, phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect + { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[1], -t, -u, -v); + L_min = L; + } + + // backwards + double xb = x * std::cos(phi) + y * std::sin(phi), yb = x * std::sin(phi) - y * std::cos(phi); + if (LpRmL(xb, yb, phi, t, u, v) && L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[0], v, u, t); + L_min = L; + } + if ( + LpRmL(-xb, yb, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[0], -v, -u, -t); + L_min = L; + } + if ( + LpRmL(xb, -yb, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // reflect + { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[1], v, u, t); + L_min = L; + } + if ( + LpRmL(-xb, -yb, phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect + { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[1], -v, -u, -t); + } +} +// formula 8.7 +inline bool LpRupLumRm(double x, double y, double phi, double & t, double & u, double & v) +{ + double xi = x + std::sin(phi), eta = y - 1. - std::cos(phi), + rho = .25 * (2. + sqrt(xi * xi + eta * eta)); + if (rho <= 1.) { + u = acos(rho); + tauOmega(u, -u, xi, eta, phi, t, v); + assert( + std::abs(2 * (sin(t) - std::sin(t - u) + std::sin(t - 2 * u)) - std::sin(phi) - x) < RS_EPS); + assert( + std::abs(2 * (-cos(t) + std::cos(t - u) - std::cos(t - 2 * u)) + std::cos(phi) + 1 - y) < + RS_EPS); + assert(std::abs(mod2pi(t - 2 * u - v - phi)) < RS_EPS); + return t >= -ZERO && v <= ZERO; + } + return false; +} +// formula 8.8 +inline bool LpRumLumRp(double x, double y, double phi, double & t, double & u, double & v) +{ + double xi = x + std::sin(phi), eta = y - 1. - std::cos(phi), + rho = (20. - xi * xi - eta * eta) / 16.; + if (rho >= 0 && rho <= 1) { + u = -acos(rho); + if (u >= -.5 * pi) { + tauOmega(u, u, xi, eta, phi, t, v); + assert(std::abs(4 * std::sin(t) - 2 * std::sin(t - u) - std::sin(phi) - x) < RS_EPS); + assert(std::abs(-4 * std::cos(t) + 2 * std::cos(t - u) + std::cos(phi) + 1 - y) < RS_EPS); + assert(std::abs(mod2pi(t - v - phi)) < RS_EPS); + return t >= -ZERO && v >= -ZERO; + } + } + return false; +} +void CCCC(double x, double y, double phi, ReedsSheppStateSpace::ReedsSheppPath & path) +{ + double t, u, v, L_min = path.length(), L; + if ( + LpRupLumRm(x, y, phi, t, u, v) && L_min > (L = std::abs(t) + 2. * std::abs(u) + std::abs(v))) { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[2], t, u, -u, v); + L_min = L; + } + if ( + LpRupLumRm(-x, y, -phi, t, u, v) && + L_min > (L = std::abs(t) + 2. * std::abs(u) + std::abs(v))) // time flip + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[2], -t, -u, u, -v); + L_min = L; + } + if ( + LpRupLumRm(x, -y, -phi, t, u, v) && + L_min > (L = std::abs(t) + 2. * std::abs(u) + std::abs(v))) // reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[3], t, u, -u, v); + L_min = L; + } + if ( + LpRupLumRm(-x, -y, phi, t, u, v) && + L_min > (L = std::abs(t) + 2. * std::abs(u) + std::abs(v))) // time flip + reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[3], -t, -u, u, -v); + L_min = L; + } + + if ( + LpRumLumRp(x, y, phi, t, u, v) && L_min > (L = std::abs(t) + 2. * std::abs(u) + std::abs(v))) { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[2], t, u, u, v); + L_min = L; + } + if ( + LpRumLumRp(-x, y, -phi, t, u, v) && + L_min > (L = std::abs(t) + 2. * std::abs(u) + std::abs(v))) // time flip + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[2], -t, -u, -u, -v); + L_min = L; + } + if ( + LpRumLumRp(x, -y, -phi, t, u, v) && + L_min > (L = std::abs(t) + 2. * std::abs(u) + std::abs(v))) // reflect + { + path = + ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[3], t, u, u, v); + L_min = L; + } + if ( + LpRumLumRp(-x, -y, phi, t, u, v) && + L_min > (L = std::abs(t) + 2. * std::abs(u) + std::abs(v))) // time flip + reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[3], -t, -u, -u, -v); + } +} +// formula 8.9 +inline bool LpRmSmLm(double x, double y, double phi, double & t, double & u, double & v) +{ + double xi = x - std::sin(phi), eta = y - 1. + std::cos(phi), rho, theta; + polar(xi, eta, rho, theta); + if (rho >= 2.) { + double r = sqrt(rho * rho - 4.); + u = 2. - r; + t = mod2pi(theta + std::atan2(r, -2.)); + v = mod2pi(phi - .5 * pi - t); + assert(std::abs(2 * (sin(t) - std::cos(t)) - u * std::sin(t) + std::sin(phi) - x) < RS_EPS); + assert( + std::abs(-2 * (sin(t) + std::cos(t)) + u * std::cos(t) - std::cos(phi) + 1 - y) < RS_EPS); + assert(std::abs(mod2pi(t + pi / 2 + v - phi)) < RS_EPS); + return t >= -ZERO && u <= ZERO && v <= ZERO; + } + return false; +} +// formula 8.10 +inline bool LpRmSmRm(double x, double y, double phi, double & t, double & u, double & v) +{ + double xi = x + std::sin(phi), eta = y - 1. - std::cos(phi), rho, theta; + polar(-eta, xi, rho, theta); + if (rho >= 2.) { + t = theta; + u = 2. - rho; + v = mod2pi(t + .5 * pi - phi); + assert(std::abs(2 * std::sin(t) - std::cos(t - v) - u * std::sin(t) - x) < RS_EPS); + assert(std::abs(-2 * std::cos(t) - std::sin(t - v) + u * std::cos(t) + 1 - y) < RS_EPS); + assert(std::abs(mod2pi(t + pi / 2 - v - phi)) < RS_EPS); + return t >= -ZERO && u <= ZERO && v <= ZERO; + } + return false; +} +void CCSC(double x, double y, double phi, ReedsSheppStateSpace::ReedsSheppPath & path) +{ + double t, u, v, L_min = path.length() - .5 * pi, L; + if (LpRmSmLm(x, y, phi, t, u, v) && L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[4], t, -.5 * pi, u, v); + L_min = L; + } + if ( + LpRmSmLm(-x, y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[4], -t, .5 * pi, -u, -v); + L_min = L; + } + if ( + LpRmSmLm(x, -y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[5], t, -.5 * pi, u, v); + L_min = L; + } + if ( + LpRmSmLm(-x, -y, phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[5], -t, .5 * pi, -u, -v); + L_min = L; + } + + if (LpRmSmRm(x, y, phi, t, u, v) && L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[8], t, -.5 * pi, u, v); + L_min = L; + } + if ( + LpRmSmRm(-x, y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[8], -t, .5 * pi, -u, -v); + L_min = L; + } + if ( + LpRmSmRm(x, -y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[9], t, -.5 * pi, u, v); + L_min = L; + } + if ( + LpRmSmRm(-x, -y, phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[9], -t, .5 * pi, -u, -v); + L_min = L; + } + + // backwards + double xb = x * std::cos(phi) + y * std::sin(phi), yb = x * std::sin(phi) - y * std::cos(phi); + if (LpRmSmLm(xb, yb, phi, t, u, v) && L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[6], v, u, -.5 * pi, t); + L_min = L; + } + if ( + LpRmSmLm(-xb, yb, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[6], -v, -u, .5 * pi, -t); + L_min = L; + } + if ( + LpRmSmLm(xb, -yb, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[7], v, u, -.5 * pi, t); + L_min = L; + } + if ( + LpRmSmLm(-xb, -yb, phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[7], -v, -u, .5 * pi, -t); + L_min = L; + } + + if (LpRmSmRm(xb, yb, phi, t, u, v) && L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[10], v, u, -.5 * pi, t); + L_min = L; + } + if ( + LpRmSmRm(-xb, yb, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[10], -v, -u, .5 * pi, -t); + L_min = L; + } + if ( + LpRmSmRm(xb, -yb, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[11], v, u, -.5 * pi, t); + L_min = L; + } + if ( + LpRmSmRm(-xb, -yb, phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[11], -v, -u, .5 * pi, -t); + } +} +// formula 8.11 *** TYPO IN PAPER *** +inline bool LpRmSLmRp(double x, double y, double phi, double & t, double & u, double & v) +{ + double xi = x + std::sin(phi), eta = y - 1. - std::cos(phi), rho, theta; + polar(xi, eta, rho, theta); + if (rho >= 2.) { + u = 4. - sqrt(rho * rho - 4.); + if (u <= ZERO) { + t = mod2pi(atan2((4 - u) * xi - 2 * eta, -2 * xi + (u - 4) * eta)); + v = mod2pi(t - phi); + assert( + std::abs(4 * std::sin(t) - 2 * std::cos(t) - u * std::sin(t) - std::sin(phi) - x) < RS_EPS); + assert( + std::abs(-4 * std::cos(t) - 2 * std::sin(t) + u * std::cos(t) + std::cos(phi) + 1 - y) < + RS_EPS); + assert(std::abs(mod2pi(t - v - phi)) < RS_EPS); + return t >= -ZERO && v >= -ZERO; + } + } + return false; +} +void CCSCC(double x, double y, double phi, ReedsSheppStateSpace::ReedsSheppPath & path) +{ + double t, u, v, L_min = path.length() - pi, L; + if (LpRmSLmRp(x, y, phi, t, u, v) && L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[16], t, -.5 * pi, u, -.5 * pi, v); + L_min = L; + } + if ( + LpRmSLmRp(-x, y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[16], -t, .5 * pi, -u, .5 * pi, -v); + L_min = L; + } + if ( + LpRmSLmRp(x, -y, -phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[17], t, -.5 * pi, u, -.5 * pi, v); + L_min = L; + } + if ( + LpRmSLmRp(-x, -y, phi, t, u, v) && + L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect + { + path = ReedsSheppStateSpace::ReedsSheppPath( + ReedsSheppStateSpace::reedsSheppPathType[17], -t, .5 * pi, -u, .5 * pi, -v); + } +} + +ReedsSheppStateSpace::ReedsSheppPath reedsShepp(double x, double y, double phi) +{ + ReedsSheppStateSpace::ReedsSheppPath path; + CSC(x, y, phi, path); + CCC(x, y, phi, path); + CCCC(x, y, phi, path); + CCSC(x, y, phi, path); + CCSCC(x, y, phi, path); + return path; +} +} // namespace + +namespace freespace_planning_algorithms +{ +const ReedsSheppStateSpace::ReedsSheppPathSegmentType + ReedsSheppStateSpace::reedsSheppPathType[18][5] = { + {RS_LEFT, RS_RIGHT, RS_LEFT, RS_NOP, RS_NOP}, // 0 + {RS_RIGHT, RS_LEFT, RS_RIGHT, RS_NOP, RS_NOP}, // 1 + {RS_LEFT, RS_RIGHT, RS_LEFT, RS_RIGHT, RS_NOP}, // 2 + {RS_RIGHT, RS_LEFT, RS_RIGHT, RS_LEFT, RS_NOP}, // 3 + {RS_LEFT, RS_RIGHT, RS_STRAIGHT, RS_LEFT, RS_NOP}, // 4 + {RS_RIGHT, RS_LEFT, RS_STRAIGHT, RS_RIGHT, RS_NOP}, // 5 + {RS_LEFT, RS_STRAIGHT, RS_RIGHT, RS_LEFT, RS_NOP}, // 6 + {RS_RIGHT, RS_STRAIGHT, RS_LEFT, RS_RIGHT, RS_NOP}, // 7 + {RS_LEFT, RS_RIGHT, RS_STRAIGHT, RS_RIGHT, RS_NOP}, // 8 + {RS_RIGHT, RS_LEFT, RS_STRAIGHT, RS_LEFT, RS_NOP}, // 9 + {RS_RIGHT, RS_STRAIGHT, RS_RIGHT, RS_LEFT, RS_NOP}, // 10 + {RS_LEFT, RS_STRAIGHT, RS_LEFT, RS_RIGHT, RS_NOP}, // 11 + {RS_LEFT, RS_STRAIGHT, RS_RIGHT, RS_NOP, RS_NOP}, // 12 + {RS_RIGHT, RS_STRAIGHT, RS_LEFT, RS_NOP, RS_NOP}, // 13 + {RS_LEFT, RS_STRAIGHT, RS_LEFT, RS_NOP, RS_NOP}, // 14 + {RS_RIGHT, RS_STRAIGHT, RS_RIGHT, RS_NOP, RS_NOP}, // 15 + {RS_LEFT, RS_RIGHT, RS_STRAIGHT, RS_LEFT, RS_RIGHT}, // 16 + {RS_RIGHT, RS_LEFT, RS_STRAIGHT, RS_RIGHT, RS_LEFT} // 17 +}; + +ReedsSheppStateSpace::ReedsSheppPath::ReedsSheppPath( + const ReedsSheppPathSegmentType * type, double t, double u, double v, double w, double x) +: type_(type) +{ + length_[0] = t; + length_[1] = u; + length_[2] = v; + length_[3] = w; + length_[4] = x; + totalLength_ = std::abs(t) + std::abs(u) + std::abs(v) + std::abs(w) + std::abs(x); +} + +double ReedsSheppStateSpace::distance(const StateXYT & s0, const StateXYT & s1) +{ + return rho_ * reedsShepp(s0, s1).length(); +} + +ReedsSheppStateSpace::ReedsSheppPath ReedsSheppStateSpace::reedsShepp( + const StateXYT & s0, const StateXYT & s1) +{ + double dx = s1.x - s0.x, dy = s1.y - s0.y, dth = s1.yaw - s0.yaw; + double c = std::cos(s0.yaw), s = std::sin(s0.yaw); + double x = c * dx + s * dy, y = -s * dx + c * dy; + return ::reedsShepp(x / rho_, y / rho_, dth); +} + +void ReedsSheppStateSpace::interpolate( + const StateXYT & s0, ReedsSheppPath & path, double seg, StateXYT & s_out) +{ + if (seg < 0.0) { + seg = 0.0; + } + if (seg > path.length()) { + seg = path.length(); + } + + double phi, v; + + s_out.x = s_out.y = 0.0; + s_out.yaw = s0.yaw; + + for (unsigned int i = 0; i < 5 && seg > 0; ++i) { + if (path.length_[i] < 0) { + v = std::max(-seg, path.length_[i]); + seg += v; + } else { + v = std::min(seg, path.length_[i]); + seg -= v; + } + phi = s_out.yaw; + switch (path.type_[i]) { + case RS_LEFT: + s_out.x += (sin(phi + v) - std::sin(phi)); + s_out.y += (-cos(phi + v) + std::cos(phi)); + s_out.yaw = phi + v; + break; + case RS_RIGHT: + s_out.x += (-sin(phi - v) + std::sin(phi)); + s_out.y += (cos(phi - v) - std::cos(phi)); + s_out.yaw = phi - v; + break; + case RS_STRAIGHT: + s_out.x += (v * std::cos(phi)); + s_out.y += (v * std::sin(phi)); + break; + case RS_NOP: + break; + } + } + + s_out.x = s_out.x * rho_ + s0.x; + s_out.y = s_out.y * rho_ + s0.y; +} +} // namespace freespace_planning_algorithms diff --git a/planning/freespace_planning_algorithms/test/debug_plot.py b/planning/freespace_planning_algorithms/test/debug_plot.py new file mode 100755 index 0000000000000..ae1cd80206211 --- /dev/null +++ b/planning/freespace_planning_algorithms/test/debug_plot.py @@ -0,0 +1,134 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- + +# Copyright 2021 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import csv +from math import cos +from math import sin + +from geometry_msgs.msg import Pose +import matplotlib.pyplot as plt +from nav_msgs.msg import MapMetaData +from nav_msgs.msg import OccupancyGrid +import numpy as np + + +class CarModel(object): + def __init__(self, length=5.5, width=2.75, base2back=1.5): + self.length = length + self.width = width + self.base2back = base2back + + def _get_four_points(self): + back = -1.0 * self.base2back + front = self.length - self.base2back + right = -0.5 * self.width + left = 0.5 * self.width + P = np.array([[back, left], [back, right], [front, right], [front, left]]) + return P + + def get_four_points(self, pos, yaw=0.0): + R_mat = np.array([[cos(yaw), -sin(yaw)], [sin(yaw), cos(yaw)]]) + pos = np.array(pos) + P_ = self._get_four_points() + P = P_.dot(R_mat.T) + pos[None, :] + return P + + +def create_costmap_msg(): + costmap_msg = OccupancyGrid() + + origin = Pose() + origin.orientation.w = 1.0 + + info = MapMetaData() + info.width = 150 + info.height = 150 + info.resolution = 0.2 + info.origin = origin + costmap_msg.info = info + + data = np.zeros((info.height, info.width), dtype=int) + data[:, :10] = 100 + data[:, -10:] = 100 + data[:10, :] = 100 + data[-10:, :] = 100 + costmap_msg.data = data.flatten().tolist() + return costmap_msg + + +class Plotter(object): + def __init__(self, msg): + info = msg.info + n_grid = np.array([info.width, info.height]) + res = info.resolution + origin = info.origin + + tmp = np.array(msg.data).reshape((n_grid[1], n_grid[0])) # about to be transposed!! + + self.arr = tmp # [IMPORTANT] !! + self.b_min = np.array([origin.position.x, origin.position.y]) + self.b_max = self.b_min + n_grid * res + self.n_grid = n_grid + self.origin = origin + + def plot(self, pose_start=None, pose_goal=None, pose_seq=None, plan_duration=None): + fig, ax = plt.subplots() + x_lin, y_lin = [np.linspace(self.b_min[i], self.b_max[i], self.n_grid[i]) for i in range(2)] + X, Y = np.meshgrid(x_lin, y_lin) + ax.contourf(X, Y, self.arr, cmap="Greys") + + car = CarModel() + + def plot_pose(pose, color, lw=1.0): + pos_xy = pose[:2] + yaw = pose[2] + P = car.get_four_points(pos_xy, yaw=yaw) + ax.scatter(pos_xy[0], pos_xy[1], c=color, s=2) + for idx_pair in [[0, 1], [1, 2], [2, 3], [3, 0]]: + i, j = idx_pair + ax.plot([P[i, 0], P[j, 0]], [P[i, 1], P[j, 1]], color=color, linewidth=lw) + + if pose_start: + plot_pose(pose_start, "green") + if pose_goal: + plot_pose(pose_goal, "red") + + if pose_seq is not None: + for pose in pose_seq: + plot_pose(pose, "blue", lw=0.5) + + ax.axis("equal") + ax.text(4, 25, "elapsed : {0} [sec]".format(plan_duration * 1e-3), fontsize=12) + + +if __name__ == "__main__": + for postfix in ["single", "multi"]: + for idx in range(4): + pose_list = [] + file_base = "/tmp/result_{0}{1}".format(postfix, idx) + with open(file_base + ".txt", "r") as f: + reader = csv.reader(f) + plan_duration = float(next(reader)[0]) + pose_start = [float(e) for e in next(reader)] + pose_goal = [float(e) for e in next(reader)] + for row in reader: + pose_list.append([float(e) for e in row]) + + costmap_msg = create_costmap_msg() + plotter = Plotter(costmap_msg) + plotter.plot(pose_start, pose_goal, pose_list, plan_duration) + plt.savefig(file_base + ".png") diff --git a/planning/freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp b/planning/freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp new file mode 100644 index 0000000000000..ffd8ab5d6d479 --- /dev/null +++ b/planning/freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp @@ -0,0 +1,176 @@ +// Copyright 2021 Tier IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "freespace_planning_algorithms/astar_search.hpp" + +#include + +#include +#include + +#include +#include +#include +#include + +namespace fpa = freespace_planning_algorithms; + +geometry_msgs::msg::Pose construct_pose_msg(std::array pose3d) +{ + geometry_msgs::msg::Pose pose{}; + tf2::Quaternion quat{}; + quat.setRPY(0, 0, pose3d[2]); + tf2::convert(quat, pose.orientation); + pose.position.x = pose3d[0]; + pose.position.y = pose3d[1]; + pose.position.z = 0.0; + return pose; +} + +nav_msgs::msg::OccupancyGrid construct_cost_map( + int width, int height, double resolution, int n_padding) +{ + nav_msgs::msg::OccupancyGrid costmap_msg{}; + + // create info + costmap_msg.info.width = width; + costmap_msg.info.height = height; + costmap_msg.info.resolution = resolution; + + // create data + costmap_msg.data.resize(width * height); + + for (int i = 0; i < n_padding; i++) { + // fill left + for (int j = width * i; j <= width * (i + 1); j++) { + costmap_msg.data[j] = 100.0; + } + // fill right + for (int j = width * (height - n_padding + i); j <= width * (height - n_padding + i + 1); j++) { + costmap_msg.data[j] = 100.0; + } + } + + for (int i = 0; i < height; i++) { + // fill bottom + for (int j = i * width; j <= i * width + n_padding; j++) { + costmap_msg.data[j] = 100.0; + } + for (int j = (i + 1) * width - n_padding; j <= (i + 1) * width; j++) { + costmap_msg.data[j] = 100.0; + } + } + return costmap_msg; +} + +bool test_astar( + std::array start, std::array goal, std::string file_name, + double maximum_turning_radius = 9.0, int turning_radius_size = 1) +{ + // set problem configuration + fpa::VehicleShape shape{5.5, 2.75, 1.5}; + + double time_limit = 10000000.0; + double minimum_turning_radius = 9.0; + // double maximum_turning_radius is a parameter + // int turning_radius_size is a parameter + int theta_size = 144; + double curve_weight = 1.2; + double reverse_weight = 2; + double lateral_goal_range = 0.5; + double longitudinal_goal_range = 2.0; + double angle_goal_range = 6.0; + int obstacle_threshold = 100; + + fpa::PlannerCommonParam planner_common_param{ + time_limit, + shape, + minimum_turning_radius, + maximum_turning_radius, + turning_radius_size, + theta_size, + curve_weight, + reverse_weight, + lateral_goal_range, + longitudinal_goal_range, + angle_goal_range, + obstacle_threshold}; + + bool only_behind_solutions = false; + bool use_back = true; + double distance_heuristic_weight = 1.0; + fpa::AstarParam astar_param{only_behind_solutions, use_back, distance_heuristic_weight}; + + auto astar = fpa::AstarSearch(planner_common_param, astar_param); + + auto costmap_msg = construct_cost_map(150, 150, 0.2, 10); + astar.setMap(costmap_msg); + + rclcpp::Clock clock{RCL_SYSTEM_TIME}; + const rclcpp::Time begin = clock.now(); + bool success = astar.makePlan(construct_pose_msg(start), construct_pose_msg(goal)); + const rclcpp::Time now = clock.now(); + const double msec = (now - begin).seconds() * 1000.0; + if (success) { + std::cout << "plan success : " << msec << "[msec]" << std::endl; + } else { + std::cout << "plan fail : " << msec << "[msec]" << std::endl; + } + auto result = astar.getWaypoints(); + + // dump waypoints (will be used for debugging. the dumped file can be loaded by debug_plot.py) + std::ofstream file(file_name); + file << msec << std::endl; + file << start[0] << ", " << start[1] << ", " << start[2] << std::endl; + file << goal[0] << ", " << goal[1] << ", " << goal[2] << std::endl; + for (auto & point : result.waypoints) { + auto & pos = point.pose.pose.position; + auto & ori = point.pose.pose.orientation; + file << pos.x << ", " << pos.y << ", " << tf2::getYaw(ori) << std::endl; + } + file.close(); + + // backtrace the path and confirm that the entire path is collision-free + return success && astar.hasFeasibleSolution(); +} + +TEST(AstarSearchTestSuite, SingleCurvature) +{ + std::vector goal_xs{8., 12., 16., 26.}; + for (size_t i = 0; i < goal_xs.size(); i++) { + std::array start{6., 4., 0.5 * 3.1415}; + std::array goal{goal_xs[i], 4., 0.5 * 3.1415}; + std::string file_name = "/tmp/result_single" + std::to_string(i) + ".txt"; + EXPECT_TRUE(test_astar(start, goal, file_name)); + } +} + +TEST(AstarSearchTestSuite, MultiCurvature) +{ + std::vector goal_xs{8., 12., 16., 26.}; + double maximum_turning_radius = 14.0; + int turning_radius_size = 3; + for (size_t i = 0; i < goal_xs.size(); i++) { + std::array start{6., 4., 0.5 * 3.1415}; + std::array goal{goal_xs[i], 4., 0.5 * 3.1415}; + std::string file_name = "/tmp/result_multi" + std::to_string(i) + ".txt"; + EXPECT_TRUE(test_astar(start, goal, file_name, maximum_turning_radius, turning_radius_size)); + } +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +}