From 06bbf081b4c4b1645fd561907039aa78771da2f0 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Fri, 7 Jun 2024 08:28:47 +0900 Subject: [PATCH 1/3] add perfix Signed-off-by: Go Sakayori --- .github/CODEOWNERS | 2 +- .../CMakeLists.txt | 34 +++++ .../autoware_steer_offset_estimator/Readme.md | 65 ++++++++ .../config/steer_offset_estimator.param.yaml | 8 + .../image/kinematic_constraints.png | Bin 0 -> 47715 bytes .../image/steer_offset.png | Bin 0 -> 56450 bytes .../steer_offset_estimator_node.hpp | 69 +++++++++ .../launch/steer_offset_estimator.launch.xml | 22 +++ .../package.xml | 30 ++++ .../schema/steer_offset_estimator.schema.json | 65 ++++++++ .../src/steer_offset_estimator_node.cpp | 143 ++++++++++++++++++ 11 files changed, 437 insertions(+), 1 deletion(-) create mode 100644 vehicle/autoware_steer_offset_estimator/CMakeLists.txt create mode 100644 vehicle/autoware_steer_offset_estimator/Readme.md create mode 100644 vehicle/autoware_steer_offset_estimator/config/steer_offset_estimator.param.yaml create mode 100644 vehicle/autoware_steer_offset_estimator/image/kinematic_constraints.png create mode 100644 vehicle/autoware_steer_offset_estimator/image/steer_offset.png create mode 100644 vehicle/autoware_steer_offset_estimator/include/autoware_steer_offset_estimator/steer_offset_estimator_node.hpp create mode 100644 vehicle/autoware_steer_offset_estimator/launch/steer_offset_estimator.launch.xml create mode 100644 vehicle/autoware_steer_offset_estimator/package.xml create mode 100644 vehicle/autoware_steer_offset_estimator/schema/steer_offset_estimator.schema.json create mode 100644 vehicle/autoware_steer_offset_estimator/src/steer_offset_estimator_node.cpp diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 278329cd3c725..ea6cfa9122b86 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -242,7 +242,7 @@ tools/reaction_analyzer/** berkay@leodrive.ai vehicle/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp -vehicle/steer_offset_estimator/** taiki.tanaka@tier4.jp +vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp vehicle/vehicle_info_util/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp ### Copied from .github/CODEOWNERS-manual ### diff --git a/vehicle/autoware_steer_offset_estimator/CMakeLists.txt b/vehicle/autoware_steer_offset_estimator/CMakeLists.txt new file mode 100644 index 0000000000000..80ae467ed1f85 --- /dev/null +++ b/vehicle/autoware_steer_offset_estimator/CMakeLists.txt @@ -0,0 +1,34 @@ +cmake_minimum_required(VERSION 3.5) +project(autoware_steer_offset_estimator) + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_EXTENSIONS OFF) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror) +endif() + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(steer_offset_estimator_node SHARED + src/steer_offset_estimator_node.cpp +) + +rclcpp_components_register_node(steer_offset_estimator_node + PLUGIN "autoware::steer_offset_estimator::SteerOffsetEstimatorNode" + EXECUTABLE steer_offset_estimator +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/vehicle/autoware_steer_offset_estimator/Readme.md b/vehicle/autoware_steer_offset_estimator/Readme.md new file mode 100644 index 0000000000000..164d411e31050 --- /dev/null +++ b/vehicle/autoware_steer_offset_estimator/Readme.md @@ -0,0 +1,65 @@ +# steer_offset_estimator + +## Purpose + +The role of this node is to automatically calibrate `steer_offset` used in the `vehicle_interface` node. + +The base steer offset value is 0 by default, which is standard, is updated iteratively with the loaded driving data. This module is supposed to be used in below straight driving situation. +![image](./image/steer_offset.png) + +## Inner-workings / Algorithms + +Estimates sequential steering offsets from kinematic model and state observations. +![image2](./image/kinematic_constraints.png) +Calculate yaw rate error and then calculate steering error recursively by least squared method, for more details see `updateSteeringOffset()` function. + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| --------------- | -------------------------------------------- | ------------- | +| `~/input/twist` | `geometry_msgs::msg::TwistStamped` | vehicle twist | +| `~/input/steer` | `autoware_vehicle_msgs::msg::SteeringReport` | steering | + +### Output + +| Name | Type | Description | +| ------------------------------------- | --------------------------------------- | ----------------------------- | +| `~/output/steering_offset` | `tier4_debug_msgs::msg::Float32Stamped` | steering offset | +| `~/output/steering_offset_covariance` | `tier4_debug_msgs::msg::Float32Stamped` | covariance of steering offset | + +## Launch Calibrator + +After launching Autoware, run the `steer_offset_estimator` by the following command and then perform autonomous driving. Note: You can collect data with manual driving if it is possible to use the same vehicle interface as during autonomous driving (e.g. using a joystick). + +```sh +ros2 launch steer_offset_estimator steer_offset_estimator.launch.xml +``` + +Or if you want to use rosbag files, run the following commands. + +```sh +ros2 param set /use_sim_time true +ros2 bag play --clock +``` + +## Parameters + +{{ json_to_markdown("vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json") }} + +## Diagnostics + +The `steer_offset_estimator` publishes diagnostics message depending on the calibration status. +Diagnostic type `WARN` indicates that the current steer_offset is estimated to be inaccurate. In this situation, it is strongly recommended to perform a re-calibration of the steer_offset. + +| Status | Diagnostics Type | Diagnostics message | +| ----------------------- | ---------------- | --------------------------------------- | +| No calibration required | `OK` | "Preparation" | +| Calibration Required | `WARN` | "Steer offset is larger than tolerance" | + +This diagnostics status can be also checked on the following ROS topic. + +```sh +ros2 topic echo /vehicle/status/steering_offset +``` diff --git a/vehicle/autoware_steer_offset_estimator/config/steer_offset_estimator.param.yaml b/vehicle/autoware_steer_offset_estimator/config/steer_offset_estimator.param.yaml new file mode 100644 index 0000000000000..2f73449cd2969 --- /dev/null +++ b/vehicle/autoware_steer_offset_estimator/config/steer_offset_estimator.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + initial_covariance: 1000.0 + steer_update_hz: 10.0 + forgetting_factor: 0.999 + valid_min_velocity: 5.0 + valid_max_steer: 0.05 + warn_steer_offset_deg: 2.5 diff --git a/vehicle/autoware_steer_offset_estimator/image/kinematic_constraints.png b/vehicle/autoware_steer_offset_estimator/image/kinematic_constraints.png new file mode 100644 index 0000000000000000000000000000000000000000..810b91139c80b616595c9ca066633bd6728c17f2 GIT binary patch literal 47715 zcmb4r1zc2HyElr0NC`-nk`mILDj*FCNOyO4jglhW4Jsud-8uBoDcvnO^Z*0HxA7d` zbI!f*z4!g*H^knvXZG69T6?YM`NxF3QIN!ZNb(Q~2?24bE^W^~wu;;qO zcLMlx&*_!4$^+ox{lNGmuubeNq3*0~XX@-`;AnzmW@~3-^4!VD(Zs~o$=uEviVPM3 z4&t;>QFj(|G%;|tu(N%lVqs$f>_kH1VB_Feud8I^*+}~c{7TGu!p^sm?8nZr{xOJ) zV>2&?e?EpE3F!%vwD?OE_q5%4khb=EI_!p!Es2vyb(9W$4wo~lNA+uUj3wze_76$* z$ttrijJQ=WamTdqsz|nNsW%e8Y0)AuG`Xd??$6dfnw-XN!1?P$Ch8t|!6YV6Ff4j2MZhcJ0m(zkNi+K2*Q~9wChQX;i=i_Z=gj z1hAi`K*j#k$B!SSRPvV|1FuJaD|Z*7KoSrXq~_V*-liHBNt5z%c5_31L`dk?@AE9! z@vkT3XRiU;f)T^0uk7LBA!_G-tUarMBbe-w}ZPfxGZ%5dAhwL zcBogWZe0)v_H=DlmQgo^`gCM$4Ecri?vhLK-Gd_hOc9S~f;ow`w(t6_3#r09f zJm9TiQjC0(`SwgHn(II?qobvOPx=9J;e1he8*~m_4Iv6_r1bQ398xzI7aVg+g=~@f zhK4&ILqi2OMBR0PxzAceSM3}BC{n1z@V3Rhep`Q5jyW5dN%%EZ)feR@&%>QE(4cNRZ z`Pa*6%pbH?8yXtmwy~6Qii$%~HdLoL`JnX&i;{(KRaP45nUs!Kyd~g4 zaMQtE)~173i)AaPI}TR|!A6#U?-}Ry;fI?KV8Dg7YI&U@AzmE=Z&J8MrHm4B+kaoJ zY{SD7pP+QpippGv@N5CIn!WS5kRD(LE)2IHcj|qXEt3D^F8uc++GdLtI&QfK ze|ipE?zkNpoIh4S%x_Td?PQZh!`U#XcgtG4NOz9^c571e1}o%;0weaX`~LThm*b}l zG*$eo%>COD{crBvgtIf(7O;nzxA#?4xS)VQkhhQ$rLeFtQb!k-?j|GT;F8b%K!3_8 zFK`;$N~r&DGe+3l|8$=&pB_pirC-x4W{~j=xhG-&HRy@z_?=~R{`VIB*QrcHsA+b` z+12&6_1yTl#AhGA=*yq``zTLXSoUwHNYRo>(lhm1p;d#w54g3B(tFUd#}?q6^YinM zHW6-%^y@^rltBgo!aP&%Mn3;Mc9_BCKbuZ}ht&jaj%0Cue%>whO5fAdGsqe*KT_(N z3332`u=|C3uKK^7;NhR)r!Czw)7IARzcOj&I2JeBjDuu0V z=JMGWGGE;i-rX{LkFIv_KNf;}n^Tn*c!b*aFQqb9Jwy~NuofvEvYb;4DT3ZNl`KT; zsjTY<^h5Xt49YZ%d_?cvh@}0BZ;+=@>8y9QPkJ1+<9`dXpHt)Y+3cJzd=EJTuZpah zu7JY9v8zh-DW}ES0EA&+SrAhe;}L13K^1QCX>CfRLyB154+(K&Ifpv!%Bm`d0q)7P z#+RbszPKBqRe^*(#6E@5-42pp2TWO4#|q@ulx5_8P!mWOiUyNtt;PKcm(eR(S#+%$ zTa)%6OdulFw)3C*)&&N2=eZK_qhfurdd$@MubK3o@^kyoalhkoIj1b?t~S)s44j?p zK(1H~5nXMFtM$tO?{yy+#l|GNTvR=d<6hYpjjKs6@N!B98F1*O@?h@7IVHJ_Gs-Mj zqgzZ|b$B-)t!q4P9v9y_t&pnLOukV$jw<a#wW8clarIJ=j%_C;I_UziQn;Qx#W9tmzD?OgfEc_H`E@% zaQZHH>hzT{d!QQKah{FaQmrSRyiZ{kN>Jzf2%k9JOj(atEZA|^lxZc_rZ@^bI+^Xc zq9>;^?V705JHBES!iirYp>={@xP!ABu{TPb`ubHEjgy~;K0I{XWd3ST*spttlrt2s zN3EMO^f>y%R2YT29%T88T8ps6Wb5TMGQ@8Ngm7!BMp09LeE9y)f z{CdQL>vG0HyTjOOxtC4E8D8uPj4WNAS)V_WxK<9YId4S|15Yj-kY<>Flh_>ESFEkf+any zr+-$A!`;`dCfQW~m0z;nSZe!mN*%}jv2JFbn^8g6Q+a8+Sn`dHjbYftSm}&hg?{eB zThR_U$FS5*8e_19WgxJkyv`}osyX_Z6{)1E+BH|_^x?y#-GY5P=9D#01_*IsMA8yd4(JL{mY0IJ(CmNel^dGC#b4MY{CyCEW$I*&ixKAx1gmx zy>Z!3Tyra{)vQR7qZ-&Cm6ZbSf?FCNyy!AVH(7A){EmfNT*a(LPcOP3)+L5g-YlE< z09VbK;Hix?EqvSAuYt#Os!Xe~vg)k3l1IRyez{R%GQgOPh2^upLEG?$Muh^`YJ+V4 zZjKpqJ3DA9soN+2?_0wvTJl-NvgFD^&6K+0;>Pzpj|X^r`uf^UE6S{=%bRU<&vvKV z8$FIMXQr)rta)bHZSQ7^50YP4du9dr$(kzF4Y#^&>h$7AP)6B?YHxA#?zQh&Wvvw$ z%d}OqnY&i`4GlEIn(Rycw7n$G2bp8dMUb+|Jc@<6UEEpQCxedjsd$>+h+TUP)C#`h z#Hd~Fj*)Xzx-mjb?i^mgw4EDL9N-wu4#h=!?e|7UmDydnFf;Osl1*!FRBrm$-Yw6{ z*=FHOksby1m>d3Yc{X}sFMFd17KISe*_4IBSvv{#A4$Y269jw%2O}S}QzD|y&d!?2 zN}A3{?%%(E4`GXZ!=0g=r?4KYD8he9rUwpA)Dy`pe~z!xTpftX8ejSWElt>s;ilX` zczRPFX(<*AN21K6yiAG|JsS${^LfC`sjk_WvAc%mqjOpBqrP&rBizOBP+4;mesduh z)%ejR^{AE&ONe6V{WT^YcvQhlkPK0Yhlke~Y+)x#cIHCnp;zzjG{3$ka{V-9u_?Jq zQMXr=E~Dq(QfvxnIS7Jy4?B>otbrfb3DYI9dpmqfKRf??!FNuqLwDls`w>WPL@s|S z%gGt~fUuLTko2s{=;$ci1Svst$RfO%ZvGdYW@OfOnsj*Dv`{{gaiV_ zSq-?%{cxq(^+Wu?)s=Vi<#-8&azsZ*s)s&eKxpZB^dysY_4~r>9%Ylc@+;@&iQ44v zAqO?A8c67QiYaYz42X+T`HXw&QiwApM^kKe%4Ws$-sBcDX>TiOEG+cOni^~YO1x&F z4@8D+xVXgDy_XA#z*>E^;UmD>oSIk|DuwQunu4$o0%vmGeCQCrd1&g#jbcc5u+AWP zsURm8Ff{l?1jSG>^R~@+h~>VHM`DrdvdE6U3uE#a?CN;9$sC=i&G!@{{gcK9^&JhV zLNXrbcC^6t>K;MH`Q?b(GnLo*MuUribS3&N(>ZIuJ>1TAs`SohD9O+&X@ARE5wzl{ z)sk^C*Qk~;-;$`YPS}Mms3f_otNH`BYpnySf{E5{f11I2FV=7^`&-Ztqsq8_*zkdGGU@8q`!C-RLf~jd2%cFGNQg zmET;TO%l94F%&NBb?n(z?-@@_?|gh*!k5YPWu?jZh?k|!m$~F=&&#v4dub&LlKUjx z^8OP+j52N{bC;ne-t|}P+j`8ohK?)|f$fcGXipe|<7M}=a(4;WwD*kGSCWZrPE~|7 zhWcr@xDqfO#vY+WR7o(;$IEuw5Hs6qx5mg0cI`MSA&eO?@yM+;zRm`Ak^IVO8M%3R zV-pi0Rg=1Xb(cd-vucS^4KQ`g9(zy~|XO-gN0etKG_z34a>*k6yp3Dz68#O(k zEB;TmSTmm8F}=M7o-ve+*~VTBH z!kMtxB3E3L+Q5zWssRzq={$$;S%Kr5AJ9^W6UD_WESl1p`Ls?fX(({Z=+bgqxKJ!o zUT$47)wOiDXZVRccIDkzsR!N{(X_DxaCsi=?)c7av+`P#B;LI4pSf1IsklnTv~^`= zWm*!czj0DZe(m$%&OQqC`Oou{;^R#6?(})l4y~UR6CAo%w&r#7Dk?Y)SAhiT*JLW` z=EjTU;NSq63wAsYZ0MfdISm^4T@!b?Ma;}-`d;+u0VO{@6+|jI^5>@15=j1v(?wAw z_Btdq(-`E>$=?qx%-Fc7p+DHetSM(3^q&;e1&V5_Qv)>Ju87KPa!N|dvVp^Wcs5!4 zPCFZlE~ODs*XPyn(~DbxE#fe>eckbJIhgV&^5#4;B{DXly|)n#>a(LS+5BQtau_$LL(Qa*mZE$m;{H8u+Ax-Z|Ck(Ev6wWHuk zEwWP_giv_xKF-^LOtuWM3X$*7!q|T#ieAnNXmE3*?6}FAhyJKuJhrWXICc3+M(n{S z+db^?h$n~!>&863dI~vsE9^@NlkcR-HE?A*LOvu>W~%a1?6ju_y`77ERF8^MXqUw})OSwssgPtSGQ#Cub4 zam$L+Wm^SF zZ(TI`>GZl|)2L?|zqEZycWTgeJUeG+rp)#<5Gl3?|qA_Pd%lx>}zqH9$sUU|`S&uIDNLf)7jw$l6yU_E8&JNt0InZbrj-+|bA1LvQ~5W%2Tf z@0(861TzlK=}+SVAxiWTK$a=nUL=3Pm9Il$%75u4EjtCnQi=#R$nbr z&r1_~?Rp0v8gTJ&(@jR>bUv9T)1Xsei;N>-A^5oEy()6?vbEP`Lz+QTR9nrgxw|3% zu`>N>lO#WEVt50cGs1|jC-%E~tQiML0u9qfUdXeva#;s7J0jJo!*85T$Js-&3Ic7e zm7kdqJ}ueChOsj(^j^`YSj@Um)@^M@UB#E2Z$9a7L~-=Fwi~|dS`(SiiStwvwBXn_SvxGKwOI2>Wu0{Ux<@v(ypE5 zo%WR+7qvUnv-HsoxoKM9l?}VWf$wuucDnwKCYvP?hgM>rI@7wQC@z&^YG{a0kIcl? zniY+6%^@7bN_w6l9y+~qJS56XZDD0adUOa79WE}(IyyR#abR8XnVPev6YDMk3VTJ* z2z^hzTh3tBcwN2PIvGv;>U1TPmBK5c*vE9FGigdSr9rsWhm4~yktRvbIZ5j*HP^zk ze>*isj!v*2BKja5Te01ebHFdzQ_{yS^K@fx)6h_wja(5yYi=A_2RCg9>9j5O&El1u zv~@Chm|Lb_F+DSzE5O>*A;me_bSnB%ao%dd2Zv5tcA$4iZftkPW+BbbqTg#6Bh3D1 zpfzV}j4{jn0*L@+aKV5#X)b$1_Z;sJZ!Y}QEfhMuv4O9P9uX&p7XF~!o(of#r2}}U z>7{u84?)+|%s_7u&4K5kUYkX{K@bgNU3O4L@=aT`cCJNAa6v+fG(o!@=$zGu|I9{? z^J%NI5aHZ}(f)jrEr~u!A_1&fH&UaygDpA9M)l0}(!H;(nFsDCT1;ujPL9VO&Qz0B z)RY<7WB{???kkb!KqEH$JS2KE$EC$IFpgf)|6Q8w1n0#>%yr}c^iN* zx9=$=vuagijB#ykZ+|T;L?7eQ0Q(9riKhDkXdoHGJQ=(oINP*F4{sP`#lh@4Z%?C8RcIr!b{vJ#uteYR|BsHrp zH8A+PTMic4R7hebc{hTVpXN>__t-89wD_GipUb=R2s$`=N@dFs17{hGDdsBA$6(ke z%oEaT3z>j^2|zFJet0!}bJ1*i)&vdo$6uRaYJ=G%iyz;4LVMMIr-#SO94BxjbvCrd zZEhpi$KA&!PCH&sdP)}~MW^UJ`N2xT#r@O_-}`1pcmt?np&8Aiy|AYP@FuqDh^Cw5 zn>ZC~J-?cuhD2}lDGDF$sk8yY80VS4`IDNI|q9!4W@%a?Y4!}Gp2E#+PG zjzvbjl65)W91=x*80<40k&t-YtSQ~@zop$_kk(Wf$dB$N8-T?djAZl@XBK)zfU@k0 zD{Yz(*lajlYJUPkM(tv!(h-}=BrGA6>d8G%j?X@gn4O;P2|&Y(pb@eo(!r#znB75< zWxN=Ae4MrBuD|51Zg!3?3X6EhSIm&J*O>EIL|gna%$QE&{f3fbVuJm%b8crOJk0ON zuep-g=FrN-Eq@+H0_iT97RKP!C|j3(d`yKtKXIDvVyv$T%N zMZmdO`Z{#g*KaX4hvD_2?m{b6c1bvdAQZBC=ZdmXs=mJdK_xc566Lb)(#S79z%Ho) z*0@mmn-PGV_p;l}aA|64O3BEytsb7NyI*eQ-KmA|H(YG+f{8~r%hpSmYmZ1D7Zq;s z-gvO)SL;}V1_qLk6QfRPu_>_iFL2H7st*}X-dK#jF8r+pP;osDg!n@O28%PA>o7gSo2i|yB+Te3 z4B=h;Li%Znhga#PP@MzsD?~E=H-2}z#YLq~Jhe<>E>%*qr1x7{oWpKO9+=(=Vw>Dt zlW|K!`7mV!Lc_e6)m!+zw3}HHY)#Amx{h11B{T8EF^+zjX5^LD-#I>?h5^Z`Nojs6 z*ofP9&f?!lzEvhkxiC;>>+zsq39BSPYJdU!NJ?7T;NocA04|t7W}(LVbZ_Az#^$EG4($yr5!*Z>wPp8n+I|h=GrIr{*@T#kVNlrd z`Q;?W6wC`TWw?$?7%&(-Ny)ZbV6o^;bl7p1Jpm1QW0MOcwSvi{%9Q4|d_mOgxiIfW zv?_>bD1&cgwTI72J!!prK1X(5NSK?$=~j<#H7xnf1`0io#m4o7gw`NfP19^zpl8Q5 z3QQB6es`}fh8h=%uRM(o6ivwTG>X(QlO9pd^42^(^pV^+uSCNu&0r7D??Jg*HbT(n z>dlHa4N!_=-YndQ&wd~%?Kd8r%O2jmF<`wZAy2Y4@T-EIVsVtH7IHi5!q*>Oq#?F! zd_jC%lNJf;Pl9UEkQecGfH#QNv_hpt>5qnrY)No|GHw${5>T#yT=BNzLaMfzb=8L3 zVX+CPriEgrSX!OC$dm8)gm&vZ@?Mogi3oJ%d()%5{>4kv^Dl%4ghd^?8z_Ac%vin8 z@4Z%A5;B^(USVm&Jz%hdxJRZYAa%g4bZIaDGb5B-;o&AttoOSuH28uG{1qxOUegaz z<$f*l*2v1YE`7`~W@}0=!tbonl8LFXUJRh-6Z zN+cOfn=txaUqV6RL>jT+*j}Ah&hgjd?f8wP7o<<6rIPN6@D@E~PkpAL{K<-H>D2zj zA$V|{=&9O)*C^YX7p`!9&~2@m9!%l+v1ZXXb-uwZHYVm3fJcz>+GbZ*CwLrhq%V!^ z8k?EDsWs)infalhG`;;Dbm7$??@-&{;GGyA^-amvma^Oj zkitHXOUO-!8B?**M4T8`lcvmt7RnYWdbh%pU3tlWU{cbEc+QaPbFhcg?3hYpq8y@2 zf_~pMdW(snz7Q8OBd>j-c+;Nlk(}l=Be^@TA=5Lcss!zZuoFMQhrF|RTy)KSpI0Hz zC4^k$TiyykeLjqExz>aqzbePtb7X0DQ6y7V?R(eZuA}9CKh@^7cX{qBD=~h2Xr5zd zo%}BU%fm4{ZRyL3`zmuQEtfAvG^BOU_L#r4rFMSJ&)JPQxC-mU+Et8yQ=(iAnhp?R&0P2%l$O`}}E_X^Kzf7G}unyAs^UPq+c5B3NADlS# zD)lZ-4fu)DwHV_ zh*$+nUy+Wk`2-bJ)p6yzk=E>7rH5*3j+4UWmOxc-HroT53psA3K2AKVaLlOp;Awo@akQi6sP~R(3tMoyktWfvfoy8l@|m_) zZvzO``XUZGC+ADTm-+0ozC4iTnR&VS?lq`*9LDRN}z(G9mYu`Ba)jx=crB}pCHT$p1ka~+-iOiq6lQ0>8kCsapz;BozJlPsk z+^sO+t!Ppl zR#OS)_k}*@U=j&Rwz|7Gy}#aRHS}a7jI1DHdB^Q;349Rm)F+x_-$IK9z|X1xR1P>Z z(wx(fa2`+p10%5c(`oh!DUtD);%|O21nQrsgm%7HDA+{d{DOn>96vThNhr{T=DB&L z4-O7~3~%_IA^}(zQb%Vexf5mY^5!X)kmSm#XZr^6Zw`$Uf=cO))Pl)7_kMCmc$vRZ z=XTl8LyZKIaLK$#ik1_Xl|%OkLCGZ-m~-Slpz{bzBTHBkPN3SWdHhdwGOQGWLTdM? z6eMhjY<+zlsXvV$uboZ79gA9o;N!BaL$JkEV+yyT+A$pL8l&H*Kk{7S@nQl|Dl6P^Z(c(mcEna6g=3(7w?^ zji*$Lv3W78d|b9T(YuX8A4>92L;1+AaeOo+I!dVwSxJ{ehwAf8ELMhm}+$!7fUB@r~r;$s(3Oy^QLtp zxR`czPw^Yb#KbN$`ht)VYs4PJqCg!wOL6@iTk(oAO|kf^y$#ESv{!y}k4Se#6Bi(v z*smzcE-LyWWLN4+wfqO#yLGXdiK-7kz9Zz_0J(cj=E`eL=i_&is;sIj7@LOfl<(OX z5S02!y5_|gC04YM7kiCReYzHS1U_k{D`Jt5+ze%SjZ&S}Fw-Sg5E4;x@HN;dw^^wr!IX=>WnpG~s{X2kcCWF)VP8AKDGv`OfAN&5`i_mDDgd=)tfeyM*VCtG5xu=PTrCCk zMz2KE(!J4yjaYo`5L*83WTW?m8J=o(se-*8Hj}QlBBI~Yhx9iv1OWnXW8$+F^!bZp zkrY4hrx`=~o4R?G1?ZC8dpE{>&!HzSF9~|~d1huJu2Q(%SS%8F(i*lSkK&1pwbRM# z8B^F|f6#oc3ZGybI%xKxtm92^G+#Dlq;!jNj-&qcUiFq(h|>h>ek7;O!SEv~l>E({ zGr@%S^9dNuJSi~bu{(OCRkWlY#|xGmoen#U6=-Hw5YLhT=rQs?RRxEZ`7nrO2MD58qghb zzvm(XuM9Gq3AYp}$$`1VWx@Mcz6E>%ztsWQ`hCPg-sxcDwNyCK!`oWq>Igk9W-j*3 zPR@qTzdWq(OHLL-L*_f_l_8j)B^uSc6js<~W&E->?Z{X&FFCFZ`w%UDSrr&3)EIMf zzgDmjQSBC|T*+3My}P?>+!lbwX0h=WVEEL7JYLOh=3Xuc@_7>_sYf0Qvu+XY7}t}L z{^G>8fhGHHfcMxNpd{GL@Um6uI(EPA)MK*?CM=E7N7`qU=}kHCJ>G0Q8GX&d6LEDq zGxunpMc4lalUl_^@3{3@^@zHb{CYL6Om$J)2z$t6M$%B&i)caa@bCA(@NT&aWqfo) zr4(hII(i2B=`E8;@WxsBsfOL-SP}N#_TD68w5!6>h6ceE@FTB3C2-4E=qmg{lal(_ zMa$LXe`*wg@&(YkbsrZuUs?`|-gr+GX}P^}a)u?nPXu3qD3^}Y34a8qVxQIc(WZA) z_?#my%@7-b9d_QK=m!qj=)885&`$KEc|aDu*g}@jqg}g%!lG?|e@rB`^^@97IIl<_ z&1qVRL50f5$<4yXXFJPo8B@2-MgA#b#kP*-&q?p6SD~|;$0K9N`lEZtn}?@K!->@9 z0QGQkp1EsB>OP-9Lnhh~S;(1pQ1o@aU*la{c%a(BYX?)kgy_rLIVw@?ma+j*f+?&m zAoa=v)+us9*Mn8c8$OvV50A~9hYM(k=5YU#@>O}(G{MyViuas&rFVm8XZgr}^k2_b z329Hx%0dZU-EUTHH{`%k_&1PwyR-#-`Sztgf+f;vW&}y?&5&~3HG8E=Ux{yjSU#bn z+C01W+sl!kI^U|+Mce%sWtW;_@aIlv5p@z&758|q!$LztYwws_Tkl5M1dT~TKi|Tf z0XMGizsyAZX0_s1V`N#r0L{II!zv8gQ6`FYZpl-xHm8oxuJ^PdVW4lTm%EvcK7*ZU zJ~Mg_BFg;{{?f*apwycak6u`Jaz(<-4IKSw0&=)&*EKrxMq*3Be;j+$>HJcj%Ni87 z7gA@ebEN1Exx`34Vp+A@P$6q zwAGS%ja!K*_8S-ySYDwjZg8d|Kz~FCC;;(D-NOkCjqVtJtWYmiZ^0!+ej%53vq^o7 zBl-QN$H!*%u8q;%Koax5Aa7ZUu_dEjw!0d44=L~4=87ag`Z@RTd%K$^QE+?qKwdMPV`)JoG<05N zFw^*rycl-z*A7gyYOak1?XLRpzKGoc4-T5=IctZOB*n%0>o%d?Q_VlXKC#_w-+qyU z4CkH$=JPqW;4F$E@+Q%Kmb|k(vAOTDEBdRlizd|9Y7t63i_MW&3z>l2JlnYJGMQNw zo5R*?7>Z|FVtmZRBt`*SHdCmj5R7Wo~twmAFj#{#zhwPiXL4Ad0i$<%4N7eAspQr|$Gt zeG2Iw_;L&W{>#pwK#&GoUAVF&yookuUL&t???Sx80BGqy`W9JYh?hty6Y+kq>zv~(CUmvM+cCCZnoI` z-_h89CujjT)4_yyx40?j@a+2xdT@O6~&qoJ*mhgZU2^!^P%s9>$Fc_Nuf;S z7utI^am{&Pv9qf>%4E{pZEvZM@s2#EQy4?8DD9$m+O&$U>B1q#`ePLUM4j>5+m?U` zqHNk)=;rDe;Nb&=_8se{D$Iu1Bcl`2#Yk*apw6Sk{c*Vgkv%aq>3%*zpizjIvw3pd2)4Zep^ZS)e84vwas$FPex#dfOLf88` zZd;7Byqv+9UQbqYsXkFMx3K4j04&y;(Bop~fVIxlXNx}pfG3~V=F3sM%)^p%oJnSx z4!A4-JJ8RYFuH<*l!M&0C}Fp@w?nB?eE&lU^S?^a!%E0JJUp(B62aL`P3fXH7el*? z;7mo4i+~V3`nv~HMv)Hiy&6u7QJRPgXdQ!7-HP}5ndW@ z?OfLrV{ebL9KPxH=5Wic7CLUTCcl>+`Tc_Ve8a*U3Rf&^HfK2I)y8NRbN6bwTH(a1 zu5l7L7@3%@g~?+RmP|``+HiV0d8g(q3a7Rw-lRPj1;tr4`*L#rG=>dLzBxS%oI8cC z&v``OR2^O0;epNXL=q4lX%EISr`SKRs{w^Y&d!FEWwg6BCv;oLEy*(I0Ytd~DPMmg z;WeI_n$XbkQ1jpsHz9?`JY{1`AJj9s%=#%%*9;5#w0r7Zl0pIP)r0N!-BTd%OpOKv z)0h{4i3osp`-_Wd~T zfA7E759A+r_>qABcWWJY8$<`Vm|dN6#+GvHZm9|}6cd7J$`4*3eJnv2*9w(x$#V^)BE+IZ^J7atT7ZDPBy zC@Kkt++FQw;enlbJr7<0j`uanoZdc+bZ~l@>u|A(@CM#cQp6R@9F&YW(2MAYM{bYX-x-zd{qnMbOAo=9=6F%2`T)hX>juBSh ze{}L^Yoz2)Pfxk^|9g6a5l}eN^7BvMSZ#arG@+82XK~LVHPfXmz}nVSlwvPMlUn+> zdX}tmr(KN6c3rKnwREE-CUWv=Ft2dyTQ!A^LrNfNMsMptLJPYw?(7uK)J2O^wOIoh?0-FU(02b3cIDk>Jc$ z;K%aDBYoy)hVb;owkLCLD)gLvch4`ems)r3(~$(g{azS-y+hV^tuf3O)H?DbUQD`) zCov4J_V(gy?1~&}mlwB6GqMGYl@_09#k#)x?H^LO(Gt+L6_S#YQWB4iX19^o*)H*$ z0E*OG7VVj)ve^1;r?zonmSbXS!2LQtIv7uKQVY%d5Z6)GA({`}i*J1b;_o5J`?hChgfnlH#?QEB|9vBQ_jlW;5R7n8^6(S#Ul zN!0W8=ypi#>jdUiH$zoEv@}(_HjT0FWnot3RfV>)4hLi9(>N6+dVfI4-*ty6Nq26a zZIDH?+mb$>JhJNx#|o&wYH4nP5lE&u0+yW}))7J07Ef@)aj0_oD$bJPSB}0C&6Ggs? z`>H+{3$`Y)#_~WQ-{wzoo=1UDrR7O;1sddsF$aY?P2)X+=Yv$OT8bCdzBVGya=uQ4 zvO`{~;_4emH?g51-gHg~2S-){QuxaXZ`GorT#wSg@rBh7RKhf^ZQ718GvB;x-;cUs zkWHTHrZPI--MY2Xg~{-wh6Cv7vSVE>Y{9Fiw|7Mkv96aS?8S4uF(CMXdb($D@U#7Z zDWWPrJ$u)>oDN0Qc1c~UV^pV3<;odLt;q|We^Cg%q)+-HHit{jxzt2@=5rIhj+Xdx zHSDm(IVuKtv#ZKu+tiou4;VW`qj5TBSU^@cym`&gf%l*iAy{@u@^)2dZ&+g~!&n zkDd3t+e)HP{K=iDr_-OH!<`0NWSweW6;X|MZd0@A&j3ddf_w!RMf?0A$marEJRdSx z8hw1yAkV=LN8`af2Ym&>>ZiK~{hYb>BWbe?4Lf;PKfRBoaw`&!3e~_JJ`&i<*RP(w z3tsLArS)M(7Mb}hcp$WwyOI+6ba=soNj?Dt{o15qR;dtdVBPLA2xA^Y)fb7_a$X zgRp)3M&xjwK|Py2TH>`M98j@B<;=SJjb(AyWS}uPZ~&k2^Nw$C%kb30U`f<5)je|o$s+y1b9{#(1!zq73}Q$(V^|0mw| zVW79&W{Y!9B(8l3Py`D9y9`scunHQyv>1%{3qX4liRzjfSy>Y6D8Ap$_74>84|fyb zSo^h70EX26xMjZ$wHg5bf9GZ+9q`7A@$CQnNp!0)IXO8&dPFMdo?iF|%<69tnNDCT z`u&jYpOL&(kKZ|P7sBC%-ur`aZJ##3t&|~z2CiqBLLQD&xBj&*&4_Cj!p@zEviwSw ze;NF;L~h-EVJ}j7tUntJWhj%20p7y^0KepD+jXm(YIb2l)znl^&jb~$0(m?cFOU^d z_vd1gUiy~YnmdWnflCN`@?m`7J>V$4;$nsVxQ~m2!++=3?$*N8JD4sm^rFC9yV0`! zl#K&^g6oOBwQp^s94Y^~_pa+z1S+)7Y`FTgstR(lKp`7}=z_z){^=ivWVYirLX@(v z6INDNsjC6yTxOh+yAM$i&e@dytqhZBkN>PeTLrPL=3gy1JlZy7R~IPR*ZVbvI_>bP z`H${<1_|l8tq`bR)c*Fla%cjW8-FKCgDa=D;4dd^R`f%KXk}|Y;JR*YyU`=St}3MR&f7yKqOT>I(`36eavYcFJF7Y_wJVVmA-3tsSu@yUsm zfpm9qtWYOQPufGQmq204CVdwaXpUO8K(sTBAM9ZPD}3CFepw z47RVXVpBAL&Q{mBo9f%u*(ouH#Kpto+Rf9xmE|^ko7%O31Y6$NKrX$*s>vb=@S{0w zNbUoMGc2SRyW}Bbp5Rb0F3j$9hd)?a~-23(jOH&NZ3^~>ADnXdsq(H z2TTuSEYKyx2hluwPRW-1jNg+Z(KSDFNJt3MEwYyCcK6;)Fkl;9w&p6hojpR?1mTJq zLj2Yl!0chfAbDfw%XbXOo+~r|noa({FY4Df0C?6+ZvB_)U9a?}npJWP5XN~lEtEpq z)&U-aJ;5<4m-y(IQ0(Nl`Wg_)0jrhl0flVznbxPs$jGS;cbJb-#PX>D(d#KA|8U-k zO(W*@k0Bvw7Z;TeuEYL7o^B=8BbmQUoVVXe5X535@j7YsdcuGC1ZPXndt~rXZ(sli zE<((ISK-wAUPng)}3iyQU@0CQI9%+2K_nBq;^j5QCitA3SH6M&J|%J12RL-+Uh8|44} z;y1!a3E0a4)AJSYNDw9|l8Q5y7+@9w(y&m=8&UZ5(6^$Z@F`coli>qR?_2*`S65de zRW)tRtW_P>-!BJL-|Yk?07nEY2^jocQa4V8zotHR-P>jKb^6AJX-edZ!u}znuyA^R ze}6L-RNSdf+t}2!-1qwOqlAs8rvNE1!GHfA1{|93Tq|ha7F%OPyT(>WZzMln0RSsH zai@-GZjJC~^#3rz_u?RC?*v&2s%{_?o#oFS78ey^9+WT_Yt`%rzyLU42q5cm%b=K~ zJO>k6c5hWxC)AQ|O?vM^fzH$ACO$THwaX}g0=d^HQn-scQV4fcQCoWs?ILXJ=Fe4( zUNjiM;=8_?^d%TnOn+6fuGeM(0zZTeI&XhEJ3c;M23$k4^2QxPJ#Tg-VEgHw4G$?0 zy4CeWy$RsE6uODN0xL_HCU7;2TRV7rWe^JFCHUeEB5Lopi<+620d~^9rHrY#_HJUI zgpSVqVIVMfdy|f%|I zZGYX3fokI>AJI+wQnRkaW(x4yrq#w}IF0njPD5HbIdSp$4!>B-*VNjEE|>hDh+nXy zf3ry0f@s>X&Y5vXJh?QP8AxONWau>qFbQ(7fyx?s9GrL91ZgU#T=MNPw6aU5p3BD< z7_3zV1)peT6I6UY;D(6b?mYDjRgEkxC;&y6cJ$h34h5?-C-7z@;r!sjl$V#k1O={o zH0g42b8k`7JBAoZpj0?{taP9uwQP;$J$L#PdGk|JRI^gg8NhF5TY=P3I_`MkuW>>^f{QM!wH| z%ZVIgPolOmHtw)beVd^vObOU#utmFb$T3Hk8y2Mq#?tjyj+)xA*I5!x3{Lq4pITdAS}!&W+cmts!=n0)FoVfK)a1#dVRVI& z0G-;^2*HCkbk?7VmFS_C(Ir(?<0nqSo+saYzmJFQeU%8ss0r;9hc>}7nr*DDF;-Vs z-@$x($@*K#It2s->^J&}0q71Nwg>{XXJT(4X#+;&OTjujQiq25YKZzC;rzzlr2u>I zHPP#vshaBQlxE$c3~Y(FCmK9u!`TNJFB}*=7%RfR{!DrP>Fbk65A?T2bC4ETXB;`D zVgfot2~!CiR~p5sa2gSpJAhmZTnwEpHSk}*j#7O%B)0Ftyc>&#R02i_Anm|eC0gqo zR=d9XrWm5&ce6a=pqin(-c|#T)(j+bqQ=I?zPtFd;kHeussXQ_HXijdsh1f_bUGr9 zJBW}7qe7Rn3(kHhD{kG7a*s1nRE%6Mo7DB%W6nvbpPL@mXM51%&OXo8)+m<5(g{z zIcujPZ7QB>;^-ZHd;2$_h6Ag3FS!3Aw8p2X&S_JDffVN*A@B`6fSWmC52ryzu-5#e zrC+VJE+12pmhpHSH7gtr$7IbzheT3BSbY!C$08GH&<@?n;4mn}4g}XC6ZO>wPmWqg zE7m1FAI43z3_Dw2KrF2#1Zke9;6`&tLO65a^Z6nUL9v!?p{&j3wK|X4ly%sP3oLba zK5t#ovxF-Knlt>Ep4O;ToZGa>1%oN0rS8She5t7+Y;fIsB}6evc-22a%hYhpd=}cq znW+BF7*;E<>q|{lz?!z4onn8qCXLi3O#WeaU`zR_w9-QF?pD&^?kp?lLKdlITuo1> zk`*^Zeeey1u;=4XUmxRJ8J3Lz(aHNkV42(h>6LWM$&F)3vbsisjTx`R4lNZ`0X7ih z+_h@|QLX{kr_sqWItABrn$NJ*z4D%~vtA|Xf!l1ev7g91`2(j_1u zt)Rp*C?%u>ge48q-QCjtjvMzr@3WtC&hwt<`u_X8*5!o)Yu)!f=Nxm4UyOPCo0=Xp zC9$I8%(|->fEnLi`@*kS4O)+c?%`Yw4bfm}Wi*7V`PjBAPqk5;3YzzB;jf{>OHXJ-MR!~qt zq2d#o=5?m*1^g^Rbc<}lZis(?U@@KO6jm;;EqeVbQQ)`fwb3BfPZAdiB!sAwA05@n zGkM^=D6(s>n>;}Fs$eqCTHY4XD9xPuybt1+Z;{i|`mr_a3apaLE4Fiqihdvq%}`G1 z(v0TR{YtDXx_XLH?x%T}a*CME_SxHVk*}G8W+hQ_kt<)aJpIE% z<#Xn`@PnbS)uZ>sO!1}+kk=Vwh2)J4@dL}B&2>>%*|+*bBkD}9@WwTU)Eb0+D2%MD zt2p)R(493daf7>Q7Rc zgM))R#HRJSX96-m^C|kYOjk!-l3l<5B*5(1>8tAe4sL4zaOdmP zYd5psFOZ02#GK0v$Xr)bZ*qSerxozyu;};41e(8)Wgv7d(}Nd8zG{E`{GJadR$WU? z@)KbxT~$ha)tPabP(`dwJ@v)5af-!PEqm3@3-61@SB0)zy-ElH!~DZt(?D6ZX6MZ` zSbwATg$jaK_H=FPfV5oAbj6FQ4QLR6J@+`u}#JUxDt++qr zSI69rg{>{e9HD@im~Gqz)X!PIKHS|15gKDhMeWk6yZF#;N0em~=3yA?&3+5o;wg zHDvnV!CMy0!(X*y5cYGze)907!A3X{s%X%*-}u8O4EvS6RF3&T^{E`XG}y%K6ME-6 z8+L@8rb28k^@;C~;tOpJIAvUydFLcb7HoKN`j>Mo<0y6%>5Wi(u~RB5T~%AmPF%7d zr(H*$o*8j0UYUqePR-74`IWpQBShE8y+&Q?9|dWB(5Vwx`wQmc<0lkZ{vb_+>_hGO zmfBtB+!00~{ZjLcD&-Ko$+YGf^3wtJL8l=zA|#BCzRea208e*pT|(TeS2?1!wzws$ zan(EIss1tT#`6ar9e45Cwp7KNjS`X1t3-C#MwLBbp=x+PHCYhq`uUzCV~Cbl7r}{W zz8vpW@cDC(0LsSJwm`JDj@(?|S;m;lf3+R!L)gcyH5FxHoRpb%BW|TjiTKE>gZPkc z3F*ombrMt#@X7~^y^V%%BPuu=BL-V2l;FxKGtexhdUkqG<8Co-FF2to*@OV|w|bRs z38Bbuk0IhLv2@&^gcP=xJs>ZgTyl|+87XXGjB>RVZkmK3x2Y0(&cE8PMHK(k2?&+> zbOD*DbI4nZ5WvcWZ2kKM<%^V|8XN>Fc*jrfA*=_;r(nLHJcDO&u)7f*CiNDm8cWo- znVHPR$~Xn=G1p6vj04OjW!OCv!z!t@FI~Fi2h)zPY9}*;+Bb9Sfa%=2K7rK>{D>WL5%RG4SepDd8 z`~C0dwP)X)OOY`Izr=O?>hQwTQ@#2>4l2pdl5aLRW} zYM^ee6?!=LautFI;dC`nBn&wfP}A!@&tY1pP=Kz}*}plOdU)?YP?xKxjmAtIohog7!P{d2u9 z0~+gi9Z|RPorl8GLB%1<@}3@+yj0Ec8wq~~;<9=XQeSGk7F+UE$}ytb;}{HP!}OQg zl`B`+!gHyrZ9S&!#r$U8Os@Al7Dq-a2Y~QGIvgY9L@LX5Xajd&6y$A9N zsJpxFAa`QS@;iD=wC?Y$&Q1PVfNp;Do2#s#>6Oxb|y}Zue?16<9YYH zQIv%hvJ_5%js?mF+`{~C7a8KkU|OhDpTqWn2m>#~kh8W4<=?i4n84;0hIlN95*@7& zdEmo%;+`|gZ4YggXDnZkPEWT)o~qdsh&osj)ud{$+qGE`qh6y~RI^@|E3@Gd+TC4z z(6Q{4D*wNZC(NdJZGDr16+4PUhw>@mj#EO;GX&+oqO)J8rJWq!X?8)O1P7h(>NP`o za?(qbcF^dz#B8qNNf@kdP<7K3V*T3c?k7~N!J zuH&Tq2c2Rf6r$83N5Q~F3D&NTV+hZl%CR4<%A0)EOx`#u>i>`6zOvq~JPr^Ef8rP0 zkr#r9QXw;l^P0$Yh zSF6aLK88d0UZ9rR38S`H!hEBb0rKH6Lj0l*ocg0UQ!u>vZ|+!Zo{WBxZn=wV%OAqq z?|AL}M5JjP#1k{Zb4sZq-^(NJUXmj+(T42`;nmdCeY@vt0L!xaN~6jW4XN^XKpf0O zV;JR%=0BC>fTog&F+umKgv4^yML8nLHw3|osoJ&AqB6rW(Kt}D8*l}{%qL-wxoB)e z%0_T@&p^^D+Te5IQ2jnKBOz-CS5oPbT=b2S$J z$@?duMNt6w_Xq5Uf4;j7!!@$DLlBO6V6~|k$p~V`+tFb+I&ySw-n@y*Yq~aQTR2%+ zU0ofsw^;k?)hiT=PcT9G1CM_`w^EXbDWvt4;xA#r&oTR3{9r9zTPh(C&oDE_#l=OE z`wJ=Cr=Z=cpP%1Kma-=f3aK<3d@po*iCJC7!00$M3r~+U=pQ=Pv|zq{Lp@p^3bpeX zr%E5bW+v>lo;pk?+9j35+gI#oc#HXj+)4kJM7s;X1L>!C0H~P0%%zZSI zU#PYJY4H+5D7RT_Z$(+zAeZu`#PG-UD%%tO_(|@cW`&GG_#bqker!gviEbvj3}wx( zsjv!%(OgS!xuUu2A-X%0_JZ*baNz8{bfOk^JcTqPV|N;GZdY_2^(C`EI@n6f&u{1R zZ*Qq#!l+>~H>8>^U1{614 z2N{r>KgP10bV}LN>GW)tQX7Og+bJZif_iOX_+w;bWWnF^POjF6pM=i5%qQ?+jPBc& zb#4l+Vw$Yib3fFamX}fs3HA%H(qf7Jd31wAhuU#vL9o5=H&pDOJ1$~)_wUh&IG;tM=P<|6NU`H( zSWggsH9lxPRbx?KcYrrKgOX+aK_Xp=R)3GcVkh_^2Y{04exVZQ+t7ejr{yg+l2zg0 zO$9W1to6;!%ic5$@z)ba8PSFShv7Y05O3AX?p}EXAa-PVdXdSs=%FyBTE6*%87Wa( zPD|R1t`FKiFo7<@{s|!2YOubPon7{5)8<%d;8-4bs3FYjWs`}e;MbX`iVIMNj=hW3 ztK#q0NfTeY=7N1c#*``OnH0lQKwj+c^?HiYDJ2R$wewm_*xsKO$5(7`?d{FlS`3k5 zfLs`gu9n1!>HJ&xLMvha>kMk zanJ`{Poq#$Y_~Rtma&JAGtogA$&clad>Elc@?ZtC-Wt?5eAG85cj%uLAMI?QztTa~wq|1dZ(7+3qSV_r>>G@!77|ERPg4`{=2w=Y8-{$Ek_mZ|~~W zt8E<}CcCS{(Bup07FSBmkg!c1>geq3JhD`>TwCdL#sQGNeE?tU6Hc>>3W63oeGl&U z$-;ussF-4Vj>nE;J9U;C4gx7botA6S#<0KTeIy9=px3Xcl##=|WlqZFY4M}t(Qd_w z1`{4~3JT`lmWJzF13s>zwpy+%LC@TmiZLtWtOrgFNb%EUT;%9I+PiVz5kV3gKQCW^ z#PuJQ-QIEjU(-w-%C@l66pHI`cP{j$ z?x$4GNJc|z>qb6Ix#u3rq~8)6Z_UQx(}=t*oZIg;PwB+)iexaP^e=LV(8(lvd9&#h z5x_LEARQcEl~5sWcVPL)?ZDQWN_jb`;`BLEVjE3$b#Jw_!6>tI$ELTNudF8kZfYMUWi79H#^DhDv53ye!h$K=Ft7KWeTg?g z2y%7yC7?M%*%hNfeWP#w1vp z`x5rIoX&6(b@kN|AN+e_W{Lw=2F}Iq=xjkM$a}pi(zQ-qID3jM#U^?0VH}5CB=yEv zBfI^u>-c%3cdFaocZG$%FAp-3Os_ze_^k5cajuwGYAq|(3AutwXrw6xxU}pl1DS{c z>i(o#5+qhTy>=s#5q4tFE}PY{8ZC%R@QaWW0<0LWuFju5g6m%`eNK>A8uoxLbM>QN zoJT|`wv=Jp_2Sa)vEa+ar_}z4)qBjmxjbz5Ro^2N+S8PlE*49Ryf`qfL|^2m5{zYH z0E~1sP}w8Z;t2SjPlfmE*?)o~V7*ZKDRrpKd3Vn#mdVu5I+2XC!@*K&dqwg|nSP#| z`6;JYyhaIevFRJ~M#VeE2w$ZVh(2Ctf*dY}Qy))V{SA}6UT*u)P;z1Fy;2!l!&FO3 zxOUL6zbE7D)^Q3QPaofqOuWFI|4RPduOMLuF|g(Omdb{SZT1-NI;6Uwi%xNpJ`cRl zxVyK9WfI&mAbFQKyy|kS&Iwd{c;>*D2V{W89eqQ+K8j%2)kmYP`mN;mpWcv~klIir zA&4+OTERbhQgJw6(M9%6$DxMA6}p86hh5-JDb9~d^*0eo>f)@PCMAbu+mi5(xJJ!3 zf-q3(A^@;#Giqi6@8g(i6N%OH*e+4y-Bcllyc{6MiR()|1ZOWs%g-LjT$Za!uqzL= z=`S#>e0Ex^(3a*IfTj;5?%us1N*jLI2TWr%ptqqHt|}oBJ(3YRxx?!I&pbii`X?fN7us#lP53<_vGSvUd=cT>S|>_c^&+Nh&lDnIgBZ zMBP#EZ1eOsi?vxp);D*~zPWR&;-#*u z`;(q*OUf|X>yQ*?a8d?g#@(hJ936i;uSRZ*#0?r{!OrQ=W(0*(d{r~Oj#^xWRze#;TH#Ae&qOn3sJtpCBYEGxdNlIYYdTrg~0 z{Jks*wm0^^Lg>)9eQ;PRZc8~j9fN?UA21`=6Q$078()2$k#Tj|t;5sPvuHBrK9~2Q z#|N$46BYZDoG>M8?%Nih1}@FblcGilenjhw6$xqvQ@YW0AC-4{0g_+y*?gApowezC zc5kU0x(^Dhdr!c#$w=|)+wAeD^CE|$)IszSOLP@nZ zFR-bP3(PDp{yzB%+EDg)rZhD*#bAUe#utK{EpVr}mZU8nT0>74NJ4uyGir)cE<3+zIW#sJ^y1GT{D1N}Y9$T~*kf0hP=ucmkqNjx&F1L7EVPJx;H zSm>d_EA}fQ9Lbq^K7E~I0h$LU86{~FVDS{x)W8`4!10?oYFzh#9PfFxp~u|a6rO`i zzypAKP>~rkROU|Kz=Ke{7wp z*^E(jS-w|Nzt$k7wlG5fp~6TF)k~TZ1aG$Um1Uc~k+}F|Xh=`iIFM8;m9WI%k+7b# z%teM1NIm{?8Y6zl{bX1BscyZ1x(sg&WTr5NyNz5xTqB^(r0Yhfrun{W-D8tS!A~*c zl^2vnRh+FwX{T|o63!wRMiPIt+46dMax!h11ir5%*mYO)H@;IrS5jirJnPzslBTpM5N4Rf*> z9~YOwE@P^U^TZEA7)uDSkoXT(vYW&)dQg(b`{&=Nm5j=SLDVO zYCI~^STx!(=0fjUj#Vd1S+)fid57H>0;61VB+N+zrhVT|orzgx(GV(iXAM5e8t;Q{ z@91@h7oFd&x(eFN7hqEXmOjV4g%(ilL@`fF)N3aBAqVIk(>*NavAtp~!-zgcS||a0 ziK%fOog9}z>LEaEJKt-bM8SrN|9YDql^|%>b#7~5EGpnbF_fVwlLVKqgSHJm{{H?5 zy#s+03uR#|knI##-AkUKl*BV2fO$=)aa=jlQ~ttPF5Tn!-ZE=FMZn@I_A2eOFh|+C zDje}KuegNu8aTwVvNF`2^)ij+>6=227Rbw2L+uP)UCFb{cUiE{oWU~bHI={K=M*K}iF}l%c;?0-6waG=c6Ne| zfNmjCTx@6b=5+D{kz>%D$tEl;3=cBGlTd6#GLFKggdx$?;hq-`QTsLjt8Cd5U!q_H zj`28hLG@CM+6(FM)zTep%ifAKaUGgF27g|P9HWT*&kCu_633Zs zl>$3dsEZp=U$Yx00}y{K&a&bMY$~4{&RgrR??$#h+^p!`oO_==XScP!PQ0l6P8G2G zRaXxIW5P~RWag=nEaCd*{Fv_?UXEle+b&Hlp`zP)Um@udcW%;zC#%9n?d9@dNo;Sl2$7MA4H53U5jO(XlN5D`-nSLH=3dm6%9*K6-#5GZx_|m43NG6qkWG0f zZ{IXlH@#wTcsTr>ui5e}0_CDKE~o61 zMVx$>STuu4DDsxVJZ(__#fapQK6dxboIy4jpAx+s$f#HPCZ2scIzj0GH z*U8wd_jscJi)7*$*#;JhXZe6T7y-8VtinL#HpZ&Ig9G^5(59-jr1%;e5|R%Tei>wTDOjEmDN#Tj1PzfU{FsE*~Sg&&)NggSSkz zyEp?oi5#*#uH?Ux*~E-reh>_CtrD3WL3Me!+A+ZSKFAy0ev&>qi=o4`cAH-=*VuaLr+=Val5G@Ep;{(IJ(;$8blWU? zQ$(et-XZTDU}nMes^|vQaEGIFhs@ezYU-=8AY0ww@fAN)BU)CHzPoe2+L}*Gq%Bm+ahaKUp2Q8G@c7tnbHY zeVLk(OYfhFkUm7N_U=I81&oD_4gY}I=3~fy=9py->6(QF#yfuQKm|Sd(p>nm+_T|j zj3zYVik!@hS>sNkJ{j)^u}2vW8)6nTXem?ks_vy2d-LW^yx1`#twJU2Dwh;s7G1Pp zElV6fntx8c{tM;3cD_vXz3A8(Uq>C5s|@jq#{*KAx8NF+pD6u0-4b?W(A(&*+*O2y zvfrQIqVzz0he%t-MH&CF`}&rBB|f40X&8IH`NT#?t9a~`mRP|CZJd)QPa=MzwR_}& zWBHNN(-2uq)oY%lH(99foEJ_xNw!a*^2GpBoBZZkwhUKQeAEGLb6j7s(^aS}H9ub` z3T%8_DI9fs5?0_R{R&!5y@w>6(HB%Yjp27l3`px&hLZab! zI^)%(PTAv)5dG>PCY}_xUvm3^G|SVmazqbP;9V=9O$o@PToEK8RDa&amT}BE}!C7$yN$m{|ZF*S%eaq^|9upO4NVOwu^w|}_D z#3kPHb=~c+#jInu9fs4iR(PY-CsVZYPC3G)zd#u6^T5L5tVDrZM*m`gsH>}Mk7LCk zIUFp2dICpVScU^1{%0~}AZ_(8lBs$(F^=+WqXUY06l|ZLwtNw*X$U-1{A(^t9pR8t z^n88DDz^Rx|4m7Wd!O+4c|2TPgN?aP0JKlPSdN^o!YAdBp$dq;Y38k`pU_YMRLV=jM#p(pV->Xb zraiy#_#Kdetu7$-n^ReYE8r?kf68 z{DG&4aI)9#Y-+d*kDm}-1s(NwCv(lO%G0VlN2N<5`@<=RpJ(6wlK;(E_z26#Ary6H zs^jwH%kx3mPyqpc-BJ5vdW}9#L22({XprJHnC#|I`*G5VJWmV!{!*-9#j6oSRt@?c zQc@ewAq=V~7G?a*JPV3WfD!6UhyoKCl-v29SC2++&hRm4M7O-f+DkHRz9pr$2r0Ts zO#$<83cjZXC4^>FUy`wlT}rJO)re@H<&1jxkG|odS9!R|^-UAJ-l&z~PF_ z;sD@?e~O$oo~)0S&QFA)$YYx?yY|#N*8@a@fF~tVQpR_^`^6zAnZY<3rKuO_PUre< zy-42M`%fK*5uV-!1}g%P-L~@`Q!6K$UXx$==m&TqA0_`nuyFsrmpG^`A>Bl%vjZ{{ zL;Bq>w@w{#H=PzQZef{zM#qr)69!KW13v}g@@K}FFyXI!NqY`3et@h3fWlweA$H$H zTLxscM+|53wv3yZg_P9Q6PFE2@m(H{)+X3B-&a?Hj0w`|%&>rl2{c-SgX=miK4iDY z+hgQVziQ(nnKTsygu&bvspC$%xzY(iu~8zRX2=Hf{d=6q|7XS~Fw*N>{{N!Tm554_4&6kwef*ih~6?gA;b9?s7Y z{~5Gq&n4eb@SBpouRo*8d=NKTjAQqZ?hF^U0bU3MNkWy$9C%-PrKM`Nj?PYBpi>C) z*s7PeuEo0%hexgN9h^ON0us($(@iZlKMTHi!Dd*<2=_ca8P|OGiQdvO2ETkyms&-A ze`?#I!8o)_!?v%KV&1MSI<_8CP+Y*CSzP8im;p>-*1d8DG$DW?6#-hC;rWMlBqOzu zJqmybpdqgTH-$!nJYd)Akz)J0`cm=t+&ngbHulHJD!u`d>!ZfN9d|U+K{;wI8 zef_(Qn}%{#%ja;GI6vq%7(s@LQ~W)28>Gu_f|FGLPJI=oa3yNXYgyN&(suAOWE{iG zvJ4Rt0QF$T+vrGkfE;bv_CR>bnc3MJ0Kx%SrQz&7ElsBT{0JaDw%wkAE@{bgPXtVk z`bfxrC6Ollx$gwKKjy+7fl97*Z&PE^AdT|nTzBC^s1yl7MV{D&AuHe^s>Ry( zMjcXpJHoQ36t0=l_Q#{Cch_guD%Lx%I0v0-$YF+nvZ`rCPu6g>$~O!{l>gdjAP$0N zf1w=)0hQC!uYg*zOm ziA8`s1$_aq9(2xZGif|wxCin3?{E-_QM)n7LIFtC>j@btOVsQLRTPyGFjlz z=&bEz0iWEV#g}PGym67>+gMF-uHCR$dv_DN{d^li37HrDl#a+BD-KL81mQP3on-b#%iMUMLwTOGY3g_lgf9?)fNPCP z*?(*4@X?a;Q}GlfD#u#sXf5Ta)Ivrp#&oDcPD*VOwkUN8+o$Rl;NRz^72gtT2J#n_ z^#d-$o~GKjOlp?5`iIh3-l{SK3U$CNTg)g|wYxFD>O;5xdS)Ca{4zu8+&IyeXlPhi zA8lft3EOf+9@R}gRza)Tap%7)u|7`bd_Cm>OoOrg_5pt%KzZbox8A8D!iE>@LgG7h z%6(?+{&23r8&K4M3WKSy5HuZ)DdKc?pv)h-8w6q2rF@MBP;hD}aFHj6STulR1Sw2j zCdp6aU%)V~Y?1$-d=IDX5ngV2qTJ?x%7LwzVcs)atzME!Q}HMC88PU-RqH!|7}d5E{d32@klkVI*LJZhMsH4f+dT7;~E~##t_8TVS_Z z7bgF5BSB_#y85ccqS{D{=m(l*by;?wT|FXPSsCYAs8c4W>q%9`3|tW=P%*)8=vJvvx# zFREO|BqeUV#YXgHrUIR^nqg^QgB3xNis%0uX@kFWVNSK1fjALTKIp#Q;HVRhx$B&L zMTMO;ak8=I_F{(xK;UXJl?L|ptQhft1>9-pMl6FNb(_b1E#h>V9J)clWE>qS#dxSA z+4hxzUhVo^1#G7Q+Xjcj;RL%{AcR+-lNQ-x35Ys!XY3AT=vsbk_YS49H%)n8y;ir{ zT(Ud{c;YqCOZy0?M;ZsRjhhDdTRL)najK1)({2ZS#?`0RYf6Pp_+u+8Ig@wqfV8nG zGlAWUo(q&eUV>atl*#zk4-Z?s{P3w789@4+*+q?1pnxk|y6L<*!W!XAcUhitLw&fG zN~prWXRk>nR`Qs?YskyJbD!22Z;DA8Pg7R*4C-Q%Qoq3RDbz9Q{;$x_drls^?J3Es zl@xgXt9IeyVY!u+sn7Du%4nd%a1`Wd$k2{i^bZxcFbI*ROz^15jB6&(?AJC{T zNj_WlM9~qwo}s?L*-lKnEzfgr?pfNduwZW~}n3gdyGzk)2zI=l0>7qzpdT7|?^l z1m9X)UyO%eLZ60Eoi0Zl7bqpkc^E>gY^iA<6x|DGFDPL06P__$B#{QS5h7&WJMc5c zOF7^yTqy&1=>6EwhSpXB*z~F=x1Y6`7h9bD!O0gmhw$l^5a*CACb)o#-!#}E;pWRS`CsW15bf9hm7d5?Xyu!oXNb7fRu1%{ zvq)0xIA|~U*o4|=`9OLTQMg!3WhVtRvlF5vfv+3)wsUj2-?q=9MUE4pRj)AfWDnKh zuG!TQ1aT$n`joUm-RX!RZaT%@ro9I>lgEhatl}V2HdIB|8X?kt5P(R9fg+xCPQafIng8l5)Yd)A4Y(-OS@9L=R{q|vFI5X$z7wglI3zL zASYV+*zMBQ+WBCkMYcFpYj?LMUvlrW%V@kuWwcoHx3v*UY_5SDs;tqg$vH{F3|4&m zfv>-sbzHn2Eq_D3Q=7Bz#8U~qrz}hEgt22zPJo&;y*2!7L8RQ-FcT9i2?w$BQdY~| zsHV;d|HD+u3n@tsCA?=gxRK{KGszv3|R4GYQ9!Bz*1Ut%vK3n8e0 zU_DZVg5*K{a8zFHqmGf~{`PiJxx!H6pU`YiXbW{ShTs^PeK36~TE238wNVIBFhdOl zax#<&8SWsY*nrrb1}UkPkOqHZcyqH-V}f9dfbtjbl&%M$*1pp2j!hzcgOO--5no-t zoe%a{%$6i;P^!3yz!rXw8p~~S~ zuxaI>veeLw#&Gy4?VsXkd+?hgns;kfDbowVH9~9ZHBh8gjpi)UokXLn<~LxrgP5Ue zdTr8E_rOaW@+3IOZF}R2A+;HZVNh%R!kLaBBRzF&J!K2Oi-5TJAbSIi ztDQP&aLsx+$(Fi%nO>sHkejsey{2b^V=d<(12GrM8nZIJEF5vcH&!o81W0S}x{ZTu z;LG)9*N`KezqA0yY8uaoH<|&>6%W)GDn`BPROPcdgck#r1hn&=*Q(ZH+=WYC3Gz;|G zg^3bhsN4QIz9c)pqM~AE4K?JwfNoDwfd>drOTb(sKg7t|p?pE_l8d#&@&ecfbIqFK zOUJ|L#PKecTv~QoPYl>!N`il!G8d|g;Pjlmy*rt%^KLg-j2dqo z5*-9E^ESNO6ez_2LQhFXqDnvw2m+%7Ywj}@=o zo`9<5b_^SWVy7}e+1!(78a(<+Vw3uDnI5FzZ&kBOx0-4+LN;TfwJN2gV=Yj%CTVD6FxG7joh~z$~Kpav+WKpA5=Bubfqffe4 z+^O^I3)wyb(JR=F+$`eL^?xSKnQnla*QPc<^&BZ1S1F$@BT*nYjwKMu=!uKsYvA8q zfei|r7*t|^u(?oQEcw|#?sknuNEMC>k4NNDGS3>fnt;(Gq6{9)!2(VhShUGMwJp`=>NzFrrfpeG5E}B;@ z(8b;>lDehF0eBa3WqO1Rv}y78p9J0hbhk|RZ4SS3F>_FA3uRDCT8{E3u>0z8G2z^L z?fQtHGSuj|p}e!urZ=x<k!KmN|atr#{s3QEtM0A=`l>!V;Hd z86j$Tbp`K$F6f0r^5jc4@Sd%eBAv)g&12=b~e%kh%2)ND~>c`9^|Z=pAruwq|RR~oD6d< zHAEDufEL=w|B*; zv7Hl{>EzS}Z(Oax2FuMISWck(Jb3fXT`=%N?nt6^Dn=Isf#8fn)GN@5K=%k^l^){N zD;N13K!9iy4~ED3@J5G4H^VV$;@MO`Dm+-1I6uded=N-&WwXZm;=W}Is?mmD#!lxx zgNr2F!fz8Qua=TCe8f1j2e;3iQ&ViWU!PI=k*DK)Nb5Eck=jjqx`Ob1oY5-gYf&`n z$x!L=hc8iWJ&^G?{!O7$QzmS-@DIyHckxEzct_Sk?WenGE3t_!e8n)8%{&<}dIgJ$uWt7x;n z1~_|(Ax?p58nh%a&I7j?pFzjB_yuU%8qEpkH9p`Mtj@Be1m9+Kx89HWjk)uW&Feo{G}***U$9QNA*DtEY=^$Ec)QBF}} zH`l7D8?jKI1}-l@Y8VC=(<1jfi>pTbwa^6Md?Caz-1FyWD^O;UH;J=5;aI;vm3hS# z91;&b5Pqgn1CJHv<||(Fuu1Oa@;#1ba0FO}k515mvXid*gO+oA^}@K5la?nPe;<=G2mW-NMe!{3+tkRy%2xH?lA{m*?>kjHzHv4UhkA?+&m!0~&y1-)XECr8t<{ z`?7E86a{7dlN*47#kc^td3 z5xx{}DszY$3?}ed|K2rzY%oSlu)y^pm#y)ya=(A-76bB;KMmxFO}I?>-#2CX`0=A( zf1_UZf4`gm$oTwUuL}YzpzE0*{wG6QcQI1HLz`L(+XUlQ{P&0+2Oi$<7d*oM2&p=j zY(g;yFSOv_O}hWdbNpvBF*zN0nxNaXg8Sbo6x(&@YHebbUdLpFu zUwJ5aa{uZZ!lh{&7n#WP7J4i zY$1I8e?QOuB6)s4BjoS2$4>T$&-#CLQU9S>_aEc;k`=@1k7wBSYm%gezQgE0a=jjF zppl2C@`>6>Yz6BF=u@{-x^?|q#Se{Z9M6IrroHaBg;N3Ug8rdP+-x9Nolz%fsYhfz*K{IA*^3ZHny}~l@L7}{5d1AzDa7+z%IJA z(4+EH?aNaj*`b5_Nlj-L0B5O|s9O0voG^IJuJJi~$!hPyXoR1M@8yg04vGti1PRk^ zKbiHqx`LuVhdZfOXPU9qGHS*vXIa>VgYqG z&zgH}m4!)n$N_2LAG8y!{r>$F>UDANzI=HUHC>8ei=#L)r}%de zB-p9?e2@Kf67MG;^gG%FdA!(6g(S5+6goBa3Oo$-Wx*j2-trt9!&JtHcfNEO zD>-#cfao9od>LuJb5`)wi5bwAwmy*J*S0@|qo~lC3#@MVAi^<>=uRkHj5ZlD zca#F9m*zRLX4_24W7S{4kEbxuY<)4;(&CgdSYMz8fQ^Q0&Rb1P9dS8%a(A!PS&W}U zB{cjmGU~kxJVWPQb3|b6e1+kTMYX4r^pNNeA&C;H%htD>6c=5@5u{8>h{UBDBn46jFJFk@fY!Z=|BNgM| z!)Rz>k@-`_DrSc_6j^WqTb41$Juv=Nto;910N|3{nEHQL?f;*nB_xBfYQHFo=_ODnz}v#`tlZ<+FzMHQ2hv6SvTe3o!vfl3JAKdo54(pc6 z%v1KtrV|tP2Aq=Dbd<6#NS>vC{^GNwe-r`o)msvg#OKIYj2~M^8IQlR^u@bMk9;M^ z>MZmJ^3|<-b{G>{K9v534J>176ITqvUABO)Sl6j%hB>DHfF-#PQzW2?kEzkI0{|OEKs1f(iep>o$4u3OWh#DN-q~J3zF4hOML2jJVZL(k&ONpTBr%aE}pw zN?N5ANM*oSALYEmy$>}o`u+PiO!Wr0DWbut44FHe7FQV~d6oj(K6RaYUovEsf;3xL!LdcqEskF>nGe(Gs1_MjIUsbnYZgNGlU7w?w`a^4wj2J&*E} z@w{{9;T>5IDs5q5;a|5WrnTTW%d6~B78Q*GDU8_{9wOiV>lH#x6Y?(yYW5OPYX}_< z$A+|1o=3%}zsbxz3rFPnVa7+%YeJy8A|@fp9VV3YyA0zhM_A2eP}uJ<(@IYbzz0C& zla6gSzM|l_!8ncuTvcD+Jt*A3T!mZkf!=q<K|9{!ENQusPhkyf^UsU{XTmnA8z51ywzthw(TK zR;d{R9c&?o!2r^35p!KIAO8MhjNT$qR{86Q3;_$io&G|ygV zTy6wHLaQh(?b7I>i2$@$ID-P|$nv!6nTNRiGzdG3G636GK&c*dfH;d{Vq$vH-=38w zF5s6M1}y`yP)N}^F)^VvrzW&~2A?*heo;Vm{t_)nA4pLTDo#FuJvuwa}c}{?mxPPCjHiY7WlfIkVj^GEg5oQ*appq6oMO1+M z;e{&--+&KG_~{TvEzBT}$ro&GPS<))+~7uqK0Dpd6;ia(aqTc#ix6MH&rm|W^G2uS z**Dd4w-4li9*yrXBJ#xqR%?xZ6~-PU6=rtsTmv| z91MlFxS5NHpFD<5JF=rZGb1lAFY_@`$n!Hv&d??IF}SrIb4&>&o8b)G7eX*=jlVoR|1~NuKCJ%TqFkz}Z)uVX>HBk~zKBe^e7RCkp$3ag)i)ody4DRo3TTYn4gq z>##+H*{4IWfi_D%>^=l1ApCxx++H0=rP3%>b0N}%lL2(H=HxQ+@Ar0}1>96P1B%Lk zlI<)2uuw)}Jy_Q_qAa3~mh*BQZE$4yG>i_;RdV6Zd=(o>YmJVMKAHEGmyqElJyBu* z`6sIhS>WQihsqM(dH!NO>atPxUvcUW<1dlDw;qkB;?0rEi=->Wop^n<#q4bv0DD*{ zqy_N6fKEd>xIf3+mBmlDI?-~LtrJ-bP+d_@#zpF$Uy~ zT!0KC0IerF98s1m9hwCD*_Q8^AuZd2_x5hlq+2p@a<-&ig|-#l4;50xXkebG+)Id$ zM{KRgzfp+JNcd}aN5^yML-G3U+fx$C{aI+1dF{_NU}k+c2%R%PkcB9>5Tf5QzH+fs!EcWl(hZ;vZ0<*H(neZoE$LnS{9a;QX}pEli+6veDJ9l8?nekP`=di4rU0_OaL(r!|)BbO(&rY zie+TSkGSVvhta21i?(Fl&1f`%V|p$Rq%;EDFHk+Ya=Q05-rV+;hfG06Xf(?fbmP77 zMEl-7%8hG<{Wi?^RaEFJ&iLGDpLLE$DO3#G!Oz&7O$bVTRcX-L*wP|crk4%clcu~p z9{7=aVVw1WPJtbn&|Grkak~cH!54bx01<*+#dbb${F6urT2{|*#P96vAgA&`^F;+z zdjFyTeD}bsqDJHYRCeXzRIP7&p*TtiM`Q|xQbI!eNP{V5(=J4knRbII!!dS>jF~eW znP)0$tB8;&LS?8VQ)ZD0k)-u|_hkIE+?)^DG~d7byfzVwqAk?B-PUUUui@V10t8)cm>mdP{qMgT&>@0OyofKFI9t;_(S*W z*Lp@qPnMQ^w{icHq@Um6s-Byhn{d{Jl4?(-Ml2mSHnxA7q)?Y7&bUX9?E7JZLtSGJ zn}|MEbQz_nsA#i_wviFl$SC`Ch|n=3qj*7F)>8gNHTGCS|9tiNqjL4fRa`ojUf1%d z_?&NDcUmTl$K58vR_1ni=j3*#Bq%wQo`~k}gXzSF&pKV)oVm`?C|aAEnr@sd^-N{& zjwvWwYgB?xd?ifX+foyLZ78$V;3BVZ*9Sf=1(Y!y+h|9QNT*hqMBc+%yqcPFrlji6 z!Z}o)TAI&=g7X2f2w(ZITdUuWU#zn_`}!80A%fLb3tFgzQBrts9~Z2ZjqKsJmrFf$ z^5md8-zUdYH+M12>jTWzXV3i*a6i~^u(eh|e=pAs9E83L1Hp>7pMq_lhKaWN$rXF* zH>9a~9g=$o)n&AT=Y{HeOO%up-aC2M)cBPTCqi6;T1*l^4rW(WtksDUjsK96 zPI2F~qz-dQ^%4mSkqux?ThGx}&&wlK(nsz$fxesEJrj=1Wjw;wd!=5hhCHi>A3ridQ zC7aZy>v>IXouFN&4jh}mv-&F4v2sfJ)s%;la<*AzIzb3}>uT;XRJMi>QNh)#aSCNY zRvCqb?C6=lvbkik!dHMdd;krLgL#76I9TwX>R=Jed%NWBT|wMJSxzX=^mXf)*Unz+ zByHE%9WmokBw%WT-T(F%cDeOGhMfs)^<~yqjqXgaRE|Q#AJL0;>$Or;$Q7mI-<{nCB zjE4?0XD~~URikeK5S?0{K{}@vjRaX=nwn4%e%DteL^#*2Qh5Vvr`?6dw>&wI^mkxx z-S*Jz;K6mNo2VT?)xqxQTU++@&utBi>t(ZfGAo*zn&3{FGdt!+xq0q~ziA=_vZ7Hs zFG~fylsGi>9c06pp?*OvzfPXx)oJA&sa1&E;}wqV?kHg@U!jU>==FbodH39p@8w)L zZ&`3uGC+w`@&oh7Nl|07v*zaJ$eQQxYVsT`5M^J;qw9%lHFBRnJQ2vj{nMlyrem3S z(GX_K?1~g$Dlx1Cpim3c)88U&SPSo~)}EeAj~;0Y1Th8IiR(DlM^I+UB)B`YN0BAO_ zb246^p7X7uf`V2PE7+3A$jXL)Nq$bg%qUtvf)>-x?2E7Zfl5O|!}?XXarQMfHb(o^ z4mg`wtD%*@&+oJO^Ulr#e%OvMvD^1(oJVo3ATMVyHA8xI1Fc1XSemr>@c=FUqMqjz zg$nP*{rT^#^Jn_0oxu5b${f4lUN>-JV456ZYiqlHb6i-&EL+t&GRyn#F9lyW=fMA0 zY7KOZJe+%P`+j3&eMH99tFm+k&a zU_)bj?MC;1Ug-bkBNRF0Ic#oh;BI$fAemw!%+1YpVO(n!GIMjEJ=uIpME^VK{_AmM z({yOG)%*AFzv21e_)Fw@zloT}>_~_mF>69Dcyx5{tUB%Q4;E|`Y$bqqjWbxoQS1rm zj5-6IK}nKyux-U#?q72b@W0(j;NK7He^{%(ZXq<|?%f@u9-tXkTwFYpNRMbd5d=Pk zr5?TLZ04P8W{(Qcv!4r>#0Jaeb#>h4oi5E=%HF_6MjJ>O_B%Ze0<6$Sg@uJ3Jbs+B zvNw$}ixlRaN2MN}kDeIarkP-}7Aeb?#K#RosBg13uP=>hQAd<^enEmp;3nW zOepXrT8{Hg-Kwk2Q0#e3a>U}IH)MHS;rv@3eEZxVg`>K5%3}yfoFMd)mDqvMQHU<< z^OkipZ;&mycfkVvI_&PS-6#Kbn|;fDSbC4RNa-d0f!T2zo;P`9M#kg?NTvjG5Xkpv zmunLgir6piMT`(WEtq{_<)6l)VdMqzgYo)m?AgPFEMk+aEQWa;w6NeJ5XD#s5~?C; zT9}SHm(rT&tc(dBW53IK(AbjJ(G0tknDo)S8 ze*Mgi4IExD+CvoQBL&9^erqZ|hC~mn=vUHgBp_?$cefGm-|Sc>1S$4f5Kup7BoO%> z^sc8y6ShiZBI%zsNdfcpY>cIK+lC|N=G2B+A?*$&LCGU{@=*;eS~P*fSEL|#Q_q;M z-~I{BOb`Psu<>ctUNbEPl@eRPKpaW;oncpBc*CNXB+oQ5GEz`n9C-=?|Hesp*#kOY zQuopMmC~(b02W0Yw?tbGVnjqlglmn7xjGONd2YKzLHk7-iZSiJtZXH_b?a7o6}Mvh zo68h&zj}F&x37r%Fo=MkE{-NdvdtAXiI@n3A#o?_A40U?ts;h9l|^X!V*McP*pNT*H_i;#v4nz@04_| zL>M3wHuMkD-bPCNOpc**Gpi0~OKfC>V*2#5Ka#lA5CvGHRUIRvV^;X=6!!y{gj;S& z{q2aH6!OxCrO(t?8X1kqgjosv4j-pQyIn8GQ;H`wJcgeSP2ZoKv&NHVZ+7?el-#y$ z+sVrQ4<9;CkDC=axwI9X|8?yvOk9sC7@di>m*UDqK6abl-O@LnWTwzsADxFnN?%+?j(1sWjb8 z%^6_0u^RRR9&dZXVsvoV=A9#RBXi!locSH>`5mEHKvRB_JmO7D40)!+A^Cp0c>9*s zipd$^RKh~y#{rq{+%a|}^{YM0jEpYk(MdyB*Ry92GtLOGl7}BmX0RksB&mJ8&qB@( zk+*LVK#%Mv;m58k7vXYqQv?~^zKb@q(>ADRqYj*R($)ojFDZU`8(cP;~E z3gACp5sA|W+i@?6%OW=(&Li`H1O^f=h%fg~vZM$Mpe{fglS=7~jg7q}d?h+lFJXbL z_r;6&Tlkpz3vP)m+Mb>&M7{9Hz89=G@+{wSXY^z?!FzOU``QA;LMEcF}F4?+SrT4MUx7*jo&}~_`WqW(q#Rq zM1(L>jsj&5`;@Jn-2g;h5#7p#Ug~Eercch|D@`Y&GkuIKj)GPLFFME5>w25<%B~DZw zQcbZQh(`LL>z{_ntnD%FnLWEexi4l*%1TS?_=heDhhr#jjvdd`ny%5fhb4&N;7TRp zLyL;a(LB=zIZaB6FxVbY$ENS5fDm^-lhH1sAOXn{SuHJ~vbo zpa9-DjG%1WGH?wCx8 zEHSfZBMyW-&VhaTt|fe(#ZTV_1k^fwQ;_kdZHJXoGw#~<&4(XmH zB#$$dRswib=d-{c%ap$v;(We;(ye-^SDpi>A0>C=oQc7M!nEv=h)HvGz7<+$U;w|{ z&1Ww7{ON!JMzpTlJEASJ4@QgAP<9&Wd*yo%h2@keR1)(3OAATlh&Fbj959(6fW%xa zKHSorPI-A=g7&qd*O6!wUlw?YAIL41S^3JA(RnQFJ?PA4DxLLw`p3~e^0Ols02+O{ zD6+&Cn$$ZXKeg-0F!|Nz-75uEVNRT2iOm<`pG1a<2Z8LQZ`|;SelS)fgu-8vO=BP~ zVGSW`eCnl-DIGoQbFD`a&R=BaL;Scq||3e^kXeN5gH zAddCK^Fo1L{%XRU!D_`Owy;%%=T#V+m@hZNQ9I4^?lHzH@UqM6MocFk5%@m-N=MahxRPR2?)Zbn1Si{G<)qSTU!)?HM1w`T(%_}_~ zx_?KavgKwfOQ>oTJFk?ohFE2Gw-%o8iq@NfJSJ$6m-s#fxz+P4O5tz1v7}PemD?FO1;eTh> z080F8`j=UPn4wF8W|D1ADVW8r{)eFJ}g-hu(C~jLgScF4CRhfzg!eLyhs|Y z!@l(4t?M#j?Du;r+^-^4wM*wd(`FWo#v+haa%G{DTN5JpeGPrOAr|Z$rhRX2(zf08 ztForpYSmQzE(4^Emhi)5mIoI_GINLa~>hh5wal8)OWMySXJVD}NU09i!I+T1IFGFC}etej!(W80MhSwmtfNP*&K3Cnl zd*7qox0;*cWvN8_V_yBt1>xqdOK!^~L7qx<8~A!w_VSCwaQ?C2SlXp$-kE!*%@K?u zSkkhT@GKeE8f3HIq>cSPIR+Shr4MWDa|&YAZ4}mROWPal93qjbMf0o@k(^$K<+p3Q z2~5EIN1;rZDb~9At8aC|ck$v?|GvnA+5*9r4Z_Z?@hjF(rz zQ+Ye1v^3bZDYuXGmekVHN-)%l@!Elh5&-kwqyD^GzZ=648l<5g#oyii_Gt$#+8Z~D zT@8>$Sl0a!*N3abLXdg+Jr$}z;{hmh(;zDjAZoO00~ZH$Pif-?o0*v*0rlJ?IY1)p z2(mwcab4?c_&oQ`975jVsW3t#QUDw1pGgIjSgPztBZb4(xIYgV5~ma;iV?Feih zVbrUK8*1Y{VlU|?Ne0A@_|7aV0Yw9+^@9;qG5>|kk&1{H29iIdUQ2(PkIXmb+psC} zw;1!i?M!63Qj^AKc;pDlMWU5k3w43^oRR51eQN<$u>4=$e1Y0fItDFf!~6{OAHi+* z#2s*c@-xiwX<{3vrx+}(@|_B4$i|C4>M;=b zX*rA>F)odCDqyVAta`XsE9`Ut*lm;fsh+!s@0`!012!+*I1zwS1!p-`i{?Cey)5st z5mL*f52gl&>c+n{Om35?)XZA_(2$#JPw4#E*qBbPT4nTU*6GO3^lJUa-EkYzvcRFY zIPga`y77V?kTkBoQ~eseh`I*Cs!?&V+}$bU5p}>%2eI^^JAF|-N&*Xw(y|MRG}h#}qjDF?O`A3m z1UYI;`Shzl5Jkz^9z?Zh)fe;MJL6JL+j+Qmh3m|VMnfEgX z4<8N?`!=rgJ0Q@_->0nsriMbL)9z!cV{}|xzz6@&m4vtOGt$ymMTPuElN**yn5}c{ zV*137VF=R(P<&=A<(0Uv_*7+%I^U(SG#`D@vjy`}0~t0bW|~xbY;n9dt?ku|@t&OI zeV`=$5oX#_WjNSGz_EkRWY@6`7>xd&var!PA#h#6607b495<(Ak zqRrC6bdriwnx2m2;E4nK_k*C?czC1MN$zYanwg@%;mCrdqRBOC=e&vG1NT}~s550& zpiUxdF(-KHq-s26xpt@fZ+z~cu}jR}OnTmV21X1WBVbzOVCSj>)Cb7pBh@7;fvVf1R+LC~sXv zDmRK8ZaA!`wml{+qK~2(mQ?$)O$=e3EKcknX`I#7YCx%O&|Yl(YUKCV0!80`GNVBW zoR6G&+PSb5gQv2t>_hvCuC8u7Ei$ta)E*aG>9l2igc&+pdz72cT0D7dY;k! z?!ABC_nmW{^Z%KPS6{hcX4YCy+|PaAYl0Q!C2m~1cMX9++>nwKRYoAtLJ^1y8yFYi zJ37U!JqW~@l$5BDs%z5fxT!AA;2`>@mh;lHC1p`=8Y(fPP-$!Kb~3K{JGijUZKfU9-Al_yr_IgczN9!fI6?D{#e=sz z>C)(6hFmNaBl|p?&~?=($M7iu&99>C>kVmKYE({Ga+?fq#?Iziz`u;P372 zjn$pdFSV-slHMaE)N#M{&vO2~E{5qh2Td%0pCl?dnf}j{FuBeZUhb=3Z&km1`7-u> z0z1@u{`;lTF>PXMs-vY9EWprIfLbH%t18!5s24@O>|^0e@b~Mxt#cTNzw42_K5LJL z_`4!l)8)T!z2_kdi%O3k0&%qw;|BbOpmwn)os`Q3#3RhVD}ptB$u26|NUEs$&x_;P zWzZMK$7|&cnxqBEJflUeCWMk9<GM$W1|7*mzcXWIzExqld8}hd_V%lwCqDlfPH2;Rd-)i>1mzMuZg#Qnv@}+JB zLa?o~)7HxB5r(kPhof%oKe4N(mQh&9@IPbsUq^1BdoQptr>KZhyU=4Cl^@V6@CgX6 z{?GjQyYy{5yfPwGAy5DBBj-mRdNf zLoH?0(Ew`Y@Le37Z^q2kzZqz0N2}~U`uR1^w&?@i(J@b&YHWzZX0-C-R*`}6du&M|36Pe+%noA|x` zZ%Z|qAbmpkLKc2|o=<#cs>9>kF?6Qa^nYvL%b&di1MtK)&Uc#4VJo_X=&^Og$7}c>Uh~3oU*d=n_qfxrp{|4&rD4@?50I!z0f`wN!DB{HJyPo;;?z^$oO8wb*~p~)&mWJ zz!JEA{W|JRK+tUUk%TW_wG>0e#X6waXICK&_ci-YU$Rn zbVqodj#L2>EUeFZ+VdM5une~gcnJ7mjH_3xy-xNc?(?8^_D;!pVP3uZrB7m!6AGx; zLVo}FdX*Ks&U3TZ^mPm7LPA2<@fdJC4`j~0Q~w<*b38VNhSTq8HP*+fqmz>8IIjs| zMMOlvb3b=-a&mAW!$`}{ZvFiE$>y&w{QUfFv5W%Ft8p*9sx@#{28&WzOgnzYv*_vR zUEY;`&SAW@5LP7|7OEA2K--!;F3--+wj3-R9vYIY;elh8f}Ki?kC&>!V`k*y;(CC3 zOr0L>6d;Gk#yn3Cx5kvTWH>A;Dk>t0xFFQu%(cZ*K6-?~|Ev3>L?kia^5SBZ;z6$%XnPYzcn>Ms8wp? zO)d3iIV^POAwAumKQB&AHR#2C#eD1_uFLeTiJNtCHBNTE#%V>9Zs2%trQ|angxf2K zRK2R_Pn$w;>oT4Jh`jj9)W*i94)@uYFJBzyf0|2J+_kmcNKa2E@jiTMc-wqE?cl`= z1f9~QkjKJ)9oLOmAXV5~=OoABDV-c0GiBpTEe9Dc_>rtzHNso5<4ig{bhWj$wef&Z zt`z}D`g^nSRwRkQ{?5+FDj8$r*>AyjM(<;DN5`d;8hx>BEN)uU)_X`}}01t4nd>^Uv||8r6zJ8)n9=7ElfVwIhmS+fl-v5NtE)Tj%(ufo9zA+gZa!_;lBF(eiYno} z7jAX68nJ9SqXr<+hpen`d8n8J-LA!?j-&0%pP~w*iY`}#rHRSFaz#AV zwDK^`4LdEmyBnWYry2uCUGBFLl9p)ZmzT2w1iWB}IyrxTe|W6WnWsUR_#T{Mi0_^!HOpn5{85F5@UbXX&-1{p>blt@ZRg-lwh{9F_a` zMRjyWySuj_70`qpQBbho{{S!b?b|na`fn{Qv9Yl(`E92Rx>dy%{WMd=cV;pDIIJtn z`j^FZkAiAVJBcSQu`X8&8XxTZ?Zfb=^GFrc`j&|MWEj5RjZwwt^!yXC+w`~KG3*h@ z`-RR_1uRi5tzoE=(=#(O)6=2}cLcb&s&jLtH!GwUPJf41{r-LB!YCr0$oBHR<-`k! z7oNZ7@%>G|`F2kyRgY{cLaNi7V!(rl#iN zia*(at=n4}tYqA2Ioz6=M0ybt5G-wM6crS-(@L(buOp!*bJ$KC9v!jOk}-4pKG6)k z!Yr$!lh|bV^a)H@q?13|+T3n+35$q~Ze^wFRD|&aM@dhWs#}kKvi|;te5^VaQY|br zbjEsne}8{#EB^6QVPoTT$R9yL#3a(X{lV4b8;~N6iaXc{#H=hj<;M3sk-(dFfof1` zCMG6u4yM)VWgwp=CCyyCPfgZ_N@iAy8ld+l3i$B5SvBM0p&kqK^LOFTjSUib;NpsT zUkYuKmX|+YE$j3jB7aT!&*b+u&nBeF(0US?e6rEn+NwU;>80LG9&*mf#RXLo4;R;K zs|l}e_)WWWV`JmY{@Un=4e7U@7`bUaR9TW&dBkgfe-BSSy98eMGobgQqQApTv~NHy&6D*F{5c28GFn9w8%<` zK1NE)z>^K7kK$sYqOU8ZJ39&NGFTX3kPG68u+1s`f1Kk+Mn=?&+C{Nrf2ePL3l9l_ zeXs8u2XfK#_%S?0?m@I9Ubxs zB*|OP@fxaYYj?C^t8KCGX_%Q&9r?YU#1sVJgTh;qq4MwAn5e1E;jmPtlcb0^0zTH( z@>J@7f*j_;YXuPZCOZ1;?Ch#u2n}pRiBXFyy&SrU?nR5L3*~5k0X^0oY6Uc5EdRvB#1kJhW5*$+ zmxsOmc5jx#WuhP7zXun+B1GW+lM>y0w$wBA3C{{DUd`w4#@0DWhDvh(sREi5c7Egf{A$JIJ685$XV zOiO#Xq;M5*)>4pRh>?ZGGUTC=p&|T~ii!&Sk3X?6;%+GJ?c2BU@F=Z~SSX^o{?vC4 z1%=N28)1N$pw5z!kwHX9M@PG@$;-f`xp_g4g=0N*~$LXmjjcsPP8ETA=i2>{Yt@P8UPw*%F z^U9Sgo*QoyQ~$wf4}qPl_dYu=)T=!|-BHkQt9DqJsP`Dmkim;;o~r@y0|ysD%tvz= zS6EmGIb*^c@5r58t064x`%9185HKWsA4(v+_qrN2dM_%P)Ik7xEiGC3`C&Yg4)*pv z0|R$GU(&BMXavzN18qQ|XK!zx@|%*Jd=AE!7lB5ABYG}lsyhFA8`)`wzt)VG@@k1e40K>rG<>cgeCc=pUh*B@m?*D@23wZDW z9bJCLl8>$|g#(m$BoYaGF?+2+;B@nni}Wmv3<3Ql5)v&}?@&BPH~Gp}l4_kAL6 z!YdnFdA}Bl*Czfl8Eq0{@GhYF!n=dLIrtt;Ny6`mRb2GV>u~b{w5L;|R8kBzwf--D z=pOE<2gHGf&{Xt859MvZttiF^zTO2_0p@~ZSc^!Ejm5in&;4+73RW1i&*!@NYq>v< zAndMfugm6+xVZQgG&Bs?TS8cm-HVKXYyjW_u*LyR$Z@IX*--IQGKq-O=}<;l zSy}GGD5!GWe$MInoLN;h4}eyOgN~H+eTH^F zbW>OsKo%HmBSJ%WHaD?|y8HW`05HM&U|DPHpSqqsdp5VQ5c~G+>!OOP-wce5MKFQo z=g(GXsH(jlJDsRGr`}!dv*)D?P|>Q$ zm?nH+u6J~D8g(aHrTrC{kUyHPM%>iUSk(sqjjF;6&pkv@L2dx@Y}a925bCj60SCX+Y{jTwR|NwCJV6f8W~$Hm(L$<^ zdcG!;aqDYXw0t6a_;=%w_cIWv+l=(|YtYI0oR(FAvuM&YV;zAu0T3bZ=6&fPSKgV` z)t|=9iOC7A_toL$*zSL=uBic5^NmCz93o8CkzrxG2L}rgU4UoYqVe6Fn!m9}M(HUl z6Wxg}b75SVlkp{$*R8|aGc)GhG^+sIqH(+Uy z<4{v>o2Pz<$`k$O4RJEx$=0kC`dyiZ5~YUk9M+_PogU{Mx+}zxxa-UEiXlbd81wNTA<%98K?6{-u zu8)t;HU{9n;LON&*WE=WPtQ|7ol5+zEiy~XlZt(B#+PKQKt}*81Nl!8{at4J!LP}& z-3N8N59!Zpfwd+-=%2_+>vh$?_i&@MwlLc+ttP? zCG|&unV@C+h8D9m88hb;^)S-V{4je+Nh$FelY$>$0Ptgwd9fJ2UA?_K`}-;E)(Q3X z^`1!*rNltwk7SmYJHogMU6hW7=JqB#8yg#dKiDHzH@EnNgpdM{9w`Zlg*L{9)9p4! z*kqsOKESQ=vIeB{F);irW?S#Je z4J4RVV6Gt6VFpe|;vFcUN};u(;X`uV&&`n}BzNyN55^@W{q!=6e*OBhbu}dJErHX| ziF1-z-+<}+UaP2JGpv5~>eVrx*7Ba7t7vv{q*VIG&oR>8TMjNWBA>`79cG#;1V6$C zh8iCDkDnk6P7*n6t3FoXG3rCpU4V2^jZlXQHrpBnjThqo@bFMJfz`bA^@E3tY>G|4 z$aj{kfH|yTBO^0{sT&wAK-u(bO-~++M-Xv&>{|i-lb>rLZD8;l24@tdc>UTnd1%qF zBT!M;y+&s#=%E{4e(>NjA-ma4!b|~|!j9SR_B$Q{|AdjJsP;^H7EGt<*Ch5{mi zb%*ou^7QQM<9FL6+v?;2%!I^F06Y)pf{Tj_9J4DK>)lW`AbI`JZ=oPQOF+J6iEmwO zR#q0|AC^xC&_AT`i^IW3JJbg`WlcLY&A9{1Z56Y>0-y! zC}AsugM)p3pSk3HJOGS0{s%hNLPWvYCNmjbnM9Ke{;luy2JrAe4U_^8;JN_j;cfnM z{q^}J@V;dx?ZO1tXh0{A0YcAexD*;CEDU~qD~3Psw!f)NtsN(c&BW>R9g~=pl#oge zhb==ja~fIHJi-qpqSkqh+ja9vqI6aSKGQ=^&bV4{oog@y7U@(1nKuDYbbQ?#2{KLoIDFK+Do0|jZHtPp`%2isQ8F+tf$*s}x@#bP!y%>h9LW@eHv6;EK zEaq>#1z*e;KlPV=Hb`2;4Jf?Y=QoN15*Gdnd&%#8O7)}#-uQhUXD9=WJw5ivyQsQ~ zA^Xmw1)DYLbujJ%e?Xnrt98E5WpC{2 zRAFK1Q4$)O7eOS&XD`~{Bqs1!v2!psV%Y*{9={Y`w^HDOhK4kkRqpin^?^mfXqkKwJa_1lA+v)B*xNK*!;yI3*PnSZiu(dV8OL)$eOy z4_>BJDE0Gw6COT!e5`)D6}VV~4r>#&Vm|@itTFJ`25h0MEN0VGd~ophOu0mur+^i( zG&QAMmJfN`(9n>Yn)-qR=5R>C2wuUq)>h3r*OKb$BbQ0YkmCqk*tR}L=MPyC^rf9Z|xl%X5=HSCZmeh9lS7{_Wu22&%;gN)qnrs`*e&S-I4_ zmjV{(wlfceWpG()@--8#^9B^|goy2mmlg&l$_{-eZq@{VBaJN))>I7g znzj2Pva*9eq(f>4N;KV82IdM3iq_X{IBip)NU@TWM>&Hu_96|6byru{=H_Nd$hDB# zuBBb*V<4?TiP22=ipGH=2$TT{i4XANv$Mwc!sh|StgVeBOSGVMi;8}OAwsiA{{~qQ zA6j=LDb>WfT1n;LEsU;2mcXZGLlIruLSkaiMnF2ul%u7mhq207R`#cX&so3K_8N@T z5I!W3M`KlXv>Js(+>Y6Y9<-B>g@F{NqN6)quib!(mvBa(-n#@~OTWV69q@RECj;h8 zySuN}CKXmEe|K)pNC}*qMW+-B*(u!20@960|wAZUGRbx(Dq@z zsZhl!rv|>o$LF^#@<`mVdOpJ+$|Ueg9Pa{ttvX+XDc%m|0cZ&<4Ak+WSY%gyr`awg zfA5QD5)mL3td|-&?vRy`Fzrqg3%yJK;q3!ODuzCh z(=P3>mZpgNgsueuBWm5v%@oYcrAwQ#dU||RR8)L?XV78sQ>3IPwaVr*GvXUO-Aum) z`7G|vw`H>h>gnoMS!(2l%2=fG2h_Th{ca<;49Rx|1~DckCV=1sysn!td{Eu&1a-Ob z>(?qa?^$ox0Xt}BFjndaSg!Q3S?KsB?Fg~F)ibOqI z6Jz6Y6zC4cGs=j6Tf8`Nmbfw~BO}wuVNEmC;G?OAyQhUQ=Kqju(z`8*GiqriZ(zI3 zHU8Y|9}=rB+tVQ{@Zk^Hm2pN)!2(!jt6YF~kVid6r?JIOH!6u*;wa;u3| zZFT3c?fl2&*RS&l2%Nn@kcWAXeucI6_wV)RY3NkighxaaLj5`>wy}tTS&d$|>N&ha zclX~0ZGx}7i_#z2PZj7V8}Z;4R6iFf0W4L;>58T>3bbZ`8DDqLNM!XLINo9#^&ZnGm!$y zL@B@vb|i7_0F>dd8H)qzUM7p5 zvA=5WJPQMv+iWYgEX`|s7zPPBY~@pV4p6vd?s(4*jVXmRTZ1>d^Cum~RqDef$^vY% z-Gz?+{q1QPs)r&Co&WNE(30Ch@%jXbA~2$S+ytU81UYoT$4pF9Y}%Tdiq-7Vhj1Rc z&Tej}32b5#5mkKy%DSFuOvXXpPu}mROWDUW89ceBSPVcJNQ&O6_>7D>m^W?5s$NdT=NEta zgmhlhhBA9VN0)i$8<8)k43=sy|82A{CK|f+2~5wVOM|8MdotK^a?)045Qx@1h!+@B zP)rU?1bu;~;5C4G2O1CPaPLi0;Nrdme!jtV3&ls?ULth#2O~D*Um#uCC5zqV5R31KkG97@;-M zrG*SEECP>ab28>ma#RQz^i?gaa8A7w-n{AP%VF0j&fIGVi&kW>INl>*XadhLmH~aEDRg z7jTn6kbf#J2L7w@oQK#GdC~jU}eiIir*cd2K zR{m3`0h#i(Q?!40*lIyO>(n!ENOOL%8!egPmG{L+XnTMMhy}dI0P1Awz|;!98u#5r zyR&1btpmBc-;Xc~kVx<0(q|BXP#5P$jh{Vp0uCN#ZkM$YwTE7pra=3wf)It`Rgj;L z;oC|Pr!+hK!UryaCwP0mzeK|Zq;T^$=2v_nZQ`x@bb8F zO-jmB#n)%il=})P_zYUYgZ;P)0w1)X0D3{=0gW#zN~yO1{4jmlO8WZx$)~YN*W8Fd zWMpL>faC+}a*>{#oHZ;3NUYu6-M69*g8tC|V-pf;o;CtxRr4hsLW>f_qQx-86j~(> z;spzAV6IWg_CSG$h0Qsj&z>?Eiq zaX3D-@^DnfUP4C-xME!u1JQOAMv_eV^cuj(JU`%Td7f0_1NpA>P#FWDKloW$TSL{f zTk0VP?mSbcx3?GS9vraEmW%B1_fZUbF0NtF@fW*4daeN;851UVbsTV`qNUv!saS!* zRBj=LC@g}w=9x?*(yM-=ZmHCs{G$xsa$te`;bVs{zQ#r~zsYeRv$?>9LqbT%V+Qct z?@BV4!>e`^mEpF50d_h%I!elgSOf2+MG2sy$oc4+j|TK@eE#iOGBZni2vMK&NHGPZce#qZSe$XiKxKtbOB1 zJ-1WW_HaVcOMCebQPhfzOt@BAACQ2UH?CH5M*gLDcudFsC~?^U%YA))W71gJo_u}* zhaYy2E!R9{Yu_tvdfJeWkI(Id%Ylh!~Kc3#pau>H`C zRQE5Mt7~dj88(G1E}F?lqdk80>J?yYqQ_4Jd+XD;4zzad%!zIWCWd8a1j_u&elAqD zq|5DUj4Xh(0<{QW*SrT|vOJ2GOklG_I}Ll!VrFFprwzMAm^g6*HPr&QRn<9cvAr$* zkPMs)mO1q7hdz!q&6`v1FJHPxQ*`5pWsW|Z<`w=U0j(w3_4f3@&;cO(a6kg%eSZGx z%uE^dEuf*MyeEMAt*Wm6-riZwz_Q~dDr%>ydcR`VYY)vXkdy)In}~1mTKCN6R3j>o zOUYV81kMkQ0QdlUwyZIS9tJe_g5}%XNz;<1cY$^?V1f?~m4WsiA3qEX1d3+B>=YCd zdI~=Z@&*Wmo{2zXj%6v3*i38GynOlP$Gdv{hIPA*6#XYp5^sm7>NlhS?c7_a=a60C z1U`!3TBw`pQqfQ}K;x3Ib2WMLWD_tL7~5g001KB`AKzQ0@OSUXySt0{_)@jB=L7u} z2~z4G23eyqg^;RafAhL$z15Qe)N0eF?0FbI(=-4NGVw688tO-nj2F8;Kom`Hyep47 z`XB?&9n{{(xa{uldjrv0JGkVldym;zQd;^4u!=_`T66KOhCVAQVgs?uA?}Kq?RyKRY_Wb;qoJ=(ezMl- z{oMp}u+#JBX2)Y0Wl?L`BS1l2xkaq2sw!%us-y&MY6E~ooNQ(~_Z4LsC_9k+AY4Kn zp52Fl_#hGpTzoVkE-UNqLi@_rua_dy*HCY}^(Dj#;A;4?K0iIeVe#rUV+EZF$Txl< z87Au7Jbn26<;CxW_btrdwI1H?nK*x!XK5!YYV<7Q*MS2L&UsolY`dB7kTh1&x#hv; zrrFYk>#gyiy>cWP)&oBY5e*WNd4hJ@&g&`c5g2Zehtt=QTvs7xenZE=qt||vqyJJC zNQ5nc-=~cS8H#FZY{2NibjRk^5K`|2^o`Tc@7;W!nwGm}zVcc4K`MHBx9^|14;9Dm z?~CbF4lK-H`)~lvl(Rw#Z#<6+Ttygub%XF4bvhO}iJ`v&`2cMIk3koo-6}5IgDRBM z$tk0x#8y1g+rlR0cjGN5bMu1rG&Ae7tmN^b=4NuDjvKz&3l+39Hp8WJzz<2T4Y)mT z!|9A?$y&+;0TCQQnORw(4H`Xy>Jnz?H;LldEbqF|-;WFoY=K3H6sll$-9|?b1U`CG z?s-vBQ7V&>xJ(9@8Ro0yp^{I3(cJlInY}|3pSE&rOiY9Gnu@~?hf(v}6uvfdqh?72 z!i?l*pu^PH03bY2(1e#aXEek#6lhoEnv+k1B~K6RBpE;7A>_<0EFdHt;7Di1ZwB7M!Pz}K zn7lru)ZN!-)}O0iWH368Ea35Ams5LZA<14lz1$y0t@2tC4I$VE^8(<|_4V;u=^hD`LK^`A z;fIo8kOoX`hf4#B#ydMVK+@Dyx@Mh`pYI9ITi~CN`*MlwU>bIiQO0<`v~J_JiqG*O zNc;DB-^?~Sj=2+(AAwMejgPOk=+6a$VaLbr$ZB8D|6HHw9UvR*>yu65+=AHjT+7oa zf@3NBWrHY(drl8P*;Y}BwzW4>RqX?i4nsnrw7clQ=|)+?z1~TK_Li*mxwg{HO_Ute z)P(a<12SuG^TAr8Z8?PkdmN93b=P~7Ns4bfLC5NU-39TXC(svwSgNY3%Is&ECt#+~Ba0(XlkBqlyTk3J-qjlMq)RhWTn>vAgENg}P^>KrtD3 z?eznLe>jnyn+rNw8%OkIZk8*4B`^4tBY@KO%|g1>9A?H;Xfp3Jy-DGL-UmfZ7|_ZUXWn z)5C|;kb8XxkTz!kB>%Aded(t6BB0}?*9u~xeE~_H$0_#_P44lQQAjP--r|Rug)9Nn zn@0+oMn*G9Tn^BAk0z{aY`l-QpUvKUk;%);3;l%I3Mv<)!JAPKroh6&{auCN$_A~} zri)5#B@Gpo<7q2cA%K|kT++qIYz7bjF#o|57sN8C(@&o~!NSLvOc^^o+%f{i4mc7! z89kL_FLl+vRCYO^k@DlQv1y~0iNL@?(y}W-{Tc&V)Sq zb4BZ6;oBDA&TfEUeEqtmif=eJnK*bYBk!?=h<~)(&}{p$fa|7vGmD1*e7yT(M#Jw8 zb7ryd1)VN#UR26ga%{Ab8pe8L4rsU-2rU>{DH?m+c062u%VVezf z{Ze4w0JU2<<6UUIDpqdVZXqHZ_3Bk=RaN=cOca!s_vGg0<`7nDgN1q;`I1UYc9;q z-QL}`;^sxEBH#%Ko+7}=EGW27LNe)i+X@m2+%dCA)r9iME^tZlI4*X9A<7<12lMd5 zTqZy9QNb7o`~Y+}P~*Ob!%2dL2{`#Rp3KZzkIGiblYF`zKlFZd%=bt##t)L+LnV?_ z7ZIPG09%5*G&(%IHd+~3L}wub2-h1ZhSk+o7<-36@~;WJ|6pD>;(q}^eJc1QG+LT* z`393GYdW=r9FAU|I0?1CHPzMG;r&6;jUqH>9Ra(A&&e7G5}g#$KFuF#p3t!dXO@zZ z0y5)k$)ax}xt*_JEui10DQIMZVm?vp5?K_6`vU6*G4COO9dI7aHpAUJsH}jXok?Ok zjF&qT2WP%q3Ve&xNG`LON^DSE+x0rNzD2~m=MlFjD^CChKlw8nf_`Qx%;Q{m_ zAmbnU;C`8!nu2|SO9NLlr)8Am<65s_%CfV2udJL*4bZ1mq*BVMsSUPB{N7!fARuU7 z8K90&tlaGY%>_mjV4nTQTAw@ye9B@w!8^4}%#CitU8$C*zE$DSa{owDylOZPv# zd;1oXgrAp(CvnW|>C-K!Vz3gKT#YWN-SzPk*b~pTin6k@EZO*;t)fe~9v)@MJjvVJ z`5j4988vBXV1MJ}J)QgYrE_idn)gx0hvMQrFYr|xC@FOV!pJWuSoj&==rTTe8>sZT zIVT`kP_o?q>M%gBwDt625MF|I4{x}+iRpaett|7HTh=DR7JBCV3cAbq{)Wqs&dRU| zbz)|JEKZ)cO@=q{AHQI1@hdHbju=ZRm(bTeA(FMb(gY_YxW}2 z5@z5ufoXF-@9Eb94#s6$1_T4B6o5B1wX~uLVOW$1zeoNSeFfBkxi zRCke5P#|G7!3?sJ!qhbpGWvqp3Q%kT#z zCK|&O0h|y!GxHnOqW5>0nV5njBRQCu9&nrk^7tqoo|}_{t&St6qS9Dl>4EgNb~*X9 zzB+6zN44!d{Y~|HXp(J1ft<`8^;iVrQE20oZmqL5aFqbdA^330F2dDO+tE+-JUkwt zm9ew4!;$4@%S->zFMTvT#A$TA8)7-A&3LKtiJ3y&6R-0+l+aV4qejIz3LGH`lOfuq zJp!&C0Q|10uC6HBLGZGe{H*dm1M3cVH4`J_Mkph)wXH2$wMbNSS={W#jT=A$ffz%| zaStCKgl!3F8h^noLlYC{lYMI>o4L=~-XK(%d;TZ0A>zG`E|t8_KdA*K>F8wpn*xpt zSHFIB(W&IGtnfm`5pID0Lj-B*X zIQpwUfCTYW6Tdb+y?78{s%0*+zj#_r>-{Dcwln~NnntlnwNDkZ!=&;To4b# z2bW2!iyE+`Yg1DXOf7rx3kC}CObgcGgg|titg`bPYc*yD)xpTpl9m(eMbHpvz;$lD zG{|pTFb^fZtJdu5Uj(6$0w2I$Ta8+|Mm#)rAvClCkgAo$G@|!~A zRWcVZqh;T?_o!n>L-WrK#7c+eb}(+%y4Z?}ikh3}{KDde_X&2NqvgD!E139j+q)0$ zCNY>vF%_1dC29S+G*>%gfA8LpLIcLoklZ@^02K|&LsDHw@XA^z6gD(~Q5vL|@QWT3 zR%0NfKW%)qMK909!4U~}Or~+L7yuCif`Zcb#umNK`)mZ<@F>KkMr3^80o>mQuamV( z5Y{Oxf#@Cs2xi)u@@Dxq;*Yh`2eeh-pR2bHCVdQQoeLIyb2+)<*N2{_#t*LzF=Y&> zn?$pL$5326v%0$8-kIU*bt9jI8@LF;5nj*3uFlRPcs9W5grLMmM05bO0g?0$E-u@9 zdNtWu&9zWGw@L3rm|ytprUR?01_Di46KVn_Dzmdww6ydNR+V60_p+<5z667AYdGXH zFlqQHFR6w`MxeBJ4h_YP9YV7Pw}>KL!-F%_wddPKZa%DmX>qx83N!3Pj@I-Z1GjxkXY4rX3>OJ^qJj5%xJrBYk}? zdFu5i=N|tCA2!ZELKHg;rfg82)v*q&*mjdt@D4)mdCCx?IXr)^S>u=!8F_0`k7en1 z9Zuz6kz%Il8C*#Lu*?5&dgi0V#fwo)va-8pXE)|MZK;j;_d0b{R3Po*pz_9^5(C#k zCx0Odq~uzdAb)-F`z}^}etrVV=LX>9-0bYvlXRhz(LLLkYrrmoaclPO<;wvuI@}`S zR21gB_-kQ(-TQdg9BEwi^5sha&v!)}$w3Sz@mWoddg=lEV!1g~)LajC*0*4)4=4Fu zZmIDINHlXrC8ZLt6K5a}At6*qQc#yDGzxXyV6d)p+c|t?y6tblAaQe{u|3h&v{Rm) zy+gY^=*MOlcu82Ca{Du6_Lr726WOm)nTaa_d;}fw==>H~&A?_3w$xHTbabqr0|WbT zBMQpPY%|F3AYmxe#Za}U8~VpYN3%GuY9g27z_CZdVUv_zgVvP~WRf+EJ!3%c!973C zt#>o;yUWER%3O;3ixs#bcz8}=Ufh4{fNZOYxl$P3-~ZnnQZe-yLHf!P z!IjIy0&a%CXM>+AVx9G7-MC*4G9s`s_MssmKS+E|;RXxUH!6fL7dN+lt+U)xZ!oYA zHsL`*uT^9Hg};)OLooyu66w0-J9gNFX8?4(jdQIQI zJ0948aN9Q1!p6rp8m0IsL!-#0;cP�EZ4CmQQz! z)!onvllFU;E?rV`QO+$+pkpsY(YaG!vznX#=ruKB<;N`Py=-vMA>mFx+E_*_Wcr7- z7L&mfEC718tPOl10H@2kF5vS3;_HINFE63PSn|de`v(Ln%Be5qlr!^)S6BxW)XB(B zpqQao)nU#fl!N56Qh8h=7@HPBX@OQqnZrPxox9wTWbQH}zENo#K2WH}%9eq&m6Mk4 z*q-~InYna_GRB~8$el?Afw%_sn%#E7>giJ^Aa;QqQ5^o)6b-xp%CQI|6IxMvtOo$5 z%ZVHU0GPO*|2nyZJ~TH60cT}tS>smbq^ax!TxF0Zo@KnRiMUeBOiZnT2;DGJ#^$(J0fxL!8bzPhI(K}oioKDOb5Ji7g=!=O3#Kvl7OtM+3w3&}(r=xekz>lhhJn^9J*?}*Sc0u> zW5Y0MNbE}rz_+(Rha-3w{e1y=ilI(*3@)y$&?566TiQ0D7H~L6>45nOkC>R@RTskdKDT3# zZ3itC zJ2L%yLJ&oS=Y*fYAa#dQ9yqd$%*<=+xWmBXg3Xy5u61)KPkhnGEbk=)`d`iw2HIJDAomc|tqlsBQvJKM?x2moNn-tbn8eePuQV zY`Ovd{*t)@^h$R2%;P1E{48ao-5-~UiLGU*ZsWdNpW5n~KrRj%5N6A1UVI^s(vX4b z0Gk6?RMI$kRa8}BXHEWGwU`Do)1vT?QwEQrRXC(pn1?EKD#xC+Wn*@lNlX9y9!<}v zU#_4qs9m4H!+R$YT*3grqjlg?bCGU!&#-d!3s#oLkEU^YUmX6U8(yY55PAlc&VO_T{RY~{~GSeS@+PLxb@5k5#;2yv< z20%I@JluNEhA9#t59-;8h^%_Hg{gDS>V(5|5@YuHc~8AmarQj)L8?3k5rm(=F6_wg zybfGeAQR5D-LzjFVlu^k6oR&hVM8%Qz+$qgU6s)fH=v+|emyYBIh(*bc%NNW6<5^9 zkt`3Yep;cTr6VFp1&$F~Ys-_zuJlAVO~FdIG1(CNqzFv~uK(&+7A~v|4)~nstjvh0 zsAbepChFP!Vfk|A=d0Ud`pch*-$ArqU{3_0Zwcnp8~0eLC@5Y{Z$ig*1`9H5;&{1v z^oyx@Pb1LKBt+}(aqm_aSbymhP$5VOE`LwpWW_$()|Qu^?mu=2wnVvPZncMJ7qG10 z`QU~EWn~@6eo*LOgm|;8tP||y-#qmk^hWK|CFVG2wLlR|B#k4mYT(7sz%4i%14BBH z?b5jds@-PGHa0Qc-SS6ACQqMQOH+M?>3gD#vgymz+~=1Yw}{iEK5MwF1nnud8dN2e-|yJjw?Zi?W$h(@p!o&n=-dPrV^``bUhXey4mHp%ony1J8%@5W*EpW97tq-~{*&5d`#NH&v0>JIXyREpYhqmX*5m zdAdr;VuCZEU+=B8wH$}F{m-A}HLg)yZlyuj5-Prf6%pyMAa5TE-b&cYV$RFy@xH!a zflG#GZViWui3*?enm&qYo?5tmu?L2j*E+Ita&UL=+rR~c5=eOXlQ;`NaY3U&tr=a- z)bw8rgM8}1J-&qZb-t-6HRI0CNbgSkJ2h`f$+N8LxC?^fprTm<7Ki&m;GG30v8r?T z;Nb7A780N<;PVs=ZEYE$&wOb9jl5+rG;;TRSLJ?a|1v`=4y#U?cz2)b?s)nm4vyHO z=C?610~MBohd*9klzc!D?KbxV7dfeBU|?WBjmRNKVr!%BAg^`;u1K09RRG`yq~~{f z7>fY@zFAhN?SA_fKC_^t-oEK@qd|_tR{c{2^!NLr?<&2|uIr5MMv=)xkl3a_@5D!> z%fT=VjN8fX(hNA5z(aSl!gL0L4JzIlXgy%-;5PMc$PK*3g2&)F62o;_?s|ffr!+OO zx3{=u6TxJ8h@H;)2m_2(%F3f%g z!4yoY;xw2C`kKL&LFY=F3i=NifhxeR>5!xXK++1mt42v4TpWua ztqN!bzzPmH;axc>cfB!?iWitkz4fy+P+i4NR4~HICHm z?CQ#AA0&y$%HggKs^5*J<>i5An}Nyy3RVN$I9T?oiCBRTT8Nsji%>OlcYS^*B#wmh zJ^vE~d@RP?oY=`hR!voUO%=|ofD!?@%U2LRGvLQTsbnlHCreqWfUUCsryu7_W1|Qt zrtC?;m+mZto}ESi!7=G?Mq~cY9PRID0p~OeoIRTNHL->{5k95kwms@{{p!SX{|-8! zT^P+z!ExLaTdg<}WaJMYIs@0@#BGKfd<1${{OWpoduM7dD5|@B|0IY%&-Y=Z93X+B&-Zxy+&Q9mYm$~yk-yNSxES^ zYr1om;M4kv{4@v#=A)h!2~knFAOP(Zv1VdshH^jI%h=g5P2RvT7XjL4VSvPnnoUD1@8x_HCf|GV0aztrK5rMSXY(a&iami2-P5KbcqWgj*{#PELEytD|3bG@k3q zi->>}(7!dq#$l^mE%-p?F|%?ayPVOyth>YD!=5A5CyLF{*}yFvI3CEfhfICOCF%Vnc;2!Qd@)DbQ&N*fuP4Ct3Y;0+5U67ot zcb7VkF#5aa*>S~F9h>?~t!bbjgJSp^PZK^Q4qy>`t+2?Zo9Mqj8BeJ!QPkyJIdW7{ z^YFYi>Hr(N!giwEF+0W#^L{P~em2XqYi5X~+cbe(`D86$ zT|HoDr>(EgdgWt*5P3@579{E)>metU_*bT+D{!k4&RW>U4T=_6B_8#Yd=cdo_5jl& z^iFA;t=-+(yxa?tG=288tuafmP(lUL4&7rZA{7PO znCI0>xLOW(%3%Q)U;#R%##gHm2{0oqtB9Ba`;;M_FbQlz1MrGh_a%67fHt20S%P%R z8%*R7&(okyh*O-bq#!3ZZ3;P^sQ;rzdjr*g;LZkc5A-}JS46*P>fh{nu{9k092{@H&+y0lRs1#8mB1AG(rXpjBG7nLv z2AMKN#*AB%$P|%zCW$g7x=wbd z3kokbJX2F?Xt;x&Uzk_PE|x4<8>QPi1jZ7FDSUO6m7O_OifrTR^70v26yepuYM;xOW8_sY%jNV$DprowTii*h(hhVcTT+}eb)UG@e)~+-;$-?=-o7De_97p zi2KKeh9gCcIOS_lwn$HpPfQ@4{a6?DA!6Os7Q6r9EpK8;GpB&%j~JOay5Cb!H|K^d zYSkKESnR_zP1x@#cN~)J6Xk2<5-FNooI0koH;O_vK3eycS?e9$Ztd*sDmAr$PmU2g zrFQ&NQ^4TU2TA5b5Oc=&8>Xgk9ZTk3egP|!iHQldqpHsBiHVCU@r?&W_&#@uI!@^v zD-JY${=7s&!a>C9XJgIrD-{M8$U-HL2qg-Nh&bW{83F*wy55>>MF5us{mRF>g_hk2 zjfh=XNWa2LpBO9Yv4LWWqX>;p1PEkla|kIhets9_<;jb2x*EXI36Cxr9^F#c`GCs# z(L#^)R1pt}*xHnGYq(|V`ZqIjY^DdRK5zbFD^cE3ll`yTrVhb4^ps+>Ovb3;{(`cP zNG_T$J7BmmtBbiAxmd9yfPB=JDr$r=U z@Ao~PV?>MdkmfRe`&0PIbIU|g=Y08K8459og))1{Sh(>F*Fmrd)m=`La1eeT?`B-$ zQiQwINKrAG&kkBe6@snwf=B=8In^8aQOBgxpF~6yS@nvdI)x=EJtal8$Nar7H3*Du z&9jaZwNlB)#r40u4|+Wle0FEgu7ADuAS^6y4>JSL<>oY9g( z(3DZW?9V7lAtqLekkI2E+vOkEGd>Pi1JgM=(rbM|w+I&adAE1yz)~FT+{UsrX19v_ z3)@M(`2}TV?DlbRFD#{g&3p6@o{_C*Ui*a&q~>(x&oQC}65NyPiDy$k1PZC@9y^P= zgy(8p>D_|%7EJT6fmWUJ75>Ns5^IZN4_=^Rt z*+$vaBgnPR^Tx7vc2)S?N<`m&SYh6F7S8s_W-rKo8|C`ZCb7C_F z&GN>q&^qi|g*M;Lzhxo>n}Nvo=;1^3j0eka=5<2Rkg%ViouPcZUdl4`mxi0$IvOGJ zRx8*PaF*~sxK(Ndal!GtCJDBp7g+jkyfZIO|B@9wTO9z^RV#w;1gADf=#b;0ked!rQlHUO3ske}5Co9F_;1$&jH*4Y6J&bo$v`B_8|o8pY_=_;1b8U zcdv{=IHjJQzW#zIfq3%=F(2g7`%>u5>NtIKJJ}f_qI^E~Eq%q0a8n;z6Cg4OKjF}e z?9BfyO^i|O{qznlpACqpJ7<>(xmLswl~5$OUalDde<@DoHI+d$qB07n^IZ?TEUvIs0I-K2nCql;iAcbL$#jpra6;57G1>yeCp5uyhQCgY@^f zTTL3hEun{qA!AzNyW;@ z!9Tsv!RLo0>VI4JZL0Il_H|^}YDf$0_dgOR1+CMS;vkChZzCfdabpDa8!+m-(on)p z#y>g#)rGGD=e7xzKLtfk zg$ES*HQ1b!TgTr`JfgjIl*hHmQuj}!q@VfJ-+cVm_H@WquD*TS8yZ@r)vTx$gS8vy z{H4d|ldlho+bJWN%i1sAgw?^{KUB|=T;?)cKEf(+EQa?0KV_T9NH4YV!>Hjda#Uz( z9L{L0;Va3uim)!XaoQ+rppZQkvq!|bJXUBYg{;(3BAh4e!J(d;{6&BArf*)J zK=IZhUNNs2)pKq&R1;#XiR5;A*i=3+CxC8ZPmCVr&{yfhE04@W?Ts89iA+KZc^bn` zBSCbUTkDLFkdacH9^PC_bMpk>vBgFGBFj4;8wvvbTjP#PkL-wg$Qkhs>nzOwidI+h zi~|k~Zjt9K-$8>DlajJ>xTXoY*KefmE8|6Uc!9604LF)i!t$l4-(AeSou{u3o6#AU z#TWSdyl*N#cg^!s+c&sy`PE%BZHP)0wZG+d{=BoI;&@9kWt*`tH7xhF`fqfchvbLv z?-cT(WQ(e&2`vGGS)EGc^l2h9k4*aZDMk`GQ?6;$Xo#jReeXn(vr~F~qmAyWYYtGF zaB2w(3X)G3D{jU>95BksIfBG{d>|`Xg4wN!`lpGLqv`DxlG0R+pGZ#c31#n- z9xpr%Nv1|dW!LYa12bHF2OtHSFzfg`6BD=i4C)Vvg-5HVNN_8ptdm^8+ zQ8sOGo3*TEe- z{gadXVVe6L?0jOpY1GjUGkr`4 z4|Y#5X&pLyw(>sKao{8V{yRa*Ej%m!4)&$lfl3rkpEVi_pWnQmI69inO!are)2phg zENA1j|8D<-F%78(kwN72rPz!Nt|hbMQYOT}9hUZyp`qJXg#`r}&o~A1(@8S7xLMoT z9WB6tZ`-Go+xV0Yr{!-6Hbhqdj?ZszU`OgLFpnTxV|#hP$EVDj_3r#=kyxU9z`4=n zd-)XPC}CF?pS;PXn`TCVRzGzl%c)-1;u)El_rz$@cWYM z=Zu^<*0(mK^q_z9uClV0c>H+(#-4!YIZh^zb$2tKk~(1>`a`TWBo+xSNO@9LL@zdY zJRi`C<^ov;+^Jw)*wIzr=-9PMtkv5sO~a}H`Y7DJ>ir?nszde_?l0Gt_yES z`t&j`qp;9H!J3bkx3|Kh0{&&tKMtL7k{VtXWN4_X!w#$qmH?DWl>AJSFT)1+3A%{6 zEI!aJBHtk^*S396A^Dz&4KHIR_6fZ}V55e%6aw3Uz!#m_Il`5kYj3yA_0D4}BERg% zq0YpRSoIrg_E`6L5WS~p`FtvR;6&jrcATA7^U}hvUnQLEKkv?0n@;Ie6^2>9xNz~~ z?j0A=$$u*GW^mR1*gjk74G=Wvdv(n&AYusTIzEt&;NW1zTLMdP1B0haAx_B|OE#nFU8(!C5qHKe@qL11jMvx5$-Fx{)zFnu>af{8rr^N#|}8g9#8J}Y`X&K^XkF` zb|AlsgHz0jZ?MJT3JitgS#fwRNr8~!(M@%wZu#}Z7-ol92e}2~R-u<23QL5~99ZRxBRz%G?^kRl*3?4!GTLYW?p|yHNRn zXP8*YWsupx2>{1ZNgSa~;@vpv121lOxNu=0TR(%34`27MU;jQhsO6YAIX>>T@Z_J! z;kK;iaad>-f|T#o7vW9}e%D zyN#@^J&^JS2oCU&1K_P^`Kx<1WEb0Wqf?Ab+4ochuHL+aR@jXT{Q?S_>IEq&FWEcn zw`Ug1LRh9{AGq4Sv^()>3r~9gdW|jNWw7!hYmSQ8Yeq^Q@ zq(+Y$R_~f4{Rzhl)=TJdTINkf=h}p3hK2d=B?_5`1K?mkJ`SBDRW3+)XqcieB7L`hc`8;eCUX{eq*kJt%y;lOXB6&AS?g{tEDaFuU*GU zkB*d)jCmV3#l681zpoBIV>8AV)2Q{SNNT&EQeHylZ{z_B0;nm%JSn6hK##M z;RS)_5X^N&_n`HcYw>Yb4y*ZT5!whxg~gu^J>g*Syukjtyu6!MxcnML5`f-i*WP*s zGD=^%WDnJ#DNel9c6f)i6Nd-`H@8A^(kJmV21qjfoP4S2W3q#RLDb#7y~t`oUP)+q zT5S5qE+?Fj&e?oHor1GXP|ryeFKT34f=PkHVy_@J7%?T~l-S>2vlOf}E`5h28hRBv zSMyLl4~6Hm7Snt*!5+6VYdSBE-u`H7c6+~F+pP!U`e7MhNP6-*vblanH%r`Om7KomTwxh zY;A`F5CU{+x{8RF)($7m$knfJOExxE1&oiHnv%cKKKaw-NXYA)oSY$-N!Zg0Fr?s> zn3Rbzj8}t$b3?T>(+Wt=fLxa*TLn?OaFkvLkTi(ZwY*OU$(yNNO^5)AC->#})E`Ex zz8_ebKeRMGzIEG<*B^&I47k2_o}YSgMI|60MD?6jepHzn!D{gr6k;?Lj}K?MYo9eR zXbIuv_Lh zOsLAp<;L%ZlI-TZjMa~dibnmiMNAWp z!6%v~gqt$hN4D)|l(zzk^!1mdB4=-y7Q$m<6s_J`9`FqOCKg1b?1|7?soe|1VhKZX ze(`PT?(R}03fYT>hW$-3EA=0bc~ts{s%bsnIssTSYWmJVCIls-`80#ornpUw574#^ zR|hB?G{3lqaH_YvqM{9%>2?ZbJBxXoAA}zT1W@{!5$s|@LurbaxBc}nFxOYvo9F?h?$$KcbK}7KPA){>`p#ZudLrJ(U|ie0cC{FAb9s9X{r4xGnbV3EF*#9k`^*%H%BbFYMVILPF5Z z)6>$d-;{l9iW_eGjOThaj}Htaf?Si)NT{I# zbq!cc+nxQVhlCeu5vF2s6vSK6s9svjK7eJxR>oHvEzbSMJ0YGL^XG8T3; zb=uq8hr-b}S9mVKa*nt_m6!j19cROQ2g_(a6LW+%BKU?mXfs|Dy9VcOAwVqS`lE_z zM)v&q9h06i)o$0sTpZx~Ykzm2nOQt3H?%tVuyyDN=!^`42C8VR$cw6 zp}x(eUKQ-fz5;WiC_39ztZxJC0~QeMr5h-ALPUtAY$~ZbH5Juy=eZ#)#YMCcRBNL~ zqeGf;r_^wKfs$J=y&2>c64KR{!2n(#FAoF5LI2FmeYecJ8Hzqj)D6#ELI-)GfPUdM ztZgjT4Cvu(n`j|XP0P#_b6vhYM?MBs9Gw=bg{5u(GYv?{d9vSQQ>o9Jn!)onh^}Bw z|1cm5TIf6co}O}hvxRnHz9>tVTHD*k&5hz}zt6jOgJWY$0|P=_T)g%V_u#$Vm~8j6 z>=t}L*%~jV?e_ih)=QV@m&CYw~Ac7 zdnnkD_yD`R6EB0-i)(h{GH(5Um|#e1l6!p>6by@%jGvy0of&+bXKSQ%>(=C&s}4G$ zwHJQ&dhe$=5%CR5=>_-GAOyp_l`xMtaNvy7@nYFs4|}?f%X}+Ue@{*+MZ4U{bLQ-% zcbKI`iB<2!(@?`Z172tuklmZGv%_`+8BaVf_hbL7#6O~eStYk=`1F*%!^W8>X9SO$ za@_ZRiY3MG8<4}^_BTD1Wq;8yWo!(*eDQ*vE`>9S=P3yx@vB%KjH`3VdtR{L#_n5v z?f9Frw(|iu==ME{Khv4!&1%o1)mLKgJlT<1T6(ZCI$gl|WOmu`fzqo`3rmpb;U^HPy@ zQ5LbQdD`Nsk)0hlB-t*D*PJ+FiMyC>jF;CITQ3o?W|}0{6pzYn8?%6k>^)0^i8IFA z+1TXBv#B#B&MMgq=^i5`$hXu%Z*00|WB;Nhz?(Ta)HbPn z*v?Rd>*N`KPEDtq?!W3jNLKnv^~bF9YYJK0aQ+SkNdtbCgqGS1+a&l0=K{fSa9^~z zaPuZW`Ce>u&6<}Y`}*!~Y)ni~lLb_Zr72>P+0-??@|)X!S8Ql_z#zjnGmO|fh?D)F zqQ%@d)bILeX=q^W+6>mkj2|kd@>EkqYfKYf4Kj-!JYqh{7cJ6V?ri8ht*48%`As((kJnCM2IhPK*w3nMYt;z*Oi(9ar)W&!Zj^3V7Q zb5a@_dAJxu`$PC-lLd*T2xo!9|(C-i?xO$&$2(q~_~9eWEKxI{XL38i;r4C>M~5{W~$L#0K5T!93p4~~b9 zJe>34NPTHrPR%g)oz$11|4MjB$l;7Q&qqYh_3Xmu*#*n`dLGf+3Cmw{d>m(vPV24@ zU6>B#bmrE^$pjR}TLB0Dx}?Zjg$``sLuckg%IhQ?MG2AF@yvIATvKzPWS2Tx%vkHZ zNYSIaooZY8ysxz@yB?+o$g`E_?P_XH=>4KQoDx<;Z8niC^8(> zWjL4#{g0U{0TLj43j5a|k`{{(fLCK>1xr_5Bk{`;jSGCmXTKn;1Fj;Q$&K<7lq<>|}gPeJ~btAh@ z9z&1%TTsh#Hj~Zpwq_gG(GdCg#DenO0oHe)KxsokU$aU|K(ie;J2vIA2n%5`z@lw? zNmkw-7Ze0G0M0w{>0XW46UlCP{3CcXSL~kbRBb^nk&$}#)>!jsVc}NEO+_Q8^BR{v zFU;nY+9W%k_o-c7aC+29Z|C~yJzS#P$BsGiBjJc=Nz6%+0B9L(W+QKS`1m;DP2YW9 zC8xxm#x4`Hr!|pA9e9pjCNbEtd0E+nx*p4V0<>3V(lqJ5uD$jZv>{*#h1e_&* zY^y0+vT|7-9Ll9Q3ZnC;p7>|3dAo}85m;c!k~9$N*`JmtIP1O~Wm?RYcd zAAq9C3BIsjaF&!sz^#Nr*>qL-?Wi@pWVE;X*s@=IFyiJmhvqM2uBCr>b?x4E1;ZO( z?%(%X8q9E?V;4Jm)MUjrYxWylgMvPLMgv(>R_6UqTb*@xAI~woFBkYqQlE!~(A%tP z($4e7lQ0}7J~=sgP*Zazmud?Ko23?d^$wk+o3n+NG5} z#6jD#bC(4gh|jx=@?70Ql@xO$_)-nNDx~EoT-;IlPF-IQU-$)V^Y9yQcx@GSoN-W5 zp3c1?t57L0<}DgW=Qs0_5+ek?Wi2|4vx1tJZ+ttmooY|HHAzd>`K?q^*ot`r8O^TB zguK%)#fxo3sHT+Z*~Nw(5H9^S@fl52jZ*tMgIw=Vx5Li2G78t96zw`8+3&jPUa+w) z+jk*Yh^cAVm(iNQ%F0Vb23K)3Bz7Q_*xE{?rcLm~C6&j(nWe`K#wJEa7hXv=M{=2( zj;*ZNtH_Tnj3`Cy;~ukg{#yCFm;0-|W2thgo9qEwiMyYYrH;;Yln`u9t<{gXBwfNU zzA^j1CBc^Q@7t)7a9~1gblw0qD#R6P_V9x^(na&|TOko1k^x)b;Gya@tS= zi@K``BZsKhd#>&;cD*H^-KtxlfXSoB;wi~(p#^8NIYJS!o=^VisQVCw{rCK?87Fb!-gB3wF16+th$q78UgENtkU+0$(wB4n z%>HzOZ|BG8XZP?>t@Qg$iy~R%FLAgEa}OyJUu+{ky7gQa$^Se!-uRFxtp4ov&qq_mu;aSn1)xUQ~X?>eoBzv zV<1C4PrAJ;Y+Xi_#_x{-%N@rzKw)}>%>QIL5P9m-D;|6b5u>|slR1tgUv2xH({t;o z%?WY7`v^y=nhNO8-tJwUQ`x+H18ak_tBD?B5v_Tb@SA}aM~=3Y$?3gc_s%^jz#?V2 z_`M{8zb-lXpA~BDZ`?UDa7i~%(Civ%yyR$aDaxz5E53*r&t*;e4hA8u;2pcRNC7$P zMT?SbK4~gS#@(}Kv@0tZ-F4$(-HjZ;*1MRNptB7{U~?j;>p#5!D|w+oG&OCxNSAOO zHOBJT42pgGv5WHNef6M291xGKyEL8GiArnL6Yg_oNuMyC{``3#r;1k0nG92_?9rK* z-zGC*(|P8iKy}U#M9vHiBe|e?Wfv7?7dgV>jV%%9 zfr5DBNSXxXasIm``y6>DGA*U;t%1Qu zfx88fJC2iBmpBu1gSf)O#rZUpb8>aX%*836jn(t%^>8*%`G+Rn?HBpvVn*@$CZ;SA zrV|sZ^P@{nKmJC#zs_&pBbCgHRN9>3x@zM3gvlH6>E>Q8R7?DX(Bl=AmdJ5i=hpI-CgBFBL&#mTP& zn%WWP;rd17B3bHBm9pjoy!~NR`C;R;JA>` zy=E~0qm-?5UcVSaq*(Nx4wE-`4$w2$Z4=yfZ+y7w=Nya`JZD^ApJMg8>pUj9pBsqI zGRlL*XwvLb2ZLC+swO+R7Ya9rjbCfNz96Boe6hIL3+qgz-~~{FTYF;@TDv!$3G6#C zPM0{S)U$Cno8Xux+OFHUwHaRMU0GVTX$fJ2x}bT;8OFp{ohS;m0F>)!Z9R0tt8yT0 zbA@xk%a}+2ua8U?cPsHLcVBba!@>@OEK?^F9+i;2DuJGb0nNm%jOOHhsnPc!CR&a* zKK}NBi-R_in(P4!1AwwBF$o9mUpIX=I++Qd_6_U)TlQ*%9BL~*IlW>$gqXl(=iu7E z1@oXLSjOTMDa*HjP)+}Jm-t<=~8$B?sIGWrPv^A z_ETc~{`pJ&Oi}kTzQcc&=07@XBfrSJb?458(|6j^lrNc{j8@wr$xj?0h#6(5D5nDb zQCX->el4Jv9&ot_5XtH{{-$c6H;RDgF7WBxq$Xr`rcdmEcnny0(Jm5egxc-F^bV?U8lx#3)G`IoN zsxBU%#>o=>tS%-x;?G;Z1e5W*t(=nJlaO?c~e&zZ2 zS@{jeqR=qab4?%Qa9bc_Tl0o2SP&N;yA2-rj0ZlNws?9lOuIPYikT)YqWoW-_0h-s zQzHB+PNVe=_`zGXM{wW^z+g%Rsu~x zFtV1$-Zr-!KKfE6^G|6BU`1Vj#Y7|17H$Wr9d^ef*obS-#WN^YnrzuC&gEJYY~GPm ziY6jT>6I+!AH)PLAo?U84S(a6Q|3(Kr#T!qc&KOA$*FU{%*)}E-rn28!gL5w!0;wmp=QOB@p zViACAFc;LoxA`pyhH9i(PTSjSE++i9K$y^~dpDX0*m{2He5Tf=^#$#J9z2alu2HJ* z(LXQA;;m94ZMNarzZ1_@#*uwZ#D_|r3KJJU+-m&9an5e-V+JO6WQ5h8G0FZ8yN2A@C_|WigKJ6e&5ueXUzq?-YspziXhLA%j~Rf zKVtw1=HQN~mT`u-IQ(m!&8+R_3)YABq0o-9=)6&8rU8#`)xf|L5vzQmMBk+1;<$3%Bwr2D%?jzoDe?DSRL$+!Ytd^C%N>c^7D5PidKesao~!UDSh>j+0&L|w zR^!|4JV;!`nZ;Knu=rN*Mlt8+;UO+rVSMMebDw`7qx=ON=9k%l|y19 zVe!`PUp-enN!lE5Vm9YYXDE@p`}Oao?R#?T>SQ}EjP1J2qb29?0VbM|$JKg)&~%c< z$OwY|Gmk3CDO2c+5;{?oOr)>_Eq3KHD*f^8WJlMR-h1*sdSc83(Q;w5sUu#pf-^!nwoY1pyIh_6jr?T;rMUUoE3`iQ9Ob>_b}bUN$T;~ z*yAx%93;SPUoXD1mDZBf^dsP-Y^A_}gkDWkGq^@U(EJgrfg|eg%D!Q-^<*r*ANWrk zSstn+L%aHmJb6EkcnO-xNekd{S|Hsr@qkhwCy&Og-}`>`wK2uG7bo0Z(QsXPNCQ11 zV^l2TH~P4)`;~NOgVIXo%lyqcc?y=xa{I9#UPp#Ax#bk&?xkU%PwuyH5m;c{%j=}4 zrytr+9nh?Eu&2M53X~{gl}rDlTUeR+62(RaCVfWw z3vX^bMQy%HLL!=H(n`6D+{^UqZE~0hf6c3RJx{CNMSg7?SsNB1+Cv6^MBdwWhj4ho z@}qe5s*rYv@cY!VC&5ASchVpIITMKP#WZKu6DLBJPV(|v0*>kxw2h!ywqlo5nwn}P zmfb+UqyJ#mi?eJ|k9K3x#}$}v{n1Oal}boiUmtkns*sSj(3{PXiX-`EIua7k*HW;Bvl3Wcx@ue@n zcd)Gfx=w95{*ucWk2qO>5z!&NRc~%bIfKz6jmSNaAI^^^3{^sTzgdJLbyfZIm;?_l%+<)rIk7J)?n>w^ngh+%> zNsAG8|G$W5A+~aR)2#A){KAcQ2(wNL6Z=+D$I7=RgW72BPH zy}d%cy`@uq`gbQZH~u2EM}*tv1EkVEM0u>bg%?Oj?SB2rH>qc_vpd&yDOeJ%gOJFUUC@xT${(C9_+F>`w($A>n6p3^fw{r0}P1Mt8wIow~T(|>Ujelk3RZ9A~p2qC2 z5m%qlZQtIBi7}$?REl`nd|8;iEn)`rV}{e{Q3aP|M= z_dm)gWIC&%{weZIXZYIuuN9NwLLR;>w|Nf7g$Z09YbZ40cYIo#SxVf!7^U{2#|6{G z^7K7&?a9f1ex~v@7S{FsgkoY;!1d?YnlJeT#kNZ^F+YC+iBz8$I&$%^S3hvD?0v1q zNUi2RttYnE&$KBj6{l(NYX%#=UQ-N*Gxn2D!7tAw$sxrF{ruridWKYLhO2uXA5CA` z;<-4mw*PMdLDTJc1W^INR)tAH+dq35mz1E}i53I`s$MK(vB_zXWZ3TT#r3^c_wGa+ zHY{vDT+?5E0I$a+);IGd5j{0blW6=o4sK+M{??pvCq6kZ7Qi!V_-nVmAW3jrZiIxc z`1%04PFd|`GoLf*ijPQ07}zmw@dQr?9j9Pj3^q9OdeKz@2-F1C`9qkDY^7vt3)x`2 zHZ*{iM(p1L1_{k0sSY1fbDsn!$LGBoJoY@}1nHKiBqRlha!5M80%q*_lQHt7e>cfU z8qNuD#!8FTg1YxQub*~&{u=ZK)*`g2zeCD^S=1|tg1`%P>M&=g7CN1RrmAa=Zp1<= z)!q~#8H{Zzi@?#v)%kA{DPIsQv6a-iWS|}U^()KU4bKR&=bd?wjfT zPb4Uu_uu5v$nGX7bu4It|IGp+3pj5h_h(4S_*GXT5yW(|eH;69s1e*gOp?BFaR%r- zIT0s5((K(U>VDZ%8S%gFp$KH)7?KpDsuI+T3^2S7kyi|E8!Eu0d%KxFeY@T*WA)1$ zfxGEXdcVC!o-NLwl!ePKrb0G(L`- zAsi82xzoj0^?|GX&vHj*_=&wb=Jb~Hy~IS(k_O&nS-}UUheSpu@>_ET7^(oziq_w2 zBvOQOu0Ztk0LiEA#dS0>?QsvjdP7FQb4+l3f3T*C)JL=tM?E&(h_$I{RHe_A^KxP% zqtP?{FWb_CE|*YDr9c!KSn6MDta(*xui&_75%v7oXYtPOewo?|BMl0FI?5uiTOS{)DY41-!?iNQa;_>9<$Q`bK zOD+mF3KHLa0cqm{iQ@w;mP^xr@T%GxjddSz1N0PR{%O7*es__w%5iuRE<&s@b4mLM z3D0tKAM>jX5}}C6YNGJ1MHu+8TPdks{cg zXrL8y>@qQqia(PfbXQP1T>}Za|IoSV92{UA*Nl(m{^aiU9#dfPAt$j(t@(PaP<*Cl zfHjM7<1bm$zbnyZlyniUteeazc7{@|IiUnGwUp=TbnxR(^8;t!tjwQCRSHDi|1^}N z(*P1^q#4?59}5fHma>}adA__F$S7VxRPAC@OybjP+ujprmtKDGPF;}b5O93|>Q~A- zn;>+oB$f?pl3Z(H>~-?t-Lfbhe7C1 zI}28+$0zKM;Z(Aap2;JnemP9TvGDmgdB7QsorGrybiMZ2lqi-35)ec1La)NonDo^4 zf)XJi2@Y~z-hd@_X=xI+eC7K%Dj(P%J~8-sVi3PLpK6f<6G>-d?4N{r7Y#@Aan3>- zbOK-fK|lWbn*=-WvzZ#``uJB}=_&)$y%v7=8>J@}##+t>t&hpQEGrh08@9U?s1ftua|RAEsnQtcPeuZF4tOy<(zYgs=WQT$0MB$H5|Je+&f9jyBiWxC* zg=*JZPwZw+4CMVvA#;oX{nmJ=b!KELh2YexLM&N?ChXd ztL=J2HpaeOz7-H}UAS1N&H;k8#H^$y>Cs)X&!!4|z#EqiNgC`sSm(Tyooe9brL65> ze<}X7hJD*n8MWE7hTk3}v7#39F(9ocQ)917#}n!lmXQFPbxym&T-JR?Wa*ljob@d@ULrKK8fkU06Ghc5hs%!y%GRX5^EhoB*W?-q}9TOmt(mf?6#))|- z261AJjcA0hp!dE7Q%{W@6aU!9{P?WIc0_S?cTKFVO|Gn<5ZRHceU5YaG#lS(D>o~? zq8NrJVFK|9Ekth>u@ihs4OU+*SSDtzi1YI!_!d9s$M7dki2p#!t_KNJzJR6;AI#K;GQ^Kcetd zUT*zvrcY8WTd58OyuH`3`%r$<$6I$~Lgwa@*4M5sO)iyqc(Bt_gL!NVHTHaRLzIwz zkL^So*Wp9VQsuL;{ID(4s`Nl2CHHy?C;Q3~NZ}x)3eU!xv;0QmGaIj8FAYVep6 zCmZMAwSOsMUBbzM9Y23Sdb^Y^48@2upGrxAx*@Nmu8tcT-a?}FK=Zk@=eb#Z4LmtT zsaua@P*7|v;H8GPJDm$6C*#q3f$b8uw3|Z+QDUtCLNBv%*DfaKkp{@NO4v<9s;)c zwSumd*}X7R9IpW$nu>S-2bmIhNU3@J#uz7onc?2spL4m$=%KaNmwzFHcZq!B&YhjY z*6zk;D;OaUvH7%+P|~D{$u*GYei}AL3jFr4l05q=rU7GX)&7zOHo+}4OeE*N0-}Nk zfAFZ`m+yNzUKV8}&{sCUs+$|emi0x_IZ48ikI8(uv?x{;O0DegAyHlH)B11z{@a0_ zmg~0d$KPRIjeAnLzt-1l`I(V;!kmx9azc#{RHPJ@&8Yd_ajJ|(OoikS1-<5s$A+H# zI?320A_(}=qg{Op3<1KJqDry2{aL1xLY;md$LFrqtO)J#@z$7<5-o>o|E3Werb;ZM zpXcSBx=YdQz;JK7F5~Gzh&9yIEopi}0sHoWv{NzGFZn0E@8ivCc?6D9J#3rsAaN9Z zJ;4A|cTj?!o*vE`@At>5UA@}WP}=`EO?TnvPYH~)L<-lx!xk|1T!!=>uky>lB%kNp;b$n@ECTSY})Q!6|2-^HgO0l7M0bffBZOIf`* zpR%$~5Tl+Q{R5f-)qT$%h}u&ZLci=fU;3@EYc$XT#97OE(CK0+XzVx?6P|>_eO0k% z&&vxJsBcr{;uQw7bp4C0J|7U(#6jQWW0)~r@r91jC+GBb?%a8-!`L#w+{lPHGYIjw zIUNi@zywmZujGW-{r!S~%x=fzLt(e*F*G_?b~RwgP(wpNk5_#bVd@U%fXxxj*i1}J zFexto;*Vc`dV=WW@Apu_G5F^7>t$B@Kxa-_^|dX`s;OSucUF?*{UaE${&5zrjD@^? zcOT5+)$%_qo12D)?LEa$!bT|^4<*$M*HmdApj2of=)5cXb+1^SIe@nV>G4b+v++0xD!nls7W6aazti zd=>^ihNJw}_Z)~QfPnLGngB&4{wSCv3S=cdXFs-BWjc?CU5hY8gnvYaWEy7>rs+LW zqqg84e)^>To9)K_nVzNVQnMn_as!RwKb9McPw-7}CMG<8K04DcemD^f83u)LOzl(e zkBC-f?`#Vba-Mro7jc@BGHEhhkxG_NE}Kuk#0flRT?~;Gp|08ztdG&2Y!!@vNiK7W z6nJV=d3`@5 zS?KcX%kA2|CE3{rL@8KIaBtoGGhBO7$+)kMb6#JhmO3=` zCFkBRUfi7}_#5HMMgNJN86CAcYtXm$?Aa%H=vrI1%55@>>Q}aEp!r-^=MSvqa;7@5 zr^%X4TWut8U?P;$yy>Z0{F8-^=EP5i9~kE5$e07tk!kgq>iSK@3~Gn>>A>m7i)NoK zxPFy=qL09J)X6`}&hFi@cmMuE%**Uy^;XV?`U11pP&nATt)}_LDo54gE12$L(e?(! zB|e_H*a*YAV02(Q!{g}+k$a?$`lLxCW0*9}R-%@Q)!4uQE6@GOb~XAquFfw9tb0rm zIoNNziB0a-(G<1e8+7~2`*Xgn2Qp2NZW|*G(~deq8XwX1Z?alQ zP!PBte$3K!;>A*-`}%gGmyDcs4{6P_-(VjaK&e_ke}2-ohgw#)M6gVQ*sb{2*I@7P-BhDipFp((HzhEY4j{jXyZ5wvv!YjM%y&81 z!a^_C;!66(qo1Vl9I^#{z}%37bab4>(**f1I6Bqb=cA>iEeETj)?V%aai!3DX`ti| z`+hg-Tk_!=!rUkh8_w~3Z!YKDxSt}*Ci&(2T&6buP;sg~OKEGv-G8kQNOt{vLq?F+ zjEVUNMM6*0insEaQ>C2Y3gtpZBh@>GM8H{Q;IQT_0z>-(OzFXrm<+~IfyvIMm~VgNGyQ2PK2t4NxhMZe zwfKreb72m(iX@3AE7bDdD|tjIV|_6T{?3b*^f_(6Cr>Q=XWZ54N;6ZcDF#Y%f6K2*BH!bKChs zuUK6@HpFb|sA*c)%lPr>UaV38o<_yR!E44c99G{D(2+F>IR&kn#TQou)ouN?ep@n( z6=PTbEa<~06Xibu?2SPV5JZf>lG^QcT``~aLY4o zd1C_-7nWINd}p;wOVb7a7QDN;xC)UdY>4kqJHkg`aTbh9dm#5`@=M;UiBxe~&A#`lLjl+9w)n_Sz|Dy<)Qq@blLR?88t8swmLCJtj+v>dD;Yg6}) z$(CxX4rJ$E%Msf9Oo@G_hE+DEsV{m{xEfiKNVR8( zibYTLjE6;-*stbeid35k&z)q)4M-D~<%o>ncq%g~JK{E0%-lS!6hiO)Kn{M5CxdneQelmk1!fD-;zv9 zObD3xiJyw#714zXJ}Z3vnw5R%e%|~}lhLF%E=P2l>noGHa}31|Dulb<=vH-J*(SS% za0jEGDciG!Ub}VA%?*bO({h2m+|ZW6&%>J+&X;vjIovq%@!;)KxsNndRlk6IVV?qg z)$!x1;X;IFRu&ddQE@hJ45F$NNcKNaYIV1R!`%4bfdf34$%Mt)o;X#Kk)EEbFhxkp z$%^Xh;@XG}@$U(Y;^u!jJdij%pr)%nx7e2PE;xAZ{dHPK z()R}R2Roz*&AHycAMJK1#_$;s6VBLIO@O>e%*4FjwnOw4Vt)8hCTcLm<$X!?-c^GN zOV`~2RJqu}(SM()LDeUT;T|K>gegSns~#Uwc*ch8T|R%oTgJAn4ShZjM8w2HHMBco z#k++i%1!Q;*hqOMy=dRP#nVCBKtrRczhW&`Y!OjB%cJU%VPVCl)Nd$dZ+6z@G@^0| z3k#dr_&7RWN`hJd5w*K9_HgR#u ztVDS@@_u!^Ow~z0aAnc<1z_|=AeN}hHO5PNVA@%y_7)aW)WrS)0jYs64BqH`-$nBV zZ{R$6ZPZfQPx+SGNiNhG6^I7~TacPY2CJT^8?;8&4PRVX4p389@5(XUZqJSxOej|KX-Qec!8euvf1Q1I zJeU95_NNqSYN#a1E<#xuiIgOvY>~ZZ$;xa9C4`K~%%0iVrR-VRvtjRD2+#4U?|t9j z=eeKpdOg?c_s8%1>Vxa^zTVgQKF{Mk&f}1kP4Gc7n=o2bt|xnwI|q`Puq%|8fSALh zFN4jUA1f;(gdKwfxd79mPX3~}hkZ+6V1>3er?4>XodSUe4_f!Bzx$Av`E8` zos}E|se?kBi45d7+Cvh)f`bDgll>V>vrHn=DeSDZ{UxiC(|xil3pE>y?Ooq>j9(aD z?k~wj8|tx#2bs+P%zRFrI1!a{>^`5eipq($MII+5~5#>O`e?VOmY-M=5k0m3|74k++eLqZH_IWv-yelE5{Qn^T@ z%wlFTe@;-4>%=~SU_zlgeO^tCgH&)9hRmJ%@t>pnnVsNq8RSkcmxW{0B!3n(dEmDZ zl@5fiHpmKLc4TZlIV$S**LRzaj2k~YU}%Km4=PQuKC$ufT*=bg?<<)1m)@G-AqpYp z=HwW$O4ypr&F`?Au%8-OsIQ2-y|Lcq?{8qMmC4i7+u%z>)UevITWP#onOT1`fkMm^ z9EnP`JbuiV?LF2P$HX%ExV6>t!-pL#vMzese)|ur^j;P|Y&<%sQdL_!24#;pA2)aR z^UvoVhZC}hHe^sfx-Nk~Zm6w&L0MS(`S+cO65y(#n>ThvOY68y@I}Mt0RarQg{eTy zp;y3rYq9$No5Gb|P1iUFMK>naF=)%$>w7(!@Q0>-4U=@24u0*A!=WX<0B@Z(e>sFFxW+?J8 z%SK$IIm5-JGm*S6_0_AR4@5<``30ET=e32Vxjlykk>pyLO$26BlhvvURuo! zNRCxQ*Al|tU%oyHbEbjXWlB<#b9rf+)7sS#wE%xP+wYeuUUHY)O&<|zk%0SvgtuHI zm$>oQccel?+`pIU4;55T?ks3^-MEEMwsvNh&&^eeQ8Tv3dDZ@!H3?v;6B2Y0n?gEh zZf-uhX6NJSNg)(4G(An!OsjmlN$b3;>jrvVauP({Q2+o2>%}_ckHv1hE~s<}$uVG~ zgBrTsrx}?e3iy=dkkYCci6E?5t)rRNu`YQM+&75ig5p{^8*u z1ChG8?CMkOR^jli!g2q4t^XcG@z79+wh)9e#c-r+pNcR73&z2{X+pCQ>{ zA4-%N(yyD4mvdlb9&=sGEsl?0NZCR#BC#491GlZCvP!7fsnce8?jY}h<(UD=rKglJ z?)1}~x9I(OrCw(SGqi#XP|NzqNQp>>ziJ zMQeK_~}8q4bQ(9m3m#f#k8EuUUX z(bI=&76&%8%`N3UduHu4UuoUVr!OS*@&!4edFe%J>NVH(&e;a)l*AM4mX_rPQg2@; zMpxJQG0=v-)K62Lr{h&jw#lOu7A^sZd80iK9K*%gS@_pRXR_W8f(aazh>H`3{(C)N zy;8Tg=l>v-U!#MwMm5(Y@X;d@8;C5dLvGh!TJU~7G-$se4Q%m46g^`ey%MzVMIfcS z+c`TMXEXEgqI=vTY$=_$UN|hA?kj9PiFPNKTwQk<)2td5fxxVr*%_)^b@TFNL4Ey~ zfMColIhRX+r>6EuhaFQ>6QMo#c4X#T<&me&-F1E@=)CKsEukbYf?ZGH*rs1wpqX_| zMkd||T8Fj}akg${prdMNMmowsPyf;43Cx6U>FC6mZ6`c`04t2A?2o{t1_9MIt9$Zy ztl*h5ADTEjt3A&e%5+w7H<7lo8ySSXO3l|J?|vsrOuVX(b-#-mx9jf|aY?16j2j9JcTl!v@`%l+lKxjAgFBnF7cLBmTrM@4V< z%b=0r;bHV(Xlm-~UkN+roiZgn_Xo25v{y_RYU!{o{-oH%LZP5^kXC4^ym!s7;9grO zFRezYneCxdMx+G9G-8^?E7fxSjSEtsqGr@)d)d1)t)>c-@)W-AeH^Pn!EIrzRVp=1?B2ZsJOrEU@S;s23CYQ004fq>nzqpq&v}`qkjpCa^Xn5p zk(_4BYgsK9O(f$D=SWE%q=Gt_S=9QAlU7@mi91tt-y9g*UWdBR+iN+G2c?&}db!v` zH6T#HZYsc{muqdU&a&5E!_WV^yu6Uj*o&ALonBATip(_!m=KUNs3)eau z8xiSW$1)OMxn`vS1%UaN%93dph945}90BXc`4qzmaAD-rFGkXk3@G12r4;AD>)q==%Qp0@Sr=*L z5(uw%<0P{Il$Ujq5OqHKI=_DH3m`*sWPm;!!-W#! z;>6`|q>0V@o8!%xSetEPaN0*wuYBv4u+_ko%nXBz5s3(fZJA#iET>>Pq#@yc8eT_lB49wm&Xs`x+)CLITMIsOFD~ z9mFm5j)JwsfgA-^ea-07>a+>O$PY@D(`?n(7pJ3ZBHQI)rYk=)-^AP5DVO%8pPHh;N^TO z8w#ZN6@V?IuGe&fEay$d?H=UNwS5gGYBijhpriTm{1bQ)H4&B0l_d$gZbEzu1D8n* zF-^uqx_2Fy+n<_5)91)ybN#7d7-`>pC{)pj+~ZbW{duN137r@S66q4R-H<#FH}}dn zkBHGxc8e2oYOCw$IBNELK#EE!HPK|*q0^t(m4z6X1dZ{G?Qz0Mc-D`ls%C#AMM7P* z@@R5*SktgqTe`(H)4Y9RTQ*nuHnbfUkOQ;N`^M`_H1kQS=8G%l-D%Z- z^6r;+1&+$B^`B(5usC}5?2qr??Gj`tAG<3F+c#S)+L$0;$TP3&&Xdly)C^b6=5co3 znw%VYU6Cep7=gD7DtHiu*oah-=LY%D&CRWk-Pmb!vs_FYC2VL~-orEuh;r7HTF%;f zkJd*4p1rQFu9>nrmmb}?aU-XNM3i#x-WwYq9wLEig0dv(=tDdV8leawfs%>td?QTN z#2a1}b~tR=YZ4G@0y;HL?#w7Ef@smZZ?}(hGiJPgE#z9-&|Adkx{)?E%+l{~6T>#u z=bWwe9tTd=P<@i8ucg=34MSk;kR6Zn;dy(CQk2@{HeD$vWb*)$Al=C8u-S3*ORfQ* zjj5KF7W|WL-@Z*emu40hOKyLA7#60spKR0fWHh~`LwO{RQ(Pwl(oqZ?DpMkFa{P*l zyu8)A6SM^-t$F+=G&bLpmPWsP;rDN>wRq&m>Y>GMcQxWMj>1gZOz~HfYYu`(p=EzJ z#$R#JlsE)lY15QeQC&WNYQkA11l|9L$jGUM(e2F4?8(XRhp8zk2dAcFO5SEBCK@3V zhFm#@VxPyJCe)NTEq{jOSz@B6AV2y+#27%^l+&KUSg=#jgE`A?S_7s$V^?f!Y}P18 z2ztx{0-berQf6B{QKJC)mv@L(l#M7>E&Uz+H&MHBqd~Um4RL`z-u;+mbYhf(1b*#- zFgE4$z^U4j756mMueV>1?bPQEgM|rNu$*Jte5=O$%Qp6p_G~5#Z$se-KF7z#W2K}%6=qrCA zpfuwXG4b)X-^#b5|1^e&xsGQ%-COjt#$#(#q19k5{?kjOv>i<>ddSh{)=;17rl}<2 zERf#d;>v~|c^7pR)y@eH1pPa<)3&uWnf%U$b=7{vJT8jiTi$?91!;|` z$yj5grQJs9Ejj=9=#_|F^ur;g{3Ri{vO?0{Q4Nj#?2jKWWhPwL(3lz>T}F1CJ93?% zfbL)zBwstC;^GF8QZxvD_h{J}j@tzR30{jI1&`<(7!YU*jmfr6BAUDNSb??g+t*wIvvj~zL6Q!n@h@qcfO{EB^K z#_I?KLcH;Z{IEY?25wf3&?=thGCAP)Yiy6UzCH%JID2}Isj3WYA)U+4V%#%$n;(LD z!j4O^yXTgF6C(j?5B9`kUp05YU<19unIBC%*5@NPdP*GITUuVEC&xZ5z-i(6;K6&q z13P!_Ond~;nRu2wc@mASJd+MN0myyW24-hw&f+81H-$O>*F$$+sJhOMiuda9yG;ob zW{p$5thD_ey9k74o}ieRrC`mQ5)wjl_BheDv%lP=WT*#khMb&e;@`v?l0gfS=D@Zs zXxRmu1h9|T|8iOfG>+aT3*XeYZ+_38H?P>~KdTrap1D}Vu3S^3lP&LSYp=@6HX-(X zQlzxjDub93AhVR@p`f_LUp1q+Ta7Dyb(wKMW1qSFB5w7dU`|)7i+*;d?MheQXym!OUp6zF2sxvh z_(&}J_9%>sgHG*L(?1+_0Ybu<1Hg5NI#SSP3<*s4OwfK(op#N9jb}OS^%hIj7)nNo zv@kd40D9HpCNP-b`Hp6V>X)sAD^tK7ZUTnrh)PSFgy=Es0hgUzq{<=z7*01uuy5bR z?&Zzozb597a&%$#(@S2d$$nW{5xRWoJpVlVH6k#EGfyptmx19!M~BMO0$$#yB%~p` zsdRF5B_z={|MtN@Ct+U_J1eV*^+-+h#o7{w(Z+~0-aGV*{*IaI0s;jvL_(;dLTfkP zXBq|{;48VVFDF2d(XF7Fobu42qM{;^#GiNGJ*8yhv*oV>HdnF*tdsUcZ|tGv}__9>7`S-VxwYBjjB}8xzRT7 zv-hl2uRUY@!kv5J5kJ|Ut`e690sHHdKfEqt?{@_Oq-yLbP&#XYf^3}q7VE~WG?R3S z!_0Bh+3y=`K1EIineOzc3*jDk>y6ffj$b%%fiTWv+skGg6XZGO+n#T!nK?@3Re{Ox zuD5p>q{V9v6j@v_Eo`d~x}8#5x{jZKgg&P&Sr^g5QbmR6_Howv=zZpyWhYI|{uT3h zv~g^P>Z!(z7lzvJBLoTBrk>_e@b?nEgw2u@FZ~4&L7L;w%X{h|IQ-9nXzr-T5zJQO zn9WzOc-vZGV=&l4Ex*+3S^dUjeioZDWAVsE6_DWf-q^P{x_WR7f$3uo`MhOOM7$71soycfxgu zGf2-t2|`v3zJ@t2CEu%3oHi3ghc79Q-#!?Ywl)}i(6Fg1F7BmSU#gxt`*JBzK{QRi zoD+ty07Z+MfB_iMa8%N9E54b3j+g0oy``_obyQ z0?xLuhVzL1@C~h~L~aI~uL`Auq(({?F1*J<2HPSIzEXn*;AlQIHM|>}lN{y-8s-M~ zNMFlsxje z(ZGlv8y14)2^}nFAXSM`4or&jP;Q;v<6Cvt);8TWaGq!ZXx7oZP>SBz*7xsaR~Mx+ z^P6DF#w=3S$xkdm2o3%koK-<`wEWKB*ci{q z-ALEq*7@iOVey6Je6wrT5CDu2#u4AH6nL?S*u<2Os2Uj1%e;fb2{535fWRj?O7E`0 zzioksZ{D2FWaCHE8vFlI+-K2!*bDgS{0>gBPl}Dm{=BD{4+K?KmWJ}NcUF%q{$Ad< zSmqy$0X9OlBKkf?n8lW6Ex-gIElgs>^6<&N;IM_;Vd%zskpT zHS%=y#GJmInyG<-EjAQ3=u=@Xkk|pUpwMS%c@IbjzyUaWIh}mL&Bo541fd#0Fxp#GtBOhwGy(utrnfWx zbkvULYnH)9x}wT=$M`KhOI7u(shr%p}aK&M=N72bpiqP3qW$kE=GJ3$+Af{CdDR_5@5*ZBdN zTL7%*(cDhB>;C^`U=5i!xeTFucy*i_Hn3rkk0Ozt~>;tx4d+Cz4@`dk6#?n&7&)BDeTA9cIun zVrO6o&&s;lbv>3@NXYI>yu{ED=ecvtrlwVzrDl41j7uSJ-|~}@k*V)#rP{J}t26%o zVt+a|a$k`hys*V{6e=ht9f5C;BIiPCvPNr&8Wui!f({EOXv8;NguOJsfB@VJJiYN# zM2a-bgIeCteZ16Hd~c8UGY#oT4TnV&U9XbsNl=;GMSiEY=9{});+`WdL2)FA56v3s zqdL@wop3}#1W8#wfz{Em%KPw{Pwy|7IcjT1LkQ`gR(7R02{-!A@MRbRjFYyZNt~Pm zN%m<8)3{sL8uoAbpcSl?rw0d__%tBdkB3jnY4*4=J~h=0Bxw|cNoA}b5LmFEm48xa zVo5B!^A0$!8bb7b^=Es~3m(VYfM-9nrWA=do7`JWMt_C<7yDM6>W!_u2hQ}CX+oXh zFP7xXlmlQ+!s@oozE?a(fXR?A6QK#w=lR+Z0Svlvrz{Z!xb7)p(W(5)yj+=2g(j z#`_&1Wq*`{Vy298>DTXCuS0b*uM%ahJii?$6B8B1Wfj{sP;>PW+5UUWyXOVP&@)0w z^*KaMK_NCJrQ0PkV`gzYtKT)_*N;6HE?m$hGj1k3$fk7Sx7YJkx9b@9g$Q+VXZ&lRnM2*X>7|i{^(VrKNQx zOt16N-Eh0KS1#YjJ1=i3h+S={F`O;$^S+!zsIEbdHx(6qhnMdo9}I+uwgRBf0zuz3 zRp&Ns*g0(LmU1*{Vsa7_0H?uS%$x;0$s`rjq8WQs@bst06JUBIiU`mD{8>hOD1nxG zHP&vLrNnWVY^x-fa6o&j;{5y{#EKyOnh#r}^i}~=J|)$DF5lhZ5%-@sO9k@AqOpq1Q zH#9Zx@gx?4q7H|Nd1wbI>8-NW#`Rg(NcUlE)kv(A$?ak_UhME! zuOJ!iv%Yy!+`(Z5KF8n$#op_gvY==L6@`hP^A;iZFgoa02xS=h>=3)2evW_ zv6n)27O-1lfBYb4aCo>Wls9GlA?r~wz9ZC{cnf=SM$PTtz9}s1ym;df&zGe|*kKR| z$IU0>f_0^mb{&2vaQod!77ywp$x~yj%RYr}^~VQf#dh!et}35xxoQhLcYu95gKErd z@MoTO-ROpQ9I&XieiI|3!|)G;lDcSUtjBAg6`Y94||4W1|IbJ1#EH zjp87kGr6j4wYXT@-p^85j}j3&1?(wygl-}bZrPtZ*2`4=@IM|y zq+|`1!=(hxsFD-x>?rn=5JoVIzmM)Ud8fpc19ak7PgPAM-lyCW~iM zTADEW&fxdC@1b=;rM9xCxuvD2)Y%bJaA9F#6LqF#9Zu)VM%CEWvI8m5nLgt9Y~n7< zwUE=GEbOA@!-4vQ-K=4FKHt2X2+@NB_3g9D(Eja@k({X)*_y)ygM?0(e3tRj9Jgkz zj0~~!A|1*&7SeQRo2RH~SNBiuzdFY9*lI70d_5%l*=r40cx`CwFVrCO+ zoos`Kt~c6`Fx;Kp|CwfSbvfX!P@O=IAb1%dRpQj47P2*4OG8S7gY)n4A2VS}LXJKT zh!2jf?V7%)PVh@tYl}HChDFqjkC`-u8QxjVYv^|!=TNy%j6wH}p^?(d)GP}=86s>7 z^;xrk0GmS`FWOrJZ%Z7cYpbXTRm=OBk`!)t*U@peQB+pUQ*Nj8>L07i61=Bi(%^78#;r(2uA-=I2ySG zR0<*(suoxcBC?EI>NNhOgnnGF01qqBGWaKfwR913#p`VtLQqz2hbNZ!k5B_r&!^eL$3CQ@ms{cyTt^XQ*M05aT1ayeE?cC`!`~9(5@+1L_s?D1>7urov4GkTnp}Cdcaf&jmA%f5R zCj4DNTgSK2)70~5=`=K=M~07Arx?K#b=MK6cfd;$uD#STH;37iOXfj_<4lT!gH>hA z29fdc%fFZ9A@j%7Ed^{o0P?$Fj*8e``_SMW^Dd~CF_2Ty)Nr{Qz zogHUqpTsyMf;ksQmhOk0lN)!ftO|+#aSReiCaPt(Ny?(lXL&5R4pEnF1v6UOa&o_# zquW7NEw!`Un461F|Gajn2nc#z5E_RISFW|Jjj=7ebEqNp)HnddE&Nir{RG_z|HUL5=RBI|#Uk4j!yc)+0U1!O@4a z9cd?^w_tWP+x!~J-9$fZaQM(mK>!^cAFoTTZY1T-A%*(_o(Qq0@8{=7Lb}sv<_y}T zVSMIXr%$WA(Yjz_lKhNqLJMpue`lwuv5{hsETw&fwrp^(_)91#){ za>cX}SaZ%B>m~K9!6neN#pbcaS+TL)*ly&x zi8dYGCI1wvL0;Zm7U|FP^K2N;NQsWlVcS9=JU?^H*W-&(TC9nVXZlr2F&oHdZ!G5BK=Vo}}eDCNBy_$tCT~7Wdt);k+qzzhrUcJAvl_>oT3Uu`sM5En~`C8%ki@N#)j=1^;Z`IUOav* z4wEiyes~SO0Ukj*Es7y0AGB7UJ!@%eivS-DW$4P!Y0gzSs+6~Hf8ieZq=JlGenl~L za%=~9&uwVZ^eXAyw=21P*jXbx5yfz!1`2xqoB~M>6_u)jLdyb&SoCS!Im|e*%BK$2 zy?-BVkyrW7D*<|&40fT5dK4)T2&Mq&vP{bS${u{W) z7-(@s?;p#3HZQgki;fc$7tSeU>%s>0hwbd_6cwMy9I`ow8rj#=lOHq8*pv7GflfEH z`*B=MjDSlqTt?ut4f03XBWF#zzlg9O8wzWtdzNk55uDxyuq(nbN4|Y~q03sKQL+-E z^v4UA0M8;X2eA<&MwhmYcIBoZkF6-Xq=}wPjg|w$f$iDZ*ij2oQHqC zS#{IfOTV=ItoXr$zJ*bg%P~I74H{)Q&j`(Vq#zbxZW!cvkeQ&|uz`Jk=FAxgYXuJU zgoYqap`~-}h`cf2&iYcbf&U>H$V=fXXQj7sL79D~{*2?W%a7#^3Pshe0I`Nj22zynO z^Iom@`1#TN$%k)5TW`emtC;6}`gCPHqim|LqMX z;0UgJ=X-W+O0)#2-;XL^rZSSi1_O{qpaycM$1qY~HZ)eqG-$p4r5OoHk`flM*+)-L zPs_dX1i~RIJD|8ffh~%kjegR%xuUA-Y{yw2a&)%fXL~9%5Qs=i?*R|f7hOB*n`6uS zh?h%ivLcif(YYtaRlHhYwS94X!lCcu>zl9}{oXqT>Y(Uy1grgg46KN!ZX*(i!=IS) z3_WWE+vF*)p!IVw%b-Re27v^n#P#;MD?i?oh;5^e{En3r6{0gKnjRT>YxIf!d?fJ- z3|t)3jIq0V?pQ`);Z43poQenr4Um}a>3LN*2$JAk{-Yeh-N!iVHnZYhrNFAR-lT^O z3tAPTCkD*t=jWM39wrv0bVT7X7$rmA&%nqiF+QHTa8_YKyjK%Mk0PmYo+XIH%N_G& zS=k$a$==Z6DJ0oO&Bs4U@DtDUhG^WMAUQ{{lpXo;lO!Z0`}YSR<$UUGh*2|mvto7i z^#g-~o|a7Gt$`rQe&-7`P}fyj4#tE%T-mjQ4Hg0Z|kxUa$g>Li-yBcE<|~+MEp`hJPaGUs}T? z$D!e7BLgk1uXx>m{P-|Dk8F(CwMf`NM?%uXg!S%_nHgU<9@&a60ArX_S_cF1Z@!>s zU|_|6v@iuLo5`e_U&^aSRit#5-9(O*^J#WyR%Ng?9drS^JmJ@1UZ>R)9as z6Hh*EY(gl&;#r%U_r8|cgZ>6SXItX_3w*rEseY3z-#+dyI{kB4FHxH@oH;3=$rPC zKsar|tB3!8UuH+i(M<$y9^#Lnhy89R+QEeTC;uQIXo#G?Nc?45PmvlFN)ZU5+U{61 zT<;EqL<1=yoZjjnu$jQd!Xj~;fPh>8x3$Dv@&3u?y1j&dZeaU@)fPg1Gx1Lo2qByQ z-fz4prv%|Y?iiWV2*)OZkvr9qzn_xV`g5=E4vY+LBbc3!z_K$1i8>B$x?uF04zEAgis{-|O#_0yZ`o9AN??^&B z{;W=xn}!eJ{{Qwq{#iBfQb>E5{&Rh?!rT9TxsZo-gP(70CN%H-*H_eQ-s)eZ z;=h)Qi~XM)4WZ}e4w%{p4+JyGwlvEIrONbH@BjLObvZrt_1AFjbq-&BONrG^-)VJc zH}OFeSNXrMaLDHW&pm-v?iXku`;R&wcdCDr1JWZ)B`0mX!Gl_&tcL^zHz( zWB=UqMB&ynq3)Z#|K0^eW>{SgGQ~gJ?_W><|8Q?_)j9sPo?6>+3jAO8tAP>mt6zJ7 z$MmkYre^Q9Ep8M71@4BXX`NTMfvT!3FK;@}@UIACTigS{9qzWa5yQlNoWEXbcJboH z^O3SgG=CQIs*%&-bqCwQ+(qxd_H&O<@G3Zb|A8qHzn*@8R|;M?;uikjF7f|!$A7gd zunr~=cs~5|o)Uim2$^P!UD+Ap&Eu + +namespace autoware::steer_offset_estimator +{ +using geometry_msgs::msg::TwistStamped; +using tier4_debug_msgs::msg::Float32Stamped; +using Steering = autoware_vehicle_msgs::msg::SteeringReport; +using diagnostic_updater::DiagnosticStatusWrapper; +using diagnostic_updater::Updater; + +class SteerOffsetEstimatorNode : public rclcpp::Node +{ +private: + rclcpp::Publisher::SharedPtr pub_steer_offset_; + rclcpp::Publisher::SharedPtr pub_steer_offset_cov_; + rclcpp::Subscription::SharedPtr sub_twist_; + rclcpp::Subscription::SharedPtr sub_steer_; + rclcpp::TimerBase::SharedPtr timer_; + + TwistStamped::ConstSharedPtr twist_ptr_; + Steering::ConstSharedPtr steer_ptr_; + double wheel_base_; + double update_hz_; + double estimated_steer_offset_{0.0}; + double covariance_; + double forgetting_factor_; + double valid_min_velocity_; + double valid_max_steer_; + double warn_steer_offset_abs_error_; + + // Diagnostic Updater + std::shared_ptr updater_ptr_; + + void onTwist(const TwistStamped::ConstSharedPtr msg); + void onSteer(const Steering::ConstSharedPtr msg); + void onTimer(); + bool updateSteeringOffset(); + void monitorSteerOffset(DiagnosticStatusWrapper & stat); + +public: + explicit SteerOffsetEstimatorNode(const rclcpp::NodeOptions & node_options); +}; +} // namespace autoware::steer_offset_estimator + +#endif // STEER_OFFSET_ESTIMATOR__STEER_OFFSET_ESTIMATOR_NODE_HPP_ diff --git a/vehicle/autoware_steer_offset_estimator/launch/steer_offset_estimator.launch.xml b/vehicle/autoware_steer_offset_estimator/launch/steer_offset_estimator.launch.xml new file mode 100644 index 0000000000000..9ee05189a35d8 --- /dev/null +++ b/vehicle/autoware_steer_offset_estimator/launch/steer_offset_estimator.launch.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/vehicle/autoware_steer_offset_estimator/package.xml b/vehicle/autoware_steer_offset_estimator/package.xml new file mode 100644 index 0000000000000..4246f8dee8a4e --- /dev/null +++ b/vehicle/autoware_steer_offset_estimator/package.xml @@ -0,0 +1,30 @@ + + + autoware_steer_offset_estimator + 0.1.0 + The steer_offset_estimator + Taiki Tanaka + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_vehicle_msgs + diagnostic_updater + geometry_msgs + rclcpp + rclcpp_components + std_msgs + tier4_autoware_utils + tier4_debug_msgs + vehicle_info_util + global_parameter_loader + pose2twist + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/vehicle/autoware_steer_offset_estimator/schema/steer_offset_estimator.schema.json b/vehicle/autoware_steer_offset_estimator/schema/steer_offset_estimator.schema.json new file mode 100644 index 0000000000000..cb2a03c97159b --- /dev/null +++ b/vehicle/autoware_steer_offset_estimator/schema/steer_offset_estimator.schema.json @@ -0,0 +1,65 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Steer Offset Estimator Node", + "type": "object", + "definitions": { + "steer_offset_estimator": { + "type": "object", + "properties": { + "initial_covariance": { + "type": "number", + "description": "steer offset is larger than tolerance", + "default": "1000.0" + }, + "steer_update_hz": { + "type": "number", + "description": "update hz of steer data", + "default": "10.0", + "minimum": 0.0 + }, + "forgetting_factor": { + "type": "number", + "description": "weight of using previous value", + "default": "0.999", + "minimum": 0.0 + }, + "valid_min_velocity": { + "type": "number", + "description": "velocity below this value is not used", + "default": "5.0", + "minimum": 0.0 + }, + "valid_max_steer": { + "type": "number", + "description": "steer above this value is not used", + "default": "0.05" + }, + "warn_steer_offset_deg": { + "type": "number", + "description": "Warn if offset is above this value. ex. if absolute estimated offset is larger than 2.5[deg] => warning", + "default": "2.5" + } + }, + "required": [ + "initial_covariance", + "steer_update_hz", + "forgetting_factor", + "valid_min_velocity", + "valid_max_steer", + "warn_steer_offset_deg" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/steer_offset_estimator" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/vehicle/autoware_steer_offset_estimator/src/steer_offset_estimator_node.cpp b/vehicle/autoware_steer_offset_estimator/src/steer_offset_estimator_node.cpp new file mode 100644 index 0000000000000..fdb5fdb404c0c --- /dev/null +++ b/vehicle/autoware_steer_offset_estimator/src/steer_offset_estimator_node.cpp @@ -0,0 +1,143 @@ +// Copyright 2022 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_steer_offset_estimator/steer_offset_estimator_node.hpp" + +#include "vehicle_info_util/vehicle_info_util.hpp" + +#include +#include + +namespace autoware::steer_offset_estimator +{ +SteerOffsetEstimatorNode::SteerOffsetEstimatorNode(const rclcpp::NodeOptions & node_options) +: Node("steer_offset_estimator", node_options) +{ + using std::placeholders::_1; + // get parameter + const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + wheel_base_ = vehicle_info.wheel_base_m; + covariance_ = this->declare_parameter("initial_covariance"); + forgetting_factor_ = this->declare_parameter("forgetting_factor"); + update_hz_ = this->declare_parameter("steer_update_hz"); + valid_min_velocity_ = this->declare_parameter("valid_min_velocity"); + valid_max_steer_ = this->declare_parameter("valid_max_steer"); + warn_steer_offset_abs_error_ = + this->declare_parameter("warn_steer_offset_deg") * M_PI / 180.0; + + // publisher + pub_steer_offset_ = this->create_publisher("~/output/steering_offset", 1); + pub_steer_offset_cov_ = + this->create_publisher("~/output/steering_offset_covariance", 1); + + // subscriber + sub_twist_ = this->create_subscription( + "~/input/twist", 1, std::bind(&SteerOffsetEstimatorNode::onTwist, this, _1)); + sub_steer_ = this->create_subscription( + "~/input/steer", 1, std::bind(&SteerOffsetEstimatorNode::onSteer, this, _1)); + + /* Diagnostic Updater */ + updater_ptr_ = std::make_shared(this, 1.0 / update_hz_); + updater_ptr_->setHardwareID("steer_offset_estimator"); + updater_ptr_->add("steer_offset_estimator", this, &SteerOffsetEstimatorNode::monitorSteerOffset); + + // timer + { + auto on_timer = std::bind(&SteerOffsetEstimatorNode::onTimer, this); + const auto period = rclcpp::Rate(update_hz_).period(); + timer_ = std::make_shared>( + this->get_clock(), period, std::move(on_timer), + this->get_node_base_interface()->get_context()); + this->get_node_timers_interface()->add_timer(timer_, nullptr); + } +} + +// function for diagnostics +void SteerOffsetEstimatorNode::monitorSteerOffset(DiagnosticStatusWrapper & stat) +{ + using DiagStatus = diagnostic_msgs::msg::DiagnosticStatus; + const double eps = 1e-3; + if (covariance_ > eps) { + stat.summary(DiagStatus::OK, "Preparation"); + return; + } + if (std::abs(estimated_steer_offset_) > warn_steer_offset_abs_error_) { + stat.summary(DiagStatus::WARN, "Steer offset is larger than tolerance"); + return; + } + stat.summary(DiagStatus::OK, "Calibration OK"); +} + +void SteerOffsetEstimatorNode::onTwist(const TwistStamped::ConstSharedPtr msg) +{ + twist_ptr_ = msg; +} + +void SteerOffsetEstimatorNode::onSteer(const Steering::ConstSharedPtr msg) +{ + steer_ptr_ = msg; +} + +bool SteerOffsetEstimatorNode::updateSteeringOffset() +{ + // RLS; recursive least-squares algorithm + + if (!twist_ptr_ || !steer_ptr_) { + // null input + return false; + } + + const double vel = twist_ptr_->twist.linear.x; + const double wz = twist_ptr_->twist.angular.z; + const double steer = steer_ptr_->steering_tire_angle; + + if (std::abs(vel) < valid_min_velocity_ || std::abs(steer) > valid_max_steer_) { + // invalid velocity/steer value for estimating steering offset + return false; + } + + // use following approximation: tan(a+b) = tan(a) + tan(b) = a + b + + const double phi = vel / wheel_base_; + covariance_ = (covariance_ - (covariance_ * phi * phi * covariance_) / + (forgetting_factor_ + phi * covariance_ * phi)) / + forgetting_factor_; + + const double coef = (covariance_ * phi) / (forgetting_factor_ + phi * covariance_ * phi); + const double measured_wz_offset = wz - phi * steer; + const double error_wz_offset = measured_wz_offset - phi * estimated_steer_offset_; + + estimated_steer_offset_ = estimated_steer_offset_ + coef * error_wz_offset; + + return true; +} + +void SteerOffsetEstimatorNode::onTimer() +{ + if (updateSteeringOffset()) { + auto msg = std::make_unique(); + msg->stamp = this->now(); + msg->data = estimated_steer_offset_; + pub_steer_offset_->publish(std::move(msg)); + + auto cov_msg = std::make_unique(); + cov_msg->stamp = this->now(); + cov_msg->data = covariance_; + pub_steer_offset_cov_->publish(std::move(cov_msg)); + } +} +} // namespace autoware::steer_offset_estimator + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::steer_offset_estimator::SteerOffsetEstimatorNode) From 481b84d5d8ece798d746f0b89db0db4c3ee708fc Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Fri, 7 Jun 2024 08:32:57 +0900 Subject: [PATCH 2/3] fix directory structrue Signed-off-by: Go Sakayori --- vehicle/steer_offset_estimator/CMakeLists.txt | 34 ----- vehicle/steer_offset_estimator/Readme.md | 65 -------- .../config/steer_offset_estimator.param.yaml | 8 - .../image/kinematic_constraints.png | Bin 47715 -> 0 bytes .../image/steer_offset.png | Bin 56450 -> 0 bytes .../steer_offset_estimator_node.hpp | 69 --------- .../launch/steer_offset_estimator.launch.xml | 22 --- vehicle/steer_offset_estimator/package.xml | 30 ---- .../schema/steer_offset_estimator.schema.json | 65 -------- .../src/steer_offset_estimator_node.cpp | 143 ------------------ 10 files changed, 436 deletions(-) delete mode 100644 vehicle/steer_offset_estimator/CMakeLists.txt delete mode 100644 vehicle/steer_offset_estimator/Readme.md delete mode 100644 vehicle/steer_offset_estimator/config/steer_offset_estimator.param.yaml delete mode 100644 vehicle/steer_offset_estimator/image/kinematic_constraints.png delete mode 100644 vehicle/steer_offset_estimator/image/steer_offset.png delete mode 100644 vehicle/steer_offset_estimator/include/steer_offset_estimator/steer_offset_estimator_node.hpp delete mode 100644 vehicle/steer_offset_estimator/launch/steer_offset_estimator.launch.xml delete mode 100644 vehicle/steer_offset_estimator/package.xml delete mode 100644 vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json delete mode 100644 vehicle/steer_offset_estimator/src/steer_offset_estimator_node.cpp diff --git a/vehicle/steer_offset_estimator/CMakeLists.txt b/vehicle/steer_offset_estimator/CMakeLists.txt deleted file mode 100644 index eec8b2e24bec7..0000000000000 --- a/vehicle/steer_offset_estimator/CMakeLists.txt +++ /dev/null @@ -1,34 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(steer_offset_estimator) - -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) - set(CMAKE_CXX_STANDARD_REQUIRED ON) - set(CMAKE_CXX_EXTENSIONS OFF) -endif() -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic -Werror) -endif() - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(steer_offset_estimator_node SHARED - src/steer_offset_estimator_node.cpp -) - -rclcpp_components_register_node(steer_offset_estimator_node - PLUGIN "steer_offset_estimator::SteerOffsetEstimatorNode" - EXECUTABLE steer_offset_estimator -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_auto_package( - INSTALL_TO_SHARE - launch - config -) diff --git a/vehicle/steer_offset_estimator/Readme.md b/vehicle/steer_offset_estimator/Readme.md deleted file mode 100644 index 164d411e31050..0000000000000 --- a/vehicle/steer_offset_estimator/Readme.md +++ /dev/null @@ -1,65 +0,0 @@ -# steer_offset_estimator - -## Purpose - -The role of this node is to automatically calibrate `steer_offset` used in the `vehicle_interface` node. - -The base steer offset value is 0 by default, which is standard, is updated iteratively with the loaded driving data. This module is supposed to be used in below straight driving situation. -![image](./image/steer_offset.png) - -## Inner-workings / Algorithms - -Estimates sequential steering offsets from kinematic model and state observations. -![image2](./image/kinematic_constraints.png) -Calculate yaw rate error and then calculate steering error recursively by least squared method, for more details see `updateSteeringOffset()` function. - -## Inputs / Outputs - -### Input - -| Name | Type | Description | -| --------------- | -------------------------------------------- | ------------- | -| `~/input/twist` | `geometry_msgs::msg::TwistStamped` | vehicle twist | -| `~/input/steer` | `autoware_vehicle_msgs::msg::SteeringReport` | steering | - -### Output - -| Name | Type | Description | -| ------------------------------------- | --------------------------------------- | ----------------------------- | -| `~/output/steering_offset` | `tier4_debug_msgs::msg::Float32Stamped` | steering offset | -| `~/output/steering_offset_covariance` | `tier4_debug_msgs::msg::Float32Stamped` | covariance of steering offset | - -## Launch Calibrator - -After launching Autoware, run the `steer_offset_estimator` by the following command and then perform autonomous driving. Note: You can collect data with manual driving if it is possible to use the same vehicle interface as during autonomous driving (e.g. using a joystick). - -```sh -ros2 launch steer_offset_estimator steer_offset_estimator.launch.xml -``` - -Or if you want to use rosbag files, run the following commands. - -```sh -ros2 param set /use_sim_time true -ros2 bag play --clock -``` - -## Parameters - -{{ json_to_markdown("vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json") }} - -## Diagnostics - -The `steer_offset_estimator` publishes diagnostics message depending on the calibration status. -Diagnostic type `WARN` indicates that the current steer_offset is estimated to be inaccurate. In this situation, it is strongly recommended to perform a re-calibration of the steer_offset. - -| Status | Diagnostics Type | Diagnostics message | -| ----------------------- | ---------------- | --------------------------------------- | -| No calibration required | `OK` | "Preparation" | -| Calibration Required | `WARN` | "Steer offset is larger than tolerance" | - -This diagnostics status can be also checked on the following ROS topic. - -```sh -ros2 topic echo /vehicle/status/steering_offset -``` diff --git a/vehicle/steer_offset_estimator/config/steer_offset_estimator.param.yaml b/vehicle/steer_offset_estimator/config/steer_offset_estimator.param.yaml deleted file mode 100644 index 2f73449cd2969..0000000000000 --- a/vehicle/steer_offset_estimator/config/steer_offset_estimator.param.yaml +++ /dev/null @@ -1,8 +0,0 @@ -/**: - ros__parameters: - initial_covariance: 1000.0 - steer_update_hz: 10.0 - forgetting_factor: 0.999 - valid_min_velocity: 5.0 - valid_max_steer: 0.05 - warn_steer_offset_deg: 2.5 diff --git a/vehicle/steer_offset_estimator/image/kinematic_constraints.png b/vehicle/steer_offset_estimator/image/kinematic_constraints.png deleted file mode 100644 index 810b91139c80b616595c9ca066633bd6728c17f2..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 47715 zcmb4r1zc2HyElr0NC`-nk`mILDj*FCNOyO4jglhW4Jsud-8uBoDcvnO^Z*0HxA7d` zbI!f*z4!g*H^knvXZG69T6?YM`NxF3QIN!ZNb(Q~2?24bE^W^~wu;;qO zcLMlx&*_!4$^+ox{lNGmuubeNq3*0~XX@-`;AnzmW@~3-^4!VD(Zs~o$=uEviVPM3 z4&t;>QFj(|G%;|tu(N%lVqs$f>_kH1VB_Feud8I^*+}~c{7TGu!p^sm?8nZr{xOJ) zV>2&?e?EpE3F!%vwD?OE_q5%4khb=EI_!p!Es2vyb(9W$4wo~lNA+uUj3wze_76$* z$ttrijJQ=WamTdqsz|nNsW%e8Y0)AuG`Xd??$6dfnw-XN!1?P$Ch8t|!6YV6Ff4j2MZhcJ0m(zkNi+K2*Q~9wChQX;i=i_Z=gj z1hAi`K*j#k$B!SSRPvV|1FuJaD|Z*7KoSrXq~_V*-liHBNt5z%c5_31L`dk?@AE9! z@vkT3XRiU;f)T^0uk7LBA!_G-tUarMBbe-w}ZPfxGZ%5dAhwL zcBogWZe0)v_H=DlmQgo^`gCM$4Ecri?vhLK-Gd_hOc9S~f;ow`w(t6_3#r09f zJm9TiQjC0(`SwgHn(II?qobvOPx=9J;e1he8*~m_4Iv6_r1bQ398xzI7aVg+g=~@f zhK4&ILqi2OMBR0PxzAceSM3}BC{n1z@V3Rhep`Q5jyW5dN%%EZ)feR@&%>QE(4cNRZ z`Pa*6%pbH?8yXtmwy~6Qii$%~HdLoL`JnX&i;{(KRaP45nUs!Kyd~g4 zaMQtE)~173i)AaPI}TR|!A6#U?-}Ry;fI?KV8Dg7YI&U@AzmE=Z&J8MrHm4B+kaoJ zY{SD7pP+QpippGv@N5CIn!WS5kRD(LE)2IHcj|qXEt3D^F8uc++GdLtI&QfK ze|ipE?zkNpoIh4S%x_Td?PQZh!`U#XcgtG4NOz9^c571e1}o%;0weaX`~LThm*b}l zG*$eo%>COD{crBvgtIf(7O;nzxA#?4xS)VQkhhQ$rLeFtQb!k-?j|GT;F8b%K!3_8 zFK`;$N~r&DGe+3l|8$=&pB_pirC-x4W{~j=xhG-&HRy@z_?=~R{`VIB*QrcHsA+b` z+12&6_1yTl#AhGA=*yq``zTLXSoUwHNYRo>(lhm1p;d#w54g3B(tFUd#}?q6^YinM zHW6-%^y@^rltBgo!aP&%Mn3;Mc9_BCKbuZ}ht&jaj%0Cue%>whO5fAdGsqe*KT_(N z3332`u=|C3uKK^7;NhR)r!Czw)7IARzcOj&I2JeBjDuu0V z=JMGWGGE;i-rX{LkFIv_KNf;}n^Tn*c!b*aFQqb9Jwy~NuofvEvYb;4DT3ZNl`KT; zsjTY<^h5Xt49YZ%d_?cvh@}0BZ;+=@>8y9QPkJ1+<9`dXpHt)Y+3cJzd=EJTuZpah zu7JY9v8zh-DW}ES0EA&+SrAhe;}L13K^1QCX>CfRLyB154+(K&Ifpv!%Bm`d0q)7P z#+RbszPKBqRe^*(#6E@5-42pp2TWO4#|q@ulx5_8P!mWOiUyNtt;PKcm(eR(S#+%$ zTa)%6OdulFw)3C*)&&N2=eZK_qhfurdd$@MubK3o@^kyoalhkoIj1b?t~S)s44j?p zK(1H~5nXMFtM$tO?{yy+#l|GNTvR=d<6hYpjjKs6@N!B98F1*O@?h@7IVHJ_Gs-Mj zqgzZ|b$B-)t!q4P9v9y_t&pnLOukV$jw<a#wW8clarIJ=j%_C;I_UziQn;Qx#W9tmzD?OgfEc_H`E@% zaQZHH>hzT{d!QQKah{FaQmrSRyiZ{kN>Jzf2%k9JOj(atEZA|^lxZc_rZ@^bI+^Xc zq9>;^?V705JHBES!iirYp>={@xP!ABu{TPb`ubHEjgy~;K0I{XWd3ST*spttlrt2s zN3EMO^f>y%R2YT29%T88T8ps6Wb5TMGQ@8Ngm7!BMp09LeE9y)f z{CdQL>vG0HyTjOOxtC4E8D8uPj4WNAS)V_WxK<9YId4S|15Yj-kY<>Flh_>ESFEkf+any zr+-$A!`;`dCfQW~m0z;nSZe!mN*%}jv2JFbn^8g6Q+a8+Sn`dHjbYftSm}&hg?{eB zThR_U$FS5*8e_19WgxJkyv`}osyX_Z6{)1E+BH|_^x?y#-GY5P=9D#01_*IsMA8yd4(JL{mY0IJ(CmNel^dGC#b4MY{CyCEW$I*&ixKAx1gmx zy>Z!3Tyra{)vQR7qZ-&Cm6ZbSf?FCNyy!AVH(7A){EmfNT*a(LPcOP3)+L5g-YlE< z09VbK;Hix?EqvSAuYt#Os!Xe~vg)k3l1IRyez{R%GQgOPh2^upLEG?$Muh^`YJ+V4 zZjKpqJ3DA9soN+2?_0wvTJl-NvgFD^&6K+0;>Pzpj|X^r`uf^UE6S{=%bRU<&vvKV z8$FIMXQr)rta)bHZSQ7^50YP4du9dr$(kzF4Y#^&>h$7AP)6B?YHxA#?zQh&Wvvw$ z%d}OqnY&i`4GlEIn(Rycw7n$G2bp8dMUb+|Jc@<6UEEpQCxedjsd$>+h+TUP)C#`h z#Hd~Fj*)Xzx-mjb?i^mgw4EDL9N-wu4#h=!?e|7UmDydnFf;Osl1*!FRBrm$-Yw6{ z*=FHOksby1m>d3Yc{X}sFMFd17KISe*_4IBSvv{#A4$Y269jw%2O}S}QzD|y&d!?2 zN}A3{?%%(E4`GXZ!=0g=r?4KYD8he9rUwpA)Dy`pe~z!xTpftX8ejSWElt>s;ilX` zczRPFX(<*AN21K6yiAG|JsS${^LfC`sjk_WvAc%mqjOpBqrP&rBizOBP+4;mesduh z)%ejR^{AE&ONe6V{WT^YcvQhlkPK0Yhlke~Y+)x#cIHCnp;zzjG{3$ka{V-9u_?Jq zQMXr=E~Dq(QfvxnIS7Jy4?B>otbrfb3DYI9dpmqfKRf??!FNuqLwDls`w>WPL@s|S z%gGt~fUuLTko2s{=;$ci1Svst$RfO%ZvGdYW@OfOnsj*Dv`{{gaiV_ zSq-?%{cxq(^+Wu?)s=Vi<#-8&azsZ*s)s&eKxpZB^dysY_4~r>9%Ylc@+;@&iQ44v zAqO?A8c67QiYaYz42X+T`HXw&QiwApM^kKe%4Ws$-sBcDX>TiOEG+cOni^~YO1x&F z4@8D+xVXgDy_XA#z*>E^;UmD>oSIk|DuwQunu4$o0%vmGeCQCrd1&g#jbcc5u+AWP zsURm8Ff{l?1jSG>^R~@+h~>VHM`DrdvdE6U3uE#a?CN;9$sC=i&G!@{{gcK9^&JhV zLNXrbcC^6t>K;MH`Q?b(GnLo*MuUribS3&N(>ZIuJ>1TAs`SohD9O+&X@ARE5wzl{ z)sk^C*Qk~;-;$`YPS}Mms3f_otNH`BYpnySf{E5{f11I2FV=7^`&-Ztqsq8_*zkdGGU@8q`!C-RLf~jd2%cFGNQg zmET;TO%l94F%&NBb?n(z?-@@_?|gh*!k5YPWu?jZh?k|!m$~F=&&#v4dub&LlKUjx z^8OP+j52N{bC;ne-t|}P+j`8ohK?)|f$fcGXipe|<7M}=a(4;WwD*kGSCWZrPE~|7 zhWcr@xDqfO#vY+WR7o(;$IEuw5Hs6qx5mg0cI`MSA&eO?@yM+;zRm`Ak^IVO8M%3R zV-pi0Rg=1Xb(cd-vucS^4KQ`g9(zy~|XO-gN0etKG_z34a>*k6yp3Dz68#O(k zEB;TmSTmm8F}=M7o-ve+*~VTBH z!kMtxB3E3L+Q5zWssRzq={$$;S%Kr5AJ9^W6UD_WESl1p`Ls?fX(({Z=+bgqxKJ!o zUT$47)wOiDXZVRccIDkzsR!N{(X_DxaCsi=?)c7av+`P#B;LI4pSf1IsklnTv~^`= zWm*!czj0DZe(m$%&OQqC`Oou{;^R#6?(})l4y~UR6CAo%w&r#7Dk?Y)SAhiT*JLW` z=EjTU;NSq63wAsYZ0MfdISm^4T@!b?Ma;}-`d;+u0VO{@6+|jI^5>@15=j1v(?wAw z_Btdq(-`E>$=?qx%-Fc7p+DHetSM(3^q&;e1&V5_Qv)>Ju87KPa!N|dvVp^Wcs5!4 zPCFZlE~ODs*XPyn(~DbxE#fe>eckbJIhgV&^5#4;B{DXly|)n#>a(LS+5BQtau_$LL(Qa*mZE$m;{H8u+Ax-Z|Ck(Ev6wWHuk zEwWP_giv_xKF-^LOtuWM3X$*7!q|T#ieAnNXmE3*?6}FAhyJKuJhrWXICc3+M(n{S z+db^?h$n~!>&863dI~vsE9^@NlkcR-HE?A*LOvu>W~%a1?6ju_y`77ERF8^MXqUw})OSwssgPtSGQ#Cub4 zam$L+Wm^SF zZ(TI`>GZl|)2L?|zqEZycWTgeJUeG+rp)#<5Gl3?|qA_Pd%lx>}zqH9$sUU|`S&uIDNLf)7jw$l6yU_E8&JNt0InZbrj-+|bA1LvQ~5W%2Tf z@0(861TzlK=}+SVAxiWTK$a=nUL=3Pm9Il$%75u4EjtCnQi=#R$nbr z&r1_~?Rp0v8gTJ&(@jR>bUv9T)1Xsei;N>-A^5oEy()6?vbEP`Lz+QTR9nrgxw|3% zu`>N>lO#WEVt50cGs1|jC-%E~tQiML0u9qfUdXeva#;s7J0jJo!*85T$Js-&3Ic7e zm7kdqJ}ueChOsj(^j^`YSj@Um)@^M@UB#E2Z$9a7L~-=Fwi~|dS`(SiiStwvwBXn_SvxGKwOI2>Wu0{Ux<@v(ypE5 zo%WR+7qvUnv-HsoxoKM9l?}VWf$wuucDnwKCYvP?hgM>rI@7wQC@z&^YG{a0kIcl? zniY+6%^@7bN_w6l9y+~qJS56XZDD0adUOa79WE}(IyyR#abR8XnVPev6YDMk3VTJ* z2z^hzTh3tBcwN2PIvGv;>U1TPmBK5c*vE9FGigdSr9rsWhm4~yktRvbIZ5j*HP^zk ze>*isj!v*2BKja5Te01ebHFdzQ_{yS^K@fx)6h_wja(5yYi=A_2RCg9>9j5O&El1u zv~@Chm|Lb_F+DSzE5O>*A;me_bSnB%ao%dd2Zv5tcA$4iZftkPW+BbbqTg#6Bh3D1 zpfzV}j4{jn0*L@+aKV5#X)b$1_Z;sJZ!Y}QEfhMuv4O9P9uX&p7XF~!o(of#r2}}U z>7{u84?)+|%s_7u&4K5kUYkX{K@bgNU3O4L@=aT`cCJNAa6v+fG(o!@=$zGu|I9{? z^J%NI5aHZ}(f)jrEr~u!A_1&fH&UaygDpA9M)l0}(!H;(nFsDCT1;ujPL9VO&Qz0B z)RY<7WB{???kkb!KqEH$JS2KE$EC$IFpgf)|6Q8w1n0#>%yr}c^iN* zx9=$=vuagijB#ykZ+|T;L?7eQ0Q(9riKhDkXdoHGJQ=(oINP*F4{sP`#lh@4Z%?C8RcIr!b{vJ#uteYR|BsHrp zH8A+PTMic4R7hebc{hTVpXN>__t-89wD_GipUb=R2s$`=N@dFs17{hGDdsBA$6(ke z%oEaT3z>j^2|zFJet0!}bJ1*i)&vdo$6uRaYJ=G%iyz;4LVMMIr-#SO94BxjbvCrd zZEhpi$KA&!PCH&sdP)}~MW^UJ`N2xT#r@O_-}`1pcmt?np&8Aiy|AYP@FuqDh^Cw5 zn>ZC~J-?cuhD2}lDGDF$sk8yY80VS4`IDNI|q9!4W@%a?Y4!}Gp2E#+PG zjzvbjl65)W91=x*80<40k&t-YtSQ~@zop$_kk(Wf$dB$N8-T?djAZl@XBK)zfU@k0 zD{Yz(*lajlYJUPkM(tv!(h-}=BrGA6>d8G%j?X@gn4O;P2|&Y(pb@eo(!r#znB75< zWxN=Ae4MrBuD|51Zg!3?3X6EhSIm&J*O>EIL|gna%$QE&{f3fbVuJm%b8crOJk0ON zuep-g=FrN-Eq@+H0_iT97RKP!C|j3(d`yKtKXIDvVyv$T%N zMZmdO`Z{#g*KaX4hvD_2?m{b6c1bvdAQZBC=ZdmXs=mJdK_xc566Lb)(#S79z%Ho) z*0@mmn-PGV_p;l}aA|64O3BEytsb7NyI*eQ-KmA|H(YG+f{8~r%hpSmYmZ1D7Zq;s z-gvO)SL;}V1_qLk6QfRPu_>_iFL2H7st*}X-dK#jF8r+pP;osDg!n@O28%PA>o7gSo2i|yB+Te3 z4B=h;Li%Znhga#PP@MzsD?~E=H-2}z#YLq~Jhe<>E>%*qr1x7{oWpKO9+=(=Vw>Dt zlW|K!`7mV!Lc_e6)m!+zw3}HHY)#Amx{h11B{T8EF^+zjX5^LD-#I>?h5^Z`Nojs6 z*ofP9&f?!lzEvhkxiC;>>+zsq39BSPYJdU!NJ?7T;NocA04|t7W}(LVbZ_Az#^$EG4($yr5!*Z>wPp8n+I|h=GrIr{*@T#kVNlrd z`Q;?W6wC`TWw?$?7%&(-Ny)ZbV6o^;bl7p1Jpm1QW0MOcwSvi{%9Q4|d_mOgxiIfW zv?_>bD1&cgwTI72J!!prK1X(5NSK?$=~j<#H7xnf1`0io#m4o7gw`NfP19^zpl8Q5 z3QQB6es`}fh8h=%uRM(o6ivwTG>X(QlO9pd^42^(^pV^+uSCNu&0r7D??Jg*HbT(n z>dlHa4N!_=-YndQ&wd~%?Kd8r%O2jmF<`wZAy2Y4@T-EIVsVtH7IHi5!q*>Oq#?F! zd_jC%lNJf;Pl9UEkQecGfH#QNv_hpt>5qnrY)No|GHw${5>T#yT=BNzLaMfzb=8L3 zVX+CPriEgrSX!OC$dm8)gm&vZ@?Mogi3oJ%d()%5{>4kv^Dl%4ghd^?8z_Ac%vin8 z@4Z%A5;B^(USVm&Jz%hdxJRZYAa%g4bZIaDGb5B-;o&AttoOSuH28uG{1qxOUegaz z<$f*l*2v1YE`7`~W@}0=!tbonl8LFXUJRh-6Z zN+cOfn=txaUqV6RL>jT+*j}Ah&hgjd?f8wP7o<<6rIPN6@D@E~PkpAL{K<-H>D2zj zA$V|{=&9O)*C^YX7p`!9&~2@m9!%l+v1ZXXb-uwZHYVm3fJcz>+GbZ*CwLrhq%V!^ z8k?EDsWs)infalhG`;;Dbm7$??@-&{;GGyA^-amvma^Oj zkitHXOUO-!8B?**M4T8`lcvmt7RnYWdbh%pU3tlWU{cbEc+QaPbFhcg?3hYpq8y@2 zf_~pMdW(snz7Q8OBd>j-c+;Nlk(}l=Be^@TA=5Lcss!zZuoFMQhrF|RTy)KSpI0Hz zC4^k$TiyykeLjqExz>aqzbePtb7X0DQ6y7V?R(eZuA}9CKh@^7cX{qBD=~h2Xr5zd zo%}BU%fm4{ZRyL3`zmuQEtfAvG^BOU_L#r4rFMSJ&)JPQxC-mU+Et8yQ=(iAnhp?R&0P2%l$O`}}E_X^Kzf7G}unyAs^UPq+c5B3NADlS# zD)lZ-4fu)DwHV_ zh*$+nUy+Wk`2-bJ)p6yzk=E>7rH5*3j+4UWmOxc-HroT53psA3K2AKVaLlOp;Awo@akQi6sP~R(3tMoyktWfvfoy8l@|m_) zZvzO``XUZGC+ADTm-+0ozC4iTnR&VS?lq`*9LDRN}z(G9mYu`Ba)jx=crB}pCHT$p1ka~+-iOiq6lQ0>8kCsapz;BozJlPsk z+^sO+t!Ppl zR#OS)_k}*@U=j&Rwz|7Gy}#aRHS}a7jI1DHdB^Q;349Rm)F+x_-$IK9z|X1xR1P>Z z(wx(fa2`+p10%5c(`oh!DUtD);%|O21nQrsgm%7HDA+{d{DOn>96vThNhr{T=DB&L z4-O7~3~%_IA^}(zQb%Vexf5mY^5!X)kmSm#XZr^6Zw`$Uf=cO))Pl)7_kMCmc$vRZ z=XTl8LyZKIaLK$#ik1_Xl|%OkLCGZ-m~-Slpz{bzBTHBkPN3SWdHhdwGOQGWLTdM? z6eMhjY<+zlsXvV$uboZ79gA9o;N!BaL$JkEV+yyT+A$pL8l&H*Kk{7S@nQl|Dl6P^Z(c(mcEna6g=3(7w?^ zji*$Lv3W78d|b9T(YuX8A4>92L;1+AaeOo+I!dVwSxJ{ehwAf8ELMhm}+$!7fUB@r~r;$s(3Oy^QLtp zxR`czPw^Yb#KbN$`ht)VYs4PJqCg!wOL6@iTk(oAO|kf^y$#ESv{!y}k4Se#6Bi(v z*smzcE-LyWWLN4+wfqO#yLGXdiK-7kz9Zz_0J(cj=E`eL=i_&is;sIj7@LOfl<(OX z5S02!y5_|gC04YM7kiCReYzHS1U_k{D`Jt5+ze%SjZ&S}Fw-Sg5E4;x@HN;dw^^wr!IX=>WnpG~s{X2kcCWF)VP8AKDGv`OfAN&5`i_mDDgd=)tfeyM*VCtG5xu=PTrCCk zMz2KE(!J4yjaYo`5L*83WTW?m8J=o(se-*8Hj}QlBBI~Yhx9iv1OWnXW8$+F^!bZp zkrY4hrx`=~o4R?G1?ZC8dpE{>&!HzSF9~|~d1huJu2Q(%SS%8F(i*lSkK&1pwbRM# z8B^F|f6#oc3ZGybI%xKxtm92^G+#Dlq;!jNj-&qcUiFq(h|>h>ek7;O!SEv~l>E({ zGr@%S^9dNuJSi~bu{(OCRkWlY#|xGmoen#U6=-Hw5YLhT=rQs?RRxEZ`7nrO2MD58qghb zzvm(XuM9Gq3AYp}$$`1VWx@Mcz6E>%ztsWQ`hCPg-sxcDwNyCK!`oWq>Igk9W-j*3 zPR@qTzdWq(OHLL-L*_f_l_8j)B^uSc6js<~W&E->?Z{X&FFCFZ`w%UDSrr&3)EIMf zzgDmjQSBC|T*+3My}P?>+!lbwX0h=WVEEL7JYLOh=3Xuc@_7>_sYf0Qvu+XY7}t}L z{^G>8fhGHHfcMxNpd{GL@Um6uI(EPA)MK*?CM=E7N7`qU=}kHCJ>G0Q8GX&d6LEDq zGxunpMc4lalUl_^@3{3@^@zHb{CYL6Om$J)2z$t6M$%B&i)caa@bCA(@NT&aWqfo) zr4(hII(i2B=`E8;@WxsBsfOL-SP}N#_TD68w5!6>h6ceE@FTB3C2-4E=qmg{lal(_ zMa$LXe`*wg@&(YkbsrZuUs?`|-gr+GX}P^}a)u?nPXu3qD3^}Y34a8qVxQIc(WZA) z_?#my%@7-b9d_QK=m!qj=)885&`$KEc|aDu*g}@jqg}g%!lG?|e@rB`^^@97IIl<_ z&1qVRL50f5$<4yXXFJPo8B@2-MgA#b#kP*-&q?p6SD~|;$0K9N`lEZtn}?@K!->@9 z0QGQkp1EsB>OP-9Lnhh~S;(1pQ1o@aU*la{c%a(BYX?)kgy_rLIVw@?ma+j*f+?&m zAoa=v)+us9*Mn8c8$OvV50A~9hYM(k=5YU#@>O}(G{MyViuas&rFVm8XZgr}^k2_b z329Hx%0dZU-EUTHH{`%k_&1PwyR-#-`Sztgf+f;vW&}y?&5&~3HG8E=Ux{yjSU#bn z+C01W+sl!kI^U|+Mce%sWtW;_@aIlv5p@z&758|q!$LztYwws_Tkl5M1dT~TKi|Tf z0XMGizsyAZX0_s1V`N#r0L{II!zv8gQ6`FYZpl-xHm8oxuJ^PdVW4lTm%EvcK7*ZU zJ~Mg_BFg;{{?f*apwycak6u`Jaz(<-4IKSw0&=)&*EKrxMq*3Be;j+$>HJcj%Ni87 z7gA@ebEN1Exx`34Vp+A@P$6q zwAGS%ja!K*_8S-ySYDwjZg8d|Kz~FCC;;(D-NOkCjqVtJtWYmiZ^0!+ej%53vq^o7 zBl-QN$H!*%u8q;%Koax5Aa7ZUu_dEjw!0d44=L~4=87ag`Z@RTd%K$^QE+?qKwdMPV`)JoG<05N zFw^*rycl-z*A7gyYOak1?XLRpzKGoc4-T5=IctZOB*n%0>o%d?Q_VlXKC#_w-+qyU z4CkH$=JPqW;4F$E@+Q%Kmb|k(vAOTDEBdRlizd|9Y7t63i_MW&3z>l2JlnYJGMQNw zo5R*?7>Z|FVtmZRBt`*SHdCmj5R7Wo~twmAFj#{#zhwPiXL4Ad0i$<%4N7eAspQr|$Gt zeG2Iw_;L&W{>#pwK#&GoUAVF&yookuUL&t???Sx80BGqy`W9JYh?hty6Y+kq>zv~(CUmvM+cCCZnoI` z-_h89CujjT)4_yyx40?j@a+2xdT@O6~&qoJ*mhgZU2^!^P%s9>$Fc_Nuf;S z7utI^am{&Pv9qf>%4E{pZEvZM@s2#EQy4?8DD9$m+O&$U>B1q#`ePLUM4j>5+m?U` zqHNk)=;rDe;Nb&=_8se{D$Iu1Bcl`2#Yk*apw6Sk{c*Vgkv%aq>3%*zpizjIvw3pd2)4Zep^ZS)e84vwas$FPex#dfOLf88` zZd;7Byqv+9UQbqYsXkFMx3K4j04&y;(Bop~fVIxlXNx}pfG3~V=F3sM%)^p%oJnSx z4!A4-JJ8RYFuH<*l!M&0C}Fp@w?nB?eE&lU^S?^a!%E0JJUp(B62aL`P3fXH7el*? z;7mo4i+~V3`nv~HMv)Hiy&6u7QJRPgXdQ!7-HP}5ndW@ z?OfLrV{ebL9KPxH=5Wic7CLUTCcl>+`Tc_Ve8a*U3Rf&^HfK2I)y8NRbN6bwTH(a1 zu5l7L7@3%@g~?+RmP|``+HiV0d8g(q3a7Rw-lRPj1;tr4`*L#rG=>dLzBxS%oI8cC z&v``OR2^O0;epNXL=q4lX%EISr`SKRs{w^Y&d!FEWwg6BCv;oLEy*(I0Ytd~DPMmg z;WeI_n$XbkQ1jpsHz9?`JY{1`AJj9s%=#%%*9;5#w0r7Zl0pIP)r0N!-BTd%OpOKv z)0h{4i3osp`-_Wd~T zfA7E759A+r_>qABcWWJY8$<`Vm|dN6#+GvHZm9|}6cd7J$`4*3eJnv2*9w(x$#V^)BE+IZ^J7atT7ZDPBy zC@Kkt++FQw;enlbJr7<0j`uanoZdc+bZ~l@>u|A(@CM#cQp6R@9F&YW(2MAYM{bYX-x-zd{qnMbOAo=9=6F%2`T)hX>juBSh ze{}L^Yoz2)Pfxk^|9g6a5l}eN^7BvMSZ#arG@+82XK~LVHPfXmz}nVSlwvPMlUn+> zdX}tmr(KN6c3rKnwREE-CUWv=Ft2dyTQ!A^LrNfNMsMptLJPYw?(7uK)J2O^wOIoh?0-FU(02b3cIDk>Jc$ z;K%aDBYoy)hVb;owkLCLD)gLvch4`ems)r3(~$(g{azS-y+hV^tuf3O)H?DbUQD`) zCov4J_V(gy?1~&}mlwB6GqMGYl@_09#k#)x?H^LO(Gt+L6_S#YQWB4iX19^o*)H*$ z0E*OG7VVj)ve^1;r?zonmSbXS!2LQtIv7uKQVY%d5Z6)GA({`}i*J1b;_o5J`?hChgfnlH#?QEB|9vBQ_jlW;5R7n8^6(S#Ul zN!0W8=ypi#>jdUiH$zoEv@}(_HjT0FWnot3RfV>)4hLi9(>N6+dVfI4-*ty6Nq26a zZIDH?+mb$>JhJNx#|o&wYH4nP5lE&u0+yW}))7J07Ef@)aj0_oD$bJPSB}0C&6Ggs? z`>H+{3$`Y)#_~WQ-{wzoo=1UDrR7O;1sddsF$aY?P2)X+=Yv$OT8bCdzBVGya=uQ4 zvO`{~;_4emH?g51-gHg~2S-){QuxaXZ`GorT#wSg@rBh7RKhf^ZQ718GvB;x-;cUs zkWHTHrZPI--MY2Xg~{-wh6Cv7vSVE>Y{9Fiw|7Mkv96aS?8S4uF(CMXdb($D@U#7Z zDWWPrJ$u)>oDN0Qc1c~UV^pV3<;odLt;q|We^Cg%q)+-HHit{jxzt2@=5rIhj+Xdx zHSDm(IVuKtv#ZKu+tiou4;VW`qj5TBSU^@cym`&gf%l*iAy{@u@^)2dZ&+g~!&n zkDd3t+e)HP{K=iDr_-OH!<`0NWSweW6;X|MZd0@A&j3ddf_w!RMf?0A$marEJRdSx z8hw1yAkV=LN8`af2Ym&>>ZiK~{hYb>BWbe?4Lf;PKfRBoaw`&!3e~_JJ`&i<*RP(w z3tsLArS)M(7Mb}hcp$WwyOI+6ba=soNj?Dt{o15qR;dtdVBPLA2xA^Y)fb7_a$X zgRp)3M&xjwK|Py2TH>`M98j@B<;=SJjb(AyWS}uPZ~&k2^Nw$C%kb30U`f<5)je|o$s+y1b9{#(1!zq73}Q$(V^|0mw| zVW79&W{Y!9B(8l3Py`D9y9`scunHQyv>1%{3qX4liRzjfSy>Y6D8Ap$_74>84|fyb zSo^h70EX26xMjZ$wHg5bf9GZ+9q`7A@$CQnNp!0)IXO8&dPFMdo?iF|%<69tnNDCT z`u&jYpOL&(kKZ|P7sBC%-ur`aZJ##3t&|~z2CiqBLLQD&xBj&*&4_Cj!p@zEviwSw ze;NF;L~h-EVJ}j7tUntJWhj%20p7y^0KepD+jXm(YIb2l)znl^&jb~$0(m?cFOU^d z_vd1gUiy~YnmdWnflCN`@?m`7J>V$4;$nsVxQ~m2!++=3?$*N8JD4sm^rFC9yV0`! zl#K&^g6oOBwQp^s94Y^~_pa+z1S+)7Y`FTgstR(lKp`7}=z_z){^=ivWVYirLX@(v z6INDNsjC6yTxOh+yAM$i&e@dytqhZBkN>PeTLrPL=3gy1JlZy7R~IPR*ZVbvI_>bP z`H${<1_|l8tq`bR)c*Fla%cjW8-FKCgDa=D;4dd^R`f%KXk}|Y;JR*YyU`=St}3MR&f7yKqOT>I(`36eavYcFJF7Y_wJVVmA-3tsSu@yUsm zfpm9qtWYOQPufGQmq204CVdwaXpUO8K(sTBAM9ZPD}3CFepw z47RVXVpBAL&Q{mBo9f%u*(ouH#Kpto+Rf9xmE|^ko7%O31Y6$NKrX$*s>vb=@S{0w zNbUoMGc2SRyW}Bbp5Rb0F3j$9hd)?a~-23(jOH&NZ3^~>ADnXdsq(H z2TTuSEYKyx2hluwPRW-1jNg+Z(KSDFNJt3MEwYyCcK6;)Fkl;9w&p6hojpR?1mTJq zLj2Yl!0chfAbDfw%XbXOo+~r|noa({FY4Df0C?6+ZvB_)U9a?}npJWP5XN~lEtEpq z)&U-aJ;5<4m-y(IQ0(Nl`Wg_)0jrhl0flVznbxPs$jGS;cbJb-#PX>D(d#KA|8U-k zO(W*@k0Bvw7Z;TeuEYL7o^B=8BbmQUoVVXe5X535@j7YsdcuGC1ZPXndt~rXZ(sli zE<((ISK-wAUPng)}3iyQU@0CQI9%+2K_nBq;^j5QCitA3SH6M&J|%J12RL-+Uh8|44} z;y1!a3E0a4)AJSYNDw9|l8Q5y7+@9w(y&m=8&UZ5(6^$Z@F`coli>qR?_2*`S65de zRW)tRtW_P>-!BJL-|Yk?07nEY2^jocQa4V8zotHR-P>jKb^6AJX-edZ!u}znuyA^R ze}6L-RNSdf+t}2!-1qwOqlAs8rvNE1!GHfA1{|93Tq|ha7F%OPyT(>WZzMln0RSsH zai@-GZjJC~^#3rz_u?RC?*v&2s%{_?o#oFS78ey^9+WT_Yt`%rzyLU42q5cm%b=K~ zJO>k6c5hWxC)AQ|O?vM^fzH$ACO$THwaX}g0=d^HQn-scQV4fcQCoWs?ILXJ=Fe4( zUNjiM;=8_?^d%TnOn+6fuGeM(0zZTeI&XhEJ3c;M23$k4^2QxPJ#Tg-VEgHw4G$?0 zy4CeWy$RsE6uODN0xL_HCU7;2TRV7rWe^JFCHUeEB5Lopi<+620d~^9rHrY#_HJUI zgpSVqVIVMfdy|f%|I zZGYX3fokI>AJI+wQnRkaW(x4yrq#w}IF0njPD5HbIdSp$4!>B-*VNjEE|>hDh+nXy zf3ry0f@s>X&Y5vXJh?QP8AxONWau>qFbQ(7fyx?s9GrL91ZgU#T=MNPw6aU5p3BD< z7_3zV1)peT6I6UY;D(6b?mYDjRgEkxC;&y6cJ$h34h5?-C-7z@;r!sjl$V#k1O={o zH0g42b8k`7JBAoZpj0?{taP9uwQP;$J$L#PdGk|JRI^gg8NhF5TY=P3I_`MkuW>>^f{QM!wH| z%ZVIgPolOmHtw)beVd^vObOU#utmFb$T3Hk8y2Mq#?tjyj+)xA*I5!x3{Lq4pITdAS}!&W+cmts!=n0)FoVfK)a1#dVRVI& z0G-;^2*HCkbk?7VmFS_C(Ir(?<0nqSo+saYzmJFQeU%8ss0r;9hc>}7nr*DDF;-Vs z-@$x($@*K#It2s->^J&}0q71Nwg>{XXJT(4X#+;&OTjujQiq25YKZzC;rzzlr2u>I zHPP#vshaBQlxE$c3~Y(FCmK9u!`TNJFB}*=7%RfR{!DrP>Fbk65A?T2bC4ETXB;`D zVgfot2~!CiR~p5sa2gSpJAhmZTnwEpHSk}*j#7O%B)0Ftyc>&#R02i_Anm|eC0gqo zR=d9XrWm5&ce6a=pqin(-c|#T)(j+bqQ=I?zPtFd;kHeussXQ_HXijdsh1f_bUGr9 zJBW}7qe7Rn3(kHhD{kG7a*s1nRE%6Mo7DB%W6nvbpPL@mXM51%&OXo8)+m<5(g{z zIcujPZ7QB>;^-ZHd;2$_h6Ag3FS!3Aw8p2X&S_JDffVN*A@B`6fSWmC52ryzu-5#e zrC+VJE+12pmhpHSH7gtr$7IbzheT3BSbY!C$08GH&<@?n;4mn}4g}XC6ZO>wPmWqg zE7m1FAI43z3_Dw2KrF2#1Zke9;6`&tLO65a^Z6nUL9v!?p{&j3wK|X4ly%sP3oLba zK5t#ovxF-Knlt>Ep4O;ToZGa>1%oN0rS8She5t7+Y;fIsB}6evc-22a%hYhpd=}cq znW+BF7*;E<>q|{lz?!z4onn8qCXLi3O#WeaU`zR_w9-QF?pD&^?kp?lLKdlITuo1> zk`*^Zeeey1u;=4XUmxRJ8J3Lz(aHNkV42(h>6LWM$&F)3vbsisjTx`R4lNZ`0X7ih z+_h@|QLX{kr_sqWItABrn$NJ*z4D%~vtA|Xf!l1ev7g91`2(j_1u zt)Rp*C?%u>ge48q-QCjtjvMzr@3WtC&hwt<`u_X8*5!o)Yu)!f=Nxm4UyOPCo0=Xp zC9$I8%(|->fEnLi`@*kS4O)+c?%`Yw4bfm}Wi*7V`PjBAPqk5;3YzzB;jf{>OHXJ-MR!~qt zq2d#o=5?m*1^g^Rbc<}lZis(?U@@KO6jm;;EqeVbQQ)`fwb3BfPZAdiB!sAwA05@n zGkM^=D6(s>n>;}Fs$eqCTHY4XD9xPuybt1+Z;{i|`mr_a3apaLE4Fiqihdvq%}`G1 z(v0TR{YtDXx_XLH?x%T}a*CME_SxHVk*}G8W+hQ_kt<)aJpIE% z<#Xn`@PnbS)uZ>sO!1}+kk=Vwh2)J4@dL}B&2>>%*|+*bBkD}9@WwTU)Eb0+D2%MD zt2p)R(493daf7>Q7Rc zgM))R#HRJSX96-m^C|kYOjk!-l3l<5B*5(1>8tAe4sL4zaOdmP zYd5psFOZ02#GK0v$Xr)bZ*qSerxozyu;};41e(8)Wgv7d(}Nd8zG{E`{GJadR$WU? z@)KbxT~$ha)tPabP(`dwJ@v)5af-!PEqm3@3-61@SB0)zy-ElH!~DZt(?D6ZX6MZ` zSbwATg$jaK_H=FPfV5oAbj6FQ4QLR6J@+`u}#JUxDt++qr zSI69rg{>{e9HD@im~Gqz)X!PIKHS|15gKDhMeWk6yZF#;N0em~=3yA?&3+5o;wg zHDvnV!CMy0!(X*y5cYGze)907!A3X{s%X%*-}u8O4EvS6RF3&T^{E`XG}y%K6ME-6 z8+L@8rb28k^@;C~;tOpJIAvUydFLcb7HoKN`j>Mo<0y6%>5Wi(u~RB5T~%AmPF%7d zr(H*$o*8j0UYUqePR-74`IWpQBShE8y+&Q?9|dWB(5Vwx`wQmc<0lkZ{vb_+>_hGO zmfBtB+!00~{ZjLcD&-Ko$+YGf^3wtJL8l=zA|#BCzRea208e*pT|(TeS2?1!wzws$ zan(EIss1tT#`6ar9e45Cwp7KNjS`X1t3-C#MwLBbp=x+PHCYhq`uUzCV~Cbl7r}{W zz8vpW@cDC(0LsSJwm`JDj@(?|S;m;lf3+R!L)gcyH5FxHoRpb%BW|TjiTKE>gZPkc z3F*ombrMt#@X7~^y^V%%BPuu=BL-V2l;FxKGtexhdUkqG<8Co-FF2to*@OV|w|bRs z38Bbuk0IhLv2@&^gcP=xJs>ZgTyl|+87XXGjB>RVZkmK3x2Y0(&cE8PMHK(k2?&+> zbOD*DbI4nZ5WvcWZ2kKM<%^V|8XN>Fc*jrfA*=_;r(nLHJcDO&u)7f*CiNDm8cWo- znVHPR$~Xn=G1p6vj04OjW!OCv!z!t@FI~Fi2h)zPY9}*;+Bb9Sfa%=2K7rK>{D>WL5%RG4SepDd8 z`~C0dwP)X)OOY`Izr=O?>hQwTQ@#2>4l2pdl5aLRW} zYM^ee6?!=LautFI;dC`nBn&wfP}A!@&tY1pP=Kz}*}plOdU)?YP?xKxjmAtIohog7!P{d2u9 z0~+gi9Z|RPorl8GLB%1<@}3@+yj0Ec8wq~~;<9=XQeSGk7F+UE$}ytb;}{HP!}OQg zl`B`+!gHyrZ9S&!#r$U8Os@Al7Dq-a2Y~QGIvgY9L@LX5Xajd&6y$A9N zsJpxFAa`QS@;iD=wC?Y$&Q1PVfNp;Do2#s#>6Oxb|y}Zue?16<9YYH zQIv%hvJ_5%js?mF+`{~C7a8KkU|OhDpTqWn2m>#~kh8W4<=?i4n84;0hIlN95*@7& zdEmo%;+`|gZ4YggXDnZkPEWT)o~qdsh&osj)ud{$+qGE`qh6y~RI^@|E3@Gd+TC4z z(6Q{4D*wNZC(NdJZGDr16+4PUhw>@mj#EO;GX&+oqO)J8rJWq!X?8)O1P7h(>NP`o za?(qbcF^dz#B8qNNf@kdP<7K3V*T3c?k7~N!J zuH&Tq2c2Rf6r$83N5Q~F3D&NTV+hZl%CR4<%A0)EOx`#u>i>`6zOvq~JPr^Ef8rP0 zkr#r9QXw;l^P0$Yh zSF6aLK88d0UZ9rR38S`H!hEBb0rKH6Lj0l*ocg0UQ!u>vZ|+!Zo{WBxZn=wV%OAqq z?|AL}M5JjP#1k{Zb4sZq-^(NJUXmj+(T42`;nmdCeY@vt0L!xaN~6jW4XN^XKpf0O zV;JR%=0BC>fTog&F+umKgv4^yML8nLHw3|osoJ&AqB6rW(Kt}D8*l}{%qL-wxoB)e z%0_T@&p^^D+Te5IQ2jnKBOz-CS5oPbT=b2S$J z$@?duMNt6w_Xq5Uf4;j7!!@$DLlBO6V6~|k$p~V`+tFb+I&ySw-n@y*Yq~aQTR2%+ zU0ofsw^;k?)hiT=PcT9G1CM_`w^EXbDWvt4;xA#r&oTR3{9r9zTPh(C&oDE_#l=OE z`wJ=Cr=Z=cpP%1Kma-=f3aK<3d@po*iCJC7!00$M3r~+U=pQ=Pv|zq{Lp@p^3bpeX zr%E5bW+v>lo;pk?+9j35+gI#oc#HXj+)4kJM7s;X1L>!C0H~P0%%zZSI zU#PYJY4H+5D7RT_Z$(+zAeZu`#PG-UD%%tO_(|@cW`&GG_#bqker!gviEbvj3}wx( zsjv!%(OgS!xuUu2A-X%0_JZ*baNz8{bfOk^JcTqPV|N;GZdY_2^(C`EI@n6f&u{1R zZ*Qq#!l+>~H>8>^U1{614 z2N{r>KgP10bV}LN>GW)tQX7Og+bJZif_iOX_+w;bWWnF^POjF6pM=i5%qQ?+jPBc& zb#4l+Vw$Yib3fFamX}fs3HA%H(qf7Jd31wAhuU#vL9o5=H&pDOJ1$~)_wUh&IG;tM=P<|6NU`H( zSWggsH9lxPRbx?KcYrrKgOX+aK_Xp=R)3GcVkh_^2Y{04exVZQ+t7ejr{yg+l2zg0 zO$9W1to6;!%ic5$@z)ba8PSFShv7Y05O3AX?p}EXAa-PVdXdSs=%FyBTE6*%87Wa( zPD|R1t`FKiFo7<@{s|!2YOubPon7{5)8<%d;8-4bs3FYjWs`}e;MbX`iVIMNj=hW3 ztK#q0NfTeY=7N1c#*``OnH0lQKwj+c^?HiYDJ2R$wewm_*xsKO$5(7`?d{FlS`3k5 zfLs`gu9n1!>HJ&xLMvha>kMk zanJ`{Poq#$Y_~Rtma&JAGtogA$&clad>Elc@?ZtC-Wt?5eAG85cj%uLAMI?QztTa~wq|1dZ(7+3qSV_r>>G@!77|ERPg4`{=2w=Y8-{$Ek_mZ|~~W zt8E<}CcCS{(Bup07FSBmkg!c1>geq3JhD`>TwCdL#sQGNeE?tU6Hc>>3W63oeGl&U z$-;ussF-4Vj>nE;J9U;C4gx7botA6S#<0KTeIy9=px3Xcl##=|WlqZFY4M}t(Qd_w z1`{4~3JT`lmWJzF13s>zwpy+%LC@TmiZLtWtOrgFNb%EUT;%9I+PiVz5kV3gKQCW^ z#PuJQ-QIEjU(-w-%C@l66pHI`cP{j$ z?x$4GNJc|z>qb6Ix#u3rq~8)6Z_UQx(}=t*oZIg;PwB+)iexaP^e=LV(8(lvd9&#h z5x_LEARQcEl~5sWcVPL)?ZDQWN_jb`;`BLEVjE3$b#Jw_!6>tI$ELTNudF8kZfYMUWi79H#^DhDv53ye!h$K=Ft7KWeTg?g z2y%7yC7?M%*%hNfeWP#w1vp z`x5rIoX&6(b@kN|AN+e_W{Lw=2F}Iq=xjkM$a}pi(zQ-qID3jM#U^?0VH}5CB=yEv zBfI^u>-c%3cdFaocZG$%FAp-3Os_ze_^k5cajuwGYAq|(3AutwXrw6xxU}pl1DS{c z>i(o#5+qhTy>=s#5q4tFE}PY{8ZC%R@QaWW0<0LWuFju5g6m%`eNK>A8uoxLbM>QN zoJT|`wv=Jp_2Sa)vEa+ar_}z4)qBjmxjbz5Ro^2N+S8PlE*49Ryf`qfL|^2m5{zYH z0E~1sP}w8Z;t2SjPlfmE*?)o~V7*ZKDRrpKd3Vn#mdVu5I+2XC!@*K&dqwg|nSP#| z`6;JYyhaIevFRJ~M#VeE2w$ZVh(2Ctf*dY}Qy))V{SA}6UT*u)P;z1Fy;2!l!&FO3 zxOUL6zbE7D)^Q3QPaofqOuWFI|4RPduOMLuF|g(Omdb{SZT1-NI;6Uwi%xNpJ`cRl zxVyK9WfI&mAbFQKyy|kS&Iwd{c;>*D2V{W89eqQ+K8j%2)kmYP`mN;mpWcv~klIir zA&4+OTERbhQgJw6(M9%6$DxMA6}p86hh5-JDb9~d^*0eo>f)@PCMAbu+mi5(xJJ!3 zf-q3(A^@;#Giqi6@8g(i6N%OH*e+4y-Bcllyc{6MiR()|1ZOWs%g-LjT$Za!uqzL= z=`S#>e0Ex^(3a*IfTj;5?%us1N*jLI2TWr%ptqqHt|}oBJ(3YRxx?!I&pbii`X?fN7us#lP53<_vGSvUd=cT>S|>_c^&+Nh&lDnIgBZ zMBP#EZ1eOsi?vxp);D*~zPWR&;-#*u z`;(q*OUf|X>yQ*?a8d?g#@(hJ936i;uSRZ*#0?r{!OrQ=W(0*(d{r~Oj#^xWRze#;TH#Ae&qOn3sJtpCBYEGxdNlIYYdTrg~0 z{Jks*wm0^^Lg>)9eQ;PRZc8~j9fN?UA21`=6Q$078()2$k#Tj|t;5sPvuHBrK9~2Q z#|N$46BYZDoG>M8?%Nih1}@FblcGilenjhw6$xqvQ@YW0AC-4{0g_+y*?gApowezC zc5kU0x(^Dhdr!c#$w=|)+wAeD^CE|$)IszSOLP@nZ zFR-bP3(PDp{yzB%+EDg)rZhD*#bAUe#utK{EpVr}mZU8nT0>74NJ4uyGir)cE<3+zIW#sJ^y1GT{D1N}Y9$T~*kf0hP=ucmkqNjx&F1L7EVPJx;H zSm>d_EA}fQ9Lbq^K7E~I0h$LU86{~FVDS{x)W8`4!10?oYFzh#9PfFxp~u|a6rO`i zzypAKP>~rkROU|Kz=Ke{7wp z*^E(jS-w|Nzt$k7wlG5fp~6TF)k~TZ1aG$Um1Uc~k+}F|Xh=`iIFM8;m9WI%k+7b# z%teM1NIm{?8Y6zl{bX1BscyZ1x(sg&WTr5NyNz5xTqB^(r0Yhfrun{W-D8tS!A~*c zl^2vnRh+FwX{T|o63!wRMiPIt+46dMax!h11ir5%*mYO)H@;IrS5jirJnPzslBTpM5N4Rf*> z9~YOwE@P^U^TZEA7)uDSkoXT(vYW&)dQg(b`{&=Nm5j=SLDVO zYCI~^STx!(=0fjUj#Vd1S+)fid57H>0;61VB+N+zrhVT|orzgx(GV(iXAM5e8t;Q{ z@91@h7oFd&x(eFN7hqEXmOjV4g%(ilL@`fF)N3aBAqVIk(>*NavAtp~!-zgcS||a0 ziK%fOog9}z>LEaEJKt-bM8SrN|9YDql^|%>b#7~5EGpnbF_fVwlLVKqgSHJm{{H?5 zy#s+03uR#|knI##-AkUKl*BV2fO$=)aa=jlQ~ttPF5Tn!-ZE=FMZn@I_A2eOFh|+C zDje}KuegNu8aTwVvNF`2^)ij+>6=227Rbw2L+uP)UCFb{cUiE{oWU~bHI={K=M*K}iF}l%c;?0-6waG=c6Ne| zfNmjCTx@6b=5+D{kz>%D$tEl;3=cBGlTd6#GLFKggdx$?;hq-`QTsLjt8Cd5U!q_H zj`28hLG@CM+6(FM)zTep%ifAKaUGgF27g|P9HWT*&kCu_633Zs zl>$3dsEZp=U$Yx00}y{K&a&bMY$~4{&RgrR??$#h+^p!`oO_==XScP!PQ0l6P8G2G zRaXxIW5P~RWag=nEaCd*{Fv_?UXEle+b&Hlp`zP)Um@udcW%;zC#%9n?d9@dNo;Sl2$7MA4H53U5jO(XlN5D`-nSLH=3dm6%9*K6-#5GZx_|m43NG6qkWG0f zZ{IXlH@#wTcsTr>ui5e}0_CDKE~o61 zMVx$>STuu4DDsxVJZ(__#fapQK6dxboIy4jpAx+s$f#HPCZ2scIzj0GH z*U8wd_jscJi)7*$*#;JhXZe6T7y-8VtinL#HpZ&Ig9G^5(59-jr1%;e5|R%Tei>wTDOjEmDN#Tj1PzfU{FsE*~Sg&&)NggSSkz zyEp?oi5#*#uH?Ux*~E-reh>_CtrD3WL3Me!+A+ZSKFAy0ev&>qi=o4`cAH-=*VuaLr+=Val5G@Ep;{(IJ(;$8blWU? zQ$(et-XZTDU}nMes^|vQaEGIFhs@ezYU-=8AY0ww@fAN)BU)CHzPoe2+L}*Gq%Bm+ahaKUp2Q8G@c7tnbHY zeVLk(OYfhFkUm7N_U=I81&oD_4gY}I=3~fy=9py->6(QF#yfuQKm|Sd(p>nm+_T|j zj3zYVik!@hS>sNkJ{j)^u}2vW8)6nTXem?ks_vy2d-LW^yx1`#twJU2Dwh;s7G1Pp zElV6fntx8c{tM;3cD_vXz3A8(Uq>C5s|@jq#{*KAx8NF+pD6u0-4b?W(A(&*+*O2y zvfrQIqVzz0he%t-MH&CF`}&rBB|f40X&8IH`NT#?t9a~`mRP|CZJd)QPa=MzwR_}& zWBHNN(-2uq)oY%lH(99foEJ_xNw!a*^2GpBoBZZkwhUKQeAEGLb6j7s(^aS}H9ub` z3T%8_DI9fs5?0_R{R&!5y@w>6(HB%Yjp27l3`px&hLZab! zI^)%(PTAv)5dG>PCY}_xUvm3^G|SVmazqbP;9V=9O$o@PToEK8RDa&amT}BE}!C7$yN$m{|ZF*S%eaq^|9upO4NVOwu^w|}_D z#3kPHb=~c+#jInu9fs4iR(PY-CsVZYPC3G)zd#u6^T5L5tVDrZM*m`gsH>}Mk7LCk zIUFp2dICpVScU^1{%0~}AZ_(8lBs$(F^=+WqXUY06l|ZLwtNw*X$U-1{A(^t9pR8t z^n88DDz^Rx|4m7Wd!O+4c|2TPgN?aP0JKlPSdN^o!YAdBp$dq;Y38k`pU_YMRLV=jM#p(pV->Xb zraiy#_#Kdetu7$-n^ReYE8r?kf68 z{DG&4aI)9#Y-+d*kDm}-1s(NwCv(lO%G0VlN2N<5`@<=RpJ(6wlK;(E_z26#Ary6H zs^jwH%kx3mPyqpc-BJ5vdW}9#L22({XprJHnC#|I`*G5VJWmV!{!*-9#j6oSRt@?c zQc@ewAq=V~7G?a*JPV3WfD!6UhyoKCl-v29SC2++&hRm4M7O-f+DkHRz9pr$2r0Ts zO#$<83cjZXC4^>FUy`wlT}rJO)re@H<&1jxkG|odS9!R|^-UAJ-l&z~PF_ z;sD@?e~O$oo~)0S&QFA)$YYx?yY|#N*8@a@fF~tVQpR_^`^6zAnZY<3rKuO_PUre< zy-42M`%fK*5uV-!1}g%P-L~@`Q!6K$UXx$==m&TqA0_`nuyFsrmpG^`A>Bl%vjZ{{ zL;Bq>w@w{#H=PzQZef{zM#qr)69!KW13v}g@@K}FFyXI!NqY`3et@h3fWlweA$H$H zTLxscM+|53wv3yZg_P9Q6PFE2@m(H{)+X3B-&a?Hj0w`|%&>rl2{c-SgX=miK4iDY z+hgQVziQ(nnKTsygu&bvspC$%xzY(iu~8zRX2=Hf{d=6q|7XS~Fw*N>{{N!Tm554_4&6kwef*ih~6?gA;b9?s7Y z{~5Gq&n4eb@SBpouRo*8d=NKTjAQqZ?hF^U0bU3MNkWy$9C%-PrKM`Nj?PYBpi>C) z*s7PeuEo0%hexgN9h^ON0us($(@iZlKMTHi!Dd*<2=_ca8P|OGiQdvO2ETkyms&-A ze`?#I!8o)_!?v%KV&1MSI<_8CP+Y*CSzP8im;p>-*1d8DG$DW?6#-hC;rWMlBqOzu zJqmybpdqgTH-$!nJYd)Akz)J0`cm=t+&ngbHulHJD!u`d>!ZfN9d|U+K{;wI8 zef_(Qn}%{#%ja;GI6vq%7(s@LQ~W)28>Gu_f|FGLPJI=oa3yNXYgyN&(suAOWE{iG zvJ4Rt0QF$T+vrGkfE;bv_CR>bnc3MJ0Kx%SrQz&7ElsBT{0JaDw%wkAE@{bgPXtVk z`bfxrC6Ollx$gwKKjy+7fl97*Z&PE^AdT|nTzBC^s1yl7MV{D&AuHe^s>Ry( zMjcXpJHoQ36t0=l_Q#{Cch_guD%Lx%I0v0-$YF+nvZ`rCPu6g>$~O!{l>gdjAP$0N zf1w=)0hQC!uYg*zOm ziA8`s1$_aq9(2xZGif|wxCin3?{E-_QM)n7LIFtC>j@btOVsQLRTPyGFjlz z=&bEz0iWEV#g}PGym67>+gMF-uHCR$dv_DN{d^li37HrDl#a+BD-KL81mQP3on-b#%iMUMLwTOGY3g_lgf9?)fNPCP z*?(*4@X?a;Q}GlfD#u#sXf5Ta)Ivrp#&oDcPD*VOwkUN8+o$Rl;NRz^72gtT2J#n_ z^#d-$o~GKjOlp?5`iIh3-l{SK3U$CNTg)g|wYxFD>O;5xdS)Ca{4zu8+&IyeXlPhi zA8lft3EOf+9@R}gRza)Tap%7)u|7`bd_Cm>OoOrg_5pt%KzZbox8A8D!iE>@LgG7h z%6(?+{&23r8&K4M3WKSy5HuZ)DdKc?pv)h-8w6q2rF@MBP;hD}aFHj6STulR1Sw2j zCdp6aU%)V~Y?1$-d=IDX5ngV2qTJ?x%7LwzVcs)atzME!Q}HMC88PU-RqH!|7}d5E{d32@klkVI*LJZhMsH4f+dT7;~E~##t_8TVS_Z z7bgF5BSB_#y85ccqS{D{=m(l*by;?wT|FXPSsCYAs8c4W>q%9`3|tW=P%*)8=vJvvx# zFREO|BqeUV#YXgHrUIR^nqg^QgB3xNis%0uX@kFWVNSK1fjALTKIp#Q;HVRhx$B&L zMTMO;ak8=I_F{(xK;UXJl?L|ptQhft1>9-pMl6FNb(_b1E#h>V9J)clWE>qS#dxSA z+4hxzUhVo^1#G7Q+Xjcj;RL%{AcR+-lNQ-x35Ys!XY3AT=vsbk_YS49H%)n8y;ir{ zT(Ud{c;YqCOZy0?M;ZsRjhhDdTRL)najK1)({2ZS#?`0RYf6Pp_+u+8Ig@wqfV8nG zGlAWUo(q&eUV>atl*#zk4-Z?s{P3w789@4+*+q?1pnxk|y6L<*!W!XAcUhitLw&fG zN~prWXRk>nR`Qs?YskyJbD!22Z;DA8Pg7R*4C-Q%Qoq3RDbz9Q{;$x_drls^?J3Es zl@xgXt9IeyVY!u+sn7Du%4nd%a1`Wd$k2{i^bZxcFbI*ROz^15jB6&(?AJC{T zNj_WlM9~qwo}s?L*-lKnEzfgr?pfNduwZW~}n3gdyGzk)2zI=l0>7qzpdT7|?^l z1m9X)UyO%eLZ60Eoi0Zl7bqpkc^E>gY^iA<6x|DGFDPL06P__$B#{QS5h7&WJMc5c zOF7^yTqy&1=>6EwhSpXB*z~F=x1Y6`7h9bD!O0gmhw$l^5a*CACb)o#-!#}E;pWRS`CsW15bf9hm7d5?Xyu!oXNb7fRu1%{ zvq)0xIA|~U*o4|=`9OLTQMg!3WhVtRvlF5vfv+3)wsUj2-?q=9MUE4pRj)AfWDnKh zuG!TQ1aT$n`joUm-RX!RZaT%@ro9I>lgEhatl}V2HdIB|8X?kt5P(R9fg+xCPQafIng8l5)Yd)A4Y(-OS@9L=R{q|vFI5X$z7wglI3zL zASYV+*zMBQ+WBCkMYcFpYj?LMUvlrW%V@kuWwcoHx3v*UY_5SDs;tqg$vH{F3|4&m zfv>-sbzHn2Eq_D3Q=7Bz#8U~qrz}hEgt22zPJo&;y*2!7L8RQ-FcT9i2?w$BQdY~| zsHV;d|HD+u3n@tsCA?=gxRK{KGszv3|R4GYQ9!Bz*1Ut%vK3n8e0 zU_DZVg5*K{a8zFHqmGf~{`PiJxx!H6pU`YiXbW{ShTs^PeK36~TE238wNVIBFhdOl zax#<&8SWsY*nrrb1}UkPkOqHZcyqH-V}f9dfbtjbl&%M$*1pp2j!hzcgOO--5no-t zoe%a{%$6i;P^!3yz!rXw8p~~S~ zuxaI>veeLw#&Gy4?VsXkd+?hgns;kfDbowVH9~9ZHBh8gjpi)UokXLn<~LxrgP5Ue zdTr8E_rOaW@+3IOZF}R2A+;HZVNh%R!kLaBBRzF&J!K2Oi-5TJAbSIi ztDQP&aLsx+$(Fi%nO>sHkejsey{2b^V=d<(12GrM8nZIJEF5vcH&!o81W0S}x{ZTu z;LG)9*N`KezqA0yY8uaoH<|&>6%W)GDn`BPROPcdgck#r1hn&=*Q(ZH+=WYC3Gz;|G zg^3bhsN4QIz9c)pqM~AE4K?JwfNoDwfd>drOTb(sKg7t|p?pE_l8d#&@&ecfbIqFK zOUJ|L#PKecTv~QoPYl>!N`il!G8d|g;Pjlmy*rt%^KLg-j2dqo z5*-9E^ESNO6ez_2LQhFXqDnvw2m+%7Ywj}@=o zo`9<5b_^SWVy7}e+1!(78a(<+Vw3uDnI5FzZ&kBOx0-4+LN;TfwJN2gV=Yj%CTVD6FxG7joh~z$~Kpav+WKpA5=Bubfqffe4 z+^O^I3)wyb(JR=F+$`eL^?xSKnQnla*QPc<^&BZ1S1F$@BT*nYjwKMu=!uKsYvA8q zfei|r7*t|^u(?oQEcw|#?sknuNEMC>k4NNDGS3>fnt;(Gq6{9)!2(VhShUGMwJp`=>NzFrrfpeG5E}B;@ z(8b;>lDehF0eBa3WqO1Rv}y78p9J0hbhk|RZ4SS3F>_FA3uRDCT8{E3u>0z8G2z^L z?fQtHGSuj|p}e!urZ=x<k!KmN|atr#{s3QEtM0A=`l>!V;Hd z86j$Tbp`K$F6f0r^5jc4@Sd%eBAv)g&12=b~e%kh%2)ND~>c`9^|Z=pAruwq|RR~oD6d< zHAEDufEL=w|B*; zv7Hl{>EzS}Z(Oax2FuMISWck(Jb3fXT`=%N?nt6^Dn=Isf#8fn)GN@5K=%k^l^){N zD;N13K!9iy4~ED3@J5G4H^VV$;@MO`Dm+-1I6uded=N-&WwXZm;=W}Is?mmD#!lxx zgNr2F!fz8Qua=TCe8f1j2e;3iQ&ViWU!PI=k*DK)Nb5Eck=jjqx`Ob1oY5-gYf&`n z$x!L=hc8iWJ&^G?{!O7$QzmS-@DIyHckxEzct_Sk?WenGE3t_!e8n)8%{&<}dIgJ$uWt7x;n z1~_|(Ax?p58nh%a&I7j?pFzjB_yuU%8qEpkH9p`Mtj@Be1m9+Kx89HWjk)uW&Feo{G}***U$9QNA*DtEY=^$Ec)QBF}} zH`l7D8?jKI1}-l@Y8VC=(<1jfi>pTbwa^6Md?Caz-1FyWD^O;UH;J=5;aI;vm3hS# z91;&b5Pqgn1CJHv<||(Fuu1Oa@;#1ba0FO}k515mvXid*gO+oA^}@K5la?nPe;<=G2mW-NMe!{3+tkRy%2xH?lA{m*?>kjHzHv4UhkA?+&m!0~&y1-)XECr8t<{ z`?7E86a{7dlN*47#kc^td3 z5xx{}DszY$3?}ed|K2rzY%oSlu)y^pm#y)ya=(A-76bB;KMmxFO}I?>-#2CX`0=A( zf1_UZf4`gm$oTwUuL}YzpzE0*{wG6QcQI1HLz`L(+XUlQ{P&0+2Oi$<7d*oM2&p=j zY(g;yFSOv_O}hWdbNpvBF*zN0nxNaXg8Sbo6x(&@YHebbUdLpFu zUwJ5aa{uZZ!lh{&7n#WP7J4i zY$1I8e?QOuB6)s4BjoS2$4>T$&-#CLQU9S>_aEc;k`=@1k7wBSYm%gezQgE0a=jjF zppl2C@`>6>Yz6BF=u@{-x^?|q#Se{Z9M6IrroHaBg;N3Ug8rdP+-x9Nolz%fsYhfz*K{IA*^3ZHny}~l@L7}{5d1AzDa7+z%IJA z(4+EH?aNaj*`b5_Nlj-L0B5O|s9O0voG^IJuJJi~$!hPyXoR1M@8yg04vGti1PRk^ zKbiHqx`LuVhdZfOXPU9qGHS*vXIa>VgYqG z&zgH}m4!)n$N_2LAG8y!{r>$F>UDANzI=HUHC>8ei=#L)r}%de zB-p9?e2@Kf67MG;^gG%FdA!(6g(S5+6goBa3Oo$-Wx*j2-trt9!&JtHcfNEO zD>-#cfao9od>LuJb5`)wi5bwAwmy*J*S0@|qo~lC3#@MVAi^<>=uRkHj5ZlD zca#F9m*zRLX4_24W7S{4kEbxuY<)4;(&CgdSYMz8fQ^Q0&Rb1P9dS8%a(A!PS&W}U zB{cjmGU~kxJVWPQb3|b6e1+kTMYX4r^pNNeA&C;H%htD>6c=5@5u{8>h{UBDBn46jFJFk@fY!Z=|BNgM| z!)Rz>k@-`_DrSc_6j^WqTb41$Juv=Nto;910N|3{nEHQL?f;*nB_xBfYQHFo=_ODnz}v#`tlZ<+FzMHQ2hv6SvTe3o!vfl3JAKdo54(pc6 z%v1KtrV|tP2Aq=Dbd<6#NS>vC{^GNwe-r`o)msvg#OKIYj2~M^8IQlR^u@bMk9;M^ z>MZmJ^3|<-b{G>{K9v534J>176ITqvUABO)Sl6j%hB>DHfF-#PQzW2?kEzkI0{|OEKs1f(iep>o$4u3OWh#DN-q~J3zF4hOML2jJVZL(k&ONpTBr%aE}pw zN?N5ANM*oSALYEmy$>}o`u+PiO!Wr0DWbut44FHe7FQV~d6oj(K6RaYUovEsf;3xL!LdcqEskF>nGe(Gs1_MjIUsbnYZgNGlU7w?w`a^4wj2J&*E} z@w{{9;T>5IDs5q5;a|5WrnTTW%d6~B78Q*GDU8_{9wOiV>lH#x6Y?(yYW5OPYX}_< z$A+|1o=3%}zsbxz3rFPnVa7+%YeJy8A|@fp9VV3YyA0zhM_A2eP}uJ<(@IYbzz0C& zla6gSzM|l_!8ncuTvcD+Jt*A3T!mZkf!=q<K|9{!ENQusPhkyf^UsU{XTmnA8z51ywzthw(TK zR;d{R9c&?o!2r^35p!KIAO8MhjNT$qR{86Q3;_$io&G|ygV zTy6wHLaQh(?b7I>i2$@$ID-P|$nv!6nTNRiGzdG3G636GK&c*dfH;d{Vq$vH-=38w zF5s6M1}y`yP)N}^F)^VvrzW&~2A?*heo;Vm{t_)nA4pLTDo#FuJvuwa}c}{?mxPPCjHiY7WlfIkVj^GEg5oQ*appq6oMO1+M z;e{&--+&KG_~{TvEzBT}$ro&GPS<))+~7uqK0Dpd6;ia(aqTc#ix6MH&rm|W^G2uS z**Dd4w-4li9*yrXBJ#xqR%?xZ6~-PU6=rtsTmv| z91MlFxS5NHpFD<5JF=rZGb1lAFY_@`$n!Hv&d??IF}SrIb4&>&o8b)G7eX*=jlVoR|1~NuKCJ%TqFkz}Z)uVX>HBk~zKBe^e7RCkp$3ag)i)ody4DRo3TTYn4gq z>##+H*{4IWfi_D%>^=l1ApCxx++H0=rP3%>b0N}%lL2(H=HxQ+@Ar0}1>96P1B%Lk zlI<)2uuw)}Jy_Q_qAa3~mh*BQZE$4yG>i_;RdV6Zd=(o>YmJVMKAHEGmyqElJyBu* z`6sIhS>WQihsqM(dH!NO>atPxUvcUW<1dlDw;qkB;?0rEi=->Wop^n<#q4bv0DD*{ zqy_N6fKEd>xIf3+mBmlDI?-~LtrJ-bP+d_@#zpF$Uy~ zT!0KC0IerF98s1m9hwCD*_Q8^AuZd2_x5hlq+2p@a<-&ig|-#l4;50xXkebG+)Id$ zM{KRgzfp+JNcd}aN5^yML-G3U+fx$C{aI+1dF{_NU}k+c2%R%PkcB9>5Tf5QzH+fs!EcWl(hZ;vZ0<*H(neZoE$LnS{9a;QX}pEli+6veDJ9l8?nekP`=di4rU0_OaL(r!|)BbO(&rY zie+TSkGSVvhta21i?(Fl&1f`%V|p$Rq%;EDFHk+Ya=Q05-rV+;hfG06Xf(?fbmP77 zMEl-7%8hG<{Wi?^RaEFJ&iLGDpLLE$DO3#G!Oz&7O$bVTRcX-L*wP|crk4%clcu~p z9{7=aVVw1WPJtbn&|Grkak~cH!54bx01<*+#dbb${F6urT2{|*#P96vAgA&`^F;+z zdjFyTeD}bsqDJHYRCeXzRIP7&p*TtiM`Q|xQbI!eNP{V5(=J4knRbII!!dS>jF~eW znP)0$tB8;&LS?8VQ)ZD0k)-u|_hkIE+?)^DG~d7byfzVwqAk?B-PUUUui@V10t8)cm>mdP{qMgT&>@0OyofKFI9t;_(S*W z*Lp@qPnMQ^w{icHq@Um6s-Byhn{d{Jl4?(-Ml2mSHnxA7q)?Y7&bUX9?E7JZLtSGJ zn}|MEbQz_nsA#i_wviFl$SC`Ch|n=3qj*7F)>8gNHTGCS|9tiNqjL4fRa`ojUf1%d z_?&NDcUmTl$K58vR_1ni=j3*#Bq%wQo`~k}gXzSF&pKV)oVm`?C|aAEnr@sd^-N{& zjwvWwYgB?xd?ifX+foyLZ78$V;3BVZ*9Sf=1(Y!y+h|9QNT*hqMBc+%yqcPFrlji6 z!Z}o)TAI&=g7X2f2w(ZITdUuWU#zn_`}!80A%fLb3tFgzQBrts9~Z2ZjqKsJmrFf$ z^5md8-zUdYH+M12>jTWzXV3i*a6i~^u(eh|e=pAs9E83L1Hp>7pMq_lhKaWN$rXF* zH>9a~9g=$o)n&AT=Y{HeOO%up-aC2M)cBPTCqi6;T1*l^4rW(WtksDUjsK96 zPI2F~qz-dQ^%4mSkqux?ThGx}&&wlK(nsz$fxesEJrj=1Wjw;wd!=5hhCHi>A3ridQ zC7aZy>v>IXouFN&4jh}mv-&F4v2sfJ)s%;la<*AzIzb3}>uT;XRJMi>QNh)#aSCNY zRvCqb?C6=lvbkik!dHMdd;krLgL#76I9TwX>R=Jed%NWBT|wMJSxzX=^mXf)*Unz+ zByHE%9WmokBw%WT-T(F%cDeOGhMfs)^<~yqjqXgaRE|Q#AJL0;>$Or;$Q7mI-<{nCB zjE4?0XD~~URikeK5S?0{K{}@vjRaX=nwn4%e%DteL^#*2Qh5Vvr`?6dw>&wI^mkxx z-S*Jz;K6mNo2VT?)xqxQTU++@&utBi>t(ZfGAo*zn&3{FGdt!+xq0q~ziA=_vZ7Hs zFG~fylsGi>9c06pp?*OvzfPXx)oJA&sa1&E;}wqV?kHg@U!jU>==FbodH39p@8w)L zZ&`3uGC+w`@&oh7Nl|07v*zaJ$eQQxYVsT`5M^J;qw9%lHFBRnJQ2vj{nMlyrem3S z(GX_K?1~g$Dlx1Cpim3c)88U&SPSo~)}EeAj~;0Y1Th8IiR(DlM^I+UB)B`YN0BAO_ zb246^p7X7uf`V2PE7+3A$jXL)Nq$bg%qUtvf)>-x?2E7Zfl5O|!}?XXarQMfHb(o^ z4mg`wtD%*@&+oJO^Ulr#e%OvMvD^1(oJVo3ATMVyHA8xI1Fc1XSemr>@c=FUqMqjz zg$nP*{rT^#^Jn_0oxu5b${f4lUN>-JV456ZYiqlHb6i-&EL+t&GRyn#F9lyW=fMA0 zY7KOZJe+%P`+j3&eMH99tFm+k&a zU_)bj?MC;1Ug-bkBNRF0Ic#oh;BI$fAemw!%+1YpVO(n!GIMjEJ=uIpME^VK{_AmM z({yOG)%*AFzv21e_)Fw@zloT}>_~_mF>69Dcyx5{tUB%Q4;E|`Y$bqqjWbxoQS1rm zj5-6IK}nKyux-U#?q72b@W0(j;NK7He^{%(ZXq<|?%f@u9-tXkTwFYpNRMbd5d=Pk zr5?TLZ04P8W{(Qcv!4r>#0Jaeb#>h4oi5E=%HF_6MjJ>O_B%Ze0<6$Sg@uJ3Jbs+B zvNw$}ixlRaN2MN}kDeIarkP-}7Aeb?#K#RosBg13uP=>hQAd<^enEmp;3nW zOepXrT8{Hg-Kwk2Q0#e3a>U}IH)MHS;rv@3eEZxVg`>K5%3}yfoFMd)mDqvMQHU<< z^OkipZ;&mycfkVvI_&PS-6#Kbn|;fDSbC4RNa-d0f!T2zo;P`9M#kg?NTvjG5Xkpv zmunLgir6piMT`(WEtq{_<)6l)VdMqzgYo)m?AgPFEMk+aEQWa;w6NeJ5XD#s5~?C; zT9}SHm(rT&tc(dBW53IK(AbjJ(G0tknDo)S8 ze*Mgi4IExD+CvoQBL&9^erqZ|hC~mn=vUHgBp_?$cefGm-|Sc>1S$4f5Kup7BoO%> z^sc8y6ShiZBI%zsNdfcpY>cIK+lC|N=G2B+A?*$&LCGU{@=*;eS~P*fSEL|#Q_q;M z-~I{BOb`Psu<>ctUNbEPl@eRPKpaW;oncpBc*CNXB+oQ5GEz`n9C-=?|Hesp*#kOY zQuopMmC~(b02W0Yw?tbGVnjqlglmn7xjGONd2YKzLHk7-iZSiJtZXH_b?a7o6}Mvh zo68h&zj}F&x37r%Fo=MkE{-NdvdtAXiI@n3A#o?_A40U?ts;h9l|^X!V*McP*pNT*H_i;#v4nz@04_| zL>M3wHuMkD-bPCNOpc**Gpi0~OKfC>V*2#5Ka#lA5CvGHRUIRvV^;X=6!!y{gj;S& z{q2aH6!OxCrO(t?8X1kqgjosv4j-pQyIn8GQ;H`wJcgeSP2ZoKv&NHVZ+7?el-#y$ z+sVrQ4<9;CkDC=axwI9X|8?yvOk9sC7@di>m*UDqK6abl-O@LnWTwzsADxFnN?%+?j(1sWjb8 z%^6_0u^RRR9&dZXVsvoV=A9#RBXi!locSH>`5mEHKvRB_JmO7D40)!+A^Cp0c>9*s zipd$^RKh~y#{rq{+%a|}^{YM0jEpYk(MdyB*Ry92GtLOGl7}BmX0RksB&mJ8&qB@( zk+*LVK#%Mv;m58k7vXYqQv?~^zKb@q(>ADRqYj*R($)ojFDZU`8(cP;~E z3gACp5sA|W+i@?6%OW=(&Li`H1O^f=h%fg~vZM$Mpe{fglS=7~jg7q}d?h+lFJXbL z_r;6&Tlkpz3vP)m+Mb>&M7{9Hz89=G@+{wSXY^z?!FzOU``QA;LMEcF}F4?+SrT4MUx7*jo&}~_`WqW(q#Rq zM1(L>jsj&5`;@Jn-2g;h5#7p#Ug~Eercch|D@`Y&GkuIKj)GPLFFME5>w25<%B~DZw zQcbZQh(`LL>z{_ntnD%FnLWEexi4l*%1TS?_=heDhhr#jjvdd`ny%5fhb4&N;7TRp zLyL;a(LB=zIZaB6FxVbY$ENS5fDm^-lhH1sAOXn{SuHJ~vbo zpa9-DjG%1WGH?wCx8 zEHSfZBMyW-&VhaTt|fe(#ZTV_1k^fwQ;_kdZHJXoGw#~<&4(XmH zB#$$dRswib=d-{c%ap$v;(We;(ye-^SDpi>A0>C=oQc7M!nEv=h)HvGz7<+$U;w|{ z&1Ww7{ON!JMzpTlJEASJ4@QgAP<9&Wd*yo%h2@keR1)(3OAATlh&Fbj959(6fW%xa zKHSorPI-A=g7&qd*O6!wUlw?YAIL41S^3JA(RnQFJ?PA4DxLLw`p3~e^0Ols02+O{ zD6+&Cn$$ZXKeg-0F!|Nz-75uEVNRT2iOm<`pG1a<2Z8LQZ`|;SelS)fgu-8vO=BP~ zVGSW`eCnl-DIGoQbFD`a&R=BaL;Scq||3e^kXeN5gH zAddCK^Fo1L{%XRU!D_`Owy;%%=T#V+m@hZNQ9I4^?lHzH@UqM6MocFk5%@m-N=MahxRPR2?)Zbn1Si{G<)qSTU!)?HM1w`T(%_}_~ zx_?KavgKwfOQ>oTJFk?ohFE2Gw-%o8iq@NfJSJ$6m-s#fxz+P4O5tz1v7}PemD?FO1;eTh> z080F8`j=UPn4wF8W|D1ADVW8r{)eFJ}g-hu(C~jLgScF4CRhfzg!eLyhs|Y z!@l(4t?M#j?Du;r+^-^4wM*wd(`FWo#v+haa%G{DTN5JpeGPrOAr|Z$rhRX2(zf08 ztForpYSmQzE(4^Emhi)5mIoI_GINLa~>hh5wal8)OWMySXJVD}NU09i!I+T1IFGFC}etej!(W80MhSwmtfNP*&K3Cnl zd*7qox0;*cWvN8_V_yBt1>xqdOK!^~L7qx<8~A!w_VSCwaQ?C2SlXp$-kE!*%@K?u zSkkhT@GKeE8f3HIq>cSPIR+Shr4MWDa|&YAZ4}mROWPal93qjbMf0o@k(^$K<+p3Q z2~5EIN1;rZDb~9At8aC|ck$v?|GvnA+5*9r4Z_Z?@hjF(rz zQ+Ye1v^3bZDYuXGmekVHN-)%l@!Elh5&-kwqyD^GzZ=648l<5g#oyii_Gt$#+8Z~D zT@8>$Sl0a!*N3abLXdg+Jr$}z;{hmh(;zDjAZoO00~ZH$Pif-?o0*v*0rlJ?IY1)p z2(mwcab4?c_&oQ`975jVsW3t#QUDw1pGgIjSgPztBZb4(xIYgV5~ma;iV?Feih zVbrUK8*1Y{VlU|?Ne0A@_|7aV0Yw9+^@9;qG5>|kk&1{H29iIdUQ2(PkIXmb+psC} zw;1!i?M!63Qj^AKc;pDlMWU5k3w43^oRR51eQN<$u>4=$e1Y0fItDFf!~6{OAHi+* z#2s*c@-xiwX<{3vrx+}(@|_B4$i|C4>M;=b zX*rA>F)odCDqyVAta`XsE9`Ut*lm;fsh+!s@0`!012!+*I1zwS1!p-`i{?Cey)5st z5mL*f52gl&>c+n{Om35?)XZA_(2$#JPw4#E*qBbPT4nTU*6GO3^lJUa-EkYzvcRFY zIPga`y77V?kTkBoQ~eseh`I*Cs!?&V+}$bU5p}>%2eI^^JAF|-N&*Xw(y|MRG}h#}qjDF?O`A3m z1UYI;`Shzl5Jkz^9z?Zh)fe;MJL6JL+j+Qmh3m|VMnfEgX z4<8N?`!=rgJ0Q@_->0nsriMbL)9z!cV{}|xzz6@&m4vtOGt$ymMTPuElN**yn5}c{ zV*137VF=R(P<&=A<(0Uv_*7+%I^U(SG#`D@vjy`}0~t0bW|~xbY;n9dt?ku|@t&OI zeV`=$5oX#_WjNSGz_EkRWY@6`7>xd&var!PA#h#6607b495<(Ak zqRrC6bdriwnx2m2;E4nK_k*C?czC1MN$zYanwg@%;mCrdqRBOC=e&vG1NT}~s550& zpiUxdF(-KHq-s26xpt@fZ+z~cu}jR}OnTmV21X1WBVbzOVCSj>)Cb7pBh@7;fvVf1R+LC~sXv zDmRK8ZaA!`wml{+qK~2(mQ?$)O$=e3EKcknX`I#7YCx%O&|Yl(YUKCV0!80`GNVBW zoR6G&+PSb5gQv2t>_hvCuC8u7Ei$ta)E*aG>9l2igc&+pdz72cT0D7dY;k! z?!ABC_nmW{^Z%KPS6{hcX4YCy+|PaAYl0Q!C2m~1cMX9++>nwKRYoAtLJ^1y8yFYi zJ37U!JqW~@l$5BDs%z5fxT!AA;2`>@mh;lHC1p`=8Y(fPP-$!Kb~3K{JGijUZKfU9-Al_yr_IgczN9!fI6?D{#e=sz z>C)(6hFmNaBl|p?&~?=($M7iu&99>C>kVmKYE({Ga+?fq#?Iziz`u;P372 zjn$pdFSV-slHMaE)N#M{&vO2~E{5qh2Td%0pCl?dnf}j{FuBeZUhb=3Z&km1`7-u> z0z1@u{`;lTF>PXMs-vY9EWprIfLbH%t18!5s24@O>|^0e@b~Mxt#cTNzw42_K5LJL z_`4!l)8)T!z2_kdi%O3k0&%qw;|BbOpmwn)os`Q3#3RhVD}ptB$u26|NUEs$&x_;P zWzZMK$7|&cnxqBEJflUeCWMk9<GM$W1|7*mzcXWIzExqld8}hd_V%lwCqDlfPH2;Rd-)i>1mzMuZg#Qnv@}+JB zLa?o~)7HxB5r(kPhof%oKe4N(mQh&9@IPbsUq^1BdoQptr>KZhyU=4Cl^@V6@CgX6 z{?GjQyYy{5yfPwGAy5DBBj-mRdNf zLoH?0(Ew`Y@Le37Z^q2kzZqz0N2}~U`uR1^w&?@i(J@b&YHWzZX0-C-R*`}6du&M|36Pe+%noA|x` zZ%Z|qAbmpkLKc2|o=<#cs>9>kF?6Qa^nYvL%b&di1MtK)&Uc#4VJo_X=&^Og$7}c>Uh~3oU*d=n_qfxrp{|4&rD4@?50I!z0f`wN!DB{HJyPo;;?z^$oO8wb*~p~)&mWJ zz!JEA{W|JRK+tUUk%TW_wG>0e#X6waXICK&_ci-YU$Rn zbVqodj#L2>EUeFZ+VdM5une~gcnJ7mjH_3xy-xNc?(?8^_D;!pVP3uZrB7m!6AGx; zLVo}FdX*Ks&U3TZ^mPm7LPA2<@fdJC4`j~0Q~w<*b38VNhSTq8HP*+fqmz>8IIjs| zMMOlvb3b=-a&mAW!$`}{ZvFiE$>y&w{QUfFv5W%Ft8p*9sx@#{28&WzOgnzYv*_vR zUEY;`&SAW@5LP7|7OEA2K--!;F3--+wj3-R9vYIY;elh8f}Ki?kC&>!V`k*y;(CC3 zOr0L>6d;Gk#yn3Cx5kvTWH>A;Dk>t0xFFQu%(cZ*K6-?~|Ev3>L?kia^5SBZ;z6$%XnPYzcn>Ms8wp? zO)d3iIV^POAwAumKQB&AHR#2C#eD1_uFLeTiJNtCHBNTE#%V>9Zs2%trQ|angxf2K zRK2R_Pn$w;>oT4Jh`jj9)W*i94)@uYFJBzyf0|2J+_kmcNKa2E@jiTMc-wqE?cl`= z1f9~QkjKJ)9oLOmAXV5~=OoABDV-c0GiBpTEe9Dc_>rtzHNso5<4ig{bhWj$wef&Z zt`z}D`g^nSRwRkQ{?5+FDj8$r*>AyjM(<;DN5`d;8hx>BEN)uU)_X`}}01t4nd>^Uv||8r6zJ8)n9=7ElfVwIhmS+fl-v5NtE)Tj%(ufo9zA+gZa!_;lBF(eiYno} z7jAX68nJ9SqXr<+hpen`d8n8J-LA!?j-&0%pP~w*iY`}#rHRSFaz#AV zwDK^`4LdEmyBnWYry2uCUGBFLl9p)ZmzT2w1iWB}IyrxTe|W6WnWsUR_#T{Mi0_^!HOpn5{85F5@UbXX&-1{p>blt@ZRg-lwh{9F_a` zMRjyWySuj_70`qpQBbho{{S!b?b|na`fn{Qv9Yl(`E92Rx>dy%{WMd=cV;pDIIJtn z`j^FZkAiAVJBcSQu`X8&8XxTZ?Zfb=^GFrc`j&|MWEj5RjZwwt^!yXC+w`~KG3*h@ z`-RR_1uRi5tzoE=(=#(O)6=2}cLcb&s&jLtH!GwUPJf41{r-LB!YCr0$oBHR<-`k! z7oNZ7@%>G|`F2kyRgY{cLaNi7V!(rl#iN zia*(at=n4}tYqA2Ioz6=M0ybt5G-wM6crS-(@L(buOp!*bJ$KC9v!jOk}-4pKG6)k z!Yr$!lh|bV^a)H@q?13|+T3n+35$q~Ze^wFRD|&aM@dhWs#}kKvi|;te5^VaQY|br zbjEsne}8{#EB^6QVPoTT$R9yL#3a(X{lV4b8;~N6iaXc{#H=hj<;M3sk-(dFfof1` zCMG6u4yM)VWgwp=CCyyCPfgZ_N@iAy8ld+l3i$B5SvBM0p&kqK^LOFTjSUib;NpsT zUkYuKmX|+YE$j3jB7aT!&*b+u&nBeF(0US?e6rEn+NwU;>80LG9&*mf#RXLo4;R;K zs|l}e_)WWWV`JmY{@Un=4e7U@7`bUaR9TW&dBkgfe-BSSy98eMGobgQqQApTv~NHy&6D*F{5c28GFn9w8%<` zK1NE)z>^K7kK$sYqOU8ZJ39&NGFTX3kPG68u+1s`f1Kk+Mn=?&+C{Nrf2ePL3l9l_ zeXs8u2XfK#_%S?0?m@I9Ubxs zB*|OP@fxaYYj?C^t8KCGX_%Q&9r?YU#1sVJgTh;qq4MwAn5e1E;jmPtlcb0^0zTH( z@>J@7f*j_;YXuPZCOZ1;?Ch#u2n}pRiBXFyy&SrU?nR5L3*~5k0X^0oY6Uc5EdRvB#1kJhW5*$+ zmxsOmc5jx#WuhP7zXun+B1GW+lM>y0w$wBA3C{{DUd`w4#@0DWhDvh(sREi5c7Egf{A$JIJ685$XV zOiO#Xq;M5*)>4pRh>?ZGGUTC=p&|T~ii!&Sk3X?6;%+GJ?c2BU@F=Z~SSX^o{?vC4 z1%=N28)1N$pw5z!kwHX9M@PG@$;-f`xp_g4g=0N*~$LXmjjcsPP8ETA=i2>{Yt@P8UPw*%F z^U9Sgo*QoyQ~$wf4}qPl_dYu=)T=!|-BHkQt9DqJsP`Dmkim;;o~r@y0|ysD%tvz= zS6EmGIb*^c@5r58t064x`%9185HKWsA4(v+_qrN2dM_%P)Ik7xEiGC3`C&Yg4)*pv z0|R$GU(&BMXavzN18qQ|XK!zx@|%*Jd=AE!7lB5ABYG}lsyhFA8`)`wzt)VG@@k1e40K>rG<>cgeCc=pUh*B@m?*D@23wZDW z9bJCLl8>$|g#(m$BoYaGF?+2+;B@nni}Wmv3<3Ql5)v&}?@&BPH~Gp}l4_kAL6 z!YdnFdA}Bl*Czfl8Eq0{@GhYF!n=dLIrtt;Ny6`mRb2GV>u~b{w5L;|R8kBzwf--D z=pOE<2gHGf&{Xt859MvZttiF^zTO2_0p@~ZSc^!Ejm5in&;4+73RW1i&*!@NYq>v< zAndMfugm6+xVZQgG&Bs?TS8cm-HVKXYyjW_u*LyR$Z@IX*--IQGKq-O=}<;l zSy}GGD5!GWe$MInoLN;h4}eyOgN~H+eTH^F zbW>OsKo%HmBSJ%WHaD?|y8HW`05HM&U|DPHpSqqsdp5VQ5c~G+>!OOP-wce5MKFQo z=g(GXsH(jlJDsRGr`}!dv*)D?P|>Q$ zm?nH+u6J~D8g(aHrTrC{kUyHPM%>iUSk(sqjjF;6&pkv@L2dx@Y}a925bCj60SCX+Y{jTwR|NwCJV6f8W~$Hm(L$<^ zdcG!;aqDYXw0t6a_;=%w_cIWv+l=(|YtYI0oR(FAvuM&YV;zAu0T3bZ=6&fPSKgV` z)t|=9iOC7A_toL$*zSL=uBic5^NmCz93o8CkzrxG2L}rgU4UoYqVe6Fn!m9}M(HUl z6Wxg}b75SVlkp{$*R8|aGc)GhG^+sIqH(+Uy z<4{v>o2Pz<$`k$O4RJEx$=0kC`dyiZ5~YUk9M+_PogU{Mx+}zxxa-UEiXlbd81wNTA<%98K?6{-u zu8)t;HU{9n;LON&*WE=WPtQ|7ol5+zEiy~XlZt(B#+PKQKt}*81Nl!8{at4J!LP}& z-3N8N59!Zpfwd+-=%2_+>vh$?_i&@MwlLc+ttP? zCG|&unV@C+h8D9m88hb;^)S-V{4je+Nh$FelY$>$0Ptgwd9fJ2UA?_K`}-;E)(Q3X z^`1!*rNltwk7SmYJHogMU6hW7=JqB#8yg#dKiDHzH@EnNgpdM{9w`Zlg*L{9)9p4! z*kqsOKESQ=vIeB{F);irW?S#Je z4J4RVV6Gt6VFpe|;vFcUN};u(;X`uV&&`n}BzNyN55^@W{q!=6e*OBhbu}dJErHX| ziF1-z-+<}+UaP2JGpv5~>eVrx*7Ba7t7vv{q*VIG&oR>8TMjNWBA>`79cG#;1V6$C zh8iCDkDnk6P7*n6t3FoXG3rCpU4V2^jZlXQHrpBnjThqo@bFMJfz`bA^@E3tY>G|4 z$aj{kfH|yTBO^0{sT&wAK-u(bO-~++M-Xv&>{|i-lb>rLZD8;l24@tdc>UTnd1%qF zBT!M;y+&s#=%E{4e(>NjA-ma4!b|~|!j9SR_B$Q{|AdjJsP;^H7EGt<*Ch5{mi zb%*ou^7QQM<9FL6+v?;2%!I^F06Y)pf{Tj_9J4DK>)lW`AbI`JZ=oPQOF+J6iEmwO zR#q0|AC^xC&_AT`i^IW3JJbg`WlcLY&A9{1Z56Y>0-y! zC}AsugM)p3pSk3HJOGS0{s%hNLPWvYCNmjbnM9Ke{;luy2JrAe4U_^8;JN_j;cfnM z{q^}J@V;dx?ZO1tXh0{A0YcAexD*;CEDU~qD~3Psw!f)NtsN(c&BW>R9g~=pl#oge zhb==ja~fIHJi-qpqSkqh+ja9vqI6aSKGQ=^&bV4{oog@y7U@(1nKuDYbbQ?#2{KLoIDFK+Do0|jZHtPp`%2isQ8F+tf$*s}x@#bP!y%>h9LW@eHv6;EK zEaq>#1z*e;KlPV=Hb`2;4Jf?Y=QoN15*Gdnd&%#8O7)}#-uQhUXD9=WJw5ivyQsQ~ zA^Xmw1)DYLbujJ%e?Xnrt98E5WpC{2 zRAFK1Q4$)O7eOS&XD`~{Bqs1!v2!psV%Y*{9={Y`w^HDOhK4kkRqpin^?^mfXqkKwJa_1lA+v)B*xNK*!;yI3*PnSZiu(dV8OL)$eOy z4_>BJDE0Gw6COT!e5`)D6}VV~4r>#&Vm|@itTFJ`25h0MEN0VGd~ophOu0mur+^i( zG&QAMmJfN`(9n>Yn)-qR=5R>C2wuUq)>h3r*OKb$BbQ0YkmCqk*tR}L=MPyC^rf9Z|xl%X5=HSCZmeh9lS7{_Wu22&%;gN)qnrs`*e&S-I4_ zmjV{(wlfceWpG()@--8#^9B^|goy2mmlg&l$_{-eZq@{VBaJN))>I7g znzj2Pva*9eq(f>4N;KV82IdM3iq_X{IBip)NU@TWM>&Hu_96|6byru{=H_Nd$hDB# zuBBb*V<4?TiP22=ipGH=2$TT{i4XANv$Mwc!sh|StgVeBOSGVMi;8}OAwsiA{{~qQ zA6j=LDb>WfT1n;LEsU;2mcXZGLlIruLSkaiMnF2ul%u7mhq207R`#cX&so3K_8N@T z5I!W3M`KlXv>Js(+>Y6Y9<-B>g@F{NqN6)quib!(mvBa(-n#@~OTWV69q@RECj;h8 zySuN}CKXmEe|K)pNC}*qMW+-B*(u!20@960|wAZUGRbx(Dq@z zsZhl!rv|>o$LF^#@<`mVdOpJ+$|Ueg9Pa{ttvX+XDc%m|0cZ&<4Ak+WSY%gyr`awg zfA5QD5)mL3td|-&?vRy`Fzrqg3%yJK;q3!ODuzCh z(=P3>mZpgNgsueuBWm5v%@oYcrAwQ#dU||RR8)L?XV78sQ>3IPwaVr*GvXUO-Aum) z`7G|vw`H>h>gnoMS!(2l%2=fG2h_Th{ca<;49Rx|1~DckCV=1sysn!td{Eu&1a-Ob z>(?qa?^$ox0Xt}BFjndaSg!Q3S?KsB?Fg~F)ibOqI z6Jz6Y6zC4cGs=j6Tf8`Nmbfw~BO}wuVNEmC;G?OAyQhUQ=Kqju(z`8*GiqriZ(zI3 zHU8Y|9}=rB+tVQ{@Zk^Hm2pN)!2(!jt6YF~kVid6r?JIOH!6u*;wa;u3| zZFT3c?fl2&*RS&l2%Nn@kcWAXeucI6_wV)RY3NkighxaaLj5`>wy}tTS&d$|>N&ha zclX~0ZGx}7i_#z2PZj7V8}Z;4R6iFf0W4L;>58T>3bbZ`8DDqLNM!XLINo9#^&ZnGm!$y zL@B@vb|i7_0F>dd8H)qzUM7p5 zvA=5WJPQMv+iWYgEX`|s7zPPBY~@pV4p6vd?s(4*jVXmRTZ1>d^Cum~RqDef$^vY% z-Gz?+{q1QPs)r&Co&WNE(30Ch@%jXbA~2$S+ytU81UYoT$4pF9Y}%Tdiq-7Vhj1Rc z&Tej}32b5#5mkKy%DSFuOvXXpPu}mROWDUW89ceBSPVcJNQ&O6_>7D>m^W?5s$NdT=NEta zgmhlhhBA9VN0)i$8<8)k43=sy|82A{CK|f+2~5wVOM|8MdotK^a?)045Qx@1h!+@B zP)rU?1bu;~;5C4G2O1CPaPLi0;Nrdme!jtV3&ls?ULth#2O~D*Um#uCC5zqV5R31KkG97@;-M zrG*SEECP>ab28>ma#RQz^i?gaa8A7w-n{AP%VF0j&fIGVi&kW>INl>*XadhLmH~aEDRg z7jTn6kbf#J2L7w@oQK#GdC~jU}eiIir*cd2K zR{m3`0h#i(Q?!40*lIyO>(n!ENOOL%8!egPmG{L+XnTMMhy}dI0P1Awz|;!98u#5r zyR&1btpmBc-;Xc~kVx<0(q|BXP#5P$jh{Vp0uCN#ZkM$YwTE7pra=3wf)It`Rgj;L z;oC|Pr!+hK!UryaCwP0mzeK|Zq;T^$=2v_nZQ`x@bb8F zO-jmB#n)%il=})P_zYUYgZ;P)0w1)X0D3{=0gW#zN~yO1{4jmlO8WZx$)~YN*W8Fd zWMpL>faC+}a*>{#oHZ;3NUYu6-M69*g8tC|V-pf;o;CtxRr4hsLW>f_qQx-86j~(> z;spzAV6IWg_CSG$h0Qsj&z>?Eiq zaX3D-@^DnfUP4C-xME!u1JQOAMv_eV^cuj(JU`%Td7f0_1NpA>P#FWDKloW$TSL{f zTk0VP?mSbcx3?GS9vraEmW%B1_fZUbF0NtF@fW*4daeN;851UVbsTV`qNUv!saS!* zRBj=LC@g}w=9x?*(yM-=ZmHCs{G$xsa$te`;bVs{zQ#r~zsYeRv$?>9LqbT%V+Qct z?@BV4!>e`^mEpF50d_h%I!elgSOf2+MG2sy$oc4+j|TK@eE#iOGBZni2vMK&NHGPZce#qZSe$XiKxKtbOB1 zJ-1WW_HaVcOMCebQPhfzOt@BAACQ2UH?CH5M*gLDcudFsC~?^U%YA))W71gJo_u}* zhaYy2E!R9{Yu_tvdfJeWkI(Id%Ylh!~Kc3#pau>H`C zRQE5Mt7~dj88(G1E}F?lqdk80>J?yYqQ_4Jd+XD;4zzad%!zIWCWd8a1j_u&elAqD zq|5DUj4Xh(0<{QW*SrT|vOJ2GOklG_I}Ll!VrFFprwzMAm^g6*HPr&QRn<9cvAr$* zkPMs)mO1q7hdz!q&6`v1FJHPxQ*`5pWsW|Z<`w=U0j(w3_4f3@&;cO(a6kg%eSZGx z%uE^dEuf*MyeEMAt*Wm6-riZwz_Q~dDr%>ydcR`VYY)vXkdy)In}~1mTKCN6R3j>o zOUYV81kMkQ0QdlUwyZIS9tJe_g5}%XNz;<1cY$^?V1f?~m4WsiA3qEX1d3+B>=YCd zdI~=Z@&*Wmo{2zXj%6v3*i38GynOlP$Gdv{hIPA*6#XYp5^sm7>NlhS?c7_a=a60C z1U`!3TBw`pQqfQ}K;x3Ib2WMLWD_tL7~5g001KB`AKzQ0@OSUXySt0{_)@jB=L7u} z2~z4G23eyqg^;RafAhL$z15Qe)N0eF?0FbI(=-4NGVw688tO-nj2F8;Kom`Hyep47 z`XB?&9n{{(xa{uldjrv0JGkVldym;zQd;^4u!=_`T66KOhCVAQVgs?uA?}Kq?RyKRY_Wb;qoJ=(ezMl- z{oMp}u+#JBX2)Y0Wl?L`BS1l2xkaq2sw!%us-y&MY6E~ooNQ(~_Z4LsC_9k+AY4Kn zp52Fl_#hGpTzoVkE-UNqLi@_rua_dy*HCY}^(Dj#;A;4?K0iIeVe#rUV+EZF$Txl< z87Au7Jbn26<;CxW_btrdwI1H?nK*x!XK5!YYV<7Q*MS2L&UsolY`dB7kTh1&x#hv; zrrFYk>#gyiy>cWP)&oBY5e*WNd4hJ@&g&`c5g2Zehtt=QTvs7xenZE=qt||vqyJJC zNQ5nc-=~cS8H#FZY{2NibjRk^5K`|2^o`Tc@7;W!nwGm}zVcc4K`MHBx9^|14;9Dm z?~CbF4lK-H`)~lvl(Rw#Z#<6+Ttygub%XF4bvhO}iJ`v&`2cMIk3koo-6}5IgDRBM z$tk0x#8y1g+rlR0cjGN5bMu1rG&Ae7tmN^b=4NuDjvKz&3l+39Hp8WJzz<2T4Y)mT z!|9A?$y&+;0TCQQnORw(4H`Xy>Jnz?H;LldEbqF|-;WFoY=K3H6sll$-9|?b1U`CG z?s-vBQ7V&>xJ(9@8Ro0yp^{I3(cJlInY}|3pSE&rOiY9Gnu@~?hf(v}6uvfdqh?72 z!i?l*pu^PH03bY2(1e#aXEek#6lhoEnv+k1B~K6RBpE;7A>_<0EFdHt;7Di1ZwB7M!Pz}K zn7lru)ZN!-)}O0iWH368Ea35Ams5LZA<14lz1$y0t@2tC4I$VE^8(<|_4V;u=^hD`LK^`A z;fIo8kOoX`hf4#B#ydMVK+@Dyx@Mh`pYI9ITi~CN`*MlwU>bIiQO0<`v~J_JiqG*O zNc;DB-^?~Sj=2+(AAwMejgPOk=+6a$VaLbr$ZB8D|6HHw9UvR*>yu65+=AHjT+7oa zf@3NBWrHY(drl8P*;Y}BwzW4>RqX?i4nsnrw7clQ=|)+?z1~TK_Li*mxwg{HO_Ute z)P(a<12SuG^TAr8Z8?PkdmN93b=P~7Ns4bfLC5NU-39TXC(svwSgNY3%Is&ECt#+~Ba0(XlkBqlyTk3J-qjlMq)RhWTn>vAgENg}P^>KrtD3 z?eznLe>jnyn+rNw8%OkIZk8*4B`^4tBY@KO%|g1>9A?H;Xfp3Jy-DGL-UmfZ7|_ZUXWn z)5C|;kb8XxkTz!kB>%Aded(t6BB0}?*9u~xeE~_H$0_#_P44lQQAjP--r|Rug)9Nn zn@0+oMn*G9Tn^BAk0z{aY`l-QpUvKUk;%);3;l%I3Mv<)!JAPKroh6&{auCN$_A~} zri)5#B@Gpo<7q2cA%K|kT++qIYz7bjF#o|57sN8C(@&o~!NSLvOc^^o+%f{i4mc7! z89kL_FLl+vRCYO^k@DlQv1y~0iNL@?(y}W-{Tc&V)Sq zb4BZ6;oBDA&TfEUeEqtmif=eJnK*bYBk!?=h<~)(&}{p$fa|7vGmD1*e7yT(M#Jw8 zb7ryd1)VN#UR26ga%{Ab8pe8L4rsU-2rU>{DH?m+c062u%VVezf z{Ze4w0JU2<<6UUIDpqdVZXqHZ_3Bk=RaN=cOca!s_vGg0<`7nDgN1q;`I1UYc9;q z-QL}`;^sxEBH#%Ko+7}=EGW27LNe)i+X@m2+%dCA)r9iME^tZlI4*X9A<7<12lMd5 zTqZy9QNb7o`~Y+}P~*Ob!%2dL2{`#Rp3KZzkIGiblYF`zKlFZd%=bt##t)L+LnV?_ z7ZIPG09%5*G&(%IHd+~3L}wub2-h1ZhSk+o7<-36@~;WJ|6pD>;(q}^eJc1QG+LT* z`393GYdW=r9FAU|I0?1CHPzMG;r&6;jUqH>9Ra(A&&e7G5}g#$KFuF#p3t!dXO@zZ z0y5)k$)ax}xt*_JEui10DQIMZVm?vp5?K_6`vU6*G4COO9dI7aHpAUJsH}jXok?Ok zjF&qT2WP%q3Ve&xNG`LON^DSE+x0rNzD2~m=MlFjD^CChKlw8nf_`Qx%;Q{m_ zAmbnU;C`8!nu2|SO9NLlr)8Am<65s_%CfV2udJL*4bZ1mq*BVMsSUPB{N7!fARuU7 z8K90&tlaGY%>_mjV4nTQTAw@ye9B@w!8^4}%#CitU8$C*zE$DSa{owDylOZPv# zd;1oXgrAp(CvnW|>C-K!Vz3gKT#YWN-SzPk*b~pTin6k@EZO*;t)fe~9v)@MJjvVJ z`5j4988vBXV1MJ}J)QgYrE_idn)gx0hvMQrFYr|xC@FOV!pJWuSoj&==rTTe8>sZT zIVT`kP_o?q>M%gBwDt625MF|I4{x}+iRpaett|7HTh=DR7JBCV3cAbq{)Wqs&dRU| zbz)|JEKZ)cO@=q{AHQI1@hdHbju=ZRm(bTeA(FMb(gY_YxW}2 z5@z5ufoXF-@9Eb94#s6$1_T4B6o5B1wX~uLVOW$1zeoNSeFfBkxi zRCke5P#|G7!3?sJ!qhbpGWvqp3Q%kT#z zCK|&O0h|y!GxHnOqW5>0nV5njBRQCu9&nrk^7tqoo|}_{t&St6qS9Dl>4EgNb~*X9 zzB+6zN44!d{Y~|HXp(J1ft<`8^;iVrQE20oZmqL5aFqbdA^330F2dDO+tE+-JUkwt zm9ew4!;$4@%S->zFMTvT#A$TA8)7-A&3LKtiJ3y&6R-0+l+aV4qejIz3LGH`lOfuq zJp!&C0Q|10uC6HBLGZGe{H*dm1M3cVH4`J_Mkph)wXH2$wMbNSS={W#jT=A$ffz%| zaStCKgl!3F8h^noLlYC{lYMI>o4L=~-XK(%d;TZ0A>zG`E|t8_KdA*K>F8wpn*xpt zSHFIB(W&IGtnfm`5pID0Lj-B*X zIQpwUfCTYW6Tdb+y?78{s%0*+zj#_r>-{Dcwln~NnntlnwNDkZ!=&;To4b# z2bW2!iyE+`Yg1DXOf7rx3kC}CObgcGgg|titg`bPYc*yD)xpTpl9m(eMbHpvz;$lD zG{|pTFb^fZtJdu5Uj(6$0w2I$Ta8+|Mm#)rAvClCkgAo$G@|!~A zRWcVZqh;T?_o!n>L-WrK#7c+eb}(+%y4Z?}ikh3}{KDde_X&2NqvgD!E139j+q)0$ zCNY>vF%_1dC29S+G*>%gfA8LpLIcLoklZ@^02K|&LsDHw@XA^z6gD(~Q5vL|@QWT3 zR%0NfKW%)qMK909!4U~}Or~+L7yuCif`Zcb#umNK`)mZ<@F>KkMr3^80o>mQuamV( z5Y{Oxf#@Cs2xi)u@@Dxq;*Yh`2eeh-pR2bHCVdQQoeLIyb2+)<*N2{_#t*LzF=Y&> zn?$pL$5326v%0$8-kIU*bt9jI8@LF;5nj*3uFlRPcs9W5grLMmM05bO0g?0$E-u@9 zdNtWu&9zWGw@L3rm|ytprUR?01_Di46KVn_Dzmdww6ydNR+V60_p+<5z667AYdGXH zFlqQHFR6w`MxeBJ4h_YP9YV7Pw}>KL!-F%_wddPKZa%DmX>qx83N!3Pj@I-Z1GjxkXY4rX3>OJ^qJj5%xJrBYk}? zdFu5i=N|tCA2!ZELKHg;rfg82)v*q&*mjdt@D4)mdCCx?IXr)^S>u=!8F_0`k7en1 z9Zuz6kz%Il8C*#Lu*?5&dgi0V#fwo)va-8pXE)|MZK;j;_d0b{R3Po*pz_9^5(C#k zCx0Odq~uzdAb)-F`z}^}etrVV=LX>9-0bYvlXRhz(LLLkYrrmoaclPO<;wvuI@}`S zR21gB_-kQ(-TQdg9BEwi^5sha&v!)}$w3Sz@mWoddg=lEV!1g~)LajC*0*4)4=4Fu zZmIDINHlXrC8ZLt6K5a}At6*qQc#yDGzxXyV6d)p+c|t?y6tblAaQe{u|3h&v{Rm) zy+gY^=*MOlcu82Ca{Du6_Lr726WOm)nTaa_d;}fw==>H~&A?_3w$xHTbabqr0|WbT zBMQpPY%|F3AYmxe#Za}U8~VpYN3%GuY9g27z_CZdVUv_zgVvP~WRf+EJ!3%c!973C zt#>o;yUWER%3O;3ixs#bcz8}=Ufh4{fNZOYxl$P3-~ZnnQZe-yLHf!P z!IjIy0&a%CXM>+AVx9G7-MC*4G9s`s_MssmKS+E|;RXxUH!6fL7dN+lt+U)xZ!oYA zHsL`*uT^9Hg};)OLooyu66w0-J9gNFX8?4(jdQIQI zJ0948aN9Q1!p6rp8m0IsL!-#0;cP�EZ4CmQQz! z)!onvllFU;E?rV`QO+$+pkpsY(YaG!vznX#=ruKB<;N`Py=-vMA>mFx+E_*_Wcr7- z7L&mfEC718tPOl10H@2kF5vS3;_HINFE63PSn|de`v(Ln%Be5qlr!^)S6BxW)XB(B zpqQao)nU#fl!N56Qh8h=7@HPBX@OQqnZrPxox9wTWbQH}zENo#K2WH}%9eq&m6Mk4 z*q-~InYna_GRB~8$el?Afw%_sn%#E7>giJ^Aa;QqQ5^o)6b-xp%CQI|6IxMvtOo$5 z%ZVHU0GPO*|2nyZJ~TH60cT}tS>smbq^ax!TxF0Zo@KnRiMUeBOiZnT2;DGJ#^$(J0fxL!8bzPhI(K}oioKDOb5Ji7g=!=O3#Kvl7OtM+3w3&}(r=xekz>lhhJn^9J*?}*Sc0u> zW5Y0MNbE}rz_+(Rha-3w{e1y=ilI(*3@)y$&?566TiQ0D7H~L6>45nOkC>R@RTskdKDT3# zZ3itC zJ2L%yLJ&oS=Y*fYAa#dQ9yqd$%*<=+xWmBXg3Xy5u61)KPkhnGEbk=)`d`iw2HIJDAomc|tqlsBQvJKM?x2moNn-tbn8eePuQV zY`Ovd{*t)@^h$R2%;P1E{48ao-5-~UiLGU*ZsWdNpW5n~KrRj%5N6A1UVI^s(vX4b z0Gk6?RMI$kRa8}BXHEWGwU`Do)1vT?QwEQrRXC(pn1?EKD#xC+Wn*@lNlX9y9!<}v zU#_4qs9m4H!+R$YT*3grqjlg?bCGU!&#-d!3s#oLkEU^YUmX6U8(yY55PAlc&VO_T{RY~{~GSeS@+PLxb@5k5#;2yv< z20%I@JluNEhA9#t59-;8h^%_Hg{gDS>V(5|5@YuHc~8AmarQj)L8?3k5rm(=F6_wg zybfGeAQR5D-LzjFVlu^k6oR&hVM8%Qz+$qgU6s)fH=v+|emyYBIh(*bc%NNW6<5^9 zkt`3Yep;cTr6VFp1&$F~Ys-_zuJlAVO~FdIG1(CNqzFv~uK(&+7A~v|4)~nstjvh0 zsAbepChFP!Vfk|A=d0Ud`pch*-$ArqU{3_0Zwcnp8~0eLC@5Y{Z$ig*1`9H5;&{1v z^oyx@Pb1LKBt+}(aqm_aSbymhP$5VOE`LwpWW_$()|Qu^?mu=2wnVvPZncMJ7qG10 z`QU~EWn~@6eo*LOgm|;8tP||y-#qmk^hWK|CFVG2wLlR|B#k4mYT(7sz%4i%14BBH z?b5jds@-PGHa0Qc-SS6ACQqMQOH+M?>3gD#vgymz+~=1Yw}{iEK5MwF1nnud8dN2e-|yJjw?Zi?W$h(@p!o&n=-dPrV^``bUhXey4mHp%ony1J8%@5W*EpW97tq-~{*&5d`#NH&v0>JIXyREpYhqmX*5m zdAdr;VuCZEU+=B8wH$}F{m-A}HLg)yZlyuj5-Prf6%pyMAa5TE-b&cYV$RFy@xH!a zflG#GZViWui3*?enm&qYo?5tmu?L2j*E+Ita&UL=+rR~c5=eOXlQ;`NaY3U&tr=a- z)bw8rgM8}1J-&qZb-t-6HRI0CNbgSkJ2h`f$+N8LxC?^fprTm<7Ki&m;GG30v8r?T z;Nb7A780N<;PVs=ZEYE$&wOb9jl5+rG;;TRSLJ?a|1v`=4y#U?cz2)b?s)nm4vyHO z=C?610~MBohd*9klzc!D?KbxV7dfeBU|?WBjmRNKVr!%BAg^`;u1K09RRG`yq~~{f z7>fY@zFAhN?SA_fKC_^t-oEK@qd|_tR{c{2^!NLr?<&2|uIr5MMv=)xkl3a_@5D!> z%fT=VjN8fX(hNA5z(aSl!gL0L4JzIlXgy%-;5PMc$PK*3g2&)F62o;_?s|ffr!+OO zx3{=u6TxJ8h@H;)2m_2(%F3f%g z!4yoY;xw2C`kKL&LFY=F3i=NifhxeR>5!xXK++1mt42v4TpWua ztqN!bzzPmH;axc>cfB!?iWitkz4fy+P+i4NR4~HICHm z?CQ#AA0&y$%HggKs^5*J<>i5An}Nyy3RVN$I9T?oiCBRTT8Nsji%>OlcYS^*B#wmh zJ^vE~d@RP?oY=`hR!voUO%=|ofD!?@%U2LRGvLQTsbnlHCreqWfUUCsryu7_W1|Qt zrtC?;m+mZto}ESi!7=G?Mq~cY9PRID0p~OeoIRTNHL->{5k95kwms@{{p!SX{|-8! zT^P+z!ExLaTdg<}WaJMYIs@0@#BGKfd<1${{OWpoduM7dD5|@B|0IY%&-Y=Z93X+B&-Zxy+&Q9mYm$~yk-yNSxES^ zYr1om;M4kv{4@v#=A)h!2~knFAOP(Zv1VdshH^jI%h=g5P2RvT7XjL4VSvPnnoUD1@8x_HCf|GV0aztrK5rMSXY(a&iami2-P5KbcqWgj*{#PELEytD|3bG@k3q zi->>}(7!dq#$l^mE%-p?F|%?ayPVOyth>YD!=5A5CyLF{*}yFvI3CEfhfICOCF%Vnc;2!Qd@)DbQ&N*fuP4Ct3Y;0+5U67ot zcb7VkF#5aa*>S~F9h>?~t!bbjgJSp^PZK^Q4qy>`t+2?Zo9Mqj8BeJ!QPkyJIdW7{ z^YFYi>Hr(N!giwEF+0W#^L{P~em2XqYi5X~+cbe(`D86$ zT|HoDr>(EgdgWt*5P3@579{E)>metU_*bT+D{!k4&RW>U4T=_6B_8#Yd=cdo_5jl& z^iFA;t=-+(yxa?tG=288tuafmP(lUL4&7rZA{7PO znCI0>xLOW(%3%Q)U;#R%##gHm2{0oqtB9Ba`;;M_FbQlz1MrGh_a%67fHt20S%P%R z8%*R7&(okyh*O-bq#!3ZZ3;P^sQ;rzdjr*g;LZkc5A-}JS46*P>fh{nu{9k092{@H&+y0lRs1#8mB1AG(rXpjBG7nLv z2AMKN#*AB%$P|%zCW$g7x=wbd z3kokbJX2F?Xt;x&Uzk_PE|x4<8>QPi1jZ7FDSUO6m7O_OifrTR^70v26yepuYM;xOW8_sY%jNV$DprowTii*h(hhVcTT+}eb)UG@e)~+-;$-?=-o7De_97p zi2KKeh9gCcIOS_lwn$HpPfQ@4{a6?DA!6Os7Q6r9EpK8;GpB&%j~JOay5Cb!H|K^d zYSkKESnR_zP1x@#cN~)J6Xk2<5-FNooI0koH;O_vK3eycS?e9$Ztd*sDmAr$PmU2g zrFQ&NQ^4TU2TA5b5Oc=&8>Xgk9ZTk3egP|!iHQldqpHsBiHVCU@r?&W_&#@uI!@^v zD-JY${=7s&!a>C9XJgIrD-{M8$U-HL2qg-Nh&bW{83F*wy55>>MF5us{mRF>g_hk2 zjfh=XNWa2LpBO9Yv4LWWqX>;p1PEkla|kIhets9_<;jb2x*EXI36Cxr9^F#c`GCs# z(L#^)R1pt}*xHnGYq(|V`ZqIjY^DdRK5zbFD^cE3ll`yTrVhb4^ps+>Ovb3;{(`cP zNG_T$J7BmmtBbiAxmd9yfPB=JDr$r=U z@Ao~PV?>MdkmfRe`&0PIbIU|g=Y08K8459og))1{Sh(>F*Fmrd)m=`La1eeT?`B-$ zQiQwINKrAG&kkBe6@snwf=B=8In^8aQOBgxpF~6yS@nvdI)x=EJtal8$Nar7H3*Du z&9jaZwNlB)#r40u4|+Wle0FEgu7ADuAS^6y4>JSL<>oY9g( z(3DZW?9V7lAtqLekkI2E+vOkEGd>Pi1JgM=(rbM|w+I&adAE1yz)~FT+{UsrX19v_ z3)@M(`2}TV?DlbRFD#{g&3p6@o{_C*Ui*a&q~>(x&oQC}65NyPiDy$k1PZC@9y^P= zgy(8p>D_|%7EJT6fmWUJ75>Ns5^IZN4_=^Rt z*+$vaBgnPR^Tx7vc2)S?N<`m&SYh6F7S8s_W-rKo8|C`ZCb7C_F z&GN>q&^qi|g*M;Lzhxo>n}Nvo=;1^3j0eka=5<2Rkg%ViouPcZUdl4`mxi0$IvOGJ zRx8*PaF*~sxK(Ndal!GtCJDBp7g+jkyfZIO|B@9wTO9z^RV#w;1gADf=#b;0ked!rQlHUO3ske}5Co9F_;1$&jH*4Y6J&bo$v`B_8|o8pY_=_;1b8U zcdv{=IHjJQzW#zIfq3%=F(2g7`%>u5>NtIKJJ}f_qI^E~Eq%q0a8n;z6Cg4OKjF}e z?9BfyO^i|O{qznlpACqpJ7<>(xmLswl~5$OUalDde<@DoHI+d$qB07n^IZ?TEUvIs0I-K2nCql;iAcbL$#jpra6;57G1>yeCp5uyhQCgY@^f zTTL3hEun{qA!AzNyW;@ z!9Tsv!RLo0>VI4JZL0Il_H|^}YDf$0_dgOR1+CMS;vkChZzCfdabpDa8!+m-(on)p z#y>g#)rGGD=e7xzKLtfk zg$ES*HQ1b!TgTr`JfgjIl*hHmQuj}!q@VfJ-+cVm_H@WquD*TS8yZ@r)vTx$gS8vy z{H4d|ldlho+bJWN%i1sAgw?^{KUB|=T;?)cKEf(+EQa?0KV_T9NH4YV!>Hjda#Uz( z9L{L0;Va3uim)!XaoQ+rppZQkvq!|bJXUBYg{;(3BAh4e!J(d;{6&BArf*)J zK=IZhUNNs2)pKq&R1;#XiR5;A*i=3+CxC8ZPmCVr&{yfhE04@W?Ts89iA+KZc^bn` zBSCbUTkDLFkdacH9^PC_bMpk>vBgFGBFj4;8wvvbTjP#PkL-wg$Qkhs>nzOwidI+h zi~|k~Zjt9K-$8>DlajJ>xTXoY*KefmE8|6Uc!9604LF)i!t$l4-(AeSou{u3o6#AU z#TWSdyl*N#cg^!s+c&sy`PE%BZHP)0wZG+d{=BoI;&@9kWt*`tH7xhF`fqfchvbLv z?-cT(WQ(e&2`vGGS)EGc^l2h9k4*aZDMk`GQ?6;$Xo#jReeXn(vr~F~qmAyWYYtGF zaB2w(3X)G3D{jU>95BksIfBG{d>|`Xg4wN!`lpGLqv`DxlG0R+pGZ#c31#n- z9xpr%Nv1|dW!LYa12bHF2OtHSFzfg`6BD=i4C)Vvg-5HVNN_8ptdm^8+ zQ8sOGo3*TEe- z{gadXVVe6L?0jOpY1GjUGkr`4 z4|Y#5X&pLyw(>sKao{8V{yRa*Ej%m!4)&$lfl3rkpEVi_pWnQmI69inO!are)2phg zENA1j|8D<-F%78(kwN72rPz!Nt|hbMQYOT}9hUZyp`qJXg#`r}&o~A1(@8S7xLMoT z9WB6tZ`-Go+xV0Yr{!-6Hbhqdj?ZszU`OgLFpnTxV|#hP$EVDj_3r#=kyxU9z`4=n zd-)XPC}CF?pS;PXn`TCVRzGzl%c)-1;u)El_rz$@cWYM z=Zu^<*0(mK^q_z9uClV0c>H+(#-4!YIZh^zb$2tKk~(1>`a`TWBo+xSNO@9LL@zdY zJRi`C<^ov;+^Jw)*wIzr=-9PMtkv5sO~a}H`Y7DJ>ir?nszde_?l0Gt_yES z`t&j`qp;9H!J3bkx3|Kh0{&&tKMtL7k{VtXWN4_X!w#$qmH?DWl>AJSFT)1+3A%{6 zEI!aJBHtk^*S396A^Dz&4KHIR_6fZ}V55e%6aw3Uz!#m_Il`5kYj3yA_0D4}BERg% zq0YpRSoIrg_E`6L5WS~p`FtvR;6&jrcATA7^U}hvUnQLEKkv?0n@;Ie6^2>9xNz~~ z?j0A=$$u*GW^mR1*gjk74G=Wvdv(n&AYusTIzEt&;NW1zTLMdP1B0haAx_B|OE#nFU8(!C5qHKe@qL11jMvx5$-Fx{)zFnu>af{8rr^N#|}8g9#8J}Y`X&K^XkF` zb|AlsgHz0jZ?MJT3JitgS#fwRNr8~!(M@%wZu#}Z7-ol92e}2~R-u<23QL5~99ZRxBRz%G?^kRl*3?4!GTLYW?p|yHNRn zXP8*YWsupx2>{1ZNgSa~;@vpv121lOxNu=0TR(%34`27MU;jQhsO6YAIX>>T@Z_J! z;kK;iaad>-f|T#o7vW9}e%D zyN#@^J&^JS2oCU&1K_P^`Kx<1WEb0Wqf?Ab+4ochuHL+aR@jXT{Q?S_>IEq&FWEcn zw`Ug1LRh9{AGq4Sv^()>3r~9gdW|jNWw7!hYmSQ8Yeq^Q@ zq(+Y$R_~f4{Rzhl)=TJdTINkf=h}p3hK2d=B?_5`1K?mkJ`SBDRW3+)XqcieB7L`hc`8;eCUX{eq*kJt%y;lOXB6&AS?g{tEDaFuU*GU zkB*d)jCmV3#l681zpoBIV>8AV)2Q{SNNT&EQeHylZ{z_B0;nm%JSn6hK##M z;RS)_5X^N&_n`HcYw>Yb4y*ZT5!whxg~gu^J>g*Syukjtyu6!MxcnML5`f-i*WP*s zGD=^%WDnJ#DNel9c6f)i6Nd-`H@8A^(kJmV21qjfoP4S2W3q#RLDb#7y~t`oUP)+q zT5S5qE+?Fj&e?oHor1GXP|ryeFKT34f=PkHVy_@J7%?T~l-S>2vlOf}E`5h28hRBv zSMyLl4~6Hm7Snt*!5+6VYdSBE-u`H7c6+~F+pP!U`e7MhNP6-*vblanH%r`Om7KomTwxh zY;A`F5CU{+x{8RF)($7m$knfJOExxE1&oiHnv%cKKKaw-NXYA)oSY$-N!Zg0Fr?s> zn3Rbzj8}t$b3?T>(+Wt=fLxa*TLn?OaFkvLkTi(ZwY*OU$(yNNO^5)AC->#})E`Ex zz8_ebKeRMGzIEG<*B^&I47k2_o}YSgMI|60MD?6jepHzn!D{gr6k;?Lj}K?MYo9eR zXbIuv_Lh zOsLAp<;L%ZlI-TZjMa~dibnmiMNAWp z!6%v~gqt$hN4D)|l(zzk^!1mdB4=-y7Q$m<6s_J`9`FqOCKg1b?1|7?soe|1VhKZX ze(`PT?(R}03fYT>hW$-3EA=0bc~ts{s%bsnIssTSYWmJVCIls-`80#ornpUw574#^ zR|hB?G{3lqaH_YvqM{9%>2?ZbJBxXoAA}zT1W@{!5$s|@LurbaxBc}nFxOYvo9F?h?$$KcbK}7KPA){>`p#ZudLrJ(U|ie0cC{FAb9s9X{r4xGnbV3EF*#9k`^*%H%BbFYMVILPF5Z z)6>$d-;{l9iW_eGjOThaj}Htaf?Si)NT{I# zbq!cc+nxQVhlCeu5vF2s6vSK6s9svjK7eJxR>oHvEzbSMJ0YGL^XG8T3; zb=uq8hr-b}S9mVKa*nt_m6!j19cROQ2g_(a6LW+%BKU?mXfs|Dy9VcOAwVqS`lE_z zM)v&q9h06i)o$0sTpZx~Ykzm2nOQt3H?%tVuyyDN=!^`42C8VR$cw6 zp}x(eUKQ-fz5;WiC_39ztZxJC0~QeMr5h-ALPUtAY$~ZbH5Juy=eZ#)#YMCcRBNL~ zqeGf;r_^wKfs$J=y&2>c64KR{!2n(#FAoF5LI2FmeYecJ8Hzqj)D6#ELI-)GfPUdM ztZgjT4Cvu(n`j|XP0P#_b6vhYM?MBs9Gw=bg{5u(GYv?{d9vSQQ>o9Jn!)onh^}Bw z|1cm5TIf6co}O}hvxRnHz9>tVTHD*k&5hz}zt6jOgJWY$0|P=_T)g%V_u#$Vm~8j6 z>=t}L*%~jV?e_ih)=QV@m&CYw~Ac7 zdnnkD_yD`R6EB0-i)(h{GH(5Um|#e1l6!p>6by@%jGvy0of&+bXKSQ%>(=C&s}4G$ zwHJQ&dhe$=5%CR5=>_-GAOyp_l`xMtaNvy7@nYFs4|}?f%X}+Ue@{*+MZ4U{bLQ-% zcbKI`iB<2!(@?`Z172tuklmZGv%_`+8BaVf_hbL7#6O~eStYk=`1F*%!^W8>X9SO$ za@_ZRiY3MG8<4}^_BTD1Wq;8yWo!(*eDQ*vE`>9S=P3yx@vB%KjH`3VdtR{L#_n5v z?f9Frw(|iu==ME{Khv4!&1%o1)mLKgJlT<1T6(ZCI$gl|WOmu`fzqo`3rmpb;U^HPy@ zQ5LbQdD`Nsk)0hlB-t*D*PJ+FiMyC>jF;CITQ3o?W|}0{6pzYn8?%6k>^)0^i8IFA z+1TXBv#B#B&MMgq=^i5`$hXu%Z*00|WB;Nhz?(Ta)HbPn z*v?Rd>*N`KPEDtq?!W3jNLKnv^~bF9YYJK0aQ+SkNdtbCgqGS1+a&l0=K{fSa9^~z zaPuZW`Ce>u&6<}Y`}*!~Y)ni~lLb_Zr72>P+0-??@|)X!S8Ql_z#zjnGmO|fh?D)F zqQ%@d)bILeX=q^W+6>mkj2|kd@>EkqYfKYf4Kj-!JYqh{7cJ6V?ri8ht*48%`As((kJnCM2IhPK*w3nMYt;z*Oi(9ar)W&!Zj^3V7Q zb5a@_dAJxu`$PC-lLd*T2xo!9|(C-i?xO$&$2(q~_~9eWEKxI{XL38i;r4C>M~5{W~$L#0K5T!93p4~~b9 zJe>34NPTHrPR%g)oz$11|4MjB$l;7Q&qqYh_3Xmu*#*n`dLGf+3Cmw{d>m(vPV24@ zU6>B#bmrE^$pjR}TLB0Dx}?Zjg$``sLuckg%IhQ?MG2AF@yvIATvKzPWS2Tx%vkHZ zNYSIaooZY8ysxz@yB?+o$g`E_?P_XH=>4KQoDx<;Z8niC^8(> zWjL4#{g0U{0TLj43j5a|k`{{(fLCK>1xr_5Bk{`;jSGCmXTKn;1Fj;Q$&K<7lq<>|}gPeJ~btAh@ z9z&1%TTsh#Hj~Zpwq_gG(GdCg#DenO0oHe)KxsokU$aU|K(ie;J2vIA2n%5`z@lw? zNmkw-7Ze0G0M0w{>0XW46UlCP{3CcXSL~kbRBb^nk&$}#)>!jsVc}NEO+_Q8^BR{v zFU;nY+9W%k_o-c7aC+29Z|C~yJzS#P$BsGiBjJc=Nz6%+0B9L(W+QKS`1m;DP2YW9 zC8xxm#x4`Hr!|pA9e9pjCNbEtd0E+nx*p4V0<>3V(lqJ5uD$jZv>{*#h1e_&* zY^y0+vT|7-9Ll9Q3ZnC;p7>|3dAo}85m;c!k~9$N*`JmtIP1O~Wm?RYcd zAAq9C3BIsjaF&!sz^#Nr*>qL-?Wi@pWVE;X*s@=IFyiJmhvqM2uBCr>b?x4E1;ZO( z?%(%X8q9E?V;4Jm)MUjrYxWylgMvPLMgv(>R_6UqTb*@xAI~woFBkYqQlE!~(A%tP z($4e7lQ0}7J~=sgP*Zazmud?Ko23?d^$wk+o3n+NG5} z#6jD#bC(4gh|jx=@?70Ql@xO$_)-nNDx~EoT-;IlPF-IQU-$)V^Y9yQcx@GSoN-W5 zp3c1?t57L0<}DgW=Qs0_5+ek?Wi2|4vx1tJZ+ttmooY|HHAzd>`K?q^*ot`r8O^TB zguK%)#fxo3sHT+Z*~Nw(5H9^S@fl52jZ*tMgIw=Vx5Li2G78t96zw`8+3&jPUa+w) z+jk*Yh^cAVm(iNQ%F0Vb23K)3Bz7Q_*xE{?rcLm~C6&j(nWe`K#wJEa7hXv=M{=2( zj;*ZNtH_Tnj3`Cy;~ukg{#yCFm;0-|W2thgo9qEwiMyYYrH;;Yln`u9t<{gXBwfNU zzA^j1CBc^Q@7t)7a9~1gblw0qD#R6P_V9x^(na&|TOko1k^x)b;Gya@tS= zi@K``BZsKhd#>&;cD*H^-KtxlfXSoB;wi~(p#^8NIYJS!o=^VisQVCw{rCK?87Fb!-gB3wF16+th$q78UgENtkU+0$(wB4n z%>HzOZ|BG8XZP?>t@Qg$iy~R%FLAgEa}OyJUu+{ky7gQa$^Se!-uRFxtp4ov&qq_mu;aSn1)xUQ~X?>eoBzv zV<1C4PrAJ;Y+Xi_#_x{-%N@rzKw)}>%>QIL5P9m-D;|6b5u>|slR1tgUv2xH({t;o z%?WY7`v^y=nhNO8-tJwUQ`x+H18ak_tBD?B5v_Tb@SA}aM~=3Y$?3gc_s%^jz#?V2 z_`M{8zb-lXpA~BDZ`?UDa7i~%(Civ%yyR$aDaxz5E53*r&t*;e4hA8u;2pcRNC7$P zMT?SbK4~gS#@(}Kv@0tZ-F4$(-HjZ;*1MRNptB7{U~?j;>p#5!D|w+oG&OCxNSAOO zHOBJT42pgGv5WHNef6M291xGKyEL8GiArnL6Yg_oNuMyC{``3#r;1k0nG92_?9rK* z-zGC*(|P8iKy}U#M9vHiBe|e?Wfv7?7dgV>jV%%9 zfr5DBNSXxXasIm``y6>DGA*U;t%1Qu zfx88fJC2iBmpBu1gSf)O#rZUpb8>aX%*836jn(t%^>8*%`G+Rn?HBpvVn*@$CZ;SA zrV|sZ^P@{nKmJC#zs_&pBbCgHRN9>3x@zM3gvlH6>E>Q8R7?DX(Bl=AmdJ5i=hpI-CgBFBL&#mTP& zn%WWP;rd17B3bHBm9pjoy!~NR`C;R;JA>` zy=E~0qm-?5UcVSaq*(Nx4wE-`4$w2$Z4=yfZ+y7w=Nya`JZD^ApJMg8>pUj9pBsqI zGRlL*XwvLb2ZLC+swO+R7Ya9rjbCfNz96Boe6hIL3+qgz-~~{FTYF;@TDv!$3G6#C zPM0{S)U$Cno8Xux+OFHUwHaRMU0GVTX$fJ2x}bT;8OFp{ohS;m0F>)!Z9R0tt8yT0 zbA@xk%a}+2ua8U?cPsHLcVBba!@>@OEK?^F9+i;2DuJGb0nNm%jOOHhsnPc!CR&a* zKK}NBi-R_in(P4!1AwwBF$o9mUpIX=I++Qd_6_U)TlQ*%9BL~*IlW>$gqXl(=iu7E z1@oXLSjOTMDa*HjP)+}Jm-t<=~8$B?sIGWrPv^A z_ETc~{`pJ&Oi}kTzQcc&=07@XBfrSJb?458(|6j^lrNc{j8@wr$xj?0h#6(5D5nDb zQCX->el4Jv9&ot_5XtH{{-$c6H;RDgF7WBxq$Xr`rcdmEcnny0(Jm5egxc-F^bV?U8lx#3)G`IoN zsxBU%#>o=>tS%-x;?G;Z1e5W*t(=nJlaO?c~e&zZ2 zS@{jeqR=qab4?%Qa9bc_Tl0o2SP&N;yA2-rj0ZlNws?9lOuIPYikT)YqWoW-_0h-s zQzHB+PNVe=_`zGXM{wW^z+g%Rsu~x zFtV1$-Zr-!KKfE6^G|6BU`1Vj#Y7|17H$Wr9d^ef*obS-#WN^YnrzuC&gEJYY~GPm ziY6jT>6I+!AH)PLAo?U84S(a6Q|3(Kr#T!qc&KOA$*FU{%*)}E-rn28!gL5w!0;wmp=QOB@p zViACAFc;LoxA`pyhH9i(PTSjSE++i9K$y^~dpDX0*m{2He5Tf=^#$#J9z2alu2HJ* z(LXQA;;m94ZMNarzZ1_@#*uwZ#D_|r3KJJU+-m&9an5e-V+JO6WQ5h8G0FZ8yN2A@C_|WigKJ6e&5ueXUzq?-YspziXhLA%j~Rf zKVtw1=HQN~mT`u-IQ(m!&8+R_3)YABq0o-9=)6&8rU8#`)xf|L5vzQmMBk+1;<$3%Bwr2D%?jzoDe?DSRL$+!Ytd^C%N>c^7D5PidKesao~!UDSh>j+0&L|w zR^!|4JV;!`nZ;Knu=rN*Mlt8+;UO+rVSMMebDw`7qx=ON=9k%l|y19 zVe!`PUp-enN!lE5Vm9YYXDE@p`}Oao?R#?T>SQ}EjP1J2qb29?0VbM|$JKg)&~%c< z$OwY|Gmk3CDO2c+5;{?oOr)>_Eq3KHD*f^8WJlMR-h1*sdSc83(Q;w5sUu#pf-^!nwoY1pyIh_6jr?T;rMUUoE3`iQ9Ob>_b}bUN$T;~ z*yAx%93;SPUoXD1mDZBf^dsP-Y^A_}gkDWkGq^@U(EJgrfg|eg%D!Q-^<*r*ANWrk zSstn+L%aHmJb6EkcnO-xNekd{S|Hsr@qkhwCy&Og-}`>`wK2uG7bo0Z(QsXPNCQ11 zV^l2TH~P4)`;~NOgVIXo%lyqcc?y=xa{I9#UPp#Ax#bk&?xkU%PwuyH5m;c{%j=}4 zrytr+9nh?Eu&2M53X~{gl}rDlTUeR+62(RaCVfWw z3vX^bMQy%HLL!=H(n`6D+{^UqZE~0hf6c3RJx{CNMSg7?SsNB1+Cv6^MBdwWhj4ho z@}qe5s*rYv@cY!VC&5ASchVpIITMKP#WZKu6DLBJPV(|v0*>kxw2h!ywqlo5nwn}P zmfb+UqyJ#mi?eJ|k9K3x#}$}v{n1Oal}boiUmtkns*sSj(3{PXiX-`EIua7k*HW;Bvl3Wcx@ue@n zcd)Gfx=w95{*ucWk2qO>5z!&NRc~%bIfKz6jmSNaAI^^^3{^sTzgdJLbyfZIm;?_l%+<)rIk7J)?n>w^ngh+%> zNsAG8|G$W5A+~aR)2#A){KAcQ2(wNL6Z=+D$I7=RgW72BPH zy}d%cy`@uq`gbQZH~u2EM}*tv1EkVEM0u>bg%?Oj?SB2rH>qc_vpd&yDOeJ%gOJFUUC@xT${(C9_+F>`w($A>n6p3^fw{r0}P1Mt8wIow~T(|>Ujelk3RZ9A~p2qC2 z5m%qlZQtIBi7}$?REl`nd|8;iEn)`rV}{e{Q3aP|M= z_dm)gWIC&%{weZIXZYIuuN9NwLLR;>w|Nf7g$Z09YbZ40cYIo#SxVf!7^U{2#|6{G z^7K7&?a9f1ex~v@7S{FsgkoY;!1d?YnlJeT#kNZ^F+YC+iBz8$I&$%^S3hvD?0v1q zNUi2RttYnE&$KBj6{l(NYX%#=UQ-N*Gxn2D!7tAw$sxrF{ruridWKYLhO2uXA5CA` z;<-4mw*PMdLDTJc1W^INR)tAH+dq35mz1E}i53I`s$MK(vB_zXWZ3TT#r3^c_wGa+ zHY{vDT+?5E0I$a+);IGd5j{0blW6=o4sK+M{??pvCq6kZ7Qi!V_-nVmAW3jrZiIxc z`1%04PFd|`GoLf*ijPQ07}zmw@dQr?9j9Pj3^q9OdeKz@2-F1C`9qkDY^7vt3)x`2 zHZ*{iM(p1L1_{k0sSY1fbDsn!$LGBoJoY@}1nHKiBqRlha!5M80%q*_lQHt7e>cfU z8qNuD#!8FTg1YxQub*~&{u=ZK)*`g2zeCD^S=1|tg1`%P>M&=g7CN1RrmAa=Zp1<= z)!q~#8H{Zzi@?#v)%kA{DPIsQv6a-iWS|}U^()KU4bKR&=bd?wjfT zPb4Uu_uu5v$nGX7bu4It|IGp+3pj5h_h(4S_*GXT5yW(|eH;69s1e*gOp?BFaR%r- zIT0s5((K(U>VDZ%8S%gFp$KH)7?KpDsuI+T3^2S7kyi|E8!Eu0d%KxFeY@T*WA)1$ zfxGEXdcVC!o-NLwl!ePKrb0G(L`- zAsi82xzoj0^?|GX&vHj*_=&wb=Jb~Hy~IS(k_O&nS-}UUheSpu@>_ET7^(oziq_w2 zBvOQOu0Ztk0LiEA#dS0>?QsvjdP7FQb4+l3f3T*C)JL=tM?E&(h_$I{RHe_A^KxP% zqtP?{FWb_CE|*YDr9c!KSn6MDta(*xui&_75%v7oXYtPOewo?|BMl0FI?5uiTOS{)DY41-!?iNQa;_>9<$Q`bK zOD+mF3KHLa0cqm{iQ@w;mP^xr@T%GxjddSz1N0PR{%O7*es__w%5iuRE<&s@b4mLM z3D0tKAM>jX5}}C6YNGJ1MHu+8TPdks{cg zXrL8y>@qQqia(PfbXQP1T>}Za|IoSV92{UA*Nl(m{^aiU9#dfPAt$j(t@(PaP<*Cl zfHjM7<1bm$zbnyZlyniUteeazc7{@|IiUnGwUp=TbnxR(^8;t!tjwQCRSHDi|1^}N z(*P1^q#4?59}5fHma>}adA__F$S7VxRPAC@OybjP+ujprmtKDGPF;}b5O93|>Q~A- zn;>+oB$f?pl3Z(H>~-?t-Lfbhe7C1 zI}28+$0zKM;Z(Aap2;JnemP9TvGDmgdB7QsorGrybiMZ2lqi-35)ec1La)NonDo^4 zf)XJi2@Y~z-hd@_X=xI+eC7K%Dj(P%J~8-sVi3PLpK6f<6G>-d?4N{r7Y#@Aan3>- zbOK-fK|lWbn*=-WvzZ#``uJB}=_&)$y%v7=8>J@}##+t>t&hpQEGrh08@9U?s1ftua|RAEsnQtcPeuZF4tOy<(zYgs=WQT$0MB$H5|Je+&f9jyBiWxC* zg=*JZPwZw+4CMVvA#;oX{nmJ=b!KELh2YexLM&N?ChXd ztL=J2HpaeOz7-H}UAS1N&H;k8#H^$y>Cs)X&!!4|z#EqiNgC`sSm(Tyooe9brL65> ze<}X7hJD*n8MWE7hTk3}v7#39F(9ocQ)917#}n!lmXQFPbxym&T-JR?Wa*ljob@d@ULrKK8fkU06Ghc5hs%!y%GRX5^EhoB*W?-q}9TOmt(mf?6#))|- z261AJjcA0hp!dE7Q%{W@6aU!9{P?WIc0_S?cTKFVO|Gn<5ZRHceU5YaG#lS(D>o~? zq8NrJVFK|9Ekth>u@ihs4OU+*SSDtzi1YI!_!d9s$M7dki2p#!t_KNJzJR6;AI#K;GQ^Kcetd zUT*zvrcY8WTd58OyuH`3`%r$<$6I$~Lgwa@*4M5sO)iyqc(Bt_gL!NVHTHaRLzIwz zkL^So*Wp9VQsuL;{ID(4s`Nl2CHHy?C;Q3~NZ}x)3eU!xv;0QmGaIj8FAYVep6 zCmZMAwSOsMUBbzM9Y23Sdb^Y^48@2upGrxAx*@Nmu8tcT-a?}FK=Zk@=eb#Z4LmtT zsaua@P*7|v;H8GPJDm$6C*#q3f$b8uw3|Z+QDUtCLNBv%*DfaKkp{@NO4v<9s;)c zwSumd*}X7R9IpW$nu>S-2bmIhNU3@J#uz7onc?2spL4m$=%KaNmwzFHcZq!B&YhjY z*6zk;D;OaUvH7%+P|~D{$u*GYei}AL3jFr4l05q=rU7GX)&7zOHo+}4OeE*N0-}Nk zfAFZ`m+yNzUKV8}&{sCUs+$|emi0x_IZ48ikI8(uv?x{;O0DegAyHlH)B11z{@a0_ zmg~0d$KPRIjeAnLzt-1l`I(V;!kmx9azc#{RHPJ@&8Yd_ajJ|(OoikS1-<5s$A+H# zI?320A_(}=qg{Op3<1KJqDry2{aL1xLY;md$LFrqtO)J#@z$7<5-o>o|E3Werb;ZM zpXcSBx=YdQz;JK7F5~Gzh&9yIEopi}0sHoWv{NzGFZn0E@8ivCc?6D9J#3rsAaN9Z zJ;4A|cTj?!o*vE`@At>5UA@}WP}=`EO?TnvPYH~)L<-lx!xk|1T!!=>uky>lB%kNp;b$n@ECTSY})Q!6|2-^HgO0l7M0bffBZOIf`* zpR%$~5Tl+Q{R5f-)qT$%h}u&ZLci=fU;3@EYc$XT#97OE(CK0+XzVx?6P|>_eO0k% z&&vxJsBcr{;uQw7bp4C0J|7U(#6jQWW0)~r@r91jC+GBb?%a8-!`L#w+{lPHGYIjw zIUNi@zywmZujGW-{r!S~%x=fzLt(e*F*G_?b~RwgP(wpNk5_#bVd@U%fXxxj*i1}J zFexto;*Vc`dV=WW@Apu_G5F^7>t$B@Kxa-_^|dX`s;OSucUF?*{UaE${&5zrjD@^? zcOT5+)$%_qo12D)?LEa$!bT|^4<*$M*HmdApj2of=)5cXb+1^SIe@nV>G4b+v++0xD!nls7W6aazti zd=>^ihNJw}_Z)~QfPnLGngB&4{wSCv3S=cdXFs-BWjc?CU5hY8gnvYaWEy7>rs+LW zqqg84e)^>To9)K_nVzNVQnMn_as!RwKb9McPw-7}CMG<8K04DcemD^f83u)LOzl(e zkBC-f?`#Vba-Mro7jc@BGHEhhkxG_NE}Kuk#0flRT?~;Gp|08ztdG&2Y!!@vNiK7W z6nJV=d3`@5 zS?KcX%kA2|CE3{rL@8KIaBtoGGhBO7$+)kMb6#JhmO3=` zCFkBRUfi7}_#5HMMgNJN86CAcYtXm$?Aa%H=vrI1%55@>>Q}aEp!r-^=MSvqa;7@5 zr^%X4TWut8U?P;$yy>Z0{F8-^=EP5i9~kE5$e07tk!kgq>iSK@3~Gn>>A>m7i)NoK zxPFy=qL09J)X6`}&hFi@cmMuE%**Uy^;XV?`U11pP&nATt)}_LDo54gE12$L(e?(! zB|e_H*a*YAV02(Q!{g}+k$a?$`lLxCW0*9}R-%@Q)!4uQE6@GOb~XAquFfw9tb0rm zIoNNziB0a-(G<1e8+7~2`*Xgn2Qp2NZW|*G(~deq8XwX1Z?alQ zP!PBte$3K!;>A*-`}%gGmyDcs4{6P_-(VjaK&e_ke}2-ohgw#)M6gVQ*sb{2*I@7P-BhDipFp((HzhEY4j{jXyZ5wvv!YjM%y&81 z!a^_C;!66(qo1Vl9I^#{z}%37bab4>(**f1I6Bqb=cA>iEeETj)?V%aai!3DX`ti| z`+hg-Tk_!=!rUkh8_w~3Z!YKDxSt}*Ci&(2T&6buP;sg~OKEGv-G8kQNOt{vLq?F+ zjEVUNMM6*0insEaQ>C2Y3gtpZBh@>GM8H{Q;IQT_0z>-(OzFXrm<+~IfyvIMm~VgNGyQ2PK2t4NxhMZe zwfKreb72m(iX@3AE7bDdD|tjIV|_6T{?3b*^f_(6Cr>Q=XWZ54N;6ZcDF#Y%f6K2*BH!bKChs zuUK6@HpFb|sA*c)%lPr>UaV38o<_yR!E44c99G{D(2+F>IR&kn#TQou)ouN?ep@n( z6=PTbEa<~06Xibu?2SPV5JZf>lG^QcT``~aLY4o zd1C_-7nWINd}p;wOVb7a7QDN;xC)UdY>4kqJHkg`aTbh9dm#5`@=M;UiBxe~&A#`lLjl+9w)n_Sz|Dy<)Qq@blLR?88t8swmLCJtj+v>dD;Yg6}) z$(CxX4rJ$E%Msf9Oo@G_hE+DEsV{m{xEfiKNVR8( zibYTLjE6;-*stbeid35k&z)q)4M-D~<%o>ncq%g~JK{E0%-lS!6hiO)Kn{M5CxdneQelmk1!fD-;zv9 zObD3xiJyw#714zXJ}Z3vnw5R%e%|~}lhLF%E=P2l>noGHa}31|Dulb<=vH-J*(SS% za0jEGDciG!Ub}VA%?*bO({h2m+|ZW6&%>J+&X;vjIovq%@!;)KxsNndRlk6IVV?qg z)$!x1;X;IFRu&ddQE@hJ45F$NNcKNaYIV1R!`%4bfdf34$%Mt)o;X#Kk)EEbFhxkp z$%^Xh;@XG}@$U(Y;^u!jJdij%pr)%nx7e2PE;xAZ{dHPK z()R}R2Roz*&AHycAMJK1#_$;s6VBLIO@O>e%*4FjwnOw4Vt)8hCTcLm<$X!?-c^GN zOV`~2RJqu}(SM()LDeUT;T|K>gegSns~#Uwc*ch8T|R%oTgJAn4ShZjM8w2HHMBco z#k++i%1!Q;*hqOMy=dRP#nVCBKtrRczhW&`Y!OjB%cJU%VPVCl)Nd$dZ+6z@G@^0| z3k#dr_&7RWN`hJd5w*K9_HgR#u ztVDS@@_u!^Ow~z0aAnc<1z_|=AeN}hHO5PNVA@%y_7)aW)WrS)0jYs64BqH`-$nBV zZ{R$6ZPZfQPx+SGNiNhG6^I7~TacPY2CJT^8?;8&4PRVX4p389@5(XUZqJSxOej|KX-Qec!8euvf1Q1I zJeU95_NNqSYN#a1E<#xuiIgOvY>~ZZ$;xa9C4`K~%%0iVrR-VRvtjRD2+#4U?|t9j z=eeKpdOg?c_s8%1>Vxa^zTVgQKF{Mk&f}1kP4Gc7n=o2bt|xnwI|q`Puq%|8fSALh zFN4jUA1f;(gdKwfxd79mPX3~}hkZ+6V1>3er?4>XodSUe4_f!Bzx$Av`E8` zos}E|se?kBi45d7+Cvh)f`bDgll>V>vrHn=DeSDZ{UxiC(|xil3pE>y?Ooq>j9(aD z?k~wj8|tx#2bs+P%zRFrI1!a{>^`5eipq($MII+5~5#>O`e?VOmY-M=5k0m3|74k++eLqZH_IWv-yelE5{Qn^T@ z%wlFTe@;-4>%=~SU_zlgeO^tCgH&)9hRmJ%@t>pnnVsNq8RSkcmxW{0B!3n(dEmDZ zl@5fiHpmKLc4TZlIV$S**LRzaj2k~YU}%Km4=PQuKC$ufT*=bg?<<)1m)@G-AqpYp z=HwW$O4ypr&F`?Au%8-OsIQ2-y|Lcq?{8qMmC4i7+u%z>)UevITWP#onOT1`fkMm^ z9EnP`JbuiV?LF2P$HX%ExV6>t!-pL#vMzese)|ur^j;P|Y&<%sQdL_!24#;pA2)aR z^UvoVhZC}hHe^sfx-Nk~Zm6w&L0MS(`S+cO65y(#n>ThvOY68y@I}Mt0RarQg{eTy zp;y3rYq9$No5Gb|P1iUFMK>naF=)%$>w7(!@Q0>-4U=@24u0*A!=WX<0B@Z(e>sFFxW+?J8 z%SK$IIm5-JGm*S6_0_AR4@5<``30ET=e32Vxjlykk>pyLO$26BlhvvURuo! zNRCxQ*Al|tU%oyHbEbjXWlB<#b9rf+)7sS#wE%xP+wYeuUUHY)O&<|zk%0SvgtuHI zm$>oQccel?+`pIU4;55T?ks3^-MEEMwsvNh&&^eeQ8Tv3dDZ@!H3?v;6B2Y0n?gEh zZf-uhX6NJSNg)(4G(An!OsjmlN$b3;>jrvVauP({Q2+o2>%}_ckHv1hE~s<}$uVG~ zgBrTsrx}?e3iy=dkkYCci6E?5t)rRNu`YQM+&75ig5p{^8*u z1ChG8?CMkOR^jli!g2q4t^XcG@z79+wh)9e#c-r+pNcR73&z2{X+pCQ>{ zA4-%N(yyD4mvdlb9&=sGEsl?0NZCR#BC#491GlZCvP!7fsnce8?jY}h<(UD=rKglJ z?)1}~x9I(OrCw(SGqi#XP|NzqNQp>>ziJ zMQeK_~}8q4bQ(9m3m#f#k8EuUUX z(bI=&76&%8%`N3UduHu4UuoUVr!OS*@&!4edFe%J>NVH(&e;a)l*AM4mX_rPQg2@; zMpxJQG0=v-)K62Lr{h&jw#lOu7A^sZd80iK9K*%gS@_pRXR_W8f(aazh>H`3{(C)N zy;8Tg=l>v-U!#MwMm5(Y@X;d@8;C5dLvGh!TJU~7G-$se4Q%m46g^`ey%MzVMIfcS z+c`TMXEXEgqI=vTY$=_$UN|hA?kj9PiFPNKTwQk<)2td5fxxVr*%_)^b@TFNL4Ey~ zfMColIhRX+r>6EuhaFQ>6QMo#c4X#T<&me&-F1E@=)CKsEukbYf?ZGH*rs1wpqX_| zMkd||T8Fj}akg${prdMNMmowsPyf;43Cx6U>FC6mZ6`c`04t2A?2o{t1_9MIt9$Zy ztl*h5ADTEjt3A&e%5+w7H<7lo8ySSXO3l|J?|vsrOuVX(b-#-mx9jf|aY?16j2j9JcTl!v@`%l+lKxjAgFBnF7cLBmTrM@4V< z%b=0r;bHV(Xlm-~UkN+roiZgn_Xo25v{y_RYU!{o{-oH%LZP5^kXC4^ym!s7;9grO zFRezYneCxdMx+G9G-8^?E7fxSjSEtsqGr@)d)d1)t)>c-@)W-AeH^Pn!EIrzRVp=1?B2ZsJOrEU@S;s23CYQ004fq>nzqpq&v}`qkjpCa^Xn5p zk(_4BYgsK9O(f$D=SWE%q=Gt_S=9QAlU7@mi91tt-y9g*UWdBR+iN+G2c?&}db!v` zH6T#HZYsc{muqdU&a&5E!_WV^yu6Uj*o&ALonBATip(_!m=KUNs3)eau z8xiSW$1)OMxn`vS1%UaN%93dph945}90BXc`4qzmaAD-rFGkXk3@G12r4;AD>)q==%Qp0@Sr=*L z5(uw%<0P{Il$Ujq5OqHKI=_DH3m`*sWPm;!!-W#! z;>6`|q>0V@o8!%xSetEPaN0*wuYBv4u+_ko%nXBz5s3(fZJA#iET>>Pq#@yc8eT_lB49wm&Xs`x+)CLITMIsOFD~ z9mFm5j)JwsfgA-^ea-07>a+>O$PY@D(`?n(7pJ3ZBHQI)rYk=)-^AP5DVO%8pPHh;N^TO z8w#ZN6@V?IuGe&fEay$d?H=UNwS5gGYBijhpriTm{1bQ)H4&B0l_d$gZbEzu1D8n* zF-^uqx_2Fy+n<_5)91)ybN#7d7-`>pC{)pj+~ZbW{duN137r@S66q4R-H<#FH}}dn zkBHGxc8e2oYOCw$IBNELK#EE!HPK|*q0^t(m4z6X1dZ{G?Qz0Mc-D`ls%C#AMM7P* z@@R5*SktgqTe`(H)4Y9RTQ*nuHnbfUkOQ;N`^M`_H1kQS=8G%l-D%Z- z^6r;+1&+$B^`B(5usC}5?2qr??Gj`tAG<3F+c#S)+L$0;$TP3&&Xdly)C^b6=5co3 znw%VYU6Cep7=gD7DtHiu*oah-=LY%D&CRWk-Pmb!vs_FYC2VL~-orEuh;r7HTF%;f zkJd*4p1rQFu9>nrmmb}?aU-XNM3i#x-WwYq9wLEig0dv(=tDdV8leawfs%>td?QTN z#2a1}b~tR=YZ4G@0y;HL?#w7Ef@smZZ?}(hGiJPgE#z9-&|Adkx{)?E%+l{~6T>#u z=bWwe9tTd=P<@i8ucg=34MSk;kR6Zn;dy(CQk2@{HeD$vWb*)$Al=C8u-S3*ORfQ* zjj5KF7W|WL-@Z*emu40hOKyLA7#60spKR0fWHh~`LwO{RQ(Pwl(oqZ?DpMkFa{P*l zyu8)A6SM^-t$F+=G&bLpmPWsP;rDN>wRq&m>Y>GMcQxWMj>1gZOz~HfYYu`(p=EzJ z#$R#JlsE)lY15QeQC&WNYQkA11l|9L$jGUM(e2F4?8(XRhp8zk2dAcFO5SEBCK@3V zhFm#@VxPyJCe)NTEq{jOSz@B6AV2y+#27%^l+&KUSg=#jgE`A?S_7s$V^?f!Y}P18 z2ztx{0-berQf6B{QKJC)mv@L(l#M7>E&Uz+H&MHBqd~Um4RL`z-u;+mbYhf(1b*#- zFgE4$z^U4j756mMueV>1?bPQEgM|rNu$*Jte5=O$%Qp6p_G~5#Z$se-KF7z#W2K}%6=qrCA zpfuwXG4b)X-^#b5|1^e&xsGQ%-COjt#$#(#q19k5{?kjOv>i<>ddSh{)=;17rl}<2 zERf#d;>v~|c^7pR)y@eH1pPa<)3&uWnf%U$b=7{vJT8jiTi$?91!;|` z$yj5grQJs9Ejj=9=#_|F^ur;g{3Ri{vO?0{Q4Nj#?2jKWWhPwL(3lz>T}F1CJ93?% zfbL)zBwstC;^GF8QZxvD_h{J}j@tzR30{jI1&`<(7!YU*jmfr6BAUDNSb??g+t*wIvvj~zL6Q!n@h@qcfO{EB^K z#_I?KLcH;Z{IEY?25wf3&?=thGCAP)Yiy6UzCH%JID2}Isj3WYA)U+4V%#%$n;(LD z!j4O^yXTgF6C(j?5B9`kUp05YU<19unIBC%*5@NPdP*GITUuVEC&xZ5z-i(6;K6&q z13P!_Ond~;nRu2wc@mASJd+MN0myyW24-hw&f+81H-$O>*F$$+sJhOMiuda9yG;ob zW{p$5thD_ey9k74o}ieRrC`mQ5)wjl_BheDv%lP=WT*#khMb&e;@`v?l0gfS=D@Zs zXxRmu1h9|T|8iOfG>+aT3*XeYZ+_38H?P>~KdTrap1D}Vu3S^3lP&LSYp=@6HX-(X zQlzxjDub93AhVR@p`f_LUp1q+Ta7Dyb(wKMW1qSFB5w7dU`|)7i+*;d?MheQXym!OUp6zF2sxvh z_(&}J_9%>sgHG*L(?1+_0Ybu<1Hg5NI#SSP3<*s4OwfK(op#N9jb}OS^%hIj7)nNo zv@kd40D9HpCNP-b`Hp6V>X)sAD^tK7ZUTnrh)PSFgy=Es0hgUzq{<=z7*01uuy5bR z?&Zzozb597a&%$#(@S2d$$nW{5xRWoJpVlVH6k#EGfyptmx19!M~BMO0$$#yB%~p` zsdRF5B_z={|MtN@Ct+U_J1eV*^+-+h#o7{w(Z+~0-aGV*{*IaI0s;jvL_(;dLTfkP zXBq|{;48VVFDF2d(XF7Fobu42qM{;^#GiNGJ*8yhv*oV>HdnF*tdsUcZ|tGv}__9>7`S-VxwYBjjB}8xzRT7 zv-hl2uRUY@!kv5J5kJ|Ut`e690sHHdKfEqt?{@_Oq-yLbP&#XYf^3}q7VE~WG?R3S z!_0Bh+3y=`K1EIineOzc3*jDk>y6ffj$b%%fiTWv+skGg6XZGO+n#T!nK?@3Re{Ox zuD5p>q{V9v6j@v_Eo`d~x}8#5x{jZKgg&P&Sr^g5QbmR6_Howv=zZpyWhYI|{uT3h zv~g^P>Z!(z7lzvJBLoTBrk>_e@b?nEgw2u@FZ~4&L7L;w%X{h|IQ-9nXzr-T5zJQO zn9WzOc-vZGV=&l4Ex*+3S^dUjeioZDWAVsE6_DWf-q^P{x_WR7f$3uo`MhOOM7$71soycfxgu zGf2-t2|`v3zJ@t2CEu%3oHi3ghc79Q-#!?Ywl)}i(6Fg1F7BmSU#gxt`*JBzK{QRi zoD+ty07Z+MfB_iMa8%N9E54b3j+g0oy``_obyQ z0?xLuhVzL1@C~h~L~aI~uL`Auq(({?F1*J<2HPSIzEXn*;AlQIHM|>}lN{y-8s-M~ zNMFlsxje z(ZGlv8y14)2^}nFAXSM`4or&jP;Q;v<6Cvt);8TWaGq!ZXx7oZP>SBz*7xsaR~Mx+ z^P6DF#w=3S$xkdm2o3%koK-<`wEWKB*ci{q z-ALEq*7@iOVey6Je6wrT5CDu2#u4AH6nL?S*u<2Os2Uj1%e;fb2{535fWRj?O7E`0 zzioksZ{D2FWaCHE8vFlI+-K2!*bDgS{0>gBPl}Dm{=BD{4+K?KmWJ}NcUF%q{$Ad< zSmqy$0X9OlBKkf?n8lW6Ex-gIElgs>^6<&N;IM_;Vd%zskpT zHS%=y#GJmInyG<-EjAQ3=u=@Xkk|pUpwMS%c@IbjzyUaWIh}mL&Bo541fd#0Fxp#GtBOhwGy(utrnfWx zbkvULYnH)9x}wT=$M`KhOI7u(shr%p}aK&M=N72bpiqP3qW$kE=GJ3$+Af{CdDR_5@5*ZBdN zTL7%*(cDhB>;C^`U=5i!xeTFucy*i_Hn3rkk0Ozt~>;tx4d+Cz4@`dk6#?n&7&)BDeTA9cIun zVrO6o&&s;lbv>3@NXYI>yu{ED=ecvtrlwVzrDl41j7uSJ-|~}@k*V)#rP{J}t26%o zVt+a|a$k`hys*V{6e=ht9f5C;BIiPCvPNr&8Wui!f({EOXv8;NguOJsfB@VJJiYN# zM2a-bgIeCteZ16Hd~c8UGY#oT4TnV&U9XbsNl=;GMSiEY=9{});+`WdL2)FA56v3s zqdL@wop3}#1W8#wfz{Em%KPw{Pwy|7IcjT1LkQ`gR(7R02{-!A@MRbRjFYyZNt~Pm zN%m<8)3{sL8uoAbpcSl?rw0d__%tBdkB3jnY4*4=J~h=0Bxw|cNoA}b5LmFEm48xa zVo5B!^A0$!8bb7b^=Es~3m(VYfM-9nrWA=do7`JWMt_C<7yDM6>W!_u2hQ}CX+oXh zFP7xXlmlQ+!s@oozE?a(fXR?A6QK#w=lR+Z0Svlvrz{Z!xb7)p(W(5)yj+=2g(j z#`_&1Wq*`{Vy298>DTXCuS0b*uM%ahJii?$6B8B1Wfj{sP;>PW+5UUWyXOVP&@)0w z^*KaMK_NCJrQ0PkV`gzYtKT)_*N;6HE?m$hGj1k3$fk7Sx7YJkx9b@9g$Q+VXZ&lRnM2*X>7|i{^(VrKNQx zOt16N-Eh0KS1#YjJ1=i3h+S={F`O;$^S+!zsIEbdHx(6qhnMdo9}I+uwgRBf0zuz3 zRp&Ns*g0(LmU1*{Vsa7_0H?uS%$x;0$s`rjq8WQs@bst06JUBIiU`mD{8>hOD1nxG zHP&vLrNnWVY^x-fa6o&j;{5y{#EKyOnh#r}^i}~=J|)$DF5lhZ5%-@sO9k@AqOpq1Q zH#9Zx@gx?4q7H|Nd1wbI>8-NW#`Rg(NcUlE)kv(A$?ak_UhME! zuOJ!iv%Yy!+`(Z5KF8n$#op_gvY==L6@`hP^A;iZFgoa02xS=h>=3)2evW_ zv6n)27O-1lfBYb4aCo>Wls9GlA?r~wz9ZC{cnf=SM$PTtz9}s1ym;df&zGe|*kKR| z$IU0>f_0^mb{&2vaQod!77ywp$x~yj%RYr}^~VQf#dh!et}35xxoQhLcYu95gKErd z@MoTO-ROpQ9I&XieiI|3!|)G;lDcSUtjBAg6`Y94||4W1|IbJ1#EH zjp87kGr6j4wYXT@-p^85j}j3&1?(wygl-}bZrPtZ*2`4=@IM|y zq+|`1!=(hxsFD-x>?rn=5JoVIzmM)Ud8fpc19ak7PgPAM-lyCW~iM zTADEW&fxdC@1b=;rM9xCxuvD2)Y%bJaA9F#6LqF#9Zu)VM%CEWvI8m5nLgt9Y~n7< zwUE=GEbOA@!-4vQ-K=4FKHt2X2+@NB_3g9D(Eja@k({X)*_y)ygM?0(e3tRj9Jgkz zj0~~!A|1*&7SeQRo2RH~SNBiuzdFY9*lI70d_5%l*=r40cx`CwFVrCO+ zoos`Kt~c6`Fx;Kp|CwfSbvfX!P@O=IAb1%dRpQj47P2*4OG8S7gY)n4A2VS}LXJKT zh!2jf?V7%)PVh@tYl}HChDFqjkC`-u8QxjVYv^|!=TNy%j6wH}p^?(d)GP}=86s>7 z^;xrk0GmS`FWOrJZ%Z7cYpbXTRm=OBk`!)t*U@peQB+pUQ*Nj8>L07i61=Bi(%^78#;r(2uA-=I2ySG zR0<*(suoxcBC?EI>NNhOgnnGF01qqBGWaKfwR913#p`VtLQqz2hbNZ!k5B_r&!^eL$3CQ@ms{cyTt^XQ*M05aT1ayeE?cC`!`~9(5@+1L_s?D1>7urov4GkTnp}Cdcaf&jmA%f5R zCj4DNTgSK2)70~5=`=K=M~07Arx?K#b=MK6cfd;$uD#STH;37iOXfj_<4lT!gH>hA z29fdc%fFZ9A@j%7Ed^{o0P?$Fj*8e``_SMW^Dd~CF_2Ty)Nr{Qz zogHUqpTsyMf;ksQmhOk0lN)!ftO|+#aSReiCaPt(Ny?(lXL&5R4pEnF1v6UOa&o_# zquW7NEw!`Un461F|Gajn2nc#z5E_RISFW|Jjj=7ebEqNp)HnddE&Nir{RG_z|HUL5=RBI|#Uk4j!yc)+0U1!O@4a z9cd?^w_tWP+x!~J-9$fZaQM(mK>!^cAFoTTZY1T-A%*(_o(Qq0@8{=7Lb}sv<_y}T zVSMIXr%$WA(Yjz_lKhNqLJMpue`lwuv5{hsETw&fwrp^(_)91#){ za>cX}SaZ%B>m~K9!6neN#pbcaS+TL)*ly&x zi8dYGCI1wvL0;Zm7U|FP^K2N;NQsWlVcS9=JU?^H*W-&(TC9nVXZlr2F&oHdZ!G5BK=Vo}}eDCNBy_$tCT~7Wdt);k+qzzhrUcJAvl_>oT3Uu`sM5En~`C8%ki@N#)j=1^;Z`IUOav* z4wEiyes~SO0Ukj*Es7y0AGB7UJ!@%eivS-DW$4P!Y0gzSs+6~Hf8ieZq=JlGenl~L za%=~9&uwVZ^eXAyw=21P*jXbx5yfz!1`2xqoB~M>6_u)jLdyb&SoCS!Im|e*%BK$2 zy?-BVkyrW7D*<|&40fT5dK4)T2&Mq&vP{bS${u{W) z7-(@s?;p#3HZQgki;fc$7tSeU>%s>0hwbd_6cwMy9I`ow8rj#=lOHq8*pv7GflfEH z`*B=MjDSlqTt?ut4f03XBWF#zzlg9O8wzWtdzNk55uDxyuq(nbN4|Y~q03sKQL+-E z^v4UA0M8;X2eA<&MwhmYcIBoZkF6-Xq=}wPjg|w$f$iDZ*ij2oQHqC zS#{IfOTV=ItoXr$zJ*bg%P~I74H{)Q&j`(Vq#zbxZW!cvkeQ&|uz`Jk=FAxgYXuJU zgoYqap`~-}h`cf2&iYcbf&U>H$V=fXXQj7sL79D~{*2?W%a7#^3Pshe0I`Nj22zynO z^Iom@`1#TN$%k)5TW`emtC;6}`gCPHqim|LqMX z;0UgJ=X-W+O0)#2-;XL^rZSSi1_O{qpaycM$1qY~HZ)eqG-$p4r5OoHk`flM*+)-L zPs_dX1i~RIJD|8ffh~%kjegR%xuUA-Y{yw2a&)%fXL~9%5Qs=i?*R|f7hOB*n`6uS zh?h%ivLcif(YYtaRlHhYwS94X!lCcu>zl9}{oXqT>Y(Uy1grgg46KN!ZX*(i!=IS) z3_WWE+vF*)p!IVw%b-Re27v^n#P#;MD?i?oh;5^e{En3r6{0gKnjRT>YxIf!d?fJ- z3|t)3jIq0V?pQ`);Z43poQenr4Um}a>3LN*2$JAk{-Yeh-N!iVHnZYhrNFAR-lT^O z3tAPTCkD*t=jWM39wrv0bVT7X7$rmA&%nqiF+QHTa8_YKyjK%Mk0PmYo+XIH%N_G& zS=k$a$==Z6DJ0oO&Bs4U@DtDUhG^WMAUQ{{lpXo;lO!Z0`}YSR<$UUGh*2|mvto7i z^#g-~o|a7Gt$`rQe&-7`P}fyj4#tE%T-mjQ4Hg0Z|kxUa$g>Li-yBcE<|~+MEp`hJPaGUs}T? z$D!e7BLgk1uXx>m{P-|Dk8F(CwMf`NM?%uXg!S%_nHgU<9@&a60ArX_S_cF1Z@!>s zU|_|6v@iuLo5`e_U&^aSRit#5-9(O*^J#WyR%Ng?9drS^JmJ@1UZ>R)9as z6Hh*EY(gl&;#r%U_r8|cgZ>6SXItX_3w*rEseY3z-#+dyI{kB4FHxH@oH;3=$rPC zKsar|tB3!8UuH+i(M<$y9^#Lnhy89R+QEeTC;uQIXo#G?Nc?45PmvlFN)ZU5+U{61 zT<;EqL<1=yoZjjnu$jQd!Xj~;fPh>8x3$Dv@&3u?y1j&dZeaU@)fPg1Gx1Lo2qByQ z-fz4prv%|Y?iiWV2*)OZkvr9qzn_xV`g5=E4vY+LBbc3!z_K$1i8>B$x?uF04zEAgis{-|O#_0yZ`o9AN??^&B z{;W=xn}!eJ{{Qwq{#iBfQb>E5{&Rh?!rT9TxsZo-gP(70CN%H-*H_eQ-s)eZ z;=h)Qi~XM)4WZ}e4w%{p4+JyGwlvEIrONbH@BjLObvZrt_1AFjbq-&BONrG^-)VJc zH}OFeSNXrMaLDHW&pm-v?iXku`;R&wcdCDr1JWZ)B`0mX!Gl_&tcL^zHz( zWB=UqMB&ynq3)Z#|K0^eW>{SgGQ~gJ?_W><|8Q?_)j9sPo?6>+3jAO8tAP>mt6zJ7 z$MmkYre^Q9Ep8M71@4BXX`NTMfvT!3FK;@}@UIACTigS{9qzWa5yQlNoWEXbcJboH z^O3SgG=CQIs*%&-bqCwQ+(qxd_H&O<@G3Zb|A8qHzn*@8R|;M?;uikjF7f|!$A7gd zunr~=cs~5|o)Uim2$^P!UD+Ap&Eu - -namespace steer_offset_estimator -{ -using geometry_msgs::msg::TwistStamped; -using tier4_debug_msgs::msg::Float32Stamped; -using Steering = autoware_vehicle_msgs::msg::SteeringReport; -using diagnostic_updater::DiagnosticStatusWrapper; -using diagnostic_updater::Updater; - -class SteerOffsetEstimatorNode : public rclcpp::Node -{ -private: - rclcpp::Publisher::SharedPtr pub_steer_offset_; - rclcpp::Publisher::SharedPtr pub_steer_offset_cov_; - rclcpp::Subscription::SharedPtr sub_twist_; - rclcpp::Subscription::SharedPtr sub_steer_; - rclcpp::TimerBase::SharedPtr timer_; - - TwistStamped::ConstSharedPtr twist_ptr_; - Steering::ConstSharedPtr steer_ptr_; - double wheel_base_; - double update_hz_; - double estimated_steer_offset_{0.0}; - double covariance_; - double forgetting_factor_; - double valid_min_velocity_; - double valid_max_steer_; - double warn_steer_offset_abs_error_; - - // Diagnostic Updater - std::shared_ptr updater_ptr_; - - void onTwist(const TwistStamped::ConstSharedPtr msg); - void onSteer(const Steering::ConstSharedPtr msg); - void onTimer(); - bool updateSteeringOffset(); - void monitorSteerOffset(DiagnosticStatusWrapper & stat); - -public: - explicit SteerOffsetEstimatorNode(const rclcpp::NodeOptions & node_options); -}; -} // namespace steer_offset_estimator - -#endif // STEER_OFFSET_ESTIMATOR__STEER_OFFSET_ESTIMATOR_NODE_HPP_ diff --git a/vehicle/steer_offset_estimator/launch/steer_offset_estimator.launch.xml b/vehicle/steer_offset_estimator/launch/steer_offset_estimator.launch.xml deleted file mode 100644 index 8b98537c75500..0000000000000 --- a/vehicle/steer_offset_estimator/launch/steer_offset_estimator.launch.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/vehicle/steer_offset_estimator/package.xml b/vehicle/steer_offset_estimator/package.xml deleted file mode 100644 index 636d901d71ef5..0000000000000 --- a/vehicle/steer_offset_estimator/package.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - steer_offset_estimator - 0.1.0 - The steer_offset_estimator - Taiki Tanaka - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - autoware_vehicle_msgs - diagnostic_updater - geometry_msgs - rclcpp - rclcpp_components - std_msgs - tier4_autoware_utils - tier4_debug_msgs - vehicle_info_util - global_parameter_loader - pose2twist - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json b/vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json deleted file mode 100644 index cb2a03c97159b..0000000000000 --- a/vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json +++ /dev/null @@ -1,65 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "Parameters for Steer Offset Estimator Node", - "type": "object", - "definitions": { - "steer_offset_estimator": { - "type": "object", - "properties": { - "initial_covariance": { - "type": "number", - "description": "steer offset is larger than tolerance", - "default": "1000.0" - }, - "steer_update_hz": { - "type": "number", - "description": "update hz of steer data", - "default": "10.0", - "minimum": 0.0 - }, - "forgetting_factor": { - "type": "number", - "description": "weight of using previous value", - "default": "0.999", - "minimum": 0.0 - }, - "valid_min_velocity": { - "type": "number", - "description": "velocity below this value is not used", - "default": "5.0", - "minimum": 0.0 - }, - "valid_max_steer": { - "type": "number", - "description": "steer above this value is not used", - "default": "0.05" - }, - "warn_steer_offset_deg": { - "type": "number", - "description": "Warn if offset is above this value. ex. if absolute estimated offset is larger than 2.5[deg] => warning", - "default": "2.5" - } - }, - "required": [ - "initial_covariance", - "steer_update_hz", - "forgetting_factor", - "valid_min_velocity", - "valid_max_steer", - "warn_steer_offset_deg" - ] - } - }, - "properties": { - "/**": { - "type": "object", - "properties": { - "ros__parameters": { - "$ref": "#/definitions/steer_offset_estimator" - } - }, - "required": ["ros__parameters"] - } - }, - "required": ["/**"] -} diff --git a/vehicle/steer_offset_estimator/src/steer_offset_estimator_node.cpp b/vehicle/steer_offset_estimator/src/steer_offset_estimator_node.cpp deleted file mode 100644 index 86c76dc6f2f26..0000000000000 --- a/vehicle/steer_offset_estimator/src/steer_offset_estimator_node.cpp +++ /dev/null @@ -1,143 +0,0 @@ -// Copyright 2022 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "steer_offset_estimator/steer_offset_estimator_node.hpp" - -#include "vehicle_info_util/vehicle_info_util.hpp" - -#include -#include - -namespace steer_offset_estimator -{ -SteerOffsetEstimatorNode::SteerOffsetEstimatorNode(const rclcpp::NodeOptions & node_options) -: Node("steer_offset_estimator", node_options) -{ - using std::placeholders::_1; - // get parameter - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); - wheel_base_ = vehicle_info.wheel_base_m; - covariance_ = this->declare_parameter("initial_covariance"); - forgetting_factor_ = this->declare_parameter("forgetting_factor"); - update_hz_ = this->declare_parameter("steer_update_hz"); - valid_min_velocity_ = this->declare_parameter("valid_min_velocity"); - valid_max_steer_ = this->declare_parameter("valid_max_steer"); - warn_steer_offset_abs_error_ = - this->declare_parameter("warn_steer_offset_deg") * M_PI / 180.0; - - // publisher - pub_steer_offset_ = this->create_publisher("~/output/steering_offset", 1); - pub_steer_offset_cov_ = - this->create_publisher("~/output/steering_offset_covariance", 1); - - // subscriber - sub_twist_ = this->create_subscription( - "~/input/twist", 1, std::bind(&SteerOffsetEstimatorNode::onTwist, this, _1)); - sub_steer_ = this->create_subscription( - "~/input/steer", 1, std::bind(&SteerOffsetEstimatorNode::onSteer, this, _1)); - - /* Diagnostic Updater */ - updater_ptr_ = std::make_shared(this, 1.0 / update_hz_); - updater_ptr_->setHardwareID("steer_offset_estimator"); - updater_ptr_->add("steer_offset_estimator", this, &SteerOffsetEstimatorNode::monitorSteerOffset); - - // timer - { - auto on_timer = std::bind(&SteerOffsetEstimatorNode::onTimer, this); - const auto period = rclcpp::Rate(update_hz_).period(); - timer_ = std::make_shared>( - this->get_clock(), period, std::move(on_timer), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(timer_, nullptr); - } -} - -// function for diagnostics -void SteerOffsetEstimatorNode::monitorSteerOffset(DiagnosticStatusWrapper & stat) -{ - using DiagStatus = diagnostic_msgs::msg::DiagnosticStatus; - const double eps = 1e-3; - if (covariance_ > eps) { - stat.summary(DiagStatus::OK, "Preparation"); - return; - } - if (std::abs(estimated_steer_offset_) > warn_steer_offset_abs_error_) { - stat.summary(DiagStatus::WARN, "Steer offset is larger than tolerance"); - return; - } - stat.summary(DiagStatus::OK, "Calibration OK"); -} - -void SteerOffsetEstimatorNode::onTwist(const TwistStamped::ConstSharedPtr msg) -{ - twist_ptr_ = msg; -} - -void SteerOffsetEstimatorNode::onSteer(const Steering::ConstSharedPtr msg) -{ - steer_ptr_ = msg; -} - -bool SteerOffsetEstimatorNode::updateSteeringOffset() -{ - // RLS; recursive least-squares algorithm - - if (!twist_ptr_ || !steer_ptr_) { - // null input - return false; - } - - const double vel = twist_ptr_->twist.linear.x; - const double wz = twist_ptr_->twist.angular.z; - const double steer = steer_ptr_->steering_tire_angle; - - if (std::abs(vel) < valid_min_velocity_ || std::abs(steer) > valid_max_steer_) { - // invalid velocity/steer value for estimating steering offset - return false; - } - - // use following approximation: tan(a+b) = tan(a) + tan(b) = a + b - - const double phi = vel / wheel_base_; - covariance_ = (covariance_ - (covariance_ * phi * phi * covariance_) / - (forgetting_factor_ + phi * covariance_ * phi)) / - forgetting_factor_; - - const double coef = (covariance_ * phi) / (forgetting_factor_ + phi * covariance_ * phi); - const double measured_wz_offset = wz - phi * steer; - const double error_wz_offset = measured_wz_offset - phi * estimated_steer_offset_; - - estimated_steer_offset_ = estimated_steer_offset_ + coef * error_wz_offset; - - return true; -} - -void SteerOffsetEstimatorNode::onTimer() -{ - if (updateSteeringOffset()) { - auto msg = std::make_unique(); - msg->stamp = this->now(); - msg->data = estimated_steer_offset_; - pub_steer_offset_->publish(std::move(msg)); - - auto cov_msg = std::make_unique(); - cov_msg->stamp = this->now(); - cov_msg->data = covariance_; - pub_steer_offset_cov_->publish(std::move(cov_msg)); - } -} -} // namespace steer_offset_estimator - -#include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(steer_offset_estimator::SteerOffsetEstimatorNode) From 24480bf40a16a8aa99506b3b5eb73f2ce07d7ce2 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Fri, 7 Jun 2024 08:49:40 +0900 Subject: [PATCH 3/3] fix include guard Signed-off-by: Go Sakayori --- .../steer_offset_estimator_node.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/vehicle/autoware_steer_offset_estimator/include/autoware_steer_offset_estimator/steer_offset_estimator_node.hpp b/vehicle/autoware_steer_offset_estimator/include/autoware_steer_offset_estimator/steer_offset_estimator_node.hpp index 88bec5aadc40a..4e03cbe0162fe 100644 --- a/vehicle/autoware_steer_offset_estimator/include/autoware_steer_offset_estimator/steer_offset_estimator_node.hpp +++ b/vehicle/autoware_steer_offset_estimator/include/autoware_steer_offset_estimator/steer_offset_estimator_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STEER_OFFSET_ESTIMATOR__STEER_OFFSET_ESTIMATOR_NODE_HPP_ -#define STEER_OFFSET_ESTIMATOR__STEER_OFFSET_ESTIMATOR_NODE_HPP_ +#ifndef AUTOWARE_STEER_OFFSET_ESTIMATOR__STEER_OFFSET_ESTIMATOR_NODE_HPP_ +#define AUTOWARE_STEER_OFFSET_ESTIMATOR__STEER_OFFSET_ESTIMATOR_NODE_HPP_ #include "diagnostic_updater/diagnostic_updater.hpp" #include "rclcpp/rclcpp.hpp" @@ -66,4 +66,4 @@ class SteerOffsetEstimatorNode : public rclcpp::Node }; } // namespace autoware::steer_offset_estimator -#endif // STEER_OFFSET_ESTIMATOR__STEER_OFFSET_ESTIMATOR_NODE_HPP_ +#endif // AUTOWARE_STEER_OFFSET_ESTIMATOR__STEER_OFFSET_ESTIMATOR_NODE_HPP_