From ebda1f81a194b3d6e3306d8787e8c639dc9c327e Mon Sep 17 00:00:00 2001 From: HiepLM Date: Fri, 16 Jan 2026 15:13:14 +0700 Subject: [PATCH] update --- config/costmap_common_params.yaml | 7 + config/custom_global_params.yaml | 1 - config/pnkx_local_planner_params.yaml | 24 +- config/two_points_global_params.yaml | 1 - examples/CSharpExample.cs | 28 + examples/NavigationExample/Program.cs | 28 + examples/NavigationExample/libnav_c_api.so | Bin 1847752 -> 125696 bytes src/APIs/c_api/include/nav_c_api.h | 41 + src/APIs/c_api/src/nav_c_api.cpp | 94 +- .../Libraries/mkt_algorithm/CMakeLists.txt | 1 + .../include/mkt_algorithm/diff/pure_pursuit.h | 50 + .../src/diff/diff_go_straight.cpp | 3 +- .../diff_predictive_trajectory copy 2.cpp | 1327 +++++++++++++++++ .../diff/diff_predictive_trajectory copy.cpp | 1320 ++++++++++++++++ .../src/diff/diff_predictive_trajectory.cpp | 14 +- .../mkt_algorithm/src/diff/pure_pursuit.cpp | 52 + .../mkt_plugins/kinematic_parameters.h | 17 + .../mkt_plugins/one_d_velocity_iterator.h | 10 +- .../mkt_plugins/src/kinematic_parameters.cpp | 42 +- .../src/limited_accel_generator.cpp | 2 + .../mkt_plugins/src/xy_theta_iterator.cpp | 12 +- .../Packages/global_planners/custom_planner | 2 +- .../pnkx_local_planner/pnkx_local_planner.h | 11 +- .../src/pnkx_go_straight_local_planner.cpp | 17 +- .../src/pnkx_local_planner.cpp | 31 +- .../src/pnkx_rotate_local_planner.cpp | 11 +- .../tf3/include/tf3/LinearMath/QuadWord.h | 16 +- .../include/move_base_core/navigation.h | 899 ++++++----- .../robot_nav_core/base_local_planner.h | 7 + .../include/robot_nav_core2/local_planner.h | 7 + .../local_planner_adapter.h | 8 + .../src/local_planner_adapter.cpp | 11 + .../Packages/move_base/src/move_base.cpp | 18 +- 33 files changed, 3597 insertions(+), 515 deletions(-) create mode 100644 src/Algorithms/Libraries/mkt_algorithm/include/mkt_algorithm/diff/pure_pursuit.h create mode 100644 src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory copy 2.cpp create mode 100644 src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory copy.cpp create mode 100644 src/Algorithms/Libraries/mkt_algorithm/src/diff/pure_pursuit.cpp diff --git a/config/costmap_common_params.yaml b/config/costmap_common_params.yaml index 5619b75..a847d64 100755 --- a/config/costmap_common_params.yaml +++ b/config/costmap_common_params.yaml @@ -1,3 +1,10 @@ +position_planner_name: PNKXLocalPlanner +docking_planner_name: PNKXDockingLocalPlanner +go_straight_planner_name: PNKXGoStraightLocalPlanner +rotate_planner_name: PNKXRotateLocalPlanner +base_local_planner: LocalPlannerAdapter +base_global_planner: CustomPlanner + robot_base_frame: base_footprint transform_tolerance: 1.0 obstacle_range: 3.0 diff --git a/config/custom_global_params.yaml b/config/custom_global_params.yaml index 71565e3..f462e6b 100644 --- a/config/custom_global_params.yaml +++ b/config/custom_global_params.yaml @@ -1,4 +1,3 @@ -base_global_planner: CustomPlanner CustomPlanner: library_path: libcustom_planner environment_type: XYThetaLattice diff --git a/config/pnkx_local_planner_params.yaml b/config/pnkx_local_planner_params.yaml index 40dc56d..3667330 100644 --- a/config/pnkx_local_planner_params.yaml +++ b/config/pnkx_local_planner_params.yaml @@ -1,10 +1,4 @@ -position_planner_name: PNKXLocalPlanner -docking_planner_name: PNKXDockingLocalPlanner -go_straight_planner_name: PNKXGoStraightLocalPlanner -rotate_planner_name: PNKXRotateLocalPlanner - -base_local_planner: LocalPlannerAdapter LocalPlannerAdapter: library_path: liblocal_planner_adapter yaw_goal_tolerance: 0.017 @@ -92,7 +86,7 @@ MKTAlgorithmDiffPredictiveTrajectory: # only when false: lookahead_dist: 0.5 # The lookahead distance (m) to use to find the lookahead point. (default: 0.6) # only when true: - min_lookahead_dist: 1.0 # The minimum lookahead distance (m) threshold. (default: 0.3) + min_lookahead_dist: 0.6 # The minimum lookahead distance (m) threshold. (default: 0.3) max_lookahead_dist: 2.0 # The maximum lookahead distance (m) threshold. (default: 0.9) lookahead_time: 1.6 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5) min_journey_squared: 0.3 # Minimum squared journey to consider for goal (default: 0.2) @@ -120,6 +114,20 @@ MKTAlgorithmDiffPredictiveTrajectory: cost_scaling_dist: 0.2 # (default: 0.6) cost_scaling_gain: 2.0 # (default: 1.0) + + use_mpc: true + mpc_horizon: 10 + mpc_dt: 0.1 + mpc_w_pos: 6.0 + mpc_w_theta: 2.0 + mpc_w_v: 0.2 + mpc_w_w: 0.2 + mpc_w_dv: 0.4 + mpc_w_dw: 0.4 + mpc_iterations: 3 + mpc_step: 0.15 + mpc_eps: 0.001 + MKTAlgorithmDiffGoStraight: library_path: libmkt_algorithm_diff avoid_obstacles: false @@ -133,7 +141,7 @@ MKTAlgorithmDiffGoStraight: # only when false: lookahead_dist: 0.5 # The lookahead distance (m) to use to find the lookahead point. (default: 0.6) # only when true: - min_lookahead_dist: 0.8 # The minimum lookahead distance (m) threshold. (default: 0.3) + min_lookahead_dist: 1.0 # The minimum lookahead distance (m) threshold. (default: 0.3) max_lookahead_dist: 1.5 # The maximum lookahead distance (m) threshold. (default: 0.9) lookahead_time: 2.5 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5) min_journey_squared: 0.3 # Minimum squared journey to consider for goal (default: 0.2) diff --git a/config/two_points_global_params.yaml b/config/two_points_global_params.yaml index 99f7480..cb9ca6b 100644 --- a/config/two_points_global_params.yaml +++ b/config/two_points_global_params.yaml @@ -1,4 +1,3 @@ -base_global_planner: TwoPointsPlanner TwoPointsPlanner: library_path: libtwo_points_planner lethal_obstacle: 20 \ No newline at end of file diff --git a/examples/CSharpExample.cs b/examples/CSharpExample.cs index 3d52a77..6ffb99a 100644 --- a/examples/CSharpExample.cs +++ b/examples/CSharpExample.cs @@ -53,6 +53,14 @@ namespace NavigationExample public double theta; } + [StructLayout(LayoutKind.Sequential)] + public struct Twist2D + { + public double x; + public double y; + public double theta; + } + [StructLayout(LayoutKind.Sequential)] public struct Quaternion { @@ -93,6 +101,13 @@ namespace NavigationExample public Pose pose; } + [StructLayout(LayoutKind.Sequential)] + public struct Twist2DStamped + { + public Header header; + public Twist2D velocity; + } + [StructLayout(LayoutKind.Sequential)] public struct Vector3 { @@ -180,6 +195,14 @@ namespace NavigationExample public static extern bool navigation_set_robot_footprint( IntPtr handle, Point[] points, UIntPtr point_count); + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] + [return: MarshalAs(UnmanagedType.I1)] + public static extern bool navigation_get_robot_footprint( + IntPtr handle, out IntPtr out_points, out UIntPtr out_count); + + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] + public static extern void navigation_free_points(IntPtr points); + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] [return: MarshalAs(UnmanagedType.I1)] public static extern bool navigation_move_to( @@ -231,6 +254,11 @@ namespace NavigationExample public static extern bool navigation_get_robot_pose_2d( IntPtr handle, ref Pose2D out_pose); + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] + [return: MarshalAs(UnmanagedType.I1)] + public static extern bool navigation_get_twist( + IntPtr handle, ref Twist2DStamped out_twist); + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] [return: MarshalAs(UnmanagedType.I1)] public static extern bool navigation_get_feedback( diff --git a/examples/NavigationExample/Program.cs b/examples/NavigationExample/Program.cs index 3d52a77..6ffb99a 100644 --- a/examples/NavigationExample/Program.cs +++ b/examples/NavigationExample/Program.cs @@ -53,6 +53,14 @@ namespace NavigationExample public double theta; } + [StructLayout(LayoutKind.Sequential)] + public struct Twist2D + { + public double x; + public double y; + public double theta; + } + [StructLayout(LayoutKind.Sequential)] public struct Quaternion { @@ -93,6 +101,13 @@ namespace NavigationExample public Pose pose; } + [StructLayout(LayoutKind.Sequential)] + public struct Twist2DStamped + { + public Header header; + public Twist2D velocity; + } + [StructLayout(LayoutKind.Sequential)] public struct Vector3 { @@ -180,6 +195,14 @@ namespace NavigationExample public static extern bool navigation_set_robot_footprint( IntPtr handle, Point[] points, UIntPtr point_count); + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] + [return: MarshalAs(UnmanagedType.I1)] + public static extern bool navigation_get_robot_footprint( + IntPtr handle, out IntPtr out_points, out UIntPtr out_count); + + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] + public static extern void navigation_free_points(IntPtr points); + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] [return: MarshalAs(UnmanagedType.I1)] public static extern bool navigation_move_to( @@ -231,6 +254,11 @@ namespace NavigationExample public static extern bool navigation_get_robot_pose_2d( IntPtr handle, ref Pose2D out_pose); + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] + [return: MarshalAs(UnmanagedType.I1)] + public static extern bool navigation_get_twist( + IntPtr handle, ref Twist2DStamped out_twist); + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] [return: MarshalAs(UnmanagedType.I1)] public static extern bool navigation_get_feedback( diff --git a/examples/NavigationExample/libnav_c_api.so b/examples/NavigationExample/libnav_c_api.so index 3ffa135cdf3a9fd1819b4b49e7d91d6a8722737f..8c6aee65fab080395b23f7b40c6f11be92bf56fd 100755 GIT binary patch literal 125696 zcmeEv33wF6*7gJv7zCYwfI&qD7&NFr!kWlMCxn3>7%-B6QN&3I2}H7)%s_Ct1d}M^ zm}~Unic4_C9bCZ$!;aT2;)W~11$u};ge!uI`QKAj-BZ(* z&N)?es=8U=aE)yf71h=xer-(`nxb&s_yh;+0ylk2DF4|_Nv4h_yUA+m#qvgLH^Q8i zS`KPwQ!GytwHUgrqd)l7vA_Dc_f0&lo#p3Pc?p6a!?`4pKc}7L=i1?xn!}${%RybEt4P!RQPJmL*74WJzx?L~)+f*HKj+mi7he4VZksmXn2N)S zqazMeo8I;|H*_(bG;N`&zTSr_p%kT}!XDjaeO*+=qWCsZ9oj@&qfIe=dM`3X-EKC; z)>hc93r!~X+q-p&az&>^pJb{xSu1K!u4vP?jk(QDaecEY+L)qGHT8z-SxsOo*3>S`YL2sR zHf1H=J9CU_bVWseR#cY?v)vRm#(r62=h4DJM-`5095>=1v%dvL4G#MK3r8)E+i={DLBD%&+{>Q@hls|Rte!?9GPAHw-zaZRVka4f^|B#x(WJd0yFj^}Z_fa66RFX4Cv$4VTlaA?0* zaq$L@H*u`fK%Cc$Ytq4uI5y$fEU>q5ejCR-INlQ&o!-Ymiu)0cPjG0zt=fg*{29`p z30(Db;NP9l;;#&TX1y7aVn0kIJ)CF4TtuN!*vglJ`?AjIC|l* z;^>2eetpH+hI2o0P59ZkK1ZbEC7kZj?_7bMkMjT=gK#9`XzYFMwUfVj`{7IO9XEH! z*eNZQhlZZnyY8MBMqP8`-di_xySj7pGFQwc{cpQ-^@|ynuSORXUROL|bVF2*x^dL5 zhN755^AA;CoL4pRvcczkvT$%^-Y>VG^I6kVE8l%^(-)7KH}~9g-s-&9>fZk{`mwi8 zcE{fJ@AdmSw7G9x+dC#MetTR?`GKpxzVwEZ&v>lxhTE4f+@Q=D|J{-$Cy(v3`?!M!Pe|CN(dd;_&`DVQRWX*FM9{+jZq2Fiqo45ai z7ur7BvZ45)87XPX;e<`wf4p(^@~-1rE07xewt zJ6}F<;m?hq+*WpThqv+@tG9nKYv?_9-Te65Ki)AraPZf|7e6@QH|y#BS2~}#pzn&+ zm$k8%?=8IJx@+6LnfZ2>XYQ!xPav^i^M(odBa z-*#2Zq3TZ`Gr#*_|8IIM9K9s|?NPhBl*Jr+?QrGA@1*qEJt)R?=k)ExO7yz&UsLbC zYto9I_a1)W`58&qUTeG1S<&~gPOg^n^FBWC=IF!omR@(}4N>#$*4Y=2@3XsG^UV)j zcFsG8XW8T1J$Oca&FX2}hn_j4-PzCf{kFn=dtF`GIWOiO*!bw?pXN4oE%@}M`5V_y z?p$4T%Ar%I%&NKn(DaFO@0zyd-CfVGSa~SpMOTt{bjsr&tuW6q-|*D!C56|t?B9|) z=(#rMe?7sGIcLkVEi39i{PyRoJ}u1q>5^w`EJeJZqn2@RI6l=T-cA?y1l0Tl#I% zqGbf(Eia2`bK&77B;`o>)e;F9yj=t;gio9HvZYmUn`m($E`8^ z-}kL1Q;9pk`o<=!(mJiZn5!{vXlTX=kL&+vF- zYKh|pfQqO#%Y`>)jS?R8t<@cBDODEEs9_zMx_IU<65 zZoe>medmKuYZ$#+fx&UOdfgeJUCf=r=U)`TPG5_V|Ji}z>2!`z?mierI6jv}u-{YK zhR;8FNO(LgLc6z#;5UYWPB=faD?&T=jnFQREZdm1ab=}pTQCA_mfk? z=l?o_9IlF>Zx2V%|H9$n=}(Qo&%Ox$r%eR^wtjSY`jrquI5~`nK>y1KbPkOQ-!32% z){Y*DQ10Rg^xy3sp3e>a!{e?9e&A)uKb#(7cpH|_gDK(ZpC2KAzkh_M-xYciuH3c} z^rt$4K1@NmeN0fs4{(9sN&IAbpaaLVKIA}qfsbZ(af+$=H4ap_;pdZKN4-tmO|c%T zxyb}^vEMh$UXY(AVff|plSzRbdLss4P3HMC1l}U@XNd{haDJQ3kBH9%!6zPPzf<7f zsNAG-o-sk-_oKc`O=p-IDmkvjeLV0dtiIp!jM*apg=|~_`v2j8Hg_8+>T4JEeNN>6 zIiAxu8R(zikJGpQ$TQL$k$z9ZA5yt>TX;H#pG;5o<#@d)@O6P_jO6mE7{>XByJo)u zD3|DD9pGtgZWfD%BfP}WUd!P3NX``_IGqawogQd%%AY_JUi`-KlPUHbj#upDz*2$F z9l`6n)llCgkR>`5qFoY2{;Q$TB>(0cc)4V^^qYxs0?SVmOZ=*Y{`?aUQvNzYU(25j zKTr8%X@ZL11wwEg;l~JX{)EA%@%*+a`D~7x_HkUOooP;Qj;D#qxfb`BFXUEXklRZ1 z%S3;za{LKFKV8^`m4YVtJ;hI^w(v`2cl8E){}KEwC4Cci{SVHrsV;@*x6kE(<{!T3 zCF=DpCw#e}p9lVzf_|-t18e$Fcb=&4Nt})*|AkO&;wMw^qvc=KmFGV!7+)pmcNDl? z=#M7(>~_F(*plm=y|O08%qUVh4y0Y{uKvS3VV4$wEOK(a{PIbf0dQ`BXIW) z2dMq%mxFN~(<{NhCWlN>UsHRYQLAsc&`;}c{CQ13PZNG)neYReAD+>dx7Tvvw-x@F zsb@Q0Zllm!%};LX!}HHJPkc5DJJsaeTl8OP2D|R2yf0^KOj?n+DhIZ^N?4|B4AqSB^Q}Een;4_E$f$pX>FQ=a*^1q6Tkl$_? z!g0-B_6R+(3q2Vm^1lH;#M;Xsx1BbQFWTNXkU^;!#qwuUeK8_n&U|V*W}Zy zJEvpc$}>(C`L7WCGzxp^E%1q_bG>R@!+{B~XZra>|I!%X>23UE+9>i@2#1|3@Gq@G zKi}g3#WCsk55Z5J;OBb|n|_Afg(*>Oiv~ue?K2_izE2q;S{L;1j zwkfGS$72n8^`8s4+-4i}A^sxXjwb3T@pB0}w+Q}gKjT1@D0kRtoPOQsq4+$3FaLt$ zLM=>BL2s$PX%w)EFdxhRMf63F61b&~OWB-8znw+zR{Tj!~gM}U%$H{#JpV~l1<5R^z zi1eh^V5hwxH^Ljg zIcIQtX?UCCz4^&>s0(keMFu*ng&xN4<{34+a|*q!6AoaIpfgC=Z?nOE&wwFN|Gs<$ zkatq>HA)9NqadZmq*u8k4=8~o?%!}<7pxuG9-b>#W$gq+dsvY#6chsN`{Y)B0K{pY4TyF5k~_P2aX9aQaz-K9cNL&h#ApyO1ZU&whJ_ zpGgvSr|~no7w4x$_<7APs_a~!>xI2sDd;=~ep&l|z=5d(KLrG-Kdlh;Y{8uaJ#XkK6A_{|JGXL9bs z>-&Oe$7>)TqF*lPARGG)g&{CKF|^lhLJrLvc|M4d{g#M+HcRLs%!K{=4;FS|@MCSd zbNa^duvh4ny_r8R%-(dv**t&Ne>twn^Fv{$%|iY#ANK3jR@7JEnqS>~j;Pm9JYOH7 zZ-<5dtXR$Qj|IM@56_?WJ;yaYnSur)`54DVQ)~hc@cf_ilj$?~bCUCNgWn+gCOXy+ zc*ag5|C2)gc7yzfviT0S--vO-c_ROZiCoUh4SvkzcF!s-E^?Q7vP(T~x5@3ynCPCF zTbes7zs!?cnlUl8ptvYEBYQ?cF25K4jytD3+ntwRlwFX24KiLnY1oY7;xf5;>V;eJpWkDE-8Q+^fC$bF&L_i#(3}$rC1}C%6-b zi9E$cGxI(9#YK+RY#))1Ad{exnVIXzKRSuwd5~T1%y3yXA%(B(;2|?}^Rm4K9!&^3 z-&CsJI3e;*9G+k1)b(2ms# za+$P_g~U+Nbm1w4Rg=WQWuBSGtQ?`aM-=9km1WP$9X%|kygV_H0?jm4NSa*J5Nx_KhnKRv`xp`bqdDWp?j87ra{Jd5ae`}+K()v&C@9Wx{}nYblK*qu%Zf+t z^iNAX3_-zRx@YhZcY4r!mw2GzMI{B^3*fBZ87fAm2FDZHi6%9LpPx{|sAek7zSOLy&rq03%mAJtg|EHvF zEcSm?(#FD1xRhJ_kiST-VG8;yB^jo;$g=wjd>VH=(s+4hL7F^l{!`?z>%MpQ%E%UfW0&_od|Q(P(nfdA}%nf-|Q_pY@jtL!T@+{hbJY?z=fse3x1v^9BQwJNTy@sLxkqSI^*0{AB z+R|8ZsL;`RML8w&F{7i%#0-QpifERYGg~0JMQql{(zD9T-6grDWyKV}@XUA5O^{mr zs8b+>2U<;mMwI4yW|tPvBQM1mU^5FuFoF{$(qG-zwwhaN(=0Z+m$N48^F(Td45#L; zBT}Hr942bvxMUQL&cjhC{230odNK(yc?oIdmF9*>YD&?(e6-i(+%j)r?s2wFh)b8- z<@kgbLgu&y*Xrrx5L(Ey275l<4zG2OG$P!TCafnpCL=s@mTK%RLLK$cd9$-UeCCJwn86imH{o^=I3yKK_lzLZM_eg!FsvAHOx(*a zn&r&F!-+ZQ*4&=b?0ip|Gl!I*T)RQL~ZVKluy4ThXd4%8?f{Gr@X_-$- z&_i5qGAd0mL?}=IESNZgqTy~9t`+*Fm7(=KGjj{Gi)JBuPfj)1*jm5dDl%V+paX@J z=9-GK=el#CNcnE&kGc91nm;R>g+UQ3MUUnw7A4b&X{NVC&QY9~SBA;_tYQQc2G9Hx z+FVwaKdXoWAw#i50fj9so>A->nt`FvkRsO2mgN`a6qiLR8=Mv*njqiiO-{s;3ybIG zvSo>+iMSe#+NY9wOEneC6(&!fyMWe3D9#%Wqso$0pe!)%qO!c=Qenfxb6|W$#car= zjsGzB%9$hh2Oq|08r)B=CqpB{EXJLftOM!1P7}*!v0KOOZX7e@8q%1Y3DuofT?KvmUGUem|rNwazRJ3^JmTW819u83tf_Flw^C$a%G^D z4*;Zw$)WXy0yz&gfoC2X2`yEWn_U|I9!$bp5PCBx0SfU^Ga6OKkOK-WaY8p)xkfNA zH+SX?EGo!2lcRnk==YAxj}9I@Ge3J)5tiAYZnR2JTFC5@oIW?Tr2OJCrr4=``5StOz#>&c7`_( zlo3A$_ZS;XJ?QZ>K~)V$y;a{UI3CU-p4{+_r3aaW1UQqe$ONm8a)-O!BrjBn*1&R0 zJ>dlAn2el5c>P6gXNEf?!R<&N?#A-Z5I0+XlB95qSmOi*SzNV3w&`NZsO%MYRZR%@S zk#(edhL&XKmpaM&gQo;Zt`hs(=KFoRs@k(Z6c@K_q1XyXv_ zCi!CLftz(*d9;EX(p&4@JvoLGzNAG;VC=pzhQJDH(im?k_sU#RbVEDR%v~B32X!CQ zCYr@3h=`b`{o39HwhB#RMDw@O@gz7E&rniqCzfoPasxVwaw7-vtc_D!MHr4S#K$~M zYo{ZIIgUVrl`SSFt%^>RW`#o6j~Gmm7I%3wz-x)+Ud>dFsi=^URqM{$7zjEB){GNU z&K~s((xUoNc{ETFUN&QP(a;39HoFTW#E_+Y(k)#oP!16VJ{l2Y(L7ARX8I?faGK&D z9~lEbs0VMfqtzpHUqdTl2qGtfpA#gZKUl3lET5om9HVBml4$FqMNH|KZ0~4!4b+d7 zNvT@LCQ)NK{Hf!xG6MnK(vE{fI78J2QO6q-3~eTC=m{b2aD$m2_bwzt$plZ zw$>{q*};HS@ri)rdBzh`hGTFptw8;cl)@tDv%J}* z=+ttseX%qbCF?z+HbDO4TU0_N>OkMjS2aAj<@p|w;KhrMKLpF3QCzC!5(^{59{JM2 zL;rX%SX#UOBeYs+phPe7phsJn2`-9+$mS2yI3h2RyyG!wX)C%kB>fAl;n>PK5f*V= zC7nPEXk9K@0mYk#&xPYD##A&hnFr8joeiw;WfZ z;FmFq$CwOGJN{44w&4!=_5dyt>;mI6{o*pjGlo;>7ZXRlE(pPDv5FAb5USAgAIk*& ze=pL23GqY`E)w--@dXE3+KK9o&_fTp9#H6FhJ#dqYi0R1dqP5xQgg$jf`dE;V%hCUF>BBM5HO)>eOvfgZZ115!Jd-zWTt6^x$3zMQm zw&{l6Q=kp-xuu2J9q-ANH@q2?A|&jGEmgs{H)!9iw#O<5@jCX(1wvx9ZAEVj?Og*l zDAe~;9H|WQ`^YE=8Fd&VpPBQqDuJR6WF%1|#Mn za7Zr{aSSK#$OwIhWC%KQvFH~X^FwSxeoDmrj=Z2AW*#Ne2rXF}#QyOSluTZ*C^T4G zlp5+p+?K7ha?K9GMbw5o83k6^Qg2d*bE3mNF(nh500(<$VRc;O-AhA81Sf|S)j#$b zVRD_aG4Dpaz53ds2j+yA5=*6s%4K0om&`0}a(8%UE zADKD{D*?2#CVNKy+(e9v+&Kl=Wo2$XXwLjIZ4Eu%6$Xu=Kk{5CSG3!vEI&MB5#>Kv z+6fYTpG@>N5gkb6htfq!5w;8(U@doRPoYhDnH4h`MXW-rtQu7<1Yz865>mS(X3{B% z&1tRs-Qb2k(bF1th;qdc%!l^Ik=`~9<&PIF*gWDR25z-S!tXmiQXxlpB77O41NLxL z4&BxkuJCX-_yS9Z-!9dkIfm1=W(+6ewc(bE+7xaoyTuk{K*h%)~* z)K47mt=sNTO1qVGB9(w4$6v9rfW}CF0bLfrFY%UQ_h^2p$D2)?je?{7BXqLbko!0~ z&pA0Qoov&gKg@RN+di-$Fa|mZv_To8kd^t9x^b&G|uH5o$4MuaPYuk z{5mre_|SpLrqs;Ll+jLi;=mzDux#R1Vxn{}FnIx0(V;JRf9Z92?_4GgWdDW29=fO3@Ry_Q|@Nf z!h7q3W_a@pW?n#_N@-(iYl_ByG5FWA_&M6t9@p*g7oYNBXbk?DqV~Ak-qeBprQDP! z8eeyAFY?g8^b~`G{&gmP6>aK-yC<_0<<)XVvnToUM2GTFS@hS0FTcd-)J+W0s70Cn z{_p=s37}E&BhEXHVgE{($%=H^+4J$Gw^K|*fYFcDOuFwqJs+PaGMh%~_uHHH;UiY~ z%#f)9hi^fDe6i_d(>U?W{12W3y^f|SBAtEkF5K^6njz93J~s#I+}?DxNMFtF$C$1Y zX-|Lr6JgL&zewk^`)y5kAx*z1-0LCkQMzk>K0X!J$@G}O7T%u2~U&oHdMIyWl8w68i;d=gx@CN6%xKo!WT)n_U%5pT^9jgF21`)tjPKA zmh#V%=r5P>7>WOt5x1npf01xi!u=B7Ea7DmZj$`uTM}-T@Wm1y zE8#Clc$|cnNVrwPwSS|OZXcB7BjfQ>{zi$;a;be~JVDC;ft24a;T@#*RV4fkDgQx9 z-();Z%0ExaZnq`(NO+@!7f84&;aerVS;EIkc%1m&E%77c2c`U{ z<0d}e%zqO9gf9~C-IAOM*M4zQ{v8^Kvl0Pc6ahC$^kq6$DL?(Yz1lBJ(tjC`m+~*y zGUL2b$}i&yQvQEQ`I9944hc__@FyiaQ^HS^_^g%id!+n#OL(-DzfQv6k@7E-aQb(M zwV(E#b%Gwkp|#^mDL>&_JElo;CS3b9Ncq3jKsrnMBjff+xFlye|5k~9g+xD7;z!0C zrTpJX`Aa1FGOkMb@0Rj6OSt&-HoI$<_}?kzkCkwbgeww$y@aPp_{|cYDdAs8c$S3E zl<*P>7oXT>cgrRG8YzE;gnupJizJ->9c}GbE8$Z$5a+ECaI5%!Jdu#|E0X+W{BDU( zzC^!H!skl(G6~-%;VUKl42l1G3GXi9n9w~o`gwK(1?cXIJ5&;~s;$E$k|7i(VrEx{H$V;bY z2``jzv!tI-NqDS;-z4F260ZH*Omy2S;W<+NcnR+$;RzB>|3~ zmKo5`L0|&zA6aCA>t!wJ|2$E|>6*QvM1FKUu;TN%$!eUMt}i3BOyywLXMy z*GYJ1DgQDF?;_#LCHzzgUn$|u5?(LiT_t?8gm;th1_?h+!naDeHfE>WjS}8N%CAcJ z84}(s;b%(tK?(0E;iiQ_y**39%@XdF@K_1&CE;-r{)&WKCEP0E@el zcwY&(OZeFmu1I*igr`Y(e+kc&@N*?ROTy2S@YxbRK*CETe4vDvOZXrOuaNKr311}P zi4tBb;e#doZV4YM;dK%|Lc*6xc#?!Km+)i>Un$`iNO--3kCgDu68;YfZ;Bz&uc zpDQ`gMhPD!3ZwdS@fxjj2w*>x{z~2)1TLOPe;Qy`!_FK;S zMXCJ3toUPAZNv7C>UvL`mIkGAy?GsDx@FimfcLfZ`xYllFB9dTO?UPMwzssj)Uq_i zH}(ZS(9;wM-xpY;rzrrwFR(&S(}Lf=z*0R;f$)8S+w?RA!1o0f>S+q<>uCxs zqyBoD0?Mero<5zWQ}i?imQjB_O#x-pUr$pY8THrG6hKD(^>ip0bkT#Pg9^5_1DujmR_o-X#o=T*V7aLM*a2lIV^p(o~A%B>aV9M0F3(UX$t(J z{q-~jd{KWrO$&*rzn-SRFY2$SDd3Cx>uCz~qWyo<>Q4b)w7;IFz%JTfPg6h__1Duw zSbBw?rob-RUr!HX>D%=5aF$-Erzzlz_Se%C=tceYGzEB3e?3isUDRJsQ$QE>*V7cp zMg8?O1!PfwJxzgF)L&0u#L_?hs@31l(%bbk1w>JQJw2MG*XZd~mR_N!DNu^~>uCyv zqW$&sSe9O>r^m7M)p}ZC>1;hsfl<_7PmgEm6g^FWP}E;fQvek8*V6EAJwGGw2ENFj zA$=IJUpf7gA-&s>{@#%O%8>rpkbc*Y-e5?-VMxDZNIzppKWa$dZ%E%^NY@zB)rR!- zhP2m^E;OWb4e9BI^b|vSq9N@tq(>Rj!wl&GhIBtex~C!C&5%CXkd85=4;%F1CqsI- zA^p7}{gom8u_67gA-%zne#4M{$&h}=kbcyVzTc3(!;r2qq^k|->kVnIAzf%l=Ni(} z4e2R{^h872VMvcMq=y;O0}SbYhICIux|<<=vLPK~NFUy6uzy2(w;}z#A^nvh{jnka zt|7g_kbc9Ee#wx2#*lv0kiK6|r({e?SA4&|nFP0|{tBiny;t!M>+})cnRQr^uM6^7I!}yMYSQ8q-xQNl zQ@aQS;87({u@r5gKlO^g+de#zXDL`~>FkJC-@uqc@wabDi)&g&uGZ;W54!4DbTuyD zPW5ZtCOCv+X9&k-AZOsXgrJBVpRRMf3|Gg(vGSqBamVl+F9uV@@%b{x{`QJLvr&l> zqOSc#7WJ#3YGC{of+8}Wjk{dbdvSFvjNiINVtg`&FJVOe1(+hn%Wzv4wSn8qV${2toUgNGxmeOC zGTz2AUS~^iCGSM8QpyEgyGA@;$DZGYJDK8nkF(iB2q|^SX^FyOLXg{LTdVx~&2T=k*65AnHgwpk4w}>U~7# zaZD)G(Uh#AB=7wQp({}n?9!sh>|WACB1^@)Hb}N(U^=#SVYRNA>cj^+y{V_!lkqkRb^88PCbuu%|)(&>vTMH zCM9R_hX!C?qjn@Sg+J{yK5mHsTo#(0|@Q^352Nq0y{B1QXfHX#kWcEn_ALhSJBRXK`x|cPuYEOjY%s;c)X4kgP~DS*mU#BL0{&-eYOcg^C{pXDUND zc}w+Tx?j0IcKSMEdknZjEMYaC@V$#0=sY%=FrjWyPXg0Tk8LzXp{zSWjB*c$$U^CP z6)<@b-3Cd;w+GVx0B&V^U5l)0wcQ^Qrb1BY_JPS%t=e^Yc>}e&S$f&o`~~rxq>y%x zPpq$OIoWcPr45R%>E`(-{Bw(v6aA_Z)o>wI*=|x+rn(#{lbw^sZ5(5Z1A}91u?(+) z)~Po#)o|J3(cYbyI$5e!vVqF=N#GXsUFpD|O?W6RWlDM;p6&`d-Azqz3cgcTIwy$? zj!9$k#%MXHxYJBccWZTcb1Ei-L?m>Ic3s>Nf%!_$&HfY(lb&rG#1Y!3HCGve!)ONeH1#X` z&R`OMT{bKJX4uU5dj;u=?s}?hDl)>yRv)lb<&zfr4#SmMs;1-GRa0OqQGEMdH6C=~ zz5-j8I`&6!1{KMq@nPjbi{+*->7mMlQI_h)j(L#B;Y>}it%tWjW={#CZ+xTbTx zIKya7YFn_V{*FKUEU|Eeu9}%Pg=%0|d{wq8PnWa88JI` z5n0IoIgUmU`wGVfTsMKtxBDztG~le_ybjn_ko?Nh`99lb@XDX*`X!|?bHM0juceA! z4^{ucYj}%oC18}oS-?dVdk_~-+ejX`Sj-+JPLX(oNf313_jCEX{6gTBuXBO>+Tsog zO7W$daY-%XOO3TuFC}bKY8*}&JWjBtybeaFfLmA#K)F(r@Ml5-{>-uCPdWtGIVa7T zyxViC3mw8Dh^DCnw-b!j6c8u%llrQ+kW?0~C+!{MYn(Pc<%*Q)DOZx;g%h__KL;GD z6{v&i3wuXRT(;Q2Am$-p*C@x*-(@2n#@OQVH-jlZYuC;NHnW<(kF`54!8vbkmIaL- zj~d4@f(d~$7(qMe{j5NHG84C`hlKKHvGE3sfK(i+{tb0&1$%iaSWMun|LS}bB-yJ8qGT+i=a#JVASz7O35z_B49)iwv(#R=_P2NWi@_}n z3@UDS`DWS@Fqs5PR>eQgtiWv~;b{{9n}1v^e1@GFPz8bb0gt!zA7e|SKUwsrWMcJh zOVxgG0;b7i64a@?sRn_>Er|y(kb*4K46fceR!A>3joCIISR*|rKF<l7LqR@AEEvPPTb+2mkG z1e4s1G0Kk>%!;a*z2Y8gHq6c-;?9l)5|H9^q~Y4`O#aGaCQG^ybs?vckn%)_*BWZP&`Obdk6aH{TNC?@nb~)VOGzCenVC+ zCOyDlDK0P)MxypXv266?+Ysmn znl(;KxndnBuqhC)6I&PPM8tyB^4R(o4Z1P2Z{Lz-4nN+){c-3J(W#}o{IkpxtH1N~ zRQx^d>(B<(UwCp>g8!E06w4ZP6zIb|eWqdDx;hr(faeKx0Eci^6C+J}H-SkKpuuguu|k zALu&|tP!A;=)_64Fh;=ND}+xY|5m_!oyR7REP1>0Zhi4uRNJz+zQbB_Ba7=X?=-Kq zRKEk-O65gR>0eWPpIEBMms2-QhU@hG?>%vO4|pC3S;Vjsc~$if@gwW>*Kr*P#5o16Lg(9FLN}#q^(hM=Je4z(}oJ z{Q}P^uuCe8To5@R8aq@Vt-ja9=Ar7#BGWRKX}g}Ojxs%gOmI4wX_ALbbNSCp+=4XB zU8%XkmPKw|K~qxqU61_G?(1wx{{dMMv)Ey{-96tK` z;uz=kBqn%N*bWgdSp}H_L4RQBj44`%Ep4Mcwm;3M6v~%L!y$AZYHfh1AY75++sNYv zS2Bc4l}9XG0;wR92&Y)o3xEVIqP4MigRzqajqx>W#-8F{rXQQQaO0$x@&-2kEm71=T zl{MeAb=J7LnUtutc%+A=^XX8O6tcz9W&Shp5Hf|Iuj;c2vO&;}w&4$Y0BMLa##YY9CyUq6 z$Yk+a^9QghsCqdn-&M>=19%+DNL08cuFI?Sw{!XP#P9_!jHVY>ntb^7!!lwO|5!GH ziN_-}Qt9d+OCy*B=8sAQi0&VQ8v4V>Fy!9Pq@jJ?cW402kF74>_QWml8wj=Chgw2L zsc8^gx|Pfmt+yA6X`~4lnD`y!0a*WrZVzLL3^pN%wpsea2hjK;tEF};iY7~?xSXY` zD|(Mb(KdDY_ZZf_9Bm7ANO(P1z- z%Q2!VHqO^PI=UXCNB0aQ53mvxbgi>gzeonQa6Qot^#YK8TbI8~mp?|anBGDDPTzka z?li@p%H%&APm=sI{HY}W66XG?U!WiGOmc}8xTZ7p1$3^%d1CbeYKx!MuHW*u$a499 z)Y>8z5@OB3#E%wZgAdjWtcl1yvj!pen_%g`*j53OF8@juCrkhPL`jdZk{~KRK2)Fh z21S7>ta{K`9@Eo#^J!}8%}KGm+|`D8sa^4XPB$@4K}*Nd=+(EEyfD&`x>5rdozn6t zA6aR>cnj44ZJx#2{7#IJ)HeYIZlSS~-kwV3bqGgz$D@R%`^cW5VeyGuNCa!39#krZ z=ZI6XX$JI`j3mzG+o29-^a%!%5V(SL=sm)G+nPS-%CjNxityTqTn6sbuh#|E;W{|~ z*Jl5VASbR!M=@1&MxmxkUNzKIg`fH>?X|fPwKdr550C&;2B^gZ*I}z6Mi86RXis63ffDV%vz+TqHFE^x5N!oFBTVSFFVPhUx;S%e{fyGZ%t!sp)(=cLgOJL+li48fcOb2rQ#F&;-Z zvcu9p+SXEQWfFl^>s_DsWa{_9kR7x5rf=1s(GXn2HU+B42?iy=;NvSV{;1{MB$d~% zb$KjSSh>C;tP*3ofc_lQh40L3y#=hsn26S(uSOq@5pgW+i+Q)?GkHCYgLkU;eA&{%N5^c+6KqlR&FeF%MKRge+LInwNsUi}e<-gOde^jB-3Stz z!90l`AyobtzoumHImm%2(A9KIKD>DlI3Gy1)GDN7SpAtyqdRo<0`YC|!&6)z3)S(C zLxs$wuIN=J#$$cW&RIrvFvgE{BrQrMG=-{WU6k5iQ$+BmT{8cq_^&ssKciVlT20Su zOh_h_Gz@^L-8*#tGiG)t?+5UOvOoELQnbIvdLBpaw$Hjf*;#Q zXej8P3^#}Fj)ZwC7RwH=Kn_dQCj4!#w41Tqw}ZsHMe!r9in2XeCG7bbG7$$=G#uf9 z63ZF~1zNlqckl*bVH8UhR_TH{D3D^QdYDS+rOk(6;^bDjOR!Wwjhkd7S`*~euKEd( zs2RnUYr4(IVU_z9Cw29w2#vi;e%SAzXpC=)nXOy}^@(Z`7>2Qz81Jk)OhwdmI}?vH zvXE0FktzeJKmjuHd6-_2IJVC@=${-E-SJK76c~uS>fz6HMMl&k&^g#GD!z{cyWw`E zzJT~71)B0^9Tb>sI!?U;1TgqpOK9iFp%4a;0WE+Gv}$`$K&je7;HU zM(vG9Y17X-`tvTuzgYGuX6*i1Ly-vtvaHROZK76z)0Sq-nv;D0!KB)A79<=ujaEI! zm`s%pbCiFIxn_I|Vx+k1#kx0?gDC}C9{N%J1(~_o)9+P5W=bc@_iAXqIF_mD5&x7< zj8-RYjJqjt2c*F5W?kT3>ADoxA@MO5j|k)D4up?Kc!rQdfHy_bpi*)T!VQUK229F> z`asUw3hBWw?5%hDKE`?+|HV*G7ONz$wcIp>Xw;lP+3CaT^L}N`_ibSW>hlo13#DNa zizxwO5iZ|aSMnxLAK?dzPY=%9FH;qNDdHqoW7htu_uGjuuP!dk5=gA-Wgx_)#dmDg z42@T6u(FZ38|_xF_&k_}(ju^eaG9Ag)if%|KLS#iO+XtEA=nV5RIWpmAPuFlNl+S! zgh63pX6`sD0gVD`@PO!GVzJbNu{2ye2G@2ad87A5dI}!BMSbOCa3sj#;dzq0oR}c^ ze#dkNTga&5Vn@UspJ;tR;2O-A)Sr;X(*3P7pqEZiC%{rt$b)%1D#;&AgJXnd zBbGMW%&z6qk)M_4pQJx?nv(oJ9>L~|nB?yK*$Pq*C3&0~$)+7)p2q;{j(Sl(rx)XR zhE%5ZAJCkplgZA}LeWZcgXf%)3EutH2VDM`wa9|!EHBq9YZ|SHmSST=hXyDS*tMHj zmc380EKOeo3+40|fZz5lRw2KX45#lmcn@ge+|Zc{Hk>H_b}S$VP1DW7dlF0n)8a;S z%<6bFPbmG$ahXwIg4LVKlbWB|=bueu-73~qgM;tqX$+Rm$2W;gm{lZp);|B+>A))= z>iq@DgSvL^a-YQwY_WU}?F3_oiJ}S8F{n(_^^x+gjzdKP4z6pa5cxS+R&Mh+W^vJt}c{}U=P?4M7PrvB{d3{O~b(YcbE=&#rL*Sc__*=4WnbkfkWcf=i8K;blUqyi@gg_UmEnrrfeK@ zW(y>{!Gp%#t3Lh#H9O`%L5u1N;U>_+7CIU7HyhiSn!Z%`AS0`RZ_ziT=_^*r?I7xZwj1lvu<3IgW3_*aMcvTfwDEmTi&ClnG#PSVZN4) z{RmWVzayUd1oVU6IR6yvnx?)>_(sg-sb_>k+N=KhE@h^hG~0m!TdIm_WcLD^FOZ8X z(a*5a50V!t{nygk#N0Dp#cDmA{;<4ETBF#jt^lQ`T6Gs5L{~TxsCpr|6Z+6}7F}S% z8B!RmWjyH#W=YQzBOr4wYdsn$G}9H-&dgqY<9ra2DT=?CjmFzIR~DM1JRPS8=g<1M zH5T_eMR_qm!ie0D&U<9H&5xo5PeB=IQS)@M4-IzO@=ef4iN3a4`5SD?e`OqvBj+go zHm;hvu@kZMZ;kR)AyC)pT-tV`(a9fMl3gzC%TmEsTfsTqxM4Qx)qs-koSv; z$$LCKooMcg>rLk>{t~liCe?b3o^=3?%u;AoVjApAjN#DyynjGA!E$>&J?p){>9M?8 zP)gXJVkw>&k4HM$Xd<(jO8llJ z(K!)r+8VL0RbjS#SU2lE)4I z2``Ub!2d_&kqBcuf;=9gb|E<#{{b(f^a zw3KTTwpH&@XHqLdda+D;H>lAlkbAZbdOK}DV%+&- z9Dr$Bh^-VE*oX!WD79Is(RMEstYL13Es*l1IdYfU@*JHJ1YpZ`^*E~&nO?-qB~B4U zsCkj?1tgwvmxi5G1onG0;}SWzJEGDEAgfgfY@`GpQgNoAI+tnZUiB1`oo^53keJV? zv4lcLFrU58R)Ksjf0mUBAVQdxuBR@xgc4Ru^*WLv3Zi@j#R@-%=ZPVLnZ1;=3uGuE zZ&^<$Io!o)RTluNt>Wj~C0)t&mK$@Zx%+RXUe+r1x2f}V#t2nvN|Mx}tktgr)sg7? z(G9QTY7qS(%|ZT&B~ZoxIR4hdN^eJ$fHgZFCrCvM4$ix8I&* zslJBBv0PdX%cWIPbsl3GD~2>GDxrvgLl+Nw)8?^_ ze2j7-U>d?CqdhHEX_)yt@kBhvRd`VYW5n)Y+ETrlwaHj)&+*u1lQ*16+b?8qI1@Qo z>&~VN%(HcG*a;<(U1CI0Pv;WJC)TZ}d+^}&XEu37%Z+DZNG94E%f9LWk}p#hnrl)n zNVfuIumLGKvL#H6bO%G!lE8ma2R>iNxYY!w>H9p;$S^V9AdSIzmRJgGWjBZ%Yg((b z|7KD#^)!ejumqb|vA>*a*o#bc)Jfnta070rA5pQsZ7e#;{pPx+4%)>GIFk>ly@M(T zn-Rt+)T%GzJH~b&FFRDNx|7sUU8oht(4iW2i>6WeOZcN{nnse(Q9G_BQx2>g|d(|gcVY=yjr!GP*o4(SX5w+UTw2ov^f{jn!ujsV|E>D&V zn+PstK@7|ae!>{ji*k0VQAFQ=J+uiCPlVLZq?kt<8hfvLHnlv4q1_eVS55D;_5vEq zQSUA`3FH1lid6*1GxR>DzZgV!d+-JW!t~xaw1rx`h8O7a=duE^UZWNG5~M==PP(~# z-&28bQG3-o4tkrU@~A#Ex1k|{88O(`?}d=T>1kSEe4H5;2*xYdn-O!Z#TH(QA74tS zcUN$g47r2aNZ9Ru_Cc@eZT8yz)NQ48erdBjILGi)kx{XOWT zJE3)&UK4U}+0wLJ#HT8YGow7GI1s7xQ7lf_OU!nNhED^jN5HglK@wsH3Xd6#VU3S= zslj^7CTbW=T(e+k>gBkT!Xo3-iC&oT8CsXZBb%`P#6GNIr8cO+5=3Qv0u|)DbgMd) z(T{lvd@KGrW^Mvl71@oIW;R2zTj9S>!IR!ADhr8!(PBaVdlOmz^-26$h(~AsCZC;@&+#xK`KO-j#K5d1M0Qh88wC1w#!h7B3{A`r%# zyfUv-J&#bCu2dPgS7;}u-8-kRP68opmi`hfGBpZ-i(V0{RgG-A8kvz`8U%9c5+s_Q z*5@1KFDV+tEVaGTwj7axm||j%;zKZDQ9G?>Guf@MHOppY#(Z-JjRbRriaD@F?K@9* zr$5>TzezTI0VsHSpibQGz!R$*0tkA^xkH_RAU!-ci`+7*VCLyU;YdaE6%Y+><`8D0k|0ad@fXNJ{r0?uRH{0#~|OcwASyCmE4&wiL@s5w`U2*CeGon^=EZi??dg zN4oZ=)^Y({aFy<9gYFdu&=nNQN~Qgxzqr?8!1->FK?wehX|LTbEPiZb!= z!;~wuN0d92-*7vElj}@U4BH>hW28mH{DS3Yxl_3rH-k=&ji2=84S!6*ZNa)|J|K=& zB&-j32Et^YcYYq;|DzGV-JR_!CppL)S#3Sq2rPkKw^Z=z6!Ay6Oq)$SV4O^ zbSqUOqP^@x36ORf<%(=C@8EWXnrvrJhO5aqMq0Gfe_jr)$>q2iY!S&`ba$3Ogbn@X z`GkdUlm5ISPyVY_MdYDyTM!7ZZ#^Q`V*yy#M*(dp5vp&u0y+kLYc)Q&w1z4Zc6{&~ zyA{?q-1ZV{u(ilx^yu>V;B?3#!uVhtC`jW2D{@A1=vBxnIrJDLb%%a867u)}T2y^Y z*#1-V7H3DU)oU-ZTKxb5N3y6fpb*lvit$`0@S=CE7gI4|J@`wk6rqtxNU+M#cArSh&0}L7c~kq{?-N$pYR%7O7%X1n|luTLmDN4k9X$balKJqWkkZc2`ei_ zG|I!zON}y|SdTp3u@Fhk;fV=xU(WI)Hy>H(zu|u5@y=>6p^tZ>P)a1Z=OUvd_Z=%F zxzESFBaU};f51XGmZ~~PP0V|-BO)f-M?uFg7#L#%zlb5Unn#>TIDIwCI74#8t8rie zHhB-|81)Y;mHI^DM^;WHH5r>Tc=~GYO&fDRhiYm54W17pLd3vg0(dTxTqfcPNiOd# zm*kR-d-Tpp1xhrDqCk?b+p_U^;Mx|sZ_vggN0C?HCP`kuArVeqk65AcBd{gz@xtFS|st*X-!c?{p(OI%?(TP})DO1f6q{tMz^BB8 zj}{GMx*|ND=d=_xO!SptDXd`a#F`Q|6>#}zh2MnF1elsrD%;^JPNVKdUTk4bgj8rn zWEmLc^5gBs>UO9-dqJ08Y~O?hSAsDr=5NN^*>3FW?T1Astd_9A?jx{Q zOZ9dzir{WwEpF@ny*HCtxQ^*2l&p{YPC`N-E!>Yp-~w=>jTcbW&xrl7qmGMYI%}Vj z=u9CxkANE%p$gm^i@WF_sdKw-=YhTOi7Cwl%Z5e5! z9>mN-QXl>9M?$M(;55)mVGg}|2q$Y}WV!J>@p?S`rHG8)%!qms7{$uX$w87>FGC_Q znQ=>fL-l-Ig2T@$Nc!POT_lrQ`?${CUUdqQO2+ftKG!wbw2PkFgU)NH)YXgtn0(e)&)GyBD^h!6mhMs1;s`Cy&nx>5GYsyuk`Rb|ww~ zusJA@d_L)a^;o@JC>XOH|EM-p0T^9%4|bFF?$3g1c+>Org;u{0n%I!1+iUfe$j|kt zipJ-%4K`gLYJ=5nSYE0-F#wS)WFqOvV2aUuCTRNE$_6df4c7gJnKGNgUjDPwP2y@2`;DHn(unZS!1Bhz2soU>x4RLB0 z$@+z`NblfK3s$HB#4?UL5=6;@PkoH7*n2-}`m(8^31M+88>*+>6|wZlt@%WrauWPtPD`j?|w%j||7zpDw^7$J(DRnHy?@ zt^3nNs&w^V*Pli)Zo^wj?gJr~vg3YTt#_*PaZk6DtI=OMb+bFS9{0;dOleeDP9(bJ10I~cFj4Uia-m+%ZAf6B4ZTvInH?55@OCj zAR3kU_;j#Y@F*-aG=M_J_j3Y)BqDy3vtI7FMA>)9g9roc9~8;qVpHU%Q}EI zxt&PyvShR$$#>yhM~Ihsh;K3=A*(!Mnq zGSWxjX#qY;ILPHY=<2Vs56D}dTcfPfUiioRjh3p5Xx`}i39tI&JB94cf-XRuuOCD| zgx>JJo zjX-+WApnQOy70N=;n-g8@~Lc}EMDQOq__Cj;tl@sh$$%t72kM#FJOcBTLc(Y#dE#w$GR&fnRl_bGF9?c2T-!)b)K3WWVGN@jVB=tD9}PaAUvm7oMwJ{<9|HMg69pwXWp1O8ZYt z-Z~fC^HO6|UWKsfg$}&Y>|5tT59!1^G{`e=JH5G!?~bI#Iq-@SUgX>c(K)KNc>6eU z7jd1pykl@xdJ$-qT|n=V^8M9HjhkYmzR#7B?l@0?#-jZp3zvU7n)!1VMHYPPh!-lT z>4jQ)PVsF`+`>MH!S{=3T7-}0>07(iN^0%uEuK7lG{RNmHK*{ehk*5hHz{nUP;8lA(k9`>ztZYEuHOFb>zQ6r_vFRZ#S@#nFK=Gq5{+?mVwv&TH^@U zcy3kv;~^-#dPpBW@K42yyK5~s%tcd?pn4)T4^l%ry_aISeN$jMZs_xK;Ot*%(Bchj zeyn|89-lqJu55%hrHC_ovyE?yM|^oSg!Q5FYVZ}|21`|E#D|nuwO5Mq(F04>ooH5< zzu##EP$l|;BCSjHVc38rbLcCAyXjwX7*&jG^3nA1NMdb7oI6@A@d zVoe^FWZtq{?%3GWqjug&_NoKk7$tdYX?MK!&AwoRoTq{{yu7QJ%f1GLH%+&AcVijG zOdl<>Ibolu7q6WC6F*$g`(^I?gvpcPPH34Laz!OUd)FA7n3siV>afa zG4SdOz7nznWxrX-IH@B}@Cp=dkyWo{OA6T3j{S{gvXliWWH=6#)Q9Ma0kx=z{`RhT-+=5D4jiBH^L@p+4S6t_y&ff_4~OR9xjM)d+*zvb zVmG_R&Ze8gl94CzEwv3Q1KqMz&1ZKr&3-S;LbnurZpjCW#V0}fh8PPOLR$o6=oR}} zAZV%n49~Mqj5zU;hecy-_)r&GAh;me1Law&z5_F~-^I6MjBgi0a4z1yXtc|4pB~k} zS1r|PR3&4dQ2`E2 z!EXsDez)0=f5C=6D|ITX>Sm8M^lJj0VT4rA1+%E03-NgM0eEP9QGiv`Kbj)p7m!q` z#+K?{ObbB}UiK{UMHX@;ygjwip$BXi~IG8}H5Evu^*BTu6o0us_BG1KgK2dHRbT;mbBxpftuF*o7?BK3cZ<3lJmb zw5~#`P~IYv&-*;W{0<9-uR?qJo6I#rapipai5JI+_j&zz55;W)A3||yb}gr|_;|B; z$J{1zB3N-}<%COme4-rk6PkM;D3)!>B3+@mRGf5jLGgiivpjcrwhY5uKs~>KRHYh{ zt0XEH?J?0<-gxe@pBH54W1oiYzlSB|{eCc=y?Hk&8$OyO6MC|kcq`lTFw(QBWlkSy zXZRf$IYuH)J5HE2u}1!`L-3D;u@MjU4mUIsT=|N@mB>xmmM59Di%hI-i3v5uoS@o> z=y+^IM7r6W({S=zg@HJ`P2_ zY{DlLXodIDtnJlfyip#2Sj zZK_<4(>E>V_E-N`s+i!GK9V=Lzny4)|16r{8IkU zTJk%>XOEzq={pg!_^<~DMWyYB<^li4*eI$T*@IiLY5DtquI=^JsK#z-;5%_T~-XZt_KSNqX%tL9uiVVqif=$I1ntLLayqwlEA}!yO5o-9mRm1<7 zFc|0GK}oBI|2jeVjj_A8gYf4?X-mFg-`@PIN(UPFBhaGcprBs^0dhAI2!3GO*tb9e zzQ6`hnAi=FWf=mYvE2wfcKS9&U-++Leio-2$Ztyd>j=^HDBJvfVKfP_h?gxKchBsmZyw-B@1tR&C&oyoTCF;bL zv zHqV!Po8aq1YNp;8J4ez)dOtvniUUtj{{~-HqA$}_3uBlWL<0tf#?a?L3r9Qmp&ONg z_R^;OmlX>p#nJ#G{%^x1g0d~kpk@2p@K4QeH||2E>b})JRlaEB1;h+x!qHHf{Q7g+@O#$nueh=$V&?qDO;@R; zA?330W4NC^u!-x95a0~RZh7tNW!D`~^%Y_joxua!FyAVQo9c9q(f!kqH*N>zen&rr zvjkDd?Q$Sp?3g3A!l@lQ&*0dRBf;*O{Z;o$~M1BGQ*xf+y90>vuVE{e1NU?`#q^nF5CQjQ40IUEII z_FsApWi|HdW)L3|*0~={p-gF`tqrKii~LIKa5@fl>l*tuaxAtAX%}gewAza zj+kGqVZ{QP(Z2WZr*n3Me-F0?`%uE4D%(Q-v>YWucM2ZCV`CRwi#%+q54a$`N~mlp zLXh=&h4ces2y$PIB(U_o{%m#Hyei#MsYqCWI!JOpI&IMDd6!Pt{?|pP)0#cXUA|F$w~TqJj>A1uR7! zTLqG0BvJHV;rzhW-QOe>hH?Nlh5k$R|2Zfzl9kN$K@!DGWQY`vPPis}MPb%9SgJ*{}4!)O;U%48FDknB3G5j5JHsy#z#euI2xlqoYlFWV> z!XS?d_3Xg$^2fdd3*?XQ9C#ZFW^5S=QQDS}kSA4(9W^=k8u`PHtHu_OHB8>%j zY}6{oZblxM-dH&T9rz~Aw;@IHH#T9He~9m`>n#bqC4sjj@RkJLlE7OMcuNBRmn6^` z>y4%2Q7yeOor(2m%VX(uq%-Ev#5QF7eZ7%&k$87xO?OON6G_LTdODMe_jWE^7)d5$ zy&c*@zYVW1*Q1GEgzAfC{JnkM-TvN0#=kDo9mlAy_9lF-S@5wMaChL|jQd{PPvCwX z_X+49RO4>O-Hn@kvlnoayytW!dSY`@i8YB#JerZ(} z{flCq@!o}gyp4B8GVw&O9`B83;>g04vFX^#P=yPpQi;?;e^al>oj(~#MS5bHSSpP` zxQuX3Mr;$!>ACkdI&F*n-EkBJN<|Pd=y15jD3Dl(Ka=q1*fJ4b=s!&|FvWP1Y4E)! zkw|A2E{tu6#*!lU$xOTOw`8W7O z9@aquP>+SE5UH5VSiCnKOJ$5VsTdyDVH|tnt2Gl0>dX63A9Ym0SX1+gT3zq#?bD+h zHUz8m=0x;zJ(=i^M>mG6!eN}^k_p!8tx3Hna(PTocSTaM4m}gWTwH+*;pbEMXriw- zgRqB`h>6yUd7^NF^K-eErBfA%Q4K-uS(_lE0EK~0gG1}Z@oSCfwh#sB2LsXWL~l$m zY>Q(~f#c7YOa05JOWzW5l+EJsQFCCFaYo=DBfl?*ABhgsXin*D!bAy3JeQVdoQuS~% z!mW{})}S7q%t%{Bq($(IiAW9evf5?1X{7m7+@-jW!Mzl>A2(TXtT@&ZxUncjJ03U2 z9yJT#cj`+VGI;l?Pmb~5e@aTno!8*Yq5YaZMu;HI(b^KfH5mo@{pj{9odSQJiM z`-roA0^1@3p_o{f7MZVWOX!Zk{) z;u>ctpK|}lFEqTs+0u`3z0-5<9ta706l&#|92mjx@pv|SkOYU3(sBrGq&J&=9KyaX zk*aUV zKLEZCcw!npFbcH>@QZ-;fG+^906YN&{6WBOz{}`8;8lPpLm6%X><1hId=>CpfZZsh z9{`S_fUd}7vu!Bw&jPkX0fqsSeoY(1I-_RrI}F$k=--&legtsjBiZZ>@I8DD_ya7* z;BPVb4*;GFI11PXn1ruB4%mVTo6X2q67VL#5zI%OjQsewXR~_%`!RVu1Nj)mvV#u5 za;&b{3m5`?9WV)aHu5tHxEZhoYXJ5F4q$~yHS*)f!l0V~%du3>i+l|OZU!6&+=l#( ze-eEKQs^79*-!rLx3*; zwg8R;wgY-m`ICSZfc=1H0}cR&00#lv07n3mfTMt$0mlJv0@ScP{a(Owz+pf?;M0If zz&8O00L!7TLx8lddK@qWSdNwMZGa)b0m1{8LyrUadSn)05-shsdZ`s;x7oj;xAIt&AA?O{R17Cq$ z@vMCn@`e!^27C^NWbgr$AD-LyAUt5;-?P~pfG__V^dHaTfB`%YKM4H;oxz7t{&;Tr zI?5N&{|(TGacX%O&w%}VAs4{%ZzCLxFYOCI2-yBO@&`EneeeM|^h3xIdKr2e=>d*B z13f`K9C#M-0sDUfxx*NSp2v=RWE6jn`c2QjhTH)AUqpNu!Q{)34;jO;Y}W4w#04>m z%XQ^NnrlP3>zy;E6%WAZ&H@%mX*KPr6J*0m%NLhcEG;WpU)--<_>P5V&7DOiSHy1s z9Pa=Rgy4(lUW$7Rc(R4+qA(fUR0mPi;v(EO+xRn$L7lk_kxEA1G zn#ASD|JlGb1Gktki%ZLQx|fvtd#9I{Bgs1GD#dF?m<>X38f&)y{@!klLv*LDy?WJ zEnfs~DBVVcqw+(uBQC;S3LNQ!!cl&bz-!@yBE;w0X4yYLutiUPhF{hleeL? z#SInq15+n*(omxL5tiz$wlKMctxgfM3#t)+n8B{Iw|_oC8@og|yB-X*2&X@~}ey-0|r5$VrDyZ|b4 z!>8C@Kp(dX`?IvXW}$0;w@Q(ks?7nRQ5>1!wrY%N+`TC-_dLutGF_UWZH zz|@t_MhGKk$Op+U34dh|{G}E6t-W8#Z*j>7r$0t!yaE43eYy$ZnlHE3oqK^>1>9=z z1lu2SOQCCxcq~Ufxw$8sy$jHL2b=(#%)t%Id`an`+w)EL^wI#z0g^UzDEkS-nyFsh zey&lk5Oq`0R^LwVF3x92hk zen{m+zlCU;_&L$U&yW*8_24IjINrx(i*Po62T-?8PG__AgntltQK!+QZ}LF@+NLXG zMs1lNVdyfYc`NEL+ZI?3&rUZ{o{jtMNb5a--fLu9RPV_r)R304d)0XC0&WIy_v5#= zjM`6Bt*w;yCU55>r4>z&p_)BWTD+1FTaf^Qwcs8D-PY{Vln%Q+ ziy%w~4Wz7TBn!GsdHYUnE^ou`P1Cj(?ey*PUhnxh@j$sE{@)KjhRW6ZeK?}HsBUaV zz1q;1%|1hQV;}HNbp!Q$Ymwj$b;DEVa%8Qsgk(vViLY}^e6^d|BA!U^eBcS)Bh9;7 z@CtvT1|^(y=j{Z6(=!O!DO{n>w3p8cV1g{D}AGHJsmQj_x4n zc3;VK^{La{0J`5+bkCJ^sm(tKx|yr8*>fl#3xHo(Ej69Moe`$yLVhdgKrC(oUX%{u|2szetzYgNR6HIh6q%>P_AiaGl;X zt1==w=<2)H*Ij5_P| z`KI&&n>K7tLnyu{AopFAIOM*|4Ud_9cW%!DeKw2TP?9VyMoBzL zzBe~pq%&SryK=}`lwmvhq*n_+K7@B&7zF6RyS)_dekhm76YRn!&$3d#d%2OP#*!3% zL)%d(%_U8uB=M7I+zT25@Sz2b#MEg7K!e6f_rh=9M|{iy4cO2A0vEDKcUamxuE=^#|s-xdPZZm zH5l`IjKbf6@HyE~c!-~BI)qSH(kD_vn?dpRB3|-lmPgtW5B+L)ms33A?{&nx6Jv&g zzY8blZx+<$aik;odz&Sl3HiGe@dC(~D6d~asdM?7kiQ!c?2!Aie4sIpB*IUx0GRW0C zn{HL0F296+y@*E!F~@7cc*I`|;=TE~Z1$IwURfT0mm6|LuZ+U?Bm4`n3nKiBX!NZ4 zv4n3x_#vW?acvb0nRQJNE0jUp3(=+aOa zx6nJ#|9b@ExujnlzuoX1%pV%E7d+);Z_Zzf`x!@`7L^G5 zxCeFdxqaEJn`|!42nl(?hs(<&j~6998)+yj-#&&#{n-oN8rv{mK=Kmp95v~1L#59} zBh%%}*dIg)ExY?zm+xH9CtYF?8P8c)`SmXF@oAT5w@bT^eip*rNH0I<@_fOi?NQ`F6NHzjamMH<-JcQWvyK#$3Le-P)JkphjtxY;#Zl+%)aiMKWpc zED2{k=<@x*r@iW){=AQZd5^E8@VifP6_@+o>v^YdfzPeEu4ck-o<{FZba^Wf+k}5f z;7@WLd!Kuk>vvwyUp>CRcs(Y5b|2^RUVu0`l$24c=er&yBgo9_lVL<2z{89mx_sYs zdv0(Sea~$ohq$2kc00XyxsLy<%l9p>=QAG9176Q>J-$0kOo%vV+T+MH9(H34vS{BS zq%qa-$WwXIshmZTXD^ii=@Bl{lOui~Ec&2@zD0(hKjHi1T)u0H?lxy!$mtz+IYFQ6 zi>@>DIj^knzOLx`3E$7GxTWCxtZUw|%lG6l+7^%R(POmT9^cQWYkR!DSEg&P6!|_| zqJ6&D2VeG2#ctqlIOY`KpPN31Wq6M39b{yaz8`x$dtB~cdwfrl*5BkIgh@-`7h|wA zyZcmE=|bOCTE>T_`d?iz`IayhBFssyvNGQRmn-Dk!QkY z^zYrLx!(1%$M>;f?blx4K(T9Nn)@@w+E0s-{Hw*j{$p5?koM_8;6CDhv`B;hI9R0p z)#d(bk@gd}`>rDGZ*KR)McSXa>K}T@GtL6d$6TJ*i?ly_-M=oU>g33ERG0ZT;oP&;n|x>vYyN#C@jO`jMOS`ma!szn z+tZsUo{IApd`klVXbC(g)!9*>r^3tO(xLH(!?_MMy%Ek|A$T}xQ=I>;d>?Lp|F6bV z8=tEDseM|xD~Fwd#5Ia_61I#p`T%ZVTfT1!*+&AhW!i&7!EQVVmQojgyAT|afaG$ zoIXQ8!vMn&!xo0^43iA|84fTUWH`idnBfS+QHJ9TwJ&n|4E+oP3_}cC7`8J^GVEtK zz;KY^5W``HBMe6wjx+4P&LtVJ{a;dFztBJX18eYAdY`|xvbr*GPOwir1wUF9s0>tB zR-GyFwulao9<+LQy7OOnFf{kLBi>`QKjv5-&8w+)$BOr9s(rHJi!^2Dt@vr0Y9Fll zVokL(R{SwWdt}9<^&2!}!^Mjz?eE)QCHC%fl?*D!ju zQ+PD?>_3=EdGLj*lm2?}5!j%EUVDrckvS??L;t+mf93UihzmEq0RGy&GVGZg#n1R( zGCsuk2FAbpK8bh_<5x4jj`1`PN!PWwiT-xRmkF#?55nKX_?e9V4-Wq@S>T=Y=XRzuKEweT+`)LiZT#;WjJJ;q(sx*tuF_|f?k@#C zzupyjq#V?Eqe}gF;9c;x?e(`1|3MM{cx}kR4mjoaLWHNU-|cqhB0(p=p6ZMrV0o(k z$5p_)wS4<_Er;J`3;!7rKHm=CBEsj}nLC-zO*Z?mN8t1A%=duD@|nErC4n#1#%WO; zu5%>N{sjD~_`?5AwtK2ya*CI}tuNKI7iGW*hkupvfia2L$9S6WAv%prNA=$>1>T9D zPY8Ue7I;(=pmq3k-N$ss*GYu3KcfZc%s~fF)n!RR{$B(9t3x=X-#savxbQ>Ca|54FX@Tg{mb!$oP!~===cqTR~@l`xi=o%3<)G(hUGl`5HV< z(jQ~`6>wRO2j2gEiMWUH0pO|JLtO527#{_m=#;-A5w|k_M#c~SRwC|Y{P%$;y&ARE z>jlS3`Wok#)-uwSQ1}|jXR}0W-vXZKXg2*k167Xr8J;e~(>gu6b^`Athr2oa;BzwE z%Mxh+&3Nr;iNK?{mX#6x{HqgqC;C?bPvtvwrR1lPqyALj%e6uJa01t2#?$h8A z8mI893*eIl@VkMhe9gAmy^#XpPsdt6%2z*^3)mA^6nN54ZGn{M8H~SP;QvJ%CPxKV z4dX|cj`kyoK=l#Vn;gEJ`BC<~8Ut4(hdXV0`zhdw|AV&j{S)xS=lHXdE`2Xc*U2YJ zdcs$YN!1Qc!(nJ`cnb?+u(vzx+9#gl^pZKz$;mqiQNRe6a9yP zCwY!?eLR&T{k%ZJJa(Tf#itEFSZ+S^R?_&J%FnN@(K`s}i=jQ`Y{P_P%27I2w zZv&p}dHD||;zj1?4h}#5l*B__#We#1#7=Uk0-p4|pY2ZzhhGgm)eAq{Vby+p33%dX zgynn{hd;ph{@+N%t&Bev1K&>RRs&CTLO+)Q=^G@vwlRL-r}Ejw`T8#7hgqJgUcU}J z@jpZ#2;x%qb0+rra7yWc+hB{_g@_#g&xg|0jUQU*7dAzvQR= z&+?V>-FP@Y*yPp4N)fMJJ6q zmDeW(9^s#m;piJKy6#}S|6%#8^7sv=-*1!WnKNa&Lw}Uv@0CDX4ZMoWC;{#Pp7g(+ z^*_Kb{|G#lOUpiqIEV4RS(5(feu+?auK{=}uT{2kiF5eCk7W2drt=jJ-(qXmMuB&d z&mRRI_QB2%46;-BD+}NUfTwZ^y($?|e(%qKCpiqU9EzFG;OSBhFw`BnDtKY=H^H^PoT%(%FIA@KjAb=lhA$}?oT{lhXGeZx&x9q>fI-B#`oFh2C0 z47XAOZ3K9ya`(f~QF(>f->%{C8-OSJ15Zf=x&z|+2IIA7GMh`7|C-L2z1swj70^v`rlKlVe9vSfK9KI8HC;Fe@@I$|s0rztFXA6Y?E%3zu zL9W-To-Um0On(*dqJFUgD*D?L{wbNDD&OBQe(1*%kLoY31=W&Hi0z(|!zI9zUX9r5 z`$pgepX{fVGo1&SPRq*@q4;@G;h&NCdpZ2^^PKZ_Ht?hm!#tkwVGe&i@Nfz8t}l!5 z=s(h_zPRq>5aUe8KVRZe{l(>vj$w;`(*JL~CE?@FTyIh^HC< zrU=guCU7bmxZ_RF>gScfQ@SnhlIe=?neg)LT9yOr!!(XC!1z(dmoom3z>|F1AD0Lg zt9Bw9N}}KYBZ)`#5!Wil58L$cLB%y!Ho4K(!+;0Z)3>&U$qT(_eI+)aM%3XP6gp?F63kHU5HpUcvZ>fOnGf(@aOR z)!$Rjmvrp*HqQ9=*Ck=a=Z(Nqdo;XI3P#nhVc?z8{T1+3AG?_UM&@${DzeZwRvcB1 z7c+h+D+4OOeK+t#XV}&s`48Zo(tU};7u)LHdoJYsa=J?Y+kq$gLmXb^>kGg;(fC#?M{k++N3l_j4FC*aAG2*Rai=|2yzb{6ERz2i}lW)HrG-43y9Z zTR-I@;GO7vvH<=S;HiF%+x(@L2Fd5>OETREXX2Bs&c>kL+K{cN9E8uTMdG*`I)n~zxCVd#6=MoW4VLlfFPvsccBN4Q(8eQ$cD_xZs z`TwK9`^^acy$g6MFTaid(j^jaw_`QHJLT(Q;GO7S0lctRY-rIuiR&K5_gBk&y^Znz zDe#zIu+`t!fv5Zqd`AXU^H9gYP*8ad*xL7Y;3;22Ps#8;rvC`z{Wg1YN|OxV|Evty z%i&i8PkMNe$D=}wzY%y!x7?;De-+{3w{v;Dc`o&2&IYV(r>A4g%>+U?={nj>>4FyQ9!+Y_i>xjOB-k;*^X` zOh(PD)zuLwI??3=Mlz{LZ+dMa)svS1okAi`hSAq15}729sLAAo=}D}M>6t_xzJm_X zaKMZ3ILIav@9fGr1xO`u?ujGGWTY?6SuqI-=Y90`&>y{{ucv1tqL`j=MnF7c399RhFREJ}*260rbRB`0toVQ)Ze(O* z!$p*2I-z$(dOL93Qp3fSso2^|9QCqcgPz2xLJ1sm5zlPY*9A1eh7sbDwk8~QVVpCe ziIg?H;e#vcmN(UdYTNR9l_*Q`eTx^jhTHVEx<$=lVnx)LwR*Jc@=$0=bJL=Fy{d9< zWwp5u3!T<7VsaUM3WtlZr-Z3hznd)RDo@!dw zTCL+mnm}J~{EEI99qWVRCxW_jDhOEJ5nCJS>(1yMF)F;K)>=Ir4ig2v6_{uyn9ek{ zHX#44HF~fr8p#k%y&I=oiL)B;CR~FvdSWR$z@!Bc=PIW4-b4ooA_Qf-tG7C!b0!>4 z!?2!KVLz**ArM|?mR(^2@*EW*z4_6uRH8RAS6^9WoYDdfj$S^uH?cmvj!SCQDjg+N z8LTxImfdzy+AFOkFzG=xRH>?J4PnT`i*zU_&ND*IA*;29qfQ#CM1dYIL94dlY!ipGM~-$9=F@CYMHY0#)6^`;d@L(? zh*RN1dgcjpYK?y+hx7y&^pY*bX=oB7kV7J5rGROUatwiuT3{MLuT)gv_X}%RjCV~m4+yjHM_YZxJzPNf;68}qX6f>fLwPWljVR13otZT^7Z^SVwOg^I5CcRw4l~K3HH&q5NC{9n*tcN?pUuC2VF1>>r{0i&-JjD zW7ukxkEA^plqRdc@(9Pcal~C-O;Xj`$grhBtUCJ6UY>yRSPF-OwPX_TWfD#p?BK2k zDmZD{VY--ksoIJq7^DMsr%r4b3k?AU8TYesY?=Bu+QRV!v|sx0kc zezl#uz(_#!r6#nDmTUxNGig6GuRciTvZkRAO$m7~lyTl)}sU0 z+nMQ-r&gjtw>Py$FEyY2qwiLv)A7z;DwAq!pNHk>=*bmO+yy=I_~mfCC2Hy8b4+D}Sd&=EtyBsK~?r!j}aX~dSOdYsSYl=LdEQcB%AigqzC z1+?m>ri6VMt4CYCzAKVZy_Na$2;im_!CE<_)fvMH))+L>d(xfh`7Ic%%D|n9z^}xJ z1g?Q{ z;k8s$**U@C%ZaqD5{j0pvoDguY0YaAsf^vkOhwrz>A$RmhRrj)d-U+u^sRMr@a>}p zCKgi|0>ZeCjmexJTJTI@G5BE^8+Q6drzLJNHI+f?Ns6x4+$z1Wn=y&J7o=jstjVh7 z>?T9gEJylIsdV#{nf+dfI5&QS@=nEiFs@l(SjUoc%J#|?7-oaGH$>LN*9D=v7-5a1 z)4Jg-p=d0A7?Q)`)oj5Nopfk8b$^`7rerVPj~=G&E2C zhizzHOQI-aIOMoT98ccYOQVxEgJJmIht}zYyusocL5N0(n_8>z8iu%vGJ=SzJ=b#HwbKYlu6ee2@%g6B@T0Ba=4BG-h?@>J=kA&PQ1Wf)EqO06I)(`>df?z3m}45YmO3j|>typ~(2CqCBbD z%mds5^ZZNxym&6{{2Wdoo4IHJ#E6w13|Lw|%tz+QC47{}w(>G<=~2KTl5?QS*5qd_ z-$%|9o8gz}mvnTu*ap~5ik4e>U>=U<{%cOSQ!dziAqFR}0MPVFS`U+?SW0LpO^)N# zrn{{DAvp+fr0r=nwWnrT%2g{lQ65ThnzCuAgE4BM%ECVCAPl^Ic?)rxL#gh$B+oq<}7<=2%H9Bn=!8z(Z4-(tq_|OX? z9kg;~ExUDx*Rbc8taTZMSm1(@v2J)oPW>Onxm8WA-JhIxqBMeYQ7}L?c=4M26rqtS7^9vfN6OF4G$*Y{rD4MsU<;%R* z3i@a?c@F*&S1O}RHFaOZT=i9NKrCG~)^OPMvVe3B-3KvdIt?d8WYRopO;d{L_+$gu zN~4ctKAdaP;WqmDZO?>r!sbpTxm!F-i?x<=4L!A^wZavlBCT1D)$xn)19P!r+{5Z| zE4{Q#L0H^wnvn)VEM|+s&X|Xl3Tsn==_lKC2q;g@6u?v+b-zQ7c-m$_k9sQRN@yPB z!ZaUTiaaYh`EYYi!g;Q~=vhs=B)6LS(qdt>!(3cYx0-)qpA5qk=fd(>vnap{QZ1_= z#Ph6ndogK0+dd6$HA%c8Guo5P6SNw5R2AWf`U0qVt(o~^&@4u-w>=xm*v!wZv*3wJ zo1l)+qU8BW7IC19ZnXufdeZ&0&mPl8kwc0_u6Q_Jn zE?R)0J~T<-dk|_h_=^=C14sDw%2--KQ-CxjYj&V=Gos@Asw&GjZ#;->8k97DB!||R zzJeoadX&Cn!ly$R8%I|J>)AYkoLYqkH`G^^UGStg|tN|Q5sQ(dl^ zSFipNYY+1Zorh~p%52kprO$bqYqyv-r%}$*=iEjy$H=BaDg7b0wN~YYrL?zaJg4Va zw+gL7S0>&vU&^y-vISFoS}Lb%JGt{{T?)>P%h6g3XUQh7gPUx|!R`s=6}g&-IC|}t zg-y(WQLCs1Nsh?35RR;Mg3~^W0Eben1f$N4Xr*KLj?HPMxH0NMMQ+|br#Q+B zJbZ68UsmA>M|ja$?C8rMs-p3?DX#yu=&xywjWS_YKiBq2>^wD5p}r=f?zQnvtYL2p zG{mMZg}Hx>zBJVsG||Sel11Igd+AB^(x^5*Q8j()@b@W(Ls{hGEG%oMKy*MvtDNjh z;Zyf`D$^Ii2pJY5W=@_0ZL>)%y#nhdEX{%YTH0XyQ#nkmJ%nfu8;e&Nhdxulf|bclE~8ZzS>W>q*7G-iJX z*#?z6SYWZKG#a+q0-NQaUZ<&@%uQ=x=&isfMsgns>s$wa-Dh#|t=){Aj`3iBfiW^; z3k5NdMzQQ17gPrG5Qj)kt4wd~$wbxwW>OM%sb9SbY_QeY+gF)PC6f5Gf1_4upw{%o zyF1Q_cW5F&S0vq~Rbp`lh)I}9$v5k;6A`}Av^?l|hyHbhBJi(dcSftEnIo+dKPx*E z{39KUYL!@_j7Qo^3851mkxWFZjCJwmNnIVFrk;>Y6yFGKh{lqb(-t0|pepxOk~GwB zqC;$eq+prWl^}j1LmU7jl39~ZYuJpchrV*+ebtT>yb}bb;dV12bPgd9<0qYwtKzHk5*6&=7m9xsPQfn3 zr!#levpQE%LEcVN@J}=p|B8e4_(6CTU!A|GpgQMQrLW?v{9nuQ7coI~Zm@#toMDQ8 z5^j6^9l()Hig1f-&^d;vc*^DQYv_?3dqpLjz;?rll)Zq z8|POB2#fqu+&kFtp zFDNCIzS`ej>yYUWvi(x=?d4yDU{rThe08qp;N>!YhznMUL8Ytc+-OT*o&P!7BjfuG z#gH7R_zKc_A{0`kZ=4gFl=1r~iBH>Oo8$NM{<+qQs8g8h@#{dK=0X3zLDE zj~Qz@es)(O)WNQaDgIAS%+$ZRk|?A(l=eu zWK_1c>1^qxY%Me{W$9pNBg_?Cm04q(+SHviNYU6|P+F9+8YlQ=v=F?~wf;8BaTXN> zp^?=XWu@geZB~>LtWR1gm)km|m$J36Xe>;$SUU}B#L6KwLnz~0EW4?dUDhP4%=B~% z3uUw*j1{c11wrX;HOi`_hgUxvA1gsr)W*eZidp&9FDVF(q2kkp`of9&s|1gXQeY1( zg)x>{=|aF{E8o>ZXf+E5VelcPQn|^$w;*)3o+Q}L5Yi7P3YHc^N!FkMN6~ggQ9c`^~fpwH3}<-z#m~Ejj{vy0dk0nr&QB?TuT-Md~Ehuw9E3@Ng^l3k1y!dIS_)Q^>t_ViJy^-AvE^@* zd_yZ|*Ha3>{^nxAp>eTvp`-(}rms-ea=_XEADf)?HWteCO97!mxy-R3-55)!u}VR( zDV0?r(Zbf!-oeVzDl-O}RAcpcj7xgDeX|S!%Ip=WY8z^s=@oh;UFii4l5TIC-MVp`hJ#PoYtzRBSU3pj4jD?z`hu{{ z$Hq#q5RTX?EkF_Ktte(8+{#dvEGGDYtU?6~o1TIu%cexYLkGP zumE5oz#@Pp0CH(5AhQ6L1AGOr3Sc$BS^%Eb(}!>1xe;J1z_$RRaf0V=fV}{R0FD40 z2RI3E3gCNyGXOsT{0P9(MS!0Geg((@xCw9@;5UFf0QUgy13Uou1K>{pmLB6n_zRwY z13aU@U&8Yhz-xei0Nw(;19%U>l7)r9x~>5AFD7exmVjqTfYJcad4=)-wg4I0DoMXaLX%peaCefEEBOIm6Qhzzv`kfG0pZfc5}N03QIBeBs%VKKsG5 zJADp>XK#SM0R0I!0G^@rIUJr*0MYdKV0aDzhy{oP7z&UCkP0vyAPryyz-WMUfN=m5 z0VV-V2ABrG(oA@M0Wb$(KEOf%mX^SCDZq02`zv^^09Z+XuZHJZ`n(>V8vr%|Yz5d3 zz|szQ?gH2cupi(Mz!3nJj>7X8eLhal6Yx9cwPqh3E)?N z8vr)}egn7*a1Y=KnZ|S0Hp!S1K0sn z1gHd18K5daHGmobEY+fC9eCCSXb8{>086dl=?Tz={%!|PF92@rG^Dp%GHF(|t zxDD_dz+Hgf0qz4l1Yqe8dj18^zX6^Cya4zIfTg$WSqyXopaei^fU*GP0LlZ{0aOI2 z0>D#M_-qeQ9iS#a9e}z3^#B?Gu+$iyO#zzG-_7Cq2|x?_+Xjs0?-X00H7B@5I`_MUx0xCEUDoc1`q+D1&9I|3=j(t50C)Bh9^3J;Q%b9 z!E+QqI>0!9@c=Bb@Ou)#=KzxlHyxf|0L%uM53mqm2>?&a;PXm=RfJmu&kX>Z=j1X_?gHEcVCfM(AH(x0eP;OQ@cAXc8-RBJ?*YVQ1wICVCu{m#f}UmISq`8g zKxKfc0JQ+>0yF_=2EbBtc(wp&37`OQ184=nQfqj&2j~Fc3!nnv$qzpJ19S!G2G9c_ zFoF!cwA71NJa9@-`D?(v51KZSl7G}zugZd?z)7f-WNFDXt2cG#^s zp4HlMS(Wl_u53Bb|NXY_2Odc(_sXqKmHYRzU;MuP$j;FD^Co|NAaYOE-7A`FGupcE z2^n&3b&cTQztc4Df9*B<>5HK!w-zgvSvKH$WZi^c9eZyW)XKWyZr8_3pZW8;uijg; z)$b!O*RpO@@`hUpJNFYYIpfn7oK>9mnLFUw-X=4)o=xj<%JpR5xwDQuS^vY{!DSD3 zUF6qyX7km>$_9iD>se~nyoSD$Cb=y+zd7st=Ux3iJJWf}kc%TKxUZhwY1{6z<<>RN zSvI|9haoj~za7`3YT2_2_a5b1SI$}4yxh}?eO|r|+IHiw3H#TUTN#{u>~;&!FFYD~ z>k@4?OAjaPh!`DS@9~V`6ZSos z+@{CeO%Iw4y%93lK4j>)9BrLEjq-exzF+qYj%aB>*meR1W_D!Bi7ZgHLL3YBIB-(J~#SW4=^y3Z%Yj=Ork=aq+XDz}nWq;wg;ZH?O-GPJc53gug-g|4@7XLM^9hJlXj7!>4vyR1; zj3?=q=lflrotbdXsln8N_I8g)y{kEFw{@K5e4TQAlNqhX)jD&jVZGqbt!5@qF4_Id zPu@7L+V*ON)xlerYwnrb;?_fl?6WcU7oH>^Js&f~O53!`)z%ZwPdHhkd`Y{EViuOW z&$tKP{O+rn$L-qnTR6}0?;p1oJGbFckByGE(k<79HVFvWHZx?zg>RkieqOTk!pqIq zsE^p#4F9@z?VzE>$G&o{dE~{cwFB>-PT#vsdAU#e@Y)XAjKnLC-UnNKmoTE_qPkZf zcU*R`yz`>*Zk@mBccRv#W?8p9CN=hXwtZO6Qul9euPF7p>^#RBPg`EGy4vXA=$~vq znVK23%yaazO@Gu6R=2L)csfRy}%Dj}m@m@rr|Ci18O|f&G*!{<#=I1V+T-)G`qpe@B zKbm~k?tZH3*;jx3t%%9~wfKhC^}p@j?BeqSC$`jc3hTXUL-dJY?I%ZHr5#j{8jyJD zQOefcHR~L*KHqQYmN1X13o;YD-ws&*~cnY z^K5)>*yNJ85B-(+szh>)7H#@1?r}OIEA-_JulxR1JN?HkiZ6C@<%ZWi9sTb7{n_Eu z?VFvu9zA4yv7a8DY83Ce_-p%%OXB}pxpsZePMcTm9W*cT!RIAa--I^NrABpdoVjrA zKYgu#4~@x4oHR1+=-+V*N1bUOyf>orz8CA#PVB1vNH^-$$Yo{z9x?9KiCYIfr>AGG zDcwWa_T`L+*`a+FJt`BVnOo9w@!`10H@Zs)O8#{d%IQB0)#sq+ykZZtBQv`7UDM;yyzshTUGz_PT$TEpPw#KbcvoE6 zch!dB(LF|AsB0bZ!&R$Q4gV3AUE2}nQ8xA9a5w&-r@bl(9I=(?m43MxxiYUjSpR~y~{~8YR+F3K5Zw=S$^@`QrmuB_U4Ay zwxOMzM-B}4_x^t6hE(spZ)(&FxD)oz(FDJ@PRDD<4H@6-+08k(rtIrGII+R9Hz_%T zr&-p%yW&yPNXc z$hqJ^)N2R*-oy6~9&Fgs_O^P*0cyI*ywHf>j@1flqWuqdAae|h-)b0=i(y^=TlZetmsNxNX}t{SSI(cHFzJb>_y`Iq@TI zI%F-_`csLA+1hL8&upr-@a^&jUtK)a>HYAoqo<_|+cRw3-2K~vGA^&O*<7j9`;2qz zmZ}5BChlz)*>Zi>Cv7vAU+?qD+ey1(MK@x znY;0Fdi;|uy_&W5zw|?k-Fwzuc7C_Cc(3zk&UyZp=(Aw?#mxI?}TEM5? zQyPSZpWeOV!e`2-+EH=+8wT8|_dvUG<@=)vx1Thvv~lhs*JfvrZ;H=p-D!Jw_4O}< zL;9UM+*WICH`B3=#jtJVT5C#I%Jh1Z+Wgm~ssooa&0gO3(x)}YT9p4RXMBsRjc5M8 zw_)&`2`d_oXyTZFa3Jm&hNiW)7*79 zcBEH@iDw!_jjp}uvg5jllJC}5J-B?-7fZW1%fg6J+j;N0v9_zu=Umt^ zbc%B0_p5H6Kl7kcRNFFL-w)5JJ94D9O@pJ~bZ{@x@7KSE9RFpN&FyL9n_k=cX{|4V z#wPxv^}6!)ix#i8UG3noqy1gy`D4DXVC@su`O@h&{=*VCWd6Ldl~=&XnXjHd8a(%K z?TC_!3Yqag&hu%#|LwPPhj)p(BJ}^v=fvt;wK75$Y*<{Te%jFed)BFf&!1WO{=q)` zmzi5DH7xaO$&7igtiw*VS+PUYIVhlm!{!$^E|yb-X)Nb-o4q@JpnYmaj8BURuDAbO zc*yl(sd zw%G(PNpCylr*_KSQM(_UJ^jk%cI@TtX_a3_`y6QTN@ufY&gS20E^}?&veeo?KiTiO zc71Y1|2eCLJ zkTcFXr;pB8?OIc%y^U-7mXvyZ_s`tf`bfi@J&w!{>fms9x2E%sNijb0lU;9zd>-~) z)b7`T@mj}C$0ynqkBm;P@y+(L6H1)x(%B(IC}M{49B$Utk6DY)tLdlk$){r8XcPR`^$gc zUUu)*=*m*fmU8c0ZufZ;?bGOC`JC~;-f(lyv26EC_$!b4b(gu`_$A79;k|KRW(2J| zGSa2g+6$F`SsXt7JDU>K&kR_*t(vZ3=f4_Mc%sf(-Lcs1(+ysEzewM)vi81#_qyC( zwCMBYC97Qye(>3Y`wi^o)v0@Q!lea!Uo_rvbpn*@?%HXuyB_GWCUsu_bLyz^+bkPa zjojF)#fs=9At!qsygN5d=@1>#=<6YSod(_;dhPR}4Xc!_Heh|ZN^2jNNK3gJyrhk7 z_}3wueR~EJd->12ah2D;Z(iR1<%TNl=lv0#X1#I$$Pw@VK3DvwuYaFVb$9=xgHAgx z5AzDRHlTv{jbT6k-En4Ch2(VyyOirRY}$fpVc&&#E^;rnE%nI!GpoPox@X3YMPD9S z6=B`_t5vbdHC)duemf^IaC_L*3R9|$@m^HrO;sA18+1+&0yvzve;Tig%`u9%x@bvFVQA zUOwvf{f*3{tuBo}<34y&*8Qa0J(7cziD8Fo-S7-`yxml_{QRc0n#p@c?`u_RZNFiE z`c_(8Qt-1#40?a~(hq*M&kV>6UfV#O`25_%oz--K&(%3@?{1yG=k!|fYtX)kldDQr zE1xx^?56#FEw9b#y7=6ee=Ka5b9-gzD!ZsiZ_AJ){avkl{MK>Dv7Z<0{o`({bxkX7 zcoG`%dG^$)Bj$d4|N6eHUhjMK_v_o^;oy4xCpWLAd*AZpi-mW~uH07Jqwj>$ZDtQW znfgg|^^(IBhq+YuA~+`jQ(m!D^bedie#d2G;>t(w{!9@mLE*WmJu z12cAX9MXAZlNstY+YYTfq0U+5^L6a&@_qhzw(PfnuYW(_vqPxev%${Y18Uv-*3;#| zovpDC`gD0PFQ(GS=+jO$mD#a}eSf#Sw(!A>Ijg(-`gB@wrg(Oc`^pnlqBXj$XEr9c zUv=qi*#SSeU40o|d)lT0{TGk?(>G+!g67ugZcC;VPYild=DADrebsbzmUph|@oZd= zz_s^%lMmbZ40{%|ZO}KBO9b2(J{{q?{$#|qNxyD9*7JAwX1Z<@2HEeAQZ}}(T5QbO zvHyHubN9oGwXRjW^mgqJXWRxY*zYr|(N7Pq)EzkD)uZeC7B2VEoOY_FYyA0(S$kZ% zYm?fL(-iRIO3GXOo$8zd6u<({~A%zezqh_orE1x<9R6<^K5ia<4`%O8n#1 zr_YxiblDZx)x&+y!UuD1+q@k2#Z=2#UzE3dnf-f%iK9l{d(>og(8He^!kEvy!R;GE zK5riU{MgD9zpvc7c=o7~)&UDUrB-@8d8zGko5lxwq>MW;rEI{0zn(2yd)nsD?OW29 zWV?Shvgs2cP4L?x)O4|KxXHEOlrcyB!rp||x>suK*xFadjq!Wc&gDVI!_remuex6= z{oTf5r|)ms{M6FUeSgSzp>r$Ejjy$M{hX`4Y;U)kb5;>o%)`#=@bG^=nLTIquT>I` zu8OS|IH&c>6J0}paC>*at8V(*OK+oMs`a<&J+pbt`!WH38E#AFFIdog-`CUb2Yafc zMvScAK6B|nYxSzmRS)#P;d;sDtYYmKiE)vcowj}P&3)grSL1qIul4flov(tnweNrS zOMn0LO6SM;r>8F7m-X=c8MivMFTL&3>UGGS7p_Z|U9J5@bvQVbkEf;2;Bc7Vks{&m z1AXQ3S74D&j{ZJOg3ICegv#R|`OD+0{w|NN6CscHv6siE?vux_g~@X{Id^uF$4{&( zkGD31-)AP@j!>udWa`<+Tb}=%>GF8b?(+C0X6o(bRC)TDpUC4&H?)wgAC;N%#>|%I z6VX{7zsFY||25PNER5z#UNz+L-OR`{Vx&C(OXcM8oe#<5pH!E}SGy~Zw>Q&|6df#N z%k>p32+8ST88hu(dcQpV?H=;@d$0f_r*B`I=||_?<@ub4^#eIMtza=r4sT~hKa*k6 zOOD>Zu{@rwUCHS~HCSwt!=H!pI^@zGmAkJx@z2cI6Mr*$dj;s_+VQuZ z^890nrZibX7p`;Yk57)dMeL9pqD(}x1T(|rx|%%&EV^` zl;`sZ>P=4HR+y=uS)JtRSDCRhZ_U`5gMRXS_Ib(sm-%Mw=Z#=_KF!V8lLcn{Lc|Pt zK7nTR`7kVS%hlU6GyURyIeGpe8hN}hT^=7|#$Kgn$%D>hnZTd3t4lJbs87{*pUc{RrHVY`v8M zJ0Pbg&CSq%YbG9BXT}Z$`OBBi(M&&m3-NP3p`6gPXE9NQ zQc01%%0~R`Hi+l3M{*+K8?pssNW89Uw6hTE!qy|@Sj2Y`zlC+aDoFp7Es8@*Cj4pe zn{|aMLbN@6fCSx8Oks{J&M7B!9)NtH8pV_jWDLLiTjT@HDyF>Vx?C zY(XB9qxdhZfpjNv2M#sNs2Pijr9pD+6&A71~T zEkpWKpCI0o_*k_-yd7;k=!Wcs+0-u4#}N@i^gAoSJ_u-+fC|_ywuEna75Noab zx+yJyzJ{=g7JoT?3D|hWD_;wUC(xg5-wm#axd#Gg8h zcyOa)y6M66yo!)s9qY$~@N8cZ<8$F9(hn#6h8~D-%rg=7Sod&!dZ7yJ$W-2=_4y4pPwk-ov`VSm3L(W#PfP~ zgp3&8oo$kV#LF8n0rB_Q1{6p<-|^ogelFWk0*TpWmabPv{O#|Mk29i$TM)l7{&v1d z&-pik?e+}6nDT}2RZRb^M0|t->3O@4ERXmv4kCZ}Q%v)zz2316LXdih|H6JFP&~$e zX&K}LY9^-R*4QqOx*;B#PfS&>AiX!+I0LDv_%G~L*^PK>PsFb$yv`l*y-07l-5W&u z@a`tc(~{^9W+44;(*FR$yEj33sz~~msuc>Vn0h4@l~OywT{9f6g1zzxio zx7VRq#AjAU`nHts@otEZd4Tkky|587V*TqZ^)Gv(pG)@k*ej&3On5(VG%VlX*N8ts z_`vTFU!?`+>qGd@Kmizi%EMMnv!~>a_Vqk+N!?*8;cqQSFk)7X6cD^0qogO0p)ocS5 zB(CRd{~P0Tf#l)&enoc7?g+|RiTFfAw`KGhMmpkTHC7 z(vuLvpF4&4XO%Nev7@$qbPASCEkV(NMZ@ztG7=^sEtGyeYM2SE+QR09m1m@nIm z2x-3fFYJ8<1IzFe$e%VL{4k0WR+Ay&dcyXuG5S?xH@H4jaYFp#OW0mRiBGd%5kG)! zQiQaH@HfC`W^BQCjQBP zApQ;MLlwf`^g%w?waAC-;r&3QKlL8@C^;X(pLvdWUJs@BB7I--%e)^g2ez!dQ>os- zy^3iwG&I9Y;{oLh#7q5JAJUTqiJqjUA^j2Rzpli8eKO*o*kidqBYZbAem2+_>FwaC z0!!R(bO}ZLX0ij0;q(4l48Ja^(9nAQ(31r7Y$c}M8wWbvE zdA%3wnYY(jh~HSf)h9Xqi2t21#Frue#qGdC%6HTa!%vO|#_b>knh<`(yp(_*p zor+k`yUA~Id-dWv(*Ht!gzKBvH;C_18|C5n3dG-={B?cezhfB2pXoI2upxX!vga$w z|AIRZ(@&F;|Dn>zzbD~~lYNl-!70>U0i}?h>tQvpGot^hhV{(by=xZom-?xps}b)> zdd}PBD<$G5P@Km5qnjE3^*I=7vEPwCaQfrD5WkrEJGcL5t6=?0{nv@vNFPu2!{eET zBM|>m(jQl-5x>I@>w(*O-5&I(joC(FNDkt^V5c`C{Vf-y=l$C87UKQdBA)lVtdoe3 z{{->8T=(4&zxz7sTM+SI4u*);!xl-LpG@t$+Y$MA5`9&WpN%VjXPfyU9VPr77_c)w z!$Xmt_tP0)A%Cf#N(M4UFZF}f&mlh42l?>&@vVyd=aXM{rhL1-NBS(9Z*e4i&M#P> zlPEsn_F-iuq_<@U3n20F$PS8c*OOfZH4u}_T%@Pv!6ad`qAX4xV?&j3Sr|!zB$~9_}2|V`n@l(T)f@KQCwHc z8RfAf`UYi?zRZ54uS@ueDTv=e@^d|T4T{I)%q0Ec@}!xutJ7*Cy(^7#Gl>6mAH;{T z0~wGwpDTk{y5P)k==XO$5j3aB!4fGzcJBYEs6ZS$zSmP*s>wona4Cg#_deA z>qx(x>?gOY#SS6fTGGERgJQFK$fkLo=aldDCx|~p<7g$}A5_Qotxj4d|IBKur-(Y)nCHizQ2rS?O3+zjQB#xvhHKzu)v zlec5|7~~_3Lsq>&e9P|0pSR=vFA=|<>@&A-FS{VV3_F+vNg@6VHVi73mA4(?LH)#3 zmBvBG!;wGtgL|kQrSZ?VmyypXnm^?IT~`|Mk?b%Qq(t#wIRB$V{K9I;zb)bSXCeM9 zjUR&vKOLS-PH8-|#7x}MB?0NzN#@P6uOWUW^+#T=ZCeokE6qbXQ@(>YAig-oIh?)` z#Tx@Ep!^V?iK+Hvq?g7mpAAR+ODZq8Q8C#%V!L}#e9QGS3)b~myq81cR&F<%pG7{> z`K|>W5FaUtPg?sR-a}#!tDQ#tJMu>XBu~RqD9p!D6>eUUx_on!85XC3FyxwHrqrj4H+^1w<%vG;rpA3 zTMqO=dTCrV6V_pw-U^cO=G73Sze;fwmvb=r<*cz-Z&2-GdipEUS0{S~#SznkNr-Ri zi1b|Fij$uAVTWWPEhoElf$H-Nm5bZ?Wi-Fhfb4u(@hv#(4FfJ#4+EYdA6{<{$o?-P zKkh{Ihj$@;RS%Sh`>($rA--!@#B)C7z<@CRhsgi7BR>7@u^pxBAZN*cJ!gk&A#wR% zL?NH$#D~YFx7HxOCB>z##J>}~&hnMcyLS2n@mGID{`@@keW(XE9=W~%@xzIa&pM=E zBZ+%|pnma&;sltk5!2gDq+ihp>jBKWnCzfJSiGGhiMwLRk57~M@dTR3@RP)2U-d@* zhiHD1*R$d=;wMr4bN^B+5%E$#`;O)rlo==|x6gj{klvcsH+enpn}_&SG=Aau)5J$0 zJ`gU7DPT0xAE}A_xqXx3>4E_cbW(AAiVui#P6VW5FQT~hYDo$3)$g!NDz*S zN%0fnr&76m2p_c;@!=AE-fus--zbrxZZ~4ApV|2ulmFO92Q??jX^$6 z#NSqf^isb$rUK&aXx_Ur(fzgUgM<)^AlkmsQ#C3-$-+r|I$o2=Yv~>vbQBwR6fM{VH zC?u0d>c@BVNBl8ctRHa4V!8uUDvUma)~|gDKcfV;S3erZar^8E``;LSXIh8i^}Koy z^4a2v{K5T+X=hoCH&)X=5FRHt?}YRn?_fQ&BKj;^7t100+=%e|W+HtH+E<_;{1BRd zYfSSAJqVxeg7lFzpXo;Usox-eq-0+4XQ)?JuC1h3yuB`#M*O9HC@1gNW1|r-jT5Gl z-db5>JwW#n(+GHx@t4K}ey^NA`J(_%MHzGo9$q zI3QjcKTL-TXYF-~;s>q|6QSS?A4&5$Jf69-4Dr%^0(Zr@$X0Mj$9y3?5K~4Z(o5qL zKQF}pOye3yqHhT6{>-jkq4ff24l#vLy-DMfmm83eiu8xu=ZhB*A3*-D0r4qIc5kO- zzr+Iw;8}U^P(8q(Vj2q_mf^3HK5+gcssCnC|E){(A!g!`lrqSt1+`;+qObfL;>(j? zs80AjhY|lJ%};W9z5oNrm=cqkpHrycon*{n97siescE zaDU(x$vRyc>B)o6$bkFbfECE!gZwqOGs~(WK8f~|aDOy!8se|jM?NDdUn>|8F*yfE zBfcr&n^XMLQWF0phaw+oTwz7y(6wauc>Vi#MfyO={AcKK#P3jIzO5sN7S8MvB{&ZS~^hb;13txgEW&GRId>W^}1Ya|}unp<8 z#Q#(%+@NN-PZ1($!8 znK(4%@K;~awR{=yz?M{ch=(LN&SI>O{*NS{P{?n8Xss9ladLOx+Ame8O2(QmD=-au`{v>7fm zWc3gkjQDzl?+t=6yws03{}%Bhi4SjI7B(>YClm+r_EjH7{ABVwpx$C~COawh*Y95< zeHQrzZa3+>LcR@Z*Ww9R83IEU? z@v9{Mx)>0!@*a`2Z{6vLm+muI)2`qnh> z#QkX!*~1L7hum&QRz!N~KI-Zn5Fb$*`NQy5Ok2&^rA@Sd@(Rr>ay$0s59A~D@7+OQ zR<8OqUOPqnGil${_hiSooDE3-cT>AmC;G)IdX=l1QgHPY*7KC=<= zX%>%o8_D`nTTmn>=ia@jKVXi;G;S{9lgRJ)Cj4!%_l*83jeng8??L-Tv#B5PcBw)0 zY0~(?+Dx3V1PnOiFI`9IMEa0U`rt|V+JJ*#^isd3i9mcTT}rr^=#PTJGkWR1yGWYf zXee11ST_Udt4s84EZMO!G*9J5{0Cn_`r(p!wlh#sEZ+;4sh?Wl3sJRj{w-TFU%H?h z(s!o)$-F*Yq2P?qsvF3M<0pQOcxjwap+Dk_(fIuk$r81PJDw6%#MD_=|znFrZk=~c$Nk_sTg$iW(KHZP(X9y?6^g~VLzmxW5eM0!X@xMO^-r1;#A=u0Le zpA4Fh;`$8BQ(}E?Aib(c^gBq;rT+bEGx5gBOyrY8>vz1o+DV9?O@4vf&n^^)OZN$E zr+Tm?JE2^FAPJ(RDBcTrSqR_?jgQO7i=${@0mAP<51_+sRR& z7%X4uI)!#B;s;PYKy`^}*I>lsCDw+0WeNz48K1T^uCGM&;Y!3y{q^Eoh_6iJT<$l& zCHs~tpq%i!m|l-V`kmw-!wCN@8}U2HFLS+JPWCyP>@(LN1yn4PQ%UnwKqjVzH2+_n z*15RfJbf1F+xnn9+#V*5MZDBsU!``J`sE6=zt>s9zhWx#agxmQw1oi_lk)=2!*Dr6 z-yvS0bp#kjiK*jW#7C0-=YFa@R0!jm+{clD13-E#AeX0Jr-+WB* zZ9K&TK}28s8QRaCv=0`#t(da5A)lY!vEF#TwyhC=>;~#5Zx=@zHDO45bsX&MVx*o$uC_`0Wn2B(s-cGcEmf;dVSMsx5z22x z{c8Zldk*9`%M<;d;D{NY&NN@jOlNk zK}L+v*n=n!&$s(Oh?kzP-%}FvmF}BrMgC|4jpKNK3~7ktFD1p#jVa#?BanY{+Sf6k z@ZW=BVe;IU?7v!0^0c6J{6SQ26_z5s)GyDaxb6kTbv=mxD|l}itm9{n#`@uU?z;r} zI7|F{=GTaq`tf&QkeQstC|>1u;}OLrC9SuKuaM6vn!n=qVKD@djQ#8ef; zV0dXfU`O*UYss%UlAMQVy`~S%&+~rK2+r3tKD~*)EYa_3gZ!-}^8=rKf%s6;XD;Vy z=#Y$$G`@x3^AX3(XDJ@z`t}R0k6(|#`sD5Ic@X)WCi~CjJgGyx)Q+8@{bs(skq@^& zpA!Ga#2?JBm?~4e(UIZ}ZVz46Xa~O8jQuW!=923h|I=|G~Ok7c$;>@Wu4ys7`_W2X} z4DO2c!1@0`@uUsS1AzL8DY*pdj|2H5Kf*hWMLyE_Ar%yo$tjH!Vjys0^EPm^q{xBu z8MPVdzj8%+xZNH`dU#Euhs-Q6{?d8xre^$pLz=glMC0pvB!5S!aK=Y^zBPO&;#ZUZ z;^UNC;Gh|OO&VWJCO&6QBfdMGE8*p8JR9-0O|e{H_Qezm3e5N{rS&FmC)-e5>PzE# z-Y%2&BmD`Q|Ka+-WF6x7&^{=)e5OfQA_J2YOaM0}di_^vwHC9YR5K>b+#-=}dL_bAAls8ed4`nG!FNel+F4A|PaVuC@G4QB{{{i|>ORHiTpw0IgR*k< zrg)pTO9QAVhL5FlaE`?1i(knP()rERgjeoCd^*`Bj=$`R_9{!VkA?jJ8{>b8`VrTk z8D=t?9>8sE_J>E~(IU#<ZFVgtu?p)+Q zi`FB!KBtf#4ySXnTu(fSztq0ndWd{}rv6)x0dNqk-a4MadgJZ8iS|pRQyk0n-}VgBOV3^IzJmBz^0T~sca2B9G!C)wM*JX} zcjfsW8jkqP8Yn-vlYa9Ne~jvr^Y76U@sUqW(( zFB}oyP|{wvDZaI?kNkOmIrAsdOV3%49*6k(G+)H)KZ)dYB{_LLN5&%kA==Nw_2C}b znb3xq?=F%v@Db8W;|C!S@oS%BJwtKCH1iqaT`6vFN%+W|WSf7BG>*^m#q4qw#UjiEoj9CiS~2#D8r$#P2NH4vo@zrC*OUEx;X@1^{&h@}_sF>_YKVv2SdT=A;6G?W4_tQyE zh?m~?=m!RY$uG4Ji5;uuRkR_(~ji1copgY@j$&QMfj655Z{;P-##IHu_K7L zq4nYxgr9C^-6s&{bC{kaO3qmN)>5H{6?MEr~5ij-2PtPNM1KCO5F1AAv?@<-`z;H=Stsp>T@yw>B z*pKGnLn!8j>;7jY@p&3_1Xe$jD2@g9B&H#>4v=P(&*_98L;05SNBX8@Pk6h$eUJDfG>+ioqnlocm&O&|?uhRs*@srM1meG= z{Z3#m#8jK&ke!xTUOpZyABFVNIArM}#D_FTdTxh%*F^j&ik}A)|4*RcOn; zrRzJMWM`_9z2bf(6xx~b@ufH+j`%kN{b6>)Nz%Thz<@CNM4G4KergJc&DwoF%?mjY z9|&(n`gydT%gd#v{iXLL`}Uth+{pN(OZwMAY8UA}pSSB`|B}x052ZMKm*hUx-^Zdn z(l}~e1?01l{1LY&by}l5jV1EDs)u}}aa7xJh?mAc`^f)Zq56-f`YB2C7}7ZE+xy5T zmg08aUV~^nCA}~7IrSImeWAh6kdO5K&(XaQFO8#i(K)`HF{p=7jbhq83+bQGJTvdV zr9#m@II=$5|fRYIBE#U!|Y7v66C}E@@LfU()&EOHp6yt zkjxuw27y_=(tAg>X5z7Wt&m=Nk7(t}h!3H8IcJi8BE@Oa`#*PYMSAId9U+GhFP)#? z3IQRLb1}uk-2NP1i})00tbbR^cgtqPOXHmVV-YWni?%F9y!77DXLO%K1o~;*a_CrSbt0;JdgJTwK^&;Azq!V(O8f>!?lUJn1pyAXH_cTf`W~axrh`Z z5xl5y3DZQV<=&QjgDfOSAL7#mGSj6cYSl6EkqO$Ns$N|J)k3l^DLgKbvSztxVq+7+ zjpfrLa}gom_+fDYtS}L=0ja=HEU7{f9<51I>yk7vx@7-wm3yo4hv5P0Z260_>?$pQcSoyHYScqH(2Eorx`9*HESe= zr#diE9j6(hRVPCkv=M5ZCdy46sMf`(QdMqh_9t=5i;|JJg(V~;>l9Afq@;u-vDW>& z2dWiry6B{YVd}_~_;98RYE~;MsPRA-vGxk}mLi|G6qHv?thRvpczjtbM6RO0zbLcM{c;^{}`+OYaoUY?C@nldL6i zgM!TqY($-Rr5X{Mim1q43&yl4wpjt3ox&3m)6`-wF<3WM0CW;Vb3pG1REQm;3-yfL zc^16UU81x)w5lJ0nI@3gP}XaE#}A8%k5Kp0CWCDO2Liq$e26+cdWbp_l#+Rr;ltI5 z+N9(J<_~mf>QpB~JG!`ICpGA@COKIPz9&2(E>WY435#K`u&j(c2zxzH=dRHu#KnaB z8+sjc7HT!3MLjV2&WPTm-?>xoq3^*~g(qp_wDCGsfN>@UnWZm8Xbbp)TXG_l3;HJ* zR;H$4EzlE^mT<;WIwJ)&M`GG>%~6?lW3yByJ=83fiGrJ>Y89acFPo5Ntas*U70#N7 z2sPL+sHDUKz0oR38>@wiEExA;TFnq(Z+Ih6=Mona?;i*16{HSyX8-4IWoPn)V#863 zN!rVlM7H)!NaUNrlq7#HAPaO0G!NLJdBvJ=0?jB0nQQVeO`@uoskxD5sPF_kq6RI7 za4G^^PplRqLzxzEb_aFW#)@HYy=0 z4Z|}hw0qE}$%lm}L}=YoHL)qw-0-&XS04Oz6a~I?Ben_g5it~a#`Nj}mP0O6v5(2U z1hyjYmzW&VtfX>Ezc&>&P^TTrEL<)&ymgZj!V+|@K{0XMWOR2EQ63EC4IO~RR^s<6 z_~7B2k_4tRAs+lZ_uEDsNV6b6_izZt;uAa~h~7UoQ0FGT>fbe1p#pH?Nu^S`i9LYV zZsFebQTWHEs>FWA8s0@0>0(kG1A?S8Ae>c$2b;d5AdJ2M3Kw1ib+{&3$10t2t-?AfTgW4Q!=Wxia;K0(FNr@(*%S2PxotCZ}F1 zXD7A(ZBZ_DOk84YVT1#F#2Z4TitQQ(O#+~DS7R|z_CQxPmqHD4pb+}%bBRwFCTTKJ z`<;{1U_ckAhL|aQh=ItU6bdID=$1M$Atqj|(A;l{s-~}=JXJ@fQn-uklEJxZ)!M{_ z@MuvgBUSJS^6#cnck>E?k%qI5g?gQW^ZeSNMMkeexWUGrQ7M`v7|w+cO^HcjF^K_3 z_MdB%zOO(}i4Y=V6B3egedQUSkQ65lWw9n%~oz>(sr%V34fUs-v|Um}20jO6DsMbvN+a$vk?Mq2S>Ug~{%y-SUpbB%n4!8LKlm zP3RM@vD)Nh|9~#MmF3y1RN=8I=#KC|(+E>p$dx)fM`>XM1|x7&pXVB{iQ|5aR0%WT z?xywswsD_3O7lau#cM5hQeJcgA5UmbrfvW0)Y)P*68}3)KW!~6T?ifQM8vS=rHrL zsb=Mh8cc!@(~8JD4lz}4F$`m7ELR46-X$M7!c%2J8mxKAo00%9Jk@-}CDU@oQ6N|m zFgmFxDTL9& zJPZ9T^)FHr<&I{|c!JT?t}9xBoY?S5;DTclVGswCu_hC-rf;}7aWhK#LgO_xsUudN zfvZtiWa1(6@DS0@ZS#0Vcs1|uw-WENTSxja)9b6$-H2$`dy_S6UOkeeHeoOteJAk#1^eTd4VZQ#kqwz94LL0mtWr#?{rxT4Cj{ZLt5<1~rlI4e-+!H1Ih57A&O zm#B$J^6$dNX)u475+5@(1*SQ~^)iK8R*zLc=*n#*&Ug9;dcsT#`@%^b2s5DJIt9!- z1^TKXe)3S8suv3n*f%PeQQ|{haV99RlUkh5;nTs4j;&yDqIj6_1PlqB@8~mEahwZV z9FfU2#DbWR4=@`ra||ZJUCu=Cj?OHT z7qcz~mH1y13_I6{`!FLL{y$d4f1M%Z;~5Ar|F^W51p82T--@~WxZ&jSi|i8%r>si8EPw}$y|U@4vbrlw|_ zWb|WbzK$mL{UCq&X#~@b1#Ey&e(njTgVYgeu>1&9+-&y*%d)V-i?SO{xf|_)>4BBz=_^LmA2Qf6FMYGR>2Jkw=cakL5)|yAw?{*|f@Chec}) z7NW3i>ZXlLgq^8u11Hb&=~8=AAIubYfQ6fTBc z-yi@u1!lEj?Y59Yi3(UmiJ(68Do-pVQZa%Ll`8kHeJB0NA~kgpz2lK<0|PaAAWuDp zzaAa$>ZGP%Aa53?=JO-cqRkB|gd`?=$YmsPWyLgT2`_6N=Q<>BP<2U8g>gRlNGjo# zZ@qmeeZlHanu|#t8qSW0-HC?Qq}jREu;7PBu%j5C(lW|Q>_j*)k?llO-&{LQdzhqJ zO}~^Wg@nK;Z}7s->R?!mffHx!e1*T%y1NIk?W}s^&K6u)OmBFLt;=v>;oE%P*L$~* zlrdSyqH=?}5~Go#zHeF$+*1^lo8f);RIy3&t4-b-hGG=RaZ9N9HE0o=Dl}TT!{t4n!YuCZzg(W}^hv^4+69gO=&TG{zeRi+^u zgC9UAS`-rsHW4gm9-g%bOpPqve@;YFDR#!g6Nj?hlB2jWkzi$Mxwe?n^4eusg=bKb zCO$b5PL&T*QN&tx9d42{AqT9d3! zgd0WJ-4tMJXxh{qxgr;7Zpw&MrWa0X(RLZCC^w-<5D}~=G3cTh+JdYFiW@^^G(rKQ z>!RuMmsW7&Mk-qr3+OTo2AUtc#{zq}dLY&GP6s2K_|atnJ=F0`{fC7s6l!%`7#twe z!I4LCqD4kO6$)m@*`*M=lw@2<71b$s-NWnzTr!l5%OJ*YnauAQyaK0Z#+9pqynUlx zouJiB2v7vW3+%oPzC>lTfMq62lNCE-HrTp_;KVnY8Xti%Vd$zZq-Zde19N4`X>oA7 z%n*|@g5DKDGV}cM7tAFhHkOyrMLfBwj)=ttv{ZpU8JfzN8gflcfa^bynAM1^=;*}* zb#R{A?0FpXt|o{blok(c!~H65>K-tB2WdW>8)GDL{Ak=@o3Wvu_~l9Z`A~M2oGY*C zGNnodN9cl#-eq;{8Jhqa5(h>jAqje!LXF+gSe6D_@xIUrgO^> zFvQbcYPl`DNDX^gyj<18@Dd2T=170zg1GW+>^T(*H~_^wDZ4#{sks{ns!3zJVQ4!J zXgGcPD4h*ln+Mx=E30aCZ5*Z1{ql~;+er*G1j-WB2G`Z`U)qtUY(&Z9H-P^=B zMZ_i~;#n|in*1{MgxX|zYnduV#KNTy$y%e9&F^&uoUMurONdp&{XF6!L9=}rmlp+Qr0yVu9-*Z(dlTqL(OGmFCS(9AbVX(Qo!$4)b`sNeW2qs4Ny zbA-8XfB{>lH~t!K!~(0rs@qfCP{(GHJi5WwI&b&@^_*%vYH_uJUl$~v$`NNw zoV=m4!5tB>5kb|}_zFd5byv2lG%+DICOl2$Y&;vTaD}_b@D@Yy<{JNeUL-sI;Sv}a z8LwoE*Oe%Y3t~K;nr?b9PMX4UK_tA(KN?N!o68i^*3m;rf$P9vl~ismn2V}?;7R=HwrnaRD7eP zw6DQ_DXmUFSt$-G)Us2H;#Y;AH478%v3NI?!XqFy1>VG`8F;u;ON2xmI+RNk0Y+iT0y=9S$ zzUzNHh9(jkdvtdm+wx0SKZ?lzksQogxqRz1Pd(SycJ40tp^Oa@n;5Ws*&2&f*f&|8 zM(&&43l)PmEhmEi)uYdqjs4FT|6uW%E!orJAKZxsU&3;< zQSLGw38WAMEJNojqUp#x8-*J?yU`T~bpdR`kp+o`FT0qFct@)kb2-ECkj+j&ZEKQ? z*o~n4PWpqn3S!7ElY^rMd`M#^qJ>!xxp4v$(kO`J6E7dD--pNggFjUH28F}GAwmcL zX(JPZoFmm;MXzSMUyogl$F|6;RLP0S;c#FfGLf0yL_99HU-7L1AL4UH;5jNf$$#wI6% z#oVSSkqQP7nwY3)xbx10JShR^h)s}*niLp>8s!7^!!8gu!i2M{$zqK$tTA-MAfkh? zE*>skVl5#ll?QGBbK$$Z#L6^cYG9#>k4lLJ9!6iXK@>JN+T1y8u5(?8n5&JSy ztBqhSAoj`vI2=WHO=?GaC!euR0Rq5WouJ_C^*w;~U*k#<$BxFuGJl1=vv_G3zeLC! z-7po>u|*N=ONCvxgGkzo-PNy-j)7=VA1AVVnDl=X+S*H)>N}ws;f6uunp^}mjP*m9 z;F9p+yYkp~`3hH1rX(DNj~}$LljQpdta#}@0xP+jon`h17kvM!n-8{|S|u>jEQhHdr%EM2JJVk0?q}E+6{0sWJC=|C+0A*hR|Xt&-gM{Y&fx zlN&BHfFF8*pXA7;q;R(uMv?L-vY{s%u9%P~`PVfhzna3G;^%)!JL<2jVCy^|>qI__ z4vcSyV7%d{s@UBV;uU}5VGJ|Y+T{K|IV;IV)y&81M=BppY=h2yTxs2*ufWO>@8KU! zUWI~JW_8}pbXeOj{0_@;HCg!kZBFUZWp~T&sRId z8-ker$zIX{fiCRv9tOWekpHD(>~0TORhPSggl(k94FO=~jCca^$LK<^qXITOn$I1| zsL%bQc3ZafRql8T?*f7g%3CKzwbr7%?676FEOqP*7I?!B^tjJxIB_wI|=&3 zqG`FySm5h0*7oE+|1Yne^aSDIrenS3VpiZ|s5djB z8@oBcWYRJB+@$m{J|FIY!P7727HF@6;YC=GG5t}oe6~5jg{ADrGz>q2#rkyNa%TZm z7sEVCp(Stw3C#V{*9XnUMm>i$UJ!@!8FK(gW=Xs3IdW(%u7Q+ZFl5@2FastdXH`+j5pmK_N z<|n&8Q#JHZsPp{j@#i8jI)o)Tg;67jF(0rHTRzW=8S-Sph9&xALAh$%xfKhjXsd{R zPp>*5Y%m;`hCPo`k;H{l)5Gtu&gQITKVWOPiZi!9e$0F*4*L&f!rYK~eaN$_vB`~p zzb_WH!{pUHso@oph8JsD_E&1zH%7k_#`ZvHf}#M`i(M87;G}gvolEU0Lj;BNa^)6ZIX*oOzgGvy8;+(X+8xp z+|qZ7WV|Izif+JjG5TO5o|_{x1pgUBUZ}jx+S&qmjDls9rw*I;D)z$(rkDNjHY}P^ z&&BLtV%X*7{@*t4dCL5+H1N4gR0JcRiwWOnTIjt)MstNlyWoh8u35AhlxSFb5=TjF zcEcBcqS-${x|K${lL^MsY;6*Lxe->2*l&%p{td&&BFXf@Wzy%$B025>L9l#EVRWs2 z(FBK?6uM)IWh|~G^W4oZ^W`U$zBclg-=IZBl%K7GM`$%{{|r0%#pX=;jm`Qx#hX7Q zQyfx#fK^&Hy}|{`lbTl%sEa#g4Yzc${bIUgcE4kO6{PYstdc{noyE}^%v`4Sg2`8i zzi4;9sE~!+HD|mkQOH+87ualySRk5v^EZfQd{6~8Uf|Ejs`Ynsvx;YvyDBETI7Ws^ zuR;o7w8g}Dq7r&#VRw3b>}#*|4W8#(evt$f_ZjQ?n_HlV*<|sKuA*ci&fADv5zKdK z&}4HHrbWpTwtN(LIlf5z@v<;|=fGKoJ ziFB0*SFg0|$5pv304 zi%>xeLQ0lOLYixPx4!BM>+sxZYooX=5r3|PLL$SBvw03+6>#_+j;F)ipDvosHJZDM zL7ev+mZV9P{wn%wTE^=NGV9cdQHpN*JR!vYBZal`PqoOj@%oHosD%k_CaD#}G7+2FOkZf*TFt%O` zKFe@0@rnVgghRLh-%H^dmUl2EXBs7C1>)8oNrGJ-f??AZnd67RXd z3r?hWIY4N~EJTD>2fr>4KM0zrj){Z;0URYuN`iYW^gZ4%jM3k^VW?7OWaP`t5AYft z1Cw45z!t&%1B!N9Rh&C>h8`i>JCHowKO`X`If<3O72GWmr;Q7P6V{3Bc4e(-zf|~> z=SboVB!*wqfysLKv26TR<6i6!v~{#Q99!T&ak^AoA`)B7q(<4qBO&OZEVNYsxHe|% zoRO)%qh5#y`6Z z*T_V{t!bh!Bt0ksd+B+JB2JGe!0>RxiHG%!f;>qyVrE7JZbl1an=A|yEbQQ{J48#a ze4KB_SbmK2TPDp^c;_YVBhpW{s5L3WjgKXW0|0fTCKfikuv4q7mzd4NtUH6IF+KJG z$EFO&9*V$^m02pYo~Mk=kOkkHC+>hUxAzVvISsqt%#X<+2Xk`)h2P6ogkAjl$&frJ zTM92q;kVTpMQI;&aDp82|8AA@z{hyntpFALe|P8x?zd7WvD3NW-E<25^bbTK5io|) z;EhoKn$o~^1MuVRk^g@bMl^>JNePK!V~Fh|H7EK*4*G`6e^ar3KP|W&XmXS7lo0jv zXf*$`LPhwob7qkF4^)DK_?JixJ0aN_!C?^0h9#uHxkoeSP0aM5UNl($*OV8c5;YuZ zgMo2gCP8-ZFrNS}fX$O=Ug4bzgzjc)9K(-~dx8R-so@-fn=U00t|07Opfe6oiPDn` z;=BVmMe&S)JN=L+j?cvrS=Trx)dw;cV;2`uPBm=oje|>;{X<|x2|uz+!uuw&IXV@E zGHlTGpQtx+Yq9YG5t?I>9+5OYR$*8WaA7}k>59`~{3kB?w>T)wlMnq0lGM!Q|0YzE ze4~LH=np99gGCwQ0+bS}K93U?urOnYF+XAfOwZ5*m^>v!Qx3a*AnQ@tc=k>OCOH>H(W*@ z{Y_=s-~J`KB3f6{6LzqtJJhd9or95qK5piij~VwF*n{=mUf>io53>&rof8}6S znCLB4>aeb13N)PjN3V?rgYIf}30G7+{5mL`d`yYdUqn^}8C?ny3d4?WNG!TFIjZzg zO{)oav&WF+m(om+ArTEtYv($Gz&9qd(I2=wado9Yv^YA?_m>_`_D#!gd+ryM>ZH!+ zrz;D>hOg(CEu)!(9=-+p(ZyVwRZUKda3&vG6qE(*B)d(^zZWl)@u30nT!{SngaVwf z#otLW*Tf#|ZY=R=0-ip}v)=RAPs^^JhocX9ZOPBSjJdbG{vVVtw-6t*Z2GOS1t=Mw z^#6D*Mbo@W|&IT^8y8Qn)DvH_~Xe&yWteT=Wg*lX&Q&7>{ zhbdE0(iY%`GTj_(pxCb^G^r6$Or4Uo1Z_$WD`w8fnu2bE)e6)VSyNW6?u9EhEya!V+knT> z@WnFa<;*A=zep3~Yye{#8haxc%T&y0jnq&@7~H?cYJ$Ttu14j+gyCJS{*k%F6;DQ@ zPCIvint*8jj=33d&+~S7f{$gpG(Gv7fX(>sPJAA=!?4&KE;Z7oYH!R(yFf;C>g_oh z=XU>SyXHrH#xqi&!p~sFxv4xo4K~8dPI6k!;LY$bZKZ7?L#4NeJ%DA_?Tx?<~aM!p#_*|`_3+XZ8l;& z4W@~}{_N5pu?d;zSUJ1&HCExpqjBYdmw{Bnctil)=fpu>kUtpb^W4B*1H@}6CGY;=Yk6BA&T9Nl$c!%Mrjx&yJ#&?oB zKWGmJiUxdR-KP%kBaY*49OqpEBcW&mtxIkjN7CoW$0@jB<0(&+z4PuOIQVTwVZ+=M z-K6&ndrT(1n|MF~t8LLdr=115ho1%zG|alveaYL~WL#c!Be$;Mi2`r-Fnf?Al495$ z!EmCQ+d=q38Ecn1?}C^~53cla%Pd;kTXak5;vybtQz$Q^mOuS85|=FZPMYL9WTB3i z2HfXV(RO8%)#zK}XU--s_%$S|DEz3k;uhYvy3n(a4?VmMQ6>a2P4jtU^wo;x(QNRt zrMJU0#)|^ZrU3UjuW!YJG9B)A{f~U5fFIpOy?wM1pcfHj#ozmYknc;Q{*o6fd7V7v z7nOLql*<`yp5Y@q3W}D~_fF`081%wJcqDN^Hum!=Gn7asz{76rk5X*Mx38b#AG3V; z6GbP{w(dpj`5x2me5i}zDf~#YP--#weJI(duDkMS;N@&jr{-aN@91ahzIk3taSs(3 z<6NJ%;9Xg;aA~aV^Axr-xIWXDe-}H?1Bz(7lk=?DU8EQ>eMkRI6kp=T=nG?x(Ph4& zo6`N8=x3(6je{Nszzv{uOk?hIBmB9|+f2{hK`eh__eYe(u@)M}zH?(do7r``6rNp= z!sB;uXEklC;#ZF88xBiv|NmzPFEtLd$)TeB|DPE7cDvdlt{beQZlUoOYDQ5G_kXu5 z?>`-8hrYL~b3eDFI>%PymQ)&0Q>I_V8(!r@=od}E=2Ulqku1}QlgD2r@@Y>oJ*o&? zOt(hgRLk3zuCPJojjtEe+k3R-mELRR2e$M*AAa@m(k1EtzihO1PQ2%VmTtWa@AVy3 zqQ*>98qRRnO{2<)-BFqg;QK9(VXO1#owhh9#w!59KbDNRhs^G)9Y2Zv@ zh?3UtdMmVKi8HMkWeQ>}Xdvkw9Q@zXgZnnG(tN_%yvmQf{u^UJpX`*Q-=h_4Ds|3w zZ5kZT)-M~m8%ybP$TaZ2zGyLjdGY#Km4=&Lc^KxE4XQoS_MMKa295pg5ZW+GeOZ(Z zqqKbGO~GS?aQxl+*!PSM_n7!X+>#6<^LKfhE1z!0YaG%NXg|9DFRajPo!Z+mys>gg z_?4A0A2-hj-n)ZyT&Rh%;-BvAe=JybE6?hEr!_Oj*mrpv-AC?ugX{2HCV82JwnpX@ zxG$D?E8UTc_#*}-auZR`yBG}JM>OU@oJVQltUCBtzIp$CA(!d@YI!ZN}>j}g}H{Lg)Jsq)A=8-ys@(~=R4hF1>BUU>759N+D% zTT=3kZ%yzFFMVaj(L1h_SGpj`V@$-bP2Qx$yP$@*$GwdXb^ITbjQtQP=DMD@btcL( z)wryAgAjW7LH|G6O(3INbaFQ|;4t=`4C9DPNC#%ag>P#_E=^|LrRazjAdSA6jx9jU z2cEGDgVQX`mJ;YbRfz1)$M^`|*>&gp?#zDMbRQ{(_b2SPMRzwmJa*r2lir5TiAqTC z#T?&GhW!tv`{+MrDE-3{8W)Z+|K<2uZy(HXIkx{EaVEwdhVH+8Z$rokIWTb^nav!L znLS}%9nfTpwyWiU#3lM3m;>n5aQ%M7HUwIo8*#i8d6UAt?@-C<}-PU)I{vFaQyUkMc5e`zc>|j%Z1E@%@zb2R`O!! zRkZs|YMx08ylMLR1Kv_>KBD8CmPRFAsHk3;= zR;80B%XtM-o|*GnQHFPDzW2odddd^IPoGKv{lA#tLd+&7Be9o>ptrUK$M( z_a{`e+IspjT3%hc#61`_96a~IKV%5a;ONNATPhYW_FjFw=#m9FIoCTA9ZC;!D~I&b zSw%N4THrf4aqL4_ejjN8eZ+vi1#!g^cceVly$-xmxUi_aC?|ITSG2JQLY_A3362tq z*c%9Aj>a_@GRGcAD5wNcQ&W0-!Ge;aWy>ixbR4C77U;OF%`M`}%Srzt$EkE?OwZjE;Wm4<9^@MoifD`#GdHx1<g3_+n{eJb4bE(MR=PTV(oh1twMBrv^^E$+UPJbTZMedPX+2-?I!qz z1nI+;74r#3G$nN3qrQmt(}WK>v|-ksTeg}?BQabdp=qO@mq;-V-@UMyrZIf{WsEFz znmA{la11B1A&d(NY|5hM@xN_56Q3*SOz9*^FS=N^1Ie~hTR><(5Z3{B+H4!Cw471Z z>1dqV7i<^8Fvs5)GXSBSx`_? zw7j5r`3>bxH%bEx8q2$1l)BX&8&Z_qes}-EOKCUe2Za7E!2jHACOsTEz|YOnGb1|V zg=6$phHli|P0Y2bzl9&?I0a;+51Z3tNoUC6)U5D>tb+9Ydz3ZIqi*ubj>Ns*Z0xH( z<9Nw3yr6dh_dITOfoD)AZ{F?j`g*8bT7Gm^@*u$P@?Lr0q0N+9{uQtBFZRebRai;$ zO{3(cHZHXbi*G2ZSX}O&YH*Q%GUZiV|0_w<@WTR_Ke(fu_Bji5x)0LCc`Qa?y-fF; zPGn5MzH^c;CE7&V=Pe!7oAR=S+wJT}f;x*-Xv_q40#-hUTL;q>mH+Hd49W8`ev-mF zdYxTDIHMRvGx{#RGR_53&j#=<(%c$tg%MV1Xk28A?tYhtaP_#veYEEv!;F6#YhK8p zhRmJb>$XO(b(%0gU`ylv+m13-J|J<3;*az4GUYYSzeaeyfckM>;N~`HbY0_kCUjIp z%qI}QuhEYi#^tq~zZf38@aGuzYw$AuK$sE9xw^@GjFU53begEi8BOWRXVUZf@LC)_ zWAsi~is21SwT7Ru$>%tDLPkrl^s)B>w^(NK7dV_RoEF?zQM7Df@j{s?jX3~xzS9T+ z;0I+i>+`%@$e-TefLw8}6G9yK=4bz4ZE+(_OEBom||{ zFO#f(P;vXu3@aX2pF_JXc+Z$_8p9nIrn-!8#lSl+n3Ds?KBIWX3hOFkzBTg2lwsPU zaSbzhm~9&vcgi|0dsJt_2aE2nA+KpVFr6khAZE;o6Pk!g##l!q)U8}f3)l28j%x@tiqXJ`C(Mq0*cv-B;p~ppQj9g>Mlo8)mg)>`sot^S z91S~o(;dI|>vnDLnAh)0a{K0?Ud-KRxAYvOe5tp5a6l$RG&G|xNk~FRpAW&-o!F}c zkuzYfhcw}Ip3G9qK8suS;_H{{`EiTVa;S<%xltC(At%Oqr`NEJdGCcZf`G8`6XCQj37^P6<;E*Q0fD?gs zYs}=`8sYH_ly4Xc(8oz>7i6@O>YMTUr-!4SW4YbQ`0n_vQ0xG<20G;ohkw;jAY66Fk%NO=+Mc zMGSS`-RH*P&fR_abJ$_oyBk)lvlmca@{?{^ObF-Wa0xxu<~jB-%zMuI&iLjnIK4Bz zMHUFE8}HbNi$@9J!5;bSds;HCG5jb-xYX)j;f{LVnMC%D@$^8O*nUUp!FX649#4(6 zY>(JwyL~GyM{3_X#(|eJ;B)RCQ_QfM&vd%x{pyx|Q*L-yVT3cZhI?gUme)V=uw$6W zjnF$`O!+MqGHV+&TpRsQ>pJvH1MUuEcL`z?59-aC+Ua9BWmg^;QrWtkzTxK#`rbir z)79Hy^JT2HF?LVm-y+9@rLopRX(pUnXdg>b6GCeyndeu~roKf>Z{bG+SB+y*IbvJl zWYbs^Wkj=Hzjy#9Ebci|l-?5_Y8q$K(F)VSkl zJ$=~RJ}`Nmeg=E$ei*HIaWU-zjx1;g$m`kc^(a0tH9=YEPT#N6?VfI}8UIeI7`u>6 za!siH=rw3!y@*5`2$m{j3@6@jk4apqqWI;e&B18@zGmq_P*U1`9_@o#pCfDnwlY}?>pny z1L@Bh?%`YF(^Y)n=uG-f?t%0XVkZ8bM#noINdNpX^u`xaUbo!;Op{rpegOGE6bomb z>W*Qe#9@rDVvb}kB1s|#RXo8RL-s`&fa0)Uc6`~)AG=9Ejo+jzu3S)D$}{{~x0Mt* zyIsdq%7+W~cuH}EJzwy{AJHB~8HzA9=1lcBZ)40*-_7I9OrH&3N^nNb);A*eFAsgb zKuE`ve?D8j5RWPEd}c<dPqQDd3ew*Dty?onC1#SiY!W!D9Lrae*#0i3e96fK@aOz?ELoPy7m2 zgzfRq5^S}g#|TcUn9z^k2dqifdV1Pz%Zf^!4CmuqqSr1bL?%P&@!qXVV&rJ-9zLQ= z9&4BHPn{^mdaMSqs6;Ur5#Y!S8>hKz8x^^Tp>O1~K%j9>(PbPa^NCA>F!{;Qw9 z)1IQ-=e^|Tf4w=j!{HiRt-emn={3*8H@4X1@RgfdjGz$D_;}5*A z9UR6YHPd5!=uabUelSa0shs`R!|YJ8djjwbGuk=jy^I|(RvmS5;tIn(RE*jv*T&Qf zQ3q2(UpH7-aC0#o>o4Cq2zb&G>C7r_q1NPPBZ}kEIa5083sk?Q=+=S-1x2NcNC{kc-gyP5krx+UdeOP(70f(k<|!Ha z_blhH{CsjT>y+7n^YZhv&%LN1{gl%PHeE$rUy7)awZY-wsDPMN`gqXZ_ zX(c7{0u-ilF{|*i$&|my_ytp~cwZQi{);-(tr11X&fy3q3e;q4Mm<|mbNiN<)niJw9#oZ)g$5w#&V7kw{i>+`Noc}suhztDh|NfT( z|4V`YrNIAE;D0IbzZCe-N`d+d;{u7)U#HOja*x0L$UtCHU?XY#k3+f=u2+0$(cu9a z4Qztz=@HitgX;$czV2R6BYW>#v}jU*#v{+Unq%)^aDP~!+`Y#B*WPg=4JM8Zyx?lL z_xymucX(ij%SD6t(e;GD-&}s-2RG9|>(IbHm&;GQD}hHQ2|*{0i^TmQf%mywCVWuf zqs07g)#O9umu`}OS@$|)nFgcZ^+QK*GVqDUYiHffl2Gpv=)*jee4=w;BCH zS8q3Zp{sWp{j09tZS)pb?=|{MuHI+#*Ihki^rMzJ;U6&i39de9^lVoTB>L02(A5)+ zUgheEMsIcXWTW@FdWz8#mpkE1HG0t1(~N$rt7jU0m8)kN{UKKm8okZcbB(^;)$@)1 znyVKYJ+a&ge~Hm&yLze7FLw1xqkr1ftBih&tFJP8m8&-xz0uVhjo#+!O-2v7dW+GM zE8OyL^q{M^8NJli+l}7j>Rm?fa`kSbAAhUkZ?DlaT)ofe=ec^w=vTPIp`F*3}b@{*tRF8-38#Q;eQ`n_K>key*#h8GW9sXBxf0)w7I#vuEdM zf4mA^&NO z(Kot!lhJ?T>Mcg^aP?NBce;9;(YLyKyU|~8^)93T*44X>{)(&j8hxj$_Zhw4)k8+# z4*{oqQcd?pzEa92+>`eav6Hu@A-Pciy2uAXZ2X|A4T^y6JU z)95F=dX~}CTs>&?3|G%J`k9`4w;u86W0s5%od0xx*hwE=O+h^u-2aVk;&B`QD+IkB z^h(gLa)vnKz6$gl$1BlSf&Q|SC89Tg{$tP^LGN>hMB=^)^hKbzg8p65+d!WL;cN%} z8L{mArwjD6z)m;l{|9>VQBEY;H0p&h^k8yy_q||08SM9go&b6X^h}7?Am~|;{s9Qj zm5|N}p#KZ(CxZS5&{II)0(vUw*Ft#GKtCJYXMsK)+y_DbC*(^m=nsIN5BgDHzXWxN zZz<^S2fY&Xb0Itppx+JdyJF}8xBp=i=zb9D9qNr>=Mo5i!*NdLaXm%73EaO5;cNl@ zL9kN_;X!>chTihNaQQ^{1MiQnw}QW~L3k>`KI#Fmk9r%}=>a=cU>mi++z&+{% z;64xBr$BgK@)Ci5Q$ha<=p~^4AJ{1ceJbdcpf^IkR2kjNmqf@HcJKXb0QdKU-WEfz zg7if9jo|*nV5bT6E+|*+px^HWhJL$1k8`q4uJ(a`0@z8M63$=Lb7SbGkdNp-1opRK zIzzglJ^=3P!2KZT&qKTd5S}kV_>)2Z4CpDK^GcHUFBSAfo=Cq{(0-zx5AK&iI154l z3)m?EeFeBL1^vUISAzZrvg5T6RYv#9VF{!syZ8Pzg8Qvtzbl5G0P#il31A=fCa`lT zl+Okz52&|*`^O;tTR}ev^fu710Q=pb&jt6rpzntG_JMxAmpJs>1@T2a5%kNz-(=7) z0zC!v6Tsh8(EGsOG|+p=j+eigM)&f!1=640d;fyq{$bEdV(0_V&Y=5TaDN`O5BZ?~ z4(ykLeg~v~CFnCiZvcIr7kK(@jiIN0DBS*_`$lj-3(~m>^uL1rHqajey&ZJdE4kVW z`pFRfHb^(r`@sD^NS_esEuaTJ5RTV#5S{?k7t|BL{VU+U3d#fOiQxXL;654jHqcW* zUkZ9E=&o0CH4XI3ApJ8z|0(EMpx+1fb3sqV@&=c6j4CG4*=wAf;tuge$715xlU#T(l z%outwhF%&&uZp2J#L!bf&xd?W1N{`pmn_f^1w9w^osgb|pnnPMmw-MW(ybEo`@#My z(C-Aj5%kZ4odg({7K6WupnnS7r+_{e+^2&6HHcRl==Xs8Owd!neirCnSzvQP&`ZEh zF6dtefAc|41N()b9|v|yKtCJYSAu>l*slWpLP+OTp#Kf*H-bJD?6iP>GuUYb{WP%C z2KryXeLLts0ry>?&jf#aL8q-V`mYc4hroUa^g}=&0R36DLVrN}a5=P}$)JA>^ivzaGwdfyM;@9&jS58 zFcbv+Xh{ED&IR+rdsU=!KxC zfPOTjXDaBsA--v#e+BGhg8nqP&jS4vupb1yAHtst`XIQ^2i@HwDR&iu{v?E_1oVqR zF9rQp&?`Z|62e~v`dVp*V@ zeJSW&pyz_#4f+ufo?g(;hJ5J*Jr&{=0-ZLZ>%Rfe?^HDq7zF(duoL)bxct8d+$Vs( z5!@$&{y4-d8FY8)RIH_d?rv2VJr(pWu%8C{%MhMS(0>c=vp}zb@B~4B9Ng!E{x+m@ zKImTny%2PIVL<V+?6-ry0Q4@?*n}==poRPAbkcvp9%gB zg1!js1l-9UxBuS;_X(i)fc-?!Z-?|x2K~37r+|JG*hvN5-5M@e(?H(??lVEZ3&NiT z`qAJ%2>L7FJ{R=&f%|;WLlFK#(5Ha=63|}*y%h8_z)mITp9H-M^!J0ERiIx2;co!_ z=b$%&9tV08=;uIvYytgc$oE#zKLFur1N|`we>>>^0QX&>pA7E1LH|Cu?*%;>^ghtD zA)F!5zXSRJ=pO_-gP=bJ=@Xb9ZvQ(WoC%;`2lf*||1#*wpf3dbDWI=~@T7u%0oX|c zy$0N8g8pyNvq1kH*a?FEWpJMhdL6_!AM_7_`$EvSK)gyoe+cZ9g8m+GUkQ2;+*g6_ zzA_=cuLAv#V5b4}pM#x7(CZ=mO`z`r_bs5G2I5~Tf^@-wp0Vpf3dX1E4Pfe+NPTD8wspLb&~( z4fYd2{}{MW1pRo>lR^JBgeL{`6Tp2c=%0jerh$Gw=$WAZ80=(${tNIo2zn~G&jmdQ z_VYpC2kB4<`VYZQ3Fs$+UJCk|V5buFx4?ZB=pTXbtO9)n=nbHM4)jLQw}Jg8(B0!u zsQ&ZJ1 zK>szk4}yLyxX%SW9sJD){o`P#5cEt)pAyjBSF+`e=9-18uTjAXF|HI0=*W( z(*Sw_gufB=!@+(N=y4GK7SLyd-U|9;(Az*i1;W`5`auw$F3>*-;pql_3%KtEeG=$> zpnnzYgh2m3gmVD&QqTuMp8@F^a33Oa`L6_j6F@%&+$VzmbI_APzY6?K0sSd(p9=ad z;64rXDG;7a&`$+BS)iwZ9t1rEdM@b2ke>OV_kmsr`qv&tOETp&>KL11?)6}o&x?hf&LGOR}1KOfZhuFXTVMy=of(dcF?~8;p_ta2N2F~ z(9^+AFX+dDzkQ%5fF1%p73>dyo&n(*1pVvaZ{Q@SGIRMq9o#2?eg^1?pf3kI$)FEF zcv3*G2R#+^AhaiGpno6iXM+9}u#*M)k>EZE`cz1_T+nX?JNcl08Qd3wz5w(R(4Pf= zOF_?sbgKkC3*1+M-T~oR1^R5T(*XLJpf`ekJcP3e^iP1lEueoB{A~sOi{QQu^iP1l z?VvvZcDg{%20PuL{|Um`3;Ijoz7O;#!F~wzGr`UP=q2EO5cIPk{DG6h<^L_PlK}c0 zaGwbJ-yxjIpkE69rhvX0+^2$m5x7qS-CeR3-!nm<2X?YR|33(S5cEx;=YoDV#48{4 zJHdV-=wF0zmVn+0?n^;G2kcjZ{s#z873kjtJF7tdF1T+1-92JPd}##zC2-#a`k`RI z1@uXvw}SpNh;JL{nP9&i^el*P7wFlbcZ0qT?DT@}Zrzf*`aqun?PLh_7O+16dM(%= z1pQoaANY8<{MSG_B!GS%xK9NA9&n!w`btQ*6wr4AMB@r-UjY7L7xWxW`X`Z z=t0mQ06iDkPDY!2M{bERmO3@~w*?3*y@i`e(sTFX)eeoj%Yjz)lGC z0Mv^C&}V`DLC~K9J>XU<9{*ef{w9Ea1h`KG{dW+aWY8}LJ1L-l74k6^^vz%=4fIPO zUYVfZ2=22$Zvgv2(6@q~3wjfTGavNtgZo0zF9G)@pdSq3ECqcP*r^2l2ykBo`ftGg zD$suq@ofNoIoNLm{d92O1bPVau?6%?!QWQUw}JaM&_4+Nwu9aQdKc)IgZ*yMpMY@o zf}RWR`#_%$_Cui00(}7VUa&I=dLg(ExRZG<{}+Rv0QxUMPXv7)*iQ!iZO~IdzX8%S z74+YLo(8(RHD0V`g8qJRp9T8epa(%e81!7w{{-ou5BkR;zJ;JK20JC7yRV!|I7>ml z0@9%p^cJvF1^NbXzY6p+aNhv>S_o$&=#PWm1o}TfZvp*E@V6E8rQp5|^jjd^+Cjex z>~w*?55nIK`uo66FY3@f^nv~egeL_0_dp*2JrBY&2zm~LC*Zz}$K}5r+$VtkHiR<~ z^cmo9GU!V{PXT=r#48o_e}cbhpbvn*nV{bUdKTzE0)K;`p9cQsf}Ra}KIm(}ej(`h zK)RKHel>)@6!dFAuLM0G^eWKTK=@aI{z-7(0D3#PZv=f6gtH0sH^F@i=;uN@w1Qp) zcG^JyDA;KS{c3RE1^TrR{%+9k1v|Z<{|eH-5A+$Jhd}=z=mVht8|)8){wWA&AkB$9 zm;YMO6F~nRgg+7VcyON#`il^r6wt2&JE@@G26oawKL+$n(7mJU*jyIqQ^4OK=!b)y zT+n|7;mHTRAM6x@o&0b%@hrxXn=x;!HR)Ibr+&6$;4fY#BZvyvC zpq~%!TR=Y@+_!@Md2rtb`rF{X9rWKr_`5*A9o%<=?mm)|yLv%i1Md4k{}k8{fqor? za{%EON+^fb_`K;HoRD$pN+ z@Hc>dGU$zs=DEud#XI<$iRJh*QIeF4O`9rOXvyFfn+%0oBk{{r{DpeI4R z`amCo@Pt6`1@{A>4}twb(EkW}zN=pP36`Jmqb_6tFO3+$ADej~Uq1-%6HO3=Rr z{#Jqh9?(~T{!6ga0Q&DCzZyYb1a_K0e--SsfPNvkZw0*u^fu6c4gR)+-VFA;KtBTP zbc22#l&fCQ7lWNX(A_0`xf%lfMQ}d=`mtbt5cDPBKHv_Hx%__&!kGa22S85*{T8s3 z4Em3toTPyMDCnu6mx7%%(4PZ;GeJKd(mxCIGO!Z_{TZ;63;Hr}pAY)IV80Ob^FS{F z{V0f6Dd@+7`%2Kez~3s+^B|n7KraRR4WM5NdL!t|!G06y0dU^}`h5`2R?xFRZv*`- zu+t9uYY_e}(60qM-Jq94ID0|=DY)+geJAK4&?~^s0O&hF9|V0P*a^6U6)ykRgPs8T zI?xkAZ-;b92L0RMZwlz$pr?ZVAn0kJp9Sfe3Hs%rXMuhj*a?DO0O8LCy$r&i5Bhd+ zUkLi+V7~y|eH-Y-5U+O7SAd-^(60nL-JpLC-1mZh2k3pE-vD+(pq~Kx0O&VBx($NZYlAWuoxQu7mHEZ*y}MQ`^9$2^ zcU3EMA=|sFOgTZgNcnK#dCL5PsuU3A)aJBLWgv*rqMW4O9ij+SnJWrWlM4|XA zA0wQue5~*^<*C9+${!YvQ$9|3&pt2yDZ)FHrwR8ce?+)L`J=)cls_iitUO(KwK8uI zr~FqwLAXpgRk%p`MB#bLyfK;Lugn`_DgTu}E<8f@S(P{6ldCI)OiQ=#P z3E_0*vxKK9^G2P$yONa87LHRsM|jV_z4&Jd?@-Pb?omEhxI_6o;SI{?3pXqC1AMCg z$`=S%D_f@SP)6lnxj=Z&zr6St3hz)Z67EsHUbsVff$#?9g~H9s zypTchSLTHTs{hJ23YRH!2So8#UL-tE`6l6P<(q}mm3g8}@mF3VoTSVXREodyQsF&= zUi?dicPR4&lKMYoo*+{GEAzyP@?V)JFx3Ak^F)N=uY9X;wK5OTssB^16fRP}U3i}I zXN0qrdB98gugn8oioY@sKq>!~d4NgrSLT5wmH#)q_*V(4 zH!If&uU7toaJBLmh0Byz2^T5X3eQvil5nS>`K!Wv{^`ZP zL3oGqYT+K`yM#NG?-t&me2;Lm@*3gQ%J&LaE8izvrrao8r2IAEdCK<-XDfeQI9>T0 z!qb%33MVOlQ#elf0pUIW@Z#SjyhFKJxJUUx;SS}8gf}REOSoBio$zYqhlQ(^9}zB7 zZV@h0{CnK~LwSR6kMg6!9m+ox z-k|)LaI^A8;nm8I3s)=uNVrV7O}I$;$HMcJpAgPg{)uq9@=t}QDQ^-^Qhri6PWdU} zJ+FE3Zx`O7+#%ef{Iqa~@-xC4ls5}ED{m2At^BNTwQ{F$nR1tKk@9oG^OS!koUQzG z;dJF+2v1YqDx9SJOW`=>UkUHo>&3rYc!zS2aF6oy!X3&l2yak+QMg%ooA7GoUkg_& z|3xmUPI`M1LJlwT6gR{ouEy7KRZrzvk2PEvkZI8ON$;XQl2`1c9#P~IWjqx=Wq z4&^@zZ&3b|aI^AG;nm827OqzQi*T88NVrIOm+(C0zY1q7_Y0>hzbZUUdAD$q^52Bx zl>aWgXTXd9fbb6GJ;FW8dxblcUlZP-{JL_ z%JIUhm3hNCjsKMS!8472lzE|u#(&EE;vS8Em3cvs#=pw^f(wm*l=*-K8viKsMs^zi zDD#37jenFU3-9@x7ym@z9m@RRk>an+3;Ps*<)ei+DDws`8viNt1`HbiDZgL1TKNOQ zWy;CIMasO9h2pRLA>nN0V}#R{`Nd9(zw%V!B;^ka$0;8tyl1x;{}kaJ%Dl0h;;;M> z;SObfVV%am%Dj+B@mHQMyjuBq;cDd*gv*rqKr70Bf^7z?<@4`QyUV zlzD>?<-hVN!g0!{3h#Nf@-3pXq02(MPYK)71@Lg6yypm34$MZ)uxFBZ;LzC<`(nIC{r{FUbl zCn;Yh9H)G_@SeYV@y`|Bp*&BxNBIij4&^I_Hz;2v+^n1@yjuBc;cDe;gv*rkg^QH= zMPbT+m75T%=qpJWu&c!r97o!s*Ii7M`YDFPx)gt^9T2bmeadPg7nioTU6s z;W*_7g!k<9;@>2^L%CVFNBKeF4&{f0Hz9Zl{^-TOU3iCb zhj5Sb)50Cf&j@c&-Ynd#yhV7m^0UI#%ALYx%3Z=m%FhYUQ~sH7w(`$~)0KZAJWYA4 zaFX&bh2xZeCA{YkUi`a-cPRG=_b5Lv+@bt}@CM}oL z2=7qdBiy6BSGYs@HQ^1)uM0OT|3i4S@;`;EmERC9Qyvs9QvR3lJmoiqvz7lXoUZ(q z@HFLp!b!?+3&$xB3GaEui+|uC8UHBr0Xa1OQRWX~()?GMUnHaPk1~I7gXTZV@xrT> z4;8Lf<^#@Y{;!-MT%^n|D$w{>nO{7m`HwOm3{LYOWj<(+#{bHbgp-u{#RQuFEAxRq zH2!IO&b3zpCDYOoGM(Te4_9?W!}h6@mD@sI9>VU!qb#z2q!6@A{?iD zs_>rQd-3Ou_%!}kP8aS`o+;d+%m-ys`B&x_tf~AfX9%xW<`+vS{>o)FCP`7^@V z%Ks;vuKZcyY04{vlaxOv9H)GT@Sfjz@vjozphlT{Mw6ugYXXJ)xtf> zcL{eW-z~gB`5xhB8HT4Do@#iC z;Yo($4ez5RJZvxiVR*OUorbp?-e!2K;Vp(Y8Qy4kz2S9+*BV}9xZZG$;T47}3@ z4X-!6&hT2pYYf*Lt}(pAaE0L|hKmi)H=Jj9uHhWRa|~w~o?&>p;i-nF7@lM}-tazJ z;`imh;oXLJ8s2Vro8hg7w;0}Jc%$LrX`48zk6Pc=Nn@Fc_WhWF7UKwthF-feiN z;q8XE8QyAmi{VX%HyU1Vc%9+3hSwObH(X-fnoC;jM9TSk2OZ+N%iorbp?-e!2K;Vp(Y8Qy4kz2S9+*BV}9xZZG$;T47}3@O=oZ#d8JT*Enr=NQf~Jj3vG!&41UF+9m|yy1PcrOcQA zhIbp@X?VNgZHBiR-eP!@;f;pZ8(wF4t>HC>>kZc!USYVx@DjtthUXj3Gd$ODj^R0m zGYro#Jl*hA!&3}TG8}JsA8j%8<-g(GhIbm?Zg`vFt%kQ4-eh>A;q`{s8D496jp2I3 zHHKFht}wjBaIxX}hVu;1HJoF3j^PZ$GYn5RJk{_N!;=ih8{S7-PJQ`rc(>u5hPNBu zW_YXNErvH4-e`Ee;dO@B8eU_#-f)fK6^1JeFELzfc)sC0!*dPi7@lJ|!|)8l(+y8G zJjL)N!|{gq(H3N1{u|zHc&Fj*hPN5sYIuv`O@=obUT=7v;kAa>7_K*5V|az(3d2hb z7aN{$IM480!#RfM7|t*}!|-&&Qw>isJjrmp;eE6v-IxD{cN^Ymc)Q_khPN8tVtA9` zjfU47UT1i%;WdWq4c8c6VYtHZ62rxY=Nry5JlAlJ;W>sg49_q;-SAYyQw&cs9B+6Z zy`tdDf5W>C?=-yK@HWF+4R0~L$?!(Q>kY3nyw>m-fnoC;jM9uQ2)Y-|%k3 zI}L9)yv^`d!&?k*GQ837dc*4suQj~JaJ}Ig!z&C|7+zwy*zkPAd4}g2&M`d4aE9R- zhNl~zYIus_NrvMM@1s}ReEDy9x8a?Jw;SGOc&p(phBq1BXn4Khb%xg(USqi4aE;*= zhARv&Fa}DPho?|$}@C?J#4No;Z#qcD<@rL)&D~`VWH@w^MPQ%*`Z!^5r z@D{_H3~w~N-taoZYYne4TyMC>@Cw5fhL;#FHay>Op5eKMa}3WhoMCu|;pv8_8lGZ! zlHqv6`{-QkkXGLwPKLcZ-6cjN+JzNA`RAM9U^Ho5UiDC8LX3^fm%tc!Qjevy0tTu z|IeYJl>>2iwwF(53!dCV?>q42fBlPpIjz}Faz7OW`l~Z5nKP4b;3P|9krRo&0H}M~$ zBzj6>!!XGiaANKxC?!n-C&}^uuqh_;1N4RjU+$#*3a40trdR@|SgLyO1xV8{*;6zP zQ&^e&cy1Qov?`bHWz2T)L`(;-Jgi(X7~o1v8A?IAiVyDyrxsVc{Mr@YGc~R*=XV5)qBkJ;_b+eo?=uaa{sz4n#znPmE|=){NEI%R4>i$& z5p;5NK9trggVnFfX;qVxYEr3{pb}G`;{2{jrr%)grbGwVCJ1f}(2ogaaOEae1La51 zU+g?kaReV}7udxInFZ@>vgFpz&;wM=9iol#9RQ>rGrE>vO7tbsHtH^=sr}eLeesLvZpf)YOQ>`?w}~w|0iQ z=tVN{=5RV!Ay~I2Aoj_clkUg9H8jNU=~H}I>kQrX{Lqk1dhQsNQ3OW?5ntjBtJEHNFWeup%>q| zVXl28w1m!p3D(Z<4%X5CYJ2)2lsYEIOq0RJiJI7HjP`Q02 zG?RJ-2RlO-(9vg7!SlF+zt5@QXY{9O0z2l8bDX)+Ci|DY;6-c}UF!d7sGiP{px9vt z79IhtT+tgSKc1pQogPK6Zhk0O^E(>vP++#u*<(*~Kp9&2Mf?aW)vqQy#Wq#S`^FUc zkyeEZF_!>tZQMdF)s1*9mo)laH{krP4>`XZ`{>uE+R9CAJ3u3-m7CbSQ|`I-&=%-U z4nv)^IKkSQOu9sF`6p2Re$qvtgo%II>p%|U!#e`~@on_q0CmA`OLi993D@ZwDj}gJ zZYXMNc<4o@Bz|s_6CT*S#g)2FS~P093dR4Y)7(+dD|C_DJ2x$IS{d8~$!TK<&<&It zIqeK?(&Th8xalJUq#8Gocqo%t!zso0^g;Y~az1l$syTy$KrvoUC7VJd=(f=H89(Ud z9PJEU%`vNAlf`bGNb?aUbV*8L$tzU5xwp}V{R=!c3fu1N)BD(3FO@ah8Z7LeuZ303 zoI_@?rS!sj8`(p>(2c_#ZZ#l3%DcUieJve}*545NAy=U4&0GetC82ht`qeDX%-T(D zlu*IijjfR->j^$#GgzPTIGyZCBlyE8S)@FKX8eq9St)lqg^h0xRGjccpL0WvbHm&8 zZETP(uH}60lww0Z1?W#MPVS#v%-lbvjyMid!m89JR_on9rZe;@YLN(Y z*&DLImD}ffw{NT$wZ0}zE=te3ozCQ>>!qyJ*UN?aoCdesP2<3M&O1YVei@iPmmA}- z$9KOhD3-|Mk2zN*)`Z2*)qoqUhv_Il4OWfgd&bjrOe=@EmfC;MA1`Qgy)b=mz~{{- zY9JvHZ_^P2WH(o$q@6eNLVNkv!q5jnOMI@ z?sF{tq;qKK2|mD-ip7O=&@2_VqsW9)dY+_<6daBAlx{l8 zx#{2Z~?A)`;YKl@+==EmbIWR;4yE#n@63Y*J)s3ZuH8|iRALq+P+}zOS>qc z{r-B{wK4K`udMx*hI704M08)Myc;j2GTwik?~-@p>d3fwLHaefS^j7`MWi!SwhR>E)tY=l%p_PRUbKN8lk!u(sogL8nMPMF%8P zIqao#k)0xSIt9WR5WPjkXxABRi%btuhCcCc=bk#}p5N;|2kAXse9ysj4<`%tLZKf? zS)@@#XXtyo!m`t!ioAy8&;XCit2c9NO{1^y*o#Lfl{ENjq&YU#*Y;7VGT+jSk+l{$(~9cOEDur483pVumiG%-Ux-n>Pkdo3lcsfFd~{U^D3 z<0Z;0a^()pKlq%N`9oZ|p9$sD!4ovxtAu`)d({?Bp4v?%Qgt^L(hr5ZCg1s$z9J%@ z#Ie(nvU{Dalm_c+96L3YY)+;q&gjW$HRp1JU*}wuXs29SM+u(jbX0Zq>?@^0mFwn) z$*Em1tH~bfc4o^}od3^lj!Y2WSXx{?M6P&-;Y=auwu8F7WC>9R)4wUi=UGs3m}16;n%Nh-cmOEjO|PO)@sOKQ8R#je~* z+;Lo1>YR&`T4}+$8fnNBp z0b~Dunu87bbnUZVK4sCovH#xC*M37TsyB0{n0$&|f+I7ggc2c2$t8!wm)yH~)Pp5A zi%M=Vvc!hx;QrEj48_k@-^kMXj}DUxS7~c}CJl_KwBF5W7PYj#6RA+o%?qYNaBQhC zh2l4ID*V0Oq{3xXiJg9IR-dFoJ)Kz*nF`duq=YB;GpQ*JPwu7u6l8Kj;UJ|w_~Cv zf^)HgS21Qes~E@iCws}+L`B`ntuMSxxwS3y3Xi(&0wyh-?r$_cFotN9jyW2?rLyWo z<0+a>P&AUGMWg!FMyHqHhJ|_wZZ{+HVl4e7bx{vcA@|j?N+_m-0@UpxGKyO#`Y)SXZZl*B`*>dhQ&Upu_= z)gWgm4enYa5`YS$jObdmOy=1#c_xoeyiymUsPb^gSL!IbAEF^wD@CZ=jq3#_uC{G~ zQh9{NgU6?oofq*ieC6gKL_#ZlZAG86Lde6=J_>Xj#Wv7?F$FN(q___;_&hHP+KF_H zpZO&4*rc93b4HbY?wZjbsjtQ*s_-)e@-&eWj_&0r4abTZdMd|ezR)XaGDuH}5;y>` z9LYhgUGZuy*TL}9zQOeNl`CG2n_Tk-xvpLjqP{LLxrV>nLGyxvmGsncC7Z0D^4RC& zcoMpuq+nhA1xx6M{QD=3pF@mu(x&br-=G2{k7S>{#hQm*Tv@$ zhRvKod=j;1mo$5sVKN(nKMg++-mTc#0>(p;nsP z%zs9{waL#=B@^o6%h*=E`)IG0A8LhNcv;!XZLo{Msa`&cpPK04&* zuEE()m!INgH^us_lVsI)z;!byZk#&3gqBh0!LM(TGny}MxK44xbxuUMxQW)NIzbu; zPtYU*NTn!?BR968${pvMkR7e#Y^49|z1)mhg$75UnV z*X#0LXNv=qI}&TVU4Q*o;y4T3K!<88{zT40b%ENPx8#q+x|~17@k7;6E&chHx@6mI zxQ^7<#lfKDB}R;#guc-ij@!|0V4O7PQELBDKIvAHs18~i`7v$GU>iw38=rD)Xij)z z7Pn=QhQ>{2YHB(|d#OnGf0QE_?4)d^0$2OAIHKq8d%qv7?Fzm@-<1u;nYMxQl9v9R z)+)m0lN-tABK!C)}CE4>G7Zp=EGdr9<_NvDiG;6r) zlK8^l-2rv-(?2ocjN;}bS_D`*7&rMI?nSsgquRm?UsQ6q@C;G`pv6q*kI;O|Y0N6W zz4vfo;q`R22LY$@8n%Zv!tD~}uH%FPF#GA{hmx-Y{fDsMSX(8nxozPh5x|0gp&=8_ zb7Lny6tHR%GMH+G*kGgf)d0I_vJ4b=)GXD_eQ3A#u zt2n+K$5G@|r~hBsp5}#wh|^wsXRq}7%2hb^25D7wfU+@4TGdfE;oU8R3Gpv0!LM?? ztj(h^Q}4`ufD5tQ-Y;Yg7sp*LX!vbvX>(y?SCz$PCaEy zJ#ScZ*4JC5ks6>KN<6~W9ZGN0LIspq8qyfMp|`%rnL&ocSZC-Pynw?URXvws>K}e; zu1l-W0btKNL!Whe-%zk4ba?QIE3f@})2VIe2ZC?>ffw>SLPxS`+BU_*p%^ZLi`oM} zyZ;lx6KRV~S8Wat4(XN(j)%L15g$6;7Y{B~)C|Tq6u6TTr|r6cq!lD_u+~sr_eRF2 zgzo!3m!nVv|2$p$GP#TYwBv5mqnvQ@7r3`QDcyGbU*^-*m75cylq_C^q2T2V@bY(i zXcI+$@8pknbCGZ=3@@9X#5)RjQ{SgLcoml*{t$ZJxOeg=JJhl4>XbtIucsp06{-NV zxpB_WbN7GZb2pOl5Dlz5$=P)cn_$G?uP?PkXvwOvl4^KH~bg=)_|q5eD}|;rKXRbKFy}=4upyJkqFk)#tq7K3e!}3#El^2Hv0&X49uW zej0rS*tUZ8@kfiQ5vhycdo52gK&bwdPoQk6UGWx;g$F{HlRwVtiq|mBp+O<7JscDI z7LN|49C(*LB9|yGJkkp94?2A1injtZrR}E`G_GlGkC;%G$MeboY43)5upf5PTIQAh z-YYLeQ%q_hsfcX+0oU`q!BywVaDx7HdNrFWl&>TAYTh`O<4j?4wftg!np9jW#)nVEsI~N2>McX*yn-p?p>q>3 z|J*)#9%T7@ zxU0xxUr(LJ(X6d_(HQ1@t(!}GNIauI=OQ6(0~_^s|3ftVhf+r6Hp{h2P88cP?yJP)9Y5ZAdd*7a^-cg*Y2?62j619{eIR(_{kYY9bLshZQiS7lj?tGs6yt$ z++EQX8NwV*^B<}q+$f8SyT3!Dy_{G5!@Y0{agE6*!)>({k5R~4g0*v_JZfnQR2)wG zEL(O}QyW8b@1{6u$Xn=x+bs7lA>Z1xz|hJDZw!BoqSWRzr}U_hTr>sg`8QwVkbnK# zoUz;&lb;Dk9t8DfVHd{aS8;{WPXNZ<` z`=1YGbI$so&TvZ77<1){*SU#=Lg=P2`At(LZL6tHyG^s3d0avUsAHyJlb?O-I82-g zl;W~7@D*Ca!8ERZm6xb!6GD(yZfZB4PyfYIBMTli1*CEm$~rj;@(8=GhMhi9B{#EI z6%-{-wfZ&U+Izk(d)#JoyHKxYUUHUBpw05_boPAvAv>c4CF5;W*Fs1CnAo*jy_tjU zAH8vX3Q;NStIe~Ol@cISm-l<89R7~V9VcUWJtRK#BWGzV2x^KRlZRxJrwB7dFyftSZB^4{Wm}}`^)b52#r3Qu8O0jioxK5=j#q>fHHsN%ACQt z{$5!n^yO-l2B$9P_vGWt6i}YUhce`;y}$Wseq3V4;SBXp3q2?a=y&otaAI4iN6CG- zYC!ULQ<-kw1M#o8pVO=$jPJaSMUp;)p5!UW&FajC=9-=~=^A-;< z%8#I0K%t&N6&L#==)JgPZK69ON0#xIU*TIb@{L;Eel*8#&gL z8&vyfg6#`;BG+{1veToIGTgDTvYmJJkX2HG)X3*>smF%SSLmOn zwPwkN2`0MX|XqfBn zBgoG@CT_e4aiW$`7#mHBh7KZkPV3z0Ms9!_$~)U9-+3oB9#oi;a(&a^>q&b1a%Wn5 zFVzEY`peHo8=v^i>wJYD$vr{0agjXgyJWw9%6T^s*2RBIRK9+#d;Rk=*o*(JYx1EM zDZ!tWtIzC8ryZuDUvbM_%N>Xp#JT<;-a@YBv7s|V=OA9^ntzSj3x5z_&>%kG`nis_L5@E{2w}LIq{;66OCbzrv)#*_ zq`8obe*KhG$KPgA+21?d>o+?7cDcCf5q3_)gt{qnMUtX;7ZpV(WoY#2F22{rU*+EO zC+C4c3t7!}r7~wJh8)YrL>gX*ozGA{aIQB}t~>9t49Zx7wjNWya!2C6MvyH-2;PG! zi)nW?NvH_vc{O*AUPjS~r=A8l5+vz>2PL{ZM&?L9I@d{r>t)WtgB}_4(bdk-H)R^d zT22cY5ZkCE$7Q9ah+!fO?>GE88`KE2N_>zgPTsvg4oqP)&!``plTmrql9UGdOMI*m9N;?Vg4DQ*T^g8Ha={ueM4|OtY z5GQAnFJ_W;jgt&y#cT0s12~m69!ru!`ByjhF&XpI0CLwIR1QN6xirXHrWoBQov-B6 zmuM75Q{@?L0qi^wn!yK9{x9Tl@H2O1Pp6@hbP|}AD^BssW2n-+*)cz zHq(EciC`w}iwWEXNu#ZZ6C|H}F7_6O_EH~01 zkDJ?aY8K5%X4F1r$|6Yoo(sn0<3W)=QmEwF`y?{n|D67G3}3d^p0;hxj|_v~8Zq}y?D&og|_^>EKY{(IWpd-`Qq?_|eU`JPkY zo?psHPxI$q_nsfYJ=gI)Z&JQ{X>h;)o}1l!R>D0e@IBAMJvaF8Im^B0a=7O;8q4hB z4@Y|b%=F)rmDcF{vz`RCk^WO9{xbGchArK_dMy| z^Fz4j8oq}=O77irum7Ia?mc(FJs;(Jo~C=kbyUjxk)*rpREcE8T;2UGy}I{@5m$c| zzWQS1)eYgRk4Ij;JAAb<@@hr+>SrRaUK76hsmQCd!&lFayn0OdYD(nQeKZttQ{$k> ztFMHw{)zfalU5z!tItMWeJFgjCGu)b`0AG;uihBGx|ps~>jkTi@u4=3lJii2U+mWr zqpy#5&zkuKwZOymVT+yX95r{hVj4BT)P>VV5?UMK$IHG48_u(Tx=!mQ6f_#i`j;k; zb;1U#G!&{VZqvymy*8JW(}leun{%J+U(bz;dmvDn_ih2*k(iaq6yj^a`qD&+c^%II z=l1bK@27*cG+dF1;{$8Ngm2lXj?3U;(v9H8KJ~)a+EX*0S&vHb7W-3KwcI(<8K*`RfMx4xbp9*{SQW3cg7qa=T?cw z9BJ;D<4Ee!oq?R(*cqiX#9w~44c8n;i5jkd-S2q8$+G=EjqC8?ddwM}gu}I*22#U^ zOHwxe5*s!dizP^U^8p*q;5f$_lnl_5YAyhrmi)`?3^Sd5hXc;O!$I12NSXQn*n9i< zs)}p>{}2*P5hYsCs8NrI77-;tK){IMAs8@Vd++P_S9y8-ob1m$ ztXZ>W&6?S>_wmzV7H;w@_Vr)TMU0YOV6u%`k`j^lqaijwX+v!OMvOOR`H#lt-}19+ zOTPP$C4YU4^4GM*i;47?2~oB-dH@f(OT^)!D(g-R;2>9qF4elO$QqVJK8 zL2HIzH{M8QC0axxYjP^2xKNu60{t?V$Wb0C`PKJ(BzL@CWXf-OQ%W0?omoI$3nL3V z)b^ry2Dvl0KeUM+l6S&HJ?*Az=#nfoDvPXT7_)l)XsxiKj8ByhKkFtwL9h3_P48{p ziSXQkN5>5;b&Ch4)IGdrr}zVr9ID?hp>AQa~KG0pIGje^&Ee5uGYKz=jl{w83yio>Ie-X z#jKFEQLLuzA`#L$zn6l?L0Xx@2id!09pCfxXH=D0+Y~wuIF8}(kt9_lv16KWi5P{{ zxEHA~awX7lqH2uEyyrR%puQ zUlDp(WmNC{;e|8ZqzDXLyI(D8@A;?7#(0w(2n~;@KdlG08^(U4Q7-#|E)^){E6QB5PH}S`fX2h+^ z8pxP4H{ffffbl+F$oV<+NaP4RUNW53g&P3-Afkxh0q=eJ-DZIa|`BRtkIPTf=Mb?Dm|os+MbygO9XiB6&61n@m-lkQguRUbN_lX- zR>~c;UOihoxfLQX`RD5Y>Qz6JcglC}IIiul7xs)Fvz9T`V!ziz+4(C-8O}<}_Oi z9%@`&Z*S(>US6+hd6IvulMA2o9zJ(u{)ly1=GwogYeDf+2=chPc2Hdt{m8X-TwD90 zDoZK$7XGG~fJHA?e?hd)CQ>2r+F^ii7&Rj8Y?XOYyr*HB9gzA>=53F!%Q=?)*TIR$FJ4pe`K!pHsxh?`LNlV=ed-AQ@w`g^40 zm)S=PP{ugoErybMWM~jgSDdmk>2E5qk_WiPmE)o%rzGUYUl{Vp_|<#tXWAtM0)0sI zOG1|L=WG#tzA}r3vCp6cDeL~*l%=%c6l-yc&6ZQV<{`N}pUX_C+V}@4r=p|BknFfy z_O*}i;wk!sDv)K}D^}xlrjfO7%L291vWt{l>IvL|YcHa;a#zp4+`<+%LBAPBP zgMQY{RFN#w@_sKyp1vPFM5L0}D5=?}PHs*S4h{@mM{J;c+^3t7vptjWBoKHlb3-7D z=NJ%y=!ngEnJeZuS`}S_ICcZC$5o)Y^As)fhSG_07F~#_wI6<~@a&!PC}e1)TJo8; zp#kuiwW+(C=aDS3@%=+LtYw#V zis)Gx>l4zk^`<~xeT*9sRUh9{Zbsgt*B-hOf2tcjHi}AqhwDLGr=vZU`b;NvxQedM zs&`(Nw(M30@YXd>@4lwyo=}dOTf=&EWwLI{dpcH=foqLB)rm+rgKUSc4s#=EQkI^# zf66k)W!t1tr$`p}6}j4V_Hnb^D=Q<KiXNtw%PEgB2W3R1JPZ($KEvP~{7OKib;$)@^ITGro zzZ=HhyhdyN`xt=RKr7#FnTB)&uV%84sn>`n6GBad=d@am-}u@^G6lQAvnFncPvK1S*MjT~J?P*9wD!wGG7>jnlH zmg*Auk1#s3tm4E`+D=3{!fRHlvg$~zM!on8j_6pgz6&4u-&DyO#(vkT=30@Yp2^m8 zOu)0<)GWsEBW19dChzya*N3iV8^s-f(Y0xvts2KrHth&Aa>o(ny-(|+^7c+qeG(F4 zk{Z;JfA)dg{og+_qZ>iIQ@+lRH*j|6uS7S|QcCe_+A^ed-D(i3zk~AkW|<1D5s{5u zMwL|OPn7i4%y_gLHW zec=dT*g=+7yUaS_52xG7#h;HClfZU5@kAX|1oHd?afCkp*CBr{l|TECN+vO#;$dd~ ztO=Q+RjkN30!5;`tShTM4yP{jliJ%q2~?epX?03c=S8-^kO+c&w-6(-e3V;us%+Kj zwGvH2=0Yl?)DL{jl7Ly?+Vs4*A#%?T^UMr6b*-d}rMMHMxOL_x>A%FuD)l-Z%rno* zT~6_gQk<0Vyf_0+orw?>By;Wl&~(}VQm@M3*I@Ks_!5a;WVY|qc_>j`>kN_lkDenk4mopnIBfJV^3+RLm|OUDku`r#RzEWG zj-G6IHc8d9iG3NAhr1w|zVx70_8eUixnx44>k~5cl`MTl9YSGn=O9YLd5Wsl>z}wo zL+o|C9u8@JJCw8EMDL@LAPFg@2 zFW;p^YY#mwkwt_4F%Rv?PFl_to-aAwd>&`u+7~55eZu#+EP{VXo2}=92CjV=PH*M! z9M9L#Q7Lp?yB3t%f1X2?p>ENbB~$%>$t5Z16`A*4N$V5-c80Fu3(;!B;F+WNvp(TN zbyXgGdB>7qovi8W6Z%_!J}04$T@Lr7WG~Hr_w(S#Rc@u;ArcB%E9?bJ)pykse{K~2 zO$R$W)>StjT5fgx%hIf@dfko|TIcNAu=UK3>eMH!IZaFbUWGy0_58Kadr?(*3l&-h z^aK-h=nH&^E%9BunyJwHWV=0PEuZpOl_Yn4$_{BueZp-bhsUQB>nqVlSeR$*Hs5puABK^Pvrf6P2uuFAI!mqu>QqimWN;E0|9Y4^d;%AQ^cwM=Mg#KC` zh9BtGRY&s!zf)99Kd`t2MQK0qfjBwu*^jU42TGQa)$0eokb)gQP+6r1_EgbrgdbQT z8%w4i7+@t&Q*OiB@l<}`Gsk6k{J{5QFVEu#zQB^{n5RyO>Idq%EW`Ib+U)BGK9@ox z{6MEj5a9=&Gp^!@>Jxr+s;=R0qSc1MQ)JH^|D&!7|GFi?T|`Fw`Q>1p{3+&gyL9BM zlwut}aD&RN{J`mIFHS#%Q@U94WU65qhnajeKOp-V5q_Z365~x`SBJFyKtJj+FRBV3 zlp&!F=uy6g{-*qzertU+KVZdb{;Tf*lZ3s(&<_wZu<0zdXEygv(Fbk=-CW|cF0knB z;>E4+0}#p+G1{Zw;zulr!P|!u5#jErF%#u1wzgkFjjK5C&`*^n+oLVvE%EZ-7kSN{S#jZuHzG^1Gh{dp%IT|t-m@=+`y!LG{F@dIpq)1F2gm2Zjgo#NQnS=OT-m^bYG zX``SI^wQkk1+tfc$6obF+wJvGvbpc|b!;%aT2JQ&oh7o~rXYZ2r%`LaOYIo6hq9#4 zt#)c=T(RyKcT^bf-Z8g3^?l{NVjWwt)1BoKrHz+}fk{KHsMXx?jLbqjcYU(BQWTo7 z;w1T|xG&j{lP1hq$8Qzw58Z|lsUP0q{Uk(icH?BOE}|`)Sw}a^9)F}1P@I2M-NFr$ zhRmJv_Xr{+=D(fn5;b$J%^G&UlubbOr@GzvlC1KrJ0ACmBeQb9g#=+f+w;gW#kGg7 zC4=dFRlOU?i2{^N+m+u`N;-kdp(2@TBOh5FPxDBmHx473r#Abb)g1FD8A*DB&%X3D zO)&SqxXyl)Tl2%xVowyB5ZbSY-(G|HA*^$<$+EVP&Xp%`v_Stwuc0*c z#LE{Lg108my$_Y<*OErhO|ricn(s;?k675fu8ddw10G%l1IEsZ6JuKbUgzwmWM7EQbWT~`n&tnvkg|%@{AjU4yf^gkCQb|iijJ2{x zn~-^6;CJLTvz#ls?5^dwii?yX>m(=LZX_AF_EWVo($rFsQ@u*k6M4TaZL{CIN+o%D z^0(|Idmh3xYLN=tm>A#Dyr!!44^)wk(~oGWy2sgu%&@HNlZikj?JI7D9q+X?=*HL zGD#!l<2kAOD?Q0Nbw%#;hv&G79Ys?*Gd@$JvT7KOP$QH-SS zc*R>=sF4kiF~&>7BM@5a*?$WETenY*4}Cx3O6peQ;#GA=#_A;HR3E%X^{iqCGwQTu z$*z#}kxFtD52A$UaqUAdcwz@@#wLzSa{ZTh(($&7F$bugH#@{Ezmzi7Y^nadiTGZe zNxeF*#3ihd*NnA??!Hlpw3qr-!dHl15b*&1iH~evD-o~6*Kn_z{p=e$NXq5*&`-oW zt8Qs?_p(33dC?j2y8)`a3d%baud;aF(ZTa?BB7ol%$-cJH8wT8$IV4o`fcNOlrdA} zj&gf*F{QelAGsDs?gy0by20uJ&Ic`!CMU~oxVa}5J`+^a61U`Vb~&pngSGn2?K3xh z!sK zvn1&fnGCEuY|56ORbH_@^fwwVL6$WDhTv}b4QDF~OQSbLuSwp$A*Uk4V=SVQ%~axf z-=3Or)R`3ORED_tTInnqU?f&og4$ho;+w>Z_e#5$V(1dAwOMJ>2@GD#+$oN+SxmP^ zB2l&aAq$~V!|j-G=H?me@N&FwCRbSOS0cQIS)dGVHRmqTQ3#sgZD-?N%WMnqjr?Nl zN}8?LlUEJ}dh=aqriIT5w69Ea|rr`FcE*>A8uBUhd_eB)q$c>D_(-{46D^^5nR2 z?a9TBtIKQJ1~|F0&0H~F^X^zE<0{e7h1Aa}zJSy}osweDF!Cx`bVv`%43lij#a|+t znOEsL;hF@`xHV^pNIzq3yZ=~wf2Kc~rj>=X=vB+jx-_blc>t9pqP48`cr50y>;)W_`hDWUmYu! z_FQ+BE=g}~bKy6RJJwIk8YLat5iu5QpGd~Q98rLH5Za)6G%l4 z-`k_WsHbjjc%GN=U2Yz)&8TAu{N5FwM$9pU*0Dp8lCue~97@m!_HA2H-HF||hu&SR z^rELn@6p14iV1|>3sQORz?)bm@Sd!Yyz`z{F2iy@(G!qq%R|))BB3zOu@uXe=jtob zY^<&4t#|O9vy*=(_zIA~Q>SXs1#UuEeuudlvucZI{&g6(a8>YNaXY$Q#Cl zh!ngQQAB~8C8R^GQFqoF27i2AAmB{dpUY}~ojiO-a3}7M_)UGyNaTBm`c8YU!u9fZ z3t<)?3Fwp;uhW-1br$Cd-##kTBP>*_7IClgTFLg%vnsi)h&r=8>t{7I*o7Jprz^By zOVJ^owmtIz@dY7+grDu9X=?n*1H(ws9{PcDhfIem5^c*`_Zzu7QbH(MQmx56Ad{)e z+25PD*`jh}f z#+7Ks+%K@&t9BL;ja>uM8@H7cLMMtC$2g6BUwB-|IPh3?_}~6(=saiQ3|U?KI|-_- z1;#mAC*4|AV&SUycVNyW!MT66HMER)k9=Qw)Gf-2KH?1@6JC~clSPR-5Q{WM-d8%g zj)m1`)jvYNVoIu%2|0X~Td?-&b#?V&iSDdhgP-UL%jinaj%lsf=Bp~O!AROe9n7+! zbJg-d|6=!D5l?M6zAxdnFBt?4_KhVhETLFm$a9Pk-qVsD-{{XBVz|LwwaqG#?H?HDZ#qO zU9|+kNX+vxY7#(5>peZUN(|!e4?QoLesLf!tB>4ZQ8^NI4m_dW?#WU)LE9z zJJeTZ5iS`<#{RDi*T|h6PdvYz#xV%odDF2i9c^9bt`s~+wpAd*=BVmwW%6x$v)4R% z9ah#+28BB_*$)n{IlKr>ZbXxf%ujWuHutLc8MQg*l5dbX#JZ954#OWOgG1GheDYNF zcME@0PJ3uF!)S)=wCU#}Kbz9qJFR{gJ0~r?5mrC&HXEg}WioBupR?C}p1tmq&=03k zhE?8=rmOFymWdE&Ek7He>Xr?N?K1m>{-Q=HoPN@dHmJ>s>EbvoF(0!!hPy5H#{8H= zBgF7$totRBNVWYCHGAD5JIgY%SfNxaF=FUcJ<)HZD;KeUBTtEXd|ZgKH_;!9-r>zJ3I12=OOW%gqT)RwoFoj z4^H{kYmw0B1->T_qV$0b3Kb>Fxpq-Vm!-x*j7018qDFP$554hdyS}4s`ES>_c?xCoQqWH z++4a#RcZQ-uUTpf11zG{3&TovdL;a8epukH^_`Jybc&Nzw(LzgwQeFE*qt(ydqad= z%+TWl=QF|~o)zNd#lSl2cT3@p( z)w>rQ=BuYrs$nzIZly8XtmQ~|)Ul0>FS#pn&zzy=3eM-NC2M4lSoB85rctx@G$C4x zPhvk!=6d6%;KWJ%?XK~Rj8<0}eeV}p&}%%er(A+O$3+04jxO9uFUY33=dFOcubmmo z96WmNXA5(#Trm98sZk=JwYzUzEM?7TFt@mrA#gXge0MQGag_y{RVAB>rS* z1S~<$XN^*q`C{$uF9y^N9ddEMlUd@>06X7%l8*`xeIFyR<|$TguS4Wpr4mibIpbeNZ#&lc!?l1}kNpVs1W?3wB>Y9~rb->B`G(%M7k zqd25@?YWR)MA_#=DO>fYSTbcF`WEZD4$7wjvE*58h7b>`LUls9|A9q2FZ}+8L``~j zG_2CK*{-NpyQ#B_WtnNoj?vh*t@}HNvCWv)2MHM4E!jjK;eEg6_O`%E*}=Y(v(^!|AhOt}_8$?LiIA*qY?=Id>kOZ|iT)&Tq z?$_+f3HKO56?uqXQ2RA<^r$_w@iHkyeuoeHm9=|Fu5P7h{itPko%%Tx-|=6KwHd=W z%r8w;fk7Zz#CojX(zUx(35~NcjKZ!&yExU1d{LRwakr)8vdJF7B22{zGK^BLch=B$ zDX-(ejOKl%Qhu2pF3TA1l^UglMG~fE>RWfx%QQ<_+v*9bgZ3JihBCwJKifm08H$!^ z!-@pmfVYR{;F!FTz-l~)N0ubVEYxYV_R!#o;qotWR)U@x!qD6~GJZVzKl}1y)$@2n zpWQ}dJhG)C8wN?B%gQpgo*q!6l4!_PU5_j>taq!m$pS=0%aMB8gYXf0x(d_v$YSUT zN2I1d)j^L&i8@Rt6%l+}fww9_dF-_;lZ~wn*W#T~7iBKg%gfWG`_+OJ6}`4I8E+gq zkEl$oy8C9;&rNjRwlI|jOlF(PyEgW8zI~6;^8}dGokg+^+oPKOV631o_O6XD$0=rA z@Twe`khQOR7!xNcbD;9AJH-cD-uIi5)?HS|t3PR=x+5$NRf?XaCo27{uJ)a{st=^v z37H2fPPR+?fdm~~S>+t3c$h1P;^AeO$Xw(^SH+S$>T3x}7IvC~esgUrLzY@m_H&ax z{!nz6?AWm7T>ne92&pYVr2O7LPWAJx6u zcl4FOibTwEnRfIYqCZL#!tM~+I<%(%$8%8nSgk{;*wrE7g?W3{I+KSV%}CU7 z2T9vQGf@s|b^M+)N!KUrKj<`&q|(4&=_}rPbOX04%5I<*q&;+4FR`56()B3T?8L8r zU;X4%)g|4|Ug=#-$$GZXy(-a5#9pcRTE?E+y70ffS|ujK=(X?5$M(#j;S5{PO4}S_ zqI?}OtLCelgA!D*So$Cohn~ZR>yyl%W(~G1QV#29>7A0Xb|Y07V9VfHU90(oJVv-? zrHj1sTA+{VicINsgeoo2)@%tO4RT+MvYrqx%vyq~ezD50RKm>g66`jGy$m*$Vk6>@ z?eq0N9&TXFsXgxYP@-Ntb}@JHk+G=eu0ATv4lw=5wv03V{Mj*^$iPb9cif>CSbC`E zj`8R}Twm&EFD1H>00RxE;nyBozyx3fGCnO#aunAfqqaTtq|Bm@5vfM3A8D2({%XAF zg}9&-b$6H(rj84^+#Y(A`kDAoqOi`aOEWvX>m(HtG+Z`0gTUpm1fJekWqhhb0UE{J zy{3EMs>@ht%3pg;#r(mEJ`qNV`k;y~ST3nJRgSGU2ob9CC!CytJ;r8HH)%%U8?wERieG+=F(n}0W6-rq@QgNkPp^D!7 zM%Vj=5_7MUm94F>XD=3wc=Y}n3l5#4J#-%ytWOY{dfyh=SrSk9>wU>6x5!f&S)s*< zYwLZSG8xq;7qapW-7CxFu=^_Eb1lI$?++uWFwTONs(4mClJc|!Ce{?_dT-l9>N&7m zikPVKU{{%4JM@t{WmxB;V6Sf#KNT5a>cw}ax>q85Tl|o`>Wzn`Nnx(zMYX<-l*StM zU8*DWP#!cQym~#_t)zvXVeQzY#r~7F8#A)rVNv4S>oVDYusirPBsI>p?x4Tjjiuf6 zv#2rb*SxhKi>i(KoMa>BUaz|y&*t@_n=nIne9(aKS)fb$<}IbfBqXJ)1n|x6p)6TT z+tEvmUw#cp;xn|Nl3#X8y!Xzc*7;|(O7PSfwXSe`M4uAL9gs@4on7> z16cD48d28!OH481jxE1bMXS^(y+;O3SbV8wsf0`2dZo`iu~S%^a>h{z?Q_m~|99lH z7apwYz~9i5)EbdUIwCxru@dRNx4iZ8{57?`A~%fDvf8@db-t1v)h4@h z%bg5bou)nXcU)-b4s6NxadVW5P};jf=IJQfi)e?k!vDL*I-VzXYxk;kgxT8jWqVAG zKBKh{Ug)-VEJhb%;|TdK8ySKN;5;F$`dg&oF@4ViF|z5)=NBc+qSR!xSOb|tBRM5 zX>UJWO=G-&S7rcywLEy}LvIb*`P+HjFk{69WROCv_3oJ}x=DEXeP{5?AY|dSMPC`O zYs|?oWAJeO;V2w$GC)@#J|e^N5gC?`n5^rXZibQu+4 zdnF>zFqv%K*@{k-o3z?Fh3sLb#VyrQc8_#$Oi#~!0{M>>=y zzSG%6lruUHiM580(Z764T~s4N;=|Bk7NzzWZBr4o@<{(B5p0-8^0bMSk>^yUKAtg~ zI-?n?W!7gi28}o*$}Ep{@_tJ(hY7qPQa#(45Xw@%l^VUL_u503GnX3GMT=|XM{KQS z-S?^8h-)75I)pXq&vp`b65XnR=cCZe=PEUX1v}!D@P zVS5f@LPm8FeItHEnbGw_JvxfidBj%sr^CZ@Xm6w43O>0#^e6h+@OZYDCS;Bxlhyg} z>is^)o|WeoPLB;7xDyZAt+8@$WMVOD3u9+S&IjakON-_`l#P#)z-XPUd~g{`R}ZK_ zQbodQgzOw9Db)O45JV~Aqg>kUsmpGYTf3!i?YgYFXQT4&wA_jgLuy5ZAhYBWN!1;N zyDhKa-|`H)HVSLc3iQ(?wGd5svNO#6OWiV_ybsEniq-FUOY(b!&Q5C7^{!H0LgoK? zU0+Sh5jHx7SiF}rLW*%Oh8Ot?BV;vdHFHEtXxC<0a6b%*436#VAMns`VA#m4 z*2vyVow@fS=kVlR^$nRXSho31ndIb%Tf=<&Qk(2xTBqI)s#sjkKd4+UTDcy_t7SK= zcrm-akUQvq+S$yCHq@a#U-r7c$~^IyObP4w3HOFfaX&Frj_pJ!JM{Tbfa*wNUc z{*)NBO?;O`uy2RHbB5?4b8j;L3nd@g0ZV}9c?U&U`@2NPK{gFctBkaKeZHU@(~II~ zEZctWY!8bb!qwtwz9Wd0{YpCB7#R+&`$@@Jr|eZ6b+={KpNls>My@!SyX}ZdUI^ff zKBo>#ge+Eb&Z8K|tA(|bHd;)fSA9EECGM(Gqd<365RYvH7=IIURv{TKy*>0XDRo#O ze+?pzj=GPct<;ii5~&Q$D?gL)=^GLD%5yeqtBP#x83W{NRNJ>o-AH6^aw6AmFJQei8}{ z5j``{+XTAN8e{cS5FZz&RaaJerVWcSc{|ckp2eI^^iIBVC%a|)sXig|b;pLdoJ50J z`78w02{rpIG!Iu4 z={*7^%H&fhLNB4F%YF(@%bhC{LJ!G=7j_oVu_@6IMvtKf$Y(@*p8l{Z4JCW}Lye-$ z?$^{Hi7+Hf_tRLdd%Gs8LH}H}Av|>Zj&=%NGJO6;kmijtC*Uy6qAhu1%^6Osj4@Xc zA)z)7l_c`U)47KNHdmy4eTiw6#|P=ZBh>99?JrLgY0Xg~GuN|&*Tks0E*6SysOwtU59ClWcx%As5A?L*8$u8Vma{T*p!k=s`U9+K(YXxrAok!|BCB3_z!fV;`O zUm|Sb?exGgt-6jG*XTOiDk3fI0bHcfEB2~l7;dryO?b}3s};rIUk?$#pV?{s@Ho$7 zC|7ku8w%OkD2s#VQHc&>I$8S4!!p<6J`bHK=IlN|^GmEOdz~_v`(!nXx=r8xzNlS% zw+_tR7CTCCMn}XI-@eRO3l)1CT5rVv4AYbOrmv;t%0h8*3)3zFjItQFnsBkb#MH$}5jdy=2I+ zF~cTxke79tRm5FZnA4EC-wJc?WM0HEb#R_xKcnh^wR5u&D?k*6V0)-_Am6Pg4}*HW zPHx^OE)GmO${aRNMp#2oHA_7urkmEJ+;e7k=v-zkIU&h!sj1s|gWups(JZ+>Kmg_k z&tZ1{?kDv{dnii#Ua@KW!B%xgkf85_(3RpM{k)NQ>cPKvE51=z++Qk^@!?cv>N(8Q z5B|QJ|16zfn&gbH9cR%{G`1DD9i=?We@Jc7MlR*3w&0J$*C>(`pQ?7QO-qPzJtD0+ zzO8!tN89K8U)JNULUFV1kyhe*{f5wSN=M=v_gedv+hhpb^P&7uLtp#UUZ1^|{v=Mq z?yMiEKL60!+PUwtj>7E^t)e{ZrJ>KWs15a#xzD`mug}GWKE1vd>#+T$I}UAwmD7*v zB#H0u05r)Ks|;KB7Sm~B*}T`DpPaSqkwJ~iO=#9va#VVKu+u&bd5@y(!-7#yLoOCC zqL&*VumH9kfGxY$u$X2@tMpZs+`3<=mOrCp{;5xRj-O#vA#y^p`lh&hn29YV%Ened z;vP$XH&K@`T4M(e-S4eY26#lDj>mV07K?LH+Xr@^2H5rZ`h6;eiA+yXo+Z- zGUV8OYU)La^}IMVdsjoX{aLM-<&It!a<0oV!xc;xhF<fLM4fOZms;mWif7&)pY*MW!42Q~$CrQMz(Jzc9}KSg+l^sn@lXhV9dqU<3}fd|N{Z{xc6W*=vX6!F%i4)%WByCQ`#P2uBJQ@}QL~Bv1B>tp-M2m(hzm-rJ(W1HfN|xoMhAGr<3L78RqWRo- zmRVhGnY_pFjA+Rn_}%c9D2W~s9qX3#|2i!>GqNS8%T5`;+wqg|zIk0=iPn-A6y^4f zrzPKr){+9hmb@tv>6T=OPQz|GJC^9oGR`mi9i*aBjDPCtP4g8;KfEUTAf3mY0{!gw2`IMc!X5#S{xva3Xu%dWLpz@Z= zs=^h4S%sCA`O6A}RfW}6!Ih=?tMZFW@)wsB1|~|zKu+fDX)|VD5tux6-i!sAft)#+ znX_`{Wljssoj-MIX67`$O`dYq9Jw+lb7tmL`C=uKY;!WFPR`DDzrki-HFsVhCwubj z*>ZX6RkP>Kxk@LQnw>d$j$F){Jbx}J=g+=!_Ep!+&YL@L^1RHzwUcLM2MdZT3YSzB zuPUqzu2@-F6)ehMRTwO+&RbgH>f^!4mQm1}X~63-hZAtxQfmfxx`USH!NiYIT`YZKYd|Cm)(DE-5Ko zmR}NFQj}kTyoD9PrDZEi3xcbQic1QEl}qwVON&dF1*`Ix(W=q{dcge}TwPpM6f7+Z zR<2ySw75D@NWQYA(u&3TRmCe*rqZ%1U82pd$S)^Ll#5GC%2r1*m4!F2EG%78XfR>` zc4-bBmOCJVQ%injW%067dZnbQxSR$dd?o4)Ru$2>{1sAcL7|lAlRm$6Nl{rvlq`Pf zON#R=F@uOI@-2dV-?9uOzx0;ilCsh&>|#W4cyZ~Hl9dJMdbko&WRibkFvsYdqQdH6 z>B<$03o8P}rK_l@fDu!?goa^VD@$)GEn8h0ETk*T3*Dj&s;ca!!ctwEYYzowOO(Y1 zi%ScNm*iJroyDbM57?z+G?`aTk8;%&*UjN%smfoBZ55UVOUlY_63beuN-jVN*i2ce zlTdXi7Uf)6TvE2=rXcAmZgH-OG2K+?{TmIeEDR`pyG9etUn;geJfJ%?f;d0C{ca}*r z-7#;i2CUH;0b=l#ysC-;P*J$FutEk`LC{i5ai!8sLE+Nk(!v7OKFgvc+ocQ}Qmn|o zg{+kfso>IzvK7IVmC}#-TrUq6qh)0*`ITI8MyGvwL{Pk3@sh%e#MR{oY#DB5A&6C$;Af>qZJ_z(<(Q6gTzEmsEWOB_FJVO| z-tlGW)6G)L2dQoga7QE{ zb8ufiXI!7Ug8z-t{~x8kk5>O5qyC?!{y$dzf1LXNCG!6XD*XhNeu7FrL8YId(oaz7 zC#dujRQfcPK24=hQ|Z%G`ZSe3O{Gs$>C;qtl~Bte)u~h}5$pwl;4mheiVEyShXlbD zIwZhxjV!MyTQah;uw?1T!s^06N%7)9phWtV4`0>4ivt%|mdW2`WtCMECl-{HOq^KB z99LM7NBWBVid!a5EGf$`7C(JwiV6!$@^UJck1Q{} zsX9;PE~_XUSy{1UQATSir(kC((@`Oo>y=~|KOCuWyORYBr0B} zJZ@fbX>nCCW_4>}e6RDJ+-y zDX+Y$A{cS8ps)(LCr+e?^K^ISxjD)fFUNsnIoGRrDbp@0c$t4ejOjd_TG^7k8i>W8JMz(nRcHWnn#jCSSh1?m`8#h` z9;Togsy(u9E%VbYcyI~OtOnQ`t}M@6Q7ExaUjC9Lc!czMlO|4-#CAe!kkd>>*|Wq& zljs0EJkh!ChIy{~qc{hqy00yO)16Vu8*X)Dw0^8ykzY|IT{hB{UG-jhb?}_af~iU+ zF~l(@#jmQ3;Zc-PSykY;NYUO325{bDMsVH|9L>auGML>Vj5=fLD5_AGF}HoKN`k}A zzhKw}qB{gBUc%Utsd3^&%trNP#mXgB#JT`2_ha<5R&$<`a3<%gKDMNRj0pLjl}@HvxD0-wQruHz%K^-?~v2$A_q9M4of=kd9W&u~7ud{X#a&Zi%r zZ}PF{_Cb7K$S0l8O?(FM$>Vc7AHqBp2gu*D&c2(^34E^LBRV~c&$)br8^UJ|AKn=d zIGv9y2u|gb%;#)AaxmpeKG*ZP_1fOv7x;Y4=alPuduQ^wgU?nzf8ujGcYkN|xtq^R zeE!VmtlZvSvO53fR*fE$H@BQ_T*(TkK+KTUNR$vuGt((szRVu09LG5AH%5)e zZ`f58uP86cD=(OlGkb2{7{=O4o zB%=Hols;;l>jN!8QkRslA&@6BkYaS+s5Ei)ZZfGvYWY7aKh>Q|?6M90j7nWy!Mae* zBqH%R9c+yntuaqUU|J%l>FSFm-!WT=CMT#u=-s7d{7>e>vWi%BneC5K{?{$eE4TgE z*N{K5hbZK0Y-hA+AZ?a5^e>~co3QpkULL!sSLU7^8 zK;XM4@y1;6`zQDIHiIFs4U~h~2f(+%0O8RUoE{kpe#*()Z169fvZ(@VIkDIb?f^4J zG2e2EtO#rd>%dFS=j1CjEM6CQ4X0L<$1rDdo+Ja5 zgDnN%KfpS0GWVyqfQj63-vho4_JF_PFvrleK;Q|EZe)Yj3AEL4RNYm_$%f52k`Y19QN?g5}^OIT;5o0$adFuoHX*>;nG;CJ|hX;~AAy z@K!Jfd=4xJcY%%IXJ89BnzOE*;Bv4F+yW*MKy3$8!S}%&@Xug57`TM|;0Uk<%m6#V z1z;EW8aRl+?N4AD*aOZ3&l-=Nfm6T@puB-%8(0VK0S|&lz%87m9z?JeoY>nt9=s1+ z2v%H*-GO(58^MRb?ch`3UT`zra2U89oB-|x zcYxhs+$8b`i9f;d;0SObcn4Sw1}?`A!7Q*9ycOIB-VgSGo4^zTV|nf<1DpUZ0`CWF z!GmBkxNtJ#6KnwwfX__9UI;8-28V%rz$|dkRO|)(2y6sXr=fRnG1v*po3gv)dM5ow zfSLoQf=_`t;2y9X>^GhK;Q3$+m<4u%>%lH?2be@aKJ*ImgPXyH;QL@T_&K-{JS7Xg zf#blv-~zB4yah}?kAAq4c7t)VksHj(pC7zZAMJ*Tvp93?%qu?Sik=VKll%Gl208RlngO7q8U^BQ6 zd>iZme+woNxMyFF9AF8U13n6tgA$uJg71SZ;OAf`cuFqq0LOtz>`N^GQ^8eW4)`co z4!!|4f`0{Dz_V^3KR6rg0!zUp7BCyZRB+gh=mDGqR)aO*MsORr9Xt%~1y9dI|KJEP z`9juV;CL_>TnOF@R)e2_P2jji*ezHJ?gQ@zd%$0SDI+K^zqdCXyb@dlJ`L7_KLeXV z`IYxJum?N#Un8AIt(91xvwZa6Q-tZUqm3`@s0|fk0+8{smkJW`Qq&CE%aH^QAh+zl=O z4}evB&I8l#pZgBjqf;3DwXU@aK@Hu?se!Cl~; zb+i{8u#S2sVHaRJxE0I=JHZ<8?_d-7(tYFu6YG0>4}uqi@t0FCI262ZJ-+}1J_8nj zyTG;J=inxASOfXNHQ+(;Q7}G(a>1eCYv45SeXsz`xS#ys0&o+U`T*k!tOY}0E0{PL ze+Ui(yTL55elhXNB@Bt;AXiFc7V5oA+QNdoQ2;5hk<_wv%r3v>3?u0 zSO*??7QYAfe-3*Dhk=K|iQs_Q_?hSFf3OM60e67q;6AVsJYfs^2hRpO!MR`;SO_Lv z#rh6R1)m3V!2Mu3c+(Hb4?YRDfbW5w;BhaIAAA^0%3)pvQ^8+>IbbhX4xaoX`N0x! z8+bps2fU+&eh1$Glds0l{Rlq>js|nVT(Abb32XxI0$ah2;6CuzU=MiQR_3cYEQ`Q& z@J28f+zQr!tzaW~2y6jA2X}!_{TTg${kNgNxx|0q2=Fd21AGXa2mS)A0^bDdz`bA- z7y?_tZg3wsLbHG6hi4VXuFz#jK28V(* z;9Rf?tOi@b$H9GI8`uM8>_qNsu}5$kcpq2*z5uQTFK)yB!71Qwun0U1)_?=9qa1Jq z_$8PF27iJ5fw^EK*b26Q*{|R?z@wmSpwD>~{|mkgW`PO27C%4ju*@!J}Xcc-HIW2W#G-zraQ?WlmPBWsIjiC% z4xaRD@`FRc7H}rm308q!;3@CZ??uc%U^+Mv%mp`qwcr-88QcZ7f&D(9-@tL8+*B(9 zgWyIm1AGHq1bzuNgXw$82bO>bz!p$$2u}MA`M~GE3~(>F2u%Jh^@2rUGk6Es20jHI z0C#|LGwxk52>uDo0Q-MPesBm_3r+-^!P#IN_y;fq9szs6mVMYu3HJ(rhrNJ9z+CVr z;99T)+z4Lu5&jLF2zG*RgWcc(aKH-INBhw`I0u{tmV*W0W8hlw=inyrZEzR(F?bN% zc7Xh)wD0%$SMZ9DsUN%!tO4cUAPs>&x6TRlsZQ#1#(?7z<$VD|xt_u&dDGF}#^HQ9 zF=_gV$ukEYzdErtaQW#IhmRRLM6yc$X?$wmI@-GkwExL$Q^K`X^;p@yR~5 zxAz>mmU&{*y>U}d=(muH`BV4}d}hOs0v*1{<+pKp5j>{t@^QH;f#l!A=b0G!kHG%~ z{uIzDf0kSRAlm;!_-~s0OqWlCzu=3by=MzQ*^>V{m!AhOd)FgPe!0t6!9Ng#-vIvv z{OM-?`ELGg@EhTiO@6M+?}2ZGS8BKAD|GoI@Q=a!$v-HL*bZL$)oI_IZvHg*pU2?m z!T%n9p5(XtH||PRfa-tv!O6Y7lT3c4TmA<4G4KOTe!9zVgC7EalF4Ve{2us0@MoF4 zp}!;WC&%Ci^~I;cpJC>o;P;m>|1DF_8{Kx~!q0_IHTh*OUjx4cevHW*0Z*jd8vYejN#@KrI&@3HbnD?dn?DaWxkB!9VCK4T=#s3U_k&yhy?QoD~9xH2rV_`zlw*)CrT z-%Nf#8*YYw3Vx`W|9Urn8~iiy!%RNUY>xHF;NC;~A{?OkQ+k__G4i93Ty$l`&58RT)ypTKM59y}h4!_>UZZ6Z~iJe)GXD z_>W`o2jSn1!N-4tdzJ7PnDsAmbvP7$H~i%$zslvO!5@bA8z%+uC!X2c`?#4uZiCal zweaiV{cL0t{M|A5UGS^n{pQ1i@I^8B`2O4jfxpWmU$rCOQ1~72SD5@AM*HDEhW8uC z1@P~~M;m9V|KWGTUu~8jrzi9v*EYc)h4;uOHdg7%&_SBqv;1WY!LNlMZProj=1;_l zJqqvFhGFpc!AEO@$e0CR3twZFf5rN~YvSY7%rEUMA<+2B52; z6@S`3PlrFsZ_k6jA3mC{M2;%>weT5ycVZ7~UJ^NEJa2-3gYWT`h8$VQ@l#ihR?3-v zPISAGdiKFr!~6Al54?ISGHD$-j5s&t1op7Vf3L~M-L3?X^3&myhxq&cT#Jup*OI>m zekS?-mz#W?_UqD* z>lt&0;n(s#{--lt9g95~{&OwmWS#3@&n9?zbFJSTyXzSI!DI08Of0d=A8PT@;y`I< z731n!6%El_I%a_tUu!0!_s{#&Plh6bPo;d?VTm*o(@ZQ zxlSkc(~4Z%hx^a%``}-KznQd-eaGpAwB+xBPrT5dPe~#^gr98Y*VBR;=jre@@FPv$ zn)g-zGrrctkLp7^_Gh^=(EokU)$0sNw~cgp73sGBtB;J=db?Sn{;Ne=jW09oNF!$KZR8!KbhR6s!L9 zWAM4h;A@V-H(C4`Q@_UgxD|dh`ibV3MF0EX$H7Ol9pQW6r^nz^2!Eoll z>Ng?mw#D^2`ri%z1-#!n{V;s+4@Y}{fozU$;=vlXN%#>1gl6 ze2>4-NH?RQ@A~*P3FbVq8~OH;JH~)6{+b-+vJQ{cJax$)OY8AXOV{K!{v>83;W;)!Ka$MasRCcekeRux%rLzoGC%hl)y(@KR^Z2`QOFx z9ej8CQ2Kd?+fR!~^Db#-nQ7vtsRUww^1My}AJGKF=cRkgx!)~kbC7XHI?3bIW!wkp zfUk!4(?tlrG)Df!bMVdZmzw2Qxb+W%zaJizx%FFpLD7NgGc`|71>!eTitXF0+%ifi zV>4y=#h2^hcfb#!3@87!ZvHLst?(C^ym6mmH~eexn6{hWxbJ-!eiyvo{GLw6H{fOd ziVsb6%gEO<1i7AyaGj(n=DQ=K^tsU&^GGw8xF=eiD`ix{C&DiXFC)us>qgQ{B+VsZ zX=HanOlCX$9C(`K%CXSRzZZTUyq_+*t^Cn!Tgp$yF)SwkShIY!ldsRHjEAp=zu4rB zd#?-O?}g7Wc_UV+hJOYgExYm?vC2mHHh4c<*$)41jPm!we+C~dR+jd4!=FFd-+v}E z&_=}I$HR|?XT-Yl8~0-t!q0|ZZt}+7@a7=zf&3-buO574 zhxcoPJZC7p^1IIvE!g@t{O&=@csE8FX)>1JuSUf9rA8UXJ;;Tm3CytiW4e*X=#T7g zp$pPXG242J>yt|0r^EaCl=bk}!$B`jq5@Fw}&+QCC&Xt8nNSd+;Nvhy84;Dy$zD?maueIo29&R{?|pi`y^d{Sh^aw z?L{o+=3MC?Yt+HdhWGQ=o8hzJr5l`fS!Z!X4td`5D)?7Kjz6ZkX{24-Tsh>q$Ul>A zj#*Be-pmsnCo#FEWc&NYRQMtAesbo(2jM66p)gzjeaEUrg_K_oKWUb~9va~%!uyrq z0zV#pv?;&da#wM0C;ZG9d>4E!{Pkx3I34t<_A~i^2j0&HO4$)98K1I_aF zku4=(IsC2U_v7WP>2mmDGk=^8a-{qg_-*i~n7nm%Gsv}0_~+n%WAb7HZ@M;cgfxq0 z`=8qyghOqFPY)|Yjz)c*)!U+{T*~>#rySvH;5*@u_l%V| zXRI{Aw_fER54Xa<4DZ(u`>gyjH#jmH^Fj~&Z^`ecr<9BE74Uv@TRQyA9RIUdx$tw~ zJ$7WoNHy^C3_4T2E1wm^ik^2fR?FdE=X?COSjE|T7JL4gYtOqV=j5xSuXW`f;X(L3 z`2KvCe{xNpbDqyN`7ZyYKL!xY$}{lM^dad+z~_gRBhN=)!?hEn5dKLy^SGA7HN3DZ z^G&Y2RqzEd_zm#YKD_AVAmevE{6@aVpNq7nUhdQNNV);oc@OE7{u0B|8TyNddSZ^h z{)WOIf;aUyo@>A7nyJ5Ru6@Kcz?I3mA1>)iApR0oj=Ue`4_q_#w}ET>xaOz7ZSY+& z_&xCPbED@My$r?fli`*A;!$=K{YgKjr1A_2>HPduI{d9M_+0oBcxrI#FxE&lR(`*^ zq{-s_=DJq+^^`x*EZ>-G_QBV{PcZp%*A9E&AA$Gt4=K2|t?)T!{y2TUH^{Yg_>bZD zoBoTj+4mj2hbTH+M4Bh&`_GrP7Vp=FX88Nb@5i^n-vRG8Umk$(fR8p`ihKc-`*Mu( zgYYlF`{^(PUdlgN%ChaqxHq~8eg}Ls8xUJ;fsp*q@jd??lP?W@g{Gjl<2 z?`>v1ae9L$iEHw{pC7>6<4CUUrf5w|X5j3$lY{Xp>MSRcx@ zCyla2?jj1<$hA#;kN*gVWXmnS`B5!*5N;892VK+K`%}Jq(me0BZ7pe@BaPoU*mMkj z7yPs2$ECY<80WMO!oLI`ZJuN*52U3MQ^8Nij^ocY+H&RneH-G}C#>n$ceGfv=r0wg z^wvWEGh;dMpTT2xt}Mnq)N=UvYyIQbM)*_Ur6lQ;G(JK@K{M{BF< zfA}4DR@8m8sVGa z=X>(IXFyxv-;cp}!VkF4e;>39J`Uc`pU8Va{zmzJ{vs9rlNfvs{73M9KD8Xa$0vV~ zHaEh52EWT}zm6-_Do%8`jWiF@20tC{fp3h#AA!Fg-fz4OqH`N!S` z&#Z!f8vbOnjfT(M059(Znria+6?sG|DD8*e0sovi?)(&v@bZ2j zKOH7B0Mg*2$tW_6hd&=)?zK67P0P^VmLZokDL43^$*zH)2Ja_B6Z{nTbEv|p!`S0( zwetJ{BmX}5Ph#*r@c)Xzr?5Fa@J9do)8TJ}XU1^#m+$)OT=;w8{d`Rg z{7QJHWH-ODm(c|OZTM*Y7bHt7{H^fUnfYb@HSU2OAWaKtqS=s?5xA5X556nBjE~)R z$UA=S$m3aiGmUZ2b{hP1@E)Hna_CS|#T`YY*+-gaZIQmLgMSO&PnU8_X)nB=E<51c z;ZHGTG@fYn=$zKHj7kIxIr4If}_<5%M#@X1- z@E0#~{zZc`}N4fpp8v zvg7o_jZ*h`_|M^2cz7LjNxZobermoeuUsqP+61o2cljsf$orbcam}v{@*bzmuyVF> z?NYAUv96TU!L>B5`PoMZerOCnaT0MVykGwfgFg#?un2DJ%ot}`R{m&XMC2=i&mceB z^=^LS-ew*A6nH=T-3&h--f#SLzz>hXhu~9Ul%IGxdnoXeP5I=&4S$RL!{9}~etZ`E z0(d|D6v4~;>-^Sfb?_VDqpg#q{>|`D!4tZ;`ZLZ$bii+qQGW>jhwy}dZhq^2ri_d6 z>73<;pW26UG4(7r4SvkpzE*lj&EP#oi~Y-~rJT>;RXOMSms3qSCl>g}I31KT8Xor@ zi0^BZW85QcrHm}n%q5Lulg4@eeegB#tSVjJxIfkd|800mcX{J}c?z9DaGc<7WEd+>*@#T$e9}epH&RXww}M`L)CuxX)*X*_;K)lHdF&Y9^TJJo8YIw``KtK{Ja?T z?}MKXAI%1bq0$kI0pV}#gWo%s$kq0H*4g^L*|L*k#lJJTC%4>xKFNYFfxp`9E9?A> z=&A_*ad^M=Nge!p_+&G`@l5$<__grS`XWf44)|5@tIYgj&&J;KVbXMvCfeL8G7h+s zd#>>3n`Ib#!z19|h4-`9Z1_%izc!Y@?}U%m2C08N{EuRkzXiSpK3WVf`FF#=2Jg4V zJ`BGH{z9{TRy-W!+5iUX0r*mr*Yk#2_(~nAq#1sbzYcQXhrzSG=-QL9KVA->5hH&i z{3Lk4IIjhMHoRXScEZnr_v^zh_=Pd@C(YvA0(`VFquLLDJ$y8u5~RtsjJX>4%lRJv zhm%|#ta9hZD$3YM8b80V0sb-g;gsQwNn>Aa8~i4CKNDe;#x9ez;^J{Nv5yx$yI1HTa7uN_VB*T7$I>cKdx)C&I)yx(}*2fsE3 z-vhr2-p`g&uHrWY;4e1oH|}4j!+#r|trfSQjPoVA@S9@PUjzSW4894z4t}6nzHxuM z6}~zKzYl&Hyr29%@Y4Q?X8A^ZoyaxW1 z6=CraV^ChLBfh2yehU0GX8yR@&Yau|e+#^y{QKZb;Qf4I4}1lDH2q3^kj?n0f&V_= zu27XTztI_4Y3H z@H&7Jz65?Tyq`Z>4_^*1bEl(!W8T~X-w2P}a``yz5LNr(+u;4?o5S!g!Tb690rOci z!k=oEuZNpjGmn7Z8iUVyn<)sk*) zxqdfm{5eKCRfj%%SVj52Bn=)#{gd*ylTUspMalLL79I9lBuqAW5BY^RyRrqzdxX5h zxK_yb_&37y>N-Q@D<+Lu=Lp8bVy>w=p9s$v=jdZ74*2b`I*Z6Fztf`XtPIbq>&zwJ z2^DUgVx#3;>&G>}Ija#q9zL2+mi#U7C&K&La3}mp@F$bj(V=m+pbNe)d^8)Ce#l^q zd``RG;d}i5JI*ab`uSDe&yuc)bj_6Wx}Qqnb&Zc3$lb*sPr|?Y1wQDL@ZIAA{~vpA0v$!wZVjL6?n-rc5{Mx4 z6c9uaFh=IdFbFaTVJ2aUOoAfB0Z>2)2#BBv`)k2^9f+t?{xqCfv+~*$m z#N&SVfuQ)p?>-Y0_XphfgW`>V`%_T-5peGbiH)xNct{*{-8VyGah&^YNW2~A&I*f@ zaZmbH0fQaf(PBoVI4vi*Kl{ZB$9>Z;UUJ;0{9?c3F7=B)9QPleSn6{R`^2L@caKl( zkZtgR&%G}o<_9pSP}9UzZ0hRXDCV&G)w^QDGtPs)69MsDz+D|DcB5EvVoqFZm7vaN z&ec#$RYl&Et@L!jT^|%L1!SGJ$IbKUGB$PFi2m>*i!!}{qurH`SmM-ETasqU%|193Fl7TC)06&IlHoolX#Ik-D%{G@*`XIrd`!z(pTH5bic387Xd%2 z^G3k`t>4`k@XvCiSZ7z>?O}Ibyf_wiSH+9J!?n@W@yIAr zT=8BzStg9HafQy8K7Wp^v>jilXVMh+xZ`Yf{9ic!IkK6IQ?&!?ve0p7`JH!VllgOe zz8yaQgXhGU=pJ;OHIDyn$FG{OL=5EdU-~a_f=zraoK8A#-TwdGZK&5m$M=}yJjY&; z$#s28-Hx&hb-#6-IgamL$A6+^*Qs>jalS_#XLEEoIY{J^SQj^3dt5q2Te@jS|Ph#umP8Rnwg>JShW{QWnp=>KKFu%<4iH+Pb!|mL=9FZpps{iUaRWnB7 z~)c!w32A>to!+=m?TIwJ;$ zVLrZ7M^BW|Te@S#Y&uJhn_vUCyXdUD{~YRn+lem4(=5=z7{qTfpVGSdoNcIEA&8~Z<~TVU+}vLOo2>d*PYJVgKb@O_(TK)LdXhWEd%$N9=< zwwrwZ9sY02@qfBK|6P4z{r|3fDX|IuoA$ncGmcD{Lh{ashWGy#|8Fh#zpLkew_X2F z#rb#n{Kx;F7WhBa0zA`G*+s9*4gSODKdwb{qt|6RUmCv7^NHq0uS@#>G{668I^QMd zDI_*Wmo0i-rueVYoj>CLy&m4`5VgDLHDg~9W4DR1Gh^&gG4^dS_FXadeKGb*+GW_3 z>uA@YoqCNfS%PWmG~IJXhgmXKpGV`@vg$LxtUiyzFPqiJXi&Iqr#=tSFEs=C32G2{ zH04COTFilgdoJp;Z?48T+Jltvg5T8B?$S+{FP?T~qAnGTWL+LJ-U^gB35|?AC>rWh ziI{_XO!8y47k;j7Q_lQ)nh0e~eN295&g$|P?9+Vg<*GiW9>uhi3$_1G+Db2HtpC7& zTHyby7Raln$9-(P6z;!i#B^d7F`Jk}%q8X#^N9t-LShlIm?+xoJuZouOiUrB5z~oT z#B5>?F_)M}%qJEQ3yDRKQWn@LQEs36SIif#2jKSF^`x}EFcyVi-^TU(V6)ZlZh$BG-5h2i*~A=TE-{aoPb?r75{rn%L~#xCCngh9 zh-t)hViqx*m_y7Z<`MIW1;j#P5wVykx-x%aGBJgiMocGW5wnRo#9U$?F`rmKEF=~Y zi;1Ee^Cu<~Q;2EAbYd1Uo0vn)CFT+Hi3P+$ViB>JD7rI$Vlpv>m_|$|W)ZWAImBFI z9xCxh}py(VlFX{ zm`^Mq77~ky#YEAY`4f|gDa15lIx&lwP0S(Y67z`p!~$X=v4~hq6!L+?a{LjKi7CW1 zVmdL4m`%(f<`VOW`NRTZA+d;9OcZ^YKQWn@LQEs36SIif#2jKSF^`x}EFcyVi-^TU z(U18PlZh$BG-5h2i*~A=TE-{ao zPb?r75{rn%L@|K*6O)N4#57_$F^iZ@%pv9y^N9Jx0%9Sth*(S%1DQWDnV3RMBc>Cx zh}py(VlFX{m`^Mq77~ky#Y8cP`4f|gDa15lIx&lwP0S(Y67z`p!~$X=v4~hq6dBB) zm`qF|rV-PLS;TB&4l$RQN6aS{5DSS##A2ezWd6itVhS;hm`=L#3y6ipB4RO73}ODnWMT?2jhIf%B4!hF zh`Gc(Vm`5eSV$})78Au#=1)u}rV!JJ>BKBzHZg~oOUxtY6AOri#3EubQ4C}L#AIR$ zF^!l`%pztJbBMXbJYqhvfLKT@A{Gey;yUI}OeUrf(}?NBEMhh>hnP#u zBjyteh=s%=Vlh#SVE)8pVhS;hm`=L#3y6ipB4RO7jAH)8WMT?2jhIf%B4!hFh`Gc(Vm`5eSV$})78Av2 z=1)u}rV!JJ>BKBzHZg~oOUxtY6AOri#3EubQH){!#AIR$F^!l`%pztJbBMXbJYqhv zfLKT@A{G?F_)M}%qJEQ3yDRZN+Sc=%Ey0ctU&>oVO%Bd9fP+M?~+4F3Ub z^>;nF?K$lqP5&6$#{Vzc73qJ9w)(3KwiVF6oc>>9?3&N(_(rN~LEA_?>9o~fSP)|> zZT$9EeU{ViMElDayY^NcAOEOPpGmaw?*R4LLc1*O9kef?{RwR9jk)tmB#fSU}svdx^H`?@wr}zc(U=?-iXs zjqy6rZcckD?GChGp>3qdU9^pq`aNwUJ^n@8jMt=Bb$;sc4v5)?w&ADKHvBQPvzh;= zw9R-tNxK653EOpi)4q*q*QLJ?ZKL2%rESLBL$rsGe}eWd+ONE(U#_AYsi0z_B`5Y?`pmo?^(1>yv?*tyzgS{itm+7-;B1|KL*h@^T)%q z8!`Xgw9WW#^1hBYhyHD}4gY)Ero3?0e9R%%7jozQWN2_jApce?F3*PG4!;ly@v` zQ~$eZ_tkW7O&S zO?x%|R_AZ*VYE&CX3#eEdxG};Y>yV->GZ}wBF4U#b_?=%#@K(;Hv3P5LpokL^4rih z<2f_NKR(94fc8yH{|D_}v^#&Vjg zeEBZz%XBhv@<+X5=Ffy9CF8ZFZTx*>{BvlV_E|=IIm?ssla6Q3ce>Fw{W*^IP|hcB z9o2mK+Iac7y;|Y&fa?X8e9Y+r&FcJ590i=#M`%-;BpWv`v3LMBBuBg|>-zAjU6F>3GIpi#C5D zCOXkJ>{8=*I_!#?M+NS^3$N1l(ZO&&7&^G7a34iJMrvK{GHv9Jg z+U9(&=4s8pmgO5y`(fI_zqQ|-KQ^Ro^6wDiA49t})32dz+HVK#w)BgCbbPZvrP8iL ze?Qu0yv?9(#>>OB)#G!JW(RH4|3A|n$9VnE=={w7GnV!M`nS_I^TSEnwdt>XR;M@l zH=}LZcMR>OUcS{^JyQXeSaD4zmInHvf5ridp&Kl|L>q}#%mGn zi^%sU>GV5jzeT$b?aCKuzZqZcXq$LLXt(2hy`r4voBX%ZHvCU$r!szAdCfO=3)+L} zUrgJy*LvEfzuuxKJ~q;2M_iz}7PuLbRR_D846+FytD8$;Wae-3Rk z-gnS8`%8;(eW-}ycM)f`+Q2<%$KKVzeE0xsye+nUS3{J+hO`!(oUk?jkYPz z9Wng7XeW}NOS=i}oiX;Q7`tJ0o&Q6IPurAtQH_%2Jx$w`*R84jro0ttoAO>w+wgnQ zHsu{c+mtsq#@-oYpQ3Hbn_ElgZ^ql282dTe=J@jsZL|OQl688s|23gqmhI7rc1zlK z(l+DeCE8|x3D?%~4s!e*siSR^U-%+zoA^~@>;|;W{ip`%FywS7@(g{H%+0{1<6gt*>p< zKCNQx4BCyzpGVv5ziVmB*TTuqkxO*EPTCZWFV(i0f3j$s{(g|Q;eSfo%-_dooBWa* z=y>LQs~K%`e4RksoIkCjox$>)p>5(-zf8yLPya13_Ac5L=>Lkg89%?!HsizJP{%WN zRoZ5}4vO(lpuLmvQyb~@rhMr!_5|9dzwV3iZ;G*Z(>CMN-&n^tOWBf12_O*&3HaU z+tjC03!R^d-=4OaKPJ%b$MWu=ZRW4{Xq)-%bc{c)rH;Re={M89o_5t%+J6)6yJ?&F z570LA=^EN5zmH=0U(h!5@nPDgy-vm0!PX_~pGw=zAJ@<}{k4R)IX~J;+qD0Cw9WqY zRg7I6!;fpD^KZ}kUlU_5pl!JQ@%E|P5<!0~C z_EWSkV!T4yIkeNS*6~gHNip^c+9v&W+9rLw&N_X0#_L1d9Di?*@!w0kBl(52O?!pA z=y)c53T<=#KA!e)rhkw2{j`T%qtkDuU8bwH&G;BWJBR*nXq)@d6}oA@>5nF~&3KqY z+sr3F(Kh>|(_N=8!}w)sSEYR^ZNtARhJP(>lmB?yX8g>cZRXD>Xs0s%e%fZf_?x!L zuUrpZK68GMO52pL2W^x84Ken7+NL}!XlFA26EXg{Yju8xUzxU<-$v0k`OT(n=BGDk zoBjD{jQ{eUI==B|(l+^xkFjUaHtmx~+qCCy+NM4Kj!9ppSIPEkOk2MGLVoT|*M74< z{dIiP|D9-?c%x$MIkdlKyfFiGdJ}JcjJ<)j+5ZY? zoA?K5oBK(v2I_dGe|p5&!)TlO&!TOP$Is9<=U+d^q(2j5Ck@j1nemYvV_#0-f6 z%-0XmHv7wN+NS&mXq)|^n6_!}su? zc&<29$2a>+XWHg^==K=@6EXh%G5+u{9nZw?LEFTiPP-%PS3r9)?S8{``Z2U$qHV^@ zVcKT@yCh5Vdy#)TZL@zYqJ0tln`u{~y*tMKhPD}BCu7oAy-w$6(x=AQ-DsQi!)PyM ze#dE>>w&-s9nb0qv`3R)Z>08{>w#3-Cf?h$O}u@yP5QQ@N~Z5d+oV58+oUh1ZPNE2 zT{8U$+Gc;sp>4+R2HF>~{O{8?}*&e?aIL_k@=KYTA01w~*m6x_o%hee^!lGMsnC%Ac;D_j|As?VGAo?p1lHC3uFmxn~ZCgtROkhK4#BlU_t#i20BzTT;*8z*$~Raejed-S1(&-g|RU^vkO%xBuzGbEqA}ySWZp zVrOl+EiU*1wz!+{g$8|DHmKZ?R0R#)zp}2<2sCK_D!Ll?pyB#g)kVJ*P1C=cF7Ef} zfB}_twVR`f2UO8j_0W_9s_N>cpveYQ(^Wc%CL4HJ1~#ga zEY~}uIR-Ya(n78uK(h|KqRQWrpNOU$m|FEhx&1yg-@q%YHk9k@&}0LfRP7|!k9~%; zttzU)ai%yZ2DT}$n#Qe!IBoU%;YEpJU^~5jK&wY!JDd3T3MgAQ-P~Wi zgP7g*`d`yg&Vf4ZhJO%0Q*WPxt{OPHLOROeN|`&U2l{K^n2JMWp(?hI7lS^kB*)BO zzT~7qk2pzb=r(yevdULshF=WIa}uQ$ggyOE*pE78<>Zx=BnMwpIryY|YEobYUQ_Uw z(*damZE*Z`CFitnaaW&6n%_5GWF(eV9bLDzD>BNc^}l^yKo01PN@ZHy91{N^MUA=7 z$Kkutghb)gxDjU$z8Vib?FxU5*UE)NpvHl&Vd2*B9dkuo4dF`^UX7IQt_aph92_q~ zHR^xkh;WVLryUVrM`n$Y8xwIpgxAjzdDCCFXn!HtFn%PM^G-%Gjlm zDxGcW)$ zu1}DmMYZQ1g)ufP3zsaCrh}6)&c70tE4k~Pl#D4!f41>NJq(&^33HI$?G@xO64l1y z@#qlU!15#w>KlbY)zM*~TZDVz!a4q|*qSai@PT z^7+Si>usaN0+D-rKy3F-T@ez)Dm(2D&K9EHwneT;PVF5(tqxwD`_kl~2&S$m^F7kn z&c6r6s4h39=J}q%z*&f`E3x?6G;)O_IZmd0(!J(9=6m5Jp01Crua)F<0b5k-&@Mrw zJ|32-#K+Eyh9iT#G^lg9`l$}YY%UZiHFJTWUEoIQ@-yHcM@2zl72TIV{VtoY7J zO3n8gW5Xh6(_l}eK3o1;?Q*105vzs&M9CK>C__}c zb}Ndu;lfd}ajJduHd<<9Ia%o7X-C#PsrpAXT#>rfdk^nIxgdxZ$D;FB?O8p2XF#OB zNGR`yJtk71|o@cx_^R^FT8nPLKnvRj(M zdtKA#WJ7A|d)_CnCMe3opslfis(-x6FH%4CI^z^@E4IFFf;g%a)%UfAd%yQ%_e8N5 zE}X)!4!V%zgNY*bYj4sj3`!L86x?SdMHlj^7HE|3J!g|pg{&CD%SW;3MwlRbLTA$E z0c7%{ch_4X(F*=F!x7boe1kSF_Ie(|DFC((Hy)iZv3yNr5a)R5H^z(G;G0vz@5tk~ zNIZNqqStb~?hV5N$6E1ZDWtNuhSBqbFM1h1$CZqvqfa7PzskR%4ZZ3Ctk-e8w{Xn7 z4dpHZ;d>K??u+4G;}=umJ`0x{HqGGu8bn98a=cgH^MtH$O}KDC*R7;#;;}f!{s{O)XxKAy(P%H>((qk6fa3hUFvw( z<_3kF(%zCJReIHkiG9|g5!X20bzl0$7w~J!H>=mng-dapu_sVpY%3$Wk5@`~lNjrVs zbE)x~)CPnumZbJjP5RL1wR|R^N!Nie-jdWlrb$IU&sh-Eqd5P7+S3E6USqmA>)l38O@6Pro-9bA_4%Qs8SQ{qpcEw10r#bIaqBL#9uM zZ-7l-cF{@9M`KcE{|uMEo`*xkaKG1oG_J3}aqh&|U6QPVm7Ooiqnq9xA&>QYpW#JS zlH+W^SH2|cnq9RJyXMV)@9h;hosjvQ~h4ym_(ia2zpE|I2_jTyTO+p@wb!Z zTjlo_3}^XofG<1Z|7I=b+4X*JH_jQ=-m?I{+=#!gJm=Wt_bN^aYySrL@+1B=k78nd z*6%gJ`^!}N-S8D!f2dz&xZ}-#b$sdqpESuQUYV-z!f@4*9*%2o~{L`1(q}YT{6RTB2^cp(77s34j@6Ky5VJ(0&*ARri@NxL!1K!nXjyfDV8{o^Aeigjzi>om5hd19R zPn`V6ad#-SYQXyuwXNX#p=DCwwwzrxE-uBu5rOM^&8u0dG@BouShk{vjpf`1567jShH~u1nOJO$K4Q zAqnlz4tRIqBwl5-48Dh@Uys#Uk6^4#3wUWCI6D1S_+E*mSN?ecZ~I!N{}jFhk@ORG z;?#Xfz-#+SSWhJ<;d9EH%Blm6Uy)V?ylW1UR1JiSElE#rinKo9&E3g~G7W_8mZYaQ zMcNYZR$b@n>_&r-ZAp6OYPbi3s&Qz#?8UCG7ry|Fe>mknG!x~)-7D2@KY;MJCCNz9?WXAWyWZ@p*sB#QpzEF)zAA_C);T=m-lXFx|MNg0Op6U?L^lw2uUXmUa_{KP|cp0mmSW$=? zSR!+PqZ?htoE_)=g{xat&gNkCK9?EYs4C6!IIrC^2|CS<;OCS~6Ez|geN&wG%wCS& z6`*c7moEH@xiijt{aW_HPOv^N$&77}Pvg9m32cw!p!%Up=vvA(efd?ksytWEt|=ST z=U*sKeam~^I9!6ODmMVJl})BHkY7SGFZR4OO?Zyc53J#qDKj9crRUweFQj|r4s5=s z1j$j%P^HB>v(4##EHwEpjSCn(`SSEuw|=uihQX9gV$dU`_F=2nOpU6 zd>-@N;i?JCrLe;D*rHc5o&9}vRs_H)qtXljB!k1U6uIM>IbPjXZr z*z$cNF#)r6ThOkNRCQV@>n{9pyAV%=yvy3g3zf|X5XPE#!vBf9)rK36 zTXFAK`Dep7KgM4vY+!1sjo>+||r@&-?>kazV*VRe7V*#Y0KNc#Oh;4JU* zkhiHf&#S+I?+@dT+$-S$P0`ziy#0ehy80JX$GurBy83ov5ProR8uHRd`ZTjOSlul% zs!0`dLda{}IH;MU!J1^5vQL@&=d!TVLf*@du<`E)>k-S0%3U#6g}fv6^lc>PMX)}w zOq+Xj;Ef@#^M|}TI1K8kbLqmb0>2XSuKSD)P_70peX-~Uh$?K0nYbd^9r9LUe^Dc% z4Ol%aGpewP`Af*VeGM-R#(*`=GGhy?=%+*8VZ0te1zrm3x^wBmub5@SUYoOi&3p~4 z4=ppQu<7M-yR&B4>p3q`Gk*l@Ps@xdtYWqgdsmNV?&YCbUxGz9Kx|8C-hQ2U&wh)j{9`U`LQMAr|z_Aahm!0du0 z{?mWZD-M#WN#7o$ooD9>C?`XH@MMa6aG!G&*msx|vJ5(f>UQ;|Q#?Et4gW`IX@0y| z2KGjo;>U-*QuFu`lA5Ug#Zx#0{1LigpI__(`%9Cev^-RbL|Kp2cqcTXiz7};I@GxH zWg-$~9VC13UhD#3wlwTgGQg1zH)v8X@Ohg9IA84r>ToPkRaLh$<3H%>3OO#Xe))Az zw7nlI-;H&J(g0mKFzW>i%EgHdN(FIu6n`Thj)95UD`Gua?7nIy;A zAV-7|3Ohr#+Xw&QlAPz|5H>=gOhut^?pmMl!&Kp7gu+IUM5BemRPdBg=%-LP5F4ye z_%d>^LZS3nq3~)M$CaC`P&f+4IYQyz??!~ehKoaDCP?cfQLaRU!h7!U#7o$+8;kE< z*$Q$^w}KT4-MUdi;m*~r_!*o(WQvheC{z)RP^b(m6yAr1vqGUPG=xG~b1M`cf;iC% z;jhM`^H=R@gu>q@LA-`*ly$4dFhXI|Ojk($bhu|r%BQktj8M2?Wl(unz>{YJSfQ|` zY)B&%&MXWo%A26QYXcdfaFyp52eI{t3F4?y7@_bU+#5IpSE!z;gDxb6!ux;msrzoV z;jS+!x{wqKzdRJL3V9Vgy=;I3vL|#V6bg6XXD=h+A7?mLC_H_)Puz*E^NmL*v_hfp zUcXoc-%}<0&SLrAYAY1p)Fvo)fbelCBqJ1l2cP3gh7k%UqYbT4xDI0PHz;@LVvJTS zsyib>;e;(=aTxAP;A$-0su`?MxOE7Af`hK?0@py}RyEOrl@$t?R817)L6}vNB-3i9 z6$(Fk6Tb+;<`rOWIF~J~Q25RApz5JFK>ENE7s;8x3WZ&(CWv3*bEaUkBYnD=tx%Y` zGa!=cmqIW?;gy%giz_Tal~?tF6$+gn9nr@U)SCRVLg6wwVy#fPbeSV^EL*L~FDn%8 zU0~S|3YQP?iKi`F)j@tmgu>f{p7_ubRQ*%~SfTL2J^FC|t0bw?%P(Pt!o(L{5x4~T zW6^u^QMof(p>QJvy}IzVvwj;SsyVGt*yFiG(HGQ_=h7oW;cuS@g>wfOGYu;u6n;F( zFPx>=o@ab|R@15(gu=8tK-dcB>z1HOtO*bb_jN|}&*1#I1VL9`9VavuLgDm$#PVH= zyZ%@rwU25iO@&anCl6v>Bhb2>hZ2!-Pw#V!4z;ND{ScJxJ4ArxlBK~tO$+G0yR zA^Sk*4WaPX)ff{`!ug^l$(JTmsweZ_4=XWsV?>BXo zWoBdX(I{Jc(<=@SqRT9Rxk;lCC)?4?k6<+ZLl zs5*awa8{Dkgl2`pOg~G@8xjKCYe8X*e zD-`bgI8N{XcfdE(rZ+<2@}uZPD-^CB8CD!;J&2oZFe4PMj*uY~-gBW}ahyFMer_Xc zArM00+)4~~9KJtoFe?=H#l2mbhf}^G&cLv+WsFcb@M+w>m9xl|@U@KijZnB?a7g?6 z!j}>88=EB5IT<%RWd4icTORQnq3~ZWBvyI2*aF{+5x)@%{rBM) zozlMtzRx3mBNR^9h+l$A|8e;Kw0%&`&LM^n5ej{e;YX^n2$SKPF8yloSfQ{Me#+%Mi0!LPT79&#LSeM zC9H@}D%fph3U%Hot0Rn1=;2R+GG}K1{MVI?YJ|eQKLvH1sqoJ&8OI8ReQwjGavlL; zogqbp!Y|7u>Wp54?@j5~d$AD;XXEErvR2MPd>xX0Sycz4 zfw&k`Q%NoO8c4sYte)PCP}u5uPH&w+=w(TIdNV>{Xcr@m1K~DH($kv}3X5=`NM*MO zgyoi`XD%ZYe)uLyTR_-uNxDo%C=9jq>qz@R_@x9X>ZoRg!bd7Pn(n3GAc#fR(;lfJ zLg8HOovMgefYqi1lOza*nYe~iqyZp|v82duWQD@%BiMF1U@f#vRbwj@zIF|U?4xjQ zvIO03N;ZQ~SpFr}_AL-TvLxLkiUgtX=C@g>pFlWiN&48KNDvAa;k-qaJn0Hti(-j% zcyzldI)uW(PbFyjRiO5=^r&`IObCVFALEg099XxNU`B+(>+lmH-Txr0wxpCGfQ1_fmj|hcZ-(Vm7B3W0O3aVnqwg-g5vrqFBpgO1xEnTkZ%P%7o$`*9|mkv5slB_b4FS`@Dv{7$guTc*q)A{72LhoxA9&6`V*9L2OkVb)n3HFkmV zfngc#$MZV3=cI8MzJH8A()v7OQ%V_x!Z)rB=r*m?1gaMnJrrym6g`rf`9LWAtQGS~ zN1_`_Nf_0EMktiWVby_iz+ZlzG|U1*Ve=+z-z}iNUkW{{D~(WC^H~<_2k`&4X;fFL zFFk6FQ26vpj_-<1@mnV>y801%Y%L%ZKD~&w=m!4q^Q2)dAQYAx!V=v9>f%!9v9*9u zSfwg=rl-JvyOcDM3qvaux({%M`WpPxrKC|+kzZ!81ih~1Sd|LRgt#0_Z1p1-w^k_Z zGnU7NuHcU>C5@U!tk!Kc6Z8u5DJ?n^BlGnsNF1G z?nu#02!(wb@PvF6ShrcG4a}Gj3Pbn@kSf9=uvS~9JlHd)5em}|;Ma<>@wb7s%QB;K zH$vgDLyY+iSbtci%{@9Wgu*Q?Adtww7qmqGV~J^nh)}pRnbm3yR(H#cDy$I-j~D1W zSDxj5;9Pn{D6E3t7prO=2J4h%Mitfw zg&*LzPl{Qt74F4i(G3t)SR)knEoL9I0jsxV#unBHg-7dheBB7@v~%eZq3|vcb;dGd3u}bJy*(JXa%+g7Sk4&+ zMkst~6kE0fSbZ!rs<1{VTpjf5!j1=Px@ATc)(D03HuDm78CV-FGq$isD7@cg-QEOs z@457dP}t)${KHYU*RNomwalo(8lkWi{#TrX+y73LHV}WX=mt=U<(IHR;h486yLAMs zr)A1&kp!Xe=RS@W+s1-$rzP2NJpV94VgGmHHT_?pZaoiO?YZ22RYC}b+wl|CEhwE+ zh(ur5gtFyW7zl-Hi>W654nnx?IdxMvG)ae0IQ}o8W7Y+=-FfJ`9MuO5jgzvUJ5-3l zU}j@cLZK``)R9E>q?Y}z%f|1k{|HrV<%#>iUL#XT*{`$|O2o55+lP2mva=2RU09-m ztJ{HzvLsTxd*?>{-wK42|3zS-WH~tslq`4I1C-^I;^xX>P;c#1iAt7xaZr>jcONvm z+8-T7dz=67jepz|-LZ8r7GJ-{n71XzNx_|c4y&_eA&J%5q{r%PBV-C!ZW_-2Od>DpL%Z4@@y|Ka`dL`ZbUh5<6gG%2sCh(=yhhLzXq%FN9F z@MKvbudM)BdF{J_K=fsxk+;qR%E{{`G%OUh)~ z!bVs+l-GWHJWf?%H9Sw-0Mlhp=u9ZD1?&674)}K& zj+NKqe+`QR*!qL<=!8~YOBxs!f5Vs1KDzYIBPHau&G?T)Z4j;~g=FNlj_^6IWEgpE zG1@R9ugwUE*(mo|5GI%~5qWKK8Ar^A`);`IlWx@vR$lww=NGcV>*3mJ+^Qxq^4d+A zP(VQ_DoK)QW8}4CD3ILzCzzoQ%u$C_O>5<~r;h3#ssmCZOKegPW68>EgMRUgp71#X zvDuM6-ON^At6yG-iKP*Yy!L#4P~=*IDzEATE3dsd!6%-z1hpo=th}~Gj#w+NU3qCp z9JFk;Ccmt_cI*MmhP-y|-B7wZn&PWE$ghaJHuod^&dL&0{Zs>3d2PuYzdAw~Qn%0^iuaysgP@xm91h7PvSQ8+xr17nnB$;`+y^4j(vQKYG0%r&eSdF{mW31Wpz_Xr3Z49QVr$I5FC?$0aI zP7pq{BsD;-yykx@s7XJ9aKe(*K4#^$>0A7oRHieI@>p~$sAjVA+HcSVRd!c`(9V)% zQwje87e7gYyjJl{oI0pFgFqN2Noqo~^4ii_uHKt(hi`@nBCNdD_7+#~zYoE;+NQVi z+Q>SI#?h021&m>CJHOBweJH-0-K#%@O8WN>-0um^Wz~Z zYQB09zK0@yBd-lxNdIQ|wnh9#UTcx-)A2usZ(qc3ej~5Fga7%d^nKtPWc^lNTZM~ZX9Bj*kUo39ppUp# zUR#A5H_j3;9x1_!$ZH26*f`I_`LZEIbrjMCSppAC@U>6IprfGZXcB_zOx#HS${T@je~rbNIh28OO?NH6aztQaNYv z6@a42x~l)_;eU9Q@G=rvMW-fwb){dARU@yBTNT#n+rifmiljI4 z+D*Cmd5@glX25rkNzduc$ZK`e;x*|p5T3RqJ-r!uZOgW>ChY=Yk0t5p&B$wQZ{r;J z3katyNzYtHUV9w>l2BzT*Bw9c!=gJtPq{{3>$)JMNzFm%QGyh8^tbZbKU;j7J_gju zmTr$!5qYgKo^+sc&jo8`31&oId$O^kNza4urX{JpPS;qK6aT|oh^L#Wa0kIUVwtMO zR$lwz1)L{{9+=j!=-TQiN^F9>w!aYzRS$#|OVUlENRZcl>(9pR210*J(#H-(g1mOP zZJaL8L=fg!k~)B@;>$1UVUX8Sa+&dJP@lH+sCH9GCT)E_3vw7eSR)8dN8Uqkk{&#WAx+T z2YZ^jspwHHtLTu|D!jvftpjT6x%7ye-}-ff9{}qI%aj>J&?}Pn{<8|bgzW_ z;8>64{QYj_wTqwDR~~IaA6QC~NIzP6t!Y3PDjW11n5aTr^=FuidjR zL05k{s83qDJyMbhdF_f>JYjzWtUZ<))uiTscz+Fv(=mSm>mSRM`!aJk^4hN3!kSsB zA8wRl(TyLKyOGyc{7c`Na@vD6z%p&_(SaeaU5R_vs`s)%%{iAIk=MrU(D$dD6<}?! z%&5W|d97?FnLEMy#4@7_Yvi?Km&EJbkAmgzZ>kkrSR=1(9LAQd0cxXj=@EJDz8tn} z7qA9eW>jH~yf$zb3wtwIvn(^Jutr|H2wI?Os+C~nTV`xwjlA~Al`QOTQ1_op7xsU6 z6VI}9PktHj=_307mvj4G^=*WUStmt5C?HPkX=3v1-HGS6^lm;&nE z=h7qp!%LgS!afStvz8fESR=39`WE+?cftC?GNTG>8$;!UIhM#1_`bYacb| zOjH-tCg;+H{U6?$mF$C_U=6d(sKOd~?f#4WqLRGIz8$RjmKmAYth{yzf0EgPY28@^ z)>D=#t0goE^4dXME-TX8ARMqH8;%EHBd^s;(041Hlb}|BqN8{3l5~Bbm)n>R#lAg_JfhVoiJ5XMZ<{Cn)r zaJ;C9trwT%9F-g+Q^`~jnd)NC0am7Z>P0*j72&&M(fO-(F)~$AFP|6=*A3RK+Q7(E zNsHozRoP z;t;kLOOI+KRSF|hU0XjO0)x>rSfboUrkeD3K;8AJ4|gL;(S@W;^}gS)3VAg={cV6G z*{(Vh%2XFNOc3MXpJ+H%rkdQ+6L(?jBID5stxQ#YML;|T-Yk+nd++( z2|`x*TDXQ9x2j2uO!d_)N8AF!-6csfZH!EHcwJD1%mXw3T(+<>RrC7ss)ybI=@Uzw zqGTNNxX6uRNBj<-vqGN8NuO?JD^pFwgP|%8ErnoYs;VElqPZog@~S?tGF5v#YjBVy zs5SXzWvW6sVy#To4kx+uEL*L~FDp}(U2fTssTx)cisvj_)j@tmWUAGWOZQrWs-J2A zD^qoOQ2z|$cS%yEmtT>8fgQ-fgQ16^>#^v)pbmOFB2zu}kY6-_uaouLAW_X}WvWi^ z;~yZPjysngk*P)=dR*X!QP!3Pmkm)*u z(A$t4)e}~x>i7yCXCO&8f-u>V)Bv?ImB1r=6)6{lm6oLTF)LGz$H}H5Jr6>GC8=hz zGS$S%cqW3(Za)ZzEJ-$%@W1*!9y9@&YQdU-I;c8lL2$1#6PlH&2D+}^n`^;WPx|GN zBO+7nyqEj$Rq$PH(_5LUsF<_CaQH^s^j4sARm5*(s?ittbcm&r z4J(X9uVc}ZfeNQaqLr!I9mL$#8jQ{*SP_}(!?oC1hrl_)5F#?wF~{#e$_=* zrs|f2;y;A#kD0XkXk}%pu0aHU5zf~PA@VOU{MA9rRG-6lQ2JGHBUAlL9)_$;HNCY@ zah$kOxCx3yk#%lHrdk+D0hy|2T~`sE7GQUjDI%v-=3iiIhdVmz5csbz8P&*Ck1Y1- zI63eyEE&hjRQFen*Q9kIY&4|EzrcDWKoUh2oj2ioSNio>H!{`r4VlRy_}xxtdDq!IvWasg0rhLjt zX(9+yElE#rMyBfUEB=iqBP{{p5lhlDmyxMvev5|>Nz#iT?6f3ZCL>d|UC(*>D-e#C zAVnS3tW4GSeU>f}hus=jbUp2nDk4)=X~`ls2dhH~W<;jy7mw%t$RZ8_VZ0?pb|d>Q zF!@YG#heG$1D2_3Y-OsuPvQ>W<8W@a1l?{*w1G@@HD1)9qPz#fXO^U!M3Ep<)mg+s z{RYC{mZXmziUgVJ{+k%7;`KsYh9%PB(e0+_kg4u`6Tc3U6}=kN{+1rqZi)$+>TW#v zR52%lHMImYB2x`}nZs=f2x~1Vs@+sL$W(cFM5zk59jtdOQ;!rS;6SFDHz%NvVc&vq z%97N{W>ic?hfK9}Ki+d9PY=tD#Z?#zcmuvd+%g9u+g(5Q5&MSDflL6v5o6P1Ck*SU}PSg#4 z7g&odQ)Up6shT|N)1)V`d0PpRqnK8vx@!sw_5m257?x2UJg;tioNlC}@cC~zx9Ymv zj7&AI4qK`QsBO+ekM28_5HeM(BwQlO9by0yWtWmLssmLTJTCGY2ox&K0`MO>Pa0MQ zGF8LpIHX<#bx$eusIF95;Bk>3kKq*ki{#&Es;|0IeMMCtGF88SaeP+?wOJ|j*jhlQ zipQf~RV~uNAAO!QtOaDMz9(6WnV>E&g&tcA$W#NfnZ*|H-!COijJwpr%{8+>xT0kg1O0+2)FQ16Wfn(*|Zt{0r=< zd=_B|SZgg)_9jH~Otmv5QOCRytZ9}RRahfaU3XVlGnaz3!7^hDYhs<1|;x;QVOnH|6y zXqmBvH8R!w8Z5%ipw2p%9+9c;#S`~cVON5+(K4e7YhIzmr%aqk32{KiqWNKLxK)B12Y&hOAGBVX` z_4&`TRiM6d9=h6dx%--bfrTGnKA$4d*EXSSITi*o)sICAmenzuM*e6w$Z?Df?~+z4p34L{4yoaEG;Am1#QC@Gm!9ADvr zcyS8h&&b-W?-OTS(;Z*0CVo*K>1$$9E@zYUr>LZ}9N*D*aU5#`=T(-lITGM5$G75g zzvu_wDC^$_zoSTht3qbp?f5#L2#Cog7Ky5t;Wn}3KCh@{|8r$P0!B;3tD8q|T-W&Ki&k`qL(&|Lvs}5)V7{bhsh_K8_=+MCv zzP4~)Q})F0zzW=C+#$r%gpt(I{>RX~N3{V?3S+Fx7+S+62K07i7)>1+4$j=T#7xx@^&oW$cAqH zSyxOCcnMVb5N8mDd=(y6W z(>#Y4MlFOEGY(tsuxaEP6UtX9X7=z^lRKajQu!44yuasQ%&h`zbICL(kQozJz72a? zM_*;xxQ;7%I`tPmZ~H=&@(XPF-lqO5QpdwS@AZ9hQ2qmN@DA3|5q;%wQw2EY^B&)W zL0J>d#+J})J~C3Z)vP~!-i3I_s?!OKewHOO(yT-k3omiKZCyx=17U_G$-ETFS$hxq zQZt3$d+gbuSPa$^r7$bcku#Kv8SnQd-hqL>9kdV5rHa;ddScga?)SXg(GbodP>KyL zO2Zi(@3?KR2#Yvbn($QUe^^w9JF2;qsFK;+?``-YUXv~dp_L`67Sp7We(%|1K~3rh z!f;EHttLY9)>Y;tzxVDBDE1^c=URdq3$kCyTJ864IF7Nf5{&hhrNa2-7?$u*gHhg9NtylxQ5oW}4qk$$yPX#Xz1H*z=A_k^#XO-_==@prw85zZ-n%5x*34GA{^tFXF;fmH!6#vLk-^znaWy0q^Ki z{hVEA0era;zZ85jlLOwR+k+pV@_V0$T(E7{B_kRuk-mTOZ zJNhAPE|xCYG>#l^Li>-opYBD|xp!jdV~O}3H6ANA#VfNiJNuemh*J_r=@OX(0$%8D zO?TQNO-GYXRFtpe%IxB6l^kIY3wVPcN>n80Mlf%dY~2A;g~%Ke@M>0ZRp!n@_#Uv) z)U)a`ZwYua+xvC;jqp8d(}y<72ACW0nkS)7Z)5w%Cao^KCM*bewYQ@1hv7VK2?=Vd zdjJnH&U_MGkb0sP#S#lBnH5`i)4hC&fNve&? z=1`@W9_J0(hjY7y;I1plx1q^TJrOSkcX!;lTfl!A+_x-WA3$!Zlqd#Iblmz2F)9zh z`HdlnP{xd~7(Cx`f56P*oWgehEK_COa*~kwd7Rh!L6p7HWY^dsTg!m@HKUH$%9O#r&L%xr^VtUB)Y6+k4<-(a~gQ)SM z&X7Wi^{D5KuHfJ@5RA7u`;?G{n0wM4SK?;b10z7@$zc{aTS;& zv5dpw>lIy&2Gg~77Cd)buPTQOqS`>NpbhH6-FEs#*lUM&j0?%@gq6;R4sspZIj)ZH zb$Idal9kRQ|6s}-+BL3>?=Uviei~mQYj~#wF|=D;?M3qHLeaj)36rLk#kSfqd1<)o&y&FjivG`t)%{=;}M={ji z3A@$rOb~~#x!Ab$`M*xOJM8w)4+$5slCY?x&Z{zgfls~@c<8&~aPzW$QKzI+xQ`=R zl^&0vOKSB9XTZDHkyfo9mmOJ(jeR8l4H-wcS7QAwC%gielf9Y-0Fv$qf0bJfVG5}A zVt5Vg+A^Rx>yz7Ry;SDRG{0CTV|;)Zx=4 zlxWC0xou?lbGc1DXGv5EPr+>7Ck;-@DKeSpyP&#!ZQF*gDaA>Qr5uD6$46?)nMZ7c#jUp8KS?STn|;zFgyXWJvM6^9P>ynU$Ngu2rJ`LDL2h@+C<%(Wg$=m*Yj& za__TFt_aFPyk&jDbx^SjvbrXHi)~nGSygU$-B)uC^1M2@49_)^jp4|xqEfJ*BZkE} zHKzCl?$FMg5)@bBn*38|4gLl1zdiiL2mIrIeQfoqtk%lA+rss*A;-TQM`cg`pH>70 zm8s(VKg_*(yiL^`Kfc#KXWw=2-RE9hQ^L(WW=N(GG7p&=l$0{vgd!qRhA0&gWy(C1 zOrb)V%alX|6-8901{x%(@OwYcv)4L-}EOdiGk+UhBQ*C($qA z&Z!Rr`$ADF+$Fu%YE+g*#q-j(IbL)8U#-r!$F~={UHcnWL@yY@N94PNRFQ*38I7D# zp&`w1exZ63-!&)}VXsvq(PQOUWnUahX1tWSqlZS!iSt;ocI%?Z4g??q~1OA8^~XO~S=R)xA1S zZNRWGx}$Aah-LT>h(A7n2ElZm1Y(0nBd@~h9Cv$3Bxgn$IBS1E ze|tRo1G8?P@iDXi)wAxo>!3pF=PCJ^@2r90Ls*Vtako-S8|CpN4j~A=faQ`!uby>X z$0P4DXKzKPb$vjk)<@+}hbY;#t4d!u8DUuqS?*4-<;PI{eel8e#w7<*OUCkyq@fT$m^H=DMqbbJTk(2<|1hr?`V)D* z$X~|m*Zt3Vy~Mx3>*apY6e|Cw--y?%{4TtH%OB3`xBa=ie#c+W>oxutyk6`7#_M&y zpGxK5^~>=3J^xQ$ulG~&qP9HUHux2Iz0q&Q>rH-dUT^lN@_LKEn%D39`+2?1|CQI< z{ag_$zr(M}>z#fFUhncB<@JaDbG+W|FX8n^{ztstrecV!Fn#QKlL{U>m$7W%>OS~7fvTTpZj%!br-Blb@Nq$r}Q+vrOY!n5U5Zyw=~TQ>o;R@jbg!2B=>!^L zDb>AN=~H+!huV!CcTygX$ffwdQys_;{aL-rKCFn2fSjVfQcx(}o2M44JQQWRw@jta zkrf*3U{~+nI#M2q!896nZ(Zo!ZJtvUX?GTEszMy<#eakyr*Ij3s=RyanhsFxCJP3_ zq%NT%^a{m>bgolZRC@JYA?HC5)B-C02KiO6!c7S4QmQz83(X_&S=IAVM^{n0TnCJw z7)WMN2_j30XI0e(Yn3T zZ+)J^mkKT#l9QM20MYj-y{&hWLnSg_GUchLIFWbHpW4yAl>Vtw$ax2(#zdk&v6axh zF}lCfMF*uasaJL+Zk!=Xufiz;GVr1$adp%rPTsQAN+XrNW|Pk?_y&>IgY6XD+#XPA zRs3!6Jj&0j@MyVyR_VRT5K74Sg2>$3c{|rkbMy;J&tE3r#yD^6h_Mzu`(-(Lg3=Sa zrE<}{-)%)ZO@?=vgUMEL^rvv`6*p1ZNuc}C)mrZXkM3J(}xs&MMQnMUqXSug$ zsp9mCO^-n7?Zrx$#!ai#+heH&k)?$6_A;fDG9?-o$K%r5E0zB3E4eKFG2uT^dH#v% z?M>*db*bFjrwl3R?OjTD`XtGr5|PQKJU2hPExnBkbEVp)IKP2(1Ci)YY$e>=N0h!p zhnUncI}-Qy38inw851%v%#ye|YLcM0&nP|R62vodrV{Bdu!G*7t%}ps;ZeTy_U}q} zt(eBdZA2Egxwml@ZhMaqx9tzcju?~PzNqvv$RxJKy?qJWi7A&da-lzk%e_s#h8xhU z`1s}z)>VBv=*-jO2LBsgSMyKty1GBwrTiNHL|)hQXY#t1znIrI`6YQ>$FIWcx;}2Z z2fv=*oY(dJe|g=&|AE)H_@q7Z^l0ScBm>rseV_B2_;@TE>1IA&D};4(e+#c$_%JE;VbrG!NDWLH<7A^YE;cwC}+ zs;esn@BMw1@G?}Me`2C}zN@F6k?WRg3@M1_rLJywUC5ylUmJ)o=Zg~(&2PJUawOHc z9;7QoqCc^fa5Qgp^`8xJxC5*d8sjPwNAnI>XW}uK{W4m^?mn5xCMI< zsT$ZpG>>rUa+BjxzC`n9t{y!s&7q7*MCR6(vFi(0J9T8FSZ(ZxF^T3wu0DY0!q^r^ z^ATLzoFf@WOaZyugnG@%{C+*oAL#Gh$QRR0Z~u-9l(=gn&s0=ho0_FQJIiC&akn_# z(Bcs&y?x%*{f9|!Hl`9pmJ-t27hRn^LN4iakH@9AFS&Zh4tdM-bA&gc^86Fi+sPsQ zZcC5Hu7!pa^md+*ZgGFep%Nb&NP3&ymfpTLq;GjY#c2i786wf2*h;v!ONR8{OVgN? zfyTIs#JzoeNPlpL%cNSC#Jx>T67)8nD9eW@NGazwBDF_#L2sXQi__lcQNHwc?U4Qz zGZtlxAhNj4V^_V99=b|CYB<-}5o6NZ4MX~go*^zOGgXt2ZuLtNXY4Trq_?TpoIE{i z_#NR(o}M-RS-66dr)MpH9oEZLTYNLb3)38$yg0eobliFEj_%+)BZ>|?;N$G)7`)?N z6|K<`Cz^}ifDc559PbS5FIPu9g-yA&$+vR3IT*D@6uqGq>MQ!kK(w>tl?G6#+)T`p z$seV@I|E^@+`CcLzH)TJ)KQbviY3}f-d}bDQk3j95a^dSdGD`4zq!_+KYX6*Bp#n zd+_Q?U^%kl{bZbIP$qdL7Yu8g+|%qjhW;}xs)4HoMb#>Tx4^EGa}qG6I6L>e5E4X zGZQ6=?c$!9q>4z_M7U>Omg<0V&%9!4k8saSu}SWksbb1iFP<+X5~V-88~@0CeiY#(yGtYKuo@)^lt2hyeS+2 zYmLbW2f#W>qLDcO-nA$Pz$S}w0Bp7>2f!9pO9H^2xOXzI*@eTIj-B^B;d*EJ(rR=Ln7gTw5Sdu;R{K+K_q+?9|?y{brK0* z+ayQAH#W(UaM+lVNWdLl=P>rragjvA_xO}2?wg?uiG<^}b2$=D*d#~7Nt@(IIAxO@ z2|r5Rh*6G&pKOvN;b)uVNcbf_63!Y_BH?!xnS>V`v!fgde=7Y!$z;jkNVuT%#v$T) zIgW&Xl>YppY+HmQ;Xh+iBH@xGO(a~lC`SS=y~*wz;Yd)D#HMg0xNdADkXKIT_60Qb zCcBX@=bA`JHAW;7(p-J`Rov?iwnRd1SFgv71e76>kPp{6aRG-iBoYd`JSLb(xJHsD z5(>L!h$XOkQW#f&M5gp#hl)J$rYNGRj#{7rFFIJv@OLOCgbCg4aY zZ<8De6>O3tp`uN4Bvg{RO(aydNsfdnHp!7t)r}hysu@%wp@ys5m&Lu>)MgwBwOw7d z0&dEu4331lu5N)>=Wqr`LIYR-y9Bq4)247FG%_Y75*ka=L_!mbawIgfC`Uqbi*h8i zh>HZO!pVH-2qxs@wr=Fud=m-njS-22+g+W84~!eE=^NO(Lx5{4R7BH>9_zfv<* z9OXzD>FQ^2l*XQOB#d!&5?(*W85{}Ex%$0dBts%$oG~epFkX@-5?-`Pj)aLe$&v7q zEz6NGDJ~MIPA9Y6S<(s9+{jN0O(e`PMkEquxq2c-DLU$vNSN#DQo|%eB4MGcd*2#j zhD5^a(xTS|k+4{jDZ%WpG(HlRo9bjtSYeYqCcJ5r90@DMl+g)q;awWIOhUfNn6Spx z3o!jshD5?T+qoPG@7g3s!h1H!k+9w-ITAKX-DXVKWRn~Tn{ARKVM}}@yl+s6gzc^_ zgmWG2C`ZCB950PclMIf8k1zxr#9f}WDI5tnR;)Ko$)@m_@QE=gk?^S`O(c9~QI3TD z7Uf7dU{Q{QFXAGB>U1*S*i1U1XejdMYbFw|3l)u3j3q+4%w-?P1SS$nhxB_mAwU@t z3FSh1wx7ls5(yPTJpShnBB7!r!$BlmFG(~oE5=Gv9g;jIR5rECm{7$gITET$SrZ92 zhIF+%>3GFNLd}pahr3-VLn5KJt&Ah#CY$6)sAH2H33Y9fBjIN28IK9|ZIUCQflYEG zGz?XYRgAY7R3ZV#X6+%w*invz<{@37v$UDa4y{7^N<%FSj)XQLz3#EFYzjw0J7ZEJ zp}izcBy_Mzj)dE7k|W^`Tb3i?&QOII#YkQ`nSCnYQd9Chp~&UMCKB#7Mr2I5Kcq80 z@*Fyvlrf=ONYC#e84?LS@nz|o6*D9f9+Va>7DPfXNt!X?A=};@3B9e890`3)?Gg!n zZIUD5VJT}Op?^sKJ3GWR%a||_N5h4a#TC{GgKT9S34?8tBjItIS}Bn&sGM8c?$u2l*5AW_J2B#gl=#q(1ogU5uiA>I1@fWeXQLP%HH z>&m8ZB#bvEB@$kgq=|$HHp!9jl1*|XOtNJ;5+=t*0-q?zOsYm>!t_uid8vtnS3_|} zk+Va(PV|m2JJBTS032%k;qhE!@71jxBLi(4j$>It}!a6B{5l3bRo0QqXCS`W8Ntqp_ zZj|Ln*kqG3JJ_Vm4xu>3_`X4d*&(D4e;+t1vqMPVi#OeIBg*U$(kFKYttzuaNMCo( zkxh}=!I%tY2T7Vp_{^d*J6Kd^2aC$=5Q;r^ASay6zU3$qz6nJ#mYYa8VvNX`a4e)# zaZ`3puw_iZUFh%BlMIQ3Qz8A^gd}E2B>W^TYG#LDBxxey*Z4^I-8#u*!XKt~857Rg zBuB!ZV#-9qg^+GGUvteeCj5ihA#a+v!jbTw?Ocw8OE$@oaM>m~60X=JM}i9TE@2|U zwMmYIkWF$Vgu`)>kYrGagp{z}^I@tu%8`&3)+Ji|lEIOHd*|;D2N@g*`NO)wPqJ;I z7_TuVB@zlr(nP|wHp!7t#3nfsirTUq37O&8NT9BDGXEPxvqPzHq{y2l63Q4O5((wQ zdRuA|zkyUD;rg(yK3$%{lt`!=*3EEB2%Tt@NVqY~V}enP)g@_WhnnHIqsZE(IvEpg zvPm8j>ewVlLR~RsBB6d*t32`?sYJppVg2M%$q=2;SPGaip@~g$Bs8^2j)Z15$&t`P z>Nb(k(k3|)TG=E=LhJZQXk$=`g!W9p7nIE)~fQLx(`FBpfuTM8Y>=-9Ag2NXCS3!}{HY7d$)<25R52zc5~@nlM8XX=$&qlQO>!hu zw`DmJYIw0afxL1uPvBaYO0MfgnyfXEaI-NYk67CRFCKB%Q^g}vDT;Va{ z9#0p-+X>kf9uw}hoy(DMpG|Tkbg@Z}g!^rhBcZF*ZN`LdHp!9D-6lB_dc;RUmO&*F z9`f|6v#H`JM?zmu*Pa`A&SOG9PbZa;W|rAupr`MeDH);|2N{zR34PV$&A-PA5)!VH__NO)CDnMj!J=`4JGgM5=Q zVV!helQJeGg<{V!T2vwd$w~N71~sD0 z4#*gBCP^}QOh88RqF~E75~#>YVaS+(jKCefDjg(EBt%h;gec095Jfo>kc>IUNM1Ra zzt5v9P(ZrjkvO?O!5Wb<0m*rI*!<4eNGKDM4BHz&zl7-m47mdVMS?pJ_;!ULIr4u- z3flYsDpF1jz+^xT%(DZkDl^v;SN0Ch0MAlR4un#i1}uN{k+XTg-V_m@OHdRfLCyIg&(}@~|*h zk{HlHYU12e9uBV3O31W?{P;OSSNx50YR4Bo)-X?ii*kF@9ENn_* z(Wvl}eY^{Ys&F!E<8rA=-jx&?wbcZ}Zc~K}3m+%xVxOcq^z^L+!zXaDjbunL>`&5r zyDMf$FnlR3S|bRCuOx}{&pd=5l3>Ua1jAudodm-X>oW(#w>HVaa8yj0VE8^sryY}; zWmq_oqYgBLWw)OtyqB&VxAjJQ_oxA%ISArXynhZ`klQzsJ=)g{Ae zXhNcfWHf=?<&dalUF49cZIc`lH`yeIL>(PBNYpbMAR*CE>!z(k(s(>bG}d}9-XK68 zOGq@+x&dy^;|vaomReW1Ey5WR60L28JV>;$Ne+p&ra~Dc+S??DL0mu7A`BFr4f9TZiOcY z)Q!Lz$Ki_H!Ckm`YAEYjz5AwA=WAG1>OQb~Sti$%i{8nV^-$U|BIKes2W0g~qr0}0 zHwerOdSy}8IQ=^l-8!>ghNi%=lJdJ1w3;Z}rJ~S%0@A zRp6t5PDEjPsZZ84eX(wez?T7qw;SvHMTx9FX&2DkDuZ5Elr>YgE1Jd>RRO%JmYYEz zjL4d+`+Hj8mVnwtVR}7K)Fq#Si}lj-cs>@nYAk+UjKcKtpR5&n z%6Gm)O{-o9v^)ya(@a^bb(=F`fp-Af6NTy3Kv`?_{1qXAj|2KC3e%g1vNq~sUhrIR zXa`<$f<>B`zm$;GEA1ERpp0|4-8$<7-5B@a6Gc_QPaVURZXc_MSTF?hnAZ@pfy_dl%9b{Fx3%cpC*X*0`WGza8qp2ulkKH7;P^BOWqle({tHb z=X8NPA=ZilD`#y=2B#=Ql2N8(U`s^t{P+-1B=gy@B$St)qMAl@rW zPSnEVbWu4S$S}0GIn3O>Y!c)>ov=y!VbT6G^?<}OGo6IlG*~o0ZX#xR1Ez( zrO#{$UQ&7%)U;j3*?4-a+w4pkrJD~3KA2Y)g{s+t_324Kai)UO|Df~O<6A-KYDrP+ zG4#qx7yCZ=X5TPSr{qAF&I-}9d08EmuGcFft-TWbEw&7|DAgk`QO?3se8X{qo@+h? z){mCSBTNkQK0FiG*AZsuL%jb8i}WBl8`~7@!UIa*{#LLrRs*%s)pU6^a#j!A#*0_9 zvkUiv)z>m(oTaxjXW?nW9k|Vtna_eX)iPt8Wo93x@ob|oSAn&|G83I;`XlJKQ^Br( z6x3g@rpv35vj!;L=u)s*DZBB^0v2h77-#8q%UOe!p72TF!i``xw#*o3nfZj$Wwr%2 z?*nUqWhOey^x?RT91lBkD~tzq*41=}zu=kmw9-Q{d@yq@SUW8<##wsZa@JU-NBoo` z%wu5vW|=Y0GIN~L-i)C3)Q|9n4lLP+0n;ZcU3s<=!#9E2@@l%g8aeA_JkR=d;6it> z23lr}v-G;;9*oEAf`-)+?Dh%j#%UO5|AUD2~!OS{fwX)0@XPJq|1JX(d0n-Dl zp_ZBGEYsgodT^=0g_l8Hcs1SOueoJyRC@9>x#qqNq?lc`&KEP`;!c%863MCaS69p_ zyHtLvFWEl5%C9D-2c8{|dZNPayYVd7^c|_Jv+nsKQD>!m9HX-eAQ9DB=Z@jDe*ItKly$Q`BVerdzJjSsgcf z0q2r!;7?ChAD+-+;xeEx#&y|Vqq8_>jL!O~M}#S= z0(ey|*XXR!0Bl)PWVa`X_5$(N=&V!pT7jOx`X}Il&ie8Z;LiYi$>J2#R%Z=Jhhn6z zSps}BaVS95<1|ZiKJOA%XH6L&a{i-X;UK7|Ej@;5bQaFTh-z^^g(kuxhN-Y)b=Ibf z!OPFff>6(rtT`1!ht7JovD}oRI)XYV2YRgAMrZlmf`SuK=v7;g#{{dh+Kmf5eg}lz zmK1d+h7O(8xqcw}egO4S4s_`(tFtC-3nIPXXO2@AOSDm9nb28Zmk)ye7O*;4CXX=E zB`lnvv+CY~;{xizK46WsOma51DU8ngE?o)zRZy2+O^@oVU3h;u8{Q7q0n6m>7Z;4q zT5vva_AFSJEi=Yhqq9o232MLQbA0d?i!?x@vqonvZ~_;agL>E1^r+6N|3big6s%E} z8RM+cS!bpNF3bdLnPtW}YjoDe7d&Zz9bkQJnTgICot2ppxbP>a;r&-_TU2LlZ{>^O zOt30jW{k5&XU)UQUAYfhfOWTJ#yD$q)|vVNa{yRlEi=(sqqFY*BvlO02X*z;^r+5C zx)aBy6kmJ5`o=P2oHaUY6jU)Y&x7S1FbxpntkGFt&IuaeIr3XVw2UFx(c@ zE?3i|I_t$IIMya-hk*5*WyUybbk=JCnYjRe-m=UXXN}J4aA(l6AA|LsWhOdnbk^_} z1Ny(9`j~FrYaM`=&WJ8 zLHGgKS&Q>W*p1E_G!JhI3w?=4)3LB^MYtk&tj_wfTEuBUxvCOawJnotGCHd%5sc2F zrwf$V6ilPDD!uD+N!1^jgULi|^3&?9VOb%;UjjDO;znn!_#iCsN_9-S8?8E?pZ?{U}_2 z9G}m^gEIo(1?avg9O$ei>mXgwv}!P*C!=tnvp#*p6?h7unNc{!>k@HU2Hb=CvdC5wqHKz%K2bQZ^q(OJJNi!en^25-9M8l9Cl3+JO&Ap2c{XfF_N zjm~-j?=n$)fgMc11D%!H2&aC}0Q=kG6w_8`ojMh?eV#-3{uLH!k-JPqQk&ITm$ti3 z59-N=ptiSk?p)q^M77|2*7evIXb@4o!5UZ)i%Rn`6FO@}mtdD!0@iz$$s$%Zzc>=&aLygWAV}HOn#+oi#dZ_RF3aUJL5ZtLagl zwP{b#xyQiz%`#)0H9BirzrbcHX31-@TondJXSLrJFsp;r(lQgBH9D(lwP0uH4(hT!hz0u3D@Nrz62=ro!!bnXKlnst{E-@s6-SFbXJwQNpe1`E}&a1 zY;@Ku)ImmPO<5aaih2;d0fsBxZgtjmo^ZwipBm3GI;-}@z|KnGYYfNgtpADz@IF8X zENpZZ$BfZgnbROqK~ewU$NAoDywO?bT0>{$M|LrSXfF_Njn2w-06MD%u!aeEptEkK zFE8B*>;a2YOk17R>-jWk+@ZiH5QhR(zMIO8PCt&-S#PI>oR6s|-vISpOOIii^I30Q z7o4j49IPXjNrfG&v;M?8)>&s=03q^&sok1WF?8sx`|#}@rk4S=X%2L5A89112iFbn zsuo&TuqPatgU!;3cK(MSc@z(##y7YZk-hDz?;F^XPGh18lANQSIODtX|OI?W}>r3 zXKgPX&&KjN7=)It~ zrhv87GHvZa=Ng?g5l`x}3)?|Ga5X)uvp#z}*y+xKb=fjwoHaUYZ|A_-Yfj?QKbEV) z!04=2c(EGS-UzI_EHlwrqqDw#EucRN>Zq&f(eqg!y`#nOOt6+&W{k5&XY~&So3#V1 zFDx^rWsS~y_(0H9zk(G$Wi~6(S);Sg{2tIVL9Ki>J*u;|yGi0~3$X6C%ot~l&U$os zuvr7ZdfGB$oHaTtZeseWFsMQ*-jihdh$-cm5C&AS$P z^xKj1ii{08`9_D3N58!}Z%B(Y=fU+lW0|7g;mE@`TgY^E{LRyAguf5&#2ToUeEBm^ZHeP1g~fM z^LRbmf1lU${Nub{=>N^@*Zd^x&Ut#h?qAF6#eQ90zu|Z0^%8#=ub26gdA;0!o7cY; zsLg(yFR*1~80G&e@CoPtUEpV4Uo3D-d9wRY0mbWo3l!(|e+BNP^+VnKu1U1+?x$6t zbx(gBue1EQynfJM!|PuD$Gm>X|AE)N{foTrS<{JFg%0AK~=?{}o<8 z=D)-1LH-xK9_(M>^$(AKjRPK^;myAub=Z@_`orZBrv%)Q%BX6oF)zu(hJP!qt4AF2;btOLfJaW=AI`&b z8D7Qcq$72o4mkZ$B^I9a99HTi-^KEf8RP|36f{BcnFaSd&(Doj`Yd)Ljo3P^Gh58sOE zT|dvkqn`6EGR|UgtK*9mivB6$ID9nGyO!8Z=K_uLOdo~k{d1$%0$8{N4l8gYUhn4m zINlab1yvP5H3+T)gL2f-yR{y@F@>v9Z2{e3VL9sP-A*@sG9vgRz#g-B^8HQut$B_| z-CyC)b9l4Yq-m~``RW=RE>T#_I};NYbj{O-g_@q~yb4RZu&But7KiXJ8W!~32amw) z!(xPw>x@8sR1ht$D49c8ymdQnJ-2KsD>d4%C{`Jw1le~GX?k2()Z3!j(S8=PVL{gl zY*^4G1REB#1soRi$0_~$qhSt$#3Kl2e2S#ouZ~kb--}`RVLp)Z+tb+We^9^y=2obTy37Ys z8q5YSKeCG%NL3}=e2V1BMR)@TGL)(VLeqGX`4q`*vvC`7M}wJ9k$i>8C5Mc+R&bpKgA&*st~CWHHRJXGCmYXTUp44Hl3cap-pFPY-rOKaA?yXr*tt~ ziJ=j%-|x}T=CevBw4a0V>_dA25F6U>&Imc5BI6hqw;zQz{ZquTq0M$pXzzamu!~xg zv2Y0++Hd_8aj2jw4yY`_gJMHlpHJp$R6{_`ENnwNe@2Sn4*<)uIE6Mfi{nxESNI-> z;1xa^A8~T0P-s6;f<6*oy7+_G;Sjim|3Kj0@JejpetQ%#{Wi?KMNo0qxIRe?hCB16{mt?RFT-pK-T>9gb9(WO>5(2l}pV7c& znQj9278uVya61FBf&0P`-+3MxGqAX0DRAkZB90AQwrc|SP#Vs{YykYeDPaS5C%(T% z1=ZL1IY#h{v4Q)0n-Eu{E&{q@VH>!e{&oc~gl)PGixj88rDkzF>i!D5T4|@knk`Ar zDK&I7;-YC*QmR)A><`@fKZTs8{gbNPgmok2&^LfmI_C56+LAmecjbE)pLNKSa(9sK z6s+&zb?MGmU@N7I|2E2v4(V_sY=26(i2DZ8McZvmMY8(+xAu3)7-Yf~`ruN^d6jw= z_(-?GTHHADpYm!H_8s~{S7=P=$7hk{x_O!pmUrlflzh5txym?%&xmjZ=`C}YIS>1J z-cQ4C$6Ro^Xx_K*1dn=$Me<*Y@F;~%uErL2h(hODBssbJwn#1XH#(~kI;(H1Jl$_VixsYP zSBlfOb*@YR$wi3Pw~d#7Uy_r40V5q2_aV>}aTReK;k5T|Kjb;pfY&x0ryiHS-K)I= z{n`fEcN<9cqpC{KXYBfR^v+h4cIyv#Fi{3EN?q6Y9)XqFzBI-pbk+gDM~Omp1a7=Y74`LQc~K}A2*#GhPzKk%9#;B$ zCvr!e41%Z)u*2_1C*&@Qj|25>TBt2D3SEaIN_Fet$fF?TPQ~L)w?1|4K>&W?qBzI% zESi)a^CU-_4#y|W32ORMy@)dk_L@FZ)py2{;X+U2+<5N36H-rH#6D61wt_yI6!cNY z)HJ8>SrF!>;!(`SSYwN`Pw<VBMODo#005z6ZO zy_XfnApH+!TP*He+B`vyd!tABPDSL_HAqau=ca?yzQ>CGgxX4+tO-k}y}=q^xCQrq zEIp~rYh*1qeNVmbw?!$WN<7{WoBWG66Cb4^#`9PvT4sr5+px92c}sCxXc>ww2C{-s z_DawT-g6y1u4M<1PYtTxrf4Yf`bRKu#ang?FDr$C(}2$!ilZ4#Qr_|TX>38GE$F-( z+ZPM^5!~a^H(hy22a?!CMc_3prxrDwK25dcSDs%^Gp8N!dlERKXhVxA@A5UNT-QM0 z!-+#}qQuTP;*`X9s~;53G~f#oIP@%9-wMjxam3>m+W>rLJSR6DQ1m@oly_Z^IwZ61 z))e%1HI;htlIiX=%IkZR@}_#2asI<*U~yN&8%LnJ%1gnUYKtKIdIQCDxRB~AZ%Zj$ zcLL#7OIk-pGzUQ=<^4G@4Mw~e^$yTBckw`q~bCJqBSW#FJwx#K%2Z}`t* z!a=JfVF^qy{DAWQ`bkV&2dIL9W8wlol{WJ_E~a&AXPcP#EFWPtuD z;#eiic8!uPyBd=38NlOA39DqwUepd1REzMll;AJOVZPLjlTJI{3~@DT8=&15wn}zh z3s>+TfcwYafhec zw=mUd@@O75?xs(`)Y)XT?q3SnYhWzH;(kXBa5qEG>r;pDl+9LT?=g^~e@?F4xWwCJ zFptMd>`c`4%i-|w4B)>l`4k!B!^0*o7usAf?3_V{QW=o!MX_*Yib)wG7r9Q8g}VGD zk1JC(f!8C>IkJ(9qN~Z!YDHjLWzY`YWVL?39j^a_qPpRySCmU5RFff9b2IlGhR-IO z^p{0(ivV#a;O7;~&7l3g$;UdWYl`@`0?^w8b2|upP@lR##i2e>9|QWzz_PPu&<@?? zg#K(@VB$C6e;JM=@bCKWwSkFT=#Xo%$j0+bl0o}vlgm2emL#d>M&R{{LmRK?pOcGZ zP?N`Ng~^Q&O&m><@l}x2koesboc>gT{FV|S8u6RtQ~Jy4f!P;8m_nqe*$_=HO)~Mc z!QFwSl_0E7utfWR6I@UJBNg{dVAJrKbLAY3w-gOqkD98`i4C~f1z}&_MIf?IB~XQEm|Snz=#PSKs3^ zMLh%FILkF*KlszYw?%-K63p#j!oD(K>I1b6&^`mlhy9I(Q)Tl`0Y76nHtaWEn<^%f z&>?xS$i~NoebJ_2;Zy)#gE+MDivHQK{};g)4f{Hn^|?*&1?NF3L4HdK8}^fD1!hNq zFrG+Jvo`E=y&qV59fZ{hmQ2{c09j3)qV|CBWxSSyj9;$IdRd4$v?4;*bx^Q=l zz>SdE0*hO8FM^_K2g2yS-_6)fx*-1{gUQi+PcEFHbOpTrc{s4=4X#R(fyR6^pH~$) zhu1lkN6rG^E3)I{Qw1(nPGQbY;GYqv3JQpwG_I$h%2Tpi#5oD?h_EI=B#HZu#mZYgcxJItx0^!{JO&VRtQHvYuaRUfxl2mTZTUWPc_yW&bCd@gOCm}mf~ zsWBmk73s~C?ts^!lc!w(^@x^c2U;mz9v9*XehSd&Xla@^(%a(urQ-#j1!%D;9keNP zZc}>s_fo@F;CqaTfJ3uJI^G)41K%m7YK{Z{HNg&ZaDVlKH%s>>Co3l}me{`Of_sV6 zyWq~(z7iqV1FuD#m_BAsH>ERim4@nS54>}NowvRWIq6wS_uVa=$AFJWu*00*O5fcN zFIA)8z*xB$1>^y>4!F$q)vk~~N1Ut+bfcC-3O5z*?{&RwzwYV~rjwkwu;4CWb z;o%fSKb9c!8OC$@8w<%%bV)$v3FgR8dozEklm09|X^U4|)JJw(f^3T@K9MD)NlO2U zoxD2;1BqnAUPyW^&Kaf8R{F)Cq+P~?G>wR~2gY*nz2M4Yr7u?j-#{F4Cg3dk0H@|w zD_!sp+2#Ylj}s@sE6v3Blx~AhQc~kw0x2yu8_yp27cI0^>3hmZ6O;j|AraZ)EoK+z z`U5Ap$UcProAO$fPM{C8wsS6WMCspK$_c~qpwG{t7Dsah_>}MnOxe_H>%sgahYIld zZM;V=9p4mQ+DpDJc$%30|J(vD@~_f^7Rg2z2E7Iq;eN|@3%H2y>hGrDPz64<1-*L? zwFExpb@ksk+ehpt!JL#s1&*$9Ehdt}uKwr;*+Z9tx!&5Q?h9I;iN##)oswa8KS)1V zvoXYFleCjw+SLnt;pL$y{~t(^h-s5VVg*;{&XB+?4N?svCPr|}#_+L?}^MhO_85xq5FWoQ#0Qc_6LI&LR`*yPB@?6LB|4hqANy zU1gl5Z|v%g_#y=n{~!`({j2s4Cbn>Ofmg(0VUQ{kF=4CyOXuYdV8=THxzUw=ygDF` zQr#}&@_>poNWCMEa-Io2g~O&ulR`v*Y^e9hCrCE;{@RP{dqcnkYS!1^o?ageZ2v^c3SO1Sg&NYBa5={ODmjGx!kF@vZJ}005tqZtWc9c83&Q)cv z>jL;8qHrY?^KwEwa+g;Q&x}&WD8OThazAYdpDvHwl!oRAL{$sf zLpK507A?zYSFcVVDfZwjR7oZK zXkeL3JnLl?l#%Qju&YrCww!Z`ao#82$t>Cm?E7=5!zsb$U-F9JK%1KBaS+GnVBRS~ z!)j!TcOm%l^&${A=U_STo=d#yecVSv^GmRQ%fWnXiMd`Wya0q8O2!Ub6pOTY{PqS8 zE%FK;lufMxVk;tN(>T$qACA`q`&d`{@j8Ls??grH-F(!stkC~D>Y#VY#2j^uM%mb- zj=W89)bTDdH-KI=wh_AIqGPJeTTLoBOmqzEU|5Bjyk&I{TRfl3H%n~#I&h7>bQP`*trLI&jdT> zsAG0P>A&H?pHHx3jyf7()TO!>0AG<{#~gKhkB5wivlIAd33kj;$G5nqnq zEH0y1FOY_0XVDyWJg`fKvPmG#&&DDjb*#e#=Xl-GxLxVTTLogj0&CIMDl*iK{C2H! zO3@#hb@>lXt^9{(N&Z8#DgU9_o&S&&C{E^_s(b)2+|`?x;}E4VtQE)NE~dG+Dj%YZ zz_*}3go>$!{6+=~BnB78hmR+`=s9-*>t=AZf()?4h>UV`Rjz`Mn;~Zy@Mp8*JniN> zQ&l)~fiES_dnh1w(zu>6Zl0FQLe3UoA6Xmp&ndV+E9^vuxdo}QA}sn}a0AuPccw@q zu1C{#rJsHcaF4slvPLEUmn_Rd+sDYVYYWHAvJl>_tJ)#+PAu+cw8>VMeQ_AFtPk=B z8!SPVrR@$o--=r&^_ zD$5#mlhS=;@0@nmV5*MP4|uw!Id%g21KYd7!%33iMuTaDN9QTv<${&#{M zBg@vlEOH>vb%=f}LF5}*_5j{5!}C9&ngny?TUmCwjN`OMc4vZY)XNNLW!ar$!cKn> zMiR+}eK1X$lfl0ol2uWG>dYy$ovambl~V`SOSyCv$r1O7X4 z61=jqtXO;L^weSq5G+@DW@K6GNw{+X66i*d+7OW~o;SNV*B>}xWZ9O_M9gM^KGNFG zxd>!ggHCb^WCrMO=1@yimfd}WRIm%o!#PwCNFd0v(XUGlgfqLF3SqW>s6r34Oruv`@?OOQ@xXVJ*AvcZUc1*BY< z^{?7$Bg@t%%k)qVq}oJG*lLz#qzoMIAE=M6^y4)Lv0vr3nDbTSB{wp*6e%tIp;?#z z(A3I*XqMzZG@J6D^@c-Ipg5TeWZ4u~5C0jm>@667mpu6wJr~HbsZh;$7DDYq{vm_K z%Cc#$ezAad&H}q=aHaNHSvK9xwLT9fdgNrl+oD+5ek^B(o9ofM!l?=T7UHC#fN(^X z&2;lL#f|?RfpxVu=wBeqCc8zcu|$^5kCSE6h#lZvSNiD}SwpgxuF)U5{(s4`3h}aR zH7bieTUKEl{fhxf;iiOe`M@L&z7wXT=@aekH$n)mVKWkrQNd1NyZ|v!FL9y;~M>wI7}wv z#Q~Kin7Ym3n}X>Y{j1m{f*S&AZAu4iYGhe?ExpzQct2wz;22p}A}rNB2mIv(J4TlM z*G23s2fi-Bj*(@DCx_XePl11vV8_U^X+KMt{0aO@f*m8vDg~Tt%HjMkme^P^vaIeL zJcfX6uLrz2aX6wW$I(WXEqfr9IS&BulVHclvTfIh&trg3Ot52Q*`GsXdVB-;o5YdG zH?r*M{&FE?7ofcabL3lDmN7cye2?ru2(nQxQ>B$ylfpV0;A9aci+9RZZoY9a{uv%bGkbqUI9l1uGcaITwK}%XLW39#sXsDHUPA zw4k!3%Qm&p5rNSINtiaaCBzAquW zZefrr5-~CIj4b=+dm%Of>5l9y8d+8gw+E1q4}l z;}(!U$;KkfGExSPHwhJYr62EG5c@TG6dFoJ7Q2zm$|Sk)hh|;=LsKjNp;?mu&}_dJclCyUag%AwN;ngU#chW@FOX#`fL+1KrJl&|Z?ITd_NJ?Q-IeS- z1MDS(t2@bnoGn}F=BnNaN0rD~0{orqIIG-TBkmQ>Uf>6b)0Osqwj;9aEjQ1!e_ZDb zu)nPh`WMKuCGK_9SR%{bjgw{4h^NtXUFoOaWPC5(bxD@>uX&X$bECITz7Q|VTA;Dr zm|G`5J%uMEpF-wn0)}#%nOi4I-G#d|XCQx(!4hQI-#YBP2W-2+)d<^WB+EvxNOhh; z&Jp0Jv*SRPT|d-ij;ey2V6eF3sLj|;RF=WX;=ryaoP1QY8IJw|eL`o;vhbh)3ZxM&R6fcY{ ztMwc{mkG`u;9puh@v^Mj=?HUv1^$n<6EDj?$MFQ&$y-%9nOMZ17!Gco9C}k4b7}!^ zL>%@frY@W<^Pd+xoq=~XcA~PZ@{i)m6M#k<6H!@q8Er&f%m6euTH2f~d#;W+@GhXu z(bDE@nf_die+B4!Q#$B1Bg@)9p2Ri$3q0utvklUwMwV?XE7e>FyaI7z`o_qz*}KF} zW8iHQ>=;?L)eCW54+0;MV8_U^M_Z>dXB_aU33iMuYaVb`0$-nC$H=lBsbRLWANaQk zc8n}5vOk$Q7YMHwzgQ=B;?|5tmcB*;>Uof6WM|RHvZHwO47vUmNFQWp(a5rk4+`-c zkbch2qLF2Xj|(x3i98>ctG3$6vNf}WSP7(?iI}+6MwX?1FGEL1kg~F|$g+%-f#a3K zrgWtrZxD$6?wJ9zZe+6?SyPLY7XHwz%YSHU;6EeX*+Q5$2ivTTQ|H{GA)6aiM&;A#mO5Lvd<&Gi}H zEV2?g4S~1LjBHK$dNFuc5{gS@ubs zER#kYfi37tKmEqEO$%h1Zuq}sSxwlBxrlj`s*RCle|`X2majIh1YmLZa+?`hR=6Bw zSyklMHCTcy8;r+^+XL%taJApI8OgFe*W$Jmfm9Ic1pZe+-^X84*A+yC(D)lVz zN!Ct`? zF&X%5Vy-KID zof5z+5htdPjVwEjM}VoWX23fn*fFxK$&nCqdIKMnV8_U^<%^Sj(jW2T9@>l-1U@G3`;cXWxlqu ztlegu5CNenk!+I$le&>*rACK&d%A%15E03bSPo>_{GHNIPXm9EIOI&gF|up}-bYUD z`#SKo#IgHgEb%?1e_AEPPe3|K#6-`GEZcz#KGXz%gOqWzvG}{$#o26N+sLxxI6|i) z6+v%GMc8)EMIg(5{7Nojb^(204z)yO*_(Jan<^L&=KLHgh|03<_(nIe*MoT=2iw6G z7+IG3k*M`EpzHeoa|^f#WZ8*%QluE@HK+);eEdd7Wm)GH;!|5NyXR0rRF>s_T{`PY zFvnZl)X#z6<|5|2cO{Ho18I#l8$&d*tTEnGMA`d5`Zha@MwVrMAp^(-kaPpn5-}Ey zEc*vHDN%MYkg5_fG4hNoySI>paZ8XoWoOaIvM2E-H?lYYq^Gm9Xk^*jC1hh}g0w6< zi$<0`aEHuP+d(>zokb(dzPm%Ft1}>7%EltgGExSPw*?+{r5`T>9ntSyytNpz>n)_T@P}qy{zFqM|Djou|Ilp8e`t2+KO_Z;les{aeeLR&$Wo8P_)}Qi3)u4lS@w;q z57LJgUPk^LgT>0S!>)dB0PYI|w%Oq75*ZL#cEruqc@WwW^BjGG6zn! z19p$KL7U;|HY?>p<6MuVIg~RH_)y~1CpQF!EL(BGWq2~6=>#`n*vPUhyit)#uLiV{ zU}^;=H5gfT`mmVz0{AiFu$RIyvh2!fH#tnou0t^C)hEv?1q!#&-1`18aq*0_C(;y8-U(4CZe)zd*H<` zKzpO5&DpY7{}KmI0{SId+Q_o|aho#v=QW|%k(joS_A;_;>lxY3^1!PTC#Fq}EL-}$ z*l7d&?gTqVmVH|%nd^EK_>&2Cj4WH;Kg^sdz~?2{F|y44#AnWXz_%yZF|zE~Uf~=8 zemcR9k!2%CdTd8E#ra<>vD;;2S?Btx%qb1LDsf_B&d9QY|Am;-68Ienc8n|=JX`Q_W!ag>@Ih=44im|CQ81qx zS=M%v#M*g~oMwR^u^h;<0Y{{t3IQ)g9C9Y$7+LmEiuCu*z}pZf!7F>Vtj2gDW`Q)A zh>4yVSvCcil1S7{1Zj!2*vjnUTz}w%k!95%kt>oPfPUE8&bbI=+5YRLq0fV!+T8dZ zUnDBae#Q;G9SvKgX_;doye{!fGD$6$9D&uqB7P$0}<*HsavTRiY84~J&bSn`P zd)3IYA65ymCrE>`vuI@5tTl)a3`7$^nvAY2yq=qyRx%rWZBqvB#e)N^jmfo zjVyZ{cY;yXDVU!NVYzCnjV!D1st~Jz)QE_QTWw_7R6MXv7CVE~Cp(KqmW{)$&_o;q z(kt0mWLd_uj@J>iuJq$A1hJpecxp8q`NfU=(2A56{?M$;e`spuKQv47ADT`156$lU zhonGpG8f3Q-*MMI4v7_Rd~xz&aof|}E4Tdr;p#@;;v!}Rc`%5oL0c@ zG`Q+a21J(q>E=qsy*6Eu^9b;v*>TRhxu*3J&Sc=TiSr=s{cJ~M*##Hxw0E7ifNioi z=wBeq&bkGtu|$?#ij!s1h%3-^UFoOan4{Ew{Qj5Q|CcPoBT})lEUk6CENg)mdZ|Xp zY=Olc!EI*FmermO@4F!XA%i8zvO_(>&TwGQ8yuejH*H3;?DJ&b8Hbz&z*l6)fh_w5 zUt=Q9PT-#rXA%-($I7w{IC&D-@74xwhNJz7c$)^!mVK}mZv#M1>a7p~SlnskhQN?z zm+`H1g3AM{Lhx*cjVxIaEvUgyb(|5 zgYy#bnbwX-F6Q8D*~};LU_LnS0N-Nm2!|C9&X!$D5qA#){~^JSk!3~pi=F>~>o&%p zn7VKgb7bI8G2ms0!@X;7`QQ1Jm}mf~sWB0iWrb43i!OkAL`xf4b~bR}DL|v6rHw56 z{vh205@iGi>jsgEU!H$t-^K*$D2)9G@V+kVP$g-0C<)lVQ zK;;SM$dAgh(XLY;*=-53Eh6)^m1UhaB{|(e7)T@=_Q9lXWZ9ETq%X&VG>wR~2gY(B z%PQcBXWE`sz&8+woC!Eamc90!w95hD$BC2Rm6c_0;(g;}>=H<6?X&UB$g=I5L_m}Q zsUZ>B;zF~FbNzu6MwWem*DjI{>IC{gYdhy6kY#(v$@8A$L7$&PEm2t(zFyAYtq1dy z94d&OExWUvJhX6{m>vG-78qIf^TQ%63xi&Rig3SWy9MTK+3^i>Vzn*k-E*iVD$BmY z=X(1V^n*1ULo~9?t14sde;`F} zGi{Pc#FLoC>&gI98l)OTOpIV7%TBdQV;|ds)FnHMMwYe0@hVmHI7nl&vuI@5qpf9Q z=7F>-JBvn^oy;pizZ;}O*;zEQtP!4QrKZ2?Dcy&PR*X&b|WLYQ_c>-tLO3@#hb@>lXt^9{(N&Z8#DgRkvI3xv%les{a zC5QCTm5^nx!T2)rWC`}XK$fM1^r~f$W$z>ZV}r%Yveb}1_kNP|9k5>vu2zx(k!5}; z*OsAa&Kl%+@HRIVwjaxhgmUf03o?jP9(Z-)Y(PRdBFoZ4d3wUhmcZ_?Ht1g<%e+ug zYAlgu`9iTzVoD=6fp=Z$r{BAG`%ZE)$+C~{y-JoPN6(fWjF)ALP+4-!*|HCQM!OtB z=27xzKW(zT<-gE9@cuk`cV~bl$g%~{!TEs|Gq^fL2JG3gwEij1QRLhNyh(N($g(f! zDg-$90q;ee6G(_1E6W~&lTQJA&f1{OaCE1&a<*(XJ`h4V^MNlW&d=nAz>sB?%Z3@= z3TP+6zcXxP*`-Cv3?Bvb6T#F9N@_5&Y)zKSoKQ#H&4xw16poQ)Zw*OePFdj9h{JYb zq!MJ=;ws{4Yv3KN9pM;Rb`1AQk>!5CpGdG{WZBm8;?K*#=OoxMXUjSb6+7#IZ!&hG zXUon7u6zmTurU#pWo36u>GOd8jg~gD?Bh|gA^GmY^=~ZPAkka?hZPa{MnLrmj%iaP z%lhErF>U8vz`Gd}LAx7S_EK-LGYt5%33iMudwIXunG1Yrf*m8v>iiSpy0!t|mte=p zvKJn}w=m$(Dd2x3*fFwfeHY>QcjNpome}nwvaEbwkL^?eUWYgw(Gn|0meu((g*mqa z?~-80$g=ba;`8IcpH8r2WZ62Ly`$-ICh+;hk;pf)tZ{zPB4hxZGt_{2~amW~(qusK7%~aj>20olP0aiI~ zS^Z;*I2)wpM06_I)~MaGzb7gW^(R&)W)O0T<{Xzb_ujw)}V`WEH{CE z>?Ilai(s{^=LF>{-T?i{OLFnKWs{SXO;K-Q)gM7se_(m_mj8`M)CgM@%tpixY*p=+ zRmPqux>0(8G|W*;DYmuRE$fI+^HB0Ekd|enQLmP@#o0+j+yT)w zMjEwSRt6_9lEyGhy9o&Y>3P~MyVWjK5?=$UHW33$t=+QjCDb6-0i=EzY1D4nxzVcA zPXcK{MjEwSwzG)JdJ{-{GSDd9GV%B&!ICXh$v=A~fsD z2u-arLbIfd&}=FrG`q_PxdORJo$Z$85Y}Hk;g(fsiS@+z>qjt+|1Zdts@LY1Z5vcl=yGF6F}P<0*YPs){CZrd&E-0gq4W%P9z zzlWIRQQ7`(+2A9nmwrebj9}!aB0FwbtqQRIJ*3amSb$qL;ZzV?4{VFZc~Mf}xMiyj z;%Ek>oC1C+BM#iMi{&lJ`2+Y1;*_O2lX@Jt?9Sm}7Tq43fDxpPoQlD$sKPi!602qI zYxv{{Qpy0YM4ZZGhJxXiP0i$ya0@`R|Inx@VeOW^KQ>6hg8_{um}NGp{U+AS;7$}KrNfgg7Cq<71{3d84GVCgmB_Z>ay-7?QQrN`X?=bs@cd;B=q z@_)FE(o+a{5^@y9-muw!8WB2paEKi&n-(>udH|v&`h7ScFX#- zRR*jBw9zN6SIZvlz$aW#&Le=n)6#aGYPYONTT5~t0RKm;usPZ-`=`FjCbARq zsok>k2l0smN4sUU@S!u(V|2z&FoZy>9Jj1$ zn5vw@AeAR#pk>-ETbrUhl%^o{bu`w~x46vTHbSqK&77^4f+m2z#L@k75x8aN@aZmU zhwY%Bd`T`ox2#Gn4FE|2&zspG)KE-U*}aB)B(LSiOAY{ zxd_~{~n%u9sxsTP@p&JyF!E7r?yj=%y6A=CxaP9Ydl_ z?uwxg;Xkda-Le6gS%_E&q;fAj3JYPakj z9(PgJD?s`pBaPZETmO!_Cr*HLB_oa6Et}+4gUVkZS(wcKQ)=y&jeDUweNK={5HYaS z+AX`ZQE99LQmYI!O1F$W17>DJQ99Bevj>PN^ICeyEh{NPR(B^)3lW-iWrU_y8KGHH zMrbybkxNh@BjgI?B6YS~_NuUcs0g?043u9aOB&(Mv)!`Sgf*=S&f|E9^d}ngcgxBM zE9gPTlN|bWUdaZfyVi0QsB5{gXe~_ z2}tPeNrzr!f0eamh zt=+PknHAg-P_mY`>r}gCL%vbv90z>5R$+6rTUNHK(z6Em=K*@OTb352+V42<3junx zTecf_9o73I;Lif|Xt(VCBGpYY_vS1of`1!pw`|A9;O_+&I;h41?bUk86Tyl$HTx+5=ZrX?UpV5%AWrL zJs?>2e8(-z73*Ol8IOJud?is+rQ?>>NDE~JKqx~br`y}}sdmc>eW}XR2&6VdBs=^$ zaLfMkcx8D80e^=$WQ@(xZdrj1s=XHgUqc+He*KBq@?R6LB2(q;0qI*J23n@wvUkd; zHw^EBWcJY-Khn)6)!MqXTUKy_dY+d6dKnUtx?e5=w=8LyT5DsxQ{R5LC^l zFSO4sEBA>iK~*rD6FY+{^0{SuzEvYp3YeoD-PC-x5!x-=Ib1dWe2`WmsCbfAX{tp;=c(Xlj)ank8j~W>XoV*)+(J_rYg|`tsUu4%B|M=A?A#s|H~~4#TSbF+_Ij?%-=0L?uA?SArhC9 zJtt+I>AhuRaK1O+j`aN+3vkQwJq}^t1G}Md{+&~2w6|>d6_Z^;%D=!pskVN94&1V; zt-O+x8+cLT{6uvo^*Cr;6 zyJf>ne54bWh7Z7le*~o`y<7J1iPBRVcxB>9d;B<9EvwR6>1hePbATT0mIZ&J^o#&L zM(gppW#8GRd;n;PR^fBYdOlUs+X3zNN$b_J@wNdM0sZKc)@~X5%`40KHy|-kmqFE+ zcFRh|W7i_;A|7~t;`r66cFS7TR^_Y$yk3AF?UtEal%6iYQv&p8w`_J6L*_LR_^bdu z+ASL~%p*DLfo}=WqusI(hAPe};FkjQXt(UkQbOwa1Ne&oJ=!h1@x+px*g=>C5d8a` zcFUfuSLLbzyf$(C>PNd}BY#t?WgUQbBaZ6%+AZVuC$B~U8b`3~`How5Z9iuVk-U~5 zr`M~g(s9dP33jtxAeIdIDs$Edap8H`td5u`CT zN4sUs@o<;)lmK3ZI005Ut7UWFP`7+5ka`j^&@%0ot z7XOxdLiYveCmr1{7lB(=(p0(J2L1UrPgj)aXah0 zASDqou+-Wu8@e@A7N!A6?K0A+-Llmy)$o!A(u52&O1F$W17_Ai<#eP!=3Ed{dPWD+ zYFT>`a&8!TT8PlBD=SJ<2WXB_bNY$Q8gob97M5cFQ`7f>c?`E$f%gEmM{FF{-X3{YlyI z&~0z|FYxYv+%ms6F=wTB%h>SrTmIKKf?Jk^#PSG6BJB08mi62Mx2zG;+h{DnE!*=g zWBq}R&^Rwh3Y^ulRpTsH94T{vf1D8qZdr-HLL_G!@O{KdqB@g$9JlNcjJyc!XGaGW z181G!d$sfsGww3{exy7{5F?@_=d)OtpZm zEtG?H%hsGwIkX4fi#XCs#nEorkee!-cY#lJ^rUyoj@Jp1d94Dz$I-VVq z=A*#R1?bVMWrNlzJr99D3DBe6veUPeJy9d^BLG3QuCwL;LS3ce6+mSOrXu;=vTPNV z6^#J3@JVa8to2$Y-4D=UpR{(%W|UFzG(Zcrv|Xp#E&K9_SC(@#@SR$P&CzaI$w^Aj zdEnOq^k}ziV@b>psIRBM-EXIF8|{`|!qx%e}-X+AS-C zJvKBw{ssIwaa7OOZrT3EYM~`&6ue&q)$<*<>=|CSDT(B&1UWUL=4;0-`va#EHwU2` zk(_RCPwLt&`y6k^k*%XZnoLBp!=D4UY&|}MM4V;7KOqj?hBimLWor(pG9Ltfo;U$k zIc`~_CaOVy1&O_rfo0k)`>dN{fL(%pL&goTJu{sNJ%Pcom3}AAL*;Gb8)*NyLa*;aQEgLSZ;rrm0&4=<2$&xo{mQilm2w`144!7)cr0>$0 zzgsp^SevU0b{5!=8s|+&fpW{<7MV7k_pnw-`5U-^#ZtdNXOzg)@`B>T1J6&K_H_44 zJ<2T`Eh47D$O^z}J31(4yJbT}R;n!JmQ6_KmZ?g74Y_xuKPj6-J@&a}yWabcTjqD1 z>__R{vU!xP-uu*CC|{@Ygcpz%6Te8eh``ry=mSh%*TnN{{1~O|BZs`T-m6=%8XSYs8!Q zE;HP+5@S7#Qf32RNStY8hJxXi4Xlstaey}i+D7mk32V1(5w>v?{4Jo%1XC?=m4kN6 zD&J(1^CxgVUR$X++AZ6GU2>F?6?k6aNImJ@vi#A?(n`SVIC|2%W&7|=Y|_&Sc%J}0 z+AZ7OTj?1Od`5sC?UwyeLFriw{4=e`w_4WNHsvs&lUjw(E!#3zN#6$az$dNUvg*mo z0BZuCe4>B81AU9j{B0w&Tb5i~IkVS6f9~jhxd_~{;?I<$6*C#@UkJ+X z^ddgD?297m(Q^$jTM=6tAIO#t6AsA8gq0z3y;H$_?sLupZ+iMry3mVAddZV5@4ktp5R* zB(?>qkE51EZELk#cCeA^Z{tCln~_HCmSygtZt71#+Le(;?Us!yp+=euAl=SLqjt*% z;J8I;5vJV;g#YwB?UpTRDkQNGNactaSZeK-RUfW8eG`y6XQWZPWxKs<^cextdl_le zZrK)mF`aB&0n!&4Xq0Xlc?Qf(1Fa+dG53L(^3_B-r9Nb(2ysm%mkSY^b!CL6RvDpL zQbuStl@XfVWrSRTT%^u+%hn0&<9ztQQgIBfNeIRg+Ej-O7w`>G{ z=}<~x;3bK3oy<@$+%i|5Pzl!s)R5pi64q|n#;hR{?g?lh!Bh)&4%#idUs&bvKJfX( zkya`zv|E-FM}$(!M&LUfJ?Y)DlT(5v=R4q69X;vYvV;F9J^uiAP1pALaqtjx)peyO zJMaR;k@ooIg)RRBYqzf26{G z2xz%aTCbLs>cb@bHK0RU+OAXWmbFtn3p8mi`1nALj*`@lbTyubb9H2+LWz*hP z<=O^(Uw|IHTK3|xN9J`I`0W5a+AWJIrMfMjiH9Hv{^inc*~PAEVJ9!}!o*QMU%O>R z&?9I@uK}no!LsK&ZrL1srK3HPQwVZ;y_x|Xw=D645H=Qs*+g=x)}AJ{Thk{$jWxMkz^sxqGj{sVEy7@MQrvN~`@NzY^8=B)o(<+x>;Z@DEg0icFV3mSG6__^x2N?my5tHTQWe2Yyf@FOLFnKWjnDi zm~6TP=C3cwz_(h~7;k11+cO&vyb)AOWoV9e%Z`1cJh=*>HzyHUJ1-Z3TejbUUGC(JKHs{-Li2FU9wgG0Le8++wDix zZrRE2(d>}V4pLDf2J~KM%m3Y{>V~ZaQuB;7YPW2}Zq=buKpK^iM(vhOy{x+We2`XW zq*1$Nhj3OR+4v1er!&&1-LiGlRj2<2q$e3^)Na|V1&SDj89x!>Kc&`gS>G*cNUQ)- zeIf?j9nvi$&w!a>u&^WjG2a3)rBsxl)v~We$OrSt(?W!1T^XUNRYqu*lo6UuW#j}D z$OyRtxk#PumhBPN0ep~yAAs^>WXWUPdA3`&S6J`-3K!!V((h}`-!0oGtj1*oGhj(5 zf|TV?Nr7_9_KQqsuv*5yHCaC3B{Sk25SfxTDo$PC&4^<`Kvh3;0UPA# zpqTBJ?Go9jvXonPBAr{NDzPi9??`_}8_)2fUAJRAwBiChqbfa4u<+ImLwe4~ua_ZJ z@yc1_*xS*#Z?cuf#MZirya;O2ZNG=LZf*_53GR=PD}Mlr{KMi~UU9S5t*l1l@G>cs z#32}@fjfU#{H!~{taV!}_F4!l3cQr&u=sbnKye4FRE{848>x*oBBj~jH$nw#-5KWx zo2-+D&?Pp*hPdf?`6{+`_mJ!;M=nZX*?z=l*jx9C8af0s1g1|!Y$XLM5C?i!5(%A(9Hn&_IJ=b$J%YV*%Lqv*(<&0_{ime zK8(G53Uek@i5LfCB>fw`+lzsbktf;dK zoOmg<>$#V}ML_P+4E3q;&iCgBe9&Mqa>4eNo5e62$7Y_z92E zkB5$0g!2{Kmt_6VsMgk&BR%+Tda(_hJCjZr`NMsHFXX9ZYPdvV6pn@8ur~ue9#Eb zGSxNg`z3KyGmCXl*Rbzy;;gqU)=OQ(zI%yJ+gog)x`uuC6JH&TGY-`??0b+ntEa^# zs%zNyFmYoai_OF}OWIfttxGMMl=+g2nUg41tP0X*QLIx9#1>PGzmC`{ie0LM*hY$7 zz&|KiejE_2+?<1D?^)uKOoLb4#cR4;zm9wXdrB;ui zyMmj`0UzWMb@5=mQ?`w`pv#cv9+ui!UGjtcQX!yS)TMEdzy2QNyQ)jqL0)aM!BV@a z%bb(tYl7m+gj{H1x{Ynf&9|GI#;3Ut9#HsAI zre)@WLYROLfpx}VvSN;=jpj3)$-{30d+y*;6OoiAW%F+HlYvNy{0L9I5M*(r&FYWL zGtB*|$x=_7%hy6@1+Z#srt&Nz=_h^a59au?jLA$o0Pn3issN2 z*HO5c{5$HAdGu8^>X3Q$RR!vg`SevM>W=yKRXFv=0{ZH=CuoI&M&U>p6Iu-4f=w-A zn571Vu#+F-B>)8DGF4@0Q+$>twS-~b*e%#ENdDCaQDIXn8D>8`ATpP5mKi}x@q#n~ zQo&fLBvm%dpZ>B~ArQ(rB-su9NL38;@l>3D4?=5)q;NqwRWn@KZkj9w*f5Q&E~7H3 zVVDo!4QA7TE!4QQ1imSCsoIA5E6z^(6xjCkxYd=qQ(ePcm#BUy;>1 zKO=a^u28lLgiQ`9iIhC!lF;7>_MT;Ip97Lx$K@Z{MsiSLrh%3(_vSC?d`Uc1c8-}m zFWmxVcpP2M<^=E>74#<#nIEaGxw#?*9^>ruf~B_Q<~p3ML^VGevUU@!90;in z+^mq#Vsnwa&QU7|68T3q)3+9CDJc2jGtWd6KK9uSYo>}&`nLHJ9W$Ir%E8VuL z?>yn=n3pH)~DtGB1?HAo$^TIN^q2##h0g~IWu_E z3hcI`i^$pLsoxAX8>E%Xv_Gs`1UR+86n;`ReUp_AT&h z8F8L|hc(_+=I0|#_9yUXn!|FFBOAHN{Ckd9dYsX)Co6){lJd_@vu@-UW}%;h8D;hg zkTO2B&T8bm)ofcalx;z3Lxko&^znrd7P-Sbk59eQP~R8GKnI;H{wfXcd{@}u4r;hjxezh1TYw>}(VjDg`Hma7FZz6;=fhfq#dSU3-nzZ=TQ`ikJH!k9_Tvy@*>v)JZU_>ITSGx(m} zfDVS2FT=HmE(dhMH)yUQISW#Vu0AJEeXowp{G%|Ht0!@(Gzo~7>I0ey^Ybob8Wlm9f>fWAhw`~hh` zLO}~H9Oz}{YKXCjfsMV(p($cu6Yo6ve^YO57hSjUZjskry=UbAJ-iR)|2@6#vp7(k zSHF)}{8n@3J<-5qTcE1uSKnBy;xshbQa(mtbx(t|T}Oh2F^K`(_kJj=ror@*32)Lu z$e@ozNNW(}@3?}4=W0b)y%7COZ%0P0%m!HQcFec}s0`~6QvoC8@A#x8Bj3mSB zeS-7&-_LaymAjE|Tw$_C6(iT(NpYEcdGUo`^jlI|}Osn$30&C~Ini0Vc&wQ$dgvk%!_kK@`zY zMKOGPFr(KZ+Y=<;kF+f;BXX04;0_~59yFFep>PmOdrQp5i~f}PY(k_J3TYue0z!Fz zLWndXf35BwmeyCCI<906`D7&0OI!j%)N4MOq*B2wZM0a@D^%w5%qJs}kzzd%l8IU8 z-ErOtWmU%!QqT@A zQUMXUi%;rTc*tr0aPb~yVv-u=lakP5F6IFusfCWz7~XYAKbCe)#9s-LQeQYyHgrYg z14L4%9I2=?tI$JAaB(tHHTSPtiie%25=guV7mHuV(i}v?H`s-<@w8efVRbGNp5h%A z*jj>cipU9*MM=Ce7j>9h$~Sc6<>WJ-C#Q60Y0Z%VRv1VwSt~#bORO;$tAJ7F6SXjl zYEs?B(t2`XY*&rA%n?&iS1!T;kdfxyYASb=4f7=;D&?nlP4&;rLh~X{bU3ir78ky(u`=<_s6h>Z=~{ zmR7)`By^ICPXLj`U@gk>7b}b&u|`}UuSTHhj*voDhzCGOX01=A^9YlrJr?!iRd?9u zlaa_H(HscLTybQg3QR^mL0lXwqFVDGM@T^~E-nBfspwDbf}xL;7c4Cs7n8nMl~S4@ z*#~5$C_D=nqb{pDX{tr-I$7(1e4-)7-D1)oO40HxNL-TzKf8L9h8*hkNrPW@r%|3+^8e@pDHgv+LP(p7Tq7ZHsa-Qz^6b?Cx8*H&5 z;!@QkN!LcF$P!v$2(Jz0AV?KiLURm}--gN&q>7wp02FRE#PZKnky~qpYLbYO_@{=* zjFS$?mSI|}ty<#i4Do2Q!WU}Qw*H9k(BF?6;`CG15ZeRvOZ>1Q!r=yy{_g|yOMJf} zGX1OYCjt7`ehvM%46)>e!n1C&E5x>6;@1t4%Wmy*gj229_DlRnLsT*B@)J%~W81&( zSF|7(qT4K0;ll#-OZ>SZs!vn+!T|je|HlyZ?YBU-2k7sx10!`dA@bvqkSu?Ieu-xh zqWpS=KMBw;@hBngY*KjE&FSrrtql8ZC zv8*iHKS2Lrnt%7WM8zx0$(W<{vnUDebcs5Es7622qAY4W&A?|}qGvuOb<`&%p;Im~ z2oOo#^hrIW8Th749692alM?^jE(?p2&^4Dh2Z*HN38Dy#ipNXjX@9#!ExZ&;1%J&a zC80lDq7fh>H}*+A>5rix*c5+b?SZ6HwUphjBXndOseI~NnnLsPWO;*vk7KJiIO=&mWc z+R$O2)E4ZqNaJo%0-y7v-(Elaq$Kp*6qRh~g->c%E#wvD7F|D8T{0`4Z`)NOp-gVk z9}roXL=Z(-ROL<~EG?f~JjVlbDpy0Fl!S7-MNnqd`Fi`LqNxtcxJApE%2^%nlaf$r zx0teDNiFe7wWHdo>lSa$!9#M~mOFe>5~}4E_e&}0yiaN?)kYh)sCFhuO8w@Ol2A)1 zw4u;#PPvjs!NR_7adEG@zX}kf1_KH8a*I2Fs1mCCq=wvw3;d2-{82@J4wCQ)2&k zYENx-!YzjNRhIP7npl*Cj=04*K(Z3FJd4^!ZFSWxYP?YSf9R8v&<}3W5D-ai^GP+w zPoA{j+~WONYI3@$rPT65l*AvnMg0Y8hWbZ~+IYoSw6)6;;j2_{jQdKLTK-oG`(FUpd-dZW7F|BH^8xJpmAieSlSE9!-zTMhQ`c z%RvH1vE^OvWz=nApoWh#(MDs8t=Oj!-Aq`kcjNskkU0?;J7A>cM5&`Yix8DzFMBQ5 z&aj6lKXsqZtBdKS3plSY^$Ix^U))@(erI= zUW1Bgv~>;yX@#m8i?+i@kL5<=$ts&Nz^eyvhU0au=qcRTheu+hrw#D#4yS;uuc4>G znaPc!F2#8V_>}aV0u#@AX%)tJlGQ71e!UMCM58xzBTrUUi?8?TID|!S;l}DEs$$+X z+P6<-(O+>lH4zi3oll|O>+vjkdJA?B>is0&DtM? zuu09BQ1MrRzL{!-#q7cMP1u07bZ6KKPQ%Y59 z%rT6rEL3t106(3cqbhB&VI1nr7~TA;(v}#;^Ch7&fhw&Fi(X-P$t)(ka|e0YSGX~~ zk22$N7wlyw2_|fZ$0hI6Nw}q*`?P8uJSD7*+Np_PtR~x?`?Os_ypH`A(z|Jle z#mN^`uA#t3X^!tc{T!?2q+&jxWf~5+Py25$rHUQE4>}xK!Ond;%B8Zo3jA&WN8hLW zuY08)7n(H_f-DW+E$d6)rzwlvl2ZV9sq`G@KAjQbl{P!~>B3Vw!M;yFtf>-w_bD|I zx}3iKYSQi3>=1Q1Dt%HfoZ*3);<(7s3%5bs-UgTxqQ`}~_hWC?*~}L1AJ=7ukBOj@ zo`Y469_Kbz!Pd^Y4=nMo6KEju; zk?K!p68*S){B3^d-TRpHk`!1VHcYx)KP5)5BPQ}h?1bI#)>R9M)F-&?-qCviK=m``ekjw;^bB$ zcu(Jh?(81M9%klvPc#zeuC@=4%PU3fa#`$cFqa~%Mlinj_nzWl3Zc6Z4mhavo=A!G zo+yH5B#$X>{A1J^@@|bG{(t11_q2!d9@)slo^um@1OL1${_B!x1t8TN)X94+ z#?`^HkFg^Q%QN#wQq&!1Jn&&A4_O0&FL~cVeb}%Np39DPAXh ze5lmH@A9uMt2s)lOW1>xq@hmq zhrm(?8tN*p?ZcU$k{yM0p3E8g?#Pse+zktrz<4? zf0U5wN|sQLRta6O<6Bxc80!BY)&+pA8ex|a&qn+BhIjWaB85FE z*sYGtE9zG{@X*Zj*7x)Q> zBNc_wJ5R$uG~4055Plul0|zIyEV4K^*zl!h5Oy2p#WlV`j>#Rt7$xnDxdri+X7Fs7 zkQ>Pb2vT)$H5HO;%;opdUn?THx&uY_FN$NS)|+?XkWgLnHh?-2ER{wM!qep8o6IKI z2}EtjhXWezNWaTh77t>>x0n;~EgxF%;PI|W5IAU#E*Z>Lfwx6-ImP(9SpQ*}svm)+ zuX|5YO4891cq(U7-^<%!20jjxwB8$e3O%NFr4YQ|kgE^k%u_Deh1V#!^`J58<^|+} zPr$_Hct*h6;1BbZB|-wX_Tn&Ho)chUO;F7&=%;j2Np3Cu+{HSPTul%fYLe2TNDXjY z%E2H->IK3ehxBA3iYU_X^Ejy`x3(+^Vg2A$@M$2-AyN-ACDSbYj!60<^coE3;&=Q6 z#RurD`gpEH9KHj8_BiBX-MbECNjus-mCv6z-A6X zOq&86GGudo#G~&2X}825V7y4rlEd0QbcRvwYxHAO zMRB)41yi?%p~1;$27qgIg^HX*PTWd&9Q?9N2+>O0tu&g=aNPSlT=XqX8jo16x6<^ zZBx&u<$_q!OzYi|xcm4H2<)MZ%1}YWBsR-x{sz>YM>6#q32}~!?h2^4BP|D~q>rpoaKHIGNS>l4d0o=3Zr4@WdY^;UPR#}R8iwxUxKT|} z1vTr0to{~z9%X~YFW82iob@9}*6{KL} zh<%Uoc3%Ya#Un^bzS@U3i5Pbb142n)6&(B%pZZqTn6?-O0CjNSwNufrf5#t|f7Ogo zR1FbVgu&k}wgvfmBq@j@-&`{_--Wb22s1?o6V0%I*4o=Nl zJml0F>{6yACZc2x7;%345)M|gV~ zEEL+J5R794rAnv;k9cLTixog}DGjM=DKzS%+WJDL7a~BR~HUx?AD+H_V z@lHh6_tBM004wj{Kl|{}5&5yM#2W&8%fWx~sh?oo9O7XqfJQlRVE6dgI?+0W{R*K4 z;P5|5T6K?QmZy!y$ehiD$b7REM?=?K5h_O*ry7{-D>BXe4n>UXgAWu2)!Y_R7q?R` zsufm{(wR`2_gVvwxMZH8-$C;;U!Di7V_8+6`3W)T-VArI4q`QT6(>C=CFjqK?b0<5 zTiy!z>IWE&eM%&9%sSWE&BA~rJ4)hZ$2k$vv>QHygw*i}Ml`AakW1*>h-27O^Z}CB zX-GDOeY;A|4-o@8WBk|+!cm7LZG4*s{F+yzZ?!}tqd3m%5dI?34 z7VxZOhU#<`@KK{PIGr&OU@?avE67*dcBiBI);;ecS}36*jyvIP&7cq(#ncjky>OVR(~+%7bH64k{IMpuO5|H$x^k*jHvuL#T5Gd6sZD zi4;7uLe@K^=T;Q0b4ik1m5mtjhIelS9^2vnJM#ag-b|5n-NIW~{@>PHL;l~++e!Z4 z-utfo|8n_%2k(CS|6B6^j$Tg`$#?V?lK*$|*0cZbga6~IhNH&oe;v~K0%qun_Zh3d ztI);qxEq2?1+n_y6n=LS;^eE<-&2_0w+c_fD|z+z7OsQ1*PFzcd<`E3uW0uPvRo`pj@aK7I)!r5X%|cHMrVEj6q(UMiJX9nzCf!DR>|j+dUVde!9}vX2+tOapC_?>U|m#0cvU7Ary}qiJBtnf9+USG zJh{)Y$Bc`?Z2tlz6NyFv60dNWpuOf<+&?@klJjavdHzatpII22MR+-2H8swQk-Qvv za_o;hix1S7MnYS_J+P>BZEFPWn_kGR+dL(o-dyGth20+CB~ico?_ ztQk#SBy@%#C_)udCr`1@F^pTE<87%%NXZMlgu|H%bv9=lx4u4w7d^nK1H7rjd4U)U zCGS1QYHk&Kgs(mzWuSwT1Ph(gFoflJjYnqdr8ALJu45!(#(C;TO zmZKRD`Q<)7`VHnq%{IW1)#($XBuU|u1Q7IzR1Ki4B)V2t+9d+z;UiFN|g!$JR>Hy$gSfa79k zsl5Nj#s8@Dw(I2C8ncGG*dj1@BOE|5X87lQ53ivSdIjNU2mNo}IB8)t;JCumRNe!x z{Lj1xR+6jZ{T^VP1+xM|H3Vacf8OQsD1y+|2pt^szjXgdOjddS3hw_XcX(Y{ z?opNTgdEJR2s=spM*qCG3=NX#IUqkc=zsIZpf?ooG*K*{m-QW=Ly z>S%xs*HXtk(m{$c(jmEdA0=VlDV^dia1}#e;v(909dGs)%zb17u2OyD8;f5O;7Gk=w7JalwPlSK_|Em)Q9ScU0@uVF*D2Lg|wyoMph zvJ40gW>qHhP|{-(n5F3m924^)#L)ms{1CUkzyS*+zCN8er%RS)`anp`=b>@%FRHA> zj9BF?x5}cXzIWIpt8$E5iWTcBe{<_KQ!ujOF+uTE9Z}cugQ*HUdvfW>mT(kDL0K*z zK{+ru6$Z1sr}2(3wZ~Q@7aa7Ve|x;>fF}(Nk=`7^s81Q__Lvidrs|F4 z!5ZR?3D@lr@A0yhR7ZR|2p^;;>GpUXBOYI`G2I?yUqbdc^h#=vwb%UGqZl+g?Xdt$ zOh>`}8-cf@yn?~?wFl`j3Cy@X#$OduyaI%L;+!sD(jNB`U96YGrmR(tPJ0wB5yZ%b zaYX7u)#0>9!CfwC=*JEun}BR&2|+{gb3FMI9`fN06n$`0FRs4iVO_4{UHF)oP?o%v zNBr^+W|VTf$_BIKZR#q#-04R_EO|Q*Ct}V}lEa2HBN&?;{7B}K3MWWZme*JvMRvprN^If^1_l&bK?tcvbGvTJ?*QB*T6pKr51kdVhJ5^ zq*Q_A3p~vAGe!Yfv|L+JUKUD7@(0HI8SbZ#k-m~JnOCU9EW@hxJ7ZrV`GAJ_ z$CR0p#d(AG>0p{40N!#4D~S-=pOl9gR!4lE`WY|_eMst7_fs!AA|g4`$V^qi4ACE> zS#oB>DvarX`i)Tn{PJ2x9aQ02M*Shqu%`C%;=}O(TWA9F$i9-_usZ*QgV6dQeTc@m zG^ltD{O(OIVpv&rSn?1BV>Sp%v2WNh>AtR*rHFwZ)6noPdx*y}6o~;>M#v-?A@wps z4J0Gk5GhFV44aTJ_$GHVvQk@c^9Hy=Hbzgw3i`;+D1k@b#7EE(jP+Du<&E~}vjYul z)&xviyf}a)0yhy@LxRH$D>4sex_U@&t}(vVM;K*TeHviwN(MN>Ay7=QVrT|PZewJn z8Gw7F(svE(_ySB~AA|KpdYMb;wMtM?ryEwG0?7X;Xy+X2PM`Jj4eQMx$ol(0|8^Mr zh@n(0G^`>Ap(5-SMic~DJWd4vj8+@gG5XF#X)tOyEXv5A^{HVU!aU7egVD=j{fkpS zZPwj-=we3@3n1v^68SAg)DCUIFZMY?BL+wmYul8%7z zokNm^QzTPZLE&yidI-W3heSp(51smu93iar_|_H=zm35WLDhh4BdTwkl@CWIw!&Tc zDi~EAmQ)i{{53RUCnF~fycpjPthVQCLSvX$(@b77jS~6%`Psi z&|eja&jWKYv1KPL*0paJmRw3$uh;e{ZCikS?Pyc@Yr^_wr7eFR*kwmPX6m07OYUlv z=<|Yd%WGi_C@-u}@HsRhaq|wwe+1R5VjD0H)ZLh1K++BJomSmL;~dO;nzO za#t7D*SE0bOxl_NYvpKDcx_=t;w?+cgb%=@ikCW^|AXl0muH4{48J#eE7}r z7+o3)Yrt1Fz8TmyAD)Lw(^OcV=7!RL2G~U(UWx2$DXiH|+zS64*grn}8qQrzZY!*F z7=UDZM_~wzL$K{5_bIufux8|NDZCW0vOfH~_2@p>;(PK>x5AqMYvsdFtwQ-yg_WhC z{j7BWu%QkfLu*CJ?TlP!{-n0~y(_d07FNUU*dhlKUxGjDiA^I8Cj(i`w#67T+Z(a+ z(XA4}r*HD$usUM$v-tBPiBJVA5zo`3sD*JTWrYx&^a+sNO-Cr!aUe^cF06|9jV$wx z1D=OCzI-KTwy+A}%kwg$iojn_ug8-gpZ`jpFRXsmQJi)Fd!|<+KBM|vf`dy-TPmk_ zL71dTOyMhp^;0!Fmu0}#5U%>m=#S9eYtSF_+cmTo*kPZ%#Bt>OIGj@_t-KEGjwA0m zOY{4e!irmq0q+IU&3kq!nP&v)-X^SlBjHbGLwY`qajI*zE}D!}S4)q?C{O`lZHGXE z5SuP&%_I4Qux`8x52PzlE~}INF!5D9Jc;x8#1WS5X#C)#K$zyJklkMnH;VbMuxe&u zin#`?o#~mr(Mi!mTvo^-Tk!=@Z>OiL(Jsp@boU6C)p;-4=U*^fSWZzlzL@eMI!TPn zir;MyGYP;7YMhgKOpy{?R<1FYvaC7?P12DR)6+B->hij*&j+BUdxA04VM)_fmGXAD zKZ?7ol2cG&)4-UcSjKt@DFOKki_n|6k~1 zEnL>w5PO`y1?-u|rFrTPH3IY8UxQ}vfFgZlFeCB-)@2d=I=-jOYTTo#E^E>|F6>SO zSji!%LcE#}Zc!m&=EV^$MpJ<89fG`N#lLMqSTD>UYN=7c7z)BDO=6y?*|_hwx~#1j zC5<^qU!gJS3)$UoGx|^YGQupd5%zrr#wmv-yOUqFp8OQf%P?WK!d_g1XQ*;v#0?P)H9dsc<+ui@c11On5= zJ_vHTPe$%)kth8oj~74V(;hz(G=V%N8dsTu-WJzP9DGZV9Bm1=p~2!FegtR6{Hq`- z6}R_I+$5z2hg3qkw*_`f+{I1qZL1@{VYra>m@pN4GI%NcCL0H4E>goR+7eJ|Bew*W zvWe9jslySBKWSJdP4W+|Q1+9GnMwKN&HWKJ+{BmlL_Wf{T`g}X>I2jC8J!* zcDW}kzIl$Zl<7H6yOrXHncX|#cMCW?uS3Kh4hY7L!P|~JespjP0N-)CiXWZ(mA-fs z-jJx1sWi+iiFn+;cnpB?V}r*?DqY2oO}sb?#t$dzbVY4L)Gse$=82yeyg^dwDt=<_ zqIlTn>l!GgAO{n+7iEJ*Sezhmncf^m#$^A1_10oZY~WI-I-2aUMIQeD7gbf!%d*(#pbXZFI97XQHSO z;m_X2W0bQ|REE&u8xY3>hKLj#)`vouLy(Un=w6i%7>K5d^cWWNd1Ur%ejnT9D&cWV zeehc#NQUa~xVK9($_SBH7>P4866WNsG6cN`>uBsTD)%$2hxpbt|8N1C4?Q1}u7_l@ zUPo(L3(dC~$vZW~9}}+E(X!vP*i$5MegTB*=}CGWZ6dy;&HvDtvJ+?VA|at-IPP0o zM|%OYoOMlVLuVZ=x+B)9fL1}^9Pf_u#)$dW(MXR;V8-icSIS|F3DB|W#5rBQWF75z zL@3+jut`?s=&Yj+MSYSD#|g4vk#8L>?=xlSZ3lAJHK~Mhfq@KWd5h&jrJy~&_!I46 zEc0)V793+m0i+j0FzQhTx;@Owa09C&xq*gwbHa6doWlNrHdIHv2M7bwlfvwE=8+w7 zKTHHROXI3dRvVAHkWs@uJiIa9b1yw2o^18LgGaK|htQR%5TkjY=Ao=aQ0#?}#J?~| z%creF8sWIw*joj&{NZ9jIdeC~vH7vTSS-7TQDZ(vMo%fT1Tt2k53Evn$>cgUHMGPb z8084{K78y}*_qoR61O7^!&dCnkbPieJA_||vC}g*9Eo`}{%ibnh@ENW_!(zr18hSo zI*|&6%(uqj1lE2?9j+1Hhu{iQ@I!0=8T9+#B0Y34MtvfhQ^ix3F9eAiT@FHHL zlopr;fK)t(-&-YOKj+>)K?eJPH^2k@60u7Rk8$H~)DG1c%SA+%t2Umb28G_hU>>{L zaCugTvM^Ah5sXo!SwWu~t}&C)DUe)RLwvFi-)6WbyTe8J+7>+j z1UAsY=lbOL8?F-hg4iTr3mlx}xgY7M;o205V~|1E>5!=Q6lpg98Kt<6Bfm}oy`&kc zA9;NhbROl-@;x4(#BSmFt}Vp^=P%%jvy}3xVV(J&u|=db<{x+#2*y&fQ{m+dtMX4K z+d%lMz$y^FnQ*zR7F){5O5GC&xB`&NYO$3JYcE_ZO5i>5C&ec+I2aoMcJh4G0}as^ z-yMvtj`Jly4^gCfU@j)MG{7^O*tHGo-Cy7xZ$|n~jd9Y+JhwK0Fw(H{eILw>vq<_e zfN;*jriY1!H8&ZA$0YN_)~+bXtQ5)}7dv=fdcJOm*Kl%F?01G$Vn`6% zMi##Y>55tdi;-I@zUGB!Ple6Ch?6w&9a%~03TAI&%jyzEf544$86SngS%6a8IABv8 zZ3_R%u%0asQSvK*t@FvRdP}g_8(6aR;2;39W60N7ARUM^g; z5LTu*EJ`8S2*ymosj*n`{9aT~ZY*eB4OVjb2vc$r!z$pc;-N~enomyJSx8tTe+X7~ zw)0`q&SJu~7ai+G%{Hwho+5dtW_OC9vWXtiy%2NP+poPcWfddc7iu@qG;t&<5i3fX) zW(wA<<_EOwG*K0K!kng)D%I*u}* z`Zlv9dx2$cycZ(t^lLD`B{toO@{W*Qm@D?IJZQo-migm0RW*0PWG{4KDSv<6lD*9` z_gaS39S3GHVrQhge9pt@3!e##=b$Y_HNmT=H8YO{H)Az=BU-2<()(*nPWb#h6-KeP z2y5q{dbml40bX@~O9 z9A6u{PIjCF;U`VvvO2|gr*MZo6xI<8*p|y$+bl$q_<1ld6I;zu z^o%0b>#`bQ3%Atv7qI7!Hu;PqHj~TRJfA7~EQZ0dBiQn^h94W{vRb>;5r6zOU=?dH4(&1c^2aSWg1PJ9F5+$h>;n>?A^B=qn`hC zyp=394Fh4aLy|p0=INnT=-59z=2kovomDf#Rk2J1^M@0$=HW#=&sy}-1yE_I!jd;pxI{hRzHrQ91CeB#$q7|RQm|<~#5r-Yu){zY=V(%-xin;lnbv^{ zb|rlT!rA~$k`!rLxtqI`rhOos4A9i^3C4`0mU*Id2zx~L$Q=-9WkK1bN+(HoEpy_% zAoeGb!b}`Rh~QrZ?;Efwf3VpPE0Jo^qBCH+{z>y}v-gR&(qQ*^0dfRPI$I)2xL0FxhB!|q<#`v)tJIig>{5XVt4Z`vC zB&A7`K6aZao4xEB2*0H#Nlh_{nNYC0BJ`;oLK-Bar8k*Yo+tPu73e%G_J`(0P{nvi zoi66nd#KeqB9sM#AWk=jV|voGo?`E&?9y+5-ZH(2K+Uk&>!#HpkD7&fDhOj7lI#jn zxft^r?&^O`Yh}A&rEU>e>oa2hA6?fSCq>b;yJvTF2 zJv~+3HNlFQ{1W3-joWldP?i1ob2NsDCyGVM#pT!lm(j;P~WZ zCrc+h_7my9N(DVeQo?WhQqd&pQhUKEITkvVT_IiEc zEfYyzUit>t+Bcsr$20NnUmbm-ax(g_0yNals72S6iwv&n8g&jBb4jocTmnxv_lw|P zl^lNHde$cQbG&4R^VEb{Fd3hOIfDV1Snvh(ZK71a{^k=iP|Dj#&a)|~Nq>g2N%c|| zpID3RZ3dF`OXT5q)dX3Jw&&*|cXF~%<|I?6qVuK6xuiN(C?Gxq_d3!olI}-}*}#|V zmpREMr095QGCucwZBYVq@}gFSkfPknmC&aFS)7*LF6DF7m*fIc6|bHshCtt=$ZSah zTx$&%mFf<>#l-K0^pb%y1cga{NUD+3w2Dc^&Uu9Pd()Eat?NI3z7S+S(7^d2^1UZQ>tBXEp- z;n`Qkh=uCSM*`v;$$f&{&q?eDQk(V90UpZABcOvgrHRLp~ za&aW02`AOBZxNvbz~?L>M1-zf@b~K51~B;!0XD_r2ho}grAO;{MXhWHUCTiG&{Da2 zTGe&+=61AUKd@64r@FvWYs>phEq@5guY&N8B~g7clKxVCroxz=l!&_?N%saPqz{cHn5%>tIZ> zEbb?MqX{>cDg{#-vsQqx-jb+Z+Qt~h>G{tGgM^03gCHCyQZh9@D_IJ{?>@|rX5Ns6 zbF*sBM8zC=8$^-CjESsdjtDO<&(C8`enF~&17O$&M;6DQQbcCW{4Nt7DAlNZ30her zV2=^b15D#M_udU>wOGCfus&8kEA7V$FRRF}BD}#WJX)&n{=^AcaO8CSnM-6=mX%(0 z!pp1C%a7iT6`m~B!jCma?gsHwB6H37O(r~Bs`+gLTG{`AU9!qFzDTMfuO@OCQf9?e zjue%r-B@89x2;9dEFmTf11s*~KVmmlc!N~sU^rsDF0e)(PP?(f+oh`epwjxg0PEr5 zv>Pi7H)Y4e0ga~v8{^^hrWHOcVdIEKr&|;^(!3Vu7p*Y1zW+AL&m4IO z#1odxFIwSmr24yi6u%Damc@Ch3_qWT+;Y;TeBMhHz9LoI0qAoY!-bL@Q4&et4@G%g z(VQIa5jBkwsKv0O_YJIlSgb8_yIQeS5~JNy;XID|GBKbzLx7LA99GSoLfCHm3!D~I z`~u)Bi9=Uc>f&h;8eW;mYdT)#g`b1g-{YAmkAnT3)k>F0F9pMW9d#KSbxE82gZ^ZT zZ51tt!>bZ`?aTX#!UG)j;5yvxAj${vr@WP@L=DoUL5`aKCBCMHyGcFmtYTM1h11LSV8V)aNYKzpjfHGHZ- zT}*_B0iL!5Jxws7y-y7-pQx*O3j}|5(|WEZ*Fcxo9osCo1T`}Z*2A$(E|lM9!*PDK zwsb%<8-vvu^Yu|5bL4suw^*_b`_t)4oW_p>`^MrX?9cbu zz$0DCw_$(g{_2Pis3C41j3p%Qjwp_>KPRpQ#0J76z)BL%)$_vsbUz$@NH+x7%o1$a zp9!!qQ?ulAz9})PhG5U+B0Ku8(V;6Jw?zQiF|%H%Q&3M+eu4Z@ICs znsa<00)`e=5$6udV6jce&`lA@PRyGe>HXWr55={fPN8iKM$BRLnTc3)Gi z?H;LBXYfWg58!f3I7C+4jq!Ant#~2u8{X0L z&&y4_>|_=uFH%!zU)*XCx5tnr?SvCq7L&#$>ZgtvF2_JPV@UeeJuO+wa#is#3b_gJ zt|7>FRAhA5;ffrqFpGDln!pSu9-uM6^M>&853ckaaq*43o?3;qI4?AL>TD*Hb(wXWREeBuBnMI&<7vflkgH}daFJVrkU2o)5`yiWAY8f)!l4<^+Hs{DqG?vgEm-B|B8ZuMt3+nD#x^9xyZRh! zwUiIaQay$QWECcW$oC5?Hyzihm#SMZOGclG)m#NdIn{0q5vjes!muD*Ug#A;+7RI~t+^AZ(h;$2n8PTm95 z6O{nfAed{S;d$9dAP(YIf}aG`!AhHWS2u84SN22p5F;r^l6DjCs&*07I!n{jut?2R zuPnt3u?)nGNI^RzQF+`vdHs!y7lWf?ahJJt9a8d*LRpB8b-e(5c$}|;95u^!rHl~2 zL+3wKi8XXZHPSp=0N*#s3VvQBMkF=HM#pOWAuK7SfmO5kE)Q>&ZG9dT*&JAVi|_Z; zw^Q{Vj}v_X4YzRS@JBDIl9gQU;Mw5dMn>r-I##PwF8A#^Lb%-g-#(Hc8nnsrXk~am zkb4>_SgKz@PuXpNntuX8Pe&Jtv!XgyayBw8W69g=gAAR9$%{5B=}BKuVX>F%{rw7%boTX8bL zxt74XAK`FDh@$ny27KKGD%S(w5zDbrv}O;01q9exi{GG1*eF_;&*J#cEr9ndf!o%9 z*jy@LjZAq3il>@KSjKSyB^`TUMPgk(9v*P`%WZ? zXQAu`BlV&D-WIB6^I$oGP&_J(DId}%+}2zmRGlJ(aJeSj7SDqDx3%?) z2BUJU-;f}hfzlRM~zbUoJN3sgyjn3t}jfzCrVJh7nbXX zd)Vd)9ZRSNVN#~+wqMn{j7Kdpb`VmO5EGV*^thC5!g9R^8)hmPKY2=`VYw>TbVV5; zzQRU{3ClI{EL;P~Er8@yBK0;bR}&Om4%zh##Fs2OPej9Vy^E-_vMmT*Es5)B!gA%V z4EqPP4hH;2EX9Q78eIYr&;Tv5a9yf~4a=2)4yqJ=@!NcnQ|NPnB}JNRmwE7O>ir^Seh!_e(1k&o2GcuP)skHscnd!MpU($H*ijX zV|oq28n6V>g%{K71icl>7a;XAlG6$jlErLHuZqWT734&qvn}H>Qp_(D6w_-X-mp87 z;5rbtTT)s4ijol1tHKGNCVhqM?=5K(txMT7Kry{;ZpK9O7eF7fb!AAg2$U+05QU%l za`b)^%czn7t0VDpg6|OuSVTRiMJP*mTwpt9_69S3p{*70VDAQ*o=77o&=GYZeq@ll zU*}SHhIjvf+nqXh9)xY@avy|iZ6FMh!**K?k;6u#2Ht8Ud>1YT*)btLbjFf`@yVrV zSsHHrDY}<1TA^#@z{(RAdGSF!*RXP%g>|u6xn;kF3ziQVg^`^7)H`P7R&YKVSqa&7 z4HUa_d-WUOZGd$#xI94eX5}`rUxGM>j8_4ViluN@$E>e~OBD{^*oa3f_047o*uLR6 zhH%k*xSE8W$cUY#BEu(MK+`&Y;D-LT*cvw%EeW~b_*E)=g^oSbp8xvApxneVAqSe> z^Z!6d3G(<d^7j0bbH*j`{(Jrpl|Y;Upo3z>CH?y!d;Y&Zm>`x}HanZR zM7!rd=Vx((a&{9bk?aUIc80%HkSqF~h3dSsIwb1+Pdee!2_hF-$tz8=GqUs9MUM6% z>$Z_MRQs*#+-d2EI@hJMWkpa_%P8nE^&tXwPt|+{5z%DYbQ!z@ZlFMYY_DA|)tE4X z2tJRTzDQ0Es%(HFWTd?hGkgcUM2$lJc#HXVb;N$cH8S_pt@QUmoh86l5}rb`zPyOc zmIf32lMmt(Gq_C7USMB%@{Dhj>gk9p$VKN|1a`&B^QEWy@|v-6Nn8ZCKG2laI4j_! zJs*0$gd=9iF-_33X}hv~;S~P~H&)u$@uQ04ss2M#e8&59mM04(i0b&iE|OD_s+IpD zAwT(-%)rO`ko$~5^zAW89)x8-?P^k1~*fT2@^REc?0tYP>Q9z0zAb5998e z1KtAC5h3k0UM8rIDqREbMH`U4(?D8%eiltvJ5Ry81L%T*CB1~ol3YXPys6s16cT>| zR}V(DYff3>yx}lux~laV3Mv4`gO`%3t$sVU=5=kTCb(Ot;T%oh|16@ zyMfTxl2}WWG+(`m@WM^OFZKgE zYGIbncR3OiX*a?tXsO7D(C#Ab*ARC`{-?hOa#!6b=M(oJ07XAh!AGno!fF87r9>maJ`$`)x^Zr~QDEc5vUIyc)WwD+p>rI(=#YA`~ ziIoLaOhMwRNY<6eeLqR6Z(GNShk;c!xbFH4&20z$;lNF-&C^m%_C~a^CT9 z#F!}56#IN|=gTU=u(MSVB_IIBZy)QaMGgiy(rVbP zHH<^thHvrZC#u5R02gH@O!TSbJwfpv5k3aEhX`CpZI(`(;>-Ks%lbp!@(jQWmf(~B zD3LbJmwRw^9Kb}YZmrSFl(k!3ahZEH_zsWGbqL~Q`e5!d7rO)-%2H1cI z+zq?6hUExuu{WR_@eIJ{G85MLRCj#RjvJ8MvBg2^w{JmI? z*3m;9!dJtc9l#D*+}o6tg`$R!=&jyw2GRu(u3Hl6#SwKp0!Iu{Ghf6_i7tyr(oI+{ zDKh?uF~vxkaPswhTZj?k3Q&i~+oO;fb|leGv84Vjf}+l&!9T`h%{_1`mecgA(H%PN zs|FpN6e%w*#QfJ{WM~T@ju+hG^_;ZOE?yCzj&JdnTJn-BUIaD^2_{WcG-)tYw-}%G zSNvmslMf|WZV6nq5EV)O76H-X(O?_Mgdf8tV`JVo$js>_oW%0pW^>P(P{bUp0JYrb3* z)q{SBlqW7?pKYXNs6OntDT|w7_iE&+EDu+J|CWLoM%pKo$8V93Vi`s{@IUeSD3oF3 zY5pfEKgmQoIYX8O#32-Y0?C<0HPc8p=h6TnE+hA*LF79OpV)=xL@#IMvmv2SMs_3? zl#2;|`Ar1JjP!TXW+sRt7J82$;f{tXzJnue0>S0@CUg19*i0T7mL;(whAlU&FmXhF z0wN=w=35bU2wM7+rZrqVBX2mrz7i6nkvr8Oa;pbVaAsq3>QX>!ExgNvr#N4242ivf z4qJG?2Tykv{1y}!0Nsp%C960l%TcBCKK)#VeB(5iH$l``!;}{Cio1&90D zaSSpiT7fcEe?X^UYjI8N?30U;{~lpnRw83X5O}((5<8Inxq;*bDoo?WrJDOH;{O8s z$>OxnA&O%o0w%C5m7=P3pdD7CD*#{ruvAo_C>W(J>nE?2ig?LB85H$_HMcnT zzph0Usq)^56WxIgv^dFUtZD=7pf0DxI1uJo64gTLlB!T&G{u&*NdfTz2wMzEU#w~r zu`$w8=B$lNEEEN7jI@?&O_4Z3H_mymuNny*Rxy#{HAXr}H8l}4F7CP{B<@^E5}FkF z1o2lQ-K7flz+`!5Atog9Nd!Sr-UsxpV;ng05J&~>QE$VF_8#V0?doD1GU zB*3UY2+8Tu6! zq%D<^r7}bG$p|8hZo+2{WVkAJ{ULE3B+JC1u&5x-?vb};9vTJGB_2nUj1)sC(AS{; zY2@^<(jlrPhtrHybyTz2AjsiB$5}>pVrUgL9JS;LEG!lPTw@8OLYJLLK{6u^9Ti@S zFi;?TV@afiN%{h6W>ZHM`Y0r>gXODc+T$_#O6iiHcGN3DyjG`xR^tCtqxHjP%D@)1 zx;7ZiEvqL+yslq>f?P%xJ1TMu>-cBE=x12^w&kU6_5JPxIdDRQYCI13biK-gkQ++UjXm7_N7$3Y0vbR2}UmPB>Z(JLcY9M!)&=CfM>{nbq`*sB_4 z@N*U_>m7)o_f<$U<53X*?Ko)XE69XTE^rcEpsA;ZG|gqGMb}-j%A0$1aN) zmt_$mm)Jw_C!N?~)LQVK=?IRq&sdDtXu{vdpGAc84WMzvncM?EEz55MwwrL4=kueH zC9+Ikx(GfxKN>+)$;Lm&GfDmg<_)WjV_ZfS%ZdX$Hoo#c72oP0lFU;B{x2l0n|Dn| zI{DQ4u|BP>GO(J2bKNxF!>7J&=xX`4z&d*Jw5vMuqEGoJ26f$E0XEFTX;*b*F!bY_ zi`=$Zz~1q2+EpES-KVxr#I7Hz-zH$&J)Cw`M<)2x1Z>A-{3~E*Je;=RMW*@Gd>ljP z>-{INJ04CaQX>f3_&NMmjOVF|_9N-`b0ojWGQ{9SCtpIC43Y{Gjai41ZxOaVJ@(Rg!AR~(MxIMnonKo zg~0}8ax1W17SBR)C#%mOvZ4BX#|1 zWI=pflgb?l{7vF`Rb@^qZ1#OAQ5UoX_?lQf93?Z-$*;~7PSlD%2jQ?$q@!p?dSV~& zKA%?d6R;abiSSXB%*a55Jgge0+vQ06(;ZqCA)=kY!}QU){Nlm%C2^9yA1zowj^ef6XoV6oxh3EruP_I*yd&MArNJ5t#ygh9P4xOGFuYVq zRPW}vC&`$%9<&{nN-UwnYp!wJ2!hPe?BIM2!dXKSK3_S6-)xN+{quT6IDY|)uXms8 zyy$T-j>oB93DL)25wObLk4dpJBj3cS0?)*4NZA|J1gHq{1)*guiC0th{ebtT^Bb|-1ochr{d`cQUaKDvsn33eR-Y=HD3VI|2p+1B z^;VuR+h#6b@QKnRvK^`LQc07T|q!5v^C>W(Ji;Lk^SLw%a zauprPtR^6|wj?eqk;_VxYDwEf(G%FK7N1Fq8|i2vS(GUKoOC{ht6BLH7JGq9zF^k|h-^@@ ziC+Y+_!2)afTH=!vw@!x%>&&AOqA2ax}j!Q>^6Fy7~` z9)jucXMlHN2>KcX9;YI(hF*p5MamovQBNc;Lien$144FH_zI7!3IJ;xg8Z5Li!9dx z#N?`p*abJKzuJM&J(k4#mjbsO^&7^#91QRcOCTBHyL=PvMXW6GLxMn@47~qHb9}UuIX1>xf9qv5C3p)f(RfS)<2q}=qSMVNHE)cjFCjtu{XW%^O zOapZUk{y$ohBRG1`7#1=N*>p5`7#U?8X7fE;ISSb$nOibY=S;{0>Q!q1%26;4nWUs zfZnZCl}@9nT*iv{)KBRs_XzU8HJEOTCX~SHw>#cieg*iiC2%`5p$wvdWrv3Bjj{Aa zV(qd!7txZ6ui#TZ9>Vx253rUY=<&hRK>#83Kb;m5y&xi=0->8BWgH`od}>yFP?Ls% zFxHZ|E?QG7pL#S&Y0|qOthOXwA98O55VOA0G7QI003NagDm^-op2Z7ApXflk48nCH z^<$hbZ%_F1{>8e7#y~uJIR_HsQdfmZh-^RLe^JL~DG;hy5)XVm1_njPK*rmB3Oadc z*Wci`2)r0<1F4RWVul}ei-z?&nbcT{Sre$_EV=PB@RE9K5oW8&;LV^Ccu0+sWe{;9 z@TwZK5qB@?kZbX0n<41V-y&;F^@+d;^(Ri!ODD-;;x{0jGeogPlE)|Ty6SNRJ?13& zm~#iXuc;}mAKyJ=)Y9)m`sQ(x{7fqfN@+vWH&K?m<5B7H>XA_>vOch;1{YcKF30_K z!~OgbOjn(e{j7z2%j;mg=9BKmmC+s@0qhNnXPNLOv`$xpAHpO#7ugFvXaIJu2R>9C zr{V_q2-({_sBKq_&X3fF16XDsLG~#NW#N)O{u8hp9$t+u+k>v^RS%oW>6Q%OqGUzV1@Ml6z(cN@&qMqw6B6qoY02)KzP+7szP{u#F{@Cl)Vm6yH+)T(z=zJl|7kAPpuWHACM@)yUx* z80scdJ4Ll4e`A~vbMw$>J!|xj^{k!ijxTi~ z<6$J{8|);rp0%{KAyE&xj~PUsV>s$r%UxTFE`WMl_y>ZGXRRf^;W*SnR|yjCdDPr^ z)>fov@T@g$0ngf6S~3?Vj`gg)che{KL(2iu^eY!1^{ll>3X1c{y=oBorw31PDq%;? zJwORi%!2Zc2TyT6Y=(dkfJ#`{hs`hIWmZ1jsp}?)sxgoj7sh$^D=P0&rL}hq&a+Pt zs67B31CcqHM6;4Y4a0f158J4zg3|!aAvhPo)_F!vcPZaG&pQ6=GI1|5zpw(+lq@DCb8 z{G)^Uu?jy*kfIFEv$xypcZF+^&*VJ2fS6~r`ctg{@msrfo>lhig`stxaqFz}?AU08 zXN1&~EE)T!ICX!l^Nel-m$=q>HtaRTNJPfWSXs)FtbnUyoo9RSVOqj={RiE1p8b0Y z4=ni=cxRBDQZ(SK^DI~kx5Q24-!+&lPXy~cqe~%OLap=c514mk@z&VPi^TdQ{fY|S z-+5Mwwr+L+t6!{4Rq7gDqH&(lD3C7ktn+NcBdFyZj?_gh8- zVp!+dp?i4peFyNGC6EeTwsoEz8jKa=ldugS>6VceCS`J-<;EAWOM+GBK1{w+)_L~O z|L|CB1KM-{pXxc!8ka{Chk`M|vc_FSM{wU*=h^6MXvMo=tTrrt+ZyNDWPD@lQL6EN z;71Kda%b@amYioJpGR<7B3%XH4@=_y(j>h2|G3t#Nl9(+ctq0OL3Q$+XW#5c4a)+o zYY99O=&E|ovz-)Wx-A%8EsNDy=h<_fI}FaVxZQEgl;c64VnjUW*$W;U&a)jmLQImI z!Q4UYmQ=WPp1lYU3zaLs#-Fo<^9^8~XHDT?qC(_f_;Z(VmbcEcWtet6=UD}urX-Rq z))tmPB(2Rl&sKSCIM0sF3o%Ky2D3e}S+{kbO~%&;Sld8ggRM5}JX?lP@l=SMjz4n= z*Yd`B_SQoQy6zi*ZS`>DJiE{$+O`wGPJ6gM{&)#p0n_?=! zMKJ`a$Cq)QmH!J}vdu~{2e|9j2HPQusaqv&a(qO zaKB}5hX)^0h8kMu*#WF+5RoG4JX>4PWu|NZdW%dV#(DO&Cj#f$HXO<%rW}MnuagK> zFxn5sdG-dji#u}wE{P===h^DbiMrhFz&|67*O|t7c5Q5;F6e*2uf^)I&a+Oiuu@ZH zTzf}^ko5T0IGkrk>mgJ!;l+SGM7Zuw<2-w;d%Tu!2&|bW&p4cCRr~q1{Byv1d-BG4 zw)MA=c%SC~(ZD8n^2T}A>`c60ej!dTjyEz`FIZOLH^#$IjPq=NU)(GEz&LGLJpX%rWSwV|aC+DI z1+;%Gl~|th>`fSkX?AdOb;LsuDSA5?=h?W&T)rkwMPLmKu1AEv&c=C`7xpcF{B;H^ z?S4$-Jp1k{qN~yxWgJ*@h-oK;OwO})h=R_{tzczXf?4O;wyg1*aEb^W`Fa`WSz&?B zyoUTgsR*7fXgO(}XZf2Z=n5y{k(LihbEpm0c~&=DP;)8(uOGvaOtj9kPT0EC4uqbT z#Otb9=UK7m5eor?NwFkeP4PQDtqj?Drr!@nWBs1`;m1Oxw%dc?bj8AWnhbl{34I26 z=I7uI)C=}w=+Xx2TgWfG7Ju%yfm(A@E})}m6LzR`R7VQy7&?{mp`!}&3zMSz>0oZn z@h35Zkdx_CaIKT+@lwdOPNr!HNxJ1R~fp!F8!MpHomqW z3+#VLy0Q8~!W?-T{oc64w)l5mA;kM|NoDimJexSUd+Q_RNvg zN5XB4GE!6f_=Niuh>>j}%vd;uaTEWPSovPYQy8sQLHteRPbH0$s4#O1qc(k~b{Voi zG?1K5xH*OKzrS5Emr9pkf^aI9WKLl`lou1iC4=d^Ot@W<5$^mW)=+c`BlK*BQy9-d zqdoqjAOU zvPo8#Xis6}Zxk=64!a0iM%`ggVYD3^*~{TCTMketm_O>-pUf8Q%H1i7OP zB6lzxH5?CEnjq!^T593F1RKNgD!fU4WT7tz5^f4IjN$nFstktX*Pp{fj2l*%IM#4{ z_+&`jLxv07Il{$94aXsT*(U|LMGYcPdGG{hRRtlc0D8p2-+Ay9r%P!Zegf3h!rv2Y z496wrC5rwrkYsUdIL`Jy498SyYdD_$xDuD4V>L3@ljwC)Xbs0#u%@939sqQV;9CS+ z!!Zv}%D0B&;nM^Y?;z9H!w6Wz@dq{VmY0J3f`oBd)^Pm!ReXpL*|iNMZ&P8`aGV9Q zt$}s6c&y>LKKxDtfsKm6wGwMMp8pPJin(AcwJg!xmIA}^=W{}0E3kbQ=PtH};}2WJ ziPONYSe)cDRuzWhHf5x^2SQeia&9H#QkP^5$JL$+iJ~BsHl$33<6|_U?5T^Y2jT?X z0d2tUVk9ydjtlO=SO7NK;v|vDaJ&vXV4QhiEVnGra7_0x8;*HUyEJjt{GGLYf; z^uVZ5xF#goI!qPeAJhi^L1T!2OgBF+;ztQml)-SkvkvyMqSqrmQ9WL}+EW+P67*xf z4ne$PwT9z89rXTOYdGfCS;KJwUr@A!)FhIm9~u6{(KU)S9Mf&!64x4z_XiVL!Qoh0 zR>caqI@WOfU3*Rc`#p% zx`bN8argJIdV2;r{j3cAiVEJ}aQp%e(8}pxy%#H!OkJZ(G=^gu1=1y+H5@mFg-aeo z&KWBmrdnFVafjz}C&Tf1?6_c3Q4mU768D!i9J^`pn$!e@)|Nzd z@(jo4zCsOq0UT@zJQC=tdWPdy?tnD~jJGX|)mX!EYdjddQx{k7#xYZV0{Z7h#4{XE zqc|5F$vy(ZaX7!9N%B`P|0H%9D%={5f8HmwwrqW{E#dv;?FcL0WE(J*l|zZ7><8Kpi$}|`7^Ma9&QZBoqq^wJh3k(8l-6X#&A3_!Kd|? z0#@F`jp2CMhO-Wl?%A}e*xnU!}1KralvR6lhQE%Aw|2u7>>Ik zfG5AVl>t`C;>K{i=S%FYc@)`g2=Z!Z4ae88AoC2z=Vv2G1ekI-{*22cVhqQBc_J_z zH$AGE@^M=?v^yqr^LPaS>k%qmb`~ZtvLM5K8jN$mvAMl*03Gfj^u%|A*Ea}%%$qacon{=(=xb^&?RvhT>h@41z^ipL# z!|@uJ;%HKq4}(xEhQ!VC499kDkS!S#sH*V!13M>f)r zA%_B)uDBo57>-XI_Unb!9|vQ>SD4Kogwl9@Ru!T7gfN9YQLHVQwBJbfzP#^ z?}%eVwO1VKiZ#HtTAU=vq+OO9j34EqE&m?95owLjvXH&4+bd}AF>G*vCGtGJ^j=|{ zdU+b4f1pPKb6zGj#@^O^5uVh!kzLq8awy@(-nOq=P`ri=DXW9fFqUNOZHt%S>Co0- z#@==e1%?Z}hh;w5+lCIxU~i*-wf43v^WwzI5MGQV$5L4z;g@G`BRwvG_qVsTc|O46 zmtw>v{reyGHeca5kqgz)g;CMEL~Cyw(KTLB9m)`C5_N~QxBZ!*xT23*$lBZJDp(U6 zRoeb@c2(5gM!6!T%NO{z9_($YLo?Xh%D(E^+bZF=wYSkf*4{?{SbN(U_@j@a9$z6j z3#ppM-j-(-K2M0;KMW$5F&wqGk(oLHnsOnrpnRWTV{c13i`Acn))6G!aZqLKZSm_f z*xPP`S(qDEm^jwn))+^Z(ty20nl^LsQG45YOa$YQJKZ31hX+q^F3pS+D*&yx@Lms| z;%uA}Cq4yq%)(y~Z0v2h;_x+x7)Y|XwYOD8x2dIWz*u(h}G@T7ceZ#y;~+hmc^2Wfy6u=cj!%ix`M9P%d<#${Q1+op6x zfJXKj1Ih2HFl%pn4YGTI9kzI^y{%%GfVc?kRt&C{SbN)|>bU0_dXbP;o#YsM6Rbg+N{f1AZfiS|7s43BsjJ+)@rkCj;EHI=@ z_O^PsPM*DOW|@$nJ77Q9M~y@#d)uUs{NhJoe^{I(GTGbm*GI!cxc%}V=^pUxZFC>A zy^RO8OA}Ykq8G4#k?d_v$3|^wtD&EbYE%*aL2ck4G=}(x-~4EeA0}c0=keNz#uDf38#a$J*QIHgJh+ z?QO3WOk@SMhsDUUDptVNvG%s12+KxT&;Ouju(!eGF6Bt@Mk6`5Xuw%}+tFQkO3Xw4 za)Zg+M6mWYx)jnS)Y{vM&&5m45#*e=GW07dcz=7_+5h3z^AE?gi^O%1EFUzj|%u2`6qu<)wsvyRYl-+@*Sw@H$*4|e7E4*mE0dR&TkP2P4 zwYQDG926@-*l9_mg-Mz0ZCidz5GTO;={`)pQr6yf+eOLuK+8J9G~Fuo>}_*vqnrpB z6)medM!c?{wYPQKhY93SFxnVati5gWX2i0m8m9ptY&eoT%Wl-%h9kR7nhwGOOXB{r z_O_Q_k80Wi!d^?FI(hcC_H@wiG{7sCV6UoYZ!3VWok=kg_coHg_N>O*+lJ!7;Mv}|(j=O&Wuft-Q6jwWf<;?QJJIDkjOpV4k$vti7$B$A-PFR{_N&c?V2ix~ZGBxBYot7byz> zdw_7Ro3*#~+mWc{YXW=3lQ;IZI=lV4?j3=3^KfHt8(3U-AZjw>`MT6g+#|2W0%H2C!)iLDH<@ML8KT12@<+U_577p1o~KTg3mM$!R38(S-Bxuu)Fd z_Cdq|D3c3;Ewi|>w|x?icaCky-cOKMLu+r#$wSv{)U1rSlf;zQ@#pVMBF5fU$Pwu?*S1ihlj(!eSbuI~tAZ=3T4EX0I22lk|uxAwMT?SZ|3{FjYvbgUSA zTOHboKLOw@O9=B|GWNFS$1z#02Dsi3tiA1j&nN1M=>VYb3@mx};Sp)=ZNu+HC!IgQ zihILc4`y<4*4|e6-FU6D5LjhmnLJ5ad)tA#0nKa*R_9ozH|bh?+hDk;Xug%Nf;uXO z?%CV6Rf>}4gYZENiJRrw+fKB^J+>E&!~3a2<2bfy=?~wdkx96x8*yKz@6-z1$N!wdPL~!Z0v14@y5uH zzxXlmA0z2*$S@*|z3ts4LNBb!fmM%~G-K)2675k&gp6pElN;TnW_ANh6L{@r?QMU- zxlIjnMi8MWUoT^C`y>yhlo`lhNJa2;LCZ;NZ~OHPr7OGz_+HDQHduRGuT{}TodN!H z3`a82+S?|L$ECxwF*}kjjF&*M_O=F75TO@@%CRKR-bO1!wzui`gVLyP>ZdIb>VeXZ7%r=eg}gHVn&%FWyEEy zq9IDguKS77lx9T9mc*izDI#UC&x5{-vKpf1t0<|*kyjQOm64qObluEXQ8xZWB_X@5 zf%F2a#%pxCCpG#i(;5wIr=E@x(JTA|sFn1_sBfM1HGaML=}k2Z~d2$w1x&Q%pUsrv6h zz&7n&Qkyaz@$>2wJQAAzCSD$KZUfFvb42AEB*wA4jeHk!jLC~cFlWD;BK(TX3oK&s>tlf1&6ek}Xpz+c zHnfD;&6eNX#6DK2l(GvLy)BE2v70T=)b(rDXb`4a5|?E+Tb9E3S_W*R#c!c588%zy z$AAzn^-kmf&bpDwx6MTK$L&oSO}@7~VANlSj$5SX3OARn!4p)?wOD)vAd(Y_A^8j8 z#^jrZJy3seV;%;fYAnf^d~XfF9oN)g`W6xHJ`@%nF$*^rnS7s|gezzQUDGA8Cf{~= zO!tKFOeFa)l||pA@Jzm>$0hLoCf{{K<5~Q4jJTwK|HI^)uOPz9pgOuRDq5FlO}@|6 zNDx$q2Z-dfM0Z$|@7YsvT+vz=TEPecC|s zc@N*>_`iJw!AXJLws>E{`?KoZj{l`4Qe;Kxd68JP9O%jKbNrhT?Wr`d+7>7IjHEAd z6n{-Xv<9KOB~kBbQieVlhC1Xq4QEvHCRywu+!*cv2>4D=P9;aJtC%PTliUL2E+thX zsVW+;=BP@w{9-iWJAv&Zd;;NY9ZW9oTNuf;9M$QdX3F1?`Ps8f)-NI1FE9PmGu5s{1PS2+ar zCmq#eXh^(8HQoj3{YHbx-ILhcWopo4f8(eVgF>2g9n4$A=I-*9`VRL3qMGeIthBZ) z)9?^Ligq{S|8vy&R`|pei9HOg0^wSIIi4xW2zs`3V^GUK4y?5&&-hP{8gn!%-xt_G zPyXCnXzI_7lGUTVJqg%!E1$a`_4ZDgO7n{2WA?9(8eI!60wR5kKYQqhu1&#j5R>39 zN9{vUtl3oC?|^+zxE?%=Be>d(?NYbqU&5vv`P^g(NiO3&FdL=G++_Ame#l9tNkzIz zpp{NR^xI_NQ}ZU^!jN2T{E<`@QF_bIm_8AC?J0Z?nWiPDgNK#7jc&?|=(-1l9#pRo zMpYE084LT=FFRe`sA+^zXN%IsgXkUvHtV=3QOm9I5{AY)X*=5mTT+DF;>f`4xB@j4w4&S<$R4VV)&)TyR|W>=bgsmY9g@NNPNNMd|U^S zd!UPN6qGdAflyzUHK=FPcsHRdA|{gDKI9&WmGgZsQK>2MZoX4NO}YZYZA+qG(Gv3G zohtbeU-@;IiKValTwKT>D0luK#6rbYdKb)1|E0TnA)E?LUh7kVq2x_E1l|dwSp*ndkDH`7UZ<`g|F*&S znJ!mS*J#!zpV~bbPxd6dt>r_~?dHDIgq^szcVo#`7GMoa$e`g9pL!VXNcjZ7u9iR= zbUC`JU-;Bp2t+UCtDuasw6$JM4*1m17=v;yz?CrsttXLNb=0Rmeg@xv2jN64i5}Wf zrw}tw`P4P+9Qg^XyZ2#grw}vG;?j3<(w$G@ki!cCv* z`GVx(B9{PLX_N@w(wzLKPmQi1d4R~hz`n5Z>_SQY$EUtNs&5&25!e+gukm{bmfkF+ z<^6N92^>k6&n}ka2EK|P^L#*om!n6p-X~{JCY>K5~d8=ku!@_<|1OS>DF;A4&HFpSnzr zk9WUF#|ud+@+%TX?Ur)g4EGXXRJAO6?UD3HTbh%9_p8V^un9B= z<4MC3zSEcR8g(z=Hs}!+D~5QOqX%Ako!*2n*&TjN|8A5Q1V=R07R z2cS<$ejzQiLug*=X+T*>QPRiIsf>2fh-KCp5h z(~XyV%{BCD6JO#<7CG7mjXLbAW)<`UR-OX=f3YGy^bE$mtFE+;lKuf92>A@-o|XGv ztBkw)Z&y_wpP=uM2v`;G#|&1)RGt{8hIdk2McEvz_AyN1V^W?tRk%i+CJh8(geCES z3$E&#AlM#o2BsS#Ec>7yPb1^F5wxNQ0x*)E|f zV!(iB2a5FNYVzA;8_c~BpE^cz_E2w6mJF^{LQu+lWwU`su^QowJ88fDNCao z#nAAf;7>YZ(yI?jYfIybv9{`GuO^6eeC6wx-dI)07eIO0(DZ_VBPOJ$N>vCho71FU zP6cD0VR6-TT!r+9rJC8?A7yOO~RHJo>-UX80OR5!)=E##Eerw6Rs7N0m)jPQKq(lCWKmT|*?b}EnCe^j$ zL0wp`#kf0=bT{~D-$wdqsg8W9G+q%{bq}X~8|jm!8uC_1>wgkh2M?!x8|ky9>fA0~ z<1Yal;^DNYNuMv((kjtIMl*oDZSkzMs7aqynjd?-rb%Cn&uKlAz#O>;#Lq05*EH!X zq`HC6zmX34J^oy_IIn5a@pZ7(6LBBhMSft3xesUn3U+L#-;wGzthHE+F0rXOuK0P{G z=yN9N#T~We!$d8%5ybtmVq8Fgne||w8i+TZ@4&cZS$h1_gCl)jB0Wze&&=sf95we@ zKNDq^rLdhM@w_LgI(qs>kWMwaPf(M}gHX$oe&hb2xAgQu(f%MXD?QZG-$|qgp46Sw z#!(Z?;X9{5a(c zVle%EM{Ot)uLr_a5dN?vt~ake({a}Gf5Q=}fG$YVGDj3b@_ImbL*O3-s7{BiY|jMD z)s?`gVOYXPi?j4=jyiM@=b32CwE@97J_$EuNw8Un&-qa-5<=AZ?C z=y4$zg0L!+CR)Lz*Tie$rD*f_fp8>~CMMPOsiep80K{Gkig|wy$Ak-#OhSt#vF8wv18is+uE4X$bbkC%TNu#j=O~q-_ za1h4DYO*VV2IjfXu66dOxTo=`PAxSq4lg2E5=G53pQBwAd+3oB8DbC3uYx|ev4=K( zimmNWAm<9o`Gv|#!hc@up&P9rN_YZvBq3?s#vW?>RFLr!fJ$4K{S8!5#@Is}pgmmu zD_9XI_D~;?ZR{bUS{YGuE25=y?4gfV!ZAd0Xom@fzK4R{&xZ7TDlR|O)`mjg-jh}e z9|729Kv{$sHulgU#9Mig+9SUOslZbdVw5ZgaMW? z1o0=; z&mi5TA{&x^;|@RCpX^Zq$mB#~Og1Beafe@c9BaW6z$#e$3Bs*A{Hs>znWg}rw1il9 z_yBy^`YDJ=*$<2%mc_+bcX-uVahf#)goT#GWm$Ll#RWKu18kqgJCR~9_7L@vaQC8_ zsn^E3!aV_EWW_i%0gl+T_t7(3wq@Qa6L?yG*!r0w`UU+KZ=6eEVggGr$Y4pJg1e?caOw zpL=k`Cb6rv{mSe!7bNlq#5Lf3M7mz4dT4Z2_5tIAy#4SXkmH1oC6wnI+M6WYfyfLW zDvN$1H~it%8Qk!s$hzU*{~%HP0&W2?=^uLgtn{?Q)KSRkFTOg zpMYCRsupt-gp2R9UIOoD;&P)kTtTXub8uP%*>R|RHYD9}xRl^}Uq;2@b!uPv5UWT9 zUdC{u@FVyD@6TFA6F{vEELlah&8|Am|3|$vUo!NWy5I|lCCFZ5AbB|_@FZ^SHtzKz+~Eh*tY3XhI}YkMM88Cu zcz;{_J$Yz(`B0B2lY4u29@+p`ggg5rEV=mH5*WpiN?B$R?%r=y zXM|S&8HF?e@+hHPca5G`rP{$8juN^7>1$BkGex*_FRSw#wSv)rCm4#*=nd7PW&$f% z0%VOrwSs)ywfBl}X9$-DUusez>>b=13W%B)hS7Qg>!J=HW>^>H$EO~>b zaf;Rhz*8A0o! zH$b-QBBELuQL_WwWV|jqxE}K~$z@mEghhu zEx@jp5W6la`f#)+LqQm0Nm`3p7d^2ZTHXP;*buyRQD0QvTNiD+?22coVPArIl-SQv zeY|y1xJuMsdJW)jmSERKkBx_s3=%SgPS1{{75L1$=-5CuyPi+>!Q;AP@Tre zZ$%hg7fBuMt&39e5qhU5z*jAyH?d;ZMUT|*^SbCQklrC8H6zoyh}wC-by4OKM`JAY zd?!R6JO)jXKTqjxf|oX6R1xN_iw6INLR{nrk(~ad->i#1+>QmVER6hz3?>H=!K{m( zUjW&SVHW&=mx$wGzub8js;_yWpOcfU34ZnQL|Qqu-THh zEW0l1{ia_W1a`*a<4Li%E}}jX?sw>q)LA$r=3WCaWhp-3Li>`-euN%~*_Zs)BiIid zvoCoC^zpuAf<(#>pQ9U_Z4dQ^sNP(>JHx)@JtZj$fZkmENy)KhUovHilua{j=7-qdz+ zbG-PM@H@bK(4%oXwN=X#U_3vdA{ORpiVDg&wNVSg^Z&*TKvUZ@Als>ps8$9aV~h{! zscpq(3__C2FtruI)++fXq^DAGPHWWGPHijboSs|(V7&olJTdIl)+OK6T_kn1H?<9&gz($- z0k*b;V#JD_+Ug=KKfUtx0cj8ssTrB3Hfrbnrnbx@j>cH(bHlM?ZZ$MTp1}ba+5x?1 z3q}=T-qcobC+_X@ApJ;1K1BM>)b{Zt8dLuwUqOyBS&j&1YFl{^it+<1Zt*IF+o`Qk zaXfHq0&Hvvu~VBf!7pk-M9OYp^tCK5#!hWp7R71SSP-UJ5|?GCwzUO(Vg<0x7Ozi= zy{V1*NVuEOoYd`Dw7Z{z7+JUl?_GH18?zNXb8CCXSH9fsaanJJB!D>sx#7`QzL)64 zZZ2dOGLRfhxOwGEd_7)_?V8m%2EhfvhQ2QP9)1D$r2%3p(xQ}i4b3V zMWJNhBD4{rWJ&zq&vWj1?tJD~f1G)J=Dgp}bJlzAbIyIvIXc_ZSb?edLOwd8B{UX} zS9}DC3erie<8;iQaq1y*(7gc#kq){y{>ofCYnFTU7K{ySRz1xO=hR;(8i%+9Ht zgJ2ra8lAI-jDzk|Uz3AwlcLd{gKpOUq43m9svr?FJLtauMU-j@)z6aprKDLLbg$zx z?EplNvXEZk<8aVDuri>g16v^YD#FD<*TFi>Dqx!g|J0X|>;A2W3SZbT@Ut zM;XF90qa5de!|5;*BqBgfH>&(9~s9?Jrl9>d=cxQOFi3n&@G)!8`5?#za%ziKpb?3 z<_7yT;(xK2CY`>6?lWbv`R^X0Vz+q09>F^3&b$Zj$pQdNL=wb7m#XML9dt+K#y)(? zac4;Pv>N`)K{s(^*pOZWb2hQLy2L^Ei8Jv=+e%>TM4Q3kpc}%97ANuzu*1H*bsIW4Mex$M4!SWDVoYt90hUTQ*S0w5(zxO~=;nk6J(Jpl z+11x(9dw&k!13XfiP6B)MO(l+=>CaYy0|oN0b3&S;-Gs1sre4NJjMi9gC-8Thc`qS zxwDAXloj7WxA`We$Q*U<`j~altvNm36fK9~BKbj6`Fr+hiq0rV+wzHn?xu9t_|TRHRt15ZU!O%g_zt?J z9S9W%-4(Sw2i+cs9T+Jm4!TZn&(U@=2n&Qnzq}NzgKl$-#J+>>`*A^&shwaR{5Lu4 zpzG{|oH*#dusVwAcOa5=hb;?L3%9r#1;jzO!i5mC9|E&-B%8+*anPN&J)VipKx!vM z!?6y!IpA_eF++im70ypojpCqNIzCFx2DVsmqr*Dr9(*{4)7c1oe+0*5pZbgv2i>$u zIGzp#{Ta-=#HMkDp9t>4+OVyI?xg1x>&}JM!x9LlnJN8@x~+rmDI9`Hy6b}3n%MuQ zTO4%vV#k8kY2XdDntcb|qNibxPDcC!ivbOK>$B#GX~nH+ROJEGOAU@iI=W~75|ky%K29cZ8be=2TB_Z)N!96}N& z!T8Cti~-7aH#z7|-yN@RQ9jh?F!~Vu%D^ENo`Y_$;@JL1mQo4`C5dF-O4dO)@N$s5 zi>?o>kyWC^LHABu9L0$aqPqj@EArx?`+L4
JyWRVvK-L@m(;z9E70{cMZ#X+~z zeqekC3OVQ=_#&D~`XHFcMVmP2cK6v>*8KukYY|E7FE9y0@XA&bzAEIP`{*2#q%H`o z7~#giVH^&+)t`$t^0k3I?#o*T-Ne_-G3dH8u%3edhl6f~Iw2paOK_@K-$A$NvXBaW2~!-w$aBRr zNgQ-9wum$Bl?qm^2&U(I3kTh+d%Q+%3qp4x(E#m{;GnywsaKvcAiOFh9*sN?XNh{lK zo{xByU^2vByl~L1@V3_PVbuM&yd zj9;kYp!as-UIF2DCQa5scli>n z`p`3yV-MD}5KNv->8yip+rL68jYyS2s7oXs^bN^6=r(=J^W$m{LRU-j9dvWP>zcu5 zG_Y3)=hE{KD-OCj)8f@zz&;Y3$E!#O-BS}oY6l44MUo;NbW4oE`wxVhk)%im-FrB5 zBOYJ8@*$Y)aB`6jx=9p7y!)i88U7E=6W5e{oIh zr`=moQK|!y9Rc2p#N`?=FkCcC0VWl55Zi#{7J&=)@CVeNjl9Xm}> zl_e3J+%HpeF@*cf+w}{pT8M6BAx*!$=8Ds$-a>Qb;o1%8oOCpasoh-K9TSdKt-*Z} z;U$vJM~eAqfW#=BlTI%&wF~Fr+}K?}oD~SGd@k2+tS&~)Y^pCmJXm!|6@scGh&)AH z&ai=tX!ivbVih+4DHM|7jJ5l)cC)rMDw2Q~upF;;D`+=M8>6B!pt=^$Si5y}0@p%@ z+NCU(*xNa*N|auMneoy$Fo&)=22O0Nw_^GF8Jy6VZOm_>9p7M`^4t%|neLqgKglt_ zCw%lBEz>SRGRrBcBJ@4GcOqfe+?Hrst+yinD~lN$&j??4yT4B^US|PbvIJd%H1Ja9 zm>cen53s_82(5!iIvWC~U`ScX!*$Hfu$k2nm_6;jR%7nCd*D*=2#HlgWNnhFPFmR( z8Kbp(EH_q$TOqy+VU%Z0si-g)DjuG@u>mz4*hIl+A46Gqnboa>%d*CxZx!1bR&^k@ z7^L@z$cgx)Q1)*zprMDMdY%Ph;{Zq z7)@0^0${ojaudNi`%lGD&3Z1dj|8WatTUu8&i*5@#ZB)7ZNE@Cd)C?iQw6uD^T7TP zobsZXzorcJyVjs|wKUT) z#o52j%dW~t`t^%oOtLJ^)nr(3_P>HHGlsPkjFrOTy5flpIs0EOA7xm3KsY2Mz7xPY z`|}(|oc*g|Yd;b7-}L7@6u1!8zIFCDWb5qT<|p(JaP&j?Q(DO4?Eg}0&HY0^0qiNk zt+PMBv&GqeUuq0<^iU8-30a)|JB>6t^lV@Y1h>xqJYC`G4mtZD!G;;)=pFd8Tgc+< zzn~s&Od$Lm{`}(O*4aN>(94W-5dI$srW(ZA|EaP;li5PR9`bSP?BBE^tW(lo2iOxn zZk_%A`3ox#gm(ef%g3#=|JQvyuY~cyUJ=|n`_q&Or)gpXBRTuu>Keryy%NNALKbKL zJwsv){td9hg7cU}&i+3x#023I;{PIyo^wrI%XjwgIV_~+V93zf4q>c7FrMZD4U4+!BS8EZguHHfqSuif$Z z7Y3uaW%`y~4JNuhC#FuzgCrv8= zR}h?bHXbHI@e${#kJ?Kc$Y@pev@`Mo@Gots`5O$UlSu0)N^cO^AU((ik<-pTi38y- zKo@!qp&t?Cw6h~;qtpn*JP5p`aEf0*l5%N7)N_VY4|o&d)F+Ny+EBW!tGWS86P&ct z=g@MB3VE6PX zCX|;x0`V-7Ew&mDG=h1OHcN*}oq!3JA787}mT9*){3e~b;4egQ29UbgQiITmKGbf# zA7hlW7V)167TDGv)w@#XUf9W8O6VK{c7pI>Bpb+!<4MxiYIpuOas27t`4iY3U!L(z z+FgWBLq@2R6S>KYVC315r~JlrtT#Z7_#V|190KX2tcY{cdd1H@g*7`pu>s1Swk^w7 z&bEno*`ytdSql~Uer%{z+KDU&7Ae&i{|_X!FHpAfT_EJwsJb{xZUSPbTf`Vk)AT;< zic7ncttR59>3*=i(|*fpve9yYv3RQwpN?AT=iYuBqtqVoz9AjsNqhBS1U=_I7K2yA z1w>!9kWrtHMaQ{&e}I4MN$h_|U`fsHG_PFNq=oKR-LxTX z0AZ()SW`ate6&h?$1PewsiT0-32ch<^fTxOtKApIYV{W&jb<}NX6XlhNx{XivcY!j1P&y!(du}?e^FntJWZ<5%6b(!&(eyI1I4M(acE$K2kWWCqr4^LN1d_ z-NRS)wDCHAFdnsn6y=q5A{L0oqo;oY`HiGwLxzmLqTPyzQIu~1oV1|cl7TTvyJzSk zz3V{#5ymcJe5AP#zN+(9?-!@OLX=KK;)M}75u?XrP1bqmj|v&qqhK@;7V8Rg-A~i* z`X2+T1F+r}H&vgZxRa2Jtrg3@$lhsJxGIOQq`Z~{5rNp+;j*v2u$`I^%{I| zAlA6-HTbZ({q^}AZ)a90U%5C%0; znpT9;<^C&Frg>xsaHh$W}ew0(j2p6FJ3AL0*+aE2$1x>U**e00e+rd+5etVmwJ8S_ZE zAAalXbVlHqD()O~+p7@Qxz1q{h~UH{MYT@ftQb^dYG!MT^N;zBkP57t;Mr+PJEnHt zd%L_|+yYQrfwQ#2oxWr0B|Lf;5=&5tN0Z-W|SL~juSxuRkpBNrb|u4dgR2Sq)a&v^j@IUm`VAm!ejhT z1^yx(EpTQVgu}6GH3}8Nx7L(hM_?`CH0Ineo9#i<)gQ&UHy>#%rgU0R4(vhG&pd_a zdL5#-S;$nCJ!m>_PK-K-ft|IuZcFm^py?O#22>|R+yWdxlC0fO_%vo?ljERiYG@Ut z8Aq~@m^@#rrYQA>ds5;14yI%46FW|TajA%(!zCU3T5 z%pN#8L?**A5y^apjp&>VK`QyBx1na}qCk8S^zgHjgt?1KZXJuKZs_}g`1*)1NQtOU z^xzNuIFKJZ@RatsNhQbmq&2ayq)ybo{bMoa>R9UI?>@5#XbW$zQe0$ArvenC38vMJ_DcAvF;lY zy~{$8&p>C|xOp7d1&iy2ByXRA+kvoJiio>_T_nlc4TYZplSMoOCX3Vn$u+v5W!uNa z#8-oWc?Lo;iKV_n8Im_VPtO3bRvEDhjNKiFyo?^^#HRt{o>G8&)p=a*s7Jr*#4kX6 zK@v2*3a6fC=vB;3(Z!%2p4<=rg6`0HYerA*sz0OVc0u|p1gCQ+l+vD}y!bV=_8CN9 zw2|^)el_Fo|C)0hg{K2z4EUaX6jjv z2K|}(i}ix4CWQMT=)siMi}>Zw)Jac}z<-~qZ=9}Jd{u|K`K}u5%%uFIdF(hqKgODQ`yRh%oSXCdfO)a9A`|uQJ&9-RO4N#iED}8vn zvpN{9(g95qcpbs^?!uU9S}lx#G>gmKg}agYAZ1$aE_{709K@mHI3mxG=yp;lcNb>C zZeGgZEkO4O{*qw1yO4V%#k*t^rQq{x>$+hk7QciqVF*S*?k+5~1uvoch;Kv~rzLk6 zzVoD3oeF&Zdcw@Z-Y>nU~ zk?HQj!#L^P*$u`)Vfl9#(xdA?tw9>AYV?T0(YSPXVf1b9Uc%mxQZBm9HPz(1%D z@sDlxM>bSsaZ;4w?!p7Fn_CE*T}JlUvnI!d6?pvDq3V_xtGORR>`x#JH z++BF;b}Z9Vu0$jybpP(cjythmPge)84uW%rI-J~Hc(oCXqSlD-YBBvI5#;VdddPH; zP`SJCv0qS}DTsMfWayVC`0sZY{`C+D+rT;;DRYUc#-vC_XUYPdhkAhy5>M_f%sCxz z&U+Md)hmI%M!A%`3roCBWqc55NnzY1hTL7ayBM_A2G~ppq{5^vcNZqyj8Z*77$qdq z!X(cN*6E0OKtl(6{iD=$u-^R_CbyK_UAXlHj5?b@`}+S=z5Mle+~zG%#2>)8Cae&8 zyvd*3UDz637e~~=!2yAr(mb|2xvKU>us=5O{zEw~3H%YuF_p!u2`M-~>U0-vNKHX_ zR!Cf5hIG_%f9MlyNJBvwDZ%%@UqV?7jWy{i(!(^e+`RZ2u`3g66f#KDLCi*(u*-h zTMb}!3FimE;B^D;x(mw4w+Gf$zKuWk2{-ceSv+N6!2NY# zw8?wYb@=}vc(}d0F!gH>uL7*5kK4NoKVK0t`r82O=;QQRJY`D2%|A43@aKVz@o{^1 zVb-CsJO=1_z!v$qy}Pg%T=cm=Yy`GdaJjqitH!X?4FY>zn?~T{|jLB z9~lYS^e^23)o>!8j8aTclrt3$Y{LRtn%`7PisdBj^zY6q-~ z;P&pqTDT8O4@dNPg8UrH-GxiIGupcgAGs65OuYj1b(uu$-GwWCkwQ`Kpf_TfsZWFc z3yDw$y?XfjYcxd3DEDATtS{aJ82e`g!QNdMTifJN7Xn_2IDS^`-Gwz@)+V9HfH#ZO z6Ig}Al~X$4Twtt-P*HVX5C&RBI8}u3-cfGM3>HZ0|1I^f}6O9*ipyEdTDp zp;@pf8Fdp!e<7IC^WBA}h3(yikIlsw*%DyX6c#s{Uq^Cx;k`I4Wwr#ZlTdm53EXS1 zRkf8)aN7x&*VdeoAdIyn|L(#?c-`_#Z9cFS7B@Y@wDa3o0!%p=?LPXw={wFYunzqj z)81X!ZigAMoGW16Bc==pI`Zzq17qTh30B}1dLWmNEh)LXFn9@D;mF>qMue=~&+XlX z-Ok11{5Qn6Lok&|wxir#IQDbXF`c2n#|no^D|Z)$f77P;^MEgp;Akew-G$k<1l1N0 z_6v#aDz=FYsetRgfK{aPAp8+YVrz<5W5_aOp9`M!1~0+vFA>);T9rtjhx3z%&2&|x zx0^+&@g+ms;kG$5FcPEp_|i3d;GdNGSpIt`y0m>=y=Mi!*D=b~C6HG7@;IH2xcu9*hn32I1c1)pkw3KpZsN>;9^`;Zt^^AxCcU&1U+f<&#w=}%Att@GljS0W?rOR=D!nbv z8_lNF_lR+7(hHzIwU!EQK}2fQ3`|5xM|wrajejg!#ooap5Q0;&3s?q9b=)toBv=H| zWh|tt5?+=?aZ^zqx(Tj6z@|c|MFd_iOt0i*Ifm=69z#rT;6sGNO3YWb^vX__hEdo> z4U&EhjQPT1O=TaUTvl=1d!L~~R{`8)3C2)$o8ac@^lDCcULLKeZVv%JL7c{vlQ6@N zI`L2Z<*KWQzGKC?A(Ts|M|v$M)Uycu%uqo&{>DlUf)RJ=wVqzviJw@@xL1@1R9WCK zor{`Y$BFN8RI4Wu-JBp(hduC7A-%2>zY(s4y%0UvLYm5|+{0M*Ot0sJvP6eD;VHmh zCyvQ?u^`G_--#dpMo=w7^m-BJ=?pK>v$ubGIVb!yH1c{?dRZs@FuFu=7w9f+RZDN^ zWOI5(v;0*=-mrSqUZ;EiZYsTzlWpSI7{;^S#r|gmQ-VC?n3rDO3AcuJqpPu#`+-oH zIn}_cO_#)wO{tV}A zs7VfwvjO-{;ZPn`_LlGBdHNwV?GM-JIR*UZOq}NrU}XF=bfk|q9CaV7xd^7LTvvhq zyTHk&Llv8Oq!bX!{u?PlhXUv0ji!bmv=q_|%8}8OU5D}o;|wVcgpop;d=lnUQwz7t8a1Bk^voy5ieDT zioEGHQ%4Z`M3UIKAia`~TbYDhjs-Yb2$Zl2Or)f$>7*%dx{B&izYD?#M0$(y=-qgl ztLvnvk4Gu0Lj5_guYG(Lb<-L;IQq8Yeyo24cFD)%$I`f~bB@4^eF=7!>Yxs&5Q3*a z#~aZ9n9kYhaI{)WcnYwRKAyEM-s6pR&M9xWM!r6k3TjsbiQhN=A`9d$ARY=_R19x{J&(ERj@;7NgiDuCeC$vcU_2k5vpSh8jLD!^*`c&WX>2kN-SIQN9{Ho!Xi z_|Md*2kE$HH*14G4{VH&-&>0|AFSg>!qtN1=K)*f<9@rQkzg!D%z87`e zFdPoa_&i{XeEbg8&lnvy=xZ0@zPkgN*}A^p8nL!-*I4Pe7yNMyq?GDxYfUV zC!*a3cHhTe$GTYhcpaBA$MbPX3Znc7Uisg~htTv1I4gJX^#V7bV(H)XhXcW1W@BM= zCCKYYU?q)&)fg)s2+}5Dt@i>rYC*k@7`&S(y-Xl$$JViG6OEPnIvD>%vUuq!{h>gJ z-hbvC!Sr&0tbczP&rJBl;`v8#wv$f&T9IBn5Temo2k4~O^zwnM#c)dnk#uwXX(Q|a zofVs2F_1MT!OOv5V9yiIWiWVZAnO?1eM)tqX98PjakI5BKCI*U69 zTgs>!PXIeBc$h83<2rZ_XZGGebT9^@WIX!zsR|cAh^OS7j?0HnD|taki6E))ja$v#IF4h;y z=m*dtFfQkLvj#3oF0Dg}pKJ9*|Fq$1e0d%G7<1D}Na>A0&Fxs1t)`3S0F2KRpN_#Y z1Gzz^q~Q#$nA8!W`&fZWN@|VB)KRf_Ad`(Iz^S9-X!;NTmI3N2G7!_T{s2WQ0jl@k zRby1@>+V%7eQTW!(z$63>o-~~$imo6ck_HyR7pfXVj)exR94!ckvb)O63OW7h*x?Mbh&DE%v1u zelvT?hH$bbcq5>#BAtci+Nq1&g4Zz+9zygPE2;01cHaJ)y6l0iS&?gA_%W4$9SvLw zL0a8OT7|mR^&7V#{zi zeEos$v$*1es%$?vx<5%9WQcn%7raUl@e3iGZiC@yq^GFMg!VnHyuwETPM(E>vvhr& zR!}4yP{k=q1#)l-PvK4}n1Pf;xpX3xCRW^Z-T!}nTREC&-x!|cP=h%aU2vkjKCQ*W%Da(y>4?Oq#ozK zpn@8Dl1khUshIjB;vd2{MbimJCXARCqZ&d-Q_?eq(lE&Agp(z)Ac5F4i|E%0Hr-=v z!ndU{aefKdYl6@9@o@>MSWVDNfvpsLp|5_T+c#OOoq!GsoVj}}c5hd}5%Lha431tw z(x!VXaZh6kNZD~w6wT>AQ07xK-Me94DwJwa+*dd*SR7iCRwZEYslPFPAs(lKR4b}D z#jAkPywiOR<|3upnKZBR)BM7HDP3`zqX_wwkZjTK$Ef;S%aEQRMHkBz2&wve+_rH2 z-VDZjz7j_Ex)WXrs~teLiIRNWarP%%+ZQYJ&{_#_ok)tw!Fl)VmacjRP-lVnQ#MSe z!;bB(E3w!+9N>5%a0U6b?R7e;Z`<=qAx@xwht+H3S58G{xX9SF_F zI#qF^D_!mB=g`j&2NFJg1-(dLg4AD>=2=K+7Bh^afrRR{z}I2OCL$Qd2~x}-@9VFN za`(*(sh>!&JP0*}v>FOM(pH=*^_Xi&tw87^r1$a5eD|r3dvV?$fj8d>M5POX6svzJ zHWf7a@@S08RP0Z|mtu47k}uc8^V9ybU_33)8EjK9cNDAv8RS*U)R*vY>W86ZSS02} zu%;l5_bRq(KfD=nX2TyNFxrF?@ajWw;>aS&MixbE6(S^Sx6f+S;KKkbS%O*L;_68) zr`;;2U>K8JGZ5NYlF?#F7)8r9fSVPOhJi3nNahS_+7Xe8EAckp3#eTvja~r4+eFGo zSuwBLbzyq%8lyY4lXhDch-Hr64dQ+wm+pz%98#0h3*{%=M zxTb>?A6UC9PNhDl-5d*}R3XY^-t1WaLE!4}@Il(0@;GiaBD^ZFT7+}<%x;R*VLIEv z@^D8&hV`=mI}0K3+GN~HiCgy0;skTf(kNi#2&ej1ypthyG6wCdsOmY0f5&2)=%)Xq z&e3jrd`Hn60PYk5RjPW=;pW6edRUZr3#B6STWOFU~mu=Ud<> zg%ivLj<{tz3GwQ8V1Elv67-~$Q&a%_D9^Tm3X<`j+z)$zb^DKl@l;mxaIFmHqSarn zqA677ltwMkh2Xn=1RU$TeFWFo>b8jJgy4KhiCEw51bmIxLlHgJLgqoT`xjn8$JDcd zEw;GcNAlKp`^FI*RECHRfOkex*mv8M1HRkT2)K|2l;lFoym9j;{*wWO8zFg0Z5lu@ zxa2@p3C8uG@>X@^6@J%C0TsUv7Ym#%&c|d=a%VL_n^i}A9R#OHSLD$8UEkb+{@V)C zT`Z)_5N`dhJAQ^C1rb`m0K&vblJ&bDi%GMdYcW$rDoA-uEK)^aKg~cfad}Sc@U?hv+055!dwZfB0ShbqY41uu0aW zD1O&fr()A7q6ZSGHdTlCU2m=t&l#N}koa9sFNBX;r@z8D^O26BOxK#W2!DRi&W<@T z>I?*UK0~yw2fmC`-yr63`p?TYRf_%$`)XCKRu$t^tt;Az`!-HRq2ff)6p)yz*1_x{ z*8XY?E|JMdV(q06^LR4l-Ivk)KRcLG{!~(0A#$W{7N7kA3>elO{4OM|JGf2+?SZXT zunhKW9Q`Bi;Pj8UgWtd%4sSy29R#O2C2HNluieJo@`&AT5#51d&mDXOER@55&I;U( zVCxPZeF9fh3Dk!m6>NbB>kj_)t_<$rCy}LsT(E+~5qI#)#bQ-eV6_mO0i3+&4*p1< z7}Wx?9WA0q`S28{-ngI|4CqCH$NBJdr($wIy$OD5u*g>{MuDd8%kV+)J;upeUH5Ca2lkgHiaAs0!;w%1SwJ1foF9N6p z!3zl%UvYklC|-QUvwxwP*bgFGI1ur}3FEZHS9~gV$4x=>91H2?l$iL6 zZ#s$bAJ}@qBYnm9OvN+^*r^EIC=p-rZaXj#UI*hJVXgF2fve!FYiR^x)*r;5u8oPjOX`#1!wt<1^5!;U$dD0f(YU( zP7j$55-PspY6E)l2E^m&N||LX^o;?2IH2nSdBQ0=ldKs zE3dMrJQQ%(UkWl)KUg53iXxbPo0}YBQr^*6auYTj#&cFSB>fbaEr@-A+FcyRe|QK7 zz9L=SAJ`DlCJy88zK8=f5v`};&n&`OUL3~zJOoS}#&=@l9g*~A{MkWlex}4>Jk4jr zVSL5xSSIOtw&-l9nm`OK^OrDMw>W{cNi990XD$Lt;6`wkHejn(tj1$bRV}4?}CfN_$u7lsiO-9R04wO^F;R@#-AUKN2eITN)ZH2qlSvL z4&w`PnvH%EjOLc*JB**W8fCKZ9I(NJn<}&pj_*#PPFg9mfAI6>kz64t#v19&s42G|?1QzX`%S zR*~;8KKp%TlxzmJ!z%F|#y5ZB$)5st&X>0i<0sZf8Tq?}74}N20@h(Xdl_8zK{JPZ zzzPx0&zHex;9TzVu__0(LUmwuL|z=mH(o}EX^r@ik3VZ3Zxc*N20 z6fOeO55cq?>*PUF9LA6JjWx_lU^R|p`h%`GjDOHG&d_^+IxvFnJB)X%ilg``^~oSC zh#+yXe24K+ZcK_-gRxmy^q%n@#!EkkdixIGF-!0r#&1-?vg;MZ-?Nzi^2ZzS91O2o z(Qcm9mu#*-yJ;JoJbr_%CB8F?) zxdB$Ns4XD3vte3?@hu<680)G4SY?PwBbKSKNQd#*$|1vS3YH0y+JN zaD&^+I*hN!`m{41@lz=Yu5Ge6#bJEHLDMyy_kgb!4ppT%j29adGKKmI_=yOPW}-NZ zKUEk0zaZQf65Cag4&%F@j8-{eUlc(wIbxErrnVv7YAdvx{{uK;Hvppz0)GUvH;Fb@iuQe!FhVD~8#>W&|@)I{!N4;)?)rTSFMF&9WozTn;%)#uTK>#w`&3q%}2aQ>!dqF!h3X``7OZrtc1!=Z__@HyQ33vQ6EX?L8kH}IJz6kke%F!`!sT=^p4_W^do?( z3p`Pi8*!f|?zgxAo)dotSUbV-ty%G^Opr#C5^v0cXZ^AitQ~HLA57WgZlTx9!StZR zij!v*zc$EQq)(ocFb*oz;O9CIP|54vdTWqvy$VsElIBzWk+Ih_gWKHxKjIy^7xAYo zraOV4e*ow_HL*bol8Wy91vi^$8Fz3W+nt$yGc4L{KH;r0;6*AJAHt2&i}jF1#`1 z*=Z=bhIY&2+jb4gf-VL|dCM|YWLUMe`@rL_$9fWs*23a?Vp~4B3BI+y5@T3{Ko~6~ z%9ptVEg9cFM#HOy+DFd;;VmNl!3{{RImz#oK7cM_Z1m(VI4gcOZb$$}@4}z2h|GP0 z`+V|}3iEt&U+oT96=aUS2I5U3vt~BIlZR+G2^R^nvV@XY7DX`1434iBp)ELL17f-y zuu6oRoK3@~g5>v7m%l(cOL5^c^0Ia-yrP+-JAl|tlx2N|$jho8^~tYk_lvKhn4>3y zI72kE0iHZpyV#8~Lw+9Uz=@79ayX86UYX^!0Ln3D`9s zCj&hh$3kBG%G90?Jq#ll!ILKgJ^6n)0HJ-1(O(i+IUgqjJ^2gm2Ky_6Hv-no$H}@) z{zkhqZ+ISkeSr-WoCmh#rDeL0rkbPiC;5eKhRU(rdv$vqQ|7=cFY9uDDL z9Bsr3mI|nc5sX+c4bMJVv&nfJ_dtDRIQ4-y6%MOr&V!CSw=gc2fspPEd+81 zLNLPwm!)mM{pWkvJgi$l*e@i`Cg;GU*Dc^?Z51-iU%c=YR!xqMa@Ri*W0={? z;MIrV7v0#Z$?;L{<@#YmssutEA<@9$k+8G&S|Qi;(RLv86cV?MNv>v;`z2h|c)S@0 z!VDpC5xA+@O+LAElzVCgYH=ADYlKB(vax!T`$f4^FyYg?0q(a1#V5Zf_sJK9m#OBH z-;;+%xpfBN)(3F(4gC3=$UIV%IEk5CfKGf*9*yMg#WAMymc{p91aCN?6P=T%N4do} zdsR>sSbf6%=PAIX<(MMnjWwfXM-cj0C8pO0=%%3LEm7{^HOkb}OCY?KiFAjK-ue~J z0?U=Dr{y55B~pgunB)ZA6J5L^Za)aeGijm|os)A1-KJH&uJ8v4_cCc>Qi-5j{m*!l z@kE#;g%L75t^qpHIr;IR8$UW$b*H{x1B54tlp#+{>K1fwAh|w7>H@-Zk(&6}XZemw zKluD-YAv=B$xy)|yLb_%^!p2@2TY`ORecl5ec3mWmO`_bNLN0>QkXu7sNvedj}SYega@~ zA><&P)-?sP?=y&Byw)kp8(q_IORoWAYFGa z(y<)JK=?&Sl%I^GTkg_9STp$tgm490D$W#Z5);WuKt6R5P|8?ZCKG8;JIv15L}~~| zOUp7by9HIr?W1FI$afS^yL2b)O6qDYj*hIXY*>fXa(tG>eI}5T++3s4D`i zN;r2gF_FG66KCXG0BbAqe0>8P3`C`=&CspJpI;0n$!xn zr&GyG1FPuc)M)&Z z&YDPjE@HtJ9K8vDwhLKIr03TL4So{X4}x10iCuGo6fY)H^(DB-il2~2;QxhSp7Ip# zR}m%>fnp-fUyEfD603*UCL&gn#H@)_>3Xc;^a4IuIIP;5NE)VAInpx)_#EO;>uQs{ zXCgf|i>knyNX^smg#<*s1%LLC1a%%wP2`(MMY0)f`aB3%gk;ouCK9dcXk#qEM2d$! zM?{^g5?*}>Mr|c3keEoVb-Z~Bs)Eo^NZdU#FkvDssuohiXG2{#u+oHCgVb3QDV^RB zK?21@>f7HFTY%X2M651}iHWq3Zmii1@Jk_>VZxe7SGt+eLH_{4H6d{}IR|1QmD%l> z0);B$wSwSRrshP&L~?6+MNb8*Rs_>Gk=AbZhMcw_bQcm09KMMZkIQ|z503%iRUvWP zh>5gudaTLVQV`Y(iHpEZEhbX`zWBKF6&QzwMdPS%BBjA1)|UWYvxNUJk?O99VvbI% z0wV>%j0BM;($th##&iu3>I%tNKQNJ!zSkz>?Sb_ooV%wfoi&l3hRw)D84to#tHktr zF_GR*a7{fe17S@jk~NW*B?V1#dqFr#qzuVf6KT=pkV)+gI zsWMI@)sulO7QFBKRC_d6&HQP+R`$aNZ-^Csgjfh{Tvu0 zEK740iHY?7%R!Gd6O4tz;(8JjsT(%(v#t#w>=Y8^%Qum#wNl)I`ZNgViByvt&@+*C zE=0|WiL~yd;pn&;=spOhPuNwY$vzn-k~$y799;>-8boHzVj`Wy)_h7(w*uB)l!=Ly z>mr>C4175Lj3(UV%v(iT@DAn7nn)l09nBoQ6vP!o=H6;eq&+?vCeno2I4uSoeE@%s z5}7rNiIjLh-YB~U>?Yx?OiZN8cjJtF!lPLKLh$6RiIi_I4iATzE(ffVk6RO|?Lbp| zx*4!mK5k8#%`t*d9MQk;apz70& zxL-w>NCb+B)b$ExbVTfl*g+!JjKr*oG~}_M;Y@S+gRFkwxkor~hk!x~i^RzHF%J!g}1ASTlO5z&TO z8mvbnnVhJYNZ(^^odk7it+UiYO(2-T;on!0iWZ7vj;;n` zZ6fnX6KNvlz$uP|=}!35Lr7vGeegl7si(2PCKK*IPqK=%_vbh>=DZ8SDyziwdNGmS zeJ0M-(^nuI&P1{%(!<-dN$x5LcZifBIcp+q!gqhJxtuU03Ls>7$O6_xs@6W~MS@0C2M~H^(qvbW8ZC)dt*Gx~OR}1lNs~2^E_B6*G$OqZ!Y4%XAN)uY zi3Y7m6NwBJ90&_DC#A$~%_h>{jeQg8_6NR+bP<}xM7l}qi8`qsDgnW1J_y}JR*@e1 z38qXc;_F+?7%6RtWlf~+%juCNhBcA?d7nPCJ%^YPBKIuyKWif0r*hc3ybSXOr-JILPpm~5PlL8gj`c4DlQS`qijBu*a^X{iPZE{syS;S zb*$(z2P?O5U`Ox@LvC~Qp{;1;c!L)NR!nefA|*LkX%14nm`FQtqEugcLYgDC14&TB z>Ve#^B1|L##YF0PKWM~WMeJ-58%|=@M5;Dk8P3PRHwuSUTNCNtQJi&634RCsG;yeP zyyQI-sq$x31=d8G@OKmwbyNd<|3@$xrY7=Dqz3pXNZNF95Go4El*%)af~?k>NHtq& zChBLw?jaKCR3I^t<{b{2M`|nx(}l#{BLfpAQgWw|>P-XP3b57*a}ueuCK7HZL2D2w zCQ<;$NV3=ui2Y5(UL!Fvk%}k5&~+MO5gfsk-V77gL|TNq1!#28#XzVeB+e%1Kun}n z)#D7a8CabonVhJYNEcUY!yE_%iBDI!gze#kjtIvsx|2}w+(X@||otd{`$m~j7j5)&yo0mlVV1MLRkpjBde zy_iVXKMI?Ax(vdtOeAX}y@!+4xT&+lM#ztlF*$1@J^rgVgjE8e4w3waOiZNOI3kHP zwF9ANCQa5vdiN`wgG3o02f~z0nyiVm`WaU>rM~|j2&*$`vL;f4EK0Q`($^pyiPRKn zBGI4~X(ExKqJpPk{iM_!8pkG5@-x1PbbX6&B88s>)mSU*-3R%O@9K!EgWx!g(sw~~pYrmrnP5$%H^u?a2kc?NDK8mG*WFgz zF{h{vLNg&zeln77xuvHeQ$0W!CM3=jCnqM-$|q=rY$_;oEiIFYw7CLy-Lr}G2^d=} zOLG;;D$?$maF$`#aWF0ji|a{Dq(89_gIV`Lh;3qPfb!*=NOKB>xdnA$5Q-CNGB==S zBCXqnniUgi!K8TR=%ye(V>QZ$w$VNrCQ{2%vCPq)+iS*C0c;@JfApS1OtckSAC&NSvw2Wbn&eIfw0D>vAm`Hp6 zjxowA0johccYQIDK6XMzz7??czPw#U%7tweR6BY&u+ctlO{6!fgbh9i*jqksO{59U z9ix9eu>bkEHIe4O6E^r!V5fcDnn(+9KNo)hy9w+c!L5nZU=O#c=Zkc(ATG)TM;B=Z zuSEo}GOUSo`8lIQ*8|p2aBCv*d3HgH7ZYjW6daCEPslLDjw1=GK0Sx~RfLH|pqNMp ze^o~8BgAeHvA0Ofnn?4jc$@>kPYH)rTNCNQDRF8EC3pk4dfF?Hm%L{pmD@*EU`?b7 z9dJMph`Jd5lqU(!Fg2lXA`Og*Go;2Kv=Wjjm1iQ|+e>P#i4-o09fBb07x8D3NGzuU ziHVfsjgWZ?mVoeykhuF~V8TR7DH>E=@a*b+U>y_YO0HJg(FI?m{`7_j5-288%O_%u zSQI}0W<@ZCTSsDIBIRy^<@OYSWrbjd32P$F!LbH3I_QQVv=tI(lXD;@Qh%JN&&(lU zy%fphM8!lJkTcdW7lO4sg6W$`S#C!g(oPWe3yD(jO{62$apeZ};a@=bLrB~t%;+@;m<@O z^XM9BB0XCL-_?oq9{zkNBr%b`I_72k3t$Hb_n#**k?I#RBeK2(!e3U2>GfhFtvC^7 z>M2`Gyz&t^J08iJNWmhmsqs`0Y7r?za@ItezRDZI+JewMlP0^0lqF}B(KH5xS2Jm{ zCeo47ab_@F3c|`vnyiWR(g55pOMQP22!}FhvL;f@Ag!Jv(iISHM{0^Rk!aA0G?B=tO%vKKZEU$@pl>N-i%j|_hr(dV(qy|AN@ zuOM+{FYH{r6iKc^s|Z!=&-C{HLHGBY;fx51h(A;gnyuy1xkE+0WmZIOPCh5*?HyQ&iTgS7_QRTy2V9I_3zLn|12&jXw! z1X5wrmTj;fb_lA4AbcVu(!!)n+hBXbmy1pwJpC`s$ZfENYUAtgAD{)=*rJP4e;aJo z!(Q-E{$v|$g*qr_O)wf-ma$mvHrVRXAyt=()fISu%h6m}Y>B2|8|<-y zK|^{4gqcF(`Z6SJgUwz7-&#o1M<8qv66ML?2K&n~bglgWzZZhEs=p0(_##;2e}Zve zSgc02!3NKudD*O`ZLr%;8>TMSHlRu&m@X^ZVB>r?w!zl?CYDLMC790=yEnBv+pTnO zQZD$JQo4F5uu-DT;B^D;pJ!YnKO5Krk(X_-o2e1luuW+kaId@)%_O}O%srw_w!v=q z+1LgE5I(Ekj0I!n64PiC{`Zw9QDkCSDaGBV&!8|T%{Kw!gtoGjav^nj}l#2NiFfX(r7vTRduZ&HtRW$@L& z*84cE=cUXHxbI?TCAaqhU`Ku2ZiB5}SR4Eru$zL*HrQKX^yY9o_sbmHrU0B@qo1eqpfB6+h8BQ5Non91lUNzO%;-HPWL8-UGHe%S-|EC zZnwd{y$h=^D-rz}K{Rxl9LhG>ZQoPZwcB9TD8tm}K);+x#BPJ#>x*C;Y%IKlh^ce6 zhyND>XV9w$*#>(Q`}H0HSUZwHMs`Z=D0lK9#W~b%fp;g4pH=2Gk8-zXS0s+ikF~&BT#_q(9IB z!#jf49CjP*AJ0Xrg2(WBDGaPQ;rzOiZLp)Tvtb`>WnC9o1Cf_)u>FD> zt_<@cSa%|soSb3e-lWZ|yumJKN0=@MrsY^C50Zw7dy}r-@|cf;)jX2v54vn$)4fTl zTjER>o&$A61l?HbbZ^oVi#(mLgYZrSiHqfLgS|wDp=H2v8*Kh>ynB<@fUv=m{B5uWuEldD zJKq62XK~XbOgr0cu*2RnHSOF5E55U>25x7=wA)};-gk{*RTQj8h)E-sv6dpY!A@Bd zGR#(B83J2UvJLj7g=Tzq1`}Z@_j9`qw$hilH)#^$XHgP7T#%_L+hA*y^)mbs@D0MD zs+4W8Q>Mn6;vWG1Lj*@NQMSQW{}j_85Taqko5a`zirfbK4y=g>KqwhWVrzVM!%KTu@6}TEeuK9l{h@2nXo)lvG=>MSm^MlVnpk>fm;LS&H5|9~xelV^sz*UIf zWHFtG2r@tTf-IgOp)x<{H~{OorAA>Ep=dGl=Od(t~MqlKH_C0rJ2c0W@70g{d4eKUiHDZ;p8YmkWVZn6zbn z@N-q%{{_N9A(0j)WttzHtrw+!0qdWCVMfjmMqvwt&e0uPe-KR3MX5hOXn`}gbrmog z2rKt-Td6WXc=|4K(-Dk5mK8Za7+gK58c?y)flsp>&6Oqdg96y2%cS=~_(VutUot<~ zRYn=oJ`j!xiSp#n4=R0+q^ z)Q^Myq!sb+RbAk-F+b3;QB2Z9!5l^G;?(XkKNxmB%4nMnY=LN#`N0BQS4fHIb@;Q1 zaF&<(!2{F?GCycIDa<5&9?V~f&5x7J4<7W{m>=}}!H{%9PuTwmMz_ol#>C^^F(}dH zfK?)#waNUT&(|SNL^lK0%9p2=Z<-&}8Hek^NPZx&;XZEX2L);=gUJ<(K)v?WfW1 zr4V14Fe*C_3jX}y!%-M%o&wk*f}m;C@aG3>yMi?YjFFb*&kugU-cZisEMW5q=jILA z`N6OnX292Lfqf>pogZ|5AGP}pqE8Uy=TPPc&A2n#`N4PP6*INd8!I6Q8Aa^;puI1G z`9a5{IFJuaor*uTNQ5%z)q|ZM{5%r}gggVVb0ope4~F%RG3ky3K7lxXR_*-YOE|l7 zLJNT}kJKacgJBJ0jiQ|(?6Hdc`9bFe+9){>>{qMApC4>m>{URZ4~B09&WMMPiE`KB z5N^&yVPM4xH_c(^2lw^{)n9b4YF%Ire0h7XYVe>|Q^{QF3aq!t%lzQ*5{&X=5dW%` z_4q z&7c$47hXRIrahR+$;tfS9y%Bei@G9M^&*)(NXq=+qlvMG*#WG-y&ku^=I5K@3;C)N*=Lb5B zt4?$E!_q5)-!;9avB%`xJCB1~s)6xX1k0ZvEFXv~)!G5J3pB4y=PcG2G%pglmQ{ry{avmXk&s62g{gKY)Q%d;M^@U_&GC) zkjnks&JUh^57o3B@oOmw9xllGl=;EQQs%ws>;ryGI8<7hAAI{lv?ktBb9z`hnVKOm!21?wWeNo^`7yd6wWu40XaW=9L^&oPB!H20R)rKCF02W*~RnV zGa#^Pf|G=rr7zElR!2(UBME@k7Bto#CQIcMl@343D=L`^(zysJFMNjeG#oCi2cR6N!2wHDD^Eu?=V+#W6+#1{4Ih|u~t2p1wr_HgM6 zBVgp+u$alG3eu+Y60IH?jPtJ$oI#}7Kr5Z7`IBQ*GeozukRI*h8=a`}pW<{IU@r)sPWT{J zz1@lW=tw*qJ#bgI;FEm$&z-1+H=@*PVA};Jd7XjuwG-79FZClJ{3Imy|6vhq+co>4&!3`Xu7+m`Nt2*vug~Mtw;T?c=Bm6zWd7&b)g5w>;MF2abCqC-9Pn2?)sb?T|jxRDSE=DD8 z(M72@JAwY#h@V*3aku5g25=&6#h=gV2WKF59I+pF+}%&WS~!XLpDd<{u3~@w2!zp& zo9!$XIPW6L9qI{tgd;A#alZl$r(nkC2l!AVp-+>G=mrOz0#rrH$(;tD!ooD!;bq94)yzxa@-Np-K_?dyEn1_r%Qx<_HoDkb)z<-i9b4S{;7_UzYOdTU!L(_9d{wVcd~qV z7#6t@y!6lD)VIXTj(Zr^2-kKgU=;}G+Rie~efwPu7({v&e>&3- zQ(L13{CU1;E}G`P?)oODyXYUW3$hZd!p# zeAr1eXAG?btxVFic$KIE?y5YFk^3I8nzEwGY`lyiGb-RdGd@<)nC0C0Kf10wUZ>)X z&%Ez@?z!(>tl?U^Qf_j|8bZjHJzJI{yJTy#6CuP8A*4dGXG?`_N!bd?lB}WZ31!Qk z-}iauo#(vgcKvbg=e_g&KF`dVnKS3i_sn_5!%EyjHRTGrU1K6WFMA)@Q4v*9#*%~X z`#Z5*6()fagi&Rwq6OknJrCoxXVo}UJ^+JDhA!d4~0ynXX$ItFIe*=x?gIna|*9Mryas0Lt$WLaBzd^RcHs5omQaMq&H9&g+%p)kI()3vPT|M>wRUQLb}kNjw*5CGa18 z98-MiGsQ-0 zqkS`bwd(|y$FT3pU^XRodcMm)v=x2fbM(ui=s&tUcs;CV6=rZ*&^?JoKzbC?KeU)x zvb>3^#;{ff-D&Z7)L06}8ewtW8N&LYTObyMT>uXYAZ-9fkJxJ1v4X<6n5&w_E% z@fat(CSL8La{LQI_|53bfE>3ASJ+<|4re9sYXOIw7Pq<4c!0T#J^6|22T&jd@g@z`$2{Sj-FI11xEFr9&N zZk4dwA}K!P=EA!r%2MYAmO{9>M=_oeFYqy)VEanIs(bb%RVHN(xwmlz@;c+zz&Z+^ zonE*k6%XWMErh?tO3D#(-#}<$BI&XCGf~+5xq4FWkgEpA8GH$_WrFjn%%s>@r%rx| zs#}r1moO@+rq)%7OTNL-xg+c(WD2N1fL#@w#@7gbIP4_75>VkmcxcCA?0NiU601~6 ztFQqaMo@0Al3-QzF^x)Z9EA2lBD)CbY}lE1*)``g5QLFJ;<3wQcOvAT znGx|c3xqF)X z5ly-mc0R}(Yf7ErEmQ&yQwgR(6tE>JACG;t|h~D5hOfQk?Vb?gVpc z%|U3NhD1w5lVTkA{AF#j8wkQkB5|AX?Jme9tXrV{?f7J8fv`k884@iKP0HZ7A0PxO zx5@V)>`CK^Nm(5Ck!I%3s?URPJ&h+?BAT?_b>2CMK1SC_=E2z35=V3uFzHX%Ig3l5 zW7?Glp)!%8s$gsYWhxNoG}vqRe*>YdC7C?}lh(vIUzLh8gU zo94Lvu~qX_V2cFj@ydu$Od1s9A0~b2xNjGWWxB2c8;am*?Do-x zmz@^VC)Elj_GFXYO>t5?9XG>l^X#E}fj-!85=70Yq!W(&=8Iv|q#uE>P)OVr*m-a$ zc7RU0i3o$WBaOcati9yd6?eKsq^*fZ5 zQk6#H*M*I)N}Vu4snh~@VVo>P%sx*a3}gKsaf$&i zFPtsJ5qt8`Q<0o0ksoeln+6{|Y$*Bhtk~eO~ zC_oZmaCnpiNcAcb;JRwA%7H>x!=YPKUQO}KlK{z&Lty$6;NUvo0v+iy*YxjwB*3Kh zi25yTvNbu11o&Ek7)52+O;AUw4v_$#sv64$Jui?*fOLl3ZK=R2CF3OABG4X_kX&%@ z&gk~2(h@h6!bmTHBQTjVu8XU<_GmavtC>_sx*G_6{3P2R_4^|0 zkruPO*0RF z*Y-(>5=W#F_%nunaCM3BwFH4W*xNi{iwQT?&B7RjuN_~+82c^2e)R0E@b%NiNNG+3 zJMY&adrQ`?UMD@-`&FTxjHL7wpSC0=$j={Yc8@Vr^! zE7yx5Rg4PJ6Ig%o7PP`w;XRQmn*{75u@~X%2y*j;FS=&6^C@T|e7*i{oUz-FR82+k zgs&ENFpVHV>57M0;cE-t2XW8K_&?ZD5k2AS&(Gq_NfjcD8p{*DGRH;iYIt^5_=;=q z7`yhKofW>`I~6kJe9ObE@HHQMyl^?EdYBcyZcdCf6}ZyN&kA49zZPlApFKM(d=;pT zF^wwzFVD^jUvb0YOc#hBZO>1HujWG|8dD0eVmP?@^$D~?TH%XO5xyq24;yXjMWnv$ zw-ezjPsfNlHWUO3#A}>$NM4hJ6~5|YB=&@_#^H$bHL#&*zyGnb!dGpw6X7dr} zU=lONno+fIiG7Cq{c!t94maaoNflKZovBp z=MSnz5x#Z|h*4vJO%dGqu)rRBP;wf-L8-VT=LX-yxU-1L*^l}d1Eg_Hx z%`6eVLRH~LXMPv+KOCkKu6ZSa@YQx59#~5Ntl}dWKO%hf=@C}VKIq++*C2~MU>vcmG{V=CM?>m1mE$@Q#@Vyv>J;It z=W#Qk(Ro04m`LWXWQDIq&EmK#>ZgEJu}(bUtK9qq?jX7)uy$fE!q@uG%q64W1U6Lc zMfkcJ2pIcmz-EcP2w%_fcwmLEnb#a9>1|-{5^o}WJ@2t0e4TvFVUoT9=D*^bmobv? z_4oq`##_>OOa*XoH&6zL@O1$@t5YWWNnjNTH+5r$uZ{=J_nf*pFp67k@cRf~)3RdF z21$>=pE1G~;j7+wZSZ-(77H%ISLJ<}C2c_Z4#Mc(tf_T9;j22{5*!D1L2w#hJ>lzY z1#ILr0V~0A7<(RnnIyv3CudyK-i5&`<70Zl*VUQWUk1K)Ll9aDiIP0w>+BrIoKJ5M zh6u?>NGxYT_!@@GkUdQWVUdu$f{F0;@DDis@4(nCtaOC0?zBJV889wbmM46z`xE;# zP^sPbPzg9pC71$P;cLghMAIJ&gHVP@JmMLW6}}e#FV>t|Ll9b~Az9(8SNTZK?+wBb zB5|AX?M{TRgu{->ZYl`##FHUe;j2~lNWs4aVS5@+R`?ozC~_g40^#p8o~-ay>qXZ@ zDvp~NRM~JuSAiA2GUe2YBNZ0~p&XH-s=x|g3+9>?X!rM z_B_Oj@b%)n1T_iR9Km_KGIEs_zT#KKsnsBC^^^R<*RqH3Ehq>V{Uqbb3SS#j0xCEO zZ+&r?;&66;;p=4{Lagw$H)kBvb$QrOTy|rpDL%OfU)|Zn3SULCN4oSYp!f5ei10Py zd2<)m6G50QB<}a@T!gRdl@m>`T?f{V^q5xo+LS|lb=k-Cgs;(aT|-Jhp>yCc zC&V4jFMQE6Hw$0A|08^{g5bEA8NYU|lZD^?L{B_}}X>irq^ z2!CfnNTt^42QjSW(FBzK|(+o{Y=Q2)9+ zHG&9V=O^HH{X4+(LKy86zIy7AY6}ww`DVgloD6S@Y-C~F+I{iNDG2-t;mjnC2w%&8 z4XIkdo)etBrV+lV@XDcRt|5=th^h5tbJSA55m-Bq)#PZJ;;p}T8`Yo zqtxd}UTY!Uk8mrr?3k(5TS(CQ7Z85)ldRBk(-VGE zkX{H!U@c`}+ha~osxKthv5@|baN8b_4~SLYQyuA!AiU-$+4ktz1%x3Mv+Y6U8={Bk z7$bb$2JT<`mJzZ0ytQv}KPpA-v;(}K$=7r$hZVjuy&X`UknksvON1^Zl!Y(qjmmis zi4|(pi3nd6KlKY=_dZ1CRG{>Qum2rG#0*gC;0Wv>&mw%a!uy^!NbYJO{j-Nd_!?O# zQ4Iz*TJVE}i}3YkDMx(*Y?0u{JbMUV4=%ulEWmaNPWC#A1mWvQe2h8;!ZjhW@WrGk z;VT1R5x#n$3pk;VqJ*y;w}a{wIWLCP(l`QtQc*Sx*^ zK!mS$gA_CM+ejVdnONbA+RzieR(=&{NMC@tlGt1T5x$Ndz=EzFNIzgPO+G#0>zl{n z?jn+IrXg72YkWhgT!PO8jvN{oM!BF*ijKZ;p_cO_}U02f&7F~@jT({@6++d?rG1?3SSrNVg^KZEj>Fc zd_DM2*p#!chgsq4f$w5XIVX9T6~30{MJOz)pwGShtniiZxkyv~=-FA}3pZS2chaF|NS?Ue+=S2x5()P(?+_YsUA5x&Z<$NOIpI{Ha;t4$+(4c!}3{lOZS z4%07u?Ze_hJr}eU|D}4u*Tl@I&+TCBv#d12*VUu3Dj%Ks-yqz!B+b<+!dHui+N}7> zHVbR^aYV*(D}3ceEF0cDr4+F8gqv}kajf`y?Q3&E>n6Zjh`k73tD7TwB(6Z+3)ld$ z7vbv!7G?7=Fd5iXu@~X19*+lB_6f&nK50^AZ1t?27{{L%6ZG!q?87kyS4ZfzfUx2EUK+ z^?L6FCh51p94>4TzG~)H2A=_JuHYhkl{k!&tVQ}3!l)HAwXP?8HMo+X4g)(aI904C zd^N#r>^89YIo6&lo=GBnoh;*;_DTV(n2+fRUn4F$hEyAbCPJci_Jpqj_(F{;MZXF{ zeL~m(FisoVF}a_?mw!-sGj` zq7rbJO7sg~uOdbv=bi#WF(UDZ=NGpq~ZN|4d z5x%Z%a!huUK$sz(49N;#ng5DhL#sj9l*W@4zItJ^YA*Ou5dKKx$qHYom0h#{L~veE zWxx?#1y=a_{)#gDPdo-fNg_p6ffc@rVQ}Hqj`cujY)PK*l@;&9c<|{CtS{kw_B_Oj z@bwR3UXBGeU2ry;GYZczhJ+PgS+St$OAt2rNq*sLb2+><2H}jKWIS2n>xC!c)g2IM zdmB?6&dx7<@h9a$D}3Etg(X6u>nHGscH1#_1?a*P;p-(Hb*%99?TAR1?gaW9eiISC z>Q;|4eQ^v3(}ctg$j(Lh`a?&UUxBqHJ*E}D`m~JYBI@73`qRhsgs-6kLx$v_(3xm--yM^Fhn8DdAg6w!dIIGc+Ol(no|107ky3Y311WQVZ2+7@@}Fs51`xH zL}~;Pz8clX?fMYFQ$kqk6TbdNUYGeWujT}Rc5VU_`0zenNxw%7rqKM(yAgT)o=u^kY^FTGS7)o&m*~mh4f7i zhwxSLYghFHHcaq)gp2U?#2u_y1~x}yb{nRm7Dn`X4b6s!=1P2^}%v2PE<5R~hjp9@e!fOGm zPxym`i||GLOgjXK@bzf2Vy1o*sY5*zD|}HKdcxN`SrZLuA()>Nn+qVq*AvqaJZuZn zcUw%8Pfz$dG#;TC&LHV>8iEzR&g4OOf!NRR5(o!-Hy%XzqAI$t@HP8EtscQC2WrE* zf%R}d;cNYZkRkO2a}cq)xw^o9vD=DNP3853uV1j* zoE}vJr##FGUu$wjPE&slJ1U|le4We@Z_fNd!l*?(;p_1lj;Wrqo}CrGGJYAUj3%C) z6~5}eqD?tp_b@AbH6H1ha*p*dD}3!+lV~b%ftQ~ZzKT7I*)~<~X3x$FU+q2%7`xv+ zJ1cx;Z4hJZ?uwlVU)}0O1gsoiVCe@Ab2${{OWOabBcUREJ@Q@TE5`areZg-h!dLH$ zk(FCLL7+{ujC0;T%j95%ugVySJ>e_cvWWA=u%Vr~{$po_ucydPgs;?02~0l$lN(}2 zjm<4?E^-mR>VFc)?96D!d^k)d%;xb#gs*aEO)1KOR9%RMV}-BVBTfHm1-!FxN>Me6 z@b%E{7&QpkD8Y>nD|~hT&J<`C@RdG}DLzlbWX0F(vtqbTcY%3|*mNcG6~SFNjqugs zQF9Lef|+%hJz2^>+P4+HejOBM--W@fOziZ0i|}=z2A&RdbMRVO&z|sAx;U0>^hEkF ziy7goJXMVdUmsHFxR1b?D=e-%5x!<4_P<^WaElP4JV5xmSOJCj72tUxkO$2y5xyS7 zCwy85mt+2i!?bv1uOtw@nw-K@P=0_<_z1?22wx}hm2)i+TKP$It4$+(<;tj453ok2 z!}JSZbB3d)J_hZx|582Si*E3G6Bs)!D~<5g81-6%%JByXS1n0%b&Bw{7Mo*IWC)#M z1@^zh5gEs=@HNH_^R=Oi0DFRP^AKQ#uX+Pxxr69ufjuYoB7EI#8L@u_SWmGR;p@5c zri1BsflU&75x$<`@xTgS$G?nalKvV@+TzZXMue|A9vi~fd~7+)`{11e^KbDjE4~)s zAqkN z61E6mw;CrH`~zSg3ogRfvJ>c!%aOjGFlq%&t?LP2T^~ZoR$#{jr}5PjzN+nuRab$9 zR$6-=f0-o0*XW@!roEHFD(GW+!q@xHL`YRZcveU>KzqX1M{6VJ`!WbUgk&TnyW*?Y zJ#DfZ3&M0Ec?A>U>)ke(*e(NOqp;EuzG~tt1$_{VW0vI!U)!HiCa;^oLaS^gm;%`q zUwL<$80OUl)rbcsqKZeg=fPmgEUvhbzRH!RIAluM^H^&qJ&TUvX0% zH3HcCg7bJ~*C-&Ib3dng*adUWB5@YR}4tnk(GMx;x(0lll=M1-$=cqzj>jSdH4 zvXHpnvvU!?@*Rp?YfHgepB~c+UrRm-aS`=Fuul4zp76Dycf29}3qlwLkLs0v;ftQR zS@;_KAK{A?1c!FfE%n)juqw5FV~k2&x)m$FF4f1vu9ufV{W_Ql>X)96Zy?(}oS;&F zuLB_4bbRWV03D1zb$lMLObY&wG^O-~FWQgA6TYfUhNAr?%DaxrJd;Mh)zkmRKH=--o^fgkOs*4-yp5Cc%~1eZ@pa*2!^sW&QQ>0ty zYZ~E;3a=d6c_}5^VI#Es1%AQx2cm_RGZg{7gY>cFYdyKKLQAo=5WZ$1d5MMeX2Pw| zQs)b$wj)97??Kq(Ct0DTbPZJ635!{wg|@XxE;RaXP`xK z=-rf8W&HAlFY@CMn7;7!0A`3}-ot0E>EHVZU+=yXQZt23wkAgrzFJh#ipuacLHnsX zMEE*UFP;m!Umy{_=nPr-;{AM5{yC0Y1ca}*zCn9rJ{;X1y{n*7av=Rd903;*{-r$@ z&q8~YKyn2O=|sY9dt5pktFj_N>t-Od^OJ0QEMATF?qM<89#p;|dRt6_5xy<}_X}U! z??kWoI(1GdYNz$!Z6;rTP(@hbYyYf(T84xpKu!>Pn@|?Ms5dHS7!oVoem}toU&Vg% z3tyMkBXcTH`odSMA7WJ*P%7XE7GZYnmjgH-HTkJcV!( zzIvC#ie+Ha1ux{;L-@M2Dy+T)wn1>R*HI)0U;Qct)P4}o2#JL+CPfKf3a|)Ym$3hp z^AA!)_!>APtcsKKhrh*8g(FagiXy_-@duQuKzJ2kH3_duxCmd=&$L5;2wx>mL)Jus z?u9=CJQFK?Q5$-~SEqdeLz)fd0%CIkMEDwg2inGZq;IpBCZC@0b%Ulpzai<*Gz2Sr z9mxrT{thpJaIkmdL4+@=qWcP89Uz<4!YK!;!n&6Aa6jQ|`2yFFUI()evAMcL_?m!N zU+irHuqonAgs->^m|{`#7x=T1ei(Zze4Wh~vEL1BKjEgitnk$}Il+|o1ZH(&o6=a}>!GSxKtP$a2G&u$iSTu2TbwD) zTfl~ky$E0Rsbh)oMc1r$CW0oySN>b1f`=MW`(cC#Y5&aZxKdC z^n|Ylc_Js3eIqccY)|-l@IsU?8P^;= zbOuIvm=(T?qUUi1&hqlJ!q=9UB2D>?XJ>`4O&@7vcgVA|!q>Co6HTT6BX%NuZ7&pA z@s(*4GR9#phbDYU`-Lw;Mfmy&@31&FSWToh_S=c@)d|nYOzI8-ZG~!_^QNdK2P=G) z!$|B2Uxj}O7`wT!q5W3>V`qi0Qe-E>*Y#fv{a2V=5;Lk!ZaH(2i|`fGB*4z&He(SK z4wDJ9c{~x}tM2PA6H9_rQHX|Pg|Fnkcp-z~rWx>d!f8R(D8g6Fs5sRJ*igZZ4=a4l z*&D<8Oa=bAk7J6@6BQA@S_cxiPPc-2l-P77@)f~dIF0bNdW1RI>tH5qu_sIUNBg$I z*HJ_spjJu&vmCM0^DV+x)$#D68-mx&diI2`JwM?otUJ;NTFeMvZK-NR_&Pcglc|Yd zd@L-kI}yH?^o5({0M`p4$^(S2oE0Gu`~vWl5XggOmIz;io*|9y4k+&Twh}sdC4ul2 zNCx9UfRFnK#*YYJg`dI~fFLyUljv5PM))dLBcQs0H6$ITU-&A~7SBghK%4(xswaFs zyb!N**MaeaWu+0m<`s8UcPhtm5H47f=IRvT>+XseBYe3(ARHc!$T)6=uS!F)lOj5R zE&%Lt!p&X93SZOkqMa|}8o=s_y$D~E@%D`EI|1u1_9A>8Pfj%U?*JPs_9A>$;_<)= zUtgUJF-flglQu3kr4iw)n#YFl_4nokCg~Gk{vp0a_*&K(3r>)%gIh5P#1T0+D||iQ z4m&;&{s^#wgqwSu6~2Bd6d;`}E$qHXD&W$ym7J=|p8c$aE+JQlXt8Etuhtqhn!q=b^F=nsWYapl}ZJEs3S>fxA zsmkmXn+t>#BJrSaNLKjz^r|w#S0xatTaqVyWnUC9gHLNvuiWDj)LX#D z3C`n{k*lomb$M32nghaeKglnAZR&}|nIIhWlZ+=TeD&%Vqb`C#TTy!#P#WQ@F%KbD z_^NR`p6UA09YIAqV;j33bm58c)tpVN@YViMq_v(0y@TIGgs;(0nkNZ82!wZq#0|*K zMff^)E8^}`uvVqVw8B@+9*2vl_keZ8$Ml4+LQP#mx=sWXJgQgvg)e&MX5nl2e}peq z5S+`HLYLZy(CnoKyn@AEquN2=T9OZGvk;rE)T9xvDiz2LMeGyo#F4u1FZ^5S34Bp; z1$$kP@Nff}7aa6!wD53xImD~+NPnLS_A^zo6@t!<$8*6VB!6WgeUNY~JoNw2RmYH^ z^)3(&`$<-K_^cvEhw~P*!UOGJmi$R|T+So}g?2>=LA3j!2tm(ufPw&B{7D@86y;SL zzdRv`{5S-rF9dbQN7Q8grq5i{zxNS>TDFT*3x!R#CPxv1p2d`s%CMQBKdCxI2rAgp z6!bTNa!|nJr^o0-`V3Q4Au2ShLcEJx&K0j999~MpgfD+a7{u9i5%(~qd4|=flHA#| zSE9@eUI1l*ZCzl^1g99M5xlT=JCt@+H(+o2aO1=jptyD)e;SXz?}0I0 zSk=8;N@=&rQvvlQuyulS6`N8#sokmtV$~jC#|0<*=%QBFZnYTb-ypc?<$RWmYm?KH zR2Q|i`|^kAFd)!==1elH@uP`hrslQ*IVxz^TR%KP5<6!cpZ1eQDGFvWJXz=9A$W|hjybf)8ombqUZNfwvNDhu7+hl}bQH z>{IU~2;0JdYlqkB*bYsGSK1acAD>u0;>hsYdyAu*0&7X0e&OsR!|Sa7#i-YiI=~|O zum_I`lx?ciI6xl>{JRH_4~#z>qdo()THrGT+u?P{(gd~D2Wd8!;k7pk?@*y-c+G>L zix=P{v_Gh5JJP@vawx;=jpH%kauQlG0^(b@v3A_#6^n5Ca)rXI;a! z`5MxD6UKST@R~XUpFSb^eGBP(l$i{#Lt(oJ*jIx4hu0N-wAv2run#v*WO)5kmyvj z$;l3{g(pLY1!06Gr5RoeqMf|qwN;0BMOVNQuxTe*Q#Swb8pbEnJAfS#oGj7|uk$w` z`r#EY{uP!tywauXU9Ap{RjDzz9hJKAAYSTTJA^%D{~3ViPzCfQ^bfJ2+!|Tm&@Zi}Q$vrKkUnATOuP@`RPH(D6{VoU}`bly6cpqB6Wqq@h$DGQ3u7p}C+R3natq9Yh6};gt%_ z4Msmy&SgiiX#g1CQ-@k@cJ_* z^~I6;ltuJM3`d67DYLP72~Z1xKOxu-uM3}wQC$U^N04%M;vDVpx(|U+Wq2+7D~4A- zv3$gl;kDofD7f&lmOL%y>?6bLwaH5DMCu`n=r28ZOyJ{Y@#-R=n*y)$;PHV;^|9R} z@=U_Pe)Ts5+u=3gcf1AkL7L5Fcy%GpIaFvFUKiZP7dr6K9*LdFbQ?L8;q}t$7)1pf z3TPz3y9k!ym3t(m%kcV6X9O)p!ZIAI#XyGFI&Ja%u@mXP5XO1Q@cL>Gd;x*vYZlV` zC^H#ee{7SW;*Q|?2M3!*p56HA7f-L%%i-H4VC8(caU#QOjEkP!0E`yG`qj$?!)vP` zJ_83fKya>N8D8sN45;zIJ`tSkql=2+b!4SDwE~3ALZVaACMP?*F8Mk}9RlH$C8Zf& zN1_jS!|VDV6BJzm3Ak`_;E1jP`}BHieS#_s>?y&?BF*snbOSuSHUi^CVR^$VUAo@Y z>d;tKAteR@%2S5w`0?i=n}A@L|coX^f|_`N~9#}3CS z_ZYr)!GZsLe~wf2&!Nv0bMQoNiY`i*fkRx`F?{OjFgqCTw`EuCfQys0Kh_YX{G{Dx ziRkyBF1-)k+cA7SEn(4H!21zL;4F1Gv-|f&?auxSFGG$a{es2xMI!J^`jq)P7hPo9 zAyjq@KeGv!QTE@k^als~)ATE1nEsC8&o;rmuQph%{We#rYD|uH$8hQe+996o7@mYD zaXk_#6UF)#l~Q&L-?9eFPV_>cD}tqxj~|5Cjj!+SzJ(p|wA zAgsyg@uqyTV|c53IEx8jOtUO=*=Cti8NuhbIN9bUs2D2o3gF*bj^@ge9mBh3(S~#g zgi}J|`jQ>PS3I3)NcTX9J8r9k%H-`BUh@aE%R>N*34wb8wW_yc_}9JgT=EPU4TZ&S zWXJFVxH0G;y)jC8Ea>ik!(pcG2l`vq#M?3arPIR3j^Rt%DkkaqU@jqc0<}B8KT5%t zR;SCGeD(Lhc8E8FR}H#5p{!6Q`V9VDAe`;_{Zh&t1T&&WkR8K^#VRK0Y$x#0fWur) z{C+8Awk|cpV`Ing{t%ssq^sgjEn>58e!rB`D(IH@Jl1$?53Docd~q7Q6SgZF*=-hcA@pcT~ z(+;Y`V1VO&1a114ZiNnWDCib?7jEW(vDmV_9m6LiCYmB_0rn%|rU~d3UCQ~OI{`by z(15Q`13NFc-7$Q985BUD!i^6{R0(Cr@Z)$O(?Ppqc&_bXX6h$Euaw5b?iha2Gr^AG zuOEzIrtSp#8)QNSjMRhOF}&PjEUg&{aH5}JcMLCGB*Emn82C!!c$H~)46l_MZ!+2i z{IK7T>=<5LnN!u*K)7ukc{_$@_&nky+iCQF9FgiAG6Ujj&yYLgAJ-J56tMDyn;y+L zb_{QX#qLxux(Torp1s{Md~DwYMY9s!3)le9-tHK_AG?IMB78EisbViXhA-X^>iU_So$MH1q+gt2z64fpKa&SZ*)hET(2!w{2WzgM=?%L4o;GEo z_)GBn=m^`LI^(akH^l+PUZxloKDodn^kkEH3eydA@ve}rm@JB#OE9Ok^~KI82e zUTqU@@Pz;tw*+s;@YVNVQv>PEEM^`U%w=qM4F7m*JmPkGM z&yJB6wmXK;e==4DmV>cXSX>WY9m$U2-?j(!7-;8&N-S^3@K?SvPm0*m6*oZ~k?tHU zf$d86|B-t^%Lc>JEc?5V#A4fA$b`1Y^uu?TaXf7mvuHt86L(1#AXQ6O+ z2VtO}#7|SKZqt)tb=onUC%sNDJfx>)?SfZ}1rf$HwO+q~s!$y9s(8Av{-4NHU_~fo z<^%`rkNNgTpSjN5Nqls!hPm2^MR&?{>4TaonG%L@u#R7wSOYp}R*4LH_B& zz(od<=|V+pex+r)FmiFMDh;b1WJy1w{$%ZgLCim0xD8{6xH4T>`-964miukl6+7@x z7gjHeWBSqi(7oxx+Df>P^)>Kr;|SzLVZ7+fFy@_GF>Q=8}3&kWrJ83 zqEgCq;o1cd^g*B}g;AUsGF=GarHQ@;Fb-66qU6HlEz^ZD%e2Z1!V^LwFHA}^U6_V= zfVIGCl@8NCUC7n})3u(U4f`+En=W*z3D!qoEEHB52OW&-My3mKb+AP3TQIg;mVdgi z@7u5{LnS^5{4dMVTv;+*=x{mCkir-7=_3wP9b8{BT`1K$;;9G-Wraj#@}>)Y%3-=t zA7E=Ca8ICC^`;B&tivt37Z`(u#cpJ}aQUoE05DyM{Se!MfT=&lpUa z#bIzeT}b^HWh#c`@&tJ$lT2@Y~P;Gj)5=UrA$Prwgk+6HFIwISw=R`=HMx z6DnY&9_)0XS2sK;tpvEiPq5R40s|uX9tM7zI9^fhbYWJGSd-B`;Bl9I8Oe0v3&bg* zQ`PxFNF|c#k)O}Ri{{RF+}|B>QVm#b>qG_ZbYW?Qkg@Lotcz!Frwb{Wl_|t9VE^;% z?Q~%cUYoR`>Czlv3q5-~UFbb8q`DEl3D`EVm+8VI4`CGj4e5Vc+elxr(}gqjXch1k zOp0)rTB^!}m7OjmX2aP(4Dc~akm*9E@8iu-QW;P~3u_vpOfE8A_$t3P%&uS!@H06( znJxtIEW(4`WU%J?nLJ3!bm7e#kzsK?SbP0UZ_t(LLe=b%B3uOZrjPDT7iQuETh2Y} zRcw8X!_)|$5&iL|3%y%mq%R9bHDS?x#+xo={2CMM7XY@g1aG?VeheN>dn0{>#khY* zn#N8SH1;|VOao)SkL67lerSWMU>(36Lg49w84c`oVdGdl>zx4OhOqb)y*iTVLM99j zfehF1>Ig^FB@_JjMN9{l2ArFf&3fNJNf63fk_y`C!nX|*xc&l-fwi}|=@F)#?Q|j2 zZ`g#M?mh#-8k-)|P8YtbkzgLI=7Y78m@*)wnJ%oD;2P!uuuP5e(}GMFex4k8M!QOc zTHIcCy0GJYoO>Lesk7lQ=T48BGF|w-JYpzQfr|hyD;!Fa>B6Xbk<)Jkyq%AunJCkR zviNqd4+!rFiJzz9AX%sJKRO@U^vpxA*Hq0RU#8Z_{HsgmgM?g z00#@9IuY7&#>d@GW8h&ju!Vv@nFrbMCw!cHq>Sg>QE!9#Eoj??$^_%;qT663X7#@T z`&)1-i;f~)c8gv{ft(v?dK_E{n#vPRy5Y9jhnr$52<3#tgL){iwCvj%* zf!ck2k!$RS0DDL5GrkLrEqPw4j#;T>^rV?QLc4PwjAM@e48-N)EaONb&o4L8BahSW z(T0Yj4}}JNU*8=-a@QgIqOrBFT-vivHb8v<3)$Zbq3Cz)FLA)qr{_G<8pmxtf z6(Juw_BMjx;D~gP>pgHXFXu4RPfBMMIQg7*7qv#{Uh2c;kXoHAXyni@a=)T4<&rxk zHA5fM4uQt(U+r%B1Yu%{_&QSG6tnhZMo(qQIRfru6%mn@IFo^YA{=(joQDGLCiw15 zoYlZL5r2|`vIvx zi`f7&3v*GQ3c4A3K%@8r;8h`*VS))S1l@P*#F>jV!(H4naClXuxdbM^4hRH}ON}q< zC&8-eXL6?e%#|Dya<`3+G0b*gb@wsNGgop#$Sni4o87$w!h1rZqzI`Hp0f+bnm)Q1 zgq1?#Zeg;k6mox85l_28_+3a`)7;ejB~fzQkekp7{pC6_{Gp!^@O$%K2?lOZh#xxenl`&jBUOF>v;otR!9r0;T)zX`c( zUw2GB?FHdj8WMe%ll(`>t+_kWBX5Eb!gE4&c1#L5Zp_m$Cc9)13KGe?$b$6AO>%a} z?V4b2DY_~M&!+Ljq*TX!v4Xjk=$Aq0k;W5!a+6%caThnxDnH%i$Aa)d8c$5>;JEv{ zx~d?Nz64>N-;;d0!9prO8QERg`4Nd8RFty`Pd_R7Fc+c~Y<(59(5|PEE?X~sfZzl= z6VkKe2uvkG*{)z4^cGZ`LP#!cAw83DyMk@uFh|X&shDm6LJL31u3+o59M2=&EM^`J zltYhi$w?0)Yg)lZ>Z~jfrpceIV4H*&$D?7q3Wr`od2PclZv`9qaR^L*1>0e4*FffX zeCC?|z0V4^xrn-(isG2e$kya2E7$@%un#1Xs}pG%Rfnu#TTl}k4WKpx$qF`V9a+If zh2}Le{1BV-d29YkGw4Wg5On@u9f^8<` z3|YZOvUWZ`v3$gl6>NL=Yt;wXK=O2ivyZG``)z!jnt;@47SSg>cub(f(HQkPptS=3 z;lbkr1M(sa9H2u2|3$D}!Pe=IusY|1G@Hu`wmm4kLxq+VY!^aUG6o+hcyU0l69Tu% zp{!s#@V=v{fYkuiCRo#~N>;FOkEC>2!S+%A026y5aex@e3bqA#p zxoC`9jO3LT(k^8tE7;zE?T^6r3(hOA433BMTtB+%Jg_@H+&GaHY-^`t0ZJCUKzR@c z7eFU^xnKobXi7kp09HY8u3}li_SldZ)d*NS!O1?ls93>vwFKsWAiN_aI+aLHb_LtD zN$3V3(CZv7i5V~C`-|FWCvOGYI(!&JSHMqT)0-euc2fg(1>50ij=Bi!U%|;D%?h@U z<|EwC1GxP1;)wDh1FLtnIy6?LH14fbrY=R}3*p&>rxjgF=VDPRcRPga>QXLCH8@iI zaN4C*5=#`hf0-ImUCL)|1td0)^JA>)QZaME%h>-I3DYRw0@w^$(=SaN#WRpDWsKhp zY)~b0Ekt_I-vHiZEmRiLV!PCEZSTQce@+nmI2;1T8k{b5+=^AOtu?`S2tv6H z{EqJUN(a@YzT0j)Hs~Qd53q*?k8NFD(cq;V(xOs(F2>5}-_}DfS<)SGbP&s`IPNk9 z|E`Myryt9TjJ;S^KVL^*8wBs8D2Eo*1A0(jlUP=BZ{TW}0dS!ZLYQ7F6Q`=bb~kQJ zP@Q115%^ESnOToI2F*D04%cpre`1((2KZ&+tRs%ZvKoLO^e)Pt1&1jJc~zO7`65Q; z{WRy`6q}3z@C8n7y6Stv`X5klaD(4EdVmXPlHSsd&bq@1LOh6dZXWx;-YHhTp$HzlJ05 z9c5tKW9Jk=aWKh-gCYGr;kG^cAkN*&A|O}t$w~19oI_ji&NB2Q^1=}zGhQ7Y+S4NmnhX82`hlCC3FR$9M_6^qjFjz zvBI~D!zQj(Y|fCHsx!SDhks`V!hx-E$eaq4eq5`6pN&%)LCJNWUr%0h-
zU9FaauwFQ8ch3#lp|r+SHsB5|$$$Q4r8 z3C{)WA;RwxE^)1>pJ|5xiEGs+Pnemy9#R{7CN{1WwV@Z+>c(5~hBN@oA;jhaNL;Ix zv#@Su3esm;Op{M9uGR1g5Vcn!X=56Kjcc_#JC!*2mYss(0!Vsmv#T&o_#6OFgdz+M$^ z64&a|N0CfM0UPJp+qhQs#zjiA0N7H`-o~|RS}n%pzZKX{&)&wh>X;N~YWojhe~G=s zwW2G?i)-~x`uGRPD63l7tA&iRX#kCr= zJz!4iB4JcKFRoQ^M5KD+GKigxYc=+NST;Z>^C)4)&c?OcS~F74DjsIzS~*7&OgUS5 zn2l@IzH+1j`+ND>xK{r@m0&9Geb3IuwaTcmhZ|M=m!6%CYqbZxnJfJ#v6Hw~|H~SQ zYjqab6&&1PIwJ`lX?8LsG}v}2I(h9_r*q~=toDbXeHFqHWhZg1{%sU-UL6FIhYg8^ zVv~c7YtvDL&!hcvu5rLmKpd>}*`CM2z5GT&t@PKZ(8^$5t_;YT*_)!-T}O z8jEG6#6FJWvY*|U`iI1|`r)+%CdOyN)E|c_jp5k1R_+-yvK0khPB_`98YQk(^W!n9 zKCl-AH$H4!tLD#Y&Zh_Pkv@(oK8F~QxK{TTVm$$hJrm5Yh)v@PUlH6D)5NvP)yP!M zPB2g2*SC#pH4ZxylkdA=X32aX-xAkqPhmW1>w@4FC9WB*AKHqJvMlI!e-w|g)sf!B zV&+v%ZmJrIYc=gTJdkw-qqnfQ?j){N8FVE*2H+GSM0r45tFNBG)9@02>x4iaG_xeG zRhtiyr1yeyOlbMMk|3^C-Gb;X*8ns6)?Vk;(Tp$$nljv3(S^C81zc1)6 z!?$|XzGsaJJ{SH%YgHZex5T!!M620jn=j!NjXC9 zxos|!bS*IJ3tQq^z1mhAyfd&@1(pVh|$`*5U>CycHwO|9$2wfe0~qM8frbHVA# z_2ODB+>dYJfc@gbHIrB!Pg)gnuOJ=~x7S}_-SRPw&Ypz0Rxf>MMq~W|mLlcFVTwa` z5z^VP^Cv#3;#W*%L8vAq6CTONwaVc-Cc9Q3ydoqjlPQ?QwW_@Z^T%OeOcGW)ajl#= zcuBhujL$90i)*#yfk;=}2J9D$r-^H|^_DjM@h=c=5s61rQ)(O6>gEYN%As!b1KDx@ zIHE};jVHx8?#T)9=G4l9P>o33W_-JoxK>MtoAFh*0->{bG9(UJmBDex_lY&0-Ui{_ zG@h80#c^l!i(H7Gg0L)&CmYwwT@_>W^Bo`@5KrdpY+S3+>mcRRg>)H&yW+`^Y+S1b zjUp?+a^PLpgE%7B2FVFYYhs+Yze+TNPZ?lU28_cLM7qIFDCmeS?i_ zwQ5qLdJ}{(ei9Fvya*y`VvLjFd8KB8@P(gbJlVKbyYeThEg;bAIqw2W6W6K;4BY55YGlqs?*!qHkhsIi%MqC;b6l&_ zEg>A(woPK=z0mPOq)eRAqg8BiHm)t&2qf2Ge?u&J_Y7g!x9OKCP zCvwd1K$1fG0TKh;E8Fm10P%ZT{2pM=3h>r?+_Q+SlN8nk=xNbiv=Lkc^LZ12%lE?7 z??^mDTrRMI^K18&YKU%#WQ7xq$HA~(h8wnW=TUahj62LSF7g9UwVViC5}z~AG%l(F zde*|mMY&ZD7LiubnYk8NJT(FZ6*2itg8*vx8J&;~T`Y0zF_gZEcF#QQsCVIJ61h6W zwad`+IPa~oY5|g$TS(KdNbNS#CC{ODjh~j<{dth9_5uD~$iH!o@-uZ^{U{Z|A<#Wt z8tu^r?K;|Jc0z7E4&n%$W&>`nS~?fWlBT&3py%wi1m-*mUPX^f@u!k%>s+MHnC5y} zyHjQ<=5zqBi^t{WYN#KlNr7pPZrbhD5?`nx+wtJNPh7461NVUNzErV`rGVC0IJ&t8 zpt+Q07e50(XgQJQ8mirQ|1~Zy1G;PB=;oTBGjp{@H5U~zwG1MCr)Eq*q_@E&IOLm1)Sew~enqt83x^$!H_!gvdB1#qebojW3cS4ShKFMziOA_92jI6T24VLFaL zZW6%hmnMz~;Oy55;8&;M*0~<=W@{k=`0TS`MTYt){+uK@U$g*TY(+e0qwfL=qTB`+ z0le@v$KVeFdqi*&z)dfv)dQvC5%?@?ho*_@?OP$8GCfwkjU_)#!PcYD`T38^JgiK- zPIXj;sxvW%2%ibYUjQL{p;{QO&IJ=c3*t0`G!ld_1l=J;u+VfMQYL}(5oKEh|6vIU zF30fIpj&lyNR=ggIj}W?ySe5hs_>nldtqZd<39sBC@{AsW%NYry00ncO}JG~E5ONX zV^O9TQ{03c$xzJduYh9lsGEbRVxuZ7tQn&+g`W(?fBO&=RkFi*oW|Fr;Z~u{{Vt&i zs=&G?jzA?UZF$DVh1?BY!PKn*bg`hWO$=V=6&@eT_D(kJ!$Rkyhl4TR&nkb4@|X~E zi&drB*LMFEzwgh)d^6~gKiG<%Uw9eb+qgN{3J zysKK$iM4&VgzH^4Rt&JWe$!j5|zub%ZGq@N;;+C@`EM{1K@1g0sIf2=maEFB5Kpe5HpMOnJ->SYHT>4?M?ZM?r&fuzWB`45l z3zW;5pfAS3H|0m4#jDcY-y@k%qhoV)K*U79*^>eJsj%GnIt)FFM)&3EEg&WU*4 ztn02zcqktRstOmBs=Ge*;0V0miNm_Sy5AL|%a-3?*WG|`jUAPV#{Ie*3w?;+@$sdU zqC_=IS4mXr8Tg2w_X;LZxUa|8!0Y;zsGs<|D;@Pk2(0Ae*)UCi@iQl(E12e*TIyu0 zj&CEl(8UI!w(u;D`&mNK(8Eh=X%$KdeVnK=73~y13y)X@+dM*7ScbFc{YBr(T=WCD zn+;bBa0D*n?W*d`&=B{JA87IVdZcf&n7&H{WBafBC_X~d$AFy^Jcxa*RG1x<)S1^~ zuPy9Pi8I2%&NW{ae1R4%rLzwE6$1}Uw0;zf;=CR=q z^rrxpSx|2zh76>)5ZPxdosa$rjDvob45YPAqLlh?ptmg}%|Kdz70Q%3e@NxQ!KKhU zDI*z3-~JIrDFLv85c~t_!&?!EmrBwMgmywQUhF{n!W-zheE|-#1aBa%g`#-_sk))n zFXV0>n2U*hn9Ab~q}32VoCnJ90qzij45WKTBlaRJ^ci3mJlqbXcMe4cQWuSqh{I$c z18ISpQ1>1|dJ)2?T{NAZH;`7YfPu6cz~_W;nppmUbi$l?9!R@`)R%~K8fgYnI?pr% zsq~)c9!GsFHA9;iGQ%I!M}&^eI) zrp!;ijhyVO&t^wZ5(g%ka4@9L5pG|7zC15c{fz{zQ$Z-@C)rn@H&5cCe8ys?S1IQ^ zWR@KG4q4Ny=vD=AZO~)#)8lkvVO;$3D!S)8*dqkS@8Qt@P+oKJ%X<|~ejEbRe-&LX zm&4}!eCC?|z0a%Y@vp?H5Q<|mqpVGi@+x{U)|OKl@)GF|RfoKaermiaXgPsoW!KX< zDS0nVh2|R={ZKhe<5`PVb|nW2tYPFHa4 z%C16}P;gqNMUi!X0W%+;SU%#&%C2=av}y>f8F_k?vyZIo+KIqAU6I<`BD$~#j|t4g zgVFy0O%}L>2agZDUBpof04*2zNrLUlt_x@I6y$?6o6E|smMFYKg_f0F&mvB0MfkXf zLG%aBYHRWf%8IN|%*gb6>;<=}4%Lqlp;E%C0Jv(W|>6 z{dK}PFIm~uDW|JOAbEm?bOXvvR(5@MG^pkQ`$BNDuBq%PT=bZw|MW>%Z2`8=hZ`rd zvg?gHco;Yj#&uye^>V?=u044W`!f~S7!EF=<|>wzT{Z72RT$V)f|Gr8QL(b?m;Q*M z0YY0L(Wz*YlU>>M>p$_THwZ&4$&44WvMWED#9P@l<|POyNcj}(W!54Roz1T7I=S3Y zKL9%*I9a4w+4cEByz;&X#!X>yJ@Oz+m#%lUIy6>Qn3^4LxG54@Vf1>AJ2noM{DTU@ zKj<9z2lXNTaT+=EkJ3mfNRFa{4V1*fEV>=_!6;zfqe!rUH*c6b)q4ab4a4OpvB~mR zGNPme8{o5(U;`_hI5itqzmX;Vi2Bo#s(%hW)JtqKx(poRO0a=zxx(xqUtymuyJ81i z9EnZV^tBMv>)eO#1shnIfTvg84!oCf1lm!DtHvR=5SuJ}V-#%=(nncLzf1%PHb57d zb_g{#x3%kz!ZP76k+MN-=vTxr{a^z%yWsYJ8m!xXn^&l6OpZ3#0QCax5Kn>)EG~vS zTmHu}|G~j$pnFm&CD_0l&(l-YGe8>(qdzeu*ucIsU~~f5M+oG?rb4QQB%O?K`8!oY&HJsl>ul*t*f$<8)Fb^Q+7rT%rH{j$VsZ3% zQ$7hcP=5%L9tYz|%QBa3mPl-}l0Um@FqOC=@RpWiD$B$X*bs1I@J^RWy+IfvB(5(* z+8=PUj|&*mR1oF~iOS>!8+f0#L-`uuk3!&{K&|Qp8>mW~4IBsKg0R?)1RHo0HwG^@ z*|ypE6ah?~ttf8HI82w#PH*v3W@&eb$40P$W}{=7q^p8ii`XM5bAAU%vB~DI#D**6 ztv#^L;?3ZQO}2JAZum&nZ{yD>!r5Me4V0!vkYEG-tGP_lUx2xi*nBxjuz~U(8^H#i zdPXrx9|QB0_~v(j6r1dJ>qO)29x$hv^=5FyCVReGqOs2lEQN3`8-D|q@_NwS`T)KX zf~l?qth$HWU;`V!!Zu`tw+7bH!)>sEQbQ7q|F?h*_i!6*z`0dV3z^}s~EL8!cre%4-242B3DK0`gU@sGHs?Y`-c>Qa1D)bjU6xc|?ZLopzuVUsg z9m$^(L~U(KD8UBGT*B!|Y_eU=Hn1bvEw%@b2!3GYzonY)Q0lV(m+h79|dg6(X#{bME zF%sf1*H_R68(7x{Q8j38QXE(r!nrvm*g)0KG0&-o^ybz!(pPM-fqsQ>CwT>6KOv0a z!O8|3*z_bi(>Q>WEkS|}^uQ~99!fp~^o@lzUt!!M`TMk#ILGbz624@kLFWKiXZ=jh z&MW2s0YkU<0M| z;w$Z?s`n2g}qb zKS@cjfxZRe452L%-sASN!3MTqt#F_Z(uYzOJY3MDrUV=4{f(`U* z6XC1}zSGCiOq5^)?SIwkBnVf9#LrdyOf10$mS0AH!VNSh4pSl~@zYd#^MlMNZ|dv{ zi7ItYCj7ZedxEsjjx)u|^WE@Ka0EtL?@NGe=kT!78R@T*{|!_dR({zy1Eaz)B#*O@ z{(*2SzpSqntA0X))(b#b?k8FKWg>P((VH!1<(H?CkldvJ%0cqWktZ>%S@~rSJc|6X zer&ut32tUE^j^yA5&ZJx7xLo}n7;gSXBu9yfzrfhuIbfFQcD|l3(5{>&Y)u@LS{; z`bXp!`bXrK8Hmtb0trvz2%M*qS^1^Yn;}&fsm&~+FEeaEtix6lT>DjUxJi#4(Dj)m#?ox$uG~9gZ#oLmXA0hztnm`t6lK2k35BjQ|Th|%f*5C_6@1m zETZE)cub%IK35FG=>s^}P-pVs@qubp@M02BNrAHyY~`2Zxf4`XA7so$ez}0cJ5*?q zUryk4X&(3(gv4QF`Y<^Z`K8?KfT99U2Q-`D#|Rerg?l8Wi~MqYTMQF_LgHRA5cy@o z1L)P~kp4GeoR`Qip-o}slt)eDU`Q9C%tU@Um=)ju0V^iBUw(NHfl{giYvRL=6Omu8 zo<{+?g3()8Pk6aNei{5nj2aE>eZjekMSjWHO{qn|)(TGc(M5&)lKWk9D zC`x`QhVRl-(6;};ERFoK7!ivI%3J|Z(y(ax<;NT*YP`rVe0CzgjEqOPSXi|tOZpM@ zryNzkUw)y>z#*>4FH;i&?BEl>ExTd|TpW>Ks;!7+`nLPfJ^AI03b^g)-@!YBBk(i| zOq+r35=L`ki2QOr84u>C0sbQd za$)io`K9JJ=z*2+!4D3uDNSCOltzAOu?uTpz^a`NlUqvUm)PATHTHqZxCn3yV(`9+t+oUT98hZ9EUuF0Jzzf?JkQDZ8=MLvQy{maTP?o}9m2gdi7<;gGEV*;iK zzXLl%xM>0_zxgIoEf-%Xs||5LrE`NW}27CNw`Q>DsBRDIOvp}2Y@tftB+4UW=9iYEN!M){|=Fh-!cV=$1IBdjJN!98DBk>H9@Rz z0N(P8$c5#XE{GpsXv)6bsxiwigTBPN$s{1=M4`O19@}RHU=4^LSb$o7(cZu;za*^0 zSnmiBXDmt;uvbQQ`K5a|Y(KjNn7@`$UHKoo{IX?@eh0?M13-!adCM=S^Xjh3sSH{p zL)R9e>)9;7^w^@S!+8p*q4z?X<(Kt;3O%rz1Jnv4twTt+{L<)kcL=r{C|#mzBxRRh z@?4i%)F}e`tNJp_FN^*`G5yVWbXnS6aHwgQUzXrxDAiv-1bT|aFv>2!lqeI@m?uDQ z7=@7vXqR6KynwSX0T^gOYFrh){IcW~M@$0Xm1vL}O{wLVbn}B*6|wwsY9fy3`Qs;q z$_@*NaNWh|G3swfxCI${XWyoXoqd}N53xJ@wiKRZcJ?t+B;CY&wQ^W4nb4*VMiO#Y z3BMSYN9GP-6Q)n@ll%EU+5Dd``wr?Oh832{q|5oTTlcl z_F;2i(kBVX*{}*S;T4E?*{emfKY1VapSNRt$lP83f0H|AO66`1vMG`}x1xCDu1wwk zU%9jF)KV1cgR?XIWDURPZnGSYKlj>NSt`ZbT3G=5In>rlMvCz0k7142p}Fb5unvh} z-C|f7DUz}dMI~^*<@eyV`z=?7-K}?79)hb%%9au9V+4tM5uhwrSrEz2ZahLw>beCA2?PGIG!Gxuus z{Mw98bxYya2&+^XDN?fZfYIgI{^*Pb*wk`hYof@r%l`q+gOynjkpq`=g@sUYKS`hX zN5$hQLs3MRGbB9$)2zGwnGc|D8-Ui@(B%#Czo1T{`83OcJ^^tT5&c0P9t{b0YEc{; zV`*M3O1MYtP@$x^vY=i%#0L}J27@;4P%uZ)qcr>vak`_T9gL)vBrV(;&(c^Iu?iHyx5ofV_D1v|Ly|9$ZdSQ3z~INLqjP5hurL~w z;ooHmqSPyaxCuz?ZP2zFx~_pYoDhchvefW6nW<^^7*T3OuKb;_`a2p&NS{wb4uzlE zB$e+7Pse5*i)pZR6|?fWu7Z{&k}7Wos78W6p|kcDvpHhYbbNpgv17BB_}Y+xSTEc=k1=ZP&`p= zC;f5Is#?0;J>98bK+)TRlxE4w?J=Rqy{yb?(#n|_nREB_Qh;^F@fr%DmPb_jbr(#T zyQj}Kh2fDeV)yhHx#0!&gZl`R+s)kC-P2iy!!OCRAY3*?d4LGJd)gW87oSrfna~6o zz@i?rG|Iuiew>Esi!;=t{vv;lBV$ zg?639;{P>-!g3&r6)ibWGq)u-Y6!>3mdt=i%JdmJsgh5}B)kYf^1onlTXMgcK%r~_ zF$AdkAhp8f#7;s68RKFG#ssRI!x$Ga{XrjYF^th>u2S(c^(0x=9j?5Mf7Vg;!!T4e zh!||S5J@`|QPuQjUqyoU8PJepD%0EDk<86VP%>6ul%(IjA?W>Luxv_7Y95hXN`ANf zv9lH_kKj;g_Lkd#F}>y9J?IOnAfhHNCjmO!-m*{;mPql455cdVJ$C&t%NY%z%fpPqf=<9|Qt=gZt zkc|Y$%8pC1$`z5S?Yk5w)*zx7$Q7a?(W>zy^1}Z%Qb{`bC7UQz>r1)n{Yq<)UtmtI zXj39-TD7Z1Pz|WHhg*B9H9rAa>w(?C#6ONyZPTAHfW3%5YDm$ly)h5;UqQQK=yGqQ zYI1>Je1?d4B=;aLC0#?JRZ}mA`w%;;RgCLFYj=7F5swI8YPe{WvO6R_>m#6`-Zgn^^s+{8U_S^cA7S_^x#a zoH{M-4G!$7dPtCCw(}-Ij@eE>*nEYX&G$4pK7dabbKqMs` zMk1UN6$D7d7gy7&gELSMoDwxfd@?26Yf7ZCwKu{XDWkWMQC7*A-wn1%8S^NEg6<_l zV^`9VQpQ_GMkOVq+aN+Cl~e-AjhX zR({CMM;TyMdDKxdx}QN4rHn3=K|%MDp|MHZs5kO4%*be@WSrgV=3^CQP|&?(Xl&Q) zFlNfwZe+AjGJdWI8(=H-A#^&tj+DA(x zW2ll*3u`J$m$8&VLHClOu?ydI+si^DW0aCnCqH#WdF-JK3c8mJg$=)48F|JqPMz+- z2^nA5SHn0?utie8q0p5Rvicn$ivqm~+3Dv);?!j9i~=bMmva_>q&f@MPRNeoGX=zy z1-+WZsDo?OgiN0gz|_Ol+9D~eO-uvqUTYJr?5ft5!bxUTi;*IHpbRty>)!vux-f!u zgJESPK0a|8sd6;;J9xGC#S6$uIo#2lgS=y5VHPZ%pv)a3K;l6c6jY#`mC@9=b&RuV zyLIfrz7bo;`i&AI4@A_*B_E!G(&~tiw{=WBi!<3ty!Y0zqmSVgJ5Xmuu}l8_FI&f^ z6;2S_EtvY%FHsSZQo25RJuH5l1oV*^caclG_;I%`+H8HqH^t>_V8UkcBeWQW z-4oFR3`u@Ox>@{q=CL^O3Cm7S17LnM$Si(*Qyht{2W_*V>rTEE7i3D!b9$G7zF&Z* zmOa$#^~{7`W)Xf?VbcDlsL;5@GGRJaMIKRIt#80eJWGgMDl^UfAW9xmZD1zpx4>1DYBvUgP(oKI@81Y16%mgM23E};t7ESF5t}faqKip20Kg&BpyY?E52Z`!_>fI3w$^q zT6CBa$W#vrF7);27Z8XqwH}zD_+8$;8&oScvt*t5;~W(XibcNmp9aNp8H`JCLM`h! z;?piTb=wy+TQG^Z3{K+M&TtK8+s4mbkHr$AXy9yxHSRK+Amod!|a34DXE)A2M20AmQO089;o)6?;Q zIu)X+laT!kzIK6=9Xf*E&0xe5rxA9_#x-{m@3Mw6WqTIi(TdCIBtFEo*tn^ikefV? z^T#@jDVBii4P5%{2UP&7#Fe?wzU_E1azTmtN*Xd4(&)JMbd7La6k+$g`d^9_$06Mh zgxt^4&5n@gxY%C&B;MO`{jmry1Ax6w6uac#|Khlw#S5iFESkJJMeDelbqWaP;U$8O zu&V8z*OcWr$^y}ETGB1aJyTVt$wVp~R7Jroi}0Y29FeKfqX{2$!z^ycZAUaJ70B<4 z7r%n{IxgpHDy!TL|LXmvjUG#6jx@e%pkGmB1^oGNY5XbXC)ak0s~O017n@r^s%psE z786j*fyrZ+{QF<3yUv_g(Ziz2t5dYqeH~xDVIIa16oZrEz3Pq~ zb9xY%lWY@$Q5Sa!vhTwXkdiXxqYx3t$@O}fpZ5a4`DSS{h{A+;AN${iH z?x8NNNOX$(Pp^Xbj)sPLaY2L&^=pVlx84lp4I}P3gkFOhy0kj&Oi- zDPq>(a<0Zg_HRnI0+ja$JD^+LYG{!20>XtxUBv+~dl>p>Awr)sbUGub-!ZgvOGx<7 zFm$kPg7E*rP|Nn9-e9QQE^s(KF|aErL!v{TP&gED1RvT7U$wkAX0bz^P&fxx%hYo` zU$q8z;zfssq3|87__$GPPa*2fP&jL08)am5Z2up!Zaw=SvL*)5%_2qVt7c?nIjb2F zWn?`a(2NoJDu(sIbot8i30`T6mUU__-s09#Mpmz%bXFr|P5s3(8XbG5SVoht<2$60 zWul(gZu1q!Ydal=g~FdV(~J;5Iwzt=hQf~&)#4F#doTL$9-(mXk}0ol_45HWFXvDB z;*9i{DgyLWC_KHiDJ}yVP(Idxs%}92Ob&$~zH5tlNDiD)JuVb}<+c%C?dOS!qQitx zIMdTsy2<-X855N(qE1|_B>gXXybSN7NZ`^FuF?qN?OV^n2nV7K;`;8br}z8*O_Aw6UP6&}ydo zc4MvI&AX|-4wy%|HfySH(H6^S)Mon9-JmxlxOPIHro0$6>}Wv>ns?y#=TAHnV14S(pOB^vFQ_Q zcs+epeb(Ey1(WSoU2I!0QOkB4KI=5D;v4gB#TeA;^;TaKHMQY?$ZFTpcmyk}%>tv0 zjXK-&KTyjz7zL~K#(T{joKVhX*j?yWjfvWP$y%C;+CEd8BO0lR>ViH^Gp5dn$8@Kz zztq`yv2`h)+xF$S0}G@a6v$*uyhLhkoQz(kn16cCpx`L2m4R?9ss@=NHSY;X>FSpi zgQC}Kv0|8k@Nv83O{7*HkRTc__IH}%2oBPh7>JsUFh*3tmmNgi$v%HRya@ZPq3dA^ zX6y`vPCu3)vchg9cZTR&X(hhxTk)b%Cx6UNN9^f}#~xs}qeq>|tX%%l zQQl3qdW^sPVAh-|_o+F>p_;s4yTR9jVeOg{a7MIx-z? zZ>Y&y-2$q%heR@pXnT8>612S~sZ7>qolfz$EFDyJx(swxWL|Zu;}=sOVqHz~Uz-w8 zb+y;vylP@dq&C6i0yeU1a6okY1rsUaXd`gJSVFNkRj18nJS0WsQU1}jaMI5}0Ppd5 zDfMV(Wy;$h#YdpwPaX$Ol_LMhpT9%_H2bNNpJHBFj#Foi7~ANTD-x-9w)^M@Q?QNf z3?93WHDdS-UaAN2smC$#17vMuUPbEeVZpvxh+)k zCQ`Fw{)AdOi%$dIz8Wj~8VL7x=?z|~?>-Y?6(r$QiutIe*#@!)E7Ec%-fI!5wXl=} zNU^a}Tm$5N1G$h5QuZr|#F91=+Hwsa#l03Qjv0t@vuf{aY5~l|A?54levu2C18*6K z+SfDk2J5{Bn_WIexAied*G|J&~onBD){d3?(n(#HZ5I^58&4@&(Iuaj27s6!b7chsuy6zGo?Xx87e`yb95 zr&vGwAFLDjAXvBhjA)%Gh(linMah3-#VM09p0_I1p{uDMKcogCtA}8b$%pR~<5wxk zZdK~Owc#~1^{)PNX?{^YAs`AG$PyI4| zD7X|!7E$!pWNj0;ilcaCDrhAPT`zcMXD0X1=Adqh zO=RIqd=w|qPvA%G6B8R%b+bY^ytFo8ynIT_OzXe3MW4W_;WIhC7B^x*nHQ+ z7PcBxn8JP&A0|HusPr-GxHLCIwy=2yv@Prmy%KbCr2wf;2C60*x=&#jZ;Ha`0nA{_ zLERLaE$pKY;wws&GZVMD1X2@S*lbt$<|=r??_;d}#HN%{(HD9*| zXGqq{@gb_E`Oomu6YAysk>NKAIATIW6%J+j9M3!uDKdBYCp0#LUliyPBSTA7z%N5P z5Lhn{KIs#B*Z0KY!NMc(5tMBg5`@Uz{45$l?x&A90?#6Ni2PPLvSz%PSUNXBPBgk^fhu|EHLULw;nxP@NmQU!Lgg25QdEoAkxp7*(J!%LGFar!%qYn{ zxQR@K%7eR2dD@ttw6U`Lvm($fPy}x@(BXVQJfRvtRzCBb2=od(a7&YqN0U?2zQVUd zU-s`SgM(9%q1z-MBDcEHafsArn8pWQ^-JvIWJI=+E=Ht&_bcX4>;2372|;`XLs6$2 z=nSMD{0nENZuU33Da27=IugS`WC|_g;1GBDPuCAB%-DNjRGA#|U#{p^m{k_TJV_RX zNKIwoyb$o?EOJKdB<48Matpm}`Fe=;GdfkqB#6M+K-$uH1-n3~D&f?2WfDbTLSXE( zx(|y-g(x9f(q~Themz8BO5oZ{j^a%HX(x(jMqoR<2PKy__{iEFf*BAEpbLoqVF1d6 z!+A?;1E@0EGk~J|W5g87yUhY~vQQJ(0LbJg%@{!SXY@;XTZt!B1)M_%@ns z4B%@F*k}NENDh))-J%TO7p#dgBKs&8V-4VkvuKTAdfZU70jLZc189;xATj{ci5LbV zQ*aI7fg|vRAdR~h#x;P&I8B+D)fS@+fJI>q;7yD}81XSN4*+Zppgv;#j5Y@F!}T}? z`<+moVb=hDeP16z7ea+7AzG3(fKSRu#c2#+=XIa@U&i3Qj$eeEq+vG`eA7e_|Ceu4 ze#-St3@hKHb^~PYwJ%hzAkO&dbv$$g>*$$#{T#ZWe$RyDBmDnMC|Ujf8mg*(&xP9K zcdYF8)L_x;Yu_%cEmFXb%wr3_qQ{#E|8pM3H>pH?=CL^G2){=#Rp9R|_g7xf|MTHD zc@QE+YN`2gVp8Xy7=37yJzK{+>A> z*{IuA@yz=}Vp8v%8S$|aI}X!r_14!SlLFLox(V2hMdRAX%H5YT@2IEOu^*p|ZN?$;KULE4<;&PtnEUdbs<@W`$%tN1%hWMuqO{!^{ zdWXJxE?xS4cSr@C9TUPjTwlmFl^DC3-6~KZa7hlrNBko%saG zk8#^;(LR3usCqeHAjdSEC=Gu36KKDZt}>_Tm3@IOsR2P-kaAp%NWi7&`g1rwegLU@ zbzk6(qppyG02DDGq3QK}feSbbLo0rodSc@0rhS z{E^ELzt+&CT4uB6(*VnGp7|{PF{F_4DB#D*GLPb{`BYVCV?L!mlL{ooi#P-nmquIj zd2>BB1yS3)pcN!tWzL#Uo^>&zF%pqgK&xly>C7kek1M1*08bl`XFfS^x@ zGoPhcIARINwE%1+havju9BCZIz z)_h9VNYIi}0VqLGgd}4=?eI`pNvaP(t8|i#`Ai+@2v(nb7JwlJq|Jv$5n(=*72fz7 zW@Qr=Cwv2F^R|Ctc)LswZ`H8(H9hR@F;IvJD|GyX+8FAtRAJSfsEzpH4b`=n+!OyV z#gs=ei*VIV*dT@6bo;**gYCEw^Y1Z;L8mislJ11g{;oTn)$VT&e4U1!QhEF)PeY{b zgqlskYc^Aaco!LvYa=_M<{NPcGGpICthx!)3C;LDx)a*4E4mZve=)ifDvFKbs*`d% zq0B4vh{|+A{g5qxF67;GLJN^a(+Q0L(R4!JGT!ZkmPT|!E7=KUsem?*PG}kh@r6xv zLX*L)Iw3VuRGkpD6_rk5%&5G`=O_T%390w?Jugya4m95naYt}DPhhRv^CG*@70O=_ zf636~h!^P>m_2qvXKJJD)XR_Tgxaq0E2PXZ89T{vIn^o7dXeJ_ZM?{~0s#e*HG!;e z(bkI;$ty)&@XH>cJwv+6ob@6F@<>5jkP|?gZRqK|NbP>EkaYmOYe1eC`LmBJ`ozTwiL7n;hDEdcnsmyB@>qY86m8dnS4FHWa zLay~9Z8x}*`T+2JI!VThoZI0_dI^9f=_DC1l5?~atUkFJfR7AFdl4Fi@*<U`DElaqymU9W@u79JF?~zpB!mE zlV`^%q-+Iv2eN!jan^k9<|W#gPuDEiW(1IY5x1!pZOx}#S!B%S$`#O4^5fGh?;1%jxT zWXLlgK9lo0p*sOQmm;VOKz+!<%xe~FK2PA;luCRe051{b$+hP5t%X=_DER z*@7LXO41hqoJc3hn9ut={Wysowf#2$w+%>}4~-(id?+hr>Ph4ni(4aRc#B(Qu)ZwI zz?>@LauOcJe84Pj4etbFX@cnXh9t8ny1Telz8gBDXF(fb=+TQ?-287Bw`yb#Dx7=` z;5W&T1F|GTc5#cZ4cNsko~7Y(rv-*#HFYbX@)T|tEH^`Taf_#L*u||vx#DzknW1Yk zE~T1e=st^E%dss=J_$@S%R$`~n_b)*dJMf8%w;?@J;2|wAFlamth z@6FVmzd)57Y09z-Md*YAn94k-oi7);T;xH3=jIzxPZC2)xIM3KJ)Ri~e zITmuyUpF(fix*MhXsc$1b{o&v)PHw|_8mTess6j2W6Q_&8oKEm>mpnJ^2odC90wtb zrgLlsqUjvpXS~}v)<%xZ46Px;;ki7d0G;C+3UWKgZeUiOqbe-bIZ|6u>ECwl4DI6V z2=As|A@RK1$30+_XCdx)T+Z)!M(=fwD~iD&omm+F;Zihtg#hc_26sT&+0OCgqIiXr zr2&7OEH@OI3*l;prqIT_UBSl+36foLd&;7%cWb;jUfc!090%HD(pBcHcguV?PS6(Q z3ees%^mN|s`KzvweE=LbAkVvH2VDs{2ijFbPv_m%_r!Uxpvgp(V-8$OFUgSS-8w4e zOy~F;mO@nKs{mAwEX=%SvED8F7JRdY8gvJsKS3-n7i4B=ClZueg(jH2Bf_kjY4_1>`$2FX8=vT+RXXy`K3LZHGox74h{AO^)G42x~sw>q2>JJ}c7j02fI49B#wN@;SxX z&asU`8}m7aeMbbz*Km8oqOJLKp5+(cfM4zcZ6E0>bJl!bo9P!y%N)0xl4pAxiQ^#N!_5cQG_dFInVDQC>*#qaO| zZh}SuG=(h8yk@cH(;6=#DGgQv@HRo7T-!Nzc`Q*&+7G~2=_DERxjipYOZo$Vo9QGO z^BME0U$FXQR+vK=m#!YQg^5NHVLr@NO75Om-a+TMV6N9Wem@94ycu}gkbgP-t?3+b zeg?jOfasxyBv&cA+c~bU2G2JGv;~G9-8u60HrqLNYk@shz{wrB9U#Mc$dU}%&XF(1 z+0Jo@$DI}!R4YLoBljKLg2=w+X2^DqJZH*wj_sbuh8{9J3dj>=plXt#`*e=4Z9&sX z1E#;_P(sLNJICx@@r`K8nT*>^0;!4i_v=*WSR4t5kN$?|E9e|QpQk&=VK}j#GsVZ< z-}UbAXZTIdi<|8n$1aN(Q!e9`04B1VvQ6h0j|UC0kS7mN8QyH?_|u6w?<$;5OQdBw$48Mx(>Z1W(R7Y|81HtDCy*o4 zIi5y1yZ~EM*g5W@Ah&bO4QACjs=`v8BefNk-kTB7-YtGXgm+UfNqXL`#)B|A-+Vj? z#pT3suc2MO9Mk~Smk05M3{A!pV7=SBQJrJ0TX=L0q-=^?YqDfgXwx~q9@RNcEgVoF zIU2|b7Hz%T^0)mW8~EjN&{mPIGH1QpmapOjZ9(n??VzEj^KM@bjMqYb0pNlGd7b04 zf8pdC3h}>!0>z~gN$1@P;LKU2S0MmO6GXivL!NhA5Y;*UEfRIQ9RTV@7G_?vSnoEs zU!qQYECAC9^5k0YcB#25X*B>F(n&Jj4bfWCA%u<*6d}oYx1Ixog4HK41907dbmvH; zP~L5OYj%z-l1f>w#cA`YgZ|lDcmNWg3NfqSpWa5{RfB!i#^s!V3-`>Y_&SWOIwJll zLz4@lI>+Tvo#W3vG*Zq6d_GxDQ=IJ_UykY=zdr3(Ah`p`Pc7P-Ps})hg+FNfBWS;n zt}9(fI`g^qeL$6fd#MQ|p{BFpij-u`=heDC!RnKb0Z_((+=Yi|^P#Npr-!-jSSevHp#SS>SPK}P zc~Z}?TE67Na}l1=Q9o4UAn|{R!8ci~7>1P?^-w1~=`Xl4EG3en3E!92##8XoB__f{N58U7H@S9u|H{0Wn#K(c>|0u;t$d>Wg z{bhUnjd9ykU zthXT_o%GYlx9Oxa{p23CsjOOc(#)Vp`D`wl2`uX5GS8ysg`oI+a4*5-keiqAtEm`;w@Jky!`07l72k)7kXoSoQiYfZ;Fje@+0 z=o^M4_b9q+I&CMwwo4vMlwUzbkt^FV>&;3 z+-ZSn@5YOk)OKGA_M;#gIr?rGz_D1Q!M4T1cbUIzrCX?6wo$dZ^z;Ci2H)}fO z>jXrct^qCQ{gSyaMw#1(+n zg>X5E*b-qa>Up#}SsBrF4N2xubl0LTVfH3Ff!5p5qb-VOvRI4qUrJCoISb%LWO#&R zhO9-EVvMn<3LbY_;QHT=cmq&*7`JaNH$&ES!hmNRMKTS2I;09f#l~#FGIth;x zDG|bksG7w7{IzeleWfuj01eax-MBbhKh{tMuyc@jAJq zfSe`+Rg(W~(&&(?UsFAT`m2-3kGGTOCCi?!E%~ zhm&Z(T04nDB^=eSOm~0py1#i!IwE-h{#YlG{hSadiaTN^WXpk+ZTgqidxByuWBIy< zx>+aDuuk-dW%PJ=gyK4h@|E5G#B~yDenlIHXyYVyeyj0j0lx*Z<-dirOouZXSu|@A zQ<1z`iREUHkHXQ5V@KI3GYLRmjT=&!4OQKc9ks0DbCI< zqqoL9u_>THGUpq35`;^m?cB28E+Ky4qrAsKt4g}coSj?F&n3juOsySgJq$hF-15r@ zq!uz7fC&cV%`Jz5u7oTHZJnW~n_Jdi5Yl>m3c%+CQ7_4mH@A%58q>fZ)al*;$cN%r znb$0KZiz!8bmF-Ic$gqhuAN)%YUfI-20(*!lFZz)eiK(xPXGp_lVs+WWrq0m)|hDk zyktOnZfUp1OlS&2^0P=%HseVY`>8DJJg0WPBih~}@E#?9+lHuKO8h1cfmwNq=_O*^%$?(cZ__jUXx-{>0Q)T+Pe z6I~F|4YK9S$hLKAf7J4cQH)(kWq7kr?I@PyA_vVCaLl;+?>ePA4W8OXG)&|mpIDlRH@#j7>S(am@(!qL&7A{No+ltl?ogt+OroX4>L)pK-RaC(?r zf%vx!O_m|RuEB1f1W#z6Fs=z)z5+qC%TB*bNG8o-iH2d-DXzm^ZNqhD)QZ zqpNhv5!Jvi3xHOLbd@>l=!*X62%3eg4q78aPv_`@IBZf0c?y7j2IM)qrKvtGWHM+k z8+tlNSAAKc*6S?*J|KvCNrpT}w@N8zo-qB9FF!yjDx3d=P6GIdM5#7223jU4=I0vu$py0?8+VtYgvEe3q2O>k{CXT|s+_bd@=4 zKJ`GK!_>xsHp9@^HCHJ^!DW3{B-01Qee$(T

X;wfL*g9y_gQ^x7ibbv3y={#x*une{59m=k9HOJ*)q zdt78dtoUgI;d3r7P?W?*%-W~%an@9yCca)m8}*nnSCXmTH_whRcsW0=;O~+|mS4_F zCe~k4=r4kF(96m+Xj9;&^KIt^aADVV3crBqExcxy%7qR1&RAf!-_F`^K(Htaw=_F^ zAt&R)W`sJ*eB_+GTf3ytZS30yYmt?M{vm}Ty3MS;Vl*^MsKjR#`UFXjpOS9tS$4ai zAPQ2g@I-B0R?w@nDC*;GQ!Zz_ zQRq+RlO=A>%VvJ0ZoXL_S+hXy&o%PQBh7GPgNZlEk8k7ftzw9P#L$b!U5 zx8A+bzV%<>IXCf3kOj|*T~;K#GYWqfW_}0Wylu?X@xOP~i#%Dwfn1;0cJD>IiYp{e zZuf|a-_{1-1xBodkZeV0*__xSI}9HYTfqTH%M`j4G7<;*$nP!g-`VLQgMN$t{sQ)- zEVkD~h)fj&E2foN0a9N3yV}r)69WBY2vlD37Ye0#(k9S^?M<+0n^u_Z#5*RPtX~{F zGl|=)Q|Q;{fKHgr(XxwhS=^5^nl;m~&9Ili@^K3y!XxDiU>HS^2W>Bmu<-eEOsQ;R z!xHTU@s=MV#IMOjGN$w(g4$uF0opg4(zKc03bK?{@ zml!QD56XH<2hT0DqoZ)Xx!17#ZqxcctvW;c_;!?7nMOfBGYysKI!H`d|YrO>8 z3Z}j7m+;}4?q{^0sjk;MSNN90zg~-O^EL3T*MkZVU9U6OZSk3LTF83+NLx&Ky+o!v zbGx0*d$8`XS>0}Vi9nxH=ov5cF2;;MQs@gn{MlfQ6y(Il0O3U6RJe~5i8LQsY2W;J zI2YT_o07;HD=!N>s#dt09m%j76!cXLD}om<7@|wBkh|pdceA?iv)bw#!2A-Jo9b|% zNE%2tW7^=EQgDn7mndop!8gJ*?qr@geU%;L??4fSE=W{ucI@|_HdW^lp$ISW>}Jr* z<-ceaAlfK)C*7V#&{4_XnGKJd)i0SC6i&18_4Mb0=<3LNNC3E(jL72H+sw4fPm{tr zjZ9^y#TG5g_U+a7oxWug`Z#@!g%&dKWeReym{8}<3YriDe~-5IF>u+Kk1Evt8oQzj z3fUNGbxm6ZVpZu{JHZ0167xf~!bf3l#GTp8AZd^v(h#F(Y7oD){CjOlLCAC~CGyCe z=auvk)g4}EU!@J4qb%0QXB8e~jU)mLzZn}PDeyepD7l9n6>nT`Up5*cxd;9*GiKI3 zX;xe@6&ERFY*v$50@uqGGD$~qX^Y(xf)dL%*k^qxA<&%)b*pwFoF7xr7(}rR5U%Nn zvOisz-rE)aZ;*ZWUp0-EpYCO+>2E3YRcH*jy?hxK+XZIEHB*JlNx<6~^#=07=jh@= z`D3_8`ZO*$=fEnrL~&iAcop1H6tTBF`es1&6&pwyR{HSsne8pN(apW1HxwBbH#rS#x@$HinV?b|`Pt zRal=3{sHg5g8#<-Qn1YYOGN{_pbdjnhARs8Et}x?oXvK`zlKHKcGcX9NJc9`N`qQ$ z@J%#;o=i6za?o+CDL@+aYNNl#yys!-$VLS#_$vBn5}Wu%NUXrTa?mQ+!);8fJpSAI z_!mIA&Y8upfYJ=f2FTX`L>u_#AZpF>JM0{Oh^@z6l2<@yyTt7;4F=2;FomC%p=Nd^TbHyjM)=kXd`q05v0!YD=J&j$$)bn`z%O z%c^h)x+LmX`mWq+$M!VFw&<#<_ZZjP6iQ?d#`PsO5GldYy1feh72pIy3+CH3NieJZ zC53)?I+QwG(6>E{%5qMj?*k*oC8eq+bEln_h|Mo(gCFD7({cY0R(X)FAv4W-kwn6e zmfP|BlnCi$kwSk3Z&?RTY!mTQ4p$N;^ME$^9jE{hm|vkAvv2@FUoUx=x#cveQn!pj zUL8VgHjo&X31DiU+5p!cOBSxbTaGzSWY5B`g*!Qz%_N!RY4LZIC6XQ>bqV zWP_U&`U|s)X>8M@(?Pli%_`i^>N2yM&GctXydG4C?|Q*xgz-gl(ADlYEAB?X!0LtO z_P4?8QbAV3g~a?V{)oGyGj0bi?v5dHciefFogVgj_kKQF=d>MSD`+pvJ=pMqLgBZh zt8FzP7NcgD$0YMzZG*D)a3aw%BJf}l4C5jo$zrUiwBzyVvb)(bvQ44iM;~oa3=qgW z(<%n?e22COe11rwq0j%0wg`Owyg~z>p9|C~i~N(ecpq494%{nJIUnY&r-hEmEPkfS z&M}}DY4Ne^ws>ir7BZ5>)%GocBN1`>e`p)>THeBrM@OI*qWMK_;U=1QGfMoOg8mw^ zP8m+v8t+!luCW8~;dMQqiPZ}IWo%`6>@hR%qCuQ`J%WzpfD1`~i#B@-^bNrxx7s_K z!g0ux8d6032D3FjnGPsQa5Bh}N)Iq5sHQ!*0-;ayb*S2i*#H?}1Q(1U_v{Lt04=_vUfs8|A5;(@rU{ln`wdIOIU_GVbCs7y;20HN`=24ycqbi#NKP3%i*U7 z6iVjs7RU@+khmeQ8P8>A{~m4hD?q{Z5T>sR3hrg-#}!K9EK3mqYA;XTgR@c=`Mg5c z!#?(`6G$n*zYhlPWew!}3Va3q(q&=mJ`=xiX}z8HpJU)1kon#S>w8DuD=e)JT&I;R z(JyK%-xA3|eo~>|or!}y`&*{!%j7gb%9LrbVC3a#>%&xU`RIBhm zW{mq7p0|-RGK_A8`-X9ViN)I#N_M+dFlw)O2K!VYJJHBg_2b$EmytozR)5QErs$Vq z3GO4$!j+jA!7q~+ZX*90@9M$A$T&^FH|{?MDUMmgU_M?g{3Dz z*M&w(58u}Yr-@Q8j)I#kx=0ZZ9D|nNh^2--`RSMySFr&(=|TkFJ_Xa()m=4rSrNyI z!wU6@!wKYZK$<^={u#KyUASVo521iUsbqXV(FRw@RZw>cr`);SLQq;19-==-$II0OBZwwc^O!JmQ5yZ76H;yN#GH3{Ab4?C=&9|DBQgJx@@3lZy1 zY6H^P=3Y~rqci*t1%(~*zt9GShg{x1{T@58!ne!FE3^Tz8xF{c?Iz;+BKpd=Y3uqAWlJ}f^cIG|Ko^f>E*!#c39#7IE@JA`^iW0 zBzz?J$O;maF{hu^Xxn}YN8=v6aT$pBJ+R+i!mXd9GPXI8Q*l#JTYerZ`MO|SyR{J4 zMEL)vK1?@K%AqKc3c_}BVRH+c>@Z#h8v`j^X=$CTbG1S*VHu~xj7=8?pcHS4B6PkU zTuC!zQG5cfL1^<&g7__ueGOi)yB0>u=wKuG84bRp4ai!E3l7VyrJ#kO#m#msG|>hd z1uZ;kwu1fv16lkdM=X(UHz_o*+q)E6*zG|DQMU_!MEN!}^^j26Zf)?tKptH#3X#_z zRcL{{E{ppSg%^m;()(8x{*Rcj%ik!bgdZz(lmdS8rUc<(^IGg;{S`LWW3!t|c5ol96hGUW%f8SVii z6lkMkFQSd=R-h041brS==(oJ+Bgpvyg@z#K3koklP8ryb7499FD15UH*~w9sooQFi zGHWpu+E%Vm$}llz?s$c?J@yqNW_S*a_vE;UkP)9g5lqKl=S#E&;%VrscsC-^H|KD7 z4&R?)SvT?=p8r`>cHtAytQ$d&dc~(A?|ny`9o2WR^CeehR}V66`GA5xgtek;lP0p$ z68OC=6aKR{_&R2!3C)BG7QN1Pdm7Jf{iK=pl*s84;J!qmzlMW2>shnF?x2vw%?kZ6 zNa7MW^T+tEPy|_pFe~sQ4r`B8z_a>EqCFgqARP1q`Y3VG5}^BByT~%C&nUQ%2a06& zZEf&>F(X*&s-06#6e4!mPKu!OZ9qVRHIKy#dJ->2%vFOU(-BT?Qs@^jUk~vh`S*ZA z{}#~oU~8K-k+cwqM-@(MxsKqtm1PZ#g4O4=#dA328?KrJ1l9<#5Fr9zR`53fj>VpW zZUzDnogS$x7BO4qu)p0-k5bFsbA=NAaVH{0b}Ezvn@#7y26WAX0>Ke2c#J|ww?c5UC*=@pFhA0kUqZ{OE4Yg;D<@-E zcCVcSC6*-pYrUGN%GiF;pm3ywa<1#p6_ic|{8C9CKwPLkytC4N#;H~0?LC3;xQejY)k)T2#;%nzXXN=K^yD@_VP-7RH4t~@m%3~kekSJ zep(dzeLyRrkU3B~KMyIC25=kJS8tq&MDaES7g!~P=zmP%g>eURF21V`p2GeimtvEB zyNvuN3iT>;LU86BwbLrJXsuL`+oB~S-lm{}5zBTyr0^=jry-8yHt$drCdoB1RKfj%1oJ;?C^Us5PyM6X2R#PI~M=nZz< z3}AM1kVDS*D*$xHMsy0`qzB-7;v*ga$AHQcU-ba^3E`B}AF?n1FwV$UJ1zmW_&~0w z-lCw7;;A)=+n7c>?>Dy`Hf3FAnhj1k$VRa-?Tiv+5Q#_1J0{)- zk%qJ^@`{2#2Jn2mt0hJW<;3g?hZ4Dc@p8d(d1T`o?eHk0Dm}6Zrq(1q)MO}VvUt>> z5C~0l6Fz*IUZsnZ+6CQiro;=@>@Guor$S#OrU0G95p8M2f2h!}6B)vUJcD~dp%;Uo z-&E+g2#WVQ&r<5(A1XBPy~|Q|+JWz_RA}IPn-uDMuh>x@Qs`$9KT>X%T;^NsC9!i@ zK2u8DQHmRV_?QkXSc2dya_i6hYj=26$#FZl;7d#Lo=8sXzOP-3_qH5rcMA)8t3nI( zNa1rIRrptdLS-a+TA8VxGoyV$!Rugf&AW^aaw6WZD{v=tZ2&Fy$&z1DAYFzH3qK~) z8n%tE$oRvLKa;WZ8n1)#;+NmqHRTS3aNU2xcJM(=;hwy-B~0aEg*xhjKBuWa!GA#`IcH*tLFl(Etkd4d6K~lvR)M?cAB%o25dp?k9KCiZs^@^d0ZR?5NPx z0WKXJuR>kewiIfubB!yk-c(RSmK*bs@@BlN*fhbHpsi}J78C)dB;wokF)Gu@1-^Ji zs7M)qqb;rDEo}}(+lDMQ!-KaCSz2KHo2Wra%G{~Mu#9qtQ_~H|!oQ(cyin_$qXJoD zYgH~&6|dOKWy<%V{%E45bw@JU)jPyzrZU+=rGmM(;;BSsB2g>olJBmLw?KD=*P}O0 z^U!I;YyDeCNWLRr=MveIiS8m`2x{+9c|O!D9Yk%%dfwlaUFkm5IvhBa>>2DD+_{tM z$R`C0oHBa#R4{h;%H8W32?%Mml5=+!wcQ3AyA$!6T(#p7Ys$4r zr{pRXmLAGD+dCzM>Exr@(92lqdJTwDZ{I)R5L%dQ~K~NaP?_V#fniw{{>6!~v<3 z#faBBs9|d%6OBEdNK|bfWP+YVaZR8XC@ZSf;V+y+#x^Sd3j$3mffw<@=1FY$CQXc` zWD2Ne2un$|(*P2>OnzkUz&iD0dr_LYAC;)~li69+n;On`aShyLUnYYyk?iWjSwm6I9@J!|9ThGa zuXTtd3Z@c=t=gfLz4H*_h52u`W+a`m%Iv0q#MY&9_)Cvsg5Cqltb)p+kop_D! zNI2bjnO6szL+HV|JY;d*^3KZpad;YR4P1b;S$c#o#In{}sZkk^yJ}V9EO})ym+S`d2&<}8?GOzoNdiF<>Cjpp;{lb<;({_VtB=bdwA7-Dwds#CR~CIKF)#4ZUSJols&BugGMf2Xpy&?GGAb?nDi1 zx6t?-Ss#Q*iek|n-HEo=_R3@p|7wR(aE>}LV7KsRPg1iA8~Hc#o3^7ac7F=m4g^Yv zzA4oWVXR;faWIJL_R1WqhQ=Q$(47N2l3^I;`Fx3|B+f7!Rg0Zwfm)cWk zp2JUx>rs2Zk;2-StQpZ!(&cBe4q9{+Gn5z@ckXn{3-!V_xq)!offQIC|Gaz4O8(uE zKIGSx_+4b%ojYAJE-V@=cNeKza?>RYn2#oA;;f8Yj>$r_Gj^5w!mx?-0MB8`8?0(m z{rzc(PG|u!9p&Je_6{VwVe}(`408pj%6U~XHPA)#=K&u`r#i&|*U}S**%6b-Q#~C_ zIGs(fkhmRFI)RReFxDiC(w$xDL3+bYA$4&Vt4cIjBOJzwL!Vbea4dUz`g);+h!wGU z0!oI@Y+E^Lvu&WxLnd0+FqH%y2Wf-NMD-{hf1%yA=Wz3JM$I5CtqwB!kv^dG-WoQ= zE6R{HvS%olKFRwi6yK*l>#_vuFmB^&4R+GnmUBr$sy5nCY-NZfAIQQJ@hXz#lbP%Q ztkHcCzAKYGFg_1LB;dYOIabAZFB$Gz+mm(rLn6`JPF8Go$Hl_}gWcdrsvjbHJPG~P?(hF68hSkLvQc3QVgVIWQ`OnsT`Qt$ ze20}`yR*j!QZRXw1YJ7_8$B%KEbO}$%csTaahZ~_8mC-T;5~&4`=6$l)scEg=M7UO zD_4DmxODR7jMn%LcJCzn2l{e-9ev&G6R1gmb|(p0hH-qzszc@tuS*2<#_hP7(wxvS zJ9C__Xm?!1-DeT&PV~2kao)9Qff6CC$4YXoQO?o)Ky#hfv5h=r37D<;mw*LY81x|v zzGLM%`Tkuk+k47 zNo-Gbc7id(TGMQIG`x!&qKYB!cNsI)km(vg;0X`zDSzxS58CQVIz%|Nmj1=Vj20b< zI@m1ICsQ5b`w>R6Lmi5PmYq~q=r74ksv~7%5lCop3(PDi*J;ZHxd2;XqpjS2JlmNa zfGa}+7IFhAa>T=Ml}mLo3+rwqM@nZ;;Po5|*6~s3^(7?ml2NOI9vSxXBLX zU>qXF{2(j>on#>6CC`gQH%i+=-iTfG#KnXt-nAr_LmGD*DP4LRqg`cPPf|3&+?T{Px=q z#HU1Rl5?c^MEmxJ7BO$IYz&I^0mirIb|f1+VaS1-hFyft*j(OwpKz%@{1ELYz*U`y z*XB8IZ=dD9( z6Y)e7Q9~F0Pry!*u%=MaX7RY+c%4hsiaUilDH`}h&{U#k5GN{)egZwR1sy`ysw6g@ z?FB-RYp^Ial$X{hy zo{B|Tutmf->DdMbX;{W^@WcMK zwnBNuJS&z8V|R*Vo$#i&tYj;*P{(34yb0-U^hd8vt&6lwXo~Z_fB2AFMRT3+a5T&H}&P1Cg zzYa%S=3_+YCnl6u{O~JJhy`>-lhsNvnO|?pt6Z$%Ze5 zwhRr0$}{Z=7y+%hkokkpAoyCxae881iNiPpcLlrJn64p`ibRvI7ERtI9Qj0jNVG2P z-^VL&RF0Xjh<80-0mkK4SHcCnK$|70$X;P>993={PfV>hN=O;Wq&-zV&|XIDIq`EA znBZZ$wM<}GBkowt?d%(Z5CCbHUFbOXuCUU24$~k*1&rGR>76^F5A265N1ntjD>u4X zeM>&RbWP3}Z zX@vb{JH(glL_1garh3Tu(qt8UKL@+34|{cJZpg z69d`aN0JEq$Ye=r!QNor@UkG*wkIFyQQ)kyF(BlBV#Zvfx~P|;1|m8%S+c-+$tbf` zi7pKYXMnNH#yaGc;tX~k0TXZzV95(@$r%=U!uqnxP{^8vx^b&JQ@NByfok&2SJUhp zTe1j&?ikJrB=DVenRKq>M6z!n(T(AH!{1=8>_YrG`Clb8k@yOu8JY&f8U=2t#|VVy zDw1A57=H4H>U-q}H8Oi6{KXrF-MJp#2W_<nI!J!Rg z8KDaU?furl-6_!}z3gxgh-9Y+Ko7?E_KUxZal6(hbXvcc<9ZL#q=NlOPQV4(FL{qc zt|XAjR&FTJ(knrEBu$aX9I`Z^Q|`reiv8Oy1PkU7=Z+V-MPMHQgX>xeTu{UR_8bLP%@1 z^)c|`O<9c~yLY&uKu3xDCzc_LP;SwhJ-p-f+aU1oQP~Gvcn-nFq9|l zfVd6kEScR%M(EH`55IbOGOfH_|~SsmUYpgbR_aWMdB( z?-ScQ)1;+|B_%Q3b_6?<90Cr-YYU8bShIp_8qFi&lL+M~Y#n7nV3j%R>Z?N_4@V`X zJK4>b?C->tuMmZhb-XG((KD#=aKdA)g&@@Kj>w%IWT=7Jog&-V*({Q}s)w{qt|h&> z^R`^r!GZBNh_;&r2k3>#&b~ZhA;T|xruZM3fkVj*EYU?h$&nK&w!{YL+xzjTM=3=p z9jsa$gTMl7yxMEThBqG07Ygem*@>A&ogQC5_d;M^e1PsC*h>L+?r@Vhm;RVOGdsgk zQi|^tAt#{z`Bc8DNyLCqKotIS4EK<&zzq&0i@GrKek^#3_4sC1)~ks_)wJhMb%(QT z=n3%(vKYZgiCaz94pmEnPIp>*w`^w0gceamq4rpqh7!c4HHy}<+Pb#xA>5-NyH$GN zK)Sm>Jpf5KopZ5Vc7nLR-_WhVcoO$Hv$%pnF(FfQz^fzK3FLHJheOChqH;UzBB1qj zqmu7&!zhFZ2X+a4X*>=-vYd{#-ZcQes9x9{33Fut(Uj zT?F2>C7RX6n3Hh!CW`4;ifx=$WU839FNxy!gNWF5NI!b-Pw*) zU<@1%Fp?Bkg(zS)GHdc|U^13Jx*kQ*#{svsoy7;AWo`i-4pa@h+rWg}ZN}Zf$W9t_ z9bL2|N`r2bb%gOp@I_C!YAG&5QDbWX>y5i?Mc2{Ygt6qWs=A_V8$pb!DJmf!r%Xm} z9y`dPN+Q;_P~GA3<<;cq!fPY$xe|Vj8&Nu*X_wI85Jy4`;|^}Q*zAb_GkYLH2X8G1 zMuw>MBdSG-q^`pY(zTV|OilN~l>7n2N1BVV< zHOjAhbtI}Oe*}?2uhyle&7nHbJp|eaVijyY?!5$Fh|f!YwR_~Y9TdQ#ds`3gIkN9S zq9J+D;Y0VfC6Da6$BVGmWa7O6lRs`YtWD0XUJ;wDTI$$i0;HG`m11zV5~PcH7v;uO z{p&>p1mEZiu^I&^ib4K&I1MHEZ31z};#%ir?d)zFhLioZov-=^1LPYRMfQZqH_S~e zHv0V3&>}!I$y`Qp6a9TG)861DCSsp)s}3&aFd0i&-ZWtY4qTT%96z~U^02e_6JlJA zM5q(#Pf0{Ys~m9i=p^jF8L&x>gb?EKc2Xp zc$Kwpo#^X^VmZE$;^^2mEEV?3%m6YrWZJ|k?6SG|983Y%1o9z|Hkg1YoF}4LrRG4% z!F^kT_KZ};Be+MVSDJYCwJHQ@0`2&awm_A0&7e)xeYZl2wx7xm1_#r>PRygTFJW1W~%~+EJ>(##d*81JdbIYrZmH+{g4fb;>LFd>Z)Dv){T3c5GC34GGpTimxWYW4a>W~i6L zUmK@pIPB@JYx;u0DzjUVmNM$D3Lhq$0T$hapL^sh1Lt7#-*gx2D=twft z4~o~&Z}l!5_(G=HcbJ(bJAr)Ao2sc{=ICO{ul zgJ)x{H)>`wda7g^3$&K-l{Jl`fdP~63qpbK1D?a7->vS|8m6(h^U1U=|FEIF5_+2c%U2`7O+~q9OQ>ej$|7ASZ#A+ONgr}L%3muMH<3s=cNl> zCJJ=O=kY0OK#1os@zb{4fM8&L6X>o9CnVUpllsJ0N;iv-M(ne_2QtCd>TXr8K9GhO z(;0;F9Ax=grVz;hp>nQM^wUCd_^K%Dih5PF{ho=ONgp*mp2!DT!X{g2<0T3lpy~u@ zvu;Jl3O$-SxKa~3>?LnL`LpzgL;{fzuo*db%)+Fkae}wmC)sf#4bP8FoyQ?oMZJAK zzl#uO-wHfTSFDlJ2bzZDIW8D%+>^Z#nlo+=_q4XBJ2X!$>|CCB6wyh33YaJnGw;wE zfhCR^jlKOEi9-a-r3m>9Xv#FEWNv`b#~pc{?M2Kg{D;UtgUn~WhOT8o#Hw^Fgh%vuzszeOf-SgwYT zF#E(kKbwWib)P83PNlFhYT$=ot~lkm8?k%gn};-o?t8y&5`7r#cHTj5=RpooA|_jj zbjUeG!*Ixw%lS-;<+YY-s?;FH>Q9bfm@o^wys75jA<&=!t73P`S$CyeB4Bz+uAv~{@m2)+5EA<4f20W4wjmfze{;JEg^ z+cp`;On%3$=!P>R-G)S16=nq16XrPYkv|%ejL0uHL}W4~lEHmeSwRbnq~t@mIsg`c ztS@joSb1y;GBE5IlvNUY2nM58=ioc|&iE&#kah5JoISy09aq}ZT)Uaosakf1q@wpgKF`)P)T4c2zxYC&&b zydsCh@8S_AQLHL?UnMG3a6-)_OsYU~63{wrvg$@$y{SRqd$zB!r8}O$|5xaLqy{Cb z#J!51_8o5Ai)e<%*8MF=W7?2Bv={kI_qC|173jr)D&tFIETmS?sak(0j>S+Y!C?w7 zE)Zb_xdN(sG8KzX@meYna<`8zeR+9w_)W(t$yns;NYJHTxRi;Sa*&=BfDo@R(v_s$ zLEMGHl{Ki7&z z&>)24j%PBJk?TbqZ~Wnu7B)k16iOX@yfakb2$cyq#FhN+s9%EcTttV15K=+`I3OM7 z;>C7wP4ss0WAO4eSB5cwK(gp*ZwF!@-8AsAD zyJiyzX&*r(DHhjzB=w$TQKA)8WPh?f@w(*xmP7X!aoSnn_jp%gsk#l*btg;4r1DkB zF)h4a#>*VOdg1#`Y6XV?$Yl#KGBNAaO0=`Jsp9kkj)f+?m$!3$4!rhZ)=dlL?a7nI zK$}r03Sa+_ITB?+Ji26!cPR{ciDEJmC+3e_n20FBKhEoX3Vb)YWz{zs5^{0_frO5> zOvKd@RmV}4r-CIOiGfgnU2j2&EG!}xrke^he+n6e-0q6Q3Ao)k{I}H|60CrQ3j|aQXW7XRDr~^It0D-=9pE5*TIgg<&_E^nqLda$4Gg4C z?S~-;={{+dLb?egiy+<<)nyZ#lBZE}>kUfD0u0E9q7VsTWU_Zxr*z`{sZ?zqKNrFG z8EgU>v+ShJE%>_!OgBG0(0L}nO zmh-1^!Ql_Ezh^by8^!hoESvQV^Zb~|0{?Cv8N9L3mnzFt`vwqNeQ$p!bj`+23DMyY z^T9zFNZ~~uMyWQNg)n^E10^9WC@F}w)(43tDzv#VEkS=}g8HCz>y}wT zin>nFSR)+Qc|5I?z%jX`gMX2ZCp`O+JID}tLpo#QVMU<-jJg4dLl}D;;mlrjwed(Y zA+ZaG;H#6B2qWY{@usvTSG_MtQVS#@Fu_TJwHY;3>CP-dG3n~6-0#5Q z8^HBdqyv`x0C@%3Mqay($e>MbvJyz&CK$iSfdlSK##CQ9FGNYG7o@t7vdgTE7v*|z zGCQU4L0(tYY)CX%h$CbfZoF)RTUKUL-GgcSp+Vucj@2pB zXRQfcYg_Ser!23?ZL&+8Y5S8_4wZQiVNAgjYGXdtYk}mTyL)Me6=Gw)IR1v$;#**!^at4&=FM< zbWHhSp~=A~!7iw?mv(9%4lu4qydcKz&;;UMF?;0zzVxAiRLx4zF4{(Da09y_jHwC* z2da`grjG_`S5UXy5G>3FPu7|WGnnB%6@a2IQHE+ zhUK~*t_j7JtXFeI#q0GzwkC4vI>syJ?%KyBSOXZpH;fQ`gdHbEeaI9=DJkiqUiW%J zBi&&aU0^jtF6okvV)HR`#0v+{JLYrJ{0hQhR0H7fpn{8nvTt@*^fD5(1m9CZIx%n4 zX58B=90XrHC!LulPYb37ZpyLnm&OI0oAW zF`}@0BOD@>P@~{DLWaKzjFYWD1baj2-;VyF!4qPI;wrfTlA&7#pQuqjQ7gD6gvo^= z0da@U4oziygO?cLgnJQA7#7S(_l`I@AUidE#61v)r`37@jo^+*(&(&^S#+NRbmFza+9T`0r}q?{N$)pHyb3dwj)lW?D25{B}c ztT)NXBuzWG;+B+^g2krLHU>X}yu4tbDTov9R1w@xgk(y>hCE zpV;>0(+uF#Qph)A?@dw)#)^FElT>3T zVHr9@kZ_;%S3Szt7iq$F*=(+9U*>2Eqz)`Q)X@z~x)YA-JL{=LsG~MjP+y8qv-|3> zNKSg^((U`=tTa}%awT$>yq35{{z zq7GD8K)@-!F62zX8tpA>0g`eZ%K>zbMt0q&yVJP+|s^}n}2c}W$ z*wCP{m^aVRJmCN(va<~I^--8J5oD>bkmm8YB-cQW(}9f&;b);DcLEpo5Dlx>H|nXr z&`LOF?dj%V%li11m2q+0z=I10F-R9LQE70HeDzF+VHa^@of;%PBG&k}Q>O#67zh@1c9!UD-n2m_vsr-_Z?8ngs^t!@yzm z9~@9kE&{rpIfT2j@FF7>vh0=hT}=g9GEUVrH33d4LXdCV$&+60ScAF>T8V+eiMAtO z8r6@&A+VLqfRc4mA;OdU2^UV?Y6{jOuo~zN&T1*)K$=22Z{~9E)=#zX&l8a9J95?z z>~eP(*1yE^_`?NNOpyy+>XG-=Cz7IRCy)<^q#dzudA7l`3wXEA1M!}?`q5-u*SujG2%>VF z!J0BhGFxz??^F)8WAd1cQOciiS57rpW(Wfs&zTia`xZWXi!atEjBAy|c~adYsZ)cJ zwi~%T#W+D|?RP7=)w9ZEOTN-w0=T-bI>0tf8w^aLbb*K4ARW-n;C7p#Q+-zOjFE_d zoPdW=?#_$RA@@|c=qh0>(h52S3&7t<35F8#C^0yxLB-v1fShU-!deT$Rt7zV0Yy>? zS@uxA4-XLvdh$x9y2UVt%~P}tnF}*x|6KA0LbvhtCVM4t@zYzkk@j3K1$JkVbYQUY zq+|EN)Hr3nJs!@itVHQy$Ky&RHOP^R61)(_p!8&|vp+8s22z^|##LdD4^gE=*<+ug z*B!3tbr;sQ<1TcPT0C~V5KELHl4n3dP$UKcdsIqnpa*F-5Nv}2d7RgeQ(b_d+@t_z zn>Lla9CSy@VZQ;o0V*a*RVylpLeb}5aw-@<@j#%E@@0}rqPi8yjdVT4?$D^E32Zzh z+$IB3$ZH}AYHD(Qln~&CH3JTFxS-VU_#{faj`D~s4iF>z`$U3O$Ovmab3=Lr%Z8~5Pa8_bSYD1vSsI<^zG&{@rbk_%|UAQ@YD%47bt+l#Oph8tvBh zMp)yLdq{U-#f@a*;MGPHY)D9X`=R8aBgw;%!$pb_dxmmzh|>vjPhlA$VcSFp`6GXw zTY0MGISLt$IR;o5E(FV$?mGwyZjiBTd;(=Sks}e8se1Z)8*ku9O*+314ZP6z$SJx* z%)C?fyn)zaW}#67tZm2Rp1j>w&~+;aKJwG!xzcVEo=qe$#0GwhN7zC`VJC2Qe3@yh zCsFAUPJjAO5RoqD<|`E1YneCM6M$%H&OXV!X@bcKkqZIGM08oW3L!a#P@6hEK+)Ke zMmtDas;bahS>BZL$sXKYrW7|>n|u%x2tlh6OwDtXeT1wmxCQD-C?hZ5E`sl%HFH+R zyE-~FU_yf9aNTOKk!oYIifZk7hwnQLyELE4jxSPi*iiM_WOHFU`XTrgB)wKjp&3y7g$Yk9na z&SuvDa+h{AS}4+diWGxjHt|yCRIXr_egn=LL@tOWo$gVGS_S$<-xsTZ4aCe>n9@+p zj-de#K+Z$JyIh5-Y&j?Kr+cL1-HuU!?+z20#(gfNlq)I-0~U6ug16UO6Mzt##U)9* z_?pTxH9|=9`g4Kh5taP>6__oxv(XcomuHs~Ia?D{tBAP`WV=q} z=q_U}?!1FVe~#{9=H??rVH?cUim{d4~&gDdr2UspSdVv2K>Xm}` z6icw%XUk-&3rz_j1jwI{EhowV^<_KooZEdf-1_m;bX}20&_p97F#Rb&6_|C7eVZj}Q|4%)^x6 zjI+SeoPACbkg9^1Q@b=yylL3Axf{@DCvPHhR>XHT@Ves5b(51R_ji$<0BI(~Wa)8% zk$p)d8ta$D1%36Vxl9hBQbwpsfEIe7sG-5$hy^9Pasv+4ai!1(p(bh@w~+}dGQ0ihm{;Mo$t)S&pnp?ft!Av~%h&+R(4bQi z;jHUR65mRU&*V=G`?EVz{i%*D9JW%o7bhn`EJvzIcpt?bP#}UPlU=<-G+JU=zDcr6 zObhFXr_k*sbD~tlf2Tp2g}o4;x7V0L*JZN7xV~ZCbi)#Nn4jTI?qAo6^gBH?z8i1E z`vTQ`7=Xl_d;<9(2O6BaM^jb_vd-B7jdkl_pt%#cSfCe3xstu0ztKnY&<95 z7l>aNX|Dzyc6#{imXj~}2&=)wlTv_9f$PA=DaBS{2>}tH1Wr_!uQ!`R?Xc{dZ896k zeU#jWLc%DyO$Dm}o|y*Jc$g@SE2tH(q4bXKf!Z2g$K6liLN;2@MuGH3+F_OC!a-em z&Mt4w2YPHKciA+52gDi)CmubCOMinN<xGyBwVVjp&NK$BJ5>UMR8j04Zbs7$ zDLZ^B@s!M+fRsCu&7Gk8aV!pjpY5;>vzf-Dy}7{wo;7q$lF!qFnVej5f-@8GfmY}n zwh7(ZjwFj5o@--Yg`+sX%GcNO4o*u71X)y?CRqk{J2nI`J*_JFzWLdYZ%Y$zd z337merJ=W|MH_P(}-x3l{Vu-L4 zM1vema=`=`Fz9d*HN6gL3S2RVSP>5g6(pl|qQBcI9Cnj#=HzpEK&IirVq-AgyxSl! z3F?HdC_4GiJ1uuW*MSk-lnAnF`yg%%bs!;jFIi?Jj|Bem)EGq(Oi^itM@?CpKl7yNtRx^Abt8)H{xWz>)T9k|EwWEWAgALseJ5 zXp5gHrO81QcSIF=nC4T^;I2~_Q2DPCq=1|n-dGi=W_izdBaU*Ij2}MRkQs_(;RMkJ zWrl+^@6{V9*(ILS(&}WF4pZ5=<_2eOPoK=CVbGLvthklsx&-yGV-D;Tz*4c z5AOPsJv3iUGf{-fQk~#4sSZ@AqN2Phm@)_9O#(|5a-7F0npXZe-`K4q%3OeZ>e(Ko z&<}~p;mR@jx>qt9$ZzV*A?XSx*cAp+dvT?R409Q~_?(sk9S2LsPkKWcg*zi0)U zH9YPUr+N|loPi5+jnI0aDSqfRTudq|)t%13BZAR8+XW*5?tPHZDX*RafuRi19Q2M1 zUDOE>+v$F4*_m~>z#}qbh4c^;GG?oX)#}M)ArHP560lK7rBp*AP-mK~EV$4y=v*cA z?uT?$`!zV+=tQDa2!}ubu#ST5bE6n)G~J(E#)dQU$bVm!)ts}a|85qDv44TPN0J=he5~rdDLQd)~ zrtnUgw%1whQOWWKwLCQ;T9C)S8{#ciH&B^EFgvK+slUj%J|US`wyezGTlUH$-gX7G z(!F4-)D$}5WU+LeD0#Ovrg!rWvtCZtY1unbZV^6+EC$$^69IPbo+;*?5ePf7N5J1j>EL2gJ?=5It0W6>RO{xm>43MF3{5!9S{OQ+MPu9Me zX6z@l0jY6J!Rdh{CB_c4c}1bMUlO1J z>oKqZ7wkTE!8Rm|^0Y936SG#eyQuBRfy0SC4avjzw;bBnoNPOs*q=C@y#H|H5qz|^ z!Enwh7%Lh%UpJB&NY_Y_+Uli<)DwBnWpD7I6BvarIlQYa2ndYxUA;)ciT4~I%H+lL z30TT~ZidOb`LVjN+T=2f4{2nP6z4#nqJGyh$9JCQbxEXdsD+%6p|&UgM=H) zG4`s59f|D}jgp20bhz23)yi|e39N`!amauJHknUy2pRk}cEb2Cv5a%!4PnKIV6pS} zhFXU#tS9b)SP>k?;})g-f84!WcN^ESEzF;y?nA+QVz>DkK2B7hvg_M8!lwn!4HVqEm&aZzp zt{mP!gqZge#$0svN|P_}sh{rh#b}^*wBV`lzZ=ZI=Q!#kzg-Lig*R=|z>mUWlF4-t zn+nI}TUOSn!t4uav26fM?UQ>s{mS!}#G$a{n>cGPT!UELQm#}MlE@+HF+Kb-d zXnX}37C{v3p^D6ib)U6;>f#AVAk;8MyLEuFjQ@3)XE=X5#CEcGFaG-eL-q?QRsHv8 zi0YSP)UKuk&^OSSDlsww?8W(=pk{6FQUoKiz(;Okq5#ZwCZ{$t4_B$;LiSD?w%Z_8 z>vW-Cih05St8dUR=d7UEz?BU9klLO?9#f77P^8GY3P-jBdMtt=)LPUzFZHjODOZ^I zC&I)hmPx;=e_ych`x)AU*TI~xo#oqJFxS|p$*ENN^}sH~NIubXR23hlMGLCMGA>h> zSjL^{IjR%uW0^|<{N7)RyzJfZ8WW^Z7XZvS!WcN>jg0QN3zxUU3F+0Bj~otH{z_i? z$|dh`@G2=2SL;RVk95)BS7pP0tKXJ3urdDED(=UvK%nIVJ~-Xs^?Y_S>+G_74dw{! zB>I@W?3b=DDI&5Pei4Ub^r}Aen#y&fUHcEtJlGu~N36LD?9gwGZWUd!ziI)rJkx_G zQb#Zj0eKx_vCwiV`?4iFV z%BVs`JYel4>%X1skrrQw!J$<*=_G&t` z`alO9pSxF3znfCY-lzP(_+5ziMs8V(`6v7a2?;cM(NmnJAx$g#-u&*w`d{>pRg|nw zuejD^Ch7_}&4|scCI~^H2hVHu`fGfSbu2Q=no{nX=Bv0>fJ1nNm^3P*3{w%#CwEt- zYG=pkiMEnR{{d$xd5f01nP|2=;9+yK#9;Tf=hyYM8^JW%$^C(ITDjKYQzRF(X_=Zs z9i;BzN){~=QUo2!k463PK66Y&CJ&an)qG~Hdp;c8-g3S(J_4iWjUwWAy>lXhAsGZe zma`#-W=t1Xi-RPYS*uFd`S1$>yc?&61rd(h32J*o2qwBv?YDMiwwpHE!PvlPitB1x zhaHY{zDZ&73XsgO1blmJMQ3#c{IqpBt5Az!Zv64UUa*c@u;ad!E{s48JIJ8MU$ysM zJV>Iy8Mi+)sdmUD<5AcZ3)l~(-a~C*Ts>!MlX^(WJC#a46lx>3<(!%YbaY8f2RU2T zA#Ca<9200WFb{Xk3e`^daT7cx5r|M2DP``o<;*Qje4O802cqY6wWfQE4Eo|2-ewc=$i`YfpXE#(Rly zqrTe|Ws~M%x%C>@agSNo6o@Tl}Y4imDeBcIE+}&t%8~_EjED27iG{&{X1$?^ z1*~S}YU5J9L4md^RyfiQnbs>5PpA0ylukix`QS^B$N?=kv~dLsSKQfs0bJwihV|#d z_9Yzo0*-v4SE`9hFPbV~Ns%mJjPr5^F%GrPwo;qXT)GEvRjLmv3IIBNggqwbj*jneVPayJe(2>=xV+9@V?E}H+N)lVx0>o8$im> z*6UhOeUzRO+MwizG>omo8;w(7`xV)Q+LP^3+bMG{rByKkajcCtOO&P+l?qbHG7GSg z$ZP=zNYKrSo{{?Zt+i5HkmKdq7GgQHgV6N`kkgsDgh55sDp2m0f?H$=BC=6XWh?VG ziK7Xgq60BShls?jx572d>Dz5H;v{6&*vIGwf#)%#B zZ$Z^dW@xmFK;kRo1qiE2s;73Xe9|7k3|!8rX^(bH%$R^F{Jhg&yc{d8EQ&Xuth;0< z`|)Aaho+$R&?T`E?0fBGve)D4IgqsHz0=k~`twM@M$bY~;!}}<5N3;badsS_dpVda z^720%mv;pT>RViT;|#g1MCHG_yNg@Ji$QM_Su-}jH>rr7VWA>I0lrWn6u{@-v&L7V zWq*Q6K1W|E#5yr0t3>LS5TA!TJfvYew01*tmb0=m{F#hh_@sA&RtrQmXM;2I6=st+ z^P$RK17HOju<#&cq5LcqL9S3@(&PNw@2Vw=S_8l{W|oWquLEnt(LJ(;IZ6*33&a&V zlk6Co5U3Wg8f;8{9Et|?s6cAizJgNQr;KAquy3F4Zczf_Z{t)hxgzFrbtI(TBE*r9 z-GqqAM~E=w&SW~%R7PDl_ZMB6-WG8917nNTIGFRPPPdK#8LFf zwNf$;IYp3Ddf6d7BUdtv0>lVikHb73njSK0? z1$Ef=GBBbINe(d84yo#{kx2lZ3ZHq9vfo8o&_w~)WZuwO0TPBNFI?sGK4u}aR|T_> zH)HM;{MBrpODyRIx$N>` zbYPdlB#5wZMe8!r+RTjbgI4=h3lAqnE9E>AMM|pkqY>b_O+{4i22*exUq0u7)w(Gb zvMS*4Tq@;EAmGjBIbI6?dgdD;zJK=Tkihr07?buN-DEf&TS%YpfoznR(@xxDi>1BB zLsSFdS)6xYTiimMH3=u$wEKE2nK}2R6zzB7VV0dPTpu5Pl*Qq*(EVTD`_+xAdRDPj_DY#{_1>G1&Z8=VunZxbR|p?HHlcGnXMra zUG^?}T`m}kinjx_-hjJAoe!vcIPQkTM1>>kM4aFU|BIf$K}qNK{<_g97uQYf^bzc9 zxy{mIF(t;viQs`V;g+rRR`?JAN6rS0}fyV+LXC!nE$yBf*DvYc_H;Vzy%6&?1Ip8o6KLCf4T-qL|kDAQ&pZ_Dk zCK-3jGCgH{eZ6 za>hWmgGd#~w$!nt@kyf8P6rX{k9j_l`I~F?ywN{gzA`vn)jm)J;^xIo2{Hm}MX`0! z*%fIA`GZ=L;4*IT$@d^_hqIg!LET}rr-=Vnb85{n#ITU@SP&RzA2@BPlPQr=aC4eX zyFi;^tO?2rBIPxiWJp1*#AgMUNqqm`ZUJ@Wqn9&i?>QD&oH1Nmg$Pk@?;5{6DiHDQ zY@=#IH-u{x!f=RjXe^WagKrizRWE_9Toekd@Mg-JGdG^7dI7&8Uqi(w3B5oIaIxI$ zT0cr_A{;>jOA8ZmD!x>TQ|lg0qHIJ#VQ6W~5HP#+h{-n>2P|5q+H|%qT-uh0H+nO~ z-uybdXm|%UZ8;y`Lu7bD(AK9HBGBpHrvm;>;Pgqv)2=1zgjt-uLfGy*=fAXETobXl zDnI*}wj2dF&VLg`DrA(i$$kEId@&!)AJ5^?^*+=d3S04THeC44a&m-H71*Pu$3;C- zjo7V}BqsUSF~noAqsShiJqNq8qmx!W%#5JoasYKM^)lFbH|mwGVq*-fYRvn0yIRBn zZQdw^`WnaQ%#PQ~!9}HDCudW9mEnLy`i|SS#$zSVtv9+TIx!(;;i5Mkd+E^_czWgA zD803A5SH?jS=kC{90{}a$hH`1T@UTYQ+K6t5?SmDt)@Q~W%y`CTA8ADFpL#~M>4I1 z!F8%v1Zd;da|4)4lZH{!4N5N9EDlA*5_Qn%E2y8J=OVS!uoJ?+5dbD1N;JN@Ee|?? zg4s-<3qvraiYXXBkxxytiegHl*e`G|l;ahUr9;bDW73xSx6|Dois0+KoQhHDd_UY7 zeE)&Z@Ck5bOMD4|^4%iG$PzOAc6U0v|Mw2|XMO`_#ExV^&rSM^^NpPPSmI07QAiC! z)ra~`sf|+5)8S{S$KiEY9xV#{tHWwD{vdQ0j6<7TP;>!V@h_mVjBh?mYodL#p4rn= zXS?M)v5((!9lXoWKHg^e#VotdC$}huQDz#~Fu}>!JgQ4f-c1a4kgh(p@id2s=uM+r zy=UvtZoL@s97sLbgQ{+;#Rq9;?{ptf;`?znM_=67+Mv3B$5DNKCyJFO>gIx!R>g^_ z3t}91k&=Z$m8NeVs5*}oSIUI~N^nTMl! zF5Suq*o7R0KA6eiF^BLbqKCzDiZQY-DvIc?%X)s(k_Mxc#P}?&X4U*!dcW-sU6J{? z1rF0I1e0}Wenb%hrQsxTBc+<)4sUl(U-7n zMf|A0aT{$Oi>RAycI)c;!Q6Gp57~f5<(g5BIGq(tyWq0LrLK*G#U#&VW{1TM1Xe1b zth~PmEEUuOriC#nq7~xMO{F{vM?$__Eg$ncB+dXBBl0YkWVpk(z1XR7I4ZEs9bgFP zixOE$Pw+zBxNgd(bT|g`cOo;a5_`B!B~tl=r(At__<*id+_=hxTca9jF}}#BD_sVM ze>UelXSeN~!kZ~oUgyMfOZ9g(11W>B^`rnWvDpsBT;WXo{edlUS1};rOIC|Y{NPe8 zgMP1G&6>aeN5?PaknvI7aGnBp^zsfC2%p{|l`Eq>oh@LBKVvbZU zm;DH_(-lISZGs}`;j==iqt@k?dKZ??!_Npu$4v2)+q=az@+a^Tta~ZAT9JO%sz$3& zdOnfRf3A<8K4XGHIetP6;wcbuyrE_ualH%-Lfj^upf?iLJ&$NR6>3oQ_b~qT^cP=? z+a>~$2DB@zu$n%DBDOBJx|ysdAf0S9gPXMqMq^3vyj}{ z*_UZg`RJ9#%O`gN`D5Z+Z#0qs4GeA!cZ#_EnxgY+{oa5Kta?I>Y5_^6wijoB=FHL2zR`-`eImOiW}F4Oki@8nTu1O#xkmx@QxB!JEEVcHrt~2a$m={kK@w=%$#rV zY|1~zQz5g$szL0I86T$S>P*}pbQ!gFy!AY1%O8kW@P(Mc2}4?!KggNvbcnM7Q)B+lk!3)2cB7oeg+AHwou0ARb>`33T*fI<;L<)wC( zl`)Q5!G`lJmgRvKH~B*WqY&+#2&h|H`Zj^B!8t^u8rw1o6Rb5Z0T@+K#%%-Z8SV{Oe%2)D)sV9$!&ra)X76X>%=t9pvvHNf1&L zCA%Nz4~$e(Q`QzR{Xqh1bD3O=tG5Tf>Ia%Ai6SiAI!CNU{r-}nhsk(`Uvpu=MvAG1 z)*&J-vemMomuh5UBoBCp_-`^?W%*KfCOyQx5K+TPzJ#QU5_DT_qlq?=X^sw_3jk)D zcStB)rzh62$&VMe;~S>>hj;Q1J=BC&Q@fiwXMu{5Y)v$gYgh4S7EF$&NQ!~|ygU#x zp#?myI)Pv5Ep<^}CBFv>wjVeot=Kw(ME#Ggbjc4rkG@lq-lQlw}F29;%E~xlA%s}o#ZxL9I>Mf2Zll%&QdGQDbyZ{KF-wbo-g^f?W zvIr*N0Di}hn0bxlia%Nhq=)fx-S>1lh}>@w!;@t0uW8L*)#Cc$@LsdVfs9a3JPKQ= zU8z--PZ_nM5C1~OPhaRSN2?J~oa7jGe6aTDAqJqOU?|Wu$iPNg%x9>BOBk@8EED=P zfj-IFd8HS1(SNLv75}xEv6|?{;JnLNB;Cng%-tYZ;U#SDj5e82M5}WK1hLZvq$n^f z*QVS|1#D3!7>drX5+Z}>I?>uN>Wz@@Anrt?m>0D53%ADkw#hb7kO@K=?1AzvLf{@p zu|g-eBbLOWXrc=`U7))vbh>HL38tnxV#8MyBUdwZENf|3`swaDOUa_swG8k@xDP$x z-iKeVKU`n4*i_;+^a`<5cNf-Y*Bsu4mBnFjLaV_UNG)#rkxe*flbxY>?wy-_`7oP* z0q*?}HwZ+)Xd=k8NTbb>V!2MrM|kH~7B6a~5-5i-d2TTigQ15SuDaBgpbo zgEm*64Mg`GouGEj^)Hv0LNGm}omW4<_`pWQPcMGTetvQGTIXst&u};9n!N7diS9&o zTKOhd7Kz(v>NRRW-`=PfGEwh9GZ_ZgbV)kY$< zzR`sgH@Ml<9XfYYAaNNl2N)?!Q6=p23f7wN$zj zQ1ga|$*LZ!@5-SfV!hS3CEz@YVcuS{k`C#cmi^ewu4z;qzr*d_Hbi%E?$424;p|hu zdwMD3aNew{0Co<6=KM67T?{5a&XG3sUl*A^@!6fj$!L6UX;CG#$>Hw-cuCBf&wDJl ztCFIOie)*>!$&DNS^BhMuBp*dapioofHf={oyVyq$vHH3>gj3fCs7G*iaQHp1h6Sx zb4oBzUB0>cVA2>_`ihLfOo;WX6o#>lx2idty^**LU5{ekNVa&Kg30n_=T}V?+{tT< z8g=#@IUU2!FD1;wzrAgGTTa^digey*ZrxK)o@Wq-G{{T5F*p9{A-#>~u7B-%;)*Krz5kDg9 zA$IAXxqvo>i&s{gDHps-)f?BDWErDP5+X8RwvsZL+kuqQX<}#B#c?skt$Q$)gxe=0 zp#7S9J#2^yLV&Duw)>qUlqF>Nv4kGG5V7Q;{$adUEG&vqYA>lIzv8$iKvq0+JXlw zQS@zcgS-p8hdr=}Dvw%f&Wa-!rA^uu)TJDo#=kwC|qO~%7Vbc4zrf4~_75H-m; zRYsXYY|hgS-`>kKMihf$f>h|@@sv2MrBZPv7k8+y=j+>MMYkeh%GE6dz@%ivSP2xK zVQ&|RoU;2hxVYhndIS{>NUX1Io$;#?~(Ba)tMS zj;{x*6V-0W47{kRb_;y#j&K6QDyME+Zg+3oAW0v3qHwisBh>+jEgH0TsLfNLPGj2!7Q$Nr~u8 z7D>rm@bb&q6!(@M<@w?oH3>Gv{y^y<{8QSvX&QFLOq&PXWhn;u+c)PhI&Gvkl)EiD({9EMw|Wju6YcDlsT-1=i!2uR2im`>H& zyFmneBeLU=#gKX+F+jv^bbNOFws*|ZadGA3)f3#`!yDJgp3)T2ZVOaYDsL9^mEfIi zkIQ$d7S8Shh>-nd2@9dpZq{|=mGUG^cQRe(#s;AsWKbH*z6rx2A%b_unEWC0MG!nC zLWTtmfHw7t4IgVb=`IsR0Tl3=7pt zZSfthT5N@Q8Oo+g1;}x{@!jiN;#n+s-T%;g^{M|$FMILfr;numF0RpV_l1DLJg5$;KmMkL7$leF7(%1Wv3caVF815+foF{ z=QI^{8UzxT$K%ur`(g)q!BEcSOr@{g@3?*^fYqpMK1TC`(m*uoh54DNTot)U*4NE=HFk9RR|4=p8b| zrMcy`xEt3v3C_US&X?!|9-*6+M82Ku14MIY(-#uE_JaW%ysi-e0GP=E=~Qk|++>DI zJ0Enbn84GFchsw1dNSUKARsR(_Nz2M^$MF&uyah9F~f&t zFXC3jsuhJ|;3`KbgJ|piD-p}lWCPBfWv~iTi3lM5OI&`e)1_xp2@-w6H221tJ^VeHHl! zB=c0P1}ion{ldnp*ZIZW6{tgDYm3Akh4)GUgKL->wQ#V|7mR-s3xOw4-lD!HnMw

%7wFmm<*%)4&eMSBu+xIKCW%VMC&6XP3=zM&%H-h|U?B3tqf^`~L5} z*S#IkPGLLKCx1vqydhMnm-w%KOOdtXB5Wb z+okuW%e>8asd0(08QUu42S>>^PFUQswElXAr$eIJZ?&)%GE)d*l7pZCb(5R%656@c zn3}PA?!M)ln3vL2X#X1ub_9?tgkvqqCwKEXhGPUZB>02iPY-jdH_X)y&F^lOz|NF? z>xd}Wxi~V*Q^GE*FmM(M_MrS+g}`;#PaDsQm<@MRI}Z}f0%ldc0`&?`PN{u$h#)in zmxtxywWbBJK02`}6VPKK0Ujb?Qad7MIb0*dL7->=W8J!vHD2+yLRU)UBJDPDl`B-#EMf->SR>4*an z`T=FT@}A^1iRk=E!6M>vEEK1G;`YZ~{O*Yoi)<0<<{W~}%d`^C3c_$8G}HcH&mA1- z8k}u5)B2uL7Nr~pt341rd^K^1V#JWx&|y&-`WHAwQAilEeL@yhJAZY9r~n=dQ*-DN zqzBFJcf}lHVtZWit;N`DV?5ds9S>on!7IN9V+$b}daD>`V9-(-IS!E?#FWt@&as^8Cx?693z<&!=1mKy*YdTcQi`8f73hThJ3RpqYE}Qw<<}# zd&GKm4P!zR!-_zQNYRxizxM8X-Tc-ata5u|F>{o7n9>SUJ%Iw(qX$q7N?m_tJt}c7 zAt<-Ru5~LzNe5Wa4L2+OcS0s7-qm{ad~AaC-2BD-`{4XFM(PNRuG50YVXq1LYpVAO#)X;6hE9DsFv$;%TE{=Z#fUzWJ zidF*AGS%N2JZ^Q-Qogu%1jkBY$N1;FD4|=u)6FlIU>$O^U4qElk*s$#u1Dd7a2FVgkm=Cy^G zNh*+Q2NogH0h!rh7Mm$gCJ!mn%T&UpMzQ90ucA#b+I5K=Hb;}Ky3LWd2o9&)?nCWp z=1ax}spk&_9I~b3CYq{U5>t2Inoz=ae^V91w!g4~FrKZ&66m

m16$7WYGzgUv|z zI2(JiHlbTJ-vkk0INzk=STO8qAGng>@q%=X#D>(7!Zy*XKPD|`h43rbpL8062dOmv)%)%~aWk=x5 z_Mwecvg(0C`H+1)A}u1>K^0Mb682#9+t|F?5~K`6h=7B`@D5ZQ9X@4}uxcTSydn7^ zP3M`$CWv!DXoOdBAMy7cN5{RKVBE3*EZNSx7yo$MJNvPZ|9kPyxz6G#+ibQi(?$w? z66mZPY0m`=jGv>}c-mQTdMk*#I}K}X2$pEqxDUei+h>Ri3(?E|TlB7GFO_1_~9nt$ZNI&YcxT|4?`ud0wlg50~hSEKx%x$85mP&)LcQs15$cUb?0}uR9)MEE8(?2>ZOV04M+@y)&qxBou;_EiOW6_mO@hM<(C!%F8l5+=Wo-vWpnqZB#9j#z?f!7p!Ckgq7pf35Es)IDqB)WhJC|UYT0={j&qq zGo^UsTY3^X3@S#0GgOP*+mz8p=gtcZ(y7F}N5X2VY%U%Tk;HqNX`S#~7pVNs$gL@mrX*G*t5tY`Th6C_M5iRkfV5qmZC5>_T2$T-qCxu$r zt|!;Hw)%u6#$`n*u%Wz^e4F?^YrGRN-P6-8u;$23lh{q^b4J;d-{yOwzdd=+J%$;> zHaG+Ad7=F2uR^Vcnsu(Pmftx*Z&fa`sqZk`=V~l!a$7x`TBR(wrQmifJST5BFf)TDd02e-S1{?q?p9XS>B zdK1*9vp<8p4NztzZSy(E#KBxW%j!Dia_K9Xkf`z76T+#q5nK^t!Ajui)L@*DT%yA| zwrLuhGs1bp0LG7}chlNwbGnyp?ypMUI+AwJ7>a=bZst&qSY)6U=?7l|t9hE*qA5Hu zO$mEufv+w=Lk;~}$`8DGAVOr2{TtIVw3)0g5s0Idj9jQRsg)D9v8A-hp& zrf6EQ9*MyCvUi!R6ZxP|y$I!oPfv^3FBSB4fA|ykQgfJhKpsw{HurcpJj&UCyN6dM-Xe@N3C%5Iuj3!q9K(|2$B+fWg6P!0l6u4@ZT3y?x zyIa5kOe-{4F@Sa>r9XZ7?VZZT8W!~ag=xjb^3M>mV@n9BD-V@umzF|B%!ba%B>y@F zziaZC-Ogt);8dq@mZwrwN{mc0`9$sZd!G1?%Cx=2_aMyF_)Z@)RdbZ+z}v&>fOq}L zl>|J|^CmEMjp6XPd?s^%C633%Z~ke8YC?@qsV()B-$VSWcRob*%jh#H1Df~k zU^sAUY~mFIE~GGVd@n|iHB(V#IJy{*#&eh~h*uy022lVJ+=Bncd3&&16Yjh2z0Om0 z><-+eEh(cGjhq{i%uLgX%+G9kx6HqaUdj$MFl7=i1UYDS;7wb{+)aS+fbfz4Zvb(T z9f0ScOKZ~5q9Lgf<|+sam`H4`oX$p&dKL#-_gh`@-sszpF4)yj8>>=ta#vN|z0Mj; z9BS@YQ-Kkd}Oj{_2cZ{i&RUCs`2StO~;&yP%@=sx~>_O@Zk40$5e4j|TpO`F1%JQQ!^v zWTBphe8aL~*`KfV^K!q|^t~cr2(>Z9#9$-Or=NFz4J^&rYw`I2BR%V)X{ovlNE8g( zia|h^^WFlQpCDk|TxDl~igEGJmqKlK>*zF>P9!gZYLR1u$&y^Zy@q+e?j9WUdM64_ zArp0xdGRh-?hrqIiqu2}hCTK$Y>h+_GeBAyeVx*S+&im=&?asj`S#eFB6~?z5cAsv zC5T_H@`2>5jNur?x%7dXqs=vy2vA#Y@Vx}(5P&|@d6sI2i!EytoOruL%OEgoBlrwb zF(oww&Ho_dga|?#GvIH`LtMZUqN~}sfA2CCOxo$4z0ThMn7w;(u5SW&!fp1KE4DwRog;?#(^j*8L$jKP@}i~9q9J|if0Ax_4*d72(go>scV!q zqfqDYkv9L`)i{qZ91GKd39M;@Pf2sR&8mj(2jZ%H*hF^o*vsGdq>>q;^?ztm4o>*{ zkA0RIes)`cioF1cm<~0Xe)}S( zIhSDJ+#_u*26Mk6aI{+v^4!Snv>)+HdjqRhaV_8GNi^Eq9Es{r zBjARGs#Wt;@S9`sADvlStPro0s@5(UtN?a6O-JZ+t{~QtklFaAKZRxgl)-hdYBHE# zJ?|h^2GBj8fte=;I9RsG-?lOT&ZAZ`hNP2nPAG)w6Dtg1z0vq;ywsj&obRFgC1QpX z&gH?huwa*aEV)H&VHRlYjMacrcrvmY<+x&{DXEIjNt4W-ut4#d)|}#+TkwOah9u`1 z4cj9{OnB)U--R*-$Gjk9PacD9Ar&Fu1Ki8*4^&3_2z?U0IF-YRk&#Di8!Uqh{N}Lb zDBku&j(!$0p1h!bFQ_N`QbK$|s3^@FA|qjPwwHu>&U0u%0r|*B&m@E9qXh>tagT?+ zVXsS!9mSekaQQK+6>MWENW1lRplKM1n#~dfT{e|=UXEw+xki*fUc zKnJuhJkxK0=RmkH`=5M1lS5OS@fvd~Zk?sydj_oTe(w)`KWXB&KK7=4go18-7WD<( zY2F?T(zpN~6atD@U1_@VIY6FXcxG|dD%yw)u8GBX5=8Oo7B44%3p*XLi2TU|%pj7k z+#UcH%%uGI>cv~_*=7U{<~0ZU;Og8D=3@*t2IiUFj~C-*_Ap*v!~KtPAc8a+`zyf` zdz`J-#WulTbnwq=8}QHr`yHywlU+COS#8JC+-jZpJZq_p|Xx zmKHeK_Kxlb2p;RY^V!UeG2iAxq@84?sR4n9&oK!+;^dNeTWT{g`p+&c#m|yBbvg(~ zZkFemhcqq5(naQYNGsu{v~6#78*87H)#bML0F9})-HwB2#lm{*s$d%hxJ${~9n+xN z(0ZY!#15JY+RO3HBcz7lrE|2M=DnR3WPN&wZJxRfj((Ay)O!752eUzkF-X^Wv|=;2 z=ukILz=1 zAOQO9(`jFq!L!#r7n{uo=+Dar++KN)#P;rh_lJE7Zr; zd49{Vvt#y%zIrsPD7LmqI(^Urld*x-Xi6-DT}X_?N(F387$yA(Mv@#auJ4u{weD=S z-kCB@tJ`tQT-Leo?pX=PeSLN_f-S&^8c7CL2T3@IOuZN;Rr}6^TAph^DtT$9J7E>G zoz#r50^?&30vX<50n$--EB!MSS=C2%b#^s8 z-s?V}&n_^y78&SrHpCT}F0K}*r(!?j@06&J_}ur;TKv$?uMhd)3$j~ia=N?eh6FFe$VHm6Lg##2qRjs4+_K0c?bqu2f4-dbGdg{*l*$5r_H+VPM?QgbS^6A?QJsQV_ zB|nc_6Gg3$=8+$Hqe3rfP9nNy%|-;)=v`Ud7s(se?iF}8rm*w`g55fY1O65@8YFZ% zw%jw0L2r6+cwhCHgwU6aKnY>5U#La@Vm==TZWEX>M@fjyShOL29M9tJB0Y|$x{1>g zFjr*mH4sQi+nSe;Ek-s(1D{^S0{Ibz4Y#NH^nnP|Kd9JHnbUJrbnN}cJ zZ314+z-DStDUlf`a(^Yxf26g917GVJG|^%*`MG8eQr)uJ$dK+jQVT2FYyq`L)U5iyXGT=DiEzpkt6 z*xI~c1DCTi4lujlfry%nSm)7BWLaNH4v^u>VU;2o;SJl^$sUFlXvmOUtp>L#5LJx= zWwT(SJ~Gc)o}k{~0G3lSyTt1P+L~%WU-y?TzS-2j2SUm7u@hqP7(k2Aj)#j-Gzzj9 zDL``I z+UI~scLaVftkx85>CU`E3LBc@Dndju1Pc|@Q&8H+*B6+FbenZYr>8RN`iH0`$>@5k zexyQXX!1kKJFw8j)gX{7za66$N6ZWRjPf}z1Ie&h^7{t?du5gjUi}YdemlD=O4xjv+QkgZYDL(Kfr(;EG8H| zX&Y{4c7K9nyxIV{DhFlL5t?9Q6Tv3K1bOh<-b{lt35ed1wD6?&sOyevFDb0VYVG)2fo2 zJ!exH=-}gfzKC_f{=sf;6JiX)AQ1SlMmRCc!Ob<#k^5JhE!7RXjL_^AFH;9g^kbfn zWCTHzRv~DRL2AkkDX^0jCFrZ#wS=soVEZ-!j>hSsb?8w+4Kdpo;X4kBqFg?ui3Cwn z@wVg4$pOV-jMh1fOLgk$>b2!qdR$j0nPrGFKb!}>@bmJ z_J_*flcfR0WfPP&BqIWFQnLW05-K8T{+pe|lMC$rV0Q_=Ds9Sefpm@Kf!l=MAkwUq zOxtHGug?wNq*imEj2N@kX<;yMsY)6HyV=$?71H**X-Pa9r4^_B%HZ>Dubcb+ZseK%R2-gZ8Mt^_sH0?eKM%DLFr8NB|5x)M((WTnXf8igGp5DpL%1 zS1EodpnQE1v(%~U$eWKbCQursNmIh}#EWk&1)HyWi-@Z?a!1)!g;urseSZ5HZGNBk zyC?f6hezF$RJWhSL^ar?00w;Tke(&{+7Jn%^aK`W4coC&*aeTE3lP@}7du;#zM^Z? z>9-Nhe>4?s8A5~|Vw7ANY7z(|A{A*1dQAdC#OR_IVMU@~)Bt_I}DQB0+zfsC`P_flAOPr%+WUb5Dl zqCc+}nbRWY-z>Jp9ie6>4R0nLfw~W&*DlZ`%vX4vcmr)7c!QAVP=AxD92GG$UX~F^ zIwuJNeTkV|z@56{sYJnAfk0zbn92nc-eWWDc~Th^PsNcz7C%?6&!~5l-!8^DmpGPQ zlSmo{q(gF!LoI<8*nRBfn^-G*Nq_S4_HOwgJSn>+8?saJm|{vdg4sJqfrb&P&D7x_ znZYe$QXI&3vlZs3&`+o%bfP*!OzZ@@sIqXSjO47vE*jMeiWBygU!eG?m>j~TB=UAt zyc%8EdDerXt5E6Dy}-Y7t!(mnpLVlPjPG`2^`Y`P2NuF{$-v2&yt!qFi(b&)kA}LO zz4#^j`02%`UUvTW#Tmv?{KOyC7n&?+<*Kh0y+|kPq(@vG=*wK*-H1>~M#ho6<_YLw zgdoP3_ywJeq=WhRJ||-v$WmcQ`=9WNIKhZcv|A5)YxPT!Kq>;(+_Lf)=oI<7@eM0xb;w+7&^E97J)z4-85 z_73KQ5sI^1p1_@zS|A^M;qv@p`cQL>*#T2hV(Xv%f*C5Wv!8qau(fZ%IP;h~EKiNs zs3nD@><>=rJ}nTS$GhomcBk{)$RY72&J`^JE-LwWLPW(uZ?lgdoHK`gD(d1ufF#sZ z?*%A`ou{tYY8YsnUsn7EheKKDiujGcf&&7i^d7O)R>!?|Pbw;sn9^a0S{; zfyjLSY(xDQ54^YY?7@0BRx?we%CeS~ja(Eu{Ymbxnl2lvxwn9@zNizBfQO*9i=b7w zcrIwI7zp$Mm0NJksg!AG;P;`40DC}qqBrIhfM48qnHPZ4tJ&O-9*YWJ4$fUc_G)ph zH`SVC;zF(yYC=1|Ugek$Iv%QwDF)H#+UVo}N~kWn7tS zW3pUS^V<05D+REPKOyYGW%L{)7A~)JK!s)Mu3${YOS4|0u~Z0f(s`0oV1F{GIl03I z=+Gm1fWYG?7$t15sj@{XO?HWTHSiV|vr*Ynt1*Yv-~_A>y>^wO4WzDOnd&~((vtet z*JNVni~VWZ5D>|->;qsdJQE`KvR-!NvyK(S+B0{Bm;wQZsWZAf6(8+AOi|k9{=M4o ze>lfq$KX@eZ&B$x%*->aAGa*}0Eh}YD%ix)VegT?V8amg*XI3w(SDIb;!xA6yp~t}38F zmjfSHt;=DX`I#;$IJ&#}as!Tbk?qKaBH=2=63O=`UItgCQ+XNkc6%QlDr`CTDzFb` z032~K3x&W~bF-w!w-c;M4IcfTAFb(kMUyH?|Z(iI=*9r)4 zPOQ)|DhgoI+71gGQ-Wq!Su(#JBWJuFr6dhD6vu%z4?70LnY3n@^ba4iR4Y=?W6{{@ z7Qg&p$Q!KS(Kbt!@N|{33M1nP`6N{`?rpK6dm4iF0MzD4|K=yRSIo}9=GZ){PA4d; zvKX=53$}Sd;=(7#Pe7&NQfpCZ&PCD`2s>Es$q6#aD%~#yo0?r-f~2TUz`N8ZCv6)X zEmrJMTDV@W5%=HT!!_m>!&AM-TGa?I@?P*@RWRiK#oG%fT~UAGYY~@XAb561kHmRe zpwh_}1wh>?OT4NTmW{1)*;R)YHJN z74(ySRjDgjW@O#5pkfqxespW75wGG_1>P9tGP9>SV+N&d5LrfkyF8!e0`ISK3lM@dx5rY z(ofw$2(K;!8}aAS0;%K@eG$Ba6F@k;xVh#DG911SOYT?V}1t#cPMq9u8-DF^4S6qru z=G$Huz8wfY6l8X&D5V7-U8ZOY+l~xnIvQlYjmve6Cb;6B81@b#IOr1GcC^^oAI67l zMVQM(Mj`$p=h_UYO|W+mtF8(7;%n#X3wi{bUqE&?9=TbnmiRsW&H$PC43vX$Kj!>U z-Rv!tm^u3fW1b(zu4&1OFBh=#H+Q*?ca57dy;x{rUv#;$r4|?K(&pMGNSGfed(D_Q zQ~CXVoIgmg4j+udMex=B5WtbMN)-_GGdgnOiSY%rRWe?6sXuDP?@_?xmBAf+${v;) zaJL#NH0CUuEIHwELGe4^roxLNuMbKpHC|TZ(Ze=WcSZ(=nx6K}Plf3uX zhQZ=QcuMSG@*E9Cxl2VP_YjllaY;$d7~fm5Eb%u#{0UlS`eVS4p$T<2yvDy|7m$h0 z7k~Pb3x=VRY7NcMP_$YJcUvZ6Co3_wJv{JOjRCv(F{B)^vgH3Y+p!AVx3mPgi8Ee% z%gep}PY|e)VR0y5R~C8Y%xK0E^lAlKcfW(U4a{TrIsYbcu0#c4yY)HFd!^chKv%x* zU#cilv5}LnoIp|rM)Up(8J7V*wp6RxK|95*8+7eIH%-}WI!8t3zro$gXifY+|FOm6 z>ItgcL4e}Xq^022x6v;aCalEsyh{r>O&j3T<`xINZ#6)Dg6;=9Od@>1u^HZ9&@p7B zgy=%}hY4P{8wM4KC!#9CkVOOvxbO}86I^pd)RPe0yNPFoAb9AMUrN$Rm!&lPwy#S#G4oE0e zmzdvTVO1A#nh2N~P~-;r;kwalY6DsSuaBs-0cm0zlCwKi00`w}IH&uasR$kT90hqZ zbX=#o$~gsLVSGF5|cCwQ}hdpWnhbraNs97zHC=4bs*EyJ#u|;e}hXBm1`~?$Y!jY zavHU^xT439)RJ@hxa-*j6qx6o-5++qvRLHZ*WvqD43W|9#V}YmQ5cH5af8ybp#k-` ztOmG<9h|yO=kzpm_0M@RoeSi@nxviFSNHYk7L&<_EFgGva!D$=08)XXX>SCE<~0&fDvl5QQ3#uTqfy1kj9V_ zwW>2j)B>VX++z>ZH!Fjw>Zyk-@+bqo;Gj3~(Q8`6om;Ly0vDA{F1gSZab_#l1Nb}; zcWgoy-XI$Fs(qgL88atBjI?My?XBiZz!qw1nvo2hU!eOIZf!nAW2MmR?&s&fGUf1{(|(Z4x*?Bj>otF_PH)&KGSUVn*of%ehEiC-h_ zTyDfE|A_xEwu6uguEq_AZaE9=ae`W7yuu(lV5x{?61hb?r6NsCt+l!)%&C2{GW9x@ zp(K8^w|~P{c)bgI@FI%u1ME^kFI4q33ZJ2jmk*|W%)u-w4##1H?!F=MOB^IumLw>X zMqBW%H?FJb^1g~Qr9Ec}>`>TwPXZQ>8bM^y>k`rd+YdWbs%e$!QV4_&q&BoD4AEeh zRy0d9YeR$NQ8{M?AOv4v87qnk%R(|jF2FY}CyuRnLR^O^tP3D;gT)l6I&a|l6TaLl zPYfmxgU1DBy9N`VdzZxwTxkqm5pSx661$Lvf)cF!^4h{rO|-ErwrSy!-V|RBODy70 zw(+5Wk{PtaTz1BbJ2-cw^!aEc6+e7&h3u3cvbH9OI6!Zmh)>~}u@bEt5sKZeHt%w~ z3!f4qAc-wc-L@VHG1UexDO~s|X=qRYHbX2@_&5t6WYF|INw4*@<+vNpDJr;{bhKv9=QLV_1B*0aTkhCU9%ud+(hf5@UdyyQ%cF zPR3IVMC{*GyXSBwYoAF0?BZla*CfXRWFV5LPYXYV7l$?hVs@x8?V(djZHhCzCl-_} zTxiqXwXbBCgCQh91wTi~f}Zinwp6i<9$DP%JnkM{j7OLxBYG7u%&07~mc)OfSTW4x z>?8X-jqW!CKxM~~V8l7<-(4Gcu zfx?E`cUUK6KD}K&!oZ9d4?`9aoIOfZ6DMyc9F>Jml0vf!2C%rL$=zjA}yH_a1#A_P0aF(bh5(ibRJO~$1Uqwyj4A_+PlHer7u3*rd1XyimWVrD#xP?s> z8cpOEE={dDb^Ma_9B9jkkRuXLgkvR3%1Kd-`@dP>Wbl6*c>m>x{!c%D%3l4y7iT*U zgYojm+58tE+Xx?5jsvQ841E8r`ZcIEKnWJ?jU6U@!YOjF5E$T4^Ahl;sKoG#L|-l^ zW5+H9+FmMSU!#l-;8f^@4CCZ>21#Z)B2R7<%`2kKQbzU%)5d_opf-m0AEo=(MzFl5Dz}#uC8cWjO@md*bSEg)K+8VcZh1uNkEet-+V?8Ih!*8 zO}4rd@Cs%~mh)uS@AKLTt0hacbn?MzD9K{$g5 zBLcqr9FJ4~I;&!{p7(;`aqTE9@ACk0(Aa?8%r(t0Fm(8SGO;s{WXY38?!N`xr8|v; zXTI2a%W>mT)XnNZ$ylu0xf%}5Q>c<8Y{8=ccG}ToiNTsziz|8O+5ueyD zB04Vd?}v|ms?0Y_CsQMVYRu%SAPG?JEm?+$m241UxO<&Ff3gU>OPth+PaB6~yY$~= z$-ff+RxD+be;uQIHF@M*E(~$GcQ(CnR`uast%1kVoBzTv7~Zl{TRz)YqqclDVg={6 z8uYWU6?}spZ2lCl9?Ytp&o#J-l^0yaC)KDTECc0mwaSX^ql;%MN@lVTjDHe{T=E%p3Xonj&$u72 zu^P2^&+Fjtn4t22q+wr$YVmyslU9(@!1p9G!Zh+< zTnD%?UPE*y7X=u8!E8nwg99`QZ`0y>?FAC_ke{cOwQhz#mI;KpUOVtr&iXF`T4;m7vk zGU5X(==%x{)9Y(KK{)W83%daRk8WzMS!S2gaN=5J;o8FMZYDHYzY40As48N@Tw=~F ze*G#f!8VpTeR_M0O68{O@w8Ow2=o%6ygNDZ?3UnaQ?OWOypoH1Q z`ZC84O}fh}F(|KU%NVyv+MnuGJ#@UJV9)%;$MzP~$#PYzHhOB8x!|SRYAHJA#pW4I ziHU?a-Ex#`;3bt2(cN0i=j!a@3(Nnxfru^lkjYH7kM*Kg&~+0P@Xz(y$Dco^OrRW= zO7R+<8l4U(&^IH9-f()99;yhpdJ4FVH2F1%O+8WzvWv%MzJpHO2~mVU-(ZF+LjV78 zzq4$J8)l(;8TL`n(iWYvE!>4IyqwJ+2J=y$UCLD!6z(;^Clg)ZR-_p5wImTY+HwWB zjwFXA#!@e4>j)|B31TF`vH&cJ$O0%;4}x((i+-BSE(Vhy=Qw-)M#ZUh``}>%;_R@p z#G8F0QENR`)x>cPUra!E%dR0gHOB^@zb0!%bw;p3Q8+MNC22mL#&>~-El9r_Kz|O0 zX=4gG3a)S)+WHk?EhmX_2M0+VAQP?l{Rcdi6)=O) zKB5NTS!HC%?wjN{SIcX|xQZQ2zF9-=T9@-w*@n+5Mp0~2TqU?EsTH*dHTnBVRxef; zy;-oeXjiZ-z%-%CUC4?se9QLte@rJIZilC*`cH7S?sA7XVykQRr8aa-=zPKO%P=uP zFeA%Pk)g|c$;9sNq9@>QDf2_50m4_JmD!cR^w6E2YAMX-6g@@w6R!^9*x$~2|2Xfx z`qV><*V*gr-HY?c>1=iLCF#*?6j4Lh(h+LMXZ&*g;rg24QfWPVh$i?ZiE#9xcWmQC zdJid=i__3L>KU&HaG02t<9M1FT(qKB!Ht3Fmo!lh6(U%TLwJ(Ajg0WPKH^0>BZ{6NWVz!WONx~@sp@&oZ`g#mTha&&S^ z&M2g|L-o(iU;{7+37*MV2JQs*JQ4YfdYJx3ozW`!+`y3<1IZgy+Hi=Ia(*J~dmN8+ z3*A4|<{>flz!*Qwd^R-!7#d6n^20Bw`|cJkj<{iW_Zb8+lqeYpiyw)UDszTgYn!Vl{G+S@WN2p)o$BXsyHZ#+|S0NA6R~|ChNfj=vVAi%9aki(hc=^>T}tKXFpg$%hjeg`O!+z zdXpb64liv_=;h1qy=kGL;1-w7!rB72v6ktW0!h^ecY?l|om1AyD+m56G*RPDS=-X< ztAr=i)%~Dtd|je~Lyg-zogjY4--&mt`8!Px^_rCzEm>u#YV&N?{Ehel-PAW%gDVP= z|1+5#`eyHEz?5^YMbzS%^g($H6&XG){iVp(EbTC&JM#oT6havVpNiS+=AAdQ%5e^sI zPy50{|~jXhrSuf1=sr{s6|6{s(Wd zhmk4HEmsT%QW;S3F?^I3Ss%$M>>XZ7rG%wc$gW<@m$L_v^G$#slT{Un$%IZRCM2wl zrj3+c9a>o(I!$7A@qG`F0ms~54cx{zX#W|HAo+d;0RvFzO((XtqJ?@DQ_LIc=}^L$ z(n!c+GZyPI&?NyVAQv8SUf9hYItP}RRyE(DDt~@6ySuukdLNQLcTiF+&BQ4I6H!QH z6U?&9z##)?!|0<;KjGjKLu^UhNqYti1?X~o4%EA;HHcyAEel(f2f$4DNq{~ zAmgMN-%0MJlZt*Dgdodnu3WSNa58mjAy?rdJBPy^aVC5YFKeO_TlJ3pXnvzALtCl568mk#f2yoR= zqIC$pxuStbh^lx%{s&qg>IiXI@gzu20guQefu;Txxh4x5c)&4t5O~3`r#^H|{)#n~ zAH`zm--4V>U;weZ9b6%hpdm*#~JXo>RGrC0N6^5 zICE2xIS09?Gt^E-hPc;*o2y)UMtUEr)E=Qw({4VDm)C_l$Mf3W>W6d(%qn29vF5F@ z|Fk&s1oJeu7)Q<+me{-p{>Esk>sifkBTCZ0xn zkc1j)h7v9;_C|JGQ2GgHlvEc2vkf&irSNwu-&tg z?Izwfymr0ESi-aSE-WkoGc?Nu8K7Jyuraa({Z6tzfPy7*LjfTDt#hP*W<&~OXi{XY zVK2^J{rp~9!+b;^{I+|(ydTeji#on{^QQ>)-H@)(Jq%Vl5D zqsGggRod9G@c)y~AwgcsY9k)#G(p>Zf(>6cIYZ?fULMHk1O^hR780uoxE4gt+Orl6 z8N7!?A@hxiz24Q*P8w3l=MWF4!$tapwn+Ts>eu%^rj5lD&N1RooDLj4Yw&!It|#c3 z`mQJIipQa+EQL9Tkv9&%OK>J(vuGxwzal}j4XAYAj6~)Nq~(;}zSC&Mpe2C|ZWIAI{$T+u575_kTaj3LBP4P8LO{dxa8_Wmh+MEcT<(F^(mlE7E1l z1ilIyl0f&z*B8s_;5O@yPEX$s9`kuzO>Xidl`3+RAJXbES17?s;*ChW{%7MDa_C~E zvw}Z_wU)WP$y%d9>?rPAcpTV0>{7X2nRcW6NoiE1-a||(O+53^o*BVJkD*Bkf8Kc< zJY-ihs=3Z4Il{)FSc4+^TKy0{k;UhhI9UzcG=3z8T7*HN!4NQ=5GMz3?_ZQu;2J-{ z_Fj5V&Kxa><`6$$!buthU>)DNqR|<%K?-(m&u_ z@1mYTkK*YqW_km-FEF3-%`7ShW>aLSmVioL%BSv|h|rm7s(z2B8)S}gw04bAZrGSL zEGmjZFo(s7nzLaZPfvrk>>~cB#d4F1ROLvfJm9MYQjFfx@Y}6&-Drew6*pmZk&gKl z4C8`YEZGVF6*jW_8u9{OU?2|fFH>2xSmaTDad(BTS1yP&ZtEQ?A2c+JcV$>F@O}&9 z3a6X2W(`U373iEqY-IzjNEJi)*!d(Ezvau@_~3mNP5^`pyEs*SP6lwt%Z9w z6K@j^*mtrfDR$EEzBKEjX~U`}$8_Vka;;ik*ZG*BW*@lO7N)LzN`39c_=>4T5ueBC z!BllLHms>gw0I_Dn(U@Qp&5s-0yISDb?W@>3ra{hs}u#QpL>p!To-MnO2V*VksqbJ zZpe51r(TDXPl$LHDEFc>a4^N7%y)|`oL5&Kdctw%jR|Yw-tGpMH{re8*s2~of7YVx zw1_qKt2XFpsw?2V-z6|O_@*CZ8EZlMZUe-g8K8qKm7*E(pLTn#*xir9D-n?us zP}-;=oqmuWp>BB!Q2)AY_j*Ov**%G?FeYt14dyDq~Guq1-dA44a-H44RXN~a9r?uH;Tw0 zSQM@heNoiFBL^dhVDt$3GKavOM&~< z(w%58KI|<1g>iOR!sif+GPve(vCOBZr@I^;fSar-s9Zt9 zgIAy_w#(x`)&?r`js%wZ+1icbH=(|i*>yr=_EBMlBIpTJr=62d8q~h-YB_qzUg;rECPvidiF6F zrZ1dHP4uub{SU{R;Y!*nr!r-ij`zHPnpy|s%#eo5fy=sfx-j?>T<$xg@ow+(HlDeP zf~JpSUQL^o|g%|65j*T8+`xl&tZ)uKwSRA#`!wFIc_Z2)*w=&3EP7X>*ANM=2etz*G>!U{Ww*TTI zJx2YtNQ3}5;SZpw90|Ky<~rcW2*vyS&4a0g*4?sHN{bNQAbO553&GF3iusI0FT)EbD|oGgfl5N<))!f5Wl$3+J0j79-WD@Gm# z;*g?A!NG~3n+;fiNzJ3y=-RsK`C%|nGCZCeHnZ9Ev(cUOmE0f@1qdr9N=erUQ{7)Z zw~++STgeYR??409`c8IH@d$eZ@1H%D;dz`m?CMMumlq@}v(+Ay zDd790yn_n=Fw`W)+2b&y`4JBm{`qWub2ZqcA#X~$NX=*2OE?J+993kl7qF%n4f`-$ z3}+KpF%Hh{8)v(02Gzdnk3iAw3e8H0X@9@=Pv%RMha6Aurgf;AZeNX`taUbaui!z}SPB>TOM=N$cZ*i& z3pum(G`jR2`3{~1;c{>u@`_v2TjOTylrvuaEBCcRcf;MYz-Ps=>|=@zfP)aiM#6X9 zLu;c^4P71(*;K$tT-Nb&jONk*ktx`{ub`0JeA4`6k^gJQdbCL9ex6W)tGq$tdyEyb z%|7bJXNLmb^VzHbpK4U2H#HaQ(cDe=wHlQFLX#1dpN4fJO#Q`25RC~R(1d=wlWm4J zNmjMn+{P57`Dbq0;jg?+H~HdDS?@u*k}9q?fVO%pW!6*F<7>v=mFhq~#$LXhV(~b9 zjSDNbyb5w_^+;F_K-}PIzYke;T*l|Gh|-4if+qE9SLmyhom0@Q3QsC8=T7aOx29x{ zs+&caCuxb5j7y@Mo6VYEU+YPjvya=pM8Y~%y%;=E$o#h zepimi7|{XFk!=(^ruF3$$V(wjh-0?B*kOYr#4$WT(AJ5^s5vjS5q8uT8bEnqSh?}!TlJ`#hAStu51Z|sF9;WyJX*&XL;d4OF%o~ghHcrF?IRp#umo2NvY0cWhrxg7TlHIEJUsk1h_^C zlV^_|Y(?+EHf?TWJylu{q-uKll8~d+nQak3THxD>7WQ4|8Z{gF&q9JuSGf2l-xA5lKkuHaaiDD!LaT#UW`ctGx=S0`C!QEG|Abl7Z z!746qUV)e(yo}fHp?3f!+1rJt54GE~>c+;`U*P=Elm#Q%r50+cCeklv;9|Mt(>VYc z7Ih}i;}q}#q{gTQf$j`;0Z+dcWs^UG@Au&v7YL3mSn;xKsnxSpvJvVy%G)Bs93lL94p^Y|TU0&ohZ$}o7&u9eBM17%v%V^I028H2eUCqvW6j8#n?V=(EIhG4_lU zayqn7ld&zSnSWg-U3R1c6`vBt+AX0REfy<`)7$S zlFZ~^!I`}6xd7ftn3YluvPNK*jjCQXe4~8k5OXxqegmMwmP~LtU;NeNG}}>!zx-;F z#gS@n$VZ4<8CNqY@e5$L?{3)nr;lK^&LJc+$Hp2$3wj1RwV9<9jWfbZ)7nFItIRey z)r?d+!n}o}y#&K?$A1omi_P=1B7yFrKwmNU8BEpF=2=6m+twp^Cxb3fMw< zdP;N)Ggn1VwrLxh7aAy79QJB@$aye%F1=FK{3B}bjUq(F|J_e*R`zi}WJf^DvkmJ- z&l>47JwXO$-H<|a!s{&OdkQCJ|McEg18sA<)NjAap~#75IULEmyf^Ma8181rN7$yS zlZv~4lO)kKoxt!{)kR;s22}oym#f6Z_cB*?BMFX;SEpu3h_waJ#C7^dbQ9&!tjZC- zf98&`>-v*&6uP3^4HZKom8k#hcJ`06j$;|TFb0kRkSY4 z*+(h+w9146`puWb0a4`^uvUD5k?Rx#;yuqV#y2AkB0V9DOB}?N8l8xV_DX~}g}wv2 zWkU`;??jQ=liuX=a6fzf=mV#78Z91AnmZRXi_n}oq`yciRBz+(I}6SvugKF_ z>{N6u+suzIi&Tg8V!lQ_(8N(8{j?Oi5b2qE*X zx1`3vfuwZ5W_L;;x3eF{2uQML$JoL$ffJRZ&Yn}`SU|Tt&`&HpUYi~BJRx4b=6O9` z)chjDT&D5mqedYKWLN6e+6^lxO58RC)_{(DCyr7=cy;5p_iBwEs2s7{zkDCi1&F3 zid26lzOhzm&@^hB_$1?EQ{_wm!N&wzm^*&tG%rvv#>dsp^@Lfs5 z*8KI5G%=eFWFKZB7HI(?&9vFP5g@#b2iR$)c2mQvLFggTOn7tNF2fX>W5^c-!h4rU99s_5kr=}`64+|-j0LL#YrI=e|DN%b&N5-3@1Ge?*Xm5SeS zOM@T8ZdclJl4+kWNHd7QgOc3cv!QN$&8^jk4mCcpK*#*|m;t_=vBWk_Lk-M2o#v=J zbIB>PQr+6-dN`=5^wb7FMGqiTbaDT+*%@nCcr3BtCz;gIQ|Epa*)b~-rThodwrDN*8wCiX*|uTz=tPJ6%A9c%3F!`2k> zxRop%+WMeFA(I713+XsODjV}l31fvHXNY|B!BnYl^#Or?S1XkAPsV<8m@=@^9AT4= zmgn*%)_lW;>8)=<&9TIZDb?g_`hpL%PU9#Mg5W)AgmlUdGXW!g4@Ltw5QC}t8#tp{ zfEOq$4d#6|v>~tKKb7joNHQ@H`a}jo%clXK!%5KroC8jamSHY$Y2$Ys+Y4G80}--! z_`G7dG2vhNVVwH_N)$1O!IgkTOua$#$to7x~RYPlKoFC5O~0Po7>yYS+g+63etJu>~*!B~N$WOGQb zD5&(zVC6DHWmwf;c%#u_A-O_Wlp(wvDWJ;|6u9zcHB4X-0F@C#agrE*8-O|)a)9SS zTva#)bm(eb8y>8(Hc;XeGR|mx1!6>Jmj-Hrppa{nQomUu?xl3k@{(Luw}VMwFEt;z zw@ z^pw_Ij#a%Ch{^7EE>Xpkw)G&8qG@tw0QLEcyUV8q3;?7_dBQQUxUh1%F3~zU<`CQ| zT%O1SVpCf)f!FDgx}rW`eX*m-%w86E2i(ubBWA|pj@|j)UXa(A+*44!HDIU%J!LcT zEvt>Sd>3oON{gUx@mZN;RFIh3CWJ+m!z=UPt{L|Ctv69!L&~ru{6ep^np=$lH>(r8 z6QYBc)<^hHFcF?xW>UYW0d|uJ3N8T|%KNN3qF^PMRmn}Bzqv1xh)!nb!12KMmJ5tC zhTgTtJ1W*3%Ti-Z5-W-aegINTlp8^a=tJry56nraYV%MG zoq)nLUSx{7w_kE?yTIiiNyvd`NNs7-n)SlcFMh6ELu`fqa!xhQuz|nvN2Y1r>He`J zLrcgvmMyTGTDUaZxRmQ+vd)~H)nU^M{dIb`%)fe{N=Wl+4oFiR`ru~SpT3AUJhJDE{=eaLUG+*^(=?(9sgl^QwiQLF&OPZ6gSVOphrI`#YDs&owm$ZWZ z?e&^*XrVCIryqxH`GkA$5(W9g{hePI#dJMFQf^%~KEqwnKxa&oL4ZAwKd*Qz#6tU6 zJaQ*gfRThyGNP-sypv0~*XxYQD{oIFdBxY_$T*J+v76t=qVLgbMeS(rh@=p+>$CfD z{;)DLG(@os+?Je+(H+;1=@6oBhjbxR>!Ea8rcIR${xdT?hrr)32;=xOMxrv8@c{$c zH3%(9Uz7+pMQ6%(TWI?S65l#`uQS*f>`Py+Up`?Ti<`7~K;TVEh1k)zszSBv*mcW_{)o*e)-F5 zbctktzs~bXc0T|7m)n~!U$dLRJuJsO|I1=N{L72;{^BpgY;Zf4Kg!?nPyaQ%z1`WU zo35m_3W!$Apmz&gd+6EAh9?d`QZVVcD1-;(I!j6=ir@RZ`8XCYU%bwK?7x+Z7x1&$e*4Bn&2oCp+CAfud7xooqxgMDR- z*CL5^Nqq3CG9hNDaYIvmk0Djl0S+JzJaMI;$i=xN3uo7=BW15z{5@_mZWM5ad3HG% zVup=@`$a3w>8TFzwQu}hlPDW86@R0jJ!Rj&I6b`>kH&LU9ngfsvDotgcYyykxLWgR zfU;~BKwX{SnnjrF9c=jG5gGC*dl)aTsgN+9$>BpL0*V+8PPv2}rum}V3uMO>=bY0f z(7sQ%La#-3i@H2#?t)_*5p3|Q>Nr=M7u)tXXhMBS)TlgY_9w6?i2gWCb@r1`!Yx3Q|I zXMtjUa+Lh(A~c^)DKs<%PgY0{(gC+jFp`;_$h8WRhRwjKQbrb*QJP#ga$*ALM`Go~ z6@+m^$JHFMp~$?f?C#*rHFXaw1YOgT!$3%g7qQBJ@_sCY(zxZ55c%6l zr-%QA3BVr8(c|I`ir8XR4Kn`gbL)OyUH|Vuv+~D0ABi{u9fr(b zf!MW?|3`*%ZXT|`+Sg__1bVP=%15E$srLeierwD^Jr9-4TRb;@gN~gmY-lnR!tbXY zvmg`?Q#Gah4!stwVV+CxGfA}MOB>;hQhPEKoAnI*7F^pSWL-#L?vZs(9(4+=aRzIo zO#H`f?l;?zRJa(GxWIhJ2l|Gt(D<6b{VmTpCgh=27IVQ|$*0)n&7lyf2-!vX@0cha z;X0izd@l=4BDsolW})M5(KFtEJKgP_H_qK;pd&?vuaOk;svLu6;=m zAb`4SCg0$Jt-91d9|F&Tx`M^-1}cA|gg-S3bZ(*^5ncums3gQ7awBOduMm#D?Xa67 z6h<_<=O^|n77mE$?%G#eCZfIv@KOjq2|(aG6?+WJ+0W5ET9IN1P%!axTt+@Liyjh= z?H!S=iHVO+FVGE!0;hW?I~yCgEOz+I9N?bG3v+cnql5P%r|v#HZ+4~NNhau^0J{9W z`2Hv!*!a%i^EtoDH!l7lmf#H=ME5@d=DQIoNYnkVd&@DNq+~J>h|@8H#?QG1LjXT$ zc=>>+lS4jb#;0NizCxj|vtBYH3>ikhz;0MYsX4mo=KwNTSiOC<9#>Ft+>Fn6H$yfx zN|~*?9jhhPxim!1OwXE`wh#1@#T)jUgq0ZE7s9Tg-wFLxQKnu!%g8|*1jgSOg%m%(q?y0%R@?CqdiuwbAZFisnGK8|O_@k?i z%Vb46Wi|J?7PgdQKOA6&GFct=yUbK3x6j3zMOq#>fV2x^q{zH{f9RDo960SNUI$TC zz`EK!eY}93#3ew{5OYrnRN=ijm}7)$nOmogSKzQHCAev-h+W7u20-#@hCxfV0f{jI ziFHL@9!}5{6C&wb>(*wR6m}K{5mk!6JbpV4CbVAO4pAIgptnhntAzZUht-=jt!$!+ z=4Ui-gi?=Y(*a5m0@oXm(d4LBb|i@km+u#I;K>e@%CG30`8#zX?e{qe6`7)8`Wa5> zR&J5@OpC__W9;L2O5dxuG~v?O?_X_!4e8EB8N?dz>`7`MgLH+n+OmqSdi1KIgo-nd z!DAm1mDN^0zo!A;fd6$3<(zs4ONC?kM~wY*!P zp7rHs_8@6PXzn&BE*l4makZ*Izr&|q&t_lB2W#`hPbgzS6EgM@J`5AI7zS#9o{XhZ zF#!@w{bGm(%%J5_FQ0aG8Zr&|sttqmT?Y#WZ|LNyX*-sy!Ch0x~wNtPAL6E9b zp4z29i71g?kDcyT!6|-7ed_6{YI-xSs{fu+-7mw2IzpXvR%Dlqg^7owYy+r3D?!k; z(7&CGAsN1tol|Z1dNx67^Srz3fX3Dc(>l?gBcR*!0U~sVGldX;RF@h18gEH2`ItmP zLg9)ZFrUb_NK$gxnn2J)yACx#*X+BcM zd?+sS@A4{aiGn#)Qn%1I_PWTNc+H*4^e*@5XA!*d*BXBtR2mV>KA~v{CJWvaK43DL zb1J+%1Bo|T~6Xe;Yo3F!oYmx4i zNPmFxtX7WF@2u!{0O$++C(H>G0N?^8 zKFlfu7S2@kT}q-X!uu&(-~FVZ3xYHPqQ~|qK_>+&f%r>3>j%a-KCmnF?bh*Vyzv61%ULHWLFOV1nilO=+{|AzFgnt3a?$DNzhsw_!IcBk z2qBdy%XViHh3M2ilqt5N=& z{p$HpC%#FguQIft2H;MvFOkTOfP15R&4;ekUYx;u6nQgO9(?E#*N4F%9XaNNaCXq zp8%>I-cJ#~$INHF7`_@^raxD1O?|8S%2tF*0?(s?JotMKpwx^Q2LOhyHHHEJq;_ry z#}hdUuj8H;2PT$-#a_f=hUF{`vaxcj1t9C@4Hk~JYc;Om2@`zyX>Zy?3ve_uRT?6M zzlW8q2~t*N+#$$I-`9FG)-`XI;kws%0u|r9M8)*Ev^t!g+SlZIhh(76zKmPWN3Uj! zB|5J=hp4Ro?G}~3eDsoV#-jIOMD~yTm$%1Z2d-cKK>t~&O3Hd+*Hi3&4G4H5!WyeH zx}{{h^h=s=Iuk@F-62;&fQvY9Ib%Ed%_HP;Zob4=%Aw1jibxAsCE7!l^T%wuxLO>Z zqvK{-;e-DF)V*tSBS(@g$e*H5^JvqZCBQeWtj+2HbwfoJc}Ys$Gi$qPAOIFo0thw$ zlEt<){q{Y_Jv<^ZG7?CDD7Eg`*i5O41Ty2{kK@OW*UR~nqamXwjqr`KRXV#YpT}pz z=nf5*XV~c4xhyr01(bo+I0SKAd<#GVQr7(b~q?sbm6&Vn7<^k=5!ai6z{A^B;MF@afl1$Jn&zdzt-KWM<;QDCm@;B+71xg# zPa+B{-M@po_9JRvA0DoyZN{60YIU`_W;-}@ER;}I%hwdPxzc9IVSY+XYy<(7zRzYt zGY;O*6onpVGfZcRYD{qS(SJQ-1}d(Ah6A_-!x{MF&#vU|m1ZVA^hsWg{yEeWY<9}& zEh2};wp0noY`iSRbYAX%WB;?NTvQGQ+<|kXlM{)=%EJk|pp2RqW};^}ecSas0`DLxGEyYusVXChM5 z)_3GYMcQH~8Q6_2@Q7LFHVGc_B_iJl;~U74ZdOUAfVFfyl8;~Ds>A@7twU)X!uvLK z1ZzggiNJg^c8;e7|8p&D<<>sfZKL}KnM#Wu$Sxe0)+tu$R*F4~>P~_tEq%l2-eNiB*k&HR7XiPeyIj+9yT(^q1ef@B1bMnx zUKvL$t1bi=-&8y{9_F|*2uI)u|xBZtuIyFnE% zE@w9u+Zt1#OnFYuXiXkkTkVm6+lFSiiSDlMV-`6Ua4u2xFF#5(I|{-wxieO^7W%Zj zgU)GLevJ~tT0@TQVEj(D8<+McZLONJWV?8RvFsbI=%=@T>3q6=%j1$c@-Ng|6?W*y zXc==^!-{!>;Znowu{lgj#~+X z#j5#)Eb}KJ@zkz%?Ex}+1J*lGoW1!gZ`m^RR@W$eL?sgFX8@!m{J@U@96(FL=V3;S z2KOU|Vh;p~ZS6+2TZY3aLd#~tn%Aj6ffrTY88&$v*;7;IQ9B(awO7kL+7UVl4`J*x ztH#zx0h_D{OghqK_;u(ZvwQ4bZd#%3BmC~j&S#>YJmsmwdTvgo{B|-$DD@NKh6QBq z?$MT*+%ae2N|99ca3I?;*B=^#w%Hupm`;M*agI{kxkdtMi3fFfy3y8+O>N7=??El6q+CKPFQi2APmGUF zZ&%%tdw<9=5`9p#E&OMZc zjH>_b>$qr$yL{-Mp6dVqg(GuO-IZi@RqN=cY=P}ngVvztI6H!)NE(a@a1IU6N`WsB z7&mq1p&LHOr z$4U1bty2{4obdeX3~jNuEY4*dElMoZ31TkhG*2@j#t-=2 za>yazvov6f@@j z(?@i0uq_2|8H4UEElqn(4!M=cD6Kb&E313zdRN-U+u#$i^wetq4c}vbi-|QN;;yY4 z;;&1UO{gi>4I8OyDN=Ss%xO(>u`E|g?!5QW8wKXT3XQdcvt9Evwdr5Gx9|du>B+du z(BEE1lUh|HYwgNSWq%lla7#n|j-HPnz!q_B@5@t-Y}7^g53pn`$SJX=yA$4e%Mq)| zzw^Dz{#U)>H@b+~Hw6%^98x2fo?|p1ec3yj!wB}FCk*{R8#jzUJ-h_lK|6!&UC*Og ztx${QJ!l`nx)jqHCNId~y087A*iseI;jr`*%7RPprYk!5E?o;3YE~tWN_h1Uxu0^W zTL)7&b;gzRaeFVXR39_i(P~s(vbeE*Fu44PIVp@5R{@W0YEv5cRncA%^Ngo|eg9nx z+97)KxD4)4Y-4hl@12a^FdJNb7}a0?ER`A2K6P(EE##SXc2I!DLqpM0usGVEB)#`w(!4QJbIBLs%W}P`1KQ0owKTRVXjrDXw8ThJ64fcHn_rSk%DJ9BtZ?(5W}Rl z(%OoZYu**tYQ-aygT%af;#`D7@P{=F%cv@|`C=(|1iMsDclH-SdJ zLCwrv_TL+TEH!0UAQK@8#J73r>}DrZ6F#Nh)7LsXPxI0PF7;K5GsCHdQCt-)u}IuV z@R*$<@iELz?uJ{fBObGw#J#h4G`18msH0UJNs`@6nj9_QD`^2Xu4Lo0u&StinD3$= z;cg+)!pdiz&WOQ*FvhUMP>TngfBqsFqV) z4j*>VJAEbmOiDtbeYrQo&=HE6&0U@wj@d@%*V>D()RX?yap4E&MhSU|WG zBOkFGcr|m4DJWXglv1Aew6Q_KGAt`)l_|!{`oc+@VZBpC|3oT(j;x;VMw65F%&D?P z+!Ms9MxqGFowspOf@N5En~fP@zZp01Ibq$-m9}GU#g^2uvW?rx2MQ&3HxS`Q_F
tf?pi$!sYY!$O7!8qNdApVv7 z_d%kQMcr6@txO;hUhrq4s4b`~lo3G=I}g{8_*-GN~L zFdqSMVZMWH8hyT7aAcjkwKdt#GQ7jN1l7Xi{g9$(Y5j8$5stSYQ9QjKc{XKfdMzu)CSP)h-jLi&vN?AYw5jnMoAVcXNP!1<0psA){@5uUi($@2sb%V3QP~K_hSof%BZz;#>6~A~7!;;| zkQ<*efXM9k-~9(V+3p`neuM~eR7CqvRlV^Edn#G$eT|*0vRekAq8AR0|D%aC{){n9D%w(EWHaWEM!(3WSrOc#ZLFrFK^Gf9}4`Rw^wR;!-H&c(fldLHZ*R@ zY*XX7>~Nf~*~ph9;R{5BF>H;v(PD}@w$fR9kj2>dx$|z@dR^g6!aDp;L?Q1mgd-H; z3jh7~r?b;jKJfS7g+CjQ$n2I&sgAwIv)DDu6~iHIwK>ZVL$xOCNX9Xc;-5$?UjlHl z&NAl#Ir>uqkqGfiz+9u23Yd$tOUW)@gdI^xu4W2I&eC@1&M{N@et`K<94q$bwl|*R z#f6GYtmVx&f>{vY{Q2L|_~!rvU2KAI|?xsatr%th@6Ef0J8-t9a73 zg|ld{B~6j7lLzRZpvcBK_rr%CplQ++ z=l-+*@BfEOp6MgGibSFAhSnkyns?Y>a9A!@ z!5uZhy)J>puWKc)%Txvh;7k1-cvr4xR#-fCE9}c{UMctt2>2B2@v5hI-`ZQZQff|P(OHueOJ0K+zQ%@hlLh-;!hElk1y-P z-Q&P-9RIA+=?bug8nVb5)RJEG6yLL{csBg}IL5p{UU9karPj&=(w|&wWp3&)P|S*yP4-5jF)fG?;s|CI z?1{ct)sysJ$%b$=-PVa)Sx1TxRiMMi`|%Vr3H6}G@kafTs$Ca24&y5TzHaXHY$%>m zY~FZQ90Ns5+Bd#ztFkUX8US}XzVTj>Y7eNmIb)8|6!+BBnJ)6LTZ%^+3 z0Vdi(^Gi-hjv(59y1c=^Ce1bqyO^c|L%=^77E}65v-H{eQcjOfrw`%yi`oB01b(Cd zyV;;IL@t(0T&7LPx<&{=xs5=I-6h||LLe`6=>a#;BB3Pd zT~>MlGBY2}Ko=(%yz`scGHdd3cPw*%vLD*nzsKHoIJQL~zTPc|cOspz+gkI4wQ0G= z)2dd@vr$>Qa)2Hi93v7l9|R2;NvqyDd`cPyO{;}3eA&h(aupu4vg%R4mGx)VA0ynq zHGBoCmOimmW)Kf$9Rn!G7h>Lor16pvH=C7sWYj{QVDK;4;SkX_d(Vp%R0jBy+|=We z6s8!T@q(Aozu?6=JVZgd)9>BvAZ^Rg<&rPq)yVbr4(gN%ao z1TwkxdrWc=aRVgHe3 zhqAkIK4|pS0&tv%(y?5t$w{tVDWnDi*kWqO7{KH!5V6vxu1p#0^i(=%(w}^qjs~K^ z{QY+u{F1&sOcRo`vskRaj%UI;vXwLJIX%c z_%0IY5SRjA`ig^qe&Av(t)}`smiVyS(Xe3RH^qZcR4R;bP(r~HadN4j01CH2WR4|3 z5xn>|x6Iu@i6D^~iyzEUqc*vk8LBVLPaVjD!^EY{cn?(4L1EPm2cM0>+b5)&J6~j{;GMu^}s&vwKay2Th27d9Ydc`Muryk zW9uWuc9!scQlj=spqOrJEUyB8SwVwVkq>>Mz-j@!9@eMRnT$MhFUJCTO~hZvBZ6J5 zp>3;O*f^Tae<7^qaOP;z#+yhU0Ke+M_esDSODgT~QRL}{YtH|zGb>XawPAlJ{s>=LL5&?cs zv`m>xQE%bd<`y?8KfLgm8nTlx{w#vZeH`r}&7z|t<3kQ1nB@85X*fJjS@CwbnxNQb z4-_s~{_5bL;D5o<%e^OqrJ~=~jS5*__We*9FWD*(F}-c%pYiT&;R5;C30BnQZIDzz zz(wi_64D-;-=u5#ezNJa*WCeh#P_Lc@16}J^L&LMb*0q*m354VBiQ)HnCD^+eqI-eU+;VQ8`^Ap)c@(~rxMw!w8MwYiEEdJnh;IG7z2!GdtXJ+8H9`;!}YhF5B{WvEOGLd^;3Z*M$A`v6cCO`y<~QkFg`0e_*k zOY$(f1U$2pCw_SZ)X1eXe5(~LcS2OsZm`I-F<32fqs*jIKfP(WU@-(GynRA5JUwME z16y`5mJ0umm)WS4xDpscp%II-P&zT~4wm|Pw77e-xZQ*J+T$&F=c;|ZbZM@ z%y&KpW{k_>D}L>YXm`#uzWFuS)=3f;SyhA1~cR9t6P_+$VwgvO9k; zV<$Y$$A`IsU^({Qq>jC}gp#UEkL3*qZX%}hby#0^+WQ-YSWCD>(E-cAW&KV+b-36S zMVsnZ1nksGHw|`~I&Y+=Odbho0v42ROzvYQ(!E(`G;Y8*DH{!b%Bs4?$LIRnlF4T9 z#LqYc6x)=Dn-3XJ2G?lSIfRVc2G|CVE_=VTn8@rH%BdXPPG`@(*`Tgp*204I@JRLDoZLpGO|0XX7dqoVU_^6r)`rc?jBNq7C?h3c30n)EI*R@XF5YWaj)4X;JMD z2IotDz-9LEL%C@u$Qs!1f3?^V!Zg-AHjm$cxFX&p19S%_FR>kjH&rutDf4vi2M6z#Q8@$bJ| z2Y!#FqALuQgXbBF9dI9*2C0y^nyZlg)jPBLW%NgQ9dP;N$A|^=c%l!_|!h(<< z==xZ>_FzH}^(UEO?H98Np!D29b2-hawU4@(BD|BdQk#vVkUt?3)BvO<#qdrnQ*FfA z?O7$3&9NL!I$cZYw|@d02G0h-m?xd_kjN53P+uq|CW9Vly%;SJzQ(YH5V7Ao`b^#!Y7kxrD?#^Gf)}8~J z%LR0BA6x+)i@H{S_T&t~T~g9=57(GVe=86g4qFvGzwOw>R?t@YjxkEGWyuPuQP7k5 z&YKLd(dS?SjN*OIa6;Uj(q3Q&-j8Pe$H}}u8{G^Cm%YL0QN|MCy&4`X?KP7`p}G<> zpGMH2%u{_`2Dg0uibtqow1Jw&CrqI1=akm;iteH&Se-GUSPT+)QF&r$ZbS0fPb!L% zik3#_W`-&3mo;4uU~W{jJ(!L4Ju!9?W^5hPN-$bygVWiD?9XX3)p9LRdaYhbozZl6Ejy2RT4mCJUd zlgUqA^hWo?8N_m+oiGGwgS~j3B6S`1jCQG9s@7g<)}?M)95tqM$y&QKN%$y8Z`cM` zuK7z^u~NQB)%x6okp@kUVQ8bMKdKR9$t51TjQ>g%WM~6W0_H)QN@$0CTne&FHTnVU z*@#OS1)$^xbm3`CQ}7%^8g^VjG{j*LSBezO9R2dLQ^3AzL77@;9EMejnJK^51yhZ^ zw*y^r-kXTs6HfkrL8feg(If<9Nb9k?SO+dcevs;eC`#+erIzhJ3&&tJfBC}St`GMI zHTAJgVtrQkSW1c;HjGppp9aukkhBb-gs6*ZwYhM5Hu`o;Q`SLyNZVaSwv)K!8DRe$ z2qx>ZgB@N*BK;`)Gk|#jqt`YmV=%Ktv!KyAhv@>jb@(*u%T{NMcQ2Bi@1^01m{jS) zJLaYn%VxipoB$573j>3=*Lomo&wut=S-D>cHdA@!~e{yAxOjSM2?f>E_ovtdmWTC0?CNO zzB)fLovirTEJTg3*dZ zEb4duD%q2ZMq}iLW7b;L@YJ=t0x}=6V+h;Sf(&~I-t;drJ+PgN>tg30k5eb9#zqEL_?)Qe{g;wWV8x{!ne#cI$J$ zZyohoA%{(x%LSAJadJCcK#G@xI4*y=yW{?sAOKlDQ=(Zpv2-%-4A8|>uAuChgr``E zeU@YnuYiW4vzrphb&Q(~9tw9%6&tmKmBTbGVd`19(T$s2Y3lsjIG`1FnNCE2soP%QF=&e0$0B&EI~07$@^`U`oq^+) zZgpw$Iap=AYT92?RcC7@^amqjuRq0^y$z=d4FKzN{E~Z;vuz(YVcoPhJo#Y5_8y zb?`5VeTkY>zW5g5$s!4`vvP!aY-TPjT*Tw=xOx)SW_g?3{BjNx5wHt6)n z$k&2QSgl$reoh=s6xLdD(Z^bSy%#{}cbX^8;27PXH?1E(5kj?|uNzWHIi&Odl5*Zh)h;Q&xu= zxdCgpe7kW11wy5uf!FE@hM*othX zO8^MroCVuTW%le9;|U2L$N%l`$tsx#{-{6)4|c?=C7+P4)&EQxYiFb$I16^PUb7JZ z(qIUyWdmAZu|)V+oQqI8D0+Q3)p_?*g?Cs|8(B()@X4>i^%--Q4Wy7PBOkI%imf-1 zxpTZhl-?;(b%CqKWM&`flY4rp=eS&@=E&71cg-7^p7E7n8`Mk-f0pl$Zdxl!&cJ(b ziyYyzr~2C-2W;u87+`eUkgl9O#Q_ZqUKOH4*s5A@v_qX(m4#r01ffLk?)q+;0jwKA zebJx5ZwaPT#?YFunP>~yR}5s2p3hxXszL6lnnMP9mIUp_b>R;LG1+Dw)p%r})RG?` z9>A%-ff@?>OtA8qFr!8!>5_1yu3L&@VGL&(CW(Rvi;uG9EF3wmC`%qD0((0j4u3`P zdxK6G=I+c>*LzX6O zMR9}$jwW%#LdXr&)>A&dK4=K3(|4|{PxJOUyg-ymF%b4&6Qxqv12xMfA@bhm&&aIi zqo<*CoAkkn>Rw!IGz;Vc(;)=if|!ce)#(0xivO9<_zy?83vLS^ref&3*I0jT_tzhx z{JKwGbR=H*=l4Yy!!Yd^Ivkj%oi$eqwrP?6Y}cZt}%n8JiR$u^ainV**;|MigY%;rkV&QQTEuEJXG~4Gu}-EnBq6(I+mjdh^OZ zj>o5`E(mh6+a-Qcrohmg|Dv}<6JqfC9_EWNu8>+c-Z~%qRG-`c0`VqQWsrUlWogGPS!0&OBL-=tcO^-*w6*y3+Li? zHc&I=vQ-eDJlKl0A6$ z8Uiph0@vgfo>cq)$=ILZ8QW+CPHM1%6(ifjglgK|>`}5D(^cK&xS+GA=oNFc4h~T& zM)7vqKRGF$Zl59Oa_~YiZThivOIKnl9N}G@D5Gs0ZTo;QOU|btIC9 z>>5{xh~i4|Sz0xg4t!&Qsq2!y8swoC7?&2U5{ngRBZ{sxpWuv9@T!oxv3~df{w^tP zPCC6$MxLhv2~;hNoAY&ULw($$KBPrd^^?wcKNrn^Y#Ws-`j=wotaJU>w`axqyQ}NB@6TX( zt!|IvJS8AOVd~%UH9qFR-xC0=KS>6v3Wx+w#iRkOLvPIjp^_7y!!t0KNIF;{nLW1EqW7M8@D!Z#~* zoXSOR?eXIHJN3RzGQR=B*)G6Ix#e%yxBP|3kD-`g=&k_9I6VKrY+qaoI!Q!PI$aJo zS`BFNrm^@@7F2Y>gGq5$k9oR98=R)rVQA6x*XqM4?T|1#kV{DT-^DeNQ}+ zu~~ofsS3JU_~X&tNj9Y)8Mbw&k)y|WY2{Oh2+O-vjsJm`Uro1IHMT8k9b@WKY!WtS~Xz4ng9Z}*>+F9rLN&$9DZ-~b#W0J*p8b9qADdm^Wi-LP(7|@<{xkDo5@Db zYQN#)kK*ts7YJoyypC7sgUk*OGT!PHA(RWCGLCAa$`mxn1F?XRyG^HuPgtDz246jb z+slI*S4KAFykU_mz`zoT(8(k{Ylt26rS}kx=Nl`nKn&P`-c)M*EhXkjCkLY)$DVUw zyen_*1|f}fM)XJ9*dS@wYDv=@2x<%T@{qZYs?|<9Q&ba`0F16y1dpRJq05ae`kfJR00YA0# zTfbQl)BF7G#3*S^E2RmSCm9-VsrB&f7|Dkt)lVrxj+eIC6 z%r%XiP9`;28V54~CeeY1q6mWD_*O&BldZ93<-rL4On0^}mR}M?^7UBJvs#`y2r~iU zGJ}G)+n-9Ce9;~l*M1$-ZRaANDe*K>Az1Pkm@Grq$D;`cRz53nOAH21YwCYrDl(lL zXP&FjD&NQ{I8g#2z(AA_DCsafbQtZF9QF50sxd6|z|Er6N?cWEFA{}u5Mg&ms>+aw4qDjPD zonTtUrB%nZn*dX|D!GXX?hA`9#A_B%3Tg7eUSp49`fL4yvkTK%v)^*M61-QAY{dao z=xz5(<@S!rl9VgkT+OsMB5TVPb=`$k+>-4Hz-Vx$c$N+&hQ$B>bW@dL@GLxm* zCOf+C&unl=0T&;@5TqG2ZsN zL5EKo7=47e&in=9o5h`zD#q9X>tv{e1?GEvu;5sE2F#j?cdZxJ`(F_yT;3A|YKc`$ zwkKC9vW?IE`F(%#VEgVOO_L5gz}SVJ8zx_qB4shwpy)sdtO8%933&ywilT>Y+I>Mp z;ZALH{AQ1V>-*D}z1av#=#R<23>*wNA)*xB%SH^04w_GMire56DlO0>l+o*FQI%8@ zHx-)j0Vl(AJTn7TK6F=aQ?<6XtiFNe>tO_r1xWTEkqe4+P~ac`w@ZmC>JaTCVpfDkP?7Y7reb>Y1sOhAGZ;@@o;^dd^e9dwPWhn&yS#K6t~V@0AO5{b1QDU{$yzhVodn$%7}- zWDwC285gdezrEwv82JO1#cMGH-lon=||Z z?mh;cRyegLo+l&yp7QKIe~)SpWNX)Bri7N-IDfHe1RmHz<%puGqMOK##r@>}=#yIz zw+;rhhBOE$#Kb(JD^-5HBIkMnE)Z^F6vwt&qHm;1D96SX+K93Ss+Tshb)WH^=n;ec zddAvZLdk_mIz3G&w(u)f1=KR{0~>*LPiKD&92^;QMa5mU_J#B`d;kj>%3~PPOu$vY z-{QDLDW%r*w)P?x1bnmB0Oar*!%8mq#L5pWd{n^bq29JCw%NAg$AVS|bT#)y_qk`Bp?2P-E~?ShaNOtYgJ-U`H&r5+0IM9YwB6 z?WHct;r$c}4hv8XX#9`)y3!-5D@X!id>yIT*V+wp;Z{^Mjg+NmD>gAj!cd9IQ z=|E2q18^HhnffX^+vqd=h*ctNHH z2%Cd^c1JMK6Oz!AQWWd(d9O6Jlodhm& z^*bt^p~oYv;%h?yT3PNyTx)lO&A;-g)rZ;UP5tZ;U4hq0s=Jv=w;i>95 zt!)3gdAt>;sY|kEc{nftaYtjRHw`8QwQa&Agwh6{R*Pq~CZg8pzTeks9LU4br>y@f zR-Q@1-k18p%`Y#!CkmSu)7fA++ksrVkFs8uFeM^AHp3U+nB`J!a)!(Ft3yY>!r<^n z#EJtjXPg~P4d2(e1kf8p8F;|BN^}TCeo!_M3LBs~Kzk4Ld?u?1;@J2&N56JH-pZv7 zuwT43d~5u!XNxmzV+i;ocHI3tCo|#SZB8?*ef%f*1$;4ZM+9Mbn0NRu{k6sM)XDp4 zEZOn@cJ(8_(f#E4)yL9*$-n)8PdU?%=N~_XKVF1CUdkUC>_J(Ck|SIux1z}zgPS{` zp&DX#MCC|{nKe_9TO%SdEJv4Y3vOg76Ag99K+e}?+%2jyx zk}IoI5n~w@eK*So{xVs^Pd)6oDTQlIztU<+CR?48fIZ)N7(aeS$B~|*2$iT{ySNRP zHy~dPhf>|oGCblkonR8UC(&n0bEoJ$O7HgLEzF7w^cob^lT2p)$%?_HrtiY-S`h=v zl+35zSOF00Wl`1{T0qV)vqlY5h>3D{7-znbxOhlWbB$gwRr+P?W><~%zjd~<)9^^H zKO_NsIuj>HZ2h9?g{6)-dJu(zPtkEFz405!g%2@$mf(So>Jq3}LE`v)Nl4`jE7gDb z^S_loB^T*KkS^6Qv+71b6zp%@bX=-smnY+@tlh^dp8#?k9T}l5^KTfb=~>1S>^>c3ggA7~}(hEvhaw2Dk&c2#b{!2EjffgdbvRe3%d( z3~NJ*9c@U7-(`hd;{1Jt$_w~+%}Lp~Xv2%cu`3(%t6GdsCD#a`A;P^z_(x$VeoSs8 z^mC{G^lZW0c8t8d57|tJg^WKHJ{ilf$|6n%DsPg(Es|i zMFD{N%#J^Pg?T*!%5o_r7OPCcj9h7g5XG^Z(P5U;-X$Jn;6@X=@#W74Vtz3keqiAS z;0A5MF^9NxP2LxP18j)V#!rZ}#MShw4?_{+Rx8$x@r@3T?qlvUM_j)858DB|++!m9`}Sz$4HdLll|SXRw@1I*oY z(rfTzo4{%oOS8`|e|2dcnxxpT8I+8y{TyG@jt3L73GnKzPW2hnL zDj^O?V~-uJYMS=NU*zg~tpgAOK1?40m;ON6k%fg(##FPX$)@`bSM-S4Z+??^z%_kB z?Lht1_Ex^J*bJjjj^r}?zr9CjPFY~L#b7pl5J)N8FarE}+bgt2zT;Quxi1m%V&@hq z++2MY&e+-jy*F&@16~Jf&}b2{@_!&KQwRKa1^AbL7kIx_0sjHXhky3y{~5q~{oNS- z=MQ#(=j*>+{mid*|8;)#OXt1Si%Ib^=t+ek3cC|1)Fb~PvCX%e2n__@U*~$j?4(7YFNpbP zREb48E3$wLrIe1|+9k#5uQ*@h;V}%*1$6Qz2qiXgrkLkp3+4cPRA#n)sn#gqa*J1^ z-iR}b`=UQbKs>}SJ1yL62oiNnrR5n_>krFi(wJ%IS0)rKdEI1s9lq6vnVk}ny^+eeK0G~{6?|!PV zX!r||-dK*40Q{3P`co0%1Unh{+2yT2tB8;1%^Z0i;>kpB1nemlLmouzv1TC@X) z{B1P|Zmi%5zBBn*&p|bu8FgxG5DH!J?|q;qQIlXFK{wq0<3@Z!Z_r@Q8$Z3KhAO<3 zLr%v)PTjzhT8w>JnHmf6Q-Nri6Hz{6dMq(^JgByJcyAn#bcNPiQALNs;D{ksH+dX8 zzgThA{ruFN^vEqdKrdqs57@z1bkD{uuQaWGH*aSA>TlvsC}FvGG?!Lww&tS9p<}4= zCraRYx-Nhik2gD*tJ-F7_=*0&F{ktO#`896N9Ccvm_;|n37pMF!x_|k%l{}SF*lB} z^R@$y*LfHLo&Q1-0t;nc!!k%%)`2xL8i!P5J!O@OPIay#8T9Tj%CxKwz~0M`*QB=K zK!Wcaom^;=Uo%H_rz8y+hY$%PtxvZDfU0i{bTSAzHZnzAyPL_d*NCuhD#88^Z>AFL zU>W$$9*75=6<6XSj zC<#_>6s+?T_3~X6*f_7}>PqIQ92TdiklGm+QcC~xzx~c2lbGNXWfBy6d!DCpg6=e> z%=@`J8zIps!J>U|F5KplEQq^db{JDp&=}snWS7|Bfq&nuA{MHQjUZ~gj=Sb-Nzj<9 zlZdMnKw{)h%TeUmD|Oeq|2!-xMbo)_CcUl9Tg4@C?o_KrMt%T)It&c6G&9CpbKBXJ zC)8|UxTH5%9MQb&#L5C#5U(9VRxjNoAkhMABx6OJ@1?9Xz%4Cz4{>78W#M?1=o*&_ zO2?L8PzKZuesR%zys8^Lvb`^?@ESPkYRMJ8ZAQZ?TU&z|cTTWyzJgj3rh!ET%1TCb zti=iR%v6cjV#U|GI&i>vv8sW>=@kQu*WR92pl9T zj69z0Hoi3ehe*yDEc_YrS92#rA`ewn1_9SD^Ou&~2V^P8{$+kV{~4iDU1qdY#>DNv zLwnz+-qYwa`csjoXe5N5G8A4o-<8%Y2Iz8x((+ftbQITG9qBA${#9@Gay^B1hbbY9 zZXHEY-g9F~7B<9T2-w868|7L^zMOs8_3^OS9T3fm^0RHlMiik$VCj`75pT=F{r?}R;p z!j)0v_)xU=%$*33(iJioiXl!@M#tj$R@l<%tH8s*BbPaZmR5#*m9oHa@_;5W`6xXa zxkM6ciZg_^sEDBGlGi?p6=v}*zP;(}V{Ea+@|8eon|`5jwt#X{v4MbgSOxM#9Z@{x`}kYao*( zQL)-k*vBP0kT(_OPYK1aI67$O1qLfwKIOwnmL?1jfq5 z{f%zNlep;%bsI2CA@gO~FL4iz3nM`rqrWALrZ8`3g(;V?CR$Nm$BO1CzA36A<;xx6 z`OJFMMLEl~_)6VF;^^v&rdWXl&dx1dWM?Zi%Y(>9v4G-9R!7i)np_S09T~tEelLI8 zd7$VGP3;LyZ6nYHCEie+Qs7b%GY$e7JM(m6q*FVF@JwZVnmgzr^2N(AsZ`}*woXrjdIFNG|A@uq&M5nGiFa17X>dp6o7n3OqrGKCY9Vp$wQopKUFs%=K~S<+Y8@ z92(rnIeW{*(I1<6PXx_*mE+A9Jt-_qo7c5ILOvzsA$x;34z1u$!a zij#-O`5kt$|7%CWiX5fmrK(d8;=u&=+}HXuO$TGsYyz#ZGscn3-~tuq1%^{5jXgRZ z-Mah#yhDIfF+5n)k6`RavJ{B+8)hCIAQ%=CB-=*So|eCL17qMp%L`B;-r?CrNCg)8NAPE0=}}&A+J7c| z1=B*<^uxnB*crOJ<}ocw%`J;`QsVd#jjZdK$3N-^)Xt{84Jh?$9}IPo)K0gdm+J8163cniNhjv-^LVaTl}x{dd8-uWtj<8z)>%D5Jo; z?-!oy`FetfHR#)Av$N!ySz;wr9N*uKTPmZT&Hkl6f6zGzI^^z$HuhgAoGtBxwTuLB zUrjX_p6iu)4c;v|9Y{NAowa63W&fa z>4e!gw&690*(+pL>|_G|QC6xZIyN#7L)JP9z@hpFSicZ6a_{gvHI_6J>B5d8|JAAA zRBjNc7GIhk{yS(CQhe%R*jFLQfjfcQTiZNTS*dp8?5B5!*(z#w2!t`}&Xz8KGiFp| z7Ii1aT(C~nk#Md-&cY2dO)fF?Xp>$OTj}+>j!PfHJw6G8;+Zt5I0p76b7(A0Umqt} zUo1!hvht&KQ4!)mdKpUZy45jd@cwh}^N<=aqUtIsZ|~m4C*Obf@Bi1o+yD8me@Cu? zvg#ex-gE|Bk#;m?BMB@9Yajsuhj7d2A5x%YerySs(vI>&on8F2@l5BM1TvFEWaro- zS$EfK&Dc^XYAR8xr>-2(#g$xF-q*}pVaiwNNvsl+5reOq5LlaF3L2bE7sVs2pouHV z^R9zuZ8V=NY8`>Oz(ohIqW91NE+>cgPFrttpKw{bb_>+@)insE$9F=X9?0Olk60A7U&^)>5S?O)6foV(!}6gPKCpdh)mEN^y@+7ii(lv8D}?!%x5$ z4vK5^dQ<`=8oC&X$k=T$hmEz2h&aH0!T|rq30lSH$KK4@uwaW{dx6&|1D2(qd)-^2 zB2POh;_1pqMzSsA?;Jr+AqegGHe{YVJ7G5ca~6L`phvZh^D$fj0^*zQ5wO}3%B zr4&SL@w(J&AeW#Fc#QRPr;cdQt~}+2BUR3K4*Ju~ZX?X^`|k!K)8P;3^5fC(ps9}~ z;<#r{#n}Axf^fjMxh0hZnbCEcA%o0VhpLMASmLR?j#0L*=%a*9cDyE2Ez4jBn*XL) zd>N5mzK^eZA8Aq`S)k@5ps+U|4~K3D+c!B5h`HVjQ`IDJ61dVpuGw>)fS)BKxx#tFq(jf6*A35Bh){|1f#1y77P9z%?Ixmo_;MH z&p)=YtFs!OAP(U6+6A@cu_K&|Y7yqh(y)$T;&B9}4QwQ{FpS6UE+>O)Bx{v(*ql-W z&KCwP_-G&L{=rxo3F+BwP!r2+h_hQu{J(&jEiLckCq0QB45%Ri9INlYk?>7bjFSS^ ztGrlU{`WDCngeMxa8*{t8c1{yYmm7-{7eNmYs-#XDzdoXhf%$+Sk}4U@kLcu-cFPk z^wa#a#Kuz)9XPht7EsH&nz5HC)PKgvTu-+ax8^1 zt<b6W#RG0C6ZOl6yNu1s~rTxLoyIK}Ce8HWyLH#o+Po0OQrxO&I38%@E)5>Od;H%CiXKF&}Hzy-E zlg?O!t&@JP+5&+-I7@)AjDQs@N6fM`l%rMu1$MzEkDs2N^<*pSV;Wya>5qeF zea{KG`gU*ENsZtUub_)Y*3M#x0y+dp@Pvnj&D_N~O0M&WolDMYrvC;8L1+ih69}Sr zFymjc?A56lWKqG1Fv3p5b@45`#Th!0u~i&E>I%9!(;=VWi%58}?PD2qipQ?W4l>O^ z0VY-N?j{G3B?|A!Smb83AkrNEYgqa(;a-Jvxg^5D#HxZih|Uz+fe1y1hBN4Rnl=tK zSJgRT9=Z5w)YByq2S**vf}{ConaMEoiBjk=f^iB>RK@eG_kf^ZgYsCem@aa8$$yjB z2p0o8toA)3XkR}*V91Ni;5eJ?c7D9zWmI2)%S4e3sUww3<=QmnKCDgMC_mG(RpdUg zmbZ`Q=lwfUt7HRI{v z>1ibY-j@XJ!nu$K1_609r-~YPy0N*j=wO4fSsSn!QZt4p{%f%#6G?x57{DoXrM#@i zGdAvSnzy4_BjaA&sn{Y(VBP*%fB&ds|K|_|zX252)gahXt-vqn7zGy(^HxH5(Mm)p zR(zI|khN>ps*b2ihpl4+pMnUTOEzMtZhkkNExvoigb%_r-!XeA;dS>zin%<&=-~&P zB`mk78+oCo>1+Pn!&E70`U;VCPEciXHrek$Ly9tBP+I(z%%&X;H!~&3HPma|Q>RyY z3VlKF|GtuX$sduM>A_Va0(S9O(0S>51=K?!-4ENNfo2Q-Vw6{1Wf~nNJ22{xRxHm}oouDMG1uA#!wv$~Q>Tj-KALT+5#9t32+HiI3 z>cl*dy4hTZ3ZGbr66$WRjU*bgm@}l>N(g$<4%4Hi`!*j|3pjA% zZ>pyf`QGi)K4IOQ8q1!o)4`&!gQP_+1?41sVBvPE)=w<^G=^T|(PXqh&x8`|Z$~p^ zdQ%fJG;?QmJ$GK1_0it3*p;S_^{l{$vo%;sJBulXIq+6+;UY`AtPB13Ak3TS1$b#ZKaom^rB;HzccaSYJBG5x?q3xvN;Q{@a*D7corj?oJ~ z-z(Zj6}NYinRs=OtqGe(ql*rmvu!&+)Q5z^!qgv^{0M9!+&XFyP&62!1>3csyWh|& zYU&Nd#;wYMAAKAeisGaw(Q3z5&j$+Y1E?+?PL^cZm{4F=2)ZZySJEDfmyS2}x4s>N{x`u%s+F=P$i=3ht5Z_^c*bN;==;q_{wjnyZm*5L@BJE$<0~BRkGt9+|3JGr6h7=U^ zYfnfZJQ=3HI2PU;tcpy}VK0g!aZ71@{n_Wjt>k1)8<1{+cm26NriEsd)N#`Yzz~`A zX1}7T1m*i7Fr%wt1o`jj7&-V5xd#kfPy<(s_6K7#q{E^CE?6nrV3aO%m5sxa+PqUe zOKBhmV&}C2FE?Jo@J_p=8^H!H4~_Ix7Ly0Y^?dW(s7T2#Huwul7E4;t8kp>67kv<^& zc8_zIbq=Z4Ocis>3WSNS!k9O3>Q{~Yh~tsui0C}i!qD@c*r6%vDluz4nf$BY_) z0$XU5hT8$p9V!u~AfXF39s?JWP}QtxlpXzm#VW_R#A$nf@#ZCbI0n^{X@pKr*=_qYx!X`=jgy_^v1_4sREe z>D-l(U)S`d{*9k0RD=lBz(!W|kUq@okK(dYD6VPOQ;1W`^xQcdpoV~)_}okUc^EWh>?8Fhku3zXV}E{pxI3UH#WL;vrDit8&{S>_Y8{9{En!u zM5ge5-^&irl7#+_wEAZzL8w5h*`BRdJkddxs5aPr#y6Mpq-Q?qv$&e($++&s+-0y|E_1YzC zJcPkhWtO!EQSpxp72T|w%Wr{`LDk`n{?IW^J@vTNoaZ3pJ&buCEVCaYv%wkbKjGZx z4$}yce`h%#q?+rWgrYbC*DsqpD1zwTuqOH?}4$Hcs== zDHa%p*NUub38>S8ECQ`&u^8*Iv9_Q{*Q8lCqP8WHHY(XzdZgF7u*PgpRe@Fg)Sn*5 z3qz|njwXR<*RqsIH#q)v2+qWG;<0f)EnukQV4znqk{+9A=e2_xUUQJ7wv{w#Nc-yQMXnLUu5&{q(O`uO!cWG&BSESG% zH*3KSnvnkN<_fMJfEEe2N2mw;=2(|VZM^P-B^P+$;~JZln8Nfg9eaaleUerUiI(BJ zguSZD5mtK441RH*@C>mQOvM>B4|P&hr;VpEDb?uPa)8F>yWy5I9In@1rN%9N0+c#x z9E)Uiy5SIKrlNT2b1d!fjyHQNoNolxp)Sl|>Qbr3$TqvBsSC}QOi)BRn$)M5#bu~o z8r1w@JEvMAi5(h1(Ksc`RkI|u89PF#K7TVV7)l(X+$FG|oI-Ae@JX71RF`o9LJ_6t z34yTtX=UwXX;;6shN+m*F?4MpGBkC)OwDMOuE4XZn2PxjtC;F zgZPM_A$rbs7&|^2mK^83iVo_mw^!h7%?ztmO@hJ6zH?J=#_+U>4SAQfAy_SU1NVx! z5t7A4_+U`y>~Hz=-+k#8x0{) zRei86EmO(qWBdKb22LQqZ^=tkC+sAT?1bQ>k66}svx%31cNRg%ys9hSDjCK5I^*B~ zj+B721_&6{G2H? zjdia(;Hy}?nnR2-cH0ym0VPd#9;Hv#%`+wQfx{qoemFb-ThaOSfkjvooLj#8LV)E_ z3=C1|o@ja~+ZWF_wtORN9-?kC1O}A;jxNuEUY^a6+fv$Xer`S1RcluUtzmjGRF;GQ z!hP^@N^?prLqoQ22(NN}hy3SPQu}Ywis!d8p^I~wL7j3@Zlq3p)uwq7noJtMYBLmdW!Fd&!KbG zu>xaON2ZtdPfn)5g=4KqjH8z0@}taejM*(x*y~(U?*4>KNYYG(`_cvm7fmqSv1mAR zZFCFYi7NkW)_dU?IsLh4m>i~jE14kxaGPYLYt_rr~9~_ zW0S4x`@86Nr_6rZ4Wfz%qN#|b_J(i0x&e4@5G~Tiedqf&i8FlCt-7qOgDE(R=%O;2 zqdk!RodJ&gT@v+~``SqS5s}Ujc}-weGn}UwsPuE|5ZO1o-k54@Yko4&pI$QzfXkNy zW)NAhQD$;8Bh%vXzBhX*ZXfT#R+`>dSgt0ZDVj2;r&?h$Wzj!oe-SgN=WIxQ2=!}2fJnkhAQfFgZ}e@lc=rB^w(;w zZ$;v0F2SJY7|u=Ty>=<7#hz)xu>^MVI$`Kfq;DERqTw1%%x~$V_@?zCaV-I*e!xw% zm1gX6hmH{}?Kzbn4*RCzWl^JXNjTkguU#zkYW_)KA6@bsLG_sTkv50k+SjNfQ7N~G zTk>iFdlYp!2%#CN8rB&qYka>dLdn2#`KmADnpu~Gm)y@~ZrKlrmN|~iGGWtl`H|b{ z>>0y%XpqOw4#K~eH1S%UADLztv0)(dX33jM5>@zg+&V0lC3|+co1PqmnPHTRuLa<{ zGiCsdp=1!SdBL|laUbfP^{PNkX~|@DG9g3YC}~;e>EgPufKRB0VDG9yskywhw~X+# z45+zyzWDe|><86ZSj4%A4RAqgJ~5NJ<1k|UWmK=D%wES3R;2Ho+CIuD(ja1}%G6kB zok>StBAL+_THDERg6Z_oQh+juF2uU~95oyyneB_ueb76U{k9FPTS?pIbH8s>6I8+; z_GSL26%QPCtj^<$@gvkC&X6MvXMY`zp?zr&E*i)Cs8kl+vk_#$mM3&j>xpN*(za(7 z@ta#QK@&0?yyjS>QpZ6hu^Rj$p`$wHG~|GaUOR5n5yPqW-*j2fa}xv!_U@;kKrXTU zA9K-bYgf`WX+A13Zv$Z9IJBm)fekq+-hr4RA!A`~3x8cj&~IL0?GsUOu`mJw>lz%X zAkMsX;*@b*o4_p^iiXTg%g06^q~6{Q;`G9GZKjpZp0n5*w?&_o@KjAs^YZ!fo{;4QP{*G5DEM z@>;29iP=>V8yEHvzYBvr@BxVjT~nu)dHWr%0rVl1MhT<0aVZ=h0sp%~b7y8D8!m4A zzP>>oDIt!lDi}n^B*}-L*$wxE);rNz<~eZzwF}xdQsWVv8|#36A);04a`MTF1sa>? zStlHI{h*ae>(2iCbG=1&;n17u6_i2}@w=OZ~EmJ`!8cybuN;#0-&R*mx9 z)U>j(Qk0YCPL?eODuq$wZwDPLLQlZAZT&i$|L}WeW-qWAfDlIlP;9y7QNB<^fWY<*Z)lDH3vZFpgBZ2 z5N$Dhu>f!fm>`A-B7c*qHcv3evdz@0B)k}RfIPX{=1&xq6~w3{pJSZJjGXQ+%L4M+ zsDa`-lmi2}!|Y(3aIWnRH-HXz)WUm&CjJ+LhA)@Ap^-4nQWO|>kNa0ZCu@jUsZ`2Iv z0}=?b3e1VSKI75Nj2JX=8GJolGh`|es}F?9(;L5W#X&`UL-HH__x3C_GDVb)7Mx^K z`h1&%1MgelaiM*tL&;;3_D1*Ff@<9A#*ApJ(m7OqYA`FBVr)nKv6G@8B%l8YaPf`4 zuDdx|7&^1H_Rt%>F~tP|V>4BhVMo|-qiTjMd81FZ$HH1RmYrEL;nNRGNL@-CL#q#6 zS{h}M@Ep&ii(G>OWnn-#JBk6jk#eh?G#bqW)M98mDITt*;^lTWP1YeSy$f*4qvMSN zp>L^vVy%Y=kc2^4p%I#Kr~hz}GrB7y?YC#x4M(}EIKjKl0koMOw6Aw%JiP)-3?3ZI z&3J?fV#j)Uy_R-jid%c8vj7RR#hnF5b{y6#F^L5@=81x2?Qj zi(U3DaG$jMbz%_*eJVhv51te^GLgE3gAg)@7pH7FdWCwkIs6hrHh;xz8In(1)~j#$ zj`kW^Z|1+igdnFX&@!@=ijQ^OIL99?$?(~)av&^q8IrV9T#VtIRM`2=o`?L)m!>UK zO?Y4Q)NHc&y*Y6JdTY&tT>w&L(I%u>4KN<>(GW0b>(>XxMEwxgzG86#K*I(?J-{Y- z5s}(TT?eO>q1cFCQ>Tg2Mrgyx1yaQ$zYkT<`QmWD za8m(Y6V4_sZh#5Q6dl)YsAcsK%h)!0d~}U#B&MU8oJn*0l8$(}$9ygWk6v@kvt$L< zKx)w~i6jmpaElhLB#mUNkPUaEs%Bj}lBbolu-y zR|BpN?|O*^$KABE;&zsP8GRhhnx*iaX^?~=a4u>9QJjLdUUA(~+O{Ti2h($TUA+AO zCN5K0wGhi%_HzeXCwk&8szm+L4cNs7Xa#I;%Wvno<{l!>VNdG@Ra|+c4Sb9QIs2Tn zhLZCPGo)u|BJ*bybgKJDZU86RB$()%%^3qw`-b(q zkl~@1Ls3e9C1*wuANBpOaU-jwxmw^$K0_K?kS5JhdxPnNONCMz04Aff!OfmP>o_DB=zcstu%zT4R^!&d2M+l(3K&ktQ(X`z$TsP zr5Ar<`PpSGg2r^0Uqem@i^u4x1#0icr5@2`{aT_f8zgd!<`t7Bkha!`0SYrULaar-M84kWF4x`UUm$zV< z**Wg_9(w)J!pTjV;ob=U68O%BW%KH{9B1!#-22>WFA(t-5WFu?HfO1=;*j<}emHAi zbS0L=n|ROChEGAWF#H*Yj&l% zs=~F};OH|y0EUU!m}_m3ECCoqfj|UWGCBg3J@{&Pc*g;$iTgfP+6v2oAZj>HjMRVA zw|!M%t_U&lw<2an>=aLU@BfM{ZAc{SXgZ;=IEtuTP(&i7N}F6`XbBeOjvYx;$QK_C z`v(UndUWc!$|p!$u3jcLXk&ZrJnvj{#=cCEsOhexLrI$}m+^S(%>wRDlBDPSK0&+~ zvc$QJc(vvevr6Ujv-$mA`{)oN<#Yc3ql`Yeznz=JeaMPL6UJv1ydn0N3Og`7+zCXw zhu(`crt&nUV3g9$436cm>rX_5*Crir|AK}*Cn5+VrEPZVt%4`oBop!m0Kp{wmzK7a zgW~4mM@rQJUgqdXaaX!fdAC*{;zmnY6Z+8pJd~~VvQng%iHL!Bd`<#OLiin@LR1%i^c#)tCF}CJV>C3K@spI~YeA_VavX-cD6u*EzU)EVO#2Pu z5+aoo&RLVl&O$U?llgG=Gz?i&M*B7s6$O^ZWWu7gb+x5juy1A?Q5*&^k2B~wX_$aB zbY@oO{i&VSmJSpou7Cm$t)@_Jt;_u+i_c)3srkpfyC2RU`*-+*am{>bIzh*Py1E_t zX8Uc4NA8>5zipiUtpbmlsaLy!4+aI4rC(7|mV0S6T(xr_M)l5f**69pG5UriFY_+8{wr$J;tr6?0O5wH zJcgJVr)~@|e zr_-lSMDKx~V^k1(mfi5!?Zr2ZYaIeKF6Dl5Odfg~Z8*5mwZXhSJuOpiNiE>W zb7_%}{v21hD!|%W&GNgXgwy>)QbE&uJzpw0YeipPC1XrjbY!$D<0Dt^uY?m(nam%IEqR4QkD6%ys%)e z#{(-7HIRYk}PQ z5Qz$;W$X%xKWT)sVI+B4+>zU(^&nb<`Utc3n*zN#+t9r2&t@;jigFM*|5=LshPT zZr1#uTh~AKa6uu}%9Lj}HSRaYb#9+uvqG(1<r9KwxqY?;i;a=JmAQE9!+c!(p(obeF5q16}Eaq%ll?iW4=&+i>+ zlFpBulA)LQs`CK3a0!=Af+pVG-lC`LAJ-u_$u51uxE}hemkzUDrqAH&AUN!aIED+h zbF~gAyh?CY=hxfl>_yj#fJ;G*sKa`DXqsp92lNwsMOdJm&;dk_svC;U5Fd${lmLB2 zc&*^H-CMw?{VZiVLP9QL$pZDGYqRO)FWarP~pW%aep5!=SC~& zE28U=TiL$uW(z%jU4C-`^`=Jtwa>YR7kiD(!IN93iry}Z&-Z~*AOP@iJ>_pAvK?5A zMf(WcAi(yR$B9D`E}q;O>9soXbp=s&&2)Gp{FnjwXJ@drXsvKA2z?5-OS!pq7i;F+z67Nfk!Zj-1$4Jr{*ryW*cVZ-M+VRn|p(CaYMt}ZaHBq z(4Ts@LtOJmV5~D^6nrV)zV+H(?J6M9adr1Ji$HNqSiSJC_}?8&+j@Idyg&bR-T8FA z0~X7G&TI#9pcnnLF}0Yyb`XlQ+Wc!=xg|1nbq z2&zOIFJ|)-3h%mG{1s8TIAocbfxoKAkCyDaMGa+C4-!)#E+C3C8h`9rn~!yEDz0GO zRqa;=Oj;x~FEcU4?8(+X1S9r0DvlFb3TyvLsC%gvYi7k1Zg$PVCQW8ncs(l{O;W%Y zm3i4NxX~<&$s&8vbV)4!as9CSx8sqIyf;2rtH|w{_JW_G_lz;^LlZ>=qB?n848O{O zlb|1$<`E76*8;Roh)H-3dbU%gQNbgsgkHk5Mb*$0*Po<>-H(?@l`Z*ML9$sN%imiA z%NIIlK%|i!2?bK6pTu#J5+tN%q-j9Pk;FcY(8};4%C}lWHIhyt$rT*Z_9CA(vX(=p zS5TSNhsd}>@Pdm>#t=0!cRGd){EOZps_2x7Y@Q8n_d8L|sEylNd+7)o=vF*K>(^c3 zw89AN+|f&XJ|8d*DOSSH;z-;>36;-AX~N_7uiwdh7VpaXkoOAKT8mmwBO0D3%>0 z@@kal#e19sA82v9S*d9~j5x7YrD)}HmEK$%B&cyfRYZOc#z4f~_$>ydRQw{8cV@i- zsxW0I;rxhIXJ96>$0nDIcNG7UZOZo+LcSspQ!YXNF`%sGzGNd!%lQKrAGs_XYb;?b z?}Wosp)q^#auc8ikFWhD@`~nGYur$_`hjjFKT~f8V0@*%BZ1)(cCh?py!Q1#f9)WH zOH}1}&5F>JZOcGZr)d$wrWGzTG=N2KKFu1znJTm&4^8EhYc?VQ+CX8s079@-Vy=ETn=1* zY<@lMnKBr_ro=$h)_0fL2eV+ABX)x!`I0LW3j5Rb{5tw`WMP|gc{aJ^m_!x1lkG+0jj>RdVPD_|U;Q9N z-00miaR;Dw_JOZZeI<2q?{?A~4%I5V~Wz4{R+y#=P_kA?g!ewxgK zN(aV|(t#nLhUf?Xu7YrM65UJw@-Gai#jI7!emVW8Rij?fMF%AuWSh_}0RBinIcOtn3v{wHc+};H_2y;eL$<4!(C|znPCKaa~Hy zdKS6j$SSse3^W2Dk}`O}0Gmxv__duf%rt_^!`R8wQxTZ^v$fnf882%H!eK@aKH7QT zRDY#%nw$KRYj@NfwCwR~^0X3vouLE?s3BPJ{iDb*U9UN85jB#f>-$?AyE-b6pHMr0 zyva?deUH@?U}he~3$YN9Pse#pHjk{d6>a=kK<430OO)k$Z?+x){=h#TM@V*ufbDSZ z;UV0#N-)e^(^}>5FJg3pCmyhUUgF%&Zp6mg?|X!?ZhuI@844-&@E5bc1q5B+4-~;mF zbAQl+b;kd5TDX-HI*A5({uZjuuw~^;xW?>c;UPa{a))wtlZOaqjrO86DoAC{i4v7W zH+dT}H=~5UySovccRAD4ZH(76+Fd|@hQKfZp1O> zZrDTE^>YCY$tl7;V;qfM9OzNmTDyl%(XyAMx+$*~&dMeR$Oq4G|BX}0+L8#Xz|7C1 zA0UHV2h+Hh+G^c7n&PGHBiU(n?Cn77Tg_R>;_G}35n4Smokqq6Laar&pz?Z3vsFA= zPg%NQBbX~nh2rb)KNp{RpYRM$<*;`%#~sr(In-FAJ0?Pa&qGBwts3yIadv1dEZ!1I zi}a@KGq5?(9xeR<9!YFOrV5m)OGVt3^_>{j0-tJU8;Iq|G=imA(-%gHOR`ilW{~TZtIxtEL3uHZ`Nwj z7?64X_sOQhLl?4y)t~^9xr_!}H>W(25(?0iJ@59<`uj&6`#%`UdNLnEB$E6MS)%3F zP7y^0dr?CwhBMWrKof;fTp~sdf1ink(v;f^l&0MFN*iZVrhfJn^ze&Kub`S_u)`22 zT@D2dh+ebQv)b?2S-a>@Y~WMwQOpzNMp){eY&Ly??vQP`Tnjw02+==q*aGiiY>|N# z8uX%l1vI(){_o%~(G1|kbU&!F@LEG0RH!~qDqb6$G?rM_{p#>q`Z;(Rxiim-u4#o! z7}4}#CH4KxZJ(S?TIE5-OOtJVP|HL^825)xzr^Ns>*Sl5pw(JJnY9)h-~B)D3?5-T z&~Nf4;J$)h%HMKgbP$1{_KQSWW`%2VEk;6KqJVys5KoA;S0N-!uIPDpijNKk18OC1 ztaN`gq$yt*30&MX$ARZ!gpGae70Baxg2Ko7b4?Sd>|Cwz7D;D(%Q^^UtG0(ZQpYBINiix)Uc@%t_HjezAc5rf{h|D&Rs& z(yKrk@@nzY-`ly!yf}VRZ`-$dhOo}csXLCu;og(a$|$G+<+1;3Ibb`05x4@w;8q$M z^bzy)BUFat!cLGjPoq}K&o4&zFOYk}u!kYgIF0vsFd=kMLVH?eStGD#&`{Wmeum9Z znu6#}s>~bLbg)=5ZycNU+#lIw2{*L;*eqptOsyCi%`PNzI%Sz08$u=LXDe5Ej}i%f z2{a%RD~zl!>L2P>J?wIY1edGIgDP|)DePf){^@Z{v7hdzU(h!4q4@bz_x<^Y&d#TE zOlCPdJO5k9O=sD-EV7EE(e44ccGL`<0q<_s&y0N<7a^_NjENfeAaOK<^n1%)_g7l3 zzi>*#^vkf6*0BzxIh*!i!~Z%QV`4_@2$<`;$I*E3VKkG`EHCd4q+ZFR9=r5I@zGIy zoRBJN%({j`ng`S!+g2+g^RqS4DhoF7yv3F$PPwJ&a1>0bBnX~R5h70}q5%!=AZ&(; zAZ48ZCjEv9Norrd*-3MhjHM0ZaLmrirFIL_H2X}5hF>2bRd){$;eOIithGQgD=_st z)zI={9HsOH`Pm_I&(9c($i~X@&K|AU*^Cdd%Hk$*Pt8Gb92%Si1E0NZayjeTGm;Tj zBIBP-2an^ahjrPp!$gWp@B9FZ9FgD+3E0dl)pBvod?QX16DhN$Gu6*CJ~jt0Z^7MC8RU_~(>+DYlC|6Hygyw}eT; zA&}HmvR;8arz{6i;i}+Ej_p$-(utOk`3@l28LDz)qsGxkQh79-4uoB$x9N9)lv@5= z8~0QoLbW1`V+sdyr=;^7l@en}BMUBMz-g;}%qLV!V`a=EbZV8={Kd#rI0oR+a3F!Q z@IHav*veRvR*O|C*Y(A0d=c8D-I=mtMN%uw#IHzVQ2gjWVWF}CFZ=6V#F$?FwHe5L zIkV?j{Mf7?yVNV)sF!7PLSA0d-Ns_+>GmE7OT2#3)Q}q@oQ++ez)lbv8ciN2(zgzw zGZVoPcv?DZ3YOKc!{I1L-Bk*e*duH&To=95eDNZLG=H|VGun>W!D5OZiNykEMh}w52_NY5QmSqdgqj96m1kNM3umS>Wv)(=imLzV=<(084;Qrb(9PE`jS6M zqWL(#OzrIQz}_emdhD>h_$CEs-D&W4ZzG}i7GfE;4f4uLFzY@=({*sw%ZBR&&fTN( z3NoP~9u>LafIZ>Bmo#F{Fv7nEEuMF8KNMF#zq@*W*}V|sfR)BAawRKq8Y?EvXjM$- z4Y{$|%7_f~J;A*qiFx^NuU8WT9UIaDQ7pK8=%1eI|Nn&$FEBMny!!pWm{Av5W(j>1xD7O(!3W;^dsRhVgER|1E0*a#=?(9p>&#!@--#AxT)nXfvFF1v0jIkMmOiilh&4G8c@yb4La9Km@ z+sB<_#MUzUs{_m-joYpeEjh}{gQ(n++vlr6{OVlks{eG!I=pDzLe=rPHyhw}&?gMU zN*=e@y^YL;<3yvc5rOL_zR5c_gbLXQLL{rpivoE+*r8J?M;Cz)Zj1Ev`wB(ABe3 zm|tT$dHyWst%OW8K)%REk%!y^SU@G9=-o_b3$~5J^=i1LUy+{Ag)2{8KeTpepdl~v z3viq6`KKj6@51C=8uRN*@W7M|{*~K!RgU{4y#14jEp+=H{&opTaz?Rfp9|Y;=;hol>IrT2e|j zpH)YzSd(8fr(+3;u}ti@Tu(D@O*0Y?j!g8%Nr;+DZTOkNUmMHJ5 zeM}Y{Cc@A_BSKGmSj09io8>avOT~m>_<1<%&M^g0w9_@ib+K8Eo2@+&==Q)HR!j1I z_j%iklp7O{^?E=~7H=m!NC-aO3aM%RDB{qSK(g=n?B21A`z=F5+|@Pfvc1J=Jc}eM z?lE}rPY_l2W(4(6{(a?&b_@yJixVGj(f``?T6YEPcxdCr~ z*k)xmBx5~*9VoiF&_3qXoynECa90I8oRK~D9{?gui$27Qo{Vh*eefpIPq zK>Jf?__*)fvFvgzMITBLzP3Xx3#a#B=ojbN6n|jT}kRD1S;n zjm?hf93#McTYoZZbweYlFXWPxc6MK2AOMn(0D=R6Wb=E_Z$Iu48JSsGSwNwPZfVcj z?2JSbKp`)2@$m5YmThBE;Gc=vuS~lJ_p*~IQc8b=%VpqU`7Jb}Z`5;6yP_V=M)5R8 z4J+`L#6npi9v`grSyRkd$vk*R5m#QP&tz1p*aEu}P}kwbD<4d}K=Gh;gGV-~#Q0(d zKNz3NOBD%(HHrU1PleX4J8TS4{~bSg65$Uz(X^|o-0#-T5jBu*xp?s?c^;t5;p^Lr z&{zlTGxMSh5Of_E68if6bf&@N`WG}Mx z^_vQTmuyH=|1V&zAopKzCcCIe3?<|W@ojMo)KjM|vjd;p4n=>LY>+{{m9`jP*WkZ| zZ*WDv!IdX}ypnk6)qlVJ^f3T;=Ei%%jsFMt(%OV_jHzSvV$CLxqmN^Z5Su@rp{W8i zfF>r}nVsa3C+u3kKtTz$EZI!`Ged`W0}eoFc(3J^u*oe>K*W0-gZ>x5S5?liG5;AWaPR5L%I*n(baH?FK~m- zmy_vx@q-d*S*kh(G%v>!YmwoLWK;Q0>o6dBloutMw=luJ;NzPdV7r*4Yvlb^Dax*( zu!kC00ac)c4(|a_PMF)PhilKh&46X+qH4E<4ScH^+6N%f{JB+FVpO(6nh*P~m}iCOAG$~tZ>v&eWFeg4tIr$>&llGC>ly>f zqJKuZk TL3%3K98_^2!PO3dLazJ9jDeZl-S>S_CQb2A2aQDRdZB*t%KQ)+lng7 zerRcoT= z7+mQwHV)-7&{1%2VcH9aF-E8kHRkNN7nomd?Mo*hKFcXE<=Q^%sBC^#8z@}2cKs90 z@YPk6ZmZi++t6lJMGB9SbtN^0ILzcpngRbJDkE{O0Sj1*=>?|g!nK#UJ6Gx-rr>Z9 z>}$26Im8;sWwMZG%R;C(RAO!#`i=_w4{tBKpL&;X|H<=-H_9JSk%Bw9L};|2ybUPQ z)BDlz)8fYT0V;#8Rc7Ch{)rKj?Bd~Fh_AyM0P?_p^fDdDl=$w?m>Px)6l!DUfu!GA zrGE~3U2v0NQuj!U;6HmhZx~ss`TJ^vHtY=RKtRsL>`Q$Sk&My^7`&Iu`UwTOm8Bqe zqW&2cT}0)?Gs@ zg*&5HBsVa-PxktTZx2mSm00Q5Aqobd+p(1$Wf zx6oj}VN<4@vA0!i)nduAY!?VjNLw|*2psIi(&+}2C@e=#M7jfI0zKv6y~tR$0noiz zTQRa`SZ`m`LlLO32Ej=PV|xI+F_E@FFISKFC_UQrnCYi0q1 zeQk)QVh~vC#~l`e)gp!Ony;73!bG+;L9f?X)wuWoi>fEa;*`2k6Ydx`wM^__QHAg5 zLeSKCQYocLEVB~^jJ<>;``s(R6Ql2U{&4Vh(T3|vltK>ZIPJ$Ack7MqR|!ja{UDF? z^Grgh77bV{D*>)E&h}!>KGGqwVjTjlVhswFk$z9f#%KiF`GX_ckg@Od{@J_6h%YBY zD~;O6m*eT^2RtNmgnj;tVEXSJlMm`WAK7?_@=oZ0;kSX1Q?3za*IN8)L&h3*vV6p# zIb79>hz>+2&Tk>)S|?YI&>r&*{iLSGb=Gy70XROV z((e|x6slo}y!h5zdZe3Gs5rgZWQfl9yYb?-XdIl_q*yC%6c)N%xor;nw0)9QAXU@Q zl)9ls?KR$x)XOg%rN4Ndn%EvQi5s>E*M5+bKWy7d-IFv~FI@yr@>C3;$hNVs8=8#*{iG z=54n2-G!fM=@hcBPI1;Uu#&Y$86>BK;Np;6!Z>)m(s$!G&RDz*1sqbIQX;z^W2PFclhM;) z@#T6xt>+J+3@LNl9`2pmWrJ|qH>{k!cccAWUD!gcjJSZGrcM=X^oAGQ9cmSp*+`a4aK~gQr($wsVCs(L}+qFT8VHKrrmWSVRtZV6?UCM1$-iYw-Wpg%MgTa}z%_Z#uFT^IXo?%m&K1PsH7iL4oC~KE6veOHPFo zIdZaK;vx%jC4JI|Y<5_cnOFfa9@%h1Row}R*oz}yM127UZ&TrfXK)TZ>Y)6hqj%9u ze<1RFN2nmX&(&0%=RB@eC5h|i6AKVfd?Xss?tO&3n`=z#w1E;9I!R(A-p%ili8^cm z`Ox`qd90dF08{_GjluS%`1DhugG#a)vuidu3}qyQJu1}W$J;SWobX8rR zE4Wpbjl7sI1ZQCR7}2pVq`ktl@-7nB&kxh?;`DB$w%oqmMwD@?DY_o+rOY}$b4_c7lmUmT^>iB@zstO08x@fY|4eby4UV4+GXJ_S`ZCO%Xil@Ee-k|9O_bjwau zZtB(&@OS&wFa)j(&7Y`ZFk0Hd!0kxnSg*wPTwi^g&v_)0t7!Cz0t)A4c# z%AT0lLpT5X-R$WO2|e;;wA;R&&oSnw)~2c|q%D7_y1Ov~$}~fKdxxc35;1{uY*tKI z&Y!_=MQ>POwi`NPP3)-g_J`0kK|;sN%s zxP|M{BA4_Lz|H@gty?5u;cr16qr9f#&Z0i1iodY_R<>=yhJKpeEpJmereso3pu7n3 zhj?5h3ew}35%#6KtB&EdDgYx!HKqCZ5te*Hoymglq3Vp}T^SgLAj;prLyK65`^Z<_%vOOAY^m@|eD(3gbxYZn!6R!fIJs#t7L2nwPj_;@&NKg?{M zI7jCUB47-ctoL4Q=;94K(h(*ezp}9M`<=H7_TRH>uHsRiqiJ%5bh9G!D1>+J`UMiV zhKuRh0-qB%P-Sg9JG9K`vz({XfYNQkx z$Vpp#OP(2Qi5Y624`xVnxMZH_8M(XsWVfd|5>zlVX2}QScg!-i=xt#JPGt68k%6VS zCKQw;H0qU#+%L`OH$3x!ds6wh;!iauXz#`pDU93xH*-09A*?%4J*S+p>1K#(135ZA zF|5W;4^;?EJl|HYV*RkV+*zTvw$S~7C}|98Nr-(26!o;`gXgZWky-Q%hf7+M?6xBm zgm+=7Lj%{moxVw=9E3cS6sdzV$5pa4}p70~Y84bbLEZ{n3RanS~ zcWmXUuk_wx|F&x0@~5N}D_8Ybki58-(Sa9NGCBaxYItXxS=Up;i*8yXp*w=U*@7g> z8^{cxGBtF?_7XTaieSFx9S}sF8??fwuc**kyapBDqIlSWT~qwZv{Fs^gOW}pn~$FG}^N^id~_nNzvAvpL)JE#_#>OIwZ)-elpNO zXN=5;l>I6`$3YZLv1;N5(3kG|Nb^wmy!Fro%bC7ffjw+|1OYsxAVXAcBrFlNM@z&O zLX4v*#JCk=E}rU?Y#02YJ=EqH{MRZ{__R}>&J4P%-5w3*pzDv_lmy+uJ%9tSJ78Y+grwixn73C-_>VAsoP#ErJ<^Dxx^=v&7EBY=*h~b#v_XOz)GG zX1^WJIPF^c_D=v<9%a%&Us71Rb6;cQOI(z+6r8WbW`kVuqlL1-o=HqpxQa^D89tpe z4el@`51Al}#eeF#$OlD#-YLmHkCt-O#Kk-TDX5hDd9Uq*sohiB5TBT z0r?PzAyH_bLPoLMIkRwYh001t+JWJ`@%jS~5L5B32bC8BHh}Lq-X7uVu8UeME^y2b ztfFra4)t6!Q*vcsgH~(o*j0=8i}~(`nDU43Zl$=?)K;!(wO=Qc!eB1EmFthRlwCDk zn|O}SK<29>kTe#wtxmGzl}~3ST5L(V8_#5x8;7`g2w_#!OX^Fzg-eUz?}Z>RmoybdgR0;GKcMzC^ykkKb0A`l6VKcs8Y$u!(6vBabyqkM6IC`P0I~qN>LOf3N%H65IVKv5n%DY~;}lT8{*p z@SJH)9<`pb_G!;|6)vy$Ucdg~;rbeM5)2{#?$zI8T=Qcf%l`+OleiY;rT9Y7?+bsa zU;N|&H3P~&4Gkqaxu2s|7z{8JOJEN{@>!0$Q=hU!-R-75?;8x8s5+F|ZCjuFk3Txq zZm{~JMJ=)W1?dNWVs?)>YQ8g^O+ic5VMA(@!d=Lw(lxcV+8oj{AGt9BJk-5ggl?$h zjxh=c2XBQI1G4mt;xRrL|H1Hf&uE*f!ux-V zYstBZ)_mt8Ip3O6{7(xJKLzPTCEsxty7{5ru(;Q=b6s102oM|fzx zsH!lhr}$gv1hE_gqB@<9*&YvJs-`<p;>qF)OiIA<*JmhR_ge?T>G6mzTnL!WpdXDX?ku4EiAE7p&idc2uMX@!XJ& zL&7Dp_^fS^S5fBOfA7tajYUyd# zGN0Y89e6Akf%e64Va*I@P>eolunzv)2!F56D_AY(fcB*g!&$U6K=Q*LD6^U!_OR~s zHcL!!`6+cC1w`ou9Tf+HCnT&z;3VNpCcpgB89aXBYOF&q1TL|*4NMmv-OI>V&DPPY z@h}J79Bq{TH$XI^e{)=Wt#`!<1kvip*?0(X>hZ$OwCxSvT=ypnq)`HkgoOQ#AQ2KD z4v=Oc<-%Sfk8zd#?_d4>AAkFgzyF6AGKAtMUXeitQCz?xir5ax9`3*;%OPv!_TLPC z0u8RJtCL9MyxAEhYQ8sh>aB&aLHtBpEn974;Bh6`0Cj9XpvhYN&uBi=v+n;sx^!}# zuucuW>EXai(8`Q{lW`>Gs47ThS!z5EJ7r-d6rhJ>{&ItvsM_=n0W3CYJKaq0VDN`N zQV29c+FHq6wb69V{ZNM^Pgy{P??9)JW>x8^W9w z79sEE*cEn2d*9VMa`pAAT<=_~ze&S}jjX|Du`HG-U(rP2?ilKXriLLVg5nxN){aq4 zDYq7JFup_F67-%TILEn}2KWt0DyJ80b1iRsB8S!<}x9d^W2jLeK|TJ;#5MyFpU#YJ;+^p+)|&a#@8xn#w; z*Z_dHAhwAWaM75M71xE`CdjIa_;YSy6qIpw9mt;%kAsQ8pDPWr(kDIPnF>s{Clc9E zR|?8f(K2WAwdMdDoIm^rCpK^#bR3^cR}#8MfZk(*y9DsE2f;eO)Xmm!LK-09;jkom z05gAUjxCd3=CCm|gIXe?nd!ZBByuKtUB-(w~pkKG@7Ysa0ZMGn*V%uFIfj9HJD$UZjrCbrhUggRbsvW z`<*+m(jVmn=A!qpN7F$)mE1FHnD@lw7^zeERP&LJ`sMj{Gt#0B@>Qh~vtc5Jnyg0V zvIOtBc(IA?LO@ogWhNf!xiBZ`&$*6Zi>b*GHmJV^We1p~jX%O1IEVWh*?U^WEKqat{u82DHv(Dlep= zXJ#6P(kKIwnor^N`Pf&2b*U>*)n)AA1*(#BdK)UGvCH^NCtNGfH5WAbj#J=*3~$)C zDSD;zM+>)A4TV3npQyOr^~2pjFhS5yVc3*i`w!!Ytd%0{mi-&9fj0V0a=0 z1c|Jmwu>>Xt`Afk`MM8#LEB8JV>0`|E_}ij$~9XeABd1q1Wm0ye}Nf8;aiFEPGwl0FTkd6t}6>Ef@7PE8PZC~4(|viq4@X>?a5_%SJj+(y za&54%Jmk;oSxc_btJJ&Lqa+}EOBavo@20)^?5QHUe9o}E7WdGGl){9|d?`!aTi%Xc zIkps{a=!Dl{{>h49&{M6DfGh(71|(UDN}xa;9M}bmzsWNxnvll}-_rOu{f~F<4lH1{O;@B%@G0c0=Jx%AJFlpefQ~ zLkblb{Gzqzgm7*#9%VEKw#+SDld?eHl0qB3h^w?QSHSf=8?;hp`%YvC~ z7sqKotyyJ{99%S%uVz!!!I$wo>wWOY{IMpzZlsx76$Pi2_C; zmYWdIFQz1p&fRh_%C^u`4UtJ<7vPPbfCtJJH#3cuog+Xp2+^LEZ}xZ& z{Ne0UV)-b?$tBP0e1HdKair+eQIc{xMW5gP+Pk=Xd)euoop(B)&Mv#3Wj1tf9RrD= zB-+7m`jwvXaR*`aRHpkzpRi42vM}&ts`Pp6n;CICBn3ZET#MJn* z2yyqHBb?93unhZ%*rNS%l~eCZaloZ(P~bBcSqk zK7xw&B2yH-?jWE*tr(xB&=6@`8e>N<%pK+C$czPV(FbInEa#G?M%yNf7WwaeA0ja$ zAPuT}>&RSMx!`3c#a6xbTpDpa%e7IVw!)5nCD&NHW?0BOX;f?b^!HY%=b~5oYat`j1 zH2FpVOp<*XyC1+P%ceQH1-WpYkm+JeeXE6}dh1+>TLF02L?qj(VSI4(!d;e4enMI~ z86Csmob~7ZDLi?Tpzb`_U^k-bLOE{SHpH8am}(8zzNokphpSl0f@g^Hoeeul+Phd> zM<`MuIA%OjRP>RX6mBFt&(#{?*mu+!K>CYic?2N+?D2M$HkYwP$F0duv6SWBkSzXp zkS&+76+5bUB~xZxFq8&zXahS4i6@?Vv2bu%3N5!fKQo$&JgEiRxG2k8)sV#b>{8Cn z_$JC8a>Ocz!50wk9UxzES@n3dfLeLcqQB9}oOs}iWDvXzwZ%N0kkb&Q^NzcVHw-*(2Y*)Sv95U;8c>vB>=T$N^r+Y z=8W_Z3P76c8pBmyI}93!);r9inX#4?TB5?76?syB${Stn*kablm09k+e^Bw!%KAN? zj$ZIE^=h!vIB_v1+lia*RwhDQ_;LAfEs3h*0X&X z2}Pt#RUI``c@0x}hEb;y?rF~GIS(h>@^lo_zpwPl_<#I z!{pXIwc%UG3J%>^$*z5e7?0BqV&m`)qu`Z}A=|4CpG9@R80U1};lvWjg*!s+UHb`r zEoPu=F@b&~a^B*!kL@ozM7szFw~wyIIzwG_x+sQ1ekJnNWgn$0l!Yh0Bw&TgjS`d$ z)CQa-)|SbYy{4iItBi63IP=F_>#PB zxFS7fuZOAp%7br|)Z;*$nh)E%p7yU*8MNB*c(!cM^dy`kb;3oFmapClrLgnc6Ktpx zU|0z;QrKy=qGXEx&hFYOjawGec`f9~SDplEiyU3eZgn%!8x0m$mxX@(|L!iD?e-u8 z0oxD_(|S{`t{R3I5W~#hI5t>@WdrTHF63{(wumUtZw9l)lFc>k;p^8Q`_Ci5lBFM2 zwXK89QRZQ+pdVjH^kZnG6e(KJzEK9v|M@@bnozX@AAO5J+(tV-h)h#;^;yn}`-2F9 z0h_`ZeilTgz0 z-hS$2EwBKBmoU~I2|g{8cvQNkHvkhROINQf<}r6=k_ zkk6iK+xiEvX`9mej(a8-IMG)9V~YA$eR`CK5#j2lvg9(y!lc3wlmz z{KM$O@4aoJh{xZ;Doz$`2yd0jo0dGu{(J^B+yZJ5H|xWp@`WwO>m}h5`XdAR>4_u5 zjj!?MtzLT%MJ%*0EPA4f8;qvR+Qg2d2E0$6c?TS(Q%M3sjM}~2?OhU?hRJ-uvqQTC zqqWG`3tys?G$5_U+d8Kj?PHGp>B6=qhd+-LYvvp1qU%6GKt_v)X-RIv;b6!2=p4D~ z4}Q0pv=nl|pl}vkAv_PEoWJ!8r6~Q9UtE z>)-AvX~fFokW{pFV1%nDxM1`=m})4Va)~YikX{~_-KRmJJAeTSE zIbGM{R(&Qm5*)$YG$brNsYFmuRl<@e0W7#?h51nNLm<%W!ecDKtCR|$-;Agzs5`*A zhdDHwReSEVH5qjW>5^oB_IIzSLM{&znK4|fq(a|4`;ZOgg5!^A9bGSbR7}b${92U= zhgc27dYM~vk9ZUe%BOUzp(LDq!$z#cRYY@x}zr?8F@B?oHU-aCP+^-1vbi3r3 zb2n!+(KEG0LS72qRQDY+C3ih@B0IidmVJ)u3!z^ zBB>N_qUu07SqJ#3s5An%3~dPu>YfTMM&KP!g|(^^R>fMkTJssGE})-3Pe#sSZs+R3 z7OyGZIDp?3r;pDj4;Y*BaRyLw{?llJjIMP+V%WzqWbx23H$H=+9j0xta4eZU_A8WU>P#FLX+ zzo5Px5xvf0;5;OhFvgsBeQ^(FX@Bx-fAWC3EX%@B>yqYJ0jl6F63bZNE@ji{hEr6z zolUEsUZN?JDKFz@-mJ(1g08ei4h^&t*>MdGUZz<{)}&a$_SWXRSE~kfpy<&KO$7J- z=LznbSOF~?rfFZ!ufghYOd&FJ8Wt9{;t|cryJhTIVQeg=H%jPVW$Mvt$Ma)Bu3OG7MxwS))^rpgd~leM4UE`# z9waDIxp0W^2&(t07S1SJ0E+sB?dCF86_^%!K;KLCN&p%kmR8EL_li`*aLToF0_-F>o!6m?lf zMK0y0ueK>HoTnwZ9J+jv-QlG7rVo?l_M^lk_*Ew6ky-njAql(a{k<#E^ZdDU!Tq7qZ0sM^eP0h1C9U~GGp;%iB8q9Y z3}m7_DmfY~%^cLmCmAW#M;S_=FI*Co`t<);_wz+RUXY6GnUVd#+5#rF>p7Lh@{1ZB ztvoJWrY~5L2T4oh5?%n;ByvmAw1={6&bGP$hEPrJ*X01G?1@eNB7XV?>j^JnKJK7b zo7>nXSC9oR7vDy+G?;baO;^m*K=vQ?XBCQEPn{$5b@WEFYb49Rxe#Fww#&!N1i-|^ ztynw7zW#7$Le%8+K!$yO=}PgI(^4K&`wY}}kUXdNqapb1WQamk z;8XYG$L>Yv-RbA|sR9}g9?N_Z@I3op7RBVtCaslUoL|t8^3jZ)wn}rR-;L+0LB$Nm2o7-L^mn@lH^c6tf|0o;~L~2 zI^uy*CF_i&khw^w!m_~ta}I^Ht{^H`PnM0U8I>XMI9ed)8=zvtCOp?mqV0Gd%Rx#@ zgKJY952g>x(HG5)$w9a{oWgunod~kvoF3qXIY=%!C4BfRay45x^3czM{Fbcs0avZ)cRz*n9nYj zuV0s|z{>cJt83-I3FJH}^PyE@K89$#>_WDD5wi&jcgNVw=;~1+j^dS(kXlW5F%!rG zH*|d@I_MEKVL9(;HxIF;M^LgDYV0~8iN$EXTuUQ?ArX!cc}d=1Cw9$`aN?+o>J}fXU4c`!Pqq1m*iUMgOL2UZFSK*(#XXx3hQ<;kx=zcRd5R#Bd~%94J-EY)SK&ff|<+k zA~dCZNkCbaeU?8r5ao-agjW zQ(P&>`KO=-p`x+o<{Z-&u*9$$HTK=+h6)U3li7R+N^}ns5J;Sqr6Eh3RiY0U_mlB} zjqd1~7KAu&8xA{9 zxx_5@Zlurs+&i6TI~^neZ`^|Qm2>^zhQT6q2nifLZiUVASlGc_0ynqF#0*v zSMmL-t9|0KD-!J15$P^P!EJGTF3!%pD+~~ZV!NKiGqA287R-+zz5WFiB!Gz;WRz3P zE$*Hl{)FfkWcGV)6=q4Qd>eXZg_A_fEluG-t!CUGSql@B$lkEO>?1_{gt6}EFyg;C z$lE-Yb*Dz5av?=Ea%V9!{Da^(}vPaWtu0mb8M4D|>s`9!oN*vJA6#=8&&wVaqs#C7a z9r!V8_vmXqfbmGSjZCJ(4j~t{>zsv-T#F!)04B3J%07`pY$0-7+bsk{bM(;&J3y?= z3-k%{!2+I{wI3<8#umxI2NYjb;>Ng%D(w^a##4{f;yZ009IsFrhy7&qTSw^QezFXHWb|c(Inx z%Z{@+_&KL;yUMPd=?Z69NoXj{1#XPG(D<#ei&FjY$P3^~hyqiU0Z`#=-oF{WIsWd| zv7-o~rox0vskI-cE##L7tpmttUr=(%yf#+Um1(`?Yu>>wdJ&2}A=~E$shd%c^x2gaJ#HF6o(M&W0=CN;fL4Lz z4zj&{mejHQXSSlTN6Y)>RZdRS3F=uDh-7)q5udR0n(6YMJfIs0kmG1*6z`M!ISzx! z^7fV^r1+qScc*@&AzoRCvw33TI{pj5sKCB5tOBxmg^`#HgANttSSQm8H+#mC;L`ve z^$t_o_?>CI5+HSic4s(D_lX{+OvpLOeP=R8evYUQMA)8)$nmg?H_r`RSKiATZAF&} zUsbUPpS1{Kbc^V?ZCFukPRIS?+vD{IJ{J(WDqE#cqDCc$btjaZc6XK!_h^lgN8lwb zVne1gX$;7CeyA;23K^r-z7lzUKb8>&1*a6S=ggXMPL9!OA)sSZHL;Ny_c!Rw&O62{ z&gHuJeyd|U9npj!5LA?`1gZ{Drp}SH)y=@)RN_uiqgzi}2pwLErq&L=V7m)hVm6g@ z_n^4d+33a{a-1b8LH}l;$a)ro+5=`aw>mTrsK@%3o)3qfG$B$#n zVk7Aehj&Fk@%U0(s@XdIWPyF%)yOmQ^jjv1=Z(2`hINSktU$tpanRlLq!R zV2|HNY?XIuoUq#53^vWlx6XS@RWn64gCf>9_V^@ya z{E^{?RT~*S$iF)|7Yy`-oC{|W$z{;OWZ+iePgBwk{`CCAWlzL=G*#Rue!frEaQEXF zRfx#G0ZN3W29S@G4jl(7+4Geq7q|B2pk~nLOQ3}3EIbG@BoD#3Uev8u)*1w{#x|By zXN6K<2aeACqpzW}Kp+R4v(5Fyy92*HTV0!j5+UCV%VLG6ibgm}3Ap>2TD6w^!UE># z%U6-PI;Of8vZ)Qp1KJL;nmoYhSV>{Q-nNmSTL|W`4hMa7#~sS>jc>+FkuQh8#^0iI zX~x1%uitBdoVF$|QwW)wvtMGp^f4s|45xYQy<5H0M*w+`UjeW=A;7-pXYU#=G_ z{FJ9eT=6c{zpP^a4Xs3bIGaL{K4&EK;8{Ehj^OxC2u=61*#xEy3=c3l?1$I0IS_1% z@Ds}9v~zzC83Ul_k0Q@)=e32*vJ6%y5+xdqf?to2TvOlnNKO1#LwWvt?1n&Z`D&6KqSl>{! z612bd(w!gwQS6otwln*6YC>c&-IIw(61KI?@}=opze9S(=u3Y9!lG~2(E>Bw>+9Dc z6?;=^-y{?)Qg0zx$bJb+_b6FIBAgi|WmvoEVfN| zdk?$q_-0fio{Lj5E4A&v)P)fxUu2 zU7-}5*&$MZOP3ltetl*TZTjgzj;r{a#brBMP~AN4T9Sia#&X4nLe-u|Q{J&G2(;p$a=_ zb(8eA9LjCM-c>$PYu~yNRiqXd4@XJ_u^BJAyPssHIGt@o|H3BWbO-qqXLCzOZx6M( z!ALZtM5vT)YMHN@K?z%S5PVQUXYc>-4$?)Rjp|KZnlxEV*N zwf3FubtBY{1%6?tu%+xpTQJ7Q0|v#-CfdW$>7qAAHv?=47y%2^-xk-5(D^ZOZLpwX14pS@tjt9+g=Rc8BvwNIC);sBPeE=6ZCM&gsu1Z1 zA4rj``!hNt>lPn5$4}--$+QsDgvb=F`W@V$g8Po*uSfKFa4xu8c~a6N)R25WZw(sB zZ9>zgzz>ah#8?~~LO+q@Omipgp{Q453dgFJnuFp>}G($Fiq2})T@}jV+T#U-uc^~s- zPSkCuy;th|ft|x7%g*`jEsjvG{u(_33{N5u+C6)!4t*;Pl10;&W|X4&V>8qt!p?nJ zL}Rrir1#^ovWK)ojEBn1W=Nb2`Gw8 zy9#0ej2zk*$c+G!cX5uPfBpy^*2y!1mHX#jX#QE->}z@!CAR{sqnU&PzFJq*#4dS{ z)oUGT)W2x8T=;)I>EF=kngUNT>TclUsiYd{`i(eNWPnH3JGx*MS$a7~iq4I?fYoo}zhL!ct#*V^ zbwN0gNz_UY0Sl6b?sxecQo8Xc9U)GPzAQ&5=PGK+c&2wr8j8vrk%o(&zB2cv zkbkbQI}98VFOlR&%B&Ps z3RCW}EaK_#hzl%R7gvuP5E@C5YHl*ep@FP% zD57oeAk~(wq-Uh-rb&g+2|VDBpeusf>tvit743{mynRPtso#dJ7c{Lg4ULo^3TC?sVX$0DgO=;2-2BtSM> z6tXq`{TkP3$wLA1&Np=XSO(^a-cmqG@GoR}5k^#a!pe*<;_gQeS&D=D+b8=chez#`1BZ@ohUNx~Wl`=m&IM8fIwgI)b;s`-Ru!p4 zT<$1K0k&mgUGlC(nn!0 zvaaif*k?Y=67*~#prHTnGDw9Mw5(92Eow$Bk~NOJIKYZj(rhzBFe5{%uWRaS7TNG@yF_Mz2= zdzDH>YmXzGAb~hvaL8MSG_4OjG2ZtB_*x}d6;@A1Bh?p zA+n$qVLV>yWFA?IMFgXC$6RiY*=IOKXZ?A9y69+uVV^*-0a9fK$iSng^sa@+vCKES zzY#A_zY|G9>nPfSX;?L@lz9H_yH|owb73wR;^Y<-*ID? z9G{S1-r4Y|geaxMHtHWj6d+L;jQbmO>O#|1T zjU#ma>+P)smhr^T&JKKuPF3qq6jyVr^EF33VWdQV`TgHu5F91vZUz>{1A4ikwTQ8L zkXihjP2BVbIPy|$m{Sy(wVvIr#HxI~6QC7jZXZX+1=(K6TU+`I=sgi~H&%gey*K*z z11311ie07=@9F3+W+s#&gj*;VK-m=`#-2%*M-z|9-~LPj_rzqetOK<1(R`7GP_fY{ zAjnh!DtJAz628-%7-G3pP^42y1XDukAQKTerV0HJCsSIZ zA41d%v-9SDz_Oh{SNb}fM;N$lk=;LW@`ye4)&gNIwaCkH4{2E@*rP0pexY(#TB#;r zJ!n2=z@dqwxw`knM^oyV_WJW1G%_4ZI3wwCw3A7K+w9{U`^y@bN~OQHQ@xZfc33Fz z${?s6&-I}b*uyjcxPu#Qk%sj9U}VQW33Xgz7k=v6OR#VXgjavTv5V=fu)C2|tsy{} zOO84({*%4r3?wz8&dDnX1OX`sU^f+mkh{|UAW_qiNHqpUz+ zQAG3+`*^_wPPAEIT@}oWag_b<6-S*XjB$o5@#dXq^c&jBc=?k zDdR0qJVvAkFr1_&mf1Fq4Bp!LP$QH$DqgySl3lSV4J~~PXVvg@!4r&ba_SRoue`oS zs^IQsv-G#*G)`TYXSqCnfH=&ik7Z5`NFQyeZ=e)=k9gOSD)BDqksNn0WV|n-WeE@G zpBD;i<{xSpj-(*8`E442-0dbp<1r3h-@fm3(MIV_0dG{TS5w|&4Qb976GFGU7e$B^ z>8UH0l#CNd8~gFvJ7QA?hv<`Y;|ATm!1rFeFpzTNNNdvk#vRG*8fGRE7j+WI6s6pY ztVDDSjhy9Fg&r4Af)~k%`ph}&<2Bvtq(&RDo zK1(&pTH#PS(~fg8s#R7?QWcLL7xRtE${C*fX(#kC8epg$j;~+aPzO?DrTLb?js4O( z8@0O?rr-ZX&_nSeIyQO)jBjDE9$$i*{R6RW03rMQ7wMJ^q#PX{W1)Vq{F2$3bIdML z?5Mn-@lEW0j|w%pIQO*KBFd#kTzLI}$>KWlWyJGRkk4rCm1HYoNTl~T9zEr75u6Cz z3rCm*8C$K;_F@KBfl>!mF+FixlO`>POwrUsMTe|K6Y={J@_WP4;Bnb~8lXbc+;aB9$v6c!?m9VWg3b86r@$9z#rHl$2A% zE&$>P0e4BAU%w!k_7X8DLjzW3zc3^?tGwCn!d&hZ?8F*H>SA-1axH#wrH)wki(Ppq#tV@7F1lfX|{M?qpV!hf74hDHGU7eKFm}e1*^Tt*Mcb2vM7D^H8kh5{1wn^`bSjkf zTsq%ik#I5z3!rh60nws!_I^x(dVsAfjm9d99m9C^P9nkXoD*nZPwIGy7E!cCYWsU# zKAHG}?TvVjSZGbpLzKu>&ys`{QeiE+-M}@n-4V(cFloxY-b;ftRLSj}m(pb*uw~Zf zrbs(jhO3cwZ6JQv=Bx;AyrTm^C&APXPaL}8sL48sn|7@NMjCt=U9v9+>7|v8soPdgTl*_z3*MQTtRq-Uq0$i5E z^SM?8oTdIJ(F}~#2ts#TM=vW3E$?sdLWG!Gi)ELZYH4nPA9YaYk-mHA7o$S*gysdF zW$AFp1czuR$2!F~LEhNyMvD3jJI6^s{zf#Esu+%EFfvnqZ-QM+^jIpRL{GJoA;qS^ z6fC}ORtApwvP!_AJiOIkW?MPS9=;|~<})LDCFi{eIQ5<<=iXWYE9pS24j68necM{koj0-V72L12d}O0?cK^NcT!jx;7q&QVvY$m+QH+ zWr)j73=YYAQIaqfZ(HrkapiHd(U^4Ce;nV4YN|R|d|scU&3eljpK`0Yb>jvZr^(@n zeAgxw0~^`yMYpe8gXG{!_S@-z&BEvJVeGk$XBR)RTf^!j-pDtiVEPOJdsaIKZnIO3 zs&0-}e2WlB%iY9$;H6fu>`<07fTCWQ2Rzl3xVL&}@P$kDsEV4Qga9Di!MExR&_<99 z7Ac)Q7gdx0pYpId%+M?U@W}CWz0=%ao|1)qj?+-0zgjaNQ(p-Ir?VkQ9IE~?n(usm z`)lvw^6h1(ch>p*zWe!~yvb4aSq%;}3K9_p;wcn6*y`5T?(aVSeMDiQsq5C=CLXxS z@e2W)s4M~ww}FUOCXF@$iC#%r%5Hfs*w+WKDE*f(H|xHjZf9Q`63oa70%Or&x3_j12I*oC)0d z1Tbuny{#InWryC?O;DKGdTv)cG*R2UuG7&tOP+m;E-{MVf~fQ`hcp}9u<7lfO)2i} z=6pXmFpq59xIr}ErwvaIl#Qk$oWciO;sPhuzJxWF5=*NbH$e#4Y@0zE5k}r$&7mI3 zl_Jjr5eFUXT#BWd(O4%-Qf2?mYi|^~Z`Mj=${a^UD{}9MEBfPX{?wljyKeNVi^7Y= zwat&NoCr_>m$!IB##H#m(t#wopa39O0D~Wu{+cd+&dgv*clw~r@U=TQEqxUX&7{Y_ znK;I8yn}J)o_;w=b!tS#3H5gqEg1G~e1;=xwK14R^j$fnT@rpfS2UJ{KspADA}rPx zFhMyA5ZP4#y}YrlXa&p8qJ*pS^V#t3dG>e9aV*^f^6xy>5)gxL)`ReFzl-%yvG>mD zW$zT@dbocytS3?r)_SKsn$3w1raGN*QL$o@EBWR*i3$)_;D}+W7Q|ld{olmHZ__Bn zvmHE)>Y6lNKP`e%-+Sr*wke%LCVS|ePBE|NGSf+r%H-~&#uLv09%D%}_ayOOWB7K| zhQd!hQ`1Hbl@RzzJbFc**u0k02ltxK^2_Z-3iY!=Mha0jsP$haf|lsPc;QIZm@t=) zmjiCADSG!erUJO$2KI*UnKN{3aa*4Bx)7UKq6bqzZ;zbZfe%HA;r#r53B%{rfm?9+Wznf5dWD?N6Y!M z%-b4H^K(AWb4EbR|^i;)g!b_}Jp)=g^!$S&SgSnZV zFlF0AwQEl11_^=>U=d`|l?kmdRDjb>m1Pvm6Foxx>}~S}+uxvH_6NrAF>!h7#};nK z$EQ@}Y)CGSu7G9cjK>zXh}(eKXrS`m-7=xJfA+m{N!GXlx?9BpHh=Ac&;0=hFQ~&R zsCj4;5(6wRZ7_XUjwpD8&@wtYTZVZnKsW|x`jif?j!dwUSdL^q_-G=oRc3_a1^gM* ziwK3d)EVeQ2)GGtXE_fR5{ibJt4uoK7Hhf5t{V+A|Jp2$OG+;-j<*?J!Fq)}~X8pvw6a#-zx^abAkYB`-D$*T0gt%`;&4v(N&E zqC~mA1z#{n+qlTP2*0y)=s;~d*LFXW6R?VLC>8@TiflP9`ybJVjPE#TX(nAgnGorT zJ>O6K4rb#*wA_`#O8Gmud0YDUdcdq}D>%$1M=8FPwUhs#S(;-Op`I!m6i$zQNY>&+ zwBCTlV|kknF2L%X0wYWwp{Ar_p7&L^qxWDrqb`;ltMKg|wr<)Wdi^4+oSeGKPG;99 zj&oBS?K611vX3kQNeeL9C|_qP5L6;?6S|y4Rqugy{K=@lSRU@H*T=JM#P~XpJcB?D zDf$&7$bHrO`yG}Q93G7?Q|_ym3ILdXkL2^Z#YA}f!x-EHhql|`f!HTyPghM$$Sh~( zy7ptpFP9kO+HLO+)^?0?QVSg;u%e-6tmzM~B5$aFJYfkI`$gz0LLJvEp~PB8PjHfu zhU6YZsELa`lEmJX3vOqV;b^{U0&7N;eqHr6XDBo01{p=Tb#a#DY5l#Y0qZI`MbIy{ z&FnD#f>kL2yJoG!YRM|G7qp4x<#XU;sxsMvUyI{N7cOqZmQ@s}fz4?higxV;)`5PV z^0iO!!sPGY0p?%sJRzb4@!pkCE$i4|!(81vsyxDusQHefr;JDkb(a?;!Y1MG;;HYL z8`0}a(O2oJSb3?*Rs!93v6c2LhErGp$QDW`7Cf;V(XFFh!^AbL3P|eDO2NC3;*2IO zR@%B}_U}KGe5RfFC_bsUc5WBVfit43v?`_uarVK@E8Wc5s93slHoQXKx_v_~9A`ij z1vUd64n}A-6)q#tw_b%)M}1fHKnj8$b}2E<^aX;8*ZMPOml9MCH?0~XT$B|V)VQU% zM%~(hT!VF9VP#Y)JU=r>F~4aTLW-tO_lO$j6(qfVLDIMfX;pDnDP@$Rb$wr`j*M0{ zzYYSa&yq7&IiIQI?-6?LuWu|LCQI zbU1NZl1~nrJE$3o1 zfZ;+G$<@w-!wMJcmCS^!kKAQNG}QP!KS1^2%WCU_zvnlK4pGVTy#RLr;!)z~oH${y zLi6^1q3!s1Jj2jyU~v0gbmeLG>W?9c4|ZtjHS%y9-)~|kyTUnEwu{KyyS*qxsa&Z{ zz(435gHMGP474(5J7X)Lhx~~~5nQNBcm0Xf%TbX*`ZKh{t6vJ=+<`~? z8!F&9u0xGhuGL_Q^mpjIsYr}}oome6+;XB_nJ@+R+xAweerB7936NoH>8BtKZy-nh z`t=VF6yJFVFuc@Rl>FYwEfwk>&@`D(r9arr%2#XT(OT4MyNzwGB(Z%VPr%8Fn(?kS z3bZbYbqXCjxr(h`s|<&ld`+c#B*u>WcIq84N+-fvh@4DeZ2F*M&h~t8ZZUpkI&dJv z67<4@5A~l90Db0n=<<|o1a~M2M8}@c$^AU}Y19Ya@M&?Qjlnt6mb^ktX~x*2C9rA` zNM%D{8sUpZ#puLltoL!*yt^FBtY>-)=oKahWQo)S|uO$)%W&A?I zJy9ZT?Lh|a;u&*Wry@+~Vn&OXo8-XEVi|!JnQ8Wpj%;n3&U2y)I-f|mK{lG9iuJcS z1xUNGr}wRvMtJrht{#f>MlBtULSk#0giBXZP2U3RVyx)m%S=${LL6-4-NSS=2aj{6|!zv3Df8IIkpn>Rp@ABG@bAakvf#Nx?tWFxla+X+q)2D@~f-(1y^ z!iC+po@32GlvXH1@lXgtpzA5CJ5&}_SjDFF{ui<+(*QkKOh%(RVAZ-*qH`RI*N#aM zS?3IRX1R0I7A+36u8_UWrj>`MbC~I#V+;H6E@Vh={IsT!y1m25%OrAc}YhmWMsDUU!|7e?N@T2l~1HS$rKWSE#42DHMZq!_xUdQaT4eC&dwXR?5qs zLq0lC%ZL;+5G_%yoh!)@K^)%kW%pC3_v!7wEZV~gTTJ=F=4bi1bpZP+?P)%>O7-k^Lxw(_!HM8q$tMNvrt{P@+ zq%1^bQ$Ue{ocNvi$p5xx(Q55?QCQCkt+r0gIk(ORHV=8#lm=6F7^=S9-~;@&;k zP?r78-{WqTk6|e8f3)Q&zaK0M;b z&gUPy_^-F0q)`yF>y{*FoX)#Hg9o_H$9cdx?M$@N&j1n=5-IK>y0G3D0= z5g5o_JBWjpGpMES^tyM;OEhn+tdfW9MF9rLM%3I~A5if`LjL zMRwH=vP+4N2mSm0fHULFjHLk=2VyM8ch8vW0T_LRumIijKm4ibSeYD5e7;V+#qd$vs8qI4?8Z%myxF$?UVJ401-UlJt$fJeCATQk&u z+Nt;5?nNZBiB&MvR!#(Nyvc|?9o4C+YH$TzyT>lk0HA+fapfbdAL7#QcjhyU z)xmmlJh!h=$$U&3Y2P-qmAN!$F}2z;2HWY3{>{K1#b$eS-IQ0@;oj@lA^O#@7wIh0 z>CuoMkNEfS`@ivQyK+wqZ8Xd7C4jWlK3JH)wp-g^+;ly!7QT2Rqh{b3LYu7Xk`DiZ z-)8+aiI4Cjm4S`MXjieR0fXg0I)+Qy`;NMxGl7ZYdSY=`nn7UG;tGZZlTyhzHr~6n zolGAlOAbfSM6trCl?`FXi;GKIW%kBuSo?@U<8jxgxD_;+;SR7Fw|}?ns=SE%O7W>L zPoZi7zxr`B8p@nNHz>t~FYHSuJlD#!3#jc|lF)j$W0Vujaj&S~;pvkU5!+0GQ8wCC zCD@f8-$7_cu~INkcadeoO* zQwD$;aQ+O0y-T*zAu&I{)ZUm(nf}S7iJtgbj>R=&O=;&*dacYCM-`iJ?#M73o-mr?U@F zt`4Q)!I7(^wGJ5{T3Ky?-ijKQ4659z*=d|?<(*>c0BtR~^D<8zo(f;SjIwiNxpM{C zZkCGDevxS$eLY{%!KWn#>$gbrKKr}JoyGI?YBuSa&RPD6?YmX)bH?IfpE0AR3i{*G zK~>?c zv5z``LcL5!5p}IPc5-?Q91(cfn}-_qJ3)pTR80%8^FMhkScecnqG~lZoA?=HT1^hA z|EjpX_3KO_R!Yf0xRa(mosttOO=a~JqN%2}#T6#OS5jp*d!FH^(;c&nYVb7xlA#-M z?uC>&D&VW?kb55_@OcL4%0SV1j&E@^j$EXMBdl1C`iGd!oSS`Om0w2Bz5e`055EQR zjZTT%2P04B>No9H%*^(+EOV5Ma7#uyH|iUIxV=!MHksIK2uPfcD3uVWmVCRbMeQXM zUz4a*1_N-C#6~+Yr3e8|dHPgPrHG~IQEF%hm+yo$E4eJJ>)-N(?QPqOcpBg|o#bY1e1854&OFTa^w^>Fq8%A5@sbkL*zu+)X7KgRb72x2O0wA=Za3S@^$mBbVd6thN*21^|V zY&`Bzb>J3ME?OQij={IRW_`g&9qcx6k0IekamB5Mpgt{%M+^mZA!Cu3^$!hV+}nm; zi8Ro(kp%cmpCh;z6}u(sywEM08>;v>#4`F-a#4(hF^1P|Hf>d?m8od10wZuJ_MR4b z@K}40F?+5UCBm9B0FmUDv5KY}X1ao_*rKma0xDBbi38pwQn`)*H>)H0=yuJ`;WuRZ z9ufhZLdwAq;F$J>X5oy|3n-+x7`}7-=o+m)FapL;a_(1s`8wM4;SfCD%Nf0Tjph{j zv!VrVwa;egmm`A&o!eT6A8L`AUN#0I(5sP>xC;fa)j4M*L#8&gA!-U`3} zc)SeZAp^{G4xxJlQUvhToyGn5jtUNmTZ*njac+I)?QlW}mD)iGzN+#~R^@Q5c2FUb zZXG1egwv9A`iHU`CtM@VIE-!trWmM7t3eJ(h5_fgN8|T4aiRpBxaI8JPJ({vsMvV;uFQl zfz9>T;=;Nw^|WDvEmI^p5W9T{=g)}6jl0e1YHwQO8RbRPEV6oFNZ3g2vMI60j zSckLzyg#K6tF*M4Z{f@}?xR;3cl2~UlBFJ_A*eBEBU#*!20CSZxb9w-@PdL1hv6tI ze&Q=sGGbIV03lYFG%cqD1dpSp#q@ZbsEV*=2D3gA?g1v!eYog>*dmNoZZwQZU=28N z!<=BxO4se@br+hF`1VP75Cbx*q=Ig`HQ-4>!oNd(69^vY&iDwm=#neXj{(!{i`7+% zY-#S04w@XKnEz7ogsc4hkx9f&^)Xf18EaV-0S%KHELd_xrh`DFC$cTZWAnPs*P2^( zG?-tFZcHd5+_-g|83z)@SV!qzVw9fi{S$-y*Yb5%zxqjB5AQ}MHqD&ejw(|tDuq{V z(^4RfE=rpfb7rP*rF_}tqF)!kH_#xq7oqKhmR=^|A*}hoK=u(ebtNIe@}%V=Qm7B8 zknc1~CNoS_+o3>4?+p0^s@oo1T88+AhX-{0-nADru_Y+D zQ$22dDGtvlwK!mb@*f&l9MT4#**cPZMF(#?*;HxCldwSSSllcPL6AxjnlS>HB91GM zRZv^QRI0&aV1sTXr|IxjoLDX)|HFUDvKY3-6iYVl_vW_C4gBU z2=y!drMl`<)M)U1WRcNjfU$-@KjWQ&&i3#1+J5CS zn~RFW;G^w*9tT;8r3v|}{A&cjUReLD=f1_67y@IkGHaN-! zc|YO^t{A!nley+RYBJJ21wqH*eL6B@5QDb4nz;Q+#KK))+{_wh1z^oMSK8NA|J`r%C7xz!3z zwm}{bb?WMraoi(?Yt*+8^DGAa33_Ck<+p^uLP^){V`FIHdIi{mDfVG}NnG4>Y4ySN ze0Epe^(IYkC@|XChR)9D3*veV@YS&1dOlHJtcp*n4TJ^85}m&^@i|N32_a_ zC)3)1&Ja$?jLTAv4D+XWuX?p3d^>k>q{8E>$~cWdBraT_T-?EshuwLWUa#eSkrKcX z$|?QgR4G zHBWohB`+wdjXrn$-MJ_#IAOm_L$#Z@E_AF~oJqPJ%Cx zoJ?d-+$1OASL+W#voQX!gD;6k>LBRHCi%L@yW@S!Wxq8;>1x1oOT(SAu4aJ)FId?gA#yS{bU0Wydx9?sF{#Iz_)C(FMV%DA3Lbve+|*4_ajYonWT0I*76)3yUyc_67nQX8e#o(+c@#!GeuCIY z;^4v?l`X}WD<&irCJK>}3?wP1{doPS9)%(W1c06L6;b6Zf~HgtQ7B6SkYrGi_>mV| zZK$=mJ1RFO)D6o^vlfpLU|HmtMk-JeUnJlBZl7T$^fjr$SNs+g6fDwJOwrg=xC13l z7GiZ5XQLuL^fjZEAY;L*3j0O=Z5}nZRsJR&3J~VqmH&6g8?krSzqfHm0iP>|P{7 zj&JT1p_HkYhAX6hy?$*ZYL=b<0Z=FRQ~jh;)cn*rM&v#E0+298X;yV_Y)*^VyiW<) zYzNTv1vp(3z|%IPoI#_%PRiXByh@Kpd`Zx0vb?4GG&si4Gc_VR?(1hbKrfCX-`l;q z#5-8iTdEqR79h00jA~JSZr?2>~Xq(%}Ft zq<6F9;e$Z^cil;f@xvPE6j&(`r-#3l9R5w*rNA<&Nbg_{h630Mk7F!9f?P*L&ihg} zq{_fx9ZmI&jIUf92<7rks1k zFG&VH;Bau0fJj6Cr#$P9iTGyBOE!|QX3Z-o&{wF6bU)%swTa;0jwi$3HLHATazc7h z!)UnXFv7h_jE1+*)_$0AmfBt#h-_j-t;a|}Hs}^`JOCq*(~A!-v@4lUAQ$^=>9UFo z2W97NecS({P&3Fzt?(qQ3ZPUdO69%Fd*fDML|NK(;i?XYgCaXjZ)a(Dr7DX1(?ki%0Uj`rP_%tehDw$z z9Fiu^Irh7GM=iKSOfj!eZZob~m1sq_5u`Z$(rP-Hs%j~{Qmj@ut|yl=S`zep*D%82 zR9t5Gk@1a)74}56kjm>^G@4+Sl{sK*e_*H$7Ey1~=K!~KnDlA!TjdF&H*n=eo5Ra1 zRaDdHUjK#A1Drk>pr{W3&zpLeJtz)`g<~g=TefZD9WOg;(nD5|=g0R5R*1n|m!R;P zQS7qAt%I4C`+859;c)Ln?%savzP$hg;j;JR=`Ww(>s7Nu)99kPqRRe|)m*4Zc;ljh zsTv(z?_b-{kXVX*yjT|>Z!ly)!0KX#di~s}M|Qpp6tQvEHF1AWtHumJJ@I_R5cLHw z0EUrcJ~@Ui*=4E|&tN=;;m^qa^js3GQHkh6%M9k}^YFKqN2k|Mv6#&#lA?SBIxcn7gk1HTGqeXG+Mg zB>$E9uy}QQ*6lf;+V$BZN6d&;tZ^Y?9ib!zThYQ3kCBt3xgtufEb3M!@#r`XN=3dL zX?Dk4Q#SHJfuH_UV7uakgXjrYC8mw68fEGLh;61JkR|~Y;zJoJO!xY+t8yXG9ZpGQBc~2l|6e> zs!|pLIDk(;Mv3Y0lit;X8&$!yBs_9MS}r~rqomXm?S_8D?#JnFCnKF8eL=y@DCd|BS=WW6Rh2ZU=>r0SEtDqCk+vc>xWQ4|nS-k1 zz-)^<>Vt+=c8VN1?yA9|(P{cIeU=i=l^Yyq?Y4OFp|6v>#__M#CENb0aOuXJLFsuNNw8{)E{Pbj`#DnoQ-WV7dY7q1B z#3_%SPuvndiBis=A z0~Sx@gyx@*;y}eF<_m;uSZeGV8;(9H3mk&wBlt*p`{luuT8OQ^J0LWe!H9V{7%W$b6(F6jxbl>v##0E5@LpCVEfk#PKOtLJCXvSAX+nqhwW*T6Ji~9*m zjeyOnl;j}i#a30geEf%Z1EIF%;f2%4-7Mr&kf|g#d2`n}8%$kYFYM`G+V;Y-y_I1r z1hBzbj`Y@3kp5WWGFd;Xz2&CS@vKE*tkyJKNZ^tpSCZO*)tTc+5Eg)Cai1ks|8D1#?OPr=;AMUF)c5mLK8*nSu1YYoNVbWD{=n8t?j#4(+Z%%oMM#!c~G z*qs6Vk4DRXh)S}}#aXRW*muQ|oZztOHJH zkKm&yN;Mn6l;3+-4OK}iJ^%t^BC}E~MA+|qsd{V+!O z|GEF!{bAK%KN)V@m=~I}mW&54@5(mtwi za9X=zR@{Nim&5BBjL{J%fc2kn?*vnghdFZAOy0bQVUGCD8JCaYdqql`?;)wL5x#MH zoP82pR@};Wpq~llY@yBX&guNM#Li607vE#I$F^9^%^ZxnX9GcQ4vfQW`1>U&(g(xw zwV6BGfDVim|Fdi#;*<_&QzuU73DCV|-^l$w@nwC zns|Z&#Ayy70{T`FWMqp=)Qy_wqc|(?T(opx$SIQ8m#!{F5xzS;QoC2_Bf-$6-j6=|+872&eJwhAa^ym{1+9j(Q5;>3hvPY5 zSDAfOyd&`HhrNk!1A_<^YigWz7{Wqb;YimkNtg9*4SOitqfd8yn#Iy)hlLUpc7VMz(m7B%zTfs4Utt1rgicC& zlc7I6ucDJaKf{U?=%g-?sGpE$WHu~G7InVux!a+`^uGTL->T~1Yf`fsD0fmQ-n_@m^(&&mbUE$aqI1je zuZ_)W>11#G4vIco?)U-)8T39uK?cafD*c!YCkaj#8Zz&oA%nQ?KObN?=XbEp6pbch z@Mp7pMG0_m`&^XN7;0-+jQl{HMM>|M4RH<1gVK|4aT6Z)`FEA??lXdQBCR zRW$VwOcufAv|R?VqXU7{V(XINvB*_q{Ktg!xrw-iJXaugi9kkS>9G8*{bKyk!Cpu2 z5l8b9QnfJ2?#me5$;q>$4BNvx{dzn-wjFs|6V%S@+((g|h4N7nVPG(CR0(ZG#b`gK znzK9Z^KAL{6Pjjk)sCd=`s6@)Yk)7k=W|sfl2s!t|ID5pSM(5mIU-5D^XqEw*axWv z=@W0HldNPC5ZELP(>&Emoka^%iq`axw>a*TfkY{gP3+vadJ0WHh#S?^au0;SM+~ni z(&#tOqI~uf9d0I^p&gPOd2L{l1n32#33*7vm*LoV13zW~oSiineHEMB5@rMN2G4Wz z9RQ9K(I#=iBDAnz@RRSXV_mBBR!^!%H7e?vg-KH3Imn<{5AXSsRLqoZVx{7Bt3Ny` zRi~+gaUx(?+aMM<$zsYx2D7l|U1yw1Ff7$Ocw2CZM>lhTLt;Jp=<4+_EY>pMg^&-V zMXm`L!leRTf%MOE4sj^8bDMqLcdhOOP4A2##b>RgDBEFgvg7&d1Reut!mCN;q*(6? z9q7E#!ov)pI;s2{ssb8M-&{<^5ieW`UTT7+Dj2$ci~#-^pM!WxnL>GSn8D*GVGKuX z7&!M{CRcDh2(B#k;m0$?^w=MXW@vWzbtbaKx849%9Za2i*?(X`<$-Xst1fc06Utmx z4FNeTZ?xkVK(-&P4{ky*iZB|)21&eQS5yK zJr8$VL(GjYS;#nq#av`t;Vcyg6Emzb>ZS{^@IRenV{>8eQM8m9Q@?V|xO`}}%ejvD zF(0HY$Xy3=6^sjh;x55tjJf0xSYdseUYqcOB8AzQblBk^O=rW0$t=P)%h9!!?E%9t zM|TS(!ZhfrMus&?eet3Li~ru341!*x-h|2lps$Q#;_4|E0JdqtN{F(IO{L=r|eREiSCZ6|ABwUrHxqzy<57kV=~=)rU}2My2ox$eX|mUx=m z4IU*c+e4##`YUIoam3ar6BwPaZGmNCVpN*(ll`~ci zkpMp&LhFh5odz>5)j}V7)6lC)tu}Ma^XfsoHnheWK@!0?9B&@0tbG!P`<_*w7Ke~= zAt$YSB)qc+n zfMewpoj7E`Kvf(XROjWn_U>^jU0rL>DMqMVn^e8Qh$~M0qCIv-*kLYOR8{0<*Waty zyVxDmve?71#@wsFvJ0Iy3&|CGKwNJ@p4Z#q4a(%**@&fMS|4JdORfeJ9aEm1r}a6K zf?^8(r~0qKIA^B0!!y7)Ty{TodY|6@%hg33@3?nOUKe){-y#I$wMxMeH!z3GwOd-q zQ<-w#HigZ!=_1u3OL?4?&xzvzs>k_J?izdZ94F)v%E2~9!C zLcQp_S4Svx$$R-d$CjtJ8Sot2UvcqAHxRJnnr4hjodg3%O^OCQBmM5sVR(eh!#+C} zN@lxB*Zc0(-(!FAksRFn8Tu=p|D)}u#U?{zw?}qBq$eGHyn_X0lUv$EWgnucN-c&z za+#&d7&d^~W`E6JJ6c8cSz4K^3UulD`pz(XmFQj0{aey}NV{>|V;$>TY@YDHlM^TQ z&|NPlLe_ToN~D0$Y&QodNk~IWMae4zk4ln=1?TJY>L>Ai9L;yE=Gg69sqj*t{|E10 zJz-uDIo~<#>{O-wKh(a_D(mluhEY@~)4bHZ>qeY#F*Gs`yS4jP(2MsnbVoS$835Y$ z?dyZSHZi@Rxq-kS?spmEp0KIg|C9+G&LAW(?#BOqfQVhaj);8zk#Iwd8jZBX+j;sN zbt`Gy!5~I5OBki=`Dlb^D#iiXTJL8Dkg4-?G$0Q^A9}xNls=k^mjGm(F_Cl%pP*Bi zr~i)`f(@`>ja8)BsUC~&c~WF=xN8O@gG+3QE1TcaB?oTH)1~{8>f%#lW1rjmIPFh`%iRa5q z0I45(e-%vLW|f6E1&>>3{zdNv?iiI}I~ z9R|^0L%_sW7}y_GBgLF~eL&0?eVW5v(+Bbe8KByS3gD#VLIs+O5GH2tOif~i1pC@F zR~^F+Isx$yAB$($)LignF?Q*)3{zV{$V=s@BH_E~y&o--DWOe2PLDVYd1|Jm;vusM zG7c@fybc|nFXl##TVmQB&LXBA%%W@5IM^dv4)^3SuAtukh$z}l9 zVcphtwX60ai3?aYWD56R>d(E~F}S@jR?yzY(kaIq@y7PfOzojG{}_1cYw?4+O1W>zo;f1!bma^BYJ#HCdQY}$(EbefrQn4xVuRwuj67~K;3N~lwh zkr-k<;x2SB5Tzd%6(<0fsL{SSgy6~$<;K&hl$8tyVphh+m@z&FZKYsC%3N=3dSgmx zMYSi1C?YqYo%u2KY|}aOC?l<|z+tWrN5UgSRti`91$lMHb9hkzC>k`E4;(RLM?TwVunk# zQL05Rfd0bOXwm#)zjUq1i~HV`GaDux32xoVnOC~poc5yt8Z^1AmhQ>C4snv3^Z#-8uFH)a$YcYrA{P{D^Y8WE&)7G5vFrGYcn6~pe1 z49rud-%Mryeqti(>4}MnGIPNxW)(xz0~|v+yKo-Nj8_2<^zbz*t*XgWZ(oJrRts;S zCQ2?n7-^5tOa{k!078Rt+N=8dQ(KzZW2pWPiwaeT`B1m(pNx)V+dh#ZgLH#d>|}}z zVMa}neI}XLU9dg#5r|q->z<-Ab9?{L&mMasMD2pXXia4<#qK+yd%d5|hpSv>TWBS4 zt>QVUigoD*mslAH?X8r-q)XLUu{wd2!%zeQECN{HvF)#+Ao-5Z5;jn_+w{4MVN;-F zoFfLnDM6D5rXD?68!uKP9lZGBUl^iAX1L;&c|`54LgQL(>kv^pnw3ZM1$BQhGYdFJ zyMQ!?rHF#=VXFm&!^sGB19ZNqMG97D+nVdhnA3{uq4oeCKy^2xx}mM}<0Z@rZX9u4 zS&tor7;_Fz6sJ?B55?K=2wS=!@`jua8;IZm^I!4+y~_v_;0D{>5R%`2Y|=hAoOJ7| z4aqaOKlNn?NFEcKF1naZ=khFVV%hqnw`eQx@bbXppZTVl$d6-<`;YiP7wVMV{IL?@ zh~2T~870Y;^^UM|~-K#?i=1aIkF0@z^Lqpr<$vJOsaI7MrC zs~xsbN%Upj0cbxs)Ue=rT5T)lTK$fY*!ph2J?ZwdQmBLE^GYgCCe)D4eQ0D8KNAF? zCAN^5k=#mDgpf(bc$nAPmHUEM;MeQf29lapYWWSLv5&InofX+6r&1dR^97ycy!5Q+ zrJ+D#gFTBy<$5R~-}hz~XhwVt1#Aa-hr(p>e zFSK!?p=6TY2PR49ksJ?PGC2iM#oKyDdgH$&hFlluw zorEEu&`*9C&SG_wPmwy#p0)Kx(laH>Bfb}kHd0DQ0e8?(S$nRjKAlh{vK$I(CcL_i zU8%H}%QP&$G33d5XAQnd5T=u-f~?}Qxe1SX07efNDKG^NFgfxv$&WiRsU&8hB+mHB ziQpOWUwXcZF;?;;8@s`>x#`dsFOReC0L)($6NHEC@7pmixSiFiv!;kCh^`!<>(*+S zrf+t?XdOYAMl|VAp8)ZHbdxRdQk~|@A0WT9f<=TArkfIz{ullVz_-nXo$QFz9{DNd zevFW^7^ex+!IR{;lQmo-xeJw;yw{wClrUM(pPqM}m}Wz@I$cl_(x?sQB^@hFMjhd9 zF`Pe^WQJW3j8%}>)*Uv-W;qIQC5GAAY|zE@owVerw7~D-6*(ZRkQ!xuc5Elu5CwLiw2{33tzUHAmmfLypnmvHP*2? ze1x=08v>|}1!T;9B&x0WyvlIQgtJZP-(vhUK*%Upy5Qhjv%wSuD>^6yrJM#shYQ(h zq_LGDFZ@S3o?kf)sy?!}9ssht|2a`!QwU?dG?7Bc#5leQ@hsoCNvhPEEJ@1?87Ca^z^#L zUVtbJTu`Vm6zK)X8%Yl=z)`7~)8gtNz6=_F@D5REn3{Sixg}2-0vn>T+FF{Y-zyp` zEi;9d6o3U+Gw=ts@@Qh*yo>GEH6etw+zd27gU*|gs6Rhy0<~+!o#Mh0E(Zy;H`eL; zQu|Pvh~^Y6WvEswPOWv=2q2ww4(MSJUUGfHYMpx^FIoKqscq&r5n81Ne)Nw6*GrI) zL#cD-0?V*Z!``o2zU|gq=rSN`)0Zi>zPN+-2dAW?eB{_rICbl8#DlpM1h5GwJ8Nes z6z*{Cl(|jAhFE#z8>X3(*^P%c%gNMw;}cZ7&s6XF?0sZl>$|SlL!;n+9}_Vbo!81} z!%5a8vH(x!CZBA=Z(b>yj)iaZ`78!0u8948m_RMXvkzbBBf1 zPB+6_B>9Wr{B|!Gg1lDflCuP@((5fp1e$64C>eO@B3`oZ0|p{-1HEegW3LzAle5>s z{#}p%N{fkUV2S~NhFej$>34(+L`+5;US2kY_*`a6gb;rQq+xBA-3icU$9l9tEHZ}j zw)n{Dcz^=#4g4OTiF<%Kqcq@L9SlKme%8y>v4ifIGNW#)CcFF#K**{q2`5-?W#2$Q!_&%MeZnjUgOaO&#U`cggQ8E$c<*r zy{|il29T|c(fblGb7$5SlpQ`|iLzm7B?<|VpI+SsJ0keXb~kdYNQfHkZG zJn5*xBF&k}Ibbf2DndKExz~{`Am~k@dr3C81MxxwzS$I7Se7c_sDmBIkCy?fHdHx3 zifHeNp*c)c|1heKmFp72j+b^UL=i8jUciNefjqjs3%nAzPk(03T=>6hoO-C{YA_cC z)Xn0}JPemcPp=PURw%VC&FTc21jTJxVzRZtU}k^0py$p&;s_+dT&o{9hzO$s_WH<5 zP`0b`i(W9j)k434&9gC2l!r&v+qe>MK%8$e?LpSKJwk$~+Iixj1V??be*`Kwm_A_g ziwDw6s76a&YIZyAasF7G$sL|!d}{jx)M}O3DLOstM!}tdI~nL6D^e?0h3KVY-~e_E zuT6&Nr34t+Q*Zt&YHoiM=8b!DLEn36MDTZ8+~weB~D3+58c&}bOSdOv;Wr5tptsb^$FfK zd81F&R-v-O)A7NWGpQN~wM@K0Xw{lRGM2Sz$}27m^t=Z^c=sE?q0}35XC80t?r6|EkSt#kifK{-iUPaaP$R z8Rc#I8U|HmDcV$@xGorhMjkSaVakC+Rky98!4@=>^p zC|9(lLc+B+G}x)Iz-I3|c=A`%Ux)WQZ%^O6VoK>R+t(z^ucY2s(I3+gBm;P|Z=|`xp4ubEV=0s)Y zS``{kZ>^{4yT1rHnt)mAXPm?G4xpGm1w8-erZ-*;9g6WaEB-DD{|g3*Y7zkR2Y*cs zMJOUbv9&*3`~~-Oe)Z!;=k15=r=PDn|Af!DIJ58Q{@HAFDM@z?HrC$deS6f&F~Y+pk0pv=jE zBa7Lvk1j5dRR<3A%r9}H18wVvligSpLX~ICiPnZMOl1Xg6{cLP{ow(;Pn@84=#FD( z)@uI)=&=2iT)oA=hVv;yLmcNNCJ8OT<;Q&wrEfQtHlQaw7L~#$2F5rQ!zOdMg943> zq&o!2LE(|%CU?G`$?vE0Nly@ES5r-H5i6nwG+VE!QTycZ0^Ni00R$ARCRjSZE|=)K zsEoI&x5QP3&ao?2X0abZ+ctrlbmu%iGu1kOK80_tlIC((AH&gLfbJsR$HU7o9#0L4 z%MU`ypCe$hFFMUR%IzrLmz+3XTS_8za1T=9s3-X^^)4)kF%SU+k<4oc;sNG@4GANg zSe;H{av5qZQVgTb4H(e|nZRo=?^?(Cs2WOJj<5sCqL$bYj3VmolhLUr0@64$b$;2l zNp4$zLy8`4`&vEg&ljKqf=Jkd{pWo;j>q;>_x;7$W#|2w#c)vr9IB-d?}pL=+utCh zAW}=*x``NPMC4r>tgzAI)A_k9LyLDQM*-JbvD4qx^fUOn*{Yt`Jol^!`1cCJLa|Yl z>w#(hDVw=l%l#tHQ`qiPg8G1!H7$JSVZ64x9R4;dk?5@`;_r&&2yZ=;vkA{lnC3|?d{M^_g$omLJA9KIQ zE^MT8#nnDBVW_d7eE?}4&V2(0&7NjiEeU7B6_9w@qTzE~fZu3BTuxC)@eb+8+QPfreD>i}7s)pqGXOJ`@qz)M6kC_ z1ZNFY$|*3aG@3ucZ9opa!8p4Hd+XQMu~VN}^lqFA{&0Q_dCvJzRNRA}$QH&gPA5pv zlx0O*7D6I?AhcvT?V}JG829yTlkM%^JKh{$I-yLYeO%OzU3qALU%e&q!zq)sJLml~ zqB_5Y9DLmD1d+a8fSIpkAdUUQ4m21$?e50jQ{FSXyaI}c@$mSidcWuR$ASd=XouCF` zdW`KyPfS8H8{?wi2nFtq`wfCBMKbeySpOIt&89P0ID`CfBSk#CfnTRxPK*DZInL9n zit^?xq5%;ZJj3NwdT!0W6Z%zHm?)DC4=R*kA#C84-r{uPxidWLJnt|v!d}riTQ3mi z8(Hir#{l*xK;3|>w1+?Rf_?(z_nQ66+eAhy<29!i4rDOp6uU8;l;u;Cl+I@Rh!BBI^_sZRkFNS9t_H$Wm4H2^>X z&trG)D#Gd~JnMqU(GvrgC%~`;dyO^L{inwm$I&j{S`x^L)ERFw-pzHjn4Jvs@aAza zZb$`&^N(}RQ%b)kdjD0s`V9=Iut16D2gP33Q=t(so^X_1LL0bx^wkJfyx3CX*zr6S zQCcknyU}Am{4&Gg1<3~kyJ6e8rrFiQ42XolN1rCG&fodds;o|9V_asJMSq)MAcs=J z5gD%x>N0iw8o^v0FYgGtkE>q<=PTNBIjZ=?>#yWk(otgc&kc^lj5PriyOz_?JgS`t zJ}7aJS40|Gk0~;Y5Ljvc$^+QxoeT{HCduWDDmuPcIrITrM>eq&DKHtW!zegc=z( zg{)cYE4YbZ`==wj+?;wfyieBGQQ;@*IQAPgU#AioV6Srg-OV?#G*0&>vj&8&^F-Iq@$-lo3UxJPyCewAA6J8(A5>%t-K3MyNcwgM+1O^o7=vKI%(TM z&K`U2o~uV8&z|;=kF%SnMZb6Nf>V1smUg99laP>wyf`<3MoVpQ=V|8U3vyC~oIX+N ztK(+CDT=}mxe13v#lIT`^Rr8Vh`ycOX5L&WoI%RfxZX)b5X;`kHHzidcawzDo+ZJZ z#-vB6%NOPX`jLR(@A4SEhhpjya3I@fan(}J!#*eO!&?lqtJm7wj2KzK82KA@EY7W$ zDru665zhr807TUdc9%FzegHf$OrmhSiNqeLPOSmE849c@2wi-?$~EB{L%al_3p}@bbZ_>X(8G=yf0Dg&%a9 zFBYAhpL(+{VmDsBK1FMi+?Ray{&6^8j*v@rQ<8}cd|EeTRq7xJeFph1YvMH;LYwFc zE$ky}BShiI$^wWkMhk@d;7MyD@4w|%3V!QsM5=@UUAus0>Z&v0ykhudSY+7Yzr&%l zV4))gH$EyFl^PJUYPYs_<=jgB0UL2It_kd8Yvvozl_;=jr0)aws+ZD}>4hwTb^$iy zmt2(U-BWj=>*x5$%kyy0>_uv?bLU{&+S0)snJF{A4cA-9EqX&N0ZEy^9Ks7t#)qIYN1@jLeE030xt@(s;HDobGkW`u$@u$R^zu@|SP4mI`jj{sqW z^pz6!iG9cK7NH!X_CsL{lvk4!j(mX*9puw`&A7qvA1ZI?u>c6>_zm0*2-o$VDxn_2 z4V&DizU@~_*ITXe^eN{qbA&PWXcZ9D+PC2$xOcG3jUy~Utr_b8b8Ipb+eBJYB+(aB zzFkp=L>c^RNh|iZxNWt62u)?j%OSIy$bGNSm|HGPWZWeoBI>(vYkXEI&NA@9n8q^e z%|TNfq8csJx^-E%K91=?kVNcIk6k(&zfmK~#JPYKf^Bse1@fFr7dD~Vxxo0k5u#lD zE00bBlBoRvQWu|hRC@Z&+WM;wC&&q*YrlgDNt7?`3yX$dbm2BEqWaP+(-O5KxwxMT zKySvqTm6+D#lY;Rh;g!$$@2!i$b*tm;@PLThy+vx(UV+^dJlrI`C0z0m?`bJ3wt0L zoCDyOdmvG}=aBj&OL1e=oa3R%i!{{Sd9^>;Y^Z|pb}6r#R1j!iYvIoTr~>-AiP^W{ zY`y%Oio8_hIYmYt%ktoo)~f;E-)h3W?(6nE?|=QA0_O@$44b=6JC^Kg>chO*?y>$f z*y;6~g2KlPqf~0DM}Ld=8vHeqJ@zVz#seQT^Lu+rrM&`JH6CYZZCn@s_;iNmtq+~= z-~RmRN}ITFtH9x0{yD{5LS~lhdI&t1dT}!_%dQ}NX(k=^In|q*|I}HkGddJ4ZZ4-! z1S#(!^@#M9DL5w^;xXOyt{21nOUt}tGjP{AGG??}!_t%c9H@gagQ)<=6GcEgG!#)q z1%m729f4mYJYr@gl2Laz@`^XkD=IJ?WZS85`UL_yrun2H$zE@M+x;{;a4GjwA3A_H zJMy1j^*<&MRYTWrINiV*aLdxy8OqUEYYNd54;)WinOQ}|KsHhx&)bD+B_OZ>tq8Ll zAH`FvE^Cv!D!OXwk_pfXT7o3jv;wlBL{xV={T1m&ZOc#ve4@7soC{-<=sx_CV#Kl1Cc@~`~VW-Gi%^L@^4cIcs_KeK+N|Yvl}fmzzJ zSQuRQv5Ga%rBa_)Q4-e#HV$8XS`UKvuRPJ55vy9q@r(g1+^nkpLU4A;3l_BE*;O(Fjr<3hYrov}dpG_yOzC*$F&V#&G= z#{GRzxNx!@GCBO@B<#f5$b)_J%H59pB%h(UJ2A6EqohCj9j-;&kPGfLSrsw>72!Fv zQ~Zay5IHi~KB|&~ZB*fFDzi0>j-+BRx(6SBG=K-zW4JNyeI2LmK|qW_c7A9SPE{iP zfGXEcuRoO&yZ7}yBlqK6Z4-ms&w9$1|2q@^LIv;i!F%X5w#?l%=QBd^4pic|R zY-2CCQ*>S5yu#fN9TjWiHB0Lr)hs0T9WL3oX;J`!XhGnj3Y-!*m9nX-3oT?=97%=3 zH~|%bGY*7ts4HtiFv0}Kg?GVW0IV$FRW!w}YfEp4xX=qhi)$X##~t!qL`m!P?JwEo z)!VC1_Wo1n?M3(W2Pm>U4y^?t=ggj*P?$pdkgCsi<(}5F4Uu~%%>n$E_mrg5)sVCA z?&$uac?YmGAUP9^Li_g$<}M}H(Tt1Jj?P@%Xuhqbe_GoU^=an-0o2W>li_myj9FW^ zi&&D;8Nfhex8#ub-ytA?Qy$%lDh}E_hs&!c)Z)Q`LcU8g5z)_%R7M|+a2VJ}>~1tE z%?G$gb{F4kp}J4Jjg##*K52uRLp8vMrmKQ{dfr_*${8H>Fy?c=5-}4l=_WZAfJgNIPs!dtjV}-UIU|szr zPk}3TaPvI_jC0G(PqE-)nZ$CxB(XQ-F|m9wv-mf;eB`-wb_Syxb8<>djJPshe$C(KSR<$kG1(>%;y1-NU`Z-Q$CU*6S8v z-D6EOagbaJlG~x=n1OpBwn8{C|zWN)4FfV5PU#!2;!N`O0IPNxgnTi+{2dah* z>YMet_aCn%l9&&#K@8DI)*FvE%bUHElXnk%>hB>-Yj{tn0*(C*m`bKt#(!Q4oy%|c z*Kp+IC$@xX-Tgn>_$(RL2_z0P6nnpV(FPsF6nKDg8mce zeK@*CyE40ZMe(s{-;q+FQ3Gt}^0qgb^cV;GZ*E+xyz9Z)$%cd5;lgog)g!>cV02{2 zq_tVx`()$DF0suLYC?Jd0|&c)xCQ0ismkP3k2htS zk1c90{Z#+wRdP5bms;Kd=I9aJE1=@d*L7QS@06;zI1GBtGY4T4*t4mxSY=)?XwnHXpZ_ zGT+U9Gc$pts;)1HMU+5~W(5 zD-UMnXMhO-S}KaOm(VMk&U!!$hJMz9J3dinSAmxy6(Aq5O0mTg4%12rxK+npfSUj& z)f*4nqk-%{+;-^xTPptOV=pn*q_1nlNe3Q2rj)BaN5qwTBT{s6@noM{872)ltTI*w zE!+KUa{lpAv|bp?-lLnI3uwMON4ijsT;5@+O^N>n_{yp#Y2U!&P%)Pj#930@L$UQz zglJYE*!vx-9`;dk0+Xq@A@rLBMPVya8lQKf&M(F1Vb60pvGnfr+?!2qgtdu1h+U3h z>3RHN2+`6BX-|ALdsbM2g$8JB(B+hfygrvZMj1;!uVgzCoFT(vMkt zaB?CVYTqGi^7c2E!WVc#+pvF!iWKzlgAe3nx{@ls_TGff55Y$WTokO8GfE8Zm&aKb zf|yGX7ey-0gP{O}Xn=?b5pthjXXuC=-ME2~W-)>o@6kDWRYY-`^##du2}cn&$ZQ;O zKQ-M#FWotLtC8&ty=EV?xJwslqWAla%0%c)Oq7X8BIQX=MA)Dpv|Nx$v=U|7+o8-p(GXjuQ&Yj)!O|uFiJgP+j!mO%_*=<<)C{ zfon#N={JvKberShuSiL?iefDdh$Uhi07Ne$SF}s;%YUCeY?Y1mLGDJnl^Iz5Mxm30;H(@0K@>DFww6aR`pq zy2%ntYl%q?6>yzR-YwiPqoy0i*CyU!+7zmrEOd5G-^_OlQdcYA~@VniPSnr zT^kjHqnW@^{MB!A>mV^8H|n(6?_GdXg!|!CCNu(r*YF}AsBRNlL!JMSdQ5-{vZL1KJ{sbCf8KTfkski$I*o}URfQ+ShD<#=^B%hlOmG(H%(9-bYc=U%ehgg zbS&)2iM9%zoFFF3426{n8*6OEGK5}NOs$h(%FfS2nNNCLH!cq5GLVXBq5s_5)0w=K&awIKJqI?-vpe|)& z9@VHOl^`Vb)%<^BNiHNF7%W6eq0ZH-%rWaoN(D7vU1}e03F=!Ngdtxu+E)_Y^oNja zs!|^D)efLLwb7}HKCb5ET7?{YIF6k#08P5wqb334!rd`>!*XbJn(y~i9AujuoJA3u z&#?(#aEt=ZR@($R2xjZSOkgz2YK&&NjL)Udx&6_s+(gyY4c-cKYh!7xstm|b0n&Rf zIJ)kFgmBn#$iSoHRjo~K*ER_dd~|`UYJ8aTp}tYo%4x*W?-UAFa7Hhov>ibF4ihDv zc@-h!^W;~oJ$-alZ@&1|Wf7cL$t1$=wQ4OOH_B5mt5H`R~|E1Izjed;)w z$;HEUhnY*sV+KKV692%Fv~%mMw4YyJd5r6Pfft>fOePStx)~Tlrx;u8fs)tS%^7|M zt{8sz2b|t!b2-`E>f%RFtjnJ<(rK>+<(Qq0=-C~25Oq`f!o^)12NkeLHDQHV(avE% z;2T!kzq*CQR>Ra2ATqiaH6>&8?3Cvk&w)A&l)sogiTW2A|3pXslt$}^s@laJ&&J)h z{R@{2N4E)FBMb@2Q3n`44(HdwUZ~ctbkCTiPkz9v;NFTRL7hu1TncW--ylj+gs7~v zeo(KHGbmu%rXRGpo6fDl-(*$ws0me=+hu!Zp)o?{+J`uAONQD*Gh}pokK!o0O|Bnq zN-^p0h;3s{qq=U-bHAKhbV3xH_kacSCz*3&KTw8NHaxxX9NTMEVX?BA+g=1{&t5QNcva-O61MpUD6x>&f=ewkfKf?T*aWaBE^BXv-6*T_nWUq|d3U(hWYIK&n$wNBeLlVAS0z!riF(728vi1gD zrnlB2%>Hm@E`TYyeG%vi71S zgpc+&yMA0C`-~}{__Xqf8q<4RIWvANgGg=YO#CpOs#DpgQovlbQL#wOtt}_7Z2qUB zwrO6$`en$@*bL!I25!MN4*gbjEw@?^Gqm7l*PJqh=)kFU28-jQeg&1O-R_J@aE?i~ zgFOO3?>bgMx)(nT#GYF6C5a;pamsdD2Qx(}GnucXnUP@+`{>bFF(J3=o#3Qzw4qn)@RivMq&@u2x#v4A9Vm(?(?$*$ucIg`ykIv+ztZ zw3B13ASok*2N)bs(z;{R9^}jJr*W%;|Lxj83@(hNEvxSq6-g7Zb5F(Rr#1A1*6ijA z_6}=FE}})gqz+-%vzC4kjD2yzlwu66h%yc1pwW!LgGN*?|B;cg9U&xogxOy9OB?f* zrIxV4qiemE6~W{>R6~ceY2SGOtj!A^VKjEba=(2J4o6C%rOf0L4eUn%i{WY#CD#Nj zi0Gr7HfqvHk5^UW4Hpf67FmQoea)o?@G^c`_n0{`cbvirYYa_U)8-$hXh}ejEG{|RMWeKxMUAe<~AiU5iS4QAt&Y>SX0qbKpzwd2* z!bfBAFmV;3@TDp&R`8c8+C}XO@QeMI$t7v`mR`Fy*<#*=Bm+mbI~cki(;>X$J|=4H zIf6zW%8XzDP@4(b_VeE*ce=9|*a}#;1ThW9WaopHxAo?}n)`2tU^!-*%LmHd_&8^N zA(;6rEhXgdnPoE@C4Xk=M#vpI)P#QFz}R-{w%<1qXO(w@D_9`0fd}A(jU%Ihb}oLo zyTd0HPlQV&tNA~vRbles0&+82O#!O_!IY?cr@O#l6fPYtPuzfVI6>QN?{=8WBjXQ) zusgwAsMxH9hV9yEcesq>#1wUJkUy?p1!(7uOJN~8nPsY=8n!(Rta1HVpCgw5UK~gk z2^|RBrj8mNJdbDqg87gQl~#jgE>##H5=(iOy#8Dfwin9~+dUQoZ_nj*X3RyT{BLXK&30$IZ$DP@V53GZokz6LtD8w*i9+Y;; z=_;{*(ked34%ZluuID|pz>`}7+oIOH?I(IgBQZG?mZ`LhNdRa-T*KO>4ffS zvdp42uj(_2(wte(%G2P?pv))Y7SrAAlkoUqLE3$f$#Jeb>FlY+UJcQbeJgnW1TX_4 zZ_=r-!#3R=xOTL?JhBq}TlN+exqfyx8t61D8tz2gnZP(~NG!5JsZh8FurK%oKwst8 z&>gnQp0hYptOZUNmsBDS+Qm-i@mw*!%EuZ^eZmsJ{S-9!wu^u#16sg;Q6&Q5f{jQPlA*M5@S^!hy~;w+0FBp^j>xI-Y1 zaB}QRL~9Hm0DYBSwV8q05m^en_Q+3w*Y~^@cdK$E;Iq> z+;nj~2umS9_gAfEn;t_)J|d{Dc0?6{a)Cu0RC>%)Co@EvwXpP&AU7ft39>`XT4Y}^ zp1RzZB{017?xGG_TrBW{LQd~sWjrAN90+5ry~)DWYhJ%J;UUQ{Vv?Om9f4_TL5wzV zmQ0719q{9CUOC9_yOWbgN=JDT1aY(S26)NtXRoVzLEZhqMoDB@Fnvhl)3O_E?fBBU;o2vW)%X`Qm(i9 z2o@k3Kk$@mn_GE1H{y78#6rGS!6pgfVXf8s1UdOQu{Sya-f4;L9fW2yio{hEX{`-| zR+(V-%VqapvZ}h7ENzJ=`L)_l!``pZ1mPehpSW$$Y&1sl#4UHKgs{PaVxX9=Rsz!5 zxfG5Bcd>ceCkSk4Uc>;Z3QTHAF+LSsCt)dAR_A+{rC_F47!vcMGpy)V(!!;-k~wXw z!Iv%#8PKXMnhEi;R&Oo$$IlSN7IE|!^sJy zV;&$b$OpqQMI$hKAjAV1)uH!?+0DI%0QnJ2tvGPxMm^{h$})c}k%if^2%Jo0rg*SV zvaxXP$|$o=g5PR{@xu5p8XV~pli)%AnG-}*G89B0&d?t#w3(842IMKs9hpzBdnIxc zPVhe=xPw2Weiei}1ZG42#%Q5CuwKTB-BE|1c>%8p!q*Rr$<73P4;ktGkzkPT-k*#J zFBqetWT7SiP!gzLPSZKajUQZ|52c=561qiNsh~-Bb0=K z>)77Sa?@kKHzFYC89otqj+HkQ2j&FCX_rBxy;S+{al$F|*sm!NM1VYRzw(dS!qC;x zjI&cXkZSoV6ZOPCRww=1QRe0K`oXJ86@mO`lCQBM|IxX=;Mzcr2iovh8AH1YIZYwx zt4@zLs2}dFQ9mSn4CxDv@#c8SjsT98d%f=`$Ceqj+@iHvpnD3Y^XY=duj(nVODa7D z4up)HfV=5m&t+tZ`w~LUvl(?QhGr)7ftnH@V;=$iz*5@qO&&HOSAbF|GeBKPOs;~u z4zYo5m#6cxK!_l3K35}eOzvmjY=patf!@0UYyaI3*-vkO=$u}?>#)^Ap{7XXxb*zmwl#%b*RQpabv^{WOrZyO;kRe9e{RWymiO zm&onl4S89Y6azTN7ymoE{0IKVefi({mw2`RFsa|I`w-;VCj-}+dqy99SJWQ(Q=IoRvAcac)F#__YFrnq-wGSw6^mE`P-X-4R6T(ov}M7M)eVxl19CFPm&|((pyzh) zN}>|G<6#YN3nj$QpFRWL>py;W{>Nu{$@g|~tEcaUS!7N4u}Sa_%3c887AxfqPO~yu zT@%J`uGRspa-EaC!K_K?V{xii#2TtLK7>#z;0O9&JPk|B#Vj_65wni{;Hw4Cw6g$1uVwkw4mw8YPu-xIk59)dMNC7`=T6M!H$F!XGr(>C^b#fxb-ev|{q{h~Hed*Dx{SMA>Urrz9 z0F5QaEv@P`N{(DrNXnxB%AqQyzrsLOu#@>0(j<-v01p$0%k}|$Oc0g6$pBH~5gvWF zbM^LJ)`eiw=?4biSKYHy{osngr+OL7qookLO%Ol;^hO#+W8{0qx``fS55%i;Y3K?+evrHNI$x=rlACN9^{hGH*M@cq`|{4uYx8>aekT% zT1_z^sTw<*v&G%<+$+#5)j->Wh?g9#8aZPT;(t#R+J2gY6{c_Yb)f~Xj9c1@H=y6m z+2iNHV*{#^csfmQp_7w)y)f>jx-9=%M=BZ*V|gUiY49yY5tZ5}Q)Q>3Z$G%J&x z=3HVt*_VvUPdl@R#T`HlgdNd?PY`7$9Y}DOgb$?(<%JK|qXU(>Kt3jHntH6Q`-Dwh zu7Wa)(UZA7)0&QIOL#c~N8GFO$Z-`kkc=fIR+^z#)ra;ufX*MuU+E=#kF`mUuG%pP zoZZXy-Pym(w|8)vQ*rj?r5Y**V*QWGR^BFU?PX6hpNk>9f`qw7?h{C5Tg!1J9@@uE zp2}=HKA}@{R#`>*k-gb2s zP!}+f%^=|^R7d#0@GcloLxwIvK>WYar;*Rqw2HDSY|q4*Ro7)~t!C0mymvo+!oncd z>Rpc!nSvVf=B77ZKx9~oN_k~x6<_VuU;p;E|M=^F1VrFO=ztR?{Vibim6}_wCl50b z{)H8awg{Z-Y{m&<#vl82$gvy@tDSzK%sVWPL;M?(vh=Rgw{%<5f+}lMw1$WjO?AmB zVapwcwm>nK% zF2FH(!{yE#G3{)p)jCIQ6go$f8O)Bv@Ah=k>&cBpkP)yQNRCr35_FECl5~zABc;c` z7dVf&yUI|&eT>$kyI+Dr=mrmqmcr?fqCRy>Bn4{mgYggpe_bqQE+=*_c80fvMazkc zV@_$)#WgCZ>6>*WNOeAFZO*1N{f-taYO7VnHrrkl-n`u*knO+~_-)frE?NkAcS9(c zfy2=Og-$wOt20^bsQBR;o2~{R~o*=>b)sGxCp8fRmRp+1C_irJ& zt~1AZnv+^$E8JHdokWNm3l2#3oF}$G3CX>9Qk%L}NtPG{`tD8%W{P%bgj8zyKLkOg zMFG*oXLYclIT|`#W`h%Z48!5l-*eC=aeCckaw=0WFauJti|hhwM2{c}kDtTpfCQwE zY3W#ho-GF}l@6c;1EK_O?PkhZ0D!;>))YXSsSfydTUmQ!zT4ey-ZNNf7fI!3VDFYP zap`dfOlcSxAYg%rXcRKhsEIKOTz^yw*i@Me>YRn_EMe@~1NoX2Oy6?(2N?z;({ z9i5LKZb$c@PzM{%e;kg1h_-j3rE)R6MMgEmJig24$@O%+C`e6U>EbkaT;S=*nJoPc zC%7y}_s^J`2Ri%^gAayW>F_Y!-0UFBffIc{<#6|Wq3b)?g#ei0#0Z0btW9Emgt}`A zwYR7ng7D3&<@|x{{Nxz9k*Vmwt){9=fIOs{(<oFa`yRRV2$N8ZGGR_>8iu zKqD~#%P}HgB;y@}^Ij367^rUh5Xr7`eWO(POGoD-V~a+mKe6w{s)NgC;Y}HixEn-GECH^ppN zhZ)0;b!vN;n3+pF&%R~_hT!&WAk-iuHBg&VA7 zcw23Rs<{xeY?I)?rXnu9PmSebNy8^o^hC%j<=mPWZ1C<0bAZ}8{#{jd!tE4NwxqX| zWSXJ&BdrE5gO$0W?%&2`*_9D|421I2b==p2ap{t;VB;U~w~4k}B0yb_&mh&(C&mDN^db-OtcT z%<3*=<+J1Ay{o6Gghh+-lxyB=46N3iEEf`(APWMxUdC|lyu0ZB@Z(kX?$g`%ANlc#;2L!_}SR5SpO-80OX zd>ktGPK|6TmP|1GI>q_3U+c(gE*z#EAOr#H9zZm(weKDfOqa!O$2y$}$;hx*;ZLMThFU6(bS=wdj39D2Rj2moz$ z{*DWY$3ekxM559NF1Xbk(5a>!X%UK@MWZB(0~~~q|>V5Bl$&?tX(eJU@{u=f_eB$hl*>pVWKmSLY7)%7Ly}?Dk!n!QhAqu-2 zD(34>EV-1g--NPxVRrhcKB&a~Ohk(tnQ?}r$T>r8ACR0>0lyp~Pkf>c_-KOPClHF< zer<9=7EW_gU1KvZbfMDR%wj)6yi*g~S!!Xhbtv3wJ^KH)Al6L^^?eJ$HrTl>zWJIPIyBBXgetSv}#4orJDI~IQb1ZUdZ1w-WRJ>upB zm^^KaJD4ALgao9ll8^|2Vo-0f+!H!PO=MqJJ~e`ys50n@s_DMB8qy{kFCFhnlvSn0 z=1zE&M)m?_=3eQDoC~H)RC>ssGmsPbE;TW{970Q%=q5ZXXrq|+h87wy8SFhL__*4( zd`QIE3LrJiA1I%6X3z;Pp{+p!U?c)V))rIl_~N=~CRCxdM-1{fYuJ2WDPZk~T8zA} zgy>jumv&mOMSx+9eGaD~Q`(UEP0$@{!Z@nIz(o!nzJzZ_DBWvWF4_7kUUVi==Fds;)x34ng2`;GQUgE(GtRIib9RVf4m z3FTJ@+kJwyz~&Ev)=nE%y$OURh=!(ecp%uWnfEJE;=s(KhEiuRMXIpjPDXn-bOR(|h!!guEizUhEo^mz z1ecSH^uJ<=^37=yfb1$){0Hj(kM3Hz{+a0_xddT3F(8`4=$^n`8*gY%}S1Ejv zpT7Do>KT`2itW97=~K7-{yvue{-T3v$meh0%MMMdqrCPKC=Mj6kw?MdjbjSXfzoB% ze1qdv+j7ofvlF6*O*?A@q0>C7kL1o$M~nMWmR0+(qH+2OcNTG@U|Fzd8dwpn0$ z=1;HM-d3j>p)+X=0-+^?O#VQ2Bhv!^8E&&k*d}=%(RY$ZEkTSNb*r|liYW#{j^<}; zUpz_bwf3HskdP|!GnUFz@QjKqF>oqyuC$w#Uptyb$Xf*;diX{5mVPBME$%V@ zq)m29c$(Ki&9nJ+hK{h&O?l#2GCGDmvBHsC3~$K(kXz8gq$)Bb^3+k?z=_d_Mk|b2 z^u*W=+A~eAJaPoCE@1~;gLSvZZY()RN;=$pr#LE0#gE-+`Q4>}L+}%7Vz6Y(Yz_+X z$`&V9S@PlDKb-#j>ivKIXY26Q@&DTYU%Riqoh%>jhyQgugnq-Qk8gVb!2avY(d%zt z@4x!?_SLs%_#4C}{{?hNUiR(HdH4ORZ*O{w=X>o%eOP?^aQ`&AAAGwckh#Dw7fXNx z-%_te&^x>V8u0OE?iYPvsdx5km^A#Ne-nJqr&Se4M@VlKmATda2Q2>wH(ghJv9wF! z7;emg8u)`x&KKQ*!vpYyIgcjNaSE|u$o~P-qZ`uM%@SC^xQi~NL}l1lQO^9C+wQaO zoC@E!BG)pt;l#1IW+DAr9(1K=O~T>0Zv;lkA+(~Z?Zia3XX_eAE(k>wv8m!Z>ZAMv zt}KsN7k8K>f)R8?nwO~TyZ@p!Bfz;GbZ+CFUYy1J9(jh_NnwT4_N=78N>Ackv5YgU zE!IYs;g!xP?<&Iy)7?TT8;#r>xk&LXtP5DU#%K;^M2R8{K2b$#$fjacw~P7 z!IS@pskh8-RaOsTJK0|xz0U3eGVk$~noE>l5sn>uf*{{G@xI_dq^2IZk)re(az^l1 zZfmv=7qk3R1>m7rCx!PhUy_r}0p}l}zUD4o=M?bMD?_15kfGi4^Vc`Ayb{f$FMCYv znUg107B85PG9@{4*?S?cY*3i8kd<|?h@7!bk!lk;S9B?(Q$$f-8S|-++&{O-@&DeR=NN-f7xQJ!V-<) zQ7$$i_DY6sKE*eObQ%`M(7wZF)0-ZuUKuw$xuAjm5vKkwP!NUEkw_?M;lj4OrMh}X zzUD-ee@@01v;N76{`VJ7-4vQr?59$sOh~oB8=<3IMBh;ogJ$IP1|%}k65=`b5Jc$Y zlD?>{WOn=@BOxD5H2ejy!^;9UxY!R4C*CZ|1qcC8kzfHL1a<}-A=6~k$6SueW}a*G zj}?J9*E|(c5+d3NUa?IxO0+#Bov5^ti#JM9>sl>82hbZG&Qacca&12*Koy+37dSV2 zH@JH9mC0-YzK|V%HnZWr_c%g)%aQ>jFQ?!P5t^*+wTZGH*;~XIs{3iO+c|gfS44m= zii1mH4N9}{o^VZxy#a)%s4<#nllc2>l>ysK?s;nt4!uL9sl_S|kio94p%Ejq!pX4a z1#zGaf~OY*OzTXx@HLv+Tj=Qd+sY1ZPa(t!>n9a>mvN$XkfQl6qS=^f?;rEW6b+@- zLO(V_wYT$m?-}BN$Pa#1xm@)glZWN-3#j>S7$Ay9xA!W170S@H_C=s!h%T7L66DTf z@H162q?5`hkSZL=3t$q&(9<}DeeS6~ton*qZ0~t4nlp@}5pNt$SfYlCkNuj?)KfNh zmP1gTkt}A^9h0;Ome}SkiLn5VQJ%tNS*<+H0MBfc6B8Ms^}?ITjxk2nSKHoJ{ET6D zgmse%Wh$jQXa=`BHLQ#&ef7wSners<4V|h7D02=mPhW=^*+f!|Eu0E!*35)4XW|q_ zFqsMGCVQiM4{9Tg5qyNxG4~+1>Gk#;G4F;1g%?C-s4fD}T;b+7CH|sRBTD>@XY+p=y3x;@ zJORh=S&ej|xJmpQfbA*Z_U^fT?0ooW$&`0`~)`$ zEdMxE&etZ9F5q#_huCfGS%M9x=^s3E-PuRj9gfJktUvE?xig)%FIDGm6u{;t;{oSie)9-nYRJ!7FZd zKSc27!gumJPW$^s-=1IoGyn2m`IqdFk?Djkwhb#%QB%3ZYir@1QJ(wV4zjNg(i`-B zV5*}KN3?!sqM@tuBg0IoMU79&Omj zzT;n-tTgVr@u3>l+l9t$)E#?+adu4P9mqNifC0lw0&L zD|)+;P(a#7c=mSa#ts8Fc86U(oCB|Lb0EoMS-=EopG0u3VaTFRVu-x=H#woS2rg={ z=wg$%A;`qyxmZjn)O~bq!+4qz`SLmV#N_Xutr~{xaxl8Nu?(}qcvqrCcyld1X6!jy zU>w^@3P4};A~X#E=7#k~&_Y@}k6`fdBcpnwH&jX`wR9&jisVs|q<{d9iCi!}Aw_2O z&ZlD$b0j4gdz+V41s$~7=%p0HNKIMW;gLUOBiCV;(RUE10kS2uC2*(TF3w33> zCIn&kizVqk43!cj3AkPr-}){{1^JpDUMw>R;W5CF+LeFgDHr3?L~k~{Poq|gRBLuB z;F{!8=E1Q@+9b;@Q`<+2?q+phFlamOY~Z}uH)jzF>Z`3-cCvOs+N^>TW8IqaLo-(FNu;qdq{Lrz7-#5$A{ z3-v~&GqKcY#1kIYa-|$NNUmZNY{kez_Z!JOh*FuBDE^}fRli{-GCUlVkC3=EjNU)isbMav$?FYs7nqMC! zC~+DEc4}VYs}+$o`fI9H4}%L13$1zuQ?t=$2S9$~NYZG&w@@{ZnXgq(b)j?6uF!w@ z0sK=QfZ9KODO|FuOrZ+r_4O4m-MhWR*t{^omQ)7PqMnGuhGu4X{~UvKj;DJqGYa`E zc@AS1Jz+(*uH8u53pAxeMVl)WE~TqBXrC3CCelc zoLU}P^3V0{xA&YIZ{Qd<^JlK8tzaGd{--2V2JRrv)-miH8RYOw4>EVaqERqO~IR0qG^e!18?3(V#=t8sgpH5Bt0Gf zVrBP=goh!M9(5%?u!IBpVp^16rt?mNr>0RxwTs0?ZFIKAtNSD=iYPlC)Ep(&(2;&!xo&rqG81Z<>xp6ZEfx`G#@2iBpROhmRDmdzrG&K#V*Ub2Xa>o{b7zDSy z1!_!@!5(Hi7WT2Rde>;7v^4kQ`YW_&%{AZ(p&!EX3Q~h(#b}xCO^<&<8mI;2y6Rs4laphcTz z+98_(7Sn36Jyjm=!$K9EMdew3N=}vIhg3ufbxrpcd$G}8d_>?{QjzScW)B}-GCe_j zN4kweOR?4Pj-I5^=D340*=FlZjSc2}(#|l!kgL<-PBN3>@<-kc9}|3ov>guBSV-+t z!(*~d3jOHYv*<5#xy=~hE-A;M&9A$GY5(KMMn&7`4^IwmS8yN7{WaDrt}I?WfsLc! zRg;ZcyXd@oVEuODhN5G`CBX%6C9BPPr6=epq@0I?47te+Mu%>1F~Xqv;Om>68+0l= z4j$~amr$7Xp4rm0^<%k#_qW7ce7!_1KT5)ahgS^7Rv9S=rR1*);f56Me+}IKTH^_| z&WB2-TzH7|w%@mEkam2dM`nQrn3h&VTKhND^@k>$)K&-1h#*q1S4k9!=)DddU8Hn# z1(}N8$4@p~JX|Lx8y2|_Z$v@lRUv&AS3t*&%YrwAGvq9_$Iab*a7K@_3u@R=l zYRL%uoPQxtK~gxaSyBQ}G(hE)yMrZV%WwDEhp&&mdBy)6`lxX~dpANGor(W?BlA&U zOHpz<>Mky!Z_s0#HXfo(!rjMPX5CMt<3fo7$1=uAVNa?W0(giEY>x(BK1!t4Y3^qO zu|rGVYua&uH2A))L&WRTsm9tSQbLUaf|vO5l~s;_cwcGfoTvm{jIa?}$2nsMB&g3K zXT~7Kbx0x`e&*N-*Z1ikn`CP^d+=I8>Au)jme*42A#PQl(|2Tk7UUXcPnE;krusM2 zj9g(!wr1;KstHo�w6d=IGG|7`CZ(NIj2~aNXa;cq%;Q@gN~MG^a`rmiQ}U$G$CRKv1y~2M}GIkz3z`N zZSK1407X>WWY~mNVDRMD4TR!kWCm+59^jv0 zIGZeP7bhnoU!;(WFRQ*0!IP3m_S&y6wH~eg4k~o5yQykLNyI4z!srm!f^dl`4!L)+ zPCG92+w`rEB0PsLGUqrucCuEWEa0+G$swD-ggg?C zaVc?&a!*j*!1G@~j~T@7oR3*8l9c;y`gQcVKs{Eh9uHY|^)LefDlrsACH~$>RRXUp z6%vGw9`S!7M{-9mcE<$|4~i!b9LtR@pT|NmYqdL*(Gn#5Oa8>Pz1@7{4Xh47Ht?G@ zX=1YC#Bw@epGGP|f3oPM)uQVM`5avhG-Rkog_)pgY6h8Ez#}GS!RW*Mn%Y^xUnWH{ z-R8<+&MlfrRH=T-LK!Kx2gg+*7{Q9JVIlY6++2h1{N{;uUq>r`$stc81OOdWcpN)N zVnRc5ox*dDUzm_#)jzEPp9X9(1xp}pDL84r@6ja0?+{yxQgkX~P)?xArsk12pW;7NFUjjAByd5o@(Yz)z zO)$BxcT8o>G;#wI5*QnsFHP(RZGDMOhVQto>F{OO7lN# zza8l+ZPF603iwq?pfvDSQI==eZz1?BqkxFCg3YqMheEbdd=LRc#TJjqlpVzNNo;xj z6eMVSp8toee&w4z;i?LG!xK&K6F~HKJ{A;gdT|3)QZ6$73^iN(%)jt6!+@owV36O_ zQgV_Q*v0&kO54l-=HKW){a4@mul`TGd9iw%YO!A)p`AvoQMy``ideArLhb--mTjZ} zB{1ImKGRmfrT&Tpcot*P3qsLVN-}f-!TcT12j$9+ycD6H{*6b3(6Wv{;^yL$(W4lZ zZCY)u!!b<7+|8k%&0(g zFUQSSK_2kPMbicNijW5@faRISA4bl4+5D@eTG~>_VC|$>SBAkH*;ec1B)s2Rc1{Tc za{Ni_#CO6qTYmS_r*8TE6_-+WbDoQ*!%#+nqr~-~C);njxZP_!0x+s``~urI-uWPe!*h&={ey#JvtuX0H?JIY9cWh2I8pp1}?44ystSIs%$dHv2tH${Ybka_g7x#8k}Cw5!vJ zf#gHUw)3_TPN8p4)FDF!8yZKX^-QMsiFxT}dUCv5t%Io?GowhoOjNS?ge{@S(`YHv z4Sv}WKh#w-M9(!U6=ora5oKOoR1TsQVhXWrztbM0)%auIbyeFXhX8bq(BKD0L9%PA zw`>--Cv`y4J|j(y;Vnq$dpvu9qymRc17(7?Q3Q`8o{UtD5JKkO{EY;Fxr8)WXU4n_Y#}286N~9GPz@Pjb;Ah zFFtZmj|jRt$>JcA$5oZIB|eO*qxQOzo<;2toC&9f6%Snf<_@;$8Mf)pZ+RzQ$%&EZ z(UQ^Ejy8a^Nr(X&C3DD=cT3h`28K<+}ap)2oaB=Eh0f zL$7mWP1LAb#Mk^DpNM&<&u86|Ji+gtgcTkw z8bv(4M9kuJIROIpjx&W%j2!zP3*?o)3*u=4C+JU%%g?HfJv zgW<^uJ%#qVe++dahBTr=ZZS4wwnI1a?vws1z{Fb=e7wu8M=EMeJFFH`v~K z_5L#&&@71L*}lSmlUR)BFvzPaDS1uvMT9tveJ`^STH*M-F_ed62yUjfC{>y{tcq9v zO|Iyu!?vitQhFE_ibtC{Z(oqoV96cyOf^=OR5+8L`Vo~PIM z(ZdRqknJI0bQS`tQinjMvR;$uAW@a7Xq$( zrr}-Rat>{FH-g$Dllp#;(&y*9`r<01j6w?97$gmW;q86=8ii+(3N4zS#t{q3ZV4L& z-VVxj$%uuOZkMGRyq1bN`C`)Kgv5kQV4P_Stke$-fBDL`NL_BQi=$Y15D>xbUh2^l zcs3f@oD4FDL@KA|-;K{X_-5)D~@4SNGjS9-Z0bTwS~Jvnn^OG;Nz(mVq}bbcIbGk3IEb^QYZya%;nq za(j~|3G+ih(dg1u{kNqWtU+CyJWQQ`+%Ydo7DI>P$nUaqRay_(G4TYdb{lNr_oI3L zVY2AYN7uu_MQ<>ASil;C8_}#|&e8DlVA04-%s3?5Kt|yHC`XU0vx|VW%kTj1(=+~D z;WODimj)2}NSaxS;~rw*gejTYQ?3$|Qi(X`c~kagRn)dmwA z=*uSvhU*|oY2Z|3v^(jvSnlkNpL&polU7fF07E=%G!RUul2Tb%pKpL}vw_JdO0)nP z7Ena~AkRVJfc#VeaZ(O9-sIV)?Y#l-C`r1FRA|X8Aj99h`u4cp-rGBD@9w=mI@muv zJUH4#lV_VRm}Gh}}$CYSsw$>iz?lgqyp068`&ELzUw!T=Pst>GW_(WUAKh+Am8oh={~ z2VDdAM>RG4xV%@ZYV7DMKuLCku8L|1vrR(>#f~) z4>vamdNB@X1#>{+E_Sa}k2GfjoMW^Wvq;kIQ+b;>$Ee2_oZVSaex9Da=bzb;-4-6M!y-&zIr9kfEz1_ z8WR4Eg_WWtJ414FdM-St^-)X;Z~f7ATNh7p3`}XAB= zvvt~g{C+qbNRqsPmuy`ym!gLvsO1E+X2d6+0~+}jEGRj}olFuF}|5lnNibvk}afYR0eF|NL(Hx)-7@>+vI+~#w2Pa6yCeX=6sp1 z!8bUn`|q$E`J-GBqaMgaM_k5liU62+Cm((_YR7Yzg=9y-UN1-hd3dZou7Qx1E%v;L z;3ku%7i1LF~|^1iJFv(jZs%G@w`KKKO4Nop&OQg%R|JWN(YrU zTDeJ^>w&vTP{%AI2%AcyrDHoiUh;0&ev;kv`k3COou|S(%~MlJNy~U{hj+p(t9^Jq z8jR-9K+-N&r18pA;|y34vlw##gLLj7oR%my5o}LP)SY^F6YQ!4cdsbeNwH^}IA_L- zUJ5)NN*O~vXyirusuE4{a1N*-Kh*_sF9;P7%-0=4!qz4hgGe#ArMQSiUOMQqEzW7Y zy~Ika;zxwz3h~TiUj#UJkDMQH!Jr*@+B@}LDOTX(75(HCD{#>1L>o}o{aUirSCiLOh3B5u{e&b+>33aJk=yRGt(^fkdZ~KC! z0<2*H2RHnBA*PH9ken%pn!2BWm?uy~x2kU7@76fB;l*3~<9GxClSLQoO-CSKh_(qI z_l8ef<_)I`0sAZjMEve8n%U4p$0oFSHOtvDig<2kavEu6qN{Ow)O<8v{9Mee_jz2J&+%E|NdcyzAacvr2=BlC{d3N zD6-+#P>=xP;?KFOlz7|)iSWzPTWnY6rG*`V(-X(6OkdIPlCe=8F?I69xrJz|7?8%G z8712P{O(D3t*Vv^yrzo?55Km^iB%sbg2@yFPYm_Xxap$J<-kAZGE#$gQjq0EpNI*8 z;a9l*WQinwM^W3renx0`0&5+ye4R~YBpgPis5ATY5*VKA;{FH57@hi~l^(`;O$hQ{DuTNUt`aSr&pjqGc zqWU-Y3EjWt6SCs9c?Z`vZJ1Vwe**6*b(DU*A>|OEScAddgA`fT)qhJS9w>X(qw#!+YI>wiwh7qfn=rT_hf13X%-B?hg2Kc7zULm?8Z z?_SSGJHYg%7kB5WzgWzKzXE2@Y_S|4>m(&u@%Ce@b%X{Cq%A|V^bWGwbUf-mGY92q zddie}Ve!)jK;vsx7AU+(Y)%^~^9U%F3MK^o;S-r+vwoW@avFMBf^;nKbFRBoncX{P z2^X15kUbLO$a6_2Lry??Z~k!4b#a~0>Z@F7Cvbgu#6YHQ@9`{&Z#>+*48;L7!0ISM zVq1gQH-E0~H~#z?*ImLaX&IslYk1(-V=*ycwJY0TcX$AqC^;H!cO28FKzchlQ9gs7 z?cB;cRp$~PXq^{ZYeo?n*-`^7_6V&phhL2D9o%o`-39--aKkDCKM?!Q%uX$BpYe3?M*5%Pc#AYi)^E#OUUU;g8f|MWU*vR@hTHwlI>zgSaYr@ZlAbq`)ii?Ks zX%9Tgn}>U;3nVZHID~}mqEMH|-|Yy0(GB9@ki{7XnZPMPRagihA0=FWO;MzbSzL>a z-LAS&ORe1-ExPxkrL{LpvRdK46Qvl;;z&<_)2{XU)1Hg3tSHSMbH=pt*jzHbF_Jcj z6FY;su@!(?`_1rzipQ$fv?e1B@@j{l5OjD0r+hi=>(JxC>PMKvpxCE$U7X0kho0RK-WIBR)G&V)lV(_TpWyQseAe~BpsMRvL zyzJ&43+{P(79Om?e(5*)G;>-O9&2D;Hbj%l`tAWa*226JJ~$SsJ4iY_jHeY83slO~ z1WKe?8uLRof^2(sI}Bv?O*DN9_HD{7n)OTCB|(mDx8NRlFl1iW z>{CaAvf$0PoSF%F3HPDea_+fn!Mw5o0UZJRMQWP^(~Eqkdd4ds-kExA(vYQJ=qR(< zMq5kmEGEy>b;p-N(uOk3Ba}aPh^g2pfmi?6{{Q{m&U`tB2JRH9M2fqVD}uGEta6YP z@my0I-KBvpffNXHy>}?(ksG`R(@9GyaRee5{R_z*5{BUXtZSqaLbw#KQ`?k#@87W& z6I47|F795w$INsjJ*FN+OXj%@B3K;a42?4n4PG?wb%rpYP9ZW{-r=z0SyY4;UpgS1 zSnwCE2>KS=h~EUU5eH*lIVKG=)~x@gB^#gKB2oF zp2+N8vKl65us{t?c@eBa*j9w5H21M_ssK^n|9Kdp5FOIa;y)SyPDcmz7iZbGcQhM! zazm+QkIGlpGLppGqQEuBDvn_7zb0i`Ybi2(ltBszS%ni4v(Xtx#xkepK zoyRM7B)L^7X1S;95x*?PlL~6QbYLsVXiDf~k+1uVCA`2OSsA>pAHKcStS|`Jv4uJ~ zQ3y-480_G9;78y*r6?(fOO9A5Pb&!Y#Fq zSy|$YQ#KC`u#xaTJB8aYlDW`~8w%rwy*kgM5SMdVb634v>I2m0=> zL~3qEZVk$-)@m`DaFA|GLJPKxqeb@~T*m&V{{CUd{_iyo;qgoy^c=;W#cZA`f;zA zJk|(6b#sJYMw>Do+e}mLt=b1DfILiO(>tjC2Kg>p)^58u7$%WH;jhS8#QJ)XlTuCj z>oG-8Y7o(gg8E$}l@kbSe3|V`pK!8Sq>cU3pPI>6a$7&Rl)?F!#GYPuj$k~8UwZwe z<;wB4pQZ_Fb_ApLza#|$7KkhbNmw3j`ZTr|4A7rQIW2{~S}5L?kVI_|*< zAkpZAm?9o$nRU{as^ppEUgc-8rbGo;y|8@#_JQW)BG6J|tbckUaMK$Mm^G;ejT2gc z%l!>Nn3O1Bs>OWB%r^J@(Eow4_j}ebv8vOzx`NS=PN1;`B7<8v8*$CwnGEj6?sipC z%?V$Ul8#4FY`u{9DJb*^=*tI=M>dB}?>l^%_i%pq*ZCMrM3=a2hw4pgfc0z zAWeloP$E1WB@DMqI?bmv2MX+wS{-Jk*Wnrw<+lzS7s;0hUXf^6JbK`LiI+LFC6{mRr(0+;DKQAAvDQpusJbKq{QorZFSk0ZWl)f#9>2xw_uX|h>36g4n}^v zxmjs8>fuaCH01^hEb6Y=vN4*dFCN^u$E-|BhLFuL|QlnOC!#2yPP?ss4FAbf?Z zb_U-pqaPn+a@9CUYQn(G?GI(zsUN$739^-+9&56J#mL{a9OGhBGzn^QU^HN zSa=2k@$4SFThzGT>5oAZ(QK~ygLh0l+jlEac3MZ0N^nCtN*+FGnVWIM0TR-g$|kdH zpJExBnD@HPUA}Xvn(GByJSsM@$26RHa_(n;mco{MUv}B2MkXKaHjR7Z;!6qQa8*$} z)w9bVs=`9{w&^8Tp%x=7d$A0LOVSyshj1rCS z$G|YG&1@Ot1ssEzY2#gqpc$Ng+mH!Go_?nYMge`IRJpHtYt-#70LQA(k~rxM&m5<0 zo5%cRRk^}=C>r+YqQ{+mlCOv=7TYq64d{CPDnq94*w3_h4AZcRy7x;Mqe7s{H3|?* zs*pkXhMvf1kqKnEUtOml>otfCvsc*&2@er2EEQ-%TyiouF#^k#w6X*dvu<-Ad*%+8v%Q77 zDi|x6-eQGS&vz|y>Net`$cO_xIbUH_!j#Q4_Qd#BirA=+ZDWjbHR?CVBQ!Dz9xZsb z*GOK5;Y0&ezx6VFRFm2s0@JV|QjLhUtk`Sn+@i#DU>o2ene{6s7log1avFy03O8cJC^Xkf;FkujgJ{IxVho)`4Q4uL-P)dbbk$47Eyf2*{m$sc8^l&Ho0X&lX7ilJEuy zZY$h@rUg}3Su=F;z!%lgGl)_)xd#>NlaxzJs>0}jz*%VGrJk6q!*G`zRmI&@lCr_+ zLsbb&-;))^Oqvz*N-UqF(3)Eh$Ht8*w>VD4ajKgLG&?N@Y^k3zc7sJmDa}esKHreV zAsSY#T@tr`l(FBfV{}-ag8MfdNOSOq;q?O~>^8FfZYQ8b?m!?m{4Oyih870ZvmiUC z28$D{=$@9!czgkxS?bGiVt;J#_PVPNbQw9#XfZ=7XTkIqydRrk=OhL$i&n}~8nX^aH{u^};=;y&s!yYcCN$MBtz(5`CT5p(w304*lHV3X~`dGvB z9Zd-WHW0FxOudJ3Pi?@?4vgVa=xE%5evoT6fAow5jk1D`b>Hv}lAYrX zKG;gswh`+R6Qo1%iNl-T!+4oFSq+PXV_OeO_aSrNqEadkT%K-PxO!Zq4oL|U*pIVt zIfMmYu&x_t<(y`!OG&zIK&UX+KbWzP?>T2b=30{syWLnJPxL$T%DnCtOP+ENv;^ZF zY;j!OCPc09TS5@CG*CPkOWfez7Ln;UlM8VU!kq!=&JiuC;RE`KRb_|_R{V0 zb$1`tnB6(iR;ldv0prNUm9dK9x=y3KM&^6XQSCP7ufMTxUbS}ZA0#+pO#&!xMShYx z+FUQwywBc4yz%XVCzh>9J5Q)f*?j)OOJo>y)>F8scjF9D|%j@Q5{9xK9b}~0IP4MJ=Kt`1$+LD3LZAPJ$U2)Wl z_E$Jf#!_7lHyArHVMI!>!?X|_6~#AbiBeS3R9y!|Ws&q4V-g%nzL5635iDJoj@epJ zWg;YlpEx_az9DLRmBQ8f&KxX>e-xhj9#ldJhMiOuH|lzKnG`MopeFYj?0Fpg67}@M zsCv=s$R{1OTKOs0;~ny_an79$v;E~PKLU6>`toc6k+)JT`lE{n+aH`+BzcmeW=Hme zPUm*Xw8K$zw^_a5e#Qkh$rN!e%N&$m_u8$k`Pe8nAG7M>DCco;*f zMJaUG$Rivv*J_Ex8%Ll$Ebwrt-7h^eVpZka17Sp!5{{@CIS7i8mR1z{&v7g^h+Zb{ zX@E*|e)Z!;=k15=Crpa_XLfP+?&r&^?DX92`E@DJIg=$7t9;I5?K847ek~Wy;m9{WvhL7&uSp=2Axr*t{Gl_R$^79?AWLM^-C6?Iq0hN9(?o)1m|GOOtRux~!nUYRvP`5V}z^y82bdTO#A}|@TyNRC>!p#{On@CG8rq|Qu z_b?YTbSxqbaKm9!umvRTD#zUD#jb0Kb3H-{!eE?w{psS4Nr-*zM%w4LcauBz@hU== zHKLXyh&4#sg|meX+aO@$wM){Q>h~>Q&Qo2(#8VOIrL$h2S{Q%F{osxd9E3N zdZ`x`Kf?S}@}uw!&DH^~rR1z|wmsBT;rD6M3eegU-{y%Zq$H#qRVYz>q{nhVO0^A? z#;KIO0K>6X`LngFh-pZW{r|Xox8^pIV_TR%Wu6>+JLVh{;7w#GCPJ6C2bMa$N1{rwgiv z^nUHP3Dokj4O2$m6+OR^F-!0yJWq*A5a%>nV#bnCNg{k2ekGy6WsA66CW)^6UuHWx z_Lho%MhW#bpJ-YE8Xqd4?Fw?n{n+JmHJ-Z`*iAGTB?_Ml%eR?V z*=iBo2%v^b;2v;Hjt?QLseOx6TsZXiu54UX94$IJnGorzK+*w}50$3rtanRRD~2ga zr3jbUfQ2&A;nyJg(6i)7s$W)cRIv$_{0^{}69d^@p4<3<0I@0!io3%e#?#`2R4 z@W%A#L4!an$wWh%T7 zVtSVHjPlSK0~8bXL+9fd^!;(*2fz!OAFNC$%$S9K(O+Q}gvpW8T_9)Gj>W75AfRDv zUS+PUziODdb)UyN={H6nCf#76P6d!|@2hAXD^pAbF=YdaSM7GbXk}RYF8$I5xFkIL zXGk#C=-yj%XLOOP@n(<{DHrtX?{)^EL7)RY^8(OG%KLb$)fsnxE30iJDOqjeNgBfW zhU1EzZ?~An0r;jUgcN-R?kX<&6<80U7crc&Dw_mh!};sQ-E_YE4*w<<_nZfMTH%4B z*r_HAbm4YHMy#Mo>{vKxcbDZFke?f-{$Jy5asT|gu9~LJ4)Y#H9s5730!8)(UK$#Y zz4hgi-1bmP4RSykz`KeY|A^=(hPh8>hS*e{G-}4E;%jH-F7HcYIJy~%kF)&bX2DRQ z`Kk8|8MuEw^o)K0xKT`RcLF}-Xf}RkDYecR!?T!)#`+xKFp9a%rD*-fi;=nW-Ni7n zS1fV)IgS!>VDCy>NmFq${0iwpaLm_*D>T!QO-XQA zZB77IDm5H&g3!?-F*SI2b@4mVf!@aU$qi8JMFkXqJkb(;TeHiN&)B}u7JrGEy4p0w ziK!T&i=h9OE%SV?SHO?Elf~`gvokCR}WmJ>3heHEra)De);HsjI~?6Y$Rb}q1i=kidMMEZq?JQ1AmJv8-RGszLsymACO)*M}W%zMQf1^ z7s8)Xp?J(A#JvnhTB`ZhLVz~pv$HZG94p|{ zB(~!XZ;|kbyZiGGm;fj*XUXyfS^wOA=4mvi4 z??mpgGD^!mipIrXPr;P2Kll!Oka;PCkFu8-Cy~E`y!Q1_8*A@sK~MIb>w}Z!mqpxI-EDz{g{vxq|q!*%Z<8a6$C^J_zy2_INAqCYq}q|5|hX=+q}s zz&h%X^}^`-QUKp>>#%K?~|8k^0&QHq#)0Yl!?n0+mdJXfy}}F^rld7?4q$ zyscK%R+q*#NL93?n~YD)_Cwlhuki4zHAU0?Vhhg^AGmvDw=aq^63OcNOrHzIl&_{_ z@VlnP2Ci8y9RQ_P)+f5RId8RHC1wzs%A;9AKE^B06cS74r003pI%X!TCA@t=KswY6 zzm#AmqD~P5zqytwoDPR1`%{ru68J>I8$0)5J|x_vlh4$|(bW&xy2>2TyNO%IKv@NsmD zU8S7euf!(-fbcrowF;#exyq~Jw(wU&)rS58@d-NhUihZ#FmlA}Fd><|(CZ)l2F_k0 z*)=e?X^Wr{J%|LOa#L-lbMfjnHCtg!a_+YHQr!v|KL-d7Mvo)uiE9c6Dmam?vY=sB zCBa(z#h&XpPx4)_H*;M?)$&o|0CcvZ*7wcX1Cx`GS8Ycvjz{(?AB}FxI03=1N z&kQ#pX?a|VX_bpnib==!j+L-VOx`d-tpz$47OszE8xLsyv#QF#xXY@pdh+Uvmd?WF z^}^M^!;x6H&@@;}=q<*et^cG|ZHz}Ukpxz)KbrR+Ca!@57ho`YSV&|UPK?(Zc0@sU zUy}GlTK}&1er4rOIG{0!mXh3WL?=|KI;&2v#L98I%tlxlN`(eHgHo~G<=X_!WvVJA z2y1@v8U;3B0oT)q`+=Lrf{omrO>QifkkHW9gv(ju5iTpt2QDk%6LiVC0lKy4yp~G} z*X1*-HIK8-GG?Dl?sx`wEJLdm^l``W<@euN1D%UZJ^uMyJ%`?+b$~T+IUNu7q61uR2GR8r-?ZkuZZAe4 z#!R1Nj3s`Cs_oM?TdO2mto5RiI{T_c zNB4)0YvX=X?vut`X*(H{a97mwcJA)*H8~TJ7C|^OyTUu$W$5#=Jt3+X&DG$EEl;En z4!DGymS9-zywWu2EQ6F$>|O=L!zz*6br#7JY&Nqz?2+=y}l|#-E zJ!G_x@qZ^p(SP*BpVmfS>mXYXHyrPi3mWl^es?Nifl41Dsjy5K|8e7!0Ac{y(b61Y2HX zFl!5BzGGQ4(j_YBV-(oC_tr{R(=J!8#8x90B*>+~G;BF!1EPbjQUEZ=GnD9tI6Cao zmcORt{TGl)*J*g3^usZs6mtaW{;p+#Q9)Lz_zvVErAT8DY{U`uR$AcS4DRJKdLq0P zJmH(MnH-)_u4Y^Kv6coURj-^EbX7~9HfP&aj#nv4xLaGBpmnDx8H?j^e+{27nLVbV zvGPTRMLN$o@DSDbA6|fmhF1{+OE%DTRXGYxR3qCmMQx71G@W#N{XPx1{aIJ!WQkA4 z>adC;mFCo#v_N@!4Ow%O-Y-MYzLd@gA260?At5ceKqU>X7pUQK9O7))AHh=n%R!5X zuhPGHQ$j9v!;?IB$>}W1y`TQ^@v3wFvFKjC`P-#_uSLGs$gr**|HL?=+n)ns{Ry8r z_B-S$(Aa&xd`B`Asd5a~wmx?2N@yX*sl)pZP8&{a26EAAjiQM}%^j$CDejz`3==~W z*^rNifIK>EGVqL1|Ci_P^$0RXXtTN{|9Ls>PsiSmtcxJG3LsGyUy$HYHtEF5zVV4m zf-1l4n@~7N;P##68nxh>SesOtAXZ~4ZMtJUii8}#G*(YVAHo?e*#&C?+H^t$Vw=@M z?C-tEbj7+2i&ksS+6rdAJdY7ZlkMC-foTL4`Vppa{0!zYa5Kn*jL2+wh6dTW%1dP|I!_aL-$k0aXKlH23%*8&@v;n?2U)*(SXF)5q09`!)pk1W(xh4 zFmUH(B_-MlgNX|&+4m74b#^cz`!4072@i6=IEP2Ag=mkY^W&)70q{{+SPUDZyl{60 zQ!0&kY_kEI=3kQJNkL4eW=y0vJaUFED2>|l6lBggy9`pQQy7r?;H&{$3A;b6ATELk zrCYuY$U;lakODL2E&&?pDtjFthC2Ad;ccwJZpuCK-McyT#;a-7K>&5GWb@+HHuI%U z{jKSsv-t1$Ke(L73*@usSKars&tTz+1Nv10=;+3-i^yEbCL$!`mzxK#B}*Xw+^ClV zlCAkB~WDL84I)RFXLL*e=u4KeH=#xKZPm zdOdAGgoD8m2j5frAR%@Q$EH7!I#XzMV)Bb>Hq@|({F9W=E?(~ZuaA!sdBj$z!HKjM zVPOH6q*L&*%}c9Ws2{&$ln4CQHL+>hzo$Kj+|$UTmdmg7*2t|hKdh2|#S053B=gtv zpCLd=+`w(4>rl(?NefOCKW8KxM&Q<>`yo+s5ekGev92tz^SD_ZxJJ(@=>FQhg$E_F zglhMfGMs8#1ouat6>guaafxf@eSJHePKLzi*~fZzc24EKx+Y8`d6~BPwas~|(JkDa zlg&fqa{1zR?3yC4ruu&)WPynXuotvv&C5fU3uttuo^3b>zKm-QIAPqMfJy$U;Qy6F zyWPD%oh_cZRM7^so?m1$25__~?c#t2IO7I0>=pW|7L_fy=f0}bF zjO$ySK5)JUn3EV>AOJy(NhItGEE$aqHE%X9MHDs1uqq^H2~n6j;Y*gW)!*hB{0k7K zX?`q9zy{C%&RYK@+lvLbaLtydJ|#!i2>BPLjy!wO5y%+in)O9WpRv=V@VjnH&A@lL zvUN|A+`$@y6SG}@!n@y(Y}`#QjLMY0oW_w7m3M+H?6c8?n}Xz6?IA=3a0$>@^0hw{ zJz@z;LhV%lmWxrNeam8o`Sl8L6t<8#gGl&IMn)pH$gC-&=EPBDiV28QPbj&${z+00 zpx+`PMDTZ8MHJ3!ZW@S`BhBP}RwZ+xg)T+#9QtxP!>l9~qrLbb0Ert=^NLfp-Xi>B z&?)AeeL~TY8e(n#8qTMBJCpUy6-MX zXe_d4Awo8D5@{g^#MRu-jKRX?hHRBViLsf_nhPBR6R;$0tXrYVhRpd$;s}3YlY|el zBih8rav?I(C2^deKw1s%MzJ<5@Bqv<9-!AKTnuAp@l6&VIbfBF z{ii?KMj&+rQ|ST2An&K$YbZ_)7k{!2wj>07&$i_I-s1>@rIa$7^&D|&X9lezO_D_3 z5G|93(EQ6D&%wt>H>fTyou^tIoqBc4HMOZ|Nbv4#>;@4xHPQs`6;`o-1Z6SRjbc%31U@h>C^y-SS=-&_Q!&jGEEIFc9LQ^)U9yUd)R3R*v*| z=oita<9}Ej`TjdzP-KJX^}QQ{cL;8^25EjL;J7zW0ps+mG4$VNlvn26M#8p8<5vvf zL{7gAIahppjsIR1kHSHThWU6f{5r#a*qIdW=4?71^`G}DGtOh_tvWcXi8kX4K`l6k zNq6=h;GgU?tI01&_R+0w_R4Hz=riej%DH(7tgK*LsfeSS2SqNrEs71V@+IoRO^qwL z%^7%9>s{j?)_Mj}O6aO8u-=BsQ;w@`k>%tMSp~KKZOBLG13cw5DjGNzi|NC>kNPZ- zayc(g(+9xy)4o>&+TGpTz!0N#9b#L+h-i7UEgod4;=<@QA1gs`_)j4qqk}k|K3xEz z+N0XAO-=1BKw+T$B^fGlY=Vx!W{nN10Cf)~RFR0=`}F4L?&Z~+tD<{R{JnU0RlMhC zFuI9KxOR!9MMvwupvQ#SB*_%*+avMXL^=Cj5yZ zj`opYWibQ$KA7SLm9C_5aO3gDM4GBRBFGVGADR;t`%y~)X4^wtAs4M$A2?D$EF3n4 z)$ z2&7R0$FvLfxb|RnCplF}i19zcx!n)D#5BmA^)Pl z5N5J5)35Lic6q)Ucj8r!(mQ{YU|`+>AIh#23w&~WcKOhaaYGqA$4Zabckd?rAxjH_ z%ivjg#6kNXekpyS5nP_+PO<;EAD0gv}H#hXP)X@TR*&zh(jDM*OQHc0B+SCH;-4^GMtQmq~-Hscp%_MCd z7q4qSa?rm?#%&jjFfo!;nmpES@8K&(vQFN^EtNFK6fBb=1g~4)f7dcxJp5$e{zK6t zw$!x;AV>Z8#IYyB0p7};nJ+}}-`JTPMU9}*VchXFSB!<@6k@Mh9p9K0U)3PWO(NUP zxt8VUa?Qo<_YbmZ_f{i~N~4pp_MO3KB@Su7_ZsL+Qe zLO7g}KB>$bX>gZ+yNoqb7WKsNlgg;=eBswS=>~6@T%XOY6;d=z8naXln6Zxsc{jyl z-#%bs2tbUZ$-{E^RdHxswNL1m8V-JDb%e(>lkJQga|pDZimcEkR8OrU=BU_$iM!?+ zUL`8*xvsq6`Wh_bZ+B2$Ab1W8DN~FAI`dxWO*NpCniRuvHy{T!=2HNL5t0hS83B+* zhmprAiu5w_O@Tq`U|W7lO#IITjM>UZ{n+C>N_E}o5=em9;A|vUY!j%9faxcAhE^M+ zMPyb7r!xs8?L#Z<7Z4u2s7%bhz~=GsqR1)7S;@L5Z@G!k!B=tlB9YXZww!E(c=Yv2 zE_m(hP;eDBr>K^a6HkAK!rO>4Z{s~NA(%xZx!JML?-lN5msex`HHn#hMnk95pJ938OZZ_ z&bNUk?q+AYX@eRTAWF{jOf|~i?|aCn6iVtxy82ljwZZPBV2=cNHt7SNJ8s+*-jgJ4 z*3f6_8Lp`0W*NO?^pLB1SfN`-PgwM5UuQ~TD5sQX7HQSPy}8=}rqDLHg+Ot4CRp#f zrDo$Yms+kPPhHVEA=-v((+l|pf`yn}EmzpC+t^u(zkU4t_RYs`7lQWPP8X~ngtxuf z=>HK6#Xcj*Mcf1v2V^j1 ztm%o|aM|PoOHI$!+tr4mrd&gY0b^{a;F8Mj`AKfs-Khn-iKkopfK-9=PBz7&?>1W+m}oC>8uj}(PdQPf~}O`(=Gj}ml@xs^VYC50}w6h^@A4+ z9@Ri={iojJ zUx&j1`Ex7DO!y3->$I^^?6{)Ju}xqEf+<-Q)Dp!#{>vR2vHv2G_Nc%3%bUOb{FnEm zo15-`-3^E1?)m)7UuO5eeAQqcT&=%cKR^oMFN=BqFK^B}i@!*KPqs5ym_w1}i5@%w z6kZh0so0zZyRkA)OKJIb8g#55^3wgT>l9;^F?ysN!~$cdappM=9w%4@WE^lb@f8s- zC|nnJIq5p3p}NHcVQmJ~2N-`G-=DVI2L~tZ{e$CIM~5dTN3ZtLt39s%^rR?Mv4fpA zk~6Q*X9Wzc-1Blo>y)_AZ%*@EOsLnf~I12gKD9YWr1H$F;dR6tiG@>Vnj(Z2x2wY42|IG04hsgiYA0@JvZVER3 z%@Lx_Ak|oy z2_Ad>XIG$&+w4McxQ$ozMhN+C;}J@lAS;d^oW|zuna%Ml;QeGCX3spaqEdgy4d{=? zu8wZ8>%;O5_zu85JM-cRC|6svmIm;QX=;Bh6u-s$;X zu!Ao-6D_g>l3ShKk`;o%jfqK!7)VVztf3}tan*CEj-PB-xnB1vfU3bm?1K^8Ebjon z^EvArVXf(MRy6Dk{rkG&9u8^g^5R_j%gcXu6)W5xu^Ow)*`^XmDBOG`!MWZ2NY#Js z94o-gCu>bjG)-8>NVaIi@c5P2z$1XW>7Mi5RO$v@7nutMuR6H zN&uAZRjR4ao<_wRlP0T4M8KbL$6|!R{YqMn0+|hI+-xCM@7FO)S{I%4=D!Tl1lH?M zO|r+f$`&!}5}h?=Nh{^5Vad@74#SOr!M*P9xkC!h;2a6IVk@$twg48g zbG2bIxIaG`VSvuu)Uyz1AqA1iYo z`*t6}9VxiX8FyW?DXVakv;b{(vXVzZUH=3&L%PO-!oI#xSm2jlfyTf>=%(jv&6HRs zx&elbD9jkP{dHBSfgK~_QfpSQwhY`Dmr(L{mASpc6Zr!AEKX{kK8uhd>#y+(YO-YQ=7Lw}C9L2Glf#__-(ehz79(K?MvL62@{*&diftJ^~V1{(8eVxVU ztF8%tXKo!((%GzL_F+g7Tnn#I%2?2}y!~5dlI`Bo<&O;BEEIIfd89*8`%-RIUqVPe zg1}KvQQ^3RRDoP8_tTu-<{-eK^~0glEu#Eo_xmjmsSq*cUEQfsNjv=dGdTN`E=ZOA zU!)y&33Zfb7wEyd$9>uLTP<#Y!Ua0~;sW9Jo(^kd$saZ)?#6<3sSI+=0&h8&j90W> z1_H}#$)u(*Djm+6{qa^t*nQp+ddVTw_qc~DE2N%CVvx7U7+KrIZN3i0N){OKB|tc< zetMgav^0=>tQX1&aQ1LA5F*NTGa=@n7&Idx*7%oI9@?f#Ad6X`%vNcf5l9&*QgCo? z+*-!Zttzd5|D8j_<$s(%OzuH`U3nHcCMNu4T0%{aa2+;NrK-Z}$oQA27NQ00>`Y`E ze=r4hCBho+9v0wr^;aDB6DoI2zK1&YqGd0!!3(ICBJKOx@w3zp9bozsg<;t~t$YShf#t*eUWy5wt8Q_~szM+yI@{=Y(oF{k zwvKc_jFlE?H)a^wO%{h(4gJ`1%$<8+lXBv$89C1d=g+vt-L1jcb=}K#rBODaM2{Z` z^IGZ=u2$=mHI#>YF5|%Wn2Mhv`kA5OYuN^C~ zvoirGQeI{n4-i+?#;*2x32!RaliC-uFY(sVQjt0$#XOT8T5? zmaUIR{Z`;ew`LG_7(R`J2k5%*yGsf6Zin~7IcVKaii<^OhXXh5{G2)iH6B3`6oVaT zBwMY;^W+*+`-E%+V#Gys*JId&pNZ`#hb3FNN$2QsMANXf63Zx=6-T1RZPjP{8RE6$ zi7+HGvyezTow)UTd({8>wbkMwU19(ML7-*lsZXxk8#Fb^BLBAJBIV97zr$0J>4 zvZW~#Zu}YEQ@a(i!NsYFI7F6}E3S!;-js4!PD_ zjf>=9u@MNtHjrWaX`H2gX1c-~DW*j_hg2P|R^$cNqYAeOdhb*YJU;sX>e4IXvrwf( zNs|LvMiWc}kjHY@A*o1xVF<};E$X2Y5L?_OuV7KoP^rP9R)^`60@FEJ4^D7gh?Amb zhWR?Y8(ri-vL?}Ico=WxCNB(;j+6o zT3n7Ms#q*%La>2c+=5)I!Zd2Nq`a=vUif)sJ-LYUD13|5*z@?JuYQD4z}LJC_Rp*F z=2Z(FfgpJ8L{8*o`c{XUd;>d@lOne#O29g$j_ziyL{70|w78g#Ilz=39G!;}yRVO0 zCR!qJ!6cr?V)rqD4PweZ6gAgSr7(pi()zzs?kn}+=!-%%1l#qUX4%k6mNup`dx7yl zYKvAVla>R$!+)iQuM@(%5E>B@Dvqbk-TY?hg<-?6>H(iFH!yUVYT#LH!0Yb9ndaJY zEV{axu;b|yxG8kzb<*gyV7o-8DO&)GpNiGO0)>~%nwEydMyC;=W`=YJ1ctZ|8i99b z+QPvjgv*&e*Vp1$C2dzYn0=IfuQ?{!&55V!%w%;Qb=n-t+*m#}WQ$uwPc2Q#zLc>4UnFYxOF~NI70QhRyl{fuCdqSqlEtv$4CuB z6L1KS>0C2s&bPJ+YscjDy(CyXd^1`32zq{1-NQZ!!W#E&^n4uCY#Pj{QkIdIm7V0Rgl*5$a;9nL}xZLcT) zB*Ey{qJ2R4n`|n$QN+bqbC?&5i!Ls{ex=XP5T=q3fg+@velr*p*{P~wu2;m1z+(aZ z@!6I&t4Y%3fBIT`1F$N57KGXC@zJ3Fe9c`buGr*=coqyniBM9^dzoQ z@8zTbm^{FT-QjH77iA=I`V~THC-cxnGF{njm1{CP6l(k@K50P^lk+TH?u161+g)Ms>sEk2>B6Z|E5}2~KHSnYGn$ z!}P|&(5zyTz*o(GU^8kQNG(01N|aUdSm%qEZYozkO7f}TFGP7ljz0-S^rK|@YB=-_ zB0@Xi2uOZq#t#?gVxQ3H+YFB| zYE(GbFSX{439cmHkB2wQb>!A+eg}Wl`|2#06EuyJkA$J}6zNER5OGZ$o2_$znj*PD zW-xTLcae9~VIr;lK)Fybw``hrCSG+ii0P5~C9G4m4$CzJy+#U?WLQMY;+2KP`N(#2 zbM489k#|B2UnR{1EmYVqZTVcWy?(75SmdN{X7irUph*4!?MK<6FFT7A^=fY67hA`| zkRSIzkOvm7B>5-fe(vt3H>Pt!G`RcA5Y6FunbgxzaDWlZR__U;nrU{7d{Qo?kqat} zmPFnd{|Z-qh>i-ao5Wz&uV@v)PMS`g1N@MCfmZ8!bdMUdbZA&P)e1!WT|eHi^Kr6Y zG~!c=4vXVXLLJTl-_AlQmCowiC1T#m1Rcp3N@5S;2H3{!m&{#Rpj0XzcK=cXaG39# z8`=2~t5PyY65vP?b5sE1Wh(^0T{l7q`=r%}S{sxJ;bE20?V^DZ6b)cm^fUA&QxZ$g zVj>h2l@B%Fb!G13drbO#^eghXM;!n4|7iho^R0jiiKTO(R)cc2uM{wpzUzY7-3@PC zHb((QucE-qk9$Jq?V^UuLf`9sm+Z<IfQ(=+?Q2tUJWp``ZI6lJ7`KcSrC>0I*ylQf&RUjNtT|wUv6!oqbtd8nG4gEi{ zN~b?V;p!)d;o#c)ACbqUe<+haV^5uR?&hzv=_13YfaJn&AeNF*LnvA}3sFc6+h7i#u(Ilu0?Y3YDEu*M~>aT4OzXlV+NY!F{GGTwYe z(#2b0th6HCrZp|S(sgE7C4I6EkA(|rv1X96^_!6VF`KctxY~z1PU^e=4Tj_2aV*}? zuIR?OHqMGycyzI}YdPUJ2xkqJ$^$51^C1qtp`i%n8=y5MtyQoRAb^F8dp;kr({;39 ziTzead(GEk!AgU$u(dERhIg8RPJSr#7&GgtO z7W^YdypM;Vw8?nK^WMBS0f4eiTohVz{lkF-TL=HtI=&Ky*x0HHz@kB(Z$ExZExK=dg?ndEUg8pz|Utyh$b^I1Y$uE0?3Cqs0S{h`41;mI<9e&*Nk z?16;-8{7vrmI^enGCNzf(}>Q!^0`Movff=hd21hoiaDQBn%I&4?L2C2%#J|5!M0V> zB7_W3H>J47j$V-Ruc=tqCf$6aderVjDuo+5#t1E_iJ+4rqLEraURECY?KIx$fkH6o znzUY72ZDx!rE1H8tJvO6F-Cpv>eCmV3iKOXE(zgFy+&{5x2?S{{(l(*K|CZ0!s0h- z#x3hVUUM-t|56=&Y5T8_i2_SZ^toH75pjNW|HTQ=*SDn#~KS!V4~$U{Wp z-9sky=*JCzXeTMjw7&V)ubHRroeMCw2f1JR&h<%6jC}BT-?_tQIu}j>Ba| zXp8_FK@y1As3j<_;xJ$g6=a*x`ulKC6GVlStGc4u&1I0@c7(2mR!aax_J%wxu+x&h)?B#EWiB9cAx*FD zwvoDyiO`GX@u3;6bZ;lzKEx&6#bcKb4^c0i0xSYXDWJXrE@B@w(hq$!=q+1EMuaic z5;v=LM0ivCm6XMclgR%r+sBw=I+#ve8>d&h4zpOZ4PVboxm4K>H2Hzb!`@8FN(J{eAsMBHXL=SJ?c`6;rtOYp3eNH zS7lP+xdvBfiB9$l;Mr)Pg#55MegIEMd797o{XISV+BM3jw43GZISRzQS=C~!Oe@-Vd>_0S?gTn-_?cNT@2j#QtPdJ z7Z8^XEO)CNDw!hn^<+DE8rUp|x`xtjDPd1#6LU9{VG)u)-v-BzAkgf`Lkc$;FsAw% z{N?P4S%V!yXx{0aDTeq+X_9j-uJI!)s?ASyJ19BGOJbR7E=$J8;i{l35$882!&JHC z=#y&A$$nRZf|ndE{&zT^?sbs^0;rrz{(uKC^XagxlYXFw{_pCS2iR(Ey5=o1_Z4q} z8eLYv7VA~6Z02EQJhF-k{9Fc@ z9@JGH0S8hR!)%6aQO_Ho)dUsUHA9HYumYY|ltW!wXj!3jHOmKXowTp( z6KeN@x>tm(XV@<{#Z5+fNJs&_1+BMw**IHk5Uc)%wQh16G-T~Pd_@$tqIpuLgE0@> zUC_!@Od<&{FVG?XEcM;^5!_{|;h9iB;=#8Z|MPw{7l_n}L>2s49iyM(m|^_gV_jy%uOoMa$NfAT1Va)tytzL{Q!-a z=-WubP6xzNCkAdXu1CpCF_AK0RgH$Ugg;?ub-4s*r@bbi$pjCY0V0}VNLH#lypF2{ zZgp!uH|zBA$qFW^+r-0H^KbkGzVm9AToX{0xmL6i)w#tPzrD>XC=H2IhY-IoeqMl( zhtT;F`1pL#`(wGK^}^N_xSFl8-+#C74ndlDeu+94zR-Y|{lIS4R z@mm_W{1+pGh{2H={?&P{^nFM5qa{bIK9=6!GuzWoxr@d{+@-&TOMxF9b-}?#|0E~a zF06dyIj6HTh7EQ6E|YvOS8(FCPK1|KF%g4&%9mxRVO( zGg^w|++LB|ayy-e>R@`_dPElxy$7jnOML6>0f&T^k%t8z8f2~lB5Kmd&U|LErysj$ zCx)z%AVV}4)1_2MNt}sqGQ(Ed_(=Xt#_4i-Voy==DUJYORhumq!RPW5a+y1yQMN-_ z&eWcwi=0Wa8a!UX%%N(~MQR{Q#DGB<`7#B!l7{OIy|vty%Y&ekNBACjjqH~whhqbLTemA+RhilC zSolzQNNu-pq7&;4Y*9GzETpeaY#`a%Ot9<>+LXk{aG6PNfDi1prpcZ-$*fEso;^rxP1*!HKK_chC zS_jHQ{Of!=`R~aX@k0F_u01TpxwuStvu}oc)zx+qZq1lWq)iVr&Y|pCT9DQe7cdg{ zBN*1by?-9(Zu9pOAL%~+&33#_TPSI?s zFd=nYSx^h;1n8}#1Rd3C=yU#G9Ph(oV2HtDsHef$b1erit@JJvKI4Q>E((s%k(+Sqga#&Npps($|GQ z7I|Yys)&k+t)taxIQs`C8H+_XE=!ycG^Z|6KwEot+LTP7A($hLQf4WMk5i1)?cD;~ zUNM;#k6JE@ZbT-~bbL*&lG$w>8*ntrqpXA7&zA>z)Y#)D`kMI4r(q9MT``TgT04`g z&@BwBHSkTU0WCWjZ^&u-xNs>%qu6{DhOxY6HlSA=OMY1+BoH)lIBR zFWUJmmh^(H&-(z76*23ocGC6kzfW$Xq8Y1SRutE3v^g>X?z08B7>7|j{O} z`+LytF5%R=v&B-P2VUr!bnr+>CJ2y?VQ_R5Nw;2z zcARZD?-3`SIiLSwBvH^LqHmg;xq-!l$qb_5JGFF;TS*VyU^TcvJis>#w(V=k!~=d- z_PA~-z~W-wb<;y%ch?E*l2Hso#NG33x*X~_iVxb{@5d4yNtkXv$CmdcyYFYIutbTT znE^xzy5rt6#}zRU!(Bcsv;R7XK;2Eqg{;Njg&~P{a8#BVlc*EfU309H+;S_!SqX2+ z3`f#&$baEHF27zyG5ja%a;7w&q>2qfG-tU<9f4KTahUY`_`Xd52d;(&XRv+dW|>@f zAaQ^{Qs%(|Jub^PRKww+dC3_Sf=jKrVxa^lv{-W{Y% zC}8Rf;1=6nTF8`zLi_|%tY40ynT5N3OPs7#?$QH;mb9-e$iycK)UQJx&+4J;Vdk1FPdS2(00^2Bw762bC+ngCo#l>udjM`qx5NHj z`*a6zd4cc^)?2bjJY0yVd4XdM^S|sy zBax`R&&a?E^E&V=D0;g%%sfQSP+MMC&D{u}0b{^jQnQzb8pxB=3}C7VcOxWQZf3aV z&K*XBVz6cQ)Oce_(XvnPc7vAe$m^ji6BWmYOMu(yH7_7_L}e0OVuvo+cQ`0tB6n8A zfkmt8g`p6sL0o2N0g$Gci%D1=iZ{1uQp(QFNuosdpbO`mtm7t$e4>+GW6*0WQ1GE> zTc#)lp}fvHx`7_AgjfkE-Bs3e9kWS5AKyMdR%VTWmD=DGgJ^n8#6dU!O%0VD0@pef z%dI*ySuKg;sG=pyk2SQ!B9lr@BD&557NVRE`}dp>=BU6TAiJ5$a7w4&)0bf9Xp z$zMmPTWA$Nc2lHBoN|&hf*VGZ|MwE(+c`)3Wv`iB~8xG%K6c6r$MFsesN)u zOZ%NZtS55VN=I}-lfX5RFAZbQ&f*Hs_CB;Rjt57~9ETiD_mG)N=1P6NZU-8#OQ_c5 ze$mddU_;ds>7VV-y{JX@Ll8``>Ruw~?zs_SQFw+^5&fH!iP3}YW~LxHzQuG@G;^yN zf{lzizcFY=``!IdIn+ku&=>0lt!qJq$AeL>DcHlNEzfe0^)&q0T|g-7c)Y3NW?eE zE&(U}L@{{`RM##ZlW|8@t_jbYWaEcF|6sLTFh@XF=Ky0%%e%de7G}eI34dK4E|{K8 zR@91*7K$*SG7IVx;?8BavxQX6=94N--3%=$Xq$&P)}&5ZjaRabSQvrfFT&7uk<7|C ze)DU%`70EX(uk4T!p^CY#ux!RfC>&dmxi3C&Un^`@3ylW1(_J?L{hZVr4~Y+bS>wo zYv84#*DAa4LRo}~mB&V%ru*3WyLbnoovP6w@suJC_<34ou>5QDeLFNVSF1Eug03l5 z48KGTod2Pwq04nn375!yvdwgfmIgPk7PHYk4<5w*`oG}dF|YVI0^xf8eEtm-ks8+u z8xB6&x`^1MKx5d_<|h@~Pf3*-I#ED{UliwkexCtn#3t&1@MdzRh)hKCOz!6H61T>? zQHUIk3>*+Z%HU(-gmjl9 zHU1F_zlrlNze>$o)M9TynuKWvbuFajM&7KMC2@p>pXp3QfiALi^J8}AOyreN@IQc) zgKX;K2=<6QTD%?>ZwY7rF>gGxXbcTp^He&Q=aB!D`MJ*!4Nb9vWL?V=kg23riAQ_q z+8cQ)MG}{0cMMJ3YbZz_JyL|!S?JweUlg!IeIJ_`g^uGNB8mD~} zrX&Ig-8}fc`r#+NlWf`?CK{1Ej zv0z-L5&>Ro(yGn5nXsr;EJnY@z$>m_1t$C^55nXMn9oIVSzPVS=F?k@HUZ^;nq)v$ zF?Q^3I>#hEh%9g`=@F{9$&)eAVD$$h{#tMB8eip^WihiBIrGCG{)DD1_o^9T4prue z=?5=OIBJNeslf%~8^%w&j%kmP4Uhy5FRFZXIg>uYg*_N|$0l5uR8*EGEu9^k9)$?5 zerlp(x&hxbG;a5TIv2nqGEYy3Ux)n%?rQt7)p`Xf5~Nu}h#?HRv*~!$e+HBwnaC5{ z5wQY8HlkI`Rt{}c85TnaoTNhLOjO{5%-_*-ya$A~&qFypO7o7SpV)vx&wGnD*-I?QUlZRhg*LuDh@p z+mF5Zh~m5V7>1zc9**GcXz3lRIAP>QKXtDkCbRBf`s8(<%rR_rhj9bx1<^5r0aH^* zpH81Vp2c`+Wy}-PBt+WBlU;_|!XI^#={PSt4pv3b|5X)P7LME+)&%FP>Rgg_L0bLG z!##?oRJP$~MX+tsk1D3gQ*eMvtf2EqiB};TWwl42&A5oay^p~ku;xTyudF`Xc57yh0y z3X~fhA2Gz90#-lWO{h_e}Yqlk0L2;|ViJ{?gUvvI6kzt$ha-NPJQdtVYyYHBWAKr-hlZQ=si03oY`c4ie-elr+Ay*3_fqU}T(r%jlPrGm1j zt`E2QcWWYI{!umVwJ%WjEq4Qd@iMq^)=<{ae2|C`36^Ge98T9u)76ojnIrI6v`@>d z+lPBnZ3pK0^@QW-XO++K^WCAqTV%z>!O22^0FDL5RaGq}{8I^cftVt$`QN&G&Yxi> zY~Kat0?t_I6K;_OL4l8CF0cA`%4EGCEGoxNq!XCwtX4KHIhwKnC~{7fh?Cj3Je}H^ zClO9jPBlKorQ<8UnmtkYi+H?D(37#GpenJI>WVtoVw3a%9rDoHeujNQe1zTiwEZCK z<0x>mhoy{sqM3{00~nqPNU(h`GFC<1vK|D09%@xnfA)nA>dT&Fh~L3I?Fsq?fsQE} zUFNqgEYAMc0^-ho=KYMSv$%G-`Qi~2km50`MD zQ{l3kouMscw`6jS1XqQxNUW?eZ4)KeWVc59dnX!|^7#BQYPuq&T|WiG9e}CcSrlP2HqR@y9Du z4u_5~^N`GjxSb5faiQGqj#_i5awAwANIu^^GO)Wm6PWN?JrN&BKlbf)+FYm6Y$mrE z7wrS5d&rm=Kq#2WIbqMq}YHGxkU)2epkOic|y(GP=J7%^fzS ztQ6qYBO3$Jj=G0Ws-mBudFTVYP&E!KDP4A|RG8Uzkj_8p9>iIKj+1-^y7lOhLtoND zgxQ+7FkSt9SB_xPm5v1S7)>&Lsp%p`nP2ulVcuSOTDoFQW-ylk-y3YE>4s)^uszic9Vu1oP zdqdI+yc;kSj8b!7V-Th<(zvO9T4?h>brr=@DXzBOpx55VNM+ZPx%nD*9*K7{Q+Y))f-W$e|2Q1u3S#G^ z+|F{?kD$|G+}8FjJ$T#@EaH6as?C^DN7UPzIJQ>n|9gNZo!_(m>5BD2vKuWPkY?jm zZ9MRrQz#|DO0}PKpj=06c++k2JTr7MM4AzJGrmZOzgWOeVJ&bY_u%TP6N{Y@syX+o zLM|C^z!nJgmvzw4>B9jG0s}a^B~^d-N=K}LxxtH;bb+Rc`YG}ATet|YIiR1U#E`|u z#r;A159oqd=MLw6TbYVS8|h*Zjh7v4ZeSam4bC3zKok(7uCOF>Q7)6 zpc4B$1G20?s6wCg9W5>8G9KzO1}fk|&N@_OHZ z!nTCbC4n?TRK4m zVP3Vtk*75LYg9i(F#FZa=hlJkItf$_pcO~db8w>gfG6d(Zu?Lv*ZQEER5;d!jK31l zU+2$X{QTjL`&+W(F0&5zpn=VGaGgqQyi{2z@uJWa`h-q`j5s9KhLHM33JyYoLob2o z5IyGHEB@sD>@&K%jjZ2A=Q)6Ax;-am?)~J>lwVq{SZ0P+mgW%gr?5uF`%!;l6>rza z8nqX{weO{CxMFSG{TP3MC$Oq=RJK8?pupSa2)|d`!Zm~!D}7ldr*3`fJ^pn#99;L% z89@j^TupswoOOV3R%}t$`3E|TNWS|Ia#Y(4{CE&t`^+7}qplA9Lrr_Nhs3cZ304hJ zc;8>mMWV=vVXwWf>v*R%@k|B{O8f33*dsw%uF2uJ)>p4^Qt2!(;CDi+WPsJjzn_3veBEn7R}JaFd&X;*!T zAu^^C7_s;jsSo&N7e2hLqc^;u;6=r(4d@9Dr}Ht+HOwkBKVg%}ZI{AAiFfl-8-vFK zY&(VZxPN9Lc(~{yA^}kZ1XhfsLJ?P0jKBRkXV(Z>q->p6dWDfKa{NMiH9jUXvO<iZcv(?KA;s9 zJ)0yVqsIbxl>5$1hMx6kbdok4%@~P>S6Kj;&C(1V75x%t2q#N5>+M2-k? zs+&HqNGeZ2wE95bDy*Lm{cTKSq|IeVWSftnm0>x?N(gHomh~GtC$&Ovm9?onngLjg zdg8ZslW!ufd7ho!pb~>w@*INeM;`@{!8%SNMd#?mCHEcYH${vs z?AYe`Fm^a`X5U9Cbmt%Jl2`KRZo0_z-R}$#WhMy}yq(+h{8O~F1fZbld4=>;O6!&8^ z>Xr8`m=u*kCd=J5l!+y3En0+vso(TGJ0)AI5uIO!6f%k}lf;`lE>L2;{jNN0`_r4ByO&pQ zu8Qu*&zDzpN!hJ!who-4y1q+XJ`?o1^3=Uq0&l|zTbkoO&thAkU^T+l)? zfZqVJaH*X8=Kog!3-?wESA3(=hB#F~iGh;>(x}{hg&+_dasr6hjH4%1k7}6cpy0vF zXjNJ4M(hYWV{#YAd&*XE8rFNL;{4OITwScL4G`^paJpT;6-gPud($o3HX+8EZQx5z;2&r24ZrrNIgzvdt%rJZud1vVC8^gRQoWr1fe%{5s-L z_-A@_p-_i{AdX_Tfv9=3h6mdp3_X9G1gdiYImXE=jkDZ}pl)hrjQt?WvqWDQ>p}F- zOjAlzOTd`d!={(BM)85m`R=fDf&cw@O-WW1xNvY}Eq99LN$AW6`k*>2ydBVC8H2su ze`E`~3Pf}Obm?RJ2+-ve&0#Y%vnqidFXFTPq%v@41D?KukaCBuFBLLvT5{{yL3sfU z`CXSZ1>op(KW76nDQzN*A`kocPW|V1ouAQs|^My@z57{d3qFke#nO)jN8wEIZA z{v&)Npayd^Ye6aO=W122~EwHwp zrS-mL*K})CY#lahl?UY&VRsI?1`lihfz%1b)JO4=-1ME68X7k>hT`ELDSO9r}=Hdy`Hh=i_;aV{mZ`RIxbL zI*{xlqoSv(bMg%>BD#eGYj@GKo@!Y9vg9@325viKJh(ZIdjwZhLf)kJ~uM$&-e`){CGLDOuHgU+s|7#~%RJzU+dGPBkW z&Spjp`7+t0d;+E|>&P{T1sBV+GdsUdg9ycu+v)uIx14{nhdUU^+`3|aki;FH&(&D7P(nM&jjPyk)UpR1B%XPaWtoOLbhHM@yKRad*{s)7L+@Np~ZcVHB_#4hV zC}@s^6<1l(6~oSgAELZ&`vfX6-RXRUZa_fQfvi9pIC?k${CPq+mpP%G3Ug0%(-IzLB+fBhq1q`0xzK6;}m(?eJ1Su5~cTFaB(WxJ&jLEQQKn2Ex^Ab zpRV9Evgz54)~i}VbQE=%y8Mdt>L&9eH}mz%{e+QeJAs%ok|f}s8WRBv8lc??7w=m& zO$s%UBn)V(qxISuJa_p_N{@CD2=N%fHiV6l3j7NyJ{KQM*f;eFP(t=SSD8ae(8)Kg zRwHD6gbMUIOe$IcaGQy>=gey1^Ly#N67UqJ3Qzr243+`q6@`v!_ugsn0X`R@GcYm9 zk_IgT2P%sQAY$l|1(&#oqGqZ{g}aBjhbMq#cyYb(vgDKoBsjEJd`^pnD6nss@6M;t zEmf6w1ewM%hP{Neq$$eSXMAdAi9-!>YaMqOCBG=;RBc7MBb5@-7X7NZd0v&VRcR_U zr%}Tm&WD5QJ^xNgxd@la?#2ozrgh+&kng5rw9~JdPJD#woASE^NUC~++)+{gfG|O- zNUk%p{oc)ve2Y>8kE&N(LPUgNlao)E!@jR9r=mf=#Pfb}@xjOj8=jF6cde^C7+z~y zCY3lEJ`h1Z6hzs%z(IR1eyG?FSe;;%cr2FlXQ=e)Tq$AoyzbBfucBm1m zREv?bs3ZDN6-=(ZJF6P_=X<=ot+Ghf!n^vbTstsw$iFyc&Ot z^^zI!Oiceo`)NC0UDBc&TsfK!jNMB*ka09-PKR!Fn(m^wK%-ClSxjCu=1aR@vK9*! zUT^Y?2oJq@yWs}*1)x=SX~oIJs>GIp14YvvR=r)2mVc(i4xJ5AN= zYCW5%ZnfG92&!D5J9b|Ap~h>~m&<|mfo+1@=G;t{D8mlh4Z6wn5@2CgxE@`a)nmgY zSU`2|30|r{d)6oPhCatN^`voW0k`AagC-S_a`%d_x{iC+I?`~5hE28cNqazZ9_C%a z8J;6VQMwEj#hQKXtA20R>tir14CPp(*O+h z5-vKGDE~uAWI^7?D3hwskEKgFCTl z?0=ITd`=-)gP~5{eI4r@KI!jJXhrW)aA2FIV6tTX{NT|K^?=!;NDhWH)OQaANGTUO zG4g1l(^7#Lp=VyVY)(=Wf1bVQxyRV(>KiNTXvs-+9So?$SJjCN>HTxM)1UCVfG9~5 z^YY&&y>G?Oir2>MxR$o)Er?6H$SW-CHW-4jW;PmvDd7uy4o&+mr!xVemKw6&1z{>M zMdncFxOUS!%;E%2)@5`@Zo(begUAZ>DsbnWe>r*3cFutRNpMM{V6dU|+{&DDp2ugL@)+2W|q?wgPDqMHCdb{B%)O<%bb*J~$d#J69lKUmsHT#G)4bf-56^qn)^`t9+B{3}P^H<;$8B~%Fs z$hiv{0SYnqZJwFPudh4hggf{tCSIt&o#CQA6^FrN*4f!cg@{O=n4{NZ#kbo+>fsDn zezM!(q3tZwDXS2Sd!uviaC_9s=K?Twqdowvjf`JO(8Xpz7r_ED=e9T_f%a|Uf$AFg z&3ePPK5gsnngdVu#9g5?Q@_tlaMQyP%}EJ9C~G$xx^`5XyC5`4KN; zrx3dyF(>r=5ps2C|4G_;=F9N_<1zk)tkTmWu0!iJ=tM|r}; z*W*XUk@i(dmJg8D)7wZ%J4-qpk^u{2h~zVHa|osCmRak!z|i!xD->6v74o& zr#A*Q8Vb|6=+;^c;!k)9ETUnych7a_dBw<$L{1zO4mU3mi(T_^8d=lf8va z&`OC{t3e0?1{>jG$Rvp1Cmab-RjAZV0nQIO2^z4Nl4?somwAD%EK+I3`7UV77y@an zIx@VhyA&CSI7_IkhPIe)WpoG~#7(p3u!wOU_d8;s2qg5DQT<<)d{MQ}Eb?NLkeB|_ zy_pYvgWS>NVLAK?>0Bf*VoU2FwpI(j-n(8*$M^;PtH0VYgd@U1^ux`(rOT$KF4J)- zaeO+mhLb2Yfe|&46@(Uj4KgQo07~L=(b|{4S7XpK1}2L>oqu?0X4SV8;bH{m(^7q} z8k3lDL5P8%l-)dB=tt24hwUvM#u6mdtWoA0V-0vWMlCoqiyN|AjW~rN8@Ep+c1&#n zH4JQ)+M7}^SLsLm-Ii_Dw3P{zaYXI-sj#|}*~%@>97?R&lLSvZh%g$;fd#8HDta`H z53Ioj5rT>?{-IZ$trfKr@S+9p+V0cv_Y1W_9H(M;v1sFDv{FJV8kEqsPQ&uyc$y?z z+`-gJlw$#UJnk)TT*`%oM#Nx^#eGa&zn>m-e{KWlkh)G6`X~KgP7z74)uao(S$J{i zoyfn*MJH%O?$yANu{xMocZBeJG=+LYtMKf9(4*l!@E_h2nx&+y|3Y0dDV?#&N>gxz zc=(P$Q{NjQdR&ffMkuXmI}6^qOQm*qFkAr2#@5Vr5wdhYp85XC|r1a-^zhjW57J#x2UjY0f6o zdt~7*aN9h{Y8$MEgA^+&V&5wwnLt&L=w_3CQQH@^^v5n{TAF~S2tq8M(3uG-*!v;0 zWO1f8&p3QR<6Ne7$2|sFN7oQ;7c(FuO1h+=t%O0?4k7bN@im~#B%tLY543I{DOsP=;0I^JNnWJ|bVAFyrUR`C84ui5vo_)`Cf5(|=#Ao*}3 z2s)R4@BSSZ)Bh??gZ>@MSvr@OUHm1p6ZqUL!vH@|@uBU{>NZ2WPX^Eho==}UoX1l< zUSM>}x!%YeEOQ4~<__lKqWBq@p|^mD+yfq+)lO`{Z}Q5C1IY(|in#51D=NWsPckaj zak|hV#$(Cl`3?M~b<)JeXnAAYc$^Z54D}Z8WxB01b%w1t8u&@ygFo^L`LnX7CKJzZ z^##%>r^==)???6KCTn|P-dF{}%TQ^Zfy$au z)|{v*@Y(e-eFtZGTyZ{>HUHs zxab@j4m!d~Z^c5?e~0CP#R-?EbEU&qSTZ))*u1fZ!r|{GwGft&eKYT-2^u!#%@`3< z_YU#J9CZ2fzK`Tx){vVWegGP;L{fDiS^bLD-06|DFGf86*qLp!Gv1ppa71dy^$x8~ z9by4#s7ZKW7Yrsee6z-}htVa&uJAQ8Wxy{~jgwH{-5-rzSH`UzT9pQ_`*GxoICf>| zT7*iEFptX;wJ08<_b!sG$4!b6<8OPF^63EXS0uvx-eN{Gq`A82r~NJeqf8{^QhJJns3hT%iboMP=Z zpex%5ouuCl*Cw#!?1hyrC$!F0yhZVkE2`3b#mv>1m;wQj?g`h$)q7>yC4VVX4VSd8 zwoQ!WTohZQ)}0N2C7Y_GLy-fhWLVGBDQQhj9ixn+6a=3L(1T8Il=3wLu{>VZNci7@flaJ9PMVIGqgH zI5=6{F3!%*r)+N1KslTpC$|GMmbe=K&H2=XbbyXT0TuhRS@*_G;v;~I1TzA~g5N1m z-KY~H&>Rqn5_FDO)#!E@Ei2qMrMy_uTZ}5`7xr=MZ4i~hxflYsb9p7$L z@QN9@Kq$V&5ZVp00;HbUoua!3BnSfmdgBKR&(gLV= zkBHy&VCKW5G1S^>RQ|`nu*(-)XoO(M^+Gp99A!4`;rA|N^CPqcO2z&r4-ZND4-^%P z5kj!MS7K-*Ow2y|UD=MY6r_m1x?(#rD>8&VJ9dg}(*b0*`*p8|)k^+`xvcREY3&i704zETm&a+CJ}Gg}_`# zNIekG3~zduh^~O;(-gK<^51+qfRcQ;4RScwvQSvhxitbZ^E`SCU-Ck!M_^(l> zn(hrCjn+Zb&4x}kWr*I>b&Svv0Ol~~VDVN~r^vU_med>kPj52*D@T@cH2C|`Ts#KH z&u^1lVg{#1+hPY`DBz}pCG?f0iicj=IPW8eXe5_Nw$uSyg8eRL;}OPcqJ<;ykkcS< z>Qhb$4h$7*ZPUvs7lrr7ew%o{YS4cMNF5d=Q{T>cbH+Z^;-VB#VuS#HCw(ig%ku9M zf0R!U0xlN~G#8E;NhGEpQt7Qcaq+8Yr{PXZgb{^kSlJ{C>!5X5Elu|21?V?-1;@kH z5IKLyvbb)xkfd*OQtjL6(DK1&rP5F{_|q{9&k6lnSew}sbX9;ekA?`06LEvQQXF$Big-`*<#3=YpBHURBk;G{=Z*$i6M~KwGS(m^c&667@tV z^wqX@WbfG`P$Nljw|fS6vFT#^`#K@v56!qPC9oT}d4RZ5a6A(#^dreS)>$ej)Gq6W z&53hKle)GfWFG&Cvu)jZOtO^C*AD6~E>R;hOIn-7oA`!^7SuRFOhG}(YRU8sr(Mc8 zl|xTWH5h~kQ|}ZPBHet29mklD3EVJ)@|I?ewbEH*{G}sJaBm*&`=kOv3E~3^VEB_$ zOugZ-#nFva4cbs3osS+d5M8LX0kmMDoLCHu>Y=E)V(Je%8}VI1{;z}KWmnAq%dX44 zj|Z${I@Xe1QplXaiGiWz?*%Wk0?iy1sO^x0;_hAQQooeYpa*P(OV;){5$JX_U}x6w ztHj0e!No4^3_fPRA0BZud6?AcZn&ohp;2i3lJ{$1>EIS(w#=gx5y)C@L>T%jD310Q z*Wzp$kS16w@ZW3$LHhSbWWow|QER1E^%hqZ<9Fxw8(ReiN!HvI;3H*~OQ-JbFxvv@ z>k`@t`zLNs#+Ho8AfUXh`ZbQI$HblcTL@DNW}uAjaE=?|k0p4jN^U{Wl08-QN}$HBh7k;>p>-ZP5-Vyh%}2$<>x0y`isN>rSTW$Nfol1dsgz za$n+s(|bMkoBF_G)6uf9LWvtI_``s44?I!rTf`hAxhVBJEn8;bhvpZSu5S|qlLz+7 zD%yo3J=Kcpv<}PSrU-W?I33eDM4Gt+aiEwW3PK6!@FIY4MLmln`pCk;763bAfVkkPHy?B{ z6Ktv`V{6oGod8P|YvInO(L}#E8O|0Xl&1BdMW;ErIL%NaYsXCk(OQpNOKkG}Q#iQ9 zdqvY&M=7CKP=Tauf}>U6#jm9dd*2c zri&VWZi=TQdxW1lZo~nceVHoHc)Qfb+qtkDXye?X@P0|eO=c0Ib)%m&TzPb3@C67WipQ~7TTY{!iVtQ6A`L8!ZJB~U?wZ>PAYvTH3 zx`s0Lsc0Pw(mjUmG3%?8Z8IKU#lW&lm&asukKdtu>E85V8Bszoi}>&cwf&(>*lJd8 z6@k7nB8Lwl_=Oj(61l*}DPQw7_MW$#2(a#)={6ZAVBPR?guly-WY8wk01PxCF4$Lk zy6yFR`pXc)Q>YesQ>3ezSZnxg3R$Cax+AO+&9GKY=9js(s*oOL~ZuE=SnH8|j+2VC4VmtW(gx_`~(#Lqh zb_Q==>|GB3*@5htzG96{uB}@%6?k|Ob4(`TyQ#2B`E_-K*Ugm72h&Lp&4;?C)>D@E zaGBTePBGetG#$wGOJ#C+eCIx5wBCH)dqy9pcQfg+X{(jYKVr@aM_QmOQ`(o^@=9c5 z0T&3KEzGMzp4o)M+H&3U z3ZjFMEyE7OS**ELDoeL`Y?+Y|WEUhotB9t`T|Vt?z;Sy#CtaepQ-;*Cx1OB4P;G9MM>|^WULPB4|Dz zElLuyOXU{Y6rX2P@TA#AmHci^Tv!5>EiNn}9W|#bW9;zj&>UfI-iII*6of9c1X*W@ zTc{n!$tV&mL44eXLEbS*tp|KJjvemBi8Ppwaw`i$5zD8da#2vr7Q*N8NSw<~5htgeMhW{nv zt)W@ZOvxsvG?`|I{SUisYn;6?WoU(M%Yv-b?z^Kv>M^#yj#kT6c5cRyaTLr8NSQoD z>X8qz_?L>QrzzDR*^P0mj&wwdH;WO(bnwO}^iDvF0b!st6A79u39tNt5-R+kvKtU( z=KZcsroq0HfJ1&*G87C8+#QaGm|c85yqV62+=s|?XGnfG=nhAT{u0eLnCS=P;T}cz z87XproMjuOr(W%g?Q43uM#ZbLW|$fvmKP4Ldbc*^5~1=>RA6(bBPp!iv6yO_;tm;f zL@qebWbDX@_Nm#}kxWtYjz!6I#zC1vw5o2~TrdouBKQbWIsBtyY}m#m!8vk9NdwDO zpl$9N7uOClN&6|CHm1c#griQw6hs~`Nx;~}fj>%|c=nqJNF0_wf*_*jFcuMs@u%(# zW3Xl_C0T8DZnYm~1Ng?bEM6>%!C-JcAiqog%LC#fK!s}&7^49dm1vhJYKg!1v3K8U zzbZcVTI~}!T!l9|Ofq!MWsst?v$vSIJAZx;5ql|H2Xna&*>EvN)QyUJ0$wY=d4O4$ zl#O{Urr>*>g7ux)wcr2ftUr~WHwWWOsBXJbrPZ`gRzL${#ajEJy%Jal*)RtlQf9+( z@mREnPTy^Z#h&m{jFW<{V$wSX+ZtGKJ~|*av3~N6>)7V}X`Ec%U#TI?o|V63x;#i$ zvscZ0^oL)iU8w+#nXu#VpAS7GF#U%)o^t#!5u!olE7I&d(I-FFZbrUQsRgWR-Hye& z#ct6v2jR~MC}Dg=k5XdW1d+~{Br<24aj-o&0Yl*EmjK!Gx%m0jj~B(8_uZfVaaH_x z7ln*}pqu+=XTVd=$uo&`&wE7lVIl6}U)3CPkz($6x%Kvxxtq=aSxFstW*;ZF>m}&f zf&UTb5aZ;5qFSq#o1YM_f{QKcsFfLX1p7=W86IGk;=)I{?1KeWrGoo8yZn;>C*!<0 z+^a1^uROT?y5HgG`RPa29H!X;mI0jf_rk zu?obqP!*Iuj}JMF@Mt-Omyd%?nHwNCNIsVF&C5VL*|0c5zFz_iML5D2;N1q{i|T7@ z=vu4Jgw@=XvkW8M9S!?ON2jubyTXZDEiwCD0iqb=vnPimDSFqV#}=Bv!QX$q&pZb5 zl6TLu>GDPkDq^wXhRd1+l_9^)tPo?tik__ACE~oE=nOd+B<8{*8fc$j0!Vj?+#bQ% zI4aExf%Y8HYtWgrLb}7=cXxPi7~wWjV9Ic**D(iF7~G+;A@ngq0z5IqJ}^VUQy36D zM*sE%{Rrr^t3_oj)kn2B$cE$o)O&BdRTAIxJwx+S*#TL?nc>gz9F(gwugv$A+gUd` z9~p``{EJ!#^@D;-82CN>y2LuY7DW}wV*1E*&(1#e9{=ie5ge>sDV=lFylL@e0}_GD zG_r99DNS|Jyu9xS8vdiOD8JX%^!?D99-zS8-IvC&ovIVb02wUXSL#jB)U#EZr4+ zR!^p!NH@dpBrU<#Z^D>KdPA{7(&m#vdoXCGPJ*J(NH<|B2{$V-a;IYCbe?1D2&GjS z^x!P=0VMQl%fR=g<_ZmRQkx>f=FKiuSse!8;KV(J!2rF^jY|N!d$>|IioS}^WY4L^ zL%&MO>G2^oK|c=Ryd*i;cg*;Zc~jZXwX`$$=A595D2NZ$V(2i|3Ts5CL`UAs~5 z&jGO5a^VGcwmMOFY@LlTxO%-_Ov&C`@&fl>Az_7Oc2#AdXf5zkC7!*^&2UI3Q z7xok+!)F{jk&k=oDsrp$A#)igtJ*LoSsgu;T7V>COE*tf*HM`*=w5}nl5drF0-Frc z+JKzytB#$|u+@WM|IuogyK~%)9V0dtUML=xOe38JlW=>C&~sxi#pk1y<=G2}SHiL> z!ZLui63wrSVI7T??%AhwIiOm*sm0ppJw5ngZ#?`u0?-8i7n=BCQAb8OxLksu^J%R< zesRq!SBjmlpo)9H2c9t5*CL9UG8toX^m@r#c6(CqzcEkl424&Gj zL$;{~V<4C=W*{5as0^+PD{vhvo${?#vro;%+B=DZl{^4mDTd z-Z?3B!QG?$Wb;HTx8b@t4O&eu!!=m4XQ!2`pCutu|2p9j?xXl*GoUNq2AZ0i%I?{6 zaSv97Or(Wc^U?6)AlU<*MpJX;lv;GGd*fNeiI8)I=ycE;tXBjs&APmk`Zr@`U6rWOXoh{8ARP zoR?7kMD$fj2^2&bK!4s5oZqBEK*`_tcD4Q#uPC%ppwu$|+_aN%ZL1Y;&B2Qr**0Q^ zBZmT!2`Ul2`RxNMHCWJ6qg%}lu8qEqOb`=xB8$?VFo@>7@GbLQd@h2*t&_?c2Bn>5 zsyh*LaTO*v(58%;X|~vyMQ?Av*}LGAW)5vJOR>#itF2H{;RFF1x-o zP^DVKU4P^!g+)(o)&g4#89z}t+T}tw#=8Bjl~pw13yC-p+pBoQ z;^DdgIFZ91cbDWhe&U3Viu1~?mOM8=b9Rlf#ml=E_&%tABKUu39c%orN1#62s@?cd zhpzwS6~=<;hkkctx-)KSRE#omh7lNUXP6*;h{`jVKr1RWtr>UVhdBfUzUy+j-R<*r z)2gLMmgpjO_x*W;Sb3-#iMgmWghN-oGha!f37pZ))M&kMnxa{ss06(s2DTm;nRP^J zL`HU>NkOx}x91Sk2O>TuCi z=R%0*l_3P4$a01|K{tSEe7-cIMoDXFD|64#ORYA{4Pi6DK;Kbf1Jec<;@`{vwmy{K zWr2N)_#Hz~pS0nvRA&EBjV!?xd#B}lZv_n?*v1oDU@C)taVe5ohdX^zL&T<78&am2 zu!heHhdcTgTNul%w#%zGA3qlFyPwY0g%mSLp8^XY6pqGa3% zin(Znnoq}F53{*gE&(tZ4f=$Q(wq;L9ySo{ z$P@%ixl9E?Je^Ok0a#+Oms9X)1r0vRHj{;4^^{3)>8V45#g0OkU7m0VCRsEJ$C}oi zM@VQ9m%xdUT5lL?68*#(Sc5^C{`;KG(w0p>Fit>bT)GicH#WnRdpW~1#9TAWrLrJG z)WlR-;m5syhd_?Yyxl`>n`S0s)Vl4aE=+NlX_;mKj=s!_;d>xZ-d*_CycS4ORy^bf z7ZoIOh%PQ&GfjA?wE>WADtq5>Hh<{gVZ5>Zs~;2xkqfo5lrGInr;drCH}y!u_S+g6Fv0WM~~! zSXVQ#bbO#$(p9#4)2{~f`H`(KVC_R0%aJJxu=h1Gxk6anQFzVORFwYV;N(A2sRF@t zZ)s(hkeK}z#R+|sP>cxi)@JR%F;E$Yg*ny6dML}-wxs((QDkQmj+gTf>w%S4EO2#=LQdMV`)5*#b zAPP%~GWKs!qo0;!Pc9;`?CG=XbB#A}mmwJH@j>D914MoJ%ApKlGjh=P7$z#A71Fo2 z>R(Sgi>~WAjn@@ik?c|ZQrF#t{dF!-jy`AYJ$C*M!`VVOD7@;>(g3~deA`+s8pH9! z#=Npm2_(~wV&HfTptI2b9r}M#CHhr1^#!dP$ne7A`?ZgvloF_{HxVVLMgmk3Le7Am zZ>Xdc!X$4I*=LEDBoydo7@i8OMxp`%h%GA0EiM5QekeypSOl|b-J%C9F{ZXcYbd>H zUy3bG^2WPWtiHRuiv3v3M)#D0gu|PTUmJ@OEP6wntTY=bZW_G$<{Mp3*b~JP*)E#YS!b7zHYgQuKfB|-qu_#Fi_%E zb9MW=uOX(5muqp_B{*Q*+t7opK0YplsB|i5q?j5q90&&}o#`D+Pwm;JOTZZTHXWCK&~|4^a1VOGNqCkOx1wJfDfUr zMD!tBFaKc0O2d89=*tpo-4esj!@Vx2gt*PKVSjWp0x2A26s)(-hyVY%`xZF6s_O2G zC{k2Jl!y2Vwjxl3xsypUi4h6O1qMPgCIJy2mwDVt2Ij@wnM?*P#fpm72eoQZTZ{eb z+qP(1tJYe?M-{E5Uu|n^tJbQu)V9=GrLEQPzt;M%bN1PHpF8*7nE?Ifr>yKXXU;u$ zpS{;!&;P>O6*nsDPoQXw@c?w?bnL!>O0HI;#1aHvTENs)>si-L+g?X7ix0#FSD>L= z)fQw5;_mRF2M50|y!2L|TTQ(r9W-Lb>%!jNCRGZqYUXaSl~s&DoVKJrZu2hKvf?2( z((li-ZAS;nPGH5lLFb3-8nY8PHZ!N{rFCgIqRP0bMbXnH6(Q~+d{%HBmAy4;Y9 zlBvrjcpIfAGlHbkL)r!k)UVVDy`x$FNJ;ZX4uGa;BHC0F-zv^WA6%H-tKDC`+!@Y; z4SS_AjBYBM{IGCbqxBMID}R#m$>AGGq?IS1p8MFW4T!|(RZ_hH2#tZ3@0;_i+F1rE z@h7qTg;7@&zYwfAY`D|z_u9oL(^q4KRLA5ZKl>EXK85X;naa#cV!(v{m|pWs?SSD3ST%3Up6~A9Mh*j#?Xm7Bgqg-@S8(iHj12 zw^YiYT2D11xYMyKI?DIFB)JJQ6-*W(HKeQxB$%O;r0(vH2cbHQqN-)9c@ilmW6=c- z9ml?4<{p|uK`s&_*lr_1~wJ!w=vrK@i~n&XjU>0}QTJ7uz8toms?&Qd7Jm()e8bxQD3XD56h zdDdDs!zm{VG?{v@C>AKYD`xn2W7}AzMqt_!p;t>n+d>)lqHC_*vVlW2XeKCnXtqRx zwWGyj8a<@=PL|WHu+_S1R4=K12=T~&CM(y6Axg2!gbnn&OU+G@(1d4z(<$NIVy9gm zDcv5rS;q_2^jfs;W)1DLmw-7Am3B-VdSi2Q@YTXn1N#3oK^+s%C@pN@8d*jYAcr8W z!2<(#AR-U$>9XKu#$_ziJ-_0r4uaJtXz4**yJq)md_#*R+J;%h`My%QIwgAB+$eSj zN#rOZIbrO;-oV*~E@<$QO=}wW)a3N!0^S)`Vv9=~FFIiYE`eQeU;^{nybopo268Vj zY|z7QqA@?Ts|BGiH^g!3uCbR^n``6Q4$>P~sqI2T)(h%;YtQ25kMyK5d73fpyfHt& zI46au3gT(Y#+Rxq1^+9Ts~152fAM8}=efbpF1ofHVQ4pj1wT744f2ZEIeB%%mMxOS zl)3ZJls(TNQMXz93=tf`8ofshcS55dnJ*xUnQnS*C|PkG3eF(3+4P zV5OroG=5J%$n=9%tB{?S+^h+%M&zeit=^>(X85A(dld{EDON*f6cuAJ0&=BFVCYgW zsTnJYrz$Fl2Z{{@ReXDcZpShgRS zSgD*djlN6EZa6k!K_6%!fIZcik>;{v)Wh5-p3WUlYzah=prXkQ|+MwAEREhsl zIb5?uH?Kd>-!zRHZ?%em!l=BkC4@B)0$-hKTV&tRb}GK$68uenM$WAW?gy9+U_N)RvaFm!Fhmk3s~P zDS7fG%JNY<2)e8~;YmVqh|Cfyx<1at5rvkuj3E_nmVb)GApYLccThJ%d86qjl3Y~v zJk&nq3$^?b9D(DKbRX+pSm+x|?qa7r9T38Nlfa9H-TQl=L*&^!%& zhnc%8>F@5;OU7#?oiUHuz~aKTR7>51-`E|8MTkZ2+eG)J_S#h#QvvNhTtoh`{hGV#$JJhgpOoyB~Tf~t7lYCkoXMgTvE z9z3-@JPpkU;jW5Ja7Acd5c0|NF9ia$-r9Nwo=(L()+Fp*xK#?(byFdovhcn-IA`y_ zcD`3H zFvF7T%A9-dDAV*~97pbx&753AFwW6!Xra0x`xPpT;p-mShsfEcjG3i}XGsXjSnXf} z`xYN7;&Ca&#q~FaPmuCj0Ov{#Hlimp3q#X8r`JaqNzv9xPNoU*%(xa&7KyAdYVKu4 zlKbT+TyR`Rz7pIi(nC{^kX!b+K0d)_YMUB!%}MM<|L&QN(MyGcN*HM>CAy2dG%F`e}UKU846$`HJ)?3S|FoXoU{q(L4a8NlJ0WD(hfYGkuf!l9KA+22!SBC^c~38Oj4y^OtM10lLUUG zx#Z`b`N-3gydcRpBZtD|8%YwU9@7x{rj<@|0?FGC_C_J91*fqfk|J#tGt8WRHB~w| zHzND2ntRJbr%kdTMIgg=K@wN{A(#ZP###aBrVoxIST2}<2Tj z$4rI=54X$;eks>?55M~wdT)qU5yipvdmqeeiPSuW9=$L-jnhaX?pxW9;@sBCz>+y? zm#~T#r%?HscAu*#9svqXE$o=G4-sE(K|?^C5yvwA3v)sX+$SdIf$||*gI2j`;OixK zOh{hb59I<`V{eNFioV}1zQl^q7N~hOXE-KiL`)(VL>*@Q45$UKJ1sa;6N!%FHL1@> zW}Y{t6zwY$Hqq)hB=KEh{&hcVxyg)kas+A%v^`X(>OTn!8jF|G*IoK@)SQrTYDeA6 z4AFEz93TVO7^K)y3%uG>~C1RsXPD;$?8=8ffFS*z%J5)?g@c^#sD4AQq#AdFEY;DzS zSScOshDak`O7zu}*PqyNiPcv#yv!_nCHNfdlon|0Rlw0rPv+2qYl==8bSJ$IO5fhb z!ccB}1m7niMKZ;=`)$#ELDb$FJVdfG(Un5HmC)LdGkB4o{_z4rf^J-@hPN7D1>=8% zr17$e;M6P{yxG2Mxpbj6IF5Fh3r#u*9%xgOkmfU)i@z=!=mZ-w=2;%De^ktww>8ly zfN{e-;*hw8o9r+ghNH;^!aKAn92osbQiKkV zE@5MhIRPBtLe8g4#D6Xd*b5X%vVr?SjQN|hF8Q4zz_EDWx z_V&>jNB^m2m2b9IZ_>2XPz?qkrKv1XnL#YEM36@XCsIDN!SbO*IT*vnu-?yFjWa(3cSXMg1%H_t$r; zilK0`%Nm8YXV55U6ua~XyX3yG5_AiU?xtPPHfM)U`(ES^!U#bWfkBM5l++z-rj8kp zHJXSu!gG^FEZ5gB?~f6l@%GhOB(dDh5?*Y~U)tR7=PZ_3yckhLzdlB_E&pV?e7p4- zsdA|b;r!y*f~E}A4(^kRa99|9EFH?60MdJiCR?_$busqxV&y1NH&S-1c#|Y%c{zj^ zT9%F33NO^Vln8VI$gabp&1?Gh?5so&GwT6X*TTr8gm8)&0f*mJEg@5$g$a==HcqPr zc`)>W=IU*hY_6!DVU zRFMS`1-msXIg7|0{!`pbIB?dv#0Z{n4N-ZPEQ&S-h{IisjT|);Z)Hzfe1*J?kah%_+?FBG*k(y z(VDfImo;|O?mZ>3#h#T~RzWtb@@wUWqZTd?2m~pe(!R>vHcXysfzg^DxIHdWv=V}u z4af;gX^>uVuy0xK9GtG+p2(|Y zPniz0Q!v8-DMubuSDBLN6R6Qwz}ierj=|etW@Gwz?uTwRWp9wjcxxLx6bH=%o@;Vu z0*WGDxVz&-q0ih>>fv(fn%qRe=~gR=#(#NuQFdw?IEbt-O2APvJuae~oS z3G;|r!!TrKdzAU2H7pycV*HW~kN*eomuTMkvP@OFJc9hpS)j!}|3J=ts`*Mc>xnZPN%cOr)j zCnua3S$rnTGpztO6`}xWXN?(cX@}O92V&fj5X41ea^bdC8)K8~XoPS?N}1WcmP%dc zNriFFKy8Jb0de)3nZ4`QDVc z3^HoVd@SMtBm%I@qqa`52XdB;CN85oV6;(zj|sJ0(>Tfw3Z5opKz#y1~PjsuVg-1CH zbg2F?v=gEax|jF_@vaU+npis&%qYHlTv%xbdgSgYwyn~%HrUJI!IWE+9YnglWDJ%Q z9-&|nbW@qAh}iK9+)+n0&tR%r5x+sSrCy&OtwXR*PGm`yJ!|ApyxZvH8cdC}@_d?B zyPoCl@pmuFX)ku1p?kw#be=Nlsx~#c7Tvs?M9s}|x~NoU+^j4?vzV6FQ$ExrKSG=~ z6s~qE)YlBFjk5c2ddwwy;YY-M=;@V@&G3;956oSQ9(~xO5B8-*3y@63DKv_L^1KQ# z+99NOccqnTC2e! zCCeeLcd|QTLg{QNXd!%WzL*pF-RW{;Z)VN9gC6eCW=nPa6f|OY&m*{E`(y3SrjCJw z6j}q>k{Yelj+e0u6Gs}=O1CdrCLHBA`)_x35xVoZh?v%gHBXnB&3nD%K5}KPxT!7c zga>mWqoXY8#B@O`^$pymNoO>aKyCXf5o3hJ7?ErZ*r{6@wmM$PNucKhbmjU?oK|-2t`F_HVE3L&x9yV}f0KHiU_Bb-F|_n)js-#o^K?Jz^n!w?2rAa) zSs)Eo@UJ92^;60GPC6z9GhqG9>{8}0EqbF%#7+`i24%Y5^$0Qa+4&Jkuc{M%c!LWbERNFGN`3!7J|z&Iwcr$kPtxKnrIBWy}x$nMi(~Cpo28q3laY~ zEU*w#&}c39pn`yA9tlVvt6S zGL$Sx_!T|qlI60#U$b2B%~gEOG>E((uhWIv+|HUKuiX#dE{xpr-Bf42$YiEj9YpIs zMO1~yRp5Uo>I+Eo-UYuNeglR?4`KFs>El8rmxE^f1!J8=iJ-zXo^Jp@75@z2P)|RD zutaM&4XgCLuE#DZ;y*HS*^5^-Q;s~`r`A`-4NT>(459846q_H0@A`Pk2s%H=FJT$YpzkmJu zP5piAHx6zX*tBWGVBcVE=b={aCQpnJ(??BNs0pzrNDvfZ9I4wzdPnj)m-2Z#9(lq{ znoX!Q6U`@q*O5dZss;5leg@=?hoHeP9Dt-BM!Tu$IaEu^1C6lpMZRXXb}B(yw4p;W zEQL(&yre=%iU#^+A}%rRSYfiI@YRxO2?!Zi`*H+D90z@MRC>st$aM7O-^mxGez!q~ zd~kKS^;H}StfFL{Md=1EUE>}#SE%wVM=Fps%3F8XLVvk`H}GE{wojvL3PI12#VH4V z^C+|h?1A2|U4 zbBq@TXs;ZkN;X_1n+^~)4$hk4eHZPiZQD`5^s;@mE9yIH7i_z1=RR)J;nXei+@jsmZ_3050SM{#j6+vJ@}@?bj*r(wn$(I# zpATr+X)A0K+uc<+O7z2f-;LpmMrw{pWTq#s??b(i_TaST;y~nxBQ=}wQaLI!t*Gqf z2%HGjCc9r;YK=hk{pcPPGg}l4T~%Ddu3GhUys%DMW!WZCyaj{04FHg8GWl$+;il0? z*rx86(o-v`2_o}Ec7WOSh#8`hA~G*^iX=~jtyrn_YB|v4%zkUOW2hl|3bpzSJc$6` zG4_Q4ZY=6Sk6bp~72VgN1)?xb_HW``gK;j+&U6y<^HXzxSM&DrTV+SF`8UcQ!F2ES zz|C*qVGvHnzZ}Cc{;q(!NkXfI6ILBi?CQq&_E|-<#=Gq0`;2OnILUIJoo+15FW0A= z`BUjo0qo{|RzBOebM#Q{^FiL*^bet76)$i#@`N`%*a} zr_}9&^H2g;RwPup9zCcRGHqT?M_Zx!Ht*$S`V@=iDpt6NiV%vkB*8}m3R3P4SyU5g zuyii6P4?W3r?>aoNQW@K$mg>)J8LC6-baNj5eEIY2K0`)ZdqD8IrvU z2nC!b8#Ec!Uqrs^4#x%-N3Jjseg~j<9(=k0aC{y3=I}2>JHWB~cz8WfzQ6XGx z9_)5i@!0k}g9pCZm(FL%-k2QR|9jq6SRIh58L1i~6`0cf&pia#?X7?daPqcDINQVCLAdJ!W(9_vv zT9n9a94Ov=Mx<))&no&rvjar)sdUERQcB?mHLlH)7+~P!Q|3lqi+rs1iGvGg32K`H zjkv$QOUj)KPlT6VZLKAe1J6~nsmW=;v9@Sr_-aK{+@Gd!`%n$>4jMXNYKY0I37l)g zu;8XEhnDO6XR(kLW&uwy0z51`?)+el%3s=5k-#gkR|*=a{T-ZaEXg^Sc3AY=;?G~Y zpO7hqK$7xBdyudsbRJdA?J?7C#LnjiWl+>(khy~Ud$$nrHg2v_rE{cW6k)>j zvNuJGxtCj(MBHpf0V5`vA#sb7$`rIUl))YHe=PeyuCwP^JI%J_@vxT)%5F(1M(C*Z zbE5n83i%+X0`Z*i(QV+N@-v}*0Y+3(*>hO|(y>YleMfN!m~2zegN6JchSu)wbX?U| z@Eqe2N>+Y5|3h_S?tx>M3O%LaM3**R5_ijLRkW-qDfWG~Aml_G$)Rse2Hj!R7BoTr z%1{jRQ^r#kH{dALzRYL`qVN;LWuOCNVKTRD_984$6AdO&!VX7=ofJ~`>z-IZ03j3t z4=jRTL=8L3!$FDP!SiydAD-4A-24j?UsBOrnc=p4Yzxjia2C4TASTdQ?HDh%0WP~7>L|p z$PQTZh>5_%73S|n@DAwyMpWL~9_zva7h9I`#!9d7^z9E3c55gA!=tM{n{aTAiV`p? zWsFjCT5sa91oKqXG^8z5x+}zHw;VS=(`7ikh?ZaAnRhhl*6IN7!jl_VSmkZdP~7Ld zh9~F>;CLkmTXilv7)L0w7MESY#0Z^o z2Cpb4k5m|01c+*55}iS$X93=~`{P{;3o?~`+Iu``woiINT9j2U2v?*0yLBllH>;b< zT%1%<*R1Z0Fawx46o1q0tp9Ys^C}<)p=*hmr)Lu6!me$*cJHli-@R*xX?r~@FDrFH zY*k)@v>vDsEji1VBu|WFrZV72040ZPF>!hzoH09kbz=-^EL#iC@hw}-J8o|)e|fAO zKWklgSL>3=@6yd5^Zi0VC44eL$CX)tEdac0-ViA?RUmBRn?s#zz`GB9%G8^mDNk;( zgiennl5DHbAp_&k_={@;$yY+vO9Q!qTOXF5l*yK82x!_W3ocj#(YcrC+KGrZPE0Fq z;a6LqgCGE+-is-6g|3?vXsl3qWK~2d;xggaQwE>=EV}gSZ!q{5NAxNh$}yT@wO=h~ zLYCV>k4cZL{iYjaf+#)D+pL=*;5qtgW{?!)Np1Fp0@j+ z?HN`46syI}e>NZipPG2d+r*wnYa0;Dp0oZ|3H^7$t+(dlXl()Crf9ttA24-DjrF2r z%4SsP(_Bt@4-_`}a?F}YA8IRpGu4T4ZS!HLkAO5{HFAIDjM27pfRrsd z&O5EGF*8JPc{1$!Z0X#W(lv-M%R~(!uSo4xmHya~Eg@*Bdvqsi9PgJ_Y73Jy%W$eS z>!S^LEE{^M&w8Gas`j7iK)tLO9!J=0;&b*SI#tF|M1~U!R;1xBl;pR&4RzK!|Cip9 z&)FKXh!uh;nj6o+;DZshRbSgTTWx(xl3X?H+YE)Zwb4hkUfWp&B)M_WYE>OO+neNA3(2xd3@0D zQl^;&DqTuq0s*=F6}9sj)-that9FyY+BO|yueyJ1%)9rR;w%_tz=p2Y6u8Eb^rd9> z@&gA1MxY?=TTayuRFeBIyA7#lb(BK3wb50U`IKnh#fYDGNG3oMSmM0PkE9aSS&m&# zFv{Gn?IYP)5Xu!JW<{H`c15k{k_kEGHC~dnbF5cp8cQbe#6a2_B&UT=$MTg{9+wHV z_7cYqCa#l+MJMkl*e#I(v{cK@nU?JDd{GZ_1Jmq)ucAb=_@Qf+ekL zj=*GPzT)h0+y&RFB7|8Doo6y&NuhqPBot}$6Dt=8RaXZj&tk4IX32Qtu8&1#?pTdL zF0Fx>`ow$#4ZWI(v^0r;?mL3XCaM5d#r!vb3g|F?MK^mU$4xy5bX<7avQA>i-O_~5 zdjI&AEt-;NA)7!1tnq=V75qA>gLOQK^frQypMid;{;2*yY7?=n$RJl5irv8y7oQc{ zEVyGFESs#*g{-(A+A3{gMDT7+PeWG3-eOON6%g*!wIr$B?zhBCTG*Ur)l??%JLF~Z z?m^VW^%~W_B~af}m7v~N088D{ThF zduw|+i;>B|Q{NyV+0b8EB+!QQ**r-0oOY7Fo>Pqj=maOZNM3fc}LM`wh z456$qdAtg`r>2J0#|{AN0TN4sN!)Dlkv9|it#Y|hatJDbLS!h?x6DXJ`% z^-#etYj!pyd}#13iwJW=wBUeHy|J}UFIiuA=DF5FSe3h=XR+59C1BTkQ$bu7m3Fcl;?2oexmqcs4bNY*28bLU3(Yh-GsfLP=oRcz9nP7t)y2WA}L zpo1JrSwYxiU1iBcE^d#hc;lpWF&C-|u3el&fJw}aNjXW8y-Gh35(uo<6qfj&##}!i zDh@-8)&@iwkd0O_y({JI!xD=Jwt(c$X~7HkPoxKCZS%yfn=I#+8S538p%dX9YJqq` zVN{%bi#JR+=FN8}&fdL1N1NGi#Uy1;xm5wNTGUL{{(?sUO;gIDdeUuE%AT*<4^>zF z#yB&j%ST^5T^a&2BS$^UrTPO}A5axkvgOf9T?BwRUZQHHy|AImk|y>b`_)#f_W~4! zeC$B1bC2TqK(e3e9~K6{S}lb(sBZGo&BgTqYnHk?yJ4ZCXT=V3<1H0avD+3d(xNL6 zRvDfY|3z32%U6M@aj^wDz3TFt#^8n; zJ7|>)sp`QI$!rSlKrdlcI&tV4Mbe%4|LX$I(x$np#t3#nRgVEh-8oab8-PtUE`5j^ z3g}bUQzv^_)s6PDD8CBwzb6}IGBZxvJkvT%JY- z_%(Iu>){sk#w@Lc+ME?^z^(EMGsP$_huCgiP}d5g9p^( zsP<8+h7#X|Z*%=6J9cgwZ|v`%hhb47KXE@u-ymF4?bAyW7T{8jdn51gu)ss>K7&Ne zeJLo6Qm=tYSa@j!ULKwF5&H6h*Z2a(lO0*7D;!P5|h-^p9sla5NM` z`D3+y?Nczugv#(sJ)kYIO^rjy>4GNI_GE-5mTw+c{*$PFBRfZCfU#BEIRcQa9JOz9 z1~;fHBw>9TkY6%wi6hp3zINRt&1&T_6@I;5SbmAQY;D`S8T*A>mv}5Jy}TOUO;EC#d^EIm0L82 zdXXw6Uga7sGYPv{-L_(sEzS_;P1H?4x9Ync{Z-R7+CO6lyEKXvulI(O=rkEX@QFVz z4xR7SZd5f*oze6ebx2&KCsLu=3C@KqWLkDqrQJY&as(18QeHD9r5(B{@lsj0W4~Huad{xdGR#PDd{R8`RTb>E7+G8;3XC+aa!!nf%9=@=a9ef z=ri8Gx3REqWWTM!jfhUn&ddU{0KoV4xmm1EagZnwLcckN>rl<1PJ=r*zNiv!W@rk? zGy2aVK^4OPGZ0toV1R||B7p?jq1s8 zh$K&`sOWwhcAc={c^L+;L@6D02uCH)<@LS$w(YCc_tds;+qrXS*M;^<-Dv8rAk?NA zCz0dIhd%7AGTK)#D&YI-R_`TA>d{h^NWpsG_09sO>cH$2av~551L8Sq-hq?=1GGLn zQ6Hb325^u)a*GE9v6oHK23%w&@R)!ewhR6}E?H}+)0>6Po!CVVKDVNLwz#j-_!X_r zQhWied7hY@#};7G^NvXaucevMk1i$JR#A4UY`d(b6t>W$$XR%Vr}N&D!y~vEXDo6d zmWkp57)e)YJGKzmya-~U1-vKpo3y+@p6^eGwRm%bz92=P%83Q_JW;vEL(`Y$M3cky> z=m@Ev8td!l+d5J+Qk;wMNJ?@$x$2l7M^_8=g=tNhjBxzHwF1RS62T@W;lY>Gz{(ON z3+f7NA8eS0xA+hc8T5=YeOhjxs{$=c6QF&9O&7*>Lu0lb!k(Vwf;*7;sDi_&6{|d@ z57aioL4|l3UV%pk3Za2G3O$|5{477<+N9f?ga^ov!6Z?R#GiL{64DTEbEMJ<#FWax zgqs9!WOxM4VtdTFg0!&+E&L?84%Xr)fl@E0Kmmv;sWm63UKHQHtj9tOzn=ONxwpLU z&2x**16aM#gYcwTa5d>TcMnccJL}7{0W&D37Pujq+z9Pz@N$&4&d#s*9Bg+=v~1Bx z-K+K^5kS^N_pSB|-}@`eo`iacxxEx;^F+42;)s4Tz)hE>Rt)Q_WOt>w z-E{Wq1_I<{23l&!SeDb+Fa5@fxzX~f^KzU_Clc&?6NX{=Vz7%_Op;g;OntBLMLK2_ z9w6RZ@JogWY&Ztv`Nb7sv&iHWW2gAniNa##8CI?MD*|E81kaMYwJXl(yf+)}qM=_n z{`7yc#7$WVTGC2-fEPb+-MY>ZQ}Sr4BgyyB@jSy=DM!MdzDBH{3PhZXWCRBn8b zY<5Cni<$YbkLjRNH(}>~**C%IDJ@v^{LQkM`3y-(C&>WN@)$i7$Tak4fQp+aA5c{& zDk8`OE?ZmEeu4@BEBvWTryqk^8`O3`GBpWpJh2HR+{5re7y-e$Z$%+k!fi`7#1cNR z;8XSTs9KGg*DIe(?kc#Xdo!{JZw{VkW)X#3bEv|sRiG#>7!v&GVsp7AgHN(KGH`fX zc~Mm005E@1zc2>~Bgu3CMCty9_ARgNIdDK0Ds8^md6;~nyTw&&ThY8|W>Ii6wrpvc z{H^nHT1oQU!YtbPYQEQ&Et>3D0^#7$Gc;1V{`(e_rt3QxMvX_0yYg$eDZP6Ibz&7O zrU%DEw4ZD6{_e1ledf{5x9w1GPAF*DlE}j@^(dm99uaLGE+rIg9GYtkd&8S<_aXis zaKyOvKA?%64_l!zQs!V-K#O=t_Zg(@NXrELO^#4D>#!^F`3*>ebYaTcIq$4DgvLV5qrV5R@|%Uy5q% zpj|DxPXluohh(_|4C*+O>3#K!fC*=&;?C*5+Atp5bLik|LRzgActWT{YnYLsq?HNr z1nxPlA-6juMu<~62ph^YRQpsdz!#sM^BMQ!p2aa<7zq=r1j;_$w>Vjjm*}ga2C~$y z8PcyM8G5M`dVm{d+{iqwV}H6>`7hBK0xKt%N+p}H9rSBvX@<5^yqT~AOI>{UnqIx4 zsiiG-FKt~AnROm$V_i&pFbjPCOW}f>1XNn3eh`mycBYnc!DX{dC)~=0pR0TWV_6J7 zR7@fpWHQL3@Ksg#jF#yUg~zkYHY_a8O*MwlU8ZFlL147Rfu!_S{@gvZM*#$KD?n!B|L5PFTbYnAjo!VB==me|?rP=Y1O%ZWy0ywh zNnDBH5=taSsrsxHg_^Sk^?nB3En!xPx-JfieuLvFb8mN(BVX;ekONPA6H=DDRd)O8 zW`o*SEbqw~K^dEsO!qoVj1gB|ZZ0&YdCS@k=Hy_fsk5ws4}oSeJHIqCKW<8FPaV^^ zACi7l-K&;4F8jF%96mHs3-HCTtL&S4g2Z4;cJ%lV!jiW+l{wq2wXfKE4XBjTx7E@-m?2oU%2vII)gOsXDvH6LOv=k-;Ee}93Dz2H z91B{($(N2!+m&34?VD-?gn-Ccm&?5)6B4I>zqyjH(GqPt1K^QJzj)kX?R4vo5s$+Z z@|GPnT|?x190tE_N)Rx$@4-E)+ z*7k9-^R>`{`-BgI$;YJjnFhy7rD_+6F`Gppk~@SAdJyc}g*R612mYko69-qbsqYxS zL5UT8Zw%cl`Y)0zn(&ZWRS-o%;GxFTE*!8k$%VNutzOJFUv8O69KALyffnCa7cR@p z%_)nQE4yZ}oGNj8w!u($RH|!0*rWJJY~D=9Q+y-@&2(AqAzn@1e1HNnUspZNbzmpT z9*-9blI7xWCE3yK`e!AiwwivKmXu|;r-Uqy#j%6dx(`AM;6!e{Jy@b+~Q1)y6BM6w-sabLYmAauU-fkNg;x-X4IBVVMp>ugBQq~}G zrzXdi&*(q5XdHSQEe|S%xshj{MyGI(divh_{;Anf3zK7JBJBrzQY`|!wboxYC2daA zdoovR9>CP&p(-VE;(Zb{=hEH1l({yoH=fLR`GH+hGf;3y@uBk~ebcG4#$BbgS`XM3 zss(VVo)4>)3}XVGwM|?X0c6t8b%MaZj>P9SwW^XctiBp^^+a*OYV}!*@RiQbz%!dA z4~RM1iO5*VVVIx)LFP6JRPaFh0bQ@R0;WaKg~_AomT{uaq)n4eSZ$N6T?sxZrPK5V z*ouwlaxe<`RjcTgAc06hBZ9+w$>iDEom(9jcLjL~t-z*MZX3GHk~QIZ7AJJp$r+Rc zX@(}cGEJhFTmvBy0AGZ{BQ?dDTyPZTp6H@2X!q zv`c0!5r&=$vmcOST#P6RI1e%)H8Q})h!EWpNkl-gTHUe*>n{V#*ec=7MB52rd-+DD zM(V{Hah9aUc!xypSe4vfrn>qv0_pS$ zLm+?|TeChtx&OdI zDT0N}#|qMQ72vKeV$0nT?OttleUMx|J0X!r>0XE@wo}v{oH2a9XU~b&itm;mwe^v) zF=<*-fNrq__qMU7EZucZ;?DSd+&DJ34kbdLdZqik6s*gCI+6gcT0cg7IgkW6N4fPKb?59A9hFLiA<*6jkGBXj%mqn?K z0GFJufW)~1y}PknyC3e6h}HNcfw=NV>?rFOHBop=R+7VX)eiRfDtu2;1GEb+qlBL+ z^Ep5P)7mZ1Cuyr~*6Q*N9%$BfmWml3;7BWIj7;}*jN3jeJ2Bd%NK4Kf63QjTKtfPE znlx7jkwFDDdIa$CsqK^U`C?OGxr7N=_Eh=tfNfYB;Ph5X;=9~jA3`O?0@C)arII_y z=v0=YtF0?3*ompqdi7e$Q4PyfGQ%Mz8rNnjt~~Tghd|oZl7Fn|g_t&lzeK_$#iZ}O zOnpp<-q3O0>1i$=N!d35`j>~#N^Jt|GjiSc&{lV0IwxDC#mQ9EG8t|a# zUzR1!NVue0?BkS04Dp)cU}V9Djfx7}YG!#H@_{i^6niTiB`yu`oBUvr`SB68QuKG@ zn6w3-GBI8*uu9c5K)GoKG4=~in*kNlctf$$JT7%lEma+dNp9$YktY&l>y{R+fY0@> zcaN~8gh+lq5)ZWliaAS#Cu1vMT%`#FXt=901r@ih}~k z7&HTt?QrcPfE3#ro$&vn2L$Aan*5gSE!s2P!>!&3br@5X@|mOBmgh6b&9+HXB9oAQ zT@LjarP+*&8Pbm=8zgd+1#$s=&5y;?TH&STp)weL+H9Wf=mM2T z40~29SITV1N9=~Zg!4FqY4iE)#(NWhqhM0Hs)h;v6l9T5W1#<3Rn2B@}&eCtAH8sz<7uapaCn zEsZQ|@i;U7(|wT~ykQB{cEvXyv3zt@2NO09igiot;dV6j{A{U+ zQ*92eXX)Igr&3lEnK{JGgDvT#?#13rukh65===yURV3cG(TZoXH63RfGzC)Gj-Qm* z2hP$So1<9%!67KL2riFI;egA&LS4Es?+5COdhJ?j3Bzu6FdZ?ifa-*k4;`GF$g3XN z->?N_m=5M_<6da zcgD26+XS{ulW(Y^B?VPtyk1d(DM#Y()RY!I%0|maTJGpM zM~MtKvbnurwsq^mh;0qg-U?HF09gFjh)p>$nMVSXN~9`Vey?udtE&&w z)6{!&Qy?jWI_+GS2LvsdWK+=NM%0Cth@nL5L~bq2PQ&#fnLk^b2WICN)+H8i!eUz? z!AKM>J$CWQr9l#Q)?m4sgR=PB=|*wIr{RMzw?%)A#w0T*m8i76_7GVyQ!GH^^&>7% z{wpAd;#nnSW3z&ZY8H}i=79-F&W4_#gIH#5jBv z`ltNtMEAcqK_o&W)|Y^(QeO?`5(=JY1!h{o(C`=@9p2#VHvo2>Txbf6HZp5Poq!sU zT`rn7W7a*zl69YXLnQQETsY7a+_~k3w_(awiqCi+d>?ABRCEC!2O%PQ0AjQvJOaHJ zJHIspKg!{Y>vXeu5ZOcpN3uqzDlu$_oltqvgZs7G<-V>a^VOt!rv;!hk~&8-DwV*F z6xKwQ5SC84K!r^fx?x3%$%JFmX0N#mD=mu-iE&@%+p4Y?h(fJ_mEsK-SUn2~9C~eQ zAF!Y?Yigm(rp11rAW}ikAK8gz7=0{cg?;R*Wra)Z7Cmq(i9xpF?&%%*Gqb($wmbDP zry!No&kRKczJrv}r9zU&T7GW#;?BraA-uqj%i4l7Je@IGFqFhP8%NMWqCM#H#XzI# zwy~M;fKBs;NEkPa(LnIFb2#+!E>M<)Ff*1cGV18;FsEozfk^~8bXzYBYE=@v@pO^C<{y?F9u=KRo z?<7%-wVuB0=DEA&KAO*U8UxL6InAb%1VV|WSY-tlXiB$AhncP7Jj=g~{eM%nK~FZW zCCWsK8512yNDqda%eFN1I1emK@Md} z_tJ|}p@{(-gYZGt&Zy)7D$PmCqRPN6oIKbNaOl})km}*q^Ww}kGqX!GdDaJ$@=HFi z-GS#wVaTGGg!PWBlxCjBN8#W~x4TA4T+}|<9a=6~5E^+g{-=?DeF5Iy%!^4Vn+>Yj zsIwC%)dIu}JT<6CNBszje>O~vi~-eex)OqQPK-3+Rm*_g;uJ4f`K@K>F!8;(=xYb)! z@Uhx@L)Eu%Vmz_a5$I3BA-GZ@;CKfmoNcv;+GY)G3MioX&@WbXt#)u2P#%z887NK3 zo=Fsr!<=41ATQBRVafCJT`7UUF4I2C-&yv;yD_Gjjy??aOB=VXlwHPxMViWa+E|ue z2JjXL02mK0Y+A1=c9=c)G?B`Y4{M>+p>M0l;5mB=cu&HQ6PHYFD;1`tQrgv;X;Cfk(y;YsB(lVR zmLcoH7)QJ}=-644ce0jw&m{-52)x`99FkHxJZb^$P^#-xn01&8ElE=Ky+mDiU1niq zziqx;2FLZCSn~IG6bC0tV}8QnHxuP0sqH8JEiqRzk2W^Xctb5()M|vTP?xi;&Dc;DASl6s%3ZtLw(lFdoV%;!ux)3y-~;v| zacvG+nebgUYr_b-tROjI;HV0yf;LF1-DeX2)|^VpFZfSG}Trwi^p$1s$UknRbHWCilv*HKD3IkP+B>N6#-8_lX#T`MzZ2xITu=UhqhZyFMbJ^MsCxu z0N9|exQ>866KJ1(Eoh(m>4DH4^7;sIoCU30hR4_3loov)A74;VFS4V&ZkG8kg)M;rRR=s>i!fSA-wn6gI z8?|KZx1GL4wC9l-#D*iZ=X`}tPXbiCm&`8Qw2nHA7Grc@9d0zd%kjyHi3W-i$56~@ zaAYXrQE!ykPLXlw?#A-IQ1YT%qYf_hdeMjk+bRGBh^*Bv^0CTVVW=i*{-sM07(js~ zz+q8MAkZOPK@YGfdEl_ZwqvQx)djS3NP-g0ymb3Zah^_t#<6jO%oxMc3*8Dq&)yJM z1p7Oa%kpn-d9C>aVvZcJ+5sg34EiS9|hA``Ak9 zRJaF%4Zre99&HDpHaaRBrdUOAWnt#>L|U^Xya=q=5=(i#ctPZ*~uTlm4XsKIhaCmmHxt3c(?O6y{P$J+Om*Wlg{+B(uJM)954+!qDqO zA)kusgCe+3NyI`S`2)iQ zwv+`xJvGFFO-n(PS0iJmMx~v`PFAx zvg$ep4&w{6Hd}r@I&HO)rYqbHxGC!7&REQ5wCvPogQdC+F@e-Hgo|T+9YG~A6W#EGgc8FOZAK*$qpE44kc+;c zz|-XtzC<%UJA`roQZ#ghlI4lEyOz8rRk`EMk$vc9E&7Ts!DcR9oyDt#26Q$quyh65G>vrDX zn4NAc00m>Zxt|L0+UbR>6Une*>M(5#Q9BR4SVUOU0>qTe^n8JYTT!`@9?`PI7x; zI)K&_I67AHEUb`HmzOoW?vqZtQ!BroBe_8VDUk{Z3#*nyXoZDk_;XkW;;#%b6Ra>u ztD`N0KF)_?7{}oNLJcytDK8n9qB0n-F77BKAlS0alc#OSwaB&D1FE@s0)GHO43F1R zqjAkR;Cw^@TL~xP%gdnO)wVLXML@{Tef(s-(56yId}4j z68Fr=%z|_S)PzX~Ul5m`dVe!}f^*a-n1r^T#rNTH)Y7JwX?gxYVc&ve>?-BeijpQ8Q z6#EjOVmo$kuMh32@7=y_=e9lOxo|DW{iy{Fp*_x$l)o;bh9RpPqrD`FHTAhEln2xU zC_AW}adks>6!w69+dX!1=(#I%!c{l!Z_J<~WURh82pNr#B3|fpU9Cx*uLr`{IG9v3 zeRf6p2sBL-!Io6BhLv@22TWxND$WHUuti301bsC%Ib!wkK3nH%6qS%!!5@TG{h_!w$A zg1ZXJtS?~cX5r*e+^1%IHLYpb1u@|@7;%uQ=He*6bRuNvGCr91PV^A-_nUSWezlg9 z%oMktG;~Dc^CLhP%O!=yY^W?P1v&#=*(q5mU6&eizc%!lf}#hIo|+f-_<59c{W3_c zeP3M1T$A>jxd{Lhik{A>`xQKw$bT(X?ysHt)N%264n&kH7=;R1Jl5U7OHOCt0f#V= zM9)I6;+9=p)o`g9Mk(p@z|M>mFC=`8rgvf^XD=@|gH&h3uQrFk#c*9t15D~ZRaVjl zg4PMU4-{_}@xO_Q;fV?*kNZKXs1$Q=k_&+QDbE{{L=U`K$D3`7Xet&EHx6eJ(Cs+&TLWPX0KF%MN1NN_`H zRfjJ0Jktep45bZzS?dHz1;ZU!Zhy$9X8R$zvLq9fek?ePQL#NUW&m^u(Z$(q>hGXn z^{nkR(^TO`VIGWVth&Kh(A<*WC&LuOvXL()p8Hy;t>s?c_7fw2C<%EmDKb2MEbS75 zZxv^MiJDx@Upe1Grg(tXssP9V^X7~qKm+gV1p7dmZ4oTQ)(m|2L#}j@8W9v%W%{ng z4oq7za6sFn8)u|^Rt!wpWrLE9E!mzt|FBX+B%i+8F#NDl;;`m(sI>Fii0nwfJ6tnG zI_SHIyJjB|o;pLj;od;Zg}_gE86k4A8?N{QV+ZDEXJ)H?+G;{Wf8yp@U%$M+>OLO$ zH^;7#Jkr5&=2{E^Fk^$dgok!cA&q4!cNk+4qwEOY7&9e;oskGGL0AiJdK&c#zR|;$ z1QDijmwS&BZdmM8B)Xt#U~Xg#-PGJ(>iI!eN^`O;!`iH1GS^b4M|7;%K6bMP?SLnQ z8pJvsYZYKtH0FU?(QxGe!p8mGINi2vDV}cUR+@8lgagIphPrjf*50yZ=g4wnUh^_n za{dm^&q__*zF9dWqul3e|L|`X>qlVP&|4tNSZpqh zC>XiA{5IuiBXc9ma#(i*SK@hLxh%=RnX;X}Y7cYAEjw`3*5^m-$bFxj$X0tx1bZ6A zt%75TX22pfmmxCcfQI~R975*2%46UerjxY`kyUyDAU^jYhjM6!^2=?wl3OJ6#?+>R z1-X_fN*xJ-x6xSm=e50Ys;{m^%^Hq%3;xe=WsnvJRcfWo=(h(q_W*huzEuCue~n1hsfz2ph??mCUbFnio+W%9Sp6sl)n*|N$4*`==xu>C&NUkOZGtGwr_Tu9l{+5 znyBEu`{pdQ+Bma94x>V;O26&)K>tX+`M1_KGLpEPvb7)`QQ9a;W)+kPXnB@^m)Hx;1Yq~t zOIA;+n*+gGIRr4LZPF1mBc|swc@lD^0J{=YvmoII>FZOoOE6+aXBW})#TO|L#zK@U zne@TjQ9b13U@oMz;d>p1BxiN6F^72_=Y^cr!5LBE;JwoynzA9t{IS= znW3GN8wI;W;6HTfB7s_=yk!~dzwaaPc#AY8-c%=XvHs1_NzfSrz1I~a7kxEhTa0I^ zqOLWr8ET-ecPnycOB_#|8DNdERpTs|H-z;r(Bil;6~rVc{0|7h!2mV9UvcVWg5LDJ zl9aM!CLHX5LdZ-S3d*)Gxkthuf}U?^FPK?|B?eC759vt3_fSYAbn-QM)9oD!?svaQ zi^T&271bT8{2S<@XvximhWL)>W}DiC*FHaXTLR(PU}B|BR4QbkauL6*9|Z2|0-Wzs zKa9P)37OZD@r-|Vstvi;+p44Y$%+;8dKTq=I8=(RM2J;SY!8GJ1Rk=#E`S7pHxo}G zaREH0Jf)O+HIXbd0-$)bu0vLyP`y?Y#x~;jn&lw?jMC^e-VLr@{NCy_#d1KB zAO84RqT>4EDRaFV>N}hQjhUwPJzir2y~IbY(s{3Dr&lFmwxk{cR@QDdAr4gk6x5HN zZITYD)oE%1v0znloJ$WmmUk7D2$2b6)eX}l*Ra_@#a3+IYAp&9eOWOB_#bSd)|5oGgwk7W*|*xE+4i2#Hyb*jW>|YHM^`UNpVT}m155WT97BJQ-`X3=WAeZy8ujt+GgJ6x@-exz`e3WL(`&uaI&$K z@5Vht75BGE1DFCuBp&>D8lV|-^2@lXj694wiN<^+jkoeiWhH7*EhOtA3s%mql(ps5@ z6NcEcvX+(zd&|C7=fL{@Qon)xO1uLt$r*I4<=#Dy_?Sa&Y7zlc>tSvHiJ0720s_rq zqdA)W81u#Nn=C0pXuya&EXW&NDP&~7-z(tr`wuL18#yXkK6n|K>7yEPvH5uNsoS1< zl5-)YJ+wE9nCJ>ZpG8b+!-y_BAi4;&%WX#_p*X7j3pkBbxr3Rge%ivxY4aYOkSVuR zZ`iccOmob&CCAA!t$szxKM5@dDyPY*Hc5+1L2^Ay2G_TN1YtQ0G*j$$+YZi3*dn=4 zIRtMJcQM)_j#sYv(1R-S^9jR=Pk5`*4Wt*7#@FxoRlDxaTaA95^rzlt zp;r?fMs! zzL7M({weRV>+U9f(0grsE@^!I`^i7)eRkbBq&rCC>wk~@C;Wz8zk&2(()jwP-e%Xm ziS+%XpC*m3zjF7H%6h`E(T$`pB8{&fdZXR{y}xbreWZU(`UTP-lU9Dmu4|A^kp5Cc ze}iMEw{z_DUpaRA#NW01IvwQL=`hDmujAP1n>cp*w;Ve?^@DbQr;8jr{cVn&-odfc zKjZj|q~DF`aldExcly&DpGA6OL_f^&M@avX^ls9JQNBE!^yv|8P~JFQ;MnO~IClCu zj-CF9W2cvX#GZc_=`86S>93OBO8Tdy|CjVXNWV{d!SCDsoW7D{ryu6{Bcxx9=z~6L zfA92sj-4)Zd>!dWBl<@ie}?p%q~9X_uZSM^2Yi2|Pbb|u)|=KShm$^y^lZ{S5xtIMr?+tI^m`mT{pcUs{hjvRZeyo!=Gf_rKW@MOInrMseI4oB zNPms={iGit{W9s_kUs7XyWitUUl7s%=J~|^BRa^j(;<$X-pR4kM}3m_ zBRwsmTRC?6YK~t+`p8e&-ycW%Y|<-8Um4N2a_sbXICk3iX}h1(A&#BCm1C#>&hht1 z_y3Xo{Q=V3Bl^M5*zcWwfn%rN;MnO;eb%mb`Y#+iede9^`}0WWBl;1Jou2nOUQb#l zy^8exq#q#tMnq5iy#2k?4IFPIeKzS8q`w@|&vJYx>A)Y`{hWS?W2fKb_*B$^B zy^v$4&*FFw={q8N8^=z+%CXab?<>(h1U+lD>@e?WFG@{VUSHCjB4MACW%o@9p!?CVf8X3rK&4^m@{F zMRe0Q?C%FjMBH}~vD0U8>~t^3PH*Jc=^HtA zdd@%D{rX5Rj_4%EPCxxGcD>Wn|J}w;w{yIM^kotKEsk#^een0}@0~U{o*;cG>B~r; z`yY1w^GL6Y=)1pfzkd(uACrE8^q)!ph4kzn*!51Y;MnOeaeNEu?~{I%^vk4wL;7RV z%Dr~qCq;Az$4=kRvC}Vd>~!aU+I^f}!|@d9&y&82^c@lX6vv+?{W9s_kUsps?EX%l z%CXbSId=NQ|F-L$Uc>Pe>Cr#5-#a~vW2f6VKA&_VqHp8)*GNB3dI#x`Nh|+jpHn66 zC*2p(pW*m=(qE3~9UMFT4#!R}`;mQ))BPMDApKZG|AXW2lb-Zr`}>ngH%7F<@dW8x zNPn61&WIjUG5gu+4vw8Ja(s~VgAqOE2>w0kIi!80myuph`nrhzkYlGGdXU}E=`j!C z{YhUC(KmDK^ub5j^-gc+*y-^;;@IggaeNEu?~#6p^ps=leol9DJWTp0 zq<4`X{V==U>2{8HkdBd#lfI4g*GNB3dI#yFA8z-14C(VC`c{se{u#$kzsa%FzDL;o zoZiN<)7KtrzjylhN7~rwJ2-awagOgG{aQqiJkI{!>8CjUH0jBYvfn#>2FK@;J};tg zKHjc(`nw!|ko1cYJ?hbRz0*OCo&F-nPT$V)J4io8`f1WXC;bc3Z<2nCboXQI^M*+$ zBKph|?Dyx9-W<`-bL{kPj-4KTqW!(oQ#f{d3CBB0Ur72Q()UL64>)%ECmi2JdfG|$ zc}@p8cDns!`~42miHP3FvD1%pd=?^%*m-OSO*x%nl zdd}l)>~u57PKP+Ym~=U!FX7nf%^W-ZB*#wg<=E+2kGIcv`bmzRzWNFF``3{EcSIlZ zMEkwd6F5GRv=-6b96Nm;$4+nN*y$%Zc6u+zPH%paeZJFQEIClE$96P=Hbi1F^v(K=x(>ljjk-jdXf5EZSf8+SOq{p3U_j9_D zW2ZA5JAFIHPJhI))5rg`-OuT@9M6;f5$R`0|CaPCr2ibzBhRw?Ieje0r;t9I^a|3M zi1t6t{@&>@$4+NBcKT|LoxYdj_mSQi(Ie01^O2rFdLrp_NUtP)aGzc8^c0Sr4sz`D zVve1TSMBeezL(?ok=_~6f8zK%q)+I#zjt~L$42ec^ih zJg2|KvD3fj*y%|FcD>X8!?Dvp=J*Swe;d(9Zm_?1dMd|HCVf#ve}&_>lD=l6{k_w_ z=Gf^uo9y>}q~}L;ieslQ3?(V z^dXz={zs91Afk`mV!uCy^yLx#1&*D*jpJV<{nLnknPaEl=Gf^EIKG$kp-;EZKbo{Z zq8D;}5$WqA`azDJex75eU*Xv4JsdkdYAff5^g_~$NMAwvO447A=+V#M^OJ6j=oH6J zU(B)74|44EKhL%MIX(NCHg1?c4179i+1neKp5U-^=m)NPiU3 zUFX~VoW7A`r+0Ad^g-M0dZ$}CcDjpWr&n?8^m>k+9>2rx=X5>C1EgaSy@_L|zrnH7 zyEt|_T(kQ-UF6v5n>lv+2ONKl^xO;V@0~u2<2|H@BKq?jzl!uvNbe#&=0dxl(>{)! zPI2t?a~yx3^tl(=-#?G^*dZG`9pQMC^y?8l;bObq>3WU_NNqyUu z=<_*#0qHFfy^~|7f5WlUf93cd(o>$p`6t~G(NT__{wl{#-_Nnrf8p5axmVi#onFte z(>pnKdg^oSdZ+6-9w5CkqBnBv^eNA?zdwz1FrpW8?DW?;cKT6{oqmyHrzbq$?tda_ zjr0Q2CDKEr?<9Q}>0golHR(^h!0vYp=_RB)Nnc3%BGNx3y`6M#-Tr{^ZH}Ej z^(wpmbkZf#L!_^X==(YT0O@B*?L2kG}oA3I{7cM55hw4Zc{^kUNIlfHoT z-y?eDsNL_uq_;=(DP#6~r~Mo|{UeT@{w2p>B7MfV{k_wRId=M0j-CE1$M=w4*08^K zI?A!r8#s3Q9*&*sseI|BDgIHFb$1=n@{1!Y z53St(r4;|@%3Xhz;{QbDh99T+$5blkwLa*Pm4{WGOCMQzROPsrrTE8JzWtUI|IwAZzL(-ZrgGCG9~|CV|9xcT zgvu>R{)v@all+q^w>~a)pOY(f_@`8^*pT8su5!c16#wxp&n}E3D^Dol zCl;Gt|D=-Z*Ol;3E#W`8g)gh@!Igjear}#igYlqB>v}kr{M(~-BA+PNSKe4$Kbycm zqLR;#uj&hw-})Y>d7ty5`z-7At?S{ZACrFmTlD%9D;GV=-pkP#%g<-=e|b(%>h_ua zI{BV_eU4m=pJVaBa=j;EJAW(ro{W8pU0xX{-;=Vj!u025_(uf$(O2X1$$v2SDQ>GjFC_mV5&uo(9~JTcfc%F>{J&NH z<0?0C{rmmDL;lU=`}{uw+g#SeEz$K)B>znjUu=K5{>>5pTIC;CIhxPo_x}y@kBgr3 zPVyfW@&AGR<0JlqF@Z9lkB<1KlK+^9e=hkaMEvKHe`3TxME*$;{|)4y9PvLu{^QBV zP=CHc{(vl{|}X)%VEF&x574g4J{+A;Dkq@=!`C7z3i~Mg# z{GH_A6Y;Ml|K5oI3*=Xhvp4AT@ImsAj`)8?{&5li$K;b3 zzc1pyhWx>Z{{iyPi}-&|{zVc0Uh;<{{^Neap7V-`|4j0)iun7_-B%TOT@pF{97abwdB7m;=hIb+amtQ$p28p{|5QD zNBpB7X3zPVh<_&ecSZbNJI!{J$mt-iZHW@+;A~{3IwG zGS5dx{ENsxF5=ITe{#gXh5U69|90|EkNDppzc1oH^bz(vgAxC9^3RL-HRT^ySy;k> zf*+Tk`^jI7_^%}YV8s70`AZT1%j6%5`2R`%a>Rc;R53Zfu8a8F$bS*}evZ7H{2LY3=azy2n$}JK9bn&gF6#D6RKw@3UxB>yuJ|10F* z74czW>GOXn;y;P}uSNW4lK<_9emvS1$J_TkJ>s8DeqY4jLH=OGe?Ix=Mf_#*FN*lTK>l#Ve=qo=haaGwvW*-5 z8|1(Hm!JUS=Vo3Ihm4y9%rQWC2{@qXhRnh#s1pEh8TKxvE@cTs9 zzfG^l;dY*VFa1*Z&pY+{R{Q-n-sb@CQ6e>?GflTwh84tH}4{^PeLBli(kZ=b8Qu zn}?m`|2ePsB9_;Z|9$ekh+!Z37oTL$d*7Q zm-~1!_|@dUihNIc-AevHkncgO4dmAzXZP{q?JD^%Am581pGE$w!B2g!J9xbZNpRfg zPaj-A@|>P*>z^u3B;S)x{rXRn??pr-y#Dwnr`OL&3IB!Q z%ky~f@439s=gIe^hpptF{gZaRClg@V>(A@R_aLpWx37XP^Stil;ygbXf=E8sgRlNx zE+yZS*#>z3KPBIjI`O*o=bWe5eLQ){9D z;LCG*vMbbJ{kfBTPx|w}J@ct{y$1)Ke;xT=Z02(EUF3W6smq6}Pq+Jg`q9O8avS)v zFDf@0|7d&>^@$c;h(#Ud@lm+@;n&@;#{!>Vf{8*k|{5FpNi%e;N5+#N_h!HROBolCQT9 zlkY_i$MHTDEEsuyPrmWzpCI3p-2A&dzTd9*S?bRplJCWq&m{lvz?XG(*NL{yv7PnjNF2~||M>c+ zknhP6c-{K*cJjS=)7Rnm$@k<2Ux({A+Wlj_;%(%6(f=)m7 zy4@!}r_R6^5k2ZR-*3;q$op&qUp_aM!_(wD_{j5k{ddXtB*VSr?|+8f$CK@R9zI6C zClzBm>(8m@+V%1GdN%o30Uy*y*!z5n7Lyq?#4@xDL*55P~|{|V>W{XJ8ZWRuB(qj~+F?RFne%6&cg%jA2} zz0dzA$ahd4+*W`73w)ht>eUcC`qPgMF3;~E96rx~PresB`2A0>+4WvT<#X~v@*NDu z{SO}^-;=Jlb6>2x!0zK9PCh?-$oC>2f1Ww=y*L`nSbt8%2g$tM5Y5{wz?bjkMc3Gd z`m+ZIknp_-+Sl`MlJCX1dmd!hKYA$r-mBoteLPvt=iyHBJqgjj*Etv4^?dw)Lpo@DRq;Zx*$(l*>v`g6iAyN`nj`F`9^z8BB> zJilA{{NsRpiq|`s*rWKnZ-bwj|BbutbG-;*lGk5PzJo>id3`ha4%YNYUjKRWkBZKt zF$h38_Xm%+{f_0QKOYBQ)|D55`S&{OS;qI|ct5{>k9;q_JcjqF?6K=(|I%6Dr@rq6 zyxxn+PT+msPQDk-`{#a?d@mCFB(HxT4j_4c2lI0M=kLIm?|V^XcRzYx`gu+VU+xp@ z2`?w#lkQ*3&;2s_p4{r||FM_ZeLP9e*VSvu_vE~jc%P##x9j6`^ZDSX=Iu9mee7R4 z4jV_F-;-zkZ?6U4|ILq7@7pMOu`A1{J%Kg3g&ezGi$@k(6e_sR7 zvFp8f`5fNo3h-0U^DBP>$XFe7lbqgFcSe{}cFrPqK`>z^;$|JST!L`{H!^lh^T&F6Q-Kr1muOKMj8B z{{P179jxM`ydFJ}_4|6!%njtfo_q(P!uHgkM_y&m^C9|epl0jOh2YD)Ie6KfX8}B9Glb}!L^_PvO=lN>z<@vn`#h>RBc>Nst zo?Lx4`F{q!=#y8yZLUA}lJ8(he@^~| z5JWQn4jSgq|8nvjY_pHoe~5f9y1IeoD zj^N+x3D?;54nBGXuirqv7rUNG{!Qe^a_{5dKZ@6c~kGN@k0L5i@+E8 z`K3rt{xYw3kd7zv`pwgJA1}6bz3b1(_o5$vzb~D!dAo;x0M}>!0eqP^2g$1*VIOep ztnnQb&F5i+d_EX&ke(HODf!8~@nqTwpJT z%)C^|fAD$-N%Q%6#K_B-Tf;L_xOo_q&S-a!60$ak=nTgcyi zoqetsS?(mi?}au$xAVMs3i;0gU*3xs#rwYdDESV?;Bsm2i|l#_sd_r^b2s@8`sMdO zSu^smh;HT#Q-0S)LeRdA|bN(3o)b*GCY+9cDEcmJG z-wnR3t96{WpXPIZ34ED12S%~r2LbbQp-H}j2KxJY3;3z${6}8z#m*=4b07T@yT5}{ z4U_+A^5b~QH^5Kb|37(sd|p55M!UZk_4)n(fP4py@_ByrOYM3G+4gmH2Kiom<@32r zzJr?Gz~}#6^1ZmapZo(av-`*X`FAUy7X{>Vyxu{~?%?m{UT*hsFlaw_-bKEHy3X_Z zPm=H82EGoTbd%l3L0)_wZYAHr=Ui@l3Vd15U!$CSD(`;}uXpe#msd}Jh27slo?H(9 zGx@RKd-RodeVlLbE95(PgP)JHKX2E^{@4$Z@8BqYZvGee;^|{%_cZbyRLI}s@00H!DyMQD9`|aykAoXMjr?oKcaRpp&&SAj@Hpom`3NFVE@4 z@5l4{SCAj;8xQ#fyWYVvF5>kcCEr0L{kc82Iv>UQ~M}`L~nr;PF0hm%rZh@bjpLpU&&w2EN?KK_&N*|EJ`C_v9m$1F^3^ zC%(b1cd!AUpJDRjc)^li&!S=1D}I;!Sbz8*@*SjNJwNw(Z?w;i<9h!)!&tyqBYCuboW(4|u&7Gdq9! zO?Lk{{(BqwUaao(`D5@^uY0l0e;@C^{>^qD2V;CL`8Sg9pfSFWu6&E#=e(b@`&`27 z-wnQh7FkOE0DPGT2NU#l^3Y#4ejL9T13z`2-{JM~I{$C-9UREzTi^ey?n~e!xyn1m zWfB9nxr_s>F&Iq1WKgy45WpHu&rEwXl8`j^*a3=Gt0lFk)!puHNi*aJah8N**=!7i zU6v5mgdBzdF(eB(95MH`*_aJ%faMM(Ktciu@h*Xw{eSQKzN+_LS9N#w^w=KZp{1{1 zy?XWPd*6NhHqWm`&dj8+e`(&kpbm!0A0|(a}fAdR``QP4?G&{Yd6H?8PNM|qXw@+R!a6ew+l>*mdQHq~W{zINeivc}Z7WE~-NiO>2 zZ{OQMZW8$SWV{xU(|Hcy;M4lGSkx0_{HFx&+l4NEE05RWcH=VsCV~5Lxjz!P7Ohr2 z_jPaMd9(<{Q)QkX30#X5?-%%Gf5hXp>4HA*DS>No1*KOX5V%iQ?*N?m$PG8#$IN_O z=3l-g`F!01IPH%%t5CZ7y_E6yeLIiWV$F&_>wwdHIrIj8FCV!d-}w0kE{m`}J}TpH zl=t}a^4;fUel4D^bnIUQu1%K|e(5`SJzC5`-}{cheS6)j1+K*#^?9%QW1dHgnO`RB z`KG|N7-~h}zw#$MUYi;z{r_EoYjJH|&rkn%**9d((@!At92fYZukyZ~EAamya6fM0 zy#m+bW4g`5s~*sWu8^Q>Al?VZ9Koy&kexoy=&1c-G?s;T#NlaRpxp0yO@6d ztj8~A0jGJinN3T^zf8s-mN@)rfxlbEYw_f(1b*JTc^)mos(AGjz;zF0sQGxNj`!l6 z-zjiEeq-}io?naLEz4w|6u1`id$_V7Q^2sk8-2H{r!KNz_qyY z1v37J0@tF7x}N6y84qupyssJgQ!@VJfD;~G^hb<`9~1aD0jKqxBk?3TflvGy!~OGK z61WxzRQ!Csz_lq>TjqJEz_l6H-wOOM1@6bUKjt>RuNJLTd^n--pX2kZ?`!%4Jl^*! z{Q=-fc>4_*zadS9ly4sYVDk8P0#5s*#m&x_^`G}4hHH@-1oJ*hgDIaD&a+}0)T_pEC3^={V|0acL)KC43fYUm)sm!#De}TZY_|QWI{*MCJ zB3Zir<&W?@T1;2>@cRPSCLh}}&m%v|^3waDtKjQ=ZvYxAJT2>b^E*CN1k z0>2uFO3$UmFRu{zs{q$~3CMiB6>!@BB~MTMn#{A|o$JFN=lNgk!T(U;ew^F41g_1$ zE|i-;@)JCd7HcXC{8s@_TIXkFycW5;T*klRlRS@~m-GRFYf~3}U;ij@En@swndj)I z7=OMh`s{NB{znFW;YdU9Q}N{f|AX(VMXfKB@rMPj#p(2Yy-DDHoc8&D&hu2ISY{~m zlmzbU3%3bei&H;c#=q)+@;utKXi?zr1w3g#zmx)h+F$TIzF+vQ0@otg`W{QS^LTB7 z_H%OIR|s5-#ODP54S{P@y$1{Yr#{W|Xc5TA3A_q;()wR10JAE=3f=K7E8ZIp6jy$*P?EU4@;lr`(EOm_jdqJ^ZWaG&i`h(7L!$axFT>Z zGKS-6e%>T-Kkw{*f5rFx+#~L5#vPXNPXe6otIfooD)1`>uEl?s1pX6&YjJDc=huFY z=g}gq%J1$3oc8&4i6gpM=6T-ddAt^(e5SxZ131M4jC%0^7k`1rYmqj^w{?O0`Juli zaBWto&--?PYZD-S-Y*GUixWOX*7MZ=!}s;$I_iMy7#V6l-Y?^|n5XW;lfTIGXp<4W z_6C7#Grw7x?2Ujw*q&H^zg@;_^E+Mt$d`D2Z3g?~d+`N_1n%4O{{V1ZgMFJ@W&Cj| z2CDS)qA&COKEL}V!0G+o=*jtSlkr*<`YCdgnXm9X+U)X}z_$giMQL?y_xdW$4?m;m zr>ipl8o&u}wdvWT1b!pngg>_l{#+pN?*g8*pAYyN&!f#+8#4aMfWHCvz3GMbF%YVI zML*A$@!C}5=?oruzreL=+~q8`j@&75KM(Q9*ZIC$ME-o4=Ysmk3;&<~~!#zX|Z9{k;Eocpg7q=#c`~qV)S@o(+L()13zi{H+4l;*U^7lNCHk;6AdA7j)c$?b=uFZ3mzx+_(QByye zf9$(Fzc!PZ5%_-c>5I@ z{~8&8iHyGkaC$G=L{RbPLI0QGzMtY%0@o(LuaJ4Z3^?uEP2wMXhQKfRe>{&L$NS3y z*XF>A5AO%u$lIQr@C6yK&F9Bt{s;V!=hvd|`s{guYg6|J$oRIvwYkZr!2e3%+Dud5 z`*#JdMTM0fKJ#DszP_E|cLc6Yzw}&O`y(E&&BA|0?)#g7>zV~*KE5jBwfMh|x%|gG zk2bgayj=8kforqZH5T7TR{o90Ym?q-8NVZNE#CfQf&UkQYg5q23;d&i>ly@PKE5a8 zwQ0@M<;z#x$@kUf0+$Q??*LDlXW}P3-jB0-k-+^poSOyi$G3b(;M#Of>B&=3-G=a7 zn>#&5*7I_K`|%+k5V$sf*8TaqzwRw*xHfOobN%3Z^E|#? zt^#<{zP&)kYcuf`CdVW17q~XZUX|zl2Z3u7Ts?P(?!))hreOzU{C^d=7UzGQz<(%k zZH}Vzyzss}j}}c2Wc-%|?&lBw^!<4J1K-VrT+iKvz_nSq!jB7Fn}nPv^WO|O@za|< z`|!tPyf(?1kn!iD@C(tI(F^&YC_O(6IN^yl0nz9EoWQks|If=jEBEK|ejR`p3f!+( z^Lqls%DbqV?SNG2S1LYx6TBa6d0;SK!)YP4%WP0G@(nM17t8o3o=fn~pF;+I-iS79nwKH(5x5^8{sqA4 zecdj8_M2t=qmigi_x0lQ{_h07M1_3ubD_Ym5cmuK zH^Z+N_?rZ-&DRzG|4iW8L{<0UXCFlScHYRhZ{c}9BJ<<{r}b--3%&1)1n%GW@69}N zvGp;5Ld-OeHb2&P^mc*!@g!dnxF09^BY|tvNu6i$eBS>XB;Ql_|3!e)eeb-LpKDR~ zN8s8la7y4m0G#&W-(JV#Rn9r*0-k5*oeY15jDI5FH2#Ob#c+@j^K($fYjb$r=j&wr zt)hQjCiC1NGgTPDDW?Sn(sToA0wANnAfRI=JmOLUEtbWLh03a0H^g| zC-U<_SDa^N%g+nkkHdfJLwSB}LaOq~ zUkhBDeOw{)T>CH{uT8I&e%>H(zkbep1g=g0{-e(GaGuAHxBrO1wW+k8(+6J2<9+$? zh`_J?CchBflRbg^ae5yV_-h}+j8W}Bk9-8rugyO6eZ4^7fAe0R|6#KJ*9hE?JNhQz z^nSl0{zs50^K<`;cz$i(ru%lKz_)~+AD8)mUEn_7{Ck0GQ>C1YZ~qL>{|}$wbv{er z?-aN;k@$qbe+mvYI;Xz8_hf-Z=03%+m+Mi+O(Euk^T~m6Ja$a6hm4p9DVrA>QW)%R@inu{@8T z-+csdk{_-RKb_js-X!C-Deo`IJYQD$<&0P73;c%1@%-BSQt{_gfa^2LQ1kJ)OL_eN zyo1-N^7g#IwRx+)$F~Xmjz8t`OETFP1n%drUGezj`#u|R!b9HDBb{tao|a)qq_^8&v};(rtm?{^u`@5gC8L*UxX@Ch={p9B5| zyvG~GzO8cd|C90BTuSx6UwC5j{yYb8+8@833tXErzC+;GUe4qFJn*}KqTctBKgaWE6X;{I{uc^do4-ZRD{yV5tb6<1 zeLT;_KjQTqm3iI*xQ-E!`S>##ug!1uy+8b^Jdba`EeQMy;a@qK>?H#C<8t2yc+!18 zF5`VU>Y1Z_-viS8PU+Gqf&2AXUM_IouJ~zz`~J{;!0+Xxyca#EF9F=(|KISwT_ex+ zc7gkJ=7R!X{Wl)3`cW~*^Z0QuZwEYSA3h=Dwb}KXMJ{^vSn~Mqq`)s4=lg1t_1~5C zKNoPLpNhRv_3_uqcx^(e=j&Sn_v39IKao8Db$};5*MFArlTT+pH7V;kXOic+<4)eU z#|r$F0{82nen#Nh%v$-{xl=rkAD41M;My$j4Kn|`1^!Wqb5p)~r@*y2*`+f6nbV9X z(_UP`Zv#$p?6V}E^J6mpR=^2=v?;0X$@UDxwOO0mMZY5Ob05q5^A&mT;m`B5*1z?1I#fM@VLzFrmx+>cv$ zj=<0H{FUcDlkwpq&)%K`oc7bNn^XWiX+5PB_#0&&-`@2_fj|3S_`K*jz5f--^Zz2? zv>xAH^cR4WJba_)$Df(y@xFa#QQ&?(+ZO;%^W5V3<30^|()0d6=JE3v3j5`~{D7ZJ z>HG=6ljeE3jQ8t4eL~=Vedap_?$;xon&bN(_-DTFenHaf1g=dWA0hB>3cT`nJYITQ zj*K4QdG3&N@o*WxEpXp%_ELdA@H;$@>Vt0=xNm1ZH_!9?`3TPuxF7d^1K>&f_M0+Z zn=7gv^&bWPWlxWI#X-LB>nHepeNUe23j)_>tT}-f5Ak@vF8ZGdT$@5F-ahd#kN5rK zuLeA6{Wr^aZNk1H_uVP*Jib5r)dD~G9^U5zGX7%%*QS=r_aAy?@_nBH_!}UX14A*mUbe_lm z?i2aF;B}av&k5YGk94QNA1ii3wUa;QC_V3aBUitc=l>m+w59cj1+|LU>CGh|8G#;-w@GijhcUg-0__~bOCfCZx_buHk zk>5QXa9WRFr>-e*Z5sPbxyj!O{ONK|b^Yf*i|5g%uu30pRJhb*(KX*G@NayI_c_uM`xHhlV^~|sEJnxh7df!h1uD{#+_H7yeR)1=U2TWcPx4RFG_)b z8*q|uFOWC{eJ(ia&3oVQ_{-w}C%x=jo_@M2>msKJc)x-nXtDizG?jKd9z z?fQ15lr|za5r+OuVXIQxtd{djo%3N0@qFpya#IPju2))(V!O1JFmEn!=It?Zy}VJ} zskY6=hK+i)QaY8V2cHbXMyp+&DW5EtcG{JCEw>xYkG0CzclowaY^HxZgKxu~TGtsS zqVHGQ^FX3Xo$!m6GuGZ13v%J1`NjRS^I^CU2J_Rag`@fK=5L028`jXt^>VvdsRk3pYGt!lUJqM1UB%7v zd@g4o+c+~}eIwj1o(v7Zx;Ds}yKmL2IJ2$!To`owGS}_Pv2I_Ecl&ap+n1BwzMSgz z<#e|%XRI%E11DSUVjHKaTHnlt70{*m$y)gQahN-XwCkE;pIa zjcsG#_Rh9>AJsZY(gtW!oiUZMCgG}4Jr`>`r4!|LSgP;T+SZNc0~!H>OC-jD2OyYX zyWaW5XmK657{kY}nLRo`oo_bl&7-Z&`Cx|r4i6NT^K+|(tMcLO@}U(ovp+Cr240n4 zUMVatB#xLiBaY5qxwss58J8Pd&M)O>SMvu#_uk2quFf9nV|lq;G^ukz@|<&rXP3jm zLP$do&n_I8&nJ(g@2@Vb9u5~4!Dg%$s zE+u|H5q}>ZoL{^;aga{3l7Cj>_c{r_PoHG$=&||L!qR-6)|&jnC!-;=3v-7TmwS$y zFU+pwlShrs(wE`f;=*bk{}FBVH!&zIT!m2w!o&IGU7pYZ#}*26iwBZl*|-kMugqbS z6Yn&3Y~jel;?;Qli%0Uws62LHagGoKlg!U9C(n|{8}B}3T=A^SG}EiI`)QiO!U60I zuqXL&O%pnVK##<=1pDU~=Z@g()#YoF2226r!Xx>_?`G&b?EJCh&6?mhx3IVx9$Y+@ za{o!j5FC?kqsDYQ%#=y%45A(536sX;Mz75;FUo$=&Y5RV8W}`4Odm2idvt%{(6Pm1 zD`EOAgK@=}E@N_vc?&&pvkN+m;Vt#p#_|2L2k0bqA+f;(jX98C&L70Tg}LNcJ4S<6 zj_qHWTP`dmAIcmJSvt0Ic>nC&k;FY7r4faNmHcw@3^T_Tj?S*m9R{^Ow7ht1DU~)( zA6v*DUji4xNFsx2F*hP#DYSo@ z_UT|jI888Gg50=WY=pV>`CuIErLb^taTzAlEW(mo~xFv4x~TEd2zN z&{@hxN)B1H9UC<|WLVm1Hc6O`zi*aXP!{H=T05muxz#eSao|~I)<{3BLV`NId4e&T zC|cy{PFAb8!`4otQEx&`=E<7%wR(G^RIk>X^ApS9tbD>I9QgiuJ(&(1G8VH62Rd;G zuar5S1E0JmKd<73^TqgnxjOCff*`uRus?To9L#L00EF zzX0n13!5)2Bp}Yje!!U{Ig?E-=ZP=!6|U-@3reIRl^P9L99m^4(8cWr&f3zEAXoxm zh5x4YbzF#R=u-E>^=3H;7K*zEbpY0B{fUXk zVbc+9S=8Rj^PxM}YsO%;UT(FUJ2152?@_WdshOm;vlbRYx;JcAjmkbe9qe}pmuF!( zAHzWncRY}ePzE>y}UAM zU7o%?dd&xd{4U+<$VwXqJs2K?Ajshh7(np$U?eP*R@y-TJ0z^Q&0?k9DwOg-u~I%i zT`D$;CG2{B_lheH%@_919X}q9?Hk{hg9R67*jfA-7QfvBCnqy+llGLBAB?v!F^pB! z%38D7JeAK+!ORJE-ZHDAJ8u_H;3%3=1-7@1?uUK3+?)e`=C91>F=$j~X|$V#)i8gc zvA8;Fb^uQ`Ud3#Mr6al?d6VP(LQ2JUd9zM8E>-h*QTT5Jh*{ZWG;S1kTIKj*g3*l% zrZc!O4nybGTmb4&GW*AmOAn>*YsP&xgAGB@I<>u4uad2{N!QYgRO}j+HQ{YCu`@ep zPdO?36mIO)%)u%g^d7(S2#@c_YsR^iXUgY6a`dgI2}!|dBm{+XIrA=73+@i;Q|4Oj z^)TATl&u)nx=Ymp-gy4NYN=YPuD9{O@CsSeXj**hxHYtI;aqTx>LO z-VQWY4j9~6X-|jCYe4F9xi@+Mj~c~Fvv7oP1PHfNt6aYW{{awgVI>HYHvw?JcF<}Uu%P_H%5)gyu#YrnNH|NUjK0ZFhetth@DlS&xNuAt9oB#+ zX2eJX2erK+hcL|T%k7)Mi&)*Nje|g?zhj3;jbiiSmyUfJWy0Vd<0%|tV|2usCEIA& zprf2lVrUFTz@qF-p3l?CS(%_05g}IkEJUcR6OlA9UOHx8K7w~bsEGZ7^MhWN*;ZbS zJP{w`{@>gfUWHlpm`)vpt2=O8F`1v=4)Rwfyzzcc4Nzh(C}2Ab`Id#d>Vup@cQ&{^ zz_eHJ>L!$Q)Yf5suGjJ_y2{DYR*ae35FmO z6&Nem)@}5PX$T85hCt##_d^-SIw)g)Y1I&zRJxrgOIl)tC!`7?U%g8A$RT{W+-A8} zZbIDi1R`uJm>wY)giTqCFaCgB(ea&ZmJJd@B!`cyRw|Pa#`5SQ(|C-Ene8AaCg#5r zA<;?P)#0Gi1Y%Lod=1J2P(BEV80@qSuS{g07}fp2bjqB>1&qw>Fp|KM-X==ba#1J{ zNakq7vQLyxfqibn=M2s*>m6h}3@0*cAP@A+VT3f4$z7+!DxHG&K=HhL6q96h!(R!t zJFtN`k*|;#G|J6HJ5YhEy@}Wi1T-|u2m&brUDimhiSWa`E2Dy9y5*J7(Jkm*8SR7C z>3@S+@ZildxEsX!u)aomRtOU9k$C@DgQYR2%J1UrEkSo!UXA33TzG)=*!n37R4L4_ zjpp;XiP3HArwU7hy}jMl5R#zT8{lz>V2Czt1mw^Xs2hZq3X~+9(cnM@6YCYyd+30L zM%e>%rT^Nw$tL!*zKy6BGJl5g#l=mtVRTpsN6fAk=C?=lONqn)0)j2fn}?mt6_z3N zs$>$A5sf!!#o|CDr$xtgknN!Z?4n_(z&G83_nWk75LuF3eNlGYvAtsT*w!!z5T8@u zgMk1-8!2CTNC9{gvmwYBCSeL_W(5ua1=vaiC6e$e)-h$D6C|FlY>u|mY$-`7o8>kW z5lntMFUO`t)mC3DC-7O0wKdfW%oh2I*{+##t++6mju@yWA=y-=6>gWe*ASr6Ajt}bAi|xA-C}j8%tLY* z63Y?5B>fsvGX7u$6PrsaYfT|;j&`m3M=U$KauEzQWb#W8ix#@<+%$GB+^tv0YHaL6 zgK7x+meM&n2#0SAP$NZ8YZnn6$AmGS!GuBY1V6e$4|x+!+-h&~?aR~c`iikK?w>HG zM?#(n*xB2x?qiu*RSA{NNG_T_umdIvZ5U$FIx#{K*o1QpZp-N8F1i~lZP+_fEvD(* z5LRE|IE$d8OGj92?q(Xvs0DO4pLh?Xn<%un!xP)dZyoE7kq}|?Vc8=^JKn>~^%Pv3 zl|5L1!5!C&?P7ju&k^v%tc=UXYdhOUWvN!S$sm1Qehg8Kh7;1amIzo31BhrIhWg?k zEP5jT(K`rXHiRm>%o1R?H_#z;WPK$pUJMHa`@AG7GZE ziNiNs5n7F?;8YpyW)MERZakatp_s5t(v)Y8jK9jH#J3R1P_}?i5*>$Gi|$`n>!ArU zci&>aCY4}&p_0vSiKg#k*o{su;_{IxZafo#xlqPvn&gc z(=p}59I{W$-DCzL56T*HQEE0WI=&)U(Ytstj9yCuBM=h~!bpeHbT*C_38t5-J3yFuMCO;9hs)JQxhW(i zwtz6+XckV6d6-8YVaP< z9woh%b8`?blp7btlx&<7x&Sj6TMyZp(e+RZD@4Q= zc}b{(hdI?YF%PvWLti1sd3Mhs1W=%#327l&loS_b^z;=#5nWtqm#>HE+mGn-#rymk zNm~vxgiYo^jrOS9xx9Og4^wJ@Upa_JCbRvJ-f1F{a7jFdu+dqi=5<77h_&aeVdF%9 z#TUbdAm-%2AY#@@0wqFG)<`v?jV6Q{+@nDB!3we>lbHq~(&V1Ho@`JOk1_NDj&FdI z4Vl1f?m;+G3*G?^Jqi0H4|y0Ylx*blRiZeC>VTWkbf7Kd`i1yM5f?!S!zHW*tifY9 zkc1oi2NL*QcNR^Q4JR2oA4NAAv*t>J!!C4Mc)H0}8i%&wrbCTCab56zn0zu@J5(8V z>7?VW2IEaXTCnV3SITRM0yXkjVZJg-6fnU<%lyK~>uiSNdy=g?c2E`<@=#iWP@EQn z+N(eak5c+1CA5>-%5_VM)heBm`snUir!3(OrVUc1(+t*K9Qkx!JrQ{j-UAdR1`|(3 zM=WxdfM|rQ-AA!l?pDy*7Sp-IZlHQ4IU(|SxQ&gIfYPLiNFdi0F|O+xL~7V>&mgyG zF`=xq*A<>ERI%1DNjqpy`R-jIQz1BYS;7`oa*rcXgMdO&B_wGI8s;t;!Vo0{ibYy^ ziUBrVy&{1C^Q@OkyY0eW33MjhUZXf~_?=0}bbV@_q#`3_&>iliXruWn`*Kv{N?)ur z)Y{mRx8V53?oBDQBJOF{f3(#j4~#*Ea!V>zX<(a?%(3T9G| z;tJkFR(}mW-&te)P~mWZ=Y+fjw+2U&u)csvJeuqYJ{~7fCk0{=O!z>!Dk1{KiSU#z zXZ2%3!CWg6F6t>KtT|>T6j=XJvS`5yjWiDvyppHLmT8Jf85MhbM>L9}DND~1!;ui1 zf#m{C4Spo@_*l(6OH60OAsw!pryJQgYmSwrN*bYksobestq&OC82hC$5Wrr@| zl0=TcHUyXfmISv18#|cT(1bUV!?T$@UIXU=~DjNya3l36sZ^ER?6t zwg>b{^i6}}vGsea0<$pK!P1_w;U{<;#jfQ@x&xY6RoA`yO?wst9EHkrBHY}eY&4kN zOl>PN$uC35h=mqANR)gdh(SyW;DVT%DvVgC;|v;yV;i}sS<(B81#J)s1ZuWeMGZ_8 zAxU{VoN%r}li2_4a9|VPq+CCvBXbJbaOLK1IWNKWDF>h%%DPN?5B9R2Ogeqjd+DpO zWp3QE%z2yRizY}Vlsr5==P41F9p+3sBelCDBnrQTxej+RR2e1Z;Hr3jxx;%70x(0? z1}poJk_}*D4circlPRwvRk5PeK@P+uYLVH&4Xtd&6pw0Q{X8!nJBoWUp_RDVb>yv3 zJa&>QkUe1)97BX>*v9ydyb4D$A4HS%jnl-*Z5=u-Y(EZcV}W3f1%eI_+-W=6U1_RU zyzelu&k6obWqyIiH;2t#6Vz)tk={3G+sR3-cx)l%}`iOZZrd zdEhM3C149BqvIYTY1dE#4&kOaTJfogQbSWRD>OqK7x|@{YgnAN(-2U zc33NIHq9tQ_h8O(52m7FM(Y$~$G9casK(K6M3f>suSl;RYV>KkQAXXX!={u$ zKxQCG=O^~lo+0C`$;sdYHeC0F_>|K%fYd`D#gn?$=)@`ogTEAykw9aSNG*^W@H{*F z<}~q~o=0q&M7fO|qX8bVxzSfL1^HYrd$56up_0kn)ixxD$qpAuwc0DXeiNl}> zjD;1L1?><^6AzF`ND+^bLflpsLkh@6d;*aJPC~IR9x#D z8>C`x){Ag0cho8Ki;0ojD6{F+D1<8&Z?H3%x1Y7WS0Vh3sgDce!hUlfiT8Jn_uO0vJ+-i0p?C8&%O zEjL--6RrG;3QQs#?|uhq%ZfdaVT=*du!e!&U-s=CK;D?9J_W|KxjTZ2e^hVJ=QNfu zvD{afNVmi;WE8{_hhrU5-%}Dn$|V~;ri32lD@&ywMSXInh7*PA&!Cm1VkXX8%1nVA!=zDyN;c&Ldfx!^S$5^hl0JGm(j&(FeN@ zf{Zf-vp!xR$(;v;Mh!ydqDbZ_PA>L71-8eDan(|_hWtcM_GlDwn83SiydexurzivM zM{~8Tv$H3INRX(l|o_ESAt~N9l z2AyvKVL7~Zhu3Oh9*RiCeszgqJEX3O&f8})&2+3x%rn@SVHwq2`?(?Hw$Wk`Vj0Q5 zP+=)hn^xP0vlY>LVUubHrkNAElXXItDE*lIPIswc%Ht4+OnzgeZ7De$+_2w)3!;E| z5e<%xHomu2l=4oD$sJ^$B>O?$aeVkXQCuUYjLY0mUYj{bX?YfhwxZ3_Gd10quxTnF zK&8y5$fW`IqtqK$`O2ETBU&dFQ3lxw)(9g7%4FPX;Db3%2_lr?xWU9$u@zDYz8Z?{ zB66N7`c+s&Qb~%uL;ND^dRERw`;$CV+;75S2A;vrH?4M$bjgoV*+a1di1B=*iTZHu zEmT+9tH3aTv=>S@f}oE=3sIS`^4S|O%H9_=YIYp?o z?sO;3?>`%!N=~WRHuPE<5Zg>*6>9mRG`OXgcbrSbCr~wPfx6Y!O)|epw#>S=KGL&^ z79bds3aG}%dy+Z^N>t9MTkRC@Y%tLN5B#Hmu`TFW45nsbyeRdKw(O1N0s>nKl+<@kmzXl8%=PG?*O^_c-*0)I1CI4ZXAz zX@US}g~$WdF(X6T1oB~urwTY7g8dM;9Gk(};&O=DH3wHow6#)jm$3;0O)+$ItsrBe z7HV>qi!FrN*^$p$`-Pm)zHNta-1VAgsaa{c$hpLL_R=mHqeT3A>7CqpU;~VaGo=J$ z3EApVtx^RJD;?D+o}I+mipL@o25_7zLpuK1j#7~-p+_bG6|j7D$*7cYJteVJWAbvs zge_G*7c`pnO?37(IhCe)2%#y7OOY+ximf&GA!MFn3cL3t)r%mxAuw+@EsZ-EGVIx_RkS)T6trhiQd6ue2pwfgCPL0De+@`^VKQeuD<C%i_ zd4Qgw;Rz-82Y3zG&Z8k&X{C?Bwo6F4Ymoh_@7c%Qj?yq9e8G^+^a#b&ynu1`b0usC z>=+P(AV{4ou2pseO0h3hQ8Ld&EtptKsHe6}1rG#ePH=o0I#_F6|Ae@Oi0~v(6dz+q zF99#7sx^JQl+&QQXxRhZVlt@}PIQJr+D+LxWk#xg`lfYF{nA_yH2O)8k94J8+vKRu zJPj@&cY8%wpiP#!h*&3O_|y)Sjk!rIEV6;2n@bSb=}Sg>%Cn>AAVCId;GwdyY&67@ z9I25XN`h!q*>T$>;F82#2R4|O$f;d8 zjvzH8BO74h$^#AKY8E3M^$#F9rfZcAS!Flb$TpkkF&@vnp5&hElWN8_ylA2YMK9nVYLb+m5d{99J!g8fdHbOvoO(cbtp@Y zghbbobJ}AcVwsk#PY_W}6pUGi29*aBDsf0Weu^7}?UZ=6wpkOj4eWZ<_^{OXk<7Jw zEVP5GB4z{&M&%>dGK7gD zB~}QLawCd}=s5NcjKVubr8(*UT&Jc}+4qM6h^*x1j9y9jKsr3_gL)-d|4z%$!3I$* zA${#@Km+OKlaXB6TQ{Me!gxI}{dcJ4g3+CtNdJ!fiQ;-4R){55a@0y`(=o^+Mx^eb z!`KmAMVLdfF5ylz&Dq1Z$@duL$~lgJ-K4jTml1gaGvfo;|Tr3v{*z&L+=LTP6##Ev+o0lw6C1AoTssjP2#BSV# zPbCF!YbM%tBw1Sh#~F1x^u7EPOqb#INz19#+v=(I3!Krc;-=vh;`BDkc?WIls)ZOY zD}{2#B9c6~SN$<|E?}>-rVg-VqKURCtSHqm=J_urOG3;g97CHMZ8fw+Kzt?$j}p(n ziKXAAxC~$H0aX{=gjCf@F$cF9WjASRqc7U;d#1(2KH_;C@jQ`x1O~%&VjuG%kb2b| zTnmJ4JLgPM)>0C8tCQcNy=p{0$zf07Kv;dwS$(f+HJ)Ou-t~eP<2|JG4?~mff;Apd z&MsvkmOG_ux}6sl=}*piF-lJ-2e-`@kUdB|WBLL_9!8{%wye`u+<}{17{zWlfwFkF zF^Nl{$o-2Q2z)RhMjAtSwgh8MkW#@R{6<)S#M4ROSk>=ll*;N|8rdtg;D+t6coJ31 z*t{KqlBQ@Rb;1CZZ=BLsFf>Ct*@z}6{8Wo}W>*YID&wYtN!{VHNvT*(ij>+#F6+=M zA~npVo@&4Co>-{9NV1^}r{yHKqXt*IhdFs;kCeMlzKA!;rEF}gQlAva&_WVAI%#I& zsWLC0sFo}!;W{^nZjgYSPQOmCFR` zPn<*fM3tiMVT4nU_G#l2PQA*Ce%MQYA|6MZahj_$k3$maUHsC?2hSpNGO=KPH!UK>$PK}@jfRleWVeQ1Tr;PWGo3z%;gi|B zJ1W?tWG6}tW%kI7EP=PE2y24Tajf94O)*gF`*0$fS*KCQNX()7Sg%Hh;+|gk2Nclw zX11XT13Q8~O#eHY!Opsb?7jf<801i|jnaq^{n%=m#%*MWwXDA!VydO@b=SKZJO*OE z+&i;dRSS2m=slAXMZsPzD-LSA(mSR#YUE3A7*A&`kj8HfIl_0jag(iJV!g7lQAWaE z2`N#Cm!PvU7a|aZm=4mF;}klF3zLwR${_kzEk*1xIp3}qqvLL=LPV-CYsvx{8YmknvD$ha>Hcu!;isWwbAj(GobQCH-K0?_t(P1gHty z(K=Hw8St?#P(_V6p)mE-_AAy|NmJbfJC7}cuB_T+Ia4$Tl86Q&z1`?huk^6a^F=DF zFT|Sl_o&eW>_TcQWyTnG#AyQjq^_RgrJ&%t4vt5%7fR1X4j26~#l(=Vnj@;g*doIctR*e9X`yy_Q;D4yy4#gX2$98EPfBA1 zWdu&GSC={>85WGLol3+9p&djYrM0rvI<-=(v@52A1q%o%`;;nuH0CL>)DdIIbYa~= zY|}hFo+y+;LX_Kt!a=}TD~?NDKYmj$4Mha)E=_6ls_G$c9;u^D!(M`~FL z5dqGg_yH%a2#f{=VX^ruXy!}`Vq!MO;KD(6|0mptj0>@XH4r-MnxR8bOcS2W(V9{k zgG|GWUv2{R65S-Yh}I^&OzJrKIwGA}gkWvgcgux=xOgAU+>JGCD5{6?)0x_Uyq7cH-sTsg^2+dxn`px5UAU>OeMfDKQ`Ck{jY>tR zfK~Gb$x2Es2(%aQ_TXjp;bNv@$;&`OC+eM|$*I&E;>anWEyk?`%X5c8#(E!7ae&A` zs$4QTYu*vYd`AapY~0gRYhn3KJZP=a%@S7Y^M86YI)Zk-w6h9baPR0cBN7IXxVV}L zIAMa+0JcHru(s#sfYLJ3Q4kAEQ;P;7LB`Y+n@MAWc8|6gsp1}|IrLTg6q}bQy_+yZ zGQ~`G8rz89c)p0vLedMx-Gk-w`dYDcqDKI&Zed1o+p8cY4IU|^m z0xvKZv`NIUWe&<_Y45@A6&7ooJJn)yFnR?_Y6S*U12gE4ur@ieqMu6O*>_ai0)l6a z(ova^h@vTzH@#Xonh%f89%uIs!J}3kGi-;a#)8K8!*4c855tO>j{4qplk1q6u875Z zOvNYE{qYeavYaJM8*eLwF(1mdA%)9pVVkNEP%#)&UQZ6VBYn?W9z>Ahj(4of?tw7ihHwtoab;9Xgoi5HMh{dtp zodV1#EFYU4#k;5sewUcmQcXtgrYe(hjcBscl%jEQ4)W>>wmqrOs!e}MQxDs9LObO! zq`ET21{$J5-wMmMC|u z4;97L<}j7wPj4O0II_ESOMqJ_cGg%Z?p5EIluAFaG1BX^26pko4J4jY-5A%oCb-fm z&?E-+K@||;!OgJn9i@S5u#aieuzf1r%aR-`Qm|BCeF}*N{)M$N7r8iOKzOe(8!Na zVWXoTTknWT`22DJo(G$?>xwQBLr8W-yBO(tuFg;kma~Me6ICpu&$+QjBx)OOxJs;K z;GM(ND(XR`FD^_qEGL!FyI2J7R24c{tR*op`@|bKOAZjZ&aJ5V?Ce=8A(G6Xd9>YS zD#DZXQ^>GE5z?GlfU13NZ zx4$d^-E8HhgGa3;2r5RQOQR2L+s&*=m^ls6l~#CRapz>gSjAug(0)}*J*Y5S$GI+( zEU=FQ+VO~n$l-M^;NJ|_wnq;#>#=oPU2aR&@RKqEU5YS%Ieyin;ZcVI+y#W8<$srey z@xTxRov0v06H#qV*yM|qc8gp~of!v25%6CdEpm&sb@b9HmP#;Vgz?42O(Kn2!zGC{ zI;|B3$qLnz)#2SdQ=U}8#MAe%aU>5*MTs%*30k(*+m6C-v{XhbivDab9My6sB4xJ|ZRX>TQhpJj^eMZUU(x+CQ!ww@Y7>6p2^^>~q1 zDxHF`u`HZ=#!^Ek^td|OjTm~)u#MI>Zs4SI6kcBeEPaIC*~~&^bEn*dpflu`l!)G> z9Z6+A92Kt*Xnh+lB4RpdG14WvQ%zRuM_eRvdz|d5ul-dVpK2g85>_H zwnx*f*oFY7`3Ag?@~l=C<{;r1Ju`KqItN5*hnjbQYGIVg6x+y6h8FC9JIFHSu4UaT z`Vl3;s*(z%Yq(1v29VSCvutlCD3v5Il!A%v;tA305YE0{hB*XA75XY{3p0q-4?N3V z#cgwHWnCZ-w$!w&H_da9Q}4`J6!~QJs!}imDo+h}%VI1@JCDQY2x^iKqqFQ#4gTHzd?jkipZR1B5GgE<~iIuImRb zkOOE7CDCDPkc5-It3OK=7tX8^ps2WR&SRjsOr244cv%5+))iIvz?(EPYCmLpqy>6mj zCB%+*W$E*4qj~yg^+5rh@NAQPM=E7B;Fyq@+_8mbB^&yjGp* z6s*^+?J9Vv)QPPk!f1kmgj!pH)a&S8ATcuHozE_~WbxKyY13mA6>F_fztJJh6z*(R zYNRwnaEYauJ{EpAx}0LBLr1KDY$#*bQpKXT_D>E7mfT3%9xfB(6hU!OVDgEmFE`Qk za+6HJ2)U0N?FM6x^T4PFgGiAHBw}I0>c|`~X)x(!TC1jmH*sds0CCHXrB0Q#^z)fr zh=tE6rD&s|2VRMvwA80`l*HCSIzbOiMR*Vg&z8=qOH)?rlD}j91^lQ}*!8$|gvw}N zXdLE9t5>4w#x%q1B|*(`{u$&w(!)B70>Bc-hLS}uOxgN< zK5Y0>;`uj*js!EPXEtF2y|Hx$?Z~swwJKsh2F5R-hUq&hqRhnKFI<) zd@5E!aI$4k1LDrTw(l-t4B+I*GD|Lt3QUDnpAZe7B9r$eE`g-c2QZdV$YKVQrD5b5`^IGs4YcclWakUi$bqC2*o3h0tm4@+J`U?$ zWvR3zY?j!ihp!4Y>Tc{7R*ftg`Z|{Vxry`L*{CDCblTHU&ssm1qBh)>-k5msDfVoD zR|fMurMSVs4qY1=_N4d_lRqQoVOBVT>80ws-~izh334bW~ii#{&qORA=qR5h_f5)JAb8^rrI>%}VVg=b$% zbb;pA>G8GBPl90Q#zs)oJjF&t)^XBSNQ`rt*N{SKu;qC6czQ7_Vjre%a;)r=17L(HIZc=Wt)j;rLajjZb6WK-+ zAqefQN-O_->!JGykjcymBHb18?a9O*renF&>tX6L$}>P6B%cZ>!Xf*Nf&GiOop?;- zRwiHWfho*zByu_6u5*}*8kDhgN~M9_jQ*%WmZ2d2l)-3THeg$W!=H+}lz zfP1~kZlM`^R;2Rd-5m8O7QnS#Z(m_RK+8l&D{$RNKU&7d3e$H?2C0-A+aj8Z;ES8- z$ub>xp-SI5Iy8~dowWpwBpF2Bgw+#5lfJM{vNNn+sj+ow!t}$Qf!qYH^sFZ5ttI{xm9eacVtbIr1z^+YLENaSRjhk!Kd@*B;nalJbOrc*{t} ziyfD6DVnG@^Q?&3X_f=u?Az6Y8QFx@>|k3`1}mqsUREJs=z5nO&X;ao>bGdGmWj+~ zF4-IRVGslub^!pTRze$61#QA`qVZi(Nfad-t41aVZ`~Ah8G=&;y3^r9htItP7M>Eu z+{NckF};yR-6{r?&$Y<}3a)-yk8b`*0GUc356QuGL)@ zcMX!i4716SM&k62R8V^45$I|5Dvd>P%z~TgEG$WkjH^&~d82V6gs#QYSG*huO##bS zmP*okI%9<^+NC3+)1^vHsZr1aZuBV8k~om$g^IpHxfF!*Y~96&-*`{qbyP6Xoqjn_7(G1cjxr*rEO zFTklnXzZBM4B8l^9;QAnRf~j; zj_Jlg=am_vU8pGYiuK5+l4hp%4rxv$`~5e1i*DNo5eX2-*=OBzZOG~gbwgGE)Q&{# z#*(e9xLmRkd6vo!0@mF!$uAaO_H^MjX5g;ZtEvUIgD2Fr>sY} zJIyHn8+^;X!>h^y(V8gxQR@c~3mCE=fbuO+kZ9Bj>s>~m#}dLLjp@YQDS6zqKErBw z(c@#q!u50DovqNro={#R#U*KMN#c@B3lZ+H4i2o2F2I78SoXt~yi5@=@BnqD3LEHB zzDOxW(#UbY926o%Hi|n{Bz;qbCSoP)=-PyqV9@s}CmB!gT11NL3{$07B!L2z4BbaV zj-~Fl>;9=JA_%PDzpRc@?cBDFIg&F9U7Yu+L;3pH_3gAuE0$<)?qP;>gZ9_dYL>`V_yy$MF+csIpYVh_IiRM}D&bkFCh z39L}%yUB*-%4i9MDkF_h%4JDAuE$qi`JqSw?{NBL${=^hW*|9WXG`8&w|svH7I75M zAbM&PBMBodg)sm}`{@N{dD@-GUO|-1(Fq;Wu*y_MOiHTLm+EU4)IN6}2oO z%d|rSIF%^*iXv;J@_AxoB0})kzMK@erMr!hL#>&DgGISv+;HAv^eQ0xrb2{fR?9_X zteUZBAT$%68)GWTAyd&5IyYW66#7KPz;7e)^j3zTHA4<^uID3tGH$CdEGlq&x8WmtwnZv1aW|%u9{n!wn6uQe@#V{mdSZF*2 zitxMg^rAV*;gPA)9aLE6*u*f^Ikiq5&d*qzx!5z1O0fFNhqvz8d6RD#I{i9*vio9H6pfpdm<{-YYiI(s4lhLbsF=lr@P`MpoLWx{`{E>F8@hd`uT#6j+=9 zdq>;7jcUE#^y7|t@t%xUhMr=LCxhT9#b;UgwIi+dGU|HLnu;TiGs(UQPU4=4Id;f7 zlhV76uVF>%Jk8R4juHPw> zdm&0$OBM6>a4RoR$B=})X`~df=M+1}Sa?;=x4e^#>JSsvs?#LR)Fs4a1ol7_jYl~$ zi6vq6i&-%{(d*6%s`6?!vka4!rJCMzq&^ z7jo>{6uXPIk^sf*XXptx(!ojyb-FP&fmhlE1#=-;-KfE69Eg;v9H`C7kwbzU40NPk z!P41kMLB^wHluwib}z-M?XXjLoMNhEqUEN}lyqczI$Kg~V!4mOwTA4G^4-MYf+Y@{ zS}9gP^Q}cgN+!f-v0O?o~gmuu5k6W_c3=TDiG;bgl{;-6|D) zU^+5jRB=KBD=`;}YH?;F-8weN&>9%09k&OfAdz}8O0lhp(Qd>+{K#25o+(uf^lr~I z{8()dDg5DbxwW%RrSIqF!m)j$D*gsZ?mgAr1{NA@ii@J#MzKgJxlP89;g`gT5=qnc zDK|yY2~zzmuF_IpyAJL55HaZ6JYg?vs6 zfVuUnVpA1Jq?h-S{q;u$OqK5PeUosFM;Oh0a|dQeq-b5gQ)z;(&mBKLyT1?y`^Msx z>n`-`lGFQVJtg8J&u9YIyTwnd>z$Dpfof%~S%g29qFhX629%XC_u@-*_~5~ za73D43-i?=kAI{3gEKT?{K+bfcBUG39Gn@d#1n2K7q`Bghqw`hQc{%5K^f%L{0wp! zEu3DaU)1qN4vxz+!O19C*_DO*3F9}L<-T&?s%y$(tnZ|j#ZZ-s-YvB{L{n3a1z~pI z?*YL(faZw&bi#!6Q-Xa>D~8gCInB)jgv~|qy#Ih8kuQL}8P6n$8CVgO3!*rl{C3>i zB++`5U3x?6arbbDj$m&t2B3NJ!|eM(mL<}#O!y5skj{|Nf~wCO$1I=RZg`V*1+dts zRbD4zuwHGQQh6dS6?4{zlE`KX;jE?BV4WulEwbqprq=eBGvLw-m202=Q_5qrT!S46nU4-nb8StdWNX^0SD_*ocJsLj4Or3$%Sc=iaoW){ zdsFj>V4pQ80pD-ftZZ&|Yj+u$%DV=MxMWt)#NGYg1eZK!>rs%PFA944T}miGd=<$# zu2d8RrVkp+L*P}(WguWwGJMq+G7QI$WdP>=EQ>2op#xFbfc2>z7MsoDDN51gaj|{0 z`w`LwZ_q!Po%61EwqZ6Ka$OV|V2OWDu?wm+2MMsW1=gMxB+$i$1Cu%! z|9Du~gC2uuCXQdoFWZ^yHlsJ@1MIY^)#u2^WY36CGy0i&rc1i*w+_`w8KGM;CP(h^DCw0GGz9mgh;FJt4iMU4~9cFO(}Ph2h# z+oPL?V9n`>^@G*IG_??t#YbYMW4^OZhI)oa%P{ut7Garb%PTYX zXlek^rNortoZ7%39w{Lpg(GZ`UeRgg_Ywh6$0Na78VmnfEf+nza%e(L_iSfsqm-Cq zZnDc`CzL#V--bTmgR;lYt?9!7;#dT_IzO`0Af zrG@^JaC!V{ycQA~0*fd?IJ**<@3}!a=d4{ ze}<&HjD<&uy8{;};`pDgU zF{wVhLEZ!Dm!4~D37LEB)=JFq&}UW^a<5rzaIg#!{=^rFpgvNpM)tw$(=M*zv)$y+ zE&UCK-txZ9+Rna4lZ;aBQzQE#(ArL=y8d&O^${~*tJvBa*|&bGhROJ|-Q;gjp0NdA zwev@a@8Cr#(gpHcquL(XM@hCL`|#_&&AR;3Dwjs~waX{*CseWuM%UMi?c&J3@)jyu z7Qx=O)-jv@h1--$(o72(#}pZ8W@URd&!NB5JhTiyKYdqen*c^M+0S`+oSi7yjw>7cqEb1)ul9KfV5Qzs6ta=bgX z@zqbP^JXu>uUU$37R$PH=z^iS81U(L@R{-5U7`ELI_ zU!b42Jb}mQ{q=f%{$G*n_w%rk8-Bvq>*sCHjIaM0{OVu-a=_?{b9mUu$Q7~@`IOhE z-$w6I0WZcc_Vt&@b^3YZlXWD2ULb$!=PSJHZ@G@|ubE~;`>n}LL*X!pE zJ?{TT@A?~G&DZPaeg9JL%%6H+g}%wV{x`P>8%IX;^FijX`2X}hD&&vw3+FVvCzd5Qby$h+{jefg4xn9T7 zwe+KZ>*o&vqy5wCZ<6b8lIuqvNLR%_{`)@%7t`5^u74D-|E34<=kw&n(%GjUy|2#m zYQXIKk6bJ}be?=hh+!^|uGe|a$HmU|m&kP&@aJ*w{p)r5d69Sh@d>%^3H+(_i|-z< zU;n-s*VA13{5MSUbz7J5=ksWB*3Tu@@AT`Xa{o~euGe4g!F4+Qe2QG}4I6ot-2bL0 zx!>q@3VmA2^jk&%BA`mOi#uRoS@{U6@W*I)Y|^-BKq zuP@5={{G$XIgGfMeZZwadcA&D<$CunBO{kz{73_O-c#If^g4yo-yVvZuWr1OufOFK zk9<5nK7@Y}-Z6OOr}3${BOvo}#fSO&m#?{ZbpIL|d2q`0pStYPW}fGJ7kGb;{C~5Q B!ax83 diff --git a/src/APIs/c_api/include/nav_c_api.h b/src/APIs/c_api/include/nav_c_api.h index fab4538..1be32a6 100644 --- a/src/APIs/c_api/include/nav_c_api.h +++ b/src/APIs/c_api/include/nav_c_api.h @@ -59,6 +59,15 @@ typedef struct { double theta; } Pose2D; +/** + * @brief Twist2D structure (x, y, theta velocities) + */ +typedef struct { + double x; + double y; + double theta; +} Twist2D; + /** * @brief Quaternion structure */ @@ -104,6 +113,14 @@ typedef struct { Pose pose; } PoseStamped; +/** + * @brief Twist2DStamped structure + */ +typedef struct { + Header header; + Twist2D velocity; +} Twist2DStamped; + /** * @brief Vector3 structure */ @@ -250,6 +267,21 @@ bool navigation_initialize(NavigationHandle handle, TFListenerHandle tf_handle); */ bool navigation_set_robot_footprint(NavigationHandle handle, const Point* points, size_t point_count); +/** + * @brief Get the robot's footprint (outline shape) + * @param handle Navigation handle + * @param out_points Output array of points (allocated by library, free with navigation_free_points) + * @param out_count Output number of points in the array + * @return true on success, false on failure + */ +bool navigation_get_robot_footprint(NavigationHandle handle, Point** out_points, size_t* out_count); + +/** + * @brief Free a points array allocated by navigation_get_robot_footprint + * @param points Pointer to point array + */ +void navigation_free_points(Point* points); + /** * @brief Send a goal for the robot to navigate to * @param handle Navigation handle @@ -350,6 +382,15 @@ bool navigation_get_robot_pose_stamped(NavigationHandle handle, PoseStamped* out */ bool navigation_get_robot_pose_2d(NavigationHandle handle, Pose2D* out_pose); +/** + * @brief Get the robot's current twist + * @param handle Navigation handle + * @param out_twist Output parameter with the robot's current twist + * @return true if twist was successfully retrieved + * @note out_twist->header.frame_id must be freed using nav_c_api_free_string + */ +bool navigation_get_twist(NavigationHandle handle, Twist2DStamped* out_twist); + /** * @brief Get navigation feedback * @param handle Navigation handle diff --git a/src/APIs/c_api/src/nav_c_api.cpp b/src/APIs/c_api/src/nav_c_api.cpp index bc53e30..7cd747d 100644 --- a/src/APIs/c_api/src/nav_c_api.cpp +++ b/src/APIs/c_api/src/nav_c_api.cpp @@ -6,12 +6,14 @@ #include #include #include +#include +#include #include #include #include #include #include -#include +#include #include @@ -65,6 +67,25 @@ namespace { c_pose->theta = cpp_pose.theta; } + void cpp_to_c_header(const robot_std_msgs::Header& cpp_header, Header* c_header) { + c_header->seq = cpp_header.seq; + c_header->sec = cpp_header.stamp.sec; + c_header->nsec = cpp_header.stamp.nsec; + if (!cpp_header.frame_id.empty()) { + c_header->frame_id = strdup(cpp_header.frame_id.c_str()); + } else { + c_header->frame_id = nullptr; + } + } + + void cpp_to_c_twist2d_stamped(const robot_nav_2d_msgs::Twist2DStamped& cpp_twist, + Twist2DStamped* c_twist) { + cpp_to_c_header(cpp_twist.header, &c_twist->header); + c_twist->velocity.x = cpp_twist.velocity.x; + c_twist->velocity.y = cpp_twist.velocity.y; + c_twist->velocity.theta = cpp_twist.velocity.theta; + } + // Convert C++ NavFeedback to C NavFeedback void cpp_to_c_nav_feedback(const robot::move_base_core::NavFeedback& cpp_feedback, NavFeedback* c_feedback) { c_feedback->navigation_state = static_cast(static_cast(cpp_feedback.navigation_state)); @@ -226,22 +247,13 @@ extern "C" bool navigation_initialize(NavigationHandle handle, TFListenerHandle } try { printf("[%s:%d]\n Initialize navigation\n", __FILE__, __LINE__); - robot::move_base_core::BaseNavigation* nav = static_cast(handle); + auto* nav = static_cast(handle); auto* tf_ptr = static_cast*>(tf_handle); - robot::PluginLoaderHelper loader; - std::string lib_path = loader.findLibraryPath("MoveBase"); - auto create_plugin = boost::dll::import_alias( - lib_path, - "MoveBase", - boost::dll::load_mode::append_decorations); - - robot::move_base_core::BaseNavigation::Ptr nav_ptr = create_plugin(); - printf("[%s:%d]\n Navigation created\n", __FILE__, __LINE__); - if (nav_ptr == nullptr) { - printf("[%s:%d]\n Error: Failed to create navigation\n", __FILE__, __LINE__); + if (!tf_ptr || !(*tf_ptr)) { + printf("[%s:%d]\n Error: Invalid TF listener\n", __FILE__, __LINE__); return false; } - nav_ptr->initialize(*tf_ptr); + nav->initialize(*tf_ptr); return true; } catch (const std::exception &e) { @@ -276,6 +288,45 @@ extern "C" bool navigation_set_robot_footprint(NavigationHandle handle, const Po } } +extern "C" bool navigation_get_robot_footprint(NavigationHandle handle, Point** out_points, size_t* out_count) { + if (!handle || !out_points || !out_count) { + return false; + } + + try { + robot::move_base_core::BaseNavigation* nav = static_cast(handle); + std::vector footprint = nav->getRobotFootprint(); + if (footprint.empty()) { + *out_points = nullptr; + *out_count = 0; + return true; + } + + Point* points = static_cast(malloc(sizeof(Point) * footprint.size())); + if (!points) { + return false; + } + + for (size_t i = 0; i < footprint.size(); ++i) { + points[i].x = footprint[i].x; + points[i].y = footprint[i].y; + points[i].z = footprint[i].z; + } + + *out_points = points; + *out_count = footprint.size(); + return true; + } catch (...) { + return false; + } +} + +extern "C" void navigation_free_points(Point* points) { + if (points) { + free(points); + } +} + extern "C" bool navigation_move_to(NavigationHandle handle, const PoseStamped* goal, double xy_goal_tolerance, double yaw_goal_tolerance) { if (!handle || !goal) { @@ -442,6 +493,21 @@ extern "C" bool navigation_get_robot_pose_2d(NavigationHandle handle, Pose2D* ou } } +extern "C" bool navigation_get_twist(NavigationHandle handle, Twist2DStamped* out_twist) { + if (!handle || !out_twist) { + return false; + } + + try { + robot::move_base_core::BaseNavigation* nav = static_cast(handle); + robot_nav_2d_msgs::Twist2DStamped cpp_twist = nav->getTwist(); + cpp_to_c_twist2d_stamped(cpp_twist, out_twist); + return true; + } catch (...) { + return false; + } +} + extern "C" bool navigation_get_feedback(NavigationHandle handle, NavFeedback* out_feedback) { if (!handle || !out_feedback) { return false; diff --git a/src/Algorithms/Libraries/mkt_algorithm/CMakeLists.txt b/src/Algorithms/Libraries/mkt_algorithm/CMakeLists.txt index 1f54a64..792d5da 100644 --- a/src/Algorithms/Libraries/mkt_algorithm/CMakeLists.txt +++ b/src/Algorithms/Libraries/mkt_algorithm/CMakeLists.txt @@ -84,6 +84,7 @@ add_library(${PROJECT_NAME}_diff SHARED src/diff/diff_predictive_trajectory.cpp src/diff/diff_rotate_to_goal.cpp src/diff/diff_go_straight.cpp + # src/diff/pure_pursuit.cpp ) if(BUILDING_WITH_CATKIN) diff --git a/src/Algorithms/Libraries/mkt_algorithm/include/mkt_algorithm/diff/pure_pursuit.h b/src/Algorithms/Libraries/mkt_algorithm/include/mkt_algorithm/diff/pure_pursuit.h new file mode 100644 index 0000000..95202fe --- /dev/null +++ b/src/Algorithms/Libraries/mkt_algorithm/include/mkt_algorithm/diff/pure_pursuit.h @@ -0,0 +1,50 @@ +#ifndef _NAV_ALGORITHM_DIFF_PURE_PURSUIT_H_INCLUDED__ +#define _NAV_ALGORITHM_DIFF_PURE_PURSUIT_H_INCLUDED__ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace mkt_algorithm +{ + namespace diff + { + class PurePursuit : public score_algorithm::ScoreAlgorithm + { + public: + PurePursuit(); + ~PurePursuit(); + void computePurePursuit( + const double &velocity_min, + const double &velocity_max, + const double &linear_vel, + const robot_nav_2d_msgs::Pose2DStamped &carrot_pose, + const double &min_dist2, + const double &curvature_dist2_floor, + const double &dist2_override); + + private: + void applyConstraints(const double &dist_error, const double &lookahead_dist, + const double &curvature, const robot_nav_2d_msgs::Twist2D &velocity, + const double &pose_cost, double &linear_vel, double &sign_x); + + double getEffectiveDistance(const robot_nav_2d_msgs::Pose2DStamped &carrot_pose, + const double &journey_plan); + + double computeDecelerationFactor(const double &effective_journey, const double &d_reduce); + + bool detectWobbleByCarrotAngle(std::vector &angle_history, const double &carrot_angle, + const double &litude_threshold, const size_t &window_size); + }; + } +} + +#endif \ No newline at end of file diff --git a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_go_straight.cpp b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_go_straight.cpp index 23f5c21..469cd5e 100644 --- a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_go_straight.cpp +++ b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_go_straight.cpp @@ -107,7 +107,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::GoStraight::calculator( robot_nav_2d_msgs::Twist2D twist; traj_->startNewIteration(velocity); // Nhận tốc độ hiện tại từ odom robot::Rate r(50); - while (traj_->hasMoreTwists()) + while (robot::ok() && traj_->hasMoreTwists()) { twist = traj_->nextTwist(); // ROS_INFO("Twist: x: %.2f, y: %.2f, theta: %.2f", twist.x, twist.y, twist.theta); @@ -184,6 +184,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::GoStraight::calculator( double v_min = journey_plan > d_begin_reduce ? vel_x_reduce : (vel_x_reduce - min_approach_linear_velocity_) * cosine_factor_begin_reduce + min_approach_linear_velocity_; v_min *= sign_x; + double effective_journey = getEffectiveDistance(carrot_pose, journey_plan); double decel_factor = computeDecelerationFactor(effective_journey, d_reduce); journey_plan += max_path_distance_; diff --git a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory copy 2.cpp b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory copy 2.cpp new file mode 100644 index 0000000..c5c68b4 --- /dev/null +++ b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory copy 2.cpp @@ -0,0 +1,1327 @@ +#include +#include +#include + +#define LIMIT_VEL_THETA 0.33 + +void mkt_algorithm::diff::PredictiveTrajectory::initialize( + robot::NodeHandle &nh, const std::string &name, TFListenerPtr tf, robot_costmap_2d::Costmap2DROBOT *costmap_robot, const score_algorithm::TrajectoryGenerator::Ptr &traj) +{ + if (!initialized_) + { + nh_ = robot::NodeHandle("~"); + nh_priv_ = robot::NodeHandle(nh, name); + name_ = name; + tf_ = tf; + traj_ = traj; + costmap_robot_ = costmap_robot; + this->getParams(); + nh_.param("publish_topic", enable_publish_, false); + nh_.param("min_approach_linear_velocity", min_approach_linear_velocity_, 0.1); + + footprint_spec_ = costmap_robot_->getRobotFootprint(); + std::vector footprint = costmap_robot_ ? costmap_robot_->getRobotFootprint() : std::vector(); + if (footprint.size() > 1) + { + double min_length = 1e10; + double max_length = 0.0; + for (size_t i = 0; i < footprint.size(); ++i) + { + const robot_geometry_msgs::Point &p1 = footprint[i]; + const robot_geometry_msgs::Point &p2 = footprint[(i + 1) % footprint.size()]; // wrap around to first point + double len = std::hypot(p2.x - p1.x, p2.y - p1.y) / 2.0; + if (len > max_length) + { + max_length = len; + } + if (len < min_length) + { + min_length = len; + } + } + this->min_path_distance_ = min_length > 0.1 ? min_length : 0.1; + this->max_path_distance_ = max_length > 0.1 ? max_length : 0.1; + } + this->initKalmanFilter(); + x_direction_ = y_direction_ = theta_direction_ = 0; + this->initialized_ = true; + robot::log_info("[%s:%d]\n PredictiveTrajectory Initialized successfully", __FILE__, __LINE__); + } +} + +mkt_algorithm::diff::PredictiveTrajectory::~PredictiveTrajectory() +{ + if (kf_) + { + kf_.reset(); + } +} + +void mkt_algorithm::diff::PredictiveTrajectory::initKalmanFilter() +{ + // kalman + last_actuator_update_ = robot::Time::now(); + n_ = 6; // [x, vx, ax, y, vy, ay, theta, vtheta, atheta] + m_ = 2; // measurements: x, y, theta + double dt = control_duration_; + + // Khởi tạo ma trận + A = Eigen::MatrixXd::Identity(n_, n_); + C = Eigen::MatrixXd::Zero(m_, n_); + Q = Eigen::MatrixXd::Zero(n_, n_); + R = Eigen::MatrixXd::Identity(m_, m_); + P = Eigen::MatrixXd::Identity(n_, n_); + + for (int i = 0; i < n_; i += 3) + { + A(i, i + 1) = dt; + A(i, i + 2) = 0.5 * dt * dt; + A(i + 1, i + 2) = dt; + } + + C(0, 0) = 1; + C(1, 3) = 1; + Q(2, 2) = 0.1; + Q(5, 5) = 0.6; + + R(0, 0) = 0.1; + R(1, 1) = 0.2; + + P(3, 3) = 0.4; + P(4, 4) = 0.4; + P(5, 5) = 0.4; + + kf_ = boost::make_shared(dt, A, C, Q, R, P); + Eigen::VectorXd x0(n_); + x0 << 0, 0, 0, 0, 0, 0; + kf_->init(robot::Time::now().toSec(), x0); +} + +void mkt_algorithm::diff::PredictiveTrajectory::getParams() +{ + robot_base_frame_ = nh_priv_.param("robot_base_frame", std::string("base_link")); + nh_priv_.param("avoid_obstacles", avoid_obstacles_, false); + nh_priv_.param("xy_local_goal_tolerance", xy_local_goal_tolerance_, 0.5); + nh_priv_.param("angle_threshold", angle_threshold_, M_PI / 8); + nh_priv_.param("index_samples", index_samples_, 0); + nh_priv_.param("follow_step_path", follow_step_path_, false); + + nh_priv_.param("use_velocity_scaled_lookahead_dist", use_velocity_scaled_lookahead_dist_, false); + nh_priv_.param("lookahead_dist", lookahead_dist_, 0.25); + nh_priv_.param("min_lookahead_dist", min_lookahead_dist_, 0.3); + nh_priv_.param("max_lookahead_dist", max_lookahead_dist_, 0.9); + nh_priv_.param("lookahead_time", lookahead_time_, 1.5); + nh_priv_.param("min_journey_squared", min_journey_squared_, std::numeric_limits::infinity()); + nh_priv_.param("max_journey_squared", max_journey_squared_, std::numeric_limits::infinity()); + + nh_priv_.param("use_rotate_to_heading", use_rotate_to_heading_, false); + nh_priv_.param("rotate_to_heading_min_angle", rotate_to_heading_min_angle_, 0.785); + + nh_priv_.param("rot_stopped_velocity", rot_stopped_velocity_, 0.0); + nh_priv_.param("trans_stopped_velocity", trans_stopped_velocity_, 0.0); + if (trans_stopped_velocity_ <= min_approach_linear_velocity_ || trans_stopped_velocity_ - min_approach_linear_velocity_ < 0.02) + trans_stopped_velocity_ = min_approach_linear_velocity_ + 0.05; + nh_priv_.param("cmd_smoothing_time", cmd_smoothing_time_, 0.2); + nh_priv_.param("max_lateral_accel", max_lateral_accel_, 0.6); + + // Regulated linear velocity scaling + nh_priv_.param("use_regulated_linear_velocity_scaling", use_regulated_linear_velocity_scaling_, false); + nh_priv_.param("regulated_linear_scaling_min_radius", regulated_linear_scaling_min_radius_, 0.9); + nh_priv_.param("regulated_linear_scaling_min_speed", regulated_linear_scaling_min_speed_, 0.25); + + // Inflation cost scaling (Limit velocity by proximity to obstacles) + nh_priv_.param("use_cost_regulated_linear_velocity_scaling", use_cost_regulated_linear_velocity_scaling_, true); + nh_priv_.param("inflation_cost_scaling_factor", inflation_cost_scaling_factor_, 3.0); + nh_priv_.param("cost_scaling_dist", cost_scaling_dist_, 0.6); + nh_priv_.param("cost_scaling_gain", cost_scaling_gain_, 1.0); + if (inflation_cost_scaling_factor_ <= 0.0) + { + robot::log_warning("[%s:%d]\n The value inflation_cost_scaling_factor is incorrectly set, " + "it should be >0. Disabling cost regulated linear velocity scaling."); + use_cost_regulated_linear_velocity_scaling_ = false; + } + double control_frequency = robot_nav_2d_utils::searchAndGetParam(nh_priv_, "controller_frequency", 10); + control_duration_ = 1.0 / control_frequency; + window_size_ = (size_t)(control_frequency * 3.0); + + if (traj_) + { + traj_.get()->getNodeHandle().param("max_vel_x", max_vel_x_, 0.0); + traj_.get()->getNodeHandle().param("min_vel_x", min_vel_x_, 0.0); + traj_.get()->getNodeHandle().param("acc_lim_x", acc_lim_x_, 0.0); + traj_.get()->getNodeHandle().param("decel_lim_x", decel_lim_x_, 0.0); + + traj_.get()->getNodeHandle().param("max_vel_y", max_vel_y_, 0.0); + traj_.get()->getNodeHandle().param("min_vel_y", min_vel_y_, 0.0); + traj_.get()->getNodeHandle().param("acc_lim_y", acc_lim_y_, 0.0); + traj_.get()->getNodeHandle().param("decel_lim_y", decel_lim_y_, 0.0); + + traj_.get()->getNodeHandle().param("max_vel_theta", max_vel_theta_, 0.0); + traj_.get()->getNodeHandle().param("min_vel_theta", min_vel_theta_, 0.0); + traj_.get()->getNodeHandle().param("acc_lim_theta", acc_lim_theta_, 0.0); + traj_.get()->getNodeHandle().param("decel_lim_theta", decel_lim_theta_, 0.0); + } +} + +void mkt_algorithm::diff::PredictiveTrajectory::reset() +{ + if (this->initialized_) + { + robot::log_info("[%s:%d]\n PredictiveTrajectory is reset", __FILE__, __LINE__); + reached_intermediate_goals_.clear(); + start_index_saved_vt_.clear(); + this->clear(); + x_direction_ = y_direction_ = theta_direction_ = 0; + this->follow_step_path_ = false; + this->nav_stop_ = false; + last_actuator_update_ = robot::Time::now(); + prevous_drive_cmd_ = robot_nav_2d_msgs::Twist2D(); + + if (kf_) + { + Eigen::VectorXd x0(n_); + x0 << 0, 0, 0, 0, 0, 0; + kf_->init(robot::Time::now().toSec(), x0); + } + } +} + +void mkt_algorithm::diff::PredictiveTrajectory::stop() +{ + this->nav_stop_ = true; +} + +void mkt_algorithm::diff::PredictiveTrajectory::resume() +{ + if (this->initialized_) + { + if(!this->nav_stop_) + return; + prevous_drive_cmd_ = robot_nav_2d_msgs::Twist2D(); + last_actuator_update_ = robot::Time::now(); + + if (kf_) + { + Eigen::VectorXd x0(n_); + x0 << 0, 0, 0, 0, 0, 0; + kf_->init(robot::Time::now().toSec(), x0); + } + this->nav_stop_ = false; + } +} + +bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity, + const robot_nav_2d_msgs::Pose2DStamped &goal, const robot_nav_2d_msgs::Path2D &global_plan, + double &x_direction, double &y_direction, double &theta_direction) +{ + if (!initialized_) + { + robot::log_error("[%s:%d]\n This planner has not been initialized, please call initialize() before using this planner", __FILE__, __LINE__); + return false; + } + + std::vector footprint = costmap_robot_ ? costmap_robot_->getRobotFootprint() : std::vector(); + if (footprint.size() > 1) + { + double min_length = 1e10; + double max_length = 0.0; + for (size_t i = 0; i < footprint.size(); ++i) + { + const robot_geometry_msgs::Point &p1 = footprint[i]; + const robot_geometry_msgs::Point &p2 = footprint[(i + 1) % footprint.size()]; // wrap around to first point + double len = std::hypot(p2.x - p1.x, p2.y - p1.y) / 2.0; + if (len > max_length) + { + max_length = len; + } + if (len < min_length) + { + min_length = len; + } + } + this->min_path_distance_ = min_length > 0.1 ? min_length : 0.1; + this->max_path_distance_ = max_length > 0.1 ? max_length : 0.1; + } + + if (global_plan.poses.empty() || (unsigned int)global_plan.poses.size() < 2) + { + robot::log_error("[%s:%d]\n The Local plan is empty or less than 1 points %d", __FILE__, __LINE__, (unsigned int)global_plan.poses.size()); + return false; + } + this->getParams(); + + frame_id_path_ = global_plan.header.frame_id; + goal_ = goal; + global_plan_ = global_plan; + + // prune global plan to cut off parts of the past (spatially before the robot) + if (!this->pruneGlobalPlan(tf_, pose, global_plan_, 1.0)) + { + robot::log_error("[%s:%d]\n pruneGlobalPlan Failed", __FILE__, __LINE__); + return false; + } + + double S = std::numeric_limits::infinity(); + S = std::max(costmap_robot_->getCostmap()->getSizeInCellsX() * costmap_robot_->getCostmap()->getResolution() / 2.0, + costmap_robot_->getCostmap()->getSizeInCellsY() * costmap_robot_->getCostmap()->getResolution() / 2.0); + const double min_S = min_lookahead_dist_ * 1.5 + max_path_distance_, max_S = max_lookahead_dist_ * 1.5 + max_path_distance_; + S = std::clamp(S * fabs(velocity.x) * lookahead_time_, min_S, max_S); + compute_plan_.poses.clear(); + + if ((unsigned int)global_plan_.poses.size() == 2) + { + double dx = global_plan_.poses.back().pose.x - global_plan_.poses.front().pose.x; + double dy = global_plan_.poses.back().pose.y - global_plan_.poses.front().pose.y; + if (hypot(dx, dy) <= 2.0 * costmap_robot_->getCostmap()->getResolution()) + { + compute_plan_ = global_plan_; + } + else + { + robot::log_error("[%s:%d]\n The Local Plan has 2 points and hypot between more than is %.3f m", __FILE__, __LINE__, costmap_robot_->getCostmap()->getResolution()); + return false; + } + } + else + { + unsigned int start_index, goal_index; + if (!this->computePlanCommand(pose, velocity, S, global_plan_, start_index, goal_index, compute_plan_)) + { + robot::log_error("[%s:%d]\n computePlanCommand is Failed", __FILE__, __LINE__); + return false; + } + } + + double lookahead_dist = this->getLookAheadDistance(velocity); + transform_plan_.poses.clear(); + if (!this->transformGlobalPlan(tf_, compute_plan_, pose, costmap_robot_, robot_base_frame_, lookahead_dist, transform_plan_)) + { + robot::log_warning("[%s:%d]\n Could not transform the global plan to the frame of the controller", __FILE__, __LINE__); + return false; + } + // else + // { + // robot::log_info("[%s:%d]\n Transform plan journey: %f %f %f", __FILE__, __LINE__, journey(transform_plan_.poses, 0, transform_plan_.poses.size() - 1), min_lookahead_dist_, max_lookahead_dist_); + // } + + x_direction = x_direction_; + y_direction = y_direction_ = 0; + theta_direction = theta_direction_; + + if ((unsigned int)(compute_plan_.poses.size() > 1) && compute_plan_.poses.back().header.seq != global_plan_.poses.back().header.seq) + { + const robot_geometry_msgs::Pose2D p2 = compute_plan_.poses.back().pose; + int index; + for (index = (unsigned int)(compute_plan_.poses.size() - 1); index > 0; index--) + { + robot_geometry_msgs::Pose2D pose = compute_plan_.poses[index].pose; + if (robot_nav_2d_utils::poseDistance(p2, pose) > xy_local_goal_tolerance_) + break; + } + const robot_geometry_msgs::Pose2D p1 = compute_plan_.poses[index].pose; + if (fabs(p2.y - p1.y) > 1e-9 || fabs(p2.x - p1.x) > 1e-9) + { + const double path_angle = atan2(p2.y - p1.y, p2.x - p1.x); + const double dir_path = cos(fabs(path_angle - p2.theta)); + if (fabs(dir_path) > M_PI / 6 || x_direction < 1e-9) + x_direction = dir_path > 0 ? FORWARD : BACKWARD; + } + } + else + { + try + { + auto carrot_pose_it = getLookAheadPoint(velocity, lookahead_dist, transform_plan_); + auto prev_carrot_pose_it = transform_plan_.poses.begin(); + double distance_it = 0; + if (carrot_pose_it != transform_plan_.poses.begin()) + { + for (auto it = carrot_pose_it - 1; it != transform_plan_.poses.begin(); --it) + { + double dx = it->pose.x - carrot_pose_it->pose.x; + double dy = it->pose.y - carrot_pose_it->pose.y; + distance_it += std::hypot(dx, dy); + if (distance_it > costmap_robot_->getCostmap()->getResolution()) + { + prev_carrot_pose_it = it; + break; + } + } + } + + robot_geometry_msgs::Pose front = journey(transform_plan_.poses, 0, transform_plan_.poses.size() - 1) > 5.0 * costmap_robot_->getCostmap()->getResolution() + ? robot_nav_2d_utils::pose2DToPose((*(prev_carrot_pose_it)).pose) + : robot_nav_2d_utils::pose2DToPose(robot_geometry_msgs::Pose2D()); + + robot_geometry_msgs::Pose back = robot_nav_2d_utils::pose2DToPose((*(carrot_pose_it)).pose); + + // teb_local_planner::PoseSE2 start_pose(front); + // teb_local_planner::PoseSE2 goal_pose(back); + // const double dir_path = (goal_pose.position() - start_pose.position()).dot(start_pose.orientationUnitVec()); + const double dir_path = 0.0; + + if (fabs(dir_path) > M_PI / 6 || x_direction < 1e-9) + x_direction = dir_path > 0 ? FORWARD : BACKWARD; + } + catch (std::exception &e) + { + robot::log_error("[%s:%d]\n getLookAheadPoint throw an exception: %s", __FILE__, __LINE__, e.what()); + return false; + } + } + + x_direction_ = x_direction; + y_direction_ = y_direction; + theta_direction_ = theta_direction; + return true; +} + +mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator( + const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity) +{ + mkt_msgs::Trajectory2D result; + result.velocity.x = result.velocity.y = result.velocity.theta = 0.0; + if (!traj_) + return result; + if (compute_plan_.poses.size() < 2) + { + robot::log_warning("[%s:%d]\n Local compute plan is available", __FILE__, __LINE__); + return result; + } + + robot::Time current_time = robot::Time::now(); + double dt = (current_time - last_actuator_update_).toSec(); + last_actuator_update_ = current_time; + + robot_nav_2d_msgs::Twist2D drive_cmd; + double sign_x = sign(x_direction_); + robot_nav_2d_msgs::Twist2D twist; + robot::log_info("[%s:%d] velocity in predictive trajectory: %f %f %f", __FILE__, __LINE__, velocity.x, velocity.y, velocity.theta); + traj_->startNewIteration(velocity); + while (robot::ok() && traj_->hasMoreTwists()) + { + twist = traj_->nextTwist(); + } + drive_cmd.x = std::min(sqrt(twist.x * twist.x), 1.5); + robot::log_info("[%s:%d] twist: %f %f %f", __FILE__, __LINE__, twist.x, twist.y, twist.theta); + robot::log_info("--------------------------------"); + double v_max = sign_x > 0 ? traj_->getTwistLinear(true).x : traj_->getTwistLinear(false).x; + + robot_nav_2d_msgs::Path2D transformed_plan = this->transform_plan_; + result.poses.clear(); + result.poses.reserve(transformed_plan.poses.size()); + for (const auto &pose_stamped : transformed_plan.poses) + { + result.poses.push_back(pose_stamped.pose); + } + + if (transformed_plan.poses.empty()) + { + robot::log_warning("[%s:%d]\n Transformed plan is empty. Cannot determine a localglobal_plan.", __FILE__, __LINE__); + return result; + } + + double lookahead_dist = getLookAheadDistance(velocity); + double tolerance = hypot(pose.pose.x - compute_plan_.poses.front().pose.x, pose.pose.y - compute_plan_.poses.front().pose.y); + + if (transformed_plan.poses.empty()) + { + robot::log_warning("[%s:%d]\n Transformed plan is empty after compute lookahead point", __FILE__, __LINE__); + return result; + } + auto carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan); + bool allow_rotate = false; + nh_priv_.param("allow_rotate", allow_rotate, false); + + // double path_distance_to_rotate = hypot(transformed_plan.poses.front().pose.x, transformed_plan.poses.front().pose.y); + robot_geometry_msgs::Pose2D front = transformed_plan.poses.size() > 3 ? transformed_plan.poses[1].pose : transformed_plan.poses.front().pose; + const double distance_allow_rotate = min_journey_squared_; + const double path_distance_to_rotate = hypot(pose.pose.x - compute_plan_.poses.back().pose.x, pose.pose.y - compute_plan_.poses.back().pose.y); + const double journey_plan = compute_plan_.poses.empty() ? distance_allow_rotate : journey(compute_plan_.poses, 0, compute_plan_.poses.size() - 1); + if (avoid_obstacles_) + allow_rotate = journey_plan >= distance_allow_rotate && + fabs(front.y) <= 0.2 && + (path_distance_to_rotate > max_path_distance_ || path_distance_to_rotate < 2.0 * costmap_robot_->getCostmap()->getResolution()); + else + allow_rotate |= path_distance_to_rotate >= distance_allow_rotate; + + double angle_to_heading; + if (allow_rotate && shouldRotateToPath(transformed_plan, carrot_pose, velocity, angle_to_heading, sign_x)) + { + if (!stopped(velocity, max_vel_theta_ + rot_stopped_velocity_, trans_stopped_velocity_)) + { + if (!stopWithAccLimits(pose, velocity, drive_cmd)) + return result; + } + else + { + rotateToHeading(angle_to_heading, velocity, drive_cmd); + } + } + else + { + const double vel_x_reduce = std::min(fabs(v_max), 0.3); + double carrot_dist2 = carrot_pose.pose.x * carrot_pose.pose.x + carrot_pose.pose.y * carrot_pose.pose.y; + carrot_dist2 = std::max(carrot_dist2, 0.05); + double curvature = carrot_dist2 > 0.1 ? 2.0 * carrot_pose.pose.y / carrot_dist2 : 2.0 * carrot_pose.pose.y / 0.1; + + if (max_lateral_accel_ > 1e-6) + { + const double curvature_abs = std::max(fabs(curvature), 1e-6); + const double v_lateral_limit = sqrt(max_lateral_accel_ / curvature_abs); + drive_cmd.x = sign_x > 0 ? std::min(drive_cmd.x, v_lateral_limit) : std::max(drive_cmd.x, -v_lateral_limit); + } + + const auto &plan_back_pose = compute_plan_.poses.back(); + double post_cost = costAtPose(plan_back_pose.pose.x, plan_back_pose.pose.y); + post_cost = std::max(post_cost, center_cost_); + this->applyConstraints(0.0, lookahead_dist, curvature, twist, post_cost, drive_cmd.x, sign_x); + + const double scale = fabs(velocity.x) * lookahead_time_ * 0.9; + const double min_S = min_lookahead_dist_ + max_path_distance_ + scale, max_S = max_lookahead_dist_ + max_path_distance_ + scale; + double d_reduce = std::clamp(journey_plan, min_S, max_S); + double d_begin_reduce = std::clamp(d_reduce * 0.2, 0.4, 1.0); + double cosine_factor_begin_reduce = 0.5 * (1.0 + cos(M_PI * (1.0 - fabs(journey_plan) / d_begin_reduce))); + double v_min = + journey_plan > d_begin_reduce ? vel_x_reduce : (vel_x_reduce - min_approach_linear_velocity_) * cosine_factor_begin_reduce + min_approach_linear_velocity_; + v_min *= sign_x; + + double effective_journey = getEffectiveDistance(carrot_pose, journey_plan); + double decel_factor = computeDecelerationFactor(effective_journey, d_reduce); + double vel_reduce = sign_x > 0 + ? std::min(drive_cmd.x, (drive_cmd.x - v_min) * decel_factor + v_min) + : std::max(drive_cmd.x, (drive_cmd.x - v_min) * decel_factor + v_min); + drive_cmd.x = (journey_plan + max_path_distance_) >= d_reduce ? drive_cmd.x : vel_reduce; + + double v_theta = drive_cmd.x * curvature; + double carrot_angle = std::atan2(carrot_pose.pose.y, carrot_pose.pose.x); + if (detectWobbleByCarrotAngle(angle_history_, carrot_angle, 0.3, window_size_)) + { + carrot_dist2 *= 0.6; + curvature = carrot_dist2 > 0.1 ? 2.0 * carrot_pose.pose.y / carrot_dist2 : 2.0 * carrot_pose.pose.y / 0.1; + v_theta = drive_cmd.x * curvature; + } + if (fabs(v_theta) > LIMIT_VEL_THETA) + { + robot_nav_2d_msgs::Twist2D cmd_vel, cmd_result; + cmd_vel.x = sign_x > 0 + ? std::min(drive_cmd.x, v_theta / std::max(curvature, 0.1)) + : std::max(drive_cmd.x, v_theta / std::min(curvature, -0.1)); + cmd_vel.x = std::clamp(cmd_vel.x, -0.5, 0.5); + this->moveWithAccLimits(velocity, cmd_vel, cmd_result); + drive_cmd.x = std::copysign(cmd_result.x, sign_x); + v_theta = drive_cmd.x * curvature; + } + + if (journey_plan < min_journey_squared_) + { + if (transform_plan_.poses.size() > 2) + { + robot_nav_2d_msgs::Pose2DStamped end = transform_plan_.poses.back(); + robot_nav_2d_msgs::Pose2DStamped start = transform_plan_.poses[transform_plan_.poses.size() - 2]; + double dx = end.pose.x - start.pose.x; + double dy = end.pose.y - start.pose.y; + v_theta = atan2(dy, dx); + if (v_theta > M_PI_2) + v_theta -= M_PI; + else if (v_theta < -M_PI_2) + v_theta += M_PI; + // v_theta *= 0.5; + v_theta = std::clamp(v_theta, -0.02, 0.02); + } + else + v_theta = 0.0; + } + double limit_acc_theta = fabs(v_theta) > 0.15 ? acc_lim_theta_ : 1.8; + double max_acc_vth = velocity.theta + fabs(limit_acc_theta) * dt; + double min_acc_vth = velocity.theta - fabs(limit_acc_theta) * dt; + drive_cmd.theta = std::clamp(v_theta, min_acc_vth, max_acc_vth); + + if (this->nav_stop_) + { + if (!stopped(velocity, rot_stopped_velocity_, trans_stopped_velocity_)) + { + if (!stopWithAccLimits(pose, velocity, drive_cmd)) + return result; + } + else + drive_cmd = {}; + result.velocity = drive_cmd; + return result; + } + + Eigen::VectorXd y(2); + y << drive_cmd.x, drive_cmd.theta; + + // Cập nhật lại A nếu dt thay đổi + for (int i = 0; i < n_; ++i) + for (int j = 0; j < n_; ++j) + A(i, j) = (i == j ? 1.0 : 0.0); + for (int i = 0; i < n_; i += 3) + { + A(i, i + 1) = dt; + A(i, i + 2) = 0.5 * dt * dt; + A(i + 1, i + 2) = dt; + } + kf_->update(y, dt, A); + + // Check if Kalman filter's estimated velocity exceeds v_max + if (avoid_obstacles_ && (cost_left_side_ >= robot_costmap_2d::UNPREFERRED_SPACE || + cost_right_side_ >= robot_costmap_2d::UNPREFERRED_SPACE || + cost_left_goal_ >= robot_costmap_2d::UNPREFERRED_SPACE || + cost_right_goal_ >= robot_costmap_2d::UNPREFERRED_SPACE)) + { + drive_cmd.x = fabs(kf_->state()[0]) > fabs(v_max) ? drive_cmd.x : kf_->state()[0]; + } + else + { + drive_cmd.x = std::clamp(kf_->state()[0], -fabs(v_max), fabs(v_max)); + } + + drive_cmd.x = fabs(drive_cmd.x) >= min_approach_linear_velocity_ ? drive_cmd.x : std::copysign(min_approach_linear_velocity_, sign_x); + drive_cmd.theta = std::clamp(kf_->state()[3], -LIMIT_VEL_THETA, LIMIT_VEL_THETA); + } + + if (cmd_smoothing_time_ > 1e-6) + { + const double alpha = std::clamp(dt / (cmd_smoothing_time_ + dt), 0.0, 1.0); + drive_cmd.x = prevous_drive_cmd_.x + alpha * (drive_cmd.x - prevous_drive_cmd_.x); + drive_cmd.theta = prevous_drive_cmd_.theta + alpha * (drive_cmd.theta - prevous_drive_cmd_.theta); + } + + result.velocity = drive_cmd; + prevous_drive_cmd_ = drive_cmd; + return result; +} + +bool mkt_algorithm::diff::PredictiveTrajectory::shouldRotateToPath( + const robot_nav_2d_msgs::Path2D &global_plan, const robot_nav_2d_msgs::Pose2DStamped &carrot_pose, const robot_nav_2d_msgs::Twist2D &velocity, double &angle_to_path, const double &sign_x) +{ + bool curvature = false; + double path_angle = 0; + if (!global_plan.poses.empty()) + { + if ((unsigned)global_plan.poses.size() > 2) + { + const double start_direction_x = global_plan.poses[1].pose.x - global_plan.poses[0].pose.x; + const double start_direction_y = global_plan.poses[1].pose.y - global_plan.poses[0].pose.y; + if (fabs(start_direction_x) > 1e-9 || fabs(start_direction_y) > 1e-9) + { + double start_angle = atan2(start_direction_y, start_direction_x); + for (unsigned int i = 1; i < (unsigned)global_plan.poses.size(); i++) + { + const double current_direction_x = global_plan.poses[i].pose.x - global_plan.poses[i - 1].pose.x; + const double current_direction_y = global_plan.poses[i].pose.y - global_plan.poses[i - 1].pose.y; + if (fabs(current_direction_x) > 1e-9 || fabs(current_direction_y) > 1e-9) + { + double current_angle = atan2(current_direction_y, current_direction_x); + if (fabs(remainder(start_angle - current_angle, 2 * M_PI)) > 1e-9) + { + curvature = true; + break; + } + path_angle = current_angle; + } + } + } + } + } + // ROS_INFO_THROTTLE(0.1,"path_angle %.3f %.3f", path_angle, std::atan2(carrot_pose.pose.y, carrot_pose.pose.x)); + // Whether we should rotate robot to rough path heading + angle_to_path = curvature ? path_angle : std::atan2(carrot_pose.pose.y, carrot_pose.pose.x); + angle_to_path = sign_x < 0 + ? angles::normalize_angle(M_PI + angle_to_path) + : angles::normalize_angle(angle_to_path); + + double heading_linear = sqrt(velocity.x * velocity.x + velocity.y * velocity.y); + // The difference in the path orientation and the starting robot orientation (radians) to trigger a rotate in place. (default: 0.785) + double heading_rotate = rotate_to_heading_min_angle_; + bool is_stopped = stopped(velocity, max_vel_theta_ + rot_stopped_velocity_, trans_stopped_velocity_); + heading_rotate = is_stopped + ? rotate_to_heading_min_angle_ + heading_linear + : std::clamp(heading_rotate + heading_linear, 0.3, M_PI_2); + + bool result = use_rotate_to_heading_ && (is_stopped || sign(angle_to_path) * sign_x < 0) && fabs(angle_to_path) > heading_rotate; + + // if (result) + // { + // ROS_WARN_THROTTLE(0.1, "x %.3f %.3f theta %.3f %.3f", + // velocity.x, trans_stopped_velocity_, velocity.theta, max_vel_theta_ + rot_stopped_velocity_); + // ROS_WARN_THROTTLE(0.1, "%x %.3f %.3f %.3f %.3f %.3f \n", + // is_stopped, path_angle, std::atan2(carrot_pose.pose.y, carrot_pose.pose.x), angle_to_path, heading_rotate, sign_x); + // } + // else + // { + // ROS_INFO_THROTTLE(0.1, "x %.3f %.3f theta %.3f %.3f", + // velocity.x, trans_stopped_velocity_, velocity.theta, max_vel_theta_ + rot_stopped_velocity_); + // ROS_INFO_THROTTLE(0.1, "%x %.3f %.3f %.3f %.3f %.3f \n", + // is_stopped, path_angle,std::atan2(carrot_pose.pose.y, carrot_pose.pose.x) ,angle_to_path, heading_rotate, sign_x); + // } + + return result; +} + +void mkt_algorithm::diff::PredictiveTrajectory::rotateToHeading(const double &angle_to_path, const robot_nav_2d_msgs::Twist2D &velocity, robot_nav_2d_msgs::Twist2D &cmd_vel) +{ + const double dt = control_duration_; + const double theta_direction = angle_to_path > 0.0 ? 1.0 : -1.0; + double vel_yaw = theta_direction * fabs(velocity.theta); + double ang_diff = angle_to_path; + double max_vel_theta = traj_ ? fabs(traj_->getTwistAngular(true).z) : 0.3; + + double angular_decel_zone = 0.3; // rad - khoảng cách bắt đầu giảm tốc + nh_priv_.param("angular_decel_zone", angular_decel_zone, 0.5); + angular_decel_zone += std::clamp( + fabs(max_vel_theta) + (M_PI_2 - fabs(atan2(min_path_distance_, max_path_distance_))), 0.4, M_PI_2); + double zone_begin = std::max(angular_decel_zone * 0.2, 0.2); + double cosine_begin_factor = 0.5 * (1.0 + cos(M_PI * (1.0 - fabs(ang_diff) / zone_begin))); + + double reduce_vel_theta = std::min(max_vel_theta, 0.25 + min_vel_theta_); + reduce_vel_theta = fabs(ang_diff) > zone_begin ? reduce_vel_theta : (reduce_vel_theta - min_vel_theta_) * cosine_begin_factor + min_vel_theta_; + + // === ANGULAR DECELERATION ZONE === + double target_angular_speed = max_vel_theta; + if (fabs(ang_diff) < angular_decel_zone) + { + // ROS_WARN_THROTTLE(0.2,"%f %f %f %f", ang_diff, angular_decel_zone, zone_begin, max_vel_theta); + double cosine_factor = 0.5 * (1.0 + cos(M_PI * (1.0 - fabs(ang_diff) / angular_decel_zone))); + double cosine_speed = max_vel_theta * cosine_factor; + + // Choose deceleration profile + target_angular_speed = cosine_speed; // Smoothest option + + // Ensure minimum speed to avoid stalling + target_angular_speed = std::max(target_angular_speed, reduce_vel_theta); + } + // else + // ROS_INFO_THROTTLE(1,"%f %f %f %f", ang_diff, angular_decel_zone, max_vel_theta, reduce_vel_theta); + + // Apply direction + double v_theta_desired = std::copysign(target_angular_speed, ang_diff); + + // === ACCELERATION LIMITS === + double max_acc_vel = vel_yaw + fabs(acc_lim_theta_) * dt; + double min_acc_vel = vel_yaw - fabs(acc_lim_theta_) * dt; + double v_theta_samp = std::clamp(v_theta_desired, min_acc_vel, max_acc_vel); + + // === STOPPING CONSTRAINT === + double max_speed_to_stop = sqrt(2.0 * fabs(decel_lim_theta_) * fabs(ang_diff)); + v_theta_samp = std::copysign( + std::min(max_speed_to_stop, fabs(v_theta_samp)), ang_diff); + + // === FINAL LIMITS === + v_theta_samp = theta_direction > 0 + ? std::clamp(v_theta_samp, min_vel_theta_, max_vel_theta) + : std::clamp(v_theta_samp, -max_vel_theta, -min_vel_theta_); + + cmd_vel.x = 0.0; + cmd_vel.y = 0.0; + cmd_vel.theta = v_theta_samp; +} + +double mkt_algorithm::diff::PredictiveTrajectory::getLookAheadDistance(const robot_nav_2d_msgs::Twist2D &velocity) +{ + // If using velocity-scaled look ahead distances, find and clamp the dist + // Else, use the static look ahead distance + double lookahead_dist = lookahead_dist_; + if (use_velocity_scaled_lookahead_dist_) + { + lookahead_dist = fabs(velocity.x) * lookahead_time_; + lookahead_dist = std::clamp(lookahead_dist, min_lookahead_dist_, max_lookahead_dist_); + } + + return lookahead_dist; +} + +std::vector::iterator +mkt_algorithm::diff::PredictiveTrajectory::getLookAheadPoint(const robot_nav_2d_msgs::Twist2D &velocity, const double &lookahead_dist, robot_nav_2d_msgs::Path2D global_plan) +{ + if (global_plan.poses.empty()) + { + throw robot_nav_core2::PlannerTFException("The global plan passed to the local planner is empty."); + } + + if ((unsigned)global_plan.poses.size() < 2) + { + auto goal_pose_it = std::prev(global_plan.poses.end()); + return goal_pose_it; + } + unsigned int goal_index = (unsigned)global_plan.poses.size() - 1; + + double start_direction_x = global_plan.poses[1].pose.x - global_plan.poses[0].pose.x; + double start_direction_y = global_plan.poses[1].pose.y - global_plan.poses[0].pose.y; + double end_direction_x = global_plan.poses[goal_index].pose.x - global_plan.poses[goal_index - 1].pose.x; + double end_direction_y = global_plan.poses[goal_index].pose.y - global_plan.poses[goal_index - 1].pose.y; + + // make sure that atan2 is defined + double start_angle = atan2(start_direction_y, start_direction_x); + double end_angle = atan2(end_direction_y, end_direction_x); + double permition_threshold = std::clamp(fabs(end_angle - start_angle) / 2.0, 0.32, M_PI_2); + + for (unsigned int i = 1; i < (int)global_plan.poses.size(); i++) + { + if (fabs(start_direction_x) > 1e-9 || fabs(start_direction_y) > 1e-9) + { + const double current_direction_x = global_plan.poses[i].pose.x - global_plan.poses[i - 1].pose.x; + const double current_direction_y = global_plan.poses[i].pose.y - global_plan.poses[i - 1].pose.y; + + if (fabs(current_direction_x) > 1e-9 || fabs(current_direction_y) > 1e-9) + { + double current_angle = atan2(current_direction_y, current_direction_x); + goal_index = i; + if (fabs(velocity.x) <= trans_stopped_velocity_ && fabs(velocity.theta) >= (0.8 * min_vel_theta_)) + continue; + + if (fabs(remainder(start_angle - current_angle, 2 * M_PI)) >= permition_threshold) + { + goal_index = i; + break; + } + } + } + } + + // Find the first pose which is at a distance greater than the lookahead distance + auto goal_pose_it = std::find_if( + global_plan.poses.begin(), global_plan.poses.begin() + goal_index, + [&](const auto &ps) + { + return std::hypot(ps.pose.x, ps.pose.y) >= lookahead_dist; + }); + + // If the number of poses is not far enough, take the last pose + if (goal_pose_it == global_plan.poses.end()) + { + goal_pose_it = std::prev(global_plan.poses.end()); + } + return goal_pose_it; +} + +robot_geometry_msgs::PointStamped mkt_algorithm::diff::PredictiveTrajectory::createCarrotMsg(const robot_nav_2d_msgs::Pose2DStamped &carrot_pose) +{ + robot_geometry_msgs::PointStamped carrot_msg; + carrot_msg.header = carrot_pose.header; + carrot_msg.point.x = carrot_pose.pose.x; + carrot_msg.point.y = carrot_pose.pose.y; + carrot_msg.point.z = 0.5; // publish right over map to stand out + return carrot_msg; +} + +bool mkt_algorithm::diff::PredictiveTrajectory::pruneGlobalPlan(TFListenerPtr tf, const robot_nav_2d_msgs::Pose2DStamped &pose, robot_nav_2d_msgs::Path2D &global_plan, double dist_behind_robot) +{ + if (global_plan.poses.empty()) + return false; + if (tf == nullptr) + return false; + try + { + // let's get the pose of the robot in the frame of the plan + robot_nav_2d_msgs::Pose2DStamped robot; + if (!robot_nav_2d_utils::transformPose(tf, global_plan.header.frame_id, pose, robot)) + { + throw robot_nav_core2::PlannerTFException("PredictiveTrajectory: Unable to transform robot pose into global plan's frame"); + } + + double dist_thresh_sq = dist_behind_robot * dist_behind_robot; + + // iterate plan until a pose close the robot is found + std::vector::iterator it = global_plan.poses.begin(); + std::vector::iterator erase_end = it; + while (it != global_plan.poses.end()) + { + double dx = robot.pose.x - it->pose.x; + double dy = robot.pose.y - it->pose.y; + double dist_sq = dx * dx + dy * dy; + if (dist_sq < dist_thresh_sq) + { + erase_end = it; + break; + } + ++it; + } + if (erase_end == global_plan.poses.end()) + return false; + + if (erase_end != global_plan.poses.begin()) + global_plan.poses.erase(global_plan.poses.begin(), erase_end); + } + catch (const tf3::TransformException &ex) + { + robot::log_debug("[%s:%d]\n Cannot prune path since no transform is available: %s", __FILE__, __LINE__, ex.what()); + return false; + } + return true; +} + +bool mkt_algorithm::diff::PredictiveTrajectory::transformGlobalPlan( + TFListenerPtr tf, const robot_nav_2d_msgs::Path2D &global_plan, const robot_nav_2d_msgs::Pose2DStamped &pose, + const robot_costmap_2d::Costmap2DROBOT *costmap, const std::string &robot_base_frame, double max_plan_length, + robot_nav_2d_msgs::Path2D &transformed_plan) +{ + // this method is a slightly modified version of base_local_planner/goal_functions.h + transformed_plan.poses.clear(); + transformed_plan.header.stamp = pose.header.stamp; + transformed_plan.header.frame_id = robot_base_frame; + + if (global_plan.poses.empty()) + return false; + + if (tf == nullptr) + return false; + + if (costmap == nullptr || costmap->getCostmap() == nullptr) + return false; + + try + { + if (global_plan.poses.empty()) + { + robot::log_error("[%s:%d]\n Received plan with zero length", __FILE__, __LINE__); + return false; + } + + // let's get the pose of the robot in the frame of the plan + robot_nav_2d_msgs::Pose2DStamped robot_pose; + if (!robot_nav_2d_utils::transformPose(tf, global_plan.header.frame_id, pose, robot_pose)) + { + throw robot_nav_core2::PlannerTFException("PredictiveTrajectory: Unable to transform robot pose into global plan's frame"); + } + + // we'll discard points on the plan that are outside the local costmap + double dist_threshold = std::max(costmap->getCostmap()->getSizeInCellsX() * costmap->getCostmap()->getResolution() / 2.0, + costmap->getCostmap()->getSizeInCellsY() * costmap->getCostmap()->getResolution() / 2.0); + + dist_threshold *= 0.85; // just consider 85% of the costmap size to better incorporate point obstacle that are + double sq_dist_threshold = dist_threshold * dist_threshold; + // located on the border of the local costmap + + int i = 0; + double sq_dist = std::numeric_limits::infinity(); + + // we need to loop to a point on the plan that is within a certain distance of the robot + bool robot_reached = false; + for (int j = 0; j < (int)global_plan.poses.size(); ++j) + { + double x_diff = robot_pose.pose.x - global_plan.poses[j].pose.x; + double y_diff = robot_pose.pose.y - global_plan.poses[j].pose.y; + double new_sq_dist = x_diff * x_diff + y_diff * y_diff; + if (robot_reached && new_sq_dist > sq_dist_threshold) + { + break; + } // force stop if we have reached the costmap border + + if (new_sq_dist < sq_dist) // find closest distance + { + sq_dist = new_sq_dist; + i = j; + if (sq_dist < costmap->getCostmap()->getResolution()) // 5 cm to the robot; take the immediate local minima; if it's not the global + robot_reached = true; // minima, probably means that there's a loop in the path, and so we prefer this + } + } + + double plan_length = 0; // check cumulative Euclidean distance along the plan + double x_direction_saved = 0.0; + // now we'll transform until points are outside of our distance threshold + while (i < (int)global_plan.poses.size() && sq_dist <= sq_dist_threshold && + (max_plan_length <= 0 || plan_length <= max_plan_length)) + { + robot_nav_2d_msgs::Pose2DStamped stamped_pose; + stamped_pose.pose = global_plan.poses[i].pose; + stamped_pose.header.frame_id = global_plan.header.frame_id; + + robot_nav_2d_msgs::Pose2DStamped newer_pose; + if (!robot_nav_2d_utils::transformPose(tf, robot_base_frame, stamped_pose, newer_pose)) + { + ++i; + continue; + } + transformed_plan.poses.push_back(newer_pose); + + double x_diff = robot_pose.pose.x - global_plan.poses[i].pose.x; + double y_diff = robot_pose.pose.y - global_plan.poses[i].pose.y; + sq_dist = x_diff * x_diff + y_diff * y_diff; + + // Calculate distance to previous pose + if (i > 0 && max_plan_length > 0) + { + robot_geometry_msgs::Pose2D p1 = global_plan.poses[i].pose; + robot_geometry_msgs::Pose2D p2 = global_plan.poses[i - 1].pose; + plan_length += std::sqrt(std::pow(p1.x - p2.x, 2) + std::pow(p1.y - p2.y, 2)); + if (fabs(p2.y - p1.y) > 1e-9 || fabs(p2.x - p1.x) > 1e-9) + { + const double egde_angle = atan2(p1.y - p2.y, p1.x - p2.x); + const double target_direction = cos(fabs(egde_angle - p1.theta)); + if (target_direction * x_direction_saved < 0.0) + { + plan_length = 0; + } + x_direction_saved = target_direction; + } + } + ++i; + } + } + catch (tf3::LookupException &ex) + { + robot::log_error("[%s:%d]\n No Transform available Error: %s", __FILE__, __LINE__, ex.what()); + return false; + } + catch (tf3::ConnectivityException &ex) + { + robot::log_error("[%s:%d]\n Connectivity Error: %s", __FILE__, __LINE__, ex.what()); + return false; + } + catch (tf3::ExtrapolationException &ex) + { + robot::log_error("[%s:%d]\n Extrapolation Error: %s", __FILE__, __LINE__, ex.what()); + if (global_plan.poses.size() > 0) + robot::log_error("[%s:%d]\n Robot Frame: %s Plan Frame size %d: %s", __FILE__, __LINE__, robot_base_frame.c_str(), (unsigned int)global_plan.poses.size(), global_plan.header.frame_id.c_str()); + + return false; + } + return true; +} + +void mkt_algorithm::diff::PredictiveTrajectory::moveWithAccLimits( + const robot_nav_2d_msgs::Twist2D &velocity, const robot_nav_2d_msgs::Twist2D &cmd_vel, robot_nav_2d_msgs::Twist2D &cmd_vel_result) +{ + const double dt = control_duration_; + + // --- X axis --- + double min_vel_x = traj_ ? min_vel_x_ : fabs(traj_->getTwistLinear(false).x); + double max_vel_x = traj_ ? max_vel_x_ : fabs(traj_->getTwistLinear(true).x); + + double vx = cmd_vel.x > 0.0 ? std::min(max_vel_x, std::max(min_vel_x, cmd_vel.x)) : std::max(-max_vel_x, std::min(-min_vel_x, cmd_vel.x)); + + double max_acc_vx = velocity.x + fabs(acc_lim_x_) * dt; + double min_acc_vx = velocity.x - fabs(decel_lim_x_) * dt; + vx = std::clamp(vx, min_acc_vx, max_acc_vx); + + // --- Y axis --- + double min_vel_y = traj_ ? min_vel_y_ : fabs(traj_->getTwistLinear(false).y); + double max_vel_y = traj_ ? max_vel_y_ : fabs(traj_->getTwistLinear(true).y); + double vy = cmd_vel.y > 0.0 ? std::min(max_vel_y, std::max(min_vel_y, cmd_vel.y)) : std::max(-max_vel_y, std::min(-min_vel_y, cmd_vel.y)); + + double max_acc_vy = velocity.y + fabs(acc_lim_y_) * dt; + double min_acc_vy = velocity.y - fabs(decel_lim_y_) * dt; + vy = std::clamp(vy, min_acc_vy, max_acc_vy); + // --- Assign result --- + cmd_vel_result.x = vx; + cmd_vel_result.y = vy; + // cmd_vel_result.theta = vth; +} + +bool mkt_algorithm::diff::PredictiveTrajectory::stopWithAccLimits(const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity, robot_nav_2d_msgs::Twist2D &cmd_vel) +{ + // slow down with the maximum possible acceleration... we should really use the frequency that we're running at to determine what is feasible + // but we'll use a tenth of a second to be consistent with the implementation of the local planner. + const double dt = control_duration_; + double vx = sign(velocity.x) * std::max(0.0, (fabs(velocity.x) - fabs(decel_lim_x_) * dt)); + double vy = sign(velocity.y) * std::max(0.0, (fabs(velocity.y) - fabs(decel_lim_y_) * dt)); + + double vel_yaw = velocity.theta; + double vth = sign(vel_yaw) * std::max(0.0, (fabs(vel_yaw) - fabs(decel_lim_theta_) * dt)); + + // we do want to check whether or not the command is valid + cmd_vel.x = vx; + cmd_vel.y = vy; + cmd_vel.theta = vth; + return true; +} + +void mkt_algorithm::diff::PredictiveTrajectory::applyConstraints( + const double &dist_error, const double &lookahead_dist, + const double &curvature, const robot_nav_2d_msgs::Twist2D &velocity, + const double &pose_cost, double &linear_vel, double &sign_x) +{ + double curvature_vel = linear_vel; + double cost_vel = linear_vel; + double approach_vel = linear_vel; + + // std::stringstream ss; + // ss << linear_vel << " "; + // limit the linear velocity by curvature + if (use_regulated_linear_velocity_scaling_) + { + const double &min_rad = regulated_linear_scaling_min_radius_; + const double radius = curvature > 1e-9 ? fabs(1.0 / curvature) : min_rad; + if (radius < min_rad) + { + curvature_vel *= 1.0 - (fabs(radius - min_rad) / min_rad); + robot_nav_2d_msgs::Twist2D cmd, result; + cmd.x = curvature_vel; + this->moveWithAccLimits(velocity, cmd, result); + curvature_vel = result.x; + linear_vel = std::max(linear_vel, regulated_linear_scaling_min_speed_); + } + } + // ss << linear_vel << " "; + // limit the linear velocity by proximity to obstacles + if (use_cost_regulated_linear_velocity_scaling_ && + pose_cost != static_cast(robot_costmap_2d::NO_INFORMATION) && + pose_cost != static_cast(robot_costmap_2d::FREE_SPACE)) + { + const double inscribed_radius = costmap_robot_->getLayeredCostmap()->getInscribedRadius(); + const double min_distance_to_obstacle = (-1.0 / inflation_cost_scaling_factor_) * + std::log(pose_cost / (robot_costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1)) + + inscribed_radius; + + if (min_distance_to_obstacle < cost_scaling_dist_) + { + cost_vel *= cost_scaling_gain_ * min_distance_to_obstacle / cost_scaling_dist_; + } + robot_nav_2d_msgs::Twist2D cmd, result; + cmd.x = cost_vel; + this->moveWithAccLimits(velocity, cmd, result); + cost_vel = result.x; + linear_vel = std::min(cost_vel, curvature_vel); + } + // ss << linear_vel << " "; + // Use the lowest of the 2 constraint heuristics, but above the minimum translational speed + // if the actual lookahead distance is shorter than requested, that means we're at the + // end of the path. We'll scale linear velocity by error to slow to a smooth stop. + // This expression is eq. to + // (1) holding time to goal, t, constant using the theoretical + // lookahead distance and proposed velocity and + // (2) using t with the actual lookahead + // distance to scale the velocity (e.g. t = lookahead / velocity, v = carrot / t). + + double dist_error_limit = costmap_robot_ != nullptr && costmap_robot_->getCostmap() != nullptr + ? 2.0 * costmap_robot_->getCostmap()->getResolution() + : 0.1; + if (dist_error > dist_error_limit) + { + double velocity_scaling = lookahead_dist > 1e-9 ? 1.0 - (dist_error / lookahead_dist) : 1.0; + double unbounded_vel = approach_vel * velocity_scaling; + if (unbounded_vel < min_approach_linear_velocity_) + { + approach_vel = min_approach_linear_velocity_; + } + else + { + approach_vel *= velocity_scaling; + } + + // Use the lowest velocity between approach and other constraints, if all overlapping + robot_nav_2d_msgs::Twist2D cmd, result; + cmd.x = approach_vel; + this->moveWithAccLimits(velocity, cmd, result); + approach_vel = result.x; + linear_vel = std::min(linear_vel, approach_vel); + } + + // ss << linear_vel << " "; + + // Limit linear velocities to be valid + double min_vel_x = traj_ ? min_vel_x_ : fabs(traj_->getTwistLinear(false).x); + double max_vel_x = traj_ ? max_vel_x_ : fabs(traj_->getTwistLinear(true).x); + double min_vel_y = traj_ ? min_vel_y_ : fabs(traj_->getTwistLinear(false).y); + double max_vel_y = traj_ ? max_vel_y_ : fabs(traj_->getTwistLinear(true).y); + double max_linear_vel = sqrt(max_vel_x * max_vel_x + max_vel_y * max_vel_y); + double min_linear_vel = sqrt(min_vel_x * min_vel_x + min_vel_y * min_vel_y); + double desired_linear_vel = sign_x > 0 ? fabs(max_linear_vel) : fabs(min_linear_vel); + linear_vel = std::clamp(fabs(linear_vel), min_approach_linear_velocity_, desired_linear_vel); + linear_vel = sign_x * linear_vel; + // ss << linear_vel << " "; + // ROS_INFO_STREAM_THROTTLE(0.1, ss.str()); +} + +std::vector +mkt_algorithm::diff::PredictiveTrajectory::interpolateFootprint(robot_geometry_msgs::Pose2D pose, std::vector footprint, double resolution) +{ + + // Dịch sang tọa độ tuyệt đối + std::vector abs_footprint; + double cos_th = std::cos(pose.theta); + double sin_th = std::sin(pose.theta); + for (auto pt : footprint) + { + pt.x *= 1.2; + pt.y *= 1.2; + robot_geometry_msgs::Point abs_pt; + abs_pt.x = pose.x + pt.x * cos_th - pt.y * sin_th; + abs_pt.y = pose.y + pt.x * sin_th + pt.y * cos_th; + abs_footprint.push_back(abs_pt); + } + + std::vector points; + for (size_t i = 0; i < abs_footprint.size(); ++i) + { + const robot_geometry_msgs::Point &start = abs_footprint[i]; + const robot_geometry_msgs::Point &end = abs_footprint[(i + 1) % abs_footprint.size()]; + + double dx = end.x - start.x; + double dy = end.y - start.y; + double distance = std::hypot(dx, dy); + int steps = std::max(1, static_cast(std::floor(distance / resolution))); + + for (int j = 0; j <= steps; ++j) + { + if (j == steps && i != abs_footprint.size() - 1) + continue; // tránh lặp + double t = static_cast(j) / steps; + robot_geometry_msgs::Point pt; + pt.x = start.x + t * dx; + pt.y = start.y + t * dy; + points.push_back(pt); + } + } + return points; +} + +double mkt_algorithm::diff::PredictiveTrajectory::costAtPose(const double &x, const double &y) +{ + unsigned int mx, my; + unsigned char cost; + if (costmap_robot_->getCostmap()->worldToMap(x, y, mx, my)) + { + cost = costmap_robot_->getCostmap()->getCost(mx, my); + } + return static_cast(cost); +} + +void mkt_algorithm::diff::PredictiveTrajectory::updateCostAtOffset( + TFListenerPtr tf, const std::string &robot_base_frame, const robot_nav_2d_msgs::Pose2DStamped &base_pose, + double x_offset, double y_offset, double &cost_left, double &cost_right) +{ + robot_nav_2d_msgs::Pose2DStamped stamped_pose, transformed_pose; + stamped_pose = base_pose; + stamped_pose.pose.x += x_offset; + stamped_pose.pose.y += y_offset; + + if (robot_nav_2d_utils::transformPose(tf, robot_base_frame, stamped_pose, transformed_pose)) + { + double cost = this->costAtPose(stamped_pose.pose.x, stamped_pose.pose.y); + if (transformed_pose.pose.y < 0) + cost_right = std::max(cost_right, cost); + else if (transformed_pose.pose.y > 0) + cost_left = std::max(cost_left, cost); + } +} + +double mkt_algorithm::diff::PredictiveTrajectory::getEffectiveDistance(const robot_nav_2d_msgs::Pose2DStamped &carrot_pose, + double journey_plan) +{ + double carrot_distance = sqrt(carrot_pose.pose.x * carrot_pose.pose.x + + carrot_pose.pose.y * carrot_pose.pose.y); + + // Avoid division by zero and handle backward motion + if (carrot_distance < 1e-3) + return journey_plan; + + // Project remaining path onto carrot direction + double alignment = fabs(carrot_pose.pose.x / carrot_distance); // cos(angle) + return journey_plan * std::max(0.0, alignment); // Only positive projection +} + +bool mkt_algorithm::diff::PredictiveTrajectory::detectWobbleByCarrotAngle(std::vector &angle_history, double current_angle, + double amplitude_threshold, size_t window_size) +{ + + angle_history.push_back(current_angle); + if ((unsigned int)angle_history.size() > window_size) + angle_history.erase(angle_history.begin()); + + if ((unsigned int)angle_history.size() < 2) + return false; + + double max_angle = *std::max_element(angle_history.begin(), angle_history.end()); + double min_angle = *std::min_element(angle_history.begin(), angle_history.end()); + + double amplitude = max_angle - min_angle; + // if(fabs(amplitude) > amplitude_threshold) + // ROS_INFO_THROTTLE(0.1,"%f %f %f %d %d", amplitude, max_angle , min_angle, (unsigned int)angle_history.size(), (unsigned int)window_size); + return fabs(amplitude) > amplitude_threshold && min_angle * max_angle < 0; +} + +void mkt_algorithm::diff::PredictiveTrajectory::publishMarkers(robot_nav_2d_msgs::Pose2DStamped pose) +{ + const auto &plan_back_pose = compute_plan_.poses.back(); + // const double offset_max = this->min_path_distance_ + costmap_robot_->getCostmap()->getResolution() * 2.0; + // const double offset_min = this->min_path_distance_; + + auto points_rb = interpolateFootprint(pose.pose, costmap_robot_->getRobotFootprint(), costmap_robot_->getCostmap()->getResolution() * 2.0); + for (const auto &point : points_rb) + { + double cost_goal = costAtPose(point.x, point.y); + double dx = point.x - pose.pose.x; + double dy = point.y - pose.pose.y; + double cos_yaw = cos(-pose.pose.theta); + double sin_yaw = sin(-pose.pose.theta); + double y_rel = dx * sin_yaw + dy * cos_yaw; + const double epsilon = min_path_distance_; + if (y_rel > epsilon) + { + cost_left_side_ = std::max(cost_left_side_, cost_goal); + } + else if (y_rel < -epsilon) + { + cost_right_side_ = std::max(cost_right_side_, cost_goal); + } + } + + unsigned int step_footprint = 10; + if ((unsigned int)(compute_plan_.poses.size() - 1) < 10) + { + auto points = interpolateFootprint(plan_back_pose.pose, costmap_robot_->getRobotFootprint(), costmap_robot_->getCostmap()->getResolution() * 2.0); + for (const auto &point : points) + { + double cost_goal = costAtPose(point.x, point.y); + double dx = point.x - plan_back_pose.pose.x; + double dy = point.y - plan_back_pose.pose.y; + double cos_yaw = cos(-plan_back_pose.pose.theta); + double sin_yaw = sin(-plan_back_pose.pose.theta); + double y_rel = dx * sin_yaw + dy * cos_yaw; + const double epsilon = min_path_distance_; + if (y_rel > epsilon) + { + cost_left_goal_ = std::max(cost_left_goal_, cost_goal); + } + else if (y_rel < -epsilon) + { + cost_right_goal_ = std::max(cost_right_goal_, cost_goal); + } + else + center_cost_ = std::max(center_cost_, cost_goal); + } + } + else + { + for (unsigned int i = (unsigned int)(compute_plan_.poses.size() - 1); i > step_footprint; i -= step_footprint) + { + auto points = interpolateFootprint(compute_plan_.poses[i].pose, costmap_robot_->getRobotFootprint(), costmap_robot_->getCostmap()->getResolution() * 2.0); + for (const auto &point : points) + { + double cost_goal = costAtPose(point.x, point.y); + double dx = point.x - compute_plan_.poses[i].pose.x; + double dy = point.y - compute_plan_.poses[i].pose.y; + double cos_yaw = cos(-compute_plan_.poses[i].pose.theta); + double sin_yaw = sin(-compute_plan_.poses[i].pose.theta); + double y_rel = dx * sin_yaw + dy * cos_yaw; + const double epsilon = min_path_distance_; + if (y_rel > epsilon) + { + cost_left_goal_ = std::max(cost_left_goal_, cost_goal); + } + else if (y_rel < -epsilon) + { + cost_right_goal_ = std::max(cost_right_goal_, cost_goal); + } + else + center_cost_ = std::max(center_cost_, cost_goal); + } + double dx = compute_plan_.poses[(unsigned int)(compute_plan_.poses.size() - 1)].pose.x - compute_plan_.poses[i].pose.x; + double dy = compute_plan_.poses[(unsigned int)(compute_plan_.poses.size() - 1)].pose.y - compute_plan_.poses[i].pose.y; + if (hypot(dx, dy) > 1.0) + break; + } + } +} + +score_algorithm::ScoreAlgorithm::Ptr mkt_algorithm::diff::PredictiveTrajectory::create() +{ + return std::make_shared(); +} + +// Register this planner as a GlobalPlanner plugin +BOOST_DLL_ALIAS(mkt_algorithm::diff::PredictiveTrajectory::create, MKTAlgorithmDiffPredictiveTrajectory) \ No newline at end of file diff --git a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory copy.cpp b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory copy.cpp new file mode 100644 index 0000000..bf87617 --- /dev/null +++ b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory copy.cpp @@ -0,0 +1,1320 @@ +#include +#include +#include + +#define LIMIT_VEL_THETA 0.33 + +void mkt_algorithm::diff::PredictiveTrajectory::initialize( + robot::NodeHandle &nh, const std::string &name, TFListenerPtr tf, robot_costmap_2d::Costmap2DROBOT *costmap_robot, const score_algorithm::TrajectoryGenerator::Ptr &traj) +{ + if (!initialized_) + { + nh_ = robot::NodeHandle("~"); + nh_priv_ = robot::NodeHandle(nh, name); + name_ = name; + tf_ = tf; + traj_ = traj; + costmap_robot_ = costmap_robot; + this->getParams(); + nh_.param("publish_topic", enable_publish_, false); + nh_.param("min_approach_linear_velocity", min_approach_linear_velocity_, 0.1); + + footprint_spec_ = costmap_robot_->getRobotFootprint(); + std::vector footprint = costmap_robot_ ? costmap_robot_->getRobotFootprint() : std::vector(); + if (footprint.size() > 1) + { + double min_length = 1e10; + double max_length = 0.0; + for (size_t i = 0; i < footprint.size(); ++i) + { + const robot_geometry_msgs::Point &p1 = footprint[i]; + const robot_geometry_msgs::Point &p2 = footprint[(i + 1) % footprint.size()]; // wrap around to first point + double len = std::hypot(p2.x - p1.x, p2.y - p1.y) / 2.0; + if (len > max_length) + { + max_length = len; + } + if (len < min_length) + { + min_length = len; + } + } + this->min_path_distance_ = min_length > 0.1 ? min_length : 0.1; + this->max_path_distance_ = max_length > 0.1 ? max_length : 0.1; + } + this->initKalmanFilter(); + x_direction_ = y_direction_ = theta_direction_ = 0; + this->initialized_ = true; + robot::log_info("[%s:%d]\n PredictiveTrajectory Initialized successfully", __FILE__, __LINE__); + } +} + +mkt_algorithm::diff::PredictiveTrajectory::~PredictiveTrajectory() +{ + if (kf_) + { + kf_.reset(); + } +} + +void mkt_algorithm::diff::PredictiveTrajectory::initKalmanFilter() +{ + // kalman + last_actuator_update_ = robot::Time::now(); + n_ = 6; // [x, vx, ax, y, vy, ay, theta, vtheta, atheta] + m_ = 2; // measurements: x, y, theta + double dt = control_duration_; + + // Khởi tạo ma trận + A = Eigen::MatrixXd::Identity(n_, n_); + C = Eigen::MatrixXd::Zero(m_, n_); + Q = Eigen::MatrixXd::Zero(n_, n_); + R = Eigen::MatrixXd::Identity(m_, m_); + P = Eigen::MatrixXd::Identity(n_, n_); + + for (int i = 0; i < n_; i += 3) + { + A(i, i + 1) = dt; + A(i, i + 2) = 0.5 * dt * dt; + A(i + 1, i + 2) = dt; + } + + C(0, 0) = 1; + C(1, 3) = 1; + Q(2, 2) = 0.1; + Q(5, 5) = 0.6; + + R(0, 0) = 0.1; + R(1, 1) = 0.2; + + P(3, 3) = 0.4; + P(4, 4) = 0.4; + P(5, 5) = 0.4; + + kf_ = boost::make_shared(dt, A, C, Q, R, P); + Eigen::VectorXd x0(n_); + x0 << 0, 0, 0, 0, 0, 0; + kf_->init(robot::Time::now().toSec(), x0); +} + +void mkt_algorithm::diff::PredictiveTrajectory::getParams() +{ + robot_base_frame_ = nh_priv_.param("robot_base_frame", std::string("base_link")); + nh_priv_.param("avoid_obstacles", avoid_obstacles_, false); + nh_priv_.param("xy_local_goal_tolerance", xy_local_goal_tolerance_, 0.5); + nh_priv_.param("angle_threshold", angle_threshold_, M_PI / 8); + nh_priv_.param("index_samples", index_samples_, 0); + nh_priv_.param("follow_step_path", follow_step_path_, false); + + nh_priv_.param("use_velocity_scaled_lookahead_dist", use_velocity_scaled_lookahead_dist_, false); + nh_priv_.param("lookahead_dist", lookahead_dist_, 0.25); + nh_priv_.param("min_lookahead_dist", min_lookahead_dist_, 0.3); + nh_priv_.param("max_lookahead_dist", max_lookahead_dist_, 0.9); + nh_priv_.param("lookahead_time", lookahead_time_, 1.5); + nh_priv_.param("min_journey_squared", min_journey_squared_, std::numeric_limits::infinity()); + nh_priv_.param("max_journey_squared", max_journey_squared_, std::numeric_limits::infinity()); + + nh_priv_.param("use_rotate_to_heading", use_rotate_to_heading_, false); + nh_priv_.param("rotate_to_heading_min_angle", rotate_to_heading_min_angle_, 0.785); + + nh_priv_.param("rot_stopped_velocity", rot_stopped_velocity_, 0.0); + nh_priv_.param("trans_stopped_velocity", trans_stopped_velocity_, 0.0); + if (trans_stopped_velocity_ <= min_approach_linear_velocity_ || trans_stopped_velocity_ - min_approach_linear_velocity_ < 0.02) + trans_stopped_velocity_ = min_approach_linear_velocity_ + 0.05; + + // Regulated linear velocity scaling + nh_priv_.param("use_regulated_linear_velocity_scaling", use_regulated_linear_velocity_scaling_, false); + nh_priv_.param("regulated_linear_scaling_min_radius", regulated_linear_scaling_min_radius_, 0.9); + nh_priv_.param("regulated_linear_scaling_min_speed", regulated_linear_scaling_min_speed_, 0.25); + + // Inflation cost scaling (Limit velocity by proximity to obstacles) + nh_priv_.param("use_cost_regulated_linear_velocity_scaling", use_cost_regulated_linear_velocity_scaling_, true); + nh_priv_.param("inflation_cost_scaling_factor", inflation_cost_scaling_factor_, 3.0); + nh_priv_.param("cost_scaling_dist", cost_scaling_dist_, 0.6); + nh_priv_.param("cost_scaling_gain", cost_scaling_gain_, 1.0); + if (inflation_cost_scaling_factor_ <= 0.0) + { + robot::log_warning("[%s:%d]\n The value inflation_cost_scaling_factor is incorrectly set, " + "it should be >0. Disabling cost regulated linear velocity scaling."); + use_cost_regulated_linear_velocity_scaling_ = false; + } + double control_frequency = robot_nav_2d_utils::searchAndGetParam(nh_priv_, "controller_frequency", 10); + control_duration_ = 1.0 / control_frequency; + window_size_ = (size_t)(control_frequency * 3.0); + + if (traj_) + { + traj_.get()->getNodeHandle().param("max_vel_x", max_vel_x_, 0.0); + traj_.get()->getNodeHandle().param("min_vel_x", min_vel_x_, 0.0); + traj_.get()->getNodeHandle().param("acc_lim_x", acc_lim_x_, 0.0); + traj_.get()->getNodeHandle().param("decel_lim_x", decel_lim_x_, 0.0); + + traj_.get()->getNodeHandle().param("max_vel_y", max_vel_y_, 0.0); + traj_.get()->getNodeHandle().param("min_vel_y", min_vel_y_, 0.0); + traj_.get()->getNodeHandle().param("acc_lim_y", acc_lim_y_, 0.0); + traj_.get()->getNodeHandle().param("decel_lim_y", decel_lim_y_, 0.0); + + traj_.get()->getNodeHandle().param("max_vel_theta", max_vel_theta_, 0.0); + traj_.get()->getNodeHandle().param("min_vel_theta", min_vel_theta_, 0.0); + traj_.get()->getNodeHandle().param("acc_lim_theta", acc_lim_theta_, 0.0); + traj_.get()->getNodeHandle().param("decel_lim_theta", decel_lim_theta_, 0.0); + } +} + +void mkt_algorithm::diff::PredictiveTrajectory::reset() +{ + if (this->initialized_) + { + robot::log_info("[%s:%d]\n PredictiveTrajectory is reset", __FILE__, __LINE__); + reached_intermediate_goals_.clear(); + start_index_saved_vt_.clear(); + this->clear(); + x_direction_ = y_direction_ = theta_direction_ = 0; + this->follow_step_path_ = false; + this->nav_stop_ = false; + last_actuator_update_ = robot::Time::now(); + prevous_drive_cmd_ = robot_nav_2d_msgs::Twist2D(); + + if (kf_) + { + Eigen::VectorXd x0(n_); + x0 << 0, 0, 0, 0, 0, 0; + kf_->init(robot::Time::now().toSec(), x0); + } + } +} + +void mkt_algorithm::diff::PredictiveTrajectory::stop() +{ + this->nav_stop_ = true; +} + +void mkt_algorithm::diff::PredictiveTrajectory::resume() +{ + if (this->initialized_) + { + if(!this->nav_stop_) + return; + prevous_drive_cmd_ = robot_nav_2d_msgs::Twist2D(); + last_actuator_update_ = robot::Time::now(); + + if (kf_) + { + Eigen::VectorXd x0(n_); + x0 << 0, 0, 0, 0, 0, 0; + kf_->init(robot::Time::now().toSec(), x0); + } + this->nav_stop_ = false; + } +} + +bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity, + const robot_nav_2d_msgs::Pose2DStamped &goal, const robot_nav_2d_msgs::Path2D &global_plan, + double &x_direction, double &y_direction, double &theta_direction) +{ + if (!initialized_) + { + robot::log_error("[%s:%d]\n This planner has not been initialized, please call initialize() before using this planner", __FILE__, __LINE__); + return false; + } + + std::vector footprint = costmap_robot_ ? costmap_robot_->getRobotFootprint() : std::vector(); + if (footprint.size() > 1) + { + double min_length = 1e10; + double max_length = 0.0; + for (size_t i = 0; i < footprint.size(); ++i) + { + const robot_geometry_msgs::Point &p1 = footprint[i]; + const robot_geometry_msgs::Point &p2 = footprint[(i + 1) % footprint.size()]; // wrap around to first point + double len = std::hypot(p2.x - p1.x, p2.y - p1.y) / 2.0; + if (len > max_length) + { + max_length = len; + } + if (len < min_length) + { + min_length = len; + } + } + this->min_path_distance_ = min_length > 0.1 ? min_length : 0.1; + this->max_path_distance_ = max_length > 0.1 ? max_length : 0.1; + } + + if (global_plan.poses.empty() || (unsigned int)global_plan.poses.size() < 2) + { + robot::log_error("[%s:%d]\n The Local plan is empty or less than 1 points %d", __FILE__, __LINE__, (unsigned int)global_plan.poses.size()); + return false; + } + this->getParams(); + + frame_id_path_ = global_plan.header.frame_id; + goal_ = goal; + global_plan_ = global_plan; + + // prune global plan to cut off parts of the past (spatially before the robot) + if (!this->pruneGlobalPlan(tf_, pose, global_plan_, 1.0)) + { + robot::log_error("[%s:%d]\n pruneGlobalPlan Failed", __FILE__, __LINE__); + return false; + } + + double S = std::numeric_limits::infinity(); + S = std::max(costmap_robot_->getCostmap()->getSizeInCellsX() * costmap_robot_->getCostmap()->getResolution() / 2.0, + costmap_robot_->getCostmap()->getSizeInCellsY() * costmap_robot_->getCostmap()->getResolution() / 2.0); + const double min_S = min_lookahead_dist_ * 1.5 + max_path_distance_, max_S = max_lookahead_dist_ * 1.5 + max_path_distance_; + S = std::clamp(S * fabs(velocity.x) * lookahead_time_, min_S, max_S); + compute_plan_.poses.clear(); + + if ((unsigned int)global_plan_.poses.size() == 2) + { + double dx = global_plan_.poses.back().pose.x - global_plan_.poses.front().pose.x; + double dy = global_plan_.poses.back().pose.y - global_plan_.poses.front().pose.y; + if (hypot(dx, dy) <= 2.0 * costmap_robot_->getCostmap()->getResolution()) + { + compute_plan_ = global_plan_; + } + else + { + robot::log_error("[%s:%d]\n The Local Plan has 2 points and hypot between more than is %.3f m", __FILE__, __LINE__, costmap_robot_->getCostmap()->getResolution()); + return false; + } + } + else + { + unsigned int start_index, goal_index; + if (!this->computePlanCommand(pose, velocity, S, global_plan_, start_index, goal_index, compute_plan_)) + { + robot::log_error("[%s:%d]\n computePlanCommand is Failed", __FILE__, __LINE__); + return false; + } + } + + double lookahead_dist = this->getLookAheadDistance(velocity); + transform_plan_.poses.clear(); + if (!this->transformGlobalPlan(tf_, compute_plan_, pose, costmap_robot_, robot_base_frame_, lookahead_dist, transform_plan_)) + { + robot::log_warning("[%s:%d]\n Could not transform the global plan to the frame of the controller", __FILE__, __LINE__); + return false; + } + // else + // { + // robot::log_info("[%s:%d]\n Transform plan journey: %f %f %f", __FILE__, __LINE__, journey(transform_plan_.poses, 0, transform_plan_.poses.size() - 1), min_lookahead_dist_, max_lookahead_dist_); + // } + + x_direction = x_direction_; + y_direction = y_direction_ = 0; + theta_direction = theta_direction_; + + if ((unsigned int)(compute_plan_.poses.size() > 1) && compute_plan_.poses.back().header.seq != global_plan_.poses.back().header.seq) + { + const robot_geometry_msgs::Pose2D p2 = compute_plan_.poses.back().pose; + int index; + for (index = (unsigned int)(compute_plan_.poses.size() - 1); index > 0; index--) + { + robot_geometry_msgs::Pose2D pose = compute_plan_.poses[index].pose; + if (robot_nav_2d_utils::poseDistance(p2, pose) > xy_local_goal_tolerance_) + break; + } + const robot_geometry_msgs::Pose2D p1 = compute_plan_.poses[index].pose; + if (fabs(p2.y - p1.y) > 1e-9 || fabs(p2.x - p1.x) > 1e-9) + { + const double path_angle = atan2(p2.y - p1.y, p2.x - p1.x); + const double dir_path = cos(fabs(path_angle - p2.theta)); + if (fabs(dir_path) > M_PI / 6 || x_direction < 1e-9) + x_direction = dir_path > 0 ? FORWARD : BACKWARD; + } + } + else + { + try + { + auto carrot_pose_it = getLookAheadPoint(velocity, lookahead_dist, transform_plan_); + auto prev_carrot_pose_it = transform_plan_.poses.begin(); + double distance_it = 0; + for (auto it = carrot_pose_it - 1; it != transform_plan_.poses.begin(); --it) + { + double dx = it->pose.x - carrot_pose_it->pose.x; + double dy = it->pose.x - carrot_pose_it->pose.y; + distance_it += std::hypot(dx, dy); + if (distance_it > costmap_robot_->getCostmap()->getResolution()) + { + prev_carrot_pose_it = it; + break; + } + } + + robot_geometry_msgs::Pose front = journey(transform_plan_.poses, 0, transform_plan_.poses.size() - 1) > 5.0 * costmap_robot_->getCostmap()->getResolution() + ? robot_nav_2d_utils::pose2DToPose((*(prev_carrot_pose_it)).pose) + : robot_nav_2d_utils::pose2DToPose(robot_geometry_msgs::Pose2D()); + + robot_geometry_msgs::Pose back = robot_nav_2d_utils::pose2DToPose((*(carrot_pose_it)).pose); + + // teb_local_planner::PoseSE2 start_pose(front); + // teb_local_planner::PoseSE2 goal_pose(back); + // const double dir_path = (goal_pose.position() - start_pose.position()).dot(start_pose.orientationUnitVec()); + const double dir_path = 0.0; + + if (fabs(dir_path) > M_PI / 6 || x_direction < 1e-9) + x_direction = dir_path > 0 ? FORWARD : BACKWARD; + } + catch (std::exception &e) + { + robot::log_error("[%s:%d]\n getLookAheadPoint throw an exception: %s", __FILE__, __LINE__, e.what()); + return false; + } + } + + x_direction_ = x_direction; + y_direction_ = y_direction; + theta_direction_ = theta_direction; + return true; +} + +mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator( + const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity) +{ + mkt_msgs::Trajectory2D result; + result.velocity.x = result.velocity.y = result.velocity.theta = 0.0; + if (!traj_) + return result; + if (compute_plan_.poses.size() < 2) + { + robot::log_warning("[%s:%d]\n Local compute plan is available", __FILE__, __LINE__); + return result; + } + + robot::Time current_time = robot::Time::now(); + double dt = (current_time - last_actuator_update_).toSec(); + last_actuator_update_ = current_time; + + robot_nav_2d_msgs::Twist2D drive_cmd; + double sign_x = sign(x_direction_); + robot_nav_2d_msgs::Twist2D twist; + robot::log_info("[%s:%d] velocity in predictive trajectory: %f %f %f", __FILE__, __LINE__, velocity.x, velocity.y, velocity.theta); + traj_->startNewIteration(velocity); + while (robot::ok() && traj_->hasMoreTwists()) + { + twist = traj_->nextTwist(); + } + drive_cmd.x = std::min(sqrt(twist.x * twist.x), 1.5); + robot::log_info("[%s:%d] twist: %f %f %f", __FILE__, __LINE__, twist.x, twist.y, twist.theta); + robot::log_info("--------------------------------"); + double v_max = sign_x > 0 ? traj_->getTwistLinear(true).x : traj_->getTwistLinear(false).x; + + robot_nav_2d_msgs::Path2D transformed_plan = this->transform_plan_; + result.poses.clear(); + result.poses.reserve(transformed_plan.poses.size()); + for (const auto &pose_stamped : transformed_plan.poses) + { + result.poses.push_back(pose_stamped.pose); + } + + if (transformed_plan.poses.empty()) + { + robot::log_warning("[%s:%d]\n Transformed plan is empty. Cannot determine a localglobal_plan.", __FILE__, __LINE__); + return result; + } + + double lookahead_dist = getLookAheadDistance(velocity); + double tolerance = hypot(pose.pose.x - compute_plan_.poses.front().pose.x, pose.pose.y - compute_plan_.poses.front().pose.y); + + if (transformed_plan.poses.empty()) + { + robot::log_warning("[%s:%d]\n Transformed plan is empty after compute lookahead point", __FILE__, __LINE__); + return result; + } + auto carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan); + bool allow_rotate = false; + nh_priv_.param("allow_rotate", allow_rotate, false); + + // double path_distance_to_rotate = hypot(transformed_plan.poses.front().pose.x, transformed_plan.poses.front().pose.y); + robot_geometry_msgs::Pose2D front = transformed_plan.poses.size() > 3 ? transformed_plan.poses[1].pose : transformed_plan.poses.front().pose; + const double distance_allow_rotate = min_journey_squared_; + const double path_distance_to_rotate = hypot(pose.pose.x - compute_plan_.poses.back().pose.x, pose.pose.y - compute_plan_.poses.back().pose.y); + const double journey_plan = compute_plan_.poses.empty() ? distance_allow_rotate : journey(compute_plan_.poses, 0, compute_plan_.poses.size() - 1); + if (avoid_obstacles_) + allow_rotate = journey_plan >= distance_allow_rotate && + fabs(front.y) <= 0.2 && + (path_distance_to_rotate > max_path_distance_ || path_distance_to_rotate < 2.0 * costmap_robot_->getCostmap()->getResolution()); + else + allow_rotate |= path_distance_to_rotate >= distance_allow_rotate; + + double angle_to_heading; + if (allow_rotate && shouldRotateToPath(transformed_plan, carrot_pose, velocity, angle_to_heading, sign_x)) + { + if (!stopped(velocity, max_vel_theta_ + rot_stopped_velocity_, trans_stopped_velocity_)) + { + if (!stopWithAccLimits(pose, velocity, drive_cmd)) + return result; + } + else + { + rotateToHeading(angle_to_heading, velocity, drive_cmd); + } + } + else + { + const double vel_x_reduce = std::min(fabs(v_max), 0.3); + double carrot_dist2 = carrot_pose.pose.x * carrot_pose.pose.x + carrot_pose.pose.y * carrot_pose.pose.y; + carrot_dist2 = std::max(carrot_dist2, 0.05); + double curvature = carrot_dist2 > 0.1 ? 2.0 * carrot_pose.pose.y / carrot_dist2 : 2.0 * carrot_pose.pose.y / 0.1; + + const auto &plan_back_pose = compute_plan_.poses.back(); + double post_cost = costAtPose(plan_back_pose.pose.x, plan_back_pose.pose.y); + post_cost = std::max(post_cost, center_cost_); + this->applyConstraints(0.0, lookahead_dist, curvature, twist, post_cost, drive_cmd.x, sign_x); + + const double scale = fabs(velocity.x) * lookahead_time_ * 0.9; + const double min_S = min_lookahead_dist_ + max_path_distance_ + scale, max_S = max_lookahead_dist_ + max_path_distance_ + scale; + double d_reduce = std::clamp(journey_plan, min_S, max_S); + double d_begin_reduce = std::clamp(d_reduce * 0.2, 0.4, 1.0); + double cosine_factor_begin_reduce = 0.5 * (1.0 + cos(M_PI * (1.0 - fabs(journey_plan) / d_begin_reduce))); + double v_min = + journey_plan > d_begin_reduce ? vel_x_reduce : (vel_x_reduce - min_approach_linear_velocity_) * cosine_factor_begin_reduce + min_approach_linear_velocity_; + v_min *= sign_x; + + double effective_journey = getEffectiveDistance(carrot_pose, journey_plan); + double decel_factor = computeDecelerationFactor(effective_journey, d_reduce); + double vel_reduce = sign_x > 0 + ? std::min(drive_cmd.x, (drive_cmd.x - v_min) * decel_factor + v_min) + : std::max(drive_cmd.x, (drive_cmd.x - v_min) * decel_factor + v_min); + drive_cmd.x = (journey_plan + max_path_distance_) >= d_reduce ? drive_cmd.x : vel_reduce; + + double v_theta = drive_cmd.x * curvature; + double carrot_angle = std::atan2(carrot_pose.pose.y, carrot_pose.pose.x); + if (detectWobbleByCarrotAngle(angle_history_, carrot_angle, 0.3, window_size_)) + { + carrot_dist2 *= 0.6; + curvature = carrot_dist2 > 0.1 ? 2.0 * carrot_pose.pose.y / carrot_dist2 : 2.0 * carrot_pose.pose.y / 0.1; + v_theta = drive_cmd.x * curvature; + } + if (fabs(v_theta) > LIMIT_VEL_THETA) + { + robot_nav_2d_msgs::Twist2D cmd_vel, cmd_result; + cmd_vel.x = sign_x > 0 + ? std::min(drive_cmd.x, v_theta / std::max(curvature, 0.1)) + : std::max(drive_cmd.x, v_theta / std::min(curvature, -0.1)); + cmd_vel.x = std::clamp(cmd_vel.x, -0.5, 0.5); + this->moveWithAccLimits(velocity, cmd_vel, cmd_result); + drive_cmd.x = std::copysign(cmd_result.x, sign_x); + v_theta = drive_cmd.x * curvature; + } + + if (journey_plan < min_journey_squared_) + { + if (transform_plan_.poses.size() > 2) + { + robot_nav_2d_msgs::Pose2DStamped end = transform_plan_.poses.back(); + robot_nav_2d_msgs::Pose2DStamped start = transform_plan_.poses[transform_plan_.poses.size() - 2]; + double dx = end.pose.x - start.pose.x; + double dy = end.pose.y - start.pose.y; + v_theta = atan2(dy, dx); + if (v_theta > M_PI_2) + v_theta -= M_PI; + else if (v_theta < -M_PI_2) + v_theta += M_PI; + // v_theta *= 0.5; + v_theta = std::clamp(v_theta, -0.02, 0.02); + } + else + v_theta = 0.0; + } + double limit_acc_theta = fabs(v_theta) > 0.15 ? acc_lim_theta_ : 1.8; + double max_acc_vth = velocity.theta + fabs(limit_acc_theta) * dt; + double min_acc_vth = velocity.theta - fabs(limit_acc_theta) * dt; + drive_cmd.theta = std::clamp(v_theta, min_acc_vth, max_acc_vth); + + if (this->nav_stop_) + { + if (!stopped(velocity, rot_stopped_velocity_, trans_stopped_velocity_)) + { + if (!stopWithAccLimits(pose, velocity, drive_cmd)) + return result; + } + else + drive_cmd = {}; + result.velocity = drive_cmd; + return result; + } + + Eigen::VectorXd y(2); + y << drive_cmd.x, drive_cmd.theta; + + // Cập nhật lại A nếu dt thay đổi + for (int i = 0; i < n_; ++i) + for (int j = 0; j < n_; ++j) + A(i, j) = (i == j ? 1.0 : 0.0); + for (int i = 0; i < n_; i += 3) + { + A(i, i + 1) = dt; + A(i, i + 2) = 0.5 * dt * dt; + A(i + 1, i + 2) = dt; + } + kf_->update(y, dt, A); + + // Check if Kalman filter's estimated velocity exceeds v_max + if (avoid_obstacles_ && (cost_left_side_ >= robot_costmap_2d::UNPREFERRED_SPACE || + cost_right_side_ >= robot_costmap_2d::UNPREFERRED_SPACE || + cost_left_goal_ >= robot_costmap_2d::UNPREFERRED_SPACE || + cost_right_goal_ >= robot_costmap_2d::UNPREFERRED_SPACE)) + { + drive_cmd.x = fabs(kf_->state()[0]) > fabs(v_max) ? drive_cmd.x : kf_->state()[0]; + } + else + { + drive_cmd.x = std::clamp(kf_->state()[0], -fabs(v_max), fabs(v_max)); + } + + drive_cmd.x = fabs(drive_cmd.x) >= min_approach_linear_velocity_ ? drive_cmd.x : std::copysign(min_approach_linear_velocity_, sign_x); + drive_cmd.theta = std::clamp(kf_->state()[3], -LIMIT_VEL_THETA, LIMIT_VEL_THETA); + } + + result.velocity = drive_cmd; + prevous_drive_cmd_ = drive_cmd; + return result; +} + +bool mkt_algorithm::diff::PredictiveTrajectory::shouldRotateToPath( + const robot_nav_2d_msgs::Path2D &global_plan, const robot_nav_2d_msgs::Pose2DStamped &carrot_pose, const robot_nav_2d_msgs::Twist2D &velocity, double &angle_to_path, const double &sign_x) +{ + bool curvature = false; + double path_angle = 0; + if (!global_plan.poses.empty()) + { + if ((unsigned)global_plan.poses.size() > 2) + { + const double start_direction_x = global_plan.poses[1].pose.x - global_plan.poses[0].pose.x; + const double start_direction_y = global_plan.poses[1].pose.y - global_plan.poses[0].pose.y; + if (fabs(start_direction_x) > 1e-9 || fabs(start_direction_y) > 1e-9) + { + double start_angle = atan2(start_direction_y, start_direction_x); + for (unsigned int i = 1; i < (unsigned)global_plan.poses.size(); i++) + { + const double current_direction_x = global_plan.poses[i].pose.x - global_plan.poses[i - 1].pose.x; + const double current_direction_y = global_plan.poses[i].pose.y - global_plan.poses[i - 1].pose.y; + if (fabs(current_direction_x) > 1e-9 || fabs(current_direction_y) > 1e-9) + { + double current_angle = atan2(current_direction_y, current_direction_x); + if (fabs(remainder(start_angle - current_angle, 2 * M_PI)) > 1e-9) + { + curvature = true; + break; + } + path_angle = current_angle; + } + } + } + } + } + // ROS_INFO_THROTTLE(0.1,"path_angle %.3f %.3f", path_angle, std::atan2(carrot_pose.pose.y, carrot_pose.pose.x)); + // Whether we should rotate robot to rough path heading + angle_to_path = curvature ? path_angle : std::atan2(carrot_pose.pose.y, carrot_pose.pose.x); + angle_to_path = sign_x < 0 + ? angles::normalize_angle(M_PI + angle_to_path) + : angles::normalize_angle(angle_to_path); + + double heading_linear = sqrt(velocity.x * velocity.x + velocity.y * velocity.y); + // The difference in the path orientation and the starting robot orientation (radians) to trigger a rotate in place. (default: 0.785) + double heading_rotate = rotate_to_heading_min_angle_; + bool is_stopped = stopped(velocity, max_vel_theta_ + rot_stopped_velocity_, trans_stopped_velocity_); + heading_rotate = is_stopped + ? rotate_to_heading_min_angle_ + heading_linear + : std::clamp(heading_rotate + heading_linear, 0.3, M_PI_2); + + bool result = use_rotate_to_heading_ && (is_stopped || sign(angle_to_path) * sign_x < 0) && fabs(angle_to_path) > heading_rotate; + + // if (result) + // { + // ROS_WARN_THROTTLE(0.1, "x %.3f %.3f theta %.3f %.3f", + // velocity.x, trans_stopped_velocity_, velocity.theta, max_vel_theta_ + rot_stopped_velocity_); + // ROS_WARN_THROTTLE(0.1, "%x %.3f %.3f %.3f %.3f %.3f \n", + // is_stopped, path_angle, std::atan2(carrot_pose.pose.y, carrot_pose.pose.x), angle_to_path, heading_rotate, sign_x); + // } + // else + // { + // ROS_INFO_THROTTLE(0.1, "x %.3f %.3f theta %.3f %.3f", + // velocity.x, trans_stopped_velocity_, velocity.theta, max_vel_theta_ + rot_stopped_velocity_); + // ROS_INFO_THROTTLE(0.1, "%x %.3f %.3f %.3f %.3f %.3f \n", + // is_stopped, path_angle,std::atan2(carrot_pose.pose.y, carrot_pose.pose.x) ,angle_to_path, heading_rotate, sign_x); + // } + + return result; +} + +void mkt_algorithm::diff::PredictiveTrajectory::rotateToHeading(const double &angle_to_path, const robot_nav_2d_msgs::Twist2D &velocity, robot_nav_2d_msgs::Twist2D &cmd_vel) +{ + const double dt = control_duration_; + const double theta_direction = angle_to_path > 0.0 ? 1.0 : -1.0; + double vel_yaw = theta_direction * fabs(velocity.theta); + double ang_diff = angle_to_path; + double max_vel_theta = traj_ ? fabs(traj_->getTwistAngular(true).z) : 0.3; + + double angular_decel_zone = 0.3; // rad - khoảng cách bắt đầu giảm tốc + nh_priv_.param("angular_decel_zone", angular_decel_zone, 0.5); + angular_decel_zone += std::clamp( + fabs(max_vel_theta) + (M_PI_2 - fabs(atan2(min_path_distance_, max_path_distance_))), 0.4, M_PI_2); + double zone_begin = std::max(angular_decel_zone * 0.2, 0.2); + double cosine_begin_factor = 0.5 * (1.0 + cos(M_PI * (1.0 - fabs(ang_diff) / zone_begin))); + + double reduce_vel_theta = std::min(max_vel_theta, 0.25 + min_vel_theta_); + reduce_vel_theta = fabs(ang_diff) > zone_begin ? reduce_vel_theta : (reduce_vel_theta - min_vel_theta_) * cosine_begin_factor + min_vel_theta_; + + // === ANGULAR DECELERATION ZONE === + double target_angular_speed = max_vel_theta; + if (fabs(ang_diff) < angular_decel_zone) + { + // ROS_WARN_THROTTLE(0.2,"%f %f %f %f", ang_diff, angular_decel_zone, zone_begin, max_vel_theta); + double cosine_factor = 0.5 * (1.0 + cos(M_PI * (1.0 - fabs(ang_diff) / angular_decel_zone))); + double cosine_speed = max_vel_theta * cosine_factor; + + // Choose deceleration profile + target_angular_speed = cosine_speed; // Smoothest option + + // Ensure minimum speed to avoid stalling + target_angular_speed = std::max(target_angular_speed, reduce_vel_theta); + } + // else + // ROS_INFO_THROTTLE(1,"%f %f %f %f", ang_diff, angular_decel_zone, max_vel_theta, reduce_vel_theta); + + // Apply direction + double v_theta_desired = std::copysign(target_angular_speed, ang_diff); + + // === ACCELERATION LIMITS === + double max_acc_vel = vel_yaw + fabs(acc_lim_theta_) * dt; + double min_acc_vel = vel_yaw - fabs(acc_lim_theta_) * dt; + double v_theta_samp = std::clamp(v_theta_desired, min_acc_vel, max_acc_vel); + + // === STOPPING CONSTRAINT === + double max_speed_to_stop = sqrt(2.0 * fabs(decel_lim_theta_) * fabs(ang_diff)); + v_theta_samp = std::copysign( + std::min(max_speed_to_stop, fabs(v_theta_samp)), ang_diff); + + // === FINAL LIMITS === + v_theta_samp = theta_direction > 0 + ? std::clamp(v_theta_samp, min_vel_theta_, max_vel_theta) + : std::clamp(v_theta_samp, -max_vel_theta, -min_vel_theta_); + + cmd_vel.x = 0.0; + cmd_vel.y = 0.0; + cmd_vel.theta = v_theta_samp; +} + +double mkt_algorithm::diff::PredictiveTrajectory::getLookAheadDistance(const robot_nav_2d_msgs::Twist2D &velocity) +{ + // If using velocity-scaled look ahead distances, find and clamp the dist + // Else, use the static look ahead distance + double lookahead_dist = lookahead_dist_; + if (use_velocity_scaled_lookahead_dist_) + { + lookahead_dist = fabs(velocity.x) * lookahead_time_; + lookahead_dist = std::clamp(lookahead_dist, min_lookahead_dist_, max_lookahead_dist_); + } + + return lookahead_dist; +} + +std::vector::iterator +mkt_algorithm::diff::PredictiveTrajectory::getLookAheadPoint(const robot_nav_2d_msgs::Twist2D &velocity, const double &lookahead_dist, robot_nav_2d_msgs::Path2D global_plan) +{ + if (global_plan.poses.empty()) + { + throw robot_nav_core2::PlannerTFException("The global plan passed to the local planner is empty."); + } + + if ((unsigned)global_plan.poses.size() < 2) + { + auto goal_pose_it = std::prev(global_plan.poses.end()); + return goal_pose_it; + } + unsigned int goal_index = (unsigned)global_plan.poses.size() - 1; + + double start_direction_x = global_plan.poses[1].pose.x - global_plan.poses[0].pose.x; + double start_direction_y = global_plan.poses[1].pose.y - global_plan.poses[0].pose.y; + double end_direction_x = global_plan.poses[goal_index].pose.x - global_plan.poses[goal_index - 1].pose.x; + double end_direction_y = global_plan.poses[goal_index].pose.y - global_plan.poses[goal_index - 1].pose.y; + + // make sure that atan2 is defined + double start_angle = atan2(start_direction_y, start_direction_x); + double end_angle = atan2(end_direction_y, end_direction_x); + double permition_threshold = std::clamp(fabs(end_angle - start_angle) / 2.0, 0.32, M_PI_2); + + for (unsigned int i = 1; i < (int)global_plan.poses.size(); i++) + { + if (fabs(start_direction_x) > 1e-9 || fabs(start_direction_y) > 1e-9) + { + const double current_direction_x = global_plan.poses[i].pose.x - global_plan.poses[i - 1].pose.x; + const double current_direction_y = global_plan.poses[i].pose.y - global_plan.poses[i - 1].pose.y; + + if (fabs(current_direction_x) > 1e-9 || fabs(current_direction_y) > 1e-9) + { + double current_angle = atan2(current_direction_y, current_direction_x); + goal_index = i; + if (fabs(velocity.x) <= trans_stopped_velocity_ && fabs(velocity.theta) >= (0.8 * min_vel_theta_)) + continue; + + if (fabs(remainder(start_angle - current_angle, 2 * M_PI)) >= permition_threshold) + { + goal_index = i; + break; + } + } + } + } + + // Find the first pose which is at a distance greater than the lookahead distance + auto goal_pose_it = std::find_if( + global_plan.poses.begin(), global_plan.poses.begin() + goal_index, + [&](const auto &ps) + { + return std::hypot(ps.pose.x, ps.pose.y) >= lookahead_dist; + }); + + // If the number of poses is not far enough, take the last pose + if (goal_pose_it == global_plan.poses.end()) + { + goal_pose_it = std::prev(global_plan.poses.end()); + } + return goal_pose_it; +} + +robot_geometry_msgs::PointStamped mkt_algorithm::diff::PredictiveTrajectory::createCarrotMsg(const robot_nav_2d_msgs::Pose2DStamped &carrot_pose) +{ + robot_geometry_msgs::PointStamped carrot_msg; + carrot_msg.header = carrot_pose.header; + carrot_msg.point.x = carrot_pose.pose.x; + carrot_msg.point.y = carrot_pose.pose.y; + carrot_msg.point.z = 0.5; // publish right over map to stand out + return carrot_msg; +} + +bool mkt_algorithm::diff::PredictiveTrajectory::pruneGlobalPlan(TFListenerPtr tf, const robot_nav_2d_msgs::Pose2DStamped &pose, robot_nav_2d_msgs::Path2D &global_plan, double dist_behind_robot) +{ + if (global_plan.poses.empty()) + return false; + if (tf == nullptr) + return false; + try + { + // let's get the pose of the robot in the frame of the plan + robot_nav_2d_msgs::Pose2DStamped robot; + if (!robot_nav_2d_utils::transformPose(tf, global_plan.header.frame_id, pose, robot)) + { + throw robot_nav_core2::PlannerTFException("PredictiveTrajectory: Unable to transform robot pose into global plan's frame"); + } + + double dist_thresh_sq = dist_behind_robot * dist_behind_robot; + + // iterate plan until a pose close the robot is found + std::vector::iterator it = global_plan.poses.begin(); + std::vector::iterator erase_end = it; + while (it != global_plan.poses.end()) + { + double dx = robot.pose.x - it->pose.x; + double dy = robot.pose.y - it->pose.y; + double dist_sq = dx * dx + dy * dy; + if (dist_sq < dist_thresh_sq) + { + erase_end = it; + break; + } + ++it; + } + if (erase_end == global_plan.poses.end()) + return false; + + if (erase_end != global_plan.poses.begin()) + global_plan.poses.erase(global_plan.poses.begin(), erase_end); + } + catch (const tf3::TransformException &ex) + { + robot::log_debug("[%s:%d]\n Cannot prune path since no transform is available: %s", __FILE__, __LINE__, ex.what()); + return false; + } + return true; +} + +bool mkt_algorithm::diff::PredictiveTrajectory::transformGlobalPlan( + TFListenerPtr tf, const robot_nav_2d_msgs::Path2D &global_plan, const robot_nav_2d_msgs::Pose2DStamped &pose, + const robot_costmap_2d::Costmap2DROBOT *costmap, const std::string &robot_base_frame, double max_plan_length, + robot_nav_2d_msgs::Path2D &transformed_plan) +{ + // this method is a slightly modified version of base_local_planner/goal_functions.h + transformed_plan.poses.clear(); + transformed_plan.header.stamp = pose.header.stamp; + transformed_plan.header.frame_id = robot_base_frame; + + if (global_plan.poses.empty()) + return false; + + if (tf == nullptr) + return false; + + if (costmap == nullptr || costmap->getCostmap() == nullptr) + return false; + + try + { + if (global_plan.poses.empty()) + { + robot::log_error("[%s:%d]\n Received plan with zero length", __FILE__, __LINE__); + return false; + } + + // let's get the pose of the robot in the frame of the plan + robot_nav_2d_msgs::Pose2DStamped robot_pose; + if (!robot_nav_2d_utils::transformPose(tf, global_plan.header.frame_id, pose, robot_pose)) + { + throw robot_nav_core2::PlannerTFException("PredictiveTrajectory: Unable to transform robot pose into global plan's frame"); + } + + // we'll discard points on the plan that are outside the local costmap + double dist_threshold = std::max(costmap->getCostmap()->getSizeInCellsX() * costmap->getCostmap()->getResolution() / 2.0, + costmap->getCostmap()->getSizeInCellsY() * costmap->getCostmap()->getResolution() / 2.0); + + dist_threshold *= 0.85; // just consider 85% of the costmap size to better incorporate point obstacle that are + double sq_dist_threshold = dist_threshold * dist_threshold; + // located on the border of the local costmap + + int i = 0; + double sq_dist = std::numeric_limits::infinity(); + + // we need to loop to a point on the plan that is within a certain distance of the robot + bool robot_reached = false; + for (int j = 0; j < (int)global_plan.poses.size(); ++j) + { + double x_diff = robot_pose.pose.x - global_plan.poses[j].pose.x; + double y_diff = robot_pose.pose.y - global_plan.poses[j].pose.y; + double new_sq_dist = x_diff * x_diff + y_diff * y_diff; + if (robot_reached && new_sq_dist > sq_dist_threshold) + { + break; + } // force stop if we have reached the costmap border + + if (new_sq_dist < sq_dist) // find closest distance + { + sq_dist = new_sq_dist; + i = j; + if (sq_dist < costmap->getCostmap()->getResolution()) // 5 cm to the robot; take the immediate local minima; if it's not the global + robot_reached = true; // minima, probably means that there's a loop in the path, and so we prefer this + } + } + + double plan_length = 0; // check cumulative Euclidean distance along the plan + double x_direction_saved = 0.0; + // now we'll transform until points are outside of our distance threshold + while (i < (int)global_plan.poses.size() && sq_dist <= sq_dist_threshold && + (max_plan_length <= 0 || plan_length <= max_plan_length)) + { + robot_nav_2d_msgs::Pose2DStamped stamped_pose; + stamped_pose.pose = global_plan.poses[i].pose; + stamped_pose.header.frame_id = global_plan.header.frame_id; + + robot_nav_2d_msgs::Pose2DStamped newer_pose; + if (!robot_nav_2d_utils::transformPose(tf, robot_base_frame, stamped_pose, newer_pose)) + { + ++i; + continue; + } + transformed_plan.poses.push_back(newer_pose); + + double x_diff = robot_pose.pose.x - global_plan.poses[i].pose.x; + double y_diff = robot_pose.pose.y - global_plan.poses[i].pose.y; + sq_dist = x_diff * x_diff + y_diff * y_diff; + + // Calculate distance to previous pose + if (i > 0 && max_plan_length > 0) + { + robot_geometry_msgs::Pose2D p1 = global_plan.poses[i].pose; + robot_geometry_msgs::Pose2D p2 = global_plan.poses[i - 1].pose; + plan_length += std::sqrt(std::pow(p1.x - p2.x, 2) + std::pow(p1.y - p2.y, 2)); + if (fabs(p2.y - p1.y) > 1e-9 || fabs(p2.x - p1.x) > 1e-9) + { + const double egde_angle = atan2(p1.y - p2.y, p1.x - p2.x); + const double target_direction = cos(fabs(egde_angle - p1.theta)); + if (target_direction * x_direction_saved < 0.0) + { + plan_length = 0; + } + x_direction_saved = target_direction; + } + } + ++i; + } + } + catch (tf3::LookupException &ex) + { + robot::log_error("[%s:%d]\n No Transform available Error: %s", __FILE__, __LINE__, ex.what()); + return false; + } + catch (tf3::ConnectivityException &ex) + { + robot::log_error("[%s:%d]\n Connectivity Error: %s", __FILE__, __LINE__, ex.what()); + return false; + } + catch (tf3::ExtrapolationException &ex) + { + robot::log_error("[%s:%d]\n Extrapolation Error: %s", __FILE__, __LINE__, ex.what()); + if (global_plan.poses.size() > 0) + robot::log_error("[%s:%d]\n Robot Frame: %s Plan Frame size %d: %s", __FILE__, __LINE__, robot_base_frame.c_str(), (unsigned int)global_plan.poses.size(), global_plan.header.frame_id.c_str()); + + return false; + } + return true; +} + +void mkt_algorithm::diff::PredictiveTrajectory::moveWithAccLimits( + const robot_nav_2d_msgs::Twist2D &velocity, const robot_nav_2d_msgs::Twist2D &cmd_vel, robot_nav_2d_msgs::Twist2D &cmd_vel_result) +{ + const double dt = control_duration_; + + // --- X axis --- + double min_vel_x = traj_ ? min_vel_x_ : fabs(traj_->getTwistLinear(false).x); + double max_vel_x = traj_ ? max_vel_x_ : fabs(traj_->getTwistLinear(true).x); + + double vx = cmd_vel.x > 0.0 ? std::min(max_vel_x, std::max(min_vel_x, cmd_vel.x)) : std::max(-max_vel_x, std::min(-min_vel_x, cmd_vel.x)); + + double max_acc_vx = velocity.x + fabs(acc_lim_x_) * dt; + double min_acc_vx = velocity.x - fabs(decel_lim_x_) * dt; + vx = std::clamp(vx, min_acc_vx, max_acc_vx); + + // --- Y axis --- + double min_vel_y = traj_ ? min_vel_y_ : fabs(traj_->getTwistLinear(false).y); + double max_vel_y = traj_ ? max_vel_y_ : fabs(traj_->getTwistLinear(true).y); + double vy = cmd_vel.y > 0.0 ? std::min(max_vel_y, std::max(min_vel_y, cmd_vel.y)) : std::max(-max_vel_y, std::min(-min_vel_y, cmd_vel.y)); + + double max_acc_vy = velocity.y + fabs(acc_lim_y_) * dt; + double min_acc_vy = velocity.y - fabs(decel_lim_y_) * dt; + vy = std::clamp(vy, min_acc_vy, max_acc_vy); + // --- Assign result --- + cmd_vel_result.x = vx; + cmd_vel_result.y = vy; + // cmd_vel_result.theta = vth; +} + +bool mkt_algorithm::diff::PredictiveTrajectory::stopWithAccLimits(const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity, robot_nav_2d_msgs::Twist2D &cmd_vel) +{ + // slow down with the maximum possible acceleration... we should really use the frequency that we're running at to determine what is feasible + // but we'll use a tenth of a second to be consistent with the implementation of the local planner. + const double dt = control_duration_; + double vx = sign(velocity.x) * std::max(0.0, (fabs(velocity.x) - fabs(decel_lim_x_) * dt)); + double vy = sign(velocity.y) * std::max(0.0, (fabs(velocity.y) - fabs(decel_lim_y_) * dt)); + + double vel_yaw = velocity.theta; + double vth = sign(vel_yaw) * std::max(0.0, (fabs(vel_yaw) - fabs(decel_lim_theta_) * dt)); + + // we do want to check whether or not the command is valid + cmd_vel.x = vx; + cmd_vel.y = vy; + cmd_vel.theta = vth; + return true; +} + +void mkt_algorithm::diff::PredictiveTrajectory::applyConstraints( + const double &dist_error, const double &lookahead_dist, + const double &curvature, const robot_nav_2d_msgs::Twist2D &velocity, + const double &pose_cost, double &linear_vel, double &sign_x) +{ + double curvature_vel = linear_vel; + double cost_vel = linear_vel; + double approach_vel = linear_vel; + + // std::stringstream ss; + // ss << linear_vel << " "; + // limit the linear velocity by curvature + if (use_regulated_linear_velocity_scaling_) + { + const double &min_rad = regulated_linear_scaling_min_radius_; + const double radius = curvature > 1e-9 ? fabs(1.0 / curvature) : min_rad; + if (radius < min_rad) + { + curvature_vel *= 1.0 - (fabs(radius - min_rad) / min_rad); + robot_nav_2d_msgs::Twist2D cmd, result; + cmd.x = curvature_vel; + this->moveWithAccLimits(velocity, cmd, result); + curvature_vel = result.x; + linear_vel = std::max(linear_vel, regulated_linear_scaling_min_speed_); + } + } + // ss << linear_vel << " "; + // limit the linear velocity by proximity to obstacles + if (use_cost_regulated_linear_velocity_scaling_ && + pose_cost != static_cast(robot_costmap_2d::NO_INFORMATION) && + pose_cost != static_cast(robot_costmap_2d::FREE_SPACE)) + { + const double inscribed_radius = costmap_robot_->getLayeredCostmap()->getInscribedRadius(); + const double min_distance_to_obstacle = (-1.0 / inflation_cost_scaling_factor_) * + std::log(pose_cost / (robot_costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1)) + + inscribed_radius; + + if (min_distance_to_obstacle < cost_scaling_dist_) + { + cost_vel *= cost_scaling_gain_ * min_distance_to_obstacle / cost_scaling_dist_; + } + robot_nav_2d_msgs::Twist2D cmd, result; + cmd.x = cost_vel; + this->moveWithAccLimits(velocity, cmd, result); + cost_vel = result.x; + linear_vel = std::min(cost_vel, curvature_vel); + } + // ss << linear_vel << " "; + // Use the lowest of the 2 constraint heuristics, but above the minimum translational speed + // if the actual lookahead distance is shorter than requested, that means we're at the + // end of the path. We'll scale linear velocity by error to slow to a smooth stop. + // This expression is eq. to + // (1) holding time to goal, t, constant using the theoretical + // lookahead distance and proposed velocity and + // (2) using t with the actual lookahead + // distance to scale the velocity (e.g. t = lookahead / velocity, v = carrot / t). + + double dist_error_limit = costmap_robot_ != nullptr && costmap_robot_->getCostmap() != nullptr + ? 2.0 * costmap_robot_->getCostmap()->getResolution() + : 0.1; + if (dist_error > dist_error_limit) + { + double velocity_scaling = lookahead_dist > 1e-9 ? 1.0 - (dist_error / lookahead_dist) : 1.0; + double unbounded_vel = approach_vel * velocity_scaling; + if (unbounded_vel < min_approach_linear_velocity_) + { + approach_vel = min_approach_linear_velocity_; + } + else + { + approach_vel *= velocity_scaling; + } + + // Use the lowest velocity between approach and other constraints, if all overlapping + robot_nav_2d_msgs::Twist2D cmd, result; + cmd.x = approach_vel; + this->moveWithAccLimits(velocity, cmd, result); + approach_vel = result.x; + linear_vel = std::min(linear_vel, approach_vel); + } + + // ss << linear_vel << " "; + + // Limit linear velocities to be valid + double min_vel_x = traj_ ? min_vel_x_ : fabs(traj_->getTwistLinear(false).x); + double max_vel_x = traj_ ? max_vel_x_ : fabs(traj_->getTwistLinear(true).x); + double min_vel_y = traj_ ? min_vel_y_ : fabs(traj_->getTwistLinear(false).y); + double max_vel_y = traj_ ? max_vel_y_ : fabs(traj_->getTwistLinear(true).y); + double max_linear_vel = sqrt(max_vel_x * max_vel_x + max_vel_y * max_vel_y); + double min_linear_vel = sqrt(min_vel_x * min_vel_x + min_vel_y * min_vel_y); + double desired_linear_vel = sign_x > 0 ? fabs(max_linear_vel) : fabs(min_linear_vel); + linear_vel = std::clamp(fabs(linear_vel), min_approach_linear_velocity_, desired_linear_vel); + linear_vel = sign_x * linear_vel; + // ss << linear_vel << " "; + // ROS_INFO_STREAM_THROTTLE(0.1, ss.str()); +} + +std::vector +mkt_algorithm::diff::PredictiveTrajectory::interpolateFootprint(robot_geometry_msgs::Pose2D pose, std::vector footprint, double resolution) +{ + + // Dịch sang tọa độ tuyệt đối + std::vector abs_footprint; + double cos_th = std::cos(pose.theta); + double sin_th = std::sin(pose.theta); + for (auto pt : footprint) + { + pt.x *= 1.2; + pt.y *= 1.2; + robot_geometry_msgs::Point abs_pt; + abs_pt.x = pose.x + pt.x * cos_th - pt.y * sin_th; + abs_pt.y = pose.y + pt.x * sin_th + pt.y * cos_th; + abs_footprint.push_back(abs_pt); + } + + std::vector points; + for (size_t i = 0; i < abs_footprint.size(); ++i) + { + const robot_geometry_msgs::Point &start = abs_footprint[i]; + const robot_geometry_msgs::Point &end = abs_footprint[(i + 1) % abs_footprint.size()]; + + double dx = end.x - start.x; + double dy = end.y - start.y; + double distance = std::hypot(dx, dy); + int steps = std::max(1, static_cast(std::floor(distance / resolution))); + + for (int j = 0; j <= steps; ++j) + { + if (j == steps && i != abs_footprint.size() - 1) + continue; // tránh lặp + double t = static_cast(j) / steps; + robot_geometry_msgs::Point pt; + pt.x = start.x + t * dx; + pt.y = start.y + t * dy; + points.push_back(pt); + } + } + return points; +} + +double mkt_algorithm::diff::PredictiveTrajectory::costAtPose(const double &x, const double &y) +{ + unsigned int mx, my; + unsigned char cost; + if (costmap_robot_->getCostmap()->worldToMap(x, y, mx, my)) + { + cost = costmap_robot_->getCostmap()->getCost(mx, my); + } + return static_cast(cost); +} + +void mkt_algorithm::diff::PredictiveTrajectory::updateCostAtOffset( + TFListenerPtr tf, const std::string &robot_base_frame, const robot_nav_2d_msgs::Pose2DStamped &base_pose, + double x_offset, double y_offset, double &cost_left, double &cost_right) +{ + robot_nav_2d_msgs::Pose2DStamped stamped_pose, transformed_pose; + stamped_pose = base_pose; + stamped_pose.pose.x += x_offset; + stamped_pose.pose.y += y_offset; + + if (robot_nav_2d_utils::transformPose(tf, robot_base_frame, stamped_pose, transformed_pose)) + { + double cost = this->costAtPose(stamped_pose.pose.x, stamped_pose.pose.y); + if (transformed_pose.pose.y < 0) + cost_right = std::max(cost_right, cost); + else if (transformed_pose.pose.y > 0) + cost_left = std::max(cost_left, cost); + } +} + +double mkt_algorithm::diff::PredictiveTrajectory::computeDecelerationFactor(double remaining_distance, double decel_distance) +{ + if (remaining_distance >= decel_distance) + { + return 1.0; // Full speed + } + + // Smooth transition using cosine function + double ratio = fabs(remaining_distance / decel_distance); + return 0.5 * (1.0 + cos(M_PI * (1.0 - ratio))); // Smooth from 1 to 0 +} + +double mkt_algorithm::diff::PredictiveTrajectory::getEffectiveDistance(const robot_nav_2d_msgs::Pose2DStamped &carrot_pose, + double journey_plan) +{ + double carrot_distance = sqrt(carrot_pose.pose.x * carrot_pose.pose.x + + carrot_pose.pose.y * carrot_pose.pose.y); + + // Avoid division by zero and handle backward motion + if (carrot_distance < 1e-3) + return journey_plan; + + // Project remaining path onto carrot direction + double alignment = fabs(carrot_pose.pose.x / carrot_distance); // cos(angle) + return journey_plan * std::max(0.0, alignment); // Only positive projection +} + +bool mkt_algorithm::diff::PredictiveTrajectory::detectWobbleByCarrotAngle(std::vector &angle_history, double current_angle, + double amplitude_threshold, size_t window_size) +{ + + angle_history.push_back(current_angle); + if ((unsigned int)angle_history.size() > window_size) + angle_history.erase(angle_history.begin()); + + if ((unsigned int)angle_history.size() < 2) + return false; + + double max_angle = *std::max_element(angle_history.begin(), angle_history.end()); + double min_angle = *std::min_element(angle_history.begin(), angle_history.end()); + + double amplitude = max_angle - min_angle; + // if(fabs(amplitude) > amplitude_threshold) + // ROS_INFO_THROTTLE(0.1,"%f %f %f %d %d", amplitude, max_angle , min_angle, (unsigned int)angle_history.size(), (unsigned int)window_size); + return fabs(amplitude) > amplitude_threshold && min_angle * max_angle < 0; +} + +void mkt_algorithm::diff::PredictiveTrajectory::publishMarkers(robot_nav_2d_msgs::Pose2DStamped pose) +{ + const auto &plan_back_pose = compute_plan_.poses.back(); + // const double offset_max = this->min_path_distance_ + costmap_robot_->getCostmap()->getResolution() * 2.0; + // const double offset_min = this->min_path_distance_; + + auto points_rb = interpolateFootprint(pose.pose, costmap_robot_->getRobotFootprint(), costmap_robot_->getCostmap()->getResolution() * 2.0); + for (const auto &point : points_rb) + { + double cost_goal = costAtPose(point.x, point.y); + double dx = point.x - pose.pose.x; + double dy = point.y - pose.pose.y; + double cos_yaw = cos(-pose.pose.theta); + double sin_yaw = sin(-pose.pose.theta); + double y_rel = dx * sin_yaw + dy * cos_yaw; + const double epsilon = min_path_distance_; + if (y_rel > epsilon) + { + cost_left_side_ = std::max(cost_left_side_, cost_goal); + } + else if (y_rel < -epsilon) + { + cost_right_side_ = std::max(cost_right_side_, cost_goal); + } + } + + unsigned int step_footprint = 10; + if ((unsigned int)(compute_plan_.poses.size() - 1) < 10) + { + auto points = interpolateFootprint(plan_back_pose.pose, costmap_robot_->getRobotFootprint(), costmap_robot_->getCostmap()->getResolution() * 2.0); + for (const auto &point : points) + { + double cost_goal = costAtPose(point.x, point.y); + double dx = point.x - plan_back_pose.pose.x; + double dy = point.y - plan_back_pose.pose.y; + double cos_yaw = cos(-plan_back_pose.pose.theta); + double sin_yaw = sin(-plan_back_pose.pose.theta); + double y_rel = dx * sin_yaw + dy * cos_yaw; + const double epsilon = min_path_distance_; + if (y_rel > epsilon) + { + cost_left_goal_ = std::max(cost_left_goal_, cost_goal); + } + else if (y_rel < -epsilon) + { + cost_right_goal_ = std::max(cost_right_goal_, cost_goal); + } + else + center_cost_ = std::max(center_cost_, cost_goal); + } + } + else + { + for (unsigned int i = (unsigned int)(compute_plan_.poses.size() - 1); i > step_footprint; i -= step_footprint) + { + auto points = interpolateFootprint(compute_plan_.poses[i].pose, costmap_robot_->getRobotFootprint(), costmap_robot_->getCostmap()->getResolution() * 2.0); + for (const auto &point : points) + { + double cost_goal = costAtPose(point.x, point.y); + double dx = point.x - compute_plan_.poses[i].pose.x; + double dy = point.y - compute_plan_.poses[i].pose.y; + double cos_yaw = cos(-compute_plan_.poses[i].pose.theta); + double sin_yaw = sin(-compute_plan_.poses[i].pose.theta); + double y_rel = dx * sin_yaw + dy * cos_yaw; + const double epsilon = min_path_distance_; + if (y_rel > epsilon) + { + cost_left_goal_ = std::max(cost_left_goal_, cost_goal); + } + else if (y_rel < -epsilon) + { + cost_right_goal_ = std::max(cost_right_goal_, cost_goal); + } + else + center_cost_ = std::max(center_cost_, cost_goal); + } + double dx = compute_plan_.poses[(unsigned int)(compute_plan_.poses.size() - 1)].pose.x - compute_plan_.poses[i].pose.x; + double dy = compute_plan_.poses[(unsigned int)(compute_plan_.poses.size() - 1)].pose.y - compute_plan_.poses[i].pose.y; + if (hypot(dx, dy) > 1.0) + break; + } + } +} + +score_algorithm::ScoreAlgorithm::Ptr mkt_algorithm::diff::PredictiveTrajectory::create() +{ + return std::make_shared(); +} + +// Register this planner as a GlobalPlanner plugin +BOOST_DLL_ALIAS(mkt_algorithm::diff::PredictiveTrajectory::create, MKTAlgorithmDiffPredictiveTrajectory) \ No newline at end of file diff --git a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp index 70a6a79..bf87617 100644 --- a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp +++ b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp @@ -383,7 +383,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator( robot::log_warning("[%s:%d]\n Local compute plan is available", __FILE__, __LINE__); return result; } - + robot::Time current_time = robot::Time::now(); double dt = (current_time - last_actuator_update_).toSec(); last_actuator_update_ = current_time; @@ -391,15 +391,25 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator( robot_nav_2d_msgs::Twist2D drive_cmd; double sign_x = sign(x_direction_); robot_nav_2d_msgs::Twist2D twist; + robot::log_info("[%s:%d] velocity in predictive trajectory: %f %f %f", __FILE__, __LINE__, velocity.x, velocity.y, velocity.theta); traj_->startNewIteration(velocity); - while (traj_->hasMoreTwists()) + while (robot::ok() && traj_->hasMoreTwists()) { twist = traj_->nextTwist(); } drive_cmd.x = std::min(sqrt(twist.x * twist.x), 1.5); + robot::log_info("[%s:%d] twist: %f %f %f", __FILE__, __LINE__, twist.x, twist.y, twist.theta); + robot::log_info("--------------------------------"); double v_max = sign_x > 0 ? traj_->getTwistLinear(true).x : traj_->getTwistLinear(false).x; robot_nav_2d_msgs::Path2D transformed_plan = this->transform_plan_; + result.poses.clear(); + result.poses.reserve(transformed_plan.poses.size()); + for (const auto &pose_stamped : transformed_plan.poses) + { + result.poses.push_back(pose_stamped.pose); + } + if (transformed_plan.poses.empty()) { robot::log_warning("[%s:%d]\n Transformed plan is empty. Cannot determine a localglobal_plan.", __FILE__, __LINE__); diff --git a/src/Algorithms/Libraries/mkt_algorithm/src/diff/pure_pursuit.cpp b/src/Algorithms/Libraries/mkt_algorithm/src/diff/pure_pursuit.cpp new file mode 100644 index 0000000..8201214 --- /dev/null +++ b/src/Algorithms/Libraries/mkt_algorithm/src/diff/pure_pursuit.cpp @@ -0,0 +1,52 @@ +#include + +void mkt_algorithm::diff::PurePursuit::computePurePursuit(const double &velocity_min, + const double &velocity_max, + const double &linear_vel, + const robot_nav_2d_msgs::Pose2DStamped &carrot_pose, + const double &min_dist2, + const double &curvature_dist2_floor, + const double &dist2_override) +{ + const double vel_x_reduce = std::min(fabs(velocity_max), 0.3); + double carrot_dist2 = carrot_pose.pose.x * carrot_pose.pose.x + carrot_pose.pose.y * carrot_pose.pose.y; + carrot_dist2 = std::max(carrot_dist2, 0.05); + double curvature = carrot_dist2 > 0.1 ? 2.0 * carrot_pose.pose.y / carrot_dist2 : 2.0 * carrot_pose.pose.y / 0.1; + + if (max_lateral_accel_ > 1e-6) + { + const double curvature_abs = std::max(fabs(curvature), 1e-6); + const double v_lateral_limit = sqrt(max_lateral_accel_ / curvature_abs); + drive_cmd.x = sign_x > 0 ? std::min(drive_cmd.x, v_lateral_limit) : std::max(drive_cmd.x, -v_lateral_limit); + } + + const auto &plan_back_pose = compute_plan_.poses.back(); + double post_cost = costAtPose(plan_back_pose.pose.x, plan_back_pose.pose.y); + post_cost = std::max(post_cost, center_cost_); + this->applyConstraints(0.0, lookahead_dist, curvature, twist, post_cost, drive_cmd.x, sign_x); + + const double scale = fabs(velocity.x) * lookahead_time_ * 0.9; + const double min_S = min_lookahead_dist_ + max_path_distance_ + scale, max_S = max_lookahead_dist_ + max_path_distance_ + scale; + double d_reduce = std::clamp(journey_plan, min_S, max_S); + double d_begin_reduce = std::clamp(d_reduce * 0.2, 0.4, 1.0); + double cosine_factor_begin_reduce = 0.5 * (1.0 + cos(M_PI * (1.0 - fabs(journey_plan) / d_begin_reduce))); + double v_min = + journey_plan > d_begin_reduce ? vel_x_reduce : (vel_x_reduce - min_approach_linear_velocity_) * cosine_factor_begin_reduce + min_approach_linear_velocity_; + v_min *= sign_x; + + double effective_journey = getEffectiveDistance(carrot_pose, journey_plan); + double decel_factor = computeDecelerationFactor(effective_journey, d_reduce); + double vel_reduce = sign_x > 0 + ? std::min(drive_cmd.x, (drive_cmd.x - v_min) * decel_factor + v_min) + : std::max(drive_cmd.x, (drive_cmd.x - v_min) * decel_factor + v_min); + drive_cmd.x = (journey_plan + max_path_distance_) >= d_reduce ? drive_cmd.x : vel_reduce; + + double v_theta = drive_cmd.x * curvature; + double carrot_angle = std::atan2(carrot_pose.pose.y, carrot_pose.pose.x); + if (detectWobbleByCarrotAngle(angle_history_, carrot_angle, 0.3, window_size_)) + { + carrot_dist2 *= 0.6; + curvature = carrot_dist2 > 0.1 ? 2.0 * carrot_pose.pose.y / carrot_dist2 : 2.0 * carrot_pose.pose.y / 0.1; + v_theta = drive_cmd.x * curvature; + } +} diff --git a/src/Algorithms/Libraries/mkt_plugins/include/mkt_plugins/kinematic_parameters.h b/src/Algorithms/Libraries/mkt_plugins/include/mkt_plugins/kinematic_parameters.h index 319792a..253f43c 100644 --- a/src/Algorithms/Libraries/mkt_plugins/include/mkt_plugins/kinematic_parameters.h +++ b/src/Algorithms/Libraries/mkt_plugins/include/mkt_plugins/kinematic_parameters.h @@ -270,6 +270,23 @@ namespace mkt_plugins using Ptr = std::shared_ptr; protected: + + /** + * @brief Configure the kinematic parameters + * @param nh NodeHandle + * + * Configures the kinematic parameters from the given NodeHandle. + */ + void configure(const robot::NodeHandle &nh); + + /** + * @brief Reconfigure the kinematic parameters + * @param nh NodeHandle + * + * Reconfigures the kinematic parameters from the given NodeHandle. + */ + void reconfigure(const robot::NodeHandle &nh); + // For parameter descriptions, see cfg/KinematicParams.cfg int xytheta_direct_[3]; double min_vel_x_, min_vel_y_; diff --git a/src/Algorithms/Libraries/mkt_plugins/include/mkt_plugins/one_d_velocity_iterator.h b/src/Algorithms/Libraries/mkt_plugins/include/mkt_plugins/one_d_velocity_iterator.h index eb6b396..b49cd6b 100644 --- a/src/Algorithms/Libraries/mkt_plugins/include/mkt_plugins/one_d_velocity_iterator.h +++ b/src/Algorithms/Libraries/mkt_plugins/include/mkt_plugins/one_d_velocity_iterator.h @@ -116,9 +116,13 @@ namespace mkt_plugins * current velocity within acc_time seconds, respecting acceleration/deceleration limits. * The velocities range from min_vel_ to max_vel_ (projected from current velocity). */ - OneDVelocityIterator(double current, int direct, double min, double max, double acc_limit, double decel_limit, double acc_time, - int num_samples) + OneDVelocityIterator( + std::string name, double current, int direct, double min, double max, double acc_limit, double decel_limit, double acc_time, int num_samples) + : name_(name) { + if(name_ == "x_it_") + robot::log_warning("[%s:%d] one_d_velocity_iterator: [%s] %f %d %f %f %f %f %f %d", + __FILE__, __LINE__, name_.c_str(), current, direct, min, max, acc_limit, decel_limit, acc_time, num_samples); // if (current < min) // { // current = min; @@ -203,8 +207,6 @@ namespace mkt_plugins */ bool isFinished() const { - // if(name_ == std::string("th_it_")) - // ROS_INFO("%s %f %f", name_.c_str(), current_, max_vel_ + EPSILON); double limit_vel = direct_ > 0? max_vel_ : min_vel_; return fabs(current_) > fabs(limit_vel) + EPSILON; } diff --git a/src/Algorithms/Libraries/mkt_plugins/src/kinematic_parameters.cpp b/src/Algorithms/Libraries/mkt_plugins/src/kinematic_parameters.cpp index 84ba7ac..5af06df 100644 --- a/src/Algorithms/Libraries/mkt_plugins/src/kinematic_parameters.cpp +++ b/src/Algorithms/Libraries/mkt_plugins/src/kinematic_parameters.cpp @@ -54,10 +54,48 @@ namespace mkt_plugins setDecelerationAsNeeded(nh, "y"); setDecelerationAsNeeded(nh, "theta"); - + configure(nh); xytheta_direct_[0] = xytheta_direct_[1] = xytheta_direct_[2] = 1; } + + void KinematicParameters::configure(const robot::NodeHandle &nh) + { + nh.param("max_vel_x", original_max_vel_x_, 0.0); + nh.param("max_vel_y", original_max_vel_y_, 0.0); + nh.param("max_vel_theta", original_max_vel_theta_, 0.0); + nh.param("min_vel_x", original_min_vel_x_, 0.0); + nh.param("min_vel_y", original_min_vel_y_, 0.0); + nh.param("min_speed_xy", original_min_speed_xy_, 0.0); + nh.param("max_speed_xy", original_max_speed_xy_, 0.0); + nh.param("min_speed_theta", original_min_speed_theta_, 0.0); + nh.param("acc_lim_x", original_acc_lim_x_, 0.0); + nh.param("acc_lim_y", original_acc_lim_y_, 0.0); + nh.param("acc_lim_theta", original_acc_lim_theta_, 0.0); + nh.param("decel_lim_x", original_decel_lim_x_, 0.0); + nh.param("decel_lim_y", original_decel_lim_y_, 0.0); + nh.param("decel_lim_theta", original_decel_lim_theta_, 0.0); + reconfigure(nh); + } + + void KinematicParameters::reconfigure(const robot::NodeHandle &nh) + { + nh.param("max_vel_x", max_vel_x_, 0.0); + nh.param("max_vel_y", max_vel_y_, 0.0); + nh.param("max_vel_theta", max_vel_theta_, 0.0); + nh.param("min_vel_x", min_vel_x_, 0.0); + nh.param("min_vel_y", min_vel_y_, 0.0); + nh.param("min_speed_xy", min_speed_xy_, 0.0); + nh.param("max_speed_xy", max_speed_xy_, 0.0); + nh.param("min_speed_theta", min_speed_theta_, 0.0); + nh.param("acc_lim_x", acc_lim_x_, 0.0); + nh.param("acc_lim_y", acc_lim_y_, 0.0); + nh.param("acc_lim_theta", acc_lim_theta_, 0.0); + nh.param("decel_lim_x", decel_lim_x_, 0.0); + nh.param("decel_lim_y", decel_lim_y_, 0.0); + nh.param("decel_lim_theta", decel_lim_theta_, 0.0); + } + void KinematicParameters::setDirect(int *xytheta_direct) { xytheta_direct_[0] = xytheta_direct[0]; @@ -111,13 +149,11 @@ namespace mkt_plugins void KinematicParameters::setMinX(double value) { min_vel_x_ = fabs(value) < fabs(original_min_vel_x_) + EPSILON ? value : min_vel_x_; - // ROS_INFO_THROTTLE(10.0, "vx_min %f %f %f", value , original_min_vel_x_, min_vel_x_); } void KinematicParameters::setMaxX(double value) { max_vel_x_ = fabs(value) <= fabs(original_max_vel_x_) + EPSILON ? value : original_max_vel_x_; - // ROS_INFO_THROTTLE(10, "vx %f %f %f", value , original_max_vel_x_, max_vel_x_); } void KinematicParameters::setAccX(double value) diff --git a/src/Algorithms/Libraries/mkt_plugins/src/limited_accel_generator.cpp b/src/Algorithms/Libraries/mkt_plugins/src/limited_accel_generator.cpp index 03edf58..af19d51 100644 --- a/src/Algorithms/Libraries/mkt_plugins/src/limited_accel_generator.cpp +++ b/src/Algorithms/Libraries/mkt_plugins/src/limited_accel_generator.cpp @@ -18,6 +18,7 @@ void LimitedAccelGenerator::initialize(const robot::NodeHandle& nh) else { double controller_frequency = robot_nav_2d_utils::searchAndGetParam(nh, "controller_frequency", 20.0); + robot::log_warning("[%s:%d] limited_accel_generator: %f", __FILE__, __LINE__, controller_frequency); if (controller_frequency > 0) { acceleration_time_ = 1.0 / controller_frequency; @@ -29,6 +30,7 @@ void LimitedAccelGenerator::initialize(const robot::NodeHandle& nh) acceleration_time_ = 0.05; } } + } void LimitedAccelGenerator::startNewIteration(const robot_nav_2d_msgs::Twist2D& current_velocity) diff --git a/src/Algorithms/Libraries/mkt_plugins/src/xy_theta_iterator.cpp b/src/Algorithms/Libraries/mkt_plugins/src/xy_theta_iterator.cpp index 2820fad..6f7865f 100644 --- a/src/Algorithms/Libraries/mkt_plugins/src/xy_theta_iterator.cpp +++ b/src/Algorithms/Libraries/mkt_plugins/src/xy_theta_iterator.cpp @@ -14,19 +14,15 @@ void XYThetaIterator::initialize(const robot::NodeHandle& nh, KinematicParameter void XYThetaIterator::startNewIteration(const robot_nav_2d_msgs::Twist2D& current_velocity, double dt) { - x_it_ = std::make_shared(current_velocity.x, kinematics_->getDirect()[0], kinematics_->getMinX(), kinematics_->getMaxX(), + robot::log_info("[%s:%d] xy_theta_iterator: %f %f %f %f", __FILE__, __LINE__, current_velocity.x, current_velocity.y, current_velocity.theta, dt); + x_it_ = std::make_shared("x_it_", current_velocity.x, kinematics_->getDirect()[0], kinematics_->getMinX(), kinematics_->getMaxX(), kinematics_->getAccX(), kinematics_->getDecelX(), dt, vx_samples_); - x_it_->name_ = std::string("x_it_"); - y_it_ = std::make_shared(current_velocity.y, kinematics_->getDirect()[1], kinematics_->getMinY(), kinematics_->getMaxY(), + y_it_ = std::make_shared("y_it_", current_velocity.y, kinematics_->getDirect()[1], kinematics_->getMinY(), kinematics_->getMaxY(), kinematics_->getAccY(), kinematics_->getDecelY(), dt, vy_samples_); - - y_it_->name_ = std::string("y_it_"); - th_it_ = std::make_shared(current_velocity.theta, kinematics_->getDirect()[2], kinematics_->getMinTheta(), kinematics_->getMaxTheta(), + th_it_ = std::make_shared("th_it_", current_velocity.theta, kinematics_->getDirect()[2], kinematics_->getMinTheta(), kinematics_->getMaxTheta(), kinematics_->getAccTheta(), kinematics_->getDecelTheta(), dt, vtheta_samples_); - - th_it_->name_ = std::string("th_it_"); } bool XYThetaIterator::hasMoreTwists() diff --git a/src/Algorithms/Packages/global_planners/custom_planner b/src/Algorithms/Packages/global_planners/custom_planner index a2bebb5..49afcce 160000 --- a/src/Algorithms/Packages/global_planners/custom_planner +++ b/src/Algorithms/Packages/global_planners/custom_planner @@ -1 +1 @@ -Subproject commit a2bebb5be969471a135601da78866cc9d1db84b1 +Subproject commit 49afcce5b2247793282fe5e94d0e27f062562325 diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/include/pnkx_local_planner/pnkx_local_planner.h b/src/Algorithms/Packages/local_planners/pnkx_local_planner/include/pnkx_local_planner/pnkx_local_planner.h index 9a4f0e6..370e223 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/include/pnkx_local_planner/pnkx_local_planner.h +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/include/pnkx_local_planner/pnkx_local_planner.h @@ -46,6 +46,12 @@ namespace pnkx_local_planner */ void setPlan(const robot_nav_2d_msgs::Path2D &path) override; + /** + * @brief robot_nav_core2 getPlan - Gets the current global plan + * @param path The global plan + */ + void getPlan(robot_nav_2d_msgs::Path2D &path) override; + /** * @brief robot_nav_core2 computeVelocityCommands - calculates the best command given the current pose and velocity * @@ -179,9 +185,10 @@ namespace pnkx_local_planner std::string name_; robot::NodeHandle parent_, planner_nh_; robot_nav_2d_msgs::Path2D global_plan_; ///< Saved Global Plan - robot_nav_2d_msgs::Path2D transformed_plan_; + robot_nav_2d_msgs::Path2D transformed_global_plan_; + robot_nav_2d_msgs::Path2D local_plan_; robot_nav_2d_msgs::Pose2DStamped goal_pose_; ///< Saved Goal Pose - + robot_costmap_2d::Costmap2D *costmap_; robot_costmap_2d::Costmap2DROBOT *costmap_robot_; nav_grid::NavGridInfo info_; diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_go_straight_local_planner.cpp b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_go_straight_local_planner.cpp index c4ad108..846f693 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_go_straight_local_planner.cpp +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_go_straight_local_planner.cpp @@ -180,7 +180,7 @@ void pnkx_local_planner::PNKXGoStraightLocalPlanner::prepare(const robot_nav_2d_ try { - if (!pnkx_local_planner::transformGlobalPlan(tf_, global_plan_, local_start_pose, costmap_robot_, costmap_robot_->getGlobalFrameID(), 2.0, transformed_plan_)) + if (!pnkx_local_planner::transformGlobalPlan(tf_, global_plan_, local_start_pose, costmap_robot_, costmap_robot_->getGlobalFrameID(), 2.0, transformed_global_plan_)) throw robot_nav_core2::LocalPlannerException("Transform global plan is failed"); } catch(const robot_nav_core2::LocalPlannerException& e) @@ -189,7 +189,7 @@ void pnkx_local_planner::PNKXGoStraightLocalPlanner::prepare(const robot_nav_2d_ } double x_direction, y_direction, theta_direction; - if (!nav_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_plan_, x_direction, y_direction, theta_direction)) + if (!nav_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_global_plan_, x_direction, y_direction, theta_direction)) { throw robot_nav_core2::LocalPlannerException("Algorithm failed to prepare"); } @@ -206,9 +206,16 @@ robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXGoStraightLocalPlanner robot_nav_2d_msgs::Twist2D twist; mkt_msgs::Trajectory2D traj; robot_nav_2d_msgs::Twist2DStamped cmd_vel; - if (!ret_nav_) - traj = nav_algorithm_->calculator(pose, velocity); + if (ret_nav_) + { + local_plan_.poses.clear(); + return cmd_vel; + } + traj = nav_algorithm_->calculator(pose, velocity); + local_plan_.header.stamp = robot::Time::now(); + robot_nav_msgs::Path path = robot_nav_2d_utils::poses2DToPath(traj.poses, costmap_robot_->getGlobalFrameID(), robot::Time::now()); + local_plan_ = robot_nav_2d_utils::pathToPath(path); cmd_vel.velocity = traj.velocity; return cmd_vel; } @@ -222,7 +229,7 @@ bool pnkx_local_planner::PNKXGoStraightLocalPlanner::isGoalReached(const robot_n } // Update time stamp of goal pose // goal_pose_.header.stamp = pose.header.stamp; - ret_nav_ = goal_checker_->isGoalReached(transformPoseToLocal(pose), transformPoseToLocal(goal_pose_), transformed_plan_, velocity); + ret_nav_ = goal_checker_->isGoalReached(transformPoseToLocal(pose), transformPoseToLocal(goal_pose_), transformed_global_plan_, velocity); if (ret_nav_) robot::log_info_at(__FILE__, __LINE__, "Goal reached!"); diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp index 6749fbc..120494f 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp @@ -208,6 +208,15 @@ void pnkx_local_planner::PNKXLocalPlanner::setPlan(const robot_nav_2d_msgs::Path } } +void pnkx_local_planner::PNKXLocalPlanner::getPlan(robot_nav_2d_msgs::Path2D &path) +{ + if (local_plan_.poses.empty()) + { + return; + } + path = local_plan_; +} + void pnkx_local_planner::PNKXLocalPlanner::prepare(const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity) { this->getParams(planner_nh_); @@ -231,7 +240,8 @@ void pnkx_local_planner::PNKXLocalPlanner::prepare(const robot_nav_2d_msgs::Pose local_goal_pose = this->transformPoseToLocal(goal_pose_); // robot::log_info("local_start_pose: %f %f %f", local_start_pose.pose.x, local_start_pose.pose.y, local_start_pose.pose.theta); // robot::log_info("local_goal_pose: %f %f %f", local_goal_pose.pose.x, local_goal_pose.pose.y, local_goal_pose.pose.theta); - if (!pnkx_local_planner::transformGlobalPlan(tf_, global_plan_, local_start_pose, costmap_robot_, costmap_robot_->getGlobalFrameID(), 2.0, transformed_plan_)) + if (!pnkx_local_planner::transformGlobalPlan( + tf_, global_plan_, local_start_pose, costmap_robot_, costmap_robot_->getGlobalFrameID(), 2.0, transformed_global_plan_)) { robot::log_warning_at(__FILE__, __LINE__, "Transform global plan is failed"); throw robot_nav_core2::LocalPlannerException("Transform global plan is failed"); @@ -240,7 +250,7 @@ void pnkx_local_planner::PNKXLocalPlanner::prepare(const robot_nav_2d_msgs::Pose double x_direction, y_direction, theta_direction; if (!ret_nav_) { - if (!nav_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_plan_, x_direction, y_direction, theta_direction)) + if (!nav_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_global_plan_, x_direction, y_direction, theta_direction)) { robot::log_warning_at(__FILE__, __LINE__, "Algorithm \"%s\" failed to prepare", nav_algorithm_->getName().c_str()); throw robot_nav_core2::LocalPlannerException("Algorithm failed to prepare"); @@ -248,7 +258,7 @@ void pnkx_local_planner::PNKXLocalPlanner::prepare(const robot_nav_2d_msgs::Pose } else { - if (!rotate_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_plan_, x_direction, y_direction, theta_direction)) + if (!rotate_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_global_plan_, x_direction, y_direction, theta_direction)) { robot::log_warning_at(__FILE__, __LINE__, "Algorithm \"%s\" failed to prepare", rotate_algorithm_->getName().c_str()); throw robot_nav_core2::LocalPlannerException("Algorithm failed to prepare"); @@ -291,11 +301,24 @@ robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXLocalPlanner::ScoreAlg cmd_vel.header.stamp = robot::Time::now(); if (ret_nav_ && ret_angle_) + { return cmd_vel; + local_plan_.poses.clear(); + } else if (!ret_nav_) + { traj = nav_algorithm_->calculator(pose, velocity); + local_plan_.header.stamp = robot::Time::now(); + robot_nav_msgs::Path path = robot_nav_2d_utils::poses2DToPath(traj.poses, costmap_robot_->getGlobalFrameID(), robot::Time::now()); + local_plan_ = robot_nav_2d_utils::pathToPath(path); + } else + { traj = rotate_algorithm_->calculator(pose, velocity); + local_plan_.header.stamp = robot::Time::now(); + robot_nav_msgs::Path path = robot_nav_2d_utils::poses2DToPath(traj.poses, costmap_robot_->getGlobalFrameID(), robot::Time::now()); + local_plan_ = robot_nav_2d_utils::pathToPath(path); + } cmd_vel.velocity = traj.velocity; return cmd_vel; @@ -404,7 +427,7 @@ bool pnkx_local_planner::PNKXLocalPlanner::isGoalReached(const robot_nav_2d_msgs // goal_pose_.header.stamp = pose.header.stamp; robot_nav_2d_msgs::Pose2DStamped local_pose = this->transformPoseToLocal(pose); robot_nav_2d_msgs::Pose2DStamped local_goal = this->transformPoseToLocal(goal_pose_); - robot_nav_2d_msgs::Path2D plan = transformed_plan_; + robot_nav_2d_msgs::Path2D plan = transformed_global_plan_; if (!ret_nav_) { ret_nav_ = goal_checker_->isGoalReached(local_pose, local_goal, plan, velocity); diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_rotate_local_planner.cpp b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_rotate_local_planner.cpp index 8b728d6..6e28f67 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_rotate_local_planner.cpp +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_rotate_local_planner.cpp @@ -155,7 +155,7 @@ void pnkx_local_planner::PNKXRotateLocalPlanner::prepare(const robot_nav_2d_msgs try { - if (!pnkx_local_planner::transformGlobalPlan(tf_, global_plan_, local_start_pose, costmap_robot_, costmap_robot_->getGlobalFrameID(), 2.0, transformed_plan_)) + if (!pnkx_local_planner::transformGlobalPlan(tf_, global_plan_, local_start_pose, costmap_robot_, costmap_robot_->getGlobalFrameID(), 2.0, transformed_global_plan_)) throw robot_nav_core2::LocalPlannerException("Transform global plan is failed"); } catch(const robot_nav_core2::LocalPlannerException& e) @@ -164,7 +164,7 @@ void pnkx_local_planner::PNKXRotateLocalPlanner::prepare(const robot_nav_2d_msgs } double x_direction, y_direction, theta_direction; - if (!nav_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_plan_, x_direction, y_direction, theta_direction)) + if (!nav_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_global_plan_, x_direction, y_direction, theta_direction)) { throw robot_nav_core2::LocalPlannerException("Algorithm failed to prepare"); } @@ -199,10 +199,17 @@ robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXRotateLocalPlanner::Sc robot_nav_2d_msgs::Twist2D twist; mkt_msgs::Trajectory2D traj; robot_nav_2d_msgs::Twist2DStamped cmd_vel; + cmd_vel.header.stamp = robot::Time::now(); if (ret_nav_) + { + local_plan_.poses.clear(); return cmd_vel; + } traj = nav_algorithm_->calculator(pose, velocity); + local_plan_.header.stamp = robot::Time::now(); + robot_nav_msgs::Path path = robot_nav_2d_utils::poses2DToPath(traj.poses, costmap_robot_->getGlobalFrameID(), robot::Time::now()); + local_plan_ = robot_nav_2d_utils::pathToPath(path); cmd_vel.velocity = traj.velocity; return cmd_vel; } diff --git a/src/Libraries/tf3/include/tf3/LinearMath/QuadWord.h b/src/Libraries/tf3/include/tf3/LinearMath/QuadWord.h index 21571a0..871696e 100644 --- a/src/Libraries/tf3/include/tf3/LinearMath/QuadWord.h +++ b/src/Libraries/tf3/include/tf3/LinearMath/QuadWord.h @@ -159,20 +159,20 @@ protected: */ TF3SIMD_FORCE_INLINE void setMax(const QuadWord& other) { - // tf3SetMax(m_floats[0], other.m_floats[0]); - // tf3SetMax(m_floats[1], other.m_floats[1]); - // tf3SetMax(m_floats[2], other.m_floats[2]); - // tf3SetMax(m_floats[3], other.m_floats[3]); + tf3SetMax(m_floats[0], other.m_floats[0]); + tf3SetMax(m_floats[1], other.m_floats[1]); + tf3SetMax(m_floats[2], other.m_floats[2]); + tf3SetMax(m_floats[3], other.m_floats[3]); } /**@brief Set each element to the min of the current values and the values of another QuadWord * @param other The other QuadWord to compare with */ TF3SIMD_FORCE_INLINE void setMin(const QuadWord& other) { - // tf3SetMin(m_floats[0], other.m_floats[0]); - // tf3SetMin(m_floats[1], other.m_floats[1]); - // tf3SetMin(m_floats[2], other.m_floats[2]); - // tf3SetMin(m_floats[3], other.m_floats[3]); + tf3SetMin(m_floats[0], other.m_floats[0]); + tf3SetMin(m_floats[1], other.m_floats[1]); + tf3SetMin(m_floats[2], other.m_floats[2]); + tf3SetMin(m_floats[3], other.m_floats[3]); } diff --git a/src/Navigations/Cores/move_base_core/include/move_base_core/navigation.h b/src/Navigations/Cores/move_base_core/include/move_base_core/navigation.h index 1813d1d..824fc2f 100755 --- a/src/Navigations/Cores/move_base_core/include/move_base_core/navigation.h +++ b/src/Navigations/Cores/move_base_core/include/move_base_core/navigation.h @@ -27,495 +27,494 @@ #include #include - namespace robot { -namespace move_base_core -{ - // Navigation states, including planning and controller status - enum class State + namespace move_base_core { - PENDING, - ACTIVE, - PREEMPTED, - SUCCEEDED, - ABORTED, - REJECTED, - PREEMPTING, - RECALLING, - RECALLED, - LOST, - PLANNING, - CONTROLLING, - CLEARING, - PAUSED - }; - - /** - * @brief Feedback structure to describe current navigation status - */ - struct NavFeedback - { - State navigation_state; // Current navigation state - std::string feed_back_str; // Description or debug message - robot_geometry_msgs::Pose2D current_pose; // Robot’s current pose in 2D - bool goal_checked; // Whether the current goal is verified - bool is_ready; // Robot is ready for commands - }; - - /** - * @brief Planner data output structure. - */ - struct PlannerDataOutput - { - robot_nav_2d_msgs::Path2D plan; - robot_nav_msgs::OccupancyGrid costmap; - robot_map_msgs::OccupancyGridUpdate costmap_update; - bool is_costmap_updated; - robot_geometry_msgs::PolygonStamped footprint; - }; - - /** - * @brief Convert a State enum to its string representation. - * Useful for debugging/logging or displaying in UI. - * - * @param state Enum value of move_base_core::State - * @return std::string The corresponding string, e.g. "PENDING" - */ - inline std::string toString(move_base_core::State state) - { - using move_base_core::State; - switch (state) + // Navigation states, including planning and controller status + enum class State { - case State::PENDING: - return "PENDING"; // Chờ xử lý - case State::ACTIVE: - return "ACTIVE"; // Đang hoạt động - case State::PREEMPTED: - return "PREEMPTED"; // Đã bị huỷ bởi yêu cầu mới - case State::SUCCEEDED: - return "SUCCEEDED"; // Thành công - case State::ABORTED: - return "ABORTED"; // Bị lỗi - case State::REJECTED: - return "REJECTED"; // Từ chối bởi planner hoặc controller - case State::PREEMPTING: - return "PREEMPTING"; // Đang huỷ bỏ theo yêu cầu - case State::RECALLING: - return "RECALLING"; // Đang huỷ bỏ nội bộ - case State::RECALLED: - return "RECALLED"; // Đã được thu hồi - case State::LOST: - return "LOST"; // Mất trạng thái - case State::PLANNING: - return "PLANNING"; // Đang lập kế hoạch đường đi - case State::CONTROLLING: - return "CONTROLLING"; // Đang điều khiển robot di chuyển theo plan - case State::CLEARING: - return "CLEARING"; // Đang dọn dẹp bản đồ / costmap - case State::PAUSED: - return "PAUSED"; // Tạm dừng - default: - return "UNKNOWN_STATE"; // Không xác định + PENDING, + ACTIVE, + PREEMPTED, + SUCCEEDED, + ABORTED, + REJECTED, + PREEMPTING, + RECALLING, + RECALLED, + LOST, + PLANNING, + CONTROLLING, + CLEARING, + PAUSED + }; + + /** + * @brief Feedback structure to describe current navigation status + */ + struct NavFeedback + { + State navigation_state; // Current navigation state + std::string feed_back_str; // Description or debug message + robot_geometry_msgs::Pose2D current_pose; // Robot’s current pose in 2D + bool goal_checked; // Whether the current goal is verified + bool is_ready; // Robot is ready for commands + }; + + /** + * @brief Planner data output structure. + */ + struct PlannerDataOutput + { + robot_nav_2d_msgs::Path2D plan; + robot_nav_msgs::OccupancyGrid costmap; + robot_map_msgs::OccupancyGridUpdate costmap_update; + bool is_costmap_updated; + robot_geometry_msgs::PolygonStamped footprint; + }; + + /** + * @brief Convert a State enum to its string representation. + * Useful for debugging/logging or displaying in UI. + * + * @param state Enum value of move_base_core::State + * @return std::string The corresponding string, e.g. "PENDING" + */ + inline std::string toString(move_base_core::State state) + { + using move_base_core::State; + switch (state) + { + case State::PENDING: + return "PENDING"; // Chờ xử lý + case State::ACTIVE: + return "ACTIVE"; // Đang hoạt động + case State::PREEMPTED: + return "PREEMPTED"; // Đã bị huỷ bởi yêu cầu mới + case State::SUCCEEDED: + return "SUCCEEDED"; // Thành công + case State::ABORTED: + return "ABORTED"; // Bị lỗi + case State::REJECTED: + return "REJECTED"; // Từ chối bởi planner hoặc controller + case State::PREEMPTING: + return "PREEMPTING"; // Đang huỷ bỏ theo yêu cầu + case State::RECALLING: + return "RECALLING"; // Đang huỷ bỏ nội bộ + case State::RECALLED: + return "RECALLED"; // Đã được thu hồi + case State::LOST: + return "LOST"; // Mất trạng thái + case State::PLANNING: + return "PLANNING"; // Đang lập kế hoạch đường đi + case State::CONTROLLING: + return "CONTROLLING"; // Đang điều khiển robot di chuyển theo plan + case State::CLEARING: + return "CLEARING"; // Đang dọn dẹp bản đồ / costmap + case State::PAUSED: + return "PAUSED"; // Tạm dừng + default: + return "UNKNOWN_STATE"; // Không xác định + } } - } - - /** - * @brief Creates a target pose (PoseStamped) by offsetting a given 2D pose along its heading direction. - * - * This function calculates a new position by moving forward (or backward if negative) - * a certain `offset_distance` from the current position, following the given heading angle (theta). - * - * @param pose The original 2D pose (x, y, theta) in the local plane. - * @param frame_id The coordinate frame in which the output PoseStamped will be expressed. - * @param offset_distance The distance to offset along the heading direction, in meters. - * Positive moves forward, negative moves backward. - * @return A new PoseStamped offset from the input pose, in the given frame. - */ - inline robot_geometry_msgs::PoseStamped offset_goal(const robot_geometry_msgs::Pose2D &pose, const std::string &frame_id, double offset_distance) - { - robot_geometry_msgs::PoseStamped goal; - goal.header.frame_id = frame_id; - goal.header.stamp = robot::Time::now(); - goal.pose.position.x = pose.x + offset_distance * cos(pose.theta); - goal.pose.position.y = pose.y + offset_distance * sin(pose.theta); - - tf3::Quaternion q; - q.setRPY(0, 0, pose.theta); - goal.pose.orientation = tf3::toMsg(q); - return goal; - } - - /** - * @brief Overloaded version: creates an offset target pose from a given PoseStamped. - * - * This function extracts the 2D position and orientation (yaw) from the given PoseStamped, - * offsets it forward (or backward) along the current heading direction, - * and returns a new PoseStamped in the same frame. - * - * @param pose The original pose with full position and orientation. - * @param offset_distance Distance to offset along the current heading direction (in meters). - * @return A new PoseStamped offset from the original pose. - */ - inline robot_geometry_msgs::PoseStamped offset_goal(const robot_geometry_msgs::PoseStamped &pose, double offset_distance) - { - robot_geometry_msgs::Pose2D pose2d; - pose2d.x = pose.pose.position.x; - pose2d.y = pose.pose.position.y; - // pose2d.theta = tf2::getYaw(pose.pose.orientation); - return offset_goal(pose2d, pose.header.frame_id, offset_distance); - } - - /** - * @class BaseNavigation - * @brief Abstract interface for robot navigation modules. - * - * Provides core methods for setting goals, moving, rotating, and handling motion control. - * All navigation logic must implement this interface. - */ - class BaseNavigation - { - public: - using Ptr = std::shared_ptr; - - virtual ~BaseNavigation() {} /** - * @brief Initialize the navigation system. - * @param tf Shared pointer to the TF listener or buffer. - */ - virtual void initialize(TFListenerPtr tf) = 0; - - /** - * @brief Set the robot's footprint (outline shape) in the global frame. - * This can be used for planning or collision checking. + * @brief Creates a target pose (PoseStamped) by offsetting a given 2D pose along its heading direction. * - * @param fprt A vector of points representing the robot's footprint polygon. - * The points should be ordered counter-clockwise. - * Example: + * This function calculates a new position by moving forward (or backward if negative) + * a certain `offset_distance` from the current position, following the given heading angle (theta). * - ^ Y - | - | P3(-0.3, 0.2) P2(0.3, 0.2) - | ●---------------● - | | | - | | Robot | (view Top ) - | | | - | ●---------------● - | P4(-0.3, -0.2) P1(0.3, -0.2) - +-------------------------------> X - - std::vector footprint; - 1. footprint.push_back(make_point(0.3, -0.2)); - 2. footprint.push_back(make_point(0.3, 0.2)); - 3. footprint.push_back(make_point(-0.3, 0.2)); - 4. footprint.push_back(make_point(-0.3, -0.2)); + * @param pose The original 2D pose (x, y, theta) in the local plane. + * @param frame_id The coordinate frame in which the output PoseStamped will be expressed. + * @param offset_distance The distance to offset along the heading direction, in meters. + * Positive moves forward, negative moves backward. + * @return A new PoseStamped offset from the input pose, in the given frame. */ - virtual void setRobotFootprint(const std::vector &fprt) = 0; + inline robot_geometry_msgs::PoseStamped offset_goal(const robot_geometry_msgs::Pose2D &pose, const std::string &frame_id, double offset_distance) + { + robot_geometry_msgs::PoseStamped goal; + goal.header.frame_id = frame_id; + goal.header.stamp = robot::Time::now(); + goal.pose.position.x = pose.x + offset_distance * cos(pose.theta); + goal.pose.position.y = pose.y + offset_distance * sin(pose.theta); + + tf3::Quaternion q; + q.setRPY(0, 0, pose.theta); + goal.pose.orientation = tf3::toMsg(q); + return goal; + } /** - * @brief Get the robot's footprint (outline shape) in the global frame. - * @return A vector of points representing the robot's footprint polygon. + * @brief Overloaded version: creates an offset target pose from a given PoseStamped. + * + * This function extracts the 2D position and orientation (yaw) from the given PoseStamped, + * offsets it forward (or backward) along the current heading direction, + * and returns a new PoseStamped in the same frame. + * + * @param pose The original pose with full position and orientation. + * @param offset_distance Distance to offset along the current heading direction (in meters). + * @return A new PoseStamped offset from the original pose. */ - virtual std::vector getRobotFootprint() = 0; + inline robot_geometry_msgs::PoseStamped offset_goal(const robot_geometry_msgs::PoseStamped &pose, double offset_distance) + { + robot_geometry_msgs::Pose2D pose2d; + pose2d.x = pose.pose.position.x; + pose2d.y = pose.pose.position.y; + // pose2d.theta = tf2::getYaw(pose.pose.orientation); + return offset_goal(pose2d, pose.header.frame_id, offset_distance); + } /** - * @brief Add a static map to the navigation system. - * @param map_name The name of the map. - * @param map The map to add. + * @class BaseNavigation + * @brief Abstract interface for robot navigation modules. + * + * Provides core methods for setting goals, moving, rotating, and handling motion control. + * All navigation logic must implement this interface. */ - virtual void addStaticMap(const std::string &map_name, robot_nav_msgs::OccupancyGrid map) = 0; + class BaseNavigation + { + public: + using Ptr = std::shared_ptr; - /** - * @brief Add a laser scan to the navigation system. - * @param laser_scan_name The name of the laser scan. - * @param laser_scan The laser scan to add. - */ - virtual void addLaserScan(const std::string &laser_scan_name, robot_sensor_msgs::LaserScan laser_scan) = 0; - - /** - * @brief Add a point cloud to the navigation system. - * @param point_cloud_name The name of the point cloud. - * @param point_cloud The point cloud to add. - */ - virtual void addPointCloud(const std::string &point_cloud_name, robot_sensor_msgs::PointCloud point_cloud) = 0; - - /** - * @brief Add a point cloud2 to the navigation system. - * @param point_cloud2_name The name of the point cloud2. - * @param point_cloud2 The point cloud2 to add. - */ - virtual void addPointCloud2(const std::string &point_cloud2_name, robot_sensor_msgs::PointCloud2 point_cloud2) = 0; - - /** - * @brief Get a static map from the navigation system. - * @param map_name The name of the map. - * @return The map. - */ - virtual robot_nav_msgs::OccupancyGrid getStaticMap(const std::string &map_name) = 0; - - /** - * @brief Get a laser scan from the navigation system. - * @param laser_scan_name The name of the laser scan. - * @return The laser scan. - */ - virtual robot_sensor_msgs::LaserScan getLaserScan(const std::string &laser_scan_name) = 0; - - /** - * @brief Get a point cloud from the navigation system. - * @param point_cloud_name The name of the point cloud. - * @return The point cloud. - */ - virtual robot_sensor_msgs::PointCloud getPointCloud(const std::string &point_cloud_name) = 0; - - /** - * @brief Get a point cloud2 from the navigation system. - * @param point_cloud2_name The name of the point cloud2. - * @return The point cloud2. - */ - virtual robot_sensor_msgs::PointCloud2 getPointCloud2(const std::string &point_cloud2_name) = 0; - - /** - * @brief Get all static maps from the navigation system. - * @return The static maps. - */ - virtual std::map getAllStaticMaps() = 0; - - /** - * @brief Get all laser scans from the navigation system. - * @return The laser scans. - */ - virtual std::map getAllLaserScans() = 0; - - /** - * @brief Get all point clouds from the navigation system. - * @return The point clouds. - */ - virtual std::map getAllPointClouds() = 0; - - /** - * @brief Get all point cloud2s from the navigation system. - * @return The point cloud2s. - */ - virtual std::map getAllPointCloud2s() = 0; - - /** - * @brief Remove a static map from the navigation system. - * @param map_name The name of the map. - * @return True if the map was removed successfully. - */ - virtual bool removeStaticMap(const std::string &map_name) = 0; - - /** - * @brief Remove a laser scan from the navigation system. - * @param laser_scan_name The name of the laser scan. - * @return True if the laser scan was removed successfully. - */ - virtual bool removeLaserScan(const std::string &laser_scan_name) = 0; - - /** - * @brief Remove a point cloud from the navigation system. - * @param point_cloud_name The name of the point cloud. - * @return True if the point cloud was removed successfully. - */ - virtual bool removePointCloud(const std::string &point_cloud_name) = 0; - - /** - * @brief Remove a point cloud2 from the navigation system. - * @param point_cloud2_name The name of the point cloud2. - * @return True if the point cloud2 was removed successfully. - */ - virtual bool removePointCloud2(const std::string &point_cloud2_name) = 0; - - /** - * @brief Remove all static maps from the navigation system. - * @return True if the static maps were removed successfully. - */ - virtual bool removeAllStaticMaps() = 0; - - /** - * @brief Remove all laser scans from the navigation system. - * @return True if the laser scans were removed successfully. - */ - virtual bool removeAllLaserScans() = 0; - - /** - * @brief Remove all point clouds from the navigation system. - * @return True if the point clouds were removed successfully. - */ - virtual bool removeAllPointClouds() = 0; - - /** - * @brief Remove all point cloud2s from the navigation system. - * @return True if the point cloud2s were removed successfully. - */ - virtual bool removeAllPointCloud2s() = 0; - - /** - * @brief Remove all data from the navigation system. - * @return True if the data was removed successfully. - */ - virtual bool removeAllData() = 0; + virtual ~BaseNavigation() {} - /** - * @brief Add an odometry to the navigation system. - * @param odometry_name The name of the odometry. - * @param odometry The odometry to add. - */ - virtual void addOdometry(const std::string &odometry_name, robot_nav_msgs::Odometry odometry) = 0; + /** + * @brief Initialize the navigation system. + * @param tf Shared pointer to the TF listener or buffer. + */ + virtual void initialize(TFListenerPtr tf) = 0; - /** - * @brief Send a goal for the robot to navigate to. - * @param goal Target pose in the global frame. - * @param xy_goal_tolerance Acceptable error in X/Y (meters). - * @param yaw_goal_tolerance Acceptable angular error (radians). - * @return True if goal was accepted and sent successfully. - */ - virtual bool moveTo(const robot_geometry_msgs::PoseStamped &goal, - double xy_goal_tolerance = 0.0, - double yaw_goal_tolerance = 0.0) = 0; + /** + * @brief Set the robot's footprint (outline shape) in the global frame. + * This can be used for planning or collision checking. + * + * @param fprt A vector of points representing the robot's footprint polygon. + * The points should be ordered counter-clockwise. + * Example: + * + ^ Y + | + | P3(-0.3, 0.2) P2(0.3, 0.2) + | ●---------------● + | | | + | | Robot | (view Top ) + | | | + | ●---------------● + | P4(-0.3, -0.2) P1(0.3, -0.2) + +-------------------------------> X - /** - * @brief Send a goal for the robot to navigate to. - * @param msg Order message. - * @param goal Target pose in the global frame. - * @param xy_goal_tolerance Acceptable error in X/Y (meters). - * @param yaw_goal_tolerance Acceptable angular error (radians). - * @return True if goal was accepted and sent successfully. - */ - virtual bool moveTo(const robot_protocol_msgs::Order &msg, - const robot_geometry_msgs::PoseStamped &goal, - double xy_goal_tolerance = 0.0, - double yaw_goal_tolerance = 0.0) = 0; + std::vector footprint; + 1. footprint.push_back(make_point(0.3, -0.2)); + 2. footprint.push_back(make_point(0.3, 0.2)); + 3. footprint.push_back(make_point(-0.3, 0.2)); + 4. footprint.push_back(make_point(-0.3, -0.2)); + */ + virtual void setRobotFootprint(const std::vector &fprt) = 0; - /** - * @brief Send a docking goal to a predefined marker (e.g. charger). - * @param maker Marker name or ID. - * @param goal Target pose for docking. - * @param xy_goal_tolerance Acceptable XY error (meters). - * @param yaw_goal_tolerance Acceptable heading error (radians). - * @return True if docking command succeeded. - */ - virtual bool dockTo(const std::string &maker, - const robot_geometry_msgs::PoseStamped &goal, - double xy_goal_tolerance = 0.0, - double yaw_goal_tolerance = 0.0) = 0; + /** + * @brief Get the robot's footprint (outline shape) in the global frame. + * @return A vector of points representing the robot's footprint polygon. + */ + virtual std::vector getRobotFootprint() = 0; - /** - * @brief Send a docking goal to a predefined marker (e.g. charger). - * @param msg Order message. - * @param goal Target pose for docking. - * @param xy_goal_tolerance Acceptable XY error (meters). - * @param yaw_goal_tolerance Acceptable heading error (radians). - * @return True if docking command succeeded. - */ - virtual bool dockTo(const robot_protocol_msgs::Order &msg, - const robot_geometry_msgs::PoseStamped &goal, - double xy_goal_tolerance = 0.0, - double yaw_goal_tolerance = 0.0) = 0; + /** + * @brief Add a static map to the navigation system. + * @param map_name The name of the map. + * @param map The map to add. + */ + virtual void addStaticMap(const std::string &map_name, robot_nav_msgs::OccupancyGrid map) = 0; - /** - * @brief Move straight toward the target position (X-axis). - * @param goal Target pose. - * @param xy_goal_tolerance Acceptable positional error (meters). - * @return True if command issued successfully. - */ - virtual bool moveStraightTo(const robot_geometry_msgs::PoseStamped &goal, - double xy_goal_tolerance = 0.0) = 0; + /** + * @brief Add a laser scan to the navigation system. + * @param laser_scan_name The name of the laser scan. + * @param laser_scan The laser scan to add. + */ + virtual void addLaserScan(const std::string &laser_scan_name, robot_sensor_msgs::LaserScan laser_scan) = 0; - /** - * @brief Rotate in place to align with target orientation. - * @param goal Pose containing desired heading (only Z-axis used). - * @param yaw_goal_tolerance Acceptable angular error (radians). - * @return True if rotation command was sent successfully. - */ - virtual bool rotateTo(const robot_geometry_msgs::PoseStamped &goal, + /** + * @brief Add a point cloud to the navigation system. + * @param point_cloud_name The name of the point cloud. + * @param point_cloud The point cloud to add. + */ + virtual void addPointCloud(const std::string &point_cloud_name, robot_sensor_msgs::PointCloud point_cloud) = 0; + + /** + * @brief Add a point cloud2 to the navigation system. + * @param point_cloud2_name The name of the point cloud2. + * @param point_cloud2 The point cloud2 to add. + */ + virtual void addPointCloud2(const std::string &point_cloud2_name, robot_sensor_msgs::PointCloud2 point_cloud2) = 0; + + /** + * @brief Get a static map from the navigation system. + * @param map_name The name of the map. + * @return The map. + */ + virtual robot_nav_msgs::OccupancyGrid getStaticMap(const std::string &map_name) = 0; + + /** + * @brief Get a laser scan from the navigation system. + * @param laser_scan_name The name of the laser scan. + * @return The laser scan. + */ + virtual robot_sensor_msgs::LaserScan getLaserScan(const std::string &laser_scan_name) = 0; + + /** + * @brief Get a point cloud from the navigation system. + * @param point_cloud_name The name of the point cloud. + * @return The point cloud. + */ + virtual robot_sensor_msgs::PointCloud getPointCloud(const std::string &point_cloud_name) = 0; + + /** + * @brief Get a point cloud2 from the navigation system. + * @param point_cloud2_name The name of the point cloud2. + * @return The point cloud2. + */ + virtual robot_sensor_msgs::PointCloud2 getPointCloud2(const std::string &point_cloud2_name) = 0; + + /** + * @brief Get all static maps from the navigation system. + * @return The static maps. + */ + virtual std::map getAllStaticMaps() = 0; + + /** + * @brief Get all laser scans from the navigation system. + * @return The laser scans. + */ + virtual std::map getAllLaserScans() = 0; + + /** + * @brief Get all point clouds from the navigation system. + * @return The point clouds. + */ + virtual std::map getAllPointClouds() = 0; + + /** + * @brief Get all point cloud2s from the navigation system. + * @return The point cloud2s. + */ + virtual std::map getAllPointCloud2s() = 0; + + /** + * @brief Remove a static map from the navigation system. + * @param map_name The name of the map. + * @return True if the map was removed successfully. + */ + virtual bool removeStaticMap(const std::string &map_name) = 0; + + /** + * @brief Remove a laser scan from the navigation system. + * @param laser_scan_name The name of the laser scan. + * @return True if the laser scan was removed successfully. + */ + virtual bool removeLaserScan(const std::string &laser_scan_name) = 0; + + /** + * @brief Remove a point cloud from the navigation system. + * @param point_cloud_name The name of the point cloud. + * @return True if the point cloud was removed successfully. + */ + virtual bool removePointCloud(const std::string &point_cloud_name) = 0; + + /** + * @brief Remove a point cloud2 from the navigation system. + * @param point_cloud2_name The name of the point cloud2. + * @return True if the point cloud2 was removed successfully. + */ + virtual bool removePointCloud2(const std::string &point_cloud2_name) = 0; + + /** + * @brief Remove all static maps from the navigation system. + * @return True if the static maps were removed successfully. + */ + virtual bool removeAllStaticMaps() = 0; + + /** + * @brief Remove all laser scans from the navigation system. + * @return True if the laser scans were removed successfully. + */ + virtual bool removeAllLaserScans() = 0; + + /** + * @brief Remove all point clouds from the navigation system. + * @return True if the point clouds were removed successfully. + */ + virtual bool removeAllPointClouds() = 0; + + /** + * @brief Remove all point cloud2s from the navigation system. + * @return True if the point cloud2s were removed successfully. + */ + virtual bool removeAllPointCloud2s() = 0; + + /** + * @brief Remove all data from the navigation system. + * @return True if the data was removed successfully. + */ + virtual bool removeAllData() = 0; + + /** + * @brief Add an odometry to the navigation system. + * @param odometry_name The name of the odometry. + * @param odometry The odometry to add. + */ + virtual void addOdometry(const std::string &odometry_name, robot_nav_msgs::Odometry odometry) = 0; + + /** + * @brief Send a goal for the robot to navigate to. + * @param goal Target pose in the global frame. + * @param xy_goal_tolerance Acceptable error in X/Y (meters). + * @param yaw_goal_tolerance Acceptable angular error (radians). + * @return True if goal was accepted and sent successfully. + */ + virtual bool moveTo(const robot_geometry_msgs::PoseStamped &goal, + double xy_goal_tolerance = 0.0, double yaw_goal_tolerance = 0.0) = 0; - /** - * @brief Pause the robot's movement (e.g. during obstacle avoidance). - */ - virtual void pause() = 0; + /** + * @brief Send a goal for the robot to navigate to. + * @param msg Order message. + * @param goal Target pose in the global frame. + * @param xy_goal_tolerance Acceptable error in X/Y (meters). + * @param yaw_goal_tolerance Acceptable angular error (radians). + * @return True if goal was accepted and sent successfully. + */ + virtual bool moveTo(const robot_protocol_msgs::Order &msg, + const robot_geometry_msgs::PoseStamped &goal, + double xy_goal_tolerance = 0.0, + double yaw_goal_tolerance = 0.0) = 0; - /** - * @brief Resume motion after a pause. - */ - virtual void resume() = 0; + /** + * @brief Send a docking goal to a predefined marker (e.g. charger). + * @param maker Marker name or ID. + * @param goal Target pose for docking. + * @param xy_goal_tolerance Acceptable XY error (meters). + * @param yaw_goal_tolerance Acceptable heading error (radians). + * @return True if docking command succeeded. + */ + virtual bool dockTo(const std::string &maker, + const robot_geometry_msgs::PoseStamped &goal, + double xy_goal_tolerance = 0.0, + double yaw_goal_tolerance = 0.0) = 0; - /** - * @brief Cancel the current goal and stop the robot. - */ - virtual void cancel() = 0; + /** + * @brief Send a docking goal to a predefined marker (e.g. charger). + * @param msg Order message. + * @param goal Target pose for docking. + * @param xy_goal_tolerance Acceptable XY error (meters). + * @param yaw_goal_tolerance Acceptable heading error (radians). + * @return True if docking command succeeded. + */ + virtual bool dockTo(const robot_protocol_msgs::Order &msg, + const robot_geometry_msgs::PoseStamped &goal, + double xy_goal_tolerance = 0.0, + double yaw_goal_tolerance = 0.0) = 0; - /** - * @brief Send limited linear velocity command. - * @param linear Linear velocity vector (x, y, z). - * @return True if the command was accepted. - */ - virtual bool setTwistLinear(const robot_geometry_msgs::Vector3 &linear) = 0; + /** + * @brief Move straight toward the target position (X-axis). + * @param goal Target pose. + * @param xy_goal_tolerance Acceptable positional error (meters). + * @return True if command issued successfully. + */ + virtual bool moveStraightTo(const robot_geometry_msgs::PoseStamped &goal, + double xy_goal_tolerance = 0.0) = 0; - /** - * @brief Send limited angular velocity command. - * @param angular Angular velocity vector (x, y, z). - * @return True if the command was accepted. - */ - virtual bool setTwistAngular(const robot_geometry_msgs::Vector3 &angular) = 0; + /** + * @brief Rotate in place to align with target orientation. + * @param goal Pose containing desired heading (only Z-axis used). + * @param yaw_goal_tolerance Acceptable angular error (radians). + * @return True if rotation command was sent successfully. + */ + virtual bool rotateTo(const robot_geometry_msgs::PoseStamped &goal, + double yaw_goal_tolerance = 0.0) = 0; - /** - * @brief Get the robot’s pose as a PoseStamped. - * @param pose Output parameter with the robot’s current pose. - * @return True if pose was successfully retrieved. - */ - virtual bool getRobotPose(robot_geometry_msgs::PoseStamped &pose) = 0; + /** + * @brief Pause the robot's movement (e.g. during obstacle avoidance). + */ + virtual void pause() = 0; - /** - * @brief Get the robot’s pose as a 2D pose. - * @param pose Output parameter with the robot’s current 2D pose. - * @return True if pose was successfully retrieved. - */ - virtual bool getRobotPose(robot_geometry_msgs::Pose2D &pose) = 0; + /** + * @brief Resume motion after a pause. + */ + virtual void resume() = 0; - /** - * @brief Get the robot’s twist. - * @return The robot’s current twist. - */ - virtual robot_nav_2d_msgs::Twist2DStamped getTwist() = 0; + /** + * @brief Cancel the current goal and stop the robot. + */ + virtual void cancel() = 0; - /** - * @brief Get the navigation feedback. - * @return Pointer to the navigation feedback. - */ - virtual NavFeedback *getFeedback() = 0; + /** + * @brief Send limited linear velocity command. + * @param linear Linear velocity vector (x, y, z). + * @return True if the command was accepted. + */ + virtual bool setTwistLinear(const robot_geometry_msgs::Vector3 &linear) = 0; - /** - * @brief Get the global data. - * @return The global data. - */ - virtual PlannerDataOutput getGlobalData() = 0; + /** + * @brief Send limited angular velocity command. + * @param angular Angular velocity vector (x, y, z). + * @return True if the command was accepted. + */ + virtual bool setTwistAngular(const robot_geometry_msgs::Vector3 &angular) = 0; - /** - * @brief Get the local data. - * @return The local data. - */ - virtual PlannerDataOutput getLocalData() = 0; - - protected: - // Shared feedback data for navigation status tracking - std::shared_ptr nav_feedback_; - robot_nav_2d_msgs::Twist2DStamped twist_; - robot_nav_msgs::Odometry odometry_; - PlannerDataOutput global_data_; - PlannerDataOutput local_data_; + /** + * @brief Get the robot’s pose as a PoseStamped. + * @param pose Output parameter with the robot’s current pose. + * @return True if pose was successfully retrieved. + */ + virtual bool getRobotPose(robot_geometry_msgs::PoseStamped &pose) = 0; - std::map static_maps_; - std::map laser_scans_; - std::map point_clouds_; - std::map point_cloud2s_; + /** + * @brief Get the robot’s pose as a 2D pose. + * @param pose Output parameter with the robot’s current 2D pose. + * @return True if pose was successfully retrieved. + */ + virtual bool getRobotPose(robot_geometry_msgs::Pose2D &pose) = 0; - BaseNavigation() = default; - }; + /** + * @brief Get the robot’s twist. + * @return The robot’s current twist. + */ + virtual robot_nav_2d_msgs::Twist2DStamped getTwist() = 0; -} // namespace move_base_core + /** + * @brief Get the navigation feedback. + * @return Pointer to the navigation feedback. + */ + virtual NavFeedback *getFeedback() = 0; + + /** + * @brief Get the global data. + * @return The global data. + */ + virtual PlannerDataOutput getGlobalData() = 0; + + /** + * @brief Get the local data. + * @return The local data. + */ + virtual PlannerDataOutput getLocalData() = 0; + + protected: + // Shared feedback data for navigation status tracking + std::shared_ptr nav_feedback_; + robot_nav_2d_msgs::Twist2DStamped twist_; + robot_nav_msgs::Odometry odometry_; + PlannerDataOutput global_data_; + PlannerDataOutput local_data_; + + std::map static_maps_; + std::map laser_scans_; + std::map point_clouds_; + std::map point_cloud2s_; + + BaseNavigation() = default; + }; + + } // namespace move_base_core }; #endif // _MOVE_BASE_CORE_NAVIGATION_H_INCLUDED_ diff --git a/src/Navigations/Cores/robot_nav_core/include/robot_nav_core/base_local_planner.h b/src/Navigations/Cores/robot_nav_core/include/robot_nav_core/base_local_planner.h index 566cb2e..5373293 100755 --- a/src/Navigations/Cores/robot_nav_core/include/robot_nav_core/base_local_planner.h +++ b/src/Navigations/Cores/robot_nav_core/include/robot_nav_core/base_local_planner.h @@ -133,6 +133,13 @@ namespace robot_nav_core */ virtual bool setPlan(const std::vector &plan) = 0; + /** + * @brief Gets the global plan for this local planner. + * + * @param path The global plan + */ + virtual void getPlan(std::vector &path) = 0; + /** * @brief Constructs the local planner * @param name The name to give this instance of the local planner diff --git a/src/Navigations/Cores/robot_nav_core2/include/robot_nav_core2/local_planner.h b/src/Navigations/Cores/robot_nav_core2/include/robot_nav_core2/local_planner.h index 9adea92..95527ae 100755 --- a/src/Navigations/Cores/robot_nav_core2/include/robot_nav_core2/local_planner.h +++ b/src/Navigations/Cores/robot_nav_core2/include/robot_nav_core2/local_planner.h @@ -92,6 +92,13 @@ namespace robot_nav_core2 */ virtual void setPlan(const robot_nav_2d_msgs::Path2D &path) = 0; + /** + * @brief Gets the global plan for this local planner. + * + * @param path The global plan + */ + virtual void getPlan(robot_nav_2d_msgs::Path2D &path) = 0; + /** * @brief Compute the best command given the current pose, velocity and goal * diff --git a/src/Navigations/Cores/robot_nav_core_adapter/include/robot_nav_core_adapter/local_planner_adapter.h b/src/Navigations/Cores/robot_nav_core_adapter/include/robot_nav_core_adapter/local_planner_adapter.h index eb47b44..839f198 100755 --- a/src/Navigations/Cores/robot_nav_core_adapter/include/robot_nav_core_adapter/local_planner_adapter.h +++ b/src/Navigations/Cores/robot_nav_core_adapter/include/robot_nav_core_adapter/local_planner_adapter.h @@ -159,6 +159,14 @@ namespace robot_nav_core_adapter */ bool setPlan(const std::vector &plan) override; + + /** + * @brief Gets the global plan for this local planner. + * + * @param path The global plan + */ + virtual void getPlan(std::vector &path) override; + /** * @brief Create a new LocalPlannerAdapter * @return A shared pointer to the new LocalPlannerAdapter diff --git a/src/Navigations/Cores/robot_nav_core_adapter/src/local_planner_adapter.cpp b/src/Navigations/Cores/robot_nav_core_adapter/src/local_planner_adapter.cpp index c4671a8..696c49e 100755 --- a/src/Navigations/Cores/robot_nav_core_adapter/src/local_planner_adapter.cpp +++ b/src/Navigations/Cores/robot_nav_core_adapter/src/local_planner_adapter.cpp @@ -366,6 +366,17 @@ namespace robot_nav_core_adapter } } + void LocalPlannerAdapter::getPlan(std::vector &path) + { + if (!planner_) + { + return; + } + robot_nav_2d_msgs::Path2D path2d; + planner_->getPlan(path2d); + path = robot_nav_2d_utils::pathToPath(path2d).poses; + } + bool LocalPlannerAdapter::hasGoalChanged(const robot_nav_2d_msgs::Pose2DStamped &new_goal) { if (last_goal_.header.frame_id != new_goal.header.frame_id || diff --git a/src/Navigations/Packages/move_base/src/move_base.cpp b/src/Navigations/Packages/move_base/src/move_base.cpp index 91ef2b5..f4725da 100644 --- a/src/Navigations/Packages/move_base/src/move_base.cpp +++ b/src/Navigations/Packages/move_base/src/move_base.cpp @@ -607,7 +607,6 @@ void move_base::MoveBase::updateLocalCostmap(const T& value, robot_costmap_2d::L void move_base::MoveBase::addOdometry(const std::string &odometry_name, robot_nav_msgs::Odometry odometry) { - robot::log_info("[%s:%d] addOdometry called for: %s", __FILE__, __LINE__, odometry_name.c_str()); odometry_ = odometry; } @@ -2206,6 +2205,20 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal) { if (tc_->computeVelocityCommands(odometry_.twist.twist, cmd_vel)) { + robot_nav_msgs::Path path; + tc_->getPlan(path.poses); + if (!path.poses.empty()) + { + path.header.stamp = path.poses[0].header.stamp; + path.header.frame_id = path.poses[0].header.frame_id; + } + else + { + path.header.stamp = robot::Time::now(); + path.header.frame_id = controller_costmap_robot_->getGlobalFrameID(); + } + local_data_.plan = robot_nav_2d_utils::pathToPath(path); + last_valid_control_ = robot::Time::now(); // make sure that we send the velocity command to the base @@ -2283,6 +2296,9 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal) lock.unlock(); } } + twist_.velocity = robot_nav_2d_utils::twist3Dto2D(cmd_vel); + twist_.header.stamp = robot::Time::now(); + twist_.header.frame_id = controller_costmap_robot_->getGlobalFrameID(); } else {

qFrk|{|8Mct|-5Bu@E=7{H72WM8Z%u}w6$7n;p-1n)r_LF1KPSk(5pFH`to(!0NvL3SKzmBv_KRFm#H2vhuNZIt03lR=q z*^Nx0pKJtWO+VQh5>!8_3MKsHF_y=W3*yw8Xxf%;y*_A7NmrS(j&4e0N6;+fGoTGI^mLByZ4`+T zG8=&T2IM)qdFxyu?}E0?(9=1(?Hl8?Uf%%l6G7BVGUPeBpQ8H7S6_+K>BgbxAHbzD zuUV|4YlQ8|N`prMC{K_l*E+h3pW+jTOs*LK9n(oNj&5%?Y+z+sJP*LQbdrptYk=?m zu=?Z@09F`~c62lf<>-oGL0L<&55U-H365vmg<)}g%^La6K8@S6 z7H!Sv;$XarLAO2?wArMq%vtkk2KtA{vs?$-CPPnWKF+7Ekk0}5#(+HYY4(XLs~Gc>B7JoF(xfx^t!2B;ZXn0d`&&FAbPe7Kt$^a0>` zf>>TI$m|1qGh>{V^b!C|(n&Jr(>$MFOWF*;u5^-&`Q++>owrQj1OTTENShChBEo!_ ztCW4cbU)eU1FxSv*b5`4Tw8DmC@yCwjM4U!&(6idL|H^vGbFi3(cOM>(m1TSwgRn- zp-1XpKoPmC_9sbyU(wUSfKAq->_aR$eqHNPo zPJbaNjxhFb>dKq#ClCJOu8h0=WW@vSV>@>~IlV;mLzp{jqWj6k9bh1k7k>XYF76G< zP!0JuUEUMOqw4Z5AfWp*W>BOwS&g9-Rw&;8(6gu&M_^HX!TlUAC)fl+&B!ZzIlw0) z`ej3s85G^Ms1s*kQENbZ-_WBi>H&bQMUC6&Q#kn@z`u~;A(9!g7L}JV#-a*(+-U)E z2J0k%${fggeq5THA!|`Z6oYF~V{TwjN`^Xsv>^jklMLO*qVn-;w8Md!YB`h;vRRAz zwXakX#pd$9aOw%#~`z!vtnR21glh?d)2 zlI*YOZedSokL+gyE!ohc3wtonGce7!T8~(TleGYDN`?_6Gh_>UEMrVzPx83a0wplX z=me;I5w}^En;~1+GZcec*llpY39}_P;kJhiR82B;pTbV~7`@v$U~X6rC4_9Yux}NK zQxaun6k~Q=N)uh!YPjbA0A&{5-yemI=KB{Ad}dnlP2GI&VEDrSeck^v@tb@ak+%7+ zyAdOPz#wKIIORfQ+cw{-e>q|XW0zAI-fZ*Du+(jiZu8B##a+{OoA2*g15v}=#cxON z!;3rO?!#l(jJJj_AxCQ5$()Fk#dI1lo%TCC(-R2Rd(`!8D3&jy# z(U4?gMR!f-wbrn@CZM%9^k~y*39vPtfAMKN;^bJ|rjwyP$qZT3>B1OeI=wvZw7`XU z%oEAI6Ssqwn;~mDeHDXiI(0&cI=Rc_g1$;M$_rPoObV zPJP^(5=c$7>8KSkKdmL@PC=L<3VZ)fudpjEN6#`2ER)IB2pczSJN=5A)s`Z9jUmYv zitZNntV~FCJ81h2J-VEX6SrGrXa`x6AzRpQwTvk2KCzZNEl_bQ zx;Erm7R9X`F3ru5E$nP~RoX7wzK?B{D!Gn;^d$pTlMLObunT{Uh3Z+rEVmp=2-$35 ze~Z;@CFcXg?jVqw=)!&vkD`RXGn5KX{9G^Fp8Ht0)2Zil`>gN&e&qiCfZycexY>5v zX18A~`qdFR!6|!Ew&`YjZN%YgjO{~Zc(d(vOxEajS^=*us_CZNP78H$pFO$Dwpp>` zCvrOa;$7X2&2;pE^O%lKKw4%xS{Ye1)6r2#*-S@YL^ynLJFEzO^ABWj_r)edg6f-9 zp{O=btwbSzk3@X;4xd0sSx^zp6$W|d6VD(&!9mROfn8Vx!R1`;5@C?pz6PlnqAM7Z zyshZ2LGHuzIN1oawuT;Ukm?{cV~|%%VcG?p9F5ylGB`X>k0EQ2Jk8R!ets&}HRrUz zBjfNX0&;K1ZNKGa$QqYLcP*804k?Fvw(-PH|kCLkS_9 zHOP~XI7*_d3s7SMsfoxiV;N3pn&ouph7MySqNn3h&%1f5oO<5P*joJO%2ox$qgF+R zR;A+ky!)5Z$iOrcueZlj^@R50$?E z3M?nwCk68W^kKO^)osR?&8Pab-4E*D((eD3_)T7eNZV!>;UgqGd$keQMT${<(`Fhv zLD8GBJUma`Y@4YvB6^d@`MK_rj@xF^8bmMQ%)1f&s3Sid9NUm-Gt-bQ|5l`B+RSF; z$h4VSNZz!W1_*}}aexKeOcp3>+ROq-@Crq>8EPdeh1;Pqaf01)Z^Q&!)quAdcw{E{ z_eK!c0+%ym0Ml4Y4fn+f(D zg*FS(eQ`7gLGlo8M=jb;uve`0i?!gFzk_y#bd@l`1^l1$a1Mn?Do?N>=v!O|%mUI<>yXhpE33iXsuB05O>HN4NC7B8K67=M( zK3NHXCk;qXuxS)(f}K4lEXU7st@O-H*L>#gk1!wg@oUd~lImd+Gy}q3roh1v@0rir ztzkZE5x>#UvD)Z+6x=I#iUb9&9X_qTrYmkWg$$=|Et~H;-BV9=) z0H{Pzgd}4=Wsc+N7t5j*0A12aGUijhP@-V<$q@jIH6U$1G>QoGp{$hWG5lgb?Hu&_ z=}gx!`r8KHUF6@)4^^4jbQmkw@))8|86$Fv$$re)=oMm{Iz79(P(`-HJp}1yI=ow`VOkL$;qjr5M~%`lS*fo!opt zR+E9MNrvvzPnY=-nEk+fYdNT!Vzd49<%)?)qPzmq4Fai&_V@hcm+&t{nS}4Yhr&iD z_&W-l6S}niy7NnRe_wKc-@|WmEN-?F9M>6ddiBH8TyVwkUox&RSIQzY`Qr4g>f_GUO$hA!|_u8DlJ}h{uifnVWIqB|zmC+&;0~ z3|WgRp%`3?8nPQTLWc9W-6R85lMLO*qOx{HU!D`CQy7=#P(sLNEvi5avO_u50jf(N zH4z#3RXGga_HIF`^g{GNT=vUyTA2E>oL4n|T3bqq40?k2+hMO($_zl`T6@r z)XM3HFgVatDNQm%wpJcz zjH#8X9(P(`V2z-77*N>|w>FlWAzLf86oXqUla4w%xlw@3Bm-5G4Be+z>T**0E-)Wk z4(g`ZY^@xdpQt3t?*KYQAT`nLU>sVP@Q(#g_z;$o*v`K?qT6}b@w%NCaDV5zznk!z z9EY22=hb^+5oa6*_u!PxDBHC2m5p!$7Gv8`8QyF=Z(S7?%>QmX?`0;0?qK)mN_Q~q zw)5t)ihvThtJ$ZDx22 z!#J)MIN1faK4ch4GDFs)#xcfN)MSr4EzquLq8LW*<+!c0+zeTZnyDCEi^@_TjgAao z;Pw+4sG4NxJ{I-jhrswyI$3dP4kd(a)}n444JnDT2tXwWq$Uw1?xzu@eBBN05rw_x zs8`r+@s^tG3YMqHR;PbNVK2m*xqJc9lMP8WQgpYlg9DJYrJ$`b^ytEF0kAFX$5Rs& zP96dHJ2JE*nIT))of%^ayQjyU7I+d1p}ztu6Or{CxHLCIwy^ss2Dh+dN{4iEPXN-8 z3{*`rbf3b`w*$VcKQN;$2X#|ywy-n*;8zmm0)UngNKJHMkC+Ri_E!Z@xC3^YvH8yV zQa9iB^L6vh?f%Yif8WM$vV)s#zE^&T6VJ@^iGLtl4yA0+x$0l=Z;{QnB_7lAf4E#>lmVLWWTa!7?=Q%nYQ8VwJW1VrnL&{< z;#&;+VNw5l}3L}NkobJX+$Zn z{He!8y}t1ZyVd|KtmXR}n}BgS{ho~|Y=0IipyM;G>R zfNf#>2PY_;oB{9xGK?XaAzRoJ8Dk22y2qUscs_5USOus&gxfL8&5$kZIf}t8?Dd$- zGh6ZwZi&!WsU{h^PhoGR`4j`DvgJ@h$Yu-sAigH2Xu=xt486H=a zE0!hVn;z56x5ZlBe6zW~6W!l8@SFV4nuz9my@OwLN5odhmdhyHG~e?ths4*6eVw}U zW}9y>RCr|XdlFA))PJ}4ZJX@w9&&r%@)x3)XXhQ!%{@E`FNm}G)<(Wf^ZfyNRLytl zI@5faL6Pz$x+FH=t(X+*HrhC_=v!FqbKo9^%h}9Kn&!I>-_MjY5xvlm|O*afG;SKdZ+;9Hj@7b&`1*qiR6 z$}He1-gx5Hs^jLnW>%#BNF zq6@q4hitw(P-fxl+%JUYoB4a)d>ekGn{P(+}(h)HfvgN19 zwr#!#S2^Nk#vY_HyxHbEJcrv{-NAEBd?g~P`JQ)sW4HMhZWa9$bn!U-6f`{Y1=K2< zZvgo=&G#7csG9G19JH!?UuICGT)}IwY`#NJcoy{)zVaYTg1bB}=Oi;}ns3G9$aX_S zw=pF7v!c5ewRZrTcVEzk8hW%vou}HyqT*YI6izM!cr6+JB$**=QP&t_Eb1SRJ1tP_ zYEWzjRG!4`oaJW7T9h2f*J245@&P9`An?6{o0EF6YxVSgR@aP%`(cIt~C zX@OH%R4f3ftczO<%gvB2>?7nhh1~(4Qc%ea2V^Q4sG4NxK84)|CripVf%(XCC?RCC zh5bh`pd`v~5PO0^YN89fJaG6(F7yod<5BHszWyI|^KFH#Ib7??;r>o`f7jwS`Oe{p z=G(TVBYGmD+z-g?x0G#q-(+lTY{u9hsSIzn`CgbAy$4AQjoz!<;$ZY1q`!WM9z2Wg zdhl%?^qfMr{40=_dC(I=gn7_&87Z3wJ=YNqml%iqpw0h72KV9UMKGu~uL?yij8Q95 zXjQK`QE2>9q`&GP-Jc9O1k^!s6k1ta&hY0V46jPA6IWjXDv5F z)*wHLG|2g1Iy$)o=$Z?cQcW^+AA{V(W#lJ-X=pj9n_{yD`9$u3k|=uu)Q3Q7qRU<# z(Cp6$o^YmPdN?@mCvA|MzS0Ic#QiFU`gKUpKb~ZQvw~*NLrBCdKY`K84jX|El z$p>c`yNrdyn>ENkLhdFww?FA|Jo;(qCMvNL47xAgProG-#(!6iUjA{_e_fy}S_o z*)zy7#n46Vf}DN0oW}=6807UlQ2ivL&l!@es_15b^8{@94rsyCE^D+w)&kgi$QkeB zm3iRgqqvnPLsOC&vIg0jF{V4}=y9h79;z1DF(MYdUP(Hmyux! zZf}x-s!4|KW00knL!%?W{Af9p5VBc=oLoPkB+46zy-Of9(Pe*o84h>yFGrb#$2`b7 zDiNQ0MjPaV-)V#V=3D(+%l+RAzsVmW(i-H3R5%Yrv_&<^{*-MDGB6eIzc6+%mEp}A zWaq-s^OFL7To35ZPacJHQUe}$fYa*b==sUa7=5s}G03IJmj6?vWejpZa%2p05>hq> zIRoKvtEuP=VUW3@tTD)Skf01w6^b%QY9%WDfOpQ-qwvmWBc5f_S|awE|BO#}$+i%e zhRb;e&$_&4neFH|1|xoqp~+1I*k_sF)khiGN8y=!<5WT*`HCd)R3HqSB-E3|nO zp6%yY1(L^rJZaJPS!SPMv0@h=y8)@NLbp6*#@*8{GQ ziU3qIAn#e`&V85;P)K{wdK!AVXPNIG#iwQn8Uw&If~c2d$a|K#ODSg_g(v40I`i)X zw1X_nyk@b_GK=L))QNu!z!`!(x%OFR;e>cC=`H|qsK`i3=2>Qe8Sz?DegGaNC_<8X zmif!qv4YhnYXi{Gfb_FW8ijh6Ip_yij-N$RsKn=RrMa)@rIs&$^;}uDd|2z64gqs0 zWb$BGgc(_9t_}Nq1JUmplANjNt}Ao+^2(fHZ(8Fu+VwD|Axyc$S(retv$Qy zV(d~A@l6a(79qg;vr7$-C+p8%dcsjiITY|wWGSK0#-E*0XyecF?Z%tp0Lj(3y=l?b zpM9I?7v;b&_k#8r=_+&9pY{4VL0o4={R-L@Lr>?=dg60nN=U+Qc)1^!E5sav8;fru zC?Q2aD{JWK{8@!9eyvv%0NN8oy(B}PKRd3JGybe8hUY5X@c_*v3p1}-tUufFTbxdO z4FK;GF3%01_;OMmxV+2rf+N3Frzk^GH@z!;1xtCkz02O|0fLy|2N-F0Q# z4}(4jw55g~?aJB#Y+YIQKYa=(cLRKc44p}4$hxwgj4`gPkH?)B=)E>5P5>$$WIYj= z=4QycvVn@hb!9i;`fc`j`nR?Fe<*&F45(`Qf;{;mmEq00vf=oin{r+5G$D6G*HyWrve$4bV&teS`wiFixvngJpdQ7A zKg5^0>6KnUI>sx#jXWx^)IJXRR9=Z06e&Fl>4!d-{_rg7LLDf+7ToXPa^^FW#-fV+ z4EU#r{@jq{5=D0{s!&(V^?w2FlA%Xi)C#I?mYs&Z9a1=%4T&e?a@LT{khQ3{8DlJJ zqsN^Vc<*N^9tBi3$E}m)X2@F9hl;_qsP$!Ib#gBPGM5ZgO)_*Ji>f^U8f^w*f$bDZwgumLys=(A^_XMPQxdliId}Sn?Z&{T&iHm7WPrbn8H5JKW3Ky z!N1riNA8btJ7l>TvW5MFVsHz4A$FaqfZtG@6YaUOe&1875>=fyXUkJ zAE#ja583iJ$~MinrSyvfjJ-r%d9%&8YR~AA$Rm@YM5k+k8*Hs++Hw zR8>H>{0|}TW+c)bSu`UNXS_EO2_hWsSf0w_{cke3BavE=pxV4D6xHUbl_=D4VNeum z|1|Q~DI0V_fAYr_&mapu41<3Ia^Aw_yaMUA_0L3I%1;n|*pTE>MRyId_+;4k&!GKb z=+Oqb5@2hP4UP+ilMf*AJh+^-Br{|U@*Tz)gWTkCrv*Df%(*OP&dV94RY4jcqLK(0MHo%sfjN8y2>CY zfG0d;IOZWR$i%<2AwE`4|6VSuf4jK<$Kf~m8$?=zY;Yz{R6#_Qt4MkuWgCMm`)p9O zW9(rn!<#k8nwg`Qoo@aZz3kNaU6=08@;|=gEGc-PnaQL&bSRR2v`k<^a$UTst3{n+}GDvDA3eD&r5`}h`h!bOEqX8k2DOj^u z!X+?1-(+t<)GSx#&I|bRh^Scmg?Lf3LZC_r`qlxt5iaMi7ol@5MXD57g>S!fMQmR~ z(Vvpfw|73iXI3Tf#q^+f1!pf#0C}2$2u-aXC|xQ+@GI6UL0L=czZ9LX=tQh1)eaoO zw_SKd;4V=1dAy2RKQOO#yx^&ur$9Mtd6lyIT+8f;93$IQ#>y78JABR4t~}ml^0ce` z3@S1eJlP z`9TihavlQBYB#MjkG9;D`_XrtZU%87zw z*%v?=@A10Yz1t*KaICr*l-De;(oT;Czl6#uxA4*lU1k3po~x|84c_5PuzX9l#!S)- zl-^2#EBph|Hw{U)Q*_r=wt5Bh4AVJ%b9`Fy4u*w1DvdkTU|1AhAhdD zb(Ix4);F%QC&{Mo?t}NWT9JDsZj&rGL)KOHQ4FrDyxkrRfedfqww(-AO)_*JSDE!a zkWT?~$#N(mWV5dF#?=HRQO2PdGvZR3hzz+-V29&8Cr=tio<$K|4wu@*`j#)&O`atp zGSq0I-ay)jb2?=^fODT?V6sa@;Kv0@}*CmBk#cHcDjDeabnyvjhVcFVS+okF|qpzJ1fV5D|6aCAC% zH=h9IG^r|Kqg|J&ae}*-Z-F9^bIq%?)BA&qgD^&p=!$J$)b8AW)oyZr*nCxxYf;SX zNbO2Mc00uOFqCNRHuTWiy#Vrf1F_oOUIOm|?G}Ub8maRmwVQx9JGuFDD=0fXUe|YK zC@cjxcOD1j2g|Fp)7vLAB65r@vqNg__T2t&b=UJnEPCYuIR%%qF;ctv8)HRz#8x+y zXzlhbjZt;i9^@_tVzn#zzSeFSD5FXJFjBiB=(o8y?iEm$dc3Z7x&Fp6!JuveWt-(y z+Ueb87nOFIt0rpgR^It<+8tYq#}IcQ!Uu@+ZKQS`aT-&0#O5=UXzfNm8?Ush0CE)r zvD%$o8&GxE8kCNt{urfQFetcnXfP-vJYHA3M)QJ#TZ3K(WufI&+UdSC|2X7oWmke#*0m~+`4P}z1 zb6>p#-PA!ue`82;yrR3EdzRs7sTV-|+t8ys_bC9|&b>*~1cj5ika#LCXD-PM+0K1A zV@&71%HvK8>>BNeQh>^~xOKPO4B5_oy<%`X_l%zhb#hYySwse^CKLuO|jX|{q$_S%T76Gar>P>YNChy=V>Ws^W7G@7yb(SGw(gdzkC9DDhhH* zT+S7WG5yrA*JDL3#5OgQNK>j37}Q_)Q@ug%Zy>h4bS@0sg zAYvQ(24(h(H==1LWFE|$W9#^KM#oQfUK`+u*s6->L^SP$eDq~0VoUk{V*DVya;DQc z>|BT9v5zU9hrGervsum0-!I#&#+8^6&M%BznbWXWB4Dx^<#`V2t0ihi!JD2Vp?n{Ek%8V zoEEK{#fpCHbcSW}7kwVwG5$|Pg7EX3(8HWe=NjOlHa~$mEGE-OcO|C22*(CjQ%dmB z2~4vj?u9$5-~im~U3$S0oyvuN1Mm&msX~s6hy+YdG^4TF)A1vN6qYRbS=o2_nZ7Q44WXoby;%nA%M* z|6~%G4qeBGa~{Y}rd2XHErXor zu@zn)b4Fv6k*S5<5rkhb(9~ikt^|zEnprF~wYYQyIC~XP7+^JtmM}+hI z3P?&yM=s|9Y_B!7lynquMrbjORa!bqIEVGt(bRb9DCZo0)JRjyNkb=Hb)NVM z=2Wv_3pX0z+=bmcrX~mCv(Pl$Spwg=m|DZXJscyQCGJ5%P2+daHp|-@b+L55>-R%=av0AOotj#7_7WQrbN= z^gSl<4d#|Tz?Wmv{!*+m9s|7j26M}dgRGPmugbz%CZkp@TKvdNX%$sjNw16pZxfVd z9~yOO!xigRoSEM=Gb8aCU(prSram4ieWTP#h5vQcKe6lqEQBvC{5c_)F^Ovv!7jm0 zBmkG}#6)biot8_b{m3+#0GYUn=a6@4(L!G7eP;0iDt=%Un;OC3+Nuh>(W62l-{@Fp zVrNdy`>KhBnd_6B^YQuMv?r>pnny;78)oP!t%jOf-Ms3hW>1n8JcJAXTCwKBnUicP z(`0728Hqy+K)0figT;Q&OD3n+SRoZ=+4VJ2VZUPCh%>87V5Zkzm6T{Y4^negRdX*vRq#AF zGIx(+{S9YU@Kr{6Vz<@^`-Pe%i&@5XlA6{s^HX|nM~bzQ#eOf#rI~C2r4&Tvm)2RP z#wD*>RrG8gioqx;dXY)A{w_i_lnO28j0zi8#I3MT7Q`49c`uX_vv)#rC1|9qx;NOT zL%Xrwn~T9 zS@#@hHt7g(X2X_t)BU6)$T@wQk*2GUiBRYB?D%X#fRuzg9fOFb+odDIslo1&(}S#- z*PvX^4G9WO5BBF$U4V3TU}4JBuZYra$cr&s+!snIzvErBw01IO^02QrspZW`DMMeQ zTy>L)TFnzmO(RYRN|~o1ubay7oj(&k@%eZZ?S^VzPh*12Yl&n+y6<*Q^%U&{6Qv!J z7H-K97bSkz0cr*c|1Y&fXS^~-$N;uEaX&tPnD&+M2J+&ky1nA zNtUk{c22tjOpt{@#>3^860hrF*%lGTEr;5lA*8IE#P_%~y;sHSM`;?#GNr(v6jYJ)&oAm*xBFXf|t7Z#QatsnY@ij6)z59 zG3U^9d#XpAdi9?rUF$0+_=pi3OhP-$2iTTaFp+BXl z%6S*U91c0stKt(UF#&CqwBaJC74D)%UL|UAtj4lEB5Qrf4rP$J8x7n4#I1Z-Walo+ ztTWgC3`5`~)T=rsI3}Wn7BJInbok?nmtY5>nN}-H$@#hm909>g;4o6a^S27k zGGrMJS9`uwi-IrPpn@idIaL&zz1S}&{3eJX3{cEoA}fXoqB(X2oV`@uKNG|}rmb?* zvNCO>o7R$PnQ&dlP-awHj)`Jd)hn2A z`owD|YBMjcFhaYWnCBF(>R2MJxcWF*U%;QM(Ra?L9>C}ol`*8(^aG$Ufpx*e+6m;b-;h;y_aSyVCJod#=Z&Z(}&yHy<9gm<| z<1DE_J*qyZhq8Zte9Kj9Y>lJdeN=sxPiOxLUomGkj(Yb|^*J+){i9|wrvQ$6_fhrf zHH-c2v-y|}N4@)~`m~sXk)4C6tXnQDY+RTHMX~rZjA^SqEOL&(Z1zI6hh=oW8YgIB z8QBdAa5m~@qJ6te~=V6mULc1y!V@gmWC;(^*(m zI?6dKpi{lDnsiigK0v!+VUp~!*K$5#M|J6_?fkAdXf>pxj&maRW>{EDI_f%yMM6?X zI_f#cy3Dk&o^;fAJ}L_fnn*_j=WD!7u&}9gG;|(eZ7rmuk@IWT)=D}WI|sA2Hqw#e z9Ld_+Nk6S4`C1zYov(`{POB)z696_axH_7aa!8VAR?cc zPB54jjPX zQ4I#Wuo9yggH7eE)Rlo2U8cbdZaXbBfk9m)$vg(tvg&CKgF^H5bezHcyQq)n18hEP zr4RA^Rl=x_(x(p^fuuy9T`9_*(27}g zs2PLwQ%35_;G&)=ok7>rC!w9`Vf7#y93)ffye|7fCZ4A$2%(KQBZ zM;a*{V;1Isa2v%jIE42%OEMUHNTI3>er_nJ5rd9R^wfdD{Gm4L$6#T79j#_iJ&!^= z88{{reaB$M3msi#5W3VvcNygCX`ojOBBL>Tx)|WhO9KTk_~JJ#T40dgUQllaS(+PY z1cT*su*)<9XL+K<4AxiF(MATHhnVO9gJ-p|V2DBJArr+c0caI&q@oNqF0xQX2379i zRYwLLN0_KJgX~Rp)QiD1tX?0^Aa<~UwlKJQ+f0WU=#D9LmcjK^2D-tZ-Zcw7Wl*8A zhW=)7xf_bsQhvncHybFJ!T)YrD4M}>eA~G& z1Hv0lV;QV(ZKGKXHcUs+V({H|g|;!cPzRIS3^Z5(cb-9wtvdQsf`c|HxdJ}9a_Fck zgZ+m!)QG`HjDB@s@GV+2{TP@qVlsw-4i?U2u&Xn+(w9E(taOnw7sRM27utxO7SWN-|rdVoQI zFwtoSrm714!r|$GgDUvx5sE`FoRiB(0pbPaY;w>7_=;b3ZKE1>sI=iK^OGK9x_M?HPSl< zc`xWmzZT%TuQe3RplClMMKfrJ&qWtzQ0_;J&oFp9!a%hdL?E$OFgU){OxqZA!7d`- zG6>IYpz{n);+2+L4CV~B(sKp{@WOu9Zvd{x5H(^@2A>t~z@S`1BlTmjvW}U?FjzK2 z&`bvF*O+KIgM0;aw3R`vZrERw!F+rZ?-hf=O)!zU4j>H+!vh$^A2v{S25s?bR6YjZ zV2CxI!P6NUs?H!7*VTlma9UWlcU&%_R8H8bw{uc&!^9Xv(VDf1ly=PD= zT|*J;0iFgb)SAHqygS>A!O`p*8qVPC284Pt=fP=x4*EF3xhY9I@!(O zx=x`J40!4LWd_x6;S&xFwzt*OYX*CNGLvQ_z@iuUq$-2asGqwsm^U9qi@|j4b3K8< zW(@DoW3UUOYik&M_tHwc7`(ru&~XMj^iusVRjpz$Ue!(etOiWY9K%z`Ld41WAoP+rCQD9b6WwA^vzJ288LaPMr4J0u=n>g=0*u`+D4an-EP9G#@b_<+tY?tb z9|Ii>%01K2at0MJZ?=^|>PZb9VQ>tqlFu>7S6t9d1}F2`=oy3QxEZtW0@&FX4@3q( z81)p-;Nl{Msx!!g)q71C3_gsa#h}3mY&ODR@kR}eW1y{Jq&W;4qo?#(a*CqXVlZ+k zmg4RPn9z(Ugu!tX$QTBpBW+ZaK|}!NTo@F^^!8*1(Y-aakil~-HRN^u=BJ&o9}VQ%+!Fv+Y=~S3<6P|_GM5V zE&Ndo?x4U)Pv*w15UEe6f9 z*r+`NeAk86FsShnMTlp0st*oO3`XZP&`<_37!N+gpydWV{m7sT8gJJb>{@H0-x(wnw$lF?EJY*Gdv=1En))h4$Eb2J43DX&-}bIjwY( zLB*CvavcWf^iWV<28L+{D#hUDa5Gh7P<@Y$8Z-F1poTh14(f!d3{_pI0nBCG*VLr^MY*Doxz4(cy*OQ_X#?h z#vt~wprs5dMrdd=gMoSQB0B?Jc@6!@phGVVUNbl`Pf&qx0ZfN+Uodbi&`=EqF&#|Q zjKTh%g1RzTmJ5pp8LV=l?*O1T&csn`e1+$bR${$zJJ?=&%04Kec&L6apmlz{S&!zFN4Ts*?5XZA}on2QTxt2{` z(3ZH5U|n5xeq|KP_<#`Oaay6tGOa7VfY(R~Fqf@yPdIczt(rbak%MxTStcV*Y|tLw4K)6o)@|6E6Ivc9@dte6C4Ig|+BwV< zM4ePjY={*#=_}QV)g>&G6D+LLO;|MiQ>4dN z$P1PUm68Vys`N8*f~oxHk`r6~Gm0GT$6y*@kvU*7{GDSQ zXd7GQVjglHi!jk5n?J8O>> zGeP9Uo_dSN`^CYbmn*3zh@!8pw0MH_njn^oRnY0{nL^2SlCiPU-!jaB6A_)L~%x?fcV zVOK1)_;0CTdjsCRDBRElhQxhep*ZUh~BigNtfA>@tSC(KP)u6FeW`?}5ltQneZ@Nt5W}kfP z9MIF^nbLQF$5#z-UD&_CMeI~;lf2Pf7iGJkG!+oGl^#Etwv^a39HpR$8vUsZGPP>v z${TYc{!>8PAk!^nf(-?CpRA^zaR|;NO04@Fg?*TsFlLN^tHEWePY`XUTWRSRGROq+ zKGH%<^GOHRa6aaz@&S3AGlJ*Fmg9&vfgZEUrJ*NGF7uT4Rx>!|edrHDLng3~-Z(f1 z>&R!|BN~c0?vzLN50gZ#`*`AamR^*{@NpblE*$m7$zbZfk+Jb2(Dq#8o$|zn1;xhU zOkf|qF|Z8lXc)!EpK|i?raZELm?Uc5$4$>zdKgE&F=#T!HU!D2mq)FUn=xA1-q9P+ zOJ?im%vbR;i8smPms2@xB^>p}Xc-H0+OvY5`P@l@)y>8b$n?fNjabVeX=TCkjLXO) z`-e%6*3B$9ll9J<#d`UuHFCR1D;rRHp z736o@#0hs0GQF{7AJ)>oF(0os;p2UIWdAV9!6IMD9FHEk-Z&IFq&F^=Im*?Y-pEH? zb!gTbmpoCE{lcu~k(=vZc&4N1mNqIX+L(A-zRhoVUX<3%Qitx<2s0j-C zvJgWoh9*aeZ?=LFuG@RnNTH+gY#b&2YL1nMk-D#u8E&7Qm=jtSqq|jGs6M2-i;K$H zEf~`-%kmj|eo|Cew{S*AMJ066C9#-TRV@|8>#CgB&D~DET?j- zmWn#*w9yvNr5%K#jiOJxUbL)dIH!?-vuCT`w5+$2uT;0x5k3350oj1H9t0@*yW5ir|3h@jp4UF361IjyCFG9JSI%Z{+t1wDPDo_L9>3 z@7afs=#j|dh5xZnslV9gs>JN0H@^Re{pbA67*o4Aet-|UJ0I9z_38GJ@gpH{WUQAM zm6yUkw=kQ4UJS5a;&qCvA;ufCEB@RDTBl@ZSETBiAdX`J{)%XK6m+1Pi<+*$X1AszXL_O+oWn@v6+Pl|pm z&}j@B0s*$s>3ze1;Z0NBUs2-L!)q7*3TqIOV64}w0~t@DiByl|11M+kR(uTIJU|y& z*rRx`ui_y=mwXg|Wm-56i#l}R2H>w;X2p^q6>EGIFRW!It$D0&kXP~eV1CL9)#3?3 z`5^FEJjpbsHD2>*4zEtE_%vNbE6w#4i z=ecI|c5QQ;;sw|>(6W&={SHm!*NH`OwoAES{ZV-T=n<*!HK{=h*xq9zP~3&=nMW?( zarnSF?5j!P=`q-me=Yz02!HVm*nul{~*Fzw(;25xDO};J-R4->O_IjCfoZB8k!8> z8D0spbO{{z5GIV@pakDDBWco2>=#o^M>7Tc1Y(Tj7<|s+uShHKA^^FCl^^0;AP_w8 z2x+y3ue=E+pB{ns5B!Z7YV-++{sy$pnFJj#g$qMO=EXS{y)wzdC6oYZQ4s_w%fX&Q zhuVx;tC5MZq~I5L)usF_B!&_o*wU8Zb@6grw}9SnG<`VXmWI_nhfQOZ0EKzuz?sWD zc@4wC6Oz16BU5f!*y%ASTuOk3$vZ&Y=TQnfWfCqAtAhBHKfk> zfp|f;cyt-Qva5nct4i7$_Qy~>hposLQjKM#i-X6IIpr`{usWNm102!>k%*j}TE zO@PlV4%3~(=s6dq@G{<*5vw8C;1SY#nTv#}zmCj32Ekd6Pz||Nq(QIDM$z-P?=`eK zM`U#@AzO~;Fs_?8dhs`hfenh4BkRe@vpOoaz*Q?r6Oe6&iZVw{YaorCg_dcVlQ!);qMF#|VKn@VmB?NS6n2YOn8~3- zA{BK2Xctm6R2<%*T)_~lV60Ne@yjWsRhgemAH8aSw$-SjlWKp-tag)++MjKMN*eyH zR#M2Z2y=;|%xzPH5*}+G+V*2*Hd|K+ei^Lo>ZA6dZEIcqztu_#B{jsD-+}|o>oYa#_aP` zJLKhIXg-C%a)Ix~lU&lIuo_-b7S|!T>k-mc(FUQ^GBH=kn_;rZwG%rxpW{-5Qo&}5 zKODvP4lpZvylDqy7eS7mW@-b0 z%PoV7O$r;N57bu)*XIzT zasSR5I*BzrBCsS%0RBqViEiVSExltHFOT1q0f2DiIlrvxnHK!bNN&m0MJZ(+(7?=iKn7}ppgofbYG@{l@aYormhZHffiR2}A4wm?3xDJfaM2{`aYXLiLiumWUtGsrX9Jk^3b?kBdnJ7@zvRIkm_E*%qwEM1PR zX52OxEeo5U{mbT@MkM?$DEXEZRb-os`r7>CD5TI8$nJRM)qHIp*%*ergUkT^YIv4s zvbj(bybg8$>uj$Sty>d%@aVI z<)M0QmUiiwFr-P4!JE#t%fset|FZc6UbGb#pyUQCieQ^t``Uc*5afSA_Q5NU@wIsu zR$+)N&>e-p8lL5uY_6CU>AVaYL>bVkdZ=ETrCmBE4B_q6JY_?d0GrSK%jU**X!{yU zrn90Tj;@!l&2Ri5Uk%w-uRP4xX8+=_`2=KFGRQO8y!$ukZ2*RNg~LA{s@G;|myQWT zPAMj@&3oA9EbY=UVaVWaW-8#e`4Zdw)u*yyRMYwR6Fd_dLe`oU z-D8_K_}bj41nTGhkd5@pAN$%IKO5oaK(;!AJd@2IUclTKFvPbwobgb-HcPv7Oc*lm ztifyZ_)4(3@4sw*gn?;cfh;Tj%2l>`zpu@`^Fkg6SuwBthOf;VuzXJ>LDnRLJd@2^ zbKy?C#y0l@ZG?yFwOQJwW5ST%zWro#d?IY_{4blQYoO>5l$>Nmr`hIHzBV`gh`hfE z*<-K#CtsUCeu?_~BV_*2uZCxNCY%3>!j(+{OXLBqsE6vcS=yyz!jScNXTno9Ub4+G z|FZeR65K<5Ap43H9p>n+`Pv+fWn*FnWQ)A=N$;AjuXy zMRMZinkiU%3DX@dA?d;@PV+-Tc2ZQ~L~IT*6oOG6Aze{I5h%K^z3+3>0NkIL=aH#d zM>_W0pnQd=c!B7SGUn`6y)pAGkC<6H9^>=Zz`f53u5iqG zyfo#jXpy0&WeVjp$gGB%FGEel+DwGnW;V)D$1{cU8S_>{J(Z#EK@NGy9%gKD z3?f0g^Dm8*9`{IP&;6?MIv%~vxx$oe<=dafg!^(B>{tin^i`QlQRiZIQT1VSky?0Mr7-Q z=eH;a?<9{%$e^ZCF<92WR_K!P-jiqrVOI}9Elnn=V2jXQ#`KXG3E^Z9L3HOBRKh-? zn~T+bVmX8xy@b9@s3^#f2P$@T`|G=#z%yLf5Dhs+0Q=zR5rkza!m94x$7!9g0!pBjj(9DHE0USY8`ow3P`T z58BR}X!whk@KOgZ!&z!e&^`KyMe~rKz+d5FCyt=7Qx2ZquvG|Y5rj9u;Bgb;#~CRD z&ZHQ~Rw;WIyostc4!DL71lST)m(@>duckYif~UT-2C7#4rFx7&Bw!t=t%fZdUe6V5 znkWrnWe-6u+IvLVG!5D62j-fKEWq4`B(?*oi-$;iM2kE4N^s-AF)7f5@g&I^5BXFt zrzhvRt$9$y7I&88i6m*8LD}b_safBXv)FkHUda-^2lTxwE?@`@VTdRS>)LG!#XaTlh0z0q7ev;|~)qA&*N>R}~# zRQO-xu#a9oEMONKayZ_DTJQ2{8Dw`dEFkKuf&h1 zurV9Z@L^R~VP7 z2A3}}0jB;DZX!!82eiv*bJ3hk5TMN+{gVKb$|8d#zzDlJ7N{hi$8p(iEjSN4+ z%z`{Xz?c1B8hPT&Yo>HSBd-Ba6Oz$z{02OchO+bHM>e&?5ZrxG{QSQZSM^ma9Z;MA zPiZOxQgt$fP8fT1yQ;Hxz5lrUo1l7)l@93Sr@Lw_BQ{q4hD}m9Y1xmp;|HrJV)YnX zz4pIisP7wtbRdQr@RU|FAXP6zRV`ayx1CxVEcO4x@}^h>=(SurpqCf>s+Kcy+dX`^ z+j91E#{kR2(H>#T+x%AyK?-go&mAEhh=F&Wk(M)XTh7pHd1_TO!8VohPrcVjN1MYe zYsBV5_AZDcX&PS6-QvtP2Y9cDZisyjU1G`@ympKaM&{Gg)+_}aS5Be0+UJBH04IQ_ zRP6KY+{~G*)I;Mou&#}^IRf6Xa85k%7hiPhi76&S%n z6gRwtn*K@HV*ms`kz>YfHHwd3LPvYCem;cU*y4brh-m0Zhk5qWJ_P&r5Nk0PJ}jWb z;uU7Cc89~DLpC;I*AACo3igQ+)e*KK{>lP;9z$L8AGi*Cr|yU}kHJg-e0zwVkoWU& zD3HIgwj;(o8LLR8cq&A*K8Yi-*Yu7!T?;JAm*R~OZD;XP#6aOP@m^LFL(lq z)hw26!5xKza^%5703J^uew&dpVDvl-R+Ff$KRnWMLF_oV3pt*!Ej$j_CyQFbj_9R_ zWPY{W$N6>O8#T47dkFTL{wzUis{{uRJt0H8c?liuySNSQA(+ZAVNUoIFJYctHnKg0 znK@9GB11QM2`Doo)Evi&90lxZ6z9Bzj`j||grN0mnR)3Y%(Hj%CCtRTiehK(oZO7x zsI=(U*F71(v!FQ?Uhc{GO=4iXKD09~=wuc>jTG%^XTE@UJ#563GWZKFB(zC%??F5B z1|9Q|@&~-fRtHRIi9cQyLzf^!fqaGau_B;a_-KgTT?=xgSAt0i*$Z+jF@DXjYfEQbKfz`)v`Liqw$Rrm;wQ^^8Iq{x^SDAt9IZbqdz# zj88RDLOwJ1t!S9lZ6uU2R>qlF`OIb35Cr;1+j@a0%pfwxsSJ> z$?wNrkW|&BCnahtM{~oIn1m3fZ@fWIZZrwJzsmBz$fView<6BgdV+@Ta;r+s>0ZkMo8&%NdEFj)$*6Ie@`;TiAs}y3>0ciu9%N=qg`{KY{9C= z8IvHlH-quMyddht`PUnNNFTB)b>kk ziYD_U$mV$Ea@@e3#Ek;W*T(|}N$dx?*nz`757C{(ErWJrEJKcbpsy@xzk>3>L-S4I zc0t2?d$U6)xkg-K7W`H7<&a8GnZ%ugVz6SvtyeF(MZhcR;UbBRNQJ2Ucz#N09Y~sa zr0yhcB*#NYMm15Xaa{8$ZI870SK9Juh&OGMk0`Vf>Nc~=dYrZ`eA9L{RtU9&$M+Cl z$Vl;|?cP?n!5>2QhgUAgTfAx8Vl%1;q-|%&g&p>U;4kCyrfti1?olPAt)!IzrGkf+ zF>RN%a}O?|_)2bD@Oot8y3_WHnV*WUmPml06=&H*I+wiDXo< z>#^WBxl~Bmq9)>c`vJJ_r;CvFc)3|8tYj}N@|dcd$d0j4cU_3b6F<7e_dKvAtKHba zctxpltmD}n6a9J$ivU$JL%|1%T~q-tN5?vzVmlivniq9d0z<(EDz^n+NwYge9s?Ge zk5r|y-KUO@iOZ-l1($LmhY`!sP({+8HMh`~40OIgmChNb((A@N(2@O>ZR;Ha9RnM6 zYi#@D7&MADFut);4Mnk#_;bVrF|%dWwO~WcSm^XMZYNBdUmBs#(DS4 zbNjsC_}YJjRj4bVWS0on)|z)_$GdJDU%T8gwrrNpZWchzukpFT%t zd|qT%EyL7K_>R3Dd-208EjUUD9F*f-5iGE85VC5G`sKrLNOE|kC@I{4DAKQ0R|!z$ zIOQBoFkH`ZEy*0$$h=yP>ku|XaY21&$a}K3DBrl6Tu?u#Fb~G5IU0a zIVrKLsKwgGb6q8~a?deG4>HiM(uNnCiE=~zWsrYmZTV$fQPV86D_*V2q4``2px?Uq4XfG0h!~Ph#m#v`gx?4ib8z?hnipR>zcet;kc?-w^4bh-w643)>hd!t|g_^xK2azlUJHK zE_`=jD1?q}lhn9sq3xIc>JpiM6%xjcZgS-uOovu7KnluQYR9C>!-5 zO!Cierh^SFSAn-`T9rU^_Fzgba=gHXUgBWeEFa*%R^c}F!M4d~;4oI5J4%uIjg++K zo|z8CTKKKuq)ylz;c%$`jCLqPN`Y=z>wY-OmKCn8A`e{ZIJ_SV4u4@vvtkyw5`;++{6CKWKjy&$Ci6ND{+6BsSN2i@qFExjBI3=O-F#KBf7S@A4zD>cRRe{fW|*x;tE3=82^I6tudq#G_rq4W9x7D+`==6l&P%o0uVGF$LX=Coo1ns zCLtWqkv14f6w=&S4k|rbT0#r^hqSUDJz}6D5GiX}ivtK+tT;Uu1&?Ydq)iwHBzs7Q zAl7XU=@>L0OnXSDAZFP^ItOisJGECnY(kaAVn2~;!KZP_exjcx3Xd)OiT)OpOq>T; z{*e9yEp?@PkY$@Z53!t;{zEPKrTZ((RCyj|K~;}%!!4M=!g+)RGmtosviu_bM_c%@ zXg@K=f*BK>$674%{I#WvJdd-SlIKa52a-S8QdzpESXRsPR7;3FPqXxw=QPU|d7fqY zpFGdDSTT?mePXn*-GxW=i7~?V93aW2Xz2U=mcbn{qEK`qcHo(<4xx8~2cotZ zN}aUDN~eM?v&0YBF-x4b8I#(5i@nXmEd9E1J{(NJjdCW!=qOd5K@Q^~gpORwD#(!y zAKejWavLwO-#XQA0=9Y(X9^e}upg7byLlaLsWZim|6@NU!>=W_{19i#82vlJkI6`z zA7lI`0?DF&rjq4YS1cA@S`uN;))&^UAcpWb+u4S~Q5tQXEVJ(G>1-nrK6}573PRc# zf3+248H*M0+#a%|m9`R-DL#A`%Kh2iie*4&EIBIL6=BCJPT6wO^e<Z2A~b(s{OIfqtlC!4c441$I9&F!H9Y)ucCHfmX9RXK zLU{24vbQX+%i1)P3L@@hN?=XwSIKfEfGxt`SH4;a)h-g$nB@f^E5>qZjm6%GC}JZf z=(Awyb)~HU_0S;aH2iekOBSlr!c`C8l|(rPQMKRK_{JCF$9=>efX!2qLb`+CH?mE&$9ZI|*xie16BJ#2$G4cQfsT-|%(|II+*V_^J0 zm{ydTl@n#)KQikgHh7AK>7phM_3>AFv5EhYS!FkABuNYfbCj3u&8+%suuVI{i*(4A zvwWz$U{7W(&W2so;iDXY>}V!AGHXpuGmT>Tb;$0rTw0^11t!P--!qG|=Y|r&s|q={ zab287~d@21ktWWf?x4BzK$98_7xRA)M)otu z0=WXSpZPA3D=qt(?o`s|OIK(32!iWaRq(N9qp z$JnhHe!q}2jFpowP-xCQ<4_HG1qedb_YLJl?>`Y9)j8BhpHTQ*S2X+_U+-4qn&=y9 z;bE*8gvUq@r9+FuVmfXzaVWb_C~U-joI~|_qF&b*J$zE*`gDb|!6O=fCB!F`fpmX!D9s5qt~S1* ze!+6adhkf$P%fWPXzCY&pJOnWF<3ayH&ihUQci%!G!7Nz6Us!oj_{M+$crvZ?w%N< z6fFwU#e6aH-3@jXqKo-sI3xLe^%jNcVu2XWAn7VX7YoL4!b?|Cx>zWN6I8m2(Z#|s zoKVtLoGuoL;RKMb5_GX>3}2XZeMuLK#jwF>6*$Uc6^^(RX|4`i&dUb%r5yf65@dZY z)aj^mAMp@cW;q2$DzCe`5@HG1gKrpLUYng82)dRKIF|9sq$`apE`~$)4X!lNbp@_^ zVvtTY%SF}t*ujZA07m*pyx|wgK>sY&=tHIW+fOilWUntA1u+L^dWgN(>@7ub$JVGE zo+E-c_$%uayOx?2(H!u9nZWFmiH2P#$RlO8g;G2 zHccG1bh9@XrG%=sw+L478BWm}A^LwNlw8QAQdbF`ekBUiWYFe%sk_-kx%9yvr3B{1 z0;7W*+g1<`WF)Ct1}VA{$1&7(0m2(z!m&?UrYnI7QHrYNPY^V{Js0akTBiiYa3AQQJ;?3b0|&G^-k6!^Df*-2>uw^Z!EDqr3{ zXrc9(i4=n%8}5~x{%D76x}%ink3H(dZ1^wr$iyhDwxE3cg0=mz5;VR(W<)t5_JMH3 zL!upmM=!2g{f1+KAh#{VFOc2#$^(y;#fFdZ=5zQQq!j-J5%uxf$BWeLuN3p2TiuJ$ z!XS(IBgQ00W-OBVD>u@PI*YA zvEj9KyHjKC*jF9L5%(c`;gJiqT_?v=9&aRmYQ&Rbd7)Y~Qcq&@f z1HVRCC}1Mm&6gvx^YVsNhuK8ell_whVE?}xg)CW8xt(wP9)=%;C>5CRLw`T~=c(ReBF!^?o z0RAMU{dUoSAJE^GorycQ{4YVaT{9UQOx<}D76E~_N8qTEdxc+Z3*C7fF=Y&qC0jOr z-S|$Ni2N4p>4FFG?vxOY-?HlAs(TDywvHF!({N|F$3rOk&QT?hH#dpCb4&^3eOD;8 z-~aS<=aN4q@fK^2XiJGPu);44vwL4!{^^fzs*17LaZ`N>*-=`54_+>QOPgHzbp~qX znuV`1w02!fC2Hepuh&v%*YDG8WN>X(Y!vAlQOiPpu7lV|#^id5x8|$43U)VBgewtK zt{q%w8!Ob?_1g{&^>DRWk5~0w?~)7@=t>%hSF~MGE6~<(ZH_lmtn1J0*s{ZwvzU?W zu2oAhU+F4w4bNTI)>=d{u9ak?UM@YpLKEj&SyoUz*OV}Px!rXMQ=nQ`gQjR^yGpl* z$*!A)@wjx=z%>TDL>~jCxF%N=)YdiYy`I{;jMy@~olAqy0(5e9K8km`U86CtRl)Uj z9#jafmQiT`xh7*3OCHzuvNme!I)4ctG;p0hq@l8|x-+q3k?Z9pGi7l#et^$yy8bAF z-GW`Ou%$qdD;OV`Yvc+ZXrt1u@K+Y<;_A>2W8yA;i@k;G#-9oeb&Y&)qCT!#qw&mh zl`~l3uVDXLiz~YoZ6Mdd`B)I?N-KpbikXvWL2=<A3eD>%zHAEWzVzMnjHLn$Q;8Y;=7X2-xpI60;0M(&I0QYUgCGxPmnn zj&d4X*~jX5H4l(Uc6l&sXJCs>NCQM5gH+Pk+W)9_dl5t@|3o=X?hrS^Q*)shJ%4|*XMbc2X%#U5u<<>{ofr76@%misZ69=mWNtV=aG_i(ng}02#TzeIWdO z1@dGr1j{`_cWQD-hf9Rp@v;`Q5vf@Ka&ZTThfJKSrl!2& zuQfp*`dhr|BZ(GVLstAHQB6&E`b^RU-(UVIeI&bR24;rzVY$P;8I2ZKW#cIDjw-yy z#Z}cjZnWCC?9GAKq4E@58OZ~RcrEx2sXGa)|6O6>XRraXKT3IS23$s2aJn$c(KgTy zvVs*3gsr2dDockYU|i-rB)@v4jaXW%XPXw}$`;3Q85=RvmBX)DX=K3%5dFULsFJoM z$eM`DrmIkxKs(5tn94YCMShTra)9QnSXNlB;ttwj_9msIH2|fRhvu%_xD>le=eSTA zGj-hA!R)x?js$OVCN5W5|SlmVvM9_9B2FvtKmL4NKH zFpw)1S$*D8{8P;|pbz>flBYpR%k)%>8cEY)YjIN5jE;i>u8;EZQ$p5xu`R;{Is1lI z#7?qY6;)x0R2*9e`%OBt*zVv8xSP@XljI$$x3FA6QQNVG{TUv*nIuucVH?$=yTl{$ zDOIsAeiszx2)=v*Pkt2dL(Gv`!v{Rtw^YW>u|Pym#rEH_f5Yae)>8Z>BxHbNlQ4|L zL%-x4EN^#g6Y9p%CCA=G)x2HE)nVF_uQ6le*dfAYSut@q$379B%mXBG!*x^;e@w;;9V(h8~$r2{md{{grsio)M8t@TeEvz!>^D*8eWS_+LfjM|@*I%m8Da zheaB0`8w{4h!I#QF0W}DWP4a%lI_q$bi$MQu_%12w~aV+#0AKH{v?<8`*UG0fH@FZ zAN~Q^`%LoJB5(}Kw@lD1NTVqHrGB3*(8wp}dl5Mj+r!Hwjt8rPhecti zcTRCQM+GH(#&V?dC20MHHCK{3C1q8V@H?x}v3d!AG14vjS5DPeB5#DFVh8~v_H!(m zQ*D*Vnz4u{9*hbemOH1qDG?_k)UPCqW{|aEd96=5)mtf?yMdzS)KJJqeUi)PTz@4v zd!$u;&ZR@P{F7YfI__N0634>vOu1_}>ncm<&Y#iayBlQIHGuPl_`9E(?uO=0V6|`>;;eMnk*BuX zSt>$Lcf)eGl+L8+twi@?EfdFbKRtIfqr0De-{1Tz2(D}plWRyR+|#b$ACNMxg`xbJ zQ=XgEy81dXB<`Aw=aU|xQ?cAa?dAVwH-EApL%Lu2Y(xF%x-g5sL+29>F6T7CmU zKPk+ix8E`&^bSqF+TPGX#&l7wRd-BHiNtoTNl6#U*dSGtF3R`pOhKTjh)ltrl`<>9%i*9{fW(YA7!yD{u(1KkFo}FqSzmWxX+>P zv%`H3bDy2=bGUkb93I5UVSns$pR>8o+1=*|_c_vi&fz{sxzEw=b58d;#(j=;pL4m- zxz+QNkf23u=aW$P+2KBixzA4bIoy4A$ulJ_eo6Fuh~*w%?9*UX_%y5g>{j~Jt@No| z=~K7Tr>as)`X!H`XCbal-W{Vc`;WVhqMZYt zU*NAqb2XKRZ$Bvv!We`o3qdunuz*+izip^7nnKXpBcz^u&pw|Nwg96U@;Qqh^q;sK zF$$FNOe@C0ZzviqgGDe|kMGUoSi* z*+cBqNS_J$PISb_mDndgvrC6V!zmG066z-ByS@=0_ws{x63Y@;wp7`T0hrfQ@(o{L zP{Rpk5ap>l8yj@?j{x!YJm-N=RxOcM3Aa^?3$jSK4O*73+;Sa_VV_;9K`ZhtJE2v5 zRAVSluZ7T`vqMcJ+M8rUg$WqJQDU)S@0*%A447~cyEP%~swG`?a(=0;N@Q)KH}zEU z9!=#673oa_)wNgCJ+&LXX_Qw66=EM2pLeG>ja4^?7I@=8j)9L>+!LViq|^ze_4L;6 ze_ve23eI;~$KlKZILg=q-{;A8anCX9UmZV=M;Tv*MmZ>m! zo07E#K7*MvrW+iTR0nN@fZ~>&QWCZr-(DS%BlQz)ph`I78}I*uMA#_NpnuwkllA5#>VxG6Yg3{F#(yZF8rwsFeCw+x)+ zvfz;+ntGg9)?#IkXr($&i;cldZWHwY8P^KgDjvfsArU7sHRab%urW|Ewx|{R>$>AG zQSAJV^>mCYmS~Xy=W*Z{99V{%D2j%$Ro&tm?A1uZq0eZaDAuK6!I|hC7iTa_*8R`2 zR^Vk1yb2JPzo${MER+9j=|mBSuODE8>8ODf)V@?HFY9fFi}G0562t7+!z=1u9d($j z%l`+zY6ZTc>2VLPS)~vToO^5svro;rKV;4|`f?I-?o;WhS{l2B zvM!<^A#zxG>H#3i%2N;3zr2K!rHH)7R4ALKa3NMiK3TG~0#g3tL)IFqHRy3ZClmuihJdW1$ndjF;e7=BM)((upr( zIDKfGV4+Urk97^f2M8fg#$WlH@5K(B+&WP>eDxu6VJh`C)O*MuQpO9*=oH1tQY&#L{I)dl)VRd6~*@kJhS)S z&E{s4+%!nxLIP<(LWhLVJ4g$?Nbg9OUi<-q0)l`@F9J%DrXmW66hTChA_AhKSP&2e z6hyFreD684yZ0u4zwddzJkL(fob#SDWoKsRP8G)~TKnB8oEe!oKuMPe+$A}q%HxV& zT^@9&a58(G!*2n3$X$}N;0C_Hx_nQ)>6TgOV(9X)JDFedAGgWM5qC1{E$c&Zd0%C4 z%YTbd)Q?)SU*agaA6T;Q@hd}@$1K_T;}pV&mh8)N6v9XDVr;WdP4XRg`#CNX@f%u~ zC*28i@Kr2xwHb<0HQfED%Tw;e)x`2%$7|}AO{~-I60Z|$et+b4#C=ly)LnwjcudNe zv+j}{#N8=WW4FMS#JXi|AANQ~)bUX}5E~->KB_3OhD`T;tB4HWZ;HtD zc~DRwD(#C`L>XVYBFg%zC?d<(L=oA(u8Jt<8>EQxzHy4E;G3g}ioVr~sN~zKh|0db zim2i{p@^!!Zxm6@cT*9$zP}Yw-4~96gZR|&B`cz)ud*U)`5G&tj<1U%>idQ&qLFW^ zA{zUiS40!vDn&H)ZBaxs-yTIg=KDYq&3)$-(Zct=B3k->RYWV_Lq)Xqh2fnbKKZ@` zMYQo{D59;esv_F?8YrT@uZiZy7(q5qN{JdA|CgxS40orTZ-uEJEDj_ zzB7vG>-z@8TG;}ZK8DJq@QaJF@J-T8QK-y_gy79nnC+Eu;r~Do8zxIcZ=H`%RhUeU zUKWK04^(=*#ma~$)>=8c67I5=MLcOspb{>Vix7d%%3!Qa4wng0?~ZrzU?Ly&pG&QA zt!I4Js-vCDgH|0qT@HgV{h>Srk2Z#o&Z?s`zoWlC9sGH=tk9~XPIoYt@G^vZ900F6 znglay)lm_9(UBV)+XD-a^5>#A`4yCI|A%71g-2gJLL~I1_*sdEBPi+ifxyBeiB-GL zQh;Rvs8$fya}c%BO+aohKKkK~br8TF$PPGiXYoeRoZP`~YMY0@;g?9)4wQ(yb3bQyUamd{pkDl@om+8)nO`vSlwm z+8bvrKAHu<^EQZ<8>z)dl-1-5T6~1g93M>Kp{h4!5>{Jb(xj{FWC;>8GPB?U%1Bm>RG>C%`{d;|P0OBp|9Ci58Bi?PTwFp4l~n<&>p*|x5=Lu4Xr1EX zW#Qr$1=tmU{slo!bD>{B5u6O+vku^HzzUj+TwHO^R@MQq?Y}^1E*c!e;u8w$0|3rA zphC^Xn`nTqL3q;!1ey!~16;g9Iiat@-3WNJzc?0lbMX&;Q*I%7I%HXn+-WXKPDXXB z4}MEqR;an?z7ao6D24+87-oY4%|#MsaJjzEg6w%mZZ{Vh#jNSfO%QE=YZ>D$&^ z-!aHe2IO{g;ltbqkJDU(?4~1knu`Wun55S*b`*|By?4sbKyy)1S}P1Q0H{PD%Ai7P z6(28QH5V-a=u`+~Hy7L93|DOm4ONY|L4oFCD|R+SI~ z_S>L9b3s{MsJUqP-8`(;n;w9oEy$wbPq>YoaI^aX=LaTJ;rNg~ z#_^`{F3T_%((*Pid5|~4!}+F~1o|yn9U*u|q5`Is2t|h=wT!3lOPGBqjuU!Pvzm~= z(-T@rTX1_#YIX$CB7&f)6+@rF#p7}jILpcIBT7wY7F7)$*%~!w2iSXUk@WV0oLA_i z=7okouvXuE3i;QB@j)z$Foss>q}B=DfFC-X$M+x?h*c2Ard?+o4ZEz(QZugD^Z90zVk zpSYK`5X@eA+%!iPA!A+b0rDUF3i0vZ#O8C&U*{gJ3;cVbz=p@Qa_}-;M9TQ^MS#7a z9ZL?i#wa6YqUq1Vo@L>GD-m4||Mclt3FnW&f+m;$7*0sVxW{GfAl|78$|s{-Cn+e} z_bB|$(bJWT!=NU9@fv>W`})?%-oqyf7q+W^nqQ1Iw0tK&OGoLK31MsHNdz7($3@~Zad<%mzeOJx_!gaeAEjX_l(zkcV!?0GXRYv>4g+@5 zf%c%Q4z4eMXhgJ zjYlPjavibrEm|3FeXH6+);S=zzeOFeeuck9PeL}qkvrd_ab?h;%m;r3$*8nR%Fn>J z=;d41Q5m}cIA|Lv^ey`LXIvda{o5}9_@NNU{ub@_Ss$#20Ju=(t*o}!&Hpe!P5w$h zWSO>HsRVJFfTlJm@GYXOF7z$J=YdZn^E^PMYrejXThuG%fA}`&Jj{63 zs}yzuX6i18G(x_zFjW*ynj?8Y4!PAVYULReun2}p`4|2!zJ?vs{E{a=5^{ThvkDoD=A52c-;r9X#V zoC!m`j5VG{nD~&x5v4JBH2FWoREb{l>`Ot%b`IE!ZIRkKtK_eGR$yPS+ydEKjy#(5 z`QFHk9@&%{=^>%g*y4%qkK*$c7}p$)_&|tTJ##*X#eX2vF;~Npk;U2K0TY?fGmA4E zdva`x+dMDqMPrx^My{ig8nF1Lr!)@UmMtOc?8wWIoNrpp*cE0xhtD1uaunoK{tNSY z*y;#fVU|F?&cX0uD$34JVZHFPi|xDv`B4YM`Jpg3!cwt6gfW*OzwTf-2NdR3*q1oS zlreG>y1saVazSB!37b*LvXcgR1qZ|Fj;4iO8Mnh;onfV`8RT6Y48=!QqYQ{l=#Dl1 zy|a>2P!2tWa1B3--LfTQ*mrAj$pHbM0e7LJ%js31WEpmHwUywl0KDyhIKc{(BEw3! zq_Xr002dt)r&xhX%CIjIEYR-&JaRz%;uWZr4D0c}mF9%a*n)sZ3noOgXdHN?l(7hC3jYItKNXDP1s=%a&#X@S+1!sbf$-8Rk7_ zfp!3}*8!>2F=&tsEBTm}PiFzR%5L7dA*J`KK~IXPG7c4YG%}+%odP zX&CuIdiQoR1bsGS(XHrg;;~YCBn01%yE36@tQFH7$Z8dm|1J~Ox3%P*AnRkxtw6#k zruSsRuAf3xOs4?wv<(t2mfx2NcQBC3DOnBKW?OC<>2)3@;~!b#AD^`v^e_M?9gwPB z40<3#KgBQuuV%Xjz#Rufc_~~BdMHC9OX&&}whimQ@o<`@D(-)^#>Y!)DZ>nx%9siO zRI@?C_24L8p{Aug;m40b%D8;UItJudFbk34)>1ZL>X79lAsZKvzl;T186GWV@fU6- zUkKUKfIRyo%Bm5VEBK`Ja@(QJQ!8lP;zI24uSf z^6w~rqc!i&kF4;|Kz1P@e~I!p2D>^>SOYD$A-f-tm!|xU)x4JstIOxxf%N0C(toQi zK3;K}_qAE*-JllA3XoL`$p5DNEuwjQeQzx!&4;XGKwfSX>=)I%Pam;{H%3A>E+AiY z$SpGBHSbTj#Eb1OgluU*-flYD_R}^ zHxD19bS?Sy7s9Rg57|GqTs4HQ7Ff)lk)e5~uCfYA+-unSibvH1u2a`#`5YlCWNgwR zA^8v`!f)z~1Ddx+xD;E#e!~&vebE3Vc9e?LUzXPiR%e*w2N9T9SkSxeaxg3hF}0MU>XiclH! zjTSX_Jo;H+kAi$WVU|z|RR(>ldAqe#1#lrmt8B5PQ#`B;`cCt1+Kn85Y&Xd%2#6?y ze!`OQpLKBp>`xt0-mzIIy1!}>91WFSx3vh$t_sK!;9O}Ts65rQB28Kv>R68OH}Da} zV-@~7b8*UFj#lI~?26=LJF+3G?8wUx!>CC{4Xs?sb5bl@gMpRSkjYQaBH7clP8!~P zO)cl#FQ%Z5pmZh9M_e0gX4)mI>p2DRr^y`u8gTtUZ>_mzKHb*p$*hL#<$(NWlDE*z z9hp`!-4EFjlB>`0;Gbc?rDi79wd7wzb~zyLhzanFR+_nWuvHfxkZh-;uMb0ZwARcB zj2duVECyN0fV@B1&)3WY!uq9K6SDdNc^($IWwg=EFEXsv|J@+#X*KLs`un0MUWf>XIYL%8^ zZ6a|#g8VdLI4|l79ci7fWo*RU#8t2*9quFQ{uPclwm{2xp|unb9Ck#{mFO<5_q=-; zJ+(yqbSr}=tjsDyyqj%BNXGq(S6CK~n5F%>Ul%S|tcDWSy$*I-G znLCW_!1xzndQkZ9(%}#Ot^4q6&;MYA3jOm z>@pT#;n%PKL=yx1i?8D5FR%a8<`Sb6+hwh4_Q+V~hsKCq2q7~Li_^Bq-B)RylRs*$ zA*T7Wa4LA+E%M9F=x<1Wt?B}MlXJ)8It+hbY|=6O{#aae=#RjPC%6C3b6B9{UwIKf zQvEu%ZiQ@-JF&F$k=!B|EklMITjXb$`xWjj@_*?_jJ8F-u`^UWirgaK#lZTbM_Xid zM2hbHnO*|9l)Ode{DzfTb>Gr@U^@aGiN98x0BRckCWu=5a6Gh;>5-uw@cTcMe3^!f z8;>;;@k2Z(_+xvp(<1bS61*N=#!GZ-7&ISRJeg9Qp7(%Lr_0x z^j(UPH4?s#7ObQASfqDwENWPcY+~4UnLPzm2mK`H^#f1R~;;lG}_ad#|(4kn6SjSIi*Dulrj3!TZ={=Yh)?#J7 z_)!=&ij9>Gip-kMM8hJqB?O#C#poP_LoPZeAyzg{`*|$0n-sY>6FJ%ZI=VDvie;DH zOHCb>MAg)l$<&v?wm$~*y25|^X|x6Y7YCACx;Zs|-RLYB|0uMyXgbPQMrx#g>ol|w z{^Z^`9{w$D$iD!KY2qzS$8pk>Hjy!=ai}PB+u!u%P*D}eU&kYf5E(t*&_tQ0MQcZlTehO5{pJOiDD!!0%{a+t`*~0RS|Z z6(;5o`zZis7X(GHkusi=bav(%$X>DKB4Rk%FXw6SJU&xjrg2J$Z; z`@xpW1r$CHYh~poeY#6m!9RdJiY~G?de1Dde$@;BawwsfP(&i$B12oe^Xb%~>0r;Y4T%Uk zMkeb`@3jbYCs%{L*%nF4F%g}JTg0<=CvL|jAspy?ke?t7SyrLXkR=--4f|4FPqaYM z3+D-u^?q0qeu4Ao_~j=qZ<2dmJ?v1=?so zLfpp+&9FzNbx058gveM`L5Q-GQ}%CD8JYvA%IkL5(GMz}92I{VmlYD1PjlcMcJH|^ ziBM5GA!@@^)bg}D66UkZhm1yRltP&$B8ZjU(6ehQy3VtqJRgt7hi@xUE6?;VVDc5P zU$aGW8aMuCtBqN>K$he4cLr|U#d~)LP zaQNz*#4U+3GQ)FpDdOsDmJQRP{`SyiF?551k})i$e`*$YelkOj5~^R*Xddi z`3#T?9WlQuV58)Sbva<$bpy9Vx>e9i*I97IjV zqYRWA)O$2asq}U>ts#uckkz*3YE!2IJtnTodM|UfOy0$qybKS$X+bN{yreN z8JYt5EC<7th8v*l8kML~kvssK{g#Yde^h6nd=2QgYz^W1_;aM~s7yRO$Qm6x4cYlZ z^6N5j{b6f#?H9=YvgPXCPt&Ni%>GBFJpYE(&!Kz6j2LT6WSE1QW*t3CoeYMfn6 z^M17jeb3t9H^ZaK2^AgOBG)zAE3!w+37g8e#hV{OaUc+AdZ-QKJXLunJoE`YBpYJ3 zrs6ln54O}qTcp}*qf`~-mYGYIs8tQWW_Xf*0UAtal73AlisJ_e-~>hEBZ`4DN&gw9 z1mySN-?U|gCh1R3LTjtNhm(Wwu(DeBbq;0jaorudcuoD0Cxf*=(j4z>%$WT@N@;T{KYHDCpk^rJLQS@{%z zum1~#N&2`EAqsRK0D0I>bHPdaYdFk87KPAn0|JxuV}HXjxRet)kkumj4UUC9N#6v! zaVL?y6J*^Txid-sK?ZD(2LFGytk5KVugRw1++PmBOExGlN&oU#s}k;o?4TpJC+UCu zz^cQaLv+azJCpQHpR!g7{Q=p-fZU#>uZ>^jJV{^l2-1&7rO%n9_h2WGtPFl_l2K`s z^y&hW^kS)V_YJ&m`#zwTZez_fi z?369%-hy!1ll0LSOf^aWBLKH-P+*dtvbxYDeJItls58>DgKn5gM_sFi$GRUwC7F99 ztQvZ<2o_Gyl*vtIpsIBR@QDBz7jMwrQc8z!)!`dsc?DVR>Zm|dfSrYh5l#<F^9{g`@S)nT5<^`0_dk}h$ zTFR=*{|{ygRryr~s(gDo(5D=f8vKW1!7Bem5;CI;VEr8EOp2wmE+@vXiRUQ5{{b+k zAjqlm3*W^jbS;Ei9l*kX6;%1n0=GGmm7@TB@?RiS`K{PZ#Gs!5_}u{&tn%TxXhglJ zJ3c%rN1Y|*cTpqvQ%;nDtOCiGaxCmBUmOebE|L5($nqVzQ{|s}9kvI6KgyOBs`A64 z!v*L5TmW9ML4hjot73iFw?Vekk=s??z0j)iA47D;5j$00%(dh{Lv}kLx2wFq!n(BC zdkpEvqtfS8`Qx{d!|C8xBpH=9N%smhjJ<%h1YmXu!v;5!=>sPdH6|8G_P>6Lho zIG0Y8#$#7`PBK?{R^{re^~BG!8UQuM!RZ6r~oS>n6Ye#aQkG;sYCHb@*wUDQ<*%;(52A zh{|suzd{&JRy2z{gl6LGi@!)PD4h_{(b6hm5*AW65Sl9RzVdTs7j zWE!riB}i?En>i4U=^c6PBbTV1?YV=U1=jg%f+G9`a3cxJamgRoQ*7=TOL=D)?Qvno z2Pe7jM_DR7gilzCg9zwlzY8V%Wz&ySt5nd-Ca?HR8`?TdjP!mhJ+z3n^T+t@a=$Um zEXMX*QxrWR#Wk4thr%8=7kyBg64!=+lGEXcCkf@fDnmOq$AV>Or{O7#oJGhBT3Ler zEJN$lKs80IF0lFk7f+F+;WXhPP{wbSu`nWC)(Vq+E!F>^003QPC;6tib_-s@NzWxp zG@6KtuY^%GAmlsH+RZ)`LP9y-5POx7FNEUt*uJ_~Lxp!hg%pI~YyX@ky#1?xR0(v0 z=J>|-t2F|2%=f=z|HTyPX|>2J+_gO7UuA_)jM+yCt4cdGs?w&7s zj9;@AG_OjaIxU-ghVWy~nBlDUc{s+Vp!RklHJ6G3{~lnqm8=%ALaF6lmaKNOkeX3g z?G~%O^$0~5kvxN$v|b3U6qUV3f^zl$M3P!4E0PP+RA{liLRhV9A+_L0vYLwI$bVI6 zvrdGu+6#r$f+NXl9Ld94Y7~w=tyAv!D~5PosRUkFyF3hIht&%I^;yX^N3HU%S`S;m zg>KMG_nd%^Zcth9Tws!li06AIY0Hl1CP=rjstUQp(2aGVb>?_NPoen4;J$(f*i@q% zx8S;ss+fj$Gp!qWpmpZxMjhsddx+DJ>Gn~CBw9DRfYuG-=td8?-hChH;`;~?`-d9h zN#^&3>o&Gwg__$SS~uPRtuseA-e&#`=I>+rHm2;|2GP24543l2<8bjg5j#-nLX(L9 zH)HCTA|%ne(FC+^5Jxv!Fh7xzZJ3^wN=Tx0V;*Sl8#sP_I1zQTG_ekZZoI&lFS7_q zv~GL@S~rNJ8$U3AC-bi}UA!D2iPnu$puI=#U=KYJJpM@-7rDx261#FiuvC% zzX;PU>JgG?-Dm^a+dai4Did)QGb8;$=tf7lo|I3hxV(g8N8HTNjaNYH%+ZZknLm!< zJ3xE#8U6!S?Yj+P=*D%>-otsgEuM(ln8tko0ws(wRofAgXp}I}C}Hf@VSYHKKT*P% zp46U@MC-;>(B3jQ|Fky|eTHEb83^5&$(WOvH+M6w8=r#K4dUp=1?F#Hdy~Qxc^k;Vv-ZhvI07o~H7}IwEA&J(FL7;VmIJz;6`8AmTB-5`BBqY(gu>-WX zD>m3HAR;Os*G+-YjW-$d_Xt7~ts9R(qXe_-9!dPO%nxO{&M4v#jobk3^>qmm=|o%_ z>K2_r=teWfyfBfFMC-;<&?v#|u44XR=C5P=!X!cxts7r~_U^-^%K;)hXz_mqp&Q>Z zCUXWMiPnv5&?v#|R${)GOq?91hs`7;(Yo;@Xm8Ct+zvs+nr)_d7KCn$XUw5_gd|!w zj)F!BX7@Prmofh|)9(3%Bw9B@L3^v>&fXi(gLq+TnDB$68xf4@xRj7Y>&D}tQG(g+ z#r$&2@6YtAWrQReZ6Ijx>aJ2e%}lzcKGC3Fw{G-VAw}73aNNer&l3AdxC6=n(d;Z1 zwX_0(9g#CaU82%TGPRmrx}*TWE2&h?D6_l)2s3w$w!tSs`&Jo4~pS(W7c< z4f3@nbtuk(Et|OEECVHaoS%wo)MQR1v3_-A8(4OMWmTfdr=N!k55M-vVRNgZ$bjEr zyNw$hBjZ(yR~lUJ%X5Vo&faIqyZ1d@h6SSfOIxG}b2-WmQSBF+PI^A2!3lJ4z$dd`)R&njeuy z$`)C^Y1HdEn6aOKRul}b4? zc01BDemdnq6V@0WtWnPFq%_K#tGdqwjWRCI%i58_nGJfjpV znYSsZb6881Ap5XheOpgPfKupmP*AIE`gU-dDw`ER^cdfm($t^TCOT?%5v^=?S87$v ze5F>!917x;96Dkk^aiosc3Y1EsA4WwDpk$dN~Nm#3Wd}TM@uEhA*}IDutrt$LwI!q zOHar^HS-|gxj zdI@qKYxi`t?P`@{)>nGDW?jHxAlG~xM2~rMaelm9z-lkpYDzvyX;e4IDUIspLeeN# zmR|T;)_6Zyqq@0WY2=w(l}4ULah{EIX)v8X>m zZe)#&FM~=*4bulNqF>XDeVx-$)2srb$2knGB*<4;qlc}*K83EY)asb+m0BHhgiSoB zh`Q!Rn|RMAzEVUz^S(_)y}_Z@GqV&?-)v$NeQe?>MKmy%+r%!LIIW0==1(@^-pK|V znk5v`$jq~et~N1A5sl52HnGnpE-Ipl`L|6Z;!ZMTP!lsx5lzjmHZjR2Rw|;Ixz8pp z+Qi?Ac+5=P#daPu^K7E4B3hY~Y+?zB9^<%`>A;zN{$kL}YGodP7jbEAzM(W)nVE@Fd5Tk}cM_)v7Mh7zqM30K& zsR}*K8o9w59n2JX0qkg2QyLx3Hl(rXH_{l-8czgkbTr#3jZWrJrP0Zp2V#zF*o{8Q zjV0^6V(YMvLg-{ZqZB)v+m&Kx^DKxXt^vb(L$S3|{Jwyqqutp&sIPS6 zYi#0(P5fvRA$yQ(>-$rwd65I(_gSm|@~d9X%r^F5`}#~h+G`k2p>Ml5I8Q>+pCZBXj_ zn7=8FzUF$R(bwD$Vvg*=sn3&=CP`}r>-05K;YD=%nV&12e&%nivzJp}SLuuj*6C+< zRyzI7@OL;Z{mo1eb7a-2^e)p?vDz4{)8Cw@bOx9Wl+FONFY8RWMW0cZ()q^L;nY#Q z2AJVY<`1kG@1ZRBDaCw8 z(f;5MGAn@x3xiG9K2F|XGZVxdndqlxuCh{`UqI36OAR)MDD5ZAmP-2xa}aCyHuZPBRI{63Y|Kaz2g;j5EnbQU%ut~D9E9w=@ zVV1d!`A<9=SrV44iEF?R%s4j&zoRXaq|J_4A(e@yW|#Hg4FhC?1LJa%J{>DnlVmf` z%s+)#k4VWy0IVTU4TK}>QDEtF8T6QEuPa=E_5g6?KS9kskH=eS-Am-KPko0FXr>O12f9>mL)Sm0k)5l`yC=0Bs6^ zCS&F~Nw(JazlH0INp}bU;~bC*j@F?k$$aBnLo5-*Ad6fGz$yX-rJmNIC&@OEqefex zw*h#s5NJKt)FsKb#_-Rqopu)ixLOEA*Dxi?cE+_RYeoAb0K8WU2DjZsg`mBW7;h~W zNd=&MA<)DJ6ek=Uj7zyW;>`ePUkG$!6%M+Q9lhVI6MU4b91g%38zj=Ve=8yH6n5#P z6hBg-nGf0GfIQYsG3l)TgDoJOg|9*O4$1jts4OhMkYdtB|KxvR3Um&DZyXTW73sg8 z@dDJ}7k?aItBU>}`Adl_6;#+uM`9eQob^x2THsv%S?$oACBmUQCfujS!xz zsLAu>H!X3}OOhN>l;T*Lcvy!-%q01wtLPofi=G1d93HJDCCZYGbG59E4bDG-|CcQ* zP(_uAN#>GYVZsO7NqE?V`gpA1kdx$OvnS56mX#o_ zV-|fgq;EP1)hJMy#biBW;W=wrz)1kk+8~ibH5#WEy)U|yJQK2Vj=Xl_I?NHHj+FcrDXjhPCPH^G$&yi9 z|CZv_p(Ocy!qW?(?w8Xr*_0$_Wc-W*NbhgI+?j=og5=DM)SPhU%#&qbg*r9P)o=X& zXq&b6kwYp7Q-|WSk{{j5FwyeOLw;ShK*u5(0kkvRmY(l*Rr*VFS zC6cufDOnzXJOcGcIC2OD<}}VB%WxS7f!YJm^FKk&JzH@{1%oC6Fx3VH8t0ujj92xK?T-CCFmWc-AAVm!gA zw;Sg?3~O_vkqtmDfr3(RH_lDlSnY0G0J;|f*^TqGEbI2b@c=ws2xK?TlLuG}epUmp zxe&;1oImewwcv*VI9Ui}H_pG{)-jIwH304u0@;mo@8Y^@oWp*`S~fhKxn4^1;?ZW1EhU=fX|W3pc4x2$ z*&<20?1;{+KQrR{lhA((fY}a+(-Tcyy_jc0CN9DWuxLQ#ddRmEWNCbX z8&dB%Q&0meKY;v!J1W>i~H#!UV;c+KHICQ7^Q$HV03Hd}bjG zH4`!Oyq}D-s_h!cUoC{8RwCwkZ_(aXOL7?UlZ7zUNW{$d-ox!jT>Y;?e!CEc+K8A1 z-d#(rG79eEs1k+A9x4PQAs-hoL7lglCC1o!R_-o#O#S`vEC}`Cu9p83LUdQs)x1xQyztisuw?MH$FpN z9E^Gzr)9_=wZYhEA9E<`)?qXq7qu1mbs6(s)c1EF`_s{xAsb^PC+2We^B=8(FhibO zjS!ARW#V*DEFl{DmGP z`TR21b8iqbbPqH>#G{4uL+^(V#|Z}|*2&ztA%LZZjmbnhJ%q6|8+yh+1ojR%@{X+; zW2@V!e9uJ#*;N#XtpAIW9EfGGtLL7H&TDkmU#xkY4dIJ6K&@s>--xAcemUN|d%Cr$W(NR!2~@&~c6y^!%+$(fy}w{{ z4d?q=0Dde0lCvrz%_I~Se4+R1Aqy@sNLvI?z^42Rdw8uLm$JUn>|~#>QUTCL1>wgD z&i8p();F0a&REua0y?H3{568}ScnCG!yLBK`lUG^&{qn=(9_*S z?*(zagK_JmITr_eN%Ou(6vGpg-hsimS5aQRMmnkh)36|pH~87`dR|}$cYg_RH#4lTF-m|!A^AM!x2~n^r%QDaw z@4MpK;Ld5;NsI5XS}n%kt#!@p7HH( zRs((<^7Dj=BV&w-sQwS^)H5XZ+sU6G`^&Kr6xg|1I76{Xv3|P@K~1rYMl|E`upu!+ z#$NP_3N4F#*aV+ue4Av+)d@I9vqR*cLlvVwuq|!83OIlGpq`>ar#K2lBwaw3Rp=Z^ z%E?LX(c7%hr5J@&ca~NUxlx7gpqoJkC>vDQM|ip-sz+TBD@;*b#)Q|on-T^hF`nAh zI(I9F!jsINpS8A)8p4;RM8Ax7!Ba+gF1$@j<&~%R3O77elqUs8TNjtrl_z`#>C{%9 zOSsIdxNM+2JB|>nneuemLa^32^rS^5@xXid;n zj6!3fCw?Tk4I0*T8}x%oXV-1eNH5l&g0CAiB!V?W_}Sz(XpF>d(8z;sxx~>8`cdVf zACJ00BN1+cei*oUkX2{bLqDxzOJFVE&~zrsM$A=2xri$n%&BaiPGh2q=~ALlD$%JgkVO=AVjq%+xbE8qLi_ zMYJ$$D59nLxFTAalNFI~E>c7ra~Ft3+L!^AMY4W6GxWXKMbK{eVF7iH2A zjXl~E7tLOb_R#OsxL8+j-0FtYzcBuXN1GOc##M>pTz}L>o6#8Tj{aU~<`zhH4@LeCm3pz(&dGTzqJylO;p4MeYy*|`)V4+O-OHA+mf zeyQ$<=tw|JqcCyV#wTy%n+Ul43ZiSaSiZm}XcQ){oUsQ3B#e0kxfj{MAy^n1VTmhm z^bfH*_N5>%R|rERHE|V;4acnhb`!|k7Q)a7OI$@`aRn>7Lm(el2ty+^ag_`dFcqH# zkgqI=nZdu5<8q7C{zVs*3M?F^tW4wiptw3AG8NWsrHF7OGj@O8DUW6YHi-LwBJ2R-UId%#3D*;f;0dWV%dZ{gA7T3a& z2e2)>0H9v#2}xr-ajjyWnWZb)Sd#I`Z#2K~4&J>OGay59K17Sj_RAbMIx#S=lhOPN z6t;lc`EqI0&Ue3jIB2rzD-c@hU9a-?oT{zoAU4FSdt3SaQM z5U)WAs~Kpv&dvg5hlT*-28R#)*HoA)kk=`M;lek>7+KZ&;oBMVzJ#HaSn=V)H`J)N z+!`~P0{N^$7%qInjEVU0aRFTi`L;qBE_}m{&v2kSV~#@pNg)guz7a;-6IS874*A_e z7%qGxjmH*Szn@GLq@s9&;@pWQ+2Wow8m6OHmubr|B1Rc{Lu(4o&#HXB7)Q+s?w*KS zB&&d(kcw4J71G0uJ@Dj@?mtSThpR>=sRa(|Nsln75WACNDtbkFB=-({i)AS&Wsf(- zGAO-_M_W<>H}`Vy_^c$0jR(5L8@51*geNBp5uYAyT%%AXi1g@UTq5%)f-FI#kv|D! zNg{nBp%KngO-_$7lF<$lJccoX;4zG0cuX3@^T&gmNo2f8Sk%EQa?@jtrZm}mWQtp) z$Cjj|iKJ4P9!ig`MKJ)b#G4q?PA_7-M!5fBJ#Bh?cpJurQ%Vy!r4^E%NemO|i9U|U zVp$wYJMu%sd?>BJqunhZNH$pvovDeaNXk`r*>Hk$i2n8zKn@pWL?i?bNkC?%`S5oMnEJ zkpmfFyS~!QE0)fUz&dEuR>)dFL3G_n-1*FHOqgfPq4L>XT?`|l!}u`q6bRiIeGtv7 z?!hgwh8N?eZf59Ad;H9fIRpifs*63O=`W4Omxw8qLqzIFAR6R^h{{BqKkgQri3mOI z7Q2af_bIRFOT^9@UNIU3Hk071>pkDeC5|J~ZsRH^Ad*Aw4;TBejvzwIIAmgD0~Q!= zW6n`>iPkOpUC`cR$++b6IEX8s86u8|Lz{8dAQ45jx-&R+M5JS5Y*9IJh166YX# znM;Tml;jmBh=@q>imyOimbI}XB;sQ!uDh@o5C6SUhAy5b;-ZOPXdv#&{#ame7F6B( zk%&&+6A<1&C$t?AUv@)72m-H#-34&n#>b~5cJ(NlT%9?(QS=PagV;R^jOPU%2{PXJ zl$40=HeNkTs)|E!w?*#&-))@1VgPJ3V+^^v@fkR7V;StYjq~S8S8>R)+oHb&-)%g0 zf!vJG$gK<)+Zq|Kr1d^0-66o}?4ozd^e~RYWsdSTj;G>K^mXGCPAIumK6I1;bQv`Tn~Nobb~(hZp$Th^*k^_T?XNfO}>8l-69FJnG5$R-~9-KJtbw)V&(BFZ?dqYOz>o(-VXeu3g*kC zKW=kfHO86@NID*EQw+rR)^qegV7EoLvKU+-Llgc#3}HtE)oTm`(U z>)RrcPZ1T1SqjfAqI{P?y+G7W9P{K^MN|S7H+eRK`d0QHJ3;JCsc}n7sEdw6Dd{(S zM=-y+FFuYe`buFp|dCKrXo)OO?8M*-{-q8sX6n z1|<&X_v8=3RXjx%HZpYB8->TF1X9F^y41FDB2q&nvBSS}uBXMamBIbSgRN~U4 zk6+x>KFk0qPLbDFEukAh!i_ixy4M&;m3tW=a4wm_Z&3^8!L~2qhKMP(UK_XlH_60BYrVGE^1gj9eso7dE6jhN5x9 z9~o*3NM|y1ImnPMJbv(6yi&z7w6(CI5XVpgK0;(@6(H-$(8!?jj?32ukf9ImV*riH z``ute^feU&Q%2$YjH0$5HH~sp4Z7xpIj?OHF5Mpfjlyt7~NQ} z3TZYVmGNlff?|Z5-v1;+X*DfF&lENk>KJ;hn#$~PfJ`AnQ-TbkX{!fbi&9vS!$~_` z*pSyT)NQgdbO?|S$k5Y4hP=Y_92xo>odGsfG@?+_!W=^;Zm6fsHUNphqsmZ4sS4VjLix)_ZmLu~-*M26-E88U^Z7aIyfYgh#s^WC)GjA7rQk##-6X%)*AGV`$O$A#7+YAd|_^rXWN37S;u? zMLLd|XG5og4b6WB?`WV=FN{m}&p0@EIyeUbIZB4kScY05nkbNS$WZ&fR*Z_^LKUZE zlOdmDC_8sf$W`~mtpH>#8H&RRqrzy$8CPXo@1abs@i%|y$d*hjY znrX8y@#ir;f$618UtxM3)A{`fvz6)npa)=&ix`WT@?LrB^o<#SCYCtWcYq3YEw}n| zx^avo3rO;aB`X|>IS`U9BxwXH)V0!*%#{L@`suP+Ed5WwNcm3yNg{Z@UB+W77w35^ zRFeq$zZ?;Yj0TE`AXJZq>q22_A^#dHO8`E4hNm^>$OxPVk}jW@{G+cSNvY;z=fjr2 z@l#mlD?uL;(2qrHZ+V-Y=t{~LBPkj)3dro3Rb1!-;!G_4r=T`C0ki$NQUOj!(0{W0 zfn$aNFKWhq3d1jBi69d{Iwm;oHX=zz5Q1!k;xiQ#&AIa6Ka}(vvGkvm$`F7El}a1% zQv?CXLUYH06$^hXW{za8j3t6JhdCy!SSUm_89@ZuSm4-T#D}hZ_`p3UK63T$Ggvg0 zo3$iD;5UFOaO_eqR_6|%ZctwhM>ybxyNwS@(+>yw=Ih)+#eoQrV(Tw+j$+=X?CcH% z**lEfU)W6@PIOmx7qWYd-3RPe8bQ)QaLaBbXD>O&$T?5WWpZwl^DjB(NH~dbu4oy! z#Oo#SzLRaYh2VnM;$b+nh2u><0NtRku5QpLQ#a^)ho69GO?895G`c~b3EiMJUgr-z z&WAvQq#Gw-TQ};BqUu#~47tQfwD`o)4Qf8|^BHwn=Y~r+sENnUZY)!Fvx~zaQ0x=g z)r}cnpivQV1gZZe)y*bwJyBpJGU;YlH!gwgHYQ&rSJ5}I;U&>n4Gwjcr~L4Z@=vQ^-GYuUpIq;ns~m$sf}h2X1{M z1%7>x!M_eK)DYrX5E$0Djelh?;zgFdPR>2@W~`86lHvN}eN9aAxe_+Pm+V@EYbU%L zF%eV)i}AemM}&&0AaEcLCPm%G+%;~{%3TIN4&nKZTtyFJdMsQV%kvW9FRdj!eQ1yu zpxqYT0US3jt0aEL_hex&yNdpkY0qV{vlnh6yC|PO5VFV>;t;JHZqPW~1+H#vW&BH6 zvAPN>nJFt3-zL!zfbyL3@{#bgLmThqbF14B3HE&)#? zCR@w^na|{N2*hnf-yxT16mrm>VQeGoH)0b5^^}Db!O@Lw?9PH)_Dyn*k#mumGoFI! zZO}gM8jI;2YP&H;vX0(G{LA!qqVK}|Ne-JB2pbIDc;a^oid>wL#k9Cb97WeBGFvx3C*f2UUj38U#7H!L2JL27H;xm8ZcK91v!#& z$slox7~?LnOSEoWX18(@fGb#MHof=_Or9gQ!*odO3gNC%}Q@HX4*AzM{$1 zji%tZjbi9cC0aCb@bLr3%`VP<<0`hJ9AT(lC0d-E3WR)<`Q+jpA$H$kzVH&BT({*e z1FahyQKV51n5MMjC4(;8{~0uvW5}5S$6F^;id8sDQa7lht{c?3_SWg)7Gcjpx@`dV zdJ*y3^Iq}YY^uoA?758xpuJJE++y4udWoN*;qbIUKih58+C*)La=(UQ&md+Gt3T(V{oOi;3moe3Pt6d~G$kuE9>WMp=1fGOTxf4v)|NB~uO_8DPe2(-9=yer z3JFt7>LN4gL#$v)smRBC)lK>z?xIhr#GZP>LlK>FXNxA{Q+2t)Zs&-jTPlt|aAU z-%0dbaU`wAz*PWkvVpQGCE*?U21bQb4)}hJ!jELl=VIVdfIe}6XZr#;a?b(;d(8K7 zeQTm$^SK#&8#qr1JHD?Xk~~eV=Bky}S>Kh?)~u=K^RQMrH0nB9uaQ<^)j{)-pWpiS zzvKj{vubasO?FgyrTTxW-t?swx7PYVJkh^f(TC{loX#L2D{l^YJ^9 zpF{0ON7V@sU4;#Q;O%0bdoqqWr*V1YVkn2^#b{9?9`z;zDqqP?IMg>qm%clH;^({O z^D?|Tpml7x_)6}_#mOmQ(nn($0EIEA2LSzoK#$FoBE=_t9crTJXg-rcGXR+5fR@Y6 zmr!PlN?)t;);>7R7tX-#0PV4XGM>uXa`|8i3Pf?~8<}Y>*U)?sjJ^ou)xzl4#=|zo zjvs_NsgGo|fl?iVN2R_pR-(Z+qqC&1>_65r56$OebTuIBIq2dPlPA9a8W~VtCclG= z91K~5YDh{Y>1t6P7u{ia12c`bg80~#Kjul1vNDu!u|XwAq0CsEj4CiIwRVdTF%K_h z9ngV7W{HQVdM_&RQ4+tEiuo5VQZ&tryCiN1WJb-n_PDs4*XnV-7tQ~CE?nf9Vei6h z!e?KFiTIpIFID_vmvNg=PK;;YYL}oBx+C#ugt8<>J*5Y`MJaI0*%En-#J=)vv4zba zOTl6qJ*Rj$0fg_%&9IlO*b_xgN_Zo%4d3q5hR7+!>?Bu{P?3`w)eQn)Sn)X_V#ypt z-S;~BPB~@st|M6Opk*nf~RRg)H;cf&T6id%Sz!El> z3m3`NBfS?WW_Pb*945vSfqgK|;ctUS+rTknNl{O7Pmkyi?nqk_6tn71%&Hd;CxD7s zbth)kQ^IF~tzuT)iCOj3@Rz{$`Bq^#y?VOJ@A0B~M)=!c#|N@C;mAf)vEuqQ=7(z~SEtk`dEO2ewNhdU zB7B#z-ltZn+GSuVX;L?=3ra0o6@uUxe812XgGxnv{~)`Szt%*lBAx>{;$|ZJQ}Jl~ zR18Rx=t=0Ji5J0r$(C3#ICjhwrIM?Dfx^d&DoUk96GZqPOZJLVrE=+AB)zp>7o}2t zdmyN=SXP3?h9_O(GQ78JbLx8<I&f#+NNG(o0pYSnf#FlNe8*b6yb-e{nq8^Aiw^ zk`(nEx+O&=aBJC;pqH8Fyv)4f;RH}GGtYUMc`4!T!B#Ib&v}`7so_Jw4k~88DccQE zs%#y4X&#E0FWo0aUfCLyhn_XWXxI%`SC-{Bg3bxo8mhN$V=Zb^^E}*2S28?oK63V< zTyzNQcT4)b#d@G?S2EU98Yjfv2lfFTjUYlv;yu6NJQp7rNqAUdrS1wgFO)1^1YJk9 zkf&scNP-|1m0>X@f%bFpqMni^qpCpQ_W8O&kUGB;K)k@GWLj)X2(ZAXJ0ejxR~HlD zoq>nLDg0KDBzn^xik)syvGY)E*9|IY9;#kAy_QHSy}H5qM8(K$eBY2dYkjak+;f6u ziZPEEUo)ajGwRgMZ9*=wG4uf%XQP7edBi$>nv-xV+Hto*bRxUDF|7pwiSNnGpwQj| zsTh(ZsvEGvs9ZC@uuf0&zx z+bBasU3_k02c!RyL%u8-?RpfA(f7>&?7*Y-eGGZJf}vS5#$1cD>g7=gKCy+80unh1 ztR3sR(H5VGs}SC{0V=a|YU66aELp_ZR1PuHGj$P#hs~=s+!mmyac?bx$bc}%0q|hx zbPTH?oKJCIolG#=Jq1)tAllg|F>y3La#=Dda%Law`KR&IVUUd``Cv-L#3ylHV3tgc z^i=im+<|-^vKIsLz9WW0o)%ehzgx+7K(;F&ABi(Bvt)YY_YcFA{1jy89C>;;I!9SD z!FAt57?PqoF#~xx(`_UPOzen&?Vp z%P?adf_#Ce>(w=q+0r!p%}3xCTYpM7`dtwIKKc(>v~m4D`uOE!cwFl;x|l7=TMoOi zpSu<&j>5*r6!jUDttVXL-o}Del(BQmq#*RbhJEn`m(j+SWvWMY58!`DVGb#rbWui@ zld&N@d|kUSwjGv}aqM%~-hVrceBmTBPPtUL@vf|~p~6)i#yLMOhXifI+?vpc>K!K`-*_4xbmdqYMkA4<@x9* z9iEcPv%3*VN-59GN)%3-^87d+$JNMm%Yz}%@-jnt2KORKrt-X2k77_-d8T4hX?a;j zdEBX9c*-iz#c331w({g&A)WHdlZv7H@>oc~5xs@c$?~$Y@^o%Yk}AqG=wFIkRpt41 z9Kot7PyI#V@Z=~@^Sva=RUSE(vZ}iBEW<_2nBuuJRoIfjsq;r{0SiJoT05czw!)hRTy3PSI(sJkXMXTS~BI z%Hy9%2AV6+u2(5;EtRJ>)`XRp`N}gIgA(Os8|8VXGexwm@)Xafh_+LnD_90pUba`B zs;|1>>7YFCV0O8@?5I558c+;6E6={CC=6 zneL%Hlm8#a-UGho>;E4==Y2=sxk*THg=>WnGge3%R6m@AE!;y`va|!G_5E zjcP?gApic`A6*F@6H~D*%IqmW%40*6&#uVLhxEc7I9#Jkl>FyD*885?Z-HnU%$yge z7Ql=C0E(ZwX0AM|%s+GEQ~`Zl08ogKglTH5wYnU(Q>W=#^@|WmEtiF*>5e59o{bh& zT^srhXtRj%?0gv?^(;!$RRT|e_q8UOrjtr6ToI*ufisAjpE530xq6`9AljIicVOFS^`@7 zb%3|2E^*7Q(MChPPaM*Bj z2WX-bqbF_lngTx;8uwqRHGRw^=#;lFpqGK3u+keLf1Wz+;KX>EK5@iID1}N-`o*gr z?FIHbP&no)sg#wd^P1?2cC#JMVS>|;osYlKzypFCs~Wj!*H{Su9kS~R!iN6{(`<2vIisb{oMnQr`Qj^?aZk?1KBRhnbu}WUaEtPrVAO< zTJ{f^9nr_2@rkRYGR7^TEX^);89mfr!2ipYX;!x?W6j?TCd>W~wt? zzYF1KS1CkyN6F)gU?ZhUSp2okE6HY#$As?D} zWSmDe&qms3K-ThV`G|zCQZO}*Dp~i1Y#`-QDyEMZKOFX>5*z&JHTF{>n-R8m+5y`siC=hy7O-QCbT-q4&^K zm#fu&D7L1?nG^}H`Q19ri zRZ_anh+2uchuVYYOF!f?I@amBlV|rK7-;(jZ_-M-F6sK#(6O5=H4*{q zMbKL28k)8-T`wp<1#&*E-U8W9S6;krOxGQ%F?CGWC0#EnQEPadsOoQ^|08Y2^3ft~ zW4c}y{r3@%$aFLkrX>E2Qp%W2eE3waj!D8Tg%bVRkTs#4>0=&78klsw-afF@nIG>8 zh5oJ+qm=#hJM{Eq)t3-CmEC4_9H^&an1*(C#Tz`Jo{nJ%@!2Q)cuAEZRnC2PK0fwB zt$ssKypc{U6F@K5=`)v)zBhnF>ud|&M4<05;D37{6sOM|vRD3uD*bEl&$u$}?Fog# z8*19Bk{_%2iMqY;H1i4ZG?+c)GpdA97_n(%fXA;T)EOf^rhV(-8$} zZrEaEU}j|QA+#8tENuP7zdV7{q_928K!d7z!lOEbbzBA09%bm-_E+ms%d`T&lPhzK z+1zAcTIKja1V04Av0(+%+^}PkfsYgR{KYwWcqbGVQmG-6D1{x944qo?(0l~U6nX-( zrz3K9Ofq!+(huST*U~Y01F}OAIXfm9n16Zfx>(ck_ztq4!*c1EWa!3a&n9A?g&h-r zbH9qkzY{(?CK`d4zkY03dhx?^U?3voI0AFqQ86JX)cFA>!vFmOA{>3Wd^!DBd|CmUEF)1_3(daKBT*}XL|Q8D{ETw zb<%i}eeJ~VacU0?-k_1>ocX%`OHBHH_V7uu>ND_97L%oTnd`5!3+j8+AK?E>nWXr9 zop**=Zh+lm0}k1@#7ZdsU0ItCC>v<6e#ce~!Efct%!4zX(4cOr#7r~Du7P_+`aoky zSWBLFzHWYy!4I~NerKtv5Z->JLUzpqtX4+I!n?|T6qmPU=#er(=#@$|1E)xs+vBtM zqnnnYN6Sinx$GbNlNyuAoSK>4O!EF%k+mx9j`}S_-&pz8(WvL{z@EblJt6i(1YDGT z9MdovdSW6cDW?_A3((1wh7E3mVstEHdUNb$D9$bnVGCo1o?iK;si?nC;RfyueM^}T zD#8`$pP*tXte&AzZ*Qs99=wJ6hu1OJz^2xVj$G}FFI>^o9>hhmdNTBG!N2tdOS{{0 zc8MK_qb7PW1gl)3CRVJe{jm)+T!WsmD{#ZF-UpTU!Un`NL9wRx4_bwr+842R{u}1n zOH|Eqqv6OGls|}}BcDW9fGow8U)|JxBtA_SXHkimGZ=0{Rd)j@pv{kbv@4t1P5YF{ z^kgX95>^T~wVj*A%7f@7kgcJd>0=%y+|)MR;5 zp4UErupb1&T%le@4b$>vVlFuipU+*zXPXI)yRX!eC(YD}_UJUH8~qp*o}?1TxTbN) z)a6PpUlL~;hy9Qph{)MEWa{#zFTIC_7Zex$HDo_TGHT7#6%$Y6fUz_VZ6NCqmP^Z>sVm#h?n28w82k~GNgByW zGE-NvtKNrjZw3EOS7wq(n)Xc06MeZ4nD)1Il5 z?cOEPIrsv?AHoWJS~JwlM9-rB3#j%lL+EQAjvt4bndn(m!dE(V1@Kc`S+S-)6FrN? z8R+`7fG|I-V48L|jhVW3$>1s5G>t=`Fp5g%?QtZTsp}?wh%E`yw9SF+uB+ws6YRU< zOw+awvJI3=3QE(LsT(E^T@x_&dm(!>Z12d^628WTh0%EF`YXu358F%An5on4(zB7k z|9~Hdd@a6tu>I+W@%C3B5t*XY@| zngNf#4O$DYbR20KGj$JpD*6}FG(G{Xm;OUDyM8{CdtjM^5TXE=#S<59M)$O-POSdf z^OkB_B8W4OTOL4WN!N{R4mjNbQ{(CfiVc|3sy8zOCaDPu%cGz-)n${nZAbOp`KdRM zSk16n#o6TIW6ow=ttuBnwyMPCOkHUfhOd^4KRssri47tPbvBM`BxUJJWuEVVl}gW$ z8UbZiyR!5YdmemN%7g~;CKa=EJFp5gcZKG< zFIS^s>?Um4)5jtGHmo7ju#W#mp0QbII4(ix&vX2nIqZzrqjA5vZtU547G2kh5Y}`R z%(7_;*T1rKlM+imM+<`nSLZ?@pGtKZ%aqwW{g5{;UF|o^)ILKX8x@h43`9eoZcoDk zU=0}PIgs5Ik@tBYEB!jdZiQt8k*|YnLqt9U37n-f?La+eO>-|~Z${+jG4#(u&OL}k zszLu>LH2z_Zr{ZCXW6Hpb#9!|?ffbV|4#gWsviq^OV2#)Y;Rv5&sP<)ni2VHxUV`( zXWRXvoZ2}Tviyjg86ZpNl})?esa=OaHYzNi&QG0Z>HM;RpJGhyI|s76!t#tPY+=mO z?d?Bs54?T^{Ed_`2bdZtr5X}0OLtCe-wdC*=L^^eg|{LO7Eg|Wyo>!^Rg7G|0RM-u z1F4}nvzmq3v=TT7B?)BZqY}WsB!I~Va(`=1+p;h zHZud6wLOHru2hg&wJhDY#NnTm2E2i;f)JfWoVxd!5HD>Alr97LW zMN6-O>Z8Tf8=z&*(zQdc7gN73){luCYU#HD-le*f7pV!e@I?#H_#Csy5wy_ZgI)Gh1~9v%Y@wHl8*`bmP>9C@~BJh z67pl0JSgM|m;6Y`Q!e?9kY`=;oRELGRkOO_Kd-X&`YS_H)UHge-E&4ML7~$rps2;F5cV zoaT~;g`Dk@p9(qOB~J;t$R#fbxxyu_dh&i zT(Y~6M_qEDkRQ9`^+KL-$*Dq~a>=5_h|L`HjBIb`5C4)G)nW_jVZ1Fzjq@HYh-{2Xwv z-3-eGI1vRrB+ze{96~F@Zv!cg@xcT9h-NRW9pD^_;06u^2lqFkn!)K6)Gs(TiP{QB zCgKakfvO!PAD5(@NkGG5u6LmLI`r6MF5v0*U+W_XNLxB&Ebd_8q{z0`Z-1(b<7% z5!}HfI^=lm`^M0g(az`&tYe5}AX0&K6Kh$R?ad)QP$gFhzt7Jej!k@o@ItE{I4|TYg1t)`rZ*Z>E`|ZEBF|464GY&686Wc(6dmVfahEiUe z&~Lvkc%OU8G59jU9|QE;o$l9EdlGP5F$RbOnIfGn_%mzBUx8s8&fF~_d}1k~;U5zZ zMxQWbKf9V9xR`;rj1hp>etZM@hC_&>U*LG{=9sh(+4TXvcBjXQe-GSmbI}7=o?$xA zYwv@m-)^&!(BR{MBPBNx636j2k>2wpbqxPiNc}d~OK{WGQ`9lIfuDeblfv?*UY7K% zx{E11`Dt1a_d59J;2@s}{|m9YQ8>g=GAFTPvuHBxy4GD#CI{NSjb;OwCIZNoXfg&_`j zj?m!qfTMI{@a?sUhXmqu*jDNo{zs7dZ4S`A_V+JP$KVE@0|zJ9F_uUE#K0csqk$ve z0>?pFfe%WFyF*IfJ5ukE2O zF7$DFP&mYKM0qFSjesaS0%KlbDCGF<%D{2pcNaOtLv|V9UV(l)UZhpQLBsYo`OS6{ zzWOR*{$4`EpDZ4XK4Hl2c92$Fg7?}jjuJlb5&4Eg=ob!7$G=a01wfn!{($)Vf^*`; zZyVT4LjMpD$43uQv!}p)9}_0Ot`#Gfs zCq%md4(gCE$Tv8l-<}4J*Y5l!`35J%c6xA7f&g(`eFx#^Ur~qYA96UOz9#>q@Cng; z0pdjEVd@Zi9T+buvrp2klHgxXrsgqe?xw*HPxliV{B}Hh$X<@L#c6jyoYfVa-3!#H zfan1T&K-luOMp0iEjTx+dF7NPIwBYq1g77tRO+{M(i)`KPO^9mm7gL(M*+QXWB@=k zb7DSvGXvd)0_(Lm3w}f@jl5^c9|jIO5Wv^y>v3If3tcOwU=TKy>A>1pP<1LcLKv41 z>(Frz$ht!Qdsx>Qu0Ylk@}I-{P3*gGp;Lu~?dFedkoARZaaeaA=LOk7$TEj@M&1mk7h2K-TBS9}v%z?Dw5iRHhTk8Fw0ln$&8%Nej*9=4Rv z&RhvpN_Sjn(GqKR)9N}G>plnlZLW<B7T|MaBqo2?pm*C=G5?Q6Z(2FnNhPsu$@~Tr);J*=M8DV+GGpCsn z6YM#^V^XpU`2Ad&{(BAPMN=|0lX8k(XSg%BF%b&WTqTuJgpAr!-(nxSA8+M8@He_L z-H^|7CBTOg|BZtF?e;uexFm0XAN1dHZB$0PQ8wfY?DPD>#TVfJ;L5a|j7@ob8n$lf zd+V+G(yPePp6f8Yz`ygvmvPU1OT8rE85(UaWln~yc0|4d6BI4=!+|-UI`TG;zs*vfk#wSBk?4G`&tHH;S@9DMQ&~LJi5TgA24;>h%F;o6*@b z{uL^L)P(Hww+dB`)U@nhX9*=&_s-7lu!-S49?v{CKYPOhKK|onNiEEN9y^UeRV1}2 z`%&z31XYdHlI)XM@ocF#)S2>yN3F=d8|N8X>L(>GTe7Qt#1J+K^<4JJIOd_JBxc*Q z8_s2{pQ_5Z?8&|ly~URL=^BX@JnAjnT#1K%*K-cHP4&yxjiWlD40l5%f+NvjnIq8| zlxFLup0p>hQD`>I0{j`aVH_jnT37uTMfpkqKNdbvoUPl(-#-%-hZV2IPq{*5bNoxZ^a~5& znpN&q0M^gmOzTeZCyzk|N4Leg4=f8^Ybb3IrLOU-GbE}WQMwfhbBZbPd#%~Jdwfa} ziW1Iii_%&sJP}rU&l6WQ7D_#1Mq}5!iRnH_-*GjZS$ftQ*;tD|mFUb;e-DMzRN8?j zQ7MU7f6LYrO8QGUr9NsPszdx6`EG63!3|XU=JHr+r7MmZT zf7Z28`}7Mar`h`9(#%)3wNJA&X6sdw=i@<3_-E@!r69Dz?JtO?s#_k#p>8dL41#t91q8zhCIR^EgxlFS+=?{x+nweT zC&zDh2ky5QU~35bE0nCJpfe*8WFT1C;&iD6EJYl@+!|lAO(#rRf@>tHE|@G z$jsWfj~oa_U;-xz90KUKgZC4D0O+-k3nVAtZxpKrBC7;6t~xUmJ$ zFC5(d4ZiO(6mhRHP;`h^Q<3nP=P3Afim(F@{}ut{)Oz1T7Zt$>+_))D-64^zhIS9Z zOPBw^9==2a9~No7Q+yDEj}?5nz&rQyMLz)OxAT7BV-kAp(*lY6?SBQ|`6H#oL-uCi z=*?V1ZbktfayYw% zW28EkI@NJiyWb`r66m*UgM;xo{9wFMf_%fFXRm{&g739gmn6JZ@Vfvpq7Z!}U5Z6% zjFX{*k+WzTd@mlwYo`auzYK_uuW%TB%yGj#3lR$V$AUU{mN}i?WKTJr2 z6XO0aa4;8eiSS)O9FG-9JkV#jM=cSBG%+ti&>@?6$gch`l?}fUaKGJG98w2UQG(YK z+q-cH1NkV5khouP#D=iG7e!FxK*L_wO#(JP$VR-Ft1V1Nm$7{^TZvbM7ED`FxpdJzw`2Y;e9s&C8 zINSv1n;^cv2a2m}1bzyLWCz3zbhLjED!9=L{R`h}(atDOZOSnD1U7CHqj0APAE`)o znM#CXYf_Oy+%G1I-Rv01(V>7oH5^+8`c%W_&Po+aV~0kiRZqlW+d(O8 z^7d4!wggTq<(0v<_DUINk%cP#fJ!K;(nsi^;A+%Wu>H_u=U@-Ab^QozBG5yNa2{1Z z9b|8MzuwWw2K7vky`BB~6`bP9(a#3ik=m~t=TNpe$nP2K*CqN!gW3{oU5QkW^0A?e zuwPg~mP{QFnZ7d(v5Y((!s%fJCZijN7QQkHLEI1Fny>=yRx&+KSF5$J^EULAUWCT$ zVJ+!(!Eg@^~%C&?bTL*G<_fn1S!H#|^4TZwEuu|Fg zI4I;1upHf^R4l$_CrWog;eoKykv>QmN2zBiPL7Jw(@@wJR+8jR;df_pbnn34-Oh0E zT_}7;rLhd$#EBoC$M+yOYGxQGKwDn*^r35#dJRNb-oYhSc;$J)VD%5CnCQe z!Vf=2bIgh86iHl{uHwB zD3_Fw44-0@2A8_f+j)g*4356w-(>pYN<&K3Y#(P5z6KN;hLt4aJD!G?+B^VPOfoth zp->Q3GH<64bySWX8CZxuUk$udeIpd6P>FF;DStf9IFCvA1r_iebaFprOCxgbrpwV| zqtiaoa=EtN4B3lec}9Qi;mgrC29};hZhag44=LmOGW%6iUY$z^69cUqRNk37*H=7d>Qey)I8wLXR|AA3q;w@!|}J>g~CXsnmPz}y*} z@n9WRe|H7WVcVR`M$2=)a8ZJ%PrUo3Va? z@HZ+%a)YC=FmUH3@B=sCQ)l=umV6nzCNa<58%V>}Y^yGWja&tlvY?Rfc2S_Pxp}u% zC&&i4a!Fb(wNlDYIebft1DQ9POQ)N z9W_nfI)hV~Ir`y*8Hq~rp0yLQy%Bjwe3d6huS$rY=-7V>*;f(y-?vl#NJ2l%AaL%~ zx&)a<_rmf2*-cE*)d_7^M;mzs$f`!~9W3f6BKXE^$#M7#O{Qfsxvc>}C<-zD~jQ1ab_X zD|lBxe6$HxKJR$;fM>izkIQa?#~>J3y#&K642&7T#;vY^I8s2BOtD!kY%(yEM>B#! zJfN>Ygk*T_p8-R{h8GGaiZE_6*<|1%PvF=t0EoL4H{Vcs-C z!=ET_XoQUq;;hRYx?%U!_nEl)0cc1V=<7D3;_iBcRx0@y1b-V4I^f_Nmi38u2E;|b zk_0~0?v(fdVwV)8UVDi^;+U!sssApU34T$a!P7TU+6EBwHXqSy$H(+@&r{?O#|>A4{|1QVGr=#2)t$m2 zj@hay77nurWSyslnLJd75X8> zwabG4BGBLsc2U{_5R;6b(rWr=^fPxiImEG?D)?zY%rpspMyzHDhdAEUtCXGtL{1QR zQ8)^9XJ81U~i!Q(!Y7 z(&s3>5qj;H1ro|23j!U+&lT%xn}7&#w_4mn=?SHvIJg3D7p*_WIO z{b)-LzW6(ocpNw=p~5MNr6{jG^#o&LAXjp64YYXf`#v=dzFhG20-In-4(q&tXx2WU zPeRPceMm?g6KR5f2Z$*&fyaeIi1t!+5&s{ z&W?Z+vI&tqpAr)H+w%p_`;1cJA-frHEO!H9&yMI!_=23JqC*aD^8S)iu6Lp01dhEt zCkPk)NDqcjh&=+r87$HsV#S3mzs)siG=qY36%BKg!ZC2-T23mP=jGH23Yoz90@+{j z+Ju>1*P(S*dk4*ohg$TGrzL#+A=hdA0K!4F`e6Ey{JY(xX@6^ODe(oexbRxMBd z`540KafBMXn!OIcKKLmAqE8sIqs!5XQ&dRj-w99RyUZS8qOGb!yvLwbEHJfm?AwUn`vx_rz29ur`qe zE^-bBbirvAccbC7itFtnyNxI}?nP|ShfZ$XLoRaqL$PWdH})A3wT|oVB1xR`f&Iv0o?h6xoUfezxscyn*7uUgr-Y%}bi`;EQ`Eg|oCqM2l zW0fD**NEE3Re4ro*go!G6T|j#tv{9+c8D8bL>=N)G_XFtc>F+I>w!Jkphz% zo#LW!!68JQ;=aduX+ie6$RjQ?%|-71T*B%c_m=U~Iqq2(Nj46<#4RzLE^)WG$hr5$ zs%zXV^IToyhP%j4^IYBHnwlr=7FX6q?t;Tt^tz9t@y?$OZd#8CPt-H7=%w>CIL`(9 zW6)2|C!X#dz<43J;;dJ-LTmSmKDyTj&bHuhn2IzU&u$Bx9l?F2VjNEW%YJZnl}^TR zlykbT=q__?aP|b_adomx|KKAynCkX1yZP<=|6*>;tjOG6uM%MfY6&d#p%i07TMd4I z_wHA=l^+v74*4PL8RCHSRh&9!y804VP?i8qilCY>Z-r zkysgw95Aq}G>Msm46MEY`t7Dw2+8*i6_tZP{Wd?~jE#D2Fq)q(?89xj2u22)JAv;* z@q~UKnX`>fjTyNcQFsZe@&U1u%J&3tEL<<3x03h5{a*277&mMn`|&3k8{!2!n)}qR z=z=r|lz$w@^Ds$QP~sM^DgmTER$cMq(=+)5d0Uz7_kw}l&wyCydYsS?h-zFo29A7! zI@I^I5Ywb*$(VLM;n*=W`cybGgkx}{Q)4WpNt>xz{s!V_1g`_W-{Biht-j>=`ccO~ z!@2Q!atdA~B#sd%Al9nD@x6`c6wYrKr`qber4lV%`ZDjm0El{}zDFV!9><2Vwz{E6 zM%F=jjhhut*5jV|wz`8yUpj25F<^h{vD@m-9$$OlXRQVJHg{Xy#Z&r2gmBhMK1Q;u zr_@=HYMT|;)CS$r6aTfLr@xJRsC73_R3%uWga0?2w$H1~c&W7*o zyS*`>n#MCG@!4B8QL|@Pxv_K(dOu)*#KflC;VNrDDmVMA zhEYVucG1{agCUTC)B(iEusR|6zE4GED^S0DBLbiEMudF73j0y`4hh5Sz*j_ZB-1~5 zJEMF-x}5{j+~T!>vqop{ic;-#T+E?6a92_zey*APrblLAnYAOZFFZf|g=$9U>(chi z(3!8NU$sxS)u$9$cBFUBP*yFJ#A@^P!~D-hX*d7m)EW=8ZZ%1*w{O85w(T7~20 zTA*4O(RCw8v@H88MC}W=;al?gI>(55t)PomW#jM&qYLx5Fyz)o)Sw%!+9cHC(-pok zMS;o-#-OsvR;XC>b-Tni5N#~{>r47*|8_!M?AhamZ~3}I$w3fpDcpALLRh`Eo+jQ7L0gyIAa z>SjRH=z{N+4AL`&QiDGr_!@zsbL6K0Vh~o78G;aXe=S1de!IHhUjbsXhQJSmLx`cV z=)~e7F}SHs9ddBs6dX)42!DA!a-vfS>t#^K@Cnh$63!*jIW3$!C01vCrIfh}A1nlp z=@G%Z$!Z+tdha9gxxFw~0f7t7uO*miRQ|;-&@Cp64;oKt9v0}xyhRJph zwv>HvF3x)&Q{2XvylSoA3Z*SCyOYd{7n;V8=2!f)3C{F^Gos+yhYXHhW5c=(uu27jIDxU#G z*%LTUs^p*KlYKk8L1h_K{PsmZ-t;=4A^D6PhU<`FZKFG(!B+#vrl6jL#6tr8_A5Q8 zWB6ww#q=t+CwT3@fMZ5TqSy6L;`4eDR_;v?uLvZLi7`xiNy;>t@1#r)^m@U@M-H;v zUo`wvOqLhWoH!0$Vr@hW$GL_zq1Q;X1D9y?zGzSELmT2aqPUdv0VPFxO5kRZcIitU z;+U@5NS)InedBNXSs>C{{is76ANEA|2_Fj;>H2@D^G<)XXWt?wm=wQ`9S4)v{vbL0 zydgF;0S`>W34yHs^z=?kI50 zDR3G!1TrKz$iK^ouN8h^C2_+!j9v(81nHf09z=eBKuqxr=KEj3ENQYX8S=IVg88MV zD|$dU*MJouq`r?loLBmnmj4!kF$O*_hXv9$8`D#LlMJ5P+jYV(7AZn0-1A5KC?jRc1gYD}r8hZy*gA9yz zP=)$#5RIMqIE3$J(dc)O8VSg6DC>A-zI%mTw>{bCP@Q7h0l06y7>)wNw^=mK&ZVri zyyX!i`2_bNKVV2C_;F+vOzH`qBKTgxCnAGkVq02_-N<`5UAlpOfsWCej(Gi zN(VC7j`(JQaYS}v@vOx2jLsuKPI&A=w*=GzQD1@1HQpmSI$mccnkOu<0(=MEj9yLH zkm+;?>NtE(^dmv22D5Vo(yy;R}L@Z|%=%=`@Mm7GOALf;_KIC%@55PI#pw^2ywyH$h@fre~C z%&o&73+aHq6(am+D%l3!K8L~$BM8d^VvV;O;oV)xA&wofnJ_&jrZ1rr>-z#Iigy#r z__*jOc49MNAisdK#QJlTU#&$Bj`nOpM~Z(-tPj$?YM=1-IJ|<#x5cREZpFB?;1z7m z*##`;H+{WNs{=qUo4;AF>6C$3=mclB`!}m@EOJ5JDg=!Q@(B77+(0msU@^gZf^7r` z2|gz{OW+v|P?n%JKtZ#YJ*vxW#-tkh|NVhgIj@^e^r{g+5fQ{<(xDi26DUSvTEW*( zM5{e_dU5Nu-u0nJMcu`_xligkGqvgpylv^PJS|RX^;Qp`sx1ld{|6NG8sk+19!824 z+>DFoMgeP8F!K#dJqk=0sJIyQEU>783z;!$2e4TM!-wDt?IN9-o@&M9W;61xw+&w-3hxgr$sohYuXOGXs@zs@l>oj8qtEM?{)=L zRJ+r=NX?`PNZ86txgb`IL@nT z$74U?q!+wuCO&O$7u?k}pq?Za$bKCCKxm!xyx1AtgDLpJhE8zuXeH;jhV$Fh`Ne%k z^4HDz9pe1n;r#A(el-Ty{KIU!{6%9Z%RlWgzfq=2P)uX~`EY?Q|8N_a`7LLDbwl%; zP-K36d(3a#Y~vVTITc2EWgKaoZsMO0_ZsmJpH`9II8`LSKD9@FODp351wkBOFPJze zt&9Wk#X*03c!>s}i};IB_we@;G97;lmhSbbr;&6ibz86|=|(V=U<$!}f`LvVuNR|4NyfJA~i1T6`=6AUA`nc!}MhY6k`*hBCh!8ZgK32fx!x*>v8f>s2* z2u2c2Cs;_ZhF~kf>jWPY{6z3Cz}KF%kpcApE=%BFd4YJNt5Qp1-16xXY%m>dG81QU z`KMR?4z4}8V1nWddzBX7`&1u{o2%Wgxc%!OZ)KOe@3=Zy=2t23j zWni$X`@jYtD1^b+m^hk^-}^?H*d7Rnwi4W+I9}W@*cpVixO=d#{3?|+1RbLdB#r?{ zsHy)~sNERqBG{;8`nA6DtBd%3ZRFLVmRyEV#W6zNM^%LSj{G9jcKJS42^v-h015TM z|0~oL5b7zgQOWe%c8peI@%!rt6Y9I+XPpObP#h!FOb`sUjr=N=`^I3O`qHsMk(NKb zY74}6TgCo&502gVGI9r^xBQNy8hLRisM=dp8{epUrIe_Oh*3ZFmg~??K)T7XNe;U& zgDP6`$WO+1kF}VtW#&j*HNvZAJNl8#)gSud%vEpj;32Bj86Eo9vSn3Jnmi6GC#pV+JjR@;L=jzT|$jJ3msoSA@6x@!E?$WUC z=U3{sSE->EKJ_=aA7i@;{~~^)S2zzp+4cJ?@=h&q8#}rYzfG^yh2P6~xS_<%gWGl@KrIP7o&uam-9lu^Dj8`NimhuDO2E`ll z()}QimsILU2<8-sK|@TOBJsZfuDoayr}k=-z7ZLYr%cMPL_#_Sk&KrDt{7bBZU4unZGxW>+7`I47=UDZ4${V?SY~56h&~mLP zQ_G-wJC9oC3s~(LWTO3G*jMZ-=c(z-vv~WgajdeUn^>hMBM#Q$Ze!!{4bSMNR&~ye zND(>=XLVtAo8zoa*jZ+AXRL;jHbA!>xK@7vDbWlk+$gGKnsjR9Q@7!_v*WNq*x@{I zgJO?LT6FVk1=L1x1CDNPSogW&y5D$W_bAmLmn!kE8IqEJdes>yW%g@{Pgow)atOv+ zT$p(;j+aO1ero(Ol*TS?>tBYlRq7EZ;w5tXT+%+ z{3TWm0e7RL%ll&Zr&nEHTz7mH3MsI+OVDUUiMrUQ=(_yKe?WFQ1eN_4lFl)X(${ z7bWmh!zcz9bc;omdN4R^aeHq3@L(z{H(@+(mv@4QbUOw}5WOcTI)$IfD!pSS!({|F z=_t%_vartrC*>OBh2YB54|ASAH4`1%m%*Joz@+H9@UwgdZn*DpE1yLy*}G-Yb{~P& zf@krTS-)C%29@+X=0$&mrDd&kUU?RRTBko}t+E<3A23(R^nG^{j(|bwIw#~vuO}Vc zpg37PI(VMW(5$6y#5*m3q=}=S5{~I~a3yZD%u|`DO$}W{TEMi&!?0uplG_9+TGcU+ zr06p+w+ACdIj0NTi7LH8+5K(;O@#3wXdJxGBv9XQuxi~k!H!ogMutpqMLjt6ieNA5 zW!B+WwQ4awG4pO3rxqc{Wx#l*8^lyZrH4{L}{CiN;R6s`uywliBu@1l4P7GRwW3Uz6px7eqr-6{P|L!rb zdKbi*{w5K+hxL7rI*DLn#!-(XLP_bZ)ZN>R~rtJPP!u~Urt@ov3eu*Q|!7cYH{6Hw%(KPmy?rN_Y; zB8_4+ES|XZ;C<-9?}f(DYa)0WT*+&u2j6eT3`eDk^9%zfsMc8tre8lAFS`vgVeDfV zr#O0%K6!a?uPBUZdoc(IIeL-eFa~;87Q}E$TrmFKQ7&zj<2s5;ru(~|#PvV;J&T?4{EGy>AKak$Kz^7F!n3#t8*o0khztSBIsqV_ zSuf}TEZyB`v-N1K@?cBlXO726*RTw@L9vC$AotF%QbvUX?@U%SmD?-c9LJOS^^uBK=12n2aK-CD(~wCA4@-^2=sW>>V2J^DE$!h zEsg`$O=b7KaPhK ze|X5J=y!2ZaGU)0Q)%BK77ZMmNY||;Y)r&==%h%*5z!sGfr)65O8OA_sS`A!j_ z)_RdPwHw{!JdO4bze!FYCBqS00B%t1k%CDNv$X)ndK4h+Om(By<=FxCI)3A?@o^a3 zpqNRMv*}OM7Xe~YCqygmb&zy?vApD-(JHS`%`@{@@6zS&_dKfF24ol~ zz~u0INdq_RAt+9fbAF(6gp@lIA$7hc%?7~;br;g?rV8&NK$eP4df{(g#cKCX@AgzSmG9`x z8HY9Lx=v-B`NxPD(m73sF&LDv>rkh9H-bn6kThZy8p*iH3~})ud~yNuJx+YwT2-%V z18z|4nQ^PYSr2fm0RUlVsvEWHwYSww{BCl5M22y9fg2Pv_(;t|DSQH)`Ho(-@UuS; zuB4F}6OC3KbBE&wJ8(x{qx-$9%lZN@pvPbHap0G^<97J}3sNf)wX1ZXB%<_bs^BVC zRaU`UbaWLfRVCBY_t>1C1NFHD=6!q>j#FRPNl<()ZXfi3<5}Fw@7S-`qfp&Pm$2fl zhrpTvAmOpfFP6&mGb=5i*5Y@#6G|kNp9D83_DG@ix+kjL=v6xQ6|k)%0OFB7x?&z_ zlivUrwNQ2Z1 z+@QEX`6xwKNbA&zcs~=7+!yiaj1E?GqH9sg6!=_+_c5P@2CP?Q^@7Xha4lnJy(V#&YyCOF+Y_3Lp{K zeq{t`K5C0rZSmXBaUOX`UBC^BJyUcWoDB!Z;sN=X+5LPn5gqobO`6hX@bFl*2ER=l zkCDn}OL5bncthfj16LB)|BhE30a3y+jP$(EgDZ&}7*Abi&UC%{?d=tX*F&x0#baoenQ|wHhG8uYzlR03eN1DMV17{!+Mkn_H7il}z)LVYoTySqy9(=c!@mrN9k)2#QnW zu(#-(RpsT%mZ}XEE7#QvH>5uzq;-1v!Dy9NsB4*~l-_!@k5%LF+ujMwU4GQ7W)}Am z6t@VgF}MsX&1P7RQRJ0xf*1|{WR=%dSNzy%OLNauu~ed?TPpl8A3)bMyK5_yb6#1} zR~0SwHN!X!AZf%dfa*r&YQ9(%zZv=5aTV!~l?OK{X3UXqq2PCiSScsY$y8ba!D9z9eh4K-&*aGFXj*Cd4JOpmIhb7@& z;cHn*r#Ge2{zm;*$Fav1$?~UH6>P!les6q~Vs9X3)hm93ggXygagkxijhu&(b1f1~dGeLFPP=P~2l}!C_c1Eiz&mr9%Z#}~4))3sFI6#g) zM@Pu99Xlm?)euM)I{J~Z)Xm`9gZrDs$Go@y#C1s?C*FCOmtl9rT^zy@Q*e@6V?*pZ zSXmXe(i8(=T1Z>PzDT5-auNxKZps7|z1B)(IHu3C)@n8a+aA&9SZ5_%)PL#Uu_+?@ zF)N)TH2ZhGXqQ&e>#e$+@cmuaUu&!A$E|2i_x_GM$}k7?gq7e!(0=<6eEzPx9)tM? zE1H8kB+qSNzVdafDu7D;ZYHq@Ve*52deuAsJI+BqlxOk$S;0+$%$^n8CdeN%Oe}O4EX9>4^`G;n)gpp@ho0F>rYW*mitpv)w6glFsgeNZ=8kk z!wBTN5>8AbZM1&gN!`Bio4&XX(zAL) z!pBNBTVmrBi;Y(}#bTq|9H+i~lSh3ElbMdANSEtZaHZ^27%vf09jj0FsDu~rVPZ!& z^3avR72Ss&-P{dGoa?U9>j}N^aKud70b zR98N0%sV}CY!6M?u$%9XQM)0_XPfLalGS|8!=05C=&bw$c{#^pWI8kTC8x7O@wJ_m z->hm5E;f_WvJNbN>wI-tTjyF@#VqMg-plJ%E%hde9{|GLmSL5DL}w2ilMwR0TA=x# zZF(mk*J4NLg3kLmQ%g5RB{P(k-}qGZZGQET6NkuRK^t(dbWT0vJSf3qt@$XU!5Ln- z4W1N2RtR3}h-d49XPbY`v(11PNfpKiMMYK!7#N=|Z31krcWff>elNt~cdzB$^KIYC zcaN$7-J(jqrf#<=Z2>xlov-onGki#JdHX9?cDqGA(1ZGmVSBebS)5%*)s4#gezR3g zup2wBLdzkAvr_^>VRlIx?MPs_7^*ofNL7&GZtg>0pYbW;(ti)$};{3ir*z z)$|okQBAuYw2puOflocaWUS*TQhHW`D-Z5=_;Vja-ss}!Me@cs(2J=*M63HSsg%yH zTl=9Y#F1F(?76icnrFzO9-rLF$q&?&N8u{RaaAIm4hcKpYB0XSPW>KZWQ7^+;oqpQ zYCFo27n4V2)?g1=2$z$usKA_XRqlBNP|~r9WSm8`VO)7Bq8nG@#o}tnVsTBn$*c4= zaoy#{mHIu}xpA$ced?!*-75*sp@ob zO(%J`rrp|+T_lHm4|gUf{-INHoep!__gMHoiK~_Pmll5N1{e&WQRZ1%yTAO@ zn}BvVAx-z^Nm>@b38aR)TceVEUGU~%WeulkcSV7-M@#D9G1&NmE_VDojVaMLV(*qp zW-!O=d(=|=4s{|iI~<8;ukjR=5K!Uvh6ojIaFF~el{5pr?}H>x0sKctnH}wQ`kUU^ zeVpT~=X8#9d|4`)p`<+@rONNZ+=&y1Ug0=21oujJK?w#e`7sH*2pw1YNt%sqM%mD| zMgYho|L+ZQJ9P4D={V5+z+|oFexIheVo&Q}`JVXpD8-A{6=4tGa?46c0$F67+=HIc)`oBMlwh7Gd4R5X-=moo=ZJ za>i75I^a@i<&4QTBr5n{9><6V1_8%SO4!Z&;7UR1Tam$qC%9U|f(7NI{9-KqI(oS0 zp?nmRPyEXYyNG|)apClEQBWqRa`{%}`pDW^B8o zUBd`=GPI^Swvn;nB5=d=_E!~l*_dkT4Lp71X_990SGg z?mUygv%`rrHewwVcgS=p;4#yM?Ct22=f>i6%0rG}a@cS)4fEXbLH4PN+|bIGJY8j< zN~K%A9^5oU7cb(R&J@Q*jj)SfuXOQAaTlMYG63V^C|wMKi|*IBXu9``SR5?w;$R~N zKo?1akyss}Y7L@(f5qX%Rf%Or4D|QrL$PW;evh`jI1{L?tZ25!Q#fn zl4dC;X9q#mx(Ptigp;$yW`*hJ#Lqsp1iww3P$IL!kANE#dvp}LQFq?)D76Q_r5xR= z;rD%@xb6-s2+0Ys%I-%-|L`BBIKGk?3`4auTL*6UsSZby$epcQ;d4nHj--*$&!L~R z%-WAt^bQ}z*5~aFt5xXAT zpxEMtHUz;Jiu)bV^GI6>P~=!d8tolW3U~R{u>QDb`AM+yIp!-q)T{5So*$AIjG^fiJI=u0q^X7|OZ&+xmiwMqF_;fKCZ z++R?FK=ZT|T$J13qwsY3ZW znK}ej*Ua(LZ-aNE)OB$3v=eI2aQr9zr|X~uivnOni~YQFE(lr*!d9@ZDG0TEl?OQmAuS7@ZoI}*!kfiBT{VNEAS+(1FrE$%l0BGjr~HqBfjJ1b^B2Azf7u>A~L6CK+&;dk=qm9~-2inA7_ zQnRs#qv~6j+08NWY=fGFf4D>)T&X}gzLN;NiwYFG+0vaV)QtODr8|`Aj zTk3!lTaNG~wyf@p#nz1c!m%a!U$JGyFR@*N*v@f+iNv;m!7#S8cVlZ@hhu9Ik?tg0B3Y6#c?_`x=vIHM|I6lW&_0t^{8$( z6I>j9g6{keqSPPwZSMq<8;*3s+hI>ZagEw_8-qaYx=()lsh!rZJCH##soMKSb#Xpk z`{h`39-+_8s!ff`Y;sjn^nUE9hLSZd;#8t{m~px$ddI-UK6mK0yAZ3E5}Bg;3|vV<=R6ZC+NRsk(@iMysV^MuNcW)B zAwHm@QRB%fzh-S>%#gW_p?~Na{nkc5cBZROjQX4ORz!)3G7>5;T@$TI;9e1}BYOTm zW3U{eC5}O49&f#Ca1Lq45R%f7)_cIUP5?Mr0h11#T!6INtWybicmIt)rcNcjT{5Gnt@{0>$f+f+dZ5&DfCFOkgK2V8l?(KDPF zPsfFR6T!6>0bDt;ATgc=MKe#)V5F{N<|%+>s$}|_ft|p6@oPIFMdlknzQ$cpfJ_e?LEM&Dw_ZCJ?AE*(+^32gbSA@ z<6wXU2ecKff|^m*S%E5Y*sB;bJz9jZ{GoI!Y}A)nZI6j)o&cvyS^k1Z3`@ z%oZeE5Jh-&dwEDKt4)k}4ae6qr1sh>?}BQvJXwW!y9_tPDICib?>I*RF?Mh(LYh<^9*^IFI#LSdB}#A-P%M=|@{H1eLpWK(J_;+0G6YW&SzK zB~~aoJrI{jJ+RJe?TV+LtdPU%Y?qi9#CyBL+rib^=5_zEAHOAnE9OH;*cs@VE|Ejr z35#9gAdWtTrTgp$pjs>jA4vNI(cwXgN1HkEEwn4WAx%$`!Wen{604s4TvS{UnU-+>~y42^Y_5P9d!Il zcu@pE<|RnDO>RTYvC%6LLp-i-tB?^nR8ro5V#G`w=PNz1a^*jxei5h^V_>`oWY2TvGq|fPz>*v1Uu9@3z^=e z3i(Cr@O`O(oCL^+gCKus0O{J#kmS8*fg}YaWH~`D2jsjU$bs(#Y8ie`NK$|x(-y&= zKc&hlYkS^FVB>_cCxu7<#h&u(D4xTrEYKxCCF}2(3H-(8=QtRH9^YEBpDfsWo3feAV3-22D?}pYTV34 zP^KVAneDbRvvFc8L+7kaYBnCP2~y@v17(6*FF+Z)^;(CoWM#-LGB-h)gdk=5zppG4 zf)iUAIwxh^zs?B}BPcT&33uu)a6uypiCAus>>xY~P>SOm{LduTnd6ZN?YSWiPYcw@`~f=B6PBs zj0?XL;%~@qFldGuXqbb$Ax0p)XWE#e?FV?DP${8@>hnNlCFZFpllOi^TZe=CpyJgr ztMN9k9cgtpi8n1OC%1IM9&!WP*OTuQFMQ4e)n6M}c^wPt5 z8KDcKMO?G6#-y%m#mWV~GJLlxu0>cFnZaB!4DY00CE{YkV(hRKexw2qhh*-9FJ>qu zbuWDtO3H_65Mj0_E7F{OF$9%+pE5roVH4jcty+zRm>Ks4sv&X+;;rH^(flLq7gPbd zB|V^8i~$>d#=wYLlt80FxDulH^-3=nRJKvT<0=b6;y;dM`wQ=}(}t)6*CgEjra$~j z0{<^*A`h)W4?W*gj>zadJ*^$3q9 zbGlZnBaSOYT%Yi!TmF`9B;3pJEc7XqWwt(yCVt{$mwqqm%GP+mjqZT}N5BGdt(5wMrS@=`Tz@o+3&3{902QkxD~690>m3T*%;b9flvU;Qr(FcAMK@RbmMA7ql36dgWHKl%iA&oK{{77+T9Nk_nBZa=OI}@eV=aP z;3QQWo+9qTL+E=x!rg8h%T(F=k*TN7DsC|}^mebojhdIiV;(`m?oPKXctnY7W_X^) zWsyT51J1)w^d4y>Mg>)`Ij9z6z}*iL7R~5az-3c|c>9AF9!d`BO1uyw02_MN8ADu- zD`iQtk@h%^R1c~%d|(|aWv>fUFGCDO9=?2CShDnGUX#Q9uMcbf61)Gl1tPmIV&qQ) zXQD#a9dBPCI-2|w^pS5sZLN6qHZJ6o08LaF9oslNjGp-x%5epi(F1Z)Yi#34OR8~Z zB&_p8cUfDl&lHCj+c=xo-Q*rT-iIq@H4<(jdU9Xn5O>(a;o?plk0>m?%77unFX_+)4qe|Ml|RNR4E>M3xuc2*TwRs=9THp4WVkx5o^di|LA1*Vm8f{NgZyoiD+xX>FvZ{e*n zmMMRH#-!T;mnm_)Mb3ZTYU2XSiwo3L!h0b;7kDA?j&+qa*LJ!BREAekYH6o3Q1LS} z^Zo5aG`7>5_!2D6(_*l*+So<140YB6Az!lE^ekS%Tlm1o7O)PZAp0ugHE4EpG>1Q*W`*>V$hlBl_-f9 z5f#;`Vvx&-pinu#H{sox5F$J%eu+{__rM;YaxHtQF(z#oCd$hcpAHw!CFRfl0t-4z zo=ADx^w7(XXhH<2pEgs3do|v0Sqd?8H4^p~di&Hb;7OQsUopil9M4xJ>gjPWs20nk zq1@*K>>W_dBS;)D;UTVn2IGm+uP`$NVMKyzu^2GYuDvHzOhpWd{+{BL7RDpM6Fy#C ziY7=Z5ScEcOC$VrHLr)O%PH@rw?fG5cvJx6?bx2qX8f7shSBcbSW(OKnk;$V> z@B5Jv9ztK!CQ59;@tIDt?2S&@J3+M=5KF59WN2ws!N=jk-3eiYeU$kU372;E(6sOn zPWF-w)AL&r@)wHOFiVBT$ihKV##k93q8&2u!mz@Im*7+cX^isycZrwlxP zp<|cnrqHo##iw=HiOq%k)PsRrs{-|E;Q*)>%cJ$OTg-BaA3(WH@#z)HpP+Ij?00*-b#q-J z{#*ROmEzSmcPE1C$4d_nVBI%2EM7h7SbLEY$x@9jHzo_hnn(tWobFzD+jtsq%(+Oo zS`@dV@!BX+k7MhgYHb45VtMM`S5~^jqoA0(kTBR}j)xQ1dqZNxr#MCiVH^e3 zVll#KInyP62gNjwDvbVw;UTV9M@5Q`ARp@>+g=YdUQjI-1BSOFhLFjiL}I$9zfYXe z`xj6-LQ9wZBD55pra?Hv^>~cv_khviR3b&3moGSOBG>yyaF3?YE4?izIOyE(Q6rXu z&NMXpV)13*evcbXXwgDrjBm-(P|@!Ro3LYnZ`rXZ(eFtqVy+nIyL3^Q=(j^MVA<{a z<;Don?uz?T~s}NUTfLDn7lSUI@Oxu=FTUWTknu z#|LlzkM9D>;50t@;e86Lu5}O}qKeU7=`~v&z3P%($%xY-=76qrKAwdA5K`t3NZ3s% z#O&vD1bN$4A)@Jb*w?87bytc9)na+_mu0AX7f{TeNEqxgw3Emot~k81Hjb_-483T% z98`d>D4fT-?_t4~-{bD8!qsD4dr;X2l+i_YRJ=BjcjJ@7ITld{E8VNK_!5t9>{ZTT?{P=NgIfjXsiHy2B+l;7DD9{#J5IlkOv0 z++sY;e=|U%8!>6auzcF1M09A__yHxJJ;;t5nEj)SHY&=VgxGMDk!FY4)9L`XJP2-7 z1316n?pfjN@NU}UfSVEox2^%4UwHPcaCU&!y%)D49)hs>3KBNu*}noTJXFN^!btHw zj;)jedXhf@s>ML?Ddzng?^DM8h+At3()#+Yd3#VDUiTVkkOGQ10m(TupmzuG!b9;5 zY?Gx~eQY2NEVwHOoanvD$KU=wRY#X8D7h6K*zJXG!HJo2e(l23|= z5=ZE$(6#gYq{S`9Lm`_%W9RuE&2tKaDg9~Z>HiZu&)M!PsOC}O^M=mjc@4f81b1Tt zxM1fAgmau{65y5x!5wY@7wkNNaE|lbaDJ#b24S<&&#LKiuE$BxhpX`oKyW3k#*1HI z%vK6$=Sc&$q#>I`Dn7xlF#Lk$ zf&y&Mur$~-1=V6P)XtmR3+@ieYQ?ADVz~fR9vXi|E7A7Q{mHdLWP@r>MZ)Ec$Eu#c zQ-%-dOrjP3a)ZQ<{)k^%z_AwpGf86RSR}%ml5L85oK>pAx;jd20hJ50Z-RKQ0q;Ig zf5q5Me+wMmcN_Ay4v)Jy1k2~HH6h|JT;%y-s#J}?tw-m={e=gc)nB203nZ-mroNf?*f7`HJ7ajnEB5U#>;vBJ`CsZmA;+5v3fNB5Dl_Xy3e4iSeS$Yx)bm&RsyuR%q=0@V!v zP1S7>wqgs7Uc;hA>OHYv<1!1R-qU3m-3nT65JtrDFwq(U-S9t?#Ap6U$zMpYQbBY% z3m2xT>gZka1W>uLwy2=8_hY=JS_A43#jBrgTV(TgL@1EsLCp}Uy&u#JEI8;d%2`yN z2GzMK!v)BD1uNB^mi+Jpd8cLh0^hJbsAq9_hx!jGP&u%6g+iOA+{E`bK6@Eg8s3!d z>+p6JcbJdTi^~_oOFAoVy%0!8rgBno7)=E z+c4VQ$?pTb;C?|FRNAE^v`Vjl ziB;N*((U^N1Vd)TFUOPQ3P?T>BhRW7>$W-IGxL$KDelKrXOI;h0{Qq!yvTy%h@c{F0@Y%9 zRDyYvdW4AWpte@LIT;yxS1B z;<#L4>M?dBs1`%ODGHDwr|@Rtg@+fB8L0U6mgOL*PRF37t@kyTDSiTVT1#2C4;+U} z{N0aN-O$7x2NBuIzT+V8o|%z+_l%yM$^H&u{|g~EN}=ifbhbYlTXh2Ng_MB$bqiT? ziBt0CKwiC{R(CyX4F#X2M4bJ!WT5?YHtr=n0UYxcBy3x{m!RD&hYEQZ``7Prd{3#+ z#8Ke{s20o9s6FU+-0(OBuoxr^RtzwaLtM+A2p2s--W!C`7gUSI2%`mtxM84}qmeMi z=r~|_h-lsRJ^HU(`(}AWOc_Uo4;mmvx2}AlYPwOULZjjicA4iL4aomIdnZz#KLm>DT&dkF|96`)!#4`@h68?ze zas1CDF5!)W?rs0Xm%E!wPt^v=0+kKY;AW0Ch>V_VgUCD#G8@R3LfpIx2`k|@psrTD`ZmkuHn06|hxb;*iRObkrI|Eze`jjnXY;C93&!X&(Qj}pJ&=eo zuXd}FII4WL__qTH{A9J1k0VYkrcbl<%Z`>ev*=F67ac;xHvsLg1a%dT+eO)Tiqif> zhl^8uot)0l^R()435k5;6H)ucMwh?kZ6N1Mn)u;J+~x@-X75IvO~uLHrm}it9IQ%E z=h0mZwp}0OP^n+dp8Y$Ev^jK}LP@;fNW29edSVR4rScu4BYg9NRx0UL%VI>&BNNHh zC@Plz!-Qzj^An5SZg8#Gh#MTD=ND;o_X7(bYz3}-F;p}gZ^VB^#hyaK9zgG9XxH&j zc}pkY@%6v)I%*TCzsJ$0Bd8Y3qshIiaerhmC@&~JZQD_xaux0SBiRLbOQ0Oodlj#C zkNGyQ{gyzQXI6-4tN5;S%6<@hJn+%S!1x>&8(>bOPknU93E#Y;UsO%U?~u7qZx0p2K{X4h+-_^a#nS*{6NlB&Exs16 z5Yc5r9I0iHxbXBuI`a!GvT@uNBlZ8p(f>hE9UP0GDPU@i=9A?MtSk5g;nB1e*m(6& z@(UgL!?=#f4?U`$S|p+dWXUJhhvV5q*z2okS>DACf7(C)5BB;#w$Bo_*Hme*A7WeC zBOQJmx;++Ny8!;S0@t%vDZsh$derHK7oF4C;SRxEHV+);HAvWGx6Xlqa!Bgkh#0XM z$Ga3}Z%5(npjs?O7=5s7dkz%y6(o#tKkc}3i0g;`QQ~_Xrzng;4#o*kEfyn;ob#~< z5Mjb>g@iHwY8%iyh~161cKhObO9eLE0UHD=mST`6uvNGjGKw+=>Cm|k8S2GwGD0()_u zOB@5m{2K{_(ajG(&4~T0XAI#s!bG70)4SC3K($z&z^Z4uL?2MhY$Oau_YeHQh<)NK zA)*w=AwinW0@Y%90&8F85{p4GZ$iRga{wkh#5KKbsMwBUxWee?m})1e7K;HRdmDn! zAAoW&QkqmhbMQ5&JSsWQ91OzEkx(;Cj8eQhc+de<=9Lo>J=-uxbXp(cd5wd*Q-ymi z0?R$XWuA|Ob){eC7C9v8elt>Bj$>?Q< z9eQI>%s3d|FCIC*rTd(QT@&iN|gb+{e7yOFfr7*iV0 zsP7jNCZgUR8z$(-aphAA7lRbxT87?1f0Og`M8|otblJ7y=eo%SqT~GD^awmXEwIWg zst_Ij)8XRTh8TkYZG>yN`YBlX5C}o>{IEoXQb`+)^C3w;_f>$Lxflr>ow zzm5`r;kY_f*7QmTGddKQEQ@DL-Xe?@Q!&AHo`#=|rfX$AaAqb)bj7*Z2MNPB$BD5Q zAynas#p#uwy2K^JA0v}( z`v|BOi@`zCHlvw$m<^k`LnGD9^ux!pnNvZEaP7M)pqc5iZf1&j`#19!KSrr$t_Wym zg5qXgBtoeq{BkTJyVT6t$eA;caBa>W-8CpaEj)d|b?TN7aTAWG4XKrG=5?T2jD}_| zLWY}pAK9!pVjJb3L&BweOwBA~#U%CM(~;tH9B)yWx|x3i)nZw+!&At}X0D@VrfcqH zIExMgy$uq^{sUy=7`O2moL+(lcKhSn1cj~JI0saVWr1xG2D?xfyt5rj*W5jER!sES zNEmxOPK=CP*dk{VP9Ka55vy_Rp|JH*`~grcmId}qWC(ksu~o&mpC!ucNEnr3+{UYn zN^ZO2P(?~^<}~UYS~xP!p(8fY>ULPu<($;eUIaFsW?7?1q1zQuN)4l z#bPuDwp)$JHz?)|B#gngZSW%Wy++4xNIMS+yfimj+=SyS1vijEDGa|3RErUyT`n@D zo%;aZ*?5RD&m&=2+SX6Ny`~;Le#aT^W#K|`X@vL^#~}(;hs;iZYB2y%pFoCCz0DCl zXc++;DSrLUg%nVEI#khvRD2FCvVWZGby_<^pTwc2xDY(%I3%o(`ZjN+i1^q{`hjLf z4}oOQj1aSNeDxnW66=aC1Jz;-s5BHA2L2mQLEb@`El3<-zd3}&ejS5XvvI6fp!$CB zyP#SuPmOV+J$`o-6!Qlp4E8)lQF4f@|7}sCDISHJrZDuB9S^F-VuXLT)dCt7xS{BHW$}8j>$o9a2ABCA z5`LqELfQOA2}Q%XR`k14{QNh)QF5X+XYlD9e1%5F8aQyynY3UNDG&2Sc!+|7P9_p3m@q z%D5e=_{K$qzmm0`2B#;`2wa7!-ZH1E|!;L&ClAmdwsDS-leN?1*j!lYGvqpV5wRU@GMCjC?<% zr_5vE@;1hAnd4%elGm>JA*k${(uEMUn9#x$e}Fnp@t)_D)v9qIFPEFRJfv+$b~g-j zyYK>2M{t>akZ==Sf=f;l2@gR$be|z6;h3rl=-?Dk0IJ3E)P-jNY$hn?QX~!->{=?? z-qmF+fQ5%7{uqGuKaN7-=~4V?P%ValIj=&7hs-s?6t7U`FcQY4+hcx8l9;(AMErx} z3#X;q=evCem2AoPzEW!j*fM|0+pNkG=>1_ zCiqD1b|aRC1XzaM2Kn|fk7paNeBKZtP2pe)%W|-qfy!8GLsjqW`aK@w2h}_e3G06C zX$-MB#5wPCAx7XB9;DNFP%Rdt`uBw^6o6tbMZy>~cQ_BiQY6KB5SD|%9+D636D{t? z(f5~Zs(MGu7eTcc5F?Qf85)V^@)2R4q3BSFN@k=Z)4CZJ#Q#@V?9AC;TZ@+2_FC^8W(+jvYNx(YALbEJxdNhu{wMq1fi*0f_;~m$)%Xq`n{9 zJP8hBuDDcWK7(?*sB-nJ_%6!jtsg#&K|^YuXmX_GQ0V~3<|ErtX3>2|3^&9V5O9Sx zSN8An2AjM@H11@!orRCI!TzP9ac8sX%O?To{&Sdt#T+F121~T@muPECoIeQnf52>B z5iAjFbfYpv4x#O?ix5}i7_I80Bciu}YB2`7^(bV_6@|k4BbI#IkvaT_w0#f9_WMC) zXSEk+Sey0n(lU_7gX~nS>W+bBuM*T={<|&M=#8O~18fh>r1aWmo=NQon3~lj0lh{SsYv__t z#0!c!(3YjUT3Xga?61=YGjSXdq=*kxi{+t6+TV3}OW~CC>N$=d+zTG`;0h6TcS3k` z^3UOu>8lc98(Y}#7iF%2ty+>jLYb%YsJC3O-2O-W$o74g??M-<3iUP z9dCdQDa=EqV&RNZBj1e_$xCIaajMjpWuYi_ahzT2rGB-3I3z|SFEi5nLT{>dMs+&O zu*?`P33#miwovAnBnitG)Q(rsG`-QERPiQTMci&`M~d8RxYt5Ow##G2EBC@8HBz_H zTct&`Zti$nw;H3r(;^vr;4HI@-i~gWk}%ZKEn5;Ub#%K)K?mwK-%qzAq)4rwZmZ1! zi}4%cR~pSimGB5zFW9Wg(d$a1mvYG3wu;T3D`fpk4X@*XtIh2%LiJpu*;5b6s%pr+ z4rH!|JgC?LA@c(uM+|~d#~IB^gCOHu+twRrq}f_7J}cy|u`Z#WSIy{7A#?V!A(~Oq$Op!d)NS1A|4}Lq)@!Ju$;o-NZNN{AJ-yUSY z-M$?zmoC-Fd!V5j?c3P3OSgRky@l0CH!gG3n6Mib?_)a)snOI?^0zZnIRewWH#MwziF8Z53@B#TugmZ4_rD z*-a(eF3wOLYBx06=4g~?Yh<@wyFiUT8KH4;XqG}^KS8P*b( znLtn-R&Z)z6wyPJ^rGV?W1*u!BU=G{RN@vYEX?Rm-<0CP`6^Z7L#nTqmWbpC z!;&}{q?W7eH`>?n0%dZf(P67SB+;-r8iU?JqaM+fhKODyP<50AcB>&!#!pyD}`)aX_nTJP1Ql>{8hYDs`qFMr-!hGnrjG>xzoMMV@ zxGvPBZ;v-deHy41%hP)51H6=+35q$+275LTjMxwT5h-Tlc=&f|G>Y054?@Wc`wVSKfVCjJc)!6 z>7${3h$M6Al28%f4tEHHH0%JX#qy+K^`Cg^pkr7Xh~`ivjMsEt03Jy!i3}AbI8Ib} z1DqOHf@-lm@D3Vft>GX~uuE;bOIqhndBCJH#toNZ7kXl_bfJ}X>65O3V?5bkjwZ|N z(rZV;5q7BjvO0Y7Dfy|svfnPO!x!_DpBgN4r)pELLT;qY{al+m6RbNG>$k{)cjpj! z^;2ZQyfa5;-$!;fvTABSSi8yi88wnl`@C}6&2^Kj&~^59815o>JBanhF0=3Z(DvbG zSE{-Vb?k6A)s4H$!|7BvtaNJ^DXz|nOX6>5e2&i@G~N$EH@G)}Bwk%B4Yl6E{0Nwv zjNQmjuAU~6H#eR$m|nCThz-bnI6I2V<|!oHYV_GnV=)rpA-U)J$A~uVVM^6v*s$=Q zQJ(~=#j@C${z@1W{2!heBF@JZGYbg=((jEJ*$hY`CHF@NAC5nslxji?1y~EJ#j*e# zj0^#m-G}GS&@*qM{01bBl76mAlA&+oH4_{UC|vFQuY+o_JY37Y914B}iuofFM?pU@ zVn5U>Ml|aXChk{Yx@Wcq)na*o?K0PPf!)_MTdr)bZ<1UIKG}|Ic*;XN)!wJL+^WiQ zuv@Fw-3N`k$S-b8pn>x5dTF3r6}M6UHZb2b8Y>k0X`M$wEq-qunrKBLaZtn7UZ$Ah z?4mH>-O2+VJ+q6Ey8{~JpwTEC#no~*`(uqP4vxfsM*T<+st}3$C&{&g-x(z_qVmhytw|4Tdu7a))mjY90ppf@>pvhG=9N5Mae!c^U~F_ zOg!tX%KU}O+*j%XN2)9XUHhr67z})wGLNo(W+=+^jgt9gb?Gg7Vh$|rBfI{>I;mr+ zT7W}m*0C%@>iBbQ@najXT&ikAn+`lXr*xd-uj9nmP-1>_dYR&rRZ>U28NH|@blmHP z4*3`UjfQfqs9#W=H4C*WXp@&fm=7*Mm#-Abh0Wx=gcsj;nVXM7%ZbgNQh0V}HtMT^ zm&*JTy;LG?_d>$s67d;?(|927)Jmzq^U_8b{~jX+N_IfSiw2W01k!sx2M4(53c1Il zIQsRdU1m!R>D!h3Fh~A4$#X;X&mb(4e}rt(Kb!V$)a}xeAh|^ix#3RpBzLkUyARro zJIsz`ciwfe!xuf(f;7@nzn!zg%Ge)af9a9@RR z3H{+Cll*7YzXmGDw&-&et`*D6*|P+D13jYlvI zYYi~?GZ5Y#yYO>Zz?q`Z_1%F}{^-;O-uB>)?TlILxYXobsR(K_4pi3UUe;vgf^=Gk zc#n6NAD&n)pTG1TzeqlRdBcLqq}d6j*m`^i;jw4%8YocA8YDan5tQFBL`4j|6u(}9 z<20p!9@92}YOy?xX}>*<4BY zAqqXusa}&VKxaV2l6Md=V#zP@aRgfF;?3RGf#q(n&9I`;f_xy7mKmiNe%(W4u0)?*{M?b!m{J>%(?& zbzB_o3XBBr0Z_XtUL8#R$mW%*p@}`<{S(x^Kgw$4V?j%QM*Zrpsv3k#zLQ$z6G_86 zUbHb(gdl3rh##>{8lEAW`1?Ap+3-nJGy0H2)9NqrIgBjpQJ@w7f@i;yZgu=}vacLg zxGj;e=;_@}#&Y61kr*wKsyj&P@&!`rs;;&-OR0J4I>r={76$c8zLTn7j-iPDjQaPW zI&0fsJssPOK_UMBVnhZn)-Pl!5rIymu$|%t$J06_COD) z7R!?dE(2IkP|SWv959hXTulx{h%0dHp)hoKcRHvRivc4o0bYE^Ft0ZD#=z(Aw9d2S`Q-l{v$aJQP^wAzfxP z?0E91w1F;jlOy?7V3}{}GW)=K`>|P~zwYt?>-`K#vfg>_fx9tYyH>nkn||W`Xyix9 zK@(e~@h{;A#yhkbf)0v7wN|8!0o0=k%3eSi^=-Oiox!|qn3wu%TH)iNVzOeL=-6l+ zSn)B~uA9vEH1?p|CqV~fGgQA9X^SD)O$q8|S<8YwMb~Pxos`6{>!ngQMP{cmP_;Qs z0^t_a7685ZwXE=Ejs`C)4c;)?NI`J!0p~4>bAZG7D{)Q}U2}}o@<+)6#dy8f_ZT)v zNw|ls*jqa6iJ z-k3?k*KxZ1>}s)j0uPk<9yK)l{VQ3Q9H+=lfJ*WeSBWlNUG8pN?9`-6neS=W&U^Af ztbf6Ios!pq?6+){2SHYT&8QWae*xL2nDs1p#-Ev*IJ;^K-rw`$wuR!={jD3QYzqP= zUT+$Bvp~Hd2zNq5-s~3OtpT-L5bmOeyxtl2;;|Y~Pk$+m<8_SljLl0A)xPFEe60GN+;PlTsCv`2 z0aS|tut&;AhBsYbV;*^!GA|+tK)pX9kx@zR@p+NrYaBCzP=5#2VgR7-K!#Co18Qgr zGVw?PP&c=2&Zs0eqhFM`01TVIkWF*5W8jgXS`4saxYd||urqO219dWG%8_VP*!8Yf z)M~;*a?5brPFc2XxsgiI+=wCH{EALyW(M<83b-&wMWJsbOvh)nYN$aI^^xiB@(E&N@ehZ^ya0 z2MKGqhED9y7zodLWZQh*NPL6ihYDKnYJUdRVtLZ=Zi#2~1YQ&p2Typ2QQVA>9LV=7 zm^7!w`+#b(7{UD33ttzkZ9JS{CfhKN2fnI65?Mb*i8>sYC_LRJOF^|*9(e9!=i%p3 zK`}QYVVyn?e7k_y>*AusejKL-fxQE&#qtEU8egmX92E0=Bo3JH5Ld#waM2_c&%Fg< z#DQwD7-3AnW5b<6F?%49M&dUVi0j)^(PAu)or5r@fNHTAFg6-r<28r44Q50+$mSv> z3`DOw__ZF%e7+_^Y{Ico5aL!)EtV&(M&tFkXFxIcB4IFk(jLF=itLj=;`@gxLA6+nFecN-7SezbiG(reT?FAFu1PWYxet){24SRwYOxqF%AQ9k8O=Y8U?$lx z^x}YDy-1=7`gSdj_XgoD0o7u8!s~t)9&_#%dMAkHy+~NC(5VP6wL&61#QoB3hIj?X z`3g%98y|vdu`Gs-^~mtBF>7h~>;|gE@}%R-EAhnl z`=R|nG_#Q~-k0?7@iuOi$v7CH_=hKJ$*;NjyND6ehQM^G%`h<S}acm6K{MN-Yf-m=O?n}y5I_bUiV78L{SHdc^eX^ zNhVYvq|&i>r$}yXk~o3iID8VvCzVXGT^*~yxkj6SlyBwslkup*C_HV#%R#kRo=mt06%YMDny|lf*JwF- z(kaH){(@c zN06|x^c$sq%96}U3*W!Yz&jfXQFot6P%V}xFDBkDKVkd>HDB>&I<1xN&+FcgMcfcj z%xOrRf+t`jG`GC2I zJTR+n!Y(eKJ4Y^H-Y(<+Cl zHed04u7D<26r^I(?{EdHvSUH*dc|OOL@s560{|Di5fw{C6%M~Ci|g%F?EAAuG^Q6M#jywxz3}+MC9VHzcwxF^?t2kB<@w6FtpvkP-)NiA@GQ z+1T{2Ya>L$rU1F$oMqxT8?#uBpA$G?P#kvL9M*3kps1W+xO$5`Taqx3>h%-Kj7 zj2=t(10(hh>!QVK9EU0}Ju2S=s>SjIb`Yl74vP6S5(i9ph-=JM_zWD5or5sG0o7tL z!btwd5GOz}|3ShS^sKn>5Z58xV(D-p28|$$?x0#M28@lyv#0P0B`jzAgKUmQ!a($B zw_nXjCgDJssK)W@*QHD7n$?18u{;pHm)C}hdQf&KKE3sS2~-|#wxbcS^-rznDH5_S zP)~TLB5stBHO+p$+na|T`z0iLDID7cje4Vhz)-YfL2A(~k#NBP*ju}W zuSs36gg?+9-W>Ip#W2aDeL9nsN!b4=YFY!Tc{>s|8+|2d zLIp;+4uhy36G{qknlp%s_K^Hme8Ol4juRF75W0dtqy9}$Ee697UWW`8K-RT-eTjDDk)t;p`aEk0aqi58*`Q97Y;(eWZvTfQeYax0mREcY|uN7&Xy1=xYN&X{Gpd zQ;q&MGzx5YEyl& zT}b9|a8@c#{ZjO4o3n*Sa!%Q7w5c?X)r5*w=5*AtO>C>3`%Dp?NyFs&IyszA2K~w= zPoq4<$7>fWRC~pPk+F@hv4kte@0AiC$@817mxxd*)7uK3+5^OaN?13d4^%eSU4AWb zgKM;^vuueQTvGyC;s#fR(-Pm#4;9w~IT(Kiw6|-!%D^(g~;{w?% z*{%zz9yBA$9+K@EO*Nqjv$ly+s6wHZmWuevF7@0MO_1KvDE}gqRIJL^w*xBu%SZRj zpru~?MXn3zmIMZ-3|i_TKUCIbitr`^YXzi^@0E3_a_aJ2Al7h+HPGdivO^@+K-a|& ztHqq~{*1uf5s2NT!0cs~QU7NHFt$rS*F_3Tq6iFz7uLcf6zVC{VfKCfH-(J@{}|IjE1lBx^U{;hi7IJ5Xd7fOie3cPU=&MVkY8 z5vd;x-j_kWPVwry7Vk9V^>zX8Z=g<8yt)gEiD}CJ`VRhXYR5KL`&k=O#l395^ z5kK5aB5Peji$i3F)9O%o2%{YPi}5%%RVC=>56VEb7!Z?FEHZef#p=jMe4VZkrQL|k zO?#wuu6C@m22{4>KommHkBhWM*I@KjjC!az1V+AN65rY!OO8Nu0^Kn|zCz~F*PdF4 zdu`zCtmL(6T|@l}f~?411>O#zHdnmbv?&dF-95p3A*f~^5;j+gW3JssPi?N<#z<){ z!kD%yLM+Dd)fZ*8wYk=UYB3-@y zFHp2tiXI(e*FJmi2UzZc>G1PX!vT({Ib78y)?(KY?lSN;1=VbggqxHu;Z;{;-)n>K zAL96k!qHDH3Djo>3eui6ikm$bA*`uQKEjMd_wn%~5CFRkV&(%#xVj{}&=?vPF07$#DFB8bFs^m4 zixLNL?4e54tMyMnwHO0hu0@8rLE7qnLd7%BNe!zV4Xx}jtfHz*@knB`2M$Jv@BXH} z?0S1=nl|A~s5t(tl-lP=6+&vWVYyu!b{Tk>xqP;;T1QqrOW&IvHMy)xSZyNT2Qz9s zxms9lBMFt2xPOl!Rw}qD4%|b4i^?4D5+oG$YQIJz_htTBze3US+HTE4$#%n=z7dVP zPuF(}#n)>^S`U0^;3@^ALo>e-P#bI}Ntb^^e6E*7gtPWU?Tm|IAU6^=_7WI-0xDoN zi$bL*P+hD9Iu$tte%W@H7!2Mqs_3px9j1V4F&2y-NthVETJjN*t5zuJO3G9taSFok ze<3>rpK8Ao$7F@s(ZO5~s>Nc|vkvSw#FLJ%e8hX%tx;G#GJifJ4X!J(1yok-3cC`gHyUCes9!5yU5R&tcz?sj_c*Bg z6mNp#0ZlJaxWgoF`lwiZXsWg|)kV&m+wp_G&nUSlNA3;ds}b_SxDi0ON?jl1T))i5 zz2Pkag3()pe-5aF6t8}KRf?wX8Hw_@lt-0TmsW_T?;C9V!RLx z8FMcZ*(A7h38c0gUCMBZP!O){c_308B{o&yKu5VhLA4kGjj)qg;O*{<0UMr!OdBK) ztY0LD#2$ZBi2k_#&eO7m^cPo#foiclb&_Taq%RC65? zZi6eJo?jb~h_NkHynthc0@SwI530rTuwM@G4hwgQA91`y@#?YfcYj`YBNQAu8U;5& z;uMTqdEjceC8=>m>j19{Xn%?4COTnpF!V&+=KqIUvZ{6oNK|ES}|M1c(O>?1lVho1Ol-r`>B~+|8}-pc8f?AE#RMjz43&*Jk6r;W5Z1B4Gn>at9xCeE zpP>nOsug?}sRtAp1FFRs=vPe%3-9k|KKxp!C~8nmqka}HkEWNBsC1Za6@G|(FTP~f zZ-+E;Hxx&IM*Tfm{wufi&3M#8K@SEp*(jM zY}yVKGYtu2e1is^FiS+<;7-Ohd5?A2k7&tanX!<$i>7ZH+0H^4R3^|4S=TyXh zDRV6nMm?-h>)h|+n#du!W)^{=;swR4ca9^#d(8FaxJVIk#^~`Jj!)o8 z<8XWsQN;jOj9$ycIco0HlmA^`kJDNIP<~5bagD<5amu{iOhrI*u~hkrW29XH25@ zZK&f|=r{uxl#U}v$2rJ5-(bNSign~W!i~affR5t%MRii0g z2m+Alvu8#k%TYaYsI(g(xhhEVS4Z*^Z-C?_93bWKX)`3RQj&UQnsljMW>%*F$*dkS z#(Na$IK9pAeUuVVgyJi5RK5mOUQabf_oVi0-2@ZaoX#6l zD2w7pqWD|EWUfWR#nY!og@*($sg4%AaXj#-w4pBk6;Le}qj7soPg5KM#rzBjW66k54GB-Y zkkYp}UDBV<&mTbPkDT5;kj^J$QW`mk(q}oX98Bk(hfw+^FS2;YPWDMDT`bXPu9SrT<3?{;uc<0X@T#= zi&m-(u*yPX{Ru+E;VBeUlPn$I!f-W?ijq1IV(UT5o^6x~Sn~{M-qulp>u6U!p)0`J z;(DS3g>nh1om~v+dG zadkVgwE$1n>SQ)hy|V&ig9Lg_m*8?p!>-99(9bS_NzRkXQDb$(6B3Py*1eY?|42fO z!fm&pT6txy0+dYVvJ_jO8Yzw%sujsmNRb|a7cPju-iVU^-qTT$txgugM~Rdk+%}{~ z8tD&`bqbs;tbL678)8%o0<4NKUxYX8I79@t3~<|tT_v|#6;78*^%Dz)7hM|#ep1&O|~w*vPl3 zt2A!ecDNmd=%o}s<`{s=UPs;VP9l@KPGM4sl|cnI>_Mw+4%Gnu3ayrf@fGUZbWMmg z%EM%7_&GC}p*}z@$!RZc*BV&Mh10-(mt7W5BmVt#oxxL<(^TsX|8baVxWV>wuAvZj zbMwlkz9*pe)DJhJBpzVEZ4WS;j3{G#tPuA?e|v3O#$)S!w)Su!S|(6=n~n4R*3et1 z4vpJlQ*l2dXJOGP7e;D&d_c0JI9fzLXoO(c?jJ>a3OUM=ksi|32cH~;ozZA3xwdjR z>Nss9eX#YzWCw>T#5Q9Yh7M_Yf!}k{-9eAOk8o|M9yI+SbYx%z#;5w6@q{fHu&jGr zU-avtwqHIGU|xS8f6|Z>ln^^K0@sZvA*XUr>8p(2&eip*3zG|uPe7C4TRXOsj9We{b#Gy+w*6=I!9f7K{}M`IMShB z44?_I2lb%+VcQsrt&zKukL>lcgx#d%3badnSt6)4nBB>Q*k{wZVKw~~rK7zLa#p3U zl7Qn?Qoa4ULVhklD!pc3Q6`st?sZ8Gw-?uvdcd!7?1p>;oWok^9;0?$2W?nYp8$t^ z6MdBkRQ_9v(H<6scpKfTVdr{>ToHc$ZUC$tW7rRcc(1`Fdma+vPy-91`^89`zu!Pc zj@AM{k>uZ^*L<0Hgpvb~i%+T-}=wgX~R`@$~8X=A(de`&-zqb0S*R}z^^7UFBa+_eUJ z%{Smt^A##6#J2&e%E{uWER2+8BansUw)B{v_sd@R9bRYPtqvYT_})H;!avvwJAF35 z&OhqQ%Fg}^n4b&^RsGzcFgfD>q9s*7kZokE_^Yi1y6tba1)ySrJT-@7Y8T=!G@RVGp4Mt{g-9KI@Jdg`P*#XD z!G0Vn{rDgI3i#})TwYmdI%_~imc0TCNmK12L8XRYWH$788YTZ@`Y$}>P_o!mQ39Cd z8ZE`<44fC1G`LD_?o1j>)kS;wq6#n50!rDy*0~nf?fyexr1*8DA}?j7DX%x>!cgus zpq1=EH;~q}sYV0dXwm{(h?}HsoH@w0&CL?h=}`85Zg~*hUIeW${Z<4lC&VpeVKsn~ zqPNvWyp>0z%^ZAECfyEdN7Z`FE-ItiplxnNqQCK{c1CS zsjKaB+4Ta(;Wd8naylZIdYHuy3}O8v#9G_LC^f5v+6&#KVO7%$vCiam6#CBkpsUUx zxuL-&+v<0-4NK!24*mB?o2ZV1#UE*-Mi;q0Xxm8o`X<%JiHN*nA*jn?X9^fW?rU&S zD&gq3*>vKPs2nY`wvZN19E`i~{Q+G|4rmY97G+b(ZNY<@4`7n-p@0IUi*6+Ygg31I z!zPCo<3_L=+ZyN{*gv+bt8z={A0BzcZbH^TF7mK;G{c=r(ZcpI*?#EQk4qz~E+9Mp z6L#6kf$cH#Nr|ljPP9JXp*h(%0!;r@gNqGJzY~`!=u2JZX+D?X-)GDOY|O}gCq`Ws zdMQfTWdrdf5#ZR*`i*XwxCraH1{NTlXfW8VQP@q?bT05~fzF7?l~`(E+eSz)__cAv zMcj)Ggs8P?WZNSL19oDi&`a7aRKZvuYPSFlYeLx!%J;e1)QG=N7sS$bL9d)eIeY@s zjK#odZ;PlB`{8W_a=S{yp zgoU5oMzAgxeY!quZ5@*k;vL%xxMJ@J-VLyn>_G2n47Lej*iL##Uvuzf)4Z>*IPLI3 z!%2kH|4=hB1bGnAKeF2vRLUP#!g7U>0LsS=B>mTgLLAZj+~}WZZq>Ab{GY1pfxR5- zK-(m00{T2~KxHcF_l1qm6!Ktdyf01ch?zno!B;^%R9o`ouNyQ5(XlYp&g|F*%R`N# zYGOCXQP~^Sm?6i>W8}JiI}ZE`1uRP%e{XXG+jf8-OtlnMwf!-Ohqhin*^3pN|7>$W z7n)pukzIx5ZPZ_Bf>n_LtN_g@j5(yialeU|@+bU9qbM4UPNJ^d9T+`eH2U3aW^`)Y z0>QyHjmO6}GnyhyamrKyL##voFzJ3ImWXJ;s3^H`VS7Fx%XTGL|haicB^^0KU(bXksj6DDGbF1zcXtPaS75ivtDS>q@TB*)|WhGfED+rX51nz_rx zi!OzN3KRP}S7&VI*1Kr+MV)qoWa698bp3A1OV3ae_n=m`|H@9X(M1oXZ_-wWWt`dk zUb3)qIc4Gd6eqQ(j@54Fddt8Y)`LOS2waNY-{5-S)d#dL>;ZvS9}Fm;d_yjW9@0|m zPyTb{R(*{TNlJR?!?KlClPV)^vl|h4?u`gH63OX%+(CtS1l~aAmHq%`EE>5jRcNYwUfL^Q>U+Vq zfTGHU#f!EyQ|*a*j~o)zwD*!~AUhnfmo#(kiQ6`N*=67OLOhXlq-hpDL{t4MtPhR0 z%p}kLtwoqZJ?%4TK2!*z+lpIu~KY6w>|R>e=lJi>d^;X7Ek(b z%F!cAT2qcFZ#6*DJ%A+Nh9m_d>HHm6JCT5}BtnKkrO5H}JvmNrxsq}ysGd{MCL zs_nNQkmb~Z#UA^yOvH$U@kg~8>GF|Xk{Xc@LnF2Jc53}G#wgPEh#CZCtx5V57vGY^ z%=D>?)(LVP{0wDtd>Os%bNd|cvwwj)xNwKbS%6?=2lWF;g!+|>mNs<5XVH~! z_zKBm0f+PPu|z!zTstU$5U;>vt!m=qp@`fEV}y)De8&Y!kIV|Zk@CH5O0^!5YO1>| zKQy@5Kvqn^PhGe~JG}K|7=Ja6L26J;82?5}O;u$|Nm+rfrm!fbpnLa}zA5=7)m0*x z9!Q##k)E60%j+vCtC{1SURHB%*_5I=)q(Q)<>gh?AQu!>RF{;Oo#oVJf-o|fj|;rwhhC})%4o#=o@ zkQS?&TUA|D`tMg9!~7R@za(!~$@DyGj;fTwFi2HOY5A<8-2A+%B55Go4uRzV(I5ro zrKRO%xusRpt5T|}3+0Jjl1=#kv5e_O@QUinxq$@*P|s#w$5kB*`}Z8#IMYgeMgQJF zg+AXoWO4Ou#cH9Hit?(GIscU*GDl@qr4;1mRg{pA|5p$V`$a)Th2zGmTLjyKdR1Vh zf`*Nt!AA1?O7c^t7Zjuf@%Ob${jX}_X9(qCf$GTtu&^k1BDos?>8`JBQ|e zRX+z84OnL@z#eJOA<6}mlob}C>jiswNp(?WUUm6dEoWal2Y5b!&jwqOSDA-Fs;KfD zrtjJFY?AOWOpIkkmAS=vRmJBhy1J&qSM+~fKU)bkW#yHHMU`mLf1iV^iz|!r&RVm= zylS{ACe^b+I~P-?R~Ah#C$Bv>8xM*93RhNBT2xt5kOG^`Dypo)ymk(igPG4(G#b04 z{2V9+#g*k{|2MJ$p~?&p@(29V8t3NYYOH5g*FoMD)VBCE^~f`V9l1B z=bK(m`yE-V(uIL+F|8j{a2G-6S$DvK}!)+yH)1?{6EcRYN zQu2JPv~8!FvXYrKMbeT~6b(a?k?fv21m`gMsB$#4JRMyFm#Hj6rDYzUkA~6HWJa|> zHJ0eWLN7)~(8Zy{5~yUQuFeKPFC;CoxPsy}1yl@VSuUV!Q!6?I*a?kUnm3~;R~f53 z|4L}Wi0Dgs)3NfaswzR)fkuFWyefH#+7^Y`OKMpbFJY;7<@vCQpq^ecZ5mq`8e;&M zR$e(fuM*yeQqkf40py@S7Os+50ZpLnKmxFH8RjXJa25M8s_3`nfGic|rwu6W20!?L7ys1wno!e_f~$DL8SEImagOf{Xdf>YZDmz`CDbU?*nFmpg)WdA zXqiA$k-pd*%N;PpF)8pq8>jeSjx&;LkCrQhxhyxECJZ{OsVb@p@J$p_AgjlWylyI@ zQ`wtxXO+k)iN+Nl_Hd*H_%TA*rzJc<>sGGJrD|!2X|rkkLOImT`2k~Us|>S|VD=AhA=3`YjftDH{ghzP*7um&&8Ew4}@YUicBoE8Y> zWd${rl|^L*qy-2K#ue^$1d6Nh(hKryN_^zt{K1FWaBG@k1-@vJn_HS+Rn41DNobJG z%^jLG;v#tohQT=IN6?qp0l~$+gSo0pr4U)#E=&OsiOeM#3edu`LGy{YrY3yeNHLp6BLH!@9s$1y@Qil5>^jR?)n! zIyOo~rc7Ncnp0GOu86r34M#18&kA5rgtU~MUQ`W_=Orr$G`3(6F2Pa*gRWZ*md>1k z316;hh@vN7kYOdPi)5QuH(1!wWp;*Yzc~@`81*o^l35szi==VBqNI#%4jmh;`M_RQ zu)KcDSXQ&a@2OcHb&f-w)Ae_l(c7xG94B!#X@{%IZhwWcNhP93t6 zE>bOIg@CDvogI5-M4ZzbOqS$)Su)b`koM23B1EdnH zhxqs1WXqXG&Ijoe`Ix!l&HEHEMAh(F~_=%8=Ujk%> z2$LK@E?~&D18E3yLjBPZ@D)xki~+X8N7AQ+(&6_?%#02ykdphT0%>Bqf~*I=W}pJ( zsfH|LHF_iCC!OLfh%`DviYNYwzto~v!WPjn2S-x<{mzDABs#n8Xht#x;WH}}{4joH z+9Ohcys!@Iz(z`Lv4bd-@KT|uct3t)+o$^nT_Wj&*ODY{GVXRJd6l#~GL|Ms(&cirN7Wy_%Zx|la@Wn<09$+zXSvB1VFeH#)U61L#G%}PrFHmRL~{p zm)+S8#milQsGyF&p@|G&-AAm#BjX2S#-gT&)4koNlAYP%>>wTDfXLrSmX1z&BcJmJL-u!BPX)^XtV858wr=OeU42;75$J zZz$J4lq1C#3XOBd=3;;P9BmkV8q9%>!D4*CLRgC0=m3a+4#^zxV|NOQotO^rO}EGy z1rG~!RyyTx7&g{V@rC5emxa>V~lr zHafJ0Sr8o^!LoMK$gyV#&7sxAU#(aM7;u=n;g@@n%Y;05@@L1%ldu8eZ(vc8L1yZR z=BNE9JMB@u>dW~^vMvAN@l*&2IZpizTdeGyH^6@3+Hrsl+Uo0X#` zcG}D+ij+i-ng#TMALygrtiwmN*(|1yQL{)sR?x@qaud^pze`JV#*{t~iO>j2cm$dn zELvA=mR>Qp>Ig~<3N=ME7g_Y_;$k!XikaP{&+Y?MGn_^L5YWUG8M@&IHEmk-M*!V^ z(5#LfHO0G1%FXMdzwu~!tjVmsWXjK*6&X|AW!8+EnkUTKoLN3(%0|uhV`gXU17`IZ zv-64kzjr@j)}1kh|IT^Bm{lefxoe>*kL@zcxyR*aOwDPtB4@S?nVDBiS-siXY}Uoj ze!%Q})~w==oqy5gTJG5QuX(~8zRTQp)yy9?x1Bcg&zRLun8jxdet-Bb(}8zw%$W7% zro79(Vq3G>K(Dy_*?fl$PneBoOdRtVHCu>;TXTF&cJ7(T=A66efex)?hG|wC;eL1q8JDBHmaA3qd1RPoxSuIaIbe}o!j64)u zWDdmoO>yi!rsmst`y#U)E%(N@0&Bl)=3rL$nOP%d&S^92ep5VRcKserW781*GQY{p zp?6@HFPqxE&zqXd2BptyV!tbWe+z&1nOU)x{NuZyH3n0j&Cf5&KObxPg~%It)P&)f zHlcQeXFvNXv+zZ;O1>|lkBep@ebnQhXept1NzRnvqqGzUq}iO>Jr9PCB=E%cx0|M&b+1Y^?u6JYE*7H}jj#0{l5=m}rPuewKPEjcl67>mDh+ zY!cCvM@{WF&7N>Fqf)XUJ@N%G?2TI*)N~Gq=(3 zN6qRN&GPfW<+Em9lUaUD{yOUVYvnQCq)2R&+4S4y_6vm1cSMJQJk&vS)&+bU;6=XW zqO->40bI3Xys%4*ovSzUAJy{&B zJ9E;kebHRX;KLAmwl=ZYemip|2KC5O$%=m&r9Y{_D?FS=pOv^-a`)|5rJj`33$ z@NYD-gJ?v_1+dHF(&(Q=aJwp&8I2Ls7VfHvOrzg6#dP+TA2rdVG_LrVnNeYij|rES z#+oWM`gp0U@g2>k%G0>iM8VQEH7f}uyUv-rpO>Bls2N|Q)y1avoY`?!IKBWiyKMB2 zA*{@M+RS(Y#67yp{k*2G#aa}b8RyKR*gSU+niDtrMSyR;Y*rjK=BQcO46z6lxWZK9 zBf8ezq2}L>e$D*^C}lLZ#4Ov4k45r=X~;=h7SSZZ(LawAoAT)Ue-0=UiN0KP)KoW{ zx-qk~!mOYJHEor=M4r<0$I)k_^wh^5<)^*`Rwqx*t}ye*oM&SECe5TA{a&ot+%;ADEeu!~%trtg1P>qaVQf%)4sJBC9=c&G*glvL8flCybnK zX5vxJD;_-V>QYL%YSa;O&~wJz8IE zkXxUn?-@APWf4saAN?VY(LLzDSrKw3NJ3de^Vdgj!*ZN2nPpZ-|2+ypc5S^`-Bf}$ z(Z}A>Bpu2FnoK{s2Ew#FFj}GynC%&U=0AR>T()~ABZH>u=R?tS#h6IFUG$l}vRV!x z`UPybaaLAtn;u*yMSeK5NR1B?(5d8A6nHrMRWl9b z_?Vg1Wx&B%HJJmct}LQOC%D7XPQTAsc7)ZgH#Td$e9Pn+3zZpfIYwb=|b)1o5L z|3I@j*UbDJi=`M#x%5gxDulwV@-0puM_H|*%erpNY|FTzTBs%ZM}Te`Gx1S3RLj3aF9Ny-TyaCp zVz%_H^=G1Q1!*YgTPxW_PXp@dn|O-W$%%df(A#3oX8A>P+n6bRnpN21CKm9EFHm`& zl44?mjwBz&m(tQ>5fsuWE}73upoMv&AHhIZUp1xYWg`}t2wtV-f1+Q(t8Rg`oRdi| zfMN_fWUC5AUjP)$dff$ib|JGqEoX$QPiEZ%^ZDL$qQV)3o&-&{MWhS@ati)g}vC!YHE^ z;G*ZSH_NV(YG&+=q=A;2i+%wOZhiK=SqilUN==hlc-m>Y6wIhBq6O`uub?TY>he)u zXiSSg&zUW>;^q7m#u?TyMllK;@h-s!=|^ko(GdqRnt9nQ9wpnyf(OjZk^J9tN9>PP zBj#>!IkQT3d?}OoA3sNCCfr8*An+Obxylg&)pCH*|LKPkZ__%0(H8+-f7%pV8DuF_ zAgw+a{aO%I>l#LXgGeuk#cB+V=x3x!wC7j`Uz}4+vnPFgQH#0#J!aVjQuvBj>uM~= zV6?bm^#7p4gRw4Cc?KV#Jh2KnWJ@6eltr}4WAq}CS9QK3iY3a4O+^iswut%Di;?UG^)weGT6 zI0k)eGe-SlWCb1TrP%(mh}PMR{uy2zJU2otE%+II3C(7K(>zIX&Mb()mIKHVXbsWm zchRh13A7q%^q&FsECGo-TGurCZy0gL%(-k(ZFJ6A`q#vsjI5F|uR}|%mKuEr1S7m< z2{6x@JYkO(UyYtCExrhg6ijcU2E2;NnV^uCb&Z}cErw`?Hee~fHd;qE`f0Sukf~-% zWbHgyptiYt(#o~bKZOD_57@B|N+NHSWgWsZj$*@L{UKeBcm@j+G88Sn8+`$HJ<9il5R!C1n~dCbfhFvX`tw3Lpu z9B}ksX=In2L$r(!kyaRvE`_!O)zAtz0@O0bBr0ygoK}D=7GIK4OAD=;9NkzP8#9fU zO>yMD`7mk>Vtt-)uaDMbj{f{KTE%S`M{Is%nQSNRmezxgzGE6u`X>RmW4V@tAwWT9iBbQ4DA|2uSgh?)}no-_ehSOh`+ONB_t_q2+uwwTd}Qwd<~#X)l{a zkS?DTVj^v{Dthz^7{-bpICOpp?c3u~!0-J`3D%^R@VCORv! zxmY@0VV0qV)|8LNadxhmWmtoZS&B1eadL%OidI^)K3Z$f;wnCi_!lBL@7)T}(y~bP z7c7mxllTPAY@FNSUlZ9pUkJ?#_7;3XTRx8oErPnPe-? zn7xk?UggDYBv1TOuy_mOJYa2J|8Vh@;#Q5XT=1#4zG+ldZ5W}0GG z%p;f0(Tk>K)bz11gqIzKR!DCh#YW@vS@w(+KWgUvu~{%?s-uG!?ZKao=c1=@E}K4q zpWjT>D>^%t5dyG+PtMo=(k|UqOe<$@yJVI(k!)*VI%zQt*s9ozW;5^D?W1P%MYHAs zgDqY&W_F)5h{hz2c^`coHAm>-&?6h>dwNa1!E78e9cY0= zx{)3Q#h|YxM}ZpnXflam(^xp1@)}bCQPNal(U{t;F1_fU-@Gr``JI87lB1KoxQT>g z%&)e^?350->HM}`F}FQH8ah^B$2o&gP?{gDHs;qvALry7!2AvW6wL2_J3n`?5AysT zLUY&r=xcs{cMg-Cg_hg>;QUH68-nSmnSRc!$A+9W>(83XQPTh-Unw(wKxZr@{f!sw zjQ<#Txny%{Ozdm|N;u^n@%!++;H?70wU|Wl?-C z`!vo5RLy3yi7|Rk?4YTIrwz-1-cQPwuVNL-e8mnB?}3;e*|j)Qyi*`mprd|mD zKNE?akV&m(n$__4_GPn`T&&^WPw4M+mA=T}eqMk79?shsoww=HvN01`B_vZCeN`L% zJdk#jkQR0$Xc?=H(Z8D?Feu0#iM=R~%w=la{dGHzFA+gwx&@;w_T!8KVDelDbMQ=+ zNY}CjX-vUnAi;Lt8QC+>%&m`1C(0*HmVCo@O-=5+V&=v!xWR`N3<_d)U4cuWpoiag zH@VBz!*oWBZ!7pkQY9h}$*aj+@Zdk#S8vi)T+2_qCI34fV3}Z0QLn-@YgZk ze^vqScL=@!E-T=rs6HXwru3Wk-F|MfUIBh?vtI#zZj(_!p4-T9->!iCaM!bn`XL2O z$Dr2Gg2?Y*b^p%0EWiIme_x39Y}J(C%U`mSaDLywSn-hl{^!m*ZQzxCQ~|#U^{^7> zXJeD8Y%(?HL_m;6AJIl1#)d)nxQIgvSKgX=rh@+(gTZ?gmQ2fOa-%%X8&b7k?(^eY(twFqiC{Ac61{v zrjKfqKg4phjhSQC^0v|3fezlKP;xu$ykg?#RqbR$phtUY0|tQ0%XBw_mzPEUQXl^! zj+jYYgbx=Y$(Wp5X|nlcJH%^Pk-Y%70eN^m1^#-4|29PboN2xYMKmMyZxfKNEb>3K z!4e=BROffg>^7NW0RCSE-d+sFtNgMlJ8vHRDw|m&T^-@W*Z;d52& z6R;)znOPB?K4xx@{j*sWJ&C=z7q%v9S_UknXQyFEWV1CfToi#ofUghoA9OGvu;t8( z(%8R57Son&HU}}HAAZZu_b-8@<}0Sy8Ui*$e1e(p+ZK8O(7D*q>9E($=yDV=>0_6+ z`rDvB+7~d2VdSK* z1U^=oY-G($IUv}1mKq_zP){VtP){ZJye(3_5X-r3LF6`BMmqYR{hnRM zKPxJZtb-y4o6IK-zc6^I6b%|G@@?Gd({J7dp6tKWuSpEq+6hLkgv z$H=U+@c~5O9D_Avo2eO-=#wT>$M4IS8v3lqKhA4s;tRcYZY!ccmPU3g21-9qE(kb0 z%8!|u2&H%fLPAcN2hiy(bc%Vj)pLgs1}T(*1VPd+qD}m^DB$#s-XeRCs4$vb3~yO@ z$dq3)D~@5*E6qF}_1xDR+T|FBy)23z1S&riU4}8-2~iRr_UJay64x$lylQvhx9I2~ z^aidNdp@^_(5DT^gbyzU28;l$Ij!ul{ERW{gmejlzg-(YgT`}S#mT7<;=F~~)$c3# zIe^zLc7!;+a^#8c zDd3%DBynz`Ic?*<%3rm8y_IEA7A-3na#SH}@RDuxgh<}+)!*}ycbwn;tOC~I0oQQ9 zroa1#i)6N94bKl(9Qd~@;3aJP!mAYUa+~F_(|ETVw800+IWzxdGZ$f3O=d3aU|8=V zGwpse3o#zn+ajI*fj*<1f}D9e{gO6tcbdcDEf4Iqk}lwhAgzoyVy_`+Z;pUb-cTx&I) z#k$Xof3;)%Rp9Twi{_p)!nMT5yFsCUhZ7X!HTKwU1nt(svA+a7lml!LAFm`irhlzCH>#_Z+4JhNB@gKAIc$@ z#4id7sbtLT)+T2lJZ(b6T^T9%#BgB#B)Z6NkCdLlpJvn?gt^LW`eicZyZw@}AKMrG z1naqy0)4IjR2-9A6#O_W>MqA*6%S#rLdiLOdvrQjW!0#eW~t^9LmtG8w)rr6SoA|v z8re8s7QCAKcuL{Fh6UeXkBk`jo>S0eNU&vBA&NaOCu%uZFT#xf-430UmOJt8vZu|h z7p3pz+;^q6_#bG24pvyGSObqJ^q0$ENrlR=5~>H2GJ!v;@T)+SrB}^zE3eDo-mlOx zKo`K(iJ)B@byQ=>r~8~X_$$182D-lmc1@1rsNunVSK+^j4q}K}g{>X2iE|MXc+t#- zao|NW?P*bQY8mJ5{fV9LH?dVs=N-*NOqeGW3W5Zq$!T-(`joc$Fw}-> zc(k`Qnd&jK{hVNgOzel+=)LG@(^a!8XYRH>cNzGS|FGjA7hKs79FOrD9%ZdU7s6=? z?hvyldpkoj3Y`bG2QC&_Z-YjJLcd?Z@U)rIYqTCE$IP@#vToAm1#R;+w3&}}U6M1U z!@j0M4yMyZSaLM(B7u7M`KLXkq(Py4#CDlwSo~qzVlIz%SX+>`w-*@px}0gfXkG^+ zww;w&TRyJsUM7yyK*w03o~9Su0Xz;Jh|TfbZ-xGhm^1m=Mz!Ck0J55+oCG?OH@r&$ zcmp8!BH^raba3RJd6Cum$3KAuRXWaDF9D+ z7o?=r_BGyud|Dg*)Gdgd^?7A>627x8)~mG&eF{fl`47zOm&~--yM;EcW8%}TE&cSonw?o8HUgjHaLSMcMn73{+gksdB7^gC91xC5eixs@JnL2wsb