From 2fb4827c00672dc06788490f8c6ba2ea91c83ec4 Mon Sep 17 00:00:00 2001 From: HiepLM Date: Thu, 25 Dec 2025 15:47:10 +0700 Subject: [PATCH] test finish --- ...lobal_params_plugins_no_virtual_walls.yaml | 2 +- config/custom_global_params.yaml | 4 +- config/pnkx_local_planner_params.yaml | 88 ++++++++++-------- examples/NavigationExample/libnav_c_api.so | Bin 1847744 -> 1847752 bytes examples/run_example.sh | 17 +++- .../src/pnkx_local_planner.cpp | 18 ++-- src/Libraries/costmap_2d | 2 +- .../src/local_planner_adapter.cpp | 5 +- .../Packages/move_base/CMakeLists.txt | 2 + .../Packages/move_base/src/move_base.cpp | 60 ++++++++++++ .../Packages/move_base/src/move_base_main.cpp | 77 +++++++++------ 11 files changed, 193 insertions(+), 82 deletions(-) diff --git a/config/costmap_global_params_plugins_no_virtual_walls.yaml b/config/costmap_global_params_plugins_no_virtual_walls.yaml index d79c6a7..ce17e0f 100755 --- a/config/costmap_global_params_plugins_no_virtual_walls.yaml +++ b/config/costmap_global_params_plugins_no_virtual_walls.yaml @@ -2,7 +2,7 @@ global_costmap: frame_id: map plugins: - {name: navigation_map, type: "StaticLayer" } - - {name: virtual_walls_map, type: "StaticLayer" } + # - {name: virtual_walls_map, type: "StaticLayer" } - {name: obstacles, type: "VoxelLayer" } - {name: inflation, type: "InflationLayer" } obstacles: diff --git a/config/custom_global_params.yaml b/config/custom_global_params.yaml index f4eaf44..71565e3 100644 --- a/config/custom_global_params.yaml +++ b/config/custom_global_params.yaml @@ -10,6 +10,8 @@ CustomPlanner: nominalvel_mpersecs: 0.8 timetoturn45degsinplace_secs: 1.31 # = 0.6 rad/s allow_unknown: true - + directory_to_save_paths: "/init/paths" + pathway_filename: "pathway.txt" + current_pose_topic_name: "/amcl_pose" diff --git a/config/pnkx_local_planner_params.yaml b/config/pnkx_local_planner_params.yaml index 547ecd0..40dc56d 100644 --- a/config/pnkx_local_planner_params.yaml +++ b/config/pnkx_local_planner_params.yaml @@ -5,45 +5,49 @@ go_straight_planner_name: PNKXGoStraightLocalPlanner rotate_planner_name: PNKXRotateLocalPlanner base_local_planner: LocalPlannerAdapter -yaw_goal_tolerance: 0.017 -xy_goal_tolerance: 0.03 -min_approach_linear_velocity: 0.06 # The minimum velocity (m/s) threshold to apply when approaching the goal to ensure progress. Must be > 0.01. (default: 0.05) -stateful: true -publish_topic: true - LocalPlannerAdapter: - PNKXLocalPlanner: - # Algorithm - trajectory_generator_name: LimitedAccelGenerator - algorithm_nav_name: MKTAlgorithmDiffPredictiveTrajectory - algorithm_rotate_name: MKTAlgorithmDiffRotateToGoal - # Goal checking - goal_checker_name: GoalChecker + library_path: liblocal_planner_adapter + yaw_goal_tolerance: 0.017 + xy_goal_tolerance: 0.03 + min_approach_linear_velocity: 0.06 # The minimum velocity (m/s) threshold to apply when approaching the goal to ensure progress. Must be > 0.01. (default: 0.05) - PNKXDockingLocalPlanner: - # Algorithm - trajectory_generator_name: LimitedAccelGenerator - algorithm_nav_name: MKTAlgorithmDiffPredictiveTrajectory - algorithm_rotate_name: MKTAlgorithmDiffRotateToGoal - # Goal checking - goal_checker_name: GoalChecker +PNKXLocalPlanner: + # Algorithm + library_path: libpnkx_local_planner + trajectory_generator_name: LimitedAccelGenerator + algorithm_nav_name: MKTAlgorithmDiffPredictiveTrajectory + algorithm_rotate_name: MKTAlgorithmDiffRotateToGoal + # Goal checking + goal_checker_name: GoalChecker - PNKXGoStraightLocalPlanner: - # Algorithm - trajectory_generator_name: LimitedAccelGenerator - algorithm_nav_name: MKTAlgorithmDiffGoStraight - # Goal checking - goal_checker_name: GoalChecker +PNKXDockingLocalPlanner: + # Algorithm + library_path: libpnkx_local_planner + trajectory_generator_name: LimitedAccelGenerator + algorithm_nav_name: MKTAlgorithmDiffPredictiveTrajectory + algorithm_rotate_name: MKTAlgorithmDiffRotateToGoal + # Goal checking + goal_checker_name: GoalChecker - PNKXRotateLocalPlanner: - # Algorithm - algorithm_rotate_name: MKTAlgorithmDiffRotateToGoal - trajectory_generator_name: LimitedAccelGenerator - # Goal checking - goal_checker_name: SimpleGoalChecker - stateful: true +PNKXGoStraightLocalPlanner: + # Algorithm + library_path: libpnkx_local_planner + trajectory_generator_name: LimitedAccelGenerator + algorithm_nav_name: MKTAlgorithmDiffGoStraight + # Goal checking + goal_checker_name: GoalChecker + +PNKXRotateLocalPlanner: + # Algorithm + library_path: libpnkx_local_planner + algorithm_rotate_name: MKTAlgorithmDiffRotateToGoal + trajectory_generator_name: LimitedAccelGenerator + # Goal checking + goal_checker_name: SimpleGoalChecker + stateful: true LimitedAccelGenerator: + library_path: libmkt_plugins_standard_traj_generator max_vel_x: 1.2 min_vel_x: -1.2 @@ -75,7 +79,8 @@ LimitedAccelGenerator: # sim_period include_last_point: true -PredictiveTrajectory: +MKTAlgorithmDiffPredictiveTrajectory: + library_path: libmkt_algorithm_diff avoid_obstacles: false xy_local_goal_tolerance: 0.01 angle_threshold: 0.6 @@ -115,7 +120,8 @@ PredictiveTrajectory: cost_scaling_dist: 0.2 # (default: 0.6) cost_scaling_gain: 2.0 # (default: 1.0) -GoStraight: +MKTAlgorithmDiffGoStraight: + library_path: libmkt_algorithm_diff avoid_obstacles: false xy_local_goal_tolerance: 0.01 angle_threshold: 0.6 @@ -145,7 +151,8 @@ GoStraight: use_regulated_linear_velocity_scaling: false use_cost_regulated_linear_velocity_scaling: false -RotateToGoal: +MKTAlgorithmDiffRotateToGoal: + library_path: libmkt_algorithm_diff avoid_obstacles: false xy_local_goal_tolerance: 0.01 angle_threshold: 0.6 @@ -183,4 +190,11 @@ RotateToGoal: use_cost_regulated_linear_velocity_scaling: false # Whether to use the regulated features for proximity to obstacles (e.g. slow in close proximity to obstacles). (default: true) inflation_cost_scaling_factor: 2.0 # (default: 3.0) # must be > 0 cost_scaling_dist: 0.2 # (default: 0.6) - cost_scaling_gain: 2.0 # (default: 1.0) \ No newline at end of file + cost_scaling_gain: 2.0 # (default: 1.0) + + +GoalChecker: + library_path: libmkt_plugins_goal_checker + +SimpleGoalChecker: + library_path: libmkt_plugins_simple_goal_checker \ No newline at end of file diff --git a/examples/NavigationExample/libnav_c_api.so b/examples/NavigationExample/libnav_c_api.so index d7c12b88e59e8e093bbd28018c32ef838af045d0..873f628e73b638aa7f919cd917a8b6b4d19e14d5 100755 GIT binary patch delta 166074 zcmZr(cYsv2*G=BcBs*K^EX!8f(ifI0y?2nMqe~NzDjh@tVL?TD6Yv5eAVrZXph!_b z1f&b76sZDIq*=g%l<(YR<_+-s{>UbibMDPeUS8f!US4*`r2%^{4VYe7Hdt3=t&?N_ z!5eSHUVm`3)v-1`J4|gKJ9^dWi*Ma@#@%!z0>_>&ZaUuj&&xNzDBH|CLdym8XKjarS`I{JAk3Zsp9J?i4q>qzM?Ymwvbchg+WzeU)yd_on1Q5&9FT1=Y z681CSf4IC~q`xa8!^%bo=Rfe(tB^TDsk^;-DuYL;(;igc6ts#)@A1aBFzGX_)Nh1-lzPvnQpgG5&owfv zo(Ym0DZn}}_558CLaqg4yUQ}Ic!qAfWo)9%-v-M&L#arku1&r*RqkVdjsMoWTwbJ7 zd%f}U8a3Su`ZX@>Huc}@EfHbT!(JDhv3#$$NS08>T}%5Jw5BHaKHFFML_=J@YmWZ< zq!(3x2+^=%sJdZ@mRtkF_`}g3e~)@50xaPY(#AVnQipxsxKvlCyv>TEjMxK54_W3H zy&y5lm14DQ-#%|rdAA%RC1c(e!4e}py8o~+A-6&9@UyZH_j%(pSk~D90pX#Ve$g&M z`l^-+7mC$~4;LaQf~|xO@A(DV-Bwg8s3NqlNe_RqYN7@w9$4Ooww2BgWgz(#~$(~J<-AL zQk_GlkU<<>q(y+i+QHF9x^O7iGw+f-?2XH3+9}d>s2RURi1bgq`gSThlz)^EnGu|8 zR1G}ao9|L5Hyuf%k%s2^hrNlmeA8NYY4_ovK_(-T?jQri%-?wn+m3JY?Zu(`-+2=O zcK;67;Tlc)&YNsHkmT+n{Qv!ki*ekiH|NI)@Ii(UOAu^B`(K?HDbj!SY5lPlax?Px z1u}iOuD|pZniP(4XtWR)5zx3 zJw}KE2&Te;7J2VF2#(etMx#EJ0M;-B>JLTSfQYOif%aWz^A8<0*WlJsZ=V0TH(of0 zVYZ9bua3jm{}}3WylHGJd(2xDDmxwX<|%4SG;Njb<*H$#-CEz9=cKtmoc>@BX9>PP zWH$QbSg^kc+7DUVcf=RJ9rJed;^CKe!kfn{(`dkH@ADCJ3qr>J8MpVe_lv!!ePtpu zuI0eRk1Ja{Or*Dr;U8fwyYI%cq>Uc7+$Zi4I_PcWnm;1m*#Dw#J~l%5=SYzo!C@ik z{t@vrx!F4Cn2V7j1$dbtN5qeQ8H!)hWs<@~edM-4&;fB8bIq3%EkM_N)idt0P4Uy; zaYXt+edbf2_!7)-Sq~%fzJXs@fuDhXRR^mP&F*hJBj?0lt z0WF9*dqfI0+Y{|#;vLV=B^0&3?mH-tev$82-yeA!e&bOh>#&*;M@(ER;)aQ9M`$nS z*NMn);<^zPO8V6gjx{VGdXc;z>a$k9VO!`51j zQvuBiDiqql{iIWTjW*J&0c{Gx(maIpM;M5643f^Z|E!9mz)x(K9vDR`3k)%~S#G~w z;Et3|uTj!eAjb|Vk`My+8;h^8zPF{*VxrYo0eJ0aI3u=$Gf6tTmV1nz_P~3%oWe%W zu%qC-E1g^^UP~Gc!lV$1wq#M=ZR-xDf>~9KypvdN(EO@Ck>d>~=im-XJpZ*6FCaJ! z$r&^*t4eK1M!l)ZRL41WO^C(FSq$3h5Y=!@Rc1R*O%Y`{dw?Geao)?O23K3o%+&SQ zP-q?LbSwgYsohQ~x+6G@$u)+s>Klw3t)+ASYxo{-032rs+#hn~_>6grk+C`?MQ5_1 zFKnSq*;OK<6hwKpuqt~|am_zG;}I-b{u?Q(AUMnE6|j;`sZU?qw@P{qbr@(FmbwPi zj3=nUOFMA2&rrVv?OQ`-<4h%V@X}^@t-1@qZ#=^ZUfSK4B8(pIE-5l2*v8mlYT#bl z{_~X~6$YV9h(uj-sKvNvd^uHbS%?PYRI#d1XPA*f({thqmO)zR;1$gDrdL!%&dS|V zY(#J@)o_AW@W36%aJ~cnQ;0+UXf+N6&4^ZYGk+^ZEd=NG7Xx!Ck0&X=dV=-C{%{e$Uy6|&NsjhyBwn^ z6F*EwEbw(aA0a3zL4_-0#4t)oKwr$DDhVpKvbFreAV-Y&#JBVo{Ew=KaHAtQ2Ff-t zMTilrd^d1e=O4fmsXd@B3}?^`*3*MNO;E)Uok>t_RU3@?vOQHyRB??t{e*{Hu9Vb^ zKl6$%OsRWVie?Co6+o7Cqsujw`mJxnEU7mLuNo39OjHGAPui8JiX-|xQ6(YDnxyh) z^ka3IzLO#cf>9?tpX~}4l+vlv^P6uGSbZ4ufWm{$#M&2_FI1is(lxX#~~J#$fK&`Vbm{=%B?1G zf0#j2@~Co%zR9CfWCi*?kBUVUnOEh@Tn$QP*ik7mAvhJNYF?FCy$+X@ZR}2uDEEH0 zD~BS*XRM|k7)=Z-1kcZQzL8HXX1E)mR~W8C^YY@(t-zWa(U!cbxtvdt`C!d_<}IdT z`2d^ra%$|R*U&5AR5$r6rlOht#2-=U;~7z+?m#`|Xt=Rr_%XEZ7U&5eL-hAfxG`WB zBg^TVe5!f|+k2LO?_g$jqocXhRR&_fN6tSC?O`Zt)n$*U+frtY=fM5@6%$*jG4!zpbDuvL(dVU^eBOI5e4%yGJn5Nt_b5MB?G zo;0Al)c1}mF$LHh7eB_O_`Bk!th-X`9lOGWvj*U1mtZQ_@U?MaqA6NRej#7H7a{8B zIwIdIpo+?qRIC8n{3NuA?l9PS6=sv{y*SJf#4YU z*~_pj&IPx!+wijrL_P5vK95OaAa+#61k{i*s%c5rR57$f)aj1n5Gsu&y zN)}*MQJBog2h6dm_UMDLR#hQJ9BPxS@)ig~Z)y=@=JZ5}x(D^~u1aJA(#JC2Pgc1L z=HTABK$@#_EbGC+UhzKAl?V<)l8rOzjIFG#`0Tmt{LE8|c? zLA0fz$5NGoDlXonjoG291+Ksh8eC8nlzC`gK~+i>=R)()(SjRGrg20c~0O?MR1B!g+eM%Hp69c;g;RI5Xvq{GYY}+ zY(}dKsq($P$qN7Xjprk-o48d(=4|}CZA38>cZjHC;*JqrOx!8rtw6lg#4knc4#ZbY z+&RLZo#i`66g6>|h{l1qFEuHwCQCu53achEf(jN<(_3fF3G3n?jt&zspZN|&M~eBU zr1%)YVMN9ocwM_l5%ab0opV}j1+>S7^D#U$1>MO9K2X2=puGZ#2%ceWpHhl{ev=m1tv!*nTOom!W|LJa0r zom!U`f>sn&d1NIzfG87Zi@38}Le1_8ycq_x9QN>hJhM}^sh?>+aQY1Ymv&D6Z5buJr z7{OQ?HUZB|L*$fvFrL{zjT0iNwT%4rmK6KIJQZX+;Fx-a#5haxPXMigHE)HQ=cM@J zcw*L|D#cYD_$*_J!;k4q3yWhKG>{(huYvq4no6Z$8Z?H6r66mJ&03ADq#0~_(2crz zUWxfU5Cv=Y$1j&AX-Gv0z5z3hx^MUVSM7S5I8f)o)5PmtO^UKlCL&e7323jNMt)I3$y zkkRyRs;Y+QXeu6%(eyY~6^M^#z1c5eNUb5UvVb2wA(G{1j7jlSy_Blkp$RjBmdy@B z_j?8CPy~k|*@E$)W%2$9@dD?{=^(uSG%09VgV!*RSY2fd3%Kj+C!7Z0<;%OT*@lG_5pjewj;jZ7#CiYq*Opg8wpoR~l}0Z>m%VPlDcT z$pA`6I?<+C@`2Ed@g;W!zEOtH@#a%)#^Bu;i#8NV5t3BdRt$K5LnT%TiQA zaAq-It8$L$b06!`8=?dk(Gt*$49}zSWmT%2N1My4xDJLKHE4H)=%XE74~v;wLE014 zBNwr z=xhbB_SG2qZGxEG6e46ex^Gi-iar3}a0#4}n`mWuRV0J8Nt1CJ4QgfmM)`C{7cC6s z2f#k=%5DppHpkIvXV|n`K>u+WyO?2B%yV?{Z=oX7RVfk?jO~&M!Gfseb1G*kV+3ms zW^>KgI(qMX+!g5%?ClCadI(=-6U}{2#Tnb5aQXWja`czQJYqj9S_X+vT`6O=d1&^z z>F6z(co@=t5Poz?#&ApWd30D7Wl48HxbKp<}FTR|lwdZmIYjc7py z+)%6NU**#(t0=M}GS^cjj#g36iUu3c(JESQqrEn|W}~o51}ki%1~%$xqwzLc zUdiY@UJ1pnB7bE(ZB|jy$|^q!YKkZy_abv?g};zbi#~HadO&ToUdJ0!^g?jf)6B}4 z=&Ywrl}%|UIa*KuAgXA(p#O&ipXh^i``jyV6(2*!cQe=n{ckKpf8XrUyGHtjj6;4w zgHf|8DvvT(bUzKPqN+mUXH`@YMCYog5{ROzs^q+;7kefxz=e+X>i8XgQS%ylWg;Ft zMG#m&iKvwR%yBnA^Hc(@1d%X!gIcZjazpq6YOF4B?v{?}X>IXb7y8i%(~Kkdgn|@xJzj7QKKCaq;&;^1B^xYQZou0odFiUR<&Q z`2_2L<6WOkiZx(t3$kQiL!w&^R4%MJ`5LO{O3vr3=zpb%M{pK%G3F(COeIHG|Jf&2 zGhQB86~;HvD-BiY%o~^%Jv1ECj%~7FBCTqOL1i%=Y=~Q8FQ}CchldE)yIeyHc@kPuoij1w89XdSHu)^Vs22A=T!k^ z5gPiuN{TS)fe$foAD~6gtCXiQPCk$2v&H0Vio0Slm1(L9BWmAN<uyF0F8M169AhD_l#KWf zL~d}@L#C<3EYIqolAQZL+zx3f9@Y&{Q*pKqrX!u8MaZx*?8C+U z#-p>X!nm;SF=k5$=0Z!Zn>;~b%~ZUVK1)TL1y!H5V6$c_)|O>5-lJEW1zR+bv9OuS z^Aux0bQEI?p745NE-GJ}u3B7Tt;dBUentpbL0OucYoE%|Vrpi84Y0qa+h3nHH<#xe zM;j=zg<%%wXahAtgm$IoFNej_xE3lK^5$7+ON(H`T%yx0Fw!lizpQL@OFTyxQ;n7w z1s78{M79Zb)3laG`P!B$*;ea1+kBnQw={Rve}IG3Jgty6S7|rZeInhP)8-l+plL`K zGaS=TJ?|AjKh5ORd#VWW3HQl`UPr7zu&r@`PPvK>&?6Q$icGiibiR*^c|-fg-wYFf z`7uq*4Pnu?h_(){74y}U{_UQmVY-DV#D5i7f}bM*QPSikK?`(Hp0=|;c2 zppsJf@vdLP8_JlRQXkLb7kk4TaU0<-f-@jDOv^PBZ^UA}GRHwG^&%$p11Rl9l|R!6 zV2yEYnj<*fX!MJCA<&H$zNn&`GBg$0vkb&K%qz;6GE#4TH%jC|_G*MpLD;^=thC98 zF}0S=x)nu>TxPhBkOdOSldjsyL)0l99rF;4NLP6}9Ew9VzsDc@?9P~{YpxCxr#M$m z4tE40I3ZGI9yK%OM;V{c$KW{mO1EJmW09Uz+b_y~I&mB7*-q7p`5V-? zfJ|WY7nTcLo}KN~3-TVtwa3_Wk9)Ei_5{^zuTq+u3^)uz4DQ=`fJppN|Nbs}qU|Cb z(H+4tgh(cIF@%fybX|BVBY;hJ@k4MZf@-&;9A%^gU1+ajQ{5uqskmzX&>t6v%nhjc z&sD?4U}>;u2Mn4<%IFo8)CgR!ylV zT@SL}0%NMnGLAIz z#v^n63Q%fiRowP~@?4H*YrG>8Uw8DZ15$jCR+i6a#d}l)TL+N|S>2wPlYHb;~|c%ryk z)S-*HiX))`7jrS9p!o+aaI_KG4ejVoy6;2-LHb*8hIYtel;5Tb}c};Uk(XZL%Nu4TqDd6 z#KfXLz2R6SMiR7MQ}oyu5rP+GJPTU^T8(s;P|1M-;>^pcqP#@W-BgX3|9GG;jro_n z%RN7He3>xO`?=Ul)UO*x_y1@@H;l)UmfPstZfH13SG%d&YO+iFHJN1Sdp_%e28G;#cNqNu7GD^6_I>F!+*X(EGS2-T;3b%Z#CQ zy;V{fX2@|&3%+EjpXi7w$k-0ne#3Mr=GDdTuQ8IvIid)H zGne^G>4jHRI-(7)z_opuetreL^ksVR3f^1yN1MriKz+pYmno$W-dn%Q%^!SkT^X;M z4zil^7?r9ZI4_6b`Pniu3$caa)_~eE{3=cC1Fw%+ax|^z124*?kD&zY0RE+qs*|zS zSZrRHre*c7jS`s?91)A)Fd|u@sAAw2SsSdw(o9KUm0WyB2ydBnLoTd-r2$KK@jW5+ zFX~!NmFNd(lnbw@_&@K(infDS`&7_!xN--ln^4i{n? zzO(DS{e6P zoqcURGHan(ks>3>5fc#{Mx@~DY_G!Ttg|b@<5>u7g^QzWzkpO&9yD4Eiw9qe&jZ5tF!ZCVlo;lP2|Fkmu_Z17!q^mFhhKpPI( zu|fGK)nC%@6v18rKucY?CYND%HB^y0JQka4w*cJj5=<2r$j{Mz>z>TMq=piIFjgoZ z9t9}_{HC3|CjM%(>tDp^VhxwvNVrc+4N^HVX4D^q^}YJkZ;&dL(UOt+TyW(UeX*V5 zgePmcV`vFE1xn{2IEL{&GmOv3FXlHM#g;A>To1xmE~yk!0TN!!m;J$GNhgqf(IrjI z50an9@49!qni2=AOw~*gtWfw<3Sm#nUQhNuyzRLdxRnviz{qtltE5~nYgM3Hy$7qL zxTWac8T@kEg@fm}lxOp4Fu@u@cM3qS}54*$yak!Z~_`)K80G=!DbFb*2!g8G>&#S7ybNt8` ziN7|)F0dNoWMrL!pzy@6#xxnl3!3hm%lwgA@N}juPiZuDd=;y$nm%|H!@8yeP$i@2 zw^w0m6h#bGB~mqJI5M;nUE^VMN7T42oz2T5L?x7hCK@2JVcA()CiNPMcXZk5gQ2K= zcG^5tCDqK$vm{UK(kRjYGpSn_R%V&j*#+_a2u}78zE$e>$v(mBy3S=_zcQYia=)h9 z$Rrx@8kUHYXyR+w5}ZtjUxS&+bp18#qfBNq&3>?AtStVu>EWXPB%S_hr1-m#BXnV? z32{m>XRKpLvvjq+cC5;DRrb{xa;`JpZ`Y+abT84{{0j+o8V)XOtm}nW}OT9Ntl}YEM z(55;4QrG&%W12Iuh$9Lhm}&;#DC~3V=Qpic6;N%4tFm+yzg_O1P3l+sEAaxdI~qxv zG7R0JHXR&>i&vYj4O4klZLU^B$~;`fH#O-rQ#?OG`uCIixeno?HFDyLI-($gWBDP@ zYf^XI8eurqfj4qFX*6s&N^3`(pjx%#Vmi}LNN1RI4_2|-?5ONNQO4d%h!B05a}5gq zWF=PO3DzVTyL^gcS(%Dq#RAvr9B-;-Ixf5qZAuuU$W@q}d$WUhBBpvSS?_h6iJ zSw>5smJemFuO3EP*1uc!bf^^ zo<>+N;%QO^VAU8m#_W*1`qY1nN4HoNWjdOC5nv}*L4YvUqyPBQc2qgMG0@Sjim$DT z2_8KbJ7kuy4etZ|@L9qXkB-?HAwFTkmjHJ%;RE`eD`ahz*g)TZrYCxMWo$h{<>W(9 zJSBp4*&+L5QMo^P^zK+Y#K=T|1)e1=^ysvF+P+Gv4zMm0Ol`lm8b0>uJ-htY)RzEu zuk|crtw+C%9skDGF#yLg!5C>ap!PrHiF`8#-p~igUt)ym*eGnlSxd1Qm@TZON*OBg zxwU)+GPS*{MMj;hOU_3Mr+P`4gW!B_pf(KE(+i^U;7vz%Hv`c$=tyIR+{!ew<2a+4 zp83!#zD9<#0JKknS}ezw(nB8}6E2)>zz(~3VDal=27D%?^lM5OjdA#MdTz9ORVLEv z(JChYw_H+|;msmMvx%91$B$r|=XnvOmtswXu8mfO%-i0;E8W~uO_MUNm|mUi8R?pt88@8MmKE~ImJ+l+o;JDI7IiT=M4tM@2;sxh@HM~O6GDptx8X~tBnZr!8LIZC8c zQ_b?|qp8M##A(LjY8)j}NBe7({k33Pu*WLe?xqXS1*DI=eKRe8Q*yd%(MyYB<7IGtm8n zf6WaHi{+J`o{A}D9P*0=F&WUEKEqfzbOv6^8l`5;Q1l`4ttEVEgY1KreQk!ZBNz{T&m0OnhOv%(?rE* z^1?I^1lg#~OkUNs=@Bzkdd9GksC}<%mpr267~QZvzr*|-(SMY}^&1XwtV>`S;kouFt|^W&5Wj?rlenOAAqdNu^sm8t zzU-66s{Y>4xFJ-YZwpO^!$UY-Z`tHCJ;p@*^_d5fx%N@`-# zrplGp-$t9{@+3XxV*LKgO86H!&XD=g(7(PTG7wBduJOPxyWGB=0H)f(EH9?rq7KY$YE zs-#K-*Z`~Ttt>v_@9WWnfA-s%K}thMR6uYH$y`(0a<6mC(a^c76rK+#LuQI@Acg-` z{qBcYA;d>ogVr;<5NpQjREFjpZ{?8hknj&EOWEYEam z1V0@C6mE=hZoxZx~((%*t0V`uV4Mb%#%ISIHG1ea=J%Wfo?b(aS&Gn{!@u?EKc`|o8U%7uqDNFNoG3bSJ?ubQv1`fy!UJ zFl$&^605tFQt)+`{|#RZD;1TF{EP8$q%VFl29&VC$n@O@s(waAhJz1?fj!WJ? z7BqzgjLGUu2tFW|%taF>0xRO;bs2Xb5L13fy{ZFjo(WRMk zOe69G;_U~HrA-83wo5XFxethqZ+gTEU|U?gIcu)Z{$`+#e=bnH44s4zHIfH8%}02}8)>Mufo{;og_s5XPXB@3?RS>^o7wSYFtv9US`M91!NR7AQvDxS40J; zKFcvJzkw3|vZdr%tV-o|OA%2^@Hs?sI~-_qC`?ps;fUuEoXj+6G3G>>Y0hHIi3(B1 z63mGT(T*k9L0*XNEWwSKLXk^hUJ4gjhEkSd_G8k|wSpH`rjecfqzuEz&<;5R5S$QR z(Mm0ZR8x~%olUkAEzEva_}NL?3Yk5wTwP|kv!BC{F}R%pc+(}Y3Rn`i42@%SvIH_} zEJL$CnbCV0COJ=JgcM_v)1VC27T##>h{*`n;t4l!N0y*6a$0|+ve?R)cCJVR zK7w1ELX$tj>>!1#Aqn~38pS7RR0rW)o_lQ)9Oz!ls2cs zpTK2Kp+7ikPSGpip{G#g6-KTdM=3PI{(9g3+G>BDUJ>kW73qPSZc7O(jbRm6s>E`} zu<2+z$vw>OX-N+E>0&iKq6=p~-wu0P5Ny*LW?P!P(v-StCFV3C4T1XoVnN?3V`tG- z*luDte9c31nr86FWtH}hsD`|iMQb$vCRv?7Fw4!t-(55cKUmbDwaEYI&ZegeF+UY za*Puh*(u<4=BCPPRk4iR3|F1_BO1$p)f4e8;OJrvy~6*iC#q=*a^3mH%)yaj^Yh5* z2hI=#XFGm{<{K3o2(g>-slaBrxI5ptF#%pR@YR4e1YvETW=-klT2(Zh3p7u+rj+MX z4F3nH`KQ>Ra)7lS#h;KnbF530IKkPn(@T!%jo?@o&4mO6H+~9t#$=tPGoQkpG3lq> znKrkTRdNmTf4Vx(a!IZ`Q)3i{M1N;Yu@IaCRBavHnM+*sbI7R5nb)b$I^2WTX$mkz zt8H{>9ques>AmdvxcYL8CLrLxid|v<9fI=|1lhNXO4E^Pt>M#!Fvz{ zhcPMf5Ov*|1w0X34Q!K(YsOu7rXUX9k%s}EatTknGtII_iYSOkc^8bw9bK9!$8~3_ zPK>g&++DGPk6?{4g}LrbyCyzS5m-YP&(4}d?o3m9a|1rAno2u1;8T{V49;S6gP*ee z{I5^UGsYZ%isP&%L<)Y&QalzDgR2Ik_|NdAXm?1s?_2k5^9uDcRtyp3BI@uN?vX__ z|1%8Vi)jC6xW_-DJD;i8%pY;VxnhPyi5in-R2s#6u12PB;>_SG^v@S@NJ%&B7esIv zk=qO$ScM+EEL_Y3w9JKfF&uQqRwnqx=PtCL?tHH5bUb1d7$<716X_2Zxx1q|5gbP3 z@en-OSy@(y3V>?6@R<-i-RWFXh_-;bxbQ`qu@T!BjHZjM?hLKlsPd;=LwYq>8<=^U zb+{hcuNa89(1U=EF^p5-zEG(NcbS!HmaG$`UQ-2*NbVkvNJ4OKQ`0ZtPO&0+pZXz< ztp^jnz^B_L%Z#=6L-N=ox8MW#)bk*_%*eB#NJ9bEmn$drzPXWN3$WcT&h`iJ3R16Y zro>Ocesyt{m!=e}1WVa%a^al1$6#c}SZV5M2w0J-w#nG|;wG$H-=;~MaQoh-m77#@ z7T01sAf?fTP3iW+frZr5cgH_-gpa*;4p^8 ztL|Ii$C>m1dTU4gRP1*pVU z6_;xBT`{{7UC+_&9{WY5SFogvU~MR14H>poC6%`tf>MDa8_gnidqZ@=8?nG(@f#G0O6#%K2hZF5@vW!utg6NJN%hcwh(a z!b86>qyiw6bV+P%fCLB5*FVgX8iLTukZ9DG@Ry7&ra@!qlP~eCj-=gR!Y7KPf4;a-evHXxWb6CQ*2zzfsO ze$kEbL-_MO<5vEiI;i|W;E%M}2gBqoV1I`2EALOa>@F#!r>rvX@-K?tttV7M#4utLyl&%J?7h z)xbdElJ8n9N3eyTdUg2?a2MhM7IF#Y4I$S|T&g`@-S`)*GgJjwn+ZjY{n>bncjY&I z2a4ff7Vbywf%S0}n648;?|+RMm+A8+qde_K2AcDiui;>a@&h+S;!Xor+ldETBz4`1 zZ($6lC{5jIF69bDPu)UCZ2rxiDo+bTH3PP--Uc@Cq4X^s;S zGSF}S{zer|$i|9FF64f5OXg?D3bc!M^;>bwe-3V+qe^B<TC_(+*W#5T|xK^8tf`DsvVMwHy0LCn4F(S8x z;K|O__mo%;XoCyy3c=HzjnkF*7SJ&l-cNErTq~n#KdakCdH2J$I)Zejn<-Vf8%DFh(A9AhyFM32HVCgQ-^3s&z zx>j>?jm5SsFfv>g6L1phnghnheFxxL9jE^e;MP4(aR;&db)0G*#PZi|DtrjO)NSf@ z2)@*9nsW%g)Lk~g^`(yPfG;wCB)%pHyOs=9g4#Rsg=}1~|7~Yf3H$*Ph^`0hPix4YDIbu74Ej7|=yM7qnlhqKEdd7RY z@5Au_7;>32o{_Eg9lR$aYtG!h&n3FvQ`gF?XPK%;Rf62_pvBbYV|c~1kjMTs97uL`U- z<5oWCJ=ORchgLG)0a(`%9`v4u6v7Tc#<6}O-a^O-CgQKo+3Bl zKonN+6|iqYc+h()ywoR5L!1S6DTD{Tr+OJ)i$4VBd6T^-Qv=s~T7UxzW$rgIVMD-7 zsp+w2+IQG7)4sEhnWp?4QM}O*^q#&6!^-Sd2=B29emiC^ME>s)#Za5?;XTFBYv1E( zc9-7gD2BFw5ATVuVaR*hIy+4K3kCAKw;b^!LZF?3-qXoMTY$U+>>lG*KIlDloDyN> zGrx^t10f(E^qwv+Q^Gv2N&+i~kP%Q2^q%JKha1axX&S)Rt^(J4Dwq!J732?P%ydA$ zPea~Qjp10vgTT(X3QX4#6!9ax z2~(uWNThPeKy$YK5#CcMKX5}#wcwf`@wB>2-~R~j$#AmKqaV$sj6DwT$z%m2Y9IsD z_Q&BpnS3)Q+v)|qry>>MJ@tDBy%@pP-xzFFn2H9yrwwo8tNXd2Ej3g+d>q~r>kWBN zaR)lD(0T=E%?VSL{U=O+ zyKSRvC*eJribYbDlh}(9NOwM|8poe5hgaC6{?g`kXTkpc$;h={S+c5<5bo>a-v z>~&`;*GGvan~J@LbVNisA-a?26fo{nL5y7%gEggUr&OW%LEI|AFReCS$Mc{GoSwD_ z&LA3d3dh+oL%zS8%frMdWK08Vo?*Ha^Fe`ihVaEe8l5?XTWbJ4JcSy+O}T%9 z?>C)l{)9)@bZY+-v`=Tz_ny?A2YbloBcu03N4$#QgeXRPyE=i-7244kKSBFqI*BNQ zvt37!f8?FIFJ?{TPr1;C&QUZjEPm_Y~@!i32 z0vZ{NGR~@k@m#v=9>2HniRBp<{@;l zpA1Hs&#P+1+3JGR98ny>$-(-9XYphi>JjIF)&bIp(SkJWyy_iMhs)s0A}`bJ^EjNR z5tX`t*VBzSzZo^V02kJz+t2_vzdcR6fRlK-Z~^W~JpDR(#COy2sWXDZkn9=4aT3qz z+CFgy*nJo8$GCeE&#TzxoOuR5LqxFhLqhU6iDwh`=9C0hJ&0?`3gi&#_cLB}ni8AY zjF~^H(j|v;dLhWmSYR~ka*x|7U(GAtVSGEV-HcDByAaAenQ88EJ2|M_MU|9bWc_3K zAe;J*Uez9_nbA82q}U#~sB#Md5P$0UHvMKmRVy zV!GvMS=leR4Vd%uIov+|y?9nt8`G~%} zf>VD+(=S)>4W?l&rA$}x%ot5YuB!Z5OcvWN=b(ZpxBXR|&cmiju88DnBX=U_{ttH( za$7#j#VsW&o0EAy^=SVa7(wM>!at2cu-C;N+q1!=H}=8Q{8!}P4`R~v;}ulo8kQac z);4m}E9e!ZZC#hLg)3;rH5K375I^M(WK|#Z=v(tN7VGi!TY+GTl}wN;m=$HLJL=J2 zzJyPlLHOZm(hz!dE!fCLY6um+jy=3?Invyq{vzjf2Ol2nnTHFO>3!S?2)3V_4;f>^!hHM3VC*f5{Bn$$>adw2 zYV|fKIOO-O!v9QZ1gy2eDdUDIec=t9Cp4P&-GGBRnrIqmD;f z$$#v7@tAvFoqP(<$h7%TiV(Onf4Yiu(jNPLbvp`C`aKxjAK369j{f!u6f4uSF4JM8 zi`g_Q_T0x?;23P)T38?;d=7%wUEu{3b1NvkfT|*0%$T--Yif@u%I4GG&k7gj273Mj zN4$VwnhLkmI2JYnmuZ!&=rSEex}I%r{)#OIrw{oa`-Hj7XCQx-br?C*6Qj(D$n$-= zUiT>R09fRLAij~x-wu|sk=i|x9{ogm+3nyx|0SKhjf01b?k_3JonY5A=6^|*kYQ_R zGfXuj%4re9|M{n*7Hd$lOk0T65d?J4x9xvC#rTvYPAC=TAtTP~7H6+UV2NsPkQ0+f3=w6@!f8d6=K-2B7uk5e0_E-3y1}kc#MmFkgqlq?J zVWa(j8fAauSH26}F6Is%vl+)tOo7k$XbE-(E)6!zPgLP9x|3;xx$>1S7_T^RlJaqG8snHoaHj67M}YIx_YWR1kfPP39vjrGoK6Y%( zJNOrBT8RU=LF6b1PGI4HMVtOs^)hg#>=WBdHhznhT|Rf4lJ-MCzGiXn&Oe6onc6P=riRS-> zQI!WOw%9BNaUx)70`=9eQY_+JS$~xyS|B)8&pr5=w|YWibVlZ)48(zD6<0jPvI$Syru>b$X-tAalbVK&QIE}v(Ro>j*4TA$|c zmeY$!UE-rK!`TYn*Op7aKT-*qd~KDuii}&F`6tCc#y@5<_J#g2Q#u|5yURohrWRf6 zh*ShnJAs-bL^TK7rMHxY%hQadMgPD?(q0?zc@~1Tst+yk=={Z5uY>$l56H0!q~=p~;{j^<4fc8&I%V&jABwQ6N z1Th{y%=#^7Vq@uCTtD7eT7Kgb8%v{WzzVm&6TUS5jqN)7IbOdYIDc_1%z+5}A=~9m zVd4Sf4}p20$Kq~(kFS)=ZwT?g^0~O_;L+4hp~G{5f#1`VPQ@bH4yEIZJ2-zrhT%`B zYj^g0MJCRchoR{dYqKm0)9Bg`C2MqTla+%SYaLh2q@V8ED2OZf=kDkkKi(@>26iSqy$qWCZqRS84qF(qW84sN<2jS53=#Bs9E_C{9v z|MkXbIuxesXB1~R_bOqOOsaH)31W2{TZ11sd>6&QD)&v^=A zq^Jt8flGM0FFTXHq8jU!UBT$r(WRMk+|IoDLmYI@wDBO!bV;T#w=;j5;1SD#ZF2EC zEE4L>(e%4tSH%)u$#5N8ZwQ0K@yA^Sje09gjOJWfX$#gB5S$Pxcq;i@ynd1ntee4U zTDVTeX$YT(>x%989mcoFKEzNPRvlarErN3k_zw96$PGq&G8%E`o-#WxuojNY+>z6u zyUftY{9AEsQ(Jsh$S)$ydHZS9FhW<(`3_shndXn}v1v3nLRZK$nHAdO%;)IJV;u1X zlKCy}GBFbHQl_q;6>j=d+V7?}(yvHI7|y3m z+(?bjdF{UE?b(&?7iI@hh|zy0s&|z-9a;VBHx%OtT@B`7qPmwa_+n zJW3~ZGP3Sk=&R9KEj$aEYeBtoE>gmO6-Uy>jC6FHRD6y42wDDZfr0~s;410NM|i)M z1hA+fP^(P(*;UdJ(c$6;*y3~srAJVY2%Ta6)GBGr@F+`~2Ig#Ln|ipbqz!Nsh|#td z*ypY`i({2EVyid9D)~YH;eul(Y`EtZVt9l zUNAi(cno_Q4b7@C_caJD%BnHn<@Ebs;~{^6_Gi^8Ph~jSba6~`OJ>t4h&p7`g%Q1z zP3N~NuF%?SIu=>`k(I@0;%1UuIau*9n@-Hamr`<@N$v;8EtVa*|HFL|xh9*)g`8;;zsQH+_>LbLhC1HlHoL zi9dm|_IvctI9XoG*j;#khG5E)e=x&cru}FGMw!Y08$U&mH)(hd+|EWZOW^)qm?PNC zfsB1Qbe=*_FpT2hl5Els5IPN|SBzrHl2b?L_=h!#-5AgitT|VxQcgU)4pTZuJ88K6 zHP8OqVt@UV(_FZ)Xhespe6(S<;pi|8MTCBCmSi)^)QS*2_Tc(V!=Kp*fjc0$KD+g{ zu=rYFpS!rbKAQ!*>Er?AA7{+ejcpFC&%QGuOxytWmy2_s3*e_IHJ8qeO4P`uiy-Qq zOBX;i4UxTc<7sm)WBaLGI@va^**`jx{4sde@1*1yjl~ykrSa5=)21tpr~XJ6vuW;3 z?h0(DhBygO$isMaPE*5 z&m*1jM9EVeoM}@i+}G>_{s11`tHVAF4hVsk4ld2+Sf+)!+#`XFXWZ>6!d;rpfq%jB z0kG9BZba-iOJ@Ccl=7V!M>lfo2-__G&;!@Fe+V=^EfzMYh1(@^iP~l&HMt=cFr8rP{xj@=i+rjip?~qyf>1u z+zrg+IHsr6_3+Pp3LeD2azSW;;JiR%;&o!Cj?nWuevjh3CbSxP$)=pp+&E^0)Hm9A z1yi?z_O+${1}ZGeoB*#hjfyAWK8mLF1RblR`D^>ehv>!&Dt8L+wQ$d+&%j~VFC0Q? z2yY`e@%-_=doF!<`Z_@;U`}v80jA{xb{wQLOpK<8M3`n&KVce99m<>@A()!`Funpo z0JSNoFs5&!F>PX^em(;1&l-ohx&jJPLZlcc9o++{@^UQ1OjC*?L z$_SClxzhI?*8C8h5GgZ%B9ZZTlzGVb7|h0pie=o_`{sp<@+?*vnKfCe3JplYSZjn+ zX-1Nct!mPdNQ;-^UMQ}mh2ro%=S+5Q z!ux(d=FZ%6o^wWaWM_8fO!nXLN=LUMtj2}CxDL$HtLxudUGHL9FXDGBKEj#I)BU_3 zwTrakeT0ye=0sYdB_y1irR^pD891YAEQH`XM_A5S$VlNw7a*lI_|fY~E2N~>#&P(u z8qX4cj-vQ5l4(NYR^}jp?1(K+}=Gq&oJ<{IBf>vC$0-Rd0DnAa^qW2GSt0~9v zu#e*BB%CRH=M%v7r5Ggcg8m=#q?E!as*n|tL&8N^nN+xO!}B(#=7rGv3!@l~14tL^ zs1wj%gw_Zwm9aCwEiC>Dw4MR-b zqO1fRQ+Zk%l_{q3^cx5ez6IfENsS20?PKG9F|FhK0#u_vkfzrsagFaOiLYcdW;0&Y zA{w16mw-{4Mk5@XL7YD$jth5LCE_h5IhX;_g)E*f@GA>z0lJq#QMSS!`gZa*OTCjm_Eiw80OrPOna5eu{Q#3ZORwoNZ61{`6AAK#2rD z*1^PFL+x^miF@_Ym>S?Wb}%&=o7y z3!KrJ?iH~r!;6hUuiKeg#-I}Sq%koVD|*tWF;*#TDLWj4;lDrKj*&- z^^h8)5DqlJ$#s5U3Sl3ai?VFJco7+XAYsdMXe8wQMA0M6%21nQLDN!p57Ei zgyShV)(TG>&refE?C{f}uyUKU9 z^#yad0}u_4+12)~m-?uAoP@bREOk(##xc8kptGStn*iADfJBvTb~QResncLxb=XrV zTO6jdlK7caBF-w+io+hetBqmTkmvP{E?}bxoaEDEclE?0SYrme4_K+pUc}Ol-PNqA zN=*TIrbyDyad@)J=~Wz_-g3$tZ{_z{&iPtNN%2-#BMGmS=xw{JU9q|9dr<0M#P)4C zQ{z1t*j>GT-$yY0z#rjY*3znY#I}iULAB2&j%GXg6+^cy;XSOvV|TS;Z$EW_F?lax zn>C!NB{HC3cXiQ7e~qdPL|q3Zx*WT!8?U=mJMengd_4rn3fVC%uh5sptc0}RS+iqz zHE@oleg^(GmSL80%EO1<)t`I$tBc^>a`+cAqzrafQ%5UxmE~NQVWSW(gBFk7)wYMd zG%AK6r5)G>>QvnNq}nak>DXPpiQ5y5i@@As9P{3>yV|WxpnAY$^H21FaON#aEMY~a z36?o}nUU?TewBueP>ihuTqDN5@bF=G)jirv$$C+D@cN1_=6md})=Kh|ie^j&bC#pP zV|R6DOWp8cs0Z9{9TmGAyQ`XTl2|Vfpn4@StOZcdl2&+P z0C)Gc-POt`aoc;pt4I!*VNtgS_3Y`d$&>tf^e1MuEBeEph8@ujeYCQ8GpVJURP*{NG8Ssk2F%BpI7Kt}<9 zcc+vU5rccJu#U))+q;rSg}79E5T5;oRcs7DriS32U#nDS8Ti7_)W%j2-e%hrd}o`j zjCsK!T`}@B7!t4utgQU*+hAl!^*;dKjVd*ISRRJklZEOnq}WvwbkDlI5$RSrmH;22ZopdBwMuwSXDO<(RV*Br zH(_B-&b`A5ZOU%mNP8k{o7RU!I@6Pp7UcDI~p3)1c25Kh!f*EKX#?3uLcbUV5|e; z=pFM(TdG)D3rhr2JX{VQ8?l}GpkTK_@K+J0M^&tnuvJ#5suf?=)d9$2UHW!bQRQ9M z-7#(f8I>O4pctGaI-OtLW&Le-Ip!yR@biuB(z1 z;a&O_x-t-a>5+~jTP-U_S84(3Crb5dNdkJ-k|fTmWkp#M>Ff5iwU!kkrRK3W8?qmR z=+FP*QyHADdg*#z)sm9VTic3!PZUT;plghMOsdvGeCH|p6ua}`v^3WpDNExn^{p)` zKCUfESzr5|Y@7ulR#Z#+rBqx=HF5g>tdG^^7nkCcm=B=(4Xbxi!8%q^w4_FLpf(Hj zWbZOfsv}Qkwf2tG!Hi#YKBZ@MFi@q3^VPMU_$2Xju1R_8p`$5HmFuA!E8P*K^3<-L z71~6?RY1@~^UiiYsdS(H!$U#-1{m_bt zuGg~)hBaWBK)!-xLS-|c4o+Y_1oDNTsZf37p#iSSwZdC#;LDSSno!LQ=z7{v4PU~P z1e`>!=fV@Jn*p0kc&qLpr`jxo6QQh=Yh7wW4bwjeW@mW?a60&(Fs1?Rs&9n^OBR?R zvrv_%c%o7h63oE&>2ZClctd8ZLnb%%3H8malgGN%Mo4FQh0j`WIuUvJ^0f&i&A=8w zTUT)sU_t{kcc_1$U@8Dtm9Y(|e*-LGOO`A)9WkM?nPb$ynA1RP1Q25#jTWD6oY2I~ zQDiV~t^xZ~u$Fn)BAsjo_e}Fsox$D&)^=uVEY zp38!(D4Ur9^Pgi6)@$s+f-_4~wT5`3T}2-^#J7W0^g~0dEZzX_H$>x2g))rwL5)yZ zB%DUYobW_y)Ck>3DvfJoYG6$39!Tjmp zI7d2W6ZpFw%tXO7`w~y~ivLWQWEMRaz`yBW(lluJF?2!E^+1rskiv#1D7E| zuD*MK$!hqQPEH3!0Z`)q0%bG&U4I2=P4xh1=78pKlC-AmhJTp1Un`C32gC>mMIKZR z!~Z0%qtYb+z%mC^kB2C&DyQK;1&4SAv>AXs0-^_vF>~S)RW5Ts>Pbn%zr-pZ4SN9y z=sJVS^&wi!gi?lonNz0bhkzI9;a|S!ttON<{C~;gr}^c#HV|G5iaC zmi{$v?sdh8_>)KnA~(_SO(_0`@??R}%Y zBiehQy`T@Yoc0=NudnuIYVRBE9nszc?FBW{a@uR8y}s~t9`vJW0NY^`CL4aKu$W$o zU#-Sq7u-}hormGHshJhqd_5O>1?k#~!Im|?aT&%TfKD@znZ}QdkX7;t#a&raTKKB1 zOg8=j;&oqhdU^~1}s|Q=CW5V-hwzG(Um2xM>=*BaN9NZKCpPT4{VNsVHYJdNADw&ODMTH zo^N`12-rC}VuK4nm9K`qrxSX+ax9^B%`wqkLJt9km!$>Xc~Yrp3q00TYTN?ERO;6P z!;)0a91BlF?yljz2u5}0{i4)IZfqC&oW5Zo(GhsjpK~nyqcr-d;XQw-ub{6nTIw`W zj+RzZq%>5k0grV>O#hN!qMY!cD&a=b>TtM#W?)O}3k<}0T3PX7_xNQf=p`K*H zwg{?XVPok%IP)I0Z)Fw8@(&N&Z9wR#iE~<6;YrU}%)Tvg#y>9Aol%Q`SS~0J`?Kt^ z^|0W_?9E{9VD>Y5&mIBw%j2g=ggYJy{r?OS6q)`V#vQd(;ixrE!$GAG=Tb^wzk z^wsZNq&L87jh*qFj3fTYMPCHcFS{FLUCo6h7!YnTrw!$4V>k%?-%0t1Cg`UoFe<4!Hej^KLNoC0%sv}?0W`l@}IgxVMn?Vw;BJ# z?<-Z4nzyrx7h+W%Sm0a6*w+evG(m}~k<9stR=2bA7up8EN)IyqTEU4^0@W|z?9|AI z?J(p1ja4l*)?UMq@JF_A*xGss?prvMSq3K(m7`dS6%r$apIAT^HERBu)71lug&-tm zaj9x>TIMGjkb;5}_z{|&f^wDcxAa|#l?%<_*Ay$-I6)6mu$22JM{t6bI+y)btb&f( z2+WEbK;TS4oMVK1yyMIM4u9&eZm?iU04h14?~sIa5H9=MSIg3%<^XhbKwl%2;j+J_ z?X95f5(O)?@8_#Y+uK{w`6Slx`!#s&Ym0Zld5G$@udUv>y~yZbRW9Ji-9%RICVb1m z)<&6d!|M4RJ`TlYbE!l)(~mlIuyU8q&A4O`+6d8+l05N!y9sr%4VB4502rqw*K|Pt z6-K{zz&FS+dffrNQyAszXca78fRQ2DG0?-AoCwc-yVGmq37H1E#n_(l9K742+w#`?{y&gj>FrPbiX{K}CWX2tdz+mln+paR0CoG!H+&eRb4 zr?XWm-&sb6Pp_K3j+rBu{VZ`o;$^DV1zW)i(SR;iNVP(2ptLxCoJF>jEhrbJ8lxaK z8P4>8>{IGvF%lXJg-3_GSka-MMrZg;cYU?L+6d+~IHLjub;akE3e>PG76&TO$gX(K zRcU!wD&(M)H(+Q8GbxwFP9YQ!lFq0WLj-%CAR_&XG$33jjiUQV4aRm%(2A1Tf z14OnSV-+jYd|X+z^*rhycpHUJS9)Ns&Kk5S_EqHH6Wx{&)>B+h^!*Z^Obrm$!1at? zMFT*H7A8kvFx6v!vO@$aMU;P^}Uw=mSTee@KB8Xm$S zfpIb&Tb@#LynV2ZS=(EWHmz=rarCe_DCOZyk^X~v^ud~;gwN2lK3Fr6aF^-^m!2MwJWGaG zyZdPnwg{-{4(N;r1cRM%-TXCZB>>+!AdcQyGQ8UtONNq6DL*bQ&yr!w7I@XT55Z?5 zOa=O3I=q#d^}~|kHAXs1hF6MUPZ~f*-w2l)1Sg61EE#?|2K%l+HfG{y9`mo!Zm5B_ zN9Mxgd4hP&N>wUmWWxnLh_4`+_DSFRky=k8Q32z2?a~-~IG0OZHA4I+e zc|(2|>!ynXq>Qo-#L6RUGFZ81<+0Kqc;3Yepr*m05IPUU6ksb&VGoD02cm1-O2-CD zAv|JlD`iW?)&-p?+X7Vf;@ED?oncr(mns04o+;Y^)Z~)BDhEei5xi>5zeWR6t2S>mEaX!8;7~@@24QK_BcN*@jT|J|T|7w2VCNt!O1HjCbaxOA2r=HX zviYPOK0-c#x;LWIE@&*+SjX4{#w zY2GlaN#P59@qd=lr$c`gzSHV^9X0+?5tq6EXEM)d&p$WGe>gVS385QR9*#a*!uKg< zxD}FB!o$ZSZRzN#4&o-Q2Et!UB5tTU3PK4jF1k4d9VG$JtY2p0BjLFim%0O|6CiqT zQt$}u*cNQ89_1YooS;uI)XgqMqc7=bUf|I(omc#XY4&)NHzqDP``U!Yp-{Yza( z3U4lZ|I$v)`%`!eMhPNPdsVd8UVCG;w|ta{9oGNukFpBpdd`J(C(fmw!0Eib?MqRk ztpaU@l|SC4;@~vPyB{)CtivD`p2xI~)l^C_HNkJp-#@x^F-$-O|okG2X~^0+{I37UTN*(h!d+Kw;|ps0*&^dShEnTJM>u@VXhGasi& zcISmxbXk=eqlSH2%%#47gH_HWW2{0Ml;ok;nYHGl!f8^xwbRgGFHmoIPHHF(_4@+- zl!op^;;KYf(yUOF1m&M<1yi1}R(3puqGKWYFEt)(MZ~3Ngr7R^!V6#JWlaw8Rg#00 z5-!yf&MARKW36z@E{+}elTn<_d4!wZ*13+@W6K3_1fpj%iu;a(czT3X41eO%b#d%` zem}gnw-qoNcCWeVR7!BEI&jV-9>(H!>`TU3Jqug?A?Y;MkM^P{A41|SOEFJ3zd$NB z9*tE9jj6+U?1q(a4wlvp?W&c#45I8_64e||3lE$Rk~H8zS_>(yA&?G_w?dj}ZQM2j zJ!<~3?i9x8dj=|QIchkXjG$*Qu7OF|YXAaEWr{11Do#M7X4UUB>Va)=_CgwUJ%}`O z#2RO6)Z1VOO{4k)G15UvMrAt6jk+}q{R?V70LvW^=TAv-OMirUTL_rbO0OX4FB1% z)?*Bo2pWO;fky!w<_zCwSQTJLSonRx8|2~hJ5cyh!9DbG$MnV3I z;_YT5ZWmke3_pQAzIVLn&xts!5lnwil#E7W_6Cs>7SPJ=I(8YF7+#%Y0;y}=$|}FDpBN= zOj@f`JrGbgdQL$nW6>;lc49Vb&eg+cJc&a9C0uMLr*UFtHp?r#Hz! zADn@{CTDOD?V8W%{WV`GJ2o1MixVlWb~@wQbXWO z0hEK7)9aMw-9*#CTki0CeT{sjt38T%d_<}guCm2jf)j;N%A@8V>p^wA=e&dp|B4x- z!M#7_r{iTqq(pBiN|}xxh6(TVFh^_pt61q_`as7pM~~#kd2RT5l6N|4E)Yu{lw`{3 zVLHR?yy)5lz-|Y`DbPL4i|OcLk|_HOJm7drVlRn$&p^Gw^;hgA(OS(rt9d>%g%{0U z64laPSM5#G-b(H5)837lR$TrhE+g5GAAZ)bHeSK!-^wW5H~8^NLO~@_saa^PH32h9 zfKY*nQdsq=Cpc|{(+$*t4kwv)+O2g^EpH{5Y2Yt#F!db_T5IkbhHB0+tOtJ!V>nqx zeY!nMa-VxP8c2GiRc2dp`Wd%n6*8{~A7)xXIdDiFVda3h3cB|-9J^p~4ER*lc0>nvc`9H;>F z`^y6>uF@E!=Q)_ZHSM@KF-8W|Kh`I!&>@8bP|N{wf{d2bcD@x-L{caz5UC1h>)@RX z1O1+n{L!%|WCn{IEt_xUZk-_A#cWU(JK7}wPIs|*8Ad8W{RG4=2PK8zbQj~Z`fJpA z0B#6~vMxY%=t5-{pp7)8j_h@zSqo6}n$mjqy3kS0d!>0XB)q!pb)g>Go2tE4+S{+a z+uHM8C_3L;C;}fYL`Tqzi=t^A?CF5hk81$U0H=*`J_dEZ!x_qt$L|fdSMBBpseW^FPG^EA&#eP&X#f z4iGeRDqZ^&hjoNGi$WJ+uHBRp7h#0<;HOg8MVS=LqS+t-_$`3&PQtU}eXBVUi!p%^ z6$w;tF(wdA2kOQ;b}<@j7n-|Rp3bJlc0vZwMTBE@hB(u%(p_CDe7l$R&$>W$t~Szr zzdn}M;Otx%{>&rXfWzsfF(3ndK?eHP4D>%U(7l(SO%A64OVB2Vr=mcmO{Nho!8^YY zI?w?yb$BA(U1EiNDD<{R?536mIZsoY*Az|dRYRAu8X>s?6@cB;7K{Tw47@mp-+?Q6 z8ns@E(N+W|a!S%@EC^|y$V83Ps@B)xw}Tl_vd~ua&Y--l6u!Vo``G}*b{l1Ibe_5V zZ*z@w)L9^|IVes8R#8Lnsg&RQAD{Qvus1;XHs-8RsbzSO)2PKV)WG315nk14EG285 z;e!mTQ66s<1FW$GKc9<`hdl1NygVRIQ>M3z6Ga^aMppk$>A)K1g6jU z7nM^=Fvq~Z;9$tXpkYQ%_fwy93{SvU?{gmbA5roDkz#4{KWHHG5Q!#%q{FLd)Bjiz zC4?>|u!?o+AsZ%tqN2T3$0I11!%%pJl?rk_S)ZfDO87^r{5e|eaBB5ATC7LWdYbw< z8k2|cqiCLnQ~2RNURM8{zWR|Y#Z+k(9G>HGXn>+;@S;UdGAPIL!jrtL^^XlL68Hhu zCE*}a?F+PV!6s6lFVMz^r|LHT`4?#8)99x!q-vc10!>q^T<|4==|vNjAzY8c8bbXL zj@1}RG@JAbhq<4ioL)KwY0X^fV>tUMZqA_S5({TYzAOoJ_O{$GM%jqV@&N>&vv7JU zimbH$#hX;vSNL#JpW1$f4=43$`d9dHl8jqX(dLr};XyX11K&R_gGt zv6b3GZmYo+zs6Q-q4uHvUt3|x67B@1=g!)8&Czs+x4>>4I8%eUoi=BbbEn7JcHU|! z02>?-Ye9N0evKa4Q44~#3M={<2%gArk8SyrcuNRw=~6LpIr8^Tjhf-mmcSRq6Rh`q=3H-h`#^}Rci44Wv_;R!}`Mou23J`N0l;mDeQTW!9 z9jiN{Y8?QZ91thU{?=kzxA@fJ5il<~04e;o6u26-KAB=xrS|q|?}qk#)>;vDdPpJKmyJCOMDYZ+!IT_M z7a}J|>H9RcxU9MjQOd=@tegpe_v=1uCB0Lj6w$AO7bd#x&mt@KV2ZpRQd>lluC0}f z2i03=MZ)W~4lCfvG>g3+v|$|@S2CShCn}$@mrQxTk$+|3RpYt<3pe?&76Ai~ zBe5oVnERya?OduZoT)P>pEZ_yS-rhc)+wO(WS-Qcw)E*Yb_3`~TM$MJr@pbmb-jyk zg$mS`-Xg9HgnksWUXoIGy%keJ^axNtI7t%sLQ!+QtuovF)LT4RqfZK^i*RN#{m**I z)vxO@zZYSyB>Me7>a@4DbO+}5X92ye;X&WxONZb*`hCr-`eNO`r(oB5XnU86hJ)@V z-{KRafaMcMTN(-JI3Y+fGN`bxv#@Z+#hd~0g<8cg-%9dse)~?Ivwimtp#lhaNUguK zik6cW?c7@N(NfsnLA5bcJ0Rgk#(1i&#m1h5dE=9W1 z2jI8^Vl7C|>mN{Pj#>~3|A;Ou1Hls+y08z@@L8=~7gSz29a-+Pk_}Fh-G#mX3aV3p z=xL)ecVVd&y;WUK;{@<$+884>a~Bq&+#2;Y5E~qn|r_ zVMW_`0OlJ9Acdcg;(tPW%0_j6LKDwMqkckf6+^3kLbb_82iS|DJ50<*c{d8L)<)rV zWiN&%X>XB82I#EWSoFxzDU z82M<%CQ0uqt$RPbFwt#yVI984!#E15b0SGznWR5FoT)QscVQ<#M|DgC{bS}y zJ<3O$x7ZD!IGsZn@%^_2U6`;NVupdNMQpVzq7aHxT@V25u@zmI2dE#MB+2f=mR<-@ z5v*iJFZ2;`W;Xg|tK{nDR&-$^%$3B`g%!f5f8#lzZ#BHwHgsWv^XPZFus46#no++JnQFo@|^H4p*0A2 z5F>v^7bY#*>B6o)vlPc<&h3M&mysG~cVP`z;t&c?7`=K87=fZXfrQcvN`-IRX^Hij`R zYd@C?g#)eT4l5#D#F?Sy8TaSGAWTtj)e!s^8Z&-}RUf9VkL7oF597^s#rza4m;nZJ_e?y*YNU&%1XxE~js>FSG*LwT#4*3J;O zBF65(&t49QQpf7wZ*|bD&VznKc$9Uo6=}?;1bAtTG+0>mYzzy`d5@V9Z&51B%-zp~ z^`~t{l*+|%B?iDi;7QXe^0!;9<=9gO<03LR9oPTIxZmx~h6c?5axSAKAC7UqIceDG zBI?$GxxrEASoa%-1E>`M%$HX`eOT@R6e2L|uQg zO4{M2zoF+6`lrLt{cNJ&euI&{41@*yG3TC7@%zyL=Tqzbu(3CvKH3i(dji@{>-J-# z=zRJOBzX52w~|5*2)qt^D{069E4B{9(+$*ZfIZjWFkzcI0xPj_k|VuNw8w+m=(0ZZ z$JV&@Kx}bP+v)ZJ3_=q59`ZYgRVJMft|oh^#6i4W3E_Z86YeefaVQ#GxsiC`fz$CZ zz>xTydrRuf3RLX?NX-nIN=pvf#UxTw>DPleCF;auNP}|jEpa7b>T(u3u8AHBIs_wm zzjJhNK=2)9r(ipkJtU8=1$*;pnEtm=|J$VhojD{$>2uhM@2Kl0-?^CAA6A52UTPJT z84;tgO$<)g4Egk%H;b3Gt3P@%<|lzyllfYnzpUoX;bpyiYUwYlDd2U{e0>GV`omWC zwi;}k*i&Qu1Y@iNaD$`FF|k*_5Z-n6gMNZ}QZk%lkBPm2thh`ByvM?)@FSAt%13Z4 zZa#HCf^l>{&CuTW+B<#3ih?Hk`>~a~`1`PSU_2NDdARh9+P9r7jBu-CTz!MmTq+pO zoKMw{LgPy6uDu!X>?*(UD27VT9BTUo4ohM;k@35S9*r>4Q|ot8(hFWKT^zO@yr0VW zDS4tJ$GX%cIGtswbdDXo5siG+V(`{D{NL#$$D)geUStSI9P`j?9J3qfDH?SQ%cg=q zMeBjd&^AxeSrB4{DXsSu7r4v5qNMy&U)69NO6385p2MM33jX0KhlYPx-}n^goi(+| zIF8o@2{+I5ns6r-mox(sFadkG;mqPx^*CM=m{tP+D`;Am<4C-SSD=rNTeXaabnH0B z>=|APOS^<1|at|Ec7grcZ@2)%OW{+#=oi5L-VGxx0hBiMCZ;P|1NGkeU`^R7Bv2% zl=Em_>0wyhj_{Z8C(}@!{-RyyG5%#FJU@>Ca4$t)K>gZFA6&oyxR*v>unOiE)NL-u zz$sXT$ve#QK0MM#O`nckAaLeh+65TURWDjO>G=h`&>o{47ex<9@%Y#8BDS#YrNtL9 zjEOpVt`Bh^pcUHCqhH%~-QltlqHy44{|xl9a8l&PLr#DO>~>lHxSQR$1Lg|{z$r8y zQp_dnC>NDasQx88z9*VF;1XUKHIoUOX~8ACTm-S1c3#3{DI?-8bi^`2uL;OZKJQf@ z?{(2$>Ln|AIul8pWhe7CC0v$An9SZ@8leBp(f_{F|BhXj!g8Mt$I! z$NK33>gzwTCVq^zYS#Hb@kStNdr7bUMAP3(d9H|T;uQ=pd#S?}^a^`vlJ?eU@AoSh zUiS8r;e`UPT0uaBT@|s4SAjo99ke$Io>u=CeG7mO*Dh3*lN^?4|DqQe=n;R3lBB;x zNoRP`x*gbq$A&M{i)heX?3aSmPx1+U^A|db^o$&V7AaptN;B_AIHMN${)d4o?_3}6 z4Ut&Kh2R56_$B4NW+&$*Rk~(Zaf1e5!w4cu4f-0GG7^^RZt&J3*Z4%dIY0Ndo>mQ1 z2e=jdJkO;L!|7ycB)x(tm(X=jVbr>g5u_RKb?QSeuEP?Lgr{X1K?WIKsskY23tTEI zoGF-zuw|M)8J&m|BB%TX69ax}!BD#!$c#Wc(1aTpQBvu^4J#xzm17&u$+l;ChgZPh zCsU1+5dD+IHHfm@gjt?cioS^nWix7c6YXyzb-Rh-Vj``)i7GacPTYhgo@uPkvBZ-l zXP~M?IFJR0&n`J{VGP+yxX&Xbb}L7-D`VvGBVnyXBJZ*g8@l044WebY5cyX6=@!Ne z&c|W!jx&D=%iCi{)(J2`4#Hh<9x-=4Mc&4kahOKjMpZb>s*lqmCw!K+IN{554q<=6 zoMqr;dg~CRAAy0DI~X6XGqc1ZoP32d@8X|ld}tBuR*#t91iTNK|CA;|D9clZIpf0; z+II)G+C|oxwOu-cCE>%6Ib-WJrXu9A)xJF*y~6{Lp1%XIZMDx%#yl>|VwVbmGw)K3 zyZ_5p`=oqc>NV10CIix3V3M-``$o$Z%Wy9+gVOLbkpq$sX9Rk=&#kpB1Mf@b>*BC) zv~2SVH(H8<9boSDD6q$-t1APwg3I7t_b9NZb4}v?wESD}ygzdiU{B{Z{{(ZYTpAJJ zMKNCz;EZPL`(uH@W2?PTc6@MPR73nU<$%tQZL59eWqf<&RP+HamH9e9wypM4@B8ZH z%m8n$Bk$O1cWwOr9*>MHW%yEy2k17^!?Pb?1d#BwrDzGhwB-Rt#*Bo2u*(IeSRx*x zDcz-p4>2;{r6CV7H5619TJ{iq@m<;i61+={drAR+3%opgPpSLgR%~I0d!~kKo?vP? za=A-QgOmK|sbMbK@;CbVblvBja4vdINdhFe$p8DU%`rm5(@4!D&Y|q$xO40ucvKD(! zsVh8G3~eiYz>omd{Bu09H2h42ORqBaM6OP#()?xMed+L>iCoF^klhOUKITc*IL)4k zT$6tT)Oql3IDD=kj;-{_$Jl;*mr6Xw$a|MsJ;oq-m(sNNh4%J8hLxPV^iX@bo=9HG zJOL60va|=w&xP!oxC#ItuJ@>fM-YycMEP=}9HZxhx5Fd{*V9X1y3}nr$u$J>{wLbY z{wLbo!mFj5kUbdZ=;W*9q4Zga4`*;0s)#d_`w!pvXMnfF;peAcp;;#}Ki$g^&i2$p zfA6W?pbAsprx=GN>4j+pFd5oXVLJFO;Ry&Rqg>BC<&gBu`X+58*PpqZcgIBT`;GZb z%GcUoFoQGJQ2Q4c&)3kh7ibr2=KpI?D*Vgs?iRB9+^RQnoF0&JaL5Z zX#Go!`JCo`_KOT1_iqJv`EEOR-?19;XJKqo?urq*M(y+j{NFF{g!pkB#bcX7a z)LQdKvX_k(Geqako_NM=-2aw`R~9siQ?lVMX@{p8ZhWt0`bXcPViuL3v&7 z5Rgi_Y*H-#&2YIx(?p%TFjioldR)Zn>!1>GTN5 zo2GcVBi{2!aUC{f!laXW$z^>p5nq^=LhhS)WiKK|DS~(Au}x7FwOP?^NIZ6=qy$`8 z#Z!47x~#1|{goHKMi@aqVjDG_sVm-9zQFunmo?q;RonRa76Y#|^Es8uCH$u@tKn$3 z!t-x{&%|JU;3$y&etBQItk-SQ74!vfkfT8J-@2?1?)kC;oQ?r+p2*W~Z>cel*u(c& zA2-*|B=+)A3OuAy&!QLkxU++{PO}dCxUsu|b6lGq_()~(wL~_?a>qbLQ_Ia?n1^X^ ziS~Z6+)>Dso<+a4+(AGDxkap)8~A+GRC~kV#ftjkQUr3_w4b*XxzbzbV8$kV^@Won zM1%MhTI|+xkHcKFpl92-yc`?^Ey9PWe` zJA6Gu*w4>HFYafz*M`*1&mFJv4QUZDWh5(7^bI9H_AEO8IUoJV*KdJEAUGYnM$!X_ zatZmn@#$9Qr>wvG8=n;%-c0xW-Jx|Qd_2<#-hGgtS_jC}tU997SuLa4a1{*k3SF42-2m4naD=SjwH%U9xxrGYjm*UB7T< zBK~=1%vW>bN<-#X1FsJAtJ6>jWvR|EXJETco3gqi@`O!wseHT7m!Rf?g80{uyb4TQtsGZSn&IRnHVWBw?AQ7T{ z9+*Aa-O8U1I|j&U4fDy4>RFwl;iXB^ozda%fAcK2Arhvl$(Q!l5xWC3M zun;!e?cEJW13x>5zP-;L92JF=hzt%vYHd!8sUnq5xRw)RY9eLJg?gJvNx3klCQ|oY z?t(g=)-)#<>Tn{h1qt5ojH^y>G#vkOQkC3j0M)5gZg*^9$&(&p@JaKJBiPZ{XCIOQ zr;{OdsspXfjhvqwd1Of8I^#w+Nuezo;=V}yhibV+k+JX6%&A9}09;GJ>!{QT`Hs;~EN#qmlH z-fQ7gfe?&uiPRtj-B=;qG6(>F}zy3_1FVgZd_L_#hY>nd+*?M9_8sfQ_|2`0V)l=Sq{Gs zZH8tYV;{PNaIC~Gs`TYsvVOeW$9wQ_AN2r&Z!!oM$%oNS1X8JeK6kusZmC?b&P7|( z%3A72Zd+pxW5*v{hUS(^Kj*V+nKZXlx(Nab&kFYxP(rwSZrkIm)SiFcnT-XSHAh_P zCpeQ?##!duBgP0^AA6ap#_s@}&kVBXU*A+lmAEH7${*pb0$aWvBQQo?rxg*XXxHgz zgu77KUDoT&3}f10>)uhU8N*?!oh8ye#(bShvm)JjeO_~fE?O7q4$d!OU*20fWE!TX zQ3K7l9|Yi*CZtwaS?Fe@y9Snv;_|zLeRA=px=^Z*a7_v4XUVWqi8u>B+iV(YsK&=| z?K7My?82g0*z?TlEqqkZOe`Zmt;+8%7#|PVm*A{nZYh>=tTiR#imFgh_JDPO+2!bY zes>9@92G6#4y`C)$6C|aNK?iA0gGvHqQ^*LWsbF`#DYGm0eH=YPvZ*Uk+KGDttpAt zK&6imYSN(s7;zC0fi)SOMA-_uL!yPr5g1JMSZnJ3DT?H{OBIGQaa^~cJ0ZUl zi^p11L45S@3&kScAPekVra- z8nlM`M!ClrKhymvRD+*6y4@5IjS3{;{VZu$pqguy3OI$d3hOA1MePaT*HfMJyrgD<1Z2bM`GC^$l2?9rjI$E4@yQTOXkIXJQ#w$Xyt9>ONpz zr(Mbq&it2UoH}**mZ3Ne1;L78_H$}c73B{XYo$yVnkFZ91V;2;((tslF;AlZ|6b6$$ zwJL5t%$A+OehfI=9RF<*)G8+)Pp$IBM}WhCT+}c#2DR#6DiVWQ)sywvwd(nH^eH{C z19=df$t0H07n-!QIH-{RS3Zf)k|gxhQ8^ z`?g@2)>sV%Kf;-UP(y&wM(HY=Rx>^=bP&w*4uDl40e%U{x+4KX@dOlFMncO3cVt2a z0!OVCvCM}Ia;*$dK1iGKBLsFjLXshUd;rI! zdSy2>=o|po9gyV7Ib-l+l|T)83xMC%jM3X?45&s)cUGMlDc;AFQqmoYM=-LayCl4C zN}^>3(1ntCbhqdgdjSMXSMm5)kG%jIR!Vpa*$bde+B>7YXWGkKT6kr(*8*O?04aU@ zWI@;$D3O$Fc=?0Fbyf39yCXBDYDZ~F)p@PqrS?M0VD55@-YX+X?ZI9EeO3l@%K-Yh z3??+U=n8uQD%=yOgpysR0+0u=XG#^4)xU~uxlFc(fg z2X)$nL4D@W2X8U+1L(kec4d7`cb#x{3P_YB7fE!7>#U^V2^fzlInk~@LdZ@dK|pdA zC%R)wNG%e&ejHqt@Al{fCIdJS$F9Bg7fHi&I>GsIe4=VfWrjL`DB#x%`p$(3UMLnwxR&c1aqkakdp+D z=`i%hiC#%y2Iclif}NdUL+&!nh12aPz1(I%6wh{DId{==54fP5BL+*Fcq>kVxfe1%58g!FIb~DUO=7#1X);nwYAqxdz0bSsU+oP z_io#Ap>SsYjaMc(ohwd`=iF2YUiw%M=8jANBZ?kWk@Wgil?aP!uU=L3d%@JDs$^mz zdzI*5RrGt6=w4M+=U~cO4PGTGT@8&am|9j7@!{+R)2HyNN(!BRZwuc1+DnE12Tv7F zQt9dUhTvRIZ|3g-?*Q{F(er9{?T(_5>UOv~RX`ZAG_Q_+PioLNcnHYK*y?s26GC-b z4FZ4%s-xfY0QG~Cnqi-ls-D|WV_C_AfAKyBX9iQj8j`a*HPG*gFxM|nzn5hjCP=Lw zyHtBPz-QHPhZYu`N59kW87;6%`5Ay;Y4EWc7<~jRy;~H$f^?h^BpDf0*u7iUiRc-F zo?tgN9OA29Qql!MmWEM^*K=hWQ z9(CMdX)LAt9Bumrb|@Q+bE*2Q#~2Ec@s3y$t92~I%*K5N8npz7uN_oPMoG8BrYk~x zEsgpGfWr=mQ=r5SrB_{d9-MCutBd8tr;WXhu_rLX}1R@)trpcphOZ6JK<8-(mjcR~SKC!dFQ+te%87bQj8?WH2>sm`UqM8VUkRo&bcm4W6Bt8=B+O$Q`9g z^(mo|I}`<^jZbuIghkk78qo-n$+WBy))aL%I7NDB{fa=MBUiMPP1%!%={%O)%SENBNU6vaX}X$?if$H*k#3 zY=2c9EO7(d9(!mFVL8_7XV8*lcYo~14SFAQ|Gk{9gA|W&ehD9AJ@(xHNi|Ewo5+-~ zPE)t{vDkEx*0SV9mi&tjB3x6#w^`C&tsEHvlkt!|$I`-nD2mfpmb%^cRd+J6jN25` z6e~+l0E@!$q*yrfCCfOI`ZEi>)nB000IMFe4I17QD@z8gZiN~o4xo*; z9>e1P-I>1+jPO&3z&kB`GCn}XXAOG(Zc*$9=z)b0NDV%~{9VEisW-wJ7|6Z7MRP!i z7A8kvFx4}Ee=^TYedgt*zJkN|#$z8~UCD{Xv#xahGjH_(kT)7uu$en5s|S`on6zl- zE^PFsvCZ&;T$pw>bLVa)ZxXhN}=h#XKh?^qEtJ6vAl?% zznC4b+1PB*v%Xcinz#Cl*{_)8!)!|U&>i6?C^o4)gIay)u9(I>WTf6bR@}&T92ejj zV*sDZBCR?1shoRfd)b%I{IH7)%+(ISYcc@NS>oNh15`JN><0gcgIUoq{! zCJg4Ne*{Ef&C$Lk!fsTxxjWpLLG7EnOSK)&(c8`PVQ0Jxj~TzSYTRi6y7vSXn|%qjrzAhvz$gt zTVN4x4#(&;%bA-D!LDcg9JM=^0?dan)hG@? z`OF|Y&2g`JIa+u$wk5uabD9bNmoV*f)@OecU$9Q8J|O%E&Q|9BNOxMgTc#ankh7z# z{t91J)DPEdz?sZ4&U*ORQI=(%x2gwTGlzef`Oc2At6!O_CwPM${&kN$c9dPX5uiQ> zZ;{Q9GgyI<0fil9TXD_odLVY#DE%sQ9k(Xo3-4VPcmbC3M~@HkddmC| z@FJQ2dMGt%?M}$@nsLsT_s?l|YYcaf=-bwK^L|8!T4N^gi0*4IsLlWS$X>XdpK@VT zF+&5qRDL)eafXlV?b_fYyTsyrWKW$KsD*k!pq~iQQV-1j$lh>Py6#ngtkW#nY`Lj2b`EFd)){RYNEQz}+3#8z)U3$1x3i>|@ zH)GqaS?Hq_d;rf#*p`C#kwHX`IzdwSqGr z(MNy*{dIeHJSYEjdr{@pLH{k)!Ce&Gb{#O~6e6x0zr%5>NP zIy=fbH8NF5b}v;NPNye7gRWD{j@VJ=k>Wc1&W^IMs+d&wgIwCXvfm&^DS~&tnh$da zsKTs%3ncbBQc?oWjt8zQXZ@&?RL-oO zbzM#9><;G|k=)rG$9`J+|7D#q;z}VFrX2{QdYpp@yceDE#r+W#>VntGM^smPeYH2Y z3wD$}8mf1c{oVyT${x|>E+Y082#z4CtGgik_29=!1X)n7%4P2j(E$oURM+?x;2uEwW2=gmt-h-C6wFwvB@GIqE2%cf#M`U)>5f|y^E+{g3E|hnR zkN1S10`*f(%;Tl1!KK$D8qm#?`#Ih0cni}{8N%m1;RW68b{tP-yJHe5$&9C7-7~f6 zc$)t%VFw6YM&0pRpPo109`4p*zfD4!42xjtleWV{|oj~AHtcx(bygk>PE|Z zxbtN>!oWOy>0n+jBWG(m1fp?-?(}en2b}=#3Pf&dvD`h~;ZdyEkc$Q_zGyHnERuG{ zwk(DgLML4m4l%R@)cB2t^>o(@JI65$oN*buCR@Vd`F^)r1<(%+JV%#$VnW0S*el7} z%UvSN4MykTn-TNYH9~N!U@s(66D5)LjF3Jw5=59C`LvfiJoz33W`}yI1#qUsW$|r^ zc~cF`Yds7{fV>`Vi_OlM_>o9FF4tle$H6}<7;^VU;?Ggx-q>2!hsO1GS4j)S%a*Z( zD@F>>bL|T*c;Gecx3|ZHb(S4q?}am2!g+i9{Fbj`LE{pBt}#1*#<#Z;Kl&?C{u(S7 z4n1l1WP@+Z?b+Ch%l^b$1M-1cPyqCPANPl8-?)$f*U&1y%J;s@8dnTo+D3yi50FI+ zD~5lV3*$lgK6Y8vH+!ja%>MzrEe_ub`65vHzH(Xjcl!(fI9O*Lw!FM@M5R+2^jF@a zpjLUe13P>x74GZK<;Oe?qFR03CF&+|q!n)bg#!n(ysTe(p<6dn!o5^aIFp%1Jx0j7 zgYRswT$6KIstJ>gi9pQuplC;5EFLG(g}&~{0wVY!3;K%cQ(oD&R>r*fHt>%{hQj-~ zbEk=>pa?G&45y>hQY8lZDPJFN>))E_yo-Zb#s;X|v2}5w=RQ}Z$58p z^lVGD;e@pXvJ;~_a{P0Rr=`6yuz6=KH5LZgKrzOE`H=w97~$%Z2PIm_+X}|grT~_L z`GupwRX!m=`4;iE^5WXzGdSF7YzJ?T!0EgImiRPCQ}h`GltJlEpmtlPig-Q3ub-%A~UGnr?+ zW(1z&2 zTC$uEmms+#)AEHw#%Wlq*L$fIoWqNd_=}~!;;cFi>rezfR!a$h=PGFPorcvt$XEDb zU=?uKIzB{{v0;4$4dEvBPesGxM5HHbRw|~+n`mdMJ1lM!$F!Rh;54BZ_(H#*$;J_= zKg&^Q6uAeX32maNLHKYYq@z@SkUKP1!txNLczqvwSq1i6T1oRlUaBLU)^U{PKma<{ z4Z{2ANseVDm}?nup3XzDah_g*2QO@}cohd@>Mb$sr?yV`28|i)E*N*7HDs=rtW=f% z9W~N-w0GF_nx=B6=lk$rcQRknHN+iK?b-wg-ocMEnd*)cnSV3YC>o9S3}<>k_GIe$ zHO#7O36Dk&!2~c4^}(3{4w{Tjs$hNsXZ%OohF}8tAH5uccjW(YArglER}-l5Pa zR~)mm2vdcI4t4i$74#8^VV^g^l1C@A_os$BTo^A7a3*t%oWee_6UJ70ny;Sut9xKQ zb=V=ywwG#ZHL;Y114~*mlBy2FHjQXeAZsoY&7&zw^#WoDqnKmFdDzp<73h^d25Y{< zF6m*vTyRG<$?3Zp{en+NePnN1%4spw}a?xZ@;Mx6mq7a-{n-?%?$s zg~gpVRDTq{ezu_zqugNyI&xBLn0R4Iy{2Lj>fD<(;YGAyXU4OUTS(gx-&Q(`v{$c zgQM}TDN^Z#Cs3b>5IF{&w;&P{Igy+k$6jRPaUjJP^HOEuL~-Wto~4dkYAnZ;41OCM zV+>*?`jaNMa`>$F)}SE(jB`Mopmb1fn7qwB%hagFK&%uL{XWJ{tP~(FgF<4Bj+7@2 zUj#c+y)?AvNi-}C53nOGWN#8}Vq!#*8ZH>0?+&;@M?Pad~r_H2$!|{Cqwg7!0Q5+ zmac#=&WW1fvdWAL&=I78InkqlFV2aY?y|g}rSq48_oau=tA$Z>T~_%{UP=mL2Y7ou zd_D*qwGbJo>(czo;9W1_6_K6;ZGm^C%PM>lbM2R4`Xq4fsl>Q<%D446Dc_;vq$mkq zn3RES#j-*_EG;g9@YhoD(M;guEBw8^ZGs2FvZ@j3y z!Cpu5nSg#lm#%#Y;haI}b9hY8Rtha1PO6*d3+>PCvHP1xg#_>tnJ@Cbwt36y-(sP@ zA?Ph^S%cdb-jJ4|^uP78hR0&W=nLj>4X6uU(*!VclzeAL$M3#msr0cc4 zCBKL31|~b15zvO^N4wfk4Y57x^U=7MtF%>ty-c|7v*&vD@ zi@UQ{8t!@BolT*JWA)ndXM8USvxA=*Jj@l~T5A2NrY=sfRIb8!wG~10kX*BaZFVe5$^zfjIoQr!VP>WuU(|fmk zz(UtdpbM^&>Xh~sO%XIkdI?DB3q(ubk#P znlo@t1s;8k+b^K}!!$;u>47I{<#6}ND1(+qu;5G{c$!wF5-t=06?MZ|7QCB~tygfJYxwffo-z?N%0bhoDLzi!s4H6&QBcPfP?h z%Z)4F+*5&|?n0~qw$qKXzErumrvef5dLpI*R=F51MnRKQ;qp$xR3M&OO+x>Ury-Lt z6>t~TnhMmSO_MMcC`02XV=7RFj!wo@pbWj4jHy5h7u7u#cp8mq&HHk`LN5vTjNspNDBQ>YW7w2rD6u2X-A<}dV$@M$Q1 zMj@!0@tpeS-FAo)j4#B`QpPQP*Qx)#uS3j5!Q>ub2Ryjz)W3HnmSz~g3hWj_n$v*m z)ZenZv@-Yr(6^F11J|iP3}RJ)Xka-#xa-uf1^5V65#@nZ@!+mgf89U*ExZk|j+OY- zuRL&{`ejk9j|>7hnw3*%!#Dq_-;3X<`hEG0s>&?i;?%D!xK8~8-@v`d%Dy5I0R|d; zs~TbyM;$5sTb%kk(uHp^-lxzzjyh8842-TRRCR_j*@>eR8jZ-=I<8ay6+;tCc{rU` z1xGl7vvpjXQm5C^#CFCv0^82G<(uo&AB%Mvc^vZdE?vpTljqdWuO*ca0lu~feCqG2 z7_L+Q$&*;F39O2-6~W5hb?P5lH9&Odw#^TyoC}t!x$98(nXaQs3A)lO2;k=SnK<>U zV@b)Ko%pc@2F+3xQ*0Ja{fg6u+RjqdKNykMI8lebv*f#H>9GwJRgIpOd#>*f`!B^y zmrhng&qJ_|c~xL5Q{|`Y)ZeKi)`s4KW~x*2{^RdT2+-Dt33CE9Vz}o7F|VZRliGC{!N=}{W-Ax-%~pLR)r$Jg#+*Po z){GX+#+<-PbB@_Y3FnGct@Ph!>jgD)X?Ew*NeG$qP=!~h;5ukujk6bA3x5->)3Vn=i~1tI~>JvADLD$#-Gr(upjaTxUe~Ni!t7F?ZTQN zt@Nr>%mO_z?HLy=`N)m{5wqWxW?}^{Kkl@bLeLnpuDFtqGJe1od=wqEF0f`UT)t-g zq5P;}%r7BFd)UPX2zmn^oROlpZCn@&Xk4d_iwNE`AZ$^1g+x&~;9FjG48?LzmZDC8P!6J+}xOcfo z&sB07G8zGRGJ-aXbG?!ky7pz;G*NVrf`7R!+2R>72UXdHLz`hUEwVNwR6L&19C>*tAV#slIW$h zelb=98M8?A>td`19-t44vEAXhS|g^7EAvIs1O9r!zz257v}LHlLL|H z-?9ME(k_P8fvolQ*}nFjqi{zf6<`Y&L7wA`+zar}ciCyqce*2=GM{lZvC}zUs}M7x zyx3!aPJV}j`vBel4y%cmxs^gUJ+RSu_Uo;!Vq zc72c4#2aiO<7y%s{a>qzk>psSmo`)Dq0c_UrCuu4TcYQxH~|0ae1f?;g64-;FG!X+ zdq!Vhd&(V6jDw^%@WE~lORVNdrL9YFN7I+CF2O)EfP9wXtrYjp0gm2U5LMiIz0E(m zk+WmA-e3#MmBZPP(NuS-o*3!RuX}JE)p>dSrzPl}5%5UGw557X9%jf8rnwH@ds%R2 z4}yhYtx`-yp$kj(0kSI9UxvwQRqD13%2gSu?XB#g&nnj^0%k=?~3z+G0W%x5(T0H>e71I__+zJ?E zhFs!p@bD8utb(9mQ|yO9&@2jlz5=D$M}MwBY4*`OR^G?ThrE^L96ap}fr)z-VF;Q< zp(-o&ZgMDXT&XXWg{ko>jLU^-_$us7ElG3mFMCNfh%e>Z=0SXYbLSvlj;=6VPQjh= zhIj=(bHSAG`3|4XG+_?JCZsdmWfJbUbE;k4YC9x~im!6Wiu zp1~PwEuC;nD!c}^T2kvZu+^UW@xS);9slb>KjL5ZE=qOYLtHhm>Is)>4|>mV4+U#j zWma%VE2rhYRBoUn$U)Hl!XL?d zyF7#B`JFbwoRYvRxjB8Q&pLgv8J*49tu=~RuSb~t(qJ`S>6C*1ct*O_dR$oNrvB@3 zVV#?{t;ZZZH{D#X=d4&@0eo51<5rE{C~I5~k{Z^Do>f#Nq~$eBRZH)CVr1nRX}&l1=dxBc3Dim5$RRnKdsuTz7qdiIT zY{ka92arv~|LIDGKVpUae4Y@g&4M=5iLH9^NOr|tz{SN4aR}5G2=c=OirJ=@(-61W zhK(nPCvC%I(U&%ELm7SP7$VhnprW9C=?MgxxG@L+b_lZtr!;)Kp38L4CZ^#dLVErv ze;a0Y2PdLHO>gc;c?;WaEJx31(-~=h`gXfsA?mpwDEAa)#C*H(Ep5|VW3b!7l;`P> zx9jcgX*(9;T;9`p400Ya4xeBZi8YdNfmhHrIYJlQubR3jIne7QcT$lUdl}bw9c(gL z7oUCaCkDAFJl&CM&XZW-3x836zOC&9O>jFda8d4ZA7crf+@oiWw|v8~!U@NXLjEE& z3T5HKW*+1wO0Drnl|+lOsUulH01UyaEfbPOE;>%cU{lDF5ZTxT-Pb zYv{&Zn9;@CY{hfqc6zvp4tOqLwXvmnn1%U3r09qY@8q`L{FWx1ar)Qs>Ph^j(PSx;Xqtc2S&~s|9m@X>N!R z*zN72@E=(@ogIIHXJ@KLp_n_dF_|{)#Z=}3o!+Z&D#nhD>+}Ctmz2IwkC$EP;y&DU zVfUO~Raag;Yp8Q^ZqC8W)G=uM1LMl8FLZRn`}R$P@;e4#Bk1ArbRqtq5jt}tG{7>EYVG~x}N7M43 z^-XDf;ZwG+vuylF-aG@dpZr{Cr@jc$~go7X#E^}^SHZ{U! zhNo6i&94$K^wXGvx5$Y;=kbmV7i9qcNc^OsapPN}{X5vMN87{)h!49sz8ApZACdSL z3l^x%1MTc$FTB3*qJ%uh>3`ZqrmT(#U`i>xf$$NoI0L_Q`o!MKwwJl8rccyV9bYU3 z(G|4Um%h~afF9=WU8&UnfF7+jU^s4lh9@)YVNR(Aq@lF(fL;qzmgfib!c_)FaxLw~ zXCf;cvn_q-Cvx}mswL0y;Xb6KI`$Gz2C542d8mos>9b#OV846rCwf9z>F_0wb={M= zsk@yWiXQ1N2tH4DQ4ZonE2q9-pR4bNv0Ao*Bc%8Tl&vnx{VcF@L{TKp)TrDa@buM= zfBeLG7eyTv{6l!*LX7;H@*LEo?P^oS`{7jYAbR$C>T^(^n6v0dKXJXkvwVey!ZQDe z#C_pv2wX7$CkTo?q{kO6?Qa(e_^Uiw0Nav(MCkV)vD>SxwC{R?n{N$L^aiz{>g##Lq2m z)Y**OVN1cq=j8iM2oOWrM3GTgI6%-wQJ1rN{pe}zO_lyXI7F2kKK6I`BNqW)&6H_v z=*cTRhF+Y-13|OM{yV&%#eBE->(=5a2{s!$+E*kXXw#_i@9>_@T08FC-aGzvayx<7 z&En1lS5BiHzr*`kbPZ9EGIs^=9g7lj4jyr?avKC5?~7LTx3W$g<130FAnR7(!p?9N zr7u6HH`Qc$`fvdaS)Qj@Ln!7CG-MU3izu!NL>^a?Vx_3Xq|W2p62}lSCnSP zhOE)c$z229CX0I=Tv>kBMUVA9BG*ieC>J)j@1!xg2O(Uq^BJGqC!J7IC(gNw|f{zTrdsS=_f zWiDm9uc(axbNwJp;9O-k2t2M_o`SUdsZnHKk_|8QNcRSR$Oe8$|f;9X?yYcg)2 zwT@DY8)&Vg)c*!r>lCfJ0T)l9T|F+gpJo&1xTSyo##bChz`IIb-GGZnS(wqqn-`p1 z`?tO#00G?On{e?cwYmuxPtkBhLCRbj;0YFGD})K0t85B^$Hh+z1z1@hf%vS&{b1S2 zaf{8R*SLk&iudJ7t9$I|#~<&FA?yW4&=`{@HUAq;n2E+Bip#`w_t3F;gH2>%(qhn; zD;4_vZ}_J)Gx~R?uW4~_gLmKJhTnmIzEtK83Y3Z3A_`LGTF>?spCM?z^bLdwoU1Gj zfycimjRGulDh&yqJ+D8{iw^_I&NnRufdeF%^d7BN6;?Q zw|CKwH|XG9J%8sL%yj$dJ5pdMgTZTH-d1c6Uctxy{Rr$UhFE^Yk2#mEF*{=g9J}N+ zk`siyibT!tp#m<`zLE7pKcle^_1sL@^iXdRY2wr?K56q5Yib>Xw`CXN^#b^uiBHIxDDe@NYvSqnBfclh zqTKWV=}=Bv7nMQ02|T$%cmc}(SdWe^#-zYS@F|Fw+LJ4WmtjfJmg2fdP61{j%!4P(d!8M26#&T4vsZ#&Aiz`DBd zjMao|i|2ZDS{_!M2a3Boim}918)f*9RhjMVuU=|mC8+WQe*R#yN}E&e+Ni1&oV8K; z2wuj=3Lo(kwA58jPRZ;(*i#)uZ~cwT)bs^9O#pR%f!fGJQ(x#s9LgcplzZv;3%p*` z63{;{^b&ZEI_V#D?gp6OV|!p7q#^3^50>+>E$tt@9HMjhXIF$9%dDQ6_a!oEK&4+I zlTYc>m#Ff->H@)e7&XI7%~mf*$@sDXD|>&u)CUGkL^=~U^tg(}r&HTkdf%wiJPmLU zT^CAXroUqa_J<*8r|I!43|$u}{xyc^3(Ry6UA=x5;wqoa%i`vBMFg;Wzs9I@nx?(R zIH|BI{;kR znQuk=-slx%3zBb9jV-VUFWXTZ(xIHr*iSlBy|)-6`Y@^TYOj96>-+A0@-h&;_u z?z$!_F)8Od4E_jOA!_~}XG*1+@kF6xeOYlo2d|gKT?j5R+w&gPnM^kk1u4p(fFD?t zEFaJ;oU8m10#CDaZf{!V@~y{Z83M9y2W}xRu4}SWG8LDNY@#1{gPE(`P)k6aY3m0p zTz*YgKfv+z^zR2azMgl)Zl%bNaC`^VLKL?HB9G$>O8SevOzN-!Ct3t;J?NsHvV@ERNHXO*if2>q0$nTw2^g}kV)O4)MAA-1xGt)T62*|XNgzMlEq zC|<8pDqMD*Ny??;*bLg_E5Z>phGY$eJBP@(<8f=XAh0qnJY(0dNByM{oz|QcyMf{! zBHOaWHAHseKdvEC+h7-8fhrf`XBC@O+MIF^k-e3IbBO${vR!2_Pl9rd6;wGnm0^fX z)Qmt`iArcjZrPmLYDUY*A+X~9YLYs7T-_%^no zCR%Wht+UlvG(^y9&~RTPM%JM3e2pwY3Y!i&S=d1f`^(qJ34;!sk<+3W+psGH0qW%; zOyFGPpV09fNDqH;SXq4nUK@)$4%|XsTvwl|8)6sr*u(UVT4|Q^yzCaXrn(6L3dDvfy3*2ER zf<9fT&|W{($w9jAhdNQ%Dag-Rn9Z)RTz1sSX{v?DqSQ$D6`vqz2kC1F6F3(c3xTIj z)&&_>R^LFpz~UYPw~!atRVR_19pX5fxD4J6=Bi?=I>ARjb)&f4OAT}*+;1<}+(GJt zbSS4Y9w5hQp>9OSo@UawKX@G=7g*vtK(69C)`$*Otlt#Nd2YBx0frHctdb0)FrqdF zI`?TBYoK#KfdzNxo;*|+Cx1lee#v%U(g(v>T2F5PhU-wz%FBi0cle4K2pU5&P~px) z{qikbVXOkS)rDvDBr`oR;Ym0v-Uh{esK>IzY)DR2x?)*ov#FhUzng>>> zVog&lXZ};@H~?gI-yivRrKkYpKZL3UpeEFM(4l^Rjgx*#0O0gYOA{n#m|+S7v(dwMwu(6H1UuzhpuQTGFFTsID%YgKH}C z*)}YD??ZLc-Q!qx=G^Aal>S($jY_zWT^i!{5XZam{t>Di%tsrO&$#)8O7W;5b zNK%2daN!widJfGB!D&b1h5m`4xE)b9u3RcOO+Z z4nmx#omyEiShK=o{Cs2uRZdQ2IPFvqMFl;jCZVVxjnYDm=or4G)PYyqzuu1<75vYs ztd`Mt&@PY~ve+`oQW1D21Q(psw5L#!d^_+tg1Y$N7~gobtxvyh{KX-#V{jR1yvHysqgDd7|K(B!RtB@ zv?*g?*nR5jdIbyL-5~Gp!sHxU7KUMd5uHI4w}|QPVSWjoxLFN}d;t10r9yF8FqBWB ziditsE3EKA+}lRbrch@K8|Sy3k=C?p%|WCYXQb@F1GLyY6h^Bu;ss0dnrYL^Xl(w~N9L!BtB zH{|^-Y?+1qk_~k-g6<)*D0cuqw>+zWxHPELGnv$8631Up6%kX09O3wd!} zby7NSfEdCihJZJMxvJQzPC{vCcAWas>1lQhhw1o^B;G|H9FF0T(-{xa{Zu|2!{G@g z6+P;8ke+3U>ma>IL%<4EtUik691gG3IsnM(csK^^bovmE1MCDPMqmVb01NIuzIU3B z=yeQz{2AMQMhhcw>htXhhU?Tf7mrKHJjZb>5Xy`D)WtSEMENdD;|4B&=`_=6z(i@GViLp2JD^-&sgSyln{*}vN$V7obW0$ ze^%XH`}{3&_Ym2)sxESaD(m5=IfACNIprQAt1AWP5IOF&rm~l5piE^2RZdQ27$VO{ zV~ET_e?`OZ;uI8v7E~W>ca2g@Q*EN@NhqnWwl}9SF~(Bajq=5!k9Fe=`%rD9Lphz% z%K`LNEL!GkCiOVw<>g40xcb<5+74EzVy#guXUj~bzX8})9)F&)PI!6ZP}pu%Dh`GH zn%c)1CDLm4_G*~9Q!oGw{SCJP5HyBls=}QOqkjR(LSU<0c*Y_(W)0WkTiHZ^#givN zzQ_tK8RnF`leO=_B9|}xC0}=oRmKeGZ*XP6X)N|3Sn8Z|w^$FQ;A}D9;tngn@}SgX z1?51!)0XeE;^BKuS{4uAThfVmG?e-dva6wLO_CzZ8RVxvhMY!KbD*K7)4d#MsOg*! zk(m<>#p#S*FQAe+jpznTn3QzZ%ez%9aXGhv|F|v`AID+GD5$b6e!3!PN}E$|=eE&u zn6<0C7oWA9xRVo3Os7{l;lvV(&4mW+)yJy=S9a!Y@kw44m_VKIO0I{6akK^aOTb)yG zANfO^(lskt`^;wL_a2mhb1nx0&MDu6c9i1lb%-k{h&m>q5{A>{1hl03NT#bL@6K?D z-@%dUOPR~aHxYwoI&yLknrpDDN=`kG4buo3Lvpvmoz*ldFC-g)?Qr24t7$*IOvC_m zgca|D;;xR9EOFJw@BGKr;)Rdu;x(u;`hu^>gPXX`0cb^TbcuA@o*T7sgs$aAmzase)a`4+M4TYrLCgLJY%nC}DctGn_750rBY`El z@Ql8y&!4%D=`10BiYM!W+>8}gut83_>tI~~i(Hkkg}%#UL>E!CS&HTypMGSPtLYQp zTlvdfpd4qrGwEp_oKa>{j=XSe1=Y!mW>%kEb2am^<(imr5w)SdyLOEB=QWn5U4d1% z>&X|8MZHTH@DVhI@yo}AH2$loUm#vYYa}t{U z3iV4u?L4N1Nw|9233a#c-8SLsXeZPTvMNJzpTeEK`~3p^60pA%PMPu>g<=meEi1+l zw@1G>fyCv|uhcF-&NYhFSh1XKiPu{I!2Rrv`O#)O=|+B(>JT{!pv}~`h+J(JS4oOb zuA&yy2Z^rHhys|iKSi#tIr}Tp3mUDH2Y>11N-4auMAo^6-Q@@xLvpynovwTs2v@oT z8=!Fdt{_|)%e0jcxLrBo?aE|&S`gh*vHnslrz`uJuqbZ}(|GKY;M9>CP#X@j# zF!e127st~4LU2)iE63&HE$n}}1*%jZ%vnUCh2i2Rl*Z*^I?X9;v`#CF=Th9Q^(uyY z#-HdJ2pU7OqQYGVX?gV2_rUZUPCR2zRUa8}9i&sXO2v}}KrYP+4cQ>4+?CO+1B+Y@ ztG+?t8mYqZqKInX%I^3X;8y39yQg+!ZC5Q7n2C3du)+fTtYZb`z`7gOxLq6@)Z|Hs zuPKOpi=yTlQvRZ-IrTjlSIyb6HKN~5*ij#a=}$|GqUOdSCs)l)p}fV6>e1}1*Hz2S z`?!*8aSP9ZAZQzDYB3|iZzE6gx6{UAxIo!OR}sbSg2;1$(qoXH_?bzsp!MF;Oe$`~ zBq+^{>){=aI=RWWv1c0rx%2^7ZlvkOalx{Swj&Bs=C%U<$)en~u)q?y-ci^G$c?|0 zdeIWNK;aU}Ne~Jj*9FS$-~GgP7S{l;9&=T()dfm*8e76BQ*V5KuZ|O31FMxQ!P~-I zhU8R*J3EfXtGI`OopIqAJ5Dytg(_Ah#d01k18FD# zIi41j#8EMxPL?!sJD6tO-ulPPOyBX2Z6DdpAJ17k6P$$QsV6hhDvsBLL9b^`AMN}^$<(bz?3J)*cG8TKRn z5nvOgm~;qQzgn8_N~5urX2!vAqdE&Vi`1c0<|xL#x6o*5Cti7qX18} zC_h@*)iP*og`I%>4-4}ti^k>>$yN|}8ar;epGabHw)+_35j0h7)!5ysX<1y2rqblH zn1H4Z0IM;rLpqex85^-BT`Y@6Y|o^VFylVT`N;!!Ble(d$!J8y3V6UQXCwBdngHx7 zkIE0M)62wUoL*9CZZeM5_Ow6QXo=?=V#*m|exupuXev_<(_^A*>?#8H$PP4>SlnZnotWd=|u2{~Z zTqQjPMNxTZPpqQUN>?#868?mc`L!8)l7WvU5 zXhLOpa2*_%2Y*qfD)68d6{%trjCwy553h*i8beJ{t&Baz0oQB3z(cMG+6x+5#mJ7& z*UYYB#3R~S#fU2ZkvH?i^NZH1)vzBA#$Af67Nec>J3rC6o}XC!5B5qSXr>3PV;^A;5MKk` z1LOdsN>?pHrqcVWMl5VbS2H3a!g+*=RL+&NkNVVC#Jt2EWdtpp8dXEy;WVI{5mhdh zc`m08RR|FL9^#?kjZ$0>TF1VrfuDL0@q8fPGa5_3Rl|I~K9gJvKI?N~A?^{-H_Tv2 zwp6%t#BVwqc;G9%yAMI(8M_QW5aOQHuBjmuPgVfA7Av%8gPd{?BFP=1y!uiX#$8i| z9(#1r6kPc=e#W`gIprQ*dME|wr1o7ae=EQBpzL7<<-nd-R^RihfxcIt!fL2dr+f_~ z+In_Kk@`{>2*TI{|dHPAfoX>Sc9LcXQTHP8><(#slXi?@`$CfY*q zV{fjuc;};u?>E?Pi=e&bYP8Tg_G!g^#Z{o?fmC5sP~VzHUYU~?)oq zwUA?L8d3{6_VCWJ*;7C9H8|s#*Mm0KGU8h*Li{1}71gTP7wtd?z#f}DARJ&)Ur$yw z>{ajSq99h0E(5v2sHLlpygK$zCmMKa#ZSBiBK~DvDp*?;q(yBMWV&}jih$A*oX*Uf zPSa|mAd28B$h!sTVJOIa5WZ&;c^72NT}|+!(GDPcl?e}8#~z4x2=SWG1t3?IE(O#v z@|J83l4oG)G8$8Yn0I)W1%kHCyL7b8Pn3qVibAMo9W=}~nqCJDv(uAN4SNzs6JGk5 z4cPEE2eKHZ*`CEsm*1`UL zKV7^7X#W60YkZ5si0`BbR(o`}H#>@l|Ii-gK&Z^5&sg2c;|u$t1p$JOsFpz5D-#~H zzrD~BQ}FRW5J;L^SB;J9>4$noQrbYKyGE)N3oti52HrX5G9*VS+&NN(@C#w@1AFPh zGmcdJ1eSZGYS7SM@nqyjEEOPVGa2TTd!$+%z#`XKZ#nf&#aU0$Iw_j-thbiF1AskV zds8uK9Z1hoG2G0gi2CSS8P8cyFT-AbVG~6Wv}as+*D*h68JFGg?$1 zZTgydR*lxMZyu%#-gU7YytQsCt~TwQOB1~R-~f=LjJ~Ef^^I9A=Oo|}u_kz-a@Gi3 z+txabV(^c+Ec4>am42;!CSfumziNV^Ud>*|Ym3X;gZ{_!y60F`pL<_oL{BMpoG`y+lLf5MEJ1A4VAo(RU~NiT8LjqFx+D z^!XJ$0f|`Y6LiZIM3qJx30Q>qe6*3z?=b*uu$w#DNc0=lR;3S(M%_H7dloBrj3SpB zW0Z|54}!QLFHP0O@-hKU2k4?n3FJ_P^=jd*Rz`u^Jvr^ixizO0AA9D`?IOzf{&CPN;REdnSMq+M%w$)pf#fF(2iG?os3zdVGNp^vf%u&)N z@*v&Z>*8KbSkC@qafC+ir})K@qhVjFD(5e`_;0E@<#*CU<)X}^a7Og zr9t5|dc?W0Mzm7D^k4N2Uh01Y3@T&)zv>$(|2U_5ky8K3y}OtCoq)}s;ECe@=H8t~ zjWc?eJHt(Kl&h-w=Mnfu0R}~R1?FxdXbg(YvI78`gruA;xo*tKGWT|@yPTrJM1q;U;jgyrjOJ&l4U8aZ%%QgotG zH&bH9Ql-+giAMPUmF}2`68wkz8T~U6CCDiCD#4wr!d(LH2APv>A{+rv8P}YI67-}V zlZ>|2H*jq%#EvW~~I?Nfm*%7A0B z;>2Xkk6O{=$wm#o`fN9W%1yyFhDtY~)<`E=X$CiPj~OK!bFS9{raG{Ya2gh6&+;}g z5J9U?OQyh56($#_r)){3Yfdoh@_ z1=cGA4!aAd!EO@$1iOB*Z1+0 z-|4WFnaO=B_foP^Dked!&=BG=mwdYVj;|)(b&JXC zX!;CTQt5lN32BFwR+i}847hZQUV&fx0*iKeyYxj8%;u|V6D1Hdgvbaa# zTi@eTTh(o%AAF?xFr(CK4Aii4bjliqeO{s%Z(#W&TVF~AW@8Lo zN)2ZlmC79FuKO8xp&2rJHeF1-DKDQS)o5zicJ#wcv7Ax|uu8E4|B#;ZJ7WWc$wMNOI< zVTMPklXZ10tct|H%K0#(Koz{X28?MnZS*vkBU?7>gg#esCI%_a7E{ODZBETGVk`p> z6?iMjWCNf7Db?xr9So#YU<2xOZ)FnF#9&VC83HfEN}g-PL@Lm-UI(|d0p=(WpbUIg zixx+k;eLwokZ3NJPj=9cbB$ELt9;t-pB^~RsHBA~9)_7k74d6xxZeSfzGCy@yK&{uL%^VS(TVTZG+{fp1_3DU#%30guJ-UY=xKig2OFEoxy`D^;E zMaB?6ye+x?a`eugG-A0?5s$hZ;D4v+HX^-tOXS^1)TV$HMs~df7G%}G0{k!8^)Gb= z=F;q>tl*-`D|@tbqih(Xe-0t zv36wQXnb6|h;1XZ4?}v!r6^Z0teo3cG;=(@AiNHO`+#4%D4JYBxmFsza94EZO1QC@ zwj;9Xq*KJvdFu79zsjA98#L-DA*>@2ny$n>gL06w{aZiOJ(S+PO( z>?O7*Wj;WIRvD3=%2~L|*nkh;)LU(Yr`_hOy1)~C9HLS~+c!rsAf&dii53VNL-L8j ze`UOh?eAF_P>cIdC&>t(L+^k-Fe{) zO9&AG!L61y@fbm~C=|Wc2+ya|Tn-t>I)T3|w~4wdY`G?*EO}blL@@+QVKH@Bi@s^n z*tMAXo3wr{`mIS95hbw|u}M1s<)V=|7Ysl)@-bB3y40<@(CdrERCt|HqytaRGDR9| z3{kh1?awNjsM*>k8X;&!fXH%e&~l)5_UCtWQ5k~nfCprxG*cED1XgQ>6W=6YKmdH1c%$8 z=OSnxiYwzC?R6pV0DJDnYf}6MWZa0VZ9vA2sK*9m+=%8NieUq&C>?$~hMIcpx~R#IIiad0C;R8P$QhzxQ0n4c)p4&+8E zDfz!hTv!=jEKkh-u%;&baa?_35jZLRhtkN6Mh?GoJo+cn+KomYD_xT=Z8QpJF53Vv z1YD?f&L%}bbig^@K30}uHyK&XlXgE`l>QK3bU&qRGQ!d}=*TMg$87QkB!YKD%l#^j zktaFcnN6}n@UAF%iU02ok;5H+qIT0ih1i|hF~7YHvalqU1@F$4G)cupl4h&8Lef$d z*Gbx_;^s-aRNOh~Fk&dg%SpMFq@c7klBK0lQ(78Lq@~dTi{0-w8F`X|gRx?VOnpB^ zO=ra)5zpT)NpF&M`ASW_Eg=#}yh5qLW+Npq3Z$<1-!)7mavaEMg|b>oU|o>HJK97ng7yieZiU59EQ`apBFE;y#{iqecw5@Zcv}m9 zxYg*56HA+ISXA9fgSKHn#Vwg_xEkC^d$$<{fIVhx8#%TE+eS&-fo-D(+l@3VC;YY@ zw+*IJj&!WeucFV>jXc3~ky&uo&oldXK}%-snt5ybl5{>7B~#BIjqI7ZvkAwTLJrjf z9n+KjMKaC%(TLE{1Aq7tD>rrN{EtTd4t1HRcATD^t%bbCox$qdPoI2_a{+?(iNYrp z_7f++*FsVU+ZC>5>WYV@5xnsgS~lN>QZ$E#RtQ)L#$liIokl$8J8_3mJxG~f3urUL zZRyV)xGjik+G*rrPSQ@JWSlxw)N2k;PSHZo=F~)DHyo;|_-Txw^`TKajr`sFWGH*% zmAV+fWnTcw5~h8fq3nyI9SYZW1Ka-}9A#gbYKoCu_A9_{GOp}9f}05uyMcmt8rhvr z#8LBIMvfqrS(ENI(F#EuPZM{+lkv1>m)nzAdbtbBHg_odZlew>ciC+e=Xl|6^oQpZ zv)jhyzm7g=7X)oBrR+0e9ZZo+8=&$wQ@4Faz6^rzz{sZdW1QeV@3rWI0 z&poWT8J2b{Yy9sAda%!kNK*<2JPO}vA(e7ymcnb0eZJuAS;336Mhhv2k1i^!Q6S`Y zlQy7m!r*Tr1#i*JDqW#h9$*z0K^Xj1so-;3$<}!=2WVjcXvg4Dn))*;{3vbs*@#Fu z${CL2Z|kV9CI#QqGLLVJkKwR*C+Pbul_!=;ru{eqj#9z>%0Q|W_1cfy;HuzzXqqM3 zxF3h%QTpAA-a_c7GWvmH4j3^(oEA%D@2^B~5uePP)9W5Erbzi$`sH7YZW@m18i$R@ zd`ox=S`4?@#6!u8Y}vPkEf|B{pDb?t6`VoPED}vUj8)Vn^uuAycUdHwMxM~#w* zQjX#zqzJ|6^P@(zD?QmOz3C{{?(Wlxqej2v&$+a{xI{-}*HPGFI1ksd`3GZ10D`8_ zevCH%9AKTBczUB2fW``>v|||4KBvXUP}sqA#EPCBLwN>M>~SLxqFTp|>d9j`lSx)4 zU*45s99{w=2M@7{F$kJMzfqa=1^8eoJe>_-i2~`@eN*Rh058tk0&d zzZ%JoHE05Fg~OugABlYB)~d|>Nj zl;p$LHW4@!B~j%2RO$pOwheVWfr&;NnrQt?x1yUTj6x7*K8d-=QYv*4-KZF~K548& zteZEi5L^UtCGUD7at*u5p)m2>)R1 zI{OeU_;qP1mOMg_+6`>~fAHa2$nu4{DDMLUSAacKIE9=+=c-T1XVCHLQ|mK0TI$oF zGe+^aWbVjnak5$FaJz_&$TaIXY|k5M6Uz~_WIA;Qb)QU6&Y)u?Q`lMTZBa^|<_=Vv ziS{MU8BS`ek+U{oN>BgqvQypDKH} zR`9c$_%;h_H(@mV*}z5RACWs7_mx&Me$HASQ7pa7@5W=TY)*#rGTgjpWkX~R)v*{j z4vT>ZngR>C!GE`)q^$sasz924!AOWG!SHph2b2%$xJ-CGmRrFhoW5X8M0wl%f!%HrX;XC-^&YqG;f zw8ty2enJ56)@4+|Ju?am#C2!!a!R8)*bNcXvJJoOD< zBHK$a5Pd@p zt!My*ek!A3G#}|8PJ2$$gXriTqjIoX7gDQ(o8^~y7e7(-T~zy3DsvZ$M^~xUU8B1^ zM@LwAj&9#YTc}Gm)fRtJrh8}$Z$Zs_XbUCyo3nFIrDjloc*yRxm}?WA5Ht_T-4=eg z(3J-R9OEWD_gFz&l$wK2`LLD6AguXcB(z24kb{_FFzXjEPAL|>MY-TW#C_D%8!Br> zE$^c(-Y_#`TeMy##GfqgGS4P@AZTxBzNND3KHB09U9$fDYef+c&=$&{hm`z4<Q+da5iCPl7#yoTD}tRD5+}K)7DAIB87XlGd2zKS zGXf=M;5io?1twsU@FO@sG4CKfdW3apMJq*tk6r1FRNyg2n1fXNv5|~}f81kZ0;13- zM#U(#Dc3!r-#i9~X!2s4sE(jjr#?^63)LoN)e9@p{3qyz-h$u3$fpFnx7gDQSK=v8 zeucmM3znWLYy1zNyLf6u)K&^Lcv;Tsw&-xftDBZW(swpd5<&Yf2_5b)TyQC?4M1q6 zNHpdt`df8c@f5wG4IM&MiT6bd<9R1srQFa;HEoNN#0il9UHJ+gpwxKT8zp;qoE#sYk!4<+g&Fr5SZ8+t7tb!w0MQ%oiE&82j=$UOO z;5ij%evq-b93`D9>SL( ziCY}{1RtT^a@hy?kpIOw@0cIxXK`i%U+m_n@>_Q9I@(<_M4>cTmOp}Uz)cGAWOm5pJlR ztQ_g|tR@J}-6Sp$-fA=MCDzteKBECmbHmChpPmP>)DSBj$LGT~_Abd!`<7AamjE@XF-UV!k?BBjBw^2=i7kd8L{osMN+VG}tKEaz2=TBMxP z(e62%=0cSRp{AR}9Y^>K{0${>2CVd6nPMOp{K4{nm>pCWxG9r3lCHFX+-&DF~k?=cP!TDC4r}PA^vgTj#;&hMOXBl8mc}?Z+y^L%@FZ;L^ZxG+D;w z!?&3g{x`5^2x(qNx%z%`;uL8vjm5~Mud<0y1dG5*!e{Ii__|DHkKS$yt~8k+grZDJ zR=D3`6l1x}o{E!;>cVw_ed59SYfFhMWMm^$UIDBf%O3Rr_Vp0_hvBF=h!>lk)3G*! zN%CZ1-~I^GYDi^Of3IqnF)uL(gfK!aSc{0YH~LVmMSW2MGdT|j}=XqW)d=@pQM?c;qiNhaXJ) zUhl&93yNY&S9-H@CcT$tHj`0X*h-Zh4m=9)FQd<;;`F{@i%sl6(6-PmA2U{N!7HB3 zTxradKQdj-t8z!l+>v;B`A;m4*ot>6|usm;Y7$*a)?k4==v65HjzKrRd zveF)e?*Ae2SBG*Jm9g_^m9H5rkI_zFRNpbWH&*HFKlLEf1Zw5b0J&_7xpuY6fT54^5VGU10+c%5@M&G0i53#*&iF17l>Nzd(K8LRODsR9El(2!fjG6TjjA1F`mU=gEtOA^N<32 z`Qhsud2R87kjDaGOI)}J?8#68Tjj|*meC>JuOND;n=xt1!c@*iO@)$5Mf|qK&&uT; zX!ajnxhT#tIkPUlI$J)j;2yhmyyO7EIj7wIizbq4m|dHo1f?LZ>(*6AR&jP#wM@vz zI6O7A%se&KP7@6?2s?M@8D@AKmqi5fbUJCX`4?XNDd)q)3b&c@bj~m_mT(m$(_6zV z`K2ghQb*x+n8@cojV(A-Ny9A*mcyzh2k?}xgJ zzJ{(Koo1y~8M&_pK9x3+zpL$jQPln&s6I!~6loLt+f3p81N(PFwdv^3*$^yTb$G5e zr;(Ai1FLZ%m>+~n8A)75X)&q4zZqr~!maPDcAk9a|2FKvMpLA7`9{OYG`FEOTpHC0 z@-GcboG&fTD&Sk)9981LC+yJ{+rn44<#PnsSr=~AU`XR-)qF($-C?E9Vttk~dI-XM z7fEtP&JyvYIser#TXoGMX4!2MaR`?GYp8yJ8E#i~g|l~`05itn{KFP#UVs^!$s@2j z7#$11P_vl+1{=qyJy1o7ff#spQw{6iXMtu;{F@wT=0LP5&@5bSH+%1M^gL?lfDGUF znV;3YPwatv2$~muM}~j551-=T)5RlTZ(KNvlsm{Q5YP24)Z{CFq-I`Pg;j*|KVj00 zU^$jfUj?Bf^OhBDH_Z<+bJ%%n3yvc?7=+$?nBE4#iNlm7lNsw!H~-Z|_Zg~~$t;jT zFbIq^#o%u4x#&K(z+YVBik`R^n=%nJ56QjsV|+jht_7IxCfxQ|!IgL)O|z{02Eyh4 zMZ%SMSV%9s#d-;b+{bxQzF<`NVX701>c3Cjt!PrP8If?GOO^4eyWL=aafZdSp}dd{ z+^1hHm50G*Gz|EMC_713R42rY@KgR=qaK!MatNCAK5e$5^AP%}jQ*f^NN3`-XX)q6 zFpADceYpiyGYzF;nbAz%f*xR`DZwbvJk1mug%8)T;?M&&F&;tlklf8QZ6{9i zivX^66Q+5rpqW+(yJh772q*s+3C*-R~ykJi7KEXrJkENCX>&je~`iH2oCGtHu9 zR&*3XKb6radW>`sr#;Oyl%lelg$gMPs)0Cjt39-~I6IU*WE0g8RGoQ^-d|@mqcib# zykeEC=>!%@O46FFW_GoW-%H9n2u1d(C(vzwFJ+#9txPNk7q`3v%OU|Gs#LnqA6~9Zd&h7zn~M@Q0wvZI2%Ul zJG_#26?SeZTlgnJ_{P(U#zyW}4)K=Z_ketkAS=$p+8ec^MHUlZuaATv0!V@jm5(4y>S*-S6TWpMf>-OFwk%G4hV zqN;YShXjUG-f%PgztXYPC>#fY7njn)%_y~@Y3Nb4M~Qbn$~e3?%Z$Y4qoW+vq`$+> zs@N`>Kf){(%;RQtwTa1^#$BfV5oTdOYx5_qbEoIhEqD4MMMQ#Q?cJn??(|$5?@m9Y zy^&^AR&`74lQPY)|EgTTW4wg?m*Xf7K!eA^_rFnH`#oe@tBm}Lv(!q~N z;8*5G$a;P`@V*R1ss=)X|BwdbIE|30e!I5n7O5Ku{S}E87xfh4C~|Za;xW?stOBWw zCgW5eAwSXo!bTl6qy7ke^A<|uEOqH(9_2Pjr+FzKn`eV^6Z7g~AxiU&uAWf*(xogC z)?Smqn>wx>m*Q^;dpid87gbuUS*@DSP zvj^DSfuN0~$;rrTByCPMbNEeR>oe$5GGn zsWgJdnaGNY!-rq!c>T$BC#Nv*WDkeBm2=sjK~s^=YvrqS@kGA}on)TuZ*3Tq3!t}> zb)989@1^^%S30J=8C}K84j){h)BQ)|SwMAc<$r`_4FqLJgm9CDexqk=CoMPX0BXwc zNE%+=%n{3$LV zaD;kg6s)I(83noM*NlRE^e&^IFy*V9!DvZpkx@{N#%C0)q#rU0j?&*51(hjF6*IxB zq&2BJ1pXdh-nXNHRm@yolx(yLluRB0i4mHm>i2 ziQ~$QyAfK_zZn(Vdn+!M{u49f(Dr|66Ojm-Cxb3jyP6q=l6+n*LrM0~JjlID(!<-} zUg=+~ssooIFt#hB!M=1qqvF$cUM`%H{%xOPCio6Y{;x8W#GlGmM-_UC#vkc+`+igU zFD#8JtOKQ1N|A8ak*jbOv`VzBf>v1!`I-zy#cpZ#b)W^Xi+E-cA-GlKAy9s`OuU1x zbqpz_GUcp+bp$(AtAVpg4E3mCM#Xc1#2w9OW5P~JEz`t4cvc(P4S0=(O9V9L+8SoI z3M^ZI|0|UYO6s^2+qKmgE~8{!%{(1xil2ac$^5;21kaso&7@`NYaX?kVpSn&#WF50i%t-!YA{*;6 zK-gNq?g5{`IsPJAh6be1t7*=X)UA%$B%03$etOhnYzNo7Ax~dD9%(=IYg?Rtt&Uki z2JXksl3c&k!X~`1Ap1H>s%I9+mG1*~$RTLMu(utLO8^ZE^Ldqm0#<{#iGnDto*9vL z|2=#;CV4Oqiw~+a-4IGL3KZ)k8N#Q5u)Jn!3DY_aEC95GElgzNA&*bt!@>FV7`)<2 zP2Y9_`q=~X$Ns|d>nFFN4}vZ)0s6}Y%jq?g4PI3ZE1;+Q_&BG4AebMWS;*;%!}G+j zf_f*r^Q@KwcmWTG+Na_Yr8)!+Jwl~8@c$9^9`I2W-}~^)-IBX^Q#K@bXf`TAY6&OmSC<-DfiUNY52q+*`R8&9#5h;QcDJshQoVoYz2K@cM z?|wczcg{J_oGEvDyAPqfnz|Tggk=bxhJ5T3m`(86ouz(__bxFDAYbt~<~iIk7r@-P z5d}B!^+jmr%tlF7p89*LyD*@tVi$K?XjQzo;qU=D7UX|0$=wYt;viB#h}l_L{H2JW zrXDF7tfK@q3LLWp~~2d!(E2Htl{n-D24{; zJ|2MRr0J4xAm?RXB+P)o!?;C9hUz!Sz4xC0QGdrhFlfOajJ*R_+{IC}@z)bUS490C z_n@EwxF1qtav(2!0wc51)9P?sy((W)N67mShN5Bw2sz2i+(Xp5%ZweFlL46Z1W0D3 zq3Q$_IjLw3^scr+&a#X(&EHx-3(5c|f#};D(IW<_lCf;hT#byZrUd3Nok{MuBJzsHh-DrT7 zZ8im%Vi-Azv8dEC>Lu}@wU&X~rYf}2^1Mw@%fx;*8JE|DCzD?+HU%>|so}LRfrw(! z30V7?of@Iig*mZPKZMUwL9HY%sG7!7qeG~k&WxQI<7BBZu0)_(F6QxY^mfYtHXr12 z{FOUZ{b3`Gju{GDPl6zlFjnd2EQQ(L5x=$3D%8FP0Y4XvvOosw+%zbNEo~hlIaY`` z3{;k_H5`Vkw?$z~n@U+(l9d%L+iDU0^2lBc0PFlZHhV6eAG`^LrUh}yfa~9&y7Tfi zoGl#}Mhc(y$vU_AEPySYB)QXl+(yTCsB9_cfwV#O6=J_4zHF;ah_c)4sK2#69OkIq zxC2AlZDmE*cG?6wOW98Q6PN8CZ?82D6IhY6s$YN2S&aJ4Npi7BRO+BD=s@+2jp}r} zO8LMlO}k3j#72eIuA&kGTQ`ZFmk)-+vakk?WEpEZ?aKhREx}30jG{Tmbnngx^sC>P2x7@XwH&O{LtR ze#`-{`r6hA-4wEgUvn_qEV8-I!nTNPzhNHRwvueo-@x`dY(Mc{W5%=XNj0x4(RENm zrtq?=>$9u4xF^a@8eJ(lut!H+3y83@{gz?9&@qfqi;pA%TaH&&(?n_~L?jxU)o8<- z^1cjIb0+r;GuuU|D7K74ZA{=1;u!+>25=yOzbyquUP}kB_(-gwd573e;J3hhkHCZJ zTtkko8O3!hfs3#~L29-M-dRgYy9?&u1l~@Xe^+$0m)Slc^rsaJ)y+k5XQ(dJFrAOT zvb$6`EX<~XS1c+UU?G+ecs7{x34Ep$7+-{ML*UQi5svaaIBc)@u`@b#mxZkh1~WmT z5c2#m+*6rDBm&X<4l$ad0tAQ&^ zw^wJoTDdyt_8M$gch_Xti#t^{0vjbFx+1WSKzwB!f8}_oz#?aSP2lS2qRK?;C3+CJ zHGmxne4!NB&TM7DD}F7<0B;l<2)q)^wFDks>U9J#TYm!YzlRPWz34mQ7J)B?|99Wo#+UDziNxaQRvWc&2!cz+(ZNOyJ3-z{t{d z!7EOQM^!+eDV zFzSyw;1#D{H44-b@g;$GgSn5u#|?0E1OqSS1p>G2V`z>L;XMHkaM@W9{>rzdz%FL{ ziopN8j4>sJxrgXR;FbWkC-9k4U<4x;yy6Myqe}35;thavmV>#Pz;0SQRiBav%X7x| z8ls;tXSTlNYF-Z`JWkZOpNofZ>HQsoyW}#ql*<{4>69H>QIpxW0zfr6Dl5C1)0-;$ z@zTCV+Mkv7z&^yEEA8W@eW|oxl=d~!-m))YHcI=)u=lUF4Q<>Q1ZNy29JNHF`=cBZ zC+}_89F}E9YhhPEC&>bFw3il*1C^J1p{}?hf_iJ^JB5@%PFe;{`pKIp3v_i~h}(Bl z`9j(FRVIL3?kjP^-3%u(6;L7EX_1j-gec7iqWn%hiO&&A^oiC z{)#j}i$eWiS4T*UkQgk~_tj?A-XU2VrMMPKuU(xf&7;zcMA@*bJ*D}kG;d4uj>OLp z=lW_D!;T>5+SLeT54+k!nl(jSKP|Zoa}%o`4jtLm#xQN6qGdlVhd0_bv!AwzCtN~n z`8(J@;AvOaOvIa|!&L|ZzQb<2C#nz7veM`*l~oGu>a)`Up@U3zbrxCasF7VQeh$`_ zV!;4(8HS2Y1GL&UIx%)o+#t?j;T)*dX-{9!w5rF~S>a&EJ*bZd!!8*%`jDqpa_wr$ zeaPs;pH^wLtB>x2(Nr=%ggdKb*wr+`^%iRf!V9n1Jy1*LuZr^nF@JMQJQ}E_l(~hN z#Hi)%3Vhj!{;%z>$Qh)yuGj=;*R1M`(F)A`7&5!VZdXUD!1ROAuAX(kI$XRvNK1=c zE;+NOAc}N&&8{AegYaE(W000p=^{8W>K&|u+SLXL}MS=aAM1LPa>`T%VcLr-!gDy(G2ap(a^r}9s{f)Kf%0sl2fcIqPaf)_B zw0wN5bm0&!0ylH4AEGtF!N?m!ki=h!(4lxBDTiux@jb?|L$&zuGf6a%IGl-ohLws} zQgqNkv0oDln&PkgHXUWT%sgm&pI?Jizc*|KpOyr#OPu5KP`{FM zJ`%oVN#-@zYv4Jo>&{mTRCfRns=zDu_QZp-Fkq= zOL1uuo(E{531_GI$JkVzc=mFgX#x~O_j}liQ(F6JexWD)%^j4Sgcg7*dl;^I84r8dTxI(0M6*(dde?3~+ zm@+fbRk*A2-}-(!gvBM%HGr(^L&uZu!ROB)W>tCON6o}@Bebv%10Wx2V%Q-|%h4lQ z(hA4KB=iH&xx{;|usG4ll4g}FC=OtAF2~`Uowtt<3VQ z>4P~zEI-h>6ON<5IqhUoo)FEOjGI<3;3_pwm~BUig*iZn;I9zMkVM)l;#^@0xEZDd zhhKV))FPsY!Cc?3hx^2Edb2GjFi%oYL$P3_7Uk^Oa!oVGFN=k(%&kRo-%Zm>pgq}=! zzGTWv3YsNOj6x!=g4E?&iLpaosvg2|EU!Y)hvLyFE%ND(|$*n2C>>n;RIo>3z)8}ol;Nw6PzowX>9Ru5A!xF6LR#*x;~*T>yE#oRxeM?~T>M zM8+7+kwxBd+gPV}ff0+plpv_h$7)eA z#DE9b?3|nwP4nq;qAWQ%G)GK>Jh~a=uEo3?)YQqfv+*FGlR7B1BHB`t+sG%oO0U~S zWyh}43${_VwX2l$Hp(@2RYs8Br&XoPgY0VWhG?n3lro($ml$V6>^Lo1d6X&&$6;Y7 zO$@*TyF7kN4q%mdp!1}_r{3cR^{ZfKb9v0_09FU}U-+PkxP+6aD!h#4Q5n==>j8Kh zf2B_mqPSc_tMIVE)!2Q*_d#&X6!Mc#0pW?3uEQ*BFPWK$I#d({--bT{o+k{c5N~`eLkQu!L^aJ2SAsa>VK~g^QnQ@Sp3$azV zvFS6>cb^B@%YJ#EXNEvtJ|y{Lt1f>VvMql3@MlIro*HugAE%Ui`4I?D`T(gx*fdmy zS5W6Jb?6hV*CD&(lh5YytvLXd)ONQ67;Y0{;rPp>;xr&)1!wW8xhg!p?DP1zFe@l~ zil~gpF$jHB!SC37UxjCeP{5e~Dhfz#F8T_J!~<+$T<+tP{Jhl+Q#JVc$z zozA!h2Tv9a!Mv!6E+)=Bx=gd`mNUU43994AV|+8x+hLjsj-_{>oi)kXn6fAY|no#|H(mrvVGV*!SPwiI+$L4Yp(*Lx;uAf5Ss%n{2KsIo6byme)vB#f>=A! zaW_MS5(G(^Au_x;GeLG<5k^&FE~JnYKk^2$p4mJ>dkeguIg!~sF?cTS=x+l~cS4>f z-x8VwKHv_PT(WtR`ok|aHWln~kWVo&Y`~X8D8R|KdCxngcqv3Brr660#w1uEFBd@X z2$?|F*2WP!*D1rq_XGPS;bq_o%Gc+Bw-2Hu(O-Br?+`_4lc=_5Qi+YCI+wRyiGyPF z3L>lF73}c80(t}KuOj@3nO-DfCUh^Qi2GlG{VGNSwIOI`3OU*S*DDCkS6B%p%4h&5 zn$G;MV0~@uKt(h-tsky7<>L4>EjffpegMW%;=d~RbS=V5c77ek9m%8s`XWz(`ETSY z8!{VtGMDePSy-JM9u}|^DdQn3hr2BeUPm^pi{xmGztVzU-*!b8Mp#yFM5MbzFo=X+ zlJYw30QpFvZ7w-H(lP2?t6nl^0J6Z;p`#`Y8U;+WdKXn3+BWodA>TrnMo?m4M)vCu zP)yh;e4*skHeeqC;G_v+smn*>UJ)Lr=IubHlUlArc*hTzgc>i0mkn7z#lb3(f}kvP z?(vttuvFU1n#1G6&b+L$N~o)NI%L^?dChv{L1IMXMVM&9@;q+_SsR~x!suQDAWw?; z*SiWumHm%ig|`E_L4ALE%OL%?(Y!%WePb}jm)$9A^DT9KA4aB zQdc%QDERAs$d~3>qS8ArRIC02_0=G(^#tJ4S`?FpYQc6?#jPRi<^v#Qz3`)cMG8b? zHR3R~zKnu&svm*0WuA&FuzQvls};Y%g5zQcSC|0isWOZFZ>j#74gWWTztfcITOK^G ze;WuuTlIPd9G`&jOld#@)H_W2(3OtinJE35x+My{zyaoKdrcAyzy#n#B_G@x@Fwx2X6Gmwh%9EHD(@t{d_D01ZL3-X%=Ah2r3==m8NF>L7`l# zE`HW1WL<$8@_!%;uGXSA@M>7FczdQ6qfP_{liqRS7$|-kx8q}5-5a9p^B9QOYT)*N z{FO>Aku`qiEzz#l;PHV!XDTcS{3@nQ&%h=iAuw$af(c>k#{fEN0Nq7agD2T9)xmad zWc;TA8bQE0PH9$HyyMNj5&rjzXKoxd=ALQ$$+a{IN(@=H>vssxsnZg4L&L6 zq<4hE`om|w5U{1DOTAgC!RJJef&45v*$mlEQ?Ad5ui;VHbx?ypl}r)lsd`#23{LAC zB%%Bw@K?#r5QHbXzRH0^y zqb|ROdh=)SZi-#x= zPqbWhp{&=1-;MECqT0aqc10H^S+3I;ExSW7$Q1H;Lg;O(hbIU3niRy!fyHM4u^DH9Xbd9*mTJ=m!6LK{&(*m@HP$(ISeT2V*WVGbzBS)Vh0kddT6~@QBjn4ahe6 z<<;SjxpC=+iF2{+muGyr@M~vg2yeK>Q8;)OdS%cI1g4x!!oE zLRLk}MGxS;jbJbKy7w)fQNTi%kRS%Tmb3igUMLU<~0wI|2@>>m+(PV2%mi%P*C9@RRI04T7>$d;8mQ* z_wfEIji9ZvZu9T~VU$Z<1$*&*Lk}Mq@|w6lPYc2}iNEJ*X}Bh;+Sm)&w%;L=YnjUj8e_i19IkT zraqh&$SzWO{hOeLW;hJ_oajSnStu$z7P3@R{&*|peJc5sRBAR;&KqcsfaNV78+jQ(bdQpev)5k;*OjlGzSBHp!rGZ-Nf2}8^3Z_&h_Q#LT<#6Cyn{J) zUK8)QF8<0witTnqmxf#ReFI@f2>O^pzLXGpOOngoLD@L^Rzl&P3d9SKqhwrjd89fp z+vxMX2EdyHqH!3iUN7q2Tpkr776<8d?_LNG`TJd1(A@qA;T0di-&W?Lty`Tj@n(nTy7Hkq6z0T97vOA!wY*Qt9TITwXE6jSJ%C%x5nE1`tSp zgVb2%^2(9lV&O>iEEA(Oaw5!1gA*oIH44i`A1X$|< zoX^LoGm%Tm<}RcSES>^9@_7}@bZWO(La-KpC7K$Zoih zc`*2N2xsX4lDEgc(|qnx>tG&O%GW}+-Y=i>V*up2s#e9AXx{_b7k>GjH45Z;>LDak zdD4F#vR|c~nsIC{9YHb3SFgWg?6&8P>?{C(BL>$p0wJ$$nTahbO)?O}B*-fG<@*XL z0tITv0HaE*3t3~o+$#gvFd}=fQKR*OYyiokp6nOF( z*1>oa^#Sfo<*$Ihfn<~m^g^GSjHJuw#gR?&m|o?52EYNof<>d9kT+8=C878IBluTz z1xSA`D+QW#%f}>3@QcQzo6;D?4u6>hdRCB!)be>7$KJXYCJ$d#03eG%GAMGI+d~(E z=VLZzss}l?350DP2gvFtpLYmZ(-l{4$@*s~5TghsQ)3N}!+jt5yi($J6b_zB)lok0 zRK~K=AyK>p&{s>rtD;HF=M`i2mx6Z=v}4+UQ2a|6CkQS}jjVj~dDk+Q(SdA~mjKsb z+#-PfGHC85pLYv|>1OknPSKm1pq5Fquz!KDBCL8E%;qETiu3stuUfx8 zV=)kvC!u`Ja`&8xn5yoNLMs7bBOib^w4qz<-AToAntHb+fOUm%fDa%u%4{CCmTH#i zYNH2?O@VOs!v=PN@T@cl-lv8T*sM<79-<9$~ zO&;m_L)cenOTDxdW>;xd(ym(G#CD2ju#lyFjvL(1bf>jXs;lfOt&QdNhT*WR3DNhY z=RG6I4JJ8RlABHP1xao<$)%F~)FfY%RWTHtHN;1tPizS(9lAR=( zYm)sXS;r(tNwSGaPLpIy7v`O10?dIo>3XN^+V> zo|fcnle{d+g(m5}E9qq>tyGck*d#+FxxpmkB)QonD@t;^N!F0$rzTlnk_Sw(r6iA= zWH(8E=QZiUl0IjW<0N_6BxgwSrb#Z6|C>)G_MfbiMaj>_TDuYRaa>#UMhrE zxhiT^sj9OZrUzy8xJ9-Rat+t2>PVU!wX0;>s2F2wB#u{F)iQ6 zU2R8f`Y5?oTCr)N5A7+u15=z>rR|KO56s%t{P#)Ig)tP!BRFYp>nGN&);a zZGWuM>hl1a+`}mvQShqP1BtTgRc%W&4ZN)?P3>7#-Amv*~KgI2rx@;el&=fsWIw8(^~WkBz4Bi2p?7s)TRl4)11+sdue+HtuuXIGbQ zoA$bfSv*>~M54h&dPzI29NSe|&a+C>u11P8Z)mwVVB=n|rDJ2qV4Mi7#nYVaM6>nU zyF3OSRD;aplY8F2P7xfgPQQ0m0MhHd%FrGkO>4T?d9c;|v6V<~DFy@;N!3Lj(Op4Lt21_0H zZvgPmsxucD3O@t>fa!*L8Vyh(pQGNPGu}Uff5nt>xtTQe_3>EI;`6HXD*4HZuO-0? zOJ|gM{Eaw2!WY?V^TnE_w?jXvnF3iwzkJ6MO0$*P^wWmCK4ee%1?Gi2i9aPX&eBpjQx zyl@HvkLrpSiNEv(J15(3(kg{WNqca+N{LvoNsDMNnUlbnZo=Uc^>zz*OIK=7ym;)# zm7p~Myx{|VWeLJZEDCsQ=RoXB;S%u~q(>w|{Jlww)qaKjI?+2s;@g;h4(NvRgg@vy zpuN&j6)>`hDH9}B3Fgo`zU;@h(BGm3=3>ZNOGk4l&(aGn;8Ux-juQa#{SJX_q))z^ zhqs{Ae$Mq%B}^13F8MJ(z6bz8AnD0&{zY#jdklZc)tVvjipxPkQMLl{r9_F}-`2{< zOXgKDZu*>l#y>y?DBvr@;ziawT47CkH@Ql|m}3gKua>88d)L9%dZ=TSqmel(r;*_y zqY)YH$mmPPsBN3x(FStNbGkQcX&$;O9_Pg$&3E z^|fXAa@@ACZS-c`mx!;M%yPuPdlG+ApF8>L=Tvs8F zaFFmD3k|6C*#g}Aso@;mFCXCI*^<84B5P3#vGS!17U>^qo;*4qx|aucaNy+fW_P`^ zM74?z1ofV~Im*mlega473;Fx*wvu{k7oBn5;_fV7`4DpxZ}-E#3;dOykTMU2qL63U z;<{lj;UM^5n=)P=auZP1c9Z~DA-wAY$W38}hD=*70i6BqECPS2UEdyV0J3b6^HKi2 zRUq~F5c<@Z9*F9;Z|@;DHiNLE47pDME2kTo&oT>2nK-i5qnnQGn_v5ZTo-ariX zp(4JbMuv9R6!KPO0&&fS1kD2AB_HTmd&J)WwJwvi%c_Gm0kF*nlBt+VC)*2oTW!y7 zqjfm}z#04llp*B%1QD_w)zUq1_&~%}XCeo()YY>XoOZDNJkr8uRYSED3qTTqWHw4Y z7(|(@qb=^fgS~?g@tTm;^~-M^bwb|B7TMm$WM`lYWWD_IS`#Reoo(Mv$HDpyq+k++ z)BS)2sPqeY7u(Yhv4xBRyArase);tmDbIJcxi&f36q4_RY>!_~!}mhoJt`ktFDUi- zX~-^-T*gvn(;ROhAL7Wy zxho0_e;2Y3eR5AHOf47k8qa7;ZX!#53Bk7{q*tV`rlfu{gEWlP>il5rKe`FP-%^99 zxC3pLdoX4N@K<_@<~wjjV^n;s=BNt!v!Ndi0J#(n^iy@7mn%{IGfTULMHXcf`0tZ4y>1$L7t7s+ ze2(^RXD3q*KycC&a;g}a=lH)Aofow%^w5+m5dJ{`{~I*`bG7IH248y`7nI;%DnUHE zMp3?*r)6WcPN@uGH50&6=X4E>f^ebMwWj{Ql%^1NkpO)1P)pRtz&=x_-ywQ6?C
  • 5<*$LSmzr2W%|0SWWk%7AWG-T)f z@`ulo{FTs-=;TQEe?!L6P#OBq;5)yCd{t!teou7%l+XAuTp3x&KM1&vj6$dI=23>Rt1AxDuuH*O7`hq5&|dEq%5JSr8S60W z4oo>h{H0ifvbjau-CA+jf1fIh1gD;DJt9yreX3P|WJ^ ze5bbUhXY!W!oL@n4{2S3>2e^OHi>lMS|d^COI*4@M<&kk>sJF=UG8$`t-^&u4ogqG zR{G_=CCPy%xm}XOP4aU|jyK7ZlALCe=Oj7XB(FdPhD&mT zNhV2hvq@%1a=S^^l;o!-*+h~DOtPIMkDFv~Nq%RL-n?fdea;k5mgHrVd_j^oO>(Iu zADHB8l4QmS=e*65R84Z1BwZ$XNRm+|c}kMrM3cTK=`@qPCCN;ad?d+SlMKXVPMG2` z$!JM7G09X(wlv7q{M*$5tR7EsrlA*KsSqDfK@J*Hmde2O2s~^V;M)yOWIPy!V(1Yq zIjT4KR`pOKA?Yp_yE?u;%Gd<4{)kp7ek-K%)OQH8y&*MxGl!5N^Ppjm`2C1hNFN8t zJgVj4hUmdZwfVRZ|IedZRc{c+?S{)AEUpIpDGUGmsKN$;ecGZn;KdeO6WDJmb8t~h z1K!LM_U%+6Q}E4_2E4hY%uSGNn-WxA1zluu{jAdyzQm~{-og@47Oqv+>>-pk;4Li{ z^04^#^PHtM#7?Bp-$9FwSqq(uw8~G}+hJ-Hp2d3+o>Aic6IyZ#U4d*> zKTM_^R3imBXgwHqgVB>1+r@nVqfSfU`{fBphb-+XX|~-K)xJWs+|Lr{?hW#*+fBmM z0cSNY*cHGU@gV2n=dhQr8eJGe{OZT1;I4-v*nYHJ`3nntyfF_`KLTbppMbP)%p)z~ zrvunTAg1B3jGc*$XUbA6?_a}yOz_v5va1Xu(| zyL$5vyo*OOMd7#F*qYIOh_ytv#a++?!0hpUi03~~%2%h7uszte)sjInyISEQdDBeX z{8nqvV?^UqxX*K>=zmH}Yu$1dxf}j~V7j@*LL4&fYHD+68YLlTV6{qyRUIm`%e6Zk zkew|6Sqg|O0(WGgPejPJ1DNK2DF>*Ur>J z>+0-o;?Ok&=q_xl_dRah_2$f>2?PoSX0m%=d{znhzZ;l8S?FpEOby!AH~)ch;@Q;~ z{-tRA+Y^jok})3)+XPsx>b*xKyF#)#Qbr8h5-B4tW}R`z7v`a1;@SgvW_w@U`T^aL zZ$$WM+|rw=nhU>Sgq8m57dq2oZ{tD@Zl0;@jp)cI76-zEz9ZWVfx84hMiiR~($yc6*1-B_9%= zB1m9O@V#Ihlf!D7Gu%Qc@(L{HENb_O8k-~G%TRgXE&^mptI=hmnMSL;DZ;J}#AK0O z%_RR01CBKavYwLGc?dJ^WjH`4*+u2ET4E601YlL)lv=%_<5^TSwdRq_n>d_hYYc0Q zyb!^vhImOgnYQlYm9v=LnIv}5W0^R0R?81ODV=Ry2KkTM%KnJ_;XH4tb(ymRt!%8K zs9UI1+&1nfZ4UST8Gr)SE`73v)l*RwYRk`Zb{jVBM2NzUIAH0IED@!_lH5O#U2wv3 zWjPi=N#tpZ9x{pAe{N-!17X?uoP*6EQ5k%TWi)X`eZK4HPQug9JJ6Rkx z)FO7CY`vE;Rw)>ku>wo||`;whcdPm3aKmmhAo-dkJ@<(Jxw>s7OoFLr_pp zi<=iUck=zkXjyx-8_uW~kx=Vb+!~2es4NaOzce5C(5FZEPXq$$H6T!uuB-z zw+8T%vyX$Du=E&IeGkF?uFsQ-9m|a9k2V$GMm|XcH_O06vHbCp>W^cg_Yq!hTW~+^ zO?u(KKg7LE@J9I#I<0cdR#cZ`NeSpwsKWFbzOhoz8~PxonTJDyhQ31c7o0(1~u zx73DwvtSwepvX8Z{S^GU3{m%9dTjkMxC^d)*?ORwu#Nl~ z(D!=kK~C|-ai0(63qcr~L<;g{h%Oio{6W5JI>_}o_!Z5pjN=L%&o&(BL8cIAfQvYm z#r96!MX4a~G+ee8!>{7n*#SEAzsPg};Pa5q|4#&7e!>kBVslqLJlh}|Z#anX$Jlh> zG9qw{&(IwtvCEL987}alU-{!DmX*d^a*6WSw1k=!Kws{mrzDP+7^r$al&&{x^dQ!3 za}D$Tr02ksUc!4#bH@#P0*V_^qtKzDG<->H215J9L@X4?;AOgA-ci%sL3#fX!cV*F z{=e+=Kd{6I|TeY(LrFdwO9Ncj2Y#sASwOw5PACX zk{g0w*Q&IB1gui#6(dYkKuU$_2845W+gNqTf9R$sg+ELM;JT%I3KL=7zXwv{U)S6< z2bUHO%SUE!)*xdNn96(@G65)~mhy~TY^|)a_rx(M@a`Z5(gA5F;fqr&>@1#*jF42* zqk_0xDvcd>3R$4p%bxpSD%vW;Gs=dgJR=tuTj8TrkVpI{W;IsXYcaP}K%Nsgrkay= z0{H8$dNTM^yEnK#Y|#<)q^FD3HxPsQ5Xfq0rO`AL)x{NKZ-cweP!i>f!44B!H434I zr!jI(F})?$81F+?WVq<;bCI;#Xu{}Xk3J{9&?K%gQM#{X@AoEE9rZ5I!ce;V12yYi zUTb05Ry#z?-*GU%i&WBfI3s5Oj%GEAa!E4uZ4PmP!^4bl)Lm)S_>|duo>e zQI6pt)fd(Y;L3P;#Y;D}>h<0Rt@c17(Le|R9m#4`jo53(c_b7a2I5d>J*;$+v@>6)j$>dP`$vFDN_bRNckQK*O(|h6k#$)_+I1T$WpKI(-P|ude{)1V94}-gPVHhSrKtZfWk=_d&ZQ8c8yqTv3u-dd(+ zwT2A_f|h~wWwu;!^vtGrpU(5Rnte!-(R(`2Q}qnjQz&)L^DN{zaT}L9y(%>!F@u2C zb6g)6*(t}R+t9FSwSi1U`SOoHsM_;>$V^_?;j7uhs%=w z(A@RH*Fl8@L&Xo|2rs7Y#9>x;sG}ZPfAMPqtjv})Vy{s--Nss$M9vZ8|Ip%t7el5; z^=qDdP^|kytJ3RL@Ra>9WEf5(I_)VsEpielFHhs7p+!!W`+X>Cq+sX!PIej3?uOU+ zw1E8a68<`ZDfJAE~ivjizUw6>IJzi55V$Od^~3jn^!Fl2OTsOHZGDdfeXPjONK@=x3AaZT{WwLZ9R z>7H^$0+h7^M;X!urcWDdL9i-KR5lgQjfN6`pL7(%?F6_ucnYn5QMG%nvHc)BzWSpQ1}<5N+jw8*~ZC`krKV)NKlff z;@Hd`2}(LkAx*!&h2=%SXSCB}eBKv`4yF>f)VZjM+X9Y7%=i4sdfggjd9D^Y>QY%|ZBe`i@6?05@Hh@ME z`Ii=4^KVdY>5kq>JH*Vf5lRwZNF@_y8C6Wq++@9>CKsy<@Re23^Di_*ZGd!3H^{eT z$SsmFeI(L)q*w?*EiZWTMHp$#5|bgEN60lWq%R~Y6;$b@oR#er=b^!V7%=xde4rc? z3+yeFmx}{!W;>3$uScTZj^phKH15GbC`mA+=IxJbCg%e-bJhUQj%}aJpv}N_OZSu* z+n}s3ILas(&S@QOn3(dGQp@%9AV)p=2C~(7<`^pd<$JT=Ep$tDNT;FT%5<`0k@*;i zV8fxm19JylnQR&smXSsE&XtIIs73Nvk@*n0*t5wf$Fz9;U+mJ5y+d_xhShuqfa8Hp z;6UjDLnh5ZNJ}L;Y1@r&(@w>6M;kq9{NsdK;JT%IBu)AyRK{=g0jtCS`kU`9;L5P% z&z9k4i4&hv*dB0|FJVZZZ5625B;*%UgV+r``x<&YzM^v+Lrq+7=aJ#+y z@sbVT%3yCW`tFHUaf|LJ;40t1kX3XUcrC;Kx37|)QGu8&g`B7M!4A=P&^ zyrc}+J{4}M6}jL5X{So(QM|$`0;1G4alZECD!f|D#UTf4*p;X0EedIC)g+J&#j}aw zS#@7brk2*>hFbDupgT*v^DkQVjgX=#8_gOv=W*YOAHef|1D@WRtci^>k~i^uoWg#F zK)DV>#+sTo)`GyvbkpIx$b5$9{zf|*T(@*a+2jBkq+D>Ww$hW^pGz8oE0f#yyuA{I zkEO@0LvaIpp8@t4h1n)JOssvRrQ~h~y~aTKOWI*@ea*ept#`V8)5nL!!$*j1yUlnP zUkwXj)XX_cKE}myWVw(T$Y`r)?)%jgR6$uSCwD?Ow32UHB8jF^ zkKRnaX-TJMl7>A)E@Bj2^noQxchQm6t^16XMHvBZ=5NO5P)MA3a|FzthGoEzC?2P~ zLVHyW!^SrOVTMcpKyxd&GKT7sOU`)j4v7&%`CM|lWCzBn2-w;#@$t&gSt zH%lS>#hnh8@E+2!rT%JK`SMRDxNfNcx#kurLKZD*nrLOcAen36{j*$S8-lI&=%mlv zH~jKX?E149;cJMIAT_V%94tOW0#0JR#tK^tS4!;r(6m~=-ck$$}7h+jJr zni>sixn-m7ChskaW_#TmrDdAey-ivkOhwDSRtdeM90I)@8X7#{r(u1-uSoO0G@THz zUo3>d*;DqXgjg1>^8P7dlnwsm1hp($1DjL)tvC}o7jYIRZs8Lx@d%#2#q3q0f1f56 zS)2v9G4!~_=`Kn`^pI{SsQMhXS&^rIG{VAufxD^A^~n1BJGa4=c_Mb0bjym$jkd5* zQPt|i=Z8NqgeygJD{@S0(7vu9ioP5Tn*+FP`Xp^t!vlW}`7F6<%R(_Joi&~{PspN$ zLn^t6<1pj65K`rJ7&6DvtWf*m<5{y-hlO4eGMzeT5@OAYUg*Wv**lwu; zd2YFI*bqj?htj`Od8U7~EGhjviHWF4NR=uuq<=K!W%x%ZmO_qW)~c)pp3gRW(z~AE zx}^qqmk5Hg_oZg+-BL9ZXS~$d}p|ZLHijT-;WyC#Rgn%9RDJKG=_IC!ns~E&a!;z;Ox( zOX(ZwENz`5tjNz*&xeCvJiA{syE3G~62(Z?;jb za3%g<5GdB|Mn<5PnYAGBXMd=y0@ztbaASO#EfZX~bVixC0BvspI7$;!2Q|4Yg-{1u zYwT$}%M_>RarXDXM}zH_?x3V-9`+2pEZ$R{?nav-kmaxhJ!icPk7wD>Sre{A5{oXv%kA%};vhW3@r26`XAut-*_yKo4pH>fP*p7yi#0HJiJyph zO9VQd+1`OD9{;~B=x$4r(f;Wz=x$4%PPf!s&`&IGoo=Expr2SO>*LHiEdAThtZWuM z$tluPsHHE^JHfTfP~R8(oX&>9zk;Es!ULXKS40LPuT({wj+%(^$-!4#mzuxgqPaQwftgR zjX4T!Rr+<5}m%OkXZmg?c;8TAeT(@)#^}9eoJxhEI zT5Y>Q#K7=rq*eYFyvhz4YH~QHE6(o$F~m>{Z{&}cGzZr$H6WFONz)?nT(C15pGJEn z*qNEQ87$3kmFjc#HMlY#b`aNtohkf|2n|6)>-xmk&}N1>;}WZao{K>h{p$N17yD5| zfa*IM^mqg1?^rDaSD&WAe2t#xdsFCq9a_EophgKqPw`!#TN^t3!8~dDbYJ`y;;imf zKSc&H`@F4m1p|#I1|qpA2W0_Ks=+|np~n8P0x(;)`YeU?48zBoy5PCHp&q|!zW5FC zyLL-;cwwpFDPoPwnV9e{i5r?diGs^F9Vp=zXpYTU#gh*lAxN_WC{V$`R2B3gR4f%JW`B9P4%t3#b`_i{hn zE!`s?ZN$M)XMDo9Bx)!%p*Ms$(1wyyaj=&`MHKegW1#O#gAfNJcy(vsB8@%`^h7N0 zOT?CsJ3ds}ajCd1!RWd>pvnjsGEy|UmgD+?wDEf&DAsx}^d% zWGx6g6SvHMif0)Eo8$}9!P3|riW`!1U_}ULn6s#1g}n$x4Hz;M_2!{m>*X&3yll+* zbi#9LeLbFweM$#|>y~bjx|w1{n6q5B9pL%9U41&;b+R|XYD|5v(p|0$Te-$YXJ8{A zhS4U?5dR2dbHf{db9W6~S&04;vEk@floxfvo#9?$4#PjCyY}X^P!) zkTaeoc;fM)L9j98nE;BXKg6U7OCfLa@J*UC;#RoR?Y&!CgIg*^RkehaW6J(j`NTey zF%E@=@5f%#dU_I9@g;E*xH7a)BmF40iLWAbb-`8o!H}V&{v#||{|)BTETJ8bB)J~U zcDVWq1WO^c74q>dc08LKo?;nG{&>lj|5LMD`ikHeK}^B#AfE_6$8sR1XWfYKPvFV$ z>XR{;dA6h|>=7Z$e{O`AdWzNwN<;H>2@?!rFl1C|7mujLDMs|E_rdy49!;~wcQ^8A zcK%2!d&cnCKN%AGMJY{B3^EvGrE`2)TXntr>&08NpnIPHfKm~L%v#iqXDOs`$9sXS z7|#ZVcm9D~J8<378FE7Q*1tKsSw~L`e@9|EFz8l|XHiy5f)fzA)9DpVpRIvpEAVnQ z!e26WfvvwXaW)bS-x<&&4Yl=sN&KfD6&>Y_i%dFzaeJZeIc{s0KOE;0#Zk`we7)Eb z<;;vc2F%vlPh!f5zX;P#^om9sJ^CP8b_3(~`8FL~8Kw;JUNm~Rzlh_}&RYCK5ftOZ zjGm=cDA^e|$a(F1DWl+vsi} z6L{K<=+*Tl-DbZgw^WUQv;IT*&9#Atwe{r+UdTb#i& zX*kflFIlVWg96gF_bjfHI)b@b!>?i{GRivDK9#_GT%B8bgS0(J-XU$jmd_rnsD1+O z&j&us(BaQ{?ZK5X95}@Y?}P>l8wswm@Q9p6!}sdmE$fVS5ONCkD(n#_%A!{N4&)Pq z1L+FhPa@ZgFgU2%pXai~Ke5_A2~U!H#wxIDOS z>7L5PZYawJ$E(za>C?tq5G=N}ll8>&@_&>J0@qFMX{YTcYs=|VgVRau@QqXUJ zG)YeaxTYTW3vh_!V~KxbM|nCVN?RB*n3G>Dm2i)3LjHyKm<1tAAyxIC#rHnO!D2Uj z+T`a;7(%=UWJ`=^j785Hf8zY+Ymg{!!;mRKD`u<(q07#&u;X|RF}(2S z(eJ@^za|{X&iFR*Um;Gk@thXMeN!rr?S#RUiaFXUO2KKA+HjI-DD~G`Mc~SCzb+;w zqt;sm+Bd=PZ2uRgEn~65aH2LAAb+qF5}f*uw^8UDoVMiZG`7v!@u8Dl5YDfmr;LC0 z@Q~@lo<7nocH5*{*cEVBRoAhLiuNkzv=BRE$@YKpV4k_WWX9EMD##m}SaqN&XW zDV9phL9iATA?t+?s*Ml}Qk?GCXF1KoQ1~nH(~dUe{0ZEPoX!#7zWp%m7YRx93g!56%7{~9K6DykeoX5Mu@+h* z-ZQn1gGGN!eO%+j`3lZ><=;~RH%lcv9-8YSBh6VUt>8N&G*(zlcVw5f`t9*nR!l?} zF)hs*-kQ+$Fkd?q&++(=AmNC1Fj)Fe80QMueygU3-oJ5l9k{a8(ZHAV?ocKqF}4%z zi{et6v!?eSSl4nYW_7qyzY_LHvGjlOmD9NIvE|Ru2N!0!0axmqWOUopH)3Sj1l&yq z*57q+XJY@FX~Zc6AA21GuCg2k3P&~6f`3+Y1~!oS^(s`N&|&C@A=M@{s=gsr9Htmq z3h7(jp0lHP_BDKK>M7~syA~}`3L8swG`Rs@jOmtu^{V;~F@jqY*GE+~f z7<7H;$4eH9I+dI;_&{ivO3th@G*qSKsazZGw;9uH~N(Ec3}zr&DmTCYcAG>eK+qJEB|0!b>q8W_OJh|J2UNK#It1WHE;^?9iYONxUq zX^u@K0Cea9fK2koCe6Lp=(Fae`PGM~P7e{PB`+z?CWU5`v4yVyFzUmuqwJ#a-#PEEekj0BV!r)}J{!`k~V8;24pW?o9Ev z0>d|CWpc<`2dw`!WKFDzk@pCIlu0nWl%Hu529_*;QqstqrI7Z0r!iHH=P)BM{sohd z&f1&)AMV{!H_{++C2nT;f;{>WhRj$rTOkWeR47l`2{CH{Ev&F2ZUzzw8BTY4nIDm{ zq$6ak#n0a(6@pD;fD72FsD>+jK6fAZ-sR~0>)Owp#Qvoh~0yj7ji z-ocP6qhZKs)3ycHqASRNcX4qVo5=}LOY{rh?vfh%1umsnck9>&VI3EE{PS}t2qO`tNw$sq*&Q5aBo-CL*p+Z zhfM6-)AjTz+Jt>)SHS(&z{cvH!}oh8)*SMuyY}0d`vUILFt7~>i^UUwYk)1IS)wam zri}d8!5V?-Qyi3C+0)j*I+3>!tiNhDFk~| zAD5+xgz8SWUHb*Dz83k_QLc+cr|QnC_Re4_Q^ox1&NN3c>?>oPbPNG#?+!vsIa!rYp-IgZJ_HpD z5p*;JQ3M23?1CK>0Y&&wQAEH30*Zi2$NGEE*}c0L_@4j&KF^)mdFPyW>dsEvS+=_i zPhD&!*+Y&WVQ`TDdq6C_#FMZ*T7;bn6|?G^W$KJqV}Ke=gp{!COMirk>{Fqte~yd| zZOh)OI7cSeDZzEn2-T%~XoTu2|Go^P(m6Bm;S2SAj`THp9dhyxe20ckv)0N+qGn|8 zgm-9~8F&WQQ>vj6Dx`&MHgrxBB@Xjm$<1|9|1=Jm@|u#>ZOP_9xyZj}Sv=W)$FitOgEW8g7{3KqB$Lq2G6bCZzIr zpgf)>Z*x3r?mF0^9&aU+Lmvd(H(9;YN|t(J&Y*Ph7^0uEQK2?a&b=L~S8Lq-cf)<- zP`M8fliD2O{(oP-p#d`0KjC{5g|!CiovmPsWTLbZ{Vw+gTc8@ zW9OhEB-NETG9=~~bP_FMr-~&2HCUf=|K6G|kq$)9gu!G(5jjynQt{XgHh}yr4(CCX ze>-4<^@t=LyDf`Ia3*Qd8~Y83#7k0iWaHzok7Fi;eohfS4b&)7pS3}HF5}uB&2!UA zGdSk3e(#OL`n}fflTm#GZ!_edjdzI}XE94?h2h-BsX)2#tXvfNG683q0$m;~Yd-0F z1%%ge`5<9mSGvU*p!!`fFyU*jq945j9a>Bz%+Zp~ZE>W#bel^&4f~q4EADYlFtt0c zIO+!Tp@l61MiYS9-S*;u%bk{vGnChqcAHGCYRx+|#>{}!vb(9w+t8TzQGIUpt5A27 z-x{?Be*PQv&V5ONVP10=_5r+b4vvpua8dp5Qx1f84Fm>`ixg*J$62v+n(@m(4JJYb zVAb5QQc{^g%HGA5oy4AK0%__yAQUqIf4$6LVni zOfsvIbF{<#Kn>Yo^66r4sUcP(667Uxj)Xe)`d0X{sf`kEvIbYpomg?b3Rn zwOgF|6$uFa&C05RWw^NIC=9%G38}^vIG6;2`IwrdpHo^{Kn*6M(jwUf7)1>H4JR>v zU_CCJ(i#~o>=}(H6a&#$z~IvQ-%+qiYYvwdQN%_^iZ@_i!wpA2r?hqhHJG#9Kg3uH z7u^Tzw7o5{t>`{2;u}JKgu%fbevsND(wX{QhzR=~j~0tDm3is@iUDe{8q(*xqZuj~ zkP1tVw{byMt85FDn}Z9VQjfP#NY8io36T#NM>LjokhT0I^7DC3OoP1u|5EZS?GHov zn&jhq&$yaq5!bgPun8y=2WGB(_ds?J&ni|lS08nhEt3x6lHXpu zcXakJj_NAJ>m*P;TqSgp_5CCfaVbnBUPKQC|5EZSJx|7;Fz_J6BuE}SCRjl`1G_;$ zIcqoZya~$p7`9!`1lrk>byffu1!U6#1Nmy0Y}kBJZSN#&r2Pfo8~1#e6HSlPMAIx0 zKPJ5Pc6F_j9OBQxd=VD{%~}N}JIxs^*!!oo%QUa+vgP+nTp)t^ElGjL8m?!f}DG6Fa-loelxXskD4^~Ll11$zjn!TP8hEZewghmU1=S!{Wp`pPb9257<^CO#)eh*V=x)%@ zsUtlDvNRP)M4ne5I}E5k6$YotnI&AovxLG+THmbIXumH4thEkKgLP0QV@Vff;_HCT zEO>hj0^JS(WeNV|y8>!TOYU9j|J_bq!?EFqo_mWTJqi?tKH_*95%l7LNQ@fDP6ol33iN-GJzQ zVK7PGcxtRjYPccA4A>hi5~okN0I1PTz0h5z6>P;d*Az5acKs&-&X+l8s%80zRUWR>Uy$Mf*p>K~l4t2C zGN!-~p6YW##AaOS@2YR}WxSt+4)>1~|AqY}{-xw8JcqD8a{^cTIT#$PbTd{YGjV;G z_!qYOPso#$@coL72x)M>QT^syEfXl`?q_&zP)X!(>513(fL1`3Cxe`cw%Y^38R@35 zZv{qZ^MQ`2W)kPxBegvN*&XW59slQN67^uNt1Jo_bKoQR4kIyVXX*5PUtE_TIm%o2n4lT8CWkLI5^;Vsnap3-Z4 zP9Y2sqd}R)GkV`*W=eh8Q|9(Q2`~K`49;oVyW`x6Uea4S2pcB;#%9i{W-fT`c&7n1 zSRYyItH5!soz&=F(#Yup4-UQ=dTyNWW3jR1PM{ks5+~c|2V@J?^Sxwp?P~DjDJGaL%YJ0RMXKiRHgKmP5ia~K`U0FyG0{h@YEcghnzFjjqOk`<5PM-^>Hv{ zLwpPUZLGU-(!$DU3NzLfBGR9Z2dmIXU3fELmYzVZhy7Btna1zzG(Hd1<}rxcRRwc$ zMqj!rU+yY2 zQ&Rj1yTWafPPR#-+#qFLEDe259O&GKhS!^b!(z#=q$#fSjEMTU)?2_}`s%pQc410E zcx&Qv^7mMB8itFJ7QZucE&^(>GWav$;K4%?M>=9YxtGAO<1DUFI$-S#7s)@k z?2YXax$qlgMbIgc0-y%#g4-Yt=1#{>C^z|eGBf?UC?t=&U@-YWTxc!tK68!C+RJq0v5JR?>S)U?VZ?NDZ}#eh#e` z4q8?Q?QS9gZOKW_)QIZv)RSP?c`Cf5@a*gODh2E}@aUwUQ;WI-HCT zU@%7k&+}p1^ad^MG{w(L8XwJx5)Z+iW%0FVR+^bv1Jqy&MDGqbD0-g#*_bjV#}4(w z5E)-UQiW3@#E-B$TO7_>>t&z@i-Y40QUiytIz}rsB9JGRytCcDiRwNS8#-=-r#=7% zN8EaOewv6lrZ+xE4+L)$_~n;Ih`V5af=~X?uRWU-^Lv3B%z;q5!oe~ByNfO!BgZBf zHgQnHNop7RVcWJJ7nK&Pvt0HiP=g65e=n!vbX_3&IT*~ggGOcrB$c~TiWsaWPp~+g zM^yq)gVl&5FItFnAbL9(%rO>yNgRtYX_&0)C)rWEG|?CK2>eS)w6rM<;TfNXPtxE@ zp8{5ygo2%8h3?EvJO$KXH46Q%C?U20(RaZJ3cc5_VIpg%HnjfTw4rRd zMp~D0!^PLIPvBolN~K$22v2Kp{EjRAPZ%}_lt{2^tXo9OFcFJ?DM{gLFPPEDQhkP_ zHE0Kvy94%2mWCI7MgqO^k6ECYR^y*mSrm|+m0)&aeJiW!;(nm-S+dSXjAsL~f5wyS z5bkCq*LT(G$hw#acU{uNZa>8IUtsWFHkvrXMV6r1B~AyOP-pLGyPU`lyvu}_gv=Q& z3g*|I(ZUmj`fo+TnbB$m^j2bHHwB6o^neVbxb-oPsYxSbTIO^X$7a#h2q-WOMAzK4 z)sSfmA)&8_!I67Jy*C2GTbd}s%|O~~cVa;r_SwJ9ymKZ-^k@`1tCx4bsIP#`5BOix z9)&4Ry9oH(QVJ~dU1v{Tlk;4`7On(P=uKdBxnZYSEt-omx0-!n(7r9h02~SsbimFb(d=I;!$^>>}O*PcEGJHd+cvBC&AK5pZXkZnPD?DmXP9o@G`Xox$%n zK)C{$1&smXpjcg82Rgu#ZD3cRxGFcwA{_s0k-R)4DUE9d8n$<_!7&YDdJ7nw%e~B;o|AQpZvsa$V|jwozl z5jsuh+dvKGK$gvggB!6`LKh#C<0uR!rs=n!SdyB)DMb7W`-8vC%HRww!ZDgMSihWJ zw3?1-sW?D-0~pLk(^5ffB>((Ux9ACbt;Oc_ZU+K2SfA2-9TR0^f#_3UFxfpI!`@Fg zXO~8c<*+AM9Bl$i062&ou)%sD$?x}@Cbj|TXbGm-8GI5b7x!PdSIw$|0|;K$YSO)n zyy2<4w{Ozgp294$gIsi8rb z!*+L(-Sw^zk!k?%^0r20sF)!TzX= zeMqi+oba7TR{-Nh2w)^}a*V9wKLf8_*Uf}FxqTHVXLi+n<~oyS3pCxapoxdUnN72k zLG_MQGV?Jag8v4K(5ZKwff}q&xxNBq{fKOYKbTDvkl2K?QG(zHERsY!EAItrupW`T zb-xgg0nsM4`bUblVei1dl*Dm%AQb`oO1ERNAqsPmd5#+m%-Xm8F$72syF`R}^RgTAk@&@(xc-cz(UR@?D zQ8k$WYk-awy3UC5StTf))eV&_LIwlneu(L!^CjT?~_(`Z(C6KJzjRnI8}8H=7nA5 z+ZPm0dH|niJnbEJUG1A9GyGG~ZO5Lu1!BF{2Nc7{i;SyjGzN5)?^%E1H^LExH|m=mVI{kKI7;-N;7r zhptD8yI>!^YO;Cl(!Lw0!31C{*@Id6%zCmMpuP?U->S5WHYj$a@nC9**bVy~i_eao zzw!WJg9$*mPHV8+EvgOF5>5ctufSkRdbKx*l5_?yaf^f$%yHck#X3L@)~6`W_`@xl zriEn#)Vso9zLhoH)ekyjG&rzREMNK)Pu2040sh>Rv`5Fuk*^hdlErubyM}WPb z8!c+3qFJy4MGMJ4t+FvtgLUzUyFeT?+U=ekB3i>o&x65)bcBtT&xE8hX>)`qhJF5u zS#s_DHsb=o1}lTH6CA`?@+{VpP{AG|_tP-!SO(=cX}Z5~i=D9dTf}w|R_+68us-tJ zvm7xz0z^L#17wN#Xc}S{#76Rm;-cxyv}tHU6YD_zh{~TP>u8hJlxfJov+9Xy$iOeu z4hXb(6#|9y)x3=I2<;B1=5`*T9 z1)VBX+vzeT)odVtT2RRC=YRMMY1o}yRyYqQ4rVO&JfP-JN9ez+b<^c=OZvA3g|9u0 z&D+y!`7tMqEz6elY)E@%$n@G>(h$xr54LEGx$SSX<*xEde_`G%ggds@XfF)@zGvb8cT(Q$0uWh^36gBFOfbcGPmVxX?~M{jx*25&8LsY5kWS6Pi~VkgAPZm z=!Y+4)D5UM>PR1zqo7%{(NM}h)}$}a6+UKa;;0Twa}sH?XnY=hb`GUwW_0s}H2M~u ztGqkDJEe_%&wRW5L5R;qUx9u&G?#x`<)=WohxVcRWTwo${TH}LSW?b_>zXZv?4#WD zrM`<-KkMOMzGO0D9^7Ia0F)UwK$iBH=TzCJ3E!ngSQQ*UOE&V4fq*^}2HyZA6;x$O zyZvAsdjflc#qHbxPXjerpKgGQ*be_95d8}nHrd@8hc~Mg?S;QvJ2xmw_-6HQz7<`1 zFX?xzz9(EsoILiXnUmS7?_JmpUj%7R=qfe! zE?KL2TdWh|mM9#JIkCnc8LN=TlvO{w_CjyTMKhnAfvK+;@LIJURAXKYP?cHvo8Jqb z`+?TC^qfV_BLUe}fwJ&I_79-D&YNM32?>-%MSUxZWvaz&Jf+*J3A5!Q|5t#srWcFG zx%?6VJrxTtCr63K?UK9T)5js@KcOA*JhRO$euSic6$WQ7#V)9JeOLjUOu- z&FkM*?U*A|aERLvb7aHltMJH~^=*h~_(SufDt<0HI+?2LT-hqRsA0h85PTjWpY`f3 z_(c5%A0lhuX}?|lJ6E>D5yb80$%f+wG{UfPs;IwSPo)Zk8qgSGaJIC{S7a}K9UFVm z*`S{@YG2KYnWFv-J;l_-p=?>?Y+^b`G0_aYTU)hno=lG3ZH4q-trl*LYx897#0vyX z5cLbRtUF(&7d8s9i?R4MJg8NZ`KWTqjji(hO!c0Rj_@QkWj>?_)Uc~kX1#qgbgCoRV#R1{-+idM(Uec>Cj-Yt$mX6KJ)%ALi`%QtCeLG#rl zD+_Um7!+L@sJt~{@SQ**;P|}sSE`Ya@DhRlkM`lBH6$Lmg}(<-gBj4UL=h8~x;*iq z9ZHTVFdSNx-*Yw7n3nYRVA+2;>@gOr({XtksKEs2W{k<;#}0Zfr*I3u2rvCZ7&p*v zuAR)Zr1<*0NO1~w%Ufu#0yUTbwA&B$&%z6hY7PXP0EhILc zF!T6fyH4~1YA^#1jjuvX=v{bbfOa@J?u6mcB5R+Fqk`EHG;uh(BB3>i+ZWuOGP;*6^NdqFp8Q3GO=sC^RMW6=jqiTnScXweQ5Md?r zaaAuaylPWW*J+AOX720o3gZ3;&Kk4P0fSVA#qG?#_XcV(0k}(^FbVGE!CC7R&i04> zjm7PZHhu$Yus%g`t;wflf=|M*`7n1$lHy?uwSaH1c(UzMZUNL_J>t38Oc!+*ROwDU z!vj38-?*QGH1d9xq73#Di_a;Rr9chV2cPE*y$kp#AbleYj@9uSw?vS9S-cc`VNbY) z?I2Kt^@*(lZ|)rjqMwCflL;?L)m{@Ws%Bv&<0g(wtuh|4!Foh8Xs%1t1EM#DVdfKW zt01YLu0@Ids&o;m?Fdq0IVi2uPGK`f{L^~Gous)aph+7tf=Y~Zj<1Rk>tTo96c3!n z3DjVHibh{-)_(_xz6%CNgZ2jCbWJ$7o)7VhpK)>O2eV2!*?R$~!Foh8oc42PgCr6L zlh6hV;U%eI(KrYO@UB}pa)27F29A;)*y(^G??yDk0yMMy;0a0@sZ>QnwgC2qTL_l` zHJE@18$F4o=7w$sP~QN9KJs$=W{74JHFYy8^ zN#FSpcILo7^Sznv)9kyX45-1nh*W1dxQYD_)_)%$#~K(+NZTH)7-4EncuDWet5MJxiI%~vNgJnH`BPe%s1Qid1gQB(jpv05-Ls=oB4f$JS zPD|7osNwb#0fkJ$30T*f2;i;n%)~k&Pi0|C*7G>tMJXf4N*H#w51NY6T3YkEkzAyt zaT%utZiT(v;&Y004^V?B+ES4&#RcWwI;}pKX+q-&A?IN*J1u<&rHhn%)(EE#)e_`j zVh*@i0qMwIn2L?i-QXS~>x$bz&lu0qU7Bn2%m`2;z(O!{g7A5HSFDXN%Bz zFx(E*U;@gaok*Aau$e=-7*Wv=r*J?fhlb>-ZJUj*ODWx0#!uv zO#c-P70@wOcpc2(5Y3!mS4S79+gJ!) zG#4p?#3)P8={vUu%Khx$%~c=ad#?;Y->w+oO&V`DKV%oHP4`1~liGhj%l>h{Y@Z&ARyAwv=ozAR z!SH5SG^e9VKGXK>H-lVkWm%pYy-a4}qtYvu;d1~B)#uCPbbn21kQ>6_Jfao%pdu#T zW50)pUa%)vY)*w71k_-Cl(@$et&4F$^t)g%8LbHik&$?vHBq7hc2|om#cvnqGk^^y zAhrYe%>2th^tWNyY{E-Y{pRAeIN0?9BsRxspa!cEN5;RJxC})97Y1|CIxW7d1m~g5 zNKxlDY|`lTpsen1ge!wZp|?(Z@0!Maf?U9QUl^=RE2%-rA)VU$!^8~Or}mjS?cDtf zfEuh1M&IoV+@cc5HcQTD$M_?lDZS_g)t8a=XhyT9W{TQ*ZLI~>ER0)g=S>JKr}{>t zQvC>(W)@MPXz|IlT)R%CK7>OuJ#c^WsTr-wc5rPRsoNitiT+`5S6Wg|q$b)@xZ~-$ z;`tc~mR3^`PDhH}ph@F!S3pLE<81i``8|V4*$Le9oqAwJ!avK)7M?e3svrN zS!09)5pEY@XX=h7p*})+#pu z4Q@j@qvpCAn0buF?w97c#YYg@zS~s2Vn?rDr+})`SIAMly1-p%Ne!{3rrA$d1M$CSh~2nnjwx5zGQ@0u3lV$;(6azR{K}Tl#CboNx2ONbNq(k z=C|;Da+evcfp&m@I6AdfN?$@+XUq$Y7YU7B9k0x!b@-klKN=4zyiu_deV{(@<_s7V zsF2Sra*I2GzV?wxJ>RCDf1_-Bkv|r)tAIXf$vW?FZM;zy6GojNyBp~JmTV2;H79ls z-Yo1(hcM2de^eTEMHefEJ**gdjx2PGDnRut7<`ZRP(2=%2@~i!gl*M8@5Iw~AnX_` zFlV;D1gOE-EMIOlJzV;CxcvF1AJDp@}Gb#URZn#rPAbPPfsR1Zv(22 zhQVoW0=?d|Mi+~O?OG<)p5F8{hNG964a70wi3qV6_9q{j$#Jq_HBf^Ikquqppls;R z_7I^CJ|=78Qzd5~leM&FDqP97zVvSBS6DR89*<@~IajQPM&!Rg-%Z0_g;b0Rcs^;h z>AsQZ%=m$h{J@OQYA1UGvSw#yNES_9CS2@9X`xPaejHTaf>4sB+R;}1>PFQd`0g z8KT+{T?tHo4hE-YH3pD(YhA;_@kQ|@8dzay55GobQtXG_)Z%n{72g3hm;-TG4F?Sa zvn&2}i+A2P!=GUXZ(v8!6Z(uPSeC8!+<^!j_3<}8yXAT+hr+=xd(b~_ap^r%ZI6lJ z`7=(9tB_4{Ntnqu@6^QOmedGa>IIO?4g+1{Ye4doHu!qtZa!yloTzbM!)ofY3OsHv zs=q2^y`*Y^U1ymHQ0sw6dth(|EK#|uWMafcunm3LMXmEH+(9GYZLlCx8A%GbOKY%= z@kSh2CX-_Z43h=fh_lwiJ5nfNWEHD`f-U zAwYes5S#|~N1zk zA^_zWj|{~4B6_2jfbOwmYulw5qv}5?JJjsi8|%83XGhy}sJi<}Y{Q)m&yJR-vr+mP z_571qCVv^8`Ysrp)$~Om9IYPnvX)-LCwD#rpPkP|il0f$;%ILN@CQ(X8Ib(9NCc(r z>CppUC@O%X77Uv)Zb4W_aqw+3bDW*_-JoVL0oBYHuni=(JA&Cn0ZBC& zhwq@Nr`Di8EF-0X>g_c$x%+-x^DCac5mRh}94)Hus&T`f$X)iHNMBijTbzSJS1TUQ zXyFf)`jj+=CiFqYeannwV2iX?Sr4dLNXRFuR=z4A>H_q0OV$~!_Pa&4sJEMrBL;m^ z+0CAwRCqoBR9~aEKZQ+jB%!_JrU^eN4Brc1Sx+d4 z-F-n^6$Tf~NG@cOs*xE@Tl1erRM=7ADTU zX=X^^ffZdh!MF~b>i=1`M;Ry7r%%fi<2v-1BDsxC5%$#$(9YewI49R%ZEsCa%9=aPH8%JVDi#w3kaMQu>F9 zsBLEYo$1i}Kn>QXVj-h~6*hhfqCt)C9KZf`SS$IjT z3qIl-J^&eJkvM~yYCsLvLx7&VY;2tdqG!Y4*q=s044Ne(AMj+r51Xjrkz5`k2EmT8 z*qpr#6M-5`P+nAM)Q5{o)AL&v#{J~D4+hg7wP?#cU&2omkYY6hC*8rm@P?Vk&a~LO zKn*599Vvr@+a?9gz2x{#{ku-aN08LTyl~9Ide%#$UF<+8u|Jd!T1p*uToU2~D}ZWt zR`!JK85e)e>>sV^`}nHa8*0XSnLFxLcwjsFbP@KhmU0HGmbh!)(FuLfB0=o=7q(qX zFm}U(YyI1LW1LLjItaJik6U$x&WGNB=XCl*F6exuby|*dO;z;`IL~zOpg<^nw3ID@ zPzI|h8)SU7B6wPyJ&AL+dTfKtiQWb{=M}u;5;`J%wmQ5)`l2t`P;cLC75glp#)AV= zd39&2UIfjwp$?5^tEJD%j?u5%P_y)z>MN4^)rOk-W~!KtGDk~O-8RZ*aYKh-k@;?% zEbl&}H(bV%Efl|~@{M?UuTU>-#PQ8%)n2&bc0;l+9Yu-gTlOe%PW`)4*2xVW3crQ- zupgTBsUqZs4yGucI-BtJU=0Z9$uPLS(A$H;OG;~MN@_YbNuxnNoCeFG?)s`>Q}rYu z;x)7SjJHeo9<_QC-cnfsPkl8EW~5g{h4&sfd(Vgx+hOm2)l|&16+Z@Quo~SQ{qP3j zAt3q>Fqng0I}`;Zb@Xc~LWbcD3yZ^PAEJR8q!vwu7!p2yx`4T8Yp>1H6{SYKA>*Ug zXst9?mDcVyvX$IA;|pWgNDJ|aD~|k`FE2I=8hc$CqFq9OwZso$68w~cA|eEw z7uyno`&=1XkYJT8**0Mug4ll(-Zo(@rp(&3AwaR{|z z3HuyOp=JwA*?Sjhnpw)^bDDifUx=S@J+LOBKZCbhY!K@it}IaFbmqmX z+yhc-zo`5JGBNpVAkVn&lvFYGR7cLZb4wQ;koZU8AB}$%{Hx+0gMT&rtK%Pwe+~Q% z{NwPiiGTdoMF$c*bC<5mPu#jLzgF9m+7k6clcW|AZ*E47!|#GhZJN{q3mik6CbiSu gx2uY#Nx51hbr?>305l;JR(my+ti9@q%%t@H1N~QmRsaA1 delta 165898 zcmZr(cYqYN_fKYbliS-nxT74$b;{9u@4a`adNct+nsiY>IFR1Ek0u~pIwD;G6_DOk zlwL$Ys!|k?^838Z?kw>A{gF#HpU-=F$z(DwnM`i~@4a^a-fK!OS!qM=bykK`6BZXJ z{ppI@k5g72%N+e*SY(BPrH9|PM&Gt10>`c`w=H+g`f}8kVvXE`v|K>zTeu6$1zWDP zaQ_pFpQrnppT2(XeEhT2Wb?D@WOu(9{Ji+3`5C#=9UCK8QvN;e7`3vo5^_D&-{X$8 z)0?RW@^hK|Zy4N+KjN7jxjj^*jFwi_hi=iopAeSKp!Iv)1yz}N5X;aXd)x)$k22qT zw1iirOp{?D#eBm04}A3@WPYYXd)-O$XL`$y`s{UQ_pyNVYxrWXJ5e5`?>PFIF7I{6 zcKDg$3*WkhaQz$srMso>@QF{H;p{t5`oJjWLT!AH)D^adiS>+!_ZK2Pf@O>V4~_kYmB0ZDd$I6C^j1 zpLJ2{d3$_9t^;G2!!oUSiS9aOd_!q}43u|?3L%ZU*89;^xx4*q%#ZFB@){N1?~aqV zslk5GZ*yVyspo!o0iQ_^_*ihpiv8}~5y6bdHtjNK4NUF}wy*53wQ>1wSo*u)+^G6< zh=vS6)eXblglk|J_bt8rC)6_mU;&5FaE!$zwLajEE#&Bw_gQhc5qoCoeoMWg3nYd( zQmmHkJK#<%;gn;fWb_CTDADKAJqLscxf60n-;{lRz#W&$verfj2p3iMik3dx%A5GKATh!gfb4v)Yc|-aOn;ALu^u05ZXEo2~KQ!N^yFS20mV4Po(T}>G19$Vjq;q0>FwfZscuzze{&G=$CH*tf`Tw;fLJ$ z(LXkDbd4?^LKnJCFFCqKiHA*8(T>{MQK}s+u%lgebkUAp9(Kn-Jm!cy@s$qtn5rEy zh4kU*8Z872)^3ij(WN7Sp81&MQFm-s(@qhlLrwj|CsMw2>$`=}p}a$cNQ+?IrV8NM zz4$yi)9)la{A{h5xXW8W#R=CnbN+>}EkGn%(sgawi9d{?ak`YQhU(ayUoa64~ z*BA$pVK=Vb|31hRE?V}Ko}A-Dg*-P@h${$a+{hE|*sA6t*yg@71o!=ErOQr3r7{l_ zB0GYqu)jq<`x699>o1~EpE3X|83Of$B5puLwjuuZ-C*Y*Ibp8BofGb)|G78bzJOu2 zz1AO&#@PQ7>N0$4Y%6xsod+u0o^&VWF(#U}O7~v*5Ycj-=hF+)+#gm?um`dP-ybrH zzC0P|FK#*rS-bDJxBPX|-NucFU&CMBNp9JMdYyIG_kErNGWMU*`_H_6)%8kTxH z11^4Sv8o{=rAajZ2x-!3FP=nj2^0B&7Y%Sk+|c)+_+4EzF+|ivZes-P7pGx2JQ>jfbi-3I^)cHNH)WJ1 zQhMui>pkKdFn?q{jK~)TetRXFa+v--)GN*cy7mTq;}=NJ)VsA3PXUS9era(^4qgIi ze)Rd{Qn1;sC569)|;ODS!)02QX+CdW#7*xuHw6A;;KHMoAayr za+-$-g5rmDiB_##ZjBia?FTFYG&AC6zU_*WFY z6|QRH5kH%=j?$KJHBpYG>S@#{8A^xKs8|*1LG?4z9i)-9A)QJe{qtv9#B%o2olgs)W=mAP7Cal2>HtAgx=OLquP&dxHHTOW5$LA1smKeQ6C?XKS1U zXhuMx&<5@yt$b^>kzNC6YXFw!A*7dKAkNT7S~vc)Rh$6+>n`bnQKTYZh_TJ)_SggN zU}<$3B25J{?3N-C!Ee8@_y+46A+5&aY<;DGSABysXcsu+rL|{;%jjtZ{C$U$&*&L& z0-R~m%9P)2lZJvYK1ibN5vr5d7&j0Cv|)}fJ(Y`8d9qAq`9AZ?dqjp$tc-nID^dSD zDc(k~7?Lw-bfhX&d#)+QRB4iBoxXvG9ewkAk598;y4mQ`7V8_qu9CxV>M(y6`` zRx`8ES2s{-HEFfU4Zo@7_fm91uo#nH8N%uxFn%|Z6$dq9#^A;gv zO;C!?r9+?CNomrn1Vs4}CGBKY_Ql1u|KglWuw;oJq$r1At)^~ZC7V)TzsAE0x(#&z zXsI@JEvTulPy?5^_Zp9(egoQ%hRVj7O6b5PPIcSrE&;#w1}AWd_x|oPdfa=YNQ+=M z#vW4x=Mwjvrwl0<2t|V=YM((Z!oB0ksJhC$)GMQkQF+_JjKVY}Bd%acq=gP#!8D(` zMS0|`+AGCo1k0uxPT&e2x@Q^AG2mx{9P&n~(I{wYl&UT-(63RrnJ>_zDAhXgK86I5 zb?GKcw5}Rg{)JmS-G^rWQHm-E*8MHLGbxuVF{gTk_4C0{5qD6EHVE$_SUG8Wj9Mz| zQ|VYJu1_su)e711vp5wcJ5r`NRW`00%cp7bT#G?tJT-Bz%hHFXsD@y5qaJZ8DU}(r zx1n8HCdHsBo&?MkL@niYaSbeyNWo27T#SatD4$`6IaD z5iA3x>z!YSL90Eta9QUa!jq{Lp!N(8r>U%`8?BF5c@dq9S1nWu#(w!Ol}=ExbvgZt zr(C?S)Qi4$i%v|bepHG^2$n5?EZdzf-azW%KZe+(t{{A9NVFh9WtZJ)PlC#a=e3vOA_Ia^CtP3e2^GcrNWEm76dyBQ09Y}`yK_m?<-f%|qIiE9k^h5m zk&GPK5MVQh;F>&MisFN%o;4;+%!CE9C$JA0XM2UWP#+X9UgAj_4&m_tJ~JTgPE<(^ zOr5xzVwqK@yIT~WFZG^g7%+~4bUL6#4q?V}i?3wy1v34efBe;c2*%4GiwY#Eig+mX zNK%>AWbO|$X=0Kpj_8LZm0y;lzmrr9qOdF~YuYMMDnm|4kp{skN9D7qgo?Geq;w;{ zcZuS2(_K3fCbqJg8er5jtROru-NiZ{v5eu4fVweUi{@m(om-AIH=ylV)LU{Pg=K{` z3z@f!@@55W(yOVilm3djfm6}subhNtdVoJ7=klrHqIz#V@kFSxV&F-%?oR0OBmMMG zR;V#x1|zHKhpeh%D%*RWfA3*tdZXhlsmt|NhWePHgA9eQzUmUyo5)CCS4)Ir?wB6I zI?hlZ1GSKmMSgILT*xjOfF##f6f$^Q8QG;PoYUF>n+6D}w(_ccsj7F78O}Brf-U&~ zgpUKHR}JVS^`jF?OawN|!B251-VV4atFMxJ_nr`8tp&KvA(+b5{%CZFXn>ZITjV>B ze4=Ki+e(Wo$k@op4Mt)MZbsWK4WG$B95aRQNMj*p zk}Fvi%+9L9F{y!*>8RSL569T5ax$W*d9uoqJq(1#L1spmPgFmwPjyft9gyxeb8fQA zoFkf5Es*BwoQyo&*DdA(U4>vVB-u!G!ZXP#Cb!8@EHK1et4kTKzYRwe8NY*n*O5^a zp95`a=m}IVhl-6eX=8S^w9z zCmhhGv?ix2(dEZT_`#pl_uVmZQ(yXY{JVv(pov@iYMHo=uak+}`bPWX6()YycfcRt zGI2X!czTv^=PO|1_P&PxxHr|yr6x!>ozA7|$+VOsx0=!{V@6mP_k3uGi2mAhBq~hI zJ1xa>1d9=wWZ(@g!$kCVo>3RH*a2vt1Lt74e}0Ug(MLV4y;7Vq5c%?`TygmrEO%gg zxJdlL^D`P!#+;EN8Ntd&4fCkPa?FrLm}V|;;@)&W-whR|kkJ~f&W7nwLfSSfEZq2s zL=oYpm3dT>tU!klrQvK5dp;aR{pxemlRR+s>#$@6ipi^DYnya6CTZ?Ti36qn`gw?G zhMeTHQWQe43}+I`^m9f^{q1p&;nW7+)Np7>UX_??s4OhP$2STSi6v#a*!Dg#4U|O) z#?r8{cwQPJr=-9i5q@U05Q)uX*v&gq902olfUN+VdIiNeOY%m#u<#>Dx@mO z7@Af{RX}v25FU^*^sjtzxg2j+*&UnDGIImB%;#@fegt@Pi0+!YK2=j>52BXV`RgTyqkVxMz#U(0jmwNVX zAr1k2j3C=n)*`UEJ+&(Wo7>amBCxqLm+07>dzagA7hVCsGaV}ex4H+FDT*gS54NNq zr68SPr&;ouy9F@RUY71=*L-3J(0$BcNDgJZ zkioA>>t!rF+H(M}JA_e8*l$I-rRaWBS{)~chz^B4;yDv0P?2IPcm8Rh6uT-#83bz< z^R+5&iSAFaF1;~aa1l)ay~FT)8dFRalJjX>F%{d|ki+}z^@;A<(lxNCxdWtq0X=dF zD=TDhpQZ1_;_{yZc-ew*24M#td9*7O7LQ0d2zL%<9b$D)@mz6_kNb1KH7upUho>6L@|y=R`Av|JYUvLepi^`Q_=!W{l>CNPl~B1;S(`K&XVIXxtk)=?V(C1&p!^Wn zrySYugQm^0bi;FO+8v;e9malU*ed2&I^T~_k>Rj4jV>nt*E9_{$9o?{_kTM3#Wk@B@vZ0^`h_Z4oGM83(b9%JsKFg(hRYmKyxg|vx1Zy)*FN=xJ zX4+cTl=d4(o9Qv4(xwY~e~$Nv?pVLiyb@ROC1gCe13l3D$pZBEZ7#iMuvf@fXED9lHGV!Wbd+1i?e>bwH_$5+@Ziaf z0Na|BH@1BYHiYIQiZ?>uviWdZ7jx_JnbG-HfxN*MxKtiK%Vv63-qa$l0=(GGRI>uw zWixfQqp=l?&b1W`^I!#|`Y)RqTMOZfnjofB1>m3((h7Nr-O9 zvDDwFu}z>#l~u8LtP=>)r5M&9;#zrrR2UCsD{$UtUT>OOStaFViu{Cm_7py@ZP+ih z!o{bYy$HNDhHFT4t}>=TRMaQpnkSB- z3RTcby(y&%8gdei7ie%qwDzS zS#>nJk22N3Dp5mfT|>pxXc&zmQt-zq`1ns=@h<1e&i_c!7r_dW()c}&!R@q=V}MOJ zIDK0~wav$E@Cd*E z+d^%jkq{VfglKz^w!EcFME_yw5UC?t`YxFV*B+U` zI&-v)#xTXM-L}uYBD#>3?FZUi7jEnU`nRrHj%YzWH9G@qk;hCc^z*nybY3g^9@VR_ zvMU>*{`FO&&!l@l$H0Az7S>n!U(5KdK9%>1H?X0K_1A&5ou!4yuxtDaeTQ^Dqwg$R;!Qe$ zi}`~~r(2D2;lNAGmJrN^mRvVThcr@gw)ADn(8EO8mZZv{oXWv+c8j+Rj)`&Tdf*A)BL`nSyG zxxmpD3Tteb`8e7_^$?+5>8M zi1^2gX<{0WB{Cz}{ptYKYNir%aB23sO7wQ+S#%WxEmxrlcx{+#6keu@%`iza>Fcxx za&|$6YIc8wH*Ov-qNgiQ^@U;LTL>O;gs;=T5C{mzHCILK^aEM>h|26?5}F zpbc+koJ9tj|G(ye=08TsEmW=yOGm?AwnTKTSplmiIjykk)UJg}R=M{8*+Uars6zJD zF?Ze``mu#7V3)gx{sWlNRLtCw<_|yZxA%o8*yMJ2U95sPa6ia++VJ9Un(ye34P z=Uh1<)DnbX1xaan)J&ZhZhS%ygQI1)jsryMLOs5!SNzU$KOpx2i~UKDQ&fDDdz^U> z8IMdRmu23nq^{M?>cepl^;se#f?W(3E#fj42@$C~b=R+y$PK8p1M6gT;uPxKQdNom z57gm6#xnXR%lR+Q_bt`i@(IPZ!r1hLd$M_cx~Xz2mH#c15z1}Z_k(u5M8Yrn?`iCb zwhXgGCj`q7BAC$L5U%L6)#0fO0yf3LkHDb_sNIEfl#z1NrB*7YkW++o2i4ry%kx3z z7F7J_sNrI;G?=F~22CSn^t!2GYZaHu8TOFanpbiX%1a&JREj8;k*&im(HX%u*VM;m zRhD}Ep8?izFeW)HQz_%7Cp45g^KX9E3J^9rB(^}f65TGk*&6Of99eDfzN7>%RJF2W)?W71x|m_KsKq7Aw%MpGe4L=|kaOn==UbD2HQI8%~m?^ZunohGJa)0uWX*iH(-I==8g$ zZB#pqN9OwFqC)LdKD!5$;c{F%;w+Kyv887mlHw<{vaBD8_oxVV9Yh*rm7xjkFgzL! zm1sjdRXD3j*I*4^qoJHj$5+Oh$1zBrG1BC2ud)|6Jfoyiu(l-%Q7l&TFTQkx$|6B>d^tJxY0PBQHYRO{0--*IbnOy`XRfr1RR1 zYlQiMn2^V#H=Yc`NP^aDfFAn}Lg1o|VPRW<)*u}bEZILmoO@4|me(n&qpB4Bk_Y-C zn19KK-1F1M6%7$xOU7KM9vv~dzofApF&=wpg&qCa5e?^|>m5~9HN{NTs8A=or{(l3 z?hC)CEz-m%zFS-}^nZx6C;yKX_#KY`M)`69V9mSUz*?ar!G>J2XL919j|@QX(z z7Lt*x&SONM7j22<2$msSVS+Pn&Yi|B9w28o@Iww~Wp*^Z&A|(RHCRGq&Q;*|9L_%G zg!B9O#1&HKn53vc7rc)*Wjvq?T~t0hy`Fk?QPosEbQalyws%oE1L^Bs&<^!TcU4KH z4BVPKlz*XNMfz3fOdVJ%I>r*&5Ue06HqAzth+CDR1-0#}O2mz1!N5zFK67zTd;C2XcyC=6 zubPgtni3e5${|>tgYdj`scD7S$#643Eg2p_J=&q`z zZZsB~7p4s(z3ak7+IUOEAXtn@Rw&9DxN&5y4Op5f2&{~Q?+M~fA~$Bj>Q_TxDGq)x zsQw*YrGXMX01a{Am8JjZy?EXd9#hL%AjwlKZoiQ2r<zZQZE-3WYVkVAJ+mNE(-P?3iMRj?DTzV(Nk4P zeZuPO*Vcn0bIu48sfm^thhQ-x@nJyVDh!RBSq2`@0$?j0JT!<8i!}T9cL6)-;1P@m z-ikNb<`EYF-F4uVHQu-i3w6DD@Gl@0l7vQ!WAVUi@i{=)o~(?Rf&;I`S5TW?Dn60L zY_mD_=6muLG^ZEdlQXo0HDqOut$UxYfZb=TdnY5g=uR({rD_5E{xit*zb7w=&2hzm zxUw*lb;OzX<3}SWUVz(-+;{}53?mEZt==l5kJF|lF%b6djST}P!^j5Sl}D9?KLOf6 z$c_xizpDOsJt{Z$3IJN-z}2}7dsjm_sY7G1$#y%yy$-=tae>@~?pyu0^ouJgai6iA zS@9^y-^**-xkJKDJGAUmx=e*#SMKA*+*TJlka=mP;{MG8( zS0%=-K=)4Nm(va$c<;Z0mh?r1-=af(@#Gsv*ZZo@@*p+phavMIb?c`Rb06f&9A^Up z!}QQzq2d%W2HQE=w6UKm8gCwU3E5+DGq?7Hg#8RWQ^QSe(OQLMx7gkPkB)8C;33^!zPLRJtpzZ7Y1D3`#*0^%Ci@>@002b?J|HbeZV$ z{-}H=+SXqsR*vUck}GCOxaj${)Xj1!vrKF4f%riLD^n2PA$6-{kKlD(>ngCDjK@>v zk5qG+je32ACE{!}?jvjs&P_)@f|y!_}#J@Q$ zp>sh^kW-vFBP~Okp)2giOP6>saycxc#7~%|f9(PHq5{C$4#8*`Wp;q|oU2E-Jd2*g zCUgL!hr=>z{H*zUe5$rdV?dbhkc_H0{ksx97wM!Xp<+3puN=4_UH%v=&BplRpAAq& zQ#dKKX-==yReo@p=1jDfc-lC49Af0N`-B`sMv!k--I2m&%-Y0r9 z=LQr!U?sN1E3EM{X2nFyW~IrC6(kEZcN?n!iH1PPt>$3lUb+tc(_OO{K|^_sw}*kHQ;Pz z9%Hio?7&{7o_Os#?rpc2$=N4CIB!U#2V+aC;WC0*>p@HO{Me;quY1K@=0@ko%n`x* zB8U%m>7+VJn71jVfK_1J7_(dQ>Qm2QF5P%_xanx}9e`~e1%ARvm%jgv-BIPhxRhyeiRs>j`38uE+*&3F+^u9e_ z+thafcB=9wW1UOChn@e%)?olgGr<^XHlX%A;tKmT8s5<7$X{%P>EsY>!P!VLshBNn zq%x^0q2xxs0%=-2)FQQ78A!m3yh<{((x4Ah*V8hU;d9=s{Y?r0#I3>^)bA$Kv& z>^M$sq^Cc3i@nIO=7aWSK#R?>OL<=(9TqCAoxqMdxPS5Mc`95&qjWFD55+jVjYW~hqJc8E)g7}&@s8jVZ)2tNX8p6B_BEWw%x-59EJnzz0FSGt*psrIUg#$&A< z4I73%*-dEHFf36<(&k~fx0hN%|VEnMbP6_dAn9P0BC{y6XZ8b4HGFz3qZMJ&+> z!Lmt|`YDukr_VmctC->R>!%oIhEvpVJmZE_wc*&EGnVx@yK~xAbBi?)Z&nn~#IZDD zxEfM%E;Hg5*Tbf<4%YR)LfioO0KsBJeqrFBcWaT{)mqsxOz2{kNQYp<%c=4Rl~Eb$ z8frBHd$%^y7b7r^Z)EA6wA)GVp^HxXAiY33(QpnjaSs=BQWhzR)%ZAcXl%lS^M1F&5T*q;tQY$UdA*mypvH)8wO3t(wV`0bF4W1XY? zD9jtUEWDLyGYXx@qz}>%r0d%G48BrYb*Xa}(PAt#&33dgF7FtVO0mgxq;4_EE7pRr z&5-E#QTR^d6lENZJLeP?AB{Z+r>NyP;|McaE~s1Up)7M~Cg`wjG5{G?aXHRBs|2q9@dO zqDuN7t7IGA=<3pIFTtvT|aCdU-KsidTc1|a?-iz64KE3Y_dx5nKo>K zcETrc$y4yAE0~ds8X^P4o>Nrrh+w|m;aIWqE zn|))du_S!j8?`9;W=1T5S-TIwVtAxGAhBKB{REF1i34;NW9v@eJG;-RZ;(6&Jzw zzv2sjMbBrzw>lD!(p~K4dGEM%MHMa%fqEsXEH_MnN z^gC0h-Q(_o`iSXICZeQ;mZ``wJ*hX2v#5)=-w4JC`I2$7 z66HOf`DstL@Jv!7Kj2b93cWv9rPNNtHkZAI(a$^Cty_PIyGpJEX%iC}lo^;|MlbIa zcg8stg^1y7c^r(hK^BG1!zQ6Llye?l3mL&Asy|P~)--7|1lnByi*~<#=dqQ%Qx7*H zf?ZM)mt>|>UggpI(xYt$0vu`xv~C{uX64|bS0H08XXc~xC{5<07r+oDd~Tu&pQCS^ zVq>VSlP*a^KUdlEdFkf|% z=c)Aq%w^8k2KYODf^-&>{u3FZ|9E_;k=)06Ymi%f(h#*a&^_9`0JES+^dHzAAFk<@e=INMvySD#EOF-o?>mNhZpsLayzhQxWAE}VO92oiqfw^Qr4jX z3su(q;o$WHG?3x+Eac3S_Tse;8!;WwY=$$_{)Lz)Wu_+!Rctv!cIHX#utWMkkQ5d` zjUJiE%A9#pjpO+09#{^8Q=>27rLYEjI+REQzd$!L8Ob#F3rvShTGI}sZDKOB6X_B% zau|>cken;R15=+Bn3mr{3IEuoBrQ^fvpA)Q@WuEXBDp0FHaZd_$~U$|eFQ5#^;v{D zQF@xS2y>#ml)4ymqP(5(+j~0;^l3r1(0fBa;vh*_CyP_pOs#Al6F95pCebB8P4qI=t~T4=K$Vz2&@8@ z#4bhS7@aJEj7m$nB>$dinWDLnpt83f^G5GTeu@j(vGEgaIx6y zlbp%e)8CLw+6RFXj*zL4xs`a5Gqkg`Nw+}w$03fa3Bku|$klT)G+ff%g8oR<2v~&ghZ_{{w1CHDIw{2F~mqtUrFEMo~Of|nW zRt@B+8LjyeLuoTQ`XyZE!gQabW)!s&9(rLayVA(DJ#;_@9I>|jum_04Yp&p&LGT!uXcKw#v(}G|(tzovL39C%0t5;!8 z6V%|Z-yb&US#9jhvl`n?42Q3Ia8A<*{!kd1EOO%z;vkE6>SqlKJa|mX(Q=TqBuWh5Lj^9S_8q);HYmAL` z)~Li+TB4_rFOY?+*>b&k$>8{P)nyb$a{Ytz=XSZB*b z|E^VeGiOTS%{G~TM?(%CW`%{d^?RN1RCb-pn;Oq>`EkFXvAow^z8?Wc<*n@&-kYxQ z#`%%!%r~a@#jei!$ms!2KLqOs{0h!DO4q{qN{mkeHp9W4`NplWSlR-<2GGU;tnH^+ zW4gUg*3Crtjlz6J=__Se%+mEeplH_Zb1HlqvJA{^&PA6* zMtRP>L)|yv9=t;nfgxIBM@Kf`&N9WGrMpi00j2#4?#vz5@VYz0O8-B1rZKho3hvBH zh6C=*iT3=7+QjyF4}xGZCb1`zyUn+D8SPW;dOVWQDm5i zgou<6!Fbump_y_Vcc%QfaGRF716J@6Y-3Dejyuz`o=21hR@=cdvF4yV)0jTph>xnK z(e91-lw}%&v)J6gr!1GBc*J~T%ps^a#cG12z^5$vVlXkdZZL}b8efWbg@p6Ib>B|6 zQ14;I5J4`X)?ecuSwi!^#_+v_4t|Y$d?nrcTE(PY$pvSM?iVg9O_1SDD0-6`obnB4 z23DajU%??I9kE{!!D2*yZ(#o_bl;_+Vh*6C4!ob?fIGG--YYga&{4X#NmXm}vr%B2 zsF7BfH&kTqgyuxB7?Ed!@C0jBF(FC;s_MX(g76fpT|psQ0BY~R*J$cyY+o>%uCcmH zv|+Q#mj5==Yrxvb%=@gv@yKpsAmTy~13JktPJ`Q`3dKKWRw1)w9WV9Ta&Sa4zi){| z1nWLE*aCNo70DOW18HnM7`p|ZZksGK*1ibJV~^bY&*4+gf$UNv&w}oTD8TmRic5W9 zc9_@>Y_Ef}{eHZZ)EgQpaR%5;2WNR{O0kt-DZ6a-nxoJsdWu8eAE{5aaaU8P9~X2%&aYm4IEmpoTyYC_kx zV<0n}tQ58b?`KUq7Zuo{Vhh>%j+ng?UBl8XUwTEEZkT5v*f!*{4H>XQC6=%?1f={& zH=0H4R+hfF6qjT&%J@zJ zF5@LKLc0g-$cij`;ej2vOV7Q+kg|hN&>^w0ei9rwPtOpWR2zh*hD1ZYfxl#IF%23= zUw(sUbp-AG20l>)J^luFbur5EEiPyT)!?WYb@~>W5i|o)YB5tn#qn6UZ-Ye=?G`0J zK%Lg$&qf5(X2NCg_wmAXn^$yX{0RR1#JDX#sv0Wa8~6(?4!|&Z2iSuker*&c0RvsS zEzV6ecz6#>q(?~gE6A=fK^yMU6GL5g0r>$IMeySl*uV)cJvcSQ#_I!X62z}82^GoH zU3&IeAxuMj0IY8i=Uvsw_(FETFQGO*5!mz|R-(TEZ_{WLu*{`L^uvw(CBUy)ID#(h ze4~B6yG;8g?=nqU9Z{TVgEagRZrLiH?+;=1xo%HOG)I7fp}Wk5*vL^ay0#0?$6};+ z!>x&+yc`vyhPzevRKAA7wVv(l;?@to!jTP7AlvrB+6;of9fskn+~j_4eYKIx6d+T9 zjbz-GH+ZUB_kD;D>{xyQu%$tH{^B=zqFZnKRSSM7$X&qpBBc5i7{XM1vO6kV3}eDY zfPXj&%xA&L3*EY!7psi_Az$_O7cTj(#c~8&xZbTxY=pZI2Qa5YC}RkjrsGoWbL+Z) zV4a~nz^Y8hW9(1ITfEDD>N%7b2eWWLY6Yyjqrh~XIGXz%W?ZJvn~XBF7a3^IKfZ&5 z9nAON5DDKKu)_CvutiXZ@9`~+;S``r-&RYZ!iO{FJl zpJnQ6^#EmvqtRczH9x#j-(Qh|e)I1SDo=bAD=N5v`^_Dt|0R#<-&R^4nJQ6*J*J8& zdrW^DVn>ViV6E0vEEgT#qY^XPX(+OXK;wBf`E0MsDTh(6z1SOGuQ{-4A3~+VA7^j) zFdDiS&y9LCcQ5vaH>T}&bb7B!3~dY%JTj__CS>hX1=BR)$5r5rlqOVhAAG{bTx36b z7wKe^9)qV?aEtWSXel~?(yhNG`XgA4Y2iK;MVj|QAZ1NW=( zDNDHgfNPa$Rj9c2F=q1!79(<{f&H!(<_#ir0G3Pu_AFcG;!iLdyZF!tf>PeGsnIC1yFU)uTdq5j__0WTSz0 z9)xSfif~5n1*GK}dU6o1mB})9>b0OeT&pk2Vnh!egr-6;7RcL7a9pdwSnkUMthj@- z{Xy5t`;JT00hZ$6EH6zdj%zh5(@1Q~0wdL7F##u{u03RIJa7oE)fxKl5N_Qw6nhxU zUuUTDVJv^$r(8$iOWmg~N8n4{r&&kfOFd>29AE0hZulbe2IFf21dB2Fm8U=tGwDmn zl`s6hRGy7na|1TkzHuVkJ3di6*8Ci4o_6si2@t!*D#l@-%k>*B> zh8~0W6vbuqM8-fzS17WA-qQ}e(=?Ob6LleU4d$B^jmF+AOkEv5nif$$bLeQ=BOw;643&7Z+$KE=Bw> z^mhc)Wc6?_ZqhaevCo^mbm2-6Vff&CuD1Kv}ORJV;k2j=>e zy(d!x$9tNO0}5s4PcdObz)Y#Z$v4_}z)91-Gf$eP+=M93Xb5;uKZIaqb_ay_*$VzT zX)Z*zpAf}S^Pk{7#nDGU;c51m=5iEAyMBWA#MdzBJ?)qoBA!5jJT}}CzaaSADd0W* zmS7hk?*V(nxGf*>p4v?G+45;eVAw$L%Llxtt4nd-9N&ZmffYwc^(zQ?PqPoYL>DGB z1lY_`;CN3tQh;?set*VH2ju%S=si^$h-Hll0LdX_HH3io)bJ-v@z(&{$b>w`{($#% zxpTPi@nt>??3|;(bR9SOet|b(iZmHnsW>vwoXviL_Y}I1$N;s~DR@sN-;Bw2^#a~g?$Yp{dW=FZMzHH|47OF6iUz!= zjU({Y{cO;d7%Ck-1@DRV2EC`)!=a|W)&)@RIvV}ei~seF`qo4S`px^l!h15KkK;W( z?y61ywo*r<^>WeLUrkjG{%ZQ$T{}wm8@wk|u?Q;n8}?%O)9rp!b>l7;$1Ch1|7i2N z(>JADm?(hS_(o#e$wk`#n@WyiuREf6cO~j=%{vHbpRYJR)+X0!VBDty7`rS6YfKeR ztDJHDxm5yRT5bLl&x3k!dRib@{b|@~9B0Q2`3chkTlllA2oawmV=`EC4AY^Q4+?B& z2ww~|p>wBkYxSe&r%~fEl=%#NzZq2d3?5xGsMQ&0pTVMYUe%t2J!A`!(RG|9K18sB z6r;UuHUH-dZE4FHXkSLZAxh)r2egDh#@rxp`9Vo__KIBZwh2- z+f}sfhpT8T_IwE?39aV9CjR1K6XcvP9#+%Uv#LOw<189jn4H)QL!o>Mnr8xRWlY{+ zLf}1X9c;spF~IPu(U0FB4cu9ny!0i;!m5hB+&O#g#1Mo8hDc+**&a3kH`v0>F zDjy;$a6x5@Q*WV6XIJcnQ_8R_OoD`>4=&)Gy%Nj_oU@mZ1HR&Hpi2-ehGaR$16J?; z&MT^LuG|U2f!9d^tEV49Cp%*>N_$aN$j4Uam~4rB2v#)f3!KFh(cdMm0Ide34x@Q! zz(v*7SBuNw%OY>k-HSM!rvVkdgxAvzIKL@1x&#;2q*JJulm9MFzJ!x_I&lHcNjyE; zy2P<5Sb{{b7?RzCI8Nd@Th$}(0ekA;eHeF6;`tEUoYPLlXNU;4{Kr9goW!#gdvgi` zs~EtwWCikL>Tww_I!%d9?TqP{Rgr>2IK2Smr7SRlbveiFl&Ihq;~3usY%k+e=plsC zPGOpJ+)gwVzoHW3jjVSVA7oS0(yLqHw7hcDEKw7|8bQ6UsHCh+k&mHBcu#2@;4#M1 zOGo1c(GYOP+PsZdRF>4&Pv?36lQ8iaB(2?`>@ze|zH>TH@GPIxmj3zUFq?E2%!kZ2 z)&`I5Ii_uGX{O_5K=4=E9P4x0(wCZqq}mD!04&A?TS4GJpQW39wt@!0ng$gZ{7*}d zK7oIZ!sYe=)-Nc3aT?BIx?^cs)+@LTtVzITIP%UBKzZJxlfPs7J%#@M9S^n<6nPad zX6z;poB=eCDqh7D;|2}AiZg(2P_94JY-L(^5&ifF4k7WUU;cq-rAa@XiCb(D<-Uef ze_qXKcMTt7kDy7&NA%4#occ3@{t&vjX)zCsgEhwpV-6elq1az>P_V1hpxMH zhI@F9l$ni>ED&&G^!!srW!TQewM9l(lgYnU(Cj~P`KQn}jz-XF`_~iuSLT}rD}B>k zw)Z)jLNhsY1Z}dhUl5_|+NS|U+*0XU+x?iG|L9n^zK0JF_RYZsOEVWY0)pMo&4-N9 zAt9cF!!Y*dL4I+@Om)~y5x!<86ddt-R^xxC)B)Da;FNmHl)m5=&J!9z2X4W^96@&x z+1KUAc3Y zMO;(+h@x~J{nLz4VQ!%MpIhQ>1k+Twokp{;5x7CC9Yr_j1kyF^=H{>1`1B#qOOG&@ z`5ff0vkoI?dSbXa5qX|R*XR^3o&gJ+AHcU$iMxR^wo}Vj(nDWKFTESM=XcZjyEu5r z=-y2c_X1thn7^CKAj7Vqonfl!E3QQ}{|BHpTC7FMvf%=(jv%0Wj<^@NfQxADJvC46 zqq=|LzS_rqv?>2NOuhfY@iQjlBX6nfYhHg zbPJoc1&r?RrC#@OLtLdP_OEa4 zU+3*#p$`m}$BydQQCB+}XGbgT=->mR>|gxKdX?M7+`+@P;kb#3@cCXW#?HVcfo8ct zr5>U?nHIT8tsknwg-rS{7Bt&mhGn(%fAEUiEy9&Zh2UgIm{S;ncRp14avCXzEc@E(XEw zH~&!We}e_|Ksv8ofDz_n$A*o2R3W^T+plA*}sPNgt9dF zF}AZaW|L^%V{AD|q9c#-;cF6?l!Fa$cF=zOflJ^7IduB7P=Ae!2(rrl!8>vB0;x|X zp8q@t8uF!|VQ*~nn!UQS+&Vrz7zqG#2MDqV7i1Goxg%XacuHWWDbP9&84$VXkB zbTu0P6nj)Eu!h(7sIb!iZ;#3%I`dT3Y*UBfz*O)=AI#RJcNHF+2o__q5fcJa!QUHT zJjxBMn1eTG+?fjg+5{tC9e~XYfl~j&RInB6k-d;J$PqJYovC1HQo^uig0RpbHK$|$ zVJc|sXwOQ5+fNqJi~q3wWEPcsregBWVsJiN5|}`JdsB)frresVEzuakvPm@T89s2F zMYEn^!o=$s>ws-yd?3r42~*0dbbZJ9%);0aAU`oWfvo4)3^tJRKgS20-&4)!cuDd- zjd~6b<$L=2IlheC&kCG5V4Zw;pRfk=3k1Alc=%iusr)a$YwFW?ts9^FO8t9>P!Yb? z643}2L*_qlig1I+0Z$tu@&ha7;Lqv(7phQ-s|D0#;-F$#OQA&ofAglySV)r}?|(l-yDmSQcV9JHY$S=F;CURD2pQ^j}BD9nSoh;$Gq( zGa37W|ClKS4}!f#!vs_Ftg}QR1W?<8njuIv2iv7Ik-5sy)R!t>mOr@u3*^#^8vg@S z|L*dNC6HUkvJBxR#D$kCcd1)UGwVw!-)G|WrL6o3P09%!KT(U*U_VE2t%sD&G`0IK zQ{$NxbzGv!%F6#lEakLro8lIKLtAx_>$1QfGY9JU?4~eNnXLSu#8PhPOPg)tD3B)D z#2vWtgTz=qqc7!U*4s00>AYQ&O2b-bB)q>UOq9X@Hk8%|j3NjYPMv&ZB;3$Ph#HJ% z1(wUfosn=V+&0E51FGr3W{^vwp;G4wSgKJRFi&v5X)Y`ujG@j@L4v3T~Zq^ z$=Q9^_*?iMp95SRAo#Z@mUD;qK)JHO`|zT?@gBVc2fw_>HXQ=<1hc!cCj0*sQK(Bt z$*z>er4tcVwxf3V*gmJRj4R_Gfa`d4p8MEH+GQg?&qA=R>P3rPI$J(g`NoLIW&VF7 zViMhV>6)@Xm2vA>)t?1Fp_XnPW2Zl*LC8-v`LFN0yVovEjA6PQ^EEbWAXv6E7vzj_ z=cB`I)*2ADI;2mTk06XvClUQ+Z+{3dX%A*U!ovr%j`t52E&HC+Gde@_q zqj*z(-U)&A+hH^pSSk+#0gQ(avwq8&*jPFn*N-=rme~Bt#?lxZU=!@`gfERB zvR&sl;q?oG^^|L24n*J&*{*I45dtSg$mhUZ&|~9He~&AZ$!iF4z_L2H>EJQcQlZ0h zf&Sl7wpks~JiD?tKlw|-{Ga);jg<_eVo&iG?7h&eGjIDs*|aer zOm|48FsC!Gk9Ua`z_vPgE!G_D%rW%0SC_{UUcpcuQ{!U>hp@SUhj{q#5HZ3SQ)WBX z6%ec-DR3(Ja9%%20oKvrG&xi!<1~a#p}KTSeuwcRvX3y7!m0xcqPcNy0pB5i0J+6z zcSe2p9^v0}ARBAp$jlrz8M=%156iX#$2PUVSA~q3^Y)uiZJ#ciaU5I6ndXn(W1G-y zpDvX&g%#Szna|Q?hgo6^lzfk1F(N;szkL{5OnM$ghUv_9dJz>0)9+xFWLy~F6--@A zE1mS$bkIp}r<+Lo4CiYmZl|>2fsD`WjAG%sNWtBluJkP)G6>c_{0gpx?r39)!;HTR ztP|rWX(oiyo@AP{7Men*!gXR>BkQb%ei((t%kz-A5zs4VBPG1oaU^Z@U`sbIgs)Lw zAj`YcU$CDLSS6kQ0`J!n0p>9TYMMsBxk@@H3SWW37ONd7?+5gV;2Gwxt&&C$47W*> z!JNr#Qx9jAv=)v6G1}Gv+vI4oajcU1cDPe*1;+sX5>yaaCGBtu@66bod%zwA6$DmE z3#awk@@aSBl`MkafWRtg$jA`Ejbs%BR-AFurp_v9_ok^(?lSbhEuG=Guvx7^?GRL# zcp4`YKelwEqS&X+RtyF<+)?K;IKH8MSV7z7d=6}}BOeu5aJ|5n-fUit&SyoNo=o@C z>H^sKlO;kgM|2=U&(6R$%B%Pzq5{XTH=+KK8gpNR(85TK`7WpDeuszrRXP}{^S_p1 zrPKK^%`KQt=SS2!oz8`5R63o_R&kTorPDFUI*6a{q_>4sx5k$>p2cS&%)9m3Jw7!bkiN!M*~{f^3fS7-h#Je{KMi=4Sef4yMQ0 zZi>4}x197}6qZ59HnH>B!oTpxU)DjFzKoOQrHt8w_h$&EEcp*JoMqZ&8!^h11z7hr zg8YjHX29)i6te{G?*$nG&Fs%OkU=Nqe1%~Y2bN?Le}>RmD7|JBQ$$7`mEjp{5_>VA zA=u{Jq%s-t@H$B;9POil_OChiukH4)Ga1c=3yDH>l1fAwW^;~CQh!9~=VnPZwP+Qe zcz++R&t&|WiQvBj0_(Fo?g|@U2W*prJL|I%*i9!7A^#L(rfzI=aD8^v*bs3G*gp== zea?@cr9zo>T2!J^CY>8m*GxJ)qREKtOE-bGWiqy(&ZLv=#x?s#hmkiL&-#6o9IdhV z!mTuc>Tue0r3us%>AZHDJCm~l+qO2&#N|$(x*z8^BG@)xrEQMzRl2~!Mya`roE6v- zyM-`!%v}gRVPR9kRmzn)XhnUbQ(q~0qJ=YUa)x>uea;`iqkFYJfWZO5-_n7l*$hjy zFqeBUurZ7~Jw-T6vl;L&SUv}~#=(t<{mqhDza64H=SI`5%-Ux+%QJfB825}Ypzxcct&*bv)(-7vo`C4q&H1I>*Eq@+H7D zqxu!oaOzOn6rW&f=A-xu1Oe0rpu(6B5{zl%5_J9eTs#Nw63xfD|E-&$22$<<`5+7A zqK64OsTEUX0p=NpE%lN9ew9xY<6P-EhBZF~D@aPqpGc(s8*Uyl9tP9#p<<~|^?^B| zq6~|bMP_A|szkjKG1eO4Vl*{T$CNkenZLmh<0I-S_&40CkvR5fSGcJ0e{{WfU=>C8 zKRmlP$!;p4Ljoy40wD<`6zL$nHxcOsr1##1fHdhK%c6% zy8e~b^-nD8MgNAyM>vytx}OiD_Ayp+fDm%foER%IMZys*?JV)nz!_CzAq3aE!g9t! zMv5>x2Pv%~j9$iA5hb)Xjw6iK_?Gyy7sZF6prcqSh103vh;Y8YZmg9rSmZ==81)As zoe6quok^R!Xv^BnLAfx{$@a0>7}Z z7NENs6lE>!qrb&rFTM@Jr87j}d>lCc2@GGN{Tsbb;>!}8Hv%pJ-QH+pVXH&>P;SaS zxfQzmp*98Ko$3WdEHq$K0R0)@?uYv05-c8o5(9psi%GbKYUf%R_v@oEHNbD|VrnwR zwK86;wM8?FSU~|2#|N~uh*dI@XMXN(o@=nP#ofprIN0I7Tg0jiFEIh#ad&E!fZE-c z#w1`6=}U_etdiJkb|?Yw1%v5!f)!nLBxlyO$GZ4PkW5g`e^2B4J)Ak%$A>-EWp{%W z_f}?(Gicy&=18hr)OybtOUsK|dEspV@gS~O19>(*WxM+ zvNndnL!R(AI)@!7aFS0i8wOdAKMauK>;u*yW-n!F*C1>7Af-M6d8SCxjwC$UmGmMB zPj4mVNw#7GR&tWpP?cmWUn2>BCDA(uS-WD_)pwxOKaYLgaHhulFfhn^{a%1z`hh>v z#e7AplM&l?x&_q%+c}y&6jTiTwS<3V6+VNk6?+G%!;Hyu0sF7vOf8WC1%s@MM+IwC zWgzOhDADB_WZit-quPVl!{O_(L6**rV%>#4FJ`5tA7{<3LDtYYmf8XQuPnnXITbsF2Z;rTm~&ZgRJci`Ds)FLrS@@OVp{j^>MYk ztkX5fdK1?w80Uex#W?1@VUV?3=}`4Ilg&%$9O2BnR3^oWNf#`0^!g(kWc?x?J2M$u z2e?LzedXiBAgevvPsu`3ckud(F6Qrc4YJm%5+oJPm;&Z3SAiD*gRHw->4pyrKHz@k zs`$Y*$a=E7pYr35@Bo-c-vq!Q>qeZ}4`RSwF#l%2D~e4;hICpTgREDod%R|sF5{pf zoX*Q`*C1=-=^mZdMqs}CCIALmt0w41W%L7c2m_?(eFj-Cz(ANJbvBp_s=bMTLDsL* zJvyylgSnXjl1SGeYqz7A!5#wrm@F6d~?2m_Z;`3$oDy4+R;KrjyjcG}URF^)mj5p}U6 z`#yNDT)uvPq~wxVTN9-Ps9{NT#JQ+jNm(|WQPQevw4@^dz`Ik@icVDZQP%_Ev#AYFpIYcR? zt=vX_s#DrZgg3afH9O$lG-Ry<1-)fO)|K!E5PXAj=yiNy1SRJUQ^mlUf=RxaaZs*z zDMT>kz^@?~>iZVnB?Q`<=DuZB$@d9sb+&~6bPH=QTY>zM(Vx(Lpc5Ej{D)yq89()e zsxLu!0hEOpO%0*9%2?fug0!>@a#4`>m$8b~>Vgey?#|lfxRcqq2!T5+#4Mv1^PM&2 z-q#E@fT@PxEgbrR^Ma^yS$uKoLe0xsZyUpCL0PME$S?+u0mk_17R8Pa$Q#r>EL2@! z!Z7lbvkK)K&AQ!hzNx!#7cICsZUZrzs+Y6I#LQxZb6D=_w;uHcnE!<{nPbeS%jGa8 zN_feF@>WhATtSiLts1xrrbBsfzhLBgN_WGXXeq++Lf^^}IM$r(nTA?=2g+R*tmmFD zZxu}51=wkDE;9EgmT}Lwh2cZ)dQhH#^@`aCD7gYYx*VYP6)<@IL?bJpy|4^!AzO?v zNZ(e#%dL>)*u+t~2&l%KTu{-0Z>1Q7Qv`QXpMYuH?w}9$->7Vbh5N`4G}y0-RZI&$qO$n7ti#W# zbrmZzSkR9&aBLMU)Cu9aCVXB6#gmb6q>2@jiSW$T5&V=BLNRaS^CF96wyV^)D0-5P zNPFU6rg{s`bR*Uu7x`HJ`S&p$Vo(zR+PEN2j2DDs`Imd5muAoq0LHo?j^4GawC!yx zys$(d#lz*`GalQi4+?fW1b-1>dib_g0!GXVRkf0H z6J&6bXfMCI$NKh~Qjeg-Xa`;==3DeJ)Ii&A_AI(z70>)Cg;j%RQ8Dc`(q3Qf&D7oo z?H$(M{c5POS1G7E)#9rUF2XCo znKQURu%Yt+&fh2cS;x|_5BwG6Vak$IU$TZ(5K=AJvuIQe%pjzLpgsrRFn48?g_A=#Ky48ycLh zdR{#*YDr1wscpr)B?_b?&^5+6KUHfXJ^&ScjBWdHTAJ&QlqC}0x3;L5T3eE`vGyC; zI1NIgsFw6gsd%c?#IgL-0an{R9>pm!??d$~R&Pu6ROjbhm-5s@M^lz6*F!f}_I;2lQ~P>WWD^P306`Ct zD#RvUmfy*AR_&7?feG4{LIJ@55XQZk*kV*#iDv z7c)gL%|FMJy&OCfwwguHIq+|~m~;&qaTH$){|)}5r=daWHNFMGWk`^x?~lNQ8^NWT zdO>jjr2M}?S&d-N)ex8f-p7%q zJRz#54@HZbSdq2l8FM7cGnv&^F!E0S#8O-|#^(U9Wq}pK5BN1mjjw3redjbxiZK5t z@D2!{o;5+2y@Dc|idSBHt+h8&dyBQVO?zjw_e^^c?`S#gwT2hKaiZ3yBb+E<{j@q9 zN7-~Y0>3+ri_N$Pm}Pp@VmL{pv4r+%9k<^>kG+Dznu+3K+H0h}zS^6qy$#wstiAi% z3wu|~X|Iv?`f6{c_BLqmu=eh2FRZzi(_SO(^@XSNpdU>G7!?~o*$5g0Q|cx8)oKj3 z$4!CLc^FMwnp=r2HgTa>kgly5j9la6mth4VLET4}r?#YtYGEnVevhg<% zFEgWZ@m|dFMLfZysr-A`DfAPI=Hl;4;}bl=E2uk&u|o9l#>DZZJX!3lUVVcCJZc0S zE~oesuy~1^%U*eSZ{qkeo-9c{yx1+k?bO(Nz~a?Dv;_u+pD48jdLNNoK}}oW`Fg`c z!Op=E8(aXYd^K!J9pBrNeFd#=fr;)4dH^uIEG_ZQGmMJ1#A6*sjaz~^jQX|2uq2f; z`@)lu`_u4W3~M{{_9!*M#y+AiXafV6&|!G-UvMn^qcr-l;Xi*^prEfYTI%!?%HGPV z5+e=OYQSS%5i_{N=O`yUs7ko1v^pGarWx4ET8V)erVx|!{lzasVb5^`Ug^2k_Qg<@ z2;)m{!I^(iht^hsEdS$SyDbRsYvP>NR#cT2EaqIJIOA`R>dmOdKr9!OkNruu#Cq5S z%IvLR?PB%|y5AaK<~VM{e4nzkv6|pKWQR7GjJ?aW)|B1`MK0kEw9E~6rCq>O5&D`p zZrB@OwZWEoPR8M2_!k^GiH~b&E089s= zzgaxXt*0de)t3;z7mA#1;1oF*5S~XDz5oO(44hAx<6J;km;clq1_RTLxXlC~dIx{0 zMSH7wAy(Cq1-@a7bKl^E@k&&UV$L>N)82|Lv>Sj`KBV`)!HFM*s-MBxt&tDfW5#`u zRV_2tUBi&@d)6oz;d%h>YdDix1}74gqga|1ksyR^EFg;-H817x^nkrC5XxlnsA_Op zW*ZGiL%|9Bcbc7sa+UBm^mUq*6V2e4G%MaXMfcONlzWXMIK@icTL3G*jgHy~4aXhg zaHb$GFhaiS@hyOd76q$2ELZ}7N-pSYB*6>9Er37QvNWg#0Pnk?FA>Uc3*gcYR#-NP zf)zR!_tmAH9jy5L5^L1G8oc(k%|GNUMD^O&_x`zTGCEq73xshuk%PO5z;ZCcQ98=7 zdVY9uhV3SYhtWY08%YK@VztUF&pB9XSns#MSHd%pyzXc>N-*LJx#h0(G9&w31BYEeGE{bt z3Wk$37$vBDCrmDHGv_?5=wwC4N%$&DyC27<#2V@WDC;1%nPqR&ckf_9LeQTwfP^EaDq4v+#wa#&5EeOWFJ+%eJoqB zdi%0rPPGG7rQ9Cu=EVJsuBK#AY8T+hd@{HxrFS5 z6MA1N+8rx;gQ;J4KnF84oo2e>iL~AgPoskfM+;^e1945aQu;2dpJ(BmeI69(VDjr> z6-k~0mVaKI&;@8|6{m;JoPp$+u*9 zrF)PDVef#N?t;$wKv*(N>K3d)s{r`g1#$H5lHs3yv1BO8l=9=^@+}#*YKd2kdk}mg z!c?Firo+3ac|R-}-eRP?WO%uVB_N}3v_}nwlSKQL3_l-(4Ot)?Gx0Nz`L}2<)Ii%q z_HI#he{|Nns0w?xC{26m+FPc*UD~^-z1P}{9)R9`7gZR5Ddd~^aFz_0)fE9g-L;Jle~EJIB$5vX!=3 z%R+ABS$G+*XPF4831R*R@uynWReTEc3D~dT%-57W9J>eose$%-4Y#6${5zwh*{J3` znm62PQutC|{GVm?>DXUI?Y8<}M~y#N#G}r^nandf^Ut3YJOVrKgwTsBk3b(S;fItq z!ior&@Q4qQHZOXLi};h)01>Pu5jRvF0U%|$BMS`fRh80=c@}e37(b7ddr$9EsQ1OZ1ez#}q#bb^8+4V(&3^9VNWE z>^-L4ns-Tf3qBA;jP~BvUI*=s)!yJgmIo2MVejkXH3 z6IN_84pYNvR$xD5s949rDk`^W9j&R9U}}Qj#Km}AOpIwQEEue^fME0he=uVnbA*Uu z-DQOJajxhG4sEnNS9tfHlNu$PCsRe`?%dyF}y{L*F zt5Rdsutmi@Y9$=ZbsipL70RF_l3r%k8cT)KrFd(nqrqOH-tgSiP&(@OCHgKM-HF6i zl`f}Skthj@onqys++(e5cnC$uLi8~;9&1G>c{9RKoww&jt@g7fM+7R#L0XDO^@MXv zVDVTh%5sWh7ye`vXFDHJroVOOeQdtv0yqrO(;3AB$3fg1Ar-@)B(E-xo%ilV)%LeS zM#CUBH=RnU9#sd0uaaPa5!TllWHr5G0p(r0f;x$V#PdC4;RO~}ERv|Q_ zjvr#1tb}v3v~FlutX!oLW%m-O=5Shg;Czsz0cWLkkkT5m(xDHnh~`=wx3jE1HGf-o z3S;y=1r@hkH5^Sw&=XkQz$EM?0HGx_#g&yRjz^=-A3I8HvkA~J^;&I5a(7m>XYMT`^AItXnMhvZvwphRCfYuT`=`v zFF#FTVlaINFFil!U+kGjEyUaTah%^S#ZMnU$Kj+bz5Er16~?jcb|7#>ItI4}PO?43v9MDdgsIPJ~+V&Ij6OZNiUVrSG2!`g^3SR!Zy z=DR)xY_T)yXTz!h1H;1a3*KNKpWlI^ju_U&X|U&w92qmgo9FVgy!!#SqGwpN!K560Sgv zC!>FouoPeg8Ucc4R;8tr(LV{ZHpk`mPfK~%_x3U#^$VOCOb;icfAT4*N--a0(psD9 zfq=Tv^CNUJ!88k=lbEfVbNVAIPDjPnP+J~~>g{Ls%YtU{XIYPW2#2U*rbx|eI0c)K zbtRD=YPO%1_ky8zb0uh3&ZD}+Ib}>!kRxwtY|jwB%wb7&0tHO@E;8dVHElF_SzM-7ED1yBiM zZm&}o`-Y5Z;4OFgy}m@gylRgio&b?5gF9~Vmf%KVl<}$g+qz#J?>Wz*BDiA4XmBA= z`RRDs5Gm1HhSH{^hhf4SJ^`3!xgL|>qt4`}Q@3iIx%oJWcd)29y z_PT0slJ-_Qr(TT5Davj1&+m zFi{GtG4%wet#G=5I?&}bXPr)K9bC&_31%Aj3tUWN7lYQC>xQA)a10y4-^LhDmeH7Q z&yw8dnvDkHjr8r=R+4_k9a)9UE24&*R#6U4-Nvk)|ATtU{#)CrY~cqU-Fj4i68|(G{!eQI+8`MAwJ< z%#mj?0~+wS{tM4Z{yEKgF~^E4D7v{4_}X{cILxras-atlgG&8Q((YrtlT@evA46Sr zn*Xtrm&UY>!`{NWh;X6~OH$=!+>VX&IaU z^TXwFu4>KqrW~&HwZ~>~q=x-d>mA`Fp4Nw_~LD<>ro6<1^?w4cIjoDggcd za^Fg-GzRH;3T9wUCoWEmkpcC$_3>(SNKpV3b3vRSqaC%IZ$%W*dEyj^RE5)Z@J@z< zSU-;9kB&VdGeqQQ*?cQko6^!<%m!tNt4;Fnb{9*QVWbk&cR>8$qNEVq?&8DnV2wHp zzzqRW_ySai9#nb(+DHp}pS>P5YXNFr3);wD4?3cGFElTKgjbin9@Im7Q?$2Qd;7F^ zTYG^EMdw=!Mc}=K=m`38Q8cTAed=)faSfpv;ItLaR8Z%;oKgIEoQ|Nvhe`=%1Nd8A z%n%oYj^Ncv*gWGHeh2?NV|wtvAr!JmGFfgBT9Q10A=C*Z9iB|{7h!-EddXUNGLvZ+ z2%0&At}VhT9%0U<$ic%>D2^wn;n!7}v&Xy%kLWaj8 z3+)F}ho{h=pIQ;`3BBE6r>TvHoUf_PYlf!wqM=7wjgVY{3czV<3&w$;54-ktJ+wH-wtL#$wEib8-w!pk^!oMw4Y5t>~v5DN9UW% z|2h{}o(SqR5Z7E3rvY>M2z)B#$^5@(gEj0G5P^+3YgBR>9^@=)xePUMG);t8brws> zT4&T?!)lblvJWB1`BiaM}uIJ*Zn;&I(DO zcgDZCoKk{03jR44v&6-qVa7}kQeSWkkHA;&a31*I5-R>5DVDbXK?9M8xP&Hwq{HiJ z%YUrs6roEAtY@8i$c8PTxOji{{$Ui%At*e>N(H%ztk2M5CA^g?e})!2np%H`7VA^A ziKcvp#^fVx70uIdJU=SH&+4BeP(PBTm@2J?!*e_a4N&w1UcAUj2Iah7R24sK;Q%3z|@rMNqTdSnhNJU#jP0>U0~r1$(JR8&i*?6l&g`fQ^1_Z0xoW@Sz_jNGF0Pad;DDKAFvronPYt%q?ue@O0BmtVoG9m8i)r2BQ;Ubeyx;<)@H{Qi#qiWKTj- zJfUqdC5O|6$jMRqqK$1Ht8PP-axpL~X9D2;y3aaE?-VFS^sC|J6Wz{dkrh8;io6k0 z+eDJCt&@!9UJtJi)mv}H!0WXhE8xv(7JGeY(|Rd+bIP+p{*{GSjq3tT z-{i+y1S~&}!kXk!?vtvw_o%vXrp}yv)>!Um_4Y?ur-9y+c~Xx$(xMGc0~kcx5Jn7t zY_Otqy-RM53e=HaBd!dDL6opjl2Ui0m5?HO1gIaJB#C>WxVipT>77C9HJ+@|Ck@j@ zI2c6u&qm4BFB>tx7h$d>`u#udq`$Rv7v}e;0llcuJ`WBl-ubmW@hjR3_%8+# zNp3ev`7b(5Z@Bq?aYiHyRosLwEDMd^gf1)#t=ohyEGO;TgeRDD2%dW+-2o>=!vA(c z)R9AU7gqTjbYVVntOmFJ23?p?htceB(1l63FqpnB?CXN4GmAQ72!S&-n7fBaM!8+s z&GP5NkntUVei@bJc=S_*-;g83?|}(1pF5j?Zf4x}fsH>Bw@OmTYj6oG$F0 z7f_uBL{A5mxeFUq(O)&>G>!*_=Q=Dyj|vaLNU7 zqI_LgnG1;PKA5jufE0c#C4YzZl#}XyhbEqrKKKs3RWhyl4%H?n?Po8U?l3VY<=HH} zTAPK}mAzz|q`g(z`&oN8v=^{NAo1|(BugPWUD(ri(0-D;dsJCCU5K0x(!oe@d$+bS6=!(KA=+-k+Zo3<4dIwx&p zFPV;QMQh4QPqs>O^K6s+m1QrPTEeTwb-~w#`Qvt-IcP6Nr=FN=!QO9h-R3lal5_@P#P`2#=)#2E5Hk#9E&6+>A_}1-)dc~-9^a!2^8xjPlO#D^ z*wS+$Dw>td=!HH4&df=BzL#9x{2pDH7S7a#6~d=~<0+u8HN4n%bYX(?>36%ZS66XM zVTIlvRSOQf`)@}VCSd8pVrdDalY}72$e_aM!oGNcyBXF)e2Z3bWxFKL+VMu7Q{N=C z0RazU)DCoE(xTli?8+0EL`1bQ=k`I?%SjD$y0C_;a0q5K=-TFBH2A z8^f3u-p`{V;Xtdo%ZiQ?ab~D_#=Uv46jKz<9{iRX^WiS5K5Sqg-h~ZacR1F+80wsw z^v7qU|1s4#4fr({@qwHTT_uO3J9;EMD!Ln67Js3pyK%Vo1@+pE-CHkc&2F^X7j$a3 zRme2^(kn38&-(-RMOCEsKOpLg{8g|ve=c>Ro*Njf8Zy=BF#w+y;7lLLiF)l40455L zw*6pLPU74i#s8B`%gg#4%YSWO!hAWn55RfE+!QLb2YaELQP(|IgS1wRb=4am_QXJv3BY4-mwGNuqSiWpQu|8<|bF2YxZwA4xmabhrm1LQ{Y(r%Rd9B{5d)I!28E1?^yj?iphk?hYt0q z>~P)$I9C5+PoPJTvP%ZDBm<=ET(f^E)cJ(tiI4M+F0oqqil*7q_H7VN{Edl4n?LjznyZT7+V-XfZ?561Td zw1?L3!$#3X^eag4?lNu-MeG-N9ro7H(EV0o9fo@?*KLBK*IzMVn=%qBv2cpB=TP==m1ukbV48qW7#PO@OCAH!#+*8(B#`;XmI65 z;e`iI$HxFe;&U%FsWU57wFh8OX3z}!^ng=LA~l14Ie=55ZajuGDEC4WPZdmEPD95v z(L-SeVLk6SNB0VZzz>`h?4hy;<$=I8G3E(| zd0~&AS`B4J^k{4ogVQxbKKMkdo$oURetjk43(TY)b?{6mc(u+<2N5Y9$}=X)^DPu7ra`! zI2;3c-<1wh@YmV*BkG_A`qBwoa;(9~mA zEu$$NJ%%y4DQjjr#*b_F9hWYg*xkH`5Ppcn4iZI7Kj<8MuQr>nqX@n11b>2C2J~Jn99UDIgif zcTnO<80p>10%a!Sd?D zyw&fcz*ANXyrSBxf69t2o_Ultz6nxip~7tW5vDhAI$qx>OG{4Sq#=m~& zv4w3PEjf>2Ow`G9{RbBXT9FNX`nAE=T^=hn4hLTL%|I^;Cq-`j!wJxUy&fwVm$n;s zz#M4Y`I9M3nl|m%x;kuvB+{-dg1OungXu zpZZ&mtA?um+zNKg^Qc2`I$0V?FCfY#blq1NwXS0XX~lb;2GFzXummLGS(!$V!G@pe z0*LnUDR8=Az$b!RXmmIe+hU_9-^bwJ`i=+7|W8}%BY;`~)@3IgZy5UR>qGh)b z`7ZkI7RC(D$06{JF@FWiJ7Y%pcvJNP;ZJZLGItZj+{T!3lt$i0RXED3PtsyHe4e(s z;j458;b6g>XW&(O?GmIPfq|7f7$0skGi5POzQUOg@Xt3sw9IR(N6c>m-h0e{P7@)N z)o0AmlURzB3uU!+nsRz5#HIxX*5id0dty z9u)y+KA;+Z{vRXmlk#Jc4O>jirhv2%n569gebwcPWw!LFL2eRDA)z&Pd)|C*mPwT-UnF0Mewfs6gbnlCdols{xx|1pSTHd zrgK}rgPm0_jcD-Vm@f%%N3%`+vB2On;$A2lJ~%L{A%2>1K?2(ZA8RKBs!@J)oZY-&Fl?jsCa)Zz;AX>^-OW ze*{^Jz30>w9x8@5qCQ|~h-&c}o>)45Cc=5Ej5Cp|6R9+R8F-(&e0L&O;w)sp2mNQ} zN!B>czKL9ue?rt*@NT$#t{|=v^_YLL{q_N+{ELzI0k!@YgWv;7*WOC)?fVy2avsnF z?d5zVc`5w}NEpb{9!x?Pa%$pg00Ow)qY@rQI8hQ6%87EVp%2+GQK46S%B6kHT z>irZZawU#w^ubfBR=ZC*Eza%K_WM|mUk&kZSOv3;&zSEF*0tsbsMSn04g+vHGsu~9 zEqsKR+&jXf=x3PzadhtVZ{h$y6}Se28Jw|^Iy}R8zLAzaL%Y~Whn`_P|CVEP$Ma@I z`~-V}@!wMDbE{^%>x^*Hoc|7Ho8{JGLJ4Ow%lMP|PMUMVj?Y7;8tnn-ks0Kqxl{>^ z3nPU`8=qs$=QRI}{|A}&3+r>n{B$h%&jH~YICq$Pn)1G|TBSc`kb5h3)|COO)jBM( z!kNr6Ui$dB6}$3wON{_;g3I^tJ}>uH>{2hVwg%oxmmkP{tsl2y=bG=Ywt~0M;U^ia zz{r5Y#PcKA@VWrReFvqx;y}v(5-%26SRi3Nj+()lIa$9u@yzy4kcwn}UGN$+KbFQo zC`&BE+!u>qXxB?r^qh3@rF>3${?dxUzkIL6tMuysOgul!Z>YjhVbgBzQya}2 z#a>QY!VsN1XX2T>dEaXuURls6NlgvAgcF`(*!W({^a)?1VwR*$hMk;=@TXxXL2Vw> z=I@rZOuGoYex_Y8R>aD2Il2?in4>Uo{9o*Ufy0NQO@IM?l4WD5qsPupc|3LmNF_ZE zDG~o>c-h@#CPKw!(NZr}!XHNn69?YLzKn4w%joz<> zrgaX?yDoq=7=qGws_gerVLv-u7fVg5QJ)pvhQzN?h$74;m0@ZeYzQw>R#e7bs@(BO2$7(nl_f&oD zX@JkfV7}`rko|sno_nm9ZM_Qmf;ZSzp!u&o*1LBDSpiPRfHzO%X|KQ3n1}4)du)Ks zwX+I)v6Kc6Y1Fgm#Q}CU(AI0#p#U4Z8#u@H>3)DzmOx8n6D&IcDwJhEl$NYW(KnU+IJ4;3GXeUMZ`=lpKyW&Cjimb!eZk@1VQEc4S=%pUgCZcOM+2z6Rv+_t3W;PB0Z(W*ouqE!CJv@Z$wT zO+t_vfqqRxLhM?`UfLdFMR50zsCu6M$eP~G1X=e&VzH6xvwc(7Q2;^ zpL%D()6LJS3(|BqoIvZ`aB(__aIjz!7+9Phx&-L}i&L&}yF~HQ%q+0mql&$uz+l+p0z0+Ub-aR9qnGD%zg9H*DVZ{dk>OR1wS=8pp)RtOJk~I3jwQ4 z1FsA7bs;+Q(ii)Kbav9go9N2B^U`L60yh7c%^qt6upCxz>gBLYr06ggv*(I|g|OMS ze>WTr{NxP!_C7!2s3@F7WN-*l>vCXB6)7*_S`Lh<6)0;?)Y}SFB`3zz3e-KPT~No9 zMssqa4p*RcAi?{Makc4{hT~rjdOH^yKy7NB%T6pTdD24+K571b7&{vK{ETG4>10Tq z>O$*sp=Xt3q|qTa+=cEV+)UFsmt8n#&ZuaOsfDrAcmZA3FOI%mjL;F{o2D5BM1C-n zGXY?Ux@~S$b5YC^sOIBx<831&VQp?ZrfCL(D0b$p1zC{7WTa8PJW_uuvR8rH>VF^Tf1l`o+w(}--(jyd<;g3^vh39+tVTtnCh5^>ZeEN| zwP_V-?WA_OQ`8GLFyUFh54&*SbV+k+d{flD@A<1k;GJ^${QR9MYM}qG#c^mAyqChK z0udPBDo}$6bYm50fc6$>@B0Wl4#dmavmzzAg(HEiO%1d+0G?A%mjDpJsYUJE&0#6y zR&+fBJt&_jDVk4|G=^78w;pEz%Y}QarFhd0V(%TC&Z9hicS;&LD@3J(H_PP@psmoX zV;n#i5KffXMU}plOV*E<2lx*e5uolv@KpxkBKa}eiNG-Gkl#+$&21PLta}63w6d1^ zmfO~tL)h^Lm!Y{0qaFF3S|-hH7~KQ`g=a&WJG*_sU*ns_`2DXETGG`PYWZs1kRDN3qfN+py*Pel*6Y+q5DY740@1iM9*n zd%$|#nPEa(Y~4G8HDfqTwX?+7V@z0CniXT`2{3qToJH$n?7XoO4&}Y2L#JVC8aL2< z{VvR&|Ay2GD?8ncv1?$tC@I#?8<3YJqp3c^H62LRnegQ2-bdPSE8q}c8XDn ziWaaVD+<`P)-*Q8R7t;)Tf(7) zdyMe|-HSst_<^JQg+k&{fh2s0C7lXXbDdHle;}>GI!3kPQGrg=G@v`5X32|;)|F(sc7A!=VHmT{fz!l+XZ0rNYF3p(J; z$1LO4sYAC6#c3!ARsyqMQp>`qQ!i;sVbm!ByLGDQGD}SZXn~{0@bET9w@!Ts>*H&| z`%d_DsjwX#!Wwj)@(iKiBB)4038X|f{3q2%SR(_W5L#(K5j$_ZAUO(y$-Y{ZG~Z8+ zI)(ihaJW+bt0JgXZaltP6^M@jhX6URVP*nq)nh7>fLhg;^*Ocb=}z=1J+K3LFr3LO zV=(ibTGf3^pc=_kVgL0AJXG5QQ00U=(P9D%`9U%gzv zJwTm74A*rmS&G@I#$l>j41?og>R1fb?=Vd+X5TPwP~YO{cy7?f;&w537mC~YjJx!_ zI8t$!_5MxyQtVfxuB~#W;B| zxHCrkUZ@VE;B?IM?{G$FO)3^*SS<4)gPg1Ih>$kpTL|oSg(O4z_yCSc^~z>w&=~-( zyCBJvd&c0~w?j4PH2^_ZGDh#5F`ybH>~NhKDc&cPR>F?NBN$b}E&*>t3AD^`I#&XZ z?k>GxFPvcMDjEOku@_FmOA2oxd*QT2d#AMbM0J0?@Ac9oJ;oz)tiYcH}i<}P>XtCjm)Q#^ z|F`h!d6$a5CF!Wg-d*Ymud1X&pL3ewXU!NMqPV{@hTOmdgOdk_xv=*f)JYQt^_f2( zyd}&Jr~Pj^mGuez>4tMrNEu0Tkur9a&PqC-fboQymT{_&5OUEd5RjZDW$c6$sYOE9 zkAtg{oTB6-PaWS2QB7INuA6xAfkR3CTSju0x2zpkK!myK_>Mf)_z_dZ#9JPf3I}+H zvUcPpE#j{;s&MsQ+Z!ReJh{2~#{1qp`{0TBfJ}D9Bh{2qxI23Uf^c$j&!ploVDW$!Z z<*{fd$>FAC_$Co?(Ux_qPN?dGwmTY5r^JuGC~rT4MYvBZpc~6g7b>6|%T1vb(T(M& zq7_jy@(+Waf>ggEx-khizl$^#9Hx&?EvsmUMfu1H0>+QefaV-JP|=RjYOs6*%}oVg zno(}|{X@uRY1&7BiO4-UufPhns-xs*4u(Cti9UW>!!WQ@aj~R@^X5&?Kx36 zGylRX6P(T!C&zbgDutImHiEe;695*K?!PVR4XP>;7S&$8s_6IfQ%{i==OWt@aET9D*WGgs&JA@U%xjL z=W_Zp|3~olGruZ5t>)D31d6Ecglkg;gb_=N>ge~R25rDYKvu?9cj}lBYSS7J0Nh_4 z{hkk~AC%M#=bTjaT!tFUO78!I_c1s#KNYMYIjd6x{hkPO{qpsDS+-+>)cRkK>Hr7$ ztQvM?VZr(IyZxTg604M-0QiLlAFYAWN5Im%CD029~Rh9 zf6RX&V>Fa}JH6YX1xQEG|L}qbhjdh_CDoym_9oZDx`ZUBG<{vmj?SsW9IJdi5-XQ; z=z1-?ap5ws!Q+^u*lpdIhyEqsW0;(PGnuD9j8>vHweg)m2-Rt3ZBzpZ*QJfM?TBy* zm&KZ{gFfvdD$z3_g0&>;t3=Ut?1&UCE(A`2V~4WCA9#%_`UI0%IGq5|TZwwqvGb*~ zle{(+zBylAEVq`Sy6iQlp>^>H%g_S$n$vfhcUAMk>j^J~Jsd99UVrV) z*4|gz`%Qa))f1ih>)X*~n{(o_JRSs#blr2$;RC7uVb5`->7OpJd2$CvG15X*8_s%p zP;0{J0_#YF>)Qp}3TFVQAGn-utkAI~Q>3z`rRRgc+{JWsF)&&2V~YUQhhx|Z{*R2| zG~qz^KlP;qVj7^P$)oH@^%~eoIy{IzXn;;Y=n+p*c?Z!d5HxcH9cW;u77%7S$K~3N z3LAvI2De|}t0Wv&Pof&yg)%4^K@A&b(wa`gKtRb8fbh1%a}skya{?OKahlYaQXAQk zC?IWoqFW;@!ZxRojUd^amNmkfqRs}V$hA;;?r4yb3~YRbvpR52_HRQVz*`hyjWY{7 z_9+A24$#6;ud&tu=LolifRoPAEUXnt%#L-+bxjOah#S-l2rgt{Zz=x*fxJEexn&v; zNt^hdL$4d#HQO!YHz8-XKPDa1$V7$BB5)?NjL(_x%=Xtz@Kh=y6 zn=aEjmb}c8H|YSvH6?tHC7spEQPD6N56LquE$n|pv3F&u+wDMgClkxKM+wcavh)R8^_cBXBbs4l$)DCV!^)C?-T8af;;Bfeed6b*zJSB`#-s0IUCE8bx2|;d6MuCdkXIU3u(=%*5%fcIJ6CIYlWeuOh4aGpSAW9ybZYvYm=rP}k0<$3&EWp<2a zW3xfe`c~y?{^}EEzhG7XvnlmGJ32^EY*Kj+wSLd8n9e<9jNUy~+{k(i7vLFV0H4Al zX`K6EoO^eB+2>D!aB>FBH7>xO41jxJ(hO&H8k ze+!86wLtrp2zyc07Iu^|hdQ*dOST)$(L2rZL1(-Rjc2mfs7H{%V0{$+5c4@{eUOi3O%*qwr=?YD+ZBS=7HJn&m87+7gR! z^EpPhSAt#qfA-75VggWMfu^;ZO{ zqCvQJ1kPlZao)$rj!EpD8zG{Ov??-g74Q2w5=$`h%+Ww!9?1jq(DGMsh$Phmj z3#TK_@R7ZJTYO}fSlo~7gC>S*p&k(ECqlH;2Xj8MH=O0wy&8~>8g>CNPW$V&c2pM0 zqx+S8D-Bi}{N`Pt{?x$MAnU81!U_gJ_ z!A|DnpX?y2{5tBtB|F+h!EN6WQ(n;}AHSnnq5fjc=Xu}d#lNh6YABqPvLP{Q0M0j+ z!5vJ-bTG*UWYB;eW#5%TXS5#79WH=17=m)Xozs(!*ij~lh@-Igv7=0fU7)+8tWzUg z1(eNC6^GO5iDS@hYV|&Ll=-B%4!^OZEMHYjs{27M{Y}{oh*65*jj!gz?GTm7>bF7S zCs#^Jz}->y<3>~OD7y&2bq48r=juMKdzaIQVi6A@5Re78}Wg92jIuGr0`Kcao0HfTq)55M8 zaWULGTm{KO(c6j<`rSyP(MExlo>M0siB^3)N4x zOm06_4bEGSXh1h#?&oxK;!ULQGKA0i!V9`P?KqXncE==Al9@`qx@T(BsWksh!Y&ZF zjJo5s-kZ0;9(J322PdIS21fS^QF*c&*50umRX?wvdJoP#NMn0Is245oVdu~CI|Fm` zrGt6=j2vln5Jcm5y3@ms3OfbfWr*C=V!3+SQE{x;kc$Q_zGyHHERuG{wk(DgLML4m z4l%R>)Hq1Pd)oE#UEml7&bWwOldTM^%|2VL2Iw0GUZ4v-F(G0E?3IM~vQx6$VRUZ3 z88J^?BLcSy_Cg{xQ4(3th!{YlK!n+mMZN5(rhh?TcBG$L0B1^E7T=bbXOLm}ZG_B^TwNvVr;7BXnxQYV@v;3?*z0j>2X;FTvC!EPlqY@)z-63$cU(U%n zEmfV##zY`y`%tv2FBXqW(7C>LOaT$B%YuQT`VYUX-&e-G`8M$XiVQ{dvvZ}3rm$!~ zl^0G&r=?N`2C2XRf9s!`=)8-AS=s@pT#0pYu%Mz}sDdJ+Shp^NRbYO9YxHa^b#TJk z0ojSs%{l(L#^X}{7})&7OOAyBHc*T)U``M~IwL%Na-&2G`CEChv?+k4V6JpEc*>`S zsK6rrRvuhCd!`hz$+_$ z9ahFKf_KN|TaVDp0(%k$u8BQ-wm>FyagNsZ_WO8fEFJctgYLkkyN- z55Rja$l_>2CE9+5^IL2?m!F*#*Pep-T2X$i6V)$`LY)EjLI4ONVS&QW2UY=>t>Z&P z85`CY&=6%(|3PS2oCt5CW(~qLc{}YMWamrT&N2PM32>XxGkl>x#AM?z)Su=kG>YuO zXhPd5ZZJNa2cXUc;=qmhfoQ zP)q<*P#@e0;NZ#FqzdN8aK&GE(j z)oQT5aoH7_?QGMycN0BOCYJHm1o9h!Z5q{pdkvO<0^+U1Lhg#rlWrcxiHHKL5VIRm zvk`Vm{zi;)w`o+XinR6udw^)5}a%U!3?MNqwRb;Jch=O#;ixvT`~8&=a$2MYI?GtS^=kHAET3SU^Lz}MaoNf z1ofE+F=Nnq3nH})Cz6xn+KX&F4y5E_eyS{-D9-%dv*a;LP2iZCg5TD`7{ghK{-lYm z906-^9)v+d0T}0kI6+=eE||Q{H4AN$QA>bWB`ErBjFVU?z=8A}i8Z=X?sR++>`L|0 z(VnN$@N_)DuC$Q7skDWOUFinA^r;dBTUUx}@3Eezg{mpVk)hZ4@lWw)NQrf&xNaV+ zRgF-!nfcM+#W7#Y^Tj!F13cEg9C#69eiiU)`uKctPTWY3wf8$i^V7iV0+;Spz!&Gl zjrUlk$A#z!(!reQQ@|JJ#7*~D{!hI8W#E18RfVoJn!TyC;zP^`yVB1eipm@8b)|su z=ofV9I+qa68H_%M$Mmcv(c(z5A|L3Ox2*mZ7U~;<-qMjZ zxP9RbX&FlYD?e*QB1Vk9VE%uUePv)3$M^QkCRg^}2uTPKPmlx&UOYg600DwitY|5; zxU@iv1()JQ4(@Kn)8cKh;#Nwr;>D#a z!4%3lQn^`XBxYag*iv#=C+=l{Q%0(a*)|e4Y7}QAT^p&Y{|%xfB{DQrAWG8q0;44`?aF$#mvxOa+pe<(>*m&5p9(2mDl7pt$jv z3a}wu=T$~pCQ{4sIOLT`_0tj_eM|*jJOs6C1=JmaDuFD^1ou>6=si5}4s50ySH8KY z0>RycSPN{Y8)to~a&b=uqUi7OmVz?{?Pf&#`H~~|EL~1nw{X3BcO~6#ZT~uQ# zP>(iEz*L|Tjhl$6KqWdd5mSLm^v^_01=6^v?y11DSWIi)R`eJ4O7Mj-S)0mC!c;(| zt3V1tuSu8+cmxd;jqSLn0`(|s5~c!*)0D1E!c;(|ThaSTm0C%Ij(aK)unmr^gV8Kyn66K@hqw5c zEuDhkk~_DitmQuUKdq084krBtf=Kl)l8b~>f8L+01}PGRe2PT%rkf zMl+}2RFg(OPr>o~8NHf<21}!yQxSbeWu`)yMja7lex{0Hp87+z0Aa5JpN8OPB!a3L zazZKo*B_yYVaW8Ba;PyKKGonj6OCiei_@4?Me|GrgNnqmAZuv-Y3E(7MN|D$fw z$lx77|Elf`%u|0j#Hs+X!18)<^VF{e`UzDLm4KyraP!n(_j-VVw*mG^RX+7A58S7I zSrY3b0|1U<4^VEMu*TgCwPN$^d2uEuH6BYX4IKcsq~=*DeZ7*ItMma4fMP`4T8QKbYuXeI=3bNdXO`qi)07T72@wEJDsI4X`t1N@h7wm?7KoCCN`gLF~)nYO{^8tO0N#Z z&9^6IzT|?X{JbMj#QkK+bYKOpFz&RMMbH>BuDDW;Fuvasas(Ze`dbn$hpfMzeGj7h$9u%>Pu`HF7L73x93VOdVKzuOErjLdf z-vZmAaJsd?UNdoeZddDa<%!tJS-4oK9$*P5g>y*G`rB~L6=VrtMGY5X#KFDGh4y@9 zrX!=_fF~kob2!)QIiYJ?zD*M)NBG++b_x*8Spj^LoAZdSEwtCqj4uwpdo^&{YNy!F z7NQ#9o-u;93;#T;f#r(_iXR!T0IZ4|cdrJvO|&VzC7^b0Sam?o$a^*LHcAq^j5aL7 zY9M0U)x?hH{f$D*fbt@b z0Xn%D2lrumuo$a}*SM6o0N!W99g0|jlfxYajDms>MgbBt1=M(Ga6&Aj-Wa4>IKOXSI_v| z-~J!xE!88q?OLxT9&Ot4lG^3?#p0cq_%@^MGTw7DW}e-e3ucZQ|;f zt-rN|7s%sk$lO$SnLQ~w8^7+sJgN)w`p-w8cS67;6;qbk;|efC=3tt6@ZQf6Afh2y z0M=^7R1~_f%-&ztq6W(`S*=A~mqWQ0BlW$Noj8;}gy5?WF~vd93<_;o4&}jAXa$r9 zQ;ii+9?Z%kyp{8uz@{4rnl$wnZ4oqsLX%e5`$sQkrs>MCKXGaG5R_L;TTBTnVUQVe zrMJPuPj#^#f}+i^9|l1)DAai+N^^j&uS97M&>L1hz{*FxmE~-UI1PaV_bkE@G=oBE ztL$CnaN4-azD$;)4_9McE=9vuV`pjwnvH)E71SWUjBA?*@eM6pgLoCX!f+J@cfuRu z75t|O*QA6suvL@lu7Rz()RF(yrK$X{F|EeGh{j5_Lr&M(V^2$$>qv|FUsw7b|0237)wz#w)xfGJOx51>mf_wC*09Q~ z;Luhs%l)a!I@s!uk0-$vJ}t-p2Gb_~H-diVetx!t0dw$Vy1Bugw@Qhxk&SzkRj=-WBBKp%>mf)5rIrZSMCxOy4Q#KAh_>w5hrL9H z9;n1*sN!MU^l$BD<#rnOtv#~Fb{74>Ce2e#w_>_D#8No{%7mbKNam^Ld~uv=)&a{> zI9>l16Bu=iOmT;kbECafm9lI`oyYntTaLSi3uU(A1MDKX9oCuciD&9ZL;SGW|C~s9yhlTv_3Ry6P^$3 zLu(OPCvmHH>pf}BKuZ^Do>iE?kokTZ#DZpOyKNz`+*Jx5R{-1ckpF{bti+9aB` z*aSNxYy~@whtQjnVQl%$uET8FNQ-7TE@F*)w|CbqMupH0E z!kQ&mMQ|=@8Mnfr=pESzPk!B*ipGUs3Q@VeW!XNw0t>L6R`0b}%w)n5{>yW5Rb$H6 zu#LMgqswivl**5fMMqkNt(QM$No_ledYJYL=W%Qtiu0jqf!n+Lo+c4iSK%s~~V=RN~>S_;#k8{xN_l8UH-C3M<5QO%DH&T@|O+8o`_cEp(9s zc6*r={v&H`e6-6mzFToT5$pFqOGXXZG1QeZY>5?fw5(mz4E`J-6&Z7k|KA z7k1C(RUPHkpN;HXoSU=##6}Dnf5Eu&s*fGr@X1doPPUZI7SX-XT`X984@_oE&5MLq0t1Ui&sHRswA9FrN)yI^uSZaP^Q;zrd*8ET1_hu7D-RGti zKiW5C@`X=@&s}BXKk|>WFx&WgMT@AMX_>VM`(gmQyOyV8iln!A!xIjIe7MZHi`mq0 z(+p3oq?%tPUFfSZ1#giPeSgI}GEB-q{E_&{MC0cE2<_j&axE4QHeIla!zRa$Kazh$ z(rYYOpfdNjvx)ui`hiIaeU8)r^ovYc6BWpmvUmgGpSa=-`oiTCdn-F!=Bk=HUQ=~^ zu`Kq-TtRz%;ZGm#w}%IKS1R?}Z;w?QFr2qO!;_iyFsD=l(r{X}-(DM2mgoEJ#nT2y zb1m)0XCf;fwJdvN75V#m)spA%0ZlH4Gx6FI1xYo~AzC1%< znSVsm50PpJT-hJ@SSbFGJ$K290XC6{zsi%vur2vVge`fG-Ch->ZP!!We1o6{II>qD z2IyYY_mF*buG%Q?EmM()49OC#tcD%77gK2RmoBqjXx2xE?J*8Hh`u_5%a1{ApfQ~0 zoWc2UEFDIaFcu==$9v7v%KF)IO|XbbOu9ZC8|DzSL6qYxb{Q&7wPDVWH_WA_`Po*T zad8tzU_%xHxF3Ow%m$vtnRYBKLKLjbEdadQpqzy;k#m*(AP|0c*<33>n}4A|BkQ{m zKR38B=X|+Cmw}7V$@l#_Pz+}iB}QW506`l|pPsWfh@H;fr1ksGDbn)z+1}ufTnKm# zQ>M3}r?2dB^x_;I2%1B-U*P>5=DWRLzYf=UY&L$Bzeq&TrqhSNzfGnM~B#p6lK&2}T_ z?%;iCaF_gtYqn$5P$`D;(pMIEyP2C#4=>sq$PHBS5+>UlsKq5Ler%-)m*C-6Or$&> zmMtU1UP$Ef@%~~hg0_J!UV?`kSm^8Fuejl?xc9+(YH;H&!@~_!`7&JGN}nJKR+Nt? z_>1lcFh>w3a;~yG1RfWEziczit%Eqr;9fWESg)|TtU_1pPc-?IqOPH_p7QzkC8bb8R_0Qt`inXUFxMBtM9x*_g23a-<+*@4>#rf6VQ}~UhikT0ZM@0zC7U=0-bLoV zA^iqg>jbsDfz~=f{cfPO&e7@{aPb`4)#GCODHeQi2D(3f<1Y>)Xea2^4Y+uMg}yG{ zyx`*6rumCN1aMPs!o?HR>Ly$~N5c>WD|4BEzcwgaAxz|4WitpoE`D4L567_hXNb=k z+;@hZJh#|fR{AZpR&G10!83OB<&XEq5%vNjXpG4qYVik}FguMwl#re2?xADRw-yn} zq(z{wP%8AxAMj6U`ucbFb3ALv+}q$iFu0L-;h&w#-$jA4Q(HvAiqd+PzxWJ6v(q;a zCUUN_6a*gso;C?I%&mlYv%$S=*pc^eITpk!&me!rSawRhXKxU54He>Xw)k31Ior&} zPICn98cn;0cDzFe@7W7?y2DJjpZ+6+c*vFcJD9f>+k;p3vn?5peZ>&V_xN$lVQb9x zt$?GKTt@POP*9Pm#eG!3HTvp4D&P(+KoqRaxjGTnjr znZb>EpzNfoD68WGdv=LKaKJ;{rhSPkdK@NmkcMd6Lwhkz%RzrUw5M>K?~%QzO;L)? zr)L3r41M_s8~9(+m`C>fOxX0u-ZDA}r(V&x%`;7m{Ul^tgb;tvhtJvhgq)p{9%H#C zk&Zp)d%`SAriVy}aoV`34CYPXDU~BjP{b2^YB3RlTtOZHjM>fQ+W(uXq5KI6O=ZQetUxFV#<>C6uan~!kD|T{{J{c z?L{bTE6$=7ef88nF>^m=R3fOwDL;|Y*rwgUmE|K){zlLkl1CKYobeX6mZLGB3|#Cl zav><(*Qryi5gHzdvbVC;4Z?{L zf1;ZHfgN`>)#w}`MlC_c@7el$+WMz`S-lXf4Y{l7OI%9H%1iMGD1ye2j8?d-nx5j@ zjR@^upl7FMFVJa1sM8D7Mq!%#!d}9u98yiW zpN_r2>qQL#{q@3L8qZND|Ao%|A?Ekk9+-hNM4$eJ<$P>Q`^#Pt(Ruu{DZ-8AM$atx z5}ABRnP>^8$a@Qei_OA8laU4D6S`F_Ijm*N6wn)s&E zS~SE0&S3#<_!kYa5oxm_w$lf1uzuH=n!d58%PzF=4R&XLK)c>xvhzU$=#-}`Z*Zne zCFff-Ln=g`W~g{g6E&EWcRdDw1nmQA@fK%FrRjU3uw#8$aXW+8)8H-u7n$vOi|S0J zn}~uHS+@hXm>1Wa?3AgmiSlfsFL(o) ztK3jaKwW6-J1krdqpR=W_-6X|9UR}xJ7T}1==X4Z57kDLum>WKL4^=5*JAtB=f>+Oc-9g$>J^`^i`H-EY$NB^P-xSvgMFde8<$S zpzSd28S7%hW<1wR)vHk-E}LhPidi@|gE#q$NCb@`nW1pk5czr>ZmkvtR^G&YyM80; zC-vCO)~whS6!#F>fhFb;*_r>CL!|btO?(NeT!5d|Y*uM=$~{DWp%h$098Au>tRgJcaVt?Bt?Yig_MA4Ly^9rrJl~1FETm{>~FXDi){#61|KQzq3z5RoM?|ie%{1nBeMAGg=KRp zi725t)7|6Sm`0jt!#y@*tG{T3pk>f7e?3lS&|-f*N3g=CLQV#D(7^8a>v>_&Y0>i< z6nz_Zg&;t^5`>AIi@XjU&w=#lfYZpTF?ekZ?pSb(d2!7?Q#aHm8nKD_;4NjYDz-Y1 z8qsBoUZ66!pjVxAzJW96V=!MZ`w04*r%q;sVshfxj@x7i3X`WO&5AlXPkj(2oM*bb zP9F7>;xc#G@t{vtDzwjvIypkutf&)(or3(lfmv({%V$HKoTu7|3`%;Izi5o09ihPx zCUPz^9s*CDtPj?WtiFMGzQH{NZZR*eStrq*oZ=LlxD4J6=Bi?=I>ARj?RqJ>pBmcr zNb7#Cxg*pY=`c?F9w4V^fnAS{KhLCT-+3J%msw&SAUALwtH*{Z)@j9Zog3~_psvRv zt7Kg-j;M`}&V8Q7=;+)pV8PwFCl0ZTli#Crzh=9y>7A}Gs~6A^4D(RWiRD5$Zil~^ zj-W9lLly2i)Gyz{6~<~{TTR^8lU(%F0Z(FC@ir*#Lp?7`Oiv0@5hpxRtUNoJoO)?2K4%L+P4;L6Ltjuaq{BGvoBsf69f16YGN}<3>fQN| zW{H{q1eyz0m|{&)ELZ;D&@lkW>OlbV??Ewv$bTr+2t-XTfCYC=R(XLt9lKGJ%h>KR z+8wA*l=Y}i5K36D2}Dh(E7D<{_AOycniYf+wqw%7Jzgd3#1gZF-RL}6VTyHBv0NqW zL$+W&)~52nSN+tLO|4*zY4xaiFbdm_h6U@TQyRDPYSeRl<+xxk22uo#A=yIVu11}b z4L4!-0Q*_t^gLKE7S@(&uOV<(;btnGP3L>UA7|5x*_4?c`-~E7&xR5-rUThfg0}QH z8>*`-=U`4nKHG+6?;lWIz1eDS>KKAibp+Dps5*`wgy^m7{q?a|v2*-_zE<={oK_Gt zhNR$oIzg^tAFc&SePAt3+_$FZ)67tucC5V6KOPjfBkIPLS<}2T%6-}?Fv22cfhzal z=Vvynv^nMOqw2;%sOz*-JBOySmrp=>&kCxXoboyC)C@xf{Y6c~P(fD84AW!d_?A)! zUTq)z6K+)SKbNvvM&CobKx)Kd!z4>Z(AiL2a8A*lK}GWIz~>0+?z7t(OKWl&z4WB| zZ!FYPa(2C8bV(+dty534i!S?Nk(cddIhvgvty2eSvvnF$T)3WqCDAJ3dcMl4B%V{> z;A|Mm>mR@-4g~F+(J<^j^>w*|h3~GA_cJj$pO%MXm|sd~5hW~Tx_g*kiYIP1Kq4Q4 z{-;u*gd7;kzo9BQFw85g_(9y;M$o>YP6jqQ2Zs5jv=)&;Sq*rrLAeTHBIhE9LEstY zH#ZD4vU(2jJA<1)Cx&@1t~t!lPsF`LHc|1Azo>?wsbU+q5ou6Pocg#Id7b)V>tGn2 z1m<*R4`3(Vb@FX<)X5six0x75m|HnfC!;Ae7wTj*)7^FQVv18t;LHmh#o z3w1JphUP+@D6ALc{S0imfgQ+&IvGv(5gC-bfS((bmj}>d`A-RA`gkgaL8%j zgY*zpio|euhDjxlcpan{SYjTeS7{JfVT#pTv0TI9Em{u%SsjbSfW4F6MdAQELrGB> zfu6#GyN~ai;wO3@MIV33c3;whD4hE2J-{$eeRJ@*lq_%zw;~ZVhGdw+UBk`KBQVRY z1+0mQ`+5>VQ=;KXURE3hihH;z$P&|&VsrwmFva>wv0R>%ruP7_b{HE2Pwdnn2A<@l zuVVB(R#liov?N9^T`#GpSD9}_V)0_{aXj{npfMy1E8JD)6y8<$JFxpE?px-Plo*R4 zvK%W$o$x9%e^%XHX8xAAdx-qJx?SW4Ro25#3j|GRbILtL)=>(sA#&^)O=T}LL7B`7 zs+^qi86tm;#Soc9cVgjpISP(L3#t#co1@gS`WDgbB$U)w+gsDu#}XnBn{Zt_(bb#XbZ>om1`>>#Y=AE#_a! zY2;T4lzOb79H@83@O@@(_+FQm=Z5cX=|pZcl==>`*-*77NRi_#@>3r}9zoUfprK~a z{XA%>8Jy2ta^yuraoX4G#Z)G*9@}swlakMQdAFV=rgK~Pk9nc^Bmp}{L6vRs(*;3O z+MIGb_dTtES)0mx(K*A3yLsWn40@FpPOPN(d}zSWdwVsYyaJmQfAJUT2pU83D}}on zFzy^z#`K}{w$;0$1mdp#R^tG zhM!;E>YQ@>$RFaA=B#AhpB5v(x1a=`HysE(uY3>QQI@aQA+D?-`XmvRFp4H7q9xTw zGR>B}H{B_I0Y|DYWv(XwBn+B6k&}DST#H>*a`La(FpZ!wB!5u2tC~g@gydUbJ51cS znhw#+Bn&{uS@8iV?&>(p60A~Tx^|F zWiRW4(v}reIXUGs0IkfAF0qrg=SOWEr{D9VOU%Y$>h?8pJWddApk@0FHW-o%74GtN z`#TJ_(ZG^S+}BtBl$g6qZ(FsIyguqlv5W+i0N;sSbX2}PT!Xs+>T zx3cSUHtDUAzuX1NF}6FKo)y3uWj5t02*=h^MnN>Q`sA9~%tu#fV){kYhWhT>N&2av zzAW=Pth!xKxqyPyyMzHBL1Re%p>UV$hx(u!^Z@piiTk?FA5L?-?r7>%Jh>3$HLUQQ zVNSVS|EB|sOxO97U+(s=`P?qDz?E0S-_3-M)9-gsY>SP&>$~49NouclmBT0Q?fLI|`?4h4o_b zN12urV~E?M-VI&_-a6~?(nu|8BRS6kxs765Qzx3MtVY%kp?j8YvXXA!iS`WBJd zW(ifLXnYm5pgu@+lZF?;oc%B4YR=jJC3{i5bxP(JUapkID@$a?@7P_ApfMyzDct4C zyRYC%H(>o0PK%4emGMkl1%ca@_4Hxd)Q`JWX%oFdVty1x15s=HVLQ^)#DR*VG z>cAqiVbwPX%#kV*FN&xEuIz@N{%&Np|kSgl+I z-WKLEB&R9d)p0al#XSt{tcm+}oKGmY3?`YgS<(LwuMX0MC1(HVMRmanQ>?0r!o_v!U9_@#8Sq-_Sr)Cl8w|6R zf1|WHY0bQq_78?h~2tbj)B$fT1n<37sy$pd#I_NH7ZXhg*de8?8BL^BRt;_S5XhQj$@nSsC-3CkLS|w6;ZmmELu$O zkq+auZ|PQ2awU{*J(Ch1dzEerOUy3zJ#_&qOtIQ3maBAoX)XYp%45c3qjXm)p>%WU zVI`DqJ%v}sI%{6asEnfI9S)lXsTGHFuV95K z)-lC$73BumQ&AL^2X-~7Rm|F{C`w*xk&2Gb8b-%YqY0_#`07PVX2)+TE#k;ibbR%; zr5E&1DmuOu589d?KY%i;pyQ{};wpLtIghSXfkX2^kW1(-(qWwTb!Zh8tO|!VFe&a& zFNe0W#B^u}eFj#TVzpK*mqYvT@dh}g@|gCg;n1b3aA+RguL_4)!*Hk`#Z=Q9;&p^Q ztDz65H$t4DudBg>Ti}=;+^1}5@Sq-*NYjhPJRO3ES42ws5Zw1HZ%cK;^;$3RkSl`r zHw{VCBk=i}S!sH1L_5>;m`Z*a_(X1g(OQjk+p!SbrO0U&KZ1T(sqj`G1I@6_Z0-=e zSK}IxJB<2`rX1Dv>ewdLsyYk@QNQXi97MCL>oGO6dmH|IF}5Ytvx-H3VXqW|7UV%Q zY{PAVVi?dpK=w1Lbk!ncV|rU%kB80J8hTVzERQhJ%DIZRksteuxR9K42EP|g}X-lX0w0?y~4Zu5ESm)W%z**_oQ}hx==h>8RXim(2)&t$~}mrc8Kxn zOI;Z^rwZNo*hMpN-uPYhLd$LOM)X<<5==PB(=*Q4Y+x}1)F@Qz-lqb=T1 zL@l(1KR@jZQ%}d0PL~Z1HyhL z_4j0zZmWLZE=pn*=`xTTj2gP?$jh*OJRT1^0DTQa{L8vjw2mrB%Q`5?4DW)J0Occa zIx%ksO{s%|D1up#H}lcMP>^{bEMd}I?}CiJrwLv(+5u#rGT}ipY(aR35U&Yc0CH97 zQecK&uuOZ9JOj(8qcA0idxLjbAZXuvmyWhsML9^*6hb{R&@kWA)C@GtUQb5pwq%SZ zy!0^(yajG6W><)Q=@7iKu^q@RM)%T#|67b-*Wfz(Enq)f%W7A=i_zwWE^w+p`9?g!o=w-vJ(^=IM=66kawa~QozKiAdkMzzO%G7;Trnp4#1 zU|Z7HF5UpNy#t{=zD1$u?x+YxdvvokKZ1w<&>j^*sK%sjtZwAd$98Cbpx`6wBOvXS z2@l%OR&1$5@bUi@kW9C(8XGs$clGq-%)v}IN2-E{Oism}&ZKTBj zu*Yj(eN0*h)1UP*+{~t^2IyM8=d5R!VXv^Th>{4}OD?>5%nw+Or&Azpq!1d^0B!n` z7B)bezG0qGqv^KIL+yfhU913ao!g4prk(O>g7+Wn2XchbH}p>fedb4ev&z{NFI3JM zg=^b-XHX3O5tn5_e7Vxv%5MTD6LL^f4E1XEI!;?u!6vNr{Q8Di#42CxvWz?F6xLdP z`;?sSH`JpdJgS#v5qylt`hnjIhQFfNMtV;9RaWUn`k@lipWcns6JsAuw2HTQGorl| zis*M7Jby^UD!<@c4l$Rij?xpc2+?_zUdZ|!05;go8Koy#N48bzL!(eP&*{Fw3K^}) zWk>53Vyc25F33xh?P5jwz-ImJqG@U5kj{Gb@K!6mNS!{Mc5rSjC{>8_18}xk3DSBd zGKlY6@I#WKAD;7L?tTC#P0-NXET=+sF6m?Rr2N^~Rxeor8)ot(6}u21R1R7;`6-lS zo-!6u009pvHXox$S-6>f%y}&6~2e@^V(V_G?9Vb3gI~a6zEli zdx}M26ZKwo+M!Wo6rOt!&6_^(6M4@B-jBpOcuze1HvmCXcqeYTAcbED%sCFvwoeAO z&}q(wSV2p0OpBu16u0^+>0YR+gyrWaOMq%_i&Vby8TA?(NaImniZ0 z$`&ybK~s2DklY@9G94>CYk}?b!Qs(;wwprEDX?3N?Kbna>z5CDl~d8>5j2ID_O@Ge z9|n`Qz=vWFuxriBb~{nvRKC3AbU`YNbh43Vfp1Nv<-k$21QunbDi%=- z0rU9Jr@~S$CikTu*pf=e(siVrMp{`S>o>?b7bSfIj{;aU(%YkRLs8<7@S&Pc2%5q} zL2}pBG2|u(0vqpx!=oK+H-Ij&UBPyzdE5Oy24|AsYUs`gcvS~*tGC^EcuYkHNM>B=-XsM4?LEz-$GnnB;HS~L?~xerXrpfrn!K+s-Lwdts; zyG-6hQ>Vj{Nn!==0Q3j8{kS+vjFr9R0pTd2B4lt$1LeghEy1U@YFb2J1ns{}T1XfJ|07*O7YSpauheS{)Ua}N&KQOLUZNQP!18;xzKV*> z!Wg)U8qLzHmOsT^s2g{o=`tdhU5vlvF9u_+as-0Lp!ikG1$o{tLcVx{iE}Z?XDf_O z%+gb1FR}h$Lx0F#yXZ70P`m>EmN}OwdA1&vhdIWKQCQYMo>U<_&cx63R|T+L5+|dU zwJh{L#hELYak{R9rB#u1r=lNoilp(oYv#<><8rEV`2q!w4_4q7haKQ4H~36}w~`&K z+4(wN+(p(o&{U^*!)$0%oxwWO1;7-5(F!!oX5cn9z&u3))j9gJ+O#Oz5ouM7XGC+b zWU`08pQG2e-r!U9fUKaodQ~lS+EC0U(!}u=aJd5>ca_uV@4O^+_$()46 z9udk<=Wa`MOdN(6cnb`Jlbcz@3v z+J_-MYbwe)3@hihmCT+SUkzRa!2`fAO^Sv`Rr9UVd&)I5V-?((M%xkDI}TF???_iy zq2OK3fA9HUZ}VULYW;)66JdBfUUm}Oi)4G%GZ3HIKvzPL?5y}!_UI|LCucuQ16J$N zp2}IUTK^UwyQ#NEkIcNsS8_oodOJncMwV}mU=XO^(jrm$V0>Fk2QKOd2i-g zJrX5~TB};L^;$h=keVcWJQ%)KuZ`+CzE;m)AczN=2p%z1<<^}WxuCQVaS+`4$ReH~ zXa-7>HctVyfT3@S+y0tCW(=<`5 zwM8^R&`JZ5RoI~6K%I!^ckQAk1l<7l_oXyf78(ZCXoZvA1YqRG3(>*#C~s-HzaHf+ zO(7dl-qKXjh&pe;q_;GU*`SxjQMYe{9#N|~XWYR%XD-PKA-iJa z@BDvvs2t_AiaO1%3$Z)9b6$H3WZ}sy3)!77d5VflB+pZE<>XZ=&Pd*>;ugvKRNN`~ z7-A^omQ(U8Nl|HNq)0=fmNYb)N<*Uq7P#MR(hDSqhhUWsnfiZ>nvTLBk(<9)lGQZl zidC9=Lqar=+zO?JoAuP71dzJme=n9L(ZbE>GD!?&r_-DD1)trkeSk+5hjsZEN zP*zI~Y6w!~Cl(Qppf#iVTVb)8VR6`2-T!$4yk-5P`gY|&eB5v#@)d3kjSTQHFkTE;X~ton>^t?`obUJ@dd*;EejT9A3^$_dJ8&zo5y_o; z0p=v{)XOBOLq)yX@Z=;d>>NIKk<=B3YJL2Ch@gE!BX{bByM3a{#xJ|zvVXV=+m|7c z^Fdk4v|b7~%f2wysc>yKu%G^eqwK5dJ48P&`xRg}8CUk5AJcs{5~#&4 zJx{R8tZ6rkXoY~cWsKhiPX^K2U2ad}>E$jg)jXt#-FgNqf4W;Q#qomO=nt(zhs_ z(D^$^AzL&@S{LY50+?nJgw9`*3OTQpXjPPtdnN>QRX&IKvVA zJstI>q>%es_HiF#iJ8SaLI1%}d1|O+`w2(D2`c)NGEm=$dj5o4->Tq0(iB6q@h2RH zC+HU=dJUmfWweXp_Um!MoEA%EuP;SN3BT;yv+C~GCrNof>+%7;tA=Ab{jeTgXeCcU z%i`9WcqDmYEn-{v{L$Fg!Qv0Ugfj@5L88frv2wbSzB`QhE{jC-0`qYlcOhSLSG@Cn z512nIHa$O#)7le?`x*Qvl>W0`*s0!t!;6=43k`+bss#IK!_SI(5gbtMNAxm?Qjg#y zqzGlH^ASDPOi%PmZ#shYx+iqvh~77)JD2uzF451j%Sdc1oQvz%!UHX$EP|%cuNZC7 z8DPduJh4$5z=sN?%%d37y3?YgC~PMEY(#$^MR_tQ{+M0>QSD=T&6KY>lPN|fU)+;o zEMEK~2M)4`(FmGCXR1s-2l#LqJe>t#sRHTvF=X;JJwAp^=26b$DoQ;L>+`6~aXrQP zEt)_om!Ht4<9cZ;zXA#SW*!~abCp!-R&2aMuMTZROl%=$+M73?;4flw2enQ?N!|^% zh@c@Ti6TFtvL{fnAJZo%Fwyv!#vA{#jOgYGy%>bqPhu{zipriuH!4f5PwMLtIZx?j zW0ZOQ7fd)KcFO3w4^W+jhFU~%1g$W&JEcbzFU$p24XS#N{^4?bzW%sOSaciY?jR0U zWDkqhK@CrQA3mkWB~;=b=NI1@x2^8WlGpkK3brE8LgzQut3>wG=>3%_zY(RM#`6nG z$@r95gwXO`8y#qTDXh&fi}(aVQ-t57=pQH|5;eE$n+9$5%qt6ks{&~EunrA+^RU-BB~*1%o2V*-vjHe#UF~7Le)fT zU>z85qHyJ2AFX78rkdg2U|=IWc&$~avi@3lTta}jl8I4p{%~B^F7*)p!g_VYAT8wY za#AdPj2^Wc*iZk#hiRcJ7T854KNz?I?2*DL^ej486G}OYj@N`*pT*JAga(||OC_Xo zM^+1x&9g_^M0`}Xna5yz?g)!mfuN<*sk5m2RC;qvs(Bb z3u-rU6#Uu3MdcrnKNt6vRxj=^($oujVpMsCuW8+(e9(@|gulmdD;R_`7xeKcZ=2uHTWZjN-*8S$ z&3f>g?yuqL#iy6_9Efa}^&#>xjlQg>oE9WEIQZyG{`b(a)1nF$N*a@0$M1KXQT0NXLiu zWK`hA=~!Tw?^;;#FDY0oprG4&2|STsm=Du2GFz`M$H;k!79W>O;~>JOn+Wi*oJ zAsx(V&q;a+9l5Jl3sLJrYDI9f`~vUapG&d#Q0+IU{5>ol-Jn+Y^ltJZ{mjCPbo(CK zLS3?{wzy5%?xQWd1-0&@EtKGarxr1lnofb@8N1hVjzx4t&^#n}TUc+QD-Q%X+D&-n zv4XZJJKJVhSp>q`|3yMuR0};Q4AucKPAL|>M!DcX)C1JiTdH70A3Z=@yya5)wngjZ zLfmHYr*kc$JA(F><{2ux9-uAW(k0{HzeW`G5N)CSc}6J@RSvBlqAlLiFe6$4p;cw{ zfQ}*^%xOcz}!;i8Z9+_B0U-?75oNep~-@fv1X9#f#|2--#J`ABb;;MWdt z^Ellq@|Mzj)koc}2l^c|7{ap1ACEAj$J&IaE$h63GB9zILS3L5SsW{Pfa+&3#xUQ5hO7K&$~!3@--$2 z--EN4c}M8+W2{9hS_%a{G1FVA$Pe)aPg?ZrnmQU+Bq+itFS{ zSi{yD%eY^`{TDpza?@4_mHG?YL=-othr8KQ0E_FgE_lt|+!)3~`4S{)i_`wKpHOeM z>R6p81@Nl%@tMz}ny1wsoq zi3@~JZH#@1wRM%xC_q!(uyV?;$9^m|#7pO~dGLxA)_}0hO;S!7qy*`V^OFYYBnTJX zB;}Ps$}OE2B3z^wAiOt7nJ}#UGFW+}v&~N~$0Al*L|z2LdDWr@DX(<4du}oEs{}$V zH;Frr@cZgCO5Q>yochjYkUD_S!%Z^WQ=|?uGob~ZIadCS1!J0K2QfKKLf8N!RUNK=+b6@|G@fF6TuF}~bBe=>h zdKKGNBN@$E@%_fc=S( z>2;K=Zzd;Al8$A#rz`ENEg}rTAh43~8*>G|E|(Fp+pz$`J+3eaC7D!I;nu?_#tIox zA14>ph3f)q?7{g9OGztbbQ4rw5v(1{?)3nE?jZ!=GwVqQWv*Q3?N}SZBzYpRY5&0w z$y}3Wp*W1M2lkzbqfY<$2ZL`>vc1N+oXZ4JGSU!b7*RJbWU3+BR&ytVa!6+|5e618qp{tT5d!KjOexzS>7mSJ|n7bL>-N2lo2gAq60>B+lVZ0 z4Lu{OZbTi8Xp|8xH=+YZblZq5@4QN0=p8n8n{G6Crzd^J$5ew2*pY*vHRsl{-Dnyh zlD6T49Y5onnh^8^G{A%f@z=+a%4j(@EW;%%Fj;sb zx+a2FbjHVyBJFw9m41OX;~r^#B<)cR7qQDQ2jIr1c^Q)t9HxKtEBnD+g>3*Rg# zi78#V&B~dqo|>b%j9I}}(snrU_N#<#LE?Ut&<~PCNt$a zrmJ~X{ur4*8ZRv0%;Ko6c+WP1<{|0IW}*x)@DC2-6o56|gzr37uw(i%rgO?ldl0() zhs0kR%3o5(&!yG=ju6}j-|3I)+e4T99Z@LRD}PnMToy;(LVG*~>@iOh`76uFc39}= zjw=gq!`dE#W{~Jpi=#$O?pHDu@9-00zv7;9{x39p`Ywx7SPib4*%&_tsbFc;(n)DQ zhOW+5_ZuX7VQ~}>;OU4l7s8crajT<5@eg9aIVSl436rHm0`0gzxgBPIXbSmFjr(hu ztPpWIREVkqW&DArTOCQo=WykiY7Ih?pWDQ8R^xlxZnY01cBcgxYKyWSS{<5n@Xfjt zSs-4czio~W)c=6*)c?|UN7MFQhoXS}@Z(yzP0nYjHpVFiv3M|eV-YkDDX6CvU)(5Y z$vpr?n-6TMiHo2f3>C3dn`p;NhuE|S%~Ypb=8qoik($06Z$^EDw3Bw zPEEGac-;|Ez9hJ9ycroCgyt-DU>SdEJ4rgsUKxUh9rxPL)5Bw*F1lGBltQx&=KT^x%A;zM%Xz&A^FLUTV2ayn9RTWq%zdq4QrEH0z2 zAf0KXRT;Uj20fD&QMilcK}pp9U8p`s&=hGINTRvI`vvvuifXf?Kj%U)aMj_t+FV9P zSoW{Mg;Mqv&#=p;k9C`6?Vvr*bqD?`L;x#t1_kKryMGftjkw1K9 zHM;kSJ#Y^}^TO}S$i+Y4^Ba7+cns_x6GxHq2Rn-7=6V-u@>Mumb6i@DRfI}=F=<9H z99u(Q2BRbMmKEG8n-}cJW84(iNbaQ{{T*6x9l$I%;ey8suEcw5nqlQM2$%mC z30LCbp*?K|>m?ZS2hNKMg`mQBQbq`>|0;Deq6s06sKl#WD&MQ_b^`;%K^D(~@&Y!1 z&k7qVk3t-=Fc1)`>?9jeMyMmos{A=a-3`&iP&DaP+H6F>LTFVPVFv)x**NW4`Z+k1 zVsknosd|_r+^9`8MjWJ$VU7ZMlwsAadbYr^r8$X*hk59nIt|=nh7v5{w1S(@bG8c!e7)4%u%J;}A3t$=ys-cH%U@ z5a1d&VY;XmC;ywf^;yaJe199d?duVNOcBpX3B5EM0I`bO62j_IeX5;O6 zA5=A_6IdjvKx=b4BGlG>FDY*p6cLk8pxgdZ)^P&1vhfV&mvX_A@L-IK$op$1(c7Gk z0y)fw3z%s;Y!QJ7+8s*Cg>yh6o)f{%_ExzZ$wvB5n&g%z(*}3?Z#t0+wVp^%a$%%? z$SZkQVds{zg?}QHZ#=F1P|yF$Dc&*s7Lec1$cpnY_C~F2nZtoE*2hB-1tif#<)3Up zZJ%1%D#y^H_?9s!l>parQ~qYkGkNDQwnx&42z22)v@pU^A=~S*K2E=;`w@;}*#=-i zRMoEWV8AFU80m=ouXH>$iNrzR#ih(hM~vFgG~|fdqr^KOWj?$s%Mp#uM@KlSOMgT< zs$+gwILc8rgvZUAY7>(&jk`wuq8!DoYDZ@sTJKITpj+_6P)gQ|Xh)84=K?u<2VO2K9nNwTUcyled*Iua zK-H9^fh8P?h?bOapsc|m((&b0p;Hkh zupc7PY^XK3DX5B8=ROt`5RmK8@{SzAO4tj6frfB-d9+JsI#S+o4xja0SOIl4kakvZ zB<3H;4y%@(EibCJS{zUpJ9+R111wJ>Xo}H{^c1wtFiK2u)QKL$r3mutZWm!gEg4%d z8EO6yyE_oHF*Gp+d5xjXDULkWZ`k@Qx|D)hlS)^|R&YmbJtNIlLV58tY^=T4D9j+3 z9ry@SX#|Zkk<}H455KT+_NUieoZ`S!JRIs;(X>B{CL>+Y$XDs&DSi<)!Ev&mv0+fo zhu$jIb(QT`FWrB=(s7j>v1wj*_}~hg8ZZja|EXiE@MA1%ASgQ`l$#{%8+)#H(r_aK zP&0bZ8)+}b zM^zkAh1^n+$k!J!@{^FXFh3E)yicE5L>~mrWo9uHq?2}6K{4{s4I{Eu#atJna2dnj@bVC7M=)lFdV@iI)@L1$MuuITE~R>&RK%5mP`_n`({% zpoxjHadm76lD%ZW>9Xk5(SP9#gP`T1hSeQOsM49{4K$)y}IVr?3&?8D@fSpcL@RrzF{^LQPbmr)d0P zZnq0JWx#@RsKN{=wNi?NyN+CitD#l8Z5mo-5#(!qjEddT@wpQ%Ahet_N(jNNA`gLb z+%WM5y2df2keZY?9qR~As*#SfNgnE+?ug0F1rm2Py^RBQ%4pff_qGbouK(XyxI{o> zu1k01s?4(a_`gcYprnpVv0Yn(;W9?n)f{J{9bzxgbIkDVDzXUq)p8Wg!&0bhSXaFkM72TCFX8Sj!QY#JSzmLg%sRaau0kj3g}IJjL)LgJuVaSQ!@h?lrCx zPuF(Ll=bpeP0>X2VtH*PF&YK&pJK^=ah1@5@&Dr17=m_>FXz~RQS8ujIh~?d$>2LV ztj12KS|Bwsh;*rzBf{Aof4*eFi=p(s7Ou-C;?H~+Bd)e1*0~*jcDWeowQ*S8!JlU? z!I!li<+CTDI4Wo3VnA3>X6lsTXomC1o(!CKmStVaa8#B-hp=%Z-+|iLV;3H5+eG>6 zIf~>f`pzOsA!sA9bsbMb01XfKdzFg$Ms0{&Du@Qwb42BO@)mv_l{{95=MJtqRToM! zmNwLLL>5>K=1OKyW<#M*PB}z)A$uI&P^D&K`v4tOFg>e>3xMB|zHidy45h;hqTxmC zS$=+oj^BIKGlDYd;_wtNyr{jS&2>Ub0$$=j96o7<7qc%rXe^V;I>4Lya%fb2M@WmF z5DxGKLf0Yp@DlcOIN_**PXqq{2zw9ssEY4>c;;@&&E52{=_H#3LP;TzkWB(4v;c+( zp?3nID3L8xe>uEE(Ya=KKe zElJ%aHn9(B8_t|88Gk9_CulfH2J0;5h;2>283Q8xO=G`&%os?V81~k8O8|u z?1g)HkQfu7Yd-+d7p60u+qd(*$2t!dZ0wl}LXtmWM zW9MWwH*~dA*!1 zaBl(&2T|Nl^L(&l>%7TXcA87wF6MUCVmeXLv&Tm^)>v9-D79f>3wbIanUnEJPvBo5 z<%_cejHTWqoZPn?fqS}50agPhOk*r2EkZpne($Pf;WDVyZdyUpGPD@+?>~sUWoo5t z2b#sFV$mh7R*Ul>VpwbvUenA>i&E)6oA`&eI9Xaua1SxRn-*JC2dwgiJQ0Xj$^+Qb zAeZB>{L#oC5ON;)n8IE*1&lSk`~<$5`novR4gJzDBCI>s7#wzFwL@fg*P?vMWG90; z)l(s8pq|Ih%4cVVY(VX4L9#LpY1MZvapy{IH{y~37eAAW#j7}bc5)uxS`5A@X9 zM=r%%FuVHMXPm{UpC9G0KO@q5Y5(g*Ipv^+)~QmK+NJ4KDaRdD|D0+L($#L5#4acT zBhWT4k7kdIb*%n4fNf23(b1k*&auS0JxcvW1ocKMpCcOd)>7)#!O^3J_$%vi7|>eG zK?4Q-W&P7JY)IkJ2@euDUd-vO1#}z(^nK)FV+|K*((=J;y1FaE_AuFMT?k~3S!4_Q z2DWF&_A^$F9V^Ke`#EeciIcsxq&nm1Rgw;$TZ4#t2hN-aC+K|@!Er>hwv zr4IsI8=JsV@mJoIUU$+r95cr`XehHyMng&9iQ--Y4+n5GfsfY!qp&mvuk2vFp?R0s zOyJkR+(O{7bY37=*Nocr0D(*K;$LbG6o2*6QtRIU^EQEZkmg?$9qnU|4+#BkJwtU@ z(V;I?x6z#JF8r1EYlOqb93kM9iF59qCyrMDNSvzcxZg0YNHVpe&x96~( z-mq|&#N@J_ZNu_(dsDWvOISbMp2v0$46BB{tWP5&un8ifKLQ&Zge}YXE1%T}Eb{+L z0yo9bPbS(h(T~7A0qjrUvo*j@=12yw?D<>+{Hj<(;FVymCGh<w?ji8*YZyaO zM*kr$68IdLmk7MZ0MjvCozyQPYNG_ z9{{kLz|}RtD7Yoym8B-4p`c(K5qk;z0hs#;{CEwp#vF4A{HMnN$BXcR00)IQSp@#d z>>6NfANhj7)u{$}sOU@J9su?u@Y6NGLCoO+udH2~0e(e1Pv8|`t|9QE8sK2&7)9XA zw~eH`CVnRHk6>OT@CpM=Nkaf^D;P=7YOW@B8Fz%DZZC8#t1nxe>&>Sbi1_A5} z!?8O2mE$$QVa#!iz<({kT#dp!MDzi;es=)-68KaNFoKZ;UfEO(ASHN9nDA9-v0}#{ zP1Tk|^gKC<6`u^!q9aEVbWVj4h)^`8yTx_r_WcII4FV?7D@^q+dA|EGWzyi$(#G~L zX~rDe0H7usEtFHut)y1`L1|wl?T<@)&=BI!llCdnzC_y3Nc$RTFCR*nSEYRi?8BqC zq7R#j;7q2}!gWUK{liiDrizV&wb=Lt5ER@7Bha?k=nb4IokVoJBF+p(194FVR%&&5 zq-a#Bd9a0}yb@E=4q|Mj7E^n81j-b3k(}Ndvw>YUp{wQ#LSt;$bs?T7ck9GHa<@;M zuf*)_f(ROdN3h5m0%n%zOpnf@3QXU4)OV>zSGGW@T?=z7p2tJTLcS~@gx|Z5Y}-)7 zpJID#gDXd|4*W$Wo)GBmWaRba%Rp1>R0GkBIn}N(?dmAR*sktwfW4P$0&25UohUKt zQVAL+Vuor@wAdwiuS$7KR5qvjq%@C6Gag0RsScIqE7H6s%|9f5rucfO)*$jQ3Yt@m zL&iGQA<`@sF~hW!2)mnDt#S6oskVpdaEr2GS}rf$`tUGqK2JK2dEGBye~YJ6UG)Gm zgU%Q^)fxB%x#LgKc!buZJ{>8tOQBPJo41)kACSaIozf)Te;qlne)b!_qFfPBrxp$mpAwc4>90 zx37ZHSu(c3on11VYJI{D7t2S&i$}$_ky;9Ns(dpNW#+25IZ{iFxQdv>sdb$Sd|B^8 z8*)QrkJ7p}D8mshyE-dYfmw*J-rLoIushWWDlnrUbgJJ3!g{}Wd6ZT^db#AxoQ^2c z87`;#Ndkm#i1VYg+=l1CiBo^W>p-X4Hi`TI1C>IW_hSEEoMhY8b)v&PT76z9#^0kQ zr1rx1-tB5}3OO4P4`(AK;|Q!ybsyle>1h57?Bw$J#g>|$kHkKUaI+g5X&nXA8F%GcP z$TB%L_@G!bMjPx)Kpzwz^cYZCfx~EPPW;Fx>@2yF9M`Myj^QA(V;@a%vik9R!U9=x zW8@HaSj9i|u)>m?NTL;U9E8&cue_wNm}H?QLuWO7>_d!)=3-*m7M#xbE0-TeMU9#R z4X^VHkoxrNvmWEs$q3al*W>~hdCqlH%VX!tO^Sj2lG5aau~O zlr#jlttEMVHnlZk)i|w|m^w}i(J{jy_gNUZm?$xZid7J8v&4pq6YxRz`vgQ6Eb#^r zUZo`!NxwtT?I+@|r`!heTh7Z*@LsJomh9wVSFWQEQo=L|Zvki<2^V9lX!e3g@k%g8 znmX7CUiuhk$zeRKM{{J25*8#uPXI8-0xjY%euFX*&BHo1(zkU17%YJs0orZ?c>?9- zB7O^3EhH!Mu&VmTGKmrv0`wTXa|QILf5Km#4CQrs*sVZg;;V#(O65T)HqrR&(M`i$ zhfprj89Xc7CJ>#jn`6o-3!Kelgakk%I}}Rl9vQNkc@tvImlhT zg&q{6C+ZZH1+aNgxCUtMPg-3(wvKjO7w;wUTjHnj*jpg02>Ap8pO6hxE+5*e(Xz^L_6Y&vBv@2 zN7%`Z-q2JF_;i~Nb{|b<|hYV0b31w4_{Ks*8^Jq0L!lvjL#C+45ouVW)}M* zF8T2kglfkrXuth{fk&hx1Ye!%47vyY$~ufuA&DhXw8K;3V57jk-xT4b&C2^w+=-zF zrN9bGL2~dcu=Su6SV1YM6Z{<5VPQ)#b0|pDlXx;Ks2BV;*fIWujD3G?5X)~7q4lqW zz~%fB$XY}>nw|}0H-Y2eDR0QYL2?&s5$8y|jioxUJ*LRW;jizru@;^Jif_DQOE7DZ zT#Fzq>^rQiwMZ?>g1Yzz`a4;RI?)AU`u$q8?jaMzn83*P;qpsGFhmc*j2jx$EjA9U<~o8lHJwMtZ&=0H zsCrH|o5!sTU@g%;*Ba9RQ)8ksc!ceC1RC6z0oa7UGNKeIu~ExY3Z;4Nci$*X5fa+v=BBjk^!>w9wOkxum>3KMdg)79cHnA6_oa{c>IASOcdkxVv5e zYs7I~BRo-+1v2`iid>$br0^C0f%qB z8(udZ*$$J)*}Us1RF}p)xz<65yhJtTskU_r3c_S?rsJ>NAO~qp-wcARZs4I&!R+o% z&?6vQj(s-*W;r;ZZ>;->EDX{5qzL%NNTBZ8{(}=!yH#B;Fy^ z5g15AWq&%pn$5$)ns%bORkd7N!DjF9A35QP_`fwD2>^u`j4lx%}NXl;eg4m!Oo}|47 z-uIly9PSC3jqCP%fm2DyljK`!C%{Mih8HwBJXt;d1K!etJq_}QO$;0H@n{Ngiet{> zE-79D(JE8yV?`5_Y>?Lppgck$(6x0744>_iVdDFM{gm)Ba7A_7aKL*8Q_jqt1;!s1$Vv!S<#M;J?OGJe5+Bm1 zBmPP^%FnkHT^eOuxgM!d3Beds$lLY+;%$X?v*hyV!24da>os*I5DV@^O&xU~FtO@Y z93!GWnQwr6D`85ZMAtNR!m!~i*T>@`@59$eUg!q?VIaORQ7moo{R*@ss0G`MH*!}X z`@=7vhW0R**A9JgdLYXp_u)-28Npxr!qRBVYA#QV{CWY}RJ2{ZF=Sr9yjg3^XLGqH zs{MSda%EwP+6BU17GUcAgGWF?a@5}|P=!f89t48C==R+p^ z@(;>2$kWsX9~Y}@)r41s9v9o<=a|080z4!`yn&U`;1C?UaU6y3)-7P*wO^}^vv+S z+nl0Oq87b{wz(&ygG~gdq-EYV4JZ)p)u;p5;W8P*NBjV!E%P>5f=#l#Ol`0SuPYZp zxWWW5Z^jekf4O=i2mWsc{~c52GsXaGj|BnIUA>qE*Plar%0w7|z|NG}ebpv25x{E@ z@?0~Hl=Li(&Rpj5L7^|;(?GK4j|U)`Kvd=+f0{#H8U5)P8!Ik?`(}`}^8FJqEc|qu zi%|>9`$0CCzZA07mV57mD_w9u zM(x!RG1v2~_IGtDpXj@xeEM{A#L@xvd)#I(5Xb`vH9_&~Z{@ zvP1=;f+ygwS2Mp-1352nDzoX8HV>$F_y^VWUyPrjMYSCSb`>d+D*Z}|&NrtlcrG%6 z^1J__^_1Vw$M5-6VMUeSQt??6_z>J-VcsJ?o`IcpC&k$rS`**;JY>Xo6H$j|@^bXJ zdAzo*HMR)gwkH;fzmioBh2I;p#Gvo9u_gh2wkgw#xd})Lsy_;Whp^`z039`gE+)(4 z$tlgGUQ%SFNy7-R%{v5tVhGL-yV%x^CxjdurS zw?xfp2tiX*$jQc5@#Ir3Alf(DiC}QkLD!(TPcc&H2gtpa1F~^4;OYuaJLd5YjXow< zayXF3r^OxhjaS$`@R=_JY>DYo?~L;JQ?U~vKTS?HL-vj-*T;aXcno$n!`F*`MB|huW)%Xf@M^A zCS>^}rxenoBOCiXzDC{mjIn0a6@USz5*<{u;UH;xDR~=0$BNplps>E|qEu9i67IEu z+Tik0@`M$A*V9g9Euvzqe58oa=InPAuEspNRtUz5#?Ui1a1QQ6mZkk;_vH|sTg_IPCmX8HDSNVeo_li34?O;oG5-$i}w|xz45-8 zj%6S2v7N`NEH8o29r0HZx&io>q6?F47wLnRl@N?Eg*=52dcW)CDItTW1+)5K@tHs@ zxDzG25ihT!c0|(fmmqwN06yu7Y~#JWu9`dx5!nsFAM_ zsg?F(^7GgMw9)~Ec%g~EjDpchQzzg>H^yljL463b2w?b6y?~cDP*1Nx%hncx&LpI; z)oA0rm^vLF0RM+USY-k9Hl9WVUY?H;K9&ZJgWJ za4l&V{)T=U5qNn{^x<#0J|bucS+>s)pkB($^FsH`R`gz~6teOfa`aMOTuk`bRz>e* z?t!f8pYnq6&@o0Q^%P|DNG|hOc0yj>Ecz+D2auiAddPemEd>UkdH9hxjb3U$WQQyT zvX}B=sNhDWxJhGGW@|NoT3JO9{bF}aH>scwQkiXZUuBQx9Dh(Wj{p+$z zX$EXZ!c(5q&?Rr$kOaop8KjjvTW=Y@mm+!t-FCVDZ{ZM6n0U2h&WdA*rH``DCSEz^1Dr_2r zkNW{)(;O{6l&0i%+3b1wh{!B)0!(c5_+t)UbsZO;xmtan4Q)$x|F}qMT&54!{>L7NGipOn09mQri4Ea;B`!PkLsBm8rgbhu=KfAFLQmNUExh@4sDDMV* zA98bvB6nvuw*Gx4Wqb+%4_P3q7b`0Wk}=_nAbY+z&p<-dM-umu=@Sq<+jc-1Wjl6jzKyQ41gzTbUPK|FqkBdsh z{bF*u70}Abg7Mcqkd1FXkB@q9yfIy?2U(^im(wv{K2M0g_*RhK`nHGgZVMoL$9$fs zzPb~=;}GyikxZtNoFe7(BsF<1+C3lmPnj}3k!0_gkEM>2@1u6Cg79Sv;O{*V{}eSh z3;o-BkRI?OtnM?Pr>fmU(E)!4;YABT@zv*0`RKm0@NHvmYmN7t_!|MF-ZLM)ckL_4 z#U$_>nz9jBaHP82o0#-v*IC;8}4Hiy~to~I|U z!wD~!8}96+5cy7l)zkDz0j~yX-kq9do1NC=cf5z=UDV0wz~$1$dZ4!5iHwraqAc9k zmd^*&`UFzc;yCf=0-Q995OE8!4`7LCu@D<8Dn#FfTCscUU0CY14aS#z0_?2;F60x{ zC&jA^F`Zb6qO%r%r8adci+RyJ8^oDG4d!7wu>*oVrjXN!#zJHVt@olFehc1D7DBGt zd363xztD4^3fe!f5#J2r1LrL{Onl2Hd%QI-=s8ix4V00vABMMep z^>!y*G>uI8UD50IFv#xp%R{w5$n(@GSoN+82Yd!(v;6X&*b7_8y=qG=9839H$X@o# zr(=Ry$n#Y#BhaS5FAMo2M1%Lu|Ka!;`dGG^d7yNQ{yb5`tdhu0b+rFb6K0b%P z5rGR?L6Enw&A=X=vMfZfE@bI``G>_6fg-hc0D2zjK?#H%{Q#c~VM$cZJx1#_46=JI z`PA-MOe*B*)b*(^)$Eo68t$2+Lkad#?T4gLm_QKswlJ1qrCSIEnveH{vz z-n@MT!~wsC`S-g3xLZA&jKTMJ;9s;f$R>bR-z<=t0b4+8}b1`k2iAZ?n67^y%hesd)XEh@=CSs z3#cLK;OCh#-oPgdJYAhw$VZ1TT;fl)mzM+4k5J@;k(fGYjJl*aKptk|69K69tCE_i zMJeQC)yzG{8>J-xti2QTy;1Ea1-d*zdLQ^7Y9~9=V#@k%!fG*BN^l!r6BMiY`4vQGZOO`lPR67xEePsr6KgHeey9 zkUt(vQ-&Dks6Zt9Q=w_bV_MK6e}5_x&3Lqz7P%QdRir)bqZeyVmELMPRohG0J#rsj zglQi=Zf9Q)q*tocayeCccUCYQMxbp~sJ?B!;66#NGs$X6ZZyd`l6=b~mq_wmlYCK< zdqeH08Tb`!mh>T0{GKGgG|5jSdCDYDNb;OXo|EKdle{X)>n5qBQ=nOx5$I4!swSD> zlXRF#H;`nEN#;q?W0GwoS>GhfC7ErK10}iHp!EcoN1CjOLCq``ff;ikx4r$`=!i}_iO_Hif?vP}dN$!(mj6oI^9Fw%i6n`(t`X+f&Q;^ zAdZ_mMu}A`wRZ-eM04R(yKf+Al~g|WRk9PusXq7y*?UV3Z(;(1&Dh{LRhmX&rv*%> zx*UsjPBrvN^7R#Il0DAwYrS}PmDY$K+2e4fY5rxlb6-cEe&uMSO(hM7W zT`^6wtGb=q7z9}ie_pHT7l%2HU8R|tT_roVpu+A{X?E&V7s${)Awzy}BZZJSPIbEs z?Km0ot6Par9Bc-b-jL~3)vca2S`RMY>^apXTOVAjVTF(0gd$mCB1NU0-b6c9YANl~ zbgJ><%NMkKoCyklQOm?FANSzwVRK&J)koa*qV`}yX+KOWZYZ`-k9k6aKOCE zyEu=4v4v z!J>K#-almgt2UNJT0V#DgkRosg$DUxwS(F1UWM$YF83jTX@km1!Em*X8z0>UgS-1+ z{}uj93Pm7ob2mzzd(&&5wzHon!h@!eHM8X2S1wWntJH`8z(BnV`29^8zqJyxy|jE> zW#0k={f0x0j(-vW4-&{Heee!yNy+(udfb20`mJBjaE4}li}eK7^c--z?= zm#`;}FVt+6f%-KK^&rdi%eSFJZ^4&p590!2d5uGR$nLh}MLSX`(^dpOE*@X6{XTpa zipU|`l`SgkUBsIN(C7HN4aDXLegQ0fr?Ho$MZBpk=LNhCc?^iB@K@vq>%6qRxCpa` za|JXf2Y-tx>%a*GZ=qKjBsqw3TjDaLVx5N{!%G6j&|LkHO!Tg zzTgfrC2SYpIElj2DQtxob8u`^mLMMhGbBiC+<@tkWUc{Yz2)+-Eg0XrDB@jRBeBng zOT z0fLyC&B`|)sT)xjYqYxDFrI9Hj z>s76|8GVU8Un!bM?-BWPb?IB+EpZ+J>R5Vh6p-``GMbT5N=6?tMv^gk>$+F9ksK?b z;TyI3UfUpQ-tJxQKvOql1)ZHC^N5W;;(!K9>qhz;$3gJ2u%cWphsN$bLMuU3-euMemVCez_W1+mMGeNL73=sKb$gRD+9 z(v5Rc^+m-SI4j#r%zXoMeVliALrVz~K%oOfH1T@qD-ygTuDyW;-E$&ov-ZE7En{dK zRx5lPrZzTRZ3i`*pTxj7te8gylJGMd&9?Q00^AO&;Z)%1&A6U+)lkfVY-%xHi78`6 zgDsl3fR3+^DIZg04yvV1piAZ6Mt{fqP0t~-_Yr#H$jIE$H@x(@m;W% zL}$a^Os5Bf_H}{1zoe8KNwWDk+-n6|9#6Alp*A+v)z*iCfcvA~aKMBEkODM0x@O~>}c~|(q(kYM9!9rdFO~_bMYB7ibpHR%1k+z3Jp+sMB`a_GfSZ10F1XlQAemV zplvn9yh}t7uCb7ySpYn1fsXc+-o;5&*NEhub{(}5i0u+3PH)xXb3cdu6wy`Wk?ud8 zelO-dG)*;Hl|KP+jI=-^`zT2xPCrb6yNtiC=!@6Bp!t z9ML`T)c}%LKsL-TZ$6dc)7Nnf$4)ko+y~hVzx;m}$$dY^y|=Jy3}NlaS31m_=GMi0U`!#lQ&2qlNyyHVyh?< zeuwq82{l%O9@-ZG{6y{eWMeTW_8v^w@kdE5-KKeZwt@XFqV@36F5F^1Epqr82cw<4 zd!^>s1j0Qg^+GEQw0^B($}B0o!Of}xOd5yI;Ps1k|W(J+MEivtDtBjCkE zH-f#XP7m6yMQNR3uh8l0?V3lM3j32fy`JdjVShuXKO_1e?BD40-$efbd%$R^zy1!* zlbZ~CV@XpsSq%b9J29Fel+SASy{zBdpmYSPpYHNOxYQ=XK0~KpAbKV2Yl*HBhjt*O z@4&uWr!NzI680Z-I&3HC+ps&(fCHaRbQ0`!b-JABV%SS`x{Bxu*oW!#JfeND&(P_O zJGI)4W#TID^Rc)Wv6ycTxPru{Gj{VS(J>v^N0SBx?{v@~jzxE~NBq50YZ;-ArG9Jr zLE=A)cPWloQNBw{No+3p^TDyJ45m}j(FLZ@$J+@a1R`{3V z%zmw(DE}DC=XB8E6u)>rh_&Kju7Z)c;U~~GsHri#o+!zYCi#dYt4wm9B&V3_N`6hWxk}Xa0dr5XM$;*-~H^>$I7|tNH=BciDj3gTt z;{zZlCZlUp@xB;^ha(w$r@@I%1fz*~;GmWg(*u0Fy5B=c{Xiz2!Nj@E%?GuHi7!Da z4_b#Z$6~4B^QQe5$LjCPIFej1lwoAzXN%~rVkKH@REP2*!`)N z*}+>)>#9%MU95yR4I@9oiZ-sdfoc&r1x{j$n&5bL2``p14=a0n8m^Ns!7@L&EP7@( zgRoE7_oDC+_B0IxFRW-wD_nTa2SgDfrs(W7NhJ~GK~hmbt|*rfuoB)T`W{fjDG_=> zj8oB9lpI{|Qo_q3I)Z@{Fc3M_rf=aO@V#Kz)t1|+!V@D-noh}a(BN??W2Z`&b2;eFEgU7sC0G}f{tr9Z*SvT*PEwR;F(CMq zI_PkpjKWtszUG7aX)LQq%O?I?#IK5${7V7YL7c92Aig|zc$WB|D94L}SXPXO+8Dk9 z-xQ=fc(S7SpViKI_O*>pFxu5&aO5=1g&!a|lf|nDU@G0|Ygf0VP?5?@MUi@00(Hh9 zV(bvV0T^>q0$;C7KspWSR7tVpn#eqYc+w5+PW9>~@@l|k!n6fv1uxnez}oR(*P%zz zn>MEVScu>B)9JWmp%ZN1*navGFRFNZ9;xmGW+tDC%xKS}ZM9AWu!n$n41eW;87PUS zEY<9xbyh&M3D2P5^#5og16AUt<5@-Q0Xv9x(e1??a$E_- z#{Tc2dbH;qKc3gz&Wehn2woOC9iqMc^G4xg-@KEqHw~N7+Vjqli^R7_wdkbY2%>|c zjI^Q@v&$57s&|2p*`BENnYKHYlE|rE`jy1Gy_*zw6Tg0@y^U{|Z}?n$B=|Z~$EjZa z9ob=fTr@kTO=?zq2(g}#U2i{p&<8gY?1uR1$4U9~X(a3kw&QupAemFGcZR&_B7Q!m z_4Fh@VKg3%AUS%K% zl3`crVs*QE;WxUiV0&jkmH^^Zui*s0W3Bl53#~dbf2QGkF$CRi0Fy7qeTkcA#*1ga z)SgVD53$?T-}_Sct*g`A#G$(e?5cfh(O0-#wle=II#o}hz=Casoegh@sxcVMZ*6pQ z1(vg%>Pvq?Iq`5G!`~E*zXyRaK{Doo;g}AqUA=ajWIvH?u9OkOf$_(2j7HuR7ms5! z@|6fXq2+cAnMDo)2T-Fi8N+tFN>?j8)$nGhb?Fc~)es0Bc@j5lAR&n1RKF+yn?7*o zRO$2cj^5&bC$y-bagwtgC%zmHh)v+6&X-QpJCM^W*bePf$?jMufg`}6dkaozyE;sm zO<_s8iy%Sd|D#}hDwla^UF!`>fz_~_w5bCh(AZoFUxs!B{Sk_$-55W06PLe6Kn_8S zrF8P@goyY?YZ_dgOrTe!gGWX8Z_uF7M@LZ@arns55!N`Bu2itAp*{)&nT|@a_!})D z(IXt1OV4`OFsu>7)Tn^P*`lQIM`CMbgs+U8L~_mV`rIRIIMi%W;=VR3Kwzrc%rGs zULu=Tv{qq(K%KU2DMMR25y!c3AD{lKz4hj4Z6((x!Le3vJ7asduK8YT$oY5T(=#}) zcyghW-7^v!l<=ccPd~owCb()vk19sPjHKp2;*v2`J!SsLCKVM`togH{vMVoK91iwuxuR+rWFm5lbb7-=pz;49~eE^x*EZyju>gTWX%)+g%PqnP2YiC!dUY z2BSQ`OvD#3q_>SNU+evcxALO$d2qy1NwIR;$^H~!XK}}4c$lj2|n-ZqDY zqSsz*I;$lHZw9HhWz=$X`AK{YR=YFA>MmJL#<6Z`A$8#sWkBWwXa{X5f9nlDQY}AX zz?J#@3mQydyDShbf7B9v1HiWmLPkZ!VAk>yk5hDopsR?kW0r=@yuo(%Ae>Yh9wb^G zJZX9`#V8G#r;xGhz`Z6=ZV>CH0V0{AnqOAYWd7WlLUme>v~GY;(< zTZGlVA^%hy46cmj6jSf7$mR@in;2NX-U7nJ9e0mH$*c%vAiUOqt$n z4Nn4C+rR^-K%^{&@&70hoXP@AB`xoMsIeV*+NB?OL%+j{=|QmFQXPuH0uU$$Eb|Na z^D~HngY`i9V{ijp8CyM29oTw4uEK%)E*Pu57)fb3h_pOt2(EN6&?qqLeY}m~q7!6I z3>VRsiy{AT(Pcgs2dQ0H&!Y{8PXH44FNe$iFNc}Gp+nma>9s+KkND~*E!emBA7E&Y z1d1Z^GeqAJ51 z%X|MXmze@SJ|$M2*W3x>A0R|vV}D)ic5xVpW_wLUEhEIA^2ZFs&k)r&{Ka=_<&Q55 zSZaj0mPo#UZF=dV)dkJ1wezzFUC`pX3sxjAw*Um!BWXd$Hop;jc1vm5ZC_69~w(=-O@c8Jc(^zUt=4V6{7ny zz^yFsmYU%2Z9(s1D>cqW(yst%K|j9iSMk@+T1J{}Il>eLLxzcJNR2T43PrPb;dV>W z`6Bv>)_}RC0}2EQ-M<8}Vc@PCpr=z~T|3l|t%)65h;n^*+bkcL%F{5UXH+O_ct$SX zOjp?!Jf|4?{0XpYId+`6r2_Jtz_X^?*l9f5{mb+7;9A(RU!cU@y})}DOeJK6;W-t^ z8lIDjGhG5%W5}ca<#{2v?wgk91deO$VgtbbtiK*}f9emHVDbzBEj@^F@(gfx7`PZK zg`NgiR?d}1*HPLEmxgTucg?@By9n!}Ry!v~R~#qbcx9I34cJWxOARM|E%kL*8eJS+ zc`@Yh9!=uf6Qz55vywFR)`vdx!s${Bw7ge&^Le$qkblbj4zz+}8*XQ%=z>rn$7=WAr=#{~{ z*bOU1Yhfueg3!_m!kgf_rDLSXgCJyzoP8dj9|Ccyj~=md3m^EL5wU2Y{i>C;9SvGW z!76^u!O@GKKHxgd6N-nB-jVu%>oiZ(%itiPv^>q5blD{q{HoP${esklqz(sKFK|P` z$W8?=(}A(yZXha+5Vf#EbOl_QWxt3&f7NQskIs=3me~enH0*hdO$|5x;aqKS?6s2zzATz%|CEY3J%^y8 z8+w{piM|MK^rZNVryLZke%CSvzW|=H4~7iWNhs(^vF)6jL=~o*ljhF38Gk?_OC<%{ zUw5&e@f>KVFSOJ<)*_fvAA775wysZGLBRP>kJaGw}2nUWHm-%>~yj-6OW1r6@AXz)@a+VJTys33a<#WBbI(tD4(; zgd9m69IfZ;v2sI=;We=T?xkm=zcIAEU=+3@k$w$xo-EKP-<7Q7`D9J>1gq_Qun6>Cb@zynbKbQht;n>C zqT&xNv8WPKJ+9;9k3lmPsr7s|mhfV6@#*7`7XB-}7Jw@&XQ0>)9lk$7%koK0jMdh- zzRM0`wCy8*8>U{RPuddoR%K-V^iMd^=|(G)e|?yX=;DGQp;ZAkddZo zqrb$Yl8^J>#ReJ3-yPXg&(I_*%I(2+O9fP9lAx^zI7$T!OB?G$uVe7F6#^N18aGmMm9`p+-C^JkHx34mEW8Q}GpW-O@cGxrTQ|;}f`y z2fYinaukNtNPT(@jpU|%BP@X7*%lh*7I44H+hDt;0?L>kh+pt}XiJ45wM~D*Xp?eh zr|9DYae6f}Ahro5u7uWwpJ+Qxwns#O+J`k^uMbNZX zc=WLda$JBJ0fbT)hV*F1ogR_%5gR${fM;*RBY)C$0oN_vQ_^jPvXS5@lVP~3dpod_ zhStYY%k|VFM-@YZ*z;oJP0ihAvmXp)(mm2`Jn5lybK({FQ4k@9=V?|f{{UAeTZm9^ zVHOC*kKhF``sBntDISzx=R0;EUgSv2sdpSP%fLLfaankhYJo(Jwy*luu@ zPhm)}0_#y%OvpVC1+!oA9BTOBwPJG@QJiW786`!CdH}jlMP}q+UC|6*} zSW^$lIukgB?mB!8rPA=+KdPt=u3I{z;7E0a6$ac4scAInTw zgSrRyhX&YRO=g?mXtDe@zOS}fymwo3ryK&?8azm4`n18S7l*|4+gjqieKsQTkBkjq z)G@l2?ZAz1WU>0u*Kvz-={j4g-fwou-}a-Vo9T4R{HX)bufAl9CYmN@ddK>bEt5J{ znwgD0gQbGf&9<23&phl(^vxyzT*we|kYA1O>4e7c1YH}twZ@pzz5)m{;_06;Zv$7x zBS`kxBU!5@=wq*x>xt)2La|hG zaAtcTO9f(;p{|QnU~<8AOARO{S4k7fWNAl_oehIzwt@GLr5^xSt>~k_WhnXh26pb* zjDY83u3AbRvN0>b{F-c@*6kIx7S5EU*U2p=JLE(*>eL(iJLknaQuv!WKP5A`$a%gCKou7pDI=?8*o6-!0fSs`sW))VRZb*o2 z{tDj>38PYRgA>#?e-&(@;t$2;!M9^#Y_1%9&9n@UkQr~7LsrZsGQ=F4t0;Frcvf4l zk7u!PpMlsSRYB_u_hy5i`8M`X{UmPNT<*MUa48E<(pU**rFHJd7o;}hTP2>NE0oAob88;hamGkPO|Qd-flLT!a5~2p;w$#VLg+vQo0aQ zf!W-CgPuilvfc`zRMXfafKAyPkfntYCZtu3KtA!CMZ33SQ3A{SNkl zflb#(I+U5gTVy!s9jYDCZp;#(8j$5s=Zg@WOuW$?n z*DW<59CbiYICk@|n1js_OB}AozN28~R#c2)^j?{{4tB*B477$rCjHOF-iNF`wbw?w zn&N0?^jR!(5xOk?CPHQS>0bhA46f|5NL;ha(pNryS7Pp0Vmy#_LGL9>ovxgydqK%u z3VPD$9iE{0GG`4LIglx|J6T~L6LArS)ej9xJdd-@;OL>3Dc2Isf3@D- zd|98mwyV74%X}{T9hOSIv^e8n^|xYwMwynsp}d`@gFUi|ne)?aPJKEpb$Oi_qt`21h9~9Z^@yQVF%MtH#FR z8DYfHKU|ywu3I{Tj?y{U-5|iZ)lp9i|1@VaxUz<=!q8i1PYnggF!&sX8fMFZ#WvCjeL${NhsTufl|#Fao-3+@(;G*<@BH1yZd ztSuDtG*>BqPn;m;RiV0EIm1V9hqM2`&UcqBS??Zu>z(f|TY*lO>z(gAHn&c9(EHwZ zZ0Y)>wk69v_P(9X602P26LNpqd2l^A_$&X0J*^&RdRreBVg z3^^DUpqZoHUTPot$f!a~7M{cVY}b3*46M-Q@JhYk#h}e`HG>e^iKNI=jklJqfmTMrkg@!~-<5CUsn5yAm(&kPFwLl%ysqTep&@%=bsI6xrf~Z<(61z zdym}UZL8;bC<)vJA`ynAfc7hN<{7(WD9Pc({^*{77~NhECA7*PU)B{|x72_{i4YHj zpk;bSEDmvHdp1L)84l7c2Va6K%VIzAQ-~|o^9Sfdn0C?6zus5t9RsyeWQ4jBJUO6e z8>lvxu5v$WBv3=AfSzKY{KK+^;K~+(mW%XiP)X6ZhQoRlLdz3`5$GF0cQthQL;Z#6 z(@k+M)Ya4%^e#$2UTX3I1%QmlXUG) z&{s7+l}f_*VKnCWN3`@|1?k(fB#6z% z^HAG=Mr*m>wOgw5Azr<}q$1g>Nj^SEXt+tWlHxeIDUm*6l!Lg^W*UE7jS#jvfeSHa z8jkB)j-%hd!|_)&9U~3i6)huNwSC?1MD4GMs*woKV0K>#s4@|Tj6KcnYb+#?o>RDN zZ4sWiMp%r61k~!);JT%Ibd;S5I|Fyle)zsKokbYnWGmnYYl62aZb;666(<5BU8N=I zA0QNkFk~p&%|XrAt85&2Iap^JfagPP^yFV?DIE*0Te?NE=Za?|U3CWR0?$8=8`9^h zi@gF?dm7Bu9K&Tf>U1aT?=Kb!H38Mn&HrQ zh|IAJfsl)s#tg)W&_S5Y9N7B9q8KXut-@4rUDd5PqZeXQcO$~h@0}kPif?tKC{g-~ z1{${eF}s{c!p$&H`y2ZhjSgi>mAmC!Y6?s8^4i43#A+%LnG6I=C2tDw8J<&kzTa9; zzLr+<-7pkNeQxOon!d&0qK>#K;6WqQFu~YrR5zpB>LmhNpNLD1Us}R^NYWc1vFo z{!S26`1{Ex!q4&A^caZ0Tj>elf8+N(xH9HW=P^wPG;&KXtpMzbME-t6-Bz9X?x{1S!voO@3V7yp>b*deP~4Qe}@T7zsG<`AinE1584 z`J%Z3OC^2VHU+VAJlh(v@h_|O0oN^^A^&sUyvfDvXjdekAy!4ZVm)gheY2&W@c!ce z9=LkKi?5#4E8F z0{kQn#JZaEw?$x_3mf+Ko8!%G+*2%C#JRFU#+$sl7o81mh^cX|4BtHPo@)M2-OIt1 zx_@|>B82L4>m#f`gR2~YVT?*;%1;NP(*zcNh}Sz%4J$^bhj_sw;9~D1urogoV7Kt> zV0hBXih%oLyqYjnxutGYitXeFD#b_g*_&-we%*#0hs}XiyN_dkV!_vSJIL5hHHo#U zn@G(e^916YK^K6O@r2Yz%`$xNQK0@6zK_7g-ky(#VN1(Zd=eOroc{{oX1^-8)Q#}< zB|i|pVe;9Vl^({j*ijIdo9T(@pLd-CS0>^wLQQbhiHJHtabU!5azATdufZu%l;BFN z(@y8#o^JBVMv11EC|R5869m%s!8fQi2a$h9{QS!XS>WEO&^=uG zgk(BMJ|daEl+OxQ+9nATIXGxysPUKMzTnD8^)sUFnc7xilfYFL!nkuXAcH(Xyjm!HLv6*5wo~ohN|K8~9f4Ox_od}!{A_Q(DZ#10eGtUjY%Rf)7zhFoY=v}^lbkUhq zIdCM$^9h#T3iWIb^{)ms0NX7UP(|4VZC-GcRxm7WtTUnFySms=JkME5^vb}OjRDs! zoso{0F}0Znjv`=49se=4p}qguy#U0+SP9xD4kaT0KOjBQDfCF;z7o#Pf*WV}ImW7g zzx)eZ(nw(upJMMqfgZ^b7B&@JQ?Gjt93uUg=O)exG=@a!4THj&$*K`5E9vgojr{|! zm?eWuy4pOVvT0&IzS``YO{%39bSY(|jb=$7V3xFmh*x09B%o=QrJ1FYv%BJh*&#d+ z% zc8P%=R~(LkPW8Cjpn2WtakUO{95$O*td~A2f|Feto;u*I^Xeh-Z;fdMt}NawMW19> z79S&KCcDyoi**H4Fod$jc_-p#GRpWHIJx>FB+4cjGS(quk;|P4UHdT``wY*~h8O-d z_;0{{R!ndjF8+#^pzR4;zD}b{bSBx@ zdl1ge)052KuzX_ruzQGfi=9VlHg*x*6-{;QWvgIj1|Btnb4jG6x{7_xKr3Bg$mCn} zIGQwCENz==Yq%T)>zoPMV0`jzBAyQ#`jRbukAv%$I?zzG1wjQp^G(cBcY;VU@O>@( zkKkJAibd2cO#<7eAn1BB{lE79rHGI^SaVGNjFe!UPOi*x`j6tSI#_TU1DU>XgpyV) zCf0Ff`OA{ z(|Pp5sn}P5i~Z|jOwmy^tLusjJzgR6fmWU3d1bm7TGy4MtoU5~-P{#hi{^$`YMb-m zNg$eb6d%=f)v;aq+$mNq4vhIP$O;jghNaZDqA1Pf3Aw}d6)`#uelHcX(*EW5-C}c^ zE7NxFm{SBTu{4_#Q^WJHdaj01^}jIE^wKdiO^1YC66N)vdZHLt55C^vY=u}(&bFA& zrop0T#gMRR;u|=#DPKCp>IBV<&mGRMh=%oD4F|OT((qM<#dJ<~S-pRqVrS(^FjQ_6LfqZ7%cN7X29s;>thhG4h&iUXbwzjw<%Lme%}H6 zocON3tC@n+VMz^KQ9jRC*cRDXFADw=o(ZmW@57jx+-I)Gq_Pa$4F=Y~(Avku{yoEp zLMXm#I~81IISe`Ppt+@-chp5dWuz`aF)E!8vpvk4Hlj1N=1mD$jA5yyc4be_j^H`e z@U*>Er7rxZX1DYemGTjYX=w33`Rt9?dUTpE^8lu>DaY~3FI$gr9LHHt`tfB8Me~Me z!8eFr4P8wlXue8s!tx!}K`bUbAmoBr+R#e`ATy{dYy|IKe~{>^4%MdJ)tbQ^s>NJ^gl9jORdl;K4i-3NFvq^4uH)Q3LX z0WM7g!^Nx&RO#hnV}`3%CShgiDvMUw4iNh@^$_DKSNY@1z5-W<_*ro!11pZ#L2ocn z{zPc*4#$<2lv{i~p6&&Tp_Y{@?E1Qa5$rOHmm@Aqx#HIH35WqYvk)+aYG1 zp@kJUz_;zc#fK3772hau-BJe%&1a+wJy6a-$Dsc6ZAfC-~WjEU=3&chrD=oOm**lQ-Hr)7&-T})Ez%t)XV(xlD@J4u3YchbAdzP%8+lHZiJ!=BdP1)PB5@NtXQUt_-t2O-c1b3#*F!KF$t7s?I|pu zG}P7li_q)fO0}Ph5hDj_wnuj4ADwY-6K@uQ5illT7d>9n3Nhd2H+%aKjA6X;$c;`xn-hYG?0(`)h-L z2LBTiyXj#)RZ2Htv)V;)j~Uo_(wl%kU-qX7HmB~HVY?kHRy1mY5Eg!CL}!(*X^}GF z??6@xZlJAvy6!Iz}31Mz@Eo*kRHw~*2GGH9bmhqLKO4iAgE2BAfH$YyXzgi7!y|z z=7uTXqoe80NU6+;H{lfxD4S{lEb~4-lkU+%^Rq*7i|ia%jIZ&>dLpsR7VkM&E4V(7 zi+}0Y*7Cd(T&c{MChO@i0o*`a%Li+w1My@!9L8Z{*mHtEcCa>+7TUf!Bq2w)xe*E~muh9F)bML};!nDU0Ubw)yLP zEOQ&~@2CfLj~kx&i*YWvGSu}%|6DAeO(#$PdjpFcF*e$+q|zoqq%7vT+m%MlvjjU_ zX2F@V0*1^*+K*XdT17gi?o-%%corHV@V9^a!F5absK+flh0yjTSju-WENv{6V7J@g z(E1PP75}9q1YGx*BCjc8UoLtybv1Gh1WS2DJk``ye_T22OXFQ^EuK5->IuEZ%DG+S zSi;fsj38&|dG43b4$M;*`!x;_aSnzI(0|WISt{v?ofphpB010HZc^(k)Jm6#m=tdO z6JIg`_uD#p5T;o{XeqH`WS%QAWdiIqri(VkL$3pD^G`j5O&e41$G0WKx;$5A`rE*{ zD)2?@4Jb1Fk%1@@IUhpoG_?B<)&)Q7b>;S%o#t@qkd4}F9Mwj{2SJ{vCrP?at}NL z(k&fO+Z{Q{_Wu?39pF_I-TSk9b4l3*2w@>1?S>mjC^wLVglY%@goF~hH0gu@AtZoE zzkrGq6@uu{q<0Y!MNqK=q6mTw{gk4gQY;jeChhm0vwL@M;Cuf6N~-HEvn?3NmA|L&ToP1~sPaNXz#AKn+>htqE2Tj6ztQ4u|cb zdtN_#NciMSnpgwBhDl}L*=z->vp&pojT+|=dw{4P!eO$3d;?8V-?j-8zrYW9fW!MI zV4d}dq$*Z2-2$RIFPJ1bMB*l?&+vi6WWc}GH0r}XH&TJ>tOgEGBAWd`AR)Ls(BEmR ztGEi3SKCmuai3V1%YyE99c4?sO&s|2cJr5&nm6Jc02X=wQ4z{0gLv1Pa&J?u)K&F2 z)H1Fu^k+XMNC0Xu$=qh>AD%?m|K2o2^Z;TcY1~r&f8PtD8&YbA!t)lck?Wz}#!S|3 zT*rLL+SkYuQLCRK&yo?R5UXB+!?i*8s(w{Vs!OoZN!8ymrZb7{s*MGzvp&_z-0BWd z4~Uuphshp=aU!3jBC-6dH^rG8_GKn-Fkqeah$KmOh_NI%nY8F7zZ4>Ilho>h3SuSv zpD{5(e|FVw1gejfN17u)H*sv;J#+6%Gb+Yy^x^Wi(TB~IBZIp7UVF&4dsfE$sQg(^?OiR!r%i5U3{hud*Pr4ttb6{HE2BQCxZIH8V!)LG+qDOme-j8RkmG5x5VW&M>cDT zdNOA!ta=)SIJNAOEJ@O$eAQH5W|e#kGLAEsj2RDKJ(U-->gkzgPI2)POb@wi7E<>G zICx-F4!jErsrt*E!UMrPOcT!}i4DqOtcM7hrv#rO6T>I)DZatu(z()hl3NIhgDj*a)o!$a0*z^w)x2IqU6hUE z3l|kJ5&kUvN-47R5jeurAP?VH#?d&FDA^)<1t|9uzUd#&Q;_`}=wIkt=#RPx`oj&j zB`cL2EuzIegt^NagfTN-48+>Tp_S=axX!t;Imllyt~wmf?pw8~DU*sL7~iFkU2-(N ze{00*EJwZR*;=?Hky1aO(o$9;sijzpJp=xerd9Tg_|rgjRs+Y|>d6ElRsq^CKg`jZ z#QcCmerIv+;Pk$1+6vfl0jL@(_10Q)HDg6<2H3-1+kX25e2D<3Dzg{?Kc%N$>1vhNl+9JlK`fHuLUhyFC{B2M4aEWa$m zm~~l7vn~@w{2B^4^(FkwBfD@P#eac_xPl2tK!Gx;Wk=T<%m2( z-t+Qm8_b{tUNud+RLy5nUXvrNi8dS(t%}-^m}aJApPo5Dx%Ad!P6H!6eor-{Lv@-< zq5it~(hR4Ftr625a%uq_&d?6TT3vx~=UffMaBdG?374zeV&uITayo0!IZsK{Zx|qU z!>?f)U~hEr9?QzJZIOu^IOcM-*Xa(eOvgO*{2fi8`ZWyGaJ{ELy9p!$8U<**4 zIZ$6C5TN?5%Dtmx;6R6Jm)SKj7S47|qkcGoxvLcX)e3F{`CO$g}_}~K^ zc@F{BS&v8}a6WecqV|NtBt0XkA0w%Lx+W&U-(-^51H4&4^$v1tdo9uZ4vx8Dp>s1& z*t{krz~wR-J^X*<<@TEHIR}g@=C99b1_GzfA#`$;Zel5cnSebEZ6VWgwX6zxh*ZbO ziMd*`w*`*FiWK36zYxDtiY)C;&LB9Lalyd&B^;?c;TYwC{?IPmMGC3Celk>i1pg3z zr6ev~ZJ_uqj?^=7EJZwFAekO`#P}Ed+Be{ol9=#lSnuun7aMF;F)G`(yOV642fOjWN;oWqfN1&*Z%yGdrm#z5h?g-P3BIHe>eJeROgAQ{0oO}p*0JOe1#%{RCp zQQhS2=!iG=fG#&>dCCmujk0pEPc|*dko7!|o3@!i`-dClk!AJ!pWg~Hi4Vx#9kdP# zW=K0?hV+Jy<2C8(sKxcmxNSBf+P>15jCoQ?Qf6}k)+@r;trfFsP7?NPz|k-q9IR}l z+08nqCjy;Hb4r|{=5kp_&8>e+3G@)dF)NnFb8x3H+a!;7#0hx;QR;0tT!gg##V&g{ z={?;GdANfWla-95+*VS_Ky}uq=DZv;QSE?yWXjpa+XE!j6oMBS|*D-YIc%IMBogGb`;qF-CCIzRh*9!-wjCs)ca0y7cX7?xAeb4ERkzF zYkI;?e?^_R=!RSG$p?$P`Ve`dvld_F48mCXN{ax}h6}A_?t3yQAH(6s_e@JWmgl4u4gsQC1mN1?&c@vl?+U z$Dr(EAnFk~%&~*USNSCMr#DLzmvPYFB+0QzZUWU=k4W;HsUi^nY7IC{axbP_lOS;y z7IQv?_^KwEy^8T+pgQXl*)mKq^&qklBHm=9=_kJiM)D_K38a0ix?slnc~WN$Qty(c zinXNv1{}6!TzPF0|M{H&aRUB2%_tqan?3_nXMH03cq+cW4n$QHlZFK1*p#YM3yk#fh}Y~ zRy)9D4%}T zgN7W;X$8ypZYc5Esu_8}m>WRvGfC816W~6^;X%T+784eYAf;x(VdH3*R*_GduHzwM zF#H;3qIT091ypA>%Har{=97S^3*ayZ&0Cz(T(hSoKwAJ4T zgw(lk*o6N*+o8~mig5RU)VWMWyevQLfg;(5pw8+TR?a3G3@eK}Bk9DF;3E|N5f0OS zi(6sEn5iJGgtMBs2Yh4rGY&BT{s5ET9tw{IszaH2Og)2r+(nEwY@SKs`EV?og_{(9 zm?y+5@Iy>GVc-*#u^9es#VELaR>7?YsxuoZV2KdC-W24hA}%qYTMrl5oh5qHc9Q;xDFKW&=Ogp{x17e8#AajD9$w(N0kE+9}kDQ z?*LXVa!shfI%Bm!ju!{LOme#_x&zf&8RSt27*(Bw)j>{*bEV>_i14X!n7j`TlokU~ z8udYSX-RR7z{3yt zArH_xgFwr=pgl|+U@iWY3puzNB2^b0tBi%46gKb1_rhD_;7wsvnr|JTva%yko%N_g zh+mE!Yk{a^;V=o$!(k=yCMEHAGS5v42PTJ##qcMZblFy}*8|m=0p<-wfXs6pO%KAH zCWQ{jlfAXbd=e`h6D-cdZ)1|!cf2=&>MRbDw@D2oo+`Kri3~=WnDX{|^>o>$kLIr1 z3Xy7WIBdB2BKtTId{V7{g}QooI^yz5gJ}(BA9NniAgHqvlF1`wvh_||RV=5#D{w3( zzdn)F{_5rw$KbELhg)C#*-x^*2dc9^mFLX_>}~@@y#j~H4$uu&K1rozEzv|(JkKpK zN$jgmEKr^Gh$J@*U&sQYww90d)nXr_*g*#s(UW}qN-46m5gg$fnTQAaI8rCU;RN?{ z)=6&6vw^fUp|7S#Za`3HIZEL1P$71a(r5A%67W*&KUqQINBHOPE2YTNci;$DGss@W zk$MjfComMlQQWSO;KLD45v~P_>iCtCl<*W`P9hV*NHdf6aJn^6zMfmtQVL#W8KR+A zy>{0qR!oxdpR#hSPk2g{G1T-d30K8)K;JWE?d1zE`(*D$k}SQLFiFHEJE9+EUCcT= z{!zqXNU4|L@Omzq6yo(<2X)nJM{PKPYou!+NJ!aH#2U+Ll{tMTQwuMPKR9 zz--~B#5NX%iGlDxGD+=4yCuvJZm!nSnH48!ZMpPO%z*7eELUh`b0wZcQ5*H;_x8Om;q zh*_2N2#AH(O)58AVuT4_n1puM`94scIZ$LX5a2#-1@a1Vpg_+|q+eGidsUA4YMzc+RY$U(^Y3$|)f1Sx@-_P^`s*31@iepT5=%i`!oN=OY$L8i+~gYe)hPF5VO^-^9WFHz1LtaWeveK>VP=tXGX4D=#{ zMWs_!^EmJHTJjJC6OAAmbI10II0prXCL@Mu^(#bG!SO?~Esnh%aI6l2!?{fQ0x#&& z3iFE9mAVu0qNK=w2yq|G2o_Jl5B=9L+nx@25va}_XqP<@P|Jo1&&71y6e95BO+&t+ zmCY}Ja#5SpjPmjjEy8;d=s{D~u9sUr*-A%@DM{B3@CHX9kr+5^Fwyw6P*O?F!%Y(6 zH<^TX3vCZnXML)l=Rwws$Od`+*+f2x75ot@o`C<1Nm9eg!81U0)+3U)=L@kMi24c~ zwrJyh(}N^G=&mN-hkpRSQWD3Ofl&MkN9xIlz!X~(7hDqRA1uTr_*d~OB{AVjgo2|g z6spMv!>}@pqH66763M_)@GGTA;o6TIiWVgHFdR0hCkz5D$<(`wH8t=D;8#jg*lYnE zbP%PG4_zU6yD zoPuBUKz*D8s7<&PK+T?L{B$%NrrWFp1xtsN$6V8X_QUnxb3;?L2GAlXzPY8(0J zaIJbG#U8QdLULh||)+>P5TMjSKvMSOygqozk zkJ3DCqZx>*fq02IMgq9pn9~Ej6pN3Bgy{xpPb%wOmt;vFh zc!2k^l3yZ+jnERRT*h1`J+dh3zYv1El=vs49HFJOqc0B`%FC2ChVpka4CQ4?ABuI9 z9hUogsxC1R#qFuacxF{Xq6l@N{fZJ zV3d|*CI@S71OHn?iJ8P9Gl>Qyb&;g{%E%%%B(unp@);6OQZtJn6)U%qRIEHyq$MGLmy5Kn z$}X8R21RyGjvJ%78=Z5w(77Ft4ManxLjKh(CK-cb=H7-@gdB_r`Fb9Acif>00LU<>SqpVJev?84$GfF;Qg8iSOEkZlscba@ZVF3 zI!6@$`Y7m4Sw9NWd1MYAm|`Mz>2)JVZmZ9%4OC}+GAR<5(uRqFjRC58aJb{RWX3 zZ3z~47s(?fT9Ws)3jVY(!Upd7g_(x4%t7Y|Ac^t6L z1k|(^!Nk)*)W6^uCc-#BHWEKkEllV&1I0Fz&92orp!#X~@HnleQY=S~LpfiTFO1WY z+$RuoT&ehyk*^MBzV-kuq;LJDl*OHpr^jh=p>*Exmg5zIbQwHes~OhS9VjwGaNnIW zz4a>DWV{xiV04P-rx$Wp`UHQj4U3Lv6i&tdfhkYA7RgEDah_k5YsPE+OzF$h3*T6a z4tad^6PO>yu5qUHBuK|h(2`b0;F*q0z(Tpb1)fEPYun zZTy6BBBi&7R=Uy+T0l@t9M(;XS#swDt!h2`$Xw>gz35ikwkC0iWTw849JU=mmlLYC zfS`r2pjD*2Gy&(<4N~BIWHljWQrJa?X64akg%r~1^L1OLQFcK{m;RKMX|;Ts^>Vgj zmd(`F)hn;3E}>xlzkU=+mgcROy%WCco%!f$<&FO9^JdP zNwEx(^r$Mc;t@r7{;7v&eS;_BHPQkIsFUGvTO=vJwn*C9k6<%x_yzwM=2r=!2`yHov9f*1Yjzu<8;q)dprB&-Ql|Orh3eUvu8GA51a+AKZ%Ap|oveDz3-Yy~u zd`yAi_&%b-aQsvDJEE*kzGakEV~Fki+c3tSdm9Us%j!8<^tcusnT^LnXyt{2F*8>G zfWE?POXub4$F&&mCP=q2IdY8RMs>gL<0v&tGOrWT{1RxgDQgeHPy1w_^Od?AvUh_zg`Cd$`?j zG+>?eK$0Gdntky%BcWwhVZ8{MwBbWVy{X-^<-3!$c=q(2C!Purb$`k@ zBdboqkS0UsOwpQ#jjij8If0nD6th*niI~uT5JO~jT-p2OttnbdC0;h4s@09|T@QDU zB_esFnm{cGEuuce5NwhyXHM1P>aAsgRFOPEjW;9;>zAZauz?XA#0nGCcG>b%C=5Mp zGJc^%8v?ztkbbvQEIw=G(7xbZBgq1hoUf#feH~j!loevhVbL2-JaNEmh$&vxDv+8$ zxdrZ*dDAfN9V16h!wI$>&&p|DC;c=Mx&Et>NWP`D6o{V4@Lfm4olTWmPflHTsAA=oRur% zgmhK_%RW-1EH42|a03Kl;gn<9660hR(i`1e6WI{h@?WDe7Fw0j6{yYx*e<>b5n<%! zngG^;6c`W3VD*|MxvCmflyH;c+;DUp@MoB`c9u5-)tLdt79v2#7T4Y76iHoz_fq&U z9Lrw6-j6h6dIXD$@CTT@bV=fu|CN>30qabF#$6$(qXQdn5LP@BN42X3MKlC=Z8*$* z2Qhx!D)6e4oFZ2aoQV?chM>+0;3|H}AQ(ynWBdt(n*{#~!h$CFcYijDuz^*C%Yf>v z#wPVtVG?1*^KevK3)+oi^$;93X*C`2Oh83qaBo03`fLSyk#ZJn`UgRsHOQt-27@yd z43*$m48l!w%>BLo9hfop&If0X`mD_28Ei(x`-!b{70iK0<>IeDi_otWSLPR^icf zUFQmb>NYrRSMVToy-JNiWF3hgSfYp{@TZw%c872ZsLsmh5H=vd9YTA9^b&>DMmDLx zk)-)MK9y4o@%!IQx{GBGN-9LN*RA&NM z$g+JZXyPxR-Aq|~lzYox)^!Id2WKGV7&x3VEd}tUjD#VcCZ0KpOr+Qox>xJ#<Ftv?9H`Fv)bd6_wPxjzngG=d zILt>cJNWU1dl7M~I6(A<-^L`gvppE7&IFY0L&%f!dm~R-xSgUu>{J1nOuEHRXwhhR zEM>n36{W^ly^O5DDK>7v+zJ+6wUI1w@ zsa3$U;+wM4JoML9nu3J|!SXI^chL{AkB6bNryviI7-Xhy4}r6Q^6>wv@kB^?-kX7e zA>|eJ!ud!wk<589QG~ zab-g5$KwV`hQ)Q+;*z81V`hD>+&CYqugK5lv+A|^T6R)M3*27~9XvtA=J#uYr+2iw z$8qJ*QG?}4vj{uMM;Bx0qr=ya!817t7B z4TSCXz0s$DxsmNgJ>XnPD@hfxxh>2GuxYsQjm<6aJ%05JMgu$#jYejIzIw)nWm&!k zC}W?)d`Kd~pM7qaHOeZjmX;KnDNd%e;S)t{UM2)0m_x|xKRnh^9p3g0{!K%QG{uhr3=c-_U<=u;BXN$Of$-` zNO-PIb&72e+I3hSSg2JFIqOq+N}gV*HFr6)(b<@^T`k%KplrfZve_an+LeuPwkc&B z+TWIXY!N0~=E(Jnv^rQCBabe^Bz|Rib&=LGqjD>AHDhOdA_B*rYN)D4ILQ9&{@j!R zw1{vY_frq`Hg!A3{kg!<;F zwvHD2<#W$tlc5(7|Ia}q;qg|&A6r`Tv*)oL$Lrj)@5Oc;mvKk=Gh$bnIz26&yS7gC zC7Q>Z+y-+&!$nkmN6xj!=<$0;kr#%`Ry*JgP3#shuhfMMM< zOLk^?*=&(F6tb&f8r@;z83jqzr-Q_8Y}8%PNM|K)J};$b&Cv@%4T{m?z(& zYN*|*#%Q{UCf^V)F~VqVZ_RYl6!nY9ec;1B0y9T>%Me)`XcaRtdpC!|7NbK~BPl-rms!2ODQ%@NsAoAXy<`j?Q#Z%b{ZDz_ zLPPgL8$%bBa`1axyJe-Nu)jik)Bb3kYf!j~5m^*ufgK@$s3YJo$Lry^PmBUA@=0{x=1?&ozFfaltI}cxj&znsRSZTz zEfd0ZvcM^}QeZC}CRs)#UjY{Rq;d;;1^pneP&WQRP-kH<>>?#%SOC#~DG;1%GI)t$ z7Bi5__aZ>lN8D^PKb5R9dX2UVEG3|{?D26p}3<5%%{g%S+-28 z<4u6*Qqp@B4qLw#_lGl;hXZkE_Hay7dcff(rFt_o@g@9*CZ|1w_%BeMIbg$D1n4F( zebqgu*!RAX{shb3C@dmcrcM|m^k(5N9}C9)!X4aZI@V-TI`~WPd)F!cdCyQgWMJs> z3+15YSY&WXE?SOR_t)gB%drkYmq(Usb(QP##&WH8jP6@wmH`H52Uw8^hjTPvHd~?9 zc=S5b?(>>Mv;*GFOu~L;eh^Td^^l8-q>u9~l6~A+)BtHQ1t!5UNKs7K!VJMS*ir)P zgjb+`Hz26995t__A1LA-Qu+#x_VjO|;ydJswJXEgwMwh~*!`-5;+cYw$S37i3j)PG z_@SnK304tQ?&!y%Gc63=4_PYiyvX+z(O@WKuDxp%o_#*I0LoRKd;9(Y;lDA;yaDu( zDI9B6OjVhrj9i3tt&>U0NUWdI|Zds+JSJ;h6 ztStX&6?Q(^jN|<;hloE3GZnHe^1DEF7DrLMMeF~}V zJ}yKK;=g{!C?|VCeg~jB>z5T~30GyX^&z&Q{%j(j#Oe&g24wKxHc9NKiwlA3edM0i z*bC=N9N)L3@?iNTl?SaQm7W>-_Vajruc7($gNYv0c#O-!}5#TW77T ztP9j9t8uY=Dnb~8zcqLzyO&?A5jncEQ#=NAjmea174dAj7AoFFh*a0Z;qn|%zC33G zS9UtZLHH#mgFQ#`1yG&!abDz;Y`Y+b_zQk#Q`SDmZ~4o*D!{7Xu1Gi{4X%|kX7M0a zH8o6R0>1l}k@O)@s$m?}Sr$n0}f4 zLHap)Xss6Sz2nn}Yi?<1RRYDkW;&XgPME8T-T*jJ)MS5oIp^3e;h&Ln8vRppFzT3m%Gz`C}O>(*(B z(Wh}-f3OHys?_`09EjH+Lc#1Q@~3rLn)go#sG_@R0KGBfcM_2HB25!+#E0%R%FwQ~ z`apHor%EH)UH^oNe4xMWF=XvZ>+LV=(w1S1B_Qf#FI>(#%{}|2O!Av{2aA>P-!|Fo zls5v^nE)xfNp^2&m^cLgNmDk%Dxu^4vaZXR_dX3oy#NOZXJKLhDGN7=wZ$iWLwlgW zOp@Lfi4Ig}JtXMLO~(RlAZlZozd?%(rr5Z$0MS>LY`}RinuIwXbyA7BR2Of#yOxvdt+Vp<1?jReB2$QTMkxi3}H))w+`v7O|(p6ERf6_Gh%_hwg zcFlr1d#1@sn*lX^#3z+oYnsd@XtD*hsy9tOv02Lrd&`0vB~6xJlGNW8)X+0ohHlX^ zm1Nm^i`J;xqrI`hbS5@&cmAfr z`h&zD^41otRSS`ETQyg|$UewiO*mX<^m3tahakARx+dDfFL=YKf4h_I3{+<|G(k@| zR$7k%B22mAR#TlPmuEfSIHS~#2ly+c{Ui5!4s2W0)NFX&w$#C$%uDxqzVIm=_2LnzJW&o8}0u)Kqa) zZ02mPHPw^|Ay&%{Z)#C{CcLS&tX?TXIPhV?W*S8baX=nBf)nYWqp5%fKp{SH1VIGa z&Zb%YY{aJDICeWFQP@%P>wk22tY=%Gz|oHcD``v3T5kR?+h+IT|{QzAWm(Mqj>WYuXK)!t-M`WuIC+;(pP)hbYDkCa0 zANP_?IB?W}SKft8>^Y^1e7i8{9Xd{14JLjhy35aQcp5U~j z5i@NE{2lK;ZplujyF1)9?$$FATqm_*KG>@NoR9;1_{kRs3}Ps^M21 zzsNl+jzxt}d3sx3jXm4)qO*Qg=F1BWVj2g(yAACPf4|5&4PzQBYvtgEF)h_w{pGrb cF #include #include - -// #include -// #include -// #include #include #include @@ -18,6 +14,7 @@ #include #include #include +#include pnkx_local_planner::PNKXLocalPlanner::PNKXLocalPlanner() : initialized_(false) @@ -61,7 +58,6 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, parent_ = parent; planner_nh_ = robot::NodeHandle(parent_, name); - // planner_nh_.printRootParams(); this->getParams(planner_nh_); std::string traj_generator_name; @@ -69,7 +65,8 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, robot::log_info_at(__FILE__, __LINE__, "Using Trajectory Generator \"%s\"", traj_generator_name.c_str()); try { - std::string path_file_so = "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Algorithms/Libraries/mkt_plugins/libmkt_plugins_standard_traj_generator.so"; + robot::PluginLoaderHelper loader; + std::string path_file_so = loader.findLibraryPath(traj_generator_name); traj_gen_loader_ = boost::dll::import_alias( path_file_so, traj_generator_name, boost::dll::load_mode::append_decorations); traj_generator_ = traj_gen_loader_(); @@ -93,7 +90,8 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, robot::log_info_at(__FILE__, __LINE__, "Using Algorithm \"%s\"", algorithm_nav_name.c_str()); try { - std::string path_file_so = "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Algorithms/Libraries/mkt_algorithm/libmkt_algorithm_diff.so"; + robot::PluginLoaderHelper loader; + std::string path_file_so = loader.findLibraryPath(algorithm_nav_name); nav_algorithm_loader_ = boost::dll::import_alias( path_file_so, algorithm_nav_name, boost::dll::load_mode::append_decorations); nav_algorithm_ = nav_algorithm_loader_(); @@ -114,7 +112,8 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, planner_nh_.param("algorithm_rotate_name", algorithm_rotate_name, std::string("MKTAlgorithmDiffRotateToGoal")); try { - std::string path_file_so = "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Algorithms/Libraries/mkt_algorithm/libmkt_algorithm_diff.so"; + robot::PluginLoaderHelper loader; + std::string path_file_so = loader.findLibraryPath(algorithm_rotate_name); rotate_algorithm_loader_ = boost::dll::import_alias( path_file_so, algorithm_rotate_name, boost::dll::load_mode::append_decorations); rotate_algorithm_ = rotate_algorithm_loader_(); @@ -136,7 +135,8 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, planner_nh_.param("goal_checker_name", goal_checker_name, std::string("dwb_plugins::SimpleGoalChecker")); try { - std::string path_file_so = "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Algorithms/Libraries/mkt_plugins/libmkt_plugins_goal_checker.so"; + robot::PluginLoaderHelper loader; + std::string path_file_so = loader.findLibraryPath(goal_checker_name); goal_checker_loader_ = boost::dll::import_alias( path_file_so, goal_checker_name, boost::dll::load_mode::append_decorations); goal_checker_ = goal_checker_loader_(); diff --git a/src/Libraries/costmap_2d b/src/Libraries/costmap_2d index 10521c1..0344c31 160000 --- a/src/Libraries/costmap_2d +++ b/src/Libraries/costmap_2d @@ -1 +1 @@ -Subproject commit 10521c1629301d3e81f040213f08de7881bc5e59 +Subproject commit 0344c31e5b4185da41bfb253db720d9c91b802bd diff --git a/src/Navigations/Cores/nav_core_adapter/src/local_planner_adapter.cpp b/src/Navigations/Cores/nav_core_adapter/src/local_planner_adapter.cpp index 47a166c..43ef0ba 100755 --- a/src/Navigations/Cores/nav_core_adapter/src/local_planner_adapter.cpp +++ b/src/Navigations/Cores/nav_core_adapter/src/local_planner_adapter.cpp @@ -95,7 +95,8 @@ namespace nav_core_adapter } try { - std::string path_file_so = "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Algorithms/Packages/local_planners/pnkx_local_planner/libpnkx_local_planner.so"; + robot::PluginLoaderHelper loader; + std::string path_file_so = loader.findLibraryPath(planner_name); planner_loader_ = boost::dll::import_alias( path_file_so, planner_name, boost::dll::load_mode::append_decorations); planner_ = planner_loader_(); @@ -105,7 +106,7 @@ namespace nav_core_adapter exit(EXIT_FAILURE); } robot::log_info("\nLocalPlannerAdapter initialize: %s", planner_name.c_str()); - planner_->initialize(adapter_nh_, planner_name, tf_, costmap_robot_); + planner_->initialize(private_nh_, planner_name, tf_, costmap_robot_); robot::log_info("[%s:%d]\n Successfully initialized planner \"%s\"", __FILE__, __LINE__, planner_name.c_str()); } catch (const boost::system::system_error &ex) diff --git a/src/Navigations/Packages/move_base/CMakeLists.txt b/src/Navigations/Packages/move_base/CMakeLists.txt index 4b73e49..2b24b31 100644 --- a/src/Navigations/Packages/move_base/CMakeLists.txt +++ b/src/Navigations/Packages/move_base/CMakeLists.txt @@ -117,6 +117,7 @@ if(BUILDING_WITH_CATKIN) move_base_core nav_core costmap_2d + plugins # Link với plugins library để có StaticLayer typeinfo xmlrpcpp robot_cpp tf3_sensor_msgs @@ -139,6 +140,7 @@ else() move_base_core nav_core costmap_2d + plugins # Link với plugins library để có StaticLayer typeinfo yaml-cpp xmlrpcpp tf3_sensor_msgs diff --git a/src/Navigations/Packages/move_base/src/move_base.cpp b/src/Navigations/Packages/move_base/src/move_base.cpp index dbf4217..6bf0dea 100644 --- a/src/Navigations/Packages/move_base/src/move_base.cpp +++ b/src/Navigations/Packages/move_base/src/move_base.cpp @@ -17,6 +17,11 @@ #include #include +#include +#include +#include +#include + move_base::MoveBase::MoveBase() : initialized_(false), planner_costmap_robot_(NULL), controller_costmap_robot_(NULL), @@ -175,6 +180,35 @@ void move_base::MoveBase::initialize(TFListenerPtr tf) { planner_costmap_robot_ = new costmap_2d::Costmap2DROBOT("global_costmap", *tf_); planner_costmap_robot_->pause(); + costmap_2d::LayeredCostmap* layered_costmap_ = planner_costmap_robot_->getLayeredCostmap(); + for (std::vector>::const_iterator layer = layered_costmap_->getPlugins()->begin(); + layer != layered_costmap_->getPlugins()->end(); + ++layer) + { + boost::shared_ptr static_layer = boost::dynamic_pointer_cast(*layer); + if (!static_layer) + continue; + nav_msgs::OccupancyGrid *occupancy_grid = new nav_msgs::OccupancyGrid(); + occupancy_grid->header.frame_id = "map"; + occupancy_grid->header.stamp = robot::Time::now(); + occupancy_grid->info.resolution = 0.05; + occupancy_grid->info.width = 100; + occupancy_grid->info.height = 100; + occupancy_grid->info.origin.position.x = 0.0; + occupancy_grid->info.origin.position.y = 0.0; + occupancy_grid->info.origin.position.z = 0.0; + occupancy_grid->info.origin.orientation.x = 0.0; + occupancy_grid->info.origin.orientation.y = 0.0; + occupancy_grid->info.origin.orientation.z = 0.0; + occupancy_grid->info.origin.orientation.w = 1.0; + occupancy_grid->data.resize(occupancy_grid->info.width * occupancy_grid->info.height); + for (int i = 0; i < occupancy_grid->data.size(); i++) + { + occupancy_grid->data[i] = costmap_2d::NO_INFORMATION; + } + if (occupancy_grid) + static_layer->dataCallBack(*occupancy_grid, "map"); + } } catch (const std::exception &ex) { @@ -210,6 +244,32 @@ void move_base::MoveBase::initialize(TFListenerPtr tf) { controller_costmap_robot_ = new costmap_2d::Costmap2DROBOT("local_costmap", *tf_); controller_costmap_robot_->pause(); + costmap_2d::LayeredCostmap* layered_costmap_ = controller_costmap_robot_->getLayeredCostmap(); + for (std::vector>::const_iterator layer = layered_costmap_->getPlugins()->begin(); + layer != layered_costmap_->getPlugins()->end(); + ++layer) + { + boost::shared_ptr obstacle_layer = boost::dynamic_pointer_cast(*layer); + if (!obstacle_layer) + continue; + sensor_msgs::LaserScan *laser_scan = new sensor_msgs::LaserScan(); + laser_scan->header.frame_id = "laser"; + laser_scan->header.stamp = robot::Time::now(); + laser_scan->angle_min = -M_PI; + laser_scan->angle_max = M_PI; + laser_scan->angle_increment = M_PI / 180; + laser_scan->time_increment = 0.0; + laser_scan->scan_time = 0.0; + laser_scan->range_min = 0.0; + laser_scan->range_max = 10.0; + laser_scan->ranges.resize(180); + for (int i = 0; i < 180; i++) + { + laser_scan->ranges[i] = 10.0; + } + if (laser_scan) + obstacle_layer->dataCallBack(*laser_scan, "laser"); + } } catch (const std::exception &ex) { diff --git a/src/Navigations/Packages/move_base/src/move_base_main.cpp b/src/Navigations/Packages/move_base/src/move_base_main.cpp index 597e051..3c3dfdf 100644 --- a/src/Navigations/Packages/move_base/src/move_base_main.cpp +++ b/src/Navigations/Packages/move_base/src/move_base_main.cpp @@ -33,15 +33,65 @@ #include #include #include +#include +#include int main(int argc, char** argv) { try { std::shared_ptr tf = std::make_shared(); + // Lambda function để set static transform (tương tự tf_listener_set_static_transform trong nav_c_api.cpp) + auto set_static_transform = [&tf](const std::string& parent_frame, + const std::string& child_frame, + double x, double y, double z, + double qx, double qy, double qz, double qw) -> bool { + if (!tf || parent_frame.empty() || child_frame.empty()) { + return false; + } + + try { + tf3::TransformStampedMsg st; + st.header.stamp = tf3::Time::now(); + st.header.frame_id = parent_frame; + st.child_frame_id = child_frame; + st.transform.translation.x = x; + st.transform.translation.y = y; + st.transform.translation.z = z; + st.transform.rotation.x = qx; + st.transform.rotation.y = qy; + st.transform.rotation.z = qz; + st.transform.rotation.w = qw; + + return tf->setTransform(st, "move_base_main(static)", true /*is_static*/); + } catch (...) { + return false; + } + }; + + if (set_static_transform("map", "odom", 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)) { + robot::log_info("[%s:%d]\n Static transform set: map -> odom", __FILE__, __LINE__); + } else { + robot::log_error("[%s:%d]\n Failed to set static transform: map -> odom", __FILE__, __LINE__); + } + + if (set_static_transform("odom", "base_footprint", 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)) { + robot::log_info("[%s:%d]\n Static transform set: odom -> base_footprint", __FILE__, __LINE__); + } else { + robot::log_error("[%s:%d]\n Failed to set static transform: odom -> base_footprint", __FILE__, __LINE__); + } + + if (set_static_transform("base_footprint", "base_link", 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)) { + robot::log_info("[%s:%d]\n Static transform set: base_footprint -> base_link", __FILE__, __LINE__); + } else { + robot::log_error("[%s:%d]\n Failed to set static transform: base_footprint -> base_link", __FILE__, __LINE__); + } + robot::log_info("[%s:%d]\n Loading MoveBase library...", __FILE__, __LINE__); + robot::PluginLoaderHelper loader; + std::string path_file_so = loader.findLibraryPath("MoveBase"); auto create_plugin = boost::dll::import_alias( - "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_nav_core/build/src/Navigations/Packages/move_base/libmove_base.so", + path_file_so, "MoveBase", boost::dll::load_mode::append_decorations); robot::log_info("[%s:%d]\n Creating MoveBase instance...", __FILE__, __LINE__); @@ -57,7 +107,6 @@ int main(int argc, char** argv) robot::log_info("[%s:%d]\n Navigation initialized successfully", __FILE__, __LINE__); std::cout << "Move Base Main Function :" << robot::Time::now().toSec() << std::endl; - // Explicitly reset before create_plugin goes out of scope to ensure proper cleanup order robot::log_info("[%s:%d]\n Cleaning up...", __FILE__, __LINE__); nav_ptr.reset(); @@ -71,29 +120,5 @@ int main(int argc, char** argv) robot::log_error("[%s:%d]\n Unknown exception occurred", __FILE__, __LINE__); return 1; } - - - // robot::NodeHandle private_nh_ = robot::NodeHandle("~"); - // robot::NodeHandle adapter_nh_ = robot::NodeHandle(private_nh_, "LocalPlannerAdapter"); - // robot::log_info_at(__FILE__, __LINE__, "\nUsing adapter namespace: %s", adapter_nh_.getNamespace().c_str()); - - - // std::string planner_name; - // if (adapter_nh_.hasParam("planner_name")) - // { - // adapter_nh_.getParam("planner_name", planner_name, std::string("dwb_local_planner::DWBLocalPlanner")); - // } - // else - // { - // planner_name = nav_2d_utils::searchAndGetParam(adapter_nh_, "position_planner_name", std::string("dwb_local_planner::DWBLocalPlanner")); - // adapter_nh_.setParam("planner_name", planner_name); - // } - // robot::log_info_at(__FILE__, __LINE__, "Planner name: %s", planner_name.c_str()); - // robot::NodeHandle parent_; - // parent_ = adapter_nh_; - // robot::NodeHandle planner_nh_ = robot::NodeHandle(parent_, "PNKXLocalPlanner"); - // std::string algorithm_nav_name; - // planner_nh_.getParam("algorithm_nav_name", algorithm_nav_name, std::string("pnkx_local_planner::PTA")); - // robot::log_info_at(__FILE__, __LINE__, "Using Algorithm \"%s\"", algorithm_nav_name.c_str()); return 0; } \ No newline at end of file