From 7f6ea40028224229bf35fccd8cb8548691a64901 Mon Sep 17 00:00:00 2001 From: Tony Najjar Date: Fri, 5 Sep 2025 21:13:48 +0200 Subject: [PATCH 1/3] Add debug topic to visualize whether MPPI critic has an effect on costs (#5485) * Publish criticsStats Signed-off-by: Tony Najjar * linting Signed-off-by: Tony Najjar * change header to stamp Signed-off-by: Tony Najjar * make unique_pointer Signed-off-by: Tony Najjar * typo Signed-off-by: Tony Najjar * Add readme Signed-off-by: Tony Najjar * add to readme Signed-off-by: Tony Najjar * fixes Signed-off-by: Tony Najjar --------- Signed-off-by: Tony Najjar --- nav2_mppi_controller/CMakeLists.txt | 2 + nav2_mppi_controller/README.md | 22 +++++++++ .../nav2_mppi_controller/critic_manager.hpp | 4 ++ nav2_mppi_controller/media/critics_stats.png | Bin 0 -> 119317 bytes nav2_mppi_controller/package.xml | 1 + nav2_mppi_controller/src/critic_manager.cpp | 45 +++++++++++++++++- nav2_msgs/CMakeLists.txt | 1 + nav2_msgs/msg/CriticsStats.msg | 5 ++ .../gps_navigation/nav2_no_map_params.yaml | 1 + 9 files changed, 79 insertions(+), 2 deletions(-) create mode 100644 nav2_mppi_controller/media/critics_stats.png create mode 100644 nav2_msgs/msg/CriticsStats.msg diff --git a/nav2_mppi_controller/CMakeLists.txt b/nav2_mppi_controller/CMakeLists.txt index 4abc1e888ef..4ed24919c16 100644 --- a/nav2_mppi_controller/CMakeLists.txt +++ b/nav2_mppi_controller/CMakeLists.txt @@ -7,6 +7,7 @@ find_package(geometry_msgs REQUIRED) find_package(nav2_common REQUIRED) find_package(nav2_core REQUIRED) find_package(nav2_costmap_2d REQUIRED) +find_package(nav2_msgs REQUIRED) find_package(nav2_util REQUIRED) find_package(nav_msgs REQUIRED) find_package(pluginlib REQUIRED) @@ -56,6 +57,7 @@ target_link_libraries(mppi_controller PUBLIC nav2_core::nav2_core nav2_costmap_2d::layers nav2_costmap_2d::nav2_costmap_2d_core + ${nav2_msgs_TARGETS} ${nav_msgs_TARGETS} pluginlib::pluginlib rclcpp::rclcpp diff --git a/nav2_mppi_controller/README.md b/nav2_mppi_controller/README.md index 68db5b73719..630aa19f214 100644 --- a/nav2_mppi_controller/README.md +++ b/nav2_mppi_controller/README.md @@ -59,6 +59,7 @@ This process is then repeated a number of times and returns a converged solution | retry_attempt_limit | int | Default 1. Number of attempts to find feasible trajectory on failure for soft-resets before reporting failure. | | regenerate_noises | bool | Default false. Whether to regenerate noises each iteration or use single noise distribution computed on initialization and reset. Practically, this is found to work fine since the trajectories are being sampled stochastically from a normal distribution and reduces compute jittering at run-time due to thread wake-ups to resample normal distribution. | | publish_optimal_trajectory | bool | Publishes the full optimal trajectory sequence each control iteration for downstream control systems, collision checkers, etc to have context beyond the next timestep. | + | publish_critics_stats | bool | Default false. Whether to publish statistics about each critic's performance. When enabled, publishes a `nav2_msgs::msg::CriticsStats` message containing critic names, whether they changed costs, and the sum of costs added by each critic. Useful for debugging and tuning critic behavior. | #### Trajectory Visualizer @@ -293,6 +294,7 @@ controller_server: |---------------------------|----------------------------------|-----------------------------------------------------------------------| | `trajectories` | `visualization_msgs/MarkerArray` | Randomly generated trajectories, including resulting control sequence | | `transformed_global_plan` | `nav_msgs/Path` | Part of global plan considered by local planner | +| `critics_stats` | `nav2_msgs/CriticsStats` | Statistics about each critic's performance (published when `publish_critics_stats` is enabled) | ## Notes to Users @@ -328,6 +330,26 @@ As you increase or decrease your weights on the Obstacle, you may notice the afo Once you have your obstacle avoidance behavior tuned and matched with an appropriate path following penalty, tune the Path Align critic to align with the path. If you design exact-path-alignment behavior, its possible to skip the obstacle critic step as highly tuning the system to follow the path will give it less ability to deviate to avoid obstacles (though it'll slow and stop). Tuning the critic weight for the Obstacle critic high will do the job to avoid near-collisions but the repulsion weight is largely unnecessary to you. For others wanting more dynamic behavior, it _can_ be beneficial to slowly lower the weight on the obstacle critic to give the path alignment critic some more room to work. If your path was generated with a cost-aware planner (like all provided by Nav2) and providing paths sufficiently far from obstacles for your satisfaction, the impact of a slightly reduced Obstacle critic with a Path Alignment critic will do you well. Not over-weighting the path align critic will allow the robot to deviate from the path to get around dynamic obstacles in the scene or other obstacles not previous considered during path planning. It is subjective as to the best behavior for your application, but it has been shown that MPPI can be an exact path tracker and/or avoid dynamic obstacles very fluidly and everywhere in between. The defaults provided are in the generally right regime for a balanced initial trade-off. +### Critic costs debugging + +The `publish_critics_stats` parameter enables publishing of statistics about each critic's performance, which can be visualized using tools like PlotJuggler or Foxglove to analyze and debug critic behavior. + +The published `nav2_msgs::msg::CriticsStats` message contains the following fields: + +- **stamp**: Timestamp of when the statistics were computed +- **critics**: Array of critic names that were evaluated (e.g., "ConstraintCritic", "GoalCritic", "ObstaclesCritic") +- **changed**: Boolean array indicating whether each critic modified the trajectory costs. `true` means the critic added non-zero costs, `false` means it had no effect +- **costs_sum**: Array of the total cost contribution from each critic. This represents the sum of all costs added by that specific critic across all trajectory candidates + +This data is invaluable for understanding: +- Which critics are actively influencing trajectory selection +- The relative impact of each critic on the final trajectory choice +- Whether critics are working as expected or if parameter tuning is needed (e.g. `threshold_to_consider`) + +More detailed statistics could be added in the future. + +![critics_stats](media/critics_stats.png) + ### MFMA and AVX2 Optimizations This MPPI is made possible to run on CPU-only by using a very well optimized implementation that rely on CPU vectorization through AVX2 and MFMA. All even remotely modern computers support this (2013+), but if using a very old computer you may not be able to use the plugin. Note that MPC is computationally heavy to begin with, so computers circa-2013 even if it were to have those compiler flags available probably wouldn't run it at a satisfactory rate anyway. diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp index 8790476b5df..3045288547c 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp @@ -22,6 +22,7 @@ #include "geometry_msgs/msg/twist.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" +#include "nav2_msgs/msg/critics_stats.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" @@ -96,6 +97,9 @@ class CriticManager std::unique_ptr> loader_; Critics critics_; + nav2::Publisher::SharedPtr critics_effect_pub_; + bool publish_critics_stats_; + rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")}; }; diff --git a/nav2_mppi_controller/media/critics_stats.png b/nav2_mppi_controller/media/critics_stats.png new file mode 100644 index 0000000000000000000000000000000000000000..c373f8e0dcc5edfb00b450e2f6c7d24ea562eec5 GIT binary patch literal 119317 zcmdSBbyU<{+xJaLD5WS0Qi>7+A`C;9A|Q=~bi*JF2!cqLDBV3nh(R|)NQtD>fD%KO z0!ky@JbN(C^NRaUV6zQ<=1q^c}ScAEAy4h{~P+`YSMI5>os zI5>EG#CYHpODgLW@CUA=n(Q5%f-br_92_Pbxx2SDTyPg_ceTzByx;ad_F?7d;Tf2o z4e}D{;X~)$F{kXKqrTbhFQED_!77MkWOf@zOW6W{sr{L+Oll;7sqTAHZBvhLFH zkSBJ{9FTNV=qwZ@t@v_T+&3`L*kwmgGHB&Hu%%-;u{U(AGq_w%QUz!?3cn2GB5 zyKo3Rd~xz<@@W1xL|R;Jh!Jt%WAZ;wF{LTsVDfrjn~&}LD*hV9C(1-VD+ebhv=xPS zPA;5937I!{Izap$4yKdH?zA$=U*A9sK2IC+>#p6bcOAV+%9c^k;!2aWJG9(qCWZfs_;> zo1MbNqn}^}>#@I0Y)SlU;!I3j;JaQPDaj4H2Av@~SvghWENLAJi>k~My4g6OHcWwcy04cW=V;f z!32HQvuANmP8H6}oX%SHf^`MUPaW6m0*%#<2SUVyxEFd^g_+Irexwm%IE7rX|lp|B9_^2BBQ8Bdi2aq zXQz{6Bi@W|(}}r^mM%^|+`cf3R~~^n{j@H8@7|)8x@U>C(o==SZ!FX6Y!cSrpXFbd z9tyfo9xxwk%9~)zVH7{)#>FY~<9nT^WBHSM66+}-F_g27~n>*C^UI^WJ zL)B|Z9jj6BQdF>p8IC!3!B#JIJVGhd!aj=aZ!5xe={`(OPA)EA!h8a;SJ#xmt~Ba9 zT#2elGoI;6nL(qE*GzkL490AG9B-IGi=pg}ly6aXlxua@S}&51Di< z?a;?MOMdEye$#f;1MkC4EwFx1mpLUKe~Hc9Qxu}{o8ps}!Q@@v8?Ln+$!W9lGZSY> zPOYdk9f^)7=3;Twc|4bFzK!AJ<8j|y-mLT+J2cCjrK1Zk%8I?-+?+c|>ujr+(atJ#&oCsPCQGiqU3$!Yp;fsGT8g+ zs=mtPAsWxd14Hg5Go9v<31AN8>&p^|V6a;RW^w&G7qgj-Ov_+wY^k_s=#~tP9;7UX z*&Thfx4<2PQH-)EAmPq?-GHI@P{zy-v2`zLFr$hIX!!`cnd?$3l4m;A z$|kGrVv0Fv7}M-$g>S`ob>AbU2t(_tue*I6Ebk_i^%pW#%b2aW`-q4`KA}wJ5z_IK zF6x1vR=J7ekAgRvmou6JWScX+%QJS2l{VY_nsZBt$_EQ}f}}0yK&)JvAcRt z3yo@PZC2Wlht&g$wj@yc@S?eNKdqG}u0uE=-acczn{MUS2OdQR^d*CN!96aUxABq!jz$|)gXgnFf@e%tf=%}1)T zq-||d;BX1lWe49iJ9UafC0S5!|MD2wR{SWHYns^DY!HjRD3F$R5z(y(yPr&grU z>wsz7ny84R7O4oR3M4GK}} z)Gm6jpFXA0TQ+8h0*+^fh+=tI)U0ok+U!D%P+ieO<(5y0iA@_q>0HN&v<%b|j~z8N zE$XMEelSvWB^&9M3$u#zaeCdkKNLTMz&A5Him%PGUz)yszc3#$8>?HRoeS*^yYWVC zHi033_}w)}Rnvn{R&aUwZ=_*Q@1}PSmAHE@x9%i1#nQkBx;xA_NwXK0q{x4Tn;mYj z`1Io<5nuSIFpFP1rJI*hKP|=x+IqIlwsEawJ{$^)7qo(qq#C1zYXq`>M=?W6RlQqi zcXXe0m6da2c0Nt^n<3uWf-A16KbnHnY2g`{_#hZX*KKc^7H#QB;J29y`LRw>z!|wf z@(u+nfQq5-moISKkB$ENf|t2F;D&*d3$H&o@0j3jm)h=J>yDhZX-x}jct&DjR@0TQ z@izHvDLicQhl1uVUrINdrH6h@)6;&InvJ{2-4&{)TXww^!|A<^8Dd8gi8e|wAjQob zrGG@nW>Lc*l$*dz7tYw~4L`bqkiL)(M-kNyK_1$mb-U2eoKR&%o$YqX{rr^Ytjae> zYrRZOI|xf{UMh_o)mP*c*$Ov`U`EAlWAfKb6GP9ai9O z$Qc$njpS@34yYeQ!EnQ(taKT?t`r@@W6-u3nMHg|Nn%~168+M6N& z*=0UHOsHs2VoXeK4RND^R5LOPtuNvnA7d#Rw>{zf5FL1)nZm3J1#_J3bP~h$!i3rg zz#knY3`a%P!sh7))O*lY;Gb*$(6Q6V&hWgUg+LBb*u&XH^o1EX>dSE504JZ@>dvWC zmpeM-+bbS%<_~HLf3;i6*I9e^WuWl$!~KHHeqru?=VDmSicc_IGNQt|w|vZ^c}7oQ zWn8^yZEGZ+mG4YuRH3i6Rdra+IRXCb&ixtD?ZMGY9S-W_qOay)g*xvZX=HnOL4Yqt zFUMb8EEf$#ig_!!N=sY(Kwd`_9`9~J>B!XRp8d?jd`bxdp;F1SkMLY*Gb_trg>__- zhju!)6NG7~fxIG%H{yAS>gs16zfzL4D{1AhxVX68-Q8Iu+u29@&BzPq^K2d+X@NMi zcK?XI=VaNOUxQpAr(l_XS4O#{I!6jVYyX_Rx~)|mF-@YhR+`axHe>N_Z?c~+wAb^J zx`28wYbD)`Nhio5&iZO=IVYK0Yaro{dvwfjYA7FvfaSdr2~FYGGF=mD@7cI?4{dR# z@GT$R7!%*zWGKyhW_l5hsT#;@F3bKZoKWfug?lbL$jL8Qm7Xq%x4ZVK0%kkr&kExj zE~#dMV7}JEUI_j8Y};)otjh?sMZpTYCHUN0`_LAb^(F=|{K-GkU!DIIpr@}$=FxoN z^LHLy72)eIzLx|&W9NwvOnGrNOnopKqSm@?C39U_UvF!vE%-X( z{;SVYFq?vhu7s!z8-vf79!xC^*&e;iFGr6g|W5wfdxw*^Q%qXUrrdOv;dVb08Pm!*m*xp7;G-GZC|-#hXso z!f0q{K-x!hQv#gB`MqW3GLZ5ac^}SXpHp*Vel`c(K9a(9P(2&Q5|t#9uk!NY3_{6| zg%A@;ERxP8v~g#AX;eo!53y@^UXxJsTzhY!eE8#rK_pFuH2Ytr&qHD+l&J6j{dTUy166OcF&T-_V)I4-5<-Rz2p0U-9|Q%iv%XFIkfk{I0EV@KVqDK-cFc zVnu6HvVMLOh}Dxu;FAs(yryh!|E_1>g36T;PWab@DcH}-X}x^$%0T{W0RP>dQ)j?qN~iwA$7m(If=z@zHYn2}ziRH953C)CV=8y*buM}TUM+b7 z=Mw0`5bE2~$mYz9QH-9Rp8L|luEKQh8(E66{aTx$H6)T53YCq&X&`gs`>ckRx0bY)@m29xiT)aK6LyVb9UnXh&s5UxUuk-!WALnQ!_UaGd6eCrx>4sw zGZSg{vSeaUm9~p{yI)mIzRvy68A?g~E2BEMm%q&QT87zKK6#?(wCVh|D~kE!-quoP zlH-m&S@!yvv+VxX(zjvDIQk)HSDBgXj*rZBhl!h! zDZ)-II}F{aheJr{i?_-qQ&l=BSgzyy9aFA0o!Y%KYL;kZ0|H`Mxh3Q{yQrCqVRKqr zgH>T}|4ypGAtq*;6v5=lMr^xnmgwgDiXR1qDV_87Cznm^r~Tgisn$)$eZxiNWJr@* zMmz%NvDPckLoAgeLYYx|lbQjsmbR=2f1tT(tFM0$c$T@93OQEoT<7wGal!+&Fj%~j zz|}EOTi6lL#m%N&`S@#sv~<$x(+_SMR4KL%6`3%%=~VG~HwQl>yUbr;WK`<08{8a{ z@a}1u%a5LegPDbai}`vLS0uc5UrUD=EHM3T4+$t&&%!aa`_*2rI&0LmHsaB6IIN6t zYu-cHBn?;AOE$%hM{rKFTBjBnbQZ1(5gqk2;edjMz3 zL%5Y7H!7gV?(;g`%M(#7Vi?MO)S9rSr zXbCe~9zqqCZw<$?S2B96)(;kcz4zklM-?`VO=lv{`Yf7tx5|!3ef-H5)^IoGMhcBK z>iq)RIE2U z6*_L@QGSm^@j6AVB7H>9p(0>EeeNZ89g-&Jl}$O zfWaxq%g3E2qF{L7jh-p7=;(e~_hflgdS;&|flJS8d9)d2$<5YJ&21=b*3wy2bT5Fp zZ;F_VoSf%qa49^ENmf<02n};SBsg`d+DkvT7;SYqDp|XuvQk8>{A)WVNv^BbePrDG zxGq*G=(#h&s&k_AsHpX+R)(pyDqcbNur3d&Y^MD{=mI7`>C!i8iC_s`)T6PgdL+UK z_wAl%Co^X!heFvPZ|1lA0g_8+Zx(X+p$5K-+Okntmp?|n;tT1kfYFa9Iexpju{eZk zw4OhWi;G)de}&cpRw2?VYxe10hHtzz701#jja_vgKU*Fm{G&PXgy^^NT3h0${od_0 z_c~BTZny!ORFW|1o_CD){IiX3HEy)pyy3w=YHZRltXDRt3MRSQp1j9l=m?Hj|iVX_an(l{UmL zyZH^6nGcaI)?g5kpu>2(&T>Dy?2pZ786xWGutIG! zDWyj)eT;5XVky` zO({vhPOoe}1Pt;bx8brX|J;L}{Rvi~6!hVqXP#b;c{t-sFoztA zs`D|D)ne1L=&HRv|LY2C3i9oS?+-jj%1zTV`e_A?KYV!htREceAD$23#>U30{$xp4 zukK~#IwfMtV3{f}FN?W_RxN%1Y!>)d-4giaK{)Id#3|&hF2NI$z%~L94vGgz|F)TE ztvsEIM`Ob__e9iZZ}tun%$4&#x??oVpT(XeC6Qbz=F)^{sxE>VayPAU<{2`-wj*xc zAVqKBbivr}W1>#;jy&x25lx4N1b*-B+YsSV1&jZjgo@jss;9zE@yU~8d?Io&uY--% zsg*BZsq!%&^eUF=gf$!&FexJy-YF2v@w$}za&lHujg4UE;F!EJUHp_T*cy#6-wY;S z1h@#7)yW^R?7g#{i0wuS39xwX+shS0&p0@8fxRR}MovHBUl}gjZi|_?Y4je6L>_Gp zxZhiE45;g9L(D(n&&?|+3TbH>#%pv0ypQgLee0o{*F^zs-pR@N!ef57jZ2v*9U+ZvoPSx;zvVbZVZ9!o zk)QX|_=|g#KYVtEk4lZC6~R0h&uj)l@@QtxadtPzlLTi7G5t=))~YfzB8Ozm2s_#H zb=>wIW}<|+Y~Sh<>g4-oDyQUwxZ>e5TZExl z%5`h85`p*%0^>RQF{9dnMX+uHk4BMV?vG5rOagb&mB<7C{wX$r+xw-klm9T1URWb0 zo_}q;mZ;i!MSTUThk`9N2B`35-mMwjo_N`gPI+%!{{<{i4yYh7Hivs*DygCzY}#ec zD@Uv^fqNAMHe1Z%oQJ9QtOj!=xisy^7<7x zZ1Jt=4O=P>unwoRw4bg?;d{c0R|uNLVEoDA>3&*%625U zO`J0fy1&+uf7cy|@p=^n->2Ikg@%X44?nAwK|9*_s{3iRHJw($t1S6LJ3odVz|(x8 z)gG1QH3yf&9y>aJ??SSF=^VQW>AA9nr0G-~yP8dnYk+6Udy)g3_q+AB3g1M2!E`DL zWYFc0Y4d0xh0{@Jlk~`IiyxW0ieRz1`J!hyuCpO$eH5j-J@oAPyW1C#KWB6+vlM2l z^0444Et|-GuR=n>H5PIQ;iP^HP;Ect>pAn=48G-m0DPXbv=M{&K}zpXa-!fpGxWWg zsm5L;(yOpQJURxl2`rrt8-zJ?p^+|pWl(07hvf9gJ6-c3+!%WBSV@wiCwaR&I<}`H zp)fu^zPi^O>46WId5Xwp?C&dWHiYP=X_dmv{nZciaX_^E7&%#Qf{+`VE#}|w1*DaKk>JnmO*$owK(U^jV3@s~E#wsGx&*>+>kIJ&*UfV0XtJP^ zg7nWItVIQ5?S4qxWI}jLCylGQV-s=4O`%{};2b-h@;BIIQ(yEmbJ}p=^XjE8yWv|p zn_rs!6}2w@j9Qp{qr-!BZe`2$nU1ocAiq4!hv(1V8hO_quY9ArOv?a<&%6Rv*F%lh z`tjS1KhSdCp6QqX=ZNauIfhG@YCwPpxmXw-6Tl8SJbYh1y+VQzp{d2VyE(Amg0X3M z9wc#m&@t6G5k)mvcRUh6@sbZJl$%37ymTe_BKTPFWxbi*hkFa2>3p|t?QG0Bf}w!) z>>{Uj-Vc4G)L1Pnn3p+@tcfNMQQz6e6>WX?({&~mDv*V@)G_*@Zs9c$Mq6$gU(S@X z#U8Wwd)6N}7X%DzT%5ppuXL2i{Hz#^MhMt_28my*NdP^AsCKRE`UB_wFJFMH%B?1k zPF`(|db6;wA}hOHF|>G@-)3<_BAl-k!By-#N9NM1OqQo5Gubc`&F8j$}#eBWF? zLgtzi#>B=Zdgql>{*b`L;%5&t80ckyX;!8({L3u-q4<_21kcH?b31tw z!=v=Q-Sut>1%(d%Fu5e{xycb6YwK{sIxl8!yQelbqu*X~du%OQ7>?Tvj4RHTlFesj z3sspm%g11BT0#*Z`?eRjD=)9>dFYwm*GaNH*Q;{Y7Ni*dq%<(jCljHvYm5Xs0!2R;Ruot zM7G|w{;O#Ul8P*XAycGq!mb8l;>-6^`~7T_XH_tYZ#o0T_Q5O+PN^no^OV4bhN!?o zZ!c^Y_ta!P?9EoUY@Modk`{P$pl0M<_wF6vwQHR)6v$^MH|9{^x{bgLXAqE!(b0s% zHczX^ih;EO2mfe1kAqWxdqqhlfMP%}1q~dk?GnZ9+w}r=7;sd#ry5zC%(;vV?Z38g zWukUJ_)1Mpo#jvR>`rZOXxO}l{S;s#sp6i+@BzaB<|nO@CU0{w+d+x~f>UDdHz??H z-n*ifr`vje{0NF*lqefo+}z|+F$CWv^0YLt`Le*HFxogP)R4M*Zv>qXW^iXQ^QBiR zzpcN+?osr^>dGB*rL(!%B_&2aYQZrVFur8z2Qf=?8hQDMCYZOCkXM43X>d@6sjsW}?B*LPsx z1La^!ZP5qA!;Jo93iP*(CqW$^9HI~eb^r0D|FyJ&soB?ZJ8mJ59g!roI2@CltL3ez z%n*+h{?hP50VEKoPg_?EEP@OT1YwHH@z$uJ05SzJ_pLABIGCAz4QG_7blbd03kPT3 zvgd6wEJ!oti<8zry$WYa3UrbYJ6UmD!Vq z`M$>xQKVABpU!rkiWaignB}e;EgxD0*~2@hg`2LY)ry7YS^4b7^Bg^KAYz^x78d=f zVsW(aa;skI9&eMWJi@Wr;)ieF$q!e;pb$ZmbSmD{Af`DN4uJ|1m~nmI8h4F97W2;D~d{>?9gU6P4l zP&e|H;N#Qhk#%)NDJVFD$$wtt&8A1%;GDzTikLNO9ehj<3viCg06#aB*xE4OZ zpjKC8Uz>^D4zwNwZ3vkeK4im%v)E`#=P?nMiF&&SP0c+zZ~s)*-{k$z+99 zH0nl+!C@Omx`GxGf6`%3I)`Of@=I~C?kVEKMU?CIvRG?JlJq$I=}ddS*Wv5NMrPoU z<6}!}l#IYC=4isfi9tk0Ub=YE8-yMNM}&m1KIj-DsYby-Uf70CQ6A2jfR}r^%T2uhOvUQ8H(CF+ z^`7V}b{oW6oiC`!ecTCK@t71YTo0Ve775mf!R9f*J=1DKLYmJ}QhoxOQN@JUetyOH zp2YjZn8;i2P|BZrUro3zo}&{1|{pd4IW z@NF&}Kzw|A=^Y9+^Fattrhir20NzpFC@Mw>DPc))Dy|f`_0MN_utIh$wlE=INl{Pjj>h%cmK7 zgxRBeRd~$G%v_C9{=D#tZ23&^6Owyn#NW?R#*hGATp|6^^DF)I#Ok^i&qOGmIDKPu z>3-i6r7(nIgiSbt{Jw00k1Wuj*|hXrsUOIz@}Y4N{;9j=lQyYw1JLvnZOM526%_Jt zL0wu$Cq`t!L-_IcuBz!STCE)EG!&E6OyIQ$b}oN@5T`l&v8je1)DLPVBdO)U)BPMu zRh}bXRuud;hvtm$GeY7_Df?N12V?mslduj&K1nEsfu!uSKC-A$nND{Qy4NZRj!;S~ zUGj_iKhmOCrP*cB4dQW>VHl#Dy(yPUF7_p~7WRK#pXyNPLet#mAgRlvLpOB@`b-~j zU`H5dO8IxC9;g|=h8tSx2mM;?Q?;NDQd@dl++81#_v0B!!jyfmT8taeeC!peO%PC$ z;PfCnA@zeMtdpZxu0FVMB9DOC&xVSY2$>S7C(t!BcMZa2DjV8S zMQYDpTamZ&ZFE+gvRu!rDPaGphJbVjUyvo_EfT?ku+JgvOa5S8b;^>A(knm`9g$yU zY5$;i5*bef9T6l0m|Z9hE>AQ$CUikQXHGx$g{I@wRSH}kQd@iK4>~_RX*E6^hV#)p zN(0h+jY=7)H&oh66_a_m4J(vcyTzK@q+Qmu`n@M{?)Q@NJj+%H|8mxH5&A~|DbQ`$ zZ-3?^GN*N$9eIXwePB2c`%}db%0uAN#Yn566=M_yHSw*LjiF=DP=v&FQfadvAB;f+ zbFJ)^I(}9Spl%5Dxg}uot&BEJehg@m@gFKV^(r62VoUW zl4&i8Cdtdtv&Y~}ITQCC4Cc5KT0+SRtbSQ-q7XAM*h}?&*JXbMLbgC-X-z1-oArZ7rN&Y0|I%u2o8sTIzE0Df{@7nNKc%K+=5R(Ye;&$=CK=9hwGg zxR*;1?z1XFVC`koFXo3r5)PD#W(~Di6~Q`_qh$GILyhO7-?%i`*^1}%CrlkBKyjB(K!Jt z4ZrjFFDxt+0aP^?u9eNbTTUNKk{9A?&8{{j=f4cUgFm!#^F$Wi{dpASpb#bADGjnL zA>aNdXS!&a4#<6xjCxMplX)5SP_EzVgC$TO&N3%fO|vmPZZU+kTWF=eh&y*)$x$-n zmF0V`>)%#`vi-`r`6QB)q3l=oFY*C}vc9bGzu0fEIH1np*6Iv-yGNfWBo;%DSAy*)u?cM(ty#_XpKf>j zzJ|tH8{=r6-bn%zuLadWu4t5{h{?GFrOCYd)BDpXOu4 z%bKT4RqzoS2rT@vKs^j~@qC{6lPsjhJq3lA0^Meo--atmg>1L`&Yr(3z9*27_JImX zSQms~kDhlnhDf^f;hHmO80^2DCWX%i_dx^BmB0huC*#92$W@{U|8VfQj8~Y-puKF6 zFI_C--dw4D4OvQgfb>~h4BFh>-rwBUw$j!po$JenOxurDfyB-$yRgnkU!V5eInX0n zdiwFbrzQoXIA~~ME*j;58X5F@MSj=fAblRKJhOngP?k+6Tj#|C-UwQ}9(V4jNj3UO z1?0RGa~Fbj4uWF)%$Wghunfb(Dd;O#OxC|~3qD=EM&ow47ypV;%v#i?NElQNLSom5 zean;1z*)Ww$YpyGQR8aZkxF9TG>At;ucs}YDIUmctiD51*?8ocgO`VhxZ5H~_E)c2 zl`3)=$*$MQN1~O|$MPUFZ^)nQvh&jL!Y~Gg;?{{a(%Ww=GRej#Bo%d-)_(jr8x4C2 zg?IJmN&xXoNlvcXeo9TPM=}XrFb?0^m<8JwJaag*M^*}laSvODI!jDGs7uixUl6K z3(~sI(R1>xF#pvQ;Ud`l>Upcb2ETe1&tM2yHWc|ZMRN@0t3zG#VupI9jvM2k<#-JO{P5h;IC^#QFs#2CYuC;UW20pE2|Kn=f< zADTY|X4jQ0BugVK<{8^VNpdG`$-e;^v@>%*XTnz+r~fj3jCcGuJq{nLA?RHi*(zCMXoYx{}+vDI~ zJ5!lJq{vX|W=;==qJ|bD7@*{|8$kt7_k*46o}^-EwfnZAu5OhY4T%=`z^mR?vA~j} zjQh=SOMqqbUH^7_2r@TA2iJF*br5%qvIVBJnz0Z7z8wv9Ac(x#Fk%LjnPd9 z^K4*Nrjb?Qc&!DBF4L+G{!oacI@`}!_5qpQsQ&g3wIumLmiUPUoSK&Q(Se-dK0+p0 zsmAEA?IOzW*|6G+EIg_V`T`v3<8 zN{iQ_>DE%N+v?2_Usub&K>u+3^Gxb*==CowjVzx zal_bPB^-|dhqb!erSpWinhS>IeKcj2}LquSpnlg}8mcl4Bbs(}M zhN!0k36l*V@0hri4q`!c+yEMP2>yftiuIx}fBx&{5UCwyPyjLpg+8YJ3pPq)nPkM| zS$3yZ*bO8kcq_dgvFL~&=%dTd7Ako%$2;I6khW>LwJ0<-71i>xsHnB5C=e)Qk&*TR z%zT1^O^;Z+jmull$ElI9a9@OTKQOGmpcWJ7t43-7|FVffJaz8~%I?lrS{T#`Twtp_+2Wvq47;aqu!{_y?crB$?STO z_wE#HEuG81p`;!&^@{hwJ;1$Rv|L)EX#6}g*A4;QC8WfoRE94rw^V{$?=wc$`pimG z$#*p&Jt?i%O&_`me!{%MN0#otNeuLVkb1Y z=S0*Hi)n6PRzDHZq^zjt!k{6cp$A9%F;-U0fzTweeH0Xax{ZsQQ(pj%u|Y3U5EHke zQ_79&?=(kA%WQ=O_jp}p-j|Un&ngWJ%mSN)p|>n^8})^r0|U0ud{QnfYO_3ehEWl?thD{>NVD2K0IK5{XB2u>qQc5 z;&A;xPg583bu{}c9zXuUEECG4^6;i!IrhR1uwCj4wl~$oNDBxXI37J`dW}j=9O3Np)Xo}C2)e9R>x;+%G zz;HY6TOHPx{<(@&!yaruMaL>q@F9IF<3`FsnPvn^*D>NPlN5S1-BM zaEitUl4#0|+gg)0I03e2RZ%l@1p-*9(DnUE1sHmww=Ru@fbN4scdBPu*+7P3o71)- zsk+r*baQdl`VC)*zBSizD#dI2ake}t3+CP?G z(U2iH^^TnPIrWz%hIFbnb4 z-t*Qrz3tkd8B%Txt#xgo!Q?ec1hrfM>Lm{&OS(@dfmuL`szXM8Ig0t5+YeVIm;mB&hmB)CkNF2A7q|? zb3m&?0S?g4^G>k7#>c!2`fp*p- z7c;z4YQD%1UmxYTmX7R^Qy|xJx5%0omcHeLzAZKbT$lr{la|uoG`2&Di;YM`rIMNw z3_E{A2qw>c+c{3lFp}#)d}reER~AQMj*#ZHE|HZ>w_>efwDy#$1bui+y~klJv)8Iy z*Z|eG%=|}v1T;kk@!7A>-E}ftu4+S0Noy&vIZBmfu52!0QZ51h;2%ZRfN00r{$Nm} zH?U^(yp+4R>=@xetfED2%AP4@Q6-v!=) zlbTyk@@LKcQTBvm-Fv}{(#3bx!*&`jP*SFeNCBm=ir~2g-tYE8@a;=#W4^c2or+gm zV}I&|p@@E<;@I=b^FCQP3sS}Q{s;f4di;xM(BV?31BkBbTCMl--6KfA)_`iCN=^}r z5MFv)^~MKo5U7yf9!IO}bMM9;DOTB2#6}*5kYa<(a9BPT-5S-o zVbpOEi%0Gi+)76x3KF<^iL#nMouI#Jqz#etjjLte;c{C!GTK}VEY)!7p$w^htc zOpKAIBr_;Huq74Cui0>eX6qsFC%2-S&dZe%2j0#RIW34qUr72yv#Pd8x(XBpXIlR~ zMG@*yA7^QjP9WV&7isk!VW-eWgXtu-{#C4DQ}oaSu+ z-vblvo2+jesYrPKLOQxVgqo|?<;NPJLk0>A7$GbQy^Vmk=!nlR(#5ZMba(>_9kV9m zWM>z9k|kq6=8h&^c1U0cec|s-)u5+7`Kw0-Ijp;SMnq-LcMvOJ{t>h`LIQUgfLq0C zzy#)npI!SRu_j7092q3eV^b@q`?{#WKylDr0wM{Ep%vgwK;v_6M1V!O>ev@Q zfI-5`ZD-XPH1Yw@XZaF+y!*|FLCkuz*4^mg!{@z2isDiM8T#+__s5(+-lG6ntx=7O z>)JGXT%0EOoL%s4d3kxeu__cmbO7iS$pTQMyu3VNr};cUF}iIeg0PI;bH~{`=H^CP z{pnqg1snPTuF+o3 ziM2lwWh-<~uPl&WK)T!iw9T4K6d0iGQW;>ax>BlLcGom>p{vVd?iLmo0N(?8ltQi! z1#X2ypk~x6yxF&*sxwsb!WMu8pg?RwW^W_U!l`M7wm-jViDB*Td|6lYYHA8#QG6*6 z$(`~M{j^zu5PXZRm5+Bo%D@txh;1VB+;ft}wZvYk@I?}74uF1r97!hKNk`yqISlAJ zB2QxhWrY6Lodg=`#r9LCDz)9qWBWifhWU~ zHhR1~dI~hPFJ7$k@;u9~$qS8poCWS^g!a_`z5lhlI_9A+Kdu4ZxZ}7Zw21luO{| z`^>bWlW@|T*L$BuU&;A1oe*?tM1az`8iYNKlztk{=k2l8233};s?!oxvH`-rJqqj0 z(J%9K`X*$;B@TJFyNuc`+qu1uY+Vt#dZ2GuKmQzF1|)>zA0NGyU#2F+^4T{BYpSFk zfTpI$fHk2|Ff=4QywYg_dz0d0L^lI~7ytzLQrwfre$rTJq_lLybzK~=N$l)aK%0}x zj?T^wl`_ElB>{3d>r`Z*VIQfGv1bbY0otPl;fqD6SCU`o`HIF#26{0a3U|Nbc;Scq z(9lc6swdZZ9!K^L<(0!8KgI{>SGqz1sAAXGW>$b~bzcwFkpPEVhetE)ZG~BR-hpVj z682h?J+VY*C?aN`@XOxacvS&2PeAP5S8@=aKW;$MC|=`{28}_}$oX)*F6`YAJSas@ z0U(tBN`zv5ijElvYniz`V0C0LHh?bK+uQftm*GGIccOQ{ID}3)iT^8bPe3YS5VU{z z!N>QSL+a9ad8Yu(fF&fDkJxaEWygGI665`jwM zEgs-3fhJn0U->^kK-Tc5^L+@{b?U5q8X+Q6G*+In(au4`v^Ca;0lf};W0IaYVfCQ&EJj=eZ!S66E{%+@d{|oc=fx0@y`H6_lxY*dZ*c#W>^{u7qxw$vzt>RL} zb4p6AyHn-M0HV8V{b-rb8G{9Z-&S62eUh(ZHP^MaW_J$_+@FP|iUy(dohvx-7Avy; zC6EnjZm%_)O;1KOxExIkYYou(cNom9c4 zT@)z#%Blw$7r%V4w=mYe%k=8s#SM^7tTD(z5!jORxe0nyh<5;VVf})xWngcOkgAQ{ z|Dc0KGSdElQ0zZpt-1=Bq4#B=oYr~l&Vz#3vNI8&Kc%kgm<*P0vFz%4MkbgwLlpSs z6-j7A?RVid10ZYg0Bil!y>)de8({4{+Ni<79iTruuZ$ZC1^e&B|RfU!gJ4byrx^~P6Pj=QGi8C8`xfRWyzz-glbe^k&v;Di!mgv z@4FE-pGjAs3#-b%W@Tf7)?Z4jru&a(4EZc)3-~W+y zXCy7dCR|qRO$ie4HgY)hl$0N=#^%<>Kpy(^OFn@)&#ILm6bNhtA;IbRGWG$}QY&a%?#odM*%((&mgwr8|o?nxD8H%>E<5(FkolbJ#fG;PPvP z1_Xs-ih1m-OX>~gfZ%nZd>U-`9HIv1EEO!A>4~vG7na6c$qe*%bngG*k?)p zzIz<&QT2Ueh- zdNVJ!v2BPhvU$|`q%v7K`(IBjGs_mgCH!EPVy1U{ zd31mIwrlixh}QIvy)QJUE1eLRFKQ9wn+lbGY4eSY}(JZ-C&b1k-v?g;o# zAUBo!Bj-M*FFkxBmQJzgIpKLM<>a;4c{&Wb@VR%(|Pvek-y6{Ugk??2# z>K=**LLGS4o|vT5DR<5KaL&H}|7t^G(o5Fp@e2R9)DpD1Pnd0G%_bI|+J|!Tb+#Ff zq4q;RVwbkn6;clXB7WR2vY4{G(t;j}DSyLLw)1!~uW(}SsGuiO{bYoH{A7!j#pfjq zSg;Bzb6P4Kb2ITg`IFdFbA~TciF`_=|3peU^`DstM)cJXhl6Sag?m86!Ki65K}&=@ zm+R}~{9&Zdn*gwh5yz)Pnfk|FGu>BNW7Nu_H3J>vUmM38EBc7Md)D3?7f763;`(Q| z6dMwid4^-g-hrRUoM$`b-=+Xq2=xC>o-MIk57ffM+z4B`_E;?R8e8p-?iISEV@Kz7 z+`TQ4`rytyskY0GXYQMoiT}geTR>Hnwr}H<(xM_Fp@=952qW~4i~$C?Vbk4O;L@E9lDzj^(4>a$sQJ2f)O`Im z1Ny%Y`v#PHN^uPlV5r4zKURP)Bg_>Ldfc6RYD#vWnTi#t*@ad59f3u+?rBu*hTa|Q z6nHYVT|=cKtFt+|tJ)wmJbJ!hW#xI-Xh2Sl=t4{R1rhv@I!Lurq!r)gZx{6+;?Mok zE6nZd9XReta4cND#sA4L9c?)i@T>tH-)QXikFpmKjKME_yDL|x5pI0{cB|m-@KxTh z{Url^v~ZPioPfwpJ5zbqZ8s0dM}+@c`RK^Z!S!-G>v+>Q+@08cogsiSN-C`W}ieiDz-Os5O+wy;hvOtc@ z!)i7bNR=Hgyln*{NX{x6k=jgko+Nvxg{xTBl;g&!is4RX=VIUTA2kvds!9&)@RXnc z0eO+=q5C+%Zfif07Op=A`GN7(Ck~=zG8*oe%Ia0+*F`LFPaU1dJ=Kv^7g!OS!uVZXOLMs2$oo`Hxy0_5a7338sv< zCF+93n$Pmc-d@|eF7f^+a;6Vx3`+wg@@nVE>0bW?MGG+{^Vct5tiKhkLca&Q{98c} z?1&J0!JC|%2V1KVAXvNgQsoCFiX+~-E2U}F%WJ^e89peRrdRGjEgPxYwHd7zGJ7az zF!2u5m3iv#yFlZl{=N`gG79urGc)H(O2kfDybcSy6W<{td){uQEguw!5wDJWtfAw1 zOgO_DIELdE<3%_mWTLrykwq+*FQ3Bps=aRL=Lk~Lpbri+efiY`r|9U!Y({1Piwp<| z_;Grrx0PR1*%+;3^P{MLWa!b<9yY1>|LdHnE?T|lkgF@)(Nb$?glnYi7q3{J@=^VH z^=K{GF$;%N>67^X^k}Li{!T&06n@XOK0ADLZ`?WITV)*Nzh4-z(wd(}Yk@`_HUO=@ z_MfbOWKGX??C`k#id|W`izSh&dhYSy15DeAn`lb#;>@I-gFG?4f7mPhsj5lk!vppOKG$>3s0PR;_nkYdr4 zxo;KDhcE=V>kk6Ts3<~9J~x;!3=Pet)WP3CBB-ib?fAp#A??|-t3Ywh$fyQ(Vsk&6 z$?enNa=-;Tx-MD^zQ?n+ujF(3!5$`Gw2k&ERFJ7T7ya-N8UWTYtFesO>txP=h#gM({MZ2*MMj}V-k zB>c9>fqAJ6e?|u!49Z3?fHX5N-v;QuEc+DaZ&oIb-%?Px-ftl#rMAQP;`{eRfBzr6 zCfTtg@C5*WHbTMxeHTFJ&mD<%_jW+f2?LbxGx-Ac-`{q1h*379$<0cTI}K}Q1ir>_sBVfrx@R2mho>73o^}9` zrJ2tfTcRUJ3=IrC54Nf8pUn5rTp2}xSx;Dukk#j>{(($EFBj;jQupsj{pxMxo>JJK z-~ZJtbBg_@weir0)r}2`+Bznxx`z)RV)5j6@AL}$WSVLm(mi`JUIIi8-}W0LK=l%< z5Du-;Je!T-lTN!oxOl&PEHZ$lTgvG#vFL-05uOJF2u#OHK`)BjeLdsG)vF%>U7P%h zZl1jy9)3gBp%f&otQ^BMXU^oDbs#3jXAtwekK*MO?osD~D|Q#@p08F!Hd9M~7_^hZ z67e_WW2FTj?w?pVMH3K(8_g)=n`a7`3yrr5b*H%M<|MV5dJ*SZ1uiGS9~N5TvS7wW z8B|z?Wbpjv0E1kJ4j~uf^xvzOJ1={#PKZ@+Bm3SPj&f1oTV7iM;FhVBPIycZ z+y~r%4{2`hst{%f*cgaj$w}-NhBOqxe9G3=6b1}1ASu!0Aq3)3nGkrgRX?8l$rnX= z)5U%XNS{V!&rYUFmR6Q5A{=1+Wk30q3s7I;6DM->4wis3f9qBVF8*_bLrQ8e=z6W; z=iXgxn5chXVUZtB2|v{gKqss|jMdO_yDs2#0{>2MjCHVIv-%`PZV(q&ti zteSL+R#qB8#%eWM&2)2T@?He9*prnH@(G?Kxr&?joadpe2P0^Hy(Wa4 z!-4c0+IT&OtdUHg_OT=u8o$bhE46nSE z<7g9Zg1IItnwT{|2*51_I~ZQ~l^g$O1{8gS%n;pANVotFiy&|I8r{oH#C6?4j^9O?E*jz&PzY| zpBzjAtP6%HG(t}Ff~g-q_<`aVED_)r!Cq%=n&a}el^ePkV>wdk4|+$Zr5qv>`;!)D z&wM{8$UO<7M=`IF$IBzW;02d;EP^Y&7n4J7f7f=!!UDr46{U5!bK+GCjUYEW6B7`5 z?|~8!=7}_7p3UI7#VpfUe`FulO8NH5_>Yh9Zc`nl`#QaOhrZ_7TR08GI2i5k^{Wx*+1;G((nxZoO*~3Np)iWoucf4BzQ|!ce zW23;?nNo?+O4n34tTh!{fe^Z!=$n;Nw10f6?^?j@uKPdUnnT}48Rw7nN=oQy!K9$`$fIdb`#)bZL>m`hY;&$_k+HBq^If(wsPyaO4YCm~;xp9?}98KPV!LE9Fs#x6=! z0(4GrATiE1>JnGIx%!6SzpbrbavTyJxkhBVKL?&*b*IdyB}R~`p4YpPq@caeWvFi{ zwq#ej@WaAwcG)pAOVn&?-)nG?)A-KRN5%i(-@WgX+4h~*z70ZzDv3LzBuB)C>UNhVQ9iV>j5F`(YkrxSk}Pzu^vw`!l}jtEMz?M|?}phO z-!yjmaweR{rN#nuIu?risnhYNQTiJLG}-)?q~dQ7D3>*PT?BzSmH~`sf-hhhL1-bP^EOsE zmF(E({hYO1$BYm~h)>Nl`Y_sN$I{AN7_x*o)LXhzyOF+gO`|=gpuDTk0x9!pu!DMu?vaj`=0J+g*yhlMKcD{ur{QZyM)*rIUqZtq2pfr6^%H1D< zFf&~%c>%BR+yF1oTxCX>{y-yLS`I3jxNXC9^auaKDZTx^jRog({Zm`(dD3eG9{|8wjCo}~W;u8xM- zTTuffaXj~3lc5hy!g3u3@55U7^?+^4J9hCMQ3gzY_UL3=X`G_5Bcq}Fe{(X0eKCMb z|8uv_cc3mQ zFyfw=R&(-&-WJ-EC&x}CgJ%6a!HsQkV1|R;4|eQ^wMm1|%mN5U|DYx69GYz=0dsZ@ z50x&9)30PO(z}T&+M&bgF4r}`BM%hzuA0p?FnM3k9Wq# zuKk06UWal)!?*o!vghc&2l!^sYwE7zqCm5cyxQ5fiYgk2%i8BGgcl<(}MqZ!% zuaT_s7J-6RhqS*LOYnT?JT7l~oM7*8p~^*>O1dV)qs?oSf!`)2x${d#f4Q5@G)?rG z7e!Z}dK=scUJJ{38KP)-hKJ^KFjg|9q(zAJ_&3wZ^i?W*9e%9_>QpSEt`Cv8_ta;a>DyHbH&>e>? z5m%a&+as^&X)?d#BShHpJu8ZD@->tGCPe#`(`vxch!8RC0wy8mZFi&4H>9s`G^;Ax z1(YCfKGSnLt{V4lU74`ab(S?hI~uIhC@-?x)Oy_SiVHr~Mw%0Sd!G>VvLi@lFx4dm zu}I`5E%B+p_y;(fek5N z7B`{*bx)<|tjw7^;$#CotzaJZlRb&1@F(+7`sLyNbK{lkT0Ay3HTl(STZ?6M92{0t zQ|Vw=9{D8W?c4AZ($e>v9|zT=B8qnQwu9jMx*zR15RL&EuKMG7uU=7}4MOlcqrqZ{ zSZoDJp_XFfo0bj*&%_Pluv4Yt5hk@V6r z1Qw-WW~l3#S?-+QG&m@4gl3kPd-Rc;l2G}rddM$2YZs??XQNv zV6H*qH9iZN!?T5jO0XGz{z>ka%%kbXKw1Dt8cal13_)8Vx}WIjHHWA6JYuolnc)X7P{ z{#&xn@zeJ(GAXTLLKU4`K0R**>H{xX1Y`kAZu@%^cYGNk0fEQnaQxS=gg{*$EHtKT zAB2_hR!xO{SzUdQt!fU-onbmerd@6hT+#lBEFbSXkmc0r>LVN2&S3g2+H!( zcCkY^reXy6L`6jobhM}^Bh}_As*?3{prS1+5y{OFrl#f(oLThoVdUTleHEd!N}QI8 zHnsAwEZYUv;)j&)TfuZC>2fMxzPxnbDu|j{ymFEe?t`bPDs1SAGBwTRJ&iDWr*>hf7;pI!>WrBf_CHBt+&ax`B|m9Z`2R zg%}-{nm8o(Y{~MaZS~Du4Fv^Lx81c+v5}WwxI+)6*rN28!Pv{x5?5Enp@aAaR~^Y4Ob10{rFL1Z!BlGdP5EC_8FR;l_&G|Ix8dN z`>c8HQY7q#mZqklz(9DCYaILGGmG8n>3uyzk@4r-2Px)qPk>Ok zbaG17K}>VuTj^p^M#eXbK64V%paO*3R)HgYuSxS78XqAfLFoDZUD*ijXMrw2uyctG zm%J9+gz!Yosr=&Ub3WtT=z4?tiI?wM^>S$vNuxgoW#0NEQ;<~ZT?7Zz#dr@0l-4$W z(zsjK!7G$8*Vg?B$e=)`iOjjRVzjTEi{P@kc%%EvId#^_dfzvwS8~~ zt!2AvfDpZ`Kk><@?n&>teiUfM#5{*CoI2&7B_D^Pr>5p2o3aBPLqJGM(%1r7P7)=* z1LegS2`wIz0%S8+7_zZB#x~*AV-rKawJtOCt5*-{LqeJ&(l03my!Hj@^7sCt(N3Pm zH2H)%+sAjLzWVu->sB~P+-rI?@RJQ(<1GTd zL}#lYuZrd%nAR_KJKaDKy_HfKIBENu`^Hs51v&!NGiL=rPgB-(!n}NqH!YV2C3KVi zyjs4FF4!;rlr}Ttxqm-Iw^ChO(Jn1*T2)Riz6Uj4hD#LOo4}8p@P_2q9Hmi+S%5w3 z=f|3n3*2)(ivUArX68h~yen5^vvYGJN;HASEae>fvr_vBSyu@Xz9buS*Q<12BzS=2 z!T<6;QxQ+W{r2HvdT+}U=IGeZDApQr6yrZr@`H2)>4_6w@K}%{;A;eoFjxJ3^Z4vt z`GhIk$3(gPjp3_~j+FAzwp{EMadc)!$MZZP-kHf>qq9N1us&;~ zj|FamV|dyqDp3VltA$XM8L!bp6IC@9Ys--1r71@75yYm-kTv7>9QUE}Kh}2X;#aFe zU(}Ltu$e``_sF{!fE7l*SKeA!s6>(rYI+$6ADoHZE;D1Vu7E&Iu1T{9vI4kXpF!+= zCR`)Nv|4X^zy^o8&KA++!~{E=+~A^UbFPM|=@W=z85ySZU%Dx=QBW#1yq`urb;err zgg75z39=33jJg-mVNv|!qF3hN^O{NR26h@|V!{wIwb%Ak-^Y&@z&}*g-e+%j!v-!^ z!5fxu0f_Xa=29g*=6|V<>hx(H-OZ)i)?dvskm9L#c7fHQWrF@nw?PtcV02M4yYq z&mhNRCn1fM6n{B*RBfRew0Jaa@IP_R{hZ2%J9{!B>UEHW!LT%9&-_W0UPxxyoOING z64#d|n?Nt3`4k(-Z67?)dh*0?{RH~yQyZuSn6IRMTdYn^Wg)`6oLPj!T+on|U_a8G zJsbau8?5T)laiJ@9neO7sPlpkD;-Qu-K5@oRMgc)iOoI@pne5*Wrr3tr?L}a`H{!0PDS12kF+xx2-WuZaJijE5%4Cj#x}K>Vs6^Tn1QWUI%0V z1STDs4;aho)|X)5LNa>%y1kLGIrw6iL+of7;EZL3n8qzpPc%W6Lz74yU5breyjfiV z-bIlwZV7r1Tr5Z`_@qJb<%6t~LU&xc%PXKRyX4G@;QU@jDeprO5Lkvgc9DjrXnABY zRytnDdAv2+p%LZp?+-$X1Bew85_PMT&3?|(I_1j2)=kCzI>M>dm6i4|Tz_bB_Vnpe z2b0b?A##cf#oyt8G%cQrVdufpMab+BcHn*a`%5}iP<%#RVP@{dV6>~AaMuI@uPRhZQi;HVA zAb#XLB&!m_d?vV=YGfNO4e{!+{;i9Y_t$chnO2!E`w{R;oISo8$%`$Hb7;zt4~3@L z2>;f7_#l3`KVyyxy&Y3zAc+CZ6;v6pS>1juaIx>wMPd4hlfroL@GvqnZ(G_vWl=`P z&*NxNh)g*m9Dt{e_oo8W2jP&~bZ7hbu!EA;><%e#<|T-gtqAcRpzrzAPv1u0@E#j< z$a84U8-HDM^5<)4=hExT0~z^`4%v5Q~un( zG-6&(3WN*W56W8E;466E{9B8-0VdzL`5Aa5nP_*x_Owa|ng1mb9j zNnAO_i+vOVF1F-C;Z>LP97x+A8ztY zONowDCh%6ytWnxBQ+=7cC)0rH$bZz4@0 zZ{+Sw2e!k0V~OstFUoVH9Nteb>qgSJJ|_r(i{TMcI^mjAUaVVhrEkojn(dnIINmmG zi!@(D~I0~_PaF{ zhk06ys2hgX^5-d(M2gZcCOhGl2=4h53C3>7T#yl}9qByz*sME`>Gv|x2azoGiT)m_ z;EENgrb(vXA!qX62nuVLBw;}UwY#a?D8>g8AH7asLx;OtFyeuHg0z6Fg!7GF9`Y;w zR<`299GBRRdGk=cy#Ex({7U5d8{D=X8n&08j;gByWKV23Ta00d-h5PU#srxK`pk)U zd4cbF3d%3(-4+$+!!5jUj0_{Qeas+>ryEx4;wG&H#&^3AQKoSU$U>}5v`$opOcYH)S zSFhQE-qD&;fv!RI9E|{}**O&QFF_UUe+5;79rPw?O_LE00@Y9!E(R5AQ!%@GQ zNnZHuRU+hEaU2UN?_^tQB@rb?O5Z@-KlQ!1C3cqn;XXxS0f}ZuInW33Tf}$;Udf3} znO6m1OV55m4=Iy=9Q8i1sS<)h${WrmWW*iWA6YP&?sT=*G8atdIWOwQR*3X@v7AT` zO_}IBa&E?VLd!|mjL)jhgGcXQ@pe9%B>J2(*`Eqw;*4NJ_Lp$p1}~Xx5jFs$gL9(0 z1D;TxCaHR9N#O5@pmyM!H!Mn&pLt;#a-2&0ltMiX1~o_T1f`qf(=H`#4x>@K_gV+e z=N}4c9cD0mH|*`cDdgB|FJ)xORBIADA~+XQnW&F@6`OO~O?_pEX4@*Ty^{$E<|U5w zIA@w`+HL0JRQP`?Kk>{bzmYKEn=q0~bT7OE^l9z7#WXMTFcGW%jaVmRebXr+Iy^YD zVFIB7)$^b4<@>kPIrV6({bWz|JMZE#{h8UXd6**wG!vTKZ2ZyoER&I@1ir=KTKpY2lGBWP*hF{)$Rv`C=lO@AL=K(^K6T zpWVbgTfSa1C3ny;a0k>tLrpz5*oYhP%)j{j_Wnad6JAkpTilgne0C{ZR1fW%8wDnF zM!YHN0dYQ2mv~DOdBsDx8c#Id6+g_f3hDnzE5M`*#rr1BpNscnfAM~^__o8lS(Yus zRcTBq7B?{$^*wvKhA&xQysnEia_t23?@SorZ@+VPzqG=9x%iY``U3{}AU4_H+mU#L zHU6*THAa^h1h#T-j7a3zY|5{=Q7^{P>d|nI)z<|{jGjM-SU7KGDOvLE2u_m1w6=4- z8w}0QuYtedxys7&+3lpxupj5(cbl6dut2-VK5Ty{<(5kuVXEMsmL&*Tq*FZ82~wB} z2TkA^?jf<&yvkVxV22gtStJj4q7lTTN1~WP)Sp27FF+$UMQKKxpyp>*dJ{uTDAA< z`XT?$ub_jKPv7G>h(|?VYL?CfSFboR%g8xCjpO7fMv?{$=C{#ph^fkdEU{hRH#Q7P zmrQ%6et5;=bnT{CpG@@Zu5}Inh(P$+{ZaeV2MD*W_i*0zZgnE)Wfa?HM zn%uy^Zql>Y?(~_WQI24%C~PpFZSHpe^a z9$^c!{E&#OvTro%D#?jzxA2YDQ#d}TDD+Bpe4?p`d3kKnpTPjUzueGCLcGri>Ngp9 zuj!dHH`rm`rufw&>19pP*TyH)m-hFqEN1GAa&O$TsqE}?TVJ@R%TIRBU|G!c+n4+$ z*U)%h_S?5PaGlDFJ5Y@G4__fNP45f5(x3axmD}(2Sfl7z-C|8XYIdy+=f~jwpqiYz zz);@n+zjEPM0r&UJOXlDT(Sj2=&tLDOVsUyVZPrpX?n2(rgBXd`PTq{yvU1v^G40q z_O4>*CY%`ZRQ|4>-d%-`AbCAKq5*IXp+DI%*XGCGrlZ0Z*G#s{t&g{hP!{E|DzEDt zw|y+^b+8Hc1HhM5JUx>d5Oc#2-1VX}#F0oRjeb@|eR}eGXyOAXLW>7=t7RzPh}n*< zz@b!@e9I`5R#Q`^fUZjIsMt!3jgwA=>e~0FA^@6H^IBi2%HKyhZCV@Nxf6+=uCh0F z(j0iKJpF4?2r!+n*PCJV?sguFPU~~6r?elrbLye*)L5JILtO8Dm8hM zyCHEg(Nx#60zq{P<`l;J7QWX=CRk&z5vb_+U%oH^KK2QztvlBBRMoI7c?KjC z=W2}dkJ45boQ$Fg*WP(u&$7NRzgpLswzMzu7?b|t(&e7h@V&Qa7Om^CUt%sn3NibQ zNhj_bT21s(O7s*`MVTC>WMhkf{QGzAd;!XbV2D=rUNSmHSJ=o7$Xak1UxTqiZA**A z!JfZ{M*p|)W5@iD69$Rhx|Mj!@FBB@r-Xp;70*Lnrx6qFE&@7EOBMH6RmqXulvG(b z7{uggdV!ALzXd4n!onjJ|0ZQ7(_zQ&}B@r6eXj>TW5F4htxBM)E5 z@Xil!MyChg1OPED@OtSraX(~oWOmS|_Kl+_aZ6=GE6tljI`f;4r&;i=Tpa_lie`=d z`{%kITKvlIkLZ%nQ7aX$3eFdDsuKQh1h^-wcHpmTFrGJIt7O|ayf-4Rd~x$9WHa+G!S1FZT}>&qV;UxgWVkOhU4Kuv--z zOc5{af=MlN$K)TL%fGm`NdbOdoLperA>22x^BsIi;c%3KL60=~M4S(Kjad zU%u?$TtYZEe=#o_1In3kU24d}l=+v+Tb-SEOJl9k3Jy{H9|SaNp8? zck7{yMa{`+9vAyAd9nSWt}dsIdB9BGBry-I>5ijreU9?@OhbBKS>_1|oG`1`d+(Fq zJneyN;!Jnlc~n+j$Z=?Jl}}9z$k7><Xd zmnL(supj%rZgQv~k#Y}Ol6$lJf-i_HJ!81v(!#E-QN-YR74-iKmJ5vll>%?d1PH5q zF`pbftzUjhKPya&(~S%t&MPo8w2k=us@e*!~7v_EqH`0RVu>+m9d!|>_b76Dw@ zWt*fH0lMUjB}h=PzvZ)1)f`x$;h9cL_X>*_}LUHSB9%6lb#{2R|8=IQyN*nw7#6&zWFpJ>fDY}BWR#Etq zo=wnm?+Xm|8d2jLrU0?SQ7ry`cZy3zL!QsNmq!mTMZ76Ho@-30Q8YGIfWb73kJl-R zKgvlQKS;T!1bObJ)4~%E4<#9y1vqOkgyFCgxwidlPged)A4z28HLhLHZvS4(Z{~FPh-cwro=(+4dc8;ii&dh`MrHsPjvsWmfb4Fhd}JQom%ez zmjfZbv%`t~F0I(hm;rwk#`rAq2iJ0b5SzK%Nst=q{s%Z^#>GzXU@1qD%n0RN}%z5Z8# zRTie($fX@`Y()7~D?0k{+D;2_R$mml$aL%5Nj>VWlc^=Q&K_Hhl*Pt+jlXIq{>!A# zwG}l!GS<7%oi5M7z##Th+O*mB=IU;`@G^SsS006vcpQ7^ij_y(F1hZ4z;?B? zG<^%_$%rSAQ=6M%PQ|scx~lcwK*htOyDPQDWh5jgdgYr!`G>99wm8YF9+Og54<82B zc#XvgZ9wS;KL(@;6zalp!e>c%)>~YqdfLS9#=4c`w^CaD8YnPihe>7+3U~_4CnZu} zA8#y*k#82wh;Lq9$6TZp0H(trP4O+&!N8cvbSw~ZrW9U!y96x}4(>%b-TajLh2CvT z@Dkdcun7;t!DBuNL342XOXz2t%=tV8brzoqv+&0=X4Xb%0(loNm&3U0JWx0$#m8;! zcfX}5CFLM)AAGNWO1((UorW#pH>QUoa6L?nTC3g4I)OLgyaeY|&)D1ld@=$Pdpj_M zH);2zAPrJ4VXMelIFt1}ho-#-3hRfC@Tj|+4CdzMa6ag$y@QY}ef!|%GPM@=o;zxJ-R5bds6{$BO8PJ zPB%8rs}rAOYBu!-c&^UB<5TqH2fr@&AG3G$9SSfqcO@b*$2HD;QR2f6=}gFB0MJ8| zg^yj)gUbas+Y%-};O_6dsFtf`K6yRz)5RLokjbY38e@GOGI&+}C`O8jN7Mlql&%~W zu%%ydVU^aQ65$#S-3zsBZCV!oJ0ctN?kl#)}&soP{0Tix3Czs&@!bPGmKJF64-iROJqnmIE zqughuG7GAH#8!!sefFjPYE6m9tgBS@SXm^>QrMutd+a%5G%r*jr;5tX_J5g6E@x_u z$_z9YWD>ZmKynM$>CexDVOrBOJ%in_?}BmEc_fBU5;#kOVy9GBJ+1^0;8zNA@1Ih~ zMKcz}20uk8Jr3s0<~@SN_70kQob}>zc-7QMX|(8KJBE0br~sF<1!M2|%L5m)&1*eK zd=cG($^P@$N5SQRCvZr0yf~_Wr-yFcLo`_VAe4-ZVhxVvL|=M@I;I+`{8;Caq|@n~ z=r)_TG9HAOruz<#C1LNc)e)m*c~lfROhP7)@2o-r>v)t@+DTmnOjee%q)ucHZp{>4&im>mzz4_ptADNwR3BYzy9YVkgA+e=MhZ$>4N=v>ag&Wx?vn7gcuou zJ0CJ}3k%9kQa_`{KeAr-#yN?DwfrNw$EDai$USDe9Y2q<&0~AS#8u} zR0Z718!EUJnj9KizF==N^7lNhfU2HK)i|lnLxpL|oIjK6laxWEL7E!KQz@Y|a}vgM zM?*(*#)?AZ$g<>4NKmiC<*JH2P58uk*9pnP5XBSBDp;_Y<*&fVuU7v7HUrdI8x+1D z$rdAV;+PvT3|k@I{Ijkp2{S%IFnc$YWK+fmXo;D(=((whzRam zg0vSaNTv?9|F1ahB;Q|v|2VfC6^D*tT06p(&%^=}`FH|po#lV67)hMEjp+=hZ`clI zc)t<41AYei__=3!C`Nn-9<~4%G9V}$w=h6;D1`(&vq|{`RoB&_dgXTI#xL&-{yc3L zx1!h5HyXQ^qHl^i-vcQQCU}BODtyn9Bn>zs+1en?&lLPI)iq}%WhnK}?T5Ka+thw{ zh^2?an3n5_H0nN;mgq@=muh~;F0ioRJ>^G;e{~e$yoJTqJ^liq`0o=Im=zJdom>Xv zu$!*}p8`K7P;RJI7Q56mn&+>Ghu~s*z0)FP+L^M(){N%auF_mvbLU!9lkKpGh2blUIunJ7LCg4j7x`6-hVt2 zQ9zCUOqW>9%jRLt?$4+f;xG8L?aorw#TbfhuO$ECfdSb#eXQ+kqqSnhXQ%76jh(T{z?g#4+J-MBso*GdU%D59AKT=9b;Fk1cc^t4!7hmwH5*+b;z8y}a9g9PQrs4O>UN_0mpQAC}cvhYXD3L5hW*TC13ArxDMRd zy|1xbbL)t}rmflhzd zzRJ~}N8KcR^!vcr`51PH+wCh5FhVp^{%x%aQ9f`xOjb>&Q21 zN%%x3PE@#+eeUb?nre;(c=;Pj#O3ET78Wixw(@uH3X0dI)43&Lj@a=*!0Xe?t8~RtQx#|^Whow z3`;*GRJTNtrV*bsluuic^aqjuP^?VlE*%wUU-i| z(P1YkFN0<75Y6gZOfN2O_NpDL*>_4#P0a<)D4gncdYp=qrwiz~_o72c`Ykd@?*RSVqDi3wo)&NWyFS6@0LPrfT42Xcxrk|#a7X4rW~7@`7tUYf~5qxWrYKpkWPSzMI=f|OPugNYEp;d&8yB<>4`QCM7ASK1Dq{I6a-96QMl=bttaC zr-c(Njl){9Y)q-;$ll!kE;xqkDo@1tVJv@s&jidD9LXV=CZ%w)O*W(Y7pp<%GEy}d z_NJ_~pa5%^3e4Et>p8viaS4YmdU}n!%k54AH*0GHKy{LnGxUOzg*1ru9?T6v{{REg z+Ijd}Nr|(c;8ifr>fkYU1}1pp>FX?%|Jh*NutJB`osLchxY$ScjfSez{Y0#3x0$7T z$Cbx7m+2oB8o?Zq6~<^yuckmpQopG4K>^sXVEmt%A>g~2BHkWd)S~ID31-5&k&y)Le7i1{lW`$*s@&(6e>I0%gWl* zFIMfzlkZ$L$_Rcjwrkg1w?K5j4lvXA?>*3z0pqn8wmJL>LWXNlL7YB)T9E)>#`+H~ zKn6MnOQ8M$+tx8V4^UHCS&E{fHDJ>A^w4a1T>=|=kcyY@?X`o1Dv&A~xXd+PH6IHK zh$JuWv0I>%lBIhvBcCU(2@3X(&wh%jHT}=LuFp&sE6b#(DY5YK0<I1RwE^ZGW-nX*SmTA2kUk2x5^TU8o zr^?kzUH!@Z=Jf|}vVsDusn3V5d_+ozoLL^y@M|L#>&q!#|B|UhwYq8uMom2!3_3R2 zM}A1@^btK!KTq$3d95z+P|tAT`V?8R>!FR_hw(s}BkizOg)MU;dd<)f2+oI`m}ATR z`LkO^MU7c5)_uAagdf?kb|Y1UFgFH!hF=3ED40|xA}U-rb|93f-?P~+>K z1u=-YavOf#_4luUcK{+2_)^WRt+i@A4evD(KTF2Pu0{tTg{J5}uh@+nQ$T^=ng}{? z+7zQ8m$;s*<%mF(z2?#lfBV)iC)zfbrVwdnHrJkTSXEG93K|s<6G0$<^YzqpqbAQ| z%B!bM2#n$AA}m2ZZ2>Fh(!iTG!UHW_oy<9b7^zRi0pDmuW{;|osTwim^$XsARA5U` zfl&cn{uVbk5@dd}wvR!M^k10V{uUJlh>FLVw8O8=imIO6_i%BU0{>*_1VMY!7N@3Y zS6(%|IvHvVl#oMST^RY!x;{f{sq`AJ>miO*b|8$iF?0ED`xr(@tkXGAmUuT=!KA9hvrM5bG5rPRYe(Wx* zTLdURj=5<2I+qk9bCy(4iNnaAmw)sDw#n6q!@$uV_2aW|gOf>mvP7qEcQ zg!y}Q@OJv|8WvCiEmysV$OpzTP!|mho}V2z06mtPYJ7=$PO?-m#J4or2NjSTfNl?3 z4p3F>tP7SRO^s=E5Ki!qPZ7KDB7v08$JZ8xV81rB@gu*6xayqXVlztLZrVJGhJ^Hg z3Vu*6D_J}JE7hFo<#xBcSiW|J&RcvlJY1F7PWQf+mX_l1j5mlcP}}=bhu{E6Q~%@k z*tJ2DaXy(^&VGdjqb&c0P9rSVauq~TV`D1-bB`A2C)XQ*x77ex$-(YiU)MMx{j38O zOi!b$=A2)?V-E9N<0*|q1kmw$7Am0@UH3k$d!{Qq$3T}iKd%c8+Tf1pGEz}B?33FM zsXswvcetJFWDPlvOY!O?3nR})6N}b^2VQqzlH+#WPG(NCsJ2!cqV$y*?s1)`2nm=m zmzk5WCxJuK?e@sw`aiLW3y`1sdGXTVnPzV}#~;V!z^PlxqRmzz!%Geadt44PZIdq8 z0$59PAWcp-&7SNUfnpofr2yZa_zXjxo44jN<-CV-5p=T+>B`H~0@m*sDB2NBy2tQL z`U43NQtAQBbb)c$G>9TQN`rFPQ@?_OLPb1>4yNAd&P?Zhw4c&++{hPR*4FVXPx=0( zK))2mC_0tu=g*u0f!#Ho%4?S|S5{ZwGevXi1RX@h4juORyoZJmAaPh+Z11FOUWsTaKu8!^z%do7 z+57`S9y_hSoEpBoh=8*bH-R}6&BK$D_24Ze;c+@1$#wxsjK2^s@o-l!_FGpwDbq;U z#w;!+i}Qy9_Nevvgz8iTZJnC212^|{tccqIG>ssif*hb;pk3UiNCh-75F-EHsS`8; zp%EC_cWy!9_7p++nbGpJKnn&B3xLFCp5+!q#Vn^{5tp1l>r|d4PtN!L02$9LXQSKZ z%>?Pr4qLBqx22Mp;5TEy;cKuaU^pov$Llln2GT4NSmWC zF&RQ1E2TBqou}qhYK)v7E5mJ#DO&+~5DcvD-UO7!`~^*( z?B3mu#0lt}pbo+nD&eZx+X30h;NW>vvzSJQ7a-B2QAKX0JjxaD1(|C+YX!($#9w<0 zMq`x?GOWkD!TRvIYi_Bk+qrsu@VNgIP50A{ke~zs0Z{}LBo{eDktvWQS%N^3K|xT0L=lxF65lH9KDW<3 z=e*Z<+&2b4T5YYb_P5vCYtJ?3TzM?ERsqt;N+Lg(%BMDTcthnkUe4fI3$Q-(IuzoP z`~hiPyb32+JJwMSXxr`~%~b?MFgWz0#RaFBJJ1#2roRW6)@Q)tV{uy5vSbVJ^iTTU zay$!*ORk=)P&#W8&Pt9bdpZ=|12po#9U7QT-+)7fRZTfg4)n*`{4@34=}C4Eek_2X z7cNQ+lZDq-Aer0Kn1n&yGF6TIoG%Txy%YcTNsNOpBpx3Lb&B@F!sdN+`n4Uz`_`X& z6XoDrpaA@Gq?OWKA`-9=(b#huB%=-2U z3-M(*QJE!KTqGGt>nRZClMamdgNzo||Bm#J!(jgbau>1nUi?@On6C~thvc<5X{)cx zEY60Jo8a7@P_TW{DAsJ_w=awsAOa;_4u?M>+K6&;+h#gz+nZ5xCCJ}uq$19;#A5og z>lhptJ(caS=YsB#aG9i3`A@?73h$TyN#OB^m|ZU%$o>1NU*|hsi-|sE@0KdH*;}1! zkheTPt$hAIfdDl~b_0Z3^fSp0aW;rEJxkJGc4ug0s}Fb&yAUr6@?NcLDV()HY223`PRlb?(;lOz0N;sx*WFX~hxA`J4j?KWP)%&scpWICqQ(KJO|y-YqS`)h4nQ2GiBMbvInDr7(DhU4dK`iZqfP7pS=(yKgZj13;+7c8| zsp2hBioyFUAZR3ahf&8C#7Q_s>md^j#bf|}5N4}KLa1vej(ngITZ4bR#jz%;_UUSl zU$OWKh3Iu*Qhh`cA@3j3p;~|FdLP%ZHTk`90J#1Z=|&e=;f*`UkK+z<`O1+{^>>Bt z*tpA;InQ&BB&_6Vt>n4mkaBX+4k6yk#R@+W29FMeR>qMD58NXFJ%gRqawPCe^|cxz zds?wl3(y3`Cad->9Ia?yBN5{K7JW_7^If(bt~*TG1ZesNY4%|g8HM6jT8Vev!z?K1 zr%@}e$-lU&HE>1T%Gf!EoxkseTHZ&VTBXg!dqs+6F~#I%IW4$eMc;zZ2)D$;(^G=S zCWZr4m^@7#PbC6&edHJ6U)(DW0WMH`z%{6n)y&Kne&8u#t%60@=6=QMwj#Zpb1dIA zm&YDw{Ng!sN+|5{F%vz4%BL^B&Z0ygw8fwH&A|zUuyTZGQr{L=0&UF+I?F@7)nl1P zps(dB)=qOXfv*^Mj3YuvWI*)gNq10R<$-h%TTQsTYD|D$6G9J$MvOU-A#^DT{J>W2^Hm4Z>-dQyT`0& zYI>>rWLDkl*D!ZGE;>4l1?NlQRI&vI*o?G8c>@H50egD^HM)tvLRJQ8$D>DWJHOWw zCvGo4c3CWQ*xEpWIN%b}glybm{#d3-`{uN+$~-o+W-R@|`_m^CaZ-VFGm(k}$Om?B z)w#cs16CK(op8=`0Ger!-@%zOx@5_x@R5rtJVIF~Tq21K2a}Ne{jMDLqWvrHUr*%a zKm8^zLa8)bd*94p)C{u%dqK=Y}43?nh4Q0jCtQ;6mP;4*F15=H39pEYRWUv;5) z6Qgmi?t#!!F{ee*EPLPV3w^39FRc=CUX0R-V=b-fq`Fq%O;X}SGN*+V3tZO+b!KEa zQcY6AqpZNJ0a)>0-hIPHMGg7vePq7kY6E5tm$b5<^1ik#G|1(87(}0ebA}=5q{#;y zr16P+L-z3zRIty)kYgF51kEm2`kJeQ{2eN7*c#Ntka=)NwVQLR!K-KMg-4q$KIbHp zDV4?O!mgV7AM7f(q5o1&wf4>EolXRofqJ2x)vjW4^7>Y_JyubtTcA;J^^`i;6>-3V zn{3|~g7dvXUbDf-tyd~d8Q4A-tZ6+}V|5>egzQm1kuP)AfL9CxhywQmDEiInz1>=Z z!u)@dxvmKosYy+^&#TS=j@-jprQsbp*YzYX>55J;qwK*7)b9rQ3A#3PMs=POz&K5_ z+24Qk$s4l!(QaRa6UAI8XXodAPqVPtV>~Xf!>qPS+pX_5wjMMt zHxkXhlJLC;;*DfkM@*(jP}q+OWAf;zKS1+{*t3 zcXUYOz-Z;OZ-L626yL5ShlL+p$5rnqD~zI4QY15~tLf@^*Oo_*Vvtr8ELYaSQycK3 z=PX=2+~bdX*I)>fm{>J)yNBD}MUN*)bjn`o#=-XO1*xfCU&_6C6K|>DiYCX|=)ey2 zUv&>wmfeMb9VaDmk+Ji=0-#!Q+h#WZv9nP}Y~6$Oc%Z*8X}7{H%#??lbtF|l)_xOU zn0H0P+$P)RU<{$Fs|t53z|&|e#H~7qbn;E#mj?x9!##b>;Uloy0GBx#y&S9(n`m{M zq<~>RY%nHOvcyh2^rJ}^o#p5|3&lh9o7Vj}EL=YDep(0aWOH^*D7dT<93p1_N$>X0 zJ^ldoKlEbPPm6Bxl&^PhyB{<*-3|M3+TvlYufN&++KSlo1e|0nl~wUcy*R(!d-01Z zduDJQ=ma(DC>%HpS0C`dLIU3MW9=xLFUS_4R1N2t$H#i-nK|ft0pk&f$AHQI)(Sw6P$`C6+;`tXN$CTu$n~&i z^B!JGN=$}A?m)Cnz%rc_b)L@I+WNWdo&xqbF7rOsu6f&2ExPbWMu>6fo&lhAZ-2KH zpuFd&c^JgX5DrM>X0^*nbsp%p#KZ_kH2^&ociH9UhEMbGu;=7dU3ees=?+$ zf8_RdHn=i;e+}cliqg{Zzyt?g*U(TokTj>KGeEdu{91pn^`tmJxZuELfDyp)UXQ6jkSTX2cDu5AJ>zdwFu+<=ye>F0NIP@H?L4jnf8#(?)(Z_`iBjIDZ; zuRvio8f&MiFa6*YTtE&KJ7WZGZbjb-8CBK`r!z!+zCTHcb=-M@J8iSvHT5Z0`e+BJ zvUOzWb=TkE{0bfcmFsWlR+$0~ZLstdm1apIOTGok_w1(@cDmZ=)k2hym+mW#oOd-n zaKT0e*MHmenhB$^?LXkTFlC0hz@il9iTTDf)C;QD!uA4&IsXyV#^PW*4C>r%QtG}& zmc~BiAx?jhz<%=?pB#=p>-ecY>s4rnyEEhEmJ zO)w4J(}LUDw8zeIsVGM<5}yAG z)<%Y45(Zpl=%~DZ|KOA3&)~2y7tt%YcCWT}cgmgUnEfi>gQ>W<_b@$CP*CuUeN4*1 zX#K+{f!F;9n=z&pOOJ(SJj5ln9I(54gkP3cz(c<$H#aVt3&DET1|p!*nL_n-dAfhd zmw+PCmucyQc=kcQ{pIWwjQSNU%6HKlj^Vw5ga(L&;jsIF<`Tw2jq+BNV@dyRWL4&0VCyM&HrM~BP zCHqZQ6X@JK?R?AU*nW*@gqYuqrlF^-)RMA?z!oV(`rkiS?|mhXU+a9=_v{-{PjwS< z2$!zB4HlfsVR&ssQc~C2CJcYL`)Ob7nSu8D-g6e>i(kL7z8~2X6cyE8cWOz2V z+`_N6H*V+ybP25QNjGi9=X_oN50GjXJQ`cvT@GUkd{kjEquJXKkTg- z9a#p0JQ%{rYitrnmAnBBRU2TDD8v5^tzY0%*SQyxyu)_H(a;XPeUo@R8ypDqgFBgl zUYSG~E<>2#ld(iR{6wCpXs4mr0hH05&#&r*gD4(;z$N7Id_DlOAF5oxux@~U`)2~x zg@T@YV|3OA9JrQ+YeF9Ry~_Ua*HDq1nzF>v`2U}TvN5)yGPr-df7T;!hjmvbZF(WQ z(?0g5_(G8SpD&{$K=fPo^6S=tUmj`lB^)&D=j-QYpPe@+$`fi4_yR`^xXD~|reqd< zZPg_lwLkSl)0l+4Ep#zT_W^NCd1I9`jR3;MXTO?xCrK-Zb9Hru{P-%!ft+2g-j#Bh z8wUfwz#{Sq=TVp&$-rO&200dQa*ZmlU=8nlWudiheb&9Y+IjRO8ZzA|yj@=2(?&eW zl`o)mQeRJ2S>-rEVu^j_FzWfaLnDz-nY7pN!TBv^=UpNDku)QN$HOX0x6!~xdcj?W ze~eMz>VpLj!e=ji*|(ZD@#+Yj<>Qg=D^~>41kK7}l%Kiwif>)i>$@%oGK2;YUEU_n zF+6+~k?9st6+XLnD{@8@SInOJ`^7AzJ3A~$d^J5gj@rje{#7QGdWf+h?ExvC)GhrgeG9$OK z9~a(^-i^e#$8VHN(BMi7FkZAw$JAxv7AfSTA%->=k3X{6oE_H#q&^$_r zm&MENW9|=0Ig<4+UcRI6q43)MIh@2deyvwXd~g5hL9%$Y?c)1aFWNqkZ07ik{8k0j zRPg9WlF=N9t*2zsC0P*jUHPK?^x36SBpI2Oo&6UMRpm(!FI81jP~p%L)t)zhG(J8I zg_^^wl|ly3qEYA>L&0Fxr8^I0?Z=bBhNIP(1pvO0 z$6sXjgB0&}TIXA?BlstrmYX9l_tYbQI&AV?2^Rek!rvYG~Ow9ju#ZSdy_uPN; z9J$;9y>4*0UV`HQ&9y{-kNE{A=nS{*>EA);JHa~=cu<c&D+cLF~3yWNOmWG(Ns00GbsPrrb z2qU=*UJlrO?@FYF#ems?Auv>S>b%0bV%!uZ5K@P9_oq|x%!8?qbjB$nKWt6y6|sdl z)?5qE6b3LgUbD^%V7k|Ls0!k9jj91`o_mJLjiaitIoXwfX7jpo5l{(&V}EO_A6l8f z3L<9hfW&=cMA<{|F?&)NXPFrJZQ0A0pvz}o7~f<58)rW@45xOuhchvB=6*M~Vhl0B zm;osMdp;Yj-=AE78hH8K0fWCu$q%$pct9v6=oN~zN|&N3i1!IX`#>wb{T`9@ou1(% zIB%P;-%z&NS;u5zaejPHScYz4Ys^MJ(?WB+#+rRt(=mDGb=9-w^Z$j$F{14;NX-O7 zfKk15k_hKTYiwca1=oi(^+#(_Ts#~iSrQfHAolrrEH2Y6Hq&IBKC&pR`} zE56$R>B6-|?ML~I|7t3@P98H9)T>VH5yU2f-0&yIX1^=<>fmJFX|*hLkHDBmHzCvwB*jlmj5z5FARzX zQAu+Guh{d*XrVHDEK(#Tv^ybVGuPAE12#nrhDx=PIPmf4&3ymmMSVaXt$V{s{#Y?Q zqW2)s0eY@JB8;f}$9nppUGC& zPz_iV%;v&B2y&UywF$hQLkSKZ5xjRQYCQP%${7evE0^vQ%5`OQzoX|{)*lbM zjU>_pecjh?a@yl+cn}0mwY<7j7{Blgq62&))@dEl{ssKmALt3~IT9uQ)YHM*+ zQU&)-+Os$bMp4JsXR<_0YHH*ljZm+4iX(#5NRQsP>1@`ZG76B&1)jNv}z%l;%YQk1Z+KlQFCC~%uR2E;O^O%UA(~S$eneAvpJMWL|)$Z zB03uH5keCT%+?Q9aq=%IUY!#Qh8U2$rD@6WeS#J>dGXWL9%u=4sOT7qS?ZWiVEA#h zFmuSO{S+Wo{UmrL@qk?7z2H>mW~T|@*^cL*vJDXc|4R0x zyt}j)$`C1i>E$#2$O}2S7mvwTPy-oyGC5b_)foTK4x@jAd7H@~q+Q6b&`2u_ zFReQ9(e;w&M=8ly@OUN2xS;$%ZtKxz=rldeSvHM==9}fz#V6cG6BvO*`%KEe1vDLY zkZ>zCcHTbd?!Yw^q0#ZZ;9#1_^&=WgXT&_R$2iqZ3GoT6m%F6n|6#VIo&-|5Dts`< zDRiKlO=4(?4GRFe{o6lZ(V@9G%qPHq-fRMHXOERBI7$BEph+~;R!XNp(j&_llzrH6 z<`A-KW?m~`SYnnPm0_3gxJMo>iuTXU?$OmbO>Td#kH=c>I!8iMkbxnzjh@^=`m zKms~BmlFHoRqks9S1ImSuuzU(WfE?;I?wzZI-%)s*q6Qq6f-B<6$`XAr=^AZW$8Oq z`WpI^+yoZmV5a`OkYB)wet=&Pi*qdl)zgd75#{&tT*nYCI=PfMH@nX>>NS zF_@C0GKNz4&_&xT7*a^J$A+`D932Eq5|R$zv(+Bv@Q6Mh5CO=(5-nsFD4MRuIRp_L z`THldA=QtZ3xy2PD*|py6r9f5#5dIrq;)(l7KGtBjkKxg@W4mw=;zWVPk0Lm+*P&w z$ZXK@pqhr>JhvY*WmaMPNz0IecsJM2z{s3Hv)bmGCZ6ju*!0FVGc;c2F_*oxaWoA& z?A8DMH4#h~JW61noi&)9bHDxxolhtSUSb$W_mI7=vfm{;f80LMu)u=Y3(kwFXh+Tz z_FG#6Y@$a-0K9Gvyw}lecp8-rMdAO%1a0GQl zAxHgM^H%RbfueOUKI%TqB~X0O8S_VK_@C}Ol95oKO3NI+0qY!&vrf8lO1BOC3Qi>Y z+cDyfO`Pw|#Z5L=pPt7ONAK?QbDt&UQw|Upl#kNpNxXKyNAVn~OH|Z}80+)cp{F?A z)54j$Hq^!>`H#~MC?_kg+270q|GzR1&~q)>EH7n_{g&5QoA2(+n1_P)Ow_1%k^5j7SCT0KYEuL437(9t^S@A8VAvKATE678V$Ms^1fRzIN{$>!^rXf=h=YYEG2We3>{2 zb42Y?o(!JoPd5BPR1ohSN;{mPBaqX0ptZ{3Q?>&0&hHcq=g>%Ass*?MN8GId8Ev%hzQg2AFx zzrb-HWc-MEQgAGnKX%E%vx7NrXGZ1qCVSBM_x0Qpnx z&bjny&W9_HBkQmBgieK=B?Wd+d^m|J*OSov2ae4u1;Av8B`F>{r*pL#9FuiRke)tV z(2idB8!$L2`h_U>^_5iJ9!0gAlLb$b(KUbYY_ib_mpHps&9nnsN@N>H`OEnT2|vej z=Vpf=$R2dcwoQ|S@B?wH*bfewxKs7G69xzj&+m1V4NGuE;*!WpU?u(ox4reJ1cQCK zM+^{D)`65aKLW{4TETq5bkgCXskxIhPo}vsqbRs4(#HRxG`z+V+{_{VFoJ-a<%}PO z@_}MLfn`>vc8uIlBxfm7Hh|C`t8L+vRkhl~Ef`%KNaZjYn@GOO_V&_~@uRnJ+8Dp^ zLIb#|36d6^&YQk;=m`PojOFEP;9dEJHuu#vj;g(L!vjSDw7UW`nLLi5NRSe+3UoX z*X8Rn*Wm`Vy>$tFES%0<(~Ptr-V^C*4|^Gusu*2L0~eYVtq9zbnqDc42UWm7e8B){ zhItX4in#zz-Mn$5T)zNk+8@2AVmQ~AW&!+OJt^1RDqw88u0I8UAKd6|J#1CAwT&Gd z#?$0r`s`2eb^kVsNtv&E+zLM6x<+2@7NtGOdrj@Ecfp+=Jw2liYd7(B0jDieXgUAp zNDq;y>wSE?nyV)Aggr$a>b<{BxAYN9CJ}{3+6yyU%n?bSJX&uooFwX4k9U_}#_iRN zuaqjlP^)w56n8n)0>2jY=Rbmj^c!tw!=34RRdAg`QT0;fhf3d4r>U1<@t+L0Z92LT zVj9)*N^!|urz|deVTZWF(jQHr2k_ZmEY2k_L+a+=_t~F^Q4FG#XD-9&OYlAU_VG?f zmywaa{`&gj8raC{>id8f6G*tq^b5=$>U;-}A8z`5^p?x>_w}HS#F*-XK*7h;8qlfmeZxiV!Lo( zSvBUFkWsl!UaJL*glA$)|BwA0jMT2vEa>uBo<9c*mhZ2BK0X@T=UMLdMN-ncY75xy zvAiaZjy~G@`hlSXzqJnaTNdpA6W7<{(}w`U_Wr%-lZU(=eS-UevSvGr&v$M%}ri2BhjIl-X%h zlFy~UOdZVX85vhTRcX}P>Ad>QZ8U(bH8v)$p9sn=aLa$7bqXJ@nE$)|U-u}YMhI#r zs2bj!w1lyelHX*GwUO(%>3-9cK@8-uh#prX` zgM%X+#esyR{selw&&r;r`=|R8sTcc`6U3@CJ+9(7ORBhhjf^Cg>Sp>4`Y?rvzMIN| zj+bTKnN+5!2jAtMsB4Q)-d8=?em98tg}skVoO_oo5ZyVtA~vs^R68^iqL-~Ytfi(? z_eD&|P0D0GG3w_1mE98WUz~Y%uWq-mQMQMHqyOnELyu2?HpXO+EWZAk@W}y8**8n$sDP(U415o6Xg<8;~h~BGToW^Y&#<#}oi^Z8m zrf05)?1smdp&2|s(vVqmzGO%g(jt@RkvHZcF!bXu!|w@gRGc8NyF^1T))-H$W010& znq8|#IIJw3INtgB0{ukuXLqZ~WntNOlz3(K3PIe)Xrz9XOib>HSZl1bkXHP$uT7y- z`48Z4&_8#F#QzWyzoW9%vbHwD)$_|(1rvC}l;{^27z`$$Ucr3MQpi^@=T$Wm#Uk$B zY*ET_LCxvPH@cItFvlR|WbyL&uk=<6m==>E_oOBhJsOX&{<-YYYEk<9)a9j-Lh*%y z(L$s9;c;#-I6FI=hZD_UCoeA~?lQN$GQpB5nEg^$6I|ZE*nlInT ze$1VuF`mUJ!djY#pm~8>6hXk{)^*&jW=BvRn_2qVky5I3f%nqSB|__;Tegsbh0F); zzA+T)vMIcom+yx`e(tt8K6mfBh=GRiF*LARzlK}o@91(&OvH7*&&x#`y>j5;DSR5D z1lbpX>|XlT0D_vIFbAIb`4`RMWf(kMsb6sO=Gz75p50y9^EGJ)K0hb0adGBThf;m81>D(5x*;TYq<#ORh1sWAES6`144ar3e=qy_(?<2&y63xm# z-z=lj%G`IFkd>GBiY1-gU!-J@;Th0y>?tg$$92-6wyGjaG00TZ&G~Cy`~h|xSvi-l zi(7_K){TbZ-fJej*L71wCOMD6>U(U$-la>C;emnLh$k~Zn+}<2&sq8Kb8;pw({5yB zb2^&q6R*B{^(`58&y{;q&GKi5m!tJIO{<(PUv}=E!(z9{R3hwx8c5WQj6RKQYWf}| zy?PaEse{2LB=DKl!#GWETvjEq@m19(@!_-2fW;We(Rf*HUOb}=sn7BRg&6IIUkFj^bJ`a-gP z$nob>7-U|a*5E*P{r)zSUh$Rfog|QpGGDf!9ck^r08vE?AY~XKOlNFY(FXMB@x|9q zB!&FM&n1LQ*axvAwB_YRA=20xP3WB~NUJiNdhkRsx4Bj+a^BGt8(^4uG_+=c*+hK|@byqPYU4&&rQMZ6-GR=FCqWadrxvHf47#D!&J2N4;pfHIj}ZK2B+{ zJ^Co;V5W-!`{D=*iQix*0`=W~fX3ZmPzpXZVf9@5MTWXo9fDpA2(j33@zq{PR>4B1iv; z5W7~@*GrFFr$|I=@vdc@VjE1oI766^{3Y>q(~2vTUSCM*BF3tGgpKekI=&Dimex)3 zsqcK#%cev@5w6Q3k=(7eVXW=tsyBJ}cZH0PQa{Bb8~qmFHxZUMNieLOSzrA+>Y?nQ z6^{d+_1}3t>%FKuAIDvn-~WK=G%(Mc9IN$kZ@Z{y1%BMVEM*~bEYB6PV>MQT)?~m9 zXP2+3SK?b!HDO2SWPU#Kv-5=(bi5FPSm|!4!jzHY+gm=n3HOEfXG13Ys1~UN(a6ut zHZ@M1nPk|XQRhgT+4fqi{_#q~9`jEq+t$G2LZe7d$aF|jxDzVz)tb?lhU+lcLm zIX^oNt7#Fj-SM^4i2{Dzq>}sBvX>1Ini0-gLPqa@=)CRuxE1QHK=|WKrD$A$oE+o9 zy6xbeQa_D?(#~;od{pozGlhW{-KUC7h>5AxA{3c_s)o{P6~ooEJb^ABtvADGCz}ii z|8iptx*&MWCA$C>u?I@J`rO=HsN^I!hB%@cY_$f7@kisupRiOw zGx!A3Bw2CYcYU`(IkZ7}UWLzEkc#zQNPrl>Xl|;#{cJU10MChm{YZhVa@zUuPL7^H zqM&X>`%YCyVwdnU5%xUJ%y z^3OKGOzPNj^;HcfpB0bes#MZQBG!E5tDd=+L53P!@ZvS!G^KRVj?O6M*~NVD=DfYp zb!JLnm8z)qra#48R1LY2HDytY!vHQK{yCx!9eMl45J(ZaB9MfbsX~7UrYK(w+ z1Yx3qdi2KI!-JgzJvyj%cV)$gOY}iF8|lJO+%V(qind+X5#_nMcbZH*VwTMBzv`6v zy3Emb&B<}#pyI{=q8Jl#&5dO(cQ2jMw-W5fD$%}ZIF zhCb$ZUFK&6eXxC{Vdjzy)u|*QIqOk)axtEV zi^s0#zGyzl0x3mPFKzviMwm60NXG94&y5zpKyIE540BEGWjfI%G{Y6g%|XQDkNYVe zYl;%X@+K_DW_IGXDuE(-QxFXtYo+>7?4n!V^j z74PhJQ+9Lb(I74d-pfPf4Q-%dVmop2(u*Srn?vCe!@O`r<*>PINZvgztDquxBLP8- z(_+;dQUXBsZ3s?xNIQx3WM zUU1OaBh96V9{>32k-wx5lHqQC>lb;*Ag_Y_v$@C`r(ZFb;d8rB!sjxuYIWKaM)(}_ zi?NIOG$?uh0KR?S`Ik);XoieNjxz|mX0LI7yX^bCS7A=3gCQTgSta0l-E26qfgW{$ z?F}m?|L~aB=ChH19K-!D6nrcqB*i68Kf;_gB)NlMCgX%2?&#%{RL2?$KkL4PMk3sO zUcPhI`<&9NBoG&2hr}w&Tnq{eW3^79le+zkjg*%)pmn`uJ=ld!1`;~sVM5=XD~LbR z(h>lBqri+F-_9lb(7Q_;@mtU|ZM~6-yJv*@JYA&;Ssz{eL7KSHCt!0l{FuL1AyQum z<0gDN?fNU?UDq?zuB%>SIT91ZXa);;63h)DBli_`$k5fjQV#~1bCG3fS(hUN3re4T zL-oTNJK+s06F+Y|TXa_I9E}3f4|PI6!U(|p<`rsn%xxu4lAiO&vTYAz=#ia*6!))S z`R(QP2Sh!dHVoy&9VAV8x-NMr^B+o7M5}d3Lv76UN})E@#78=q;1`v18$l<^7*h32IZXLfJieX6EqO;620&V?B#nK}v&bMCDHxaiM-9iYR{~eCMa?aku8tpELZep9>}q^3`OIm@s`ounG(kCAN&h24pi1~(uG%>rOjOOY z0STjPbD4Gur9rAou@uM%JNnZnwN@4= zUxWlF^LzHkKH(_jJ;o?_L-5jo5=6H0jgA3LsV-bC{)iAAPtF`BZ!Dj!z!BPwCv>jl zY$Xf_yY_B&`9W7=p!wEa_t)}S0A)UsDCdZIjS7{LyN?W>)i52cv;e(#*f# ziqt7P_4Mwq^8vV}?Kh0i=Ou)4!~$ zRbYG^I$C{w(MegFEb94A z#c02e(|+G!!B#&TNr7C~L>O5k7-ePSk7*+~F*jwir~49;aE}{G`|mgA(??w`Yg*z* zH8on_JZ)N7h!^5Mf7#-DMrp)I36+sC?RF5-)Sq2I@RY&xFmko9(-x^>x#_BSvW7{= zTQ%8-E^Con*Ey+-sc$_kZ3=ku@>kxAiV$r~_|v#FXBtqrlo&kdUO02EeMafU`Gu81 zX`u|MV8zlK4ea$21lBZjtZW#+ZbPAj+5@DInz*DeqyW@4fjBE2#QHqg+ zQR z^x*qrU#)IqD*((s8S;}Vr#uNNoRKWHW;43ni}C!iWo zw9K97N~4!ZV-UM?&eFzJ_9KlyoBjoCX@!`R+Ku6E0p1J6GmddWC*p}oNLrCGz1}PL zY(75?PwPj#@?}Z*wU$%q_x2ZRLs^gq7zE&+;3P=zOc&1> z&o4kY6x#S~95*DG5Rfhd=a+QVFVRTx>=#YNvOA?`epWNwrVu38i6WK0!4;8~TpVcV zIl_Iu8C6qod(I_x?aIpBt50nbXLK;BG65I39p!{0?XMg$Qh3fY8fx}D=AH9>hef1u z|7RkoVRDh{Ick^a7c1XXUY~Sm-X*l84}Ys>*_kYKZuV5&HymKZV5AYEsxjJ|REEs< zvkT&gfT(j~_uNTfBTYs1KXaiL;7Kw4@&pH_#Qn$3s;GmJ8tUdgy@s(vhJsE)kF!xD%Ds9NR z(e#INPQvE<_yR{eYP1nDR3%k2tMZ0gK5MQDFs-pXFVl{mo+V{);5y~`AN}c7mpm*f zkJ}2w{dh;+JYzv5(_vG1>AvfQsL>l^yz$}F*-E!nDR2R5`F{^kclzB`A-r8v4A%>* zhnn%p2mt{>(S@b50#>Gb2it@1g!{d)ANk^U`6@8=9^7BrIuoa+&ir$1vLHO_7wqvO zG6r+*)`pi(?Ip(4kJj!)c2!Q^wdrxFON8HooSLqM?Dd=)E5D$2wI=UE{^CqiOvEFZ zCV1`E4G$!C;?;8QO0ZJ@z)-6^WaDKSn8ZwBq1p46hLUw7$8nG%zl@O9qm0t0`5i+Yfe{R;fSP7^q{)DBJ7CH zK#k|rOW~yXR^zT38SouroW;(_Wt^M7Apb^<(SbqC!T;F7u~(tqPMr?wxmLTO-=}WB ztvT_-wuR%pzii7}<;cN50$1|C1ulo#CSN{^XL}C&d0@24wg5Fn#7oVN{3;&PZ+IK4 zT$&;tt^NL@4i-7IZ0ZK{AU_@aM2k2^vsM|s6IXvH&d=?f-tofB^koyb4i?Hgt))Pflzf-RLXbpSUZ&`0_Nu02=d4Yo-qN3Kqhw1N`0ck!v;e z@<&pa=T&FR*Ut=d*Dcv*K3DnVIn_VRXT|eL(xN%w-KauqSl5H;;qrD(ib2xsSKqQ8{vC^}^ zvU;%G50P3@0mzEm5l*nwk~8VgZaxl!pLAv4x;IUsS(kVH#nvAn73`1k4iMmLBQCL1 z7#M!`6~o;gyi4p9d^%YMev=wgLmE4lIc2E)1N?n<7l{wPn*j?B3aE#*Hq>K}LV4~C zxXF1`JKJsW9%eCZcQi>z)%NJE@DpKnjqxP%CnfR9j!FkTyIH}0l{b5N+$Vx5;z|&o zv#jL{-rE??J6~DfUrC_pbUIT>H$*aUH%WRCp;_c3d!zMQdn83Sb*l|M8W8ZHP>7UU(FmdC zkc4Ht4h;%g+8}P8)dpsDtoQVN0at3AIk+DwoJNnSZ{Xo8<7p$pn6%Zgg8l>MZNt4J zEXFno1lD8MtakA&87?|nGiYH;M$UckaadZf`S@s-^<(nJ+(@9nhu165;nz^Zs~OeG zj-0l-SA;STD;Vz&8xXxt%*abHOp(z@R-{Xzj-AXAJ;YO<{L_cN4%Sigv&-&jzi~-V ziYXK?UHgcr7D3(|30r>uWy7G}=YXuulBrl07oi@vhx+WU`$pgQ3GGD{O01b#vDS+q zozoOWAhWs{ZfjHQ=8+yj#I!jPXd?`1!p;odTfq8A3$3M@b@k~SvLthn`WGJ&Q8f}t z3k_Bc6Ade$yU2nx-gD?{di?5=Q?`nB8>@88qiOe;8aoc1c7Vm57hPN`eT8RBPqyjt zUPF(TC%KtxTpmm|OHfB@E%MEy8DzuuLudteyR*p!jft#r_5P$?E8Z}LPvD`sz4ueR zzkFy*g8l{onoHiHQTH}5O{8p!Zhi>%a63o5GDemRt4uqNheq+H!`vJmW6gSeg_0X) z!Gm)lnXEizs;2EG88hEYJw@XnrZoBFY}K*jiP{vSDpHafEZPXx?FtGLVgiVce|n`} zs{i?w_UmE==vkJ{$`1^^+pcCFnNpLp)4<*{+-^>vnK&JJT(q$%R0nb1ARVq;xyomP zlv@*G#qs~cHyf<_@Sm4cw>l$X{Y*_%vXGqF@y1^WhXAy;*+ z8$vC=Zi;2O)e*u^OS?6>KhMxe1c~9bt)Sm^^6LVe5B#isbBA`LhXOu z_s^#z)JANbpdi07Q=P>z1GNhE`&7S!1`BV_eGd;`@NvW=J&Knq+BPYkQ8{>sF z7<};zNS=K#I2&KEJiheMn_{%z6gnJ9M4p6h4><$E=3qyV*9U^pW#U*Uf|%$(R* zlo>p}hP*;T4f$Gb_7c^sA0f<4Azq_gjOUh%d47z-P532GSTk(R;FlYmBmE=liZc7W`c* z%h5V|Z7a`SC9oFbj9SAJuuAp!GgAwa2<(F68vX0{agjuNTqIB-DF#9sA-I0~gkD5m1lc)+ zG?uiWg9pa5n%^hO9W7;-Ahdo-GAQ`RN@TFc?7lhs(A^UrM53HxjKDHrGAh5i7-c1V znnma#nP%;^yXWYvp>R^^7@?S9Ot37;yH zI;LpL4S8R&kklV`;lD#90w>s0k?k?-6p1$(l?VUmyoUPd|0~v2lx-r!l%#XjZK^G> z`&aeduMb@1w2*s)E*~E@eH>eRvv{D&Wg;SgIX}M`xn^2@frw;!gd!KI@pcq8QOOZ0 z)yZ2N!$ol6ug+kCOt|*^cP3m|Y1399|6e~G$HP%yz`;klX^ja}0y{l+AHxAKhVkVR zKWLgsIdC4e7EzSiu^j%v`o;4g#`KrA;uPb$iXVR$sqsl|M5rvPu?a4<@Yf4aqgN8v zyv8b0gjx{ncS1feQ^X%3z#X1%fJN}{irtc0qM_yYFOwf3ZU)$*{sb$JEBy;t**T1B zX%61xDlGoOa`DsJ@cKjX81DzpQ>DEEhW4_}K^&I!*V;H#c+FmDBfh*pVm5H?09Mev z{|5jh2VWXf4)`dM%KB79nW!_v)VR8iRnGlW^iQu;+*OnBKU_84WBpJpMgs^Z4qJYe zH5iO535d$J`CBz^Ad0r1a~hHBO68FjCRMFQxes%5I_{2}d{PKgg$rW5HpZc|rX68u zUor!EF-KdFqt}%7^4SyCj2c)A1+`C|#s39~ogiu&88u#6;ON~mFDWAvwdZJU9)1R; zF~{Rz7s!PdDJ}q%*bRSR|{J?ulL~(%y;v1 zSy}s00Ri#a*s^5rg2nx;YA>Gv9fa$Oa#v%;J(;g6iVHuQ8n z+6)|nXO9bGU5!l_5`h%*&o=ooLWpiC>RT3Qxti}3KMk_OcglXI^^rk3W`0_sNZanx zSI=Z`LWvPq1#7z4<*#ZTobe+y!fD+cg%`gPU$M_t5@L!L&d=RTc)u>2CnD9=)D%hv zT{I7i`+!tunS6jdp1{N@0lK@UD{u0(!E*DK3>Cra9W(PO0yVcjr$Jvm9>U;nv|b*{ zo^n5d!*P|A`LF)=@MLgJM1-oAo*mzOW|K>gXN?w}O~SYI;C1}0*viK~?4a9X4+osi zPLZlta+)0nsjS^bQD(D(NZV&79cTVXw1IKY=j$TeN$QucQw2gJZudEYNA6{Px~dY- z!K_Jwx>W21lEv=mA%nWy{Hv0OSt_BK5U%ppCs(uF9 zP39!rhLz@#zJrH)#MwBCCwN=uk2e}$`amncRgD|1am$P(aTGDP(0`xiRys$=yO=a) z_TlCJ*$+#eN036x@;aGxRy(l0N8E6&KX_V49mLBsxybX!Zrc{cSm6MJ$)#^XN6E=I z$=(93a=XY**ww~TTH3FZS>^->be#OI-|-<3O=x5O(|oH3#V|*KjyHFGMmP0J@0wf% zo~TyqrEe5$T`tb&^f-Mk>`}cdI^7oMoxw>t2j|}CaVyyT zJGUka;-lz(m(jmls}!th0@dl?&`2O(!LeV-58WdL4(@J0#8GsaBz^@q{Zf2m{1r|1 zCx0?+E~SUguhE3GG4$t>CEBXHP7$)z;$=4ID+qnSuxAw!cr{;WEs4w06YBbAd%d_k zR`S?0qcb$W6O-k0vutPn+s*0b98tIiUAl5K4h?tWx3rBon8m?--!;VS>7lb5*~-^~ z{Z(T}(j2cCHGLM^NmuRGXn;^Y_b1W7X#^Td>R5^ltpd`@y0eUE;>LJRRS#=CgX9pV z>M5ICI-mA_qD#q;}s6u0tA5P#MLF6Krv#I5f?*e~5*rXm_j<|mM zGWYFx`al$l9eQt1(gv8GUt_oC`nCSTo4H%@ zkWbKqsup{9sw~0BJN*g{DG49$MF9&)e#d3a9`EqIL{qWjC{P`b5)w&zvhn}qvO5y`qg<3Iql*&PWyO=TOMjE(gL6WsLCe9>`BlJVj7}xI@*}sWcRXX zo`&M4Zc_W&&(7=&rbe|*bD<5qcWrXkk_SD$^(3+4NIyuG!h-H{VDJeW6}4JSRNg%> zy32Crj_CvQldFFF3GwkNF~DyFre3kx!AFbI&5ehn%9yD-*Q`FoO$h zNhdJ#(ZCCHxLc|ZqnEuG2Slo?U2;^q?C#tNdBGayasv?ymw~9}I8RBv5Ii@}F%|;r zuLa}fL_>}QL;5Vg8~cB(xQo>0o6}GM{^-Egk@RqUC+QeE!=#JFg&cCZfI;#d2WfL( z+}4>9QGHw^ZoW@y7Ft*Z{f^;w^&M72`-{1dI%=d0ssJx=i^~*@o zeDa5zS1Ju}CnOkA)3irLMTsZMIRl6j!p%J8O;xaa!Tcr~%*MzzaPQ0zYIma!GJ z&!$ed1WFN}m{a5+?Cr_Fx3@Ka+wnFL%cLDw4k!lVm{pzhZ6I;0{Nz)~&p-QrSbGboD%)-ETWOI-kdPJ- z0g+gAw*t~#N-VlTq!FY;Iu@yPOG}GLNw+iz(hbt_UJG@fz2E&j`#tA7-x!Q%JYzVN z`@Zfg<~8T<|DXG+gY$N*wY}MSANP`|F~)5qGud!vm3rcsT)?ITg+jp#fCiW9g&Nb7 zXF*_E0K2}oK|ul@r(%xbmKUe=N1KygYr~1yLK{xp#nqJ!2S;ziLiU%N@{5Y%1uW>;j!)OS-`Aa zopVwr+;`^YD=PAyEjIvXis}0Cw8-7uA(xW$bTo>WjEvge_U|(Sw!iJ30|ccnh41Qk z0b+ENX$Fpq?_WBX`@H=8%E2fn_qrWN9f0cE*9KuYSr&oF#eTmZd7bD1xhOWs9_MSJB zsSJ7>_qYx3Y~bBU!Ad<4S-UAfNOU%xl&;_)4| zp6@w7N-lOTzaCxQBj8Fs{U)%EgUU`Pdq~gU=A%+hELYI!9?OvnRpKTptLV70cUOcI zl+4aK&UAH_k_ma5uMQgX@UYuV*Or?OD222>O@-9iEsRc7uD{&g0>Eijj!BffspsK% z&B=ZUz%JLvgn-rV!o`I%AyY113M85YbZ*WqSg+>cDF=2PXVcDHz;Zj0U4ZW;|JAT^ zQi+~Z#CHIgN#u|7ZP%--RvLYc!N`mRfM0G!diqMDNvadKH3z4)JFsaa3nv}Kx6Rb1 z9l;Pl3Vy>*(1|f)k$rLb!yLCi+^?3_HalFUlPX<}T8xW=d+0~r_ps||H%7I5V`C$l zUI^fJl&a+!QnTubJR&%4VWeKiJ4qecb!SDThS8Oaxo6^8=`gc*iy55Pj1#4|ELmfr zdEC(D@aM5cO^@^0wmugO3%%pIIB=u;b-MUainqSif3-uwh;@zwB^L46NOcPI)l`F! z-Vx-sQ)^o!pbaX|G1~z5YbAwW0}Q`W94okp;-`$%zT9jBEG`qFh1%!=pm4Vv-8Mka z6pOK9{5)uTcnaWsJ3H~gq-t%=VyXXdTj(8df*T$^q!x62d9bppt~bu8)RTzIeF=MGo+VOM z+m6c8ig&_KJNr4h9MEv*)1QV%^Mzotg2CI_u?=YjGC36`xRbWw+J$zb`wwM#D^boQ zP6)Ghm5xk!t-K1jBN09oG)L?zxP^}zktY_X+5>J4Y;n~D4fe`7NN;nYK9qAARv@3* zDR1uoMyl<;iFl}VX832L0B(345-|m!A?TQ5afB!O;Wl~yg#w?S@tv7;CydN`E$_^4 z`Q5(Db8jpwe;hmt*xRF{q6QX{-_vtQy#HoV(okFsYdD-(kEWBeJ=pLJbN zIXy)gKPf2DpZ#{cSl(wnU6z#v_%FcvRW5ea;u-q@l;yj8{Phfjz-O3B8G~7Fr4uJT z0q2s_6lO@c6hPOElyH!AP2dUr(yeSj=7``#C=p&~TP&&{h%x_R0d&UM_nlKil6a-i zFqlkTnu?vDM>WLpqDPZ~B&++>21uhRdH?gYK8u;g&BEN=!jjqkSua#F zlNNo%+@d1Tqb9HE3RsfK06u;VG$MH`pTdhNP!5jfe`Ss_h5nT}{tqY7Qog3`PWt(| z&)l3yi$5kG*d)ixO=Ql3pT%hwv8q{g%bWD5nRZfL{NL!AH{^9$Yh_5S+pDaC`HHmN9~W64mBB*)+Ml}CBJjI_6W@;&`YK9g z(pm${_Kzu?-5M=heaBUfuLL8ukC5EeAt50${EoTnXWKRuf>RygKi zw`RR;ff}bQKXHVl&UyP1aMfYtBTNq-lxZ0P{&~xB=Imm-NxM8-?Y@1`qu5^9i%yL3 z0yL9!SY(}bEXVnQ>Ob%fbcKTbcdF>gpb6`0!1b=#4PW>>C;PVt&KoWcaSLGtckUGG zU2uOL+aqMp3+qb2LAu%dFT3Ri*7>ddI6zx6eRD{4eD65QROzbzOlI~=yY_$y@jxPr z3P@B%3r;+#Z8h5~Oe}6u_*KXN;UeBLKdV(IJHh5MJ0X|f8>!IVDxuoX!_k z40YLw3C4eF#xUvm)=ETH{7JoAE zl@2$gP_bWDRW=0jx$ZnS(VgaX*VJ#i1k@d9LPg#5Zj}vHUHvIYpozC(@4aw=yuiCz z#up(am#PaYbB$-s+K0PBc}Bje{jxC%-V0q#bYNwn5azsXRxA) zFa&?~=_8f~1&G7Ai6uOPdj?ovVH$iw=-*I|ifTPE*-|hsIENRAW+pfdY8oqh2M=xF z8_^f6i0Rj9&$U5qPM?ltMv^yjjR|nl4=t1HuIL8qe^EQ{gO_rlE9|i2mK38ju>kR` z*ijbV^S3+@GNVSDEW5`tIiGffAJno29WArdlh(?X>OO*#Lo``v%Y4oujCY6(d14v~gOEGeZR=RsHS{izr}i~ESk6O;El-QAT_MT=4^Nz6>1t~BB%Bb zf0P8#>VG=wz+H*@>nlNE{+)~)2K%pS;Mdlb%}eU6Cu(Jy6%A&c+q0qpUHzqOARm4d z@=kU$pLlS3XY5AXoyC}ji}P=viNB_JDBuw%#i-SSOrG&W=!$T1@N2HS@1Dn{Ahb-Q zjL5zTFCg#*^F}cAMpX9GPTwYf&-2{P) z=I_oZ4o;8TIWo&IMWnk7UPS()m%%KTq7f>UPD>$w`$-d<*|+M(I3>4;@WTYc5z9>z z8|%yM5XPoU^OamyfDG|SVFj7jd!h}4W4>kJ}^I!ZfOxAxBxlA+RUT}3Qh_= z;(-5V1!0`{{Z1JIFqm)t4zr*0w-XKppo!JK&M3a}6 z5~+W*CJ!PW=z!Gro#!?42;6lyquxn*04Hm8`B zcB40&^-l_5Y3=y_U)Ckc^wL38Z1y8;L{~^*@=bkrjg{PPk^_@mA$hgi{cSUTj`s!V> zQrF&}$rZ@r+=)c`i%iBf9sF0xoWw;uLNZW&r-)4^10k2nx4=uV1A;0Wxbb$ae@q&) zjfW7*@~0(*`@fa`VrO6P701gIz$ur0n*BL;o?l>X#UD-$NCH|GW?Hq9_q zT~L!SLv^drbD`8s=Y>Q*lpv`VBpnt12>g?6Gs%x0T^eh$*QAkKPAo>c*7LwI?Lm-I z`Y)RVIHvsN;H6G z@NBa5di)4@HOVqtCJv6nyM2?qNu6{c-v{yyD}_KpBT<42baS%N z^$g$mXud?pIKou{HUmN$tl~6EHQ{gK<0S`L)&zf*Dk?NH zO(rI`f1t&t|AH2ec2OBhFmV>(2|*Z?zJR)L|4r7tP$Fgt+1qO8=2x9R)^8siV6P zylOE-0(5}zEf#%N@dl^;DEJA>?&&bv?K?l;oUIBSWeEZOormDgIDlmT)!%uy{2w#q zUl{G5ltxOpEpNr1>QgUi!XK~@*5i?H@nhRMKG~IznSj;+GWzGz)9DO?w5lV~{{lIR!!^pI zrsJjb*DEMFz$*nrw(r8OIK-Wa@uGAyM5s2^?W6ASZJ-ZSfXbA(@-pPaaDX{V>M4rf zAS-tmYi@+^Is{64pfKfX;nGiz3^WaLqQsRYUV{S7%OczrFldEA{~Ecj5WI5c0i=Nc zpONj6+hCTax&|dQ+p!hfFI;G+dFkiV=muGA)z*(63k#<=PUug+CL9e!y0fbgbC z@Z%BPRS7b@7i65x{#Tz3C1ozKt3t(5#0=V>$Oy!W!8Mk|7cRr3AqQ@s0;J|-?NUpr z{b%#i0B;R~=B-hA5OFO!P0>;$9t>OjWC$NKQeTk;FHsDJILk&8;FEXbRmq{m;kEA+ zK>+|)Xo7(cE{-zGA3uO>f_Mo0;L_k3^DU?*nzp7FI1Kz;QvDd}Q%2v!d=_umvI zb>jh6{?kzG(dC))CR6O1w-z#1EA^Z#ZgwqWL#`oRpHvglfLD8*Wz;E!VC4hDmNRy3 zmYheEG|WF$uzsD7%ZfHkgWESL0HxdJ688|E7?05_NYiS#-Q+67Sx{y>4yABKlBdDh z?}-3;ra>;l+3>}z!x}lM_@<-fjo7|-sgxs3E}ekcicv`b65F$U;_18dw|yRaZk0`x zUzM*Nzl|;NidWMTGTp)1A2+wbEh2K9oh{+epK$wO5~su51^;4^e^Xrl^6AI?NgfDg za}5l>Ja;_kCLxR>Vm%)CCT*b+$ovT1LyVoJ8IPDGl&M|PFGtetr*-=cbemiRDys>m z6$vu-EZfoBW0}*pDOfpQ?I^Gb{VaV6L>Snx&!6LP0;Pa}(c&xjP7aY@U%7Me z&sSzb^C_f`o3XtQ4yI=^X)B=#(zu|4gcTC5j!o!Y*ehkofJa?w&S|sHS1I6?q4-02?RQIe9JRSYiRQ9jlI;{e`#A0RJ( zg%y1HM4NXFYe#=Q@Y3a~v$0zmG1fd=&bsrq^l}K6C=EHYxY!`hc<+OVShpm9zMwTp zVGbo{k_O$vO#hh@Zpa0xsOMb|CVOohs@z%E{VWV+l5DX-9Pr>iQ^VzEVv)L~Rk#$_ zk-tPcDhjf^&hA>_-Qw|=mx4~?sh`r*Voh~YTz#%<-fQ^xSHdJt1?E~Zyd2u>6HN3A zwr3;c>J-7$7_+prjYPD$a925#BuN3r5;k(t7y2u%rX~8D^-J{ezAC%QMcQb$yV)W4eSZS_ zi}$dLN%?Ese@jr%a4|x`LPPp$Z8d~G^l|?K6-DYBR7F5c+Nd`S5^yw9CT}ppo^`m1 z;vlVO@>Fr6Zc*jIG~0fFwToFU_{uNDX)qZ?58t}?68m(q!tUX+ak#b}mKd@#+Db^? z`lTU}kDdWoJE9=}=_8ZEz#u(p|K7kLtU#ATT7$;h;|10}fNlq>4mh#FE9vPGrP34g zOccZc7Ve_>7Dj=>;6enDQm^>v$glWGstl)JUaRj)rHC}kszX}v*ZdZKO2>n1AUp%R z^fy2(VEZ*k3b{Ljb)Kk}lMS`cslU7U7I8Ke%KFcQ^jOGWqVMEP9Z4esnqorg>cE7a-&CY3)jQP08qxO}K#Feen^agT)Ob5wE>z<9sN2lweRqlrFO*g3G$ZyS$m71WBH zJ||wg(l{HMZ%JJ5y{4UODBKLNT@4j=D2gj_AE%Y8;EHVz=lsNDwOZgD`Rd-0jn!A! z2EaKW9iSuNtj&P4EtLn=dqW=khZlQIGa&rNV!F8>?UbdA)=8N8f@2m%g&jY^ zq0#_eyY0sMo822RJ_WhS9rH%h*v3~w%`}zl<;1NKxsxX`z)%jfDOMBF^yJgS(IW@D&$~K4rO$OjQp)w~Q!l!6hN@Gs zgN`-dWeW;#L|iX+j5sY(8zv=-1a_%AJcc~oE^|v&UnzBQt^o0+-EhNc~bgU1Za_ z19K4~T`c#kYrV|c*s(9$DT1$j#9H>MJxskyZH8m`gRNI<%O(qQy|6(JFK8+7A6IUq zk-{zV13luhpv z1>IKwJuilGu_q_YZ1p-!2B=*g;SR9%hw$G2Y);IjJM8*g;e)ZxvyT21AfdqBjRwLW ztfc2HUcSsU6v=F)cg%@}XxxuA%B;oRCqCS&N>^YPq?EiqGkD%Q4uS>qtl->bpo5sv z01U#hfWdoq0}$1KpOs1jy~~cw&iz8%vd)IRnx!)J%F%1RclXtC?9RsoRGWSlOWB8( z;)qnL>{->;Kx_I4HI>_K!pD%M$ID51ctx?}+vqretB}uNYSa92ItO#*3U{tBN%$S- z3)BH#k*#vh{~);6tOj8ul<*0G(C?!~0E89gU&^5#X@-GYq~#4GeBvbZ zNfRz86PClx4rZJyLIZr5rv({f0f@>1XxQ`eY9F8?Z*ezEVQ0PJN%YA^XfCPY9>K)5xcoT_$ zPv!=h<}zi7#$t&OskB5lsUG!GNiwECS(5pUMC!38GPl!?m$9XmjZsjLfwFeNP_v6q zQ2(TE@(|xfGW<#RwpqN@fI2XpF%TK2dc{9vUGn~tgbi?TFtzLCr2FX+yCXRO+-Cp` zjpB-f)BgvoJo@=SGhTeX|RA0SE8WKUx`>+^D5q%V=Zvo&m7g~R@=)Vi_d+nMj!l*-9LpiIqmb(B@HM!m>hvhe6> zcZo}9)p95pURdJ$gFQB9u#LrVpT|6CeHU3=e@F$y+#O~HF-vf&ygSEBNNgF{EzgC4 zdRRKr&6}Ixx8qyIia_vhzOyx(=tC(COx(d^Mb|N{dmP5T8GaTe zfi5aoY90rwKohkl7m^T}Ze7j2uayJiFN0TdKZ0!($LQfq1pX^gWu)k9)Op6!zU3A8 zec*F~da}CgCp<8ubQ9m8Bj&{hlgS3WHzF+>nkhZ_L(`Dk`JffLpG>?E zX=ZRjaeSZzt%>qV)^?q3=lD^;$_efbqhJS0rJkMWP*AlUC{F}O4zyyF=nNRi=4*b7 z==?#Nf2gm&)7Eet>H_c-5Z@xBAS-_{{YG$mgy~&3)KU-Q?dL8=kk9fqZ=002CW5ak zK{+t3HiK_zAOL?GacyhxAK|H5aeECr!tSUtP^tq$PPZ`+zRb3#zUgwejr_Edm~QRTN?p$Rj6s5 zq57hVW#;(LmgBa=hj4xJy^jwBX-JXRQA30A;Ah76OBOX;cY^Qf&j7iZ40N^Ks2z7+ z1YZY{;G_hzrZpDgnGK^drJ9cvq4Lf6-Y!481O57$F!+8LIMBL@xO6LjN5tGs!v|a- zVS)Y4)fNpn9vDL}%Fq;&*o)v+4nCBB8WB4X41(D1vILg*0DcC8^kSuJ{6XcZt1pqY zTf>*oaYPftDaR3nj#}G1(hxmuf230ov4bm%@`&t#Y0fQ^9`Sp>cJ4s7o~8;G?a0}o zXVto~3$GnX_Xuo$pRUS)Jp8MR+h6eD`wsA=>mxxL{~sR!_?XRtyFgEvI5YSt1<@ov zaEj|j#}@k+^2~hAXEOTNIZy_V2s;h?&)*$Tzshfsvr&_{4Mh<}3cgz$E_Ok!)@Zxj zlhEB)E&s4`44f#K$)M)Sg9?nN$+<~Am?U_dS39GvO>Tzbr$}77Cvr}|ljubMeXoR* z8govQXRJdXqMdr>nZ9DpR>;m-BA9#2;+9E6LVEJML5f-B+lmr|RA6}^$CH0{Ctzmf zR)*70lg~aifTMx{djxJbl48?FbGn<1%P4ZUwxZUGb++gLR6jXGW_P1x7v zp!~1`x#R12S(f&1;^qG~hFuH;Px-Vr^=uE@jy;aL1Bi>W$^qMobbTiNl>azy6LG-u;cl_?s?*`Af?ueV-CDn>l)Z zJK?Pa(EeM=sm6RUX@N#6tl(ts3Ph+zC6*EqBdY8?UMTzg?_uxcDTp>$v&@;mk?X9; z@N+m|+V=MihxdOy9wd1%%%Gq&okqd!POi4TJjsX)Z9rM8a+cRfg$KL10Q;RlLHae% zNsz)N`ZZDD`Fnr~aD-;n1j`x*nvNiVzSa3>H+$FIAH*S;2R~NTxoJYc?HKZhJ)h=w zp9}jpEv61c2}09_y9iPgAR{-356f&wGJBg0Nzy#q!_T>NI6U=u(PA*Y(KNpX+<=tT zflm(5tB`I*U8#afB|Kcbh4SBF;EQ9>e4>a|ySuzb@fSlC6a2U_T2 z*0XxWWWIUpDA&AAH0Gd#>j{HDt*-j--3EW2D_>J_Ks5FR8}r`tA=&mHe!alriNAy5 zzgZmiw+9YHKqpG)KCQHxg!uaP>x^Y+YhSXtsqLeO60Kor4L^szF_p{1z+`XN7k#kl zO0L3wcYpCEt2(2D5uw=g+`aCw(RxSwvWRx{>~)1KbO!c^vuwE|;9< zC-!iz7nD4@IIOl=5F8mR*uQPU50@i+u$B^El&Rhh^Uoq&e& zwkREUsN8DIp>lE)=lc5Ui9hn6HTL!U+5!U)aAj1Nq{6=b7J_bbPr9Jj-#X%bR z`Z7tAZ$jWfk8+_@RPQ1q2}4@fes}=`zMk#*j>uiYkP+db$jG>e2!)m-glYo#$Z>c5 zvk`YXK*<4Y(bd~4=(6YQP|-50q}=u$H!c<7a2Txd@g*51*sB=ql>51$1w^3dk$e6#KXZ6mgLUV#hWw7wSD57 za?=*tuC_?55aRu~7U|m2a}O>^2`d9S5_0QOjqGPB!K&rIO~^Q2{KnsSUEss5Bs2(+ zicHyax_~sd8DC|T2!_w{c?A(3qyj#nD&;`G7R>y$7L@Lpo@C^gkR?vfJkSn#3I%tp z$h2=kLxyc~_{K^#_c*v62M0gb3VE@4bS-qe_{Uq^1(6&uy9!c_QM;~+d!G$P@sMNO zJGO5!+{*oh(kpV*)-V3Q-o&2{Km-6X<>C}P*(lepwlp)dbXNiqGkpBbaHN44CYo(G z>E5*~8L@CS+H999ur2^4Db4zm+w8J7+<39cVJy+v@ht8?4D8m&Uj*fGM;lP{Kl0~q zY?p>8D^W3EeF@O{y`6WL1)Ia+`lBpb2ma&SYq;L_DV!|NY~f-?lwc>m=vX6aW^0w3H=in@lUhc>;*2IKA>NC-f%nIM}Ee8GT6P7Db%Uro-` zfR%ogXs5SY<5MnB^aEI|8RY&?gH+w#(L`GZ% z7%>urY9-$=XO5YwzS+CQKD_e!H!;P&O8T`wl<*pq+V^FLKe-k);=fW-vbc@$z&m!$ zpArpB>THu9dvjhwvP-J0=f<|u36y9cY;&0u>YLq6M@w{!Re;j;!9ZcTQ%TE=AhiOv zL-i;BP+sUcilM^p#M9S9&jE4~z_w|DaDzqk2B zXD-!pfVw|h7RcG3N#PUH`Dkm`1Jlw>G;0rEwyM$r7Q>)jVD$_ybtUK}+%)7OpI18! z6adAV%5E2@M;`uSIf#_XZ%Xc~Q+1H5!(A)jA2NUZm}dl8JA7%Yp1*h_@d<(a`0Q~8C0bq< zDPhA&A8|+$g0Bz5AR*FCDhV2p-qpNTnLD~|)y@14!0A$g&8v*NMq5J)uZB*{^QK(As*gaAQwpK zbpz(eA6?45hI5hb7XxZNKWEu6VByrEZxa{^FSKR3?=)+wtRFR9S%WzRKYZftR}{u7 zEoP4nJ(Uy`ViLHs0l;dwU=!g`*RTP8U3)m$?AXx{AU-)+N}5$yd$hHFR#sEvw?Xt3 z^gSq06WHyfPt$K$`!pS$ugeX*Ta&o$_D=SJ3e9qB3L$5oyzz?@Ga)0$&YL>AbpB^Q zzg*~`hCNq6nucS1jN8xGo@={Q)5aG#sO~5G;&;4Nd#_~how((Aoc>ij$X=d zS*zJw)*_%$ey>Jtx#7)DTHLgU9^vKJ(r_DCf@Bp_H|0z>5OR#Dxnkc{g45|7E_Qtn z*f`Aqi3T9kh$LKPbg1A_tlJ}F^9)}oF#S->kSe}fXa~2hR=G54!(~0SS303Q_{(}+ za``>KZw6w3({PO0_}@8n12D9EaEKkud7)=3o|nb9i8v9$a%!<(4R-MJnkRe zfPFPqyHlR|;f&k1Hq&TkrqKbniKi#kXg$z50N9+Jj_xJsZPLNSY?Xhlzsb#6UN}6A zXC}0em9_M0!Y_c@*#&uB5sDc9FgS;JUwMc+&?sd;m0^6Ac4>Qltm57%s|#7*ybzb5 z!zTa&h-;!hJNHpC1mEv{oD4W4nT3hQZ(Msk->i(e6>@K`+b6$J{RP)i9$?^FzkFd$;^LA?>)%*AwK88D1}@(-o@crt zt-*~b{exu?!URM`Zbq%r)og#Uj0*S$6 ze4+d&qo1!OVgKjmRa{1ks!wH#pWV9RI(XW4wq^j#J`k$g?Vg*Ha@Mk`a( zFYwVgJ#BP9`7!n(!V$c9gWHiIdm$_$*U|qy~Ciit*vbnh_!&`t9P~Dd8vDxL77cDD^zwNd_Ed%Oajhlhtrpy^t==P zd~`_>sy!c!{PT0+Wc(9EC4m5dQj;MMDb01?VOhPW5Y6!|>-Dwy_8&d!9qBud07-@Z zVaoPq^0aqO39AJ4R|O=k3?x0EiLsHmCWMYjpw#dgU3OXPN9})LhqhH%bo#03o^2j z;Kl?VyYGt`Qg3DWfY9uz(O0<8tOM^cJwA6*3vn;(rU{6sM{$G-P=7<3F@JF_2m2vN z(1x35AM{8a)I4!Gr3{dgw&51t9f7V$lc~W8w9PKHj;eLf?7{BZZOxE?PoF-q);R3L z(vq|qltKiQNq;}N%PzqP6Qji`sf{BqXwayC<#~3fmWS{|AV0Cf<|z+In}}yy!adBH zZaRR@QanI?jo6!w`?!e8Qw{sirTs6mB~K^NefTTw%mz^F7S|Mem6hPnB&WP(6cBUm z#P~qlh!S5YFqk}z$=R{|HZ&^{(r<;RihzjNb>v)qzAkJ$rieJQs`dgk(OM|)RR+i< ztVWgOLZ5!d??oMvHIBQ;hIcgZEl2sMPC?zVII_P`6&$}w&@74vFvGu^Md9W~Re?0J zX4FD~mvipn7AnK-WhG0+(b!(?5>{gwqM-X$8>zq%~kf3D8vko5Z<5N`BK6CI5yAV*i2K z%?{U~yl;kNQbvYsMw(_AGG;5&C-2E&FNv?60s~;>07`JXST7%IvL@q$Ja`o`Blvs* zgeoBW1UT3Y?gbX?mCgGSXJFuh-|{i=ax4Xt85v%@(CPxVCcr8I0RfnTM*>su<97k% zr>NVP@o}6zz%qOC0GNUw?6hFF$n;=LiGVu+%5i@_!nGm@RiRE?ycOvGn{!)lU6+f` zbs&s_AEyD_I6I`bwbHw7)*gU`_tkP^n8VXRu`8vs7X>s_2oXRu3jKV6G-@YaEbGry z0DCdrUJhRl0N?>N0A!KCq^P>n<0c``Jt6e!6xoy}Eu@|wwB*u&)~w0kd)M6-&Yrzo zrXGsnA1VvV@3`6o)o`o}GcOq;23IhWA8vWEoAmxvLB-?qI&HQAaIQzcr}KNyK@(Mak#X^3R-Npl=GcC9+4QonSj&f=l^V^VG`+|} z4Mp*DwB#pr(#DUoir<5rM33x?yWPi`J21QgDM6wX-0iAK=6!K!Z}aaBKd z?*UVU54MLx8E^D1e))h4waB^gce@uOf^R^cO!m)SAApi}SOPf~gEu1_j(VR!H-&Xe zNs}S4GY(i}0_U}rSFk92HVSLED3m%5kjx@E?Qp*; zA2C$=CA~V}rhOLu7$RZVT|$=y>CwRwI1sv*$vC zSAex8_=(W-@69$-8Jeq7H+uR{))K5S1^1;BF%tO${MuhPA><7|vFzk!74-V)BX(6W z*CW&}pyfY7t^bmfi4|h~bf!=)379c!UA4>mhu>qEq}Yq>1Xe??TG3=Cnwe!}hB3s^ zk=ln_u@dcP8)Jb*#>hw$qMEjy#H&J3q+S+?LUG)#m-^{dq9t zAl%Wc3_KKQL<2>b*$%96%|(nxE(uuJD)=4lIPZa+#JSBLY7liGXgorNbmym@<-BB^_aA|CH!%M0yEOn%I@(pgMWmlb;(?Ic3B z*y*Zb0G!K>{7Sy;C>V^DDZ#dW-ZXcep`4S&HmQsvG8KDRNrN+}RH_h}Cz#url5=w; zw89k3OU}1R!)n;u>u=sZ3t8P3e?&cpKKP&^(7U2p7FBF*U!dem^-aoXG<^vbb~K;+ z0wOBxp6ca3sC*Bly9FPVo_}L`0iiHkC85l|_kF#7UtQ}|yse1b2T~cD6cEB90J~_m zJNl?(B|wu&mn|iWt?|MJ*|H*XHd2<*7kk@mliQmxZ{)noCtzUZkNH-a-+-KdaWglM4r3BE zd37G-*MJilLWNVNppZbv^(&s^w0@y}pFOW5eq)$}M-S1z{2rljG{dbM9m>?ydN-L1 z)3pb%H3#vNU+|UB8P??{8wG8A^=o^cH$KkDDaqN7<3#_~iNe zqknr7)O=#Bdp;881c^wA3M!cC*=S5{Omm?(MW<#ftuj{SRUm%GhzhsfAjAm7Q%@GLSCXprRjVx(^I?WA(Wa((Z@v9N`4uG&OawF<0dTQ z_9?sA_IPNF0^6%N)aWzC{pF33snVcPic8B|=v5+8Z!*=8;|H%lF<)JT7)WJU|(O#f-iohRn1w#cVc zGOj+0=_3@OR}X(C@D6Uy>fIE^~AMr0LT2Yt7{-;lV6f(3Dz+|+T0 zRA09qUI5%&8y6pIJQ#*A*8Q zTCUbBcjfQDK^&R3bJyib@qW~BeT3ih4@-V%dRYkAd9b@#+qTN;A1V4Urjg&vzGKhR zL-bp{?HO|?7H2jBzd4grC8c{f(%MsBHDB123n1U5Z#7ki=00O;oHU26*?O-3Y|_R)j=*gWi3tmfHq+~XKI!IVA)w!E zXP+D<2W z2mY`C%#MMZ0B&8lnOfTcf5ITegh)$oE3W01OtbM+_|;JxwWDbkeOcN48N1u95f*z7ZRPC3Zf?A68FB54N!b~g`3^+mg{NNB4JxRI(N9tzQX@`(Awnz+Yp;cM;Gr_>0? zF&v)i4zgbK=da&BQ@*eeP)*xUN>J#$^WKHZ{La$-5~bJeQg!S>OncPEh8a&qqh=Wx z!#(xA_{*j+iez7e4pMXy$p!Q*P_I`#Uc+uvC2;wY3w34cI^SYpJiF2!J}Q4M9OJfR z+gx-JRjl+ikx_a9eP*Mx6(`Qof9l@bL0a-G8JwgSax$>S6Poo;3}TE}QBUN3lsXPD zUcX|2ujW&b+xW|km%5z>biR98&K3p?eI}GAB!lE=*P=>I_q=>* zvg@{2-FMZ5z?jdso_ZNP|Hz;YVXr7l9jTRIa7Iu-C*Bv0y_5zUiwQT7*S;3}AYDWq zO^F|ze{=ZG>(&J1WLDwDSKl2cMS}57g6zcBl4|NGy0<9Zd3n*Srl(g3lx!vvMr?a zJ8VmS4=*C8#)*1u0sDy<@H|pWf=-0)jw)g<140PvZEi#Fj@<{U5E&AI}~B(#n8Ml*D@EK z!4VE)J4p@}@vx|=Z)g@89VEq_gf4lPZIZ?!bXSu~#DrZ)_24|6cZhP?<=z~tP37c9g~nF)lC8qgyP%V#8+;qgwj_Ms`)8ud>BNI2 zFyyMOGWiFRXNV#SUzX&1&S#Sg0~oSa6xBNJ)QG&*v^O#27DODuK*egNt_+s-k$sSl zqM(dKXh>+=b|Z2@Q3>LvhZ{9_tOZ$c2yI^q&>}U>p*6l#A|SW4;t#NJDW}BQTDi~+ z?`6{cv+xYvJ<@jyt0IxRcud(wy8GLP=<1PtC^1nSM$goF&Jnu2E7F(b=OTG&9}Tk8 z-)HfO$Y$pJ$DmQX2Sdia5m9M&Y);}{L?2F;Ont)rdufT^)~tYJE%~WLfKf}5FsfXw zD^(Qi;I@$~3f7tW7G`zcRlV0*Fsf)0@Pe`*n>YjZE|$%aWFcpb|Fe*4rd~{*)u-U` zCWfsHYtOF4W9;o%iZd&<@rOs_S=ooFW%e(_x|39Em6VT)@NMaRyVNM(2 zvx8iTEq8u&p(j#vt+2{~Ro4#g8}py2G&0p9pG4e}7`b5{{K=pjp_ho#p8sWQV-4mF zp0N!{&$$}erbIQ#3E8$DpHKP)EncU~RdUBV<&F2Zw;zfL^apb}&GIneB34ht;W{`RyFC`aXtuL1kum2mx1O9@R zvccz%8yIUpt4(8SxqFUAb!qvR_(`9a`bM-Ziy7qoiCOV{cPbfv21)RIW3Vrxr+(E; zN{T%4ou>NndVS`jy|wkXO>9xOyylGcl^^XP1h_P_+(jzCClYQ}mdD5sg1?OX^z~mu zYIEaLVWQ|+9ph6$?Dw;70+5U(MeecR*{pKOYn~KQGgP zniD6GOuPa=Yaa?_;c-=fF|D3)c3zJ?<|wo_m(6a0z2awoBDWdNAh&G?vl7Md zV($=u7p(6E7v%xg@C(*JeFTAqX>&oXKw+(brLI?VRb*{k$eVq>F|wa6ta8Ycmo{bz6QSg)ZA*{ZlV&_Gk-hb8pXlAZU1O%sp1)QOSG-KYAC z&R;=6;7O#4toz!tV@Ma`d-ux|T?_w>@Zsl=EzdJr^0`bbKdOD$u6Ztep9p6h^+gGq za1)xW>)}^Mdt9dfc^4&rk#p z%{~H`#J>#9-qcEY!+5Jqfk`tACClumh};%Ga8z9k_`ydULeyhXCZWf?d9$OjwG(S! z^x<7F8MhWnS5<60^1rm6^kh`XIAqLECf2S>5R4A>3tJDb9Dt+D=CckoSEY$ zAQus{m?M^K#!r>x*c}c7RLgS@Mc#fnNezl658A&cHkc?|zexc0S}kPgsp^rmhed*{ zs&da4lUh5=`rx~R?$LA?%>b2l6pZ2{ZP^7Kx43Q52=i2p@Qg$iA>J_R4@BkO>?mkX zZ*M@HEC=Flns8t~9r_bGc3{h>hDeC-C|!_}1~p*_gligz;JV|!Uej5BGIh18q&(u| zQfu3CTyyMkIg+N<-B2Ib`G$qVt0394gJ=ZfBCwopi#aFu^hODUrWi(?FgbB7W%6k1 zd+e;@s}+-G@7#^!ZJ(Qw;gPFG3$}gQ3#rwTW5ZDBWO}JXztKqliD{)Z+id^OC$jP{ zcbXbw#SCU21d+*^1z$c-9i&}*7y*AJ{QvPQ*&E^x)Mr{-zUliA@0t+5_(V^ce96!8 zwc}GkvOT6}ZJK-3J_(n-!;xDFm(PF>-aQzfV9Yg&i(9pngV;!Q*9LYxP|LKpCeH{X zx2aqrdRi+hWON_`CFdz^eT(H5pJ}=pV&e-V%qQLu(%KNqH5hfLI_a1>$s{mALVQ0+ zBXkQzJhhc#4aSpDv!hX^gQ6VWJS@H@Rp^y(VU7qKdef**xNi}t^dx9$)m(7Nu*@7v z_k7+>{z84~n<&0)43PjEX^yivBt+xtj{A+9!obiRX_4kR!Tn3s4x`7O7t7vWJNgOU zgktB|wQb@2C%Haq-rnYTV1&i4=O;J2Do;qi7boQ&K9lr7RjDG`vprD*W-r&Er8#dV}9WaCBOM+1e=QJc6;ziI`Ac>72mK(#yax1gRQkZKSdr5^MGj6!KCY zem@;fwQ4KP-CgX|r;V5sw%PEWZ<|PyhYeD>i-^+Dh>_A}Bk^?A$O1kPE&+X2VIiOW zwxb6JVkB3vml$;47bDb^v)&W>Kdik4P}SYnHjGM0gGh^%fOL0>q@>af(kb1gAT8a8 zl7>TfgMf5*r*wD6yYc?t&-2bZ?>FD~%zVz7GsuYN$KGr2wbpfAYc0@36vAq|giQkT zT$=GI$7j2CXhJs5Q11}z>3!`qsJ|GcjsI4y@B#*kKk!>#@{@sqceJLSTELR;^we|4 zgI2XwhwGJ{9fIN?2HwEVTViu?)Vxx_b)UoMDVNV-Ae5r)ll^;|L@3G2%~x@hP1x}R zN};oD!R~NG1=bGujavhELcBEBls0}fHJ(86udz*-;y(}>!#zt6Qo!mzLhzH`!#5IlDlus9mx9md3>IGN*T8$?0tUEz-kp zpF`lF)6sUyAD@6dhIukh3Mv^YRQ)o+@61Dr#77zd^RfT=fRT=h)S$G8BT?&4L-tt1 z%f+d9m3O1sc+;v4c9nVeCn&k5UD;Jm435!EB(pC)^;D9_Li0imq;tM(MXXh$$INp_ z+dDgK;Uchx+1F)>zJK7gLN)d$?+ATC{MiGkaqy)LyudMviwM;lZgVEQ34!HrqEh7B z_41P*%GTBeE32s`Vn%&7zOy{OMr(VX@^d%kTE8qR*t;uUD3yP2%eYn^5oJcD9Bt*y zz3&y&o1K)rmUaz&V=z+xk;n(cyEcx<(odd#g&}#z{^TcwR1%*D%oKq>L!VMX0)Ox3 z_$=T+Dx6J7_+fe~SJ{iB>s&yhu#j$G)0}_VBl)&y9URlklTfXlJi4w-u^>r25b(vF zb4oe*dUi2%e-344&EjF5S7ObRC*YHJ9}rUxeS|2V44aSl&0L`pqoU^g_H8mGo`&n- z^)*s+^W9ERZKA%@kz`i_XyMbIjp~r#^+osW7Tx6ndOhCqUPF+CM&WJn6O*+nDd`;8QGsi z<_jwM&`pvkrbk#JH5(e#63g|tsZe*(UMF zfBq{yYyHbN9(c;l8s>{75IDp=9#Bn<@09jDEAM zrFh2DRA^wD<`M_o_;y(pS%%qx?HSq1Q z0XD`&F|QO-TukY_>{1ua7+3ny=Vg*MQTFi4{UA4^2v$TYLxLJf6Yb@WSDyXB#j2`q zJ+%g|vQ`pv0B4_dncd{j%L7Sg5&NrWq6s#7C#pSG*~ldne=fKw#^=FX2~MRc%tU(| zCskT`5|20NT}Qn9o%l~kBdeV`69!n;j|kv-go6zw!0fJVj9W7vqnV`DriR~4>+InXh|z<_CIv|8y(*f>WV`p1IA)ivea;*uC~|L8J!Rv=HFKxf}&)7)@ZYNLIIUj z;Z)`qb|!u82nWY--G**j9n+xpgR6vXRlz1eD}4WMf4fvBx2!o$gDiuvI48w332 zuiV7!s^)taT>TgA4UA@WH)9v3J?d#?ZH-Kb`8Nn0Eaqy4>sR#B^fGxI-D?&GYh7gyldPpU-rOd}!imG2|0J z8FY{KkpN&HS5)d3cqcPR_~a4(7s7ZagAPU?y&f>b9s!~Bu1)g`tnzzw%i{2$P!Lzc zDPfl)dN#;jk-bzIg;}L0#VP>%a5ZLl)W)4y*UBuTh+1X_HTvgP1S2?ZkU)!tQ~FrE zF1EfG1#LchXvJZsyqYc#cFVu5T~nh8pS@`$qYy_Mr&Fvcu+)5Wdya1IRq!J}KnjY} z7xcrhr|J=Ks?(sqwbIj@;Qgf>C=93>F01oox~I8YE`^Ugl4(5O5C;bK!SnBImW&dA z5w$k#{#`&X$-(4<96;E=f#YlW9Nn-P!F^@Qhw&Ii;$+H;x7jMfmqWC)q4xk47fivQ zaZw63*j8lq-y{i3;=)qlJv|J}yql#3=+P82$eA8QIH25Zp{9f-$6*W5hdtY2s*OMt znIoQSWi(rhYBn2N#N2|x`qTLzF2Q~Cjqx+`vffc`oKVu<gww9e||!tMi={_-FN-QV6itXMt6i6QZnKMB+axz-}LM%CFi95GXt3f zcO64^Gpj=;;Q}#&)x&oyQW!Ic^Z}e2JV47$Ouft`EnYO9ph^%9NWTFz!BWn;+>0k{(4h=VAL^x2j}6$g!b|D zZK@eOFIJ_6@Lw7&Gt25-kQ>;uOcXN~a8w_VB;IW((Pn!xSO-n$c@2a>$4npXpZ@}OGU$LyT zeaxTPq4YB>OFy!OOx6D$?F>zJeI`86Dq6MKv#rSk0Sbj?!3!xV$yi!yneRl###YVD z)LotA2dw^-X+c<%yys+L5n{nwg#i)X8Z1)K3*?~4ne8a>a$=NQXyjYltOKc5bg)Ky zYQ|2a6QjRW6qFVVIVkg5AwDJGer#QgG}W-ZJbZ8+42YDI3n4t_F7Lv*nloV*7LbeE zA}4->B};NPNLMDhdpcH=R{yR}TbU2p22u89HdPVE@B6CMi(T@?h9C9@nupFB5C^IROqJU{i6>3xB>f|H%pV;^FWlH-_^B?Vbz| zW9_1$Z`!r`bP3(=f{$9=i!|RAJFtmjP$zQOP6N{io64V{`8q@IV0dg!UUWBCLjz!o zo7AY3U?R;U3o^bD2Ftw^J`4MkGH%0Q0%oJTD?A1LV^pXjROpu)4Gs;6O3Xy`Ju&ZplhDA*{nw6F{GQ=A z3iSGAeJdD5vejLp8=jH3EYF%TnnYUkaZ8U&eMu)sZE~4exypL9Wy*Y)%B-I~J~ZKAo7 z8ePrY$RM+PLw9{jWGA-BU<&nBSM)V^g3a~>q(wYT#uOMbp#p+-TUIBKGHi(rFd}QQ zSS@5^*ugvfeyyfGNG^Y@8Qv>cjiRK20;+->gdX@qum(;xdnb zF53U_5R8tF1_vjiHs9RcxM7Ubad1>+X1*MtvJFZwAR;>gkP%sQwkZ*C3~^_0X=`cS zrv=i2lwua|?cY{#IT%IIlc|#imoLFaqEihOVkpEjSfA37O}c`}=5>yQ&3Iprlb@HV1Hi*QHj0<}o>!cn zw{4*{2f%k-q7A7@K7zX^PM}qRMAvV8$}CaIUC4+{-cOs#Yto-0_g`5p4}p~9+B7k2vb62PjL|5yjAI!mX>zh+ZOP+?h7T-A|lEUFWs9OroiYEf1M9C3w_1yd3nfu zN(50@C+Vk>f&o|<%fY*Qw!5RC*oq)vVPd`Xk} z>?-u?otsi3p)XfKLA=mkS;*}y?WI=#=!&`=9^+F~a?v!a5yeW0(CKQnpIIUbI&pa! zA(wKJPyN0oK^Vs=3*yptekyT1oCg6f2cWu9<;gMCu>Mv9z1OBoprj9658wr$E=Mtq zMb*xa?)y!Ky6b&aEkhkXAn{*c*8uN&oh~(Kv%{Ug`r!ZY4PqmhR`>^$HzG2^=XW3eCQ&QIFXYmtOcaFBex!_W zCbBVWpbc}HLSGteOt&cMTuk0yez;0r(EW_)DiV~ljQZm+vb0+pDLvw-9s>9p3|LZb z3|JdDQ?M?PP<+fqlO>d1@5A{rc_r40)a&(7Uj*&v@FHuS_b*dDsvhcx&eMMEg-N;U z3?$XJ&QQ&bc;M9C8<>_oDs^np&mMDcPnPr+T@$8-g6O0I^KN$n5-CS$!K)bgemoQa zXCLI9Pwq}{_1K1|6oITq=X;r+JodFxKJimYSTwFtc;cVg2<(pnB9J@wtC>O*=3e)X zfvA9GS$?g@PE_ku)^JCtBK58_AA%M!{ ztMnW`)Eo-*)md4V2EX-6r)chNoGz4N{mUFJ4Gqat^TovI=;w&aPrS7%hf0j{B=-3!6Loluq1rPj`t(H>UicT z*jLzXJ!xLv-qL9~W*(D>9pcIZ>`X(A{wZHi6MwR6F8RjDc>pT%vUWJ~lK`invCMC* zD&aVzi-=a_F}&ZCF7Z!f8-Yp<>70M#QewZbJ`>cbX=D(?EJY;j9t0%XF%4>^B;cq!7y*2y785( zvSlWYy8nAA_02-xO)dXTckdjNG)}&B&i6ePB2o@qQN+SD`k#nMG8oAYt%}2;+1*Z< zLfOPv)0xzH5RV%E^A4Y$_~`*CVnY9)j#H;dyuhwchJaT3=poe4X}litI{#)%?@lfb zqK%5JJ)M_b2nW%u5x$SMYP`*<`XPKQRAEhT;zljfd%Y| zeO_9^j_>XxqbuWB>YE1UuYRsv9;^#6LwK&g`4V%%Hwz5O#2F3@z4+rz^2k`y*D=+& zqbg{GrR8B)>E>IB@oVa6EXL=Z867Ys1>UMi>7=UAbX{GJ&FwJW;S`h|C%5PZRo`RY zraxg3k~7H_dvqY5-N$zuFBYPpSb4hH1tZvj!r_(XK(&Vx4C0|AXL!*}jF0)mRhbx3 zv(MkrbMhn*JRJZBIkW6vx=u7*)>Xs1R6=B=l`bV+Xb>7Q29X|l&r9dAdb<8%Rk~Q= zK;3E^s2CxS*5S2OX(~U?R^^`|Y#+Xca`CdMJucbNo6D{{sv${Jx|zWIRicTd8bMlF zI7N(r=nA0+UxMmRAWF&U20UHYSwdn`jg{Ipm4@yglSb;hL&#h?@%Y`P=^Q1gCV^@k zV-g;YEXwTnF84ul)TBo)8(#kO?W*7U3k8mYQ?GVhI1A6{$_>JnuW##jdYAl!?c6$P zLLZis)ibh;yT(S2-fFFUs)HR3hWANm*!Bj&Os&ZQSQPJX4>)J{FKcvluEm{@(cO2F z>)!da=rXa%5H%Edw1yNUv)^-LBU_3r_K@0a1XkI6ns3}l`buJtDGPz`;sOFuk;k=m zc?H(mt4TsJ?kzh-zP)HVYnfwVjahb8Yl8Y6#;>cYth(pc*$^f@;-6w4KSE%VsM~`% zivFX!L?IF_9yM|40+FLOim!4sWmLsdvQHNcy#Y0js|U`y;$?TN$>+Lv7oq1!dnM6F z4H;_xBu>vsq*}%EP34QvejI2Z((2>YT`hepwGez}9eV&!;nR zwvU8e?QO|5G9kZy#cH5MNDv)Sm<3*0sfoVDgqn-={46dPBSYvk^zNF&I02caOaCBH z%Z9GD2SXwqtw(`x=N@F1?>7c+r56i2GDFMLkR6>j80hz1n2R3{dhVM6O22f>-ZXBG zF)l4E?Eby^TWw+O&W}@~L6+);!3SrHg}lHdejPZKfjw{y>dE=@vF6jZAL#yA zaj8Ix2>XmoMvMA})A*$do$I;XUAbWE;sIOPIupCj!G#E4wDb^+TA703+9O|u57%UN zp89a>FX9j=uTUnb@`i`pd=d$2^l&xk1!NakBR?fJtDcfiUslw!9r-?VvFG(lG zc(ebF^edb+*)?=lga%`UPhZeqM!SlPzkfpyC;W=76XRp*flJ@7EqB;(!*o;~5sU>j zgnXmvXFD8%Gj&$E^adYX&d@hj1l0R%SAU|ma+F!!X0zJzU7Q&*Y7qU|GyYH# zSTG*WA5+E=txoKb+iU>0+97?p%i4_;v@wLyw+nMoaDy-#_Q0a!4IKTDg25|78TdI41Im?89E_yh#hH9`Ciae(>HitO``s6<-S;9@p&MuRYhm zl4onW=t&KGN{3)vB#BM(-#r?#Ipr22sy7Vq+YZPgPYsOjK@J z|61-16Uc@T9{90!tn|>v<^z(0ETYWJB10117d&2#lX1-D--mN)jg&=>@jY2j!@?Y! zV@1QsyizL5^Qn*DvVYPNG`C210IzAt&~0r~R?HLmeCqfQE0i*;@m_fhEu2P?`J+9FrER=W{q7^Ck;_Nr{ zb*8CLW;^(cehZ45tg}2bMWzC-ECN*v(}DMPm|{SiJO%e6GFeJSafUs zjrZYx@IK2Cv08Um8NNDqTM0_vnaQpso*8t@#>5DN1v7pL%#DNNJR@UJOgxp}<#;WI zR(NeK=8`Ph*Y|87xt>_S9aJd)P_P?Fa-X8RUA#Imx29}9pA_#7mmFdsT*9chcnqgNp_rnUm6g4{&h9QQ_%KFNh z z+!GTez_w0Dgkg(u+lAS<^RADc(=KeG(BqoMVdwQtI8$btfwx&#BtH%F-|*v|#HW6B z_1M+bRm<6`ljSz5{e5k`Qp7tv;#4-C>w*&NA|D@Q9^xoaySckNcY4})dMeGxs3Q&6 zEe?W}3OH4EWRxU_hx-iuPT7HEjVj~8rr}}Zt*wMjvxNoE%1Tr^oEsnX8NsVnvfy?< zI}q4F%^Wv}mUDAe?VUb-DlL)lA22AL()Fj5qw_s)HgrsKH0g2-kitq_AJs&CqkMmxLNas za9b?W2zqhh-7*%Vkl20Y{2{y&K(t#LeY&Z5!1e@F6-_>{Y;qD?F+#oEM5VoQ0C`J> z_NO9?C;m)2WWHR#Ev|o%r%D?L#9iF^Ls{S80MXaVfT=Z#?8c>7kMTrbd+HzDtlqLA z*3t@eNtCzFf>4`goq?4l2oXr?+PhW2`~1d=48-ye+2o}`l6J1&k5TqJ(MP=emP(X8 zk(Da7UGKzM2%NLXNO=T=;{DmlldBCK1Ecl6WDUptxg1Wb&;p(2;g%MBH6hUM1sfaN z?eegc*J+=aZ)#(um7cM<0SvyozaviNvLR6Jx3Jj7YkjuP2fhJOCyL_GGF!x_U0Iq)@_ za`w2IMH^rck+|5tqkRFen$S=sVPVdKLd#{@>M!%dV`D$Q$ZKo694xc}OLBfWS-kk& zZf@Q~OS6X8ahCwU*6sQ<;qdV7Z_7NyJZOTy|HWGGB*row4UMDyDgJRl6_~*O|2bp> z3ahO@IkdRe+27c{N+YexWO0D7pxEusVp=^CUQj@u9neg*J7*)AvFBft5mwwnDZb3% zPu>cN82pI(_N~ewU;Z0H!6Wf$RMed7vhHIAjV%l~V2sauz015J$@DR>vI7p^txNwhn%F^jaC~LM8$N zMEJW{LD;2CY8ua22{p8nYBiSnBG;yQ#R>KU%)~@}a|E4|lYftmJFFOkYa241h|RODU{Wf=t#E zLqj3ozZ^LeYl-Jj*$PK1ZNX5p+sQ?q%*;EAv7CfD{bwF%=vfdR- zuaS|i=kNE$-oC(FsT_=;G&1ZzIzJ~Q@`z1JDs|ku2G@g(On*WGH#)IEX-SE8v*(|c z_Cj#&Yz*pbZmNdt>$UmGkdt44v5Skfb{D|jj*ojhZd}jz`M*x&sM2xNAr?fWO+rW? zVRa8&1{ClhuX!EIsxO{*JYW9=HS5qT#au=aXL)AcZ|#l$GD7rSq32X2oQwc3Or`sr zfh8PQucY+;^}qS(Dq8IaLZ}>_Y|z)(r(hmX9}Ek1_{n=2Vn?3BzVZ@-54FA}RcVKZ z@5~gF_~#~LBBW_Uo3O>bPH*7!u?iV=Dodp8DdtT~(Iq5Y=3%{mUcRZuZALus(n3Bs zjV@r+2~DXD1OOvQ=QpAXeSNgX7g0!FsBUrQ1id~FME`PgB|mIDPkl4vlPER4A4(^V z#!248(Wj%J;-6P&*lxFBB;s48^!tnIY6?+?;ZM#4s(qKE5*sYz+3xMPk#ZVLJBbP3 zt<+zZRf%C*1y*OtvJ2lVy@=4Lxln7ndjRT|ZQ_vG&X?F19$I#4(Ni`I&{AI8;f0kH z+zyVS3L&wZ>;ksG&`@|fq{Y1W%VJZtLAN|kFh7?wwk+7h_c(DOp#mCZ2Gr>gLj!}1 z;OlDucd7`uU&7+VGx4(7*&YLb-y$^#yohEE)AM{IM8t0EJ6aV1b2GE81HpPLoxvs# zeyKPHLEBZX;C4qx$NZwAd9brxUGs$+PCx56!9V&k?@xy_+uC{!JP;QYe`VYNn$YYu z^rutq*CPt+o{7a2eGe}YS zKVrdbiLnn>`2wYHJ#OvSo(`~u!-sc!YZB%u5mI{~D(UGdzYn?t9N}|s^_gek*ajO# zF`+UQU|Q|Rk2{6M#aYG0Yx|}PReZK8a$=4toODHL^BT<*%N=d<_Mt1LsHh>U`-ULf zg;)&+sD#gRE1vWxltuWo27azSmB@z)QwwRga6)M3^(N`6XTntOr!%gJ(!0MQvs|hK{Mie#lVm<6flgUesggk4z0!lj@CJU1dY-M2mHRM=0jttiD@R`UFr< z*_2)JVDSL6*o1_WOVC3fu>rcX(CBY%*oP*gswb>iE)`ew3#w*e!Kdlf8*Axyan9#_ z$VEqY9L%`?if`)C5?EP#^Huz>Zw6yx`givDpXM7$;NIOC^YU_*s9H!#4P=OCfG97X z2r^r>_Yz41BMW7Z)V2s;lSjX!4;=N{TDZ-Kl}sDJyv5+V=4WRT0rv1W>svBknB?YR z2^;5Yf+v9Sb$Voc$IUcg{;8xPPG6c$anBy1dpaL?ueJgwYN64ZO)%ScI6#6LJSB3N!=_;E|J zdev`^UkAi%qWp{CT_BHLyZfYH%S8e0GensL6sSD=_HrCWU=n562_XCo49mdg-95jD zg*_OjYRSpU3WK%sH?p*BtgPHyZtH|3&JJC_6l1ruwr&Dfu#8M{NXXr6Meyq7TANUEO(!>Mj_H`dYvpMTqnf z*YdOI6R9$jv;-wZ|9Ie^C!7S-XmUE_0FOFA`xiI{x{lgmnHdcCS-Bv;F>s?QCXIwV z=^Cl+N-=L6!7E5r1f+vW=l!Okxe+OH{}8{yhD+0>%;lL}u==d=+TdBOd%63rQg3xL zTRTNvdOjE#60X;rNiLzH(j)LuT87;{lRIAjn)i(B4Q;&qB0(|~f9A=}Qc1#iD_odY zzT2foU)lKUyo5Tss2^qPxBEFD0i@?5rxCo*0bqw_?UOHtTbR2qQuNn%2gjnDHeXn} zt7if^EP&e>)yhsmSE0kt1{PHm>5x*@-M+r0dMDz!CJ(EPf%&4M{Q$~#y;5c}~ zN89dxTfkuZWgSR&;Pm^0GQ3V~)U@;iyuLbY#C|`ukRu}c z`Loea#E$8t9x~0xunza>D3|W>u*4<{8(l0zco!L5?~OsCokE-vA8)wcdLjuS=JC>( z?@ZvXPkCeIvZ7Hj!CUF4a}x1aSdFj2tI+bzGx2ZSt72VQ|8AB`yX)k{$FwE}$o`>*SZCYhIfG9fTyrwv?>iWl9>@;($#owHy{&FO z42P@3a76_v)G@=T@!;0lPG*`*@z2mPGY9MIpHA=ffV#&@}%2SIY zXhm@c!50Ar;zW#twIuxa-QCynZYoF85TCzwRwE|5k=D+Ni$O^lYpaK`dp+z<7j)ci zg_fGpPFwW_6R1tK?L{`ljNiv~nNIt5^#nF?Q385o1L9J^{a{!3+AT+swKB7_`??5#Pg`ukSE5zn6j2I?@}O`%LJ&yGsJO{pOAp+M|#?|pZI(63{xU* z7paAuWcx2Qj@fzzUe3WHtbuL*7`F@Bmi8SG;EB6BCrITL8mX}%uv+3ieXGLm3C$OL>+C(aCu65S;U7gx6M#wqQa0O+#0t{Os??XL zd2nA@^SH7IpM_`HMbJ8F)SfxViEBmrHVtUpu;uw^YPVw*bGeOQpZfbII#Kf025>q< z_i!DOvdFUb-ot>IsTfZwW?g}#4!QZ7HD}|y*C+hQus1-&KkE1pz$d!{`>~%gDwnc1 zPN@#k7y9a|%n=nl!(HQt6FDG}PTB|A=gb1hzse~fT1$Ln#>6;Hg%2$SsR`tfVT|Q% zBst+pq&CP@_V3}&L2^+f#+knz zEyKKPkscg2qRE0}t;Zfo(%=dZ;TCi8+E|L&_{M|@QfeAip>9LuZDnY($)UtR^OWxj z&{T?ikECnxl;DPK_Sk&*KwF(ZT1UDhJ-hQPcS{JBYqafg{p^60ac+~+@_Ex9m8h`U zlO<^y*{u#3gDuU~p5#4ack^1AW$9f?87OIeP3fN~t-V($VM#K04N7x%Y*Z9&MEKw0 z!bCro6eiR*MFj``e zk6KtDlRVGnaHd;)3w8UE>=V648h8f{Fr#dW{nnm>Lkw*C1p~ zLc*s56^#P_XZL`RFC%_Sv!3#7nK&>5nJdv>P(Y2m=)xQcf|y($LpHl*IMJ(+BF|4p z$4XL-Ot433P1FWprK1Les&|8k6HSO3K7D%`5qWrAT2O#!f1!BaVpd@zRx@l@kpOTi z4A=xNE(*&zCGOj|54RcK`HO%OWT|tN-X$V^Zab)T+{i*+vf1#(heD;j| z1v_PsbT^Gw#HL??R&OB$9}mye)U^3xaPl<7Qj{;}fvS*fL3XhUu+j%;|2seU|7_Hp zlYUvus>N)N%AL9QsZyLl@~p{cXO&Ar7K@229K$@<9>OOhKdn4X>mC{;H9$ttAMFre zw0<3{3{OBX)Q2%!mmR)+oxps=kg|Yt6P6h!Q_*x;xOH0@nLY6loe_DetSBWrr789@ zBPT2CE?b;PEBo8B`QlS=u3M)1lDGchOl}o|b#)Liv6;Q-QC$4m$aGGB{F)!N;{>0eKl$niv)RD-X5V!K~jXD=kZ0X6ncW18t)0JI2tPVEp zHrC$6YK~|U1bIKp5WyKFdF~22>D`|IboyrT;eN9D{_G*|JT7h$#gJP^BZ|lW2{6HvE`$tLd0E88Xe`&69In)2tFp9KP^Iu74slg^?eIn&Xe@BV` z7WOQ9+vvJ6>%%Z&Ld($76yBVxd}&DnI{Mz>yP28(QlXYA2;|4o$NCGEW5z|AB6Ih0 zybzLav00d%gE%50v)WBc=f_IHmpI;m6ZJYV+Ce@al$*%jvY6+G(|v>S%V#WJ@2ksY3ostQ9iu1vBvqj4;bJccWhMB zKr&_*v(Xk8ccMrKm&etgbYUu6jaaexgdJgw)8+Hu3b;YBbYWahl@$(ZB5is{n>DYE zv=CUQ33j>!K#jR^F`mvd$oI(2I1%QJ4L=!p?1q8(Q9(#)gmQ_l`+NGU|EfYl$h`hd zcC~9z`kbrxz0^P*Oj*(rr4?oEhbW`2yoA?`o>-pj6V|5|=XV>GH>E3>5c1JtM2 z>l+<6I*e}_E-sGB-ycW7`lNj}9)#fQZ7g+-3=fYDe;!zw%`$Z1^ZdlgG3>f;rak#B z^T_K>IjFp35rUbsc8uJq+8?8>?&+XZCw5o3+w|21=Y3WO*W==51ti>^;M>i)+;$YW zO-ESDa}1iPC-VovUYF%A;GZSx5a`@eHZW;6*m;dqHzPIQn+{Kj(9ZR?S(z6t4&I&P z+6=@o?sRHbHeG66-Vp~EhrZ-<)&}s<_4rgeqnD=r!_Lf&4m$@uqS{p7Vhz7bn>b?d zBD#}3M{;|0zSc|mS-eP<-NfV_qPWc$*gFBS~- zTdA#Bt6bKL$56=6ulR8T1rwhtT?-BmclR8JtryuWtn=!KoLE&jrEC~HgH56$7j^~O zUmp29_$S7Bs<~bN#s^}aYyjwp9F)Zg{#s5~v08vk(u?@z*yxb5pTwUt9i>0qS z#K`55wz(#em0j5BM&afUOonAI;4(Kubq8DedLSeZFar(SzuFJ{RTxngMy#XH z{?!6Z#yRZRoHaH5NWO{EzOA~vKbhIP89}?)@Ukt;tmL1Y=`d+&U80~Ro1Gz_w36W) zNnLcK;iOtDPv=?MOlas_oM?8Z(7psRbJumr{gc#o;hTM@=DV?`#8;p2Wr znLjIi?Tl3F%RR3&$or<&+%m7#zs{#bSmDb6aJGc=nW!z*cbO&<^e{;u z+NtO9zS1QJ>(v4on3Mvlg|trULKavOOK76TCODpbq_wQ6DYdi+`4Q62%l6r8Xd~`!Q2gk@;p{i< z(hzs~rDFq$tgwD*Lak?;-hF7J>CH`9XewjL%4TyjnL9X{=O*lB0%#MHx6cZOaaN^3 zAyCsvc@XiL3oeBkf-5)Gp^VmEC5pBV1$C;7G_9HvYj#m+L~>SBR$ftH={M}z)-ZFz zm5s<3`$@kz%SxFp9FORw)~aLt>9L)$-*EM#g{pocsxM_O%pt!S^S3MBqpodgcFyHB z_~5JHDzcrXWa#83_2n#jj_>2qp#;!3yl{<;)1KD2_>1ngJv~|>)hqHM()$S0I z3@Ip`Jie-bv1eh2O)_lFk}&-D@(mJ6KCJ>=)<~zE3d550GgFuZq^|zFUBUC435rGm zT%B%yWOkCWS!4g*%C2ny`YPxxDX#Ff7SLba4kv<`Z@P3nl{9{oJ zzW*f0{nd2e`iqB|xemdialQla6UYy*ft~?ZYf*)3j6Mmkh_LxBc)#2>xKDmgwa+(wgML zJn;#(TUVERm7Ly#vwk=GOvl^z3+?p~9;^9{uav)Z&CCc1u8dz+G+bh7+fQ&XKpGnb z9rud-s06Rq;(pT7GRr&?nj{B(>Z}y^1q%OXWx}}GXEaNREJxV)>i?~k1@buJ5U@9^ zcJP-}W6zg=S8v%^`)fv1l9n(|dLW4-_p zgF(V30bYYP1?SaUrPA+Q#((P<4*lBsj5&AT^Qj@MN8;5j)!QA_FAj1w$#OBzfj&`y znCgzoD7{NwcAM=XCbqmiDZi4F`|UBsm2b+RAfCwD+gVIEU(VFR>Qp6Vo0}E_r>+;Z zJO7V#JMv224#koVq8+GIGPle>t>P54R^s*A7fTpGm@T7NTU3+CRDLIn`zCnJc*pmA z)w@%^&DsOJ%?<-wA*Ki_V#RsE>KeEYpI8%jV1&X)cR|b#3!u-%NJUmTs(cu^%VOl6 zcXA4xZo-7fM6qdTy&o0iI=d!Dc)EgH3|QC_I?yJleKdSjl2{$lBDdf0lxLdU`TY^B z2nmLM33YurhVA8AY^hnXxg~d$&*?fy{qeev^-;zAO@9Prk)R(!#AS8!s}3P7wkKZ+ zWPIw_mZXU^ei(iwc=kPA{8s{5Nu<%gjd?zFM5c3ttqF>hFW_G)z!Q95_{89Syg^=O zR$c^G+vR{{eU_S$H80qjrQb7?aqQQ3tq6ndak@qGm#%`zbmYo0bu2bjE1NoXpDtJH zuYc?w4X!$s5CuT+DRZ zzZ@Jr<}cxn%!=by9@cecwAm`0_J_1<;_zb<(1wM8fR;`?RDV~RoL4G4G*-zPr2xWQ zSs6cLm6za}-EnP1SE}6p@<3($PrT@^R^)y6`qH}m25gglUtf4^+2NWJDN>0dX|SlWoDb|4j94G{5aZ*nT0eUu9fh(`L#N{ttY_vzot{Wo<6`56F=C&Vo? ze>Px%6{Cm#F7~NtES;SUYSnt8&qG8uPg83J!+J?k0_9J5XGiv5$1mDG-UB7JTex>{-_0joL z{nK40K*Hb!8ys{Q3nusIDqIPPD@xQ>k{9MIIzS>1U|Zf10hs@~43TuHDjs0_Wj3Vs z981z1pQu6KJ?f9ojT20nL+i@bEi#ktU$6e!q#pOB&m&lsF?6IowqVLwttUidu)9g? z)fnrYl~4Qbz>nv(>Kq+oXOrO7I}(7MTq<}wefuZ1|B(L4q1QIcWENKyDhCgyie~;ofu*R|gop|iv^Z&;hv)i1CwyZOH zpb}1@e2dY}ERB8g=M0{cFt$Utkp^lM$ok`fZ|TA|Zt$2-b_GSBUIsNKN?Y{Dbb0?i zfRf7TUxW9vwezF<4uNy|v3DOhK+gXFPp>9n9_rpwP}pyfxK-;0$xtc}3!@Ue%-&wh zk3|^7)x6Www$u+N9{gdM9T#=bXm4n*oKjt#N-^1{d9+M=L))%F*Dr%H9h{e8X<=;G zdl9@)W2AiZT1G3m#L#;Rov>{-9|&0X$e)qLs$8iU^u?#{#Sjx$*?aa~i#9-CwcjO- zJjLv?c+GjV!VDUcDX42q^KnsmkQPAbi?}~>S_NCTgu1lTu8^H5V9{dfuR}_?m1EJi z9C}%C3MF+av2g}oOzeYPv&?-T+maV)!C9!Lm5;0XS#>|Md7GdyxPu^UdrM7RJn7z#!)7Ku|bJ`Df7? z2uUgvVFUIlOeI-vjs*ycHqQrDK7X!FOiWBji1rFJC{?v4l9KABM(t5-86U^4LV1`R zA6Lp=7ojmXH?Oa)O@KfkiHR9EESyxIV*_kp_FHFMgEW=`zgOhv=QlM8bO_vb=`zjD z&9SkwXT_2wpuo4auAHr@h%Eff%gX~FQ&sieKb@qp4e>8>(Y8df93ep$ITSLJ2$N*` z{0WR2W*4n=TJcLA**LZ|H;!t1P3d<7dwIg1u_gv(lUS5x?v-bi z!wSj~Y77RfuN%QDQ+oy!Rzn&MK85e))EZV|KhKh$9spb)|Jy6`(BYZ>az;(Y`YV%r z75!jYov!IIYyo?#feWwaAPW%m`gnD$)Z4N5AqW<|rRp599mo)@X@cd*Mu&#R#*Jh> zjVWa9)Pe)vP5gZ&TotK&5|IJlsT zfT|Lsegee}!ij=}>&26y{v2sQYIAUK;NakxnVTCM8KvJy0z$5=RvP=guy7oMmb!)p zA+caP{%?`@uKf`9FJHdM6AevHE|z@u$=iB)VJIptUaVC=F{OID0TaQQn~|ZQso7vM zoKAhlm8boo|IOcymU-dWJ#StFBRRkjJP5;BXOm*U7>JUja^89&RX*rE2R;7n!L@=V zl${|UhRp4H7{m&y$c@Ax7HyLcVu}QYRa&}>;TDb+3)jWZniegV)e}uTRLy{e5EWE* zr=%g88_1X{Ga<2NOmfRjSaaZ%NM=m6WA6S)CA>7WXm8Stzm<`whynoejOiL18zD0TavWiOf^e zcYcelTB_N(^ltY)TFU9Y`&D#qnaQ1aezDe-F)~%dn>}DU5%c<;=l9NAtBV`go`hVd zC+jhjVZ;xWZXy*Yp}AHP6`r#hF~a&%p0`%B@wsRI&B$nT-{3$?RO4X}%ny&8`4+H` z$Bs3aKcu}U-m$-W3d4@}>P0Y&ar@`}AiIMg2mie({Ow;-gHv_tj($8(V#PqGKmqYv z1TP>Pcx(}Pb2bf;?Qq@CHn@MS;!ZL;;~f?@2vy2|^ME+r+WKC6qtHdaMNnt61w?kX zT(3^~MU9M%l$DD&@;4!uTj^d+OFV}`RGgfg&z?O~P*8Ala|2%(8ynY*_4muDT%5^b zl6i=Vh>T4J8~bb)=jP_d(5is{sx@K#!99)krybX;(5x&9|280}TD8t(3^FdC2BtO+ zE;4Lv@I{w8YX#A14GSys?%v)oKba}K&u3%foQw<~<^CaZ2W#uEz5}4eH28cDjoX7Y z4A`{AxY*d(#6%5UU0ru~zUw{dD|k@%13vP-@R6d$ZzZySt}*gf%_^QHPS7b~wGfr7 zS4!5;5vB~KWTA+l<970U_rtdnzSH=$4t4RlA0jR5=yPW%2`e5D^Rkcux+>IVf+57| zY01uBS*Hzm|4{b<6!FG8ZvH_;)%`Js%dZN-}wAw$;M;XHW32XMIjdqX<1$5}EsJGYn z)%44ATHWn^PO5CpjeDz&1g%EX{{+4sDAGI+K~Q=W?s!_xjA48J`P>eqf=m68du~x6 zo*dLkbgL0uoIdLp9IE{bY_#8~uBiv-h>T0i$tmbOoQ2>3_#NkAF8u4e^TV=|3XXsf zCn0nkmwwQB$#Vm7^^=*mrCE8I3x-x^enxS=ImQw$5w2P|o%5 zOFk9?!$YOzsL%e1ppzFVRNDb#9yj8zeCPGIzs>b9fj`{wF|!4c;eSbD*lw_?>OMyu4tR&(6VvUP>^#j;?MQP?DpgD&FEj1<(&4&L0Ue z!L^^CG=Mx0!Z7%~ox&ovS`Na_p}{dh(>x=6HT#VWk!t=Q_5gSCvD@$*D3C z9UH4=W3wBAN&coxuhxD^5J-G~EEsDBE@wMiX|nP?xc1S{YYTo_`sd}N$mpC;#;Mq7 z^I@|PeGQJ>A5?``pAeqWl$yRuWe#{E{UkpuEI67b>lp*;1g<1LfkgK!8EFFai)cFu zTm$h=$+SntBn#IU{v?v9G;Sm5=|XP4^*#r~>m&U2SJx>iDOEGX2@2<@r|3_gesA!v zc{xK-75z2sDnj{A0$kl>af%occqlbLm8@1od-a3or_75{`O z9HiK1xPRJ8*i(@28DLGPn1br0hy!El@hHchKYJp@G&i1qcUJ$UQwWzyJ!*cEZ0%~E zIr4r3-cU(4ZZ>&jmcOGvpem5ow@cOA5x)7!&twY{7Ne$ZDi6o(*l+_jJ1Z{-%j;mi zB>Se?%aA&6Q>B%bM`uOnI`enmuFr3&hN%&EslABP9iM(SqGy-VtI_Oo7(YMK4-6=uBw}< za+|6($m5_J#SM$a4^u z4^FJ^?mf6uQ)0rFmVae*hhqmcGW2W8SJwnAY6_%Cyt(A!Gcs+RwJX&hD)_L18ld|8 zw}If*0{L1Dv*z&2j+K+djlT1lF`5IQsFu4ppbM z;`RM{`<&BzbQ*jv6Kd|YbCU9snr{s9OeQHTzWVc}$!5g&Qy>mvDD(00@ual8?L_FY z^zpd|w92=RN2w8si9}Jdh=^a$&d-B`f6s*2s~U zhrimbr&+jOKdne*U}Utmv~)}%N>Iojx4gOzK|-KqX8xn{0Xxss-X73}WuR2!_8e^8^sis-?Ch#4_k!nZtm0v(9Z&1_j(-oD+wA_JqL9D=yR5R3idShwt%M3N~8b!Ur7i5&mOmY$KzL5vgII#Spp4wk%sH>-MAWeWlfN4 zeTa``8I$%M)vP>jFz=7B)(Np9TwfDx4hiws+j2RB31cGj#<2I~bu3FSw58bBFICn? zKl-6SN)pC9QcYn~^3>Zs4iKm{3-{T#?xtskbMw@v7`vtghx)lKPX4z3nVzc!#iwV; zvf;3;MA+wyPgfL_Xb!B`9SI7FH*rYW?F52WJZgR=4WBT~*e2d-41-M*pA?g55;+o| z5T9HxZdaFb;;e6{Vhls%EuGEV7}>>)R9dH)vHImRLXzy*ZB)b9`!}n!l>|LgNDvoPO7KdrnQaH z@jkhPm7+Dqud1-?r4RbM_H)`*(8Q zE7Y?tp~ju)(QmvA<$h3%2~8o(wmj|N!3j`GVkqOb9byyc=S*gX)vZo* z+73%lV=p=8TlsUCY3;J!ObR1(KtnSxagK|isTp$_Lq0m&n%lJ0Z?(~G>!Y>n>fX)- zq!dWCkmuvX_YB_aW%obh%j7o=PF`LP%&qV9XI$}P;%mvF^MXoZ@7+D-)j}ty$=Qe@ zMuh1zqqDeN{PfNeZ#qi|qni$lA|F32y(k;x(5ZDAWW(1mPq6y(?K{IMv2yo7gh0oO z)O0OK#9VaR&m#{*BQ`{Dr=xoQ9$LkJOXu3r?x^_)Q#z?MdooL4`m2!?Lq0Fq2EWZY z{IqR3PyUkEGC_4wV3}Fr=lpJhfz<6!ZU#ycOd`$3EMn{LF2r8A|jn`OIWNB*pEJ3hRs++dZNW@6#>dplP zA>F}=U=U+tJzPv?S@%d0defoaG29~4h%RkrKpa*hfVfiqNCNU2%Gw5ZD{)S2FASr9 z;9G<#oG@{W3R&m44kJa#MyECz9Td51K*VJFche-yBMl2D4%G;DrIs(_uJ zN{jmJ89lFt`x!`M@v zf8aJqrCb~y*ZpHXl66C%>x6IF~{M%qN}d`8u4<(gOGKbOShTKr;+q%_ip zotLaMp&Q)FN($361p-2br|9@$(joK;&%*zZ_BovJh6^{)KVQ1&EZyhSb7eHw`Py9F z*2sFaY4&*nauL~S*_!8GV%Vv?35>dvhtdy`p z*l)d~X+`Q}i$g0fDIIWEuiR;FE?@2J7d2a5rOPfsL>r6TRG8L!_QGqsikR9qx7c#0 z&lmmFzl1adp#)0uG=p-{jl}&m0x}X3jdf=YQlH0qIxOj-mK?6Ge6H-gfS4j`C?QWe zJV=P6z;J<0jLU5SX*ZR!{_FUvz~P1GWUu|^$>V)KxyNfp7mU4<6d*{_(m|P-#_sO! z-rg;Nfrxd8X7AtEWM*b&XRl;N1XBvTkNx^3Mnglx%p9hWkB1smre6=H#v!Ai94<8z z>)VL&^1dJAYdIP^E+MUZ&{kEA0q<>UYO1Vsl#}brbYWjxTeIRN)0wdyt2uH)s832F zuFK6YEM&rTySlnUMMuBAxuJSXwYDFl=gOhL4Zm*#zBVV8B5&F)^71zn%w|*?{@lzqht5%*?u! zF$3`CW@o{z{Z{11RK zubS7V{YoSK>UHLsbI6y#$fA&!!r-+ouQ(++Zn%}Mhi&qC!6u?Uqd++y*P|WiG4Y(n_Mu9{h7OyfAb)|%-F=eZ z=J8m;!uIB!F?Uo1fm66BhOqKTq&jlOx=_Ztc*X!4 zp4DgQg$iCmFMnT-@y0Q6rn9hjQrwQ>(YCDnf6U9HC-Dt-m_S01P*jXiVl3stW=SXs z6zcfH4!%MF0d18?<-lm(V&DRrvqteW5|tf^V5V4f zbo8fBPkphK6Kjx_0~GS9UOK`J@gsFsIfIDCM;hxPL~4q|+;895SXoOugx{H)qb$kB zOJ=_v2Oi|x+=U~6FE@5}xTn6G%u=P!&(GuGAu9G(CJ}V>UW~mf=Bx~5Ok^-OH|MZX zm5^BJ@JCcvS9d3)b2_chy!Z-mfco8~Y7U0Ojbg>4;vGNAqkH$Q6hAeZc%OHWfTbpjX0|@9bL#337DVd>HtWot zQ9nyGZbsW3H6zCD?0m*d^hgXXc_P7gia!0MC3!XM8iR;6i^TmLU!N2H$@;@%ENdvC zq@iY;QT{G0cY?!9#)?O(QX`)DE9k2Kj8&2zH9P_}w)?7mx+ANbbP6AUVpGz_!gOJ) zl}-dL8-7Yd0cyX~rB0W!{o2Caek+xvuU2`?>>|ht41@Sm^17>6a~pw)@9kYH{oVd# z)qmV7;0tAgx{yWo{C~+sJq-?@!(s@zHSf!a@Ng?jOALOdyV`o77hGI!3!Hm@NelG8 zAS)6m>>D;@V8{o9?o(5o^o|qL+>c%WZ`Eh3WN!Y~CN@hOMw0@6#);hG8jL+UPkIf) zw$Ap^(?8}3-1Uy={baLdPU3*q4$p&Of8`e$#F~YGFJe@0_BnYUYMk_Pgjezken@DY zIH*6fKQZMl!Q(htosbTg{V{ibH!b?G_kk;J=Zb?IW@Q;&a^3+|qVw;nsN9RGSa!Q} zX?<~VwFN~P#ZorA?DfvF4$1xq)Np_Wir3(}01HVB1U@VkLhZX0oPI5Hl6EXU^-KB( zF=Af|CrM-YyOXSt5>ozslMd+hh&xzpa0r+wCTd8^M{Q8ZwooWDspzkVnM^rIj^sv@ zNYK247cYPc7W`E;uFttI#-lPd;)iw7r!ZD+L%El$Qp}0qy1n0c4G& z(jv|wi$CB5T%^J|U*PZ=bNNE>`mWQ$uFSbSRR6shV2Yv+WT|FksW6)S)QuX^S;sYNJ^Z%rPeb_-_=d%kHI@u2U-8964x^tej=SU?VyrRej@m~@ zWKpq{fvFNy5xy8(o`S?ba@|UFUaYZixC2pXwicPVeKjGpo3tDp9E^;}Co0*hmFJW} zDJVz8`1o|Oa$qQ)0jNm)S*FkLu)GIM)%to~Zmv|es<`kXJ_*C1Q&B1!EouVuJ2qNd z7WtaIFyyP9-u-kZ)r9n{*U@SWGbE}D(80Yl#%$Y?<_5N4#6-l-+G-xeQeQ_d@-BVg z_Bb)47NoMvc|TE+gTwoXL<7H!%A8UrixVVA^PZddDm2qf?rl^w!bNGJEG~+G+LyO? z@N68Ag!&r>REXdZR6*TLr~L5www)}Z57*$;R?BqXY{-P6TUh&j&7lDw`HDT<9#3LW z99hJCcTRAzUh^CZ!x{smb$G>H8Pf$;oe-FingrzZbzHHbAv}{I zki?OWqV< zkk_kY3Tm(D?A_!#a^TxlBqb%KpQ)*<<4x9m^e-x6F7Q@1p*lG^nJiF-@bK{PQO=St zg8;$Q)O+BL+5G$_|N8aJ*ceb6=$M$8XlMeCzu^LC00IHA=!b`g+l&2(u&|=?@;2Xl zPe(^C5CS_o>KhqZhFM?_xU%Wj+1}rrtEs82uCAunLwW~z6r#aGIQIl{){7}Tua;(| zQ;K24!;q8K*u<(VEz_n_O=#eY|D@N~p2;4l*Ov)XYf*22<2-jA&B;?H)Oayn+w7#| zZE1)B(3o{mYLwk5c>xxhIKnR!_=Ib6(vp0@24X4a%Q_8U!WMtu)D}vL7Oc<4e2_*`e_{+W_d<- zii7rA)?t|jKL{uGk;OETAodACZ2V+?v{kGc`n3wd_FMP^zfBUd;HQV^dh1mXZLOikU{ z+NuZsHh6RIXKFEzlRRLbSy)P%nri)J2c*Mj z)4$lHBdfig`m~e6(9kfM+@;0q@?f%1h4~Z6v%PuqhC{b{ee}t8UVc7^02AWkuI%hI zfl!uh#j%>*B!cR25RNpe#8h_}QQUX0FAS!d{ez@-^30kts}0fX9)`t&J_AyS#f)?V z@`RGRL+w$)((LP_scO5NY=^u_LWP43A0$I}2WC@r0 z=(Z01k||CQwIIvOS#O#D(GN#Rz;k&eZyuy3F>MVJGG`9ton|lsryv|xyFYBcKkPt*$b!x9MQ9Z&nKdnn?2T>wm4I2QPHp)Vom2|m zSAU;H<)h#!DC@m{1D=gevYIYM55uq0IwY9Nf z<>ag=F9+!;dpo=PyK5IIsV)#y1U~SmhzO8G=QLh`A{JbgwsLkVev;X^-=3d-qthQ1p5)$oG+EVjwrM~a;tJ2s{oS1a0LS=bI zBS{c@JFdHRc7pd*?nCg3g1zg}@@JF^y2B={pZR!_9nU%-*Ltd7>&0~r(6s@?C;)7}xw(1z^eGa8$;I9r*m#VLj4oRvwe|I2?_NKJtPv20#$eji zHN)AK0w{v+(5b# z`&3-5rnq?f=6v_-*RO1n(^*O4Tuq+mJEvQt+=1jnh|S(W{WpRd_R$P>c6K1F8yg!k zx#K|B+b_3(XfdElY_F`qLsbKwCvps#JwDtY92@|(0QNojq#$NYMMc%@x(|%c$>n9C zdNFFiH@(_{rKP2b3Foz*C?LAvm2lPIxw^Ux_v$~-wWe-wY^7MEq^c>G6CcY$2WbwS8u*yNwsIDw{IUdGl%fwzSBe7^G zA^avmX(sNe7G8uJQ8QHBiYL#TFW#$&{X$b2Rbznb)h~)`5<(}w@0|WDc-MOBR8Loh z3SxZY@v2P9kFjYWn|N!{F-3DAzTij|Mz)d!;x?O56q|CBp(GQrcjlT{NHf*9pIND2 z{*0_A)+TxS7q9qp)52-NxWByBi35lhJ;uo$O$(AJy49dM3{<|0v$MnqSU!-=)pZW1 zLFIq3mkkuy$a?efimVL@c5wF(p_V{$+Rx^D3t8yvRoJ;^nUKL@M`2f5?8pcGl#6=v z6P@ZG3yv+>Mkl>e=Eow~K(I6llvXJARoOjm&bEP?rm+Q8{UAC4w0?g)lN!MjJi=tP z2Iq|da(;V|YHRViz1W^CWd2lFQv(N4DwkBNsjt5rPUBz76oUxg-i~M3pGn<*lu&W| z1w$!x=AoW3Y}D63ZF!L0jj-4srTRKJ{NCAF@J-C)&BIrX;4_Wu#@^FY5HuSY96UWa z`N<8U#gTV+cc6()US3{Dhq#ZA4-hv8hr`OsN}ws&bt>Nir~+gOEmo+ULYLoVQ|W0i zf`at3*dN{9{X-zkrmLpr#H=8mNw&jr`5@)ADT?f>nAn1bjy{?$a5|I%0nLltfuS=p zq9UOPeg63^%b)w(OR%=zySjiLgOkk%tr2X0wNXmM6l)X$(FKv~^^Fa?`5M3|aqEqy zq%j0$8CdK@VT_X0;?hz;5DK+D74+q8wsiQNYu3olgkB;2gaiLx?0qP{C(q^Cz!PG& z^Ras&Rk2r7qiBXgDCae|wsHqNIImjw^eC0|v{Syq#v;`SJWSG3WP`V$ySP^PVV~XkU9IqXM4`x zf?3ut7!O;y)c!GW?sPz$j_HQQr)}@1x>W^$x1qS@Vo(GHx*Y69c!32N(^z+R0z(pN zfTLL#m3414oT5LqzyAt?N_-O1G~-p3Reb$##g643#vE*;_O3-XNh;MJdx3Gs6C@GV zJzXt&G&@do>s9ChfsDOz4BqzsY54}f@mTpBkLvMSFM^0O+T5AhIoB*Z2kY5q4n#$r zE=;=)heuQO>_t7P$UZn)^tGY$Qya9+s5)(X%Go;iH#VWq92)r?tzLES!nW=<>!vS< z5`>Cn2(gV?_g{^38aMxHwShl*!)lL3R}d!Reb&%iNX%?$+)S!LBP8Zi-sVXO5m!6w z9OPe+GL!C>fAvX4ds@u%xS;mnAil2;Q8~(iETh%){efxJ>8B)UiMBe7gNbpPsnCd} ztR*%5P5Z)Q$@fRm_r`uvi3XIJ1~Q851?E)IqkVGha-YIZU6(8EzIsW{cGl1Z7ax-r zKYvnn8_!?H?^e(0a926TZC^iOi*p*`$K1DISg&>6%=2; zR#K9aS5zDwR8e>x9U=0&%2jKz^M1SW4Ag{t%{U;_NWdzj=x1Y7Pk`G5idrrDd`lK8DUZO#eUY5jIXz`9x zC^ptOIng*KKDN#Cdg4l|3cP5$(Sw&PN|Ldx3Z?))gph&?=*7j%HYDi8(tM}%+m$+Z zdmbhCnZ^XQ50O$-1iE^sG$pXRrq6dO|N=O~%Dfo}O5R#=oD|A|>Yw zL-lGZmlt(j|I;|1PVBe-%g3Ll4_cVOzq_j#f&Q9;)pKES@#=#8Q;vDJ41f?TD=Wsy z&lq)H1C&u%RaMn|%c?Q`?px*0$;pL3I1)-O>o=vx2q*2+A?f7!HUQM_9%RERL z1p9|Odp7p(YH%FqmX>Cgmag{t<54cX+I{b*#>eNzk1HQ!&9D1^Zf=P;Q7wCiS~k(mjt!WF188uzvL3Ej z$TC7ee1MIWXR+^h-?TYWTas35k-6CFy1Vm))6D{yiNXxyV(-iKgN3b`jODiDljWrz z3pXRNrjtKC2XL9EANcJ>9ZLLsPt|sFd)cu^HK|>eDs%QE527q;FP9g~{d6z0HXfpg zwMB%}P4NQ`AB-Na?sJNzkREy)>f^R@G}cPVV~uP zyTt?^hs<-WdX|H>a=*o!%7ZzE$vN0lh0lw=9%XqvHVvcjMXARZt52mQ5MtoyxflU5 ze(^>0nY$nG$uq7UHG+WVs8>x`GckkRpd`ZOIst6DyH!ue%PUMzKQ!vln-$O7SY#2|^Ql4@rz)bkNJhCY_$ zE&`mk#n&04L*c$R1Ifd^F`UVncKei>?GJXx6{Gje_cy0a6_&$=zN1ss@tI>nOMmw5 z&vvwHE?D*M(3Tvpu2M!GB8P6dF$tw>-OJCyD$>0Ll92C(k6Uw64 z%ZDT4Oggcwn$MP|Hkk`myIw+Lm99Nym78rMDTQ5vV|_jLJq(kOyG{LH`>~OOSnnNN zIM-nLejROyBJKwdoh3}k$ICw-DzV-hkND+K)dbR*P+I;;@iIxcB*lW#ulRA<=1|oK z8#fGs8CwkB5HV5Ujs36$To7RxyW;zFlcZL)+!_wsW=P%>R6Q7B-J?TC+8}s<>)=I# z+jbWu({SwQG`04Et)50s)x+@Jq;?13}yG?<+&%WTKYS?<}($9k26**J%7qXJomo+w9@9*xUw?bGivxJ zY1GmI`{o>dej&ow_R!%mH_2n}*RN1l*R%Wallp=%hEO-S{))`GJh2b1zR(5X?9#Qa z!t&2oG|ZoTucx#O4euK>i+8#6o0t6^;O3Wp&73??Mu>dMp%xNqO1bb+QaqY_IQCI_ z?0AE%6I0P@?5Wmc>T*AH+7*hmMhJWfy4o2WLsd|69p~^UKJo#O zt3Lm|W%_GhKYj%bcmrl~H12NmmrggK(5iGJwO6_$QB~I-ZmBn_XNJ^d>ZeV6_zHeA z@!pR<=fr1s7H3BMsk37r?)H=FM9)01Z>p$89`-(07mP-={)w=!DJI5bZu#O`f33x- zH#cE;(spUY?|DVHldLlmW2SfeHIDQ<(crfCx|p~-!i&h!P0?ScnC?%WA~}VzWBPRB zl#mFjxn!zr7^iAqH9ri?%#c1rVO*nyDZ|%4R*I=&>~*D*HWAX%W>tU4k|53uHSmoh z4HUK&a&LJlGr{?%?6H0G5~xrF$Gr4L#iB9q+iTBDf+eBv9{$YHetl^y5NO0< z)9Q)b>Wti~IZv{edq0vwfEU`E&l5#m|v-PCVYMJ(jxWFuEny;6~W0b$+ZS z;<+&uA1{!Uxg+qNN{*Ji5@8el9 zKKo#+=}=_qWwX-X=v>`}f8| zH_gA!d~U{m-Q({2j^9?@Ei<%?JXs92LAMdiyvV+9zl2D(?jPQKbj|d3eo&g}s<1p< zcu?`N^ive0i-H{5FCKWD;_iFQJ+6H4v*>f0uYGuvRh`Y8>U1jYLC*F{H|?tfL^s6W`4v0mDK zUUX-6n9LTAH;;anV_LVovP(DlqI*-|s+WYlvVNJYWm`2vQF>?S`i1kr&IoNdt6R^v zvtNg=SzVth=&V;O>qx)wpqAsm}HFSGInPpDIm|sx1vBAVh?OLtd z)VIjXEs(;U&BMpe&Yzi>?j0r|b&BH>0-gV5VL6cu;k9Ce@Iod8M#rX73-;bYxTGK= zpRu5p_U{dFsV`?Rl&zlgypTFQiftbrsiZ6s3~}c411%Gl}lb;nHx98YkUw9 z5TSb*gGZ8BocX4ZHy)i)JW$@4@Zs*=#kA0?iY4v1B$%;nN_s36KB>K+l$c|vgQu^A zwY~3aU70ui;mW&j^oP@Zg`eFGbt3w|cCCX!8}vERoLmIf+aVoxT}BmUYQSd@a=R&W zNu&>77=|4gxA&NII{YMpwvCitdU%C4IV`s?xm9ct4eCOMEdCrgxr84rlC8E`#kZbU z3&4ERDG>P^Z<@bhF0A5iu4E7pytmvMdBO<6MM9ge-u~E5%})Okx)m+u?-lo5a;kv& z#`Zm^dFzW3dhhO_qj%QUg}bt_^z#t=R3IbCy^c3G=a1a}TpTQ4_h*FCgF*S3v|V@q z?$(HCtC8!z?e%_1wa|2Ld8UZ(dE`RDG$})IxAx$t3S#PJV}p}QX2EX1wvEWHv({If z1q4e4#KvNJ&h1yT=Zn{;n2U96qs?(ndnTRZshT&#>FFhTVeXl^7FK79R=o#=6lDtI zW69Mv75Xdp0jsZMxVIllDYhufl=5csh?o0W8{%jgiqUjD>* z6nwe_0394!qzi%qw3M`&1s64!oxkI%UH+d;h)pTTgj{GabmJi5CZ!DMOX1-W$>97@ zlHW-ymO`{gwS}m|e|Sgwm|jmtx}e&$i*;O|`GP|ef+XSX?L9ca@;aTlS7lV#`z6Ek z=cKplnAU+ylvCV{hj(Uif3mtC+eBzB;HNl)Flf;~etaAEF-jLMor&<>!$r@_DXbSi zBLjzn8u&tn%`oCKaJ0I5m9(DNSi`~LGRaFzXi83b2ldmk^rawDJS+zkT@Shx&C+aT z_Z=5rL~Q!&8ioOO7BEQKFJc62ZZD(!-O(;9jb*^!-f? z6;T$YI(_WgD3hP&X?(|{0L3|H_BRhFa)!e5cqZYT|EcQk#SmDtiY)Q^=j4FZc;}E9 zU&wxvx#VaXlpZP-@k$>x<&|R>8Zs?*DA8eE4CHXH0ZX8m<`g9D{ki`|5dE2FonpX4 z$^Z%T{L)b^jV=I#BW+a-^E{hfH48~U=9Qfm`6rKutOa@CAMBqbx*oNE$t^k3mEE1o z9yCPPu!0mA1Fq$!-SD<9yaQ=N*pPXaUf5q@K!e`I9>N+ zw^6*2>uGIFaNg?xJIWL?5_T zGyD3GkWjhQ>whiITMR7-mSaN;U$Guzl9FscMh+E2B^y{wHgVZQyc{Z#x~pVb3*jiW z4=Pks{~|X(4m+RJ$UMNvUq{BAI$9oEqSKzD+Q00iSqIlzB68mRN;yOO?{At5#IpV- zIa4*+;}scm-yy4g#?wi(q_rTT$#p|h`%Ie@47@6P&zj7o8NKM z1T{c>DnJ5L06pY1&w3(2ZJ2<7-~qH=e>m#GR^`LjArC?O$4B}b436peK?5QzD?cYm z+6bcl&ojjH3sO@7#S(qGT(DKcoY|(VDCP2tg zQ6XALKmfKFkhB*1vATL-4z}g+t1Z+#e2MABi-WUmn7KJ2I9xV$-X@N9GQdAmd&$ne z23jM6${CulloVZA*`NLKh0zr9AY1hcM_NmZ4+0SqYv+PMyZ|NHpa*042x&Ic5FXw? zKc7iKQKg~L4k@}VEZ~aU^))}ff33A82Fdra5l6X_$T3%fIBx-KS2VL~)r5nso zMb{HO>$61R>R8kV{Vb5fbtgbOB zBGSqOfpPzBF=;YDVE$M8);&Q+zQ0zMS5o5PGq9(El4j)D{aq&-~eZeYj{ zXO424ih~+dQlgj)|K3sl?F9`Q}`d^`RXcP1#>GL zva+*vb=)!BLEQ`3KbZVzmSR)*f#NhjdU_h0y=YKZx9Yn_Mtr|ltsaSV{}l@`Y#9EG zyN!I>_B$VPvdO=>1>h+;3+bvkE@bCzZ;jPt&utUbeR`<3cV^V#m8GS-oLq9|FDx#3 z2#>R|8m?IgR9bpnl~0*bQC3=dx%KufkW{HT@kb{~xQbMNwiO?7nZkVYAKeTwa(Pa1 zTWCp`uG31gvKK$X<3TnAHDK!J&*#j{Q`1W^2?@>K*8@SUOE3Gm9_E70`=>uh+1gSh z8yXq;vT(;HW*YxlgJD8GMz7#?h*9Gp9iN<(mzABKE`YGyH(kc}o}DKfKf%Tt8XBsG zea7N4I^@o%W|{`<|x#@=>dD1)^C z(IJ05tRa^FXfD80yVC-^*YS$>hZ~?RT?`J9KOT+;R6+maL{m__fxdee+aLF?`W+Nn z*Lwd+Vh~LjWC?9-DgyjQ1d==T%@jXwP$rw7r8Hhs$jHb5%>nS=XhuiX@XinAuN#y) zQc|#{n`%%o$Bav2Q&3i>OoPK=^ev^Kn_?k-Ez^*Oso4$X@1D!{mm@F&osMIf!Av7V zT@U+*yKA$wh43`NTYM>X_3DO(b(JcNNIraA-0`t7kX=zyP{{b_EHGj2k9(kF7nW?{ z&d$#E&JHbVwQuWS5V=JEgUAybp@3zCKW1aw?>qllhPr)e&Mwk`P4K=YDlg&dAo zSJ-R<7L{;%l^#w2jn}2@$MeDD>_`kuO#gPUwR8?6#c4pcYG->J(eFw?6s@uyam~lp zZoi{RM#%L_YC3X@>_v_!P>*TgZmJ2h>}rQta|a>|3k$OTd8YI;kV}2C z%E`7f*GR-^&ILz*xC21t3M44 zxPYdn%&eueP1Es>ZyOzSb-TmyH{N;{L`K>IRrva~Jvd}#6C)$pIy|o&pT77euCL!* zvNHixK2TzAhgesPZkAkckepq%ft66n;Qf-I1v=e6L;ZdL^KughQzGp-?*EJn19peb zhHF3pIR%B@n>S9k7p)-YoRpviHpt0|#@48||NS92Vdu+;@88Y9nSz769kG?ESW@rj z%*|`>9_~YDqf=a6FD51?1Oz;Q`2a7zJQVAbV&Os^JeAPX6J%xG5_@bs+JamE@n}_U3|%6;9+r?jmB^)L#Bzg1*+Sy=&52GN2y5xaO!*SvQDje|AKeIH z_oMNk-d=ubt%tiIc`s>N-w zK5_yAVNLnZ6!IV?%Klv7V0~Tq3nu?VMurhKl`wJy34#|9HG+RkjCk%Oy0f!0F`G`G za{5@v*Z(ruOQx6MQBguZH*8lHmLnACLwJHAG9UBdS(%yX>Bj~JSpJ+LjD0kTry?57 zj+`T}%w5~b$uVP6$(XO_BpX8esO-t?xp<2o{@u!o6m)>+hCmRrJ3hf`Y7;qbHA!&MiySaM1V`wvQZczEVd4_sLCooxSsULZ;x0;1F*e*wiD5G_!1_^BAW z7XckgH4m_}$;dQDCF*@!{F0PZw=y~8Uk0~w9U%gfKZ%M;Uqf9TP-CLO8$>xc%7K-m zMU~7}9T-$`0*Jwc_OGqTEC*WQ$L4p~?VUWpFH%}s2@Gs46h!bB$a_0Yo#Re?f2mP0 z1%+rjRD`s%$`~x`q2-U^(knwlww0S~1(jWlBFwEO9t8yjUY?#S+U|}{b6EuiAvAp# z`@VqijT+FwXA%O8W!j(JR5;5NR^e@QxT1#I_!JBk@R?- z`FOoumUz%a3}SRWT70+kZ!;~5|j z*#5ruTlhIjFnPDOR=e{p(nYhuO{F4+J2e;AD=8@rfJ6W^;^X_kksA!%Lz-nkZu$IQ z1{e3hVdV8^FKTZ@SsZC4B{s2kocIuv_|1%Ue)eNb5{Vdqb+xn%zh}r*%KPEdBq6hv zkOt6z+CyGm@55zO+iw8Fz3>-raIXp(e3?xu1b>3w}MM#BOoCm{bwl-rapX?xhBa`agg|Li?hUI^(}Z0fgNpJ9?nC zQJ7{7xyK&Ag(~)TQ?IXV(XlOBP=T>_b3oE*2XoS;r0Ariq<&Wv6d?C_+%1O&eF1QcsSz%3K^Tdcc7nd70PJ<&tj${ufu- BN0R^m literal 0 HcmV?d00001 diff --git a/nav2_mppi_controller/package.xml b/nav2_mppi_controller/package.xml index ed8332288bf..dce7b30a8b7 100644 --- a/nav2_mppi_controller/package.xml +++ b/nav2_mppi_controller/package.xml @@ -17,6 +17,7 @@ nav2_common nav2_core nav2_costmap_2d + nav2_msgs nav2_util nav_msgs pluginlib diff --git a/nav2_mppi_controller/src/critic_manager.cpp b/nav2_mppi_controller/src/critic_manager.cpp index 2065c5b241b..12f1f346bd9 100644 --- a/nav2_mppi_controller/src/critic_manager.cpp +++ b/nav2_mppi_controller/src/critic_manager.cpp @@ -37,6 +37,7 @@ void CriticManager::getParams() auto node = parent_.lock(); auto getParam = parameters_handler_->getParamGetter(name_); getParam(critic_names_, "critics", std::vector{}, ParameterType::Static); + getParam(publish_critics_stats_, "publish_critics_stats", false, ParameterType::Static); } void CriticManager::loadCritics() @@ -46,6 +47,13 @@ void CriticManager::loadCritics() "nav2_mppi_controller", "mppi::critics::CriticFunction"); } + auto node = parent_.lock(); + if (publish_critics_stats_) { + critics_effect_pub_ = node->create_publisher( + "~/critics_stats"); + critics_effect_pub_->on_activate(); + } + critics_.clear(); for (auto name : critic_names_) { std::string fullname = getFullName(name); @@ -67,11 +75,44 @@ std::string CriticManager::getFullName(const std::string & name) void CriticManager::evalTrajectoriesScores( CriticData & data) const { - for (const auto & critic : critics_) { + std::unique_ptr stats_msg; + if (publish_critics_stats_) { + stats_msg = std::make_unique(); + stats_msg->critics.reserve(critics_.size()); + stats_msg->changed.reserve(critics_.size()); + stats_msg->costs_sum.reserve(critics_.size()); + } + + for (size_t i = 0; i < critics_.size(); ++i) { if (data.fail_flag) { break; } - critic->score(data); + + // Store costs before critic evaluation + Eigen::ArrayXf costs_before; + if (publish_critics_stats_) { + costs_before = data.costs; + } + + critics_[i]->score(data); + + // Calculate statistics if publishing is enabled + if (publish_critics_stats_) { + stats_msg->critics.push_back(critic_names_[i]); + + // Calculate sum of costs added by this individual critic + Eigen::ArrayXf cost_diff = data.costs - costs_before; + float costs_sum = cost_diff.sum(); + stats_msg->costs_sum.push_back(costs_sum); + stats_msg->changed.push_back(costs_sum != 0.0f); + } + } + + // Publish statistics if enabled + if (critics_effect_pub_) { + auto node = parent_.lock(); + stats_msg->stamp = node->get_clock()->now(); + critics_effect_pub_->publish(std::move(stats_msg)); } } diff --git a/nav2_msgs/CMakeLists.txt b/nav2_msgs/CMakeLists.txt index dc49bf40f01..6ee387af9e6 100644 --- a/nav2_msgs/CMakeLists.txt +++ b/nav2_msgs/CMakeLists.txt @@ -29,6 +29,7 @@ rosidl_generate_interfaces(${PROJECT_NAME} "msg/VoxelGrid.msg" "msg/BehaviorTreeStatusChange.msg" "msg/BehaviorTreeLog.msg" + "msg/CriticsStats.msg" "msg/Particle.msg" "msg/ParticleCloud.msg" "msg/WaypointStatus.msg" diff --git a/nav2_msgs/msg/CriticsStats.msg b/nav2_msgs/msg/CriticsStats.msg new file mode 100644 index 00000000000..f02406228df --- /dev/null +++ b/nav2_msgs/msg/CriticsStats.msg @@ -0,0 +1,5 @@ +# Critics statistics message +builtin_interfaces/Time stamp +string[] critics +bool[] changed +float32[] costs_sum diff --git a/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml b/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml index b81cef7ce56..01fe9656d5b 100644 --- a/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml +++ b/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml @@ -76,6 +76,7 @@ controller_server: temperature: 0.3 gamma: 0.015 motion_model: "DiffDrive" + publish_critics_stats: true visualize: true regenerate_noises: true TrajectoryVisualizer: From bbf829f22e2490d7009e05de31ac30c2a4d868e7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joni=20P=C3=B6ll=C3=A4nen?= Date: Tue, 2 Dec 2025 16:45:23 +0200 Subject: [PATCH 2/3] Make critic stats to work with current branch --- .../include/nav2_mppi_controller/critic_manager.hpp | 2 +- nav2_mppi_controller/src/critic_manager.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp index 3045288547c..1507abded64 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp @@ -97,7 +97,7 @@ class CriticManager std::unique_ptr> loader_; Critics critics_; - nav2::Publisher::SharedPtr critics_effect_pub_; + rclcpp_lifecycle::LifecyclePublisher::SharedPtr critics_effect_pub_; bool publish_critics_stats_; rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")}; diff --git a/nav2_mppi_controller/src/critic_manager.cpp b/nav2_mppi_controller/src/critic_manager.cpp index 12f1f346bd9..6ea76fb67c2 100644 --- a/nav2_mppi_controller/src/critic_manager.cpp +++ b/nav2_mppi_controller/src/critic_manager.cpp @@ -50,7 +50,7 @@ void CriticManager::loadCritics() auto node = parent_.lock(); if (publish_critics_stats_) { critics_effect_pub_ = node->create_publisher( - "~/critics_stats"); + "~/critics_stats", rclcpp::SystemDefaultsQoS()); critics_effect_pub_->on_activate(); } From 7237bf939e343c57123ec312cc222ffb63a33fb2 Mon Sep 17 00:00:00 2001 From: Adi Vardi <57910756+adivardi@users.noreply.github.com> Date: Wed, 22 Oct 2025 20:11:19 +0200 Subject: [PATCH 3/3] [mppi] fix division by zero, clean raw pointers code (#5636) * [mppi] fix division by zero leading to cost values being NaNs, which then propagate through all the critics and results in NaN control_sequence. These NaNs were removed by the hard applyControlSequenceConstraints(), but replaced with ax_max & wz_max. These lead to high steering at the start of a run Signed-off-by: Adi Vardi * [mppi] clean ackermann constraints Signed-off-by: Adi Vardi * fix long line Signed-off-by: Adi Vardi --------- Signed-off-by: Adi Vardi --- .../include/nav2_mppi_controller/motion_models.hpp | 12 ++++-------- .../src/critics/constraint_critic.cpp | 8 ++++++-- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp index 85b1e705c01..1fbc1483ac2 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp @@ -163,14 +163,10 @@ class AckermannMotionModel : public MotionModel */ void applyConstraints(models::ControlSequence & control_sequence) override { - const auto vx_ptr = control_sequence.vx.data(); - auto wz_ptr = control_sequence.wz.data(); - int steps = control_sequence.vx.size(); - for (int i = 0; i < steps; i++) { - float wz_constrained = fabs(*(vx_ptr + i) / min_turning_r_); - float & wz_curr = *(wz_ptr + i); - wz_curr = utils::clamp(-1 * wz_constrained, wz_constrained, wz_curr); - } + const auto wz_constrained = control_sequence.vx.abs() / min_turning_r_; + control_sequence.wz = control_sequence.wz + .max((-wz_constrained)) + .min(wz_constrained); } /** diff --git a/nav2_mppi_controller/src/critics/constraint_critic.cpp b/nav2_mppi_controller/src/critics/constraint_critic.cpp index 4ed43dbf5e8..18cdd754719 100644 --- a/nav2_mppi_controller/src/critics/constraint_critic.cpp +++ b/nav2_mppi_controller/src/critics/constraint_critic.cpp @@ -82,8 +82,12 @@ void ConstraintCritic::score(CriticData & data) if (acker != nullptr) { auto & vx = data.state.vx; auto & wz = data.state.wz; - float min_turning_rad = acker->getMinTurningRadius(); - auto out_of_turning_rad_motion = (min_turning_rad - (vx.abs() / wz.abs())).max(0.0f); + const float min_turning_rad = acker->getMinTurningRadius(); + + const float epsilon = 1e-6f; + auto wz_safe = wz.abs().max(epsilon); // Replace small wz values to avoid division by 0 + auto out_of_turning_rad_motion = (min_turning_rad - (vx.abs() / wz_safe)).max(0.0f); + if (power_ > 1u) { data.costs += ((((vx - max_vel_).max(0.0f) + (min_vel_ - vx).max(0.0f) + out_of_turning_rad_motion) * data.model_dt).rowwise().sum().eval() *