From f7dd6dec9672fbf933f75d570ca72caf73966091 Mon Sep 17 00:00:00 2001 From: yjuav Date: Wed, 1 Nov 2023 15:01:00 +0800 Subject: [PATCH] hwdef: add YJUAV_A6SE_H743 board support --- Tools/bootloaders/YJUAV_A6SE_H743_bl.bin | Bin 0 -> 17764 bytes Tools/bootloaders/YJUAV_A6SE_H743_bl.hex | 1113 +++++++++++++++++ .../hwdef/YJUAV_A6SE_H743/README.md | 267 ++++ .../YJUAV_A6SE_H743-pinout.jpg | Bin 0 -> 182419 bytes .../hwdef/YJUAV_A6SE_H743/defaults.parm | 5 + .../hwdef/YJUAV_A6SE_H743/hwdef-bl.dat | 51 + .../hwdef/YJUAV_A6SE_H743/hwdef.dat | 241 ++++ 7 files changed, 1677 insertions(+) create mode 100644 Tools/bootloaders/YJUAV_A6SE_H743_bl.bin create mode 100644 Tools/bootloaders/YJUAV_A6SE_H743_bl.hex create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/README.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/YJUAV_A6SE_H743-pinout.jpg create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat diff --git a/Tools/bootloaders/YJUAV_A6SE_H743_bl.bin b/Tools/bootloaders/YJUAV_A6SE_H743_bl.bin new file mode 100644 index 0000000000000000000000000000000000000000..4c4ab96f0449ce0d12300e73308a76c220e7cce8 GIT binary patch literal 17764 zcmdsfdwf*Ywg2AdoO$E{OfpgO0_G7k5R@SSiDG3k6HY<~O(5DL>g`FQmouO;zFKU( zmjR+ivDYBfMq+P~_&{xepy@SWItXZ=wliRC2zte$4k21kNMKGL%=vxynF*rpy}$nM z=lA>Pm(ORj*V&J?*IsMwz1LoQ4a7)nA9KWf@*hak7yM)G7_JEmiTP@zJCHUbbs_yD zV_e*(?|;ze;{FW2-u;h_+x-u=`zHSX$@dF$|CXk={x6Qd`S0NWpV0aLLm%!0QHUCk z-uuh>mBB%C(^dF41^-^P*etov5b_748_vzW=Z|LyHA|tv>L){kYo25^2hJ#{XMOpmJpPuN9u6aQeQtTY z>y+{&ac&&UXet!9qYqVP#p6+`>_1OFibn}4?I6nWQBJvS#2|7?^N1jZJ16;m>d6Vy zlAn6Y&NR)-3<)BcP78>QQ*IndZzsz4RigalJW&>m6^cZeI!u(iRm^Dm7g2-QA0;75 zOnc108ynp|VB?p2mY12kOdVxsGI`EUcm6^ZTtqRA@q2Dlh0)RumrmW}N?uNDr^?H5 z;=H7)dgurDSSzX0f-gpU<`SoDZFkCafm3P#)BvbKns9y5+LF!&`G=jHjVQkwD|R+W zMQiyYQ=~yI(#u{S1E%{Lq|z?Nvrd7So1DZJ1Z?(Y2l&GDo{vru#cbfr48xD!WdE*x zlk*YB3Mo**+OhU(M~$zhDqqZz=^Uaw6BJ6ec+^O}yacj$pV=Jr`C4UufHd%DNy#=( zP-zN6X39IGoK1`UUR&fN_M_@4+adLo<)~`0A5twDEI+D#j|x-hc1#5!(XmfNj#5 z$T+6)oZ%tBL!1ZIn&R=&gj63E*;=(#s9l6`W*d^GQC*KoIk%iZznRW%+4H*3=Fse< zId$hxWujQe+N-Q<+d8RzPi01cmlC)V`ti(p;(S%tkC&kzP55H^L0YZtFZsx}Tu5pyv%Wl;6cOdJ4NOkYkMPZWD=9j2oYg-# z%D37VOe;FoLw77woysv2F@s|BkCCPW9#5C25OXY*m@|;>Luy5O3yIYqP3DWzi21=} zzsCT7in{S{)@K~of0eT_nGW3?Cxvchcs*(5?1r8D2FN6HC||^SD*1()g|$>SvN;Mp z4-nvT2kk zO{15!rzvTCT9G+K3ba^iyb8D~D&LKgD_;mFYMzTQn$Dg#iKMVK3_f2*l&eNq*@F1A zkw;WF_L1wb_v~rspK*)ys^z>+^bzWED=XIv^9HdeIeh!X>%=L6X};T}ouFvp(5<@@G_4!@&TdA* z$oXQ({kh>i1H`PIyMA}J!kg9&E#5t;%G__@pOUwD7M}C$e&cL#-NM*)yEA=nETUVS zA13(y$S`zg8=0w{o3oqWM(5L3UZq7}U=L(_btCqUZ|*w++k24GSv}HkK!IQ9%fg{a zyQf`|(ew6zjZ1xXy26vj#hyjk<%J=SNS`7~{RrKr+1FJPW#dTo>7D#<1|Q`fT3jen z$a2Go5u9B(bk}a$YUtl+D2cL}ed|0c`(zjP#$g71w2NH+h8O^^_It9AO`Dz3liEs4 zCWbFpcs}zLYk93|yVkJ9Eea09%ffu@(W5~z8Z8A+>xT`^XQJ<_SwW^fL@6BRqQrT- zUDzpL^vS@!ZfMUgHYTr+`N}S#1#1btKD($LueWhjJ-3x{6VRVk(n2q{E4r;clQNFC7EkQUpaw_gk@oS?Tn%y^U* zHak*ZX1m3^D7z-icB@oS@vC7i_S9HDcA`f|tb6pc78+KxYh1%F+r_w)SZ|Fg)Bbfs z`8ri=#)7)UF4?8U?is^5>!QjXBL;A7=7=a>3!Z;4{NkrZ@rKXXild+H6aV$I`Qk&L zF`Z$$wfzxF0u_W@(Wh3kGtMYZ5J>?y%EvxZYl2A4EyKk1-I2zT75OyW=E;oQtQL@& z;vA8ekE*sk3&fs^hdri<$wzG)RkFS7l=>ts_#{eZjfSg-MgmlsIznuN(f6Rk7L1pL z6zC8{jP<>;S<}VBP}y|js6nAh>d5VRXCndZ@Wg5A;6!SlFkm7-QcW%`wnwwI|5P=R z#93dhXfD_ZBo$ILcWANaw4g%CfxT`I>;qq_=z2Y8tn3;@>i#MwUu99}*G&{_z z)&tgJp%7&)Lt7bbzHCNOh*-$2IX+s-JIv*Qjw$kF-`j&}!WHRLn_l#!MQ)W-MSAT9 zk5!y>Bx{(ixuKm?>FRS)dJR8d=0A_D_oRv3ky#G50|^BwRhKsH@(7U@Ph;rmwJ2Ln zujK{=ZZNVum+^&-l@EUQl;Mmi6e0#+wGyn~Ru`zCg<}!kS3MLgj*8*0a~uy2L(=PtrSoR*F)9zOhsTMyqzONOHs@Sc`h zIxNF<;ez(f!^HiphmYj8(>e5-p=d5Ev9;t{x-8;YlovTMoSQjJ^T>>mNT7l%=fy1^ zE{xgbjYI<#SPR~1*Jp_)u}S=~T3}nY|06Zf{OoIhT}7R2%~p!D>$TWP4JD*ZJTPG9 z4E;f}!&4Y?i0|)xifFOjtj_g(-sJMB<;~@v>^-;FeC5Mxfpk2g#qu;#_~(fEMA0g~ ze*?eK^QW*D%Rt%hBgBUFvys|HqfDNhFLy0cfXQ@x{gig(F3G*#hIReU=nRqNe;vI- zW~WHE+H5Emu!p6l+D~WP;UuoAHGl}gz4>5m$#MaE4pefxK=t#d_5T~w9_uZskX4~eO5Ke_< zn(fFIwb%+xkf?}q(se2TEJyY+9T{J93?IYc>PRg&U%weWGgP`@x!de?4-$bcnB}%A z8sB)jhMbFh8Fh8pHoox%Cwt`#FO~TA>s~q61628_Fx3y#962^tiBf>xy zc8=;Ha&PKlvXv+|45vWP$h|3xg@IDSN`5_TsxtWw_f2+kd!R3&9?(*b`^a+^VlKZ7 zYYzCx$7c=vL#~d3C1gf+C|#sQ84-uC#WNBAGV9x;1U<08VL@B$37A>nmN^cYzx%Db z`2J;l<3GPPdS^P`%yd>RRU z{0U#5;*8k{yDf%2`x231ey>lEuF^3xyj|xTfVbfSUVe|#HQ`vXxI2$-)?&NP(`T*` zPsnqCd#8@OFUorD0Q^bRf;B)24%Kn3jnZ2ZSI5^M=!1`;&yZp1GIxag48>bKG_pb7 z(78dT#T%p*`JTF*0I`SrgyL2d|V&~x~Xbs>FEQk|DCgT_67uwt8 z9e%o?O{&drtGi^a!@mXnPRea{C;e&dHnF85A*VvobYhOaliUPb|1Z4{qj#X|ioRGi z!!=oK5yNVJGi0C2_z#UpyF|RBoml`j%%)7^MX9q)?>`Uy2XJFznDK~sI7kFJVn#O0Mz2BN(cJ566)mdXXgsR-fq$L zhDl9}tv}CUhjHG|xXI4c(vCxZCXKvK*jmu!7ql57+iA7f&mnDNuWbtU*gAG*XtAG! zO1r)}Cu@g$H8~r+@jdnV(p))XtuP}iLLcI0WJGcvq|VI8Ho2{^N$AT6SRgI_0z*7j!gM%SyIbh>Q{XV+pbjmd6}Lh1DH<6bq!#&1+_tYIaIbAQd7 zrCpW|Y8ONST9l2m!1;Z&a3yqsdGHulUW~Jz)4xxZ2Q=FhhJgY*)ofxy6KX=u@C5OS z#M_FDk!E$hjX3Qy`JQPrjXjL}j+vv81AS9U_!E4UXQj!pVdbHf2|IQ!?2P$LHaB%& z(3o6ZHj^*Xn2ZP+SR&X&s+`r9x6_vybghOS7irG{mEYs)q62BX(ov&2rHA)0J&w00 z_$l;1Y;sL8gX$OKqp}gRxy7F+=e5&js!Z2t3;!}zth(&^)`Xqaq9%4W19tgQd4)ey zCNs~5^B$)QtnPt`Fc9QUV-L2@DaB}Z_vho|Ksra&=L@a!vIm*9cU*4u-zG0=7wl5D z7L((N)r7I)Y&U&9>8C91Vlt%4@7|zJw}aR%*b#~9TA;;V9wE-deYAwh;ckXXfm4${A#H;6U(+0cepsFjVqQL+H{YT#ztPnF_*%IkDGunHBA{mA`^{4MYE{zdDZ(EJ@zgQUDk zmFj(jjJGi*+uZIqe67vfXcOoFrPBqmz`+NwTGXbRbeCHdZq;IQFM&C?WWTe)>O=z3udDPs0l@C?76TtSpG!4wC2*w{YH@V(bJ#i_;a zN?KdJ(XCh|ys{3qBIk6U;c)&F%)_QYx|lx;kL5} z8fZ~-PXq48Xlwf?d8@k7^19mS+EYOa8^d0?VI?oOt;|I~%bKgg?sJ@Hi)Y=?+TFMM z8dh@7ww1(r2=ua1*1=cA#$mUL=aC=on{v~qE7wL}2M^h36Lo5sBp=7V@sOI}Ak{g@ zJDmZh%~MLAjS2&s_=c4fc%5s7B1kQ{}HJEfm5WJSSPZi+tOnMZOliUv#U3`b-FB zV&2XASkeBqaIVoNa_AKs{RLW`8hzzLtFybtTWt^LC0qSrbQ@ZAjs7H>bwS2OusxZ^ z!Y`-KpzpKW+Aq0K`;`W)h@bx~?Lzriy`=a_*!;_J7Stf!h*X-?TT*mg*tno~@1&V? zdnOeX`8N@R~i)$Dew#jvSKn9`6_(Jj0J>-gH-Ig0G2DwAht8 zWvRL*Pdt&O=ZO}?X%lnB98jNnVNW`=hHq!9D;iC#hoz&5ylnLA>*CMY2Q5ijvx;Uw z?~Fx;Fzv}}w{)c};EG0j68+{R``f?KKj*|HMSYPpeQl0Ylc44Oq@TVwdISnJrj-ekz%W~LV|A?w$R~_!FNnHKaeeRa;=mrQAdx& zJrIwr*jHJ|?#!-^4`pBeqd0*kg^R?LDj7GY8-|%~oYdHx1N*KS-sv~t#L{BNwBac0 zH$0V?1^APW%gxxAT0C1r@bTdEWOZhrr6XVNksZnLK9C#_Xt96OsJ=&9-0@hxK6Yt` zX$i#+Yg}xqbO!E_sIqO0!)jq`ius!M;7%?Mly~w~OXXVmmfRN4Xb(8X{5vN$ zNu1MMXBIbY2vls8+n8meX3gUKUbTFd2miWfrBr#{SqXCq!Udlm=pQTi-`f7531 zsI$ysxTfIUOs5?_yW?8dDKl)wI@nK~@3`DjH_4{OZVj>egv_Q^Lp zOLLbIeXefz$k~vARq{##YJDMg6H4%h2fvKrT$z(aVbq&BH5*zrDx>FbGId=k5eTxFHim)GEbdR z8cMY@Pv!(M^)e}kDxZx~<&UF6-U}YS=Yf1dyiy#Drd}x=qwwjlQ+4W_0h~!{N0tvg zW>zbyrek&dfQ4?5fC=Y!jz3GJQl*q#w=4Tw&f4^LwJ1eI! zGz(a{V>6(Ct(t@Raw`*U{#EDya^O4A$2;L;dmV49J}>z5C&hVvUguC-odq`lrwED9u9b*`lN`8T@sWhpP`!VPyk1T#-vTYXdeq_n*#8vh z+2Q%*SO$Ed7I#W6{1PFe)4=>2AE|E!%>x$GtQ&e%3+#YtqdjWA`xTkb!&`YzRyppX zDczvsHz;Lm@okkfqowOL-1MlDJ<2=?-F^I=LY&qKom%ZDMLl7vjEt=EZ|@gUHi%V= zCLG~xuvbQjBhl9!S*lw?3hqpWq0C%I`I%^De@e;>u~aM#Re@*y@s4P+Z8)nOqZ51X z%M$ZiKxcoY`y@h)hx(erdS&n9O!pGn34NcD9_D8VVLHQ9nT<6asNiQBdJL7M{~+24 zm1v7H5-Rn=F9mz}bF9xm$F@BN(G2^IzD$&ZD%}~6wVwCp6URGyZy^@(?LIQs8Q`7V zTtTJR(pMvUxw-%5p*^{{PgvpCq{S#t7gR2PAZo^akL_%Hr50NZdor=hkr4CGCG7TT z9Gz*>?e?^pe1tfet$xXgggtML?7=Bn)XA*+giSB>Xfe}1$ISllNc5Zb`~uK#>M+ch zj8lp#IhXP|Imz{HsiJn;4B!3;ZQ<+_s}<=3WlW{ZKYVw~pj*t^V2kM~RXqVZ;; zR2al`l)gVUYwM)`{whNNcLRwytkrs z9&}-KS9Ce_OP@1x35lEOKbr&g_yxPhkP71B{P-G0Pm>^4>%!iyLyW4RgU%wHFwH~Ks2%0=dm4B!~- zwCH2--Mz9$adW-s&BiixGc2s+5OOW{hGxV#9);>HSPj){%w6L+ClziB;l?Pr1%2HR zcqDKNV86mDnp9}+NP~WUq2Z0Dgo7^)?+>nxo?*xkblJur$4P~y9R_hBT5Zs#Ezx2> z(wGOvRM=2=Sk0OOk?jcDX-Mv3)C_v*8o{2p2Wh(&yG9fGu|F*0F%vCzllDc_=3u%+mE&WUPTM@&TqRm0 z8t@7{O@1){!-#;GlHrJ9V68W=GXDnLDyHT6N<-PuFO@G29Yb8hR8USelk`HrkX|AS z1NoHQ9!ezVv|}m>OjZo0kq9(#_9o8~mA4J)5gc0VRGe|k=CH%_Q7D$^?+Yc^;ajj$ z_J>QwJ<%*XS(c7@;q7&qg(ZAjI?PL)YYW@+ph?|v3X23cwxY4H4Qs*z&VBK#gwAl~ zCf||0uqJU{Te`~g$zHrJ6Bb2vV((CtglgPm`9#=P`D+RU!+ZH_@>k}sDIX%``72YG zaOF<<$X@SI@II$x@-Yl9U_gx3Eo84(wbketSo}yOx18ZIbx;R(S8($%^8n~^MON$w zTI`Ir-2)3&ucceH*gG2YOwn?-QjESPk8qShEaodvaY((Dv$+^;EG~tI{gw->>WCUH z$dv*W3R?$mZaI6m9MCwt*c})QO6D$B9_Sdyl3PXWh=R!+|E~3W_1Kv4@A251WW3G& zh_@l*@iu~yisI?@53qO}Y1!A~Z5W>MSRI|(E=D6epX@$IrK1WrW6%7fcHdi5d-HMf zDLl8yQ_5lx?D5#0Bl%S4|o2&1K`>1h)-iN zY2%5}XTr-%kHvnP&_l?Ns>JR%O|S>BcqlRlD;+Wnz-M0IB@XD~ynmO4evfr2MQsWx zH1x9EtpwfZkpeg^S(cV8OQXdN*-v{A;dC?7Ehmmt!|QQa%`av4+GCWxq|iFv-)bCt zFB7_P_dfXU@#Ykd&CybPht+168UJo|nf0>EHM}sP%&3=Hx`vp%iP^mq`)jkvV8Q)5 z;6MjF7op0RLvn`=T*mGn~CsPM-7rgBAw{xU1(Ot*%9DU{xT$iFbgl zdKFTOc`ZOqCZxW=s|a35e1QvZYf2f$kk}b-gk+DZ<{w^T!rt>kbNBnuusqmQjK1UY zEpki6h-sQ$dfb%PZRl_0kI8@N+~lu(e1*JsR5?dRFLgZLnJxFq&7KKIGIJ00k%EMk zY=>Q_#Wrb;u=HVPuE&edh;U~0V@}uaGdDs9sP~XMHygV~r~689+h&t&a&GyRk2mJfYhNEdH{?Ej*v+uKgY$^3 ziE$oP(RTnYAP zbAlhtu46aCY$Z5p3i{72rI)?vF7ZqbGp^FP*cECRrcd_HE(bQ7pe~Rwvr~I3$g=|DL2rvFw%}xpK zeXTz@>10o{ydBYEH><*v;8SpWe~P)K{EY!&(%GKu^0e}1saE<;l-Yimca0$4?SIuj z)qUwuaQWSJd>CU^$7AxF_#fP5-S6RkLoUbOl$z3Cp=&*l9Tc|a>+sz8DURyfcoATe4(G?e zqc=y0d!9LUYh(C+J0yr_^Gx61c6C-Yk&jy?r@kjB$8plU`G`CeB!HcT%;1LH z4#qPZ)-9PqX67?{Xog2=hQ&i>B+5pQUoA3DYq3X19T()|OvXYUU=B2nl&b)<0`N4i>A0*0FCCdW) znSH=^Exx}jBf@stA!2J^?xoc=N#|Pk#IM_J@%k< z&~Gi@fT#|>t{~)H#n;7Sja>=;1%LosucH)mzI?)|*Z^e^AoN?uYSM9pV(e z=q>HSNQA|W9Fh+rPUMi}P2%(F_`G%S!_@Pu6R&28*b?R`dSumgxU>CUGl<#kkKnry zzLB<7e^~`@!!27pZS~wywz9gDp4u;gpY3Vmu_P>pi0#5;`YX`5!ae&DACeMb@gppb z)7H)+MA(_6KKWi>YUWG*hO}k5TNV|Dwut)&+>`Q-m59tbVZW2v?D6XUkhWFstK9S4 zC2jTSff%F2_&?TIj7gWL=Lj3^w^5h4LOdV)WVCJ7Kb7BBeoJ{yAAce2X>oMGJ7S<9`1YhW9 z5%X_1i_eJT@jv9U*Tk1rRd+7dCAJ+BV^KD`kC{o#bWQHgexvCpIQu4x?%8?A3uYtVMA+K+hUst{W^7=HI;Pd1N z-hSFQuG-WtENIQ07`94>5FK<#I^@qS-w1Crms|~u7ZfsJl7N;gk91Ps@>TdkEGq66 z_-)SehTJ;N(aU6|mr<1IU#LghhVgRUf7_AgWAD_D>{%{N6d$gq4Ma&BW)}Dh(x>%@ z`-Bp9H#*!$$`AJ$=V`IuYDI`L6$a)~n|Qd->5{7vTU&K>Rkk-=&uC(PWuNSoHpv^M z-^+)jG{3jb=jZD;`MvdNc<(|RyqjF>bDz=fSx|XYZL+0eZ)(DAvdQKc(&`xJvr_AS(fJ*@%NWwP)-j{>}fL~9-PXOMP zgm(honS>7m-jRe)0Dd+Jj{$yK^HES$(euNhY4)+D^uVQ?J6 zt)N|>R%LU}|m|cIPipL^vLO&SpY>xTn$(MsE8x4!)lB(4X_#&$s zHsTkA37<7;za%GIdK6CmFDLjWRvnY=LnrD|gp~ADZ`xw!;~Zl#q`3W#+06J2)t+e? zav64&49Vu`{r*PPL4X6a6Mn>S(;t8SHf};ET!>y{JMTo_Ei&#r4O!uVzgn&V6^*!e z-zQ&tvM$AUe6{nR8$m}r_Svwd-H5xorOV(Ojk11-mDhbyjJDZ$gDXbLNJg`o!Hw}~ zRt8(_>5#r<&e7FgSb;|ye(gx{ZL5cF7x&f^$F{l^4ZV12p^g=G?4(Qb1u@`kO{G-9 zv+F-9r@4>qZ8fbqjak*1x)auSJQhy+^&uy;HR{sfpl=CTSO5v|*a%5~&Nc8UXmi-_ z(&`oB8UI}xcM*J4ZNzWf8sQIW#4i~DL8gtQXN_CY-0mTbxQ9N%ZDJkiS=qD3hB6z< zY$&rO%di^An$zx@HK%K8uo?*aJ}{U{#$o6l;AY_0b6{^qo2@9@iZVS%*;bUbpsWRD zdXBOdls$p6Cs3y6D0>2B&!X&Els#)eB9w$+vUw)vkzE%bOOcyF$> z(3iU=bI83;!0$1F#knidawXGo3LP(n*4LQEx>@gBf2LB(jYg*rRXj^QfKm1d#+W$B!{3rO2;YV1iuUq(c z$pNBp2noV#Jta-eW{1s98n_f%G0|ZDFfBxFg!$&ECBXr&SzS63;;46%;zZisWQUKemKSc1LVWQCVMgRv%~53Wq93ZaSUH}vNKnUwc+>7 z6V&suijniNX=CSO10!1O)3HRGuKk1{Hnb{7MEqXS!9J3~;g=(cw>8Eu#9dy^l{dqZ zBsRkdel30-QQhXD;p{xTHMq{;cPl6EV7cN{#l3>Z&+4GCn zj(^Q9nLU3VOD?9_D+q77nNZtu!rQ)0$kU+ZzxaFR5@LQB=`EyRAax?WfV3IuUy$BK zVqM!2pZZgzV@Pi!MUc9XUPk&c(x*tQ9TuJb*8nm0oj8Do0%DZmzni z?AzZhyQ+54cPr=5Eg`Ns#U*p+T{XY->N1bFe31w=`roIy;O!J*UW^zZHt$)`50==R zu0o5@5^!NI?AHLL$Jy)-DFS=wLXTZdeCI9|jKQ USB (OTG1) + - SERIAL1 -> USART2 (Telem1) + - SERIAL2 -> USART6 (Telem2) + - SERIAL3 -> USART3 (GPS1), NODMA + - SERIAL4 -> USART1 (GPS2), NODMA + - SERIAL5 -> UART8 (USER) TX only, normally used for SBUS_OUT with protocol change + - SERIAL6 -> UART7 (USER/Debug), NODMA + - SERIAL7 -> USB2 (OTG2) + +## RC Input + +The RCIN pin is mapped to a timer input instead of the UART, and can be used for all ArduPilot supported receiver protocols, except CRSF/ELRS and SRXL2 which require a true UART connection. However, FPort, when connected in this manner, can provide RC without telemetry. + +To allow CRSF and embedded telemetry available in Fport, CRSF, and SRXL2 receivers, a full UART must be used. For example, UART1 can have its protocol changed from the default GPS protocol for GPS2 to RX input protocol: + +With this option, SERIAL4_PROTOCOL must be set to “23”, and: + +PPM is not supported. + +SBUS/DSM/SRXL connects to the RX1 pin. + +FPort requires connection to TX1 and RX1. See FPort Receivers. + +CRSF also requires a TX1 connection, in addition to RX1, and automatically provides telemetry. + +SRXL2 requires a connection to TX1 and automatically provides telemetry. Set SERIAL4_OPTIONS to “4”. + +Any UART can be used for RC system connections in ArduPilot also, and is compatible with all protocols except PPM. See Radio Control Systems for details. + +## PWM Output + +The A6SE_H743 supports up to 11 PWM outputs,support all PWM protocols as well as DShot. All 11 PWM outputs have GND on the bottom row, 5V on the middle row and signal on the top row. + +The 11 PWM outputs are in 3 groups: + + - PWM 1, 2, 3 and 4 in group1 + - PWM 5, 6, 7 and 8 in group2 + - PWM 9, 10, 11 in group3 + +Channels 1-8 support bi-directional Dshot. +Channels within the same group need to use the same output rate. If any channel in a group uses DShot, then all channels in that group need to use DShot. + +## GPIOs + +All 11 PWM channels can be used for GPIO functions (relays, buttons, RPM etc). + +The pin numbers for these PWM channels in ArduPilot are shown below: + +| PWM Channels | Pin | PWM Channels | Pin | +| ------------ | ---- | ------------ | ---- | +| PWM1 | 50 | PWM8 | 57 | +| PWM2 | 51 | PWM9 | 58 | +| PWM3 | 52 | PWM10 | 59 | +| PWM4 | 53 | PWM11 | 60 | +| PWM5 | 54 | | | +| PWM6 | 55 | | | +| PWM7 | 56 | | | + +## Analog inputs + +The A6SE_H743 flight controller has 5 analog inputs + + - ADC Pin4 -> Battery Current + - ADC Pin2 -> Battery Voltage + - ADC Pin8 -> ADC 3V3 Sense + - ADC Pin10 -> ADC 6V6 Sense + - ADC Pin11 -> RSSI voltage monitoring + + ## Battery Monitor Configuration + +The board has voltage and current sensor inputs on the POWER_ADC connector. + +The correct battery setting parameters are: + +Enable Battery monitor. + +BATT_MONITOR =4 + +Then reboot. + +BATT_VOLT_PIN 2 + +BATT_CURR_PIN 4 + +BATT_VOLT_MULT 21.0 (may need adjustment if supplied monitor is not used) + +BATT_AMP_PERVLT 34.0 (may need adjustment if supplied monitor is not used) + +## Build the FC + +./waf configure --board=YJUAV_A6SE_H743 +./waf copter + +The compiled firmware is located in folder **"build/YJUAV_A6SE_H743/bin/arducopter.apj"**. + + +## Loading Firmware + +The A6SE_H743 flight controller comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of *.apj firmware files with any ArduPilot compatible ground station. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/YJUAV_A6SE_H743-pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/YJUAV_A6SE_H743-pinout.jpg new file mode 100644 index 0000000000000000000000000000000000000000..095c7ed56d1c27d988648852b49050894039b82a GIT binary patch literal 182419 zcmeFZ2iV)x**E^AP*w{qlnsS66bd+rBoEmNNx)0CBwMz%ZKiBXwk+8imTlQULkp#4 zZzu_~Y{F_7fdmLG1qxvX0t5(j00|?|QV282|2#G!38j7M`+u+Nd%x>L8IPZ%qg&_P z=RWuN-S_dj=hyvd?E556;A0cMHDT<0@Mmn@sX4_#L(2hlnRU>6H#<35)7dzGI^pOM*I*A z{-RTm;It4r%^#ll`88?gHsI5Ar>ah468Pt@1Ha9f^!dDcz24MbV5;fVAOyp(aWa1Y z6wqTzyWetUZ%V7Z&xpu+Itis+aWu=-%+|zlx^mgb_ANB{Pz!C75^CQzj@U#HxgCo;mcq1aCo?oJoHLIH1|1u3E zFrC2A;S*Xgc{AB`PHHhrSeZNG9t9P2^maG}=p*Vc8N<+Db8t$g8)d*#f>)h4CLc9 zUufxQZa~+od@0Q(;0{5MW|oZCYo$5~SZA}a;L-vWbNWFjpBxfIavWTeMBI=?#H&gM zCYJnlOK!UDvKZx-D?~LcN^DxFX4!V9?Z{}?WTH_5OrJ=^3P4;6#bg`^M0uRI^<*LzPqJA)iSrCy zCu$|HR!a7V1kG}~hiB7Fkfr0eKx&n4azG}SM6E8fd|%Xx;Y>Uh$g{LUCTm`m*L$_$ zl*vX3Pia-Xit~Ypog4J}HET!^_T>k4lGWWT$A|KaQ7wvsRhDo>kr2ixHLIp9T248I zbjtq!YWhQhzJx)Fq7l+cO{-IBl~7f;bGjwVEt_iEHrjU`+t-C;AZS2LqVeRoh$SLX zj1SsjTqO2HcpM7ZCiORy-?orGNKu?*KKdguTGjI3i; zHyO0+RZ)Wray5+(2^w`PS!g9Pl~jg{;hB^G$t;JELex*%OuH*KsdhUbk`;+cHCu8e z0qm~;^%AzLIlLOG%3`xg%P9nQEv+#mXlA-t%8T?whjBxRj$09`X`iSXLBdoyELZBq z`bE*HC9!@C4OyDa`b0VgH~1)GmBpN%Ewgbttg%5DDUB8-Wf-jvp7#_Bj}RiM5CNY; zSwe`1?Vg5o`Usl})Lo~E8a1Puk?EqTm#`LwGlDMEi5?Yc@KrfzV~QvEha;pq;M0Ha zzYx@m%S3<<*}CcLwNZOWFwhX1u-Sm3gjNwaJ1uo#HC+^wxRXS?B_@!!Q%Wu-cjR=b z-eFbE33!4CdHD)ZH5oDn!Ob36X()*eppjtr3o1soQ&i{6oou-pYRV`=hI4Y9isy0x zIiysiY{iTw>N3xnIg2Fy{z%mjQ;JBCGCJCN8CGNZqMc13p?oJFiE1%VK*2!TLiIoX zZ#d=kkM$b^L`_M8TZCIWO!c!3Rm6*eSm;_(w9X27qQbETr`g2-=2?Beuf?Ga3v((E zAIwmcf_7T%A;AJJ=3A)A85L8=;D%}0u43jWn{GHzloYzIpzE$mWnnm3?Pz_^vHB@F z$M`derU_=>2MfcACK|L+Q5q8Dny?nEaeXQ01|zV;BvD!A;&dg8;u;wvCAd#T#Ha(C z9Y5u`0@CVxvSidNoR7C01rBv_67{zTCmVKrLxN#38$*~zgmn6RxJngmP0jc%Ipu2) zP_VPPvLCbPcu|mPhsu?5MJ>}CSXim76?mHuI^l+)IVqKNL;2EZ>(xzPGdJMqJXv-t z{kDLU$wrLNnk9dzQczu$aof1m_I)i$9ggr{iM5pu=@Cav+5RewiV+eKOwnfrk|rsT z2;WRGwM4h4YO3i8!ERBJx$#3!5^szA{`8#7)8{j}kX~#BJK<)BvipiqjjVam9bGrPHU?vw2xIM2hXrOSCiZ!Be*&^}{B4(#71WJ@~ zp0@LbQsyzjEpuqNf>tmf4ieSxb;WY9P9+5^%2vBVg6<9pc3DI5QC6a&8dW7xi}9FP3@04TCi9^x+VC|Tu@7;PK^(@)wSm`WNUS&{NMtlV zL%D^n5A~5!BM?eil&vZf9qYIR3j`RWeK2rKlme^Rg<9V4S42TXVM(*YRfPe{EC-bQ zNRJE&{s(HMK!=^CA!d8^j#Dp&SgKBCJyVTDg;*pj@cGD)Ade=XXx5dWIIBirU>YGj zR~uKJz!d2%h|Y~`O3utfpEpDkoaPL=14#~qeZ?w=_t15RtlJcnRVWnkFuI%106p34xRe1$25!Y)?L;D!RFv^Xd`Pg7 zOlT>w$_EI`%Lq;za90J6B3%^2h>{SbPLUwVK&~ZrOo`}_O~DGa7=tL)fDC9^3Q7tY zC6l$W!q+#W8to$xBp{HM@k9j|_d6GJ^GduhuXMaiHxa#D>`rEaybbNIOgx35h|&Okubr zA&G%6ZsibJ@Pq=y;ts}j(l|z=Hrh(ZYnUPrN7zLw0bb4ulEHhvrf5UJ_=-&*Ww%|d zsHtGz`ix+qU}6>t#iCUkkEY zVpxteS(?;qf}s=`!;py@Ocw%h0~g|GE7FcDtiPo<PIvC1VwArpphf1=NipPayjU5p*44p2fO1eUteaT9(fnG9P zv>mWlx{lcBiM+;IWip!*X^-r2aL+c}zML|s7S8)Nw!vg6JS1obT!#<@GT^sud_9uNSO)^Q5s`wfjTiH$j2Db zuaPG0_RER|EE^gyB*_*2rRk8A5s_|;sE1e<5=oJRSzgzSP_%lR+JrECq^4shJB4IjUXXcxD?5_a@#n^SL`$rmDRN z)=g7EJUTF)R7(VsBe2qdwhRxq%AA~$MLD2n;!HiCv>I8tW*|g7;(Ab~;0t;JF-V7O z7fZ6($a4UpL&xdJ)mAb~o3I`C%Tbo};%+LKr&%jhas4Qe@ZCo3a^0MFU zMadv<#Gw+#6cEaXGny@+A=6XYvQY)bU(EA;U@Az z>}DOgTtRDC-GUoAIPMo*Tm}o@WXzD(j~JCKRktG=m2kV79c>`tK@xXA_rChJ?givX zo%IZ@XanhL$XqZQNE@6kC&T5U-B0vuQM z&nCLT;Rq8QyB|kfn&y3u-0RsrQbGu$kW8lPxR4G6Z4eKwj}-n*sKNTMNN-3`rb|*D z5knn=4VnqGnkqucI0JO9qUnH*?ANl2-E^1E>w_UdA=5^^eA!o2VSlC{RwUNVBeEFA z;{AHnBylXKeW__%gJ`*C zxA8&?*ip`w#as#xSz^%hY^mCf2{>DA3*c3B%fOHjS*;t9f?iMg1Eq>k2CmG=v=2w9 zMo1D&Yv|QPW9yxmC}OisNK!xjZUW8=&4V|}pHXcc6j@KOz zlH4J|vdm;mfWLGsF@hLHmn{q7V1Vc*6)_FlK)K_oQl{Rh6e3N(o==w)+X?jHj-!NK zxKplrWP+f~pbb!(z(@`S4oUD%nsZdtQwEt>g3k<{ZmEL`S+Rt)y#=FqLjyv+Z)YAL(>iFU>n$EFf3> z9O_YJE-2ZoQ@5LPBLVO*zv8D%7Dn>@U^(4K1H%!b9Fl~@culZMAqIGy4y%R(JP{Xs zuv}3aLD-k-P-cS*4_H#_7%pAtk|h|4;c+P&X>kZI7+9yLwTkm6kILCqzoL%XUe_! z2xifeZ5SpUvLYpfJgFBAgHNljW=kSHkeivluT*Y^1dE^oK^=+eUKfqh8Lcig19{nw zsG2W~3vFajZgBL7hahl3>7EM|lrHfyOXH}PFj5|ka}B9jYZ}#vz*N1w1@&ST1m`=U zM#?pk0MH49V<{uUMT|zQ7%9b=95(_a^|I5ZQZ}%mv5ch{E>7n&6l}OyMZ-NZPnbav z$wE;`jR z8n7i8+fnFPIwDCxjR{~)9HpOhAtg}Bg1tiFZpq3EK@AI1c`im18Xg=e2VM%}avAul zA-53eW-2IbAvq{kuL%vWLncx#(f4RmhSFrDV8=xt)dEV|pXb$#)p1i2M#;5!gf|M9 zM~slAl&(V2m`~R$>2x##Bt>(8C(`YhwT!P{f<(mtVJ_DJFs)u4RJ3|gw^@_0BoGmA z3Lb)>bvWgX0mUx@Sx<~~Ny4onte;?tWi3ar&4NkQyhs5LafPa?*@dcIwA-~@gB1r% z0J9RrKpPT_*%n2u>kFV)ZzXMo zY8r8eO@wLSZPHnRQJdAYT5#F~WeCEc6N^x})Nq8wFpNgWy=H_8!eZDZEdYPFI-(m8 zagIuo8K#ZLm?kekN>WYIcF?Yc>LICVU_uy=0{hSEST{vQ^+t&t5=7F#`)!#%0q8!X z0Rgk9`ue~cXvlz8q zu;Hqt($9l1y95jr0XcF%QR7R#0$H`;Rwq?1wmoO$IRIbdt8kTet5tJ@V8B6LOvQ0g zZ#IFqtP!R?0I)zb8sl|<@WqvQu-52g6sBa7hB%xuo092TKi7!cZ6|IL1YH2`74(IO z1LZ_112**=OPuFAe2>Z&0I$DtBK{O1*RLbAv zGkr3{=YnDr0d`qRg(F_84^;yJA0B4t0xObbwl8qRfH3($o)+13ufpi5M!D+xha(iq zaF-vH$jU&eW-?qg?b;q`MFu2}ql0WZ+v+s|U=tJMR#9+Zzffw)D)3z4vIuOHVBram zPJlq)C|9zh@HSnnAr4=(fyCBD*x^!S$;n0au->F8$o7N)O2Q6gXf-H=lMshXExbJ`j^L)JU68L(w=jvU)y{j)-Lg%}_ex zr810J5?#mOVJ#j3L2fyU0X(?r(^1EAUD@t7eR<%=A#p`8+Kw_@ z6uwtTiA1cB64JU}gi@a51j`^4w?d|3Dk5DFS(PCjHkd47Igy34Wn2!!MJou~c>n|e z4`o9rG$hziTfo1AQ72S{X_|urOo>(iWM6Z|wpn6uBJX5tb*9Jah8k#?@x0On5TFrp zpk|$P@=X;>aHyItlQf5g*DHR$^<7l;~M@&O&mdGL^)FL49W(Bzz zz)}IT;{j~LpPz>AYCKMUaM2(?E#2*?7wxsd~ z?f@I#V)|Lcz)CXR<$+}e!A1-~3@NkR6bN6sB!sz887X5F3L@18okIE%UPas@*JsGS z<`SBY6^1;FSI5US7+)-_te_CcXa+Do36`%CZ_xzNhthhyUjrMDGC3?oIe8cYZi(&p zL7^nT8ELS{5C=iglrxG(!;sDar#(=#BQ_F_*cmp6BqUdWB@~Rd;lMq;>1zYT$xe~E zYB$@{8d)tO`PyQ@21&apMZstmm#lyua)u+!<(Z7)xgnBFxyb^T67pQdrSd|k5@m6r zBM5xD2m-Vg?o}8ulGG!EO3^ejIV4`KcVV1Wbr4U+mrwfDWVB-_(#hEYopey;y`3G8|WyP_JTiVnv`=1t6?M6nL6^ z27pDqgewLDKwim_I~M{-L;wW>oI}bgu+2mZYKCz!>#M4nt`Qz6M$>PhjG79=@W8c@ zJ`v@Tm=}dJNtY%Uv#t2|`$z?>>dC>V`} zC<7$is7j~hXF77*2ANMFV|LZ66ht^_c)6ff*LdJujUp)%=gWEv7YR8O0$GzxvBA*A zHsQ~fNWFz|dcrs85e$M?F+UGS5+LHuRLKY=6=1C>A&?voHwu}OolXqc_Hcxb-X3Hr zhA&YS1!@31K~97sk%1=hF(>7SB~9!%MX#hXW*P3}8DF1*OmRS%^=lwy?v zM!?2LNv<*#Ksrzp?Cv%rqFkROm`J8uwxgmfI%zMRa>WqHe07Ps7DO$y?PSViHIQ_g zc&m{Pcl>P-7nB83v|?CfI6{GK%K_U#OF)g4(EcDjh!LrvhuUJ99aQ=`z1wSA66_P&+*eo$4ad}xKJ?if0n>iO-_QaEfe-Mk8V*tSb=n{vh%kW=41^C@)dmezRYng>1z>LQ zX3AnB>6T{j0w%nn;Z-h!_GSTxxY2Nm1kAVtNi)6c5pGg70x*GjIm03 zEf@y!FtW=^#Vm%*Oq^mfNDuQU+XFs2>$S^zCPE}Ya9bFUFlv5810Dw+Xvz@l^cXgu zDM%m@F4JV97xY@X1yXCHA}A~?6e=Ct$K{=zt9Go07?bg0$rlTHu7o-)rFA1Bl&H9o zwjkFKt}kN&({>U$R?pVtb`pxJojTMN#EcdmZap}LqiB&gBY_xDdEICz=rB}UE+-H?5CEyukxSf{c%y6KB0{l!Hq8}5 z4UJGM`fOhJ5g7n8(?B!h4hL2ykK6rb5EeL)o1_BSWMfeC{J>R=)A5v%PhkC#V1sN* zl>-<%TL5k5g2_g$*=EBY$HjvzY1DOHLgFkL^ydPZ zpc3=-vw|pMeL|0CtgPIx@Ys-tQlo+v3!)HhWrDtPIRczMK|*~2NN7vIEw@rSG@g*G z(+uEDkioYtHRj|U?xZMHy zm<;c4R}~~h$uzK>d_^Vl@lpYeH8Wg}r0y)YRTg^16a!S=YMad%3Y@PK>u+Hei z5o%f*&o=}k*iE|y2*f%Vlua8L408Ehk*NtKjwXPW))GFD?BKd;)~M&JnF^Uq#oYu` z3Nlo`NpLhkdzzyheInN4qY)dc05s2#!_97az=u1GS_cUhp+fX2B@S{%VjynFa1rPu zD63~-zb3H-ThfE|nh9LdMyyeYCUtl?!gQf%8vqjxgesk~C^I7CxMrHg{aU%1V?p_% zCz?JOWLIrI&}CBhffaS@j%pxKnFl@nl{?8tq>V~o6qRQ&{Hu}#XB zWxMPT!~VWY7)c6LB{XRwk??|g8#n{3AeY43QC0blWLNMgDdhL89s{wTbaSbt=hTYDHhmO{2 zz`y|jwE|EyA(EsE*P~c6;$_e%q?(O318_;GnhO98Jm{yxY|!pE`jMt$EmicmC%Q!WEh$TlM|#6WOW2C75PDs~*rGD=QJctxX?b?CGdPEc_U z0f>nJ^5s-85`x5X-BnBZLOxp{Y%hu=oyus0P}Q(wW}l*1r5Up2n4p7NJdzHDA_ho7 zflwEY&~eD(s7y22ZUEd;j1~o^ing?N>F2rJK9&8rc zNuvzJ;FzxwO@MT`BB6R*h+=9@ghz$am#r98&-oPM=c2}ehs1J0Z3U|=QXSO@?K z2qAO>06d8XV zT2fGLjGJlGr_y-b(Ar&`1NdFTOu(kv0J{a0#|%t}G=gAnL`!vss-@gGxKmE!Vm%aw z`3RNCsyxp7hho$45xnC@fClZ-K>6!~{=lXKss!p~8dk?b9W|p!kp?g|{&WWi@+^A} z3i3*rI7lR;VWWu(vA6?=`(<(jJ6on;S(pi1saCJhYauX}E7ZK29ReOeHdjk?CPVyv*v)#wY5PR zuGlz$43Zi!B9u!S5m0)o0!$Q(bw`UrC)_lMOyc!KL`9e)pOw6Zo|D4}I&PTgFr@XR zejo&}6F1(0oTiDISfG>*B#BI=@AWB(sOWiL7!-%_pQqtyngvxLu{=P5<8r!C4i?b5 zmBo!xwpXA*bqDR|27FGTAe8L{^X0I?=SzW3$FkG9M`EdtDZu@>nBe1qkvo^rBiU*< zRYZZ3NalG0fXQqZWDW}c3WTU=K$e7dvo#pV^>n2N%C%dF-t5$H)fdt8*+^cCnmGex zz(Ea5_j6~dQ%0kH2$UBF!;Dn-B}(-~p@sQHsp13HLE9KC+W?z=^{3$~gRpADT}sWW zbTN~w5ChMT1rnK@5CewOB1&l7GF=%|U$o)YAcpewoQXEuXoZRu>Upoi<7(XqaW&JeedF zDV1YN6rYR>jt9yh1(%P26wD|MSEuVXQIEGUG!E=uj&0d+G7u(;)ei6$K#4~n31gvZ zKiO&9el%XG*<@O41p8T&vf5&}#{2YSOvsPY?n54arD6LzNqJ|Gu&R(vw~36XP)XoH zAVY$tA5{4WM1y3cMkofrRNz$xTc93170Q#Xrr#%VR=FWrbWX3iX0Y4|w8bjnHyWy5 z5`t}A_27U6cS31G8+ouek0*Rmx7DOgf4b>c+GN2_%c!0-lEpMqfFTVE(@~j1qD;rO zJ;;DUJ-l7CfUffoB7zC3w#))b_8h)FGW3KR=G2e`Txmv;)Ql0fssoa)$N-?0-6RiE z1&UmX4!B%M#n3^jYx$bBfIrx5`5S@&7Ib4hG@SA#b@&_K{cqeD5?rse{*9XZ$}X;9 z06+NDu18*SYwB5R$Grd4o1l2f% zzmesUOr0z$8GGPs;!-U@kZ`e#5Fkr6BxrOje{}!~iz-q@YW71l7)4u+s*@uEJjZxc zGU23p8QX%YVV+L}n+|}&ZMYo@62*R=rr}IKM|e(!CaZ%{cq>sHtjj4rMcQmWDOVJY zr{yM4z?sYd@s&C)$*+mNuH2#(xj}fojwAc2xJS9^1Yzn;0L7chM!(l#I=Ketv=gGm26NdpMM%oc@u5(`3-Q+z@|YVY(oU` znV#-hLgqPv5bT|jJ zuq!tdvZ545MNo7%*=!{Tu1u=&YPc3D;qfk!W`p@mP!vJ2BbaMDV)9TgREn@pwBAn@ zcpmDe0;v#iH*%ZQSPXf%QQhm;^P5;_z(L@Mmje~m2!OW*5&-B>$LWXMAwf_pA}eID zB!oPRu+wlo3$tww1k`Nb;ezqJW`Th)34h<{r0Q~0YY*~0+$!o(kie`}?54p5gLVLg z^N=tKZxIf%lI=W@a~G6(fVc%ZBj**r&k}1cMz!ko4yj62 zkd4qKyWeMYkgy37s5c7DRDYcI0W=j9YeK;w?LckF$2E#JC}007iCW(VL6|;c!)d50bCAmfHp=g^^89s#Yu0K0l&3oEy}zl-hJ?L+ggQP6v&y<{HZSv5gK+{+H)A z!SUN^hTH;&XuT;_MU_F_%%qu7bRwIa7|UfR3dpN>p8V?Fm#w&U;fjTqu9$oCYiC@s z;>rcDpK!)&bMBq;pRo4JNKmW z4n;GY{qp^d)_?ST!mM=0Wr;}41PxQGT6J0k4Tr;^!VUKaLdhh8L=wS3JQfc}Q9KyI z@c4St8$J3@WQkTAIENMGbF$ihKz5@?|A}nQ(ZE@F+1TjSoerQKu7ZSMxEz>LR^`By zAf|+-l*3qc3W`=?1oM}%aKyiU*k3{8pWc&D9IdNVamQ?a&4bF*hq5tE+c59Zz`}kN zg{$Zk7z5|tgCR9E1q;FcDPcrbv2rLFP-JkH`JbNMFre|39^I~PSgHSD&j0l6SCKaV zf3bD+im#yYRj+dXrM!;FeChrM66=?5qovtMbA7%W(pnpw#_w-*W1N5E>KvS+*|c^2 zjsNs0dfNqCcbZ%o-*YqDGLVw-_1maz!;rx%Mi*GY@eUga$M|0RdYj^(9{tz!dv&Gt z@4irAL~7XUUlVDYs@sztC0YYo;lKW-gAvV5ANtqCD|KKwlsuSH&AzxkfBah$CV;!(-xoK&?uT{vjcvcx=0E%P z!JAFke(YP@PuOhx3G4nab{+U4w9Urt+&{0^KWnSt?z7T8{Gl_e}8Oj zi_OM6eP@fUw%T&r&9)u;7U;Xhge|w)eup3Ivg`9(@3_;>!uetGg6E`P|LBfqukr4j z^vsD@|8jn$i0t!Pt+#)Do2dWC4=hckpFWpA@2ZD>b?qN_>z}l&017jHfj-Oxe-dZ+ z-4EY=`}Je_;=Su$82c_5=eM@sZ2Pf;$JTuI#f@)1e8YinIPeVzzTv<(9QePV1E+MS zu6kznS&wf1(}$kt2NykX!{dv&n+f8IImv6bU;I$`JmFSBf9I5Ke|9(W+6%9}cf*U5 z=j{00q*E^R@3F;%KYqg0FFoVP$L5@|@^4#Swckk}eel_`JJ+5uHu$FbzrmC5edqKW zo^0-M(;E-`+|P+^4(u#4+<65{^4%oxm`2w?Dp7^r6q$2 zOWBL-=fAPlYgcwozy17$N8Hdp$NbAB`|NY+G0W$lu}|1f@0;K5(;Gf`=zzBtnt`{v zgPSftWcEu(PkVjYUltsH#>$1xU-wO2uAO#L?czy@vSQW4KiuJg8~?a;(bPYuU%hD8 z>%Ef>IN`lT#~pCu`%5_Nl$Yl}{mJdbo#ahVoSZy=$*smEJ1?C*`ybyv{OmU#k3W+_ z&${E0zu$Z9Nx!(4IOLt{)JM`c+&1sGr=C0Q?PWjt(TR@zyWc!|?3~#Gc1~n`~cgWF4e!9SYckLeQ z#+JTv!aapU4*t-6&E6T+IsMt<7U0{#?y;FGS`iXKi%PjF1LF`ZKTIYW}0o-TLCY$`k9xelp|2dvBb$mwL}7uN*yf*2mb}kA0wx{Uh}D>Q9%o z*Nr{=glf)BZ+YR(wfQeEzH}{pbl}+1A=4i_dd9u04_i0(UVGV`HO0?CH@5H^ zdfnKc7p*z`BWmf6o2?t`(HE~9yMNXv3;%Y(_4{wR_MM9lS~qs$y0H&>e}=gHp7$*N z6?V;G&+YwEcjrguK6M~Mrmi|byGt``tB$y9_Zx1T6Opcb-3G_un(_Fd)mgT8Z7xqLCD-_JOH zzlSdrw|n`X&SNK`jisBPa?THv-(_~Z^YQjYM}7PBbz{q)zGl|nURit7XZyZ+@`V48 z13Ue7?wX4hoHzfVRSTd*$RA&v`<;Vl%sT(_ zm$Kq{=bfD0E&a;_FPWx>lFMcg>fGzk`nmt<*}vq94gWjg;Nhp8{>bq!%z5^tYCQHS zdR=?kG0UD^xKP&b{3Z93_dW~V`r5Wzt=;0LrN{jEFAvY0t8mlyJL~9k*F1Sy@e=dN z!%lnlnA$b(Kq{4*b(|LM+mpW`h&VX^dX_=8=}yYSA_&KP_9 z`Se-WrVezE*}OG(Cpfv;N_$mf=JEHS_XxXRck=-cF;}O34~I^}{U;R{z1W%Yj&s+R zcl?mOY!3YMo0m`F7RS|dlF`s-H&u4OntyNUT&}RK?|+M~y7UwM({AU2_u8La{Q8-D z?sC+9l5x+|Z$Ed+aSM;^{QZne9w;t7`_!k!d!|KF^s}d)Qv5N>@vhrW5* zv6HU2;>^2p5o^K9k1l-TXVdq%&-nIzceoGu=iXU;zr;7sGM>+W^6XW29Qn}G*Z=gh z+vp43+m5*I@88>@d*$&5cOo(Kh?J#xx4-Pny{2{kKIv;C z>H&}L_UiJ}2g&LSsfTW#bki#b6@!HzJ%dqazB^d3*M7gdZlB9)fBEaxe|mlX8IvCX z=W^yX_uXmAEyxhAZuUuY_C*7yt{9ts*!^4YE!_0> zBd6~6!{7}|!`%mtzy5b~_nEYI+RaBKA3gf&(8(|McWEu&j6X4O>s3G8`RPAC^xz$T zKlJwGj$0)j*;xV-v4!^Gf;U?SPF=a=tVjCf5!XEV;l+PmcnPTaJ^D9;nOD`$ezJ5| zV#xu#|Li+n_~f~*r(by&uP(WD&!tPYx%HOs-xs`PZ0y^mx353el9 z3m@CbmpSmQX{}RlA3U^V!ReD4q11OTFh00zuZN}=reAyVb=T+ic<@Ij8}e!tMR8Nc>~3 z$Deswo$~D+A8njCp?n+|eQnEQmd<@{=Uca5edqb-N3Q>H=kA(McHg0X_1VYC$IQL_ z^3qah>-!G!-}2C%&&+vz(T_8iKN(m#Z&CZi>#um{7k68C?(x?i(|=mbHP@VS(xRU& zz3aeZj0LxUbe?+U?z7+O-1O8wNACadzT3Z7K;Bzj-Q`TTeb&yCe^7kn>fdX7N4Ap} z#lzn6Et|pDKXI2XIUr)ZcJDotR=pHH>=*n_PZkfjb-#JO{fu3&p6al>L>>?PX~OFp zBxS;iPd|I){VkV1^l^3b?Qb3Ib=uw7(+lSE(px8FR?mKBA$s{Sr_LA8`*~^RK&OZo zUYJ+E`mkxuiPiGH+kc2NGmm}zu6ZY4a^MM=wb$BTEuDYT?2DH$2VEIXW>0zfS8s*p zh!ZE?wfxawtp8^7p;LpWAMy0%#vMBydO_rGf1Ucu0`dNfKFVF>A;RPVNXo|=}C9|p1S+i^KUB7mvX(ge>3T|KWo1V-FWWY%YT01tBy}5Y%rz z_1Fm?&3kj!9r-=|ch7j@tv?uB?Xv63QzxySd(tlt-EHCN^WOa63FnBx-M_zlzboIm zy;ppB`g`Z?fAv{J<-ntEyrMY2arzIUo1ZhWH}h-0Wbd74o%Q~j%TM0^*7uHnGkc15 z{qmExSp31I!j30B#!W7CA9?9#&iN}dFPHXvV5_A|yvL6@?AntoW7m6kcy)U6)op_p zUv>1n+=mO$YpiV>PpD75wb$I_OTYN(%;c-L9d_6SXD{EJByO92>YN9D{jqbciXZdt zAC>9T>|ey+{bb{5eh)tln3>BC-udv{>PIH5eCnoqk@vU!%i`Pm?!Qg{>Dj-ZfAfydpL`!-V4IPj9(>RPVd?Hw%YS?8)9D)?dtwU;xz1R4 znSa}3z8rn_Eq>}LD@%NA?vci8$6p6T|MdFsH!ryPIn%B@!YpnPT)+xoi2 zKc4&Wq5EC+eD~-*pILhP6Z-}#w>%*k?WwOU`stb%FF0c_te~7b?U%^BofprZ*}7rY zZCe(9`u?ZqetXvHL)VSTGj?0E-@38G4&8jSL)MKoj$OKDpLJu>E%ycgx9Ep0X1#Iq zs%6g}`S25O_GTY4ZJ$rOM^Bse{(`mF$YayqT5$^SoIiW`)776&J0yJR6FdKI-Pmj9 zr>oz7a_{m!hrj)u?Uuj!ojY!QadqQ|OMc)A6X(RFCw_8^d(Y2z+N-|e!o+VT&z=`^ zkp0^`#|~fe(YbREzA1a)f)hThTyrCHe_->g4qN&2#N&T>vbQGlLinic%-Ezm|Ni#l zlLuyH@j)}UdgNfK`PqYqJVfNudp|g7r#D^?Ev_6Nw&r@*eD`eM(%4R`j$AkP(xQ)M zefY}S$0ttSlKO19cyN8Y?3y>;e{zeTtsA@P<`*`rtQ&juzR8=i87RZA|Kv97#-2TL zS>>vAW3@Gl*Bmb0C$3q(Zfs@mwo_KmvezVDIz-y8{_%p}u6^={%BN4iliz9G*fMj? z3Gdh5pR>j`zQ65eYp(lHeE*C!<@?8;+;kNG=YHF5-PqNO=GTg|esb`2FKc5f&seqW z?KjqqEqUvci%%GP>*h{{`U&xEe(ym0NFZ@l)GHy{0D zIN44-NKXFQi^rX_!-|iWU;XC;9>3xi{FN83UUR_y$NoU_Jvi8AUUkRTn==mDv;FFv z?7Js@G+#Sv?MKBwrsI+1mZ$ojntIM7CvNq`EgwH*m~$Whjd1Oa`-wSxNpHs9v-G2< zytnwqSMOMUc$dE+(b z%z1I*k<;oSSUfgzvcf|`&9lR`Tv6Q@<^WNKQY4%QGzh&WByZClr zb?eF%tCm*^?pk_f{f}2&>0E!qY;bPkh2QLa<|YgN?XBOQX}`F~oBz1>yz70$ zc~3ue+r>|$UU}i=#mCHht3PGF`1}ucZyd4naXNo=@$CnmdM@C5Yrgivvi(lkg?anC z=k^x(A9(5H1AjRKTYSWt2d}^HBJ2;hKjalp`DpGGpZ+-WPN)C;FIQdlrztyr`it7> z`%LB!J-pF8rT5g5$%jo^b~kS0AHn_tX}v9-ZUH9y#vjHOiXv zryaR^)=P_)EbR{@vJ<2fuJ>XI2_)t;z7VoABlT;4c$4iMh7>)!OBkJbvk#sf(_A{*dh! zeEgRcvp`7m(>3=#e&)6-{_(&qvpzm_?V5$bEspyaBmRav|L<~Vuf0w`@sTyl-+tv% z=B|k!>^lGO&i60AYT8Suth{#1f6OM1|HGucUMQS##MFg9s#cD4uTXE=bG|@CUVHDP zo$gnT`E`H6zc#qLk9}*`m3!Pi@A&Iqe|`T0?pHq!gyYY-weyATUVH2Nz3lC`9QeXb z*J-!M9$Ng|t1GU*eYa1~=@XIFXMgvHi;j9qSc$dfogn=zdHXxh&f4mR^XI=g^{>xQ z+vTzYt5GUBZPft}-u}q)oA%AfS8RLXl`D+tOOKfGE>qgYXwPr|Wq15XuM4N1o4xh* zhf)*v??3kRqLwTwst?o6?+pGKO)%bU> zQO>}nfgQ9L!96BsU#VQ(j<1RWYQ2;WKcJ2}WIvwA&EjJEhoSsW%6R^+11Xw5%e_`F z7+7{FN}xRsIH3Bult@&Pb!0l>k}#b)9aA7DFRR!1m{qF3>fl?XVa}r1Kblg^Oi!-( zOTY&}Dlr;X^Kap!v46@RM9}XJtbyN~p#Z)F1pd*w`GE_c0Hc-J;@xxqVI_>{WX!)HjQepl3KKa&tvr8J>&F?R1KgRn8PZX6ICdt1f>OvgWr7l7`2+rWZ3i zXYG9afsL-9m8L*H4&aN|<7SD3Q$Xk-io_TyTFDG9G6bJ9`W5Z0o&pPNKVIS%KRQ(8 zHexV5p5Izy{Om#;0AdR!K?t@F?wgd>Vi_{^Q;EN5G@Q!$sTs2N-W6V957vh=Zo!qZ zc1Z5?=*NVGYW6ry?(3@qCncyn+)XBpyKXF=!qY`xMGp77iaG*Mho0iM3Mk%)nLq`f zC-*qT^)V6UtO4?vc<~oym}TdI?%9qN;DP?&FG?z4>{cFibhP4DY3?ryTSe}9JVti5 z&UsqRqn?iV-aFj?LxgF*dR=L_N`JMK%$w}j?i#1Kl=sNB;dz+W?Y>wKW`fxklrgV^ zsa{`~j0L~r6+v@7xIxFu%AXwF%;kv#ZIjzIT`BD_H98{8vDh|!(O2}kr__c!1NP|f z7{mJk7Fd!S4E$X2L03=CX8y_~C*on?g24HisbJyu{=l7td)l#DtAwDy9hsDL*KgT+gx3EK5$p* zR*O}*NGu<@D(U>-qBBghW2VGtTrJp-nL5hGMH%;lm{zJhD;Fze3fAYKzTn;MVuCNK zO#X3HX$@z?XQ*Gs$R|EAMb0xf#BgIM`J-(x(aa9VA^%ZatB=DsxoBx9Tvuq4)Y+xJ zw%<_93(=-=tt}MVE%J_o2pZ*&QC;?-KDvRN5m%`~W^jO1Hi|TO_nM!bvYz`Fv0I;E zlT$5cRyqN%_KzU2assB;>S3A7opEa z7HbIg`Ftd&fWJGwPm*yi^wmEaqwHsZmbV6N@ps{_gh^yiXrQ zHRuCub-F~Z23@|dOc`3%MzD=>QFv*^hrkq;@(+;mhs&s8!)1F9Sjr{JVM7sS`03aE zZyA&+8QVx6en2rE*7`eZ^QaDiSI_6EufoZ0d%nhOH8a3Mf)`Vnao!>@Wvq|=+BZ1# z|DwEyc*XhfZ3WthU9n&uZ?Lj&mZyd}a3SrOH<(H^20|rCS}QT|BoklYIrMue~uL2`g(Ov~sF73QgNak?o7+f%GV8QV4ydYF%E3toqpghZ) zSKhD8FFBN}_T_M&w((D^iVsgpsT>hsF$n}`(#GMd)byaU$oJg{V7XzcyKZF`Ct1PM zR~Q1{x0C)$!!2KK&Z)0riO%(a-{qo0WpFjeyqX@R#9JNi7)J)WNv7{r9&+8919yxG z23&HZgQ)hzlezpNJDGHh!}Aa2t+VUQCKm`yT}!$a7LaGJo>CVg<6<_32Qz$|n-;-d zIxM#p?#m8%%j};ZatSYsH-66nT^wZN&ju9GPm%z?5$^~C>$$-Wfwl9LGn7VV)}HpP zjYmzh($$rFeYhIP2lobk)N?ZZ;{5mKZ-a`aSG%s5mk2$Lw@=vzD}sw6dZ_>5EcBwh zpO`5oxQJ@$U|ZexAvnN&YMyxDL?o-1vA6^&N#mcYDR^()_S%QJ(;DanA*~2Gb&0>> za-y_)iWynNT0i8T&t141J~KJTy)0cenH0Z>dW|aaABVYrBGBqF^Km)b;y&xK)Vm17 ztjm!*;Q`PMn`yW6sUuqKe`tpfS8jFF>B8o+u3WxG$C&>5PFjDo<=ij_aM$`Aro=YI zj1|aa7yn-MaIVaba&-tKI|drW{#L2kfXw#m9ERqk83kg3#wU6V{+VbTD2};z_RwUC+f7m z1MAccOh6TcX2su!%D_5D=?ZcJ08Z2k1fkaJGP@S6soD59+SyX%Mh!i^x(8?EtI2vw zpVVX<(!!H1Yc%(2SSDq;KM}vqY0~Vzr<-{nk$dfgx^3*0lzhxv5lU~5R$5`bWIKyh z4`nGSomGc^e_M&iv96U_HP}`r-()6Eq~mRrIV51jo5dhS%CkYrAvLfYTy3Y*_0ga} z{V$5V3bfqsb+COqlRl0IN5fn1xIjwI=PTtU<+0>le#dAm19|{>GCbNebSzvDr+Gpk zRqTl3DS^#b-6e-2O5hDdPCRAXHT4h9onGiTt@#`A8kPJsL9i`6uYtK6V9V5(3(11> zST79t{KNQJKBl^iP81>45*mc!5H$;ITLN^-M+tU@^uhE=6!dD+E4p`$PwDyTS=a*w z%DKu`T$`Nug9@l-;s-_XYQ#oE?UYcL$zU4~241r*I%Gy&N2oX1FiFsQFLE=w zip)hY3oKBn$%WG(1CJZNr@nSV_X~t8NN%0 zzF07TsGO2YDxLWy`3zNtpWx7n%4=fy8jsi7%q_#|z;a>kV@cE8?r)3&M>hWj!M`Z` zAftd-lqiO4Ph(g$5<)xScd4)=PL~foDcP*z@ z!B5*xc2FiQt-<8G;?jPEpQoC__xIm$;=@04e>=p%$Dh;&ks^`nJi?(LkF;xPYTs zEf_A+c#Q2@xKmsJtl)yk_Dg@tDTgq}WcIJ|#pVw|KxGyxS--Cb{z$lYMzq&mSw9g6 z%B$ROKR(+94^w-@2Hs}QnG}AdY2_fE89lN88d0wY@d>+V;_F{-JiGV;&Lgua2cbjx zs{oaXwKeBiDH%c|#r=gb+7@;6k%h&??#U@qLur`dg40V4znqr_CKB=PcM3?lfCc<# z{c3vqlzxas0sE$lP|MNGR@rtLaH~TdmJ3B#_xGoC|$m;8CcGF!T@oEVb+uHJnf-45^&%&19(vIm!*UtbJk^;QcAg)zuy;S1*uP> zyL6`;I-r+px&KAs(zbp}ihkM%BO2U=iGGo(n5Ike#{Rtf&|qZVnhOQE8MO$hx10`{ zZo^Yf8nSl8-cU6+z|PofuPbs&w+jmkR%?qYO*8Pm7z~#p;i#isZ}>AG~V- zNp#N>%8faiV3~=Sg{3!nkh0#SNxRpF5#*=j%)jS30((%W7r@QRcCq)Dp1lVht(Bbh zRq+R<96)Bz{i>2rZGk-F^H-9GzqfJ)6>u?K?|F#P?lbQ5#F|~FwK7-yN^L@~IaZDp z>>V66{9Per$C@+-CIu}GvWBGkEb^n;6o~g(lThGAf~_8duA*55MyHtS2=^vy|H@38 ztMU0Ir@Yz$T-UtlAtN~^RDOmG1_J05Gtb5DwG(k1u0u<@=lg0`E-u!w1O~;N_A0Dz zD~qloGg5`T2koz)JpakRC<1`71=OTKAAjEG+8svwu+an;1aW!l#e!@XWZvP59JO%? zGKp28_1#<4EW<5{*RT!HZYYJ8Ca9tEM3b>XV~+XVFNrzvko#+y+BUmzFQ#Z{%f3oy zVPQLu$EanFPG5&gKIeUVHy%{Sv}1ml+x(P)n^Y5Cp7{HbGuq^(J_-sUM!;1Ky~{=M z1*fkAIxjh!1zOldVyr8mQ}v73H)dLgNHa^n+Zt_ftaabdTMC#LOBA7@Z>W@cI)@?< ztrO+h4}13FPm`IC6OETKDcO?Wl;e7fQ~Mu?s|{qig;Ng`KaT+QJL26S$CPx5Ht!-K z5J)KVt0XIuXQaEajXRwgfi6*#Mb6T~8BW3({t<^!>ViLHuaSLtcR6h6 zDv~1FT&4Sk**Zwl+Ou-E6w9z@w_HNQpY3d`6-emYwMemr69+SCnU;?XwTy zTK0oo;`+^~Br&krhiZ4%%)}IfjVyt#qedIn1IW>A`?)Pa#^c5y!#@pKR zsZrdZaQ}Zy+~}eZHrH>u;to>kv4?TvXGCo;@6di9Ozrn&rA^iE8Q*ygBu)Cr(~1$G z1TRSCi7v~pHMy3s0vh>tH8pZNAHwg5MRlRV@-*ibbx`>DWSjag`ekHTjGl^t28?$x z^S*RO|Dm(fh8QgzkI~C=OMN&P0@>+*e(`6vGh~M1h_b2zBI1mzu$V1qWPK~Y%gWB4 zzLK@X^z@l@Sw@G8=45*SsKlK^;AyzT>V_LVeqYN2ejziqZ~vkY*pw+CgC^f3am9K> z2{J|a*GR=A#d^eU%+muZwsEZzJSK)@@55+9n4@z4{C<%!OpKLsP}ocvnPgqP1VYBt z56*g22#}hExwt`jIS6U+opFrnb>TZ7Pii%HKK^<9OeXyw2eALOKvYf^9Rqr`cAxlo zp(wM%$u_!YS?qF2(}x7nT)cl#cumVY`{9V&3jhvOoZ0`E4qCtXhI#A#S3!=i^9CM) z&7!%2HLizS#`cNXx|SnXs(o_+{rd*M`MsX;T@Xm+mm4ok;J1rE$oTrGZ4s9Qr49`%Vxw6sQQNKyj(W5dOW&W^g^-fA zLXy?)A&Y@OUp+d=*=8{;js#2L3e}^`Y4s0xMP_D}c8U9Wb1;6Np;Gc^MrO>y+~>U< zPGC#>G^e_DH03aU=jhNVsILLH7ytaGVcR{_0&)`h1wW|eyb3Ccs>M1wb3oGDH< zQS0%Y6kh$KAD%b64M?jh?!&@ZC{8948xrrp;Ozp0qD@T3v74`c=i%HUnc2}Q*=cSA za{Ai(c3FMJ5H{k!Vjy^GU6zBB@AO=7S2bf9x{T4z5-kV=931fHA>6l>^B~#7?EFVd zGu*a(4Z7CN0b^wz^%~Vgu0aA070~iZsG<~GDo;|fu<(Ga-n<*|6$5m#O$cG4sZfEz zDBv~O5mN)y`?Y?qvnx}pjgfHaGRc{2kyYtZ2G&Rr0e<9a$VEpz05)A}Tk+_fy_s7* z?M?OMB8@<{i(O?M<5EXZ(B@jHMO(J`C>JLIe+K1tM_-G4{1ZNV4qGzu47`t6?s^cC z&=HM+A!p|Uej5)IT%P+~%tar#vAdE=PKbWbfYRw`u)Cjjm`S{4! zg7)wP%9ulAQeJ180Yy2QiI<;(jWnK51XtB~T&1eM|B5>eW-mVRVv1g<#-3Lz*@snL-wpw7$MRjN;o-8VaUOx4k^TJ(z&SSy)iJo) z`bTE1lbA#d;GTO+C-RATL(mp@>-N>h$bqx1>rooH`k4KWb?I`iX=FFfxO zG}$OB+gTH0jnm%LWAyqs)}4@{Qx~k<%sIK~dR*0yH*K52D|eqggk{=kfYz@}L@;^a z?EjRiK4tXyi*mk)@(&u7B?lFI^g*8&zVdar(U<++rKZJ(-Q-=!CeWdd zm_{qgk(s4xOp)Z^$B6dO=U9}h{*oZ0<@T*Tznw&_JC6MQ%0H}AOxn@TE+ahk<@LxL z#KA%(>;pf;pwyL3%J&RsR7`70!L`6EHz2%KyUX14nB=}|-H0*wTH=$YLG|HdT9=9N zgs-<~xHuxK&A)P{z)j6mQPZ;GZE?$Z{nTcs@Rqzyqv@CN0>vDee%45q@d>12CWl|f z>oWHa%qjAo)x73VRUWXpiGn^K`f&9?{r5^w-jIfYDYw?L*_bc$f|tJi0{%2>KNAyP zXt^v!mM10;l}2yQzw(F!bXzhsi~L1Vyr47W19MS*a&KJ)!iS|9d8d}`3F|dM37Tmw z6ar6w`udMiG?j#7-#5#x&`%^e_o=?;DY}YF%R+08rL*LBJD`2AM3IguJiNV1%Xe_@9VLF3v(z%lMnQ}CML7iG;rG5$>+SA?!J^<8_`H;Czeo)dCa8?kJ#sa^f-`9Oj(nL%iWYQi z9PY|6s(~ej#Ptd-h{nEamT9Ch+^3I)V03jDtJW;2fRbj6>ZcSobX+;6T2^ex3|tSj zQ!By}mkp3>)lGD4+t56HnvI9^yaj=2kL!lO}td9j5MRWihhml%|<=#+;G~8RN2iy=J4m!3>o( zfvCSIB#1#wr3qF~|EsI;M~>hp-uqV{dWYlA$EO|GHy(K9gezUOe6_kleGS8XL_XV1 zY3sbZ`}r4z_|p?({)Z@jv*&7{SK#`t_+1M|fj08)_!#%z=!x{=iE^&Eyz2k3_7^28 z?=K4SH&ui|+i_RB_=y|!!xHMhl8EQfzq1ltWEqZBU0jNLB(`Vi+E{+WbLQ%MpS zn(VkqmB#2b$L^d+vVy-O_=x8kH;7ta>w=;9u|~vR=QyU0z-Cyh<0u_mCOg_)bVFO@ znj?vpl8ANy*fp!9|eeSrsYRPq3Va9O9 zzT3U>nuSDRXYPtUVOQ%8uwGcl^gh;&5--gWG1z>hHB)jP=TelA$RXI1OtoL*z!RXw6rJ+QHy7A1mKfYrOA-cYX! zr-P_*B~N#YXuM?;Cl>1*F?f(d1B8_=-=u8x$-p1Hd?|DOMo`y){M%)6qaH!<)L z)ps;JE_&w_+P z(s;u$H^O3W|2v9NELJ_ZH!Zz`_^7Fl=_NYrH_cb^`yUMF449mDQmLuy#g6($HR7`HUFK=^qLAifX@b8Fccrh>=J$62WC@tzdG^+^n z=@&r@^sv))W}KXP6`dr>Qj_>xZBgQ<#+h&^VBh&h8A1}?&FzTeoCW;xy!|s@jpXWW z$>dJ?Vf_bo3pW`4MU3a@gGm=nQ>Y-3FWMBzEPMVz^78Xbm;Pj6!`%)rQFtH;M{6v} zo}!P4>#%29;#4fJqRyEAxthN$mn)xn9R~uZe!o3Ip~62>17RM|4_L+`A6C*W$rje^ z&LzfTb0kLN3?{*?4ltj?;FcXp%I8Yf8VczaTC5=8P)SZ!`luCwbV+f$2e{_Gz24UOVc)P--Sut%QAnLlX<*L(|jn`z2TJr(>DLTAv^5wSVs~_!tV19Mrz0#qH z);QkdN&!{!D32r*yVQae84D7EItp3rj2D2d3 zcf_`4&m$v!w8hd;2{z@yS`_bjXgU?G9E*&_^nRvD?h<4)4Vk}xWxmUn9Lmg5nOrOu>3mT z9=F0p^JI^hyzu1~sld$3nYZw$B-0Vh^&Jv;t!bh2>4W>&;%b273F@pfd76^no7GgcnFy+IZ*DU?0f9fWfTv%>yvfUXtDE!Au?;|WFDaFnr4OiD8+a>@8fqZWw^afl z2cSl%7aJjISoEII+CCS^)8*OTysW}D$}Nl?#;NT^7= z-e1IBG#ilDXf-XW`VT0gfMDOIcHF&Z-G|J z!qg0p3CULG9lfd!Z(r8%&7f1!m1rPrkvG=^!{Ez8P_Tc>gTMf43NH z>bO7FAcvTFW?X!J)EO3w*yYG?CY$gmJhA*5AMcKVYt61OlKt_ZP4 zK;Lh74_UaTC?J`eqUd-$;-ssIotpph-U&%G5o z>>Z}`SxtJ!s(7c5@|Tq>-c5?i%ARO-k8U}QXAd7XEf^2=67Gw=h9Sk$wyHps$E%We zA3gn%-L;!VO(8-|mNWL7MyZt{_ORT#@|jsBaeMuMhD%MznufO~MHNXpU+ZCWL!@sE zCIXt45|$MQnmpuhuX=<7VdZEsK!+fQ-Cl4MNZ{S|Br7!eCkCFhjMd69SH>Fc$0v6+ zz9FVn3cMmL`D^rR_tb#80xyVvVFYA|G}Fq+hi~9K1S6ku@cx*$&kJtvv>+=wmUty4 zkV@`yG<(X*u*S)ha7fDBp1Jq-`pF&t+Se~Zuo>VftG+p@zgF*Z`kMC3s(k8Cho1xL z<4Ag=zIr1+T@iP3xz;SN0_jn|7d$CEao31v$G7aex!=1+L2-L8F$z{9uA}a^TOQ-T zUUPVjW#sTSd~kNFA*$H9B##CZtV-U)$;>FDCSeZq>}5=-s- zjX=NxS?p}uoqENB4#!;kb6q?Zj3W9M<)0V@&4Fjzit75tUx%!wb837xLY!I9PN413 zebuXD9qhjL586Z|n29%RkMoVvmnd%e-i`Bm)dzp2CLf32l|GJH}sv_R+v_@vKV zp9#;V|6l-^;4zORrW3;|@Ze_3s5g9+BL2uP{xf>x9lfm#dQz3CM&)OgTHfmy%fj)$ zjC{B%fmZk~tQNnD+79`Z!xJ*oJb)Z0`#0)SO}{L(Kkt+D54!*OPh-$Om&X;3fJAxY z>|HJ|*m?1L6g(7{>}iB~%*PZZPBnJQOsVol84~x=v;_b36c^(9$G{Te3fZTw_G4{%7dl^Xyu(-XX9NVc;c)DC0%7r{-y zK$rNVlu(VKQAL04Fs`@e^67?8btjC1uf9I`|3!h-95J6SUIsjUfWHYKkFI*l=iEh3 za)eInwX3+dk_v2CGumC=?3Ytx;%qk_i*fI7>Aqd&@S{AzLOs9z=X&`+tESI7%m^h0}iV|4_i34n=8hSo-+nyg#*IJnck04wM{s4GtMd* zOh^Yr8+0XRX_oozal)wvYok-r_Ymb{Y&bI2!mi+(X;W9DPE|8eb^9MqtV`wGrr`$U zr4krC(9-E}Gh-DNmG1@}zuKvs^vN73G%R$8EHyJhwc|9b=a$YY2}&NYD6u zeG(H-)^sR+N#kq#kd`yf4j3m8`l&;$gz$rw?6z1}9n1Q(JqWw|QYqN<(yF_-Z<@O= z9S{-8j*Jh$jB*&+3C6y`BTfIJNWS|&#k&7u9)xmse;l!ohqsQ`IV~Qc%$p4KmpP8vpq2&;>i4HtIBA4<08==eYZ)ii5T2?f5M*4s=2*2Ts7g|Z(KKvT*g`tp;E;DzI(pRCn3wHF4 z=SpbWsDb0f2mC)3%ZqkXMs%#p3^t0Hy~-1%7jq%YvZE5ZX1Svl%G^qQ+HI1_vQ3cA~zFnfMm6nAx8qB zyH*Cry zqL0aAx*|+vy9}t5_@y!gQt_;;_(gMZL4^S*XAh&g(`1jaRWgXr(%@&mKkiZf=r+^* zjUgsTeRK7&ZiKqwiP2VF@s$k)tE1x<7Be=L@R`4bGy=^cZ!Swwx!H(V;;YmPrz7+U z7FCCbZU}9*>R_VazT4;`N@9w1m4A$1BDdy*eFE@h`PNknjd`lsR({NArG|?{D!p@mu2Sz2 zn;RshsW9-~p=s7*CdjgJWd@so6qoQ*O4W+3(CO%aRc+_U6gwelWL4y1u780mMf4Ax-Qq+^^zUp42gGpUvE9WK`M3IZi3`JVfZH6*+-PEAIN$V0Ud7-d(iPqm%w zx3aPkd6dRCjBP2lW8%{x_H#Nxd+=g=|8&F{YP*++Ga8kAwpo|7fg;Sh>Ty7ZI)Gga zxunTkIflVkY>^%M9R^Tf}vsfK18z5J+L?1UjPbNSsUX&@zQ@`c*n3P9G4mcIA<%g zaH?R8)%cTzVOHz-hHNO@eg3jIO|sz=MAyNCFf%_*75+*u!jp$FHOA=+=~R1zxgXts z(F;nyw%oTq>)Gu%Qd_;y6IS`ucKt+LE{!tC4NXca84(Llb~UIrqKPc(?|>RV^*puQ z^CZczj2akfmp?30heykZxD66QM~(<5r}w~gMmabE*i9OXE|6bv#Y1EBSg%N4->S?| zRvXEnyF3H?X7^IpCPr_oY3)UJeh)5MvB+B4e&L#t5B(H!Vjc;RcA*n< zX)xr(+_^pYvrF4hYG0|gqr0br0SkN>as(qx3Bnr=18uzGHS$8dh<1yMCgriBAKUtY z)BCRw<$vfIn&&c76z;p_X)N8(_6Dd>y$m=Bx=i$b^W@CGn|U6 zA=*nqGyNeldg|ixFN(_k(Sua0JsO$yvWgK1@RKp?PIpYk-TB9LTU)AnDK5cSXihA5Tx5h0)M#)8CGUV3IU^_HD} zfy^OOpWh9*RfT&bbvXz>w%b=RwF$WG@0+*39Tvv7cRcaO824i?<Am zkhz+pDQOQ9^`Y#YE{30(>#>qkMcsTJ@06&~PTlNaa*>mT)7QJJSpG!`aM_FEJM(L^ zx4kon9fca;UvZHSj~O4O5+4^Q>xsV#=SVpjj<)LiVG${`4|^iOo&$Wy^knrLbW~;F z9ZBX5o_I4VPRG_B7{qpqipN?!#alU_MYAVrL0sGjp;-MM=`MKMa8_BFoNwP^=X5Q- zKdh)yM2&Y(Xsg1dIn?cV)rYN;l0l51%639b;U{kf{{op>Ip++JpIOJKccoT{#S1g& zO}8Dd|GG)ZZK;leLG3b#C}Hko;tr6ZOU*TIaHcdFN7@337`P@hBd6x6_36R;$>-vZ zD!?6Pv-JkYG5aW6Txa_9W(UhEixc}*?&fq{_N@N(ANV2fby8-6g%16?Ycn73 zLTy|DqK~8PIEa3j-ncRW>kRvkyHw}A0of762W(@w+bCs{!<)IxcE}Eo5}ulZyxMiN ztSA?a%B-TPacV!L18FFe(i8_^M%Et>-Sx}S(Xf92l*BFmZO9RrXUu_eM~ zKP?45mN$g896n4hd%yi%YVYnr4^wml?Lp3TNi%L2-U>7w`)rqHrZ*(M-@eRn5dTV6 z-K7RJi>rj|THtpMswyLGm&RSU z`a#%**r;{$f8}AoJ130Lt~4UfTb80HJGi2 zn}-x6Kt5+0>`CV3Uz;hkB30S5Era$LV6ToxY9j|LCCd`w%pC$5Zxyu0g7KuM-!}yR z*99}t*WAy+!_#|>M;$E}#!V{i4%v-|G2UeyO)q)zot67x>AMbOQ49?n`oI@)<%0+x zS`Qt9Soy~-JA@6B`B0QDFDVZ;+xq+Gj?fmi zY_(jJ=^bCIcgU>-bE~V1Tg&Zbmd|*ZAvq%8uw3Xy*7S*J#DFHrV+33zZP4rxftAVh zF4BUJjoCRGNQFXW`agtZ|4Qsr(Volw`l;j5GvLFlkS-c~T|?cK&S%xx zbt8pd7dZ~a`KAZh8pWjs<@WNbDmkqBNZ+z0HI7@47l4lGne5AU=lPPI%;uGhH_W!n z!yD_`meJeH{Ufjfsi1i(s3eX{)qYv!oZ+;4gCTbALkBSb53>AoJGQLy38j^9f&^Qu$Tp7{107t(~@v&*} zjNLG{hz47bvoyLD`HU15(Cd3$0}A^gMSI{xJaa9YqW86=GnhX`U&+L#6o5Lr+zB97 zTP5_{d2~$=-!NOPH1XxY*~#FnB70lqB0k82z`K*fjS-h)oqnbV3(8VrWU0fGlLT~ihJ)2fbR=J8QT$QxKhPcTnkTP6M?uGmT1Mqk8NjnNdmB0w`kt-A* zF-JK4$#F@hC zV)6NpEr)jPp8bu_{P_qNXG(3Qa5GbIGRLvV>5|XgJidM|+02i>PlLHZ$i3QS+T&%u zfy8xaZF9J~W_?g7>xa9VR;Z;Xgv?DQ^)Ct@vtf1b+@gm2h7WBC58qAXh=Dm^qbPfo zsD1E5@|Swy>V>wFvLD=l$?7ldo}|5>L?@}JqP8=R;Epq3^r*UmrqC$^#Q{iTQ85~5 z%6pgT=vxg`h%3~g=jf9!F>8dV@3Ec<=~MxuVVznns~_3tQM{KQmta58 zs#&IZRaAUuI2VSE@D}1*g6A*y=K3u_Szp3CE2R0tlD_roPxsH*=*^ub$VT&cmd%?} z>rx211CvtH{oe4Z5ueXsGb?sN4ub%E_nS?L4vKu+`8;sB#3UEFG*5Qs^r{F_l zB)_Aj{psfix^wufEDt1`D?(0C$;ShstZZC^gMHo^i18JdauI;VWzPFzwKb^c3y!mOql*hKtWYg?hN zd&eH=7hRi|{4f?P%u}M{pgG}qgWg4p(7I9dVKSXdS>`27VTTm%_hs{AKUsyVOrFOC z_$1lY!gz2HvK*FP*zidKGXg{7^msJMQ=!DOKCvd%ZOd?Dz^G^7^9|Q1&|Gv?z<2SO z__m-lkm?z&?JbXySry+(BkD7C#{y6o3hZb=Yl(ZX~d?Qily5ruLByQJoFxiuNA z48;spyQd_d2#Rpt|B$x+KO`0p`9z$Zk^x1ft}f|Bu0UsnZn0-#_q>`Fn!{^!@-wbm z)EBQtl{HLyQNYvY)W4VpsQ#j>OO=%_1Onu#cMc08d9w(_A& zg*1jIwzAc`5A}%0KVuZ_O`|h{n$lOLjgG&Iz}LPO6;DTqA%6R#Pc?(GDXGS9t|Am5 z><-=qR*4RVLgCJIgoX){B;6lf(x5*hU}>QKv&Nt{a55~&f`=LV*K%n&W9x>~ zD3hF822+1a|BuE{*(qK*^;pbfKl7ghH$zxfFLyAR6VY4${k8sY{NkSAFG`0R?4g_j zZIWy(-@CBhhuqj@PHt{d2U`tdVAxo8z&=;=K0{7fLXMYK3K|wY&wDw-fGAGkE`&=n zr1XE#`VnB^7T2`67&U$uuCp7XzLG6$jxY$i(V64*l0L4Wlbbbg`zbG9AmobVNr-k) zH71l()#}H$oe$Sj{vE>aM7>LHHO{>ZToD;K+}&kQu-wJ*ymUEb$lvDxi*9*x^2~NP z`ZlOexQ%*B1EVuyA~Os@HH_6I5rWCF8VZZD6*OxvqNSxqj;`Y_!}lKzcf|^~11>#> zeaI!One=FED9wuZYA#hr=3_ZuL?GJ zJrY>Pw`%4qa*nLn%Uo2MP+F#FF8hpdzUre;Yi|_EolPknJH)l5hBUU?7pEC4?<(Pa z8H6S>dU1IKYl+kvFgIFIgVrMFwP7ev`2%;@)$yvy zzX_M(-AK;F6!Ixs%`l=5-C1BkQnVOuDZF^|iNO+Jk*YP%{L;|8|LK1M>_NT6ey@Fy zYi+a>+mU9}R*Ti>ubF(%F>z$d(Dr4(#Ct4hUYNsD_>(iud@0M)3~b3fi)V(NrT%lI zYTvB9A6roDpu42eWxKtj^;N@I8kBGVF|4o_5U^gYzcbG~;ArPgE}b(gJG8&qPUEIR zP|i|S$U9@)Y!Ju8m(!lB;sWFC^dAaOwkwY&-adv487zGJvB1zeM;NB#OFt!RyBvYn zxG^uI19hlg^ss-bN7b?0SK{SCw>=mJlV1GUs6+~ScwG0!8eSlsp&JOzMVhbGc zZNYHGH97Ge2vqR}s=Ymqed?w!qAPwTFvN!~Waiqn^Wwq)EQvf^N{tQxEgdv@mae-I zs_{_KP{O8yz7{E=S7 zL%wQ>Tz+-@Mc<=8(&pog z?%ZknSjDcE3T6?|27KB{!-!vkssDJqqrN(8V zQ|HCjE9w?f)ujqc@QilaV2ZMa0Hr(vJV)fm9x}Ss@LWxRmRaq6BHK3MLH|7eht{uw z*~fQvR6_=GGIy$MY5otAzJxU$*+jrGyM?BN1a5$jDt1YJy1c%itniB{}7 zbO`?TVtSFou;fqYhk%_8h6UHF=CC_zAH9!dxYpuW`@Os|u`+a-A95D6>;n6qyC2~H~j9tauN@ee^3!yo-;7 z72`}6i3j^U*vPetY%=%t-HUt1yLCQrCb9g|tIkL^Z*|VaVlmARcmRvCj|vYbxS3lf zuimOTDcBl&k2`_2#kG(08GiUzZUbi3V$8#{o?Z=sU+s33`d(`5f!uls$(8gVF_*&yo(z=8J5x&(~88+}e6BCK<%WH`J? zS@Pqg-PL0kmQ_D*zSI@(;YaEjN5KRe5Q2~(UdmMns>xoK#I(8&NKL83K%fG4)vY?p zk5Sn*qkS#3`xpJ$W?$TjS&7Md3#47T?|>=N$sCGyl(c0TKdETE)fR8yl?I?r6=VR{ z;mD`AhW%4SmtfE`oS==FFKo9-m4yljI{VTezoc-699t1u@T?W%*_3}DFif{_mNIrqy1ufXXtln*2~5O?njwC0RK@xot(Rj zj4VDGM`0U4&?;GMuI5Zi zBw1aO5>3Or$H7nrh8nro>zPwH19eGOz?lzAh93(5crCQ- zfL);cWxX)7bnOJs4#5Uw;8!jP`;)cJ^$Tb&{Eyc){<{YF7w?lg*Td>!n$7ZG`L^kM z|BSbE7Bnh!oG(@WJvIf#LH~3v3O1a9O0u@(On)9K>6-wt)Y|rs)W3b7GrbjW*ISZ` zd%U!CUi84i_Bd)(Tu)_3qt*sFq^y!3Cm=SUwbq?B-z>7n6|(Z|cibJQCiBV|;`eyH z#a+6ohfm(~T>8wSG!V9W;ooE8U`l1zczk8>Skt0(^b2()HT&@(aOMirzxAtk{Z!Yo z<89{}XY&VKetplos;9mXOZ1o9&$fr3?s#+W+P@3wT>2q`uvtYmKbSbBEv93D*@Yiw zpSnpP@$Xzw{_m3_9Zl!`{o+O`s@io~gi|-V+1Q5Fk%b0!tThL;YZUH?j1yq2E%NpR zt*ntxnpJ(~G%|Y}jJhULqYpLSq0$QZ%oyOj3-*s3dAimbERqIU;CZ)`F2wc3%&<>W zn?6V=>#P;_*N&o5zX1ILNl_lqYsm8RKfG8TiS3|TpeM%8K->Hmo90<6n6*NG5z6wW zxuUof{P9uuEM-XcA;xKl$BE5Pe;u*Gg|;X@}6el>A}9W#b`?^!*sNPI zA?A6KhjJ6l-l#wHu;_a2@Eb#wf z@2!L4`nGjZNJt1Igb*MEPjDxA@C0{n++7-L+zFQ8?oQBdXr!TW2=4BU1$PJ#Typz& zU!8h8yY^1)I`;0Zch)~pbFN-%%{j)DA@lo6)t)wo#q(2F=3m*^>aC=W<(9p`&NLS_ z=}tlC@#t{m%k^{y}a2BUPWS1KPN>w#wS5wc=v}tKa7heVZy; z?cX2SgNN(*1)L2K1KGsg>bQLEjL=j2#rjhi2>bk41l~|4U7u$%wsLJ&SQr=)mU%GB zk3rM!BLYR^s)pzMVw!B29eKzmFmUn|e%=u%4Oc`;^=O6~k0jp45?GHJqx)0}`P5Hb z>)j3;Klt{KzaP4=+n139t(BCj2Hp$aU+g6*rZj(~m0N!uC&&HVS zsUpxS(qWFH~4^4AA`XcjlhEOqK$jfY6J1lN>{W_~Ie?%r6@ zpE*!3oP$i4(q#!Y*7n`B@xEJJi3pQa$`|Ej5qSUY$p)#5T*|WNsRlQ+N76K%UwgTklQv@P zrsCzuupsRI0PwI>QF4BMR3=$^CKdH+c{I7qhDt3v%a}lOJeSK&mN&O!1z)GGli5ZI zSmNW*_sW{d0^fWcn5(V@7<+H^UzB)+%oUo62-GT-NI%Ce~V%CY+)zUs7p;gwi%p+OIVEcgoKIY(BIv9QOne?mkWve~RzrGsRhO&?hblo40V9AF4r+cO~4o za?Hk8W)xFJ0ZE1#tFbRF8)KE#Mn&mL0lKeext~EnM5@0*4Uzo@L-df_QhOq_kVTtE zw=xGb2yM4oSd8iJ6SD$LmP6$s6+7oAm4jOh+ZF1zuQjXFB?$2r-Uhv3um$N7Jd*uJ zB>$&JbJZ(qAHV8KT|?Rk=!xa7PnKTQ3%9hl0bHoF%z{py*Igy)&#!%*74n?cBY>r3@Bsv@pS#&pdaV?H@9gi~t&ArF%sN$B$r;WMMLBbH_3)Rt9yi!0)!XaEYCM0} z!r0l*D@k?S)L^6`qlSpUy9Z)9Yii4octzU%+sl+<$io2zu6=nPl7BPxmBVz zelLM7^*u}TF<`iL0AmkJ0e%25o~8ikWTcw0L4%QTIrqc;gSWopIEh|W8L1?{^rS$m zUn%GI6U~&qw3>%%+BrHN&rP=oqD@}+igmU|OZN5(0|3f$m&fXwo7@5>Tf9#{{?@LB0Qj_P&>WGAkOn9X=ehN);D>w6kwO};I~X5?c7eUN6x*Mq>w}yvMi(aDU3V zD+Yi`Wnj|KS{>6mdsO95VP)+(E6Y!}r!rY0)Hu}TRJ8iL`zF~`+oF(3W*O^`5y^qlC&?Zq%%XPHNVdKtJY|J3BnXo;F6 z|JL-=Y~l97M1Qa>b=yfQ$R0Z!$s;&YU6?lAj6G6yy`^G9ga+$Q_XzCclgESrVw`)p z-fvV54b0LNKG(2HjHACzjf`{e>h>lhF+{hWuDK*u&y9p4-cm3nUilpLKikMD`l>Z3 zD#M`)<{VbDq9lA19-^p2PTdpCC1t$TcIEJJ?~g-xICYu?AT~#gC^4MLsF%-5AJffm zW~k**nLOL^a2w|z$fej&hjcVYo1fj(?(hH?+tO&9z-kk6_aw+;4p!v94~O5B^VxKZ zjXp(K{gIyCd0_uoBbM*ZnmYb2E*P3`;iUaokA>9vDuGMO9AlUshbFupA737gJ**4R z78z*RzxB32=(ic+cVIFO^Wd`gX~r90T?UBInfmu>GKc1#0TUz=^<=Ks5slBY?HNgi zLD29==3~L(($z+>^6jrbJ}8`_ZgWs;Ld{?L)1!3~&dPCsT3HN04+yysSF4(~!2%PcuNxKOT~J@okK)>Iqv$%*Sx=x|1x*V5u-);m>HS z{;agW%cERSXXrLpb?YwF#4XojvwHY#DQ+!n*u@SWV*9EWUQE#h+Ev!1>0`H6@8QPh z9ab?+9f{0F4?^$SB7NI6&oDOWRGle0aB zoM2K_F%;=Bgfhehw}lyR5wbY0e8X5%rb*+=)})Fvm8PoMpy!N}E1<9{lv%KnN;747 zr}84Wn+=)6^33p&&X~Z;$SXv_c%RKE!g$0udE2+jg;CIGYSN>mghwbLJyh6PN=Eu) zz4w_PO{(l#ac<;l^6MX$?;iSR7pPhiVIzXIb0;C3NTw;cY{(D%*RR0~49`h_v_xu+ zZ+D4unRZcUlmatF@dc19ho5A{KwB_1N5X4OIgDrVa` z-zWQVr1(3x4ox|o`>!uAWy>QIQ&8TN1&Mp4LE}FE*YRbR(L_v{JBbbjZ}?DFzZvrJ`tAw z11-G77BLHqHye_eR6oJ795jIEAF}+t`%1oC|KzN`ZRoMZM}K{9EZ=UMDWLr1vK!p& zSp}TU+t`EU&pjl@$V&?=$#Bo7M^ZSxeQkYk4CTR{`-0#PPj39aSG{L*?#8T9!xbK= zUcNgwT0Gc84YP82D9@Ixold1onB5@oDc$|mi7%i2d$|w1PY(`ZrMtMvkno~?2w=Le zF~N!8p<%UDEOq9azL!N8-T1lwCBjbHTK?#5pNLl;nS-2?G z2{jaOkv~$Y>L+R}hM%pzeD(ayq+)V6daI1nlR2s!P1!iEUWi$rt6JBxZ$pr4R+v6IAA6jRR)d(7n!Q<<*qbdDG z2_3FQz9R3HDHBCvXme0r2++z{+hFx`hrT}lVO5{rwX7p1#R7L#?Cxa?5k%TUO94t1Ns>b`k6ZMp)kaBNyeBxw} zv|5eCdsbErJ1ixn_NA(rGENF~$X3}j5A}16+r`>_ z6@RzZ$xsjAl1hO{OKouyAX*=ekwUM6@Bi%$GVga z@-M&P*>pq1-o3eB)qeL+Sxf$)jsH^B-)_Pfvk}>#`;ptRJL9vMzcE&S<7q-#t`Dgj zv2$HsffweZ^_KPzR}OVJKAy;MTAH8nXKVtWaxX99O|>&G&p^g2ZIeD)&|j`QG)T}Z zs9KP*IK~i-qdcVKHjv&4yWd(OxnKr5&)d)4jD(sRTB8*&W^PIds(UlP{am8R0exRe zGsW$27zGX!e5>5y^!rz&c(59iB<+mJnL zk~E;uC|=Cr(2WsMjCz}Bx^oa$k4@5;*C$aYi;+`RI1ZTDy=` zcejJ81vU3Of)8kZa9`_lgKOb>Upr|OYx}fjtNZAk*7VpM%KN{g&N9CpzEKg*Ctr}2 z_#<5wG845#$k^VXFMEXO$0H{sJgWgR4JA#uRKE&kHd|<6=Z@vxf(_+2hB-qN6w_Lx zpDcM(I_ZvkjfA?>| z6b_S)O({#}GrYI+Ca3Om@+aCvc}P{`CvJ7ay*`12ZN{*4KebckuZ7c;o>8hnBL%lZ zDSSGiR2o@cdbV21Y5A3G{gU!K{k0A8Z34iQ$8dj?-eC&l>+5ZAKZ(w8_o$u^nY1N; z*;|)6Bd&gI6Zb^=xRbp!Q?N?o?OL+47TpYn5$7wlxf5D$wzy;(RHz|kWakP^TC`Q8 z4iaCmVfDv~0Y$)}`ia!E8J=n%H!y8jmwq)_h#vQCl=r>J8ZQ!aFwXJu-Q>+L6hnP; z7v{{aLiVzOCO6GY*D~`tUHOP>Tp!MzPV=YM0fEZ%AqNXIW&)qo7~GXwxEA8eyUpN|ab5Bx%rykH&bdxIr^s!=99cE@uH;zaWsBIi*TMm#KS_4Mg~ z(7L~zx@;}^Gw>$V^4otElf;A8GulDEu{oY`1FBZYn! z<}e_FA2NKfs6(HjjcZjap>+IX9@h}@mPo)gP=z)bqn0tCXzfK&n}YXiA>qFz#ls-5 zTuQe-K!V(u%+5G5oh`mx^mM}^gE$-X!;5FuX=fr$VO=jR<7@jQH>d_n!jOrErgLrH zyr`reolDDZiqi-DmtW8`K@9ZX8zxe;(RE+(}Xz@lRE74bCCP%mX!=S-gB-Z*@ z`D~SVb!z#{N-$zEsPb#9b=r}RcrRkyp~@;9lN4_#;1|l%Zx0OSg}J;~@5mQgd8quk zc!u<=kt+6cd8l_3XNflukhg0zf!-L0i#shV-XI=qU%)3+iSZ*~$0Pwhx70HOnb&8> zB<0m1nJAL58>+&JS2i)?>@`4jz<2d6z?UBNouqqWp>9#Cq+<#dKbX-;ytnLeYQN?J zVAjN437S^E7b_h3#5w6~I>!1#N+p>Lh3F4yHUFb?{|9O4|4(%8U)mb}lbillUs0fb z);HWaF(b3>e8vRl|um2OeQtEeW zv|QtUeWqVKoOLYvZImaeGiQ2jmTV{&2-{mhnzEB%hJ%}eX`OD~=v&su4?do9Rr;Rm zp`JJ;32J{3*HK8VwVInD`{@#OHqxF6Q7-H^TGU8N>S;PniR)N^AA8g=|-Av1@wE)C=eDS&z)Qs}8= z;TKig*zp;ayW^<;$v>jV#F3qE#FgAB`((7oe31TVOKq<)VpDU{+o(~fWnMjtvJcq^^c$~-PEnhvU18zK$5m#~u=5t%xHb#N(?;08$a?1P^!n90~a83 zsz&Y3;*fUN8Evhgv@1e7ur(T;R&A#WDUynntJ+Pd>x)G0 zz;EljQ4~G<((CSQ%Tt7bEAgA0o=6s#MT)O(@}%%jhT$Q@N^1E4^e0SmG3(s#jMI^^ z^_6eW7asflcWs3b z`YVd%KUsSJD*lsa8|lGDK|wkpIlUK=O|pDmb+>at_Y~y;-(1=-fmM4~`;d&5k^0NgVT{WG1HXIHUl5I4rq}iKxUddw_?hS(JlZDrpW?WInEH>QS18Wz=_naQ!22>2I*A*g-yu zKe>?nUZFnWyJ@I@0MkTo7b?0YLUKlRwsf7zqg+Z({z4H&a+O{t&$g80kpBrP_22nM z>{MN--Q3;0%53AS0`M;WZU_WXo&Tc1R>!VAH6e9YeUbJ35I}3#%E!E$kA*i1<`N9( zD8kItz`!eUZ{h8K^_MyO*g?l^Ub{Nld{DHdy{08Hu+&eU9y`~b z6sjL{wY2b3b{mr(FK~HR1O+qMkA)4$TWUTI&!PPuA#(G%HPcsV4;Bl|gK0RoUbDG3N`m z2*D8EA=c8_9`PQwX}bz=o%0G3E|VgWm7s@Lq|YDOm%~qijW+5r2N>=av+9jwH?wK7 z`opwIyNLshWr~u=VnGv}3SwVe*}Sx$>u%HKCQ4681UrioR^@-gBL7Pk|M?f{Z3gn} zkGx32IU4%dp2 znRR-0_60!bV{BqDTrg)ugL;!9JV+LY{eDbzcAAeFt|0!5WQ3&a<2OlCZ})>Vir61v zA1D3Fgl~lJD?bQNXWt=_BQV zdAOiqZpydefYNeI2Ra7ZEcI~Y>oYEjn_PKgE7Q#Ol<2PhIGO?H7YfbJPy*Ol3_2jo zvBd&%J>-c3&oBfe_%w2;U%pL~mzZm043BNBOXeGorlmH3a5_&@82vOk@@9&)RNxWY z35ofG9^EU5(23II%791;-}ZvOck*IIBy=GutiE?~b9^7>xZ?096!e%H=UXx^g7B2V zCsfxC)VAUJ)(eQ8&T5xIOO^r0dlj%Ab+jJI3i)>C{4p$8CL(;vhbAeveFBd6kmb>|T*xtq9 z^fO13!o*aBaHROk|F4w#pR`f5QLQ!vzm$HGRJzm|TAuE`Nqs9(V#HN)2zP1)t>gnJ zSX~jWrp?hT7HiXQpUGs9U=<%lh)DFl@it*Z^XezEFf0FolI+GlSl^nS*%H0hklCHL z8eUttr&V zI5<%?VzI?LBQ7`G$E&p-F$w*eBQ+rG{=Fozqqd4=Z%@E^1C*~zDw@&F{WSWy)Aw)K zs(&H`efU3>KOO$q3Fyj_qYWII{bl@R)!juiFgxUQ(m6z~r@9M*5;cI_qI8(wKEx(F zP(LIsHdA{W9hWI;I@c|q{RG4CkK#tdWghSz5M(*@b<5|f zMPWzAALpU3wU#Vfm@4D)+=*nCg$+qMkGlI?uG-(Ro&J`|_dj*K|HcBlOLt8mVM7Qg za)GBzUZ2|zxFFuAe%%B6C;&P%6cmmJ%<|tDtu2BVJ8GVRgV;_~i-GCy`(P`me`iPi zQK0{x%3QKB*++5wQf<>V3c8#w6)fZLwD<|Vuslxdt)uc0jUj<((z|5=<$}1lHVDu5 z$24XVN9m+e1S7HSL$^f@I8RpNN4@OgUFQ zHNthPIzvu|8`OQ(ynTaHmM7l%0L*SdN=Or;elk2?j1$dwBW-twV<;1=0_iH^udYdF zgoae<)u{JQj>bKj#S?D3|d!G30CHUmWI4}=x%5euKVbZj!tu&nkS%@-OZq`;@F z8Dvu=UFLR5j8s(*Ez32mhime6UAd;kMt>q6sdu=-2V#Q~N>(9UnxErgFC)8uk?aU16%QD_l&H9QyrCDb56#B^%*Ac9$XByL=Wqm8h z1ZGa)m0dZGP#Z!LbLd_^yx(f%jb_fv%5|z0w&21bHjH+|E#S%MFzFt^cj917Ts?zz zeqFy+-|QdMHKQG>jJq;bJ?>jWN65lFrmU-7`uH=>4NcF}^_T(*ry4EeNB4nOyD}c6Vb05~DsIZ{*K}V|8bLgv^%?GZS2l zv(-EXA(9;dv+_b=;E}~FxPKP40PaYg!Ux1~jHcwKE-;aMw9=KT?NQ-x-gjHHB(Ru`wovWyTe>XR&ek zlV6x0E$S3)GFI^PrFN@KC$Xzk+8P$?JU9w6rl8ra=_5?t!n3Z4EK|X6T12qbHc~$y zs!VXY#ofXvOX&E1q@Opwutx%kjJ4sW^;wIBRnAPkuV-u-NiFN3X*h*zMtZ2*(%ZNI zpf#4@anKb|s<`?kA9R5t6$E?~@UIRi)J(y^aB3tk)2Tv2P>uF3&>U!~mBm*yZ;NM@ z{BjH~CHu5SwPK<$$1IX83rPe2rAwP(4J(q8mt+fr2_k~`=~2abzyU*4*4%uuk)$g1 zn`NEVms9V?Tx2~}ovkO2c$)X?g+C9yG0-e>bqdQ0&k78Qw$k}x|CZm2A-4O1L$bJ! z6B|U(oXW1pf4-uG>ozy2i61&mAfF{8y`Eq`0%JRMu{Gr^}-cFSVkD72!4@2Pvc z_6~#iGB9x<%t;QvzjuWe$WErm>(Wxchb3M~yN@f=`}0+Oj))$^WB7dj*)4T8QMMO7 z{Hx2Nxw_eg9a*#3Y(@cElX6YIIBhSwE|wZjTU^|x_W+}v_NUpdn^R=#%|b+13;o@zW@ zH>K1p!RXr1-zE$G82WZqBi4qN_Aqd_iN=+Qw4+fR@H8VKtVS($_*v?)|2EQ!&D@KB zS)l@#Z6oiH(|nUfm=wKKb=)rv0LF7(ok$Fc*;tHDFq@Q~Z4Jt8qzBKFc8JS}W38H^ z>*($r(AuU?aa|u2sw+sks#rJT>ZJ0$>XcwHE^q_uvEmbq#}8Y7X;WR+WI*gX&Rbp; zv7Im&vl)9}Gw9;JowCgwgZ>N>AUW(wNDYsw(!|yX;Ur}_@^IfZW0;CtZD0@|-GggM z$jz(ova=+*HqdiOmEEd>RWsQ$D2nwbw&+jhBgsKk)M+fW^|k{PpzCypnGEh31QPs9 zt9C?^J3FWQeFZ(%(V84#f`^{4+Au~?jF8iJRPMclcqPQU5exbe(;0gL9!j0m=|usmb4?&~0cl}kT9W!5 z-5FgzQDuR?DMY@AplH?=6Tc)fkW|N|+>qINZ1->@{N=TBb&|<#z@=zkqg7%%VeAo9 zA+lCp`F5K>DZ89Vb=iBWrhBUXBbO~oUhmw-Q@ax7O|U{v$v}-m#(Ds2g2|Jwl2qQv z(?gCy0gG(j{qpg=bjXYj%6y_)@3tEP41UwA`06h!kZ!y5OfixgP(U!B^^5Mey+8{> zWO@_gUmb@3f%{P9_#tZg@Rn5Iyw1ly1PhnfvxEpU5YC2zkmIUGq%CsnWSsdd?)pNM znWJ^O4qVD&ON8Q#<7qV4B@T^MpHQi-#yGoWZuY;d*(ufZ+P+3D3+bE4S1Ss2pQEi~&wX>8q&XiK z*N&B^%S3|@oG}4JT(8qP`Q{rX#%r0OwKyuJ)#-IAj8z=Se2rjVpThNUPSEmu7&6j0 z;qojkv{?1UI=9SUGD0z*yl=`OKoIBzGZSTKI&FiQKCL=x1$P=P->gj1dDRWR8(1jx zSXZSNfJ(1j7IX^;Ju^hJsdlh7Fqfv68lS>y*yUGO6zQ=piY!=}lWgM`6>0FX4O4%r z0km|L(#VpiHg@gL83OoR(8sX#$6bE&T101NGu&Eo%Br+VB6{hoSj2+Sx95I=(Ig)G zre;JMutIzCv&LF`I2=^=u_{S+KmxAy>PS`Wo?GR3kN{S2ZwJY)MyI*|d2RWKcGX6& zhYPA-MjT_U%%yggsKQHnhjy<=fMr5ieOg0tL=|3b*-sT9UruWth)o$PASk<>;UQ8i zQs$2bNnwiOodBuu;C-Dv*B-IyIEA;=ymySK?m#~gkn99N_;+}zr>xu7;PqBw8PSZv z6-&)ZU;|Tc1H!(cn4dh(5y@iCByKXf6y@ptb_dZ@c$_*cE_tPF=A&NY#z|*l$bijI zCTW?F*3ijIJ+x`*J2$5{gZ&#)6Nb4?f_b_J5XNfK)=``>CtoL43(wNEE$$ngusKrk zZ7=Q?D|%8da}k`<|f0e1H|OlzhSISZm>WY$<;^);IeL5Rzg?@chz4eJ~7Hr`*MAxNp( znNq&@g3n`?U7j9XHD5CRBOuTFR zRpK@ov7U_;W8wjR=c^B&>j@%E_Pt}dC>1iGdxFW8rRs=@E?Ied(A0~mYYhcqk1EDi z)D+?A^KhV>wD?}9mj1d~DWjIzJUD>tI<{0-$MqAZwXgg9Syo;VrLa~aOX1igsXd|g z!eJ3T%ggywJS^#|-Ot|l<>aQ?JG!-c_JVp|K78q4s#jwbik?FxZL-9j(?a6qHFB8B zp0szNV+(chpgE`07f-8{;X0>T=cmWjEL!0c=0Yj{BJqN|UL`=A|SZ?dG;Kn*!mO(4pb&(7{+L55R-Q=y6mEsmXTnNxqYp zqaq)0!RC>XQ9dp;T`z8GeM?zZ0Wmu+H)z^Avg-Jp;LS3WV8d0Z>X4h_zQb*o+B~wt zV9M%W_dF1xv2vXihUTpYU5y9Sc0)>rl~_i!9sH7*t8LHO8&+|N&R zOCmM|k_l0J=gKblUxn|%xqW2fRtqUq>Se$zCH zqi(t3F(HB1+_-GA@sCW_nsXm^!x!VVXYHn-J2#QqS9NR4Z$k7cKDvt@3?-9O_0!OW z_wvC8N6)6t>s+NMj4Mia`4Fb`YO!KrpIQ63(gB~VN4Mou+VXgsODZjG*x8;-vKp_d zO!-c{PM4z?FVp9XsOr{$x==IX&m}D}sQe_#wCV|@WgB#;^1%R(dTvblC3>_fN-n?` z&X0?2J-##uaFdqf_|9B_xrdWo*xVct%I#iu3iuMGP~G^|W4tE+%8dnzK~ zoNdrGOx()WM5vVg6tSghlSYC#8|3Zsu<{HRB5I{7eNI+udHSMXAX-R!#WYT%*R+KV z)BgFpm%abeu=|hR^z7$K{bOusCMcbDaEY!X&$W@KuLcwz2y>O+X?o@g?T;NcKa^5k z<9&PkxSIpX@+tBS1wd%a=H)dT<2Cfi`uz+O7aBg-3VvED_57z()jzbJ~JK6!r zCWSVxc3Cb{!`@L$~r%h&JZ8I?N`T81$Vkt4&TNV60lArTXvyaMLWi}ry08t_evL9_-&6O)?W?;-XR<-DyjcHV$9jB-k<*R)upLNA~Q7Xo7*Y&t&8Y|_dpq`jY33tT8DtzgBEFN*H15uWl zqJjlfb1hk$w;Hr#@10IvFuYIr1X(au(E>a9>apVor0CFl2xJNn_t0s7|ChB4=X{<` z8tiH{Y@850Q_JzXdl*wCp{9>1rJLLPb(>>^udY9I;qg^MGK-plq=5BZeE7u&(#CFu zm(Eillic%Mc2nIqE-%&Uc%7m#oHE=UzoUZuQ2+@Zj~1K;I22MfGL6= zQLcL!Hl*rzl(r?k`*fPu4Xsa&xf8e~K2WCd4*I`bg#zgQtX^sG@s$-!^i^N=!`&!N9tUHG>7C8V}O6w~@? z5hyw!EN7^}OMDFrhyI~fXcT9^ip-Tqd^$D`J5a&735ZT!=N@(ht1gTQwuU!EEb`Sa zMii!d@!Gnnf3menRoGursi7IJC#U6LhMo_pda(*5aiG->0^CO19DP3 zu<*9h!ADJGrJNs@RE*6B_zDeG;CPq{RCk($u<9_A?2d6B zg2yC}6C!O%Y2V_i=!Hw##e52tp2){jD~oSC_J3*kFDvhVA#*Vm0s&N9YCj_f-*(hvv&s%)62CN|tR?&($vmVkUFc&9ve_bu#L};^EH&D@7QP^s`m@*miXtFC%lqicONqL+#R; zTtxA?x;4mJ-gWFaHueCAJ)Eg3NG^!QDZ{_5-3#c6{x!Q#@LcDHu0gWVMNT(7gqe@n z5P0Cx>B(pakKzw9Gv_>Ob(iSvTV73X1fZ$eeYNCkZTnFXZ!7nuKd)XjhE z3Dh+JRkE}ifizc)7Ds*+LkyS-EJHx0Osy)!E{>~&^j_$${q>7p?ChuL7&?*mSbCqs z{XbhJKeobsN;b~GRgzh+wfB|BxC@WyYceYd9XOSqZ4I0onT-*du`ZPJZ|_0=eXf7x zR%9dNlWw@rFYg;IUeMO3Wjpg!7xtQH%Dnmclw=i5HD1LA9vu-8Z5f)NWtKo;`t~p2 zg6FvNCZmER_tHmI%X8x6g7aYGbzL^A(fNlKHp7%-I*+Oy7bqFoipp-6z z(lN1qNr}?$n{F9YBAjg*=u5>n_7*N!yCu+OumEoJUCQ2)nG$rGM-RRsvu!8BRj?Ph z%3f}~6R90ew4tD`7hh;i0one!rmVrzdoZCkw_z6OG0$sv+<;984KIv}l^)QLPoy|l zsMQSyJQ~%bB&3ejqBQK}b&5-=?{>^a!G8BQE&s3k7ki}WrmI=`0DC3s1K6eKi4HjS zooB<*7ojNVoJ+IowOI)YoVOsof4IdmIQM0SNob}eU=|JuEVEZNDzVsW8AJj_ zn9lOQsvZ}Cckuw3N#7hi**q}A1&9#UnA#<&u-lQEe!9lkwNuzmaMsTq%NkyaFZSYh z5rTxJMAoK-=M>KieS_A14zbo`V1az8OU3MZE%n-O}0gq~+ z-S*icNMDY^Fo#4fs*%aA;m-1@Dh_!V``U-(J&nSjxXTtlz<+Ep3U{-UNA}mk2j=D7 zU^DbC&(C)u)K$xZI2w={BjhpK0Y%NCb>hx;kuI2cZju`%J=Fo#3#pX81b|2~dGZ@! zKh>s{x{Je!a~rR>d`AwtZbOo)r)a-W{BEQQ%aSDH?5?%9d(7UI?A$SO@r9fB5AIwx zuLyGQNEO_gQteH-(lH0AeZ=hBFA$eU-)JS1SPpBiN0wEZySO%tIWr2L zn(NdAD|8r_sK4dLPsx&%ADyiViT-dEVh*cOk(StCkShZH^MyBeEiwANm>^1aIPzYJj->&HD(>))ZUFZIYe&QY zyJxdr;mK7K)AU!5kKe^q0>>=PGJE@_`K8fb(y*K1D;4x?^kOeh9=*2{ys5rRTk2J4 zTp%DlRi3B1^unGR z;lB{uda8JkRp4eznOysLZ|#2CtcQprsh-jXsFkS)t=7XF@t#XMFjB3U1p~gw2bWNpmx;4>zkDjVe-#wI$7*UpB>HpBK)95r9LF-=PQ|t$Lw^A{ z^XdSg?P2EU>}Lcxz1q?GeE59BA{^|d<&wc1{0{og8;x~8+z~hyzgV(ARx`WB;?OcO z)Ta=&HE))rwSExkE54n^%iR)CG;2Ygr{M&;E-o3Gs@f4Bc=KD4JgubMk59PboG@&xqXNmI{O^;aYXUhl9r&5lAiE` zvgtN88V6AFd+Za{QK1ej81Q_hd>`CO$#7T#f!oaM&$dk2O?Ch++(BNffxO{l`^sXrD#IbwqT>nDUQXOz;y}Af<8s#6#XB1^C z-z9V1BXzypqyrVlH|C;_YuV3h~V#9AS~STq6OF5 zFx!eR_+Cx9WF~PZR=EOQ;I@le3#Ve57OJZDvTynpgak+9d(gzwf`$bEP8n;2&z}E6 zasGvZAm}+=ARg8qq04MOY-ulG-wxkMSMo+dJn@=Sb8CX0pP#g1FO0`d9SIb;&XcY6 z@}vWX1;^G;vhd|aUT_X1lruFxMcmAi%9rWUa*Z^_4=JG^|G5bU9IQ0 z@}8>2%VRr9!zVvSmuf82rQRk{Ju6h`P@}m+ohI$?k)Zg{w6MhT*fypsXjx0f7&uU-H0iUjQZ#DGv~Rd@;gJoxw*3ai72!YR$q`DN7F&wvwj@o8sL%I}XyVcr7i zabE{i=h!c$6$>;Oxcr!nGpv{U<%OffS~U7!UrH76ijJS7-AKAO=DnxP@HkSon^u>v z>AAHS8S^36jVl1A>AF_B8RSSzn@8Mlcot5V;6{8kw>iQE49dlycTo@`k0FyJilU|N zXTY)xFUqTn5VZQzeVoZE_CEGSSA|+C?vPWSB*ysl1mGT)wm2UkwX%G2DWTLm>W|Ph#@taZMWh{ z`M5+aKEY|`ATUO{kh~d@5!XA@VbHqpgXP1<8Csgz~&u9LRXG||3l zfMsY)CBw+d+H{!S8asD-*mPn5tC4uW``a%k5~wG<{njSD*fX^1dRmSbHES`~+9sKHxjLEhdQefJfJUxv=-44gcAT3r;6ysGGXyskoXdhS%CUsATl5x0&b{ zBo!bzasb>mcL?$ircc;=KVBl$=p`l48g-8LCl(p{abhPE&8%oTutF`AXjnXTTNCC8 z@uTOw=Y4r)KxeW-k+Fd-JBxcjx_bEKdz9l=vv{MH7WWMKakjAdPalv>VwII6qHEFj z6R}nr$4%mHx^}(-dt_>Ple`8SyW%|F7c+bMbr9g$ON%Pduy6WO%XqeBrUxz6xSn+L zSxfe2s+rXHh;yNYHJPVFnpvCW8y)JqtZH*QA{`d$T&jj)gfNkWzT~d<@W*riNId@q zWnn4Xce2C{rFyTsKR=jvo9AjaQJQuA_(Fr5p4nEuQp+|G5f_$f!Y#p@7=pO!8;ldv z>Whfg;0v;zEdFfZTrdge5*hi>GQDDl7oPvDOn+XjQWBo@sdC1GkeQVADckE~F71}6 zSmW~Ty^5J#L>WCe!MQ#|no0|di3EV%9A=Zmh z?}o+lMhn_KpJ;IG;fMmg+z!U8vv$(_a_4&TR0Qstn#wMXO;JeJ!2YqO>3D?CCZT!= zJ-hxs6sPQr1{NssAXhb{eM>xDg;ab|!251@*mSdqdYK7Qbb|d#Z*41_u3?w1WDpoM z`UgQgT(@jVw3k#q{`rAi=Gar?JjcoZXNpPi2);}VQ;4WYbQ4y>T%pBx8z;RU$>gVtln$& ze(ufR2@2$jaqn8ChX#a#Mbc5jly0>SI@i!RKCF=KZM2k(;uI*b>g=^zbCKKd%_5>8 z_Z-aMUoMjz=DA^2Sns@kvm|I$IE2ec3(j3v?Vu@C6Ha9{pQ+wznz1!Fhn;6-e%f?V zvs*ptA{&;0cg|=ZIhv)-Nx#O*93|#G(PrVL&MaOE*l@`th zJz3pJMm$V>yI0v#1>d>=y8xMeFUu674OgrO9Ai;w>1b27culLz=@7XysbKbo(XU>~<-|IgXi|$^v zYE}KJs;hqW`+iO%CS*$pceYr+$H~$g;0CgB`jh?Jb0*9XEZwr1C7sMS+CNt*^tU-J z>x93Cnh@`enRoMuxZtDV1S^i|*}CBEU3g=AM~1r!`_YD3yq5CCgw<||>+pSM z)3Z>lYF_%G0KI1`>M30tlI!Z}yz?!lk8#6!t5(z$)Sv?Fm(y?83BDFIq0&Q8fiD=} zom$o7M7$bC2=uN07#QW-C~6GgR*{@8i-Gx(Mhj$$KC0@v;ES zqfnYr91^SiGBriz$-EV8G?8&`2=$vEo%eD_N|{n^4sXZx7GPSyF|=##Nwl+|eGl+> z1KjR+xJ7q=Y<{jC@Bb!H?ybi@79YAu@0eNe&G@bxtBXph%4^LAJzwf11UzksCUezc z&U?FrS%6HRg!s2!ZbkZ1v)tr*YFXNp4{EO(df{9<{*Gn-r#|AIU!OQSx(8T>!dK3^ z6vUNqHI}hXBnE4`;mlpJ8s+u7w=&2m7-1z&y~yDX$Ic@qLY{RrQy*Vv9kw2?QvYSm-=QOkswl#*ydVlk(8Br>EwNuDsl;DlxI z#jrZB+op9u9E&4HWNXG)n*0Z5d3oXeC%9{{p)aZT8_}kw%)=XmWqY>^r$e~Ay*k>wL<(x}K9E7J4!ak9heAgd0cO_zE<8$bx6q(Y>moPQ8QF~=Vpf${AX+>%E znloOCp4Hqe&vNZsn2q^%J(tE62kDeDwf-3~0LJzw-BWa}!%QL28-b z-&voBznp^oB6aK_KewyMjkZRb(N=$Khx`BVb;wW67C+85siDL9^Jyz)iFNuA-lY&I zyZ73JEL{`SD{*Fg>YK=pjs3(h$6A4UyR2`pDyZIx?yI$-jyKdS$I%Ev$-Vch2=cpF>v7RHT&_Q}1y(!8o} z(<(jGvaf!p|G+%aWkx~Lw)j)*^#IL3r7_4x)dQx z?UB9@M1%s2I#alsS%!aSO87^=^B+6Dik4m2vQ9;Fm@DD>+NDqQ>+RFy|) zo!ncs%w`(s0v|UZ5khaJ|3Z{=W5Drb`^=om%}rC(&vB0oby=VyrA=|ll{IxBfGTh! zMPb=|i{W+4DbH_kOANZ*AYZv}YI^24vb&nH`e+R)5@*_D$V_h%>KI1r1^wjPQ-=Ns z9sYCfVJcgO5BILd7m~MWH_wIpl*a5x-Z`IVn-WReI22858y3j1(4)Ls#=i(0vS-Mp z`{~`-I_a{K6SW=J)&{OXnS)^C%+L1E*3XOjsj! z++VmhhR{0X>NIyR&{0B^mtyA+!6{&Q4G?!(00rTh1>cR!E!V52rs7Po`b&%;N79+0 z75cp<{9%i?F9{*=->zwSBVe2S;6T8Q9JJC3;+qS-6>iapl`V*P}f%W;8x@ z`hcQc>lA=|Istl;qJ);r7S&+fHb1BVc5K-UbMMe)+N9oAvf*EE(eDuqdh3O_B7}m^Zl&%+rbLo8Ce5zacWc)-mmYt zPdUi!e^FigBS!j<9Q|?B@`X9{7HXHSN`PNNYNigrHIkH@WQ{VGSn^i4 zvNvK}C>RN-hs|=D-6mA=;snB+HyTIawA^S~7I*a1y|I~ul;;lHiX9p8XDUdW6TVL1 z3AVM(j+$hOI&VoyPVBJBEvnTrj61(@zmu$%m#qLbI<5Op{5d24!1G^Z=a7%|HBeW#C33O=It08yhD;|XxR^H!Lg^yb}U%!J;8 zk*l=Gp!)u&^X~%o^(m$6E1|oXWR1lvnDGzsdAXBltDH`m7-#{0*Zwhr)x4$C`O!fz zOO;kQdeZ+2lFZ#6D{hJa?Jm9Pl?_erZL~g#%&an$z-Po|!;^gXY8g9u_Ph5}xEI43 z`+4g6ojCkXea~t$xV;N=4yjs-(n>x4 zPN|;ZGVT)g)|}EHgK?2`j>gX@*BIHC>0Gg0A)Mdjeeo}pyN$Pb`z`_z#vCOcB%fRi z{AAu(0y?Idr5$`Tk6B%O3Z;wOMwxAsS3K!FckWCQXw11c9t?A=L~#a5veVgV>n2mr z%Jn`Tz0#fkw4oA8ZA?$>^5;yF|26Xn+-}QNJi!|?glXlDbPzuB>OFh4YwqzTbP>Q& zN;&pkfLe~7-}6n-4xl1uw0Mm}noE>%ku2wFPi0e|h~FkDXF2pH{9&u%DaPN6btm&{ z`-oliF7nIX4OUZV*V3rK9CY~XjKtQNx5iG%%tr2fLN5ZkEUKL9+sP_(j?R*B#rr(< zz|#?{wlB`XvRrl(XD~2y?M2$%U(-VR(=9Fplz2TM{8#<&<@9gw}qF;Ap?SdRvLSGC+(Rd8J zPemx!_*f-xPcq}e1W&tFd}&G^3ogy z&I3QG3pw9ZkFyUXfw%*n)ZRCahMe8_5S}~_9rWYmG2Z0cjtoTf|Ginj8{dJp=r12q z9!@LZqBfzD2+$KzGP*CUM5;1$`TW0!(sm|*%MK~HGxdrhBgFz77v#fUHk zsB?8RP(&7;w+y;1;j#!7tv?nHNL=tt9TB<7h&f$I&FQ#R?w6AjdDDhNKy>o6fe*H% zg@RB*qc?1;bEEyV%i}t7yx9=SqbKT1TvF68nm+l`JUM02E-@N;?jCRQt!b?Is)hz9 z`YK~&L`eI;V;|3Aj?uA7)>sX(=eba2!(Ms4OWa%?xBt+TCo?C6zr8Z19-WF?$Nr4X z!puaEva#w`3G8ep7SjOl(fV&2vKooe*Qvvn$6I7ZTHme1BPocar%=#j+x0YXIj|j> za{h+JcrDjb6uG* zYG~5K{N@it9mwxw&yVsG=eUMw_Z>62loLIry1`a}g`A=|_kNKv>ruJ*;L010JKfg+ z3z*EnsyaI8YMWI6v4Bmja!Q)BTJaO6cgnty;V=R6t+xh=MN4W> z<L3JI&m6D%veZ~x^nfm5qOSM@MzUO;NXnR<8$@cC1X z+qfu;C^l1AUT1ikUjRS6h;2Tew)Vc8mZrtDR*Z0n_?pI@A(cE^^-oCLz~c>t8QZk2Dxdl{P+(QSYwjdP;Jq-EjG= zQ=FI)!sm7T-bmq?pEhrMHdf}J_1%}cRw4&zS{o|6rY@_lJ(JtUe8wNg$#3LjJheUB zFU|azH!Y0XbTZde*o4)G0lLg`}&x0DMUyF3bo(eYnb4G22d!Cholf9ena+~p3>cy*7HfDBBX8(R|d z7QF@`Q2E7CxgDO1g(k}e`C@dr(6R@dMCGjcws6ssubrgdZwf!Shu=fqB>>G=3yl6c zDEvC2k;Fj5X3#u@w=HM*2EW5LnN1Iu2}I^Ik1E=7&3wESwYh!{r5WO>)}EcjwyWA~ zk(wZvZA@)sh*xIAX88K+$iwfOJ|gIhpm)GHD<>aVU}AmMZylsNTZ$&6qy%{Ob{&y8 zpYuJBcscSewt0|SL>*^U1oHzXA)@&DAs>-Vz2W=1bbaR*+XYD%t&R|BXNBE@al(vQ zXYZ->I;p05eg*39KjLJ^&71=1&X3|Tf}KN=HE~bB-2G`ZLA{?MrZ5=0!04-0v6-g# zK>of{`nD0G%;#Y#JGhT4Y#SWtSiP;8%}A42f!p=zE{T;h?MCtGCEWV0y7=S){SIMd zlIpyY;TRuCu*`(4Q>a{}QCf@KS_IGInmFvddtO7ks<6f&Z;`UNS52PKpuZSMoBI5< zKKoxgF!*lZvgNqy-NO5J3kA)RX$^0)x+vA!#jiCUidn{`ORmx3n1NwA5DwFAik~BJ z%6bq<&8fR3%>-SyglzRmO%K$frhO)_3#WKZw`tBPT?_QIjXut5GZKLj*j}UJRGN(1 z$DBgfN~KAWC3fa9GRxijcE3Y(pQf!n!(Ic(k-LlieEuq<(=D=i(r<7LNC;v|<*Gas zP}FA4sOw^~rUkk#mdEMG>#sHC1Y;#^ey%c2A9t2j6}ClRX7cwv5cb0TH{$@%khp^; z^q+Nf&G}5G_8!`V+mR1&4LW3N0uzz9oVYOZb5c1{Qo_8c$4bphHW%v^c~K<{Slmz| zVB6NjmEhnBWo*beSzYPBCrs*fDVx$iv1tk&1idJ_+L4vvA%X_Q(d7@xfr9*A%?mWy zYjr)THd)haoEf}o=#c#hM}s^}Q$Xb)cVO)+SxW7WeY|O*)!M6K8^I_V3b7 zord0BN6=D8va_OK_uP$D829iRYQQ|Fs+RqvJ^dj157;q(E64?3{^Z-len8ZFb!IV@Q9s%jPSkHxsdNq zot#gcgg!Jy0^?C>!i9;8dlX{Bb`r*sNy|CZahR-Lpa~-Q&pSdd+?yMO=f_Ut?lxab zThwC=oS(nXO9mT(?PgK7`3!W*dMOvnue|8zM|L78RHy zwO^F%JvM7(2Xq~}ig1-*n;bBxGa8y?i67v}-DS}5lo3vRGmJ|;bn-<~XZBsU0z($o z)7)*zoZk*?kZh!dhqT#V7T$>!JUK}DN8jdd?e*QiaZ5T@ZhWKt2tF4&lzEErb7Cb# zc=H!4gVTno=7;yU*CIw=>+HTqM}RGO7}vh&`wcF|{}=Uo#DA>_CWVzMtsuUbF#F>! zTu0)7Ze?Jg%sV1$iqIf2K0|R$Jx*?(xH}(^dmEoeiZ?%J%*4;MXQBW`;tQlbfy1)r zleSTG<8RG0wt3W-s1}U$z}WhxICCl3y`CI$OeiB7W~7Hr7k-&*)E;KrR79kZmopqE z5DubO_(?}eUNfz*kMQ-8dcB3W9#pkqAo;u2bUzSer-a%5Vv zzKZF}y!Nq8<>^%{oR1y4d%HtGLaE-*?9$7|Y5CsanNrS(f~+l?bR5RU=!DR?w}U7z zlyFAFToV;`Gbup)BXB-UY_&7QO#pEU-5-pCd(?WmvbQ?LtXinKBn*P3K0xsrwU>4W zH1n;AYV<^4bpe$Eeb)ILSh3NH#|ypxPgUt375fi7YCq-OhPL|A`w821;Ef(CH~LvU zSwB^IeMd0$xpyhNXueJBM))Pv%^wb4vu^n}xMsVB^x_wdWyN)=o2b#n6$B`AttqT( zV8w!o)|FkB+36AmH@BXMh2&^|G(nA#d^6OFCgcjUg+c$8UXasLoOv;l0ESHgQ zpPF+V9{KX<%h=rGhkVC8?c0JAxNRDmu=O(J(1%<}%4WZZDC*O=X)C7o^@XOzq@WqW zJuBAodUnd|4B?EOhRQ7YdM;5mccw$$0rVnn!=_%cRy?Ti`Ikx@JmdD~^vn zfk+40Db2|J}bS5wpqD}10%4%=Y;_|G2!1~F=uh?|Y<4KG!i4A$(X_5H-o zC_0NgmiMkT`U3o1y$x0iV}RA3qfO{v%wBN1fUM5oCQsmqbgSweii2hs_SNJJP4$4G zZTD+*ImHa$z6}V=jtdj7BI0x@DlO)#zOc=_kt66(vl2LY{{rFG0LHS?BeP1Aiif=BUDFHfM_MRJU{bbOEpaGi^p5@CJ9p2MN}@d_-4+gHK3vYj)H6 zUge}I7wHySJqu|;`6xb0Ko(-DN2GP!(8a53$C7x46o_|-G0`^ybQEAW+X znCBhVhsxL!=eTM%XCUQp0J8yF2pjGxsu>t1FT-Um=>=!aEn37je+PzL!j&NoP*<>b zuDrCA)ot;@mBq#)w{ja@;Wm@`oZgU+y(z{aJ1RPnJ%pb<;9DkA$O9$okN+Gq=hu1B z3z$x4dBr>eOk{KD*LM1>?-6n_1JksEfpVtV>3{!)!IW>6#g3!R1R^4{(}Y5*3>PSpZ}gqvh6;6Q3T7$mRT@he>U^3x=zK3H9PTCQ9-H(YuTk&oo}V6L<6&&u3ncvpnQlrl*?DqcUOTP}9o@8(@+gWNnyIC>ocNq@A)Z z_UmH&S}s20e}mt@sJS<-5767ZVus$PELL|dZw(GfNDIUa8t|XV-@a_P77Ja!2|4u< zr63T+ghN)Ba}a9lNduQJ@8Ic4M0|oyHcN3_vPQC3rpUat4*`>f(<{#;Pp3|OY_xW} z9GKGx%{j!A*+^k(=vPp|fBoF9{;qmD?a;Q!wkQ3K-yp0D=7mT*6j9>|5X zF2dHlZUuS4Kkt-VC#vo$mxV(`x{sISs5X31w!4f8Uhv)cP|^u5hXj0X>@><_Taeo3 z)-~fFXp5ZQ+cRZixuVsDf_x&J(RHYsH;H)8Xt|a(0;xkrP}Xk>Uwe_UpSu}6W(n|J z7f!sPeGGLEpH6+ctlB1#X$_pY*yo)$NfT7mPV^wq2=o=AoM$B%rI}-;Zk9q~Le%X- zAu>opQVBW%!xMUL&bGTQ``=0rl2>Hvr#xljvJ z50yhbkrlgH_cZh8vKr2TaWVWYIXlHtjcS}-4PEw$AJo8vXsZ>a3njYvyQ-Bo4xbkk zbPh-aCl|)b)As3YyyScI`M>lU=wAB*x(s;xrxYN~k-#cc12g^+VWRJT!}U&WKo2s?-VD9_|$hP*gp};NyI+!Sat%xxQS7C!8d=(~)W<`Vw za+)GjnBJ|sfVwCh$XjO3`8o|QxUqq~$C`G7MldqP-+_z_GdPRdfbs$p<;@dkWnoc1 zph8;4h%Zd>JGUxzsktVOazW3YRe5iV1~%%wKV=}JvC~=^tVY$rcI2j(X?)k>^dn{@ z&0E*pXMy#ULg;R7?qo9IS|F5xj0rtMsuqPj%gU^XIP_PM68~?SND;y9k#)#YV^pW ztHU*FFX%I-bF$l%{s?NUF7K_Yl`$C?p9wBbd(f-l(tEfocd0<#ppw!lit#d5EjVQG$#dQM!MR0n)!nB%gtPe zN~%)Lk$@gXMTNX|dSqT{+Hgm+i?&^}y?UPOWr3B=(PG#6AgiBoYLu)yXK7-FUkRDO zU?|eZ5Jh9c^7OoSG27^Z=Yv(Bc3a`kq7y|d{AKTs4hgC+9|_Dl>tZcXDjBE1wL$`c zso5;!Y%|Ec?jp50EJiY1Qj#yCziSSJ2aPi|0Fbi>e*(lgwxYo$6o>HB#;u~8@Q1Um zv@A>0J>F*C^H7vk(M{2pkvpAPo;d()XGjm*J@uqDV}-4=1ZNC zPZY=~O7+=4e>!~7hM?7rH4aVdjBr)tx-~T=hlPuT;@g|A(2xdbA(!7uDGGA)t__9P*&-zL$F--MV7{sWTjXb^rh9+wy7HG%S zbdBD{#oB@xm|88t9uY5$Q3 zPyh9>_DSK!>-u6IT@3==;;7^cJ+$=d5~$1;z2aK(ZjwM>;J?b>X-WOnvt6by51@AZ zx8@^p-%H+aT3~C^p~bz9gJkAA{~AE{8QwJ+a$oqf9{X^9rdei=FXM!NL&wprU~uq0 zBFgt@XL{KnQe?6suJeIkd4L2)4V^m)k^ZGXF7oOU#w`Mh8b66HJ6A==a(h&bs|)Ac z26SWo21kaZNamVawn*)Ww8;o_68{EQiIj`zSEaeYZ>76-IA~~jIG5RM_xwK2ltjSC z@-UTXKal25q)A?gTgo~=0X-snI(YYo^VUk|pj|0b8bhlX_| z4lCx&oBY&h<^KFTP#^>8G%=&v-CPllrt>Ms*^Jl{=>6c<>@vQ zYcX3~_AWGD@b|K6t?T(E=HsF9ww+a9;=(xH-{4~G*KeA6Ibyb^ zT#cgGrT8I)^Si_Z)rimg=Onci_XC>};Nr2y^{m&^p63!hl?@MUTl8WtV%+$M(@IAS zt9DR!pQH9tuwjA#=7*yJ6l-yU8H~<&f=NYppEn0JcfA35v%F-IC3k&=9w=TG(UL#% z*xUunJNh&Q@{6zXNhbgrPJ-oIk#BY>21*x$dbMQ5Ufs&DCKk?v*J!ltWYQxCTj5zN zb1okNg15}!#!N!p>B9-`ywIF?7_qzfJB`=Cd3netY6_|!$+s^_L?`cs^)UvUt{h%p z5?>|lD9ZI*b(gZcwiLQEpLT2{e_HmTEAj5|g)j#FDuNhnzj6bb-xQEj%dbjfk#WIAX zAIg7Nv24*z&t^3m`JhE7ks&=$T5Ut`v%y^6T;MKWKYHbxDRs~)X_fVZU)!KVg|QW> z$YFDl_t3bB{cK^BtHDUCOxyObyuP8>0Q>DZi}1CS%$%Dh8?s9KFL^-)PpY&swoy;p zNli45N0VtzUH7~0VS6i!tLI#03`v{p%tiWXdef-SEl_EoojA8!v5|_(=6R7D^Q#)9 zOPnCA?fPRMnI+0K3@>~o8b`l)rkFa0!;2J|5=1LZbZGHjMTgS1MePh;|`H{ zJ3W{^o%iI6S=t?ec+3x7f1HkJM91AUqNx9SoKmTmp2hfNvh5$;6OSvZ((9Mm2ETO! zaq7Y>cq_}f>zk>}h#~k@sT^88X0AD}Z+e*+GoSbRAa746(|_qjnAwi&WkPjBm^!pJG`xNee9kfOhIoQa{}@?}Kc=eb^h`^6!R*#gt5 zO9HnEEskLD$*Y2qXEeLyL6h!n?kjG#Qz-|VQG@w)@z0;L*h}r~NtrrWMhcPP5s*(Y z?Z!J_y*-Z~m*rZg7Yym;ymfx|%`rTvDY`;EDW}4~#wLE&%QTYsY5|GC+&@~`@<bb0jyAgnG7FB40 zDY;wEw$;6%@zrFU)<>;k6h60eX>lF`NNwcCHapnQ$ra=pTGUqv&V{cN8C7*wuBk>U z@-Y)obW)cP=09O@Jd^pGlqiq{Gk23LUer~Hja-G9Gxw)oyb8tSSdwvB* zeh)lAV|_}jwyF4iR&Sl~3@d2kvZU2LjpEqI(kS2{52RQ=yfA4GyggM&(%G1E!tb5U zjhD~-nXVzH?uR4*Py0(cm;vd^7lSZ4>fp%meRG8DA4w!IOoWVws<^ z4kaYMJEpOsU8`;};HiBqmg24M=VW|{8)tv1ZY8$P9Sw)NIV^%#xNoqT#auI8sLEYQ ztgI|@4$-qguz90iea>)rH~ z$+**SA=5ivZPhqmq52i6HfCA+VREdRE9QbGdO?e>q9XOAE_DI{H1fa28(`?)hUWYR z$Jj0m{FfbKf1jqooTMqk_jPjY98>Oi`Nn=}aDvOW=KYhRWvr?QUy->5Eyf6EO?{ya z3Hh8hS{ek5LYXqj=N|<4fJGs5!Ild>ue&eNDjl_AaW`bG&7!0-v*nXkV=MousjQ)-5gRmp}B;C_}^Q z&;nvskKCARbD{50tZ3aWIlv{!+xfVbJqK~aR9Q{>YVyOfWO*(g${6EpjBz8{oHzjN zw=`+X&yoZ>ob~w%T;qf5W?6^~rd%%%$!EuM&249BN>?Y633lq=Qk%A}3YIYW;5PK# zxWwR07b|K&Kh?{cC%!c=(zuv<+a*WY#1z*`s)=og7$&Kz%WcNb`O<)}pw}tQj8f!)vaA_iA8)v>r=3 z#nZ%(pqb^|+1yUQmNL*>&|vt-sbyTO*A-q3J&PQui!_#d+VVb)FK%~PoR=0LCmwqU1a)F$$n1KFr@P%;H>O%D8;L< zzvL(%zaMkmuZKKY=wH6>}WoD zP2L^Uf`s-`=7HV<_1#7?UkKu8KnFtep0H-0R`+Il9z$Z(Zy1 zl2T#%#al-iWO)YabZO2%r^=;u zzZG(@k2!pi=<)7y)6%$Mbc#ONrerA7NQKxwI>hy}eCbz#>=p+E#=mvdr1Ro0rfovQ z4a=#v?EPR$*Z^B5TIcV5KJjWGS6(uZBCF?fVb+%%+bR>kIn7ifw2;xlCyijBoDD_2rVO)QF3Jt|IYZ=opE_7Swrr%S< z$)n-`^`22$GsDk6lU5IOnb@|=EM2Cp`jRk6BZDu}zxw^}JSWzN?lHgkl?=eE-vK?a z>E&;5w!XagVi)a~;r&^p_2)Q}PwJmO&i>1e@c+Alfz$p4*WmEPkrqG-JU1K^uv>TlY(Fzsm!{tJzL}r%(Tp5+VP` zUi3_5rnace?rrXVGTjE5xC-NCss=a2LcfA(i>U;409C+~cMfVgW`mf@L6s;dL!A;o z;;im4c#*K}Qw7wMUQj)#U1_I^ehB`m;7Vv-E?yDRm}Pl;yn3 z=`f`XcaYRFwWQEumNDrZmnC0#T;LUq@0oO^v+Fkpd*I*Tw6!>Xf4YAb6zWg>XW2OLL9kkNjxM7Y1lZiRgedz!z& z@%`nh|8c1JCGo%PNQTe6=iBm_kA0+kTGQir;s3{1EAErF2|#|U1g%sLbR7a<`U8)p*4ny&GG4rQi)DGNygDg;WeXpVTl`#dHc!Kp zF*i@0qLERAhL^AId!C9QD}DYxsP|>{8Y}Usy!FX8RN;K(| z&o`I@Kgu}Y$T_d`k8X}|y($>KO~1z+cP+THvx9DP1lxm}~ zTfxrtLbWj+%u!3XV6ZK-1To~gmftjapTz8JVIJmora;)k<`P5kjR4Z+HVg@jjR?Im z7POneT{LM*p$&G;=%1&X?NMDukH^;I03TJF#{p2?m(e-)nU_USh`u2%R< zrzc%_qC@*2-s<61W6L(0uFdlHV@>G(5K6hAoN0W2G z2XzuU`3?gZ_Ja!tCVyF~SC+bq&r_5Ls(T%okb8`7k|CFi906u^Z00@c0-MW9zix0C zTlgyYEiO9&ZH>q$rl8*`4Ge$gv*zg7T)6L^{vd%cLVtDN^r_xvrTdNWf8pD{ZN4SC z5HGI;{YGituQi-@^tIjkjI{X+(v5NH@d?Zl8$V>98*M%}iZ2jA`?4`R8t@G^dkp4P z>Pnsdp*4{9l)4mUOw%j~a6+n#cip6>&2}I|sByq+)S20pk15w3n6XN2R2E=V{8I80 zzyY)(MByI2zD?M{EQvn*j`6I=J#~&m8mtmNx$p@uQrmHk6(GB>$sbdx@}pqe_f+fc z#7u9zLC;__UUq;)m>OZPX1`x&G{y%q{YKovrY)j8mjX{^mGks|yG}d-xn^FEt-dTs z`B`X79a`YXOj>E5yE;x+itm6U%7+5s_g4Z~nnvgN;pv7FBhWs*Y4>NLd5gm!OZ%_g zNol=U+)W?N)|gi@8(RvLpM?57m2orpzN%FD|K1q>i5C2<@Ao?vrCu8Dm#!V+xn2a= zG4r}FU)D=1LFe(lPUgL@W80r4L4|jbZna2KNL$1I@mWjec0^sLpf7~KFA&LN8^_ys zNld@?c#V?WiLZWX;<8!ki5mXD&D#j8Gbx8)quc!D!>0Z+)GC!p?@xIpxy#wWV{?Xz zdR7ANR{`!=tk_(vs?jsbL)Cp^{)GdQz1-_o{Am2JvO(Z?7@viCrEk4oUGaV_n`+MI z(P~a*kE&tN8l-O+YcZjW>(5(%;kwuOLlx)MJ{72jDT*c{HbJ6sFzrP&ECJZ7yt&n^ zel{(lPC;XSJqH$oTODfNPb-}U9Usz3kR~_8og-TORxms+a8iJ0XiBYivlr8YN&eX* zkcEs$%RSqP*I;EDDO%qXq3)z-333rWY;zA}sxI{E>E`wSN;Jlyq3~Ez%Naq|6!cp1 z;T}qFJ&z-!2K3_g*R ztwbDqn72|;+DJ!b+FP{5uw)l~ADvOey(I1#JC0WKHh=5qufRHU!`G`10mKn;J!~jz ztALOZ7%iDIX0QIGXm`)K((-H9-ul4Z@(SzG9%h@U5LPzS}3{o zlCn{n+?M<8jH6%Hd;6U-kv8EuF5;grm85%Y8bJy79Qw@1o0XnDBT9<9Hg8$%A$AvJ z;w((k#1)x*JP#aK?h`;+&m_k&qlic9KYx6(@Iu&If2fAvzJD0FK$_~iHAmu=PD^dR zpbcssUhXN=)K3mHL!`9EL`bJBGWtaOs$R8MM{J{Kg%rX6yUirU8PQ7); zCi~0}`dTy)&9~2MP#9O&(lkfH?S4N}fEM5>$?L=`8UTy$igHBZj1C%`RX(E-Rqu>H z!*u}3*DbIt$fsXScl$P91aGG$Loc;;XEXYIm@8(NxIdQw4TTizrtGQ`&`Zqbpw`_# zY1D#vyu2)_Km|`bz4}^NvFOeYOU-~C9_ufxdQeIFLolDrS3ZZOXLz(KZ*jvk#w2kE zzr^SF!t`$mdxhbIJASuE5$z#e*=kP`+Tqeb*8uI8#+5!x48Tk-_gGjg&S}Y)*8z#; zDk|No-0?7&VVV_D?;CT(c4J^z`i$ZZdQBslwLMiXc`n~z`nwm+1lPmiHo|USLdtor zx*HErA1>)bI7@dyK@lJuw%qOJ+`&3kyfG$xu=tDQkpJH`EGe#>2}mp2}Ijs+%G+?u|stT zkM_SYE4Wt5fwU&4JNcw~yr*MYXRxBX(rL*4N3}dDm$%eZ7M1=Y|flnsr27$cYV}+bM*=9QtZc! z*c06qd$IL@qI38s)HA|=6c{Y+jV>Aroj6deQ(RF#bBBtHs??VSRk*VTyf;=aDxI3g zNS^|b9fjmG35q&pE5xOwdf)-iP*TL}WlPd1A1MPoZNXmcg%x&jFL9JXw_$H9l7+tY zDx27gm{5_y$=r#K){k$l=`x~dPe*Pn6UH@mj?dOzfc0~+!@|Tx7++1ihxJDP6)*C% z2v?sL@0}D&mQCtSqQ@DGSQF=`;drBj9*;0-Bk~)2{9B#Kta6fFdS)cf9qpDBaul|l(WpjAW;KwXfR><7L945o!2Vfs zn(Oo79gkf_gfIL}^`2jy3Z_(~+i7%`7(Pt+X8?X@th|l$0%>g!@-+8GgqU}xSJeMO z7p4OA8Yx$*>89@oML1jGy#?Hb^^7s$9m1&v%*zYRB9A2AU#EEUi3O$#6^}5MYv^OP zgV~d${#fnr^-sLlh1SL}Iz1%X5u#{Mf6FCJt93YgFXT0|kd8Z}5NxHtsLkBt8(On@ z=3;^0zp;-+hrX(c8}X)6b!_Yu>%i1hrzSi++;UzJ01&8V$z9K#qm~+)t+JdA<+C2n zbq!0ErB{pPB0yy0j4*=}>G;DA{{Nc$Z)qjMv81ipIR&}EqstB7fjKnlv|748Te(>e zyb%mlgyi83$|Djz(@l%ukCQ1~Hm~Q#rDUH^$fPjY6o?1j{7VZ*05z!;EzqOrwRPuD z9#17K0^D2OcMU>nJ6U#99!jK{x|O(n$#a8?{ZP0!g_DCH@<+Iy(aI-Y(r{C}>Ycx| zw4`Q?!%q0|h$3AIWkT#nNyO6&9t$k%P3sx;-*TAZX8y?@4f>dWf|U9HSd;m$ZJtPR zG)c8Q8k6?v%PrB3`c&rXiGdA=vicZnjhzFOE<`PXWZ&!*3`#3Ui9!5|bR>c@{gkOT zICP3U-&HdIEBe_#rD+wd>}Ve=R81`qkTF!{FuwH`x;H~WKNXnnD~sHF9#qyVUqZk? zUo_pU<~9FmACN;77ZjNAB{D>2V){mUtP^j^CY_?MSn~>qF`BW&;ka2cMZ&7&yik|k z-LIr5+HGN4u#0}&T(5`Mpnn*wQK5fiUMw}yw|W#_+s_KwVFsm}sNcpc*v$9s8Ub)Ji9`mr88SK7T{q4TTGraW^)0})&$3pQ$ncN-rpmuU}X2lSfK!kWpSW4K3Bf+-;BAZzw+gsdE44DdML^q0{o*hCQz@@%;PrF`OG1BKL34Yu%y+Y?_o;xD96$!3bqfM**Dl`!rVX&*IVSQAIOa|a}Be*MY{N0 zCuawGauS1*%?>c)9PhpBQdMk}&zPiMtLbHNo+=(l0Hn(OzGuV<7XBcDG`@IiStC8M zf1j(TFuP@8{HCK%dXb9sfwoeTdbhjPtMZi3(!{c|E33yvLM|qqW{f+Z0Csd@DZ6O?j5l$-g@$FvZq$`febqtBlct5cR`0LnPN0* zXVQF_2OG(PvGL-9c>b|vdSma^4szfnuRKmrOJqxrA9wwgq6-D^QXjHAiWBhgA^*{>Xk9`(k_8b)74TulyGE{xk4D7Ny##^ zF5Co}z}zPD7k~%=kDX__OX9T5oHiI6ub*0rcK8JsmB*Qfj_bTqjdMv+w;^SK^z#qd z1HnF77zONBcA-r~b@7T<=~QL1L<~I8M`#?CoQrj`Bw4Ni^-+JwrweWyxJ$x%_OgFOSL1ls7A{;H!7WU}ybW=>HY}Aul+r7-)1~Xwn`KD|0>$84E88Ui%&@+3uJt1cj1;e+mv>xK(9p@NxVp^O>F zmVSk9o~mzlWQ$LXt0-oEoV6?`qbT|2ejD{mbu|~s=>+uhJbH(+!7|2P>L-YOt!~_p zv2yix3m(+2xCvV4y6Hu_ggCm#TeiXhRlNdV6C6OjsgeZ1X-!bg&v062rr4T*SF-@l zG(^DK)6QIc!WDgZi_7#;THTvD%R>|b;!z+p&W*q1Yj-`(+M7O`8Am+^`_`e_IcY_4 zEdKA0CHUPzGNJUL2x-Shd9f>4ch~6_w`L!jrRJaPA8JXDc&QiJ zU=}2QqtK+;!?--n_Y6I{i*)(?NJE~}Zn3`cM!vW`HztV(>6iwe{lc7Ty@7Nv6;b%< z0|^wWZk!Q)zvl>~4FY`qn4ef4RHsx#_Q?cwYQUBAy51SB*OO9(fyV)-^9V&&kXiLv zt!00Tc*27y)gCmh(yS4ND0rf&-Q8^vsw;kKEo$e8xelMjo<N{8<`*aEf1pV#KQ;qzeY@4V+uj�_!?T7n^NRisKT7ycr9az`#CX?$ zk+KHW<(X9tItX&g-Y2E|dtHSahNWeZGmdh3aPi+xa!1UqIW2JjKzelh7TxOU7x6b` zdqBPson*Z*PDjpub&tRB+(JxkReMy6>QzQ2<$aboGsO8kH|i`!HRFxcbkSMvEXzWf zMJ;_m&2~5JrpM@2w!L7~K=6ZJpB!s^TG!d~ z7*|Ptz=CZq+GD;ez`_{p*S9NZG;ALir5MCo88;05eBqJ#&Au&o(4lLatH8uNdE0*0 z=z;1Rq`8$9kLBpMF8Y(KhqH6#V=5m{jXhs}yyv{SGsui2fWB%?< zQcCr0{Y~|03%mhCSJ&DGP6ZqEjYd*aO5DN5FRKh=X;-L&c>Dk~E(fVTFB{)j8P79X z?2@!@Ih_)1HWmo_M-&gwG$Fy9IarPE;R*j>o}7`p)y_RJjyL>uJpTPzQj0NlS{5U% zrHZo2uc7_tQD7SFzgN#cx87|X_B&uhm#|_`H*%wgK4+Jv9Gu${5H#G5jftHpubP&h zn4ju=Fl=_tq@1Fn$$QE6nLVZE4+(YKEvhHEJLSDNJ{fJttKZZ4#c#N)gRd2TzQg}k z>4MBR)AkFn@J(q-T&x~KPP($@oKN@;O07r$dtxRJF$&|p?b4yqE!p+0opTLp@^4>* z?6*{f0yoM-T2B1VgMvyz>KEPi23&;emE+E|%hoNVkRnrb;m9%bI=H%fM|q1e8!Nn$ ziY9v-`L(2?GzCO04i^Rcx;gB(&fc{yo|JUjSeKp2kcoUP; zV48H&=`Ero&O2p9_w6_{)!tsP9?=P;#w5uNQSPDHf(g_NM-}Xjov87ujbUdrf9SPK z37(k108DG#(-qT!0;#<3+pQw(!$HDybi%I0g#|Xh?4WE*^^Q9wp%2;gpBCd@I|yd) zWQE9*@_)S|vOGm-Gp+q@)hyEFMKTb+!u0C^O?tV_(kn|+=z=Qref)Rnk~kX3^;%dD z=8<9e3T17{kL+bW$clfM%msR_3^gS=sG#3(C?gm-29?>=az44%pIHbHv5ojo{I#v7vydsO1Qh)#7mAWE53^dYMOZ9Fiw$7{o7apRR zJ@@o5hv_|bGvzGO?2u`3DE)MKjJ<@Bx@$xCz#4&sp(=NjnU}?Yso}~oTgCJtv3sf% z4)}?HX7ipAdSTe{Ydu1fF8OFY(Nf)llje!qLY|av(O^poypzo~m!A;Qy^ygLKRCMs z1-9jtxWW~;T(QJoqn$T&Wxm5Z=8P8*NA(S_<~H^zZRgIW5Ua-14kYS698ex}!|tig zMEgqG?^yme46>mq9^RO{p`206QUMR;P$rr$B<(1%+4%^JX(3uB(IxUeu6W5pSK>$ z$31-?WS}qL>swr6(HIpOZ`sN5XU}e~L6GAqujk*H*W=^8z-$!MBQMSj-t}H`u+s0Y zn@ILeulF;IQ6MT-lm~|t_On&Yix;Numh0#0`}5?zwwM6%`a;=<7dwO85p1)Ftq`Yw#-gk-yLJ*tqmyw1kQ-8$@j`@TCV23UN%&5Uw>g_CXUgp zGg8T0_jr+a&yaCRuypY73X@zwp9nDN@7h!zX0MlZX8kXGv?R z<=$~TypH5G^@%$&jf-q=H>D}ICBmfC&-Xqn?(nXyd-8!{#WL3Jcg> zJoUU0SE!lK7A#h?!0u|ifdn;g%hm49q+Nt(!=|}$Lmcvf8uQa0Z(kf_TB$$`CDq?) z1P_m(yME>i*bhc5gQA!L*Mh>*;U=q=seKOo_ar-in70Azp8gQX{+8fdpl(Oq>#eYL z{1cyYmrCO#`(pWe zuWW|H9PhuYE}{paPlnT(=w23Uj~FXfuxu2r6H=Uf!2lKj&2kV1YItPdvwC5Nxd!GI z|3fvkS7@nji@isiMQQ#q*lfwy4;;{mM?=4IK~J+rUwe?;d*z?O?pM-Vu}$xP%+&y) zRCJSOGLx?=hP0>Wzs-r7(SJqz86N1M*aCL(I8h8R7ls8FAcoCBPm*g%I;Hh8)@;6g^@lg&5Q(UIARqB z`=4fZlHfoHaX5JWIfMA7AKEhZt~X*rD4JF@x08>TENWXn#B(Oo$_xd!>pVxudGHL9 zlBu%_oQ0oC`nmg{Jug8*am+pI46Q~=BN4~)Q5XYjT^A@I)@uex(?st51w=EvB)Vge z3o=feQEyL{_@TJY1GRIaGEGf&Lp(R28Ws8l#cf=N_V~uv#328OX8dnuaMZCV`cGEd zl}G$b-pR3OCT6=rADN4G46*CZ{7zBwJAHnOuAbiC8VTf@0$rI$o*&4*R{#8GJ^Zh_ zgw)=Qo3C5$=X%6d?H5;n&Pr2wgzmKKzU}I=%nxj8xs-J|?1)-n>B%dj2~i;1hr8ip zhc#3hI0S*c)Gs2e+G|=)RoMIA1XAW3hctWh(>td9KqyK3b-KunX4qCxEJG=@;=MwNjQOY_z3Y|cEuOfW z_&;vd;B3CT7Smq&K>_3yE3kLSzwktR)i}2H8%FC&g%rH8gF@sFw+QmB9kF%wN_xj8 z#t+lJzulDVUbr04Tms27tZIwwjYvH=WC1Ik+wBn#&?3wI>c}@)9c&O{Dn&(As~I@3 zYgY=kr`W|Rqk+);??zK^MEO&%>Xpw+ASI`=ug#N?Zf*s9pXUbVn`3jUM|+y3Xo)4) zEQ1w`xhZLW6sUl1!jj1qQ~4g7=Q5Xk?dth&HBr@WI-M;RbLu|y^@?E~!VlD+a8=<` zo&HgT4fWUSq(YZZ?Vdd6=5%VF+aPCld`$avkn3xmoqhB(rH52IPi7caMiGu^n`0|N zuWIU@IooPxE&hfzYp@#cv@blT@`#*UsJx|9 z{0PSO-`?JhV++rEk>?o&TO0FehJYrLdHA&kw2aiFC@tO^z! z^jsj4Qe$LI^R5L(Z4+_<1pNgi!OxY#e+YNud)Gcc(xL5FR_|36(^_~$wS^@!E!=#P z&4WwFV$KpV5PfXEg$uk0`uTT4VG0^k_35b269GCL!1=3r)}7}rF&VkVD&;!QVuu-d z8E9U<_m_DCr?(M$CnA{t`2(d4pU=-beSxlC-P}R?O`Ad4j z$XCSJn^VE3Pt#+;Bihw3LkG}2weAlO9&%)>a-8|nyrdl%p{Fem+){8ONuKbRjWC0O z0lE!_#Z#^@f?^du^FDQj;oj<78MYp?TQmSTuL_&is{Aw^5}c}A zPd>L&FNEA~=42h(F6uMF6I>Rj`h0IocGY^XpSX983Uo_}JjVfH9R=natCtk0NjmS7 z(66;*jHGb_T)1U+>hc(UQocWD8=X&L7+7&po?E6Zm!EEaGVkiH+n)dS^-Erk#eoI0 z!LPZlOC`hp37;ezTecw%1Y}hp9iK>dkRCyIT$7yAl07#;6QCZehMj#_<+%RMF_stg z#ibRN6UY@dbJX5GB4UCqnNOkW+Tk>}DcwK7G;&=tk7zZ=s+*dsaPld?4U8cyKstOk z$A)2j7ipekoruhs+a^c_$u;(DI+-4!>$~bFuF&P8AC$+WAXSJ$;GBsFH-|s@NFbui z1?6%PKcU8)YU#r92YNoM9&F+W!)2Ct2N+C|~M(E@Iy zuWn?~^IVK(yG(H_?p$DV`yJjnE3EKcaVRwLYslYfN^xNy;o7p@j?yXMC=d&BESa6I za2?Q=s^m(m@Xr^bwA7R0esbyePF@44A|4#|do!yqjr}nCBUOgy@{Ig0G^&1-QOg{$ z2OqzFGk|7ZYCyXgw$!_W(}ii2L)F&KWBPX8gxiNg0Diup4IzqMO)Wi64PrBQht)@9 z<81V?djZoL+W`pIQR-n!+pjDRG(G4Fvmt$$b$u%&jrS8m=N*8H_{uxVwJ8s*)WVCR z#JooJud&uqR6?m1KfbVSZdS1U(tnccQFfOw;;#-$_8=8}tz`8tDYTIR?22ZMT4 zo5_+YTvfw?*oyT2q?G&*_{X)raAbU$@|c!F5$x3s-p7)q`nm(NdUInQLn*S6kX;`s zE`5_4LIY~GS=+M%ArEZFWJS&r#vJ?B4CR6mZHZU=@#%$C3uvWp&?Ub+neGJ#ICO_s z>urro`+AXZ>y}{vc&ABuNKQ*jxJFI4>A`%t`0fg^=F})aIo40Mp54Y zYa$-&R7ItE&&>B;N|+iE3r$yad*&vrBHefH zdb|7OXt#GQCX1lQXwfdTq)sz_$?C-ia?SOY??h=mmS{e<{RL2O`Lq~Jg!BtW;73}+ z3ExfOm`ljbJ;rq2BEY*t!o^U=hjRjsMU(UqTs7AG>UOYhK*f779bV&o70!qdjPnK-O|w$J5MZybJ!erwrS0e!NNF_*n$ z8NqXd9NhIM{d9WXFb73T#z_1L?>cZxZZ%5+7@^V@Y{)}8!4|Lr#>G6PH#bp!?9YX^ zA?)yXTNbB`@?Ms8Uv!Mgee!sldv~PT8o!mzI52Tvr8BHgk{I>SB&LSe4z*|tAl>*T z#TJz$ovXgqP#fQ3ZtaQoj_0-Pw<-YvdKM#7H72=@qpGH$WFE{(+N|odqf>E)4>QM^ z_~xUhgB3nhvuv_I53TQG6w7*#RvMRklxFr~@08q>v^Blorp;v#K)Q4(pN;V?Z6k&p zM`IiniYA{f7#LvF9r7*&mGqSzISIgzD`M6M@PGcDu>WV<9~|vZ2Y3HM^4+hc?S*D9 zFY4U{L}Y_}#gscyU_hpcf8z0Rf|V=ISm96(@Iz9p~)+Fo>>X!{JJx@>v|D08r}fu$I5tf?9PQ{wa*>T4K?I|^|SG)&aM z*S+K<1pSmnd8ECqYaW^>9$qwko0C01A2z$zE!pIyTyY>3fUkNM$aB0zAR337 zV|6fu%juO`q7&b3=saQz252j_?$uMt5*ln4EI%}T$Z2GycymC@rP+NNNb5%@{petK&>MSnuB=(v{ zjl0zCru4h^daIh!B z4~lOypf>t53(D$d{>7H3wNEQmO2qiEwl9Wp3pLm_S1*MF=SRQV*&YiK6~%POPhiT+ zlr#s$R>T3L0~GsfbFPYJF{J#~0?bMIj-kk0CHL5jPU zV^$6xY}-{Kjz=vIPZoiFF8jdrFna&r{Wpoc#EAVvgSr3Nmnu zrg9F6Y7ki>G3#0VElcTxoT)e#>fkOJ);bWP9uVbocx_y*ry}#F^pLCk(O-B}J-zaZ z|M<5%J)jVe>ZS)2s7g^dS9L97dYNhXL05ubSbUvPWlgm}oH!&qJRQ6%BUg~cNBpZS ztIZ&_r0-)-uP2r7+Rf6wOSz;kD*akx{%e=nB`U*1tEBm&d7tLmpy}<=Nej7oZIwBu zmHOlfIqIxVF)2`y^tj~6pfBnLpE1QXi+Eu~6={$YKo3iK8`)6v!=b)3@a~B$5{ch6 z!~<1nb`84e48X4zPIR6Sl$0lLunSORA}lA-XVZ_&{KpLbwY>E4@kC^r2C*hv@_n&#|MvbNORasxp}W%~JkyDwf)PGU7nfDH=6KSe83QYOks?Px0?=K0tOyha zw>D{$%M$tx7|7Kt4^(WRB6M=dqDu^L!27Svog{kkjEOPzs~1fQoAuQT!{YH3u4^W2 zY(*G=crdaOfLTbMaHv;S(dm;zif9Y|T+X*}7s_XlbW|Qb;#fnPwF{Uwa%4|k$!znachltJLLYpG?J=R%0w2tG2l`mhLQ19*4 zTqAfEHd}rTmRGBbXXjOaT`{EG>cc8Tw~o1g){dPBiYj0|=WFy}@{L2A4d&J|ufAMe zrys-;W^jPWM3)BDqsfrOWQ~BT6I#@3PlU)n9m?s0IkKsf}UUO?&Ot?sHUhrYQH9 zn37@N()Ld|dGoRtaY6ZW67wmGJMr4%8SbXCx|N_1);bWW6m?G8Op55#(d2BJGM9Cd zJ3EZ>bCxRlA^R^VN0Z#Bs^SuBT%?)Nw-xn$SbJWJMw#cB)Esa6<#tTFW$P0$#PX1i zN$EQ6k1qM1dS%d%R8nfPfAT{XO?%uI1Pxp!BxBKCj8qh&skyWPZQpBHECHM=)!u5` zUk)lq`f(Q{x#xKiA|S`nCRT^;Gs+!yIaB?tEu<}|>!6^vH&FJosV{-($!McKTfIZO@7Y(#B~|9-+~YT+0-}*<$y;hai=MuEX3FFu zVKqSC=cUd^A7>byKh&3+UT6_Y+9bmfvgSC#7hKY~gj6Nw@uXctgYsCoIf^_=b5HB3 za8YAxVvc5bUNwJO;d)kCNpO;R+Ji|F=v>xxBg6PF2!C634Wweh&mZ9K(Z1^*zrYCy z=*@1{afN)N3-d2EViOqk@V%%uVOq=o5%0h9+tp57BJ}cKmz4i-^%tHLU*unS0gv3Q zu6w5GJqXnFs_{KUSg-wOS}7de&8jE38dbaZLnxLM4Z$f&Z2rURz6NaYS9x~ajhiZp zCEX&yx;OSg)_&OIma@y%I^SXn?F+wikJDWClDyrkAaZll>Z?06BZY>iT7(cXG$%qN z5gGdX9Pm1e??Z1_8rfip;W1bE8X}|^8B;i5)>rSVT(FaOIt>K7wo>Yc{luzkUDpi` zb`x1=00yMgf2$e!+_`7sWBJ;C#=KG`$$;dk<7x|qz+t8h`Wi`3j%a}M*~JEYsQ)%^ zS_A^B6kUA?Ml3_4l0n%E*_;R>g#hDO)rH&9CaoTsYEwqxY6fXx4YJjWx+>roXjqyi z4ic^HTS&rr__eX9n4=p{(7%1hmHo;W>|QKdfNy>VS(s>5$H5{rooX$ZYPLH(_WAC>U!R<333MEr3Hy#aqZedB)icH$e6^t9W+-Q=X^EuZEhMHA!anR z;RzKLgk)FlIPP%xa6LV^?!KW6NnOKYyUfBOabM|6s@ny=zASQC@X3%UxYAvmQ(mEgGvC9 zK0so4tobq#^tY!L{#DFGn!9YH`^zJYb#6|30$SCBE@mg6)l)Rf8qG`BI_8j}ZZt!@xwhB4&`; zPSBuIm5BuyZ_R-@l*vQGdPda0yo&U`e2}dV{A@U`c8+S+QXOCK#CIC3$yFks7f}4I zT)Jry<%qf+&`vxz2U&`&T*}MXdJ<=RR z=Rkt_%n5y?tPB!hG!n!`7E&T1)*22O?7|arHXoR`yf7n!}32j_^GJx zYsF44>4})@VvO{cpb-@O9W9$cmNoLMe#bXx1uk2XUC&VR9UaBw=(un>iU%D4I z+bWn*Vg0PmlGR*Ar7bh2sz)R)Jg;HaX-^33InQ;sR=>Pw)C?<>pc9r;xt1mA75>}^ zl=6tByq}TX94x6k>17M4Vi=*dF3V;YHOt*h@Ii}ir>FF{0`RTRV2k8|7H5vWM+tfk zd=u=?w3qs%L9t=Y_E;AAOl)pzyXgDNkYb73&cpY7Rm(<2MLC9P+HISzjt!HQ2R0)* zdqmoG%X)|Nw_mrOQ{c<+F|@?8+;p$l*Rzt0HeagP?CZ`BZ13={JZlm5yLK}ZO=!ai zew$ony?|=10JSrFYfyTlY9mbwBcEK4RXa4EH5PX1d8e)xC8Y>O)%Vy_4CU=osFOgZ zreN<0A?dYpmE9UOEcMX4o?ug@CJpkUN)H@SL>3KFoX3lm&S~knl3Ntl8X*_RT80F& z)2=k`Rk^6gwoYwg4Ew&A=Y}cbfe6|504n25JECeN%Ew+#|A{bDto{sjX+8*$lQG8U zHirFf>BoVF<)Y53`Z6#J=M72FXak^v5{SZcdYyawE8C1ZROJ^2Xc{2;y3J?^)fOp^h%*@uIiW@&z*D?)1pMJQ3EHTeBtWJs-`BOO+uIw(S9sC2sAm2Rp2 zjo!5iIhzuJ{<8-Yjm|S8zNgl~TpACpmFuiw1Q=H!GmJF$rR@-~XRZsY65o8V6(N() zVXPtsaMQ9hI+N{D%LO~#sE=)v)jP=+Ey+Qox@py;h899b5&$2s=l4l)TU7vXyP4Xe z)z} zygKI5yj7pOx}S&jjas}Mb@=0xQsjtTeD)@k)1n6v(4LTcMv(`tShJTJ*4Y1)$IGDh z2ViZ0i`OddWuuVSBA5zP9+*thafiP;jc4p`ZyqnSpli-CvW@)y@jtoJzc<7O5Z}MX zB?9uA=Ty8>nUmZ+kYic<+%_r}DcxJoZpl+|Se*2E7%4E9blmF}e) zuHt;G!r7$8@^n)>NbWxAOOAs04D_R-7`2T1S}ZB7pdwrfh`DufFD})J;W6GhgLf&v zYO_!a33%KiH@AV5S@K;eVyzV4$vE^gY{rb*0aI$g3qxdIKiuT}9jqK@(gaR_n9P~@ zbxCbk+CWUfsbbSFzCB~+*@!JwA0}GT!u^Igmg51m`IF;l-mZw*37{snUJ*;m?449Q z$!5^$t-po$6?Z30h|k@w(r>?I3fylm zRS5I%AHMB94ENyer^}FKId=@mcsJu}tG3sc8rRU6GE=9ovkoFrKYn+O9^>Yg^gVZ9 z^@R0k`_K<&cBT$MF5lSbTu*k4qy(tc4?2OzU$h^u`~ehR=I?&IoLUkI{gws5K$s@xIYpnb@bD}m1Z^rW->q2;EMP+`?`5gqfGKlFV`R%jN zQXMr~rq&7zo}~dd4CChxvRyl;b4-c_01iCI&%A$o<$Sy;_Do&S;>3!d*LuUJ?SH|q zQyg6_FDEw>)z~!lMx<*`N1kXdue&)6Mgf!>%jc00=Xd;vHbNbs5`kOs4NVTQ>#-%J z;gL%_OJ@~&(t^b0)cu8Zx3q5>@FtE&?lEw=wxL+sSfdp4yzjtpdUwK8sMA*PPPUf% zK$ph)Z#8*ZrYpKizXLAIh7n8w;zHFKoAmW8Rzqqetm&*|q6B0SpsSs6e|gMJ*?Uec zD=*6a_HNq|Wqfv)m2U}-;V<ff{BtTfQ=z@vkBbzUoHT{YwaYgOvjQTVj#TkU z@JXb?`;|uJR%dLBp>CeO`X^p$=0A)-NuPMiulKN#SkJ!t`=#L@tyDJk?a?DU*YX!_ z?b-BMZ8w=g%uXY`F0&2oIs}FbufGN$oAr`1+GZtmY#iDjNdd#N$XO}keHa!v?R&bY zj$s?RKkcRCLcAuhQ>EAH(zQ$cXi24kWaS{m9W4=n|blXt^i~eGrjHjUev(3 zGuAdWQxL}CmtlA-IBL$}mnJc-yY))-%|GVxcO~;ub@^Gz8Jdz;uDR^2J*CqBF>S@h zWCA$OL%_18`}L7`p~{|l>W_hBQ$e24q9XukRgfpCzrtQZftdLQH>XizROz+I4Q@{T z^Gda8$^?r0?IJL##;B?nf0TP1^rmpnxK!`1$Z-&jUXde$JC`X;3325q73HJ!=e6hT zV$JS^Y{%yr=Z+`mc_4_5Fr?H%|NIBNfq{3#%iSfF68RIW4e6i^GFD#q$w2!QGo|4$ z5Nl`#htmL4YM9UWznjy)wb_?y1U(8#miF@vs%06KFikYq@nC??V)y?%+d?- zb3p(kg_%4}u(qJ65wfd3QEP8U(u7OsYb*GiIm_p5zTSNJVDCSV=?=mEyi(WDX2;4K z4`6Du%Ti)hZ)D{Hqf}UUW4eObUWgI@eRz4eQuLYDs+2A{|$q zoE2}*i2aV#LhSiTSOF$;7WYV#cDMGC+Bj|1VFh(^a$23vk_Qkfw=@~%_F~7sOd0(} z(-D&54BPTBZ+;KZlOsMLp|2W8TwTNn&@3&EujUJc=)N0z?dF!;+nAczIB1rGX_jmf zd^0MI#0)_HwC~>~Zpmq=HPtf;i`3Y(>HH3$$rX|taz)x>`dec0C+bx(^MzD2vI1W9 zH>Ne9ChiDuTsu^EKjLleH2z%Wc#v$gfyB_S!5>O?16qRd$y)xL_fG)pX0bQS`ZRP0nr_}Rt{l3XtMgd^8p^4rLo_eb=0VKsYju=PR2K*{{ zi7sM2ZhKH^ti=zTFxBslU{P{rL;uF1TF{UoF+O6WdRw9%SZspE)RxZCghfoCD~2@( z`Q~NlAxm4b7TG;WU*GJu5YylZ5y1_?0?#rK|5FFZ?11T+8!Y09>nYhy&%4y>ldCOT z3_;x}Plz1NOd%}*HoKSHI>?+O8U&@T*sv5ocpe|{c-0_xVu4QLf`SU7M~Y*`$yuyj zfT@|i8w#j{0LnJM#mLp1Xo6u=4SPKF#C6E*y8&vN6U;WH5P3+65kn#3>+_^omTvrg zmayohDPHLpy$iKWVvCmk?P8^^d|RNZ)sinM@so+ELDhz;VtI(?_@AQZ&)6I-*#z1{ zU#@TJ(;Pz!1%&KI#N!fe84DkZ?K{}mY%r*ZN4;aEWVo49Xxri|$Z2zqjabXs;w;W- zwynrg{R^*?|1dUxAmI>iB*9so9BqI^0(jXWfsH7R*SWUU8OPvX)QLM~zJp~3Rr+)3HzI9*8&IF#DHFp$ zj#g!v6!)r9zBYqO5IBN+D?QU;v7Cu&F!|!kftPOLlfp^+c4YMXFC2fOdgK680LOuB-RI3CE$_sLh7Ut4e9lLqGRIp3SKvIsWce$wS(a09^$)WB57=HB_Owfmv= z%M-N_zayV7vX9zz&V}#n@K<&4`4X&(mEZP$lx96c_l$o0!*(V+J5Es4f&ASv&KSO2 zdQF3Ont`^Wl)QHc#pT!Ay&D}!Q4N$TuJ1=<&_M*iMPy3GHGAIr`d-e! z^eKttjtfv5nU>+`=rc|05U8W|T+Ghpy4!=CdVXPT6*l>_<#6r$SMtXua{;$YfDKmO znGgHpNBIbTFIf+|UN^Yka`9-nSFi)nF*oqebRAKZ1O>XzOC)B>hpZ-98^SPN=D@b0 z_4s9|9Q%%?{F1c1Dxs6}b_`|x+S~!LpG`y2O@{fso?J@WXX8?L^0?#YW%h`R4YvkI z%uoajSItxLHZVv{uX`)thkr0V)bE(F{^-BaV z9=LbI$j*8lX}vFx5pLoC&6?4Q@Vu3_7XmNV@sLsE>1xyLS#o zkyk3`A4Ak}9`TUi|0Va4NJ+7)H)cZ};%oLSG?*;S7*`*ZI=T(@$UuyFx><=SW&%eh z>3(hL%BR00_evG~y>6;hWB$Us{AaJcafNU2^0&oTbVu#%++v(iLpSzQ_(BzT^5N84 zwdl^I@H}8YOkaJByv(2CyHdf_p4Ge`5_N~`s(Fk2VlJ}HsNp^r=1nJ5v!h8NcAtm{f5=jkauDGs14bNgA6?v-4>(*!KuRod={nx{|R`=KXg8}98Im*0MWBYlasQoS92Qf^s# zeFyJi%OZsN`i)F6Zr!|p@BgQ_`50n)1g9>=v9fbPGf6&aHD+9AsthSJ`tB8!tt0w9 z*3miezL|^0%IS>OtxlJ>rC3Jg$;zWA>akWwRYc+aC3k(d_H$eiyyzuaaGVQ4qhIWt zsE$4C_Ofl7)}OEKGEO89Q|Mj?H_b-VE7z$th9Q+GhuRC~r-v0bauWAgib7{U{=4Cv zuG`!FVqVeEka41m;_Him3OF>jC6Zm+Vg3G)~H6` zIPr)Xt$istm;OcRr+5tbIE{;{1rR}&8CrqMD92I!lpT}E0N8aX{(kri9Dfgk{j2xGC zGbZ=O_Z#&kon^jzqe1NAap%Q`VD8Y})@~KHzTZ=$cqa3! zBKv*<()qOavr+tG0@-r9YsY9I$)aV@R_&%3J!QBIY2G+!a8svq|IeV)QXX(gcI{2D zNnnKXbG|h)^rs8%x;hf~F@2rs`%c5Sn8C<$Cc#d-d)c z#Onq+Y@=@is2&}=V-(a)SQ zLGUJbxd}YIu8Lb=%Or9j#;!p_=E)<^yS!PGS0z2k*&pV1T1rNtw!(_X==Z^idUcOX zxi0Q|4)0&}7}OilDsi!1l4-E$#utuDXvL-ANwqc*JK5>)&hKKr2U)&{sA<)abG4Rh z8>_!;o6dDVlWyf`giE@#09BIVY^{%*`hKT~7;t8`@P~aTW&9Tg!LAO>EMzExctHBG z?;+@&9h3BsM%I0=FlrTQaE1mwDzrrZFT6`(QX`)&@y>^!+c)%$b&J^-;HE4QL5sO! z*pp`oO{l#@p;Oom?{&T}b*vlY?iw|LXXW+&QthHj#Zj`>2KC#jtg==kQj=AVe>m8` zl^+8w*Br`Sd*&ueCaOTh(cmwxT+$!+pz8d<+<9YFb+ZfQr(^o2;cM7{JACIql(mV{ zM>U??&-{f)p7IekZyDX_2U&AHSrMH>Oj%~n;L_2Aq)0std7*&6@U}8sh5TyvB{xmR zTS-la_Ba!QDwD(>NyY7TNBea=|I(x1U+IunLt>|O0RA!8%4np|Xw_1}Th+CeEvDHP zjLH>_8D%bYPpS1H;U-Q2R=&!vQLhtCrjqsOO1Ki&ZuzFWS7l-0A*EDBq34bNoFH=wyu z71tg9e6tloqTCM0HrR@=(q%KY+@i|jEI9Nh_8hQV5h>@!6A3JQSvY(7$e;gi&))NA z(mSJSCHjfsd<#qu<$o425oy`#rxx=Ggr+w4g;Djb_u`qn_~+r`>f{$zPh&i^AzJdO z>k@uUBnlb$O#QBIzcNcWYjbe)K*7|#AJ{zab}0MoHSvrzsem@;-O+!T1}6 zXZMbbyVq1>8gh#eTzUnn?V(O^)(s9J-^H9EUW>Pf!)s(Nq~y;SzVq@+uQ>R}N28z= z-<{j$z}bUIwunNagy#ZjNbMGeUvm`GkCB1?Z=-AJQ3hgq4&-28&E&{|erwWyAMit` z0*~aYAtiU{w3k0G*6)fQ5@@44TBh&_*Gw@VBN59&XSSg>b$XigT+$1-Y)v^lsD=kC-AnV@ob~+q;n5FIMZ|D=KO# zZAxN1%c4ergmn_RvNQpO(^y1sYy> zIZr1_CLh!myB?7F&&U9-`E4sv&H(>OJ-3?l*c!~|I1|b^&#=@PJ9f4iweqAyh~vi7 zB45@01JU@2Ygdmdo;cS964Yq4aJY-bqyYsEDh4Tr-vl=<nJ3% zQP$f#8k8PU!W?qe%(NbIQYUsK(XQhu5b`VkheHBY`P<)zv@&?~0a;ah*K;4lgb!e< zPm-*0!%;~Ta_3(994>ra7R@&9LsEVPR%@&WjruqO^oht)eh~lWX6~8GonyAsjD}|@Vg0Z@#g}>MmK_@b+MHMJSFYXld5{1b z2p7TTkHhSfR}Uo|lb0EZ9E`bUd%ZR7UO@g$f($0)DSL{Hg75fZvri1muiPsV$2UHO zJGZ$N4~;|)C-06Sf=`HO9}MXGD+V*%ug!`2*S=XAaD4})o!Ln}!{^Bws@&|F#?8RD zXjtNl<2)11w2zOC4-L{_KeKJHr?bvJo1T&2llc~2IIeHy${BT^+NWuOEBUNS z8Xpyt90#f`1q%0*Ldm*fyWjB5Wy9VE^BKJva-teI`PX^l{j&^qRb9ZpO~cmhkXTWD z!g_BgWz4kiT59%dNp|l4gSWSiYO`P3g#)yug+g1jc(LHF!HX5AxJz-jV8x4+;;uo8 zOK=D-1&RbM?$F{8pt#GIXYcoX@6)~3-s?T*tabh&e`F;$x$l|z&CE4(U6zb|d^~s+ zxNq$e=YZfyir0sp{`A;NYDVXI!%dKxwE{sNpM2@cuIoAcnzmXvA;PZa)sL8f3k8Pr9yNo z7K`U3V%n(gG5A7zGZxQ3!O#C=-UA@`KK=Hz0??rsWTIbO!DA+j4bf@VuJ`M8lW>?` z@=BUHtj3x}U?tToDU@?yRh~<1MSLLhNVbMCJsJQD9jEE1%71?^!qz2HbWMy@+Wg+$ zbEf#O%-;+>*)=Vi9ku1$=Zh?5g~fPFqeZ9r=S#M8aPAOC(MF=3jkWyo645O@))CV; zOAemvWS)`7IYWWH@=t)686ka_?~rXe34Nq;XUc4Q$ybV}*V)^)NWD#*8^S5>$Dk5- zWg8t{1DD*Jkh3VSP>02Z7&$HX!I2TgQ?9E!A;osf<9DUfCqWT;{DUZ`Lt(mCn&v7( zWzia)&KX-M&h7u6rWi$uo5I|^Vx!7-dyozT!6J_dFa;baj86l8@PDrw<5)XlFTke>l{= zv|R*CD-8F_g{`F4@$9OmNtYDqg;`y`AXdxW`Q^?8NlaPP9kUoM~l3y?l-yeWTY zD~ibVreVuuz0ET%WEl$} zT`i6wN$-$Jhpx9TXw0jc2oWuU+{(r& ztq+AQh4sAl&*BD3KK$C)zwN|*GMDd#HBy=-Fbg^~!b^qMMgq=V-H#EO9Tf`(g&#xZ z5IQj-5Y9|Cxs2T#?%PD}iW($FV@;h@$avd8i+V;xmxS9QHaw&D_-!Y0&E}Gq9cSwg z+eLvd^Y%$21|}9lBIK=kjB^bn;?=9#NW6WSrB%TyN0|IEW;ZD&I&H3#mA5%6DibbD z@yPjJpiGSvUl=;Ynz2K}Q?NEsvLdt-|Gx}U^<^UFV#pHRpKZLX)g zcZUn>ZnM6}2pI{Vgez7{FDzJU)07z4`IQMY#YyNc*~lo+>wh%@dYJ2PuK~M0vSRzZ z7Pg#^hl*|c`6dJ=&5bTLTQ{VYCM~!f7$lLagVmz7`s`m-SJoFNJKUNb#ju9c7(G5r z={r))Fr&%J?k<4o0kJHYWBDPA88dqR)GBq_JMJ$>%{@GEKie*YrxvXNhJ2ePQ5Z zUL=C%tE<%P(j|Bn@p6(Y|9gUFOA2L4MMQZeI51zYIg@dpP16c9N4ImoJ*D}(P|}bpc90MaUTxwZ}<31G>~BR$eDxIH2mj<2~P|DMs7 zs6#9~6S7$MI?UEXojk{77dvIbAx&_Bj15;&yt?$|4p<{OWR~IgRQ~c1>9rT%Krz$@ zxZdZYkJpali6-;!>4s4tLJ&gZxdyD)^A7;~-JV?cQD$8a?mX`&(>nsBf=v4AMS_LH z#Q7&I4*;57O*X9h{4k&R^`k_YFC_`4v?I@n761JWc|pPcVO*dbfv!d%yC?3TlvrLB z*PzSnA&=gg6df~vwtMQmAY89%(}yIe!!xz8AKDoo0M0#{=xkLbeEoDTI=^(~n&NBz zmbp6^okiD%z?xQe$vZ{2FO5`vUE^r+yDem2lXk6xNMUWTENlizS9WxZlt6f4L8mnh z+tRe@`ATz6^JxS0J1-s_F|xcMC`=PRV|tu6KIB5eh_DwYlQ0K=l&E7w*L%&12d@%0 z&Y^Ny8B!#?QoLIG@DD{u08;rd|0=A_ALuV+`;EHE-bi=WSEp_|J7G3%D`KnNS+<^j z!P^e;D2b^&W-3&RlipUZT=rQAW+LYL$R0G4)NEFnwsSNHz3fI+!;0+1XpNI<3+N_A zk@tj0wZ)-ruqJOH+Qxa{azB@s=X?rhcqKB6V`EG*;%7U~J^ch($E<%K~yenbpDpWr7m#SPsi z5Z4-^$a9kJm?u6&fN5f0D6$Y~Y_iQ37y6*M80*$N2tIRs|FW7ry6Hr6VewtAnFp#3 zb9%D8eo$GOex?E$JR-<5gi;Qd?(f9*D7|}z-g(`&h{f;bm0#0krPS<>RSv?Y?qtCA zKE1C_3ZpTkJYJ1+#2HXQUURtUZ&9QWeS7v>N63S+9CmVXpfBum9i!%XwpNhnw6oB_ z&P?F6F|eDuTk*>+CLv>UM8VV&G=j`6)J~N?=gsY=$nG!W_FC=Ky)vvy@2W~EmQwLcYk$cVV*Z*lMn`U0LL{PRrwQ=gCuOCxV5icHBStTRV@22dJAv#epR*Jhtb3&`VOw%x;S4Rcn@r_9`w!$S&k9q+^V0wtD zI_3B#lm)X&Z3QaZmI^vObxcyxyi|louQxLI&>TLA{r7a}XuM4Vto{~@uC})OwNQ=F z1$~&!;<#d&pizEt+;e*l)r><34P*Ti!SlD1bsvxfv^ZBh37vl(Eo;c5g_BtRkND*b zp%5Quygt6Nh^RV6Sx3|jO71xeGkRriMcz|kod${DB#g=#?jB|Eu?l5J8&TY|g_2V| z#YpI{>w{2Dxqg~$z%KHd=aUE5_lB#^G+rC&3DdOyh+B#*3#*b7^zNr)!wTMh?h+Og zJSlmlMs#?2dH8tePd9%P4Vj$UH_dgY-OMrBZk;pEolU1;7SJm$i}`XO?!d}~QTNHY zg@ls%7v9S2b+O%-MI1gvBkX9A8|C`T*9Q9({`F_LeYyxYo_sMj+vPU4iY+W7k383` zu0x@qsO5N;47}QlnM>K3Xf^tjaD|jxqfknlw!bS%VDp)rERmBK8E#Uu_&yq!V}w}7 z$G9q0?n-3VZnDQ@ayzLqHAcrphVS6bc1FZ+@!vL%0F=GpYfV`8mDwFGzYtrKUXZ>@ zGUmKcrKP4%#|9qK@=^6>WmzQ$_tE@oin0ul zc-z?B3)K)=WjV#~*%1_arS`9N_r%E=IPMwp)K!mKK}SBI5f{=&cXEsgU+;?FzZ@wW z)&5!!*N<4JXkfY>i{1)3wJF87r9Jk7n>d9jW}{jcZ^Ltqe#REC3IVwPTxosm{{VoA z-XldouX<2qcNP%R%16H`$KEuE6s5OhUeqqLC(dR@D96Fb<=C98(BSWqTSq=vgGHjL zd1{)q-wjX)$0V$gGqj>W0aQ$mZ>@Bn-=r5H2YiV&3Lw(TOVi~oz%>1An_kJ%bm6sB z>##x>dTu}U7m4beo>YyLt@>M?v7}oCDa^hbR}TP0ih*BTfR~O--?CBmeUsbF&TDMd zwx!m$4(i()f^MmSTrn@_Zd3cQE5`?u zMUHPD0B3_09Wvj%Vs6mmO;Xzu6L&>iqavfMHf|#$?iR|4s*QWn>74cvGY-t~2AeUc z>rieuy$Q0%`%fI%CzbW*>Y!|9eC^C)i>c5@J)$e)hWp|aE~?hSNN%p0z6E{rY6J7! zc4fLFAAcHu!tT|rZ)7k2{3%y8cPah&+h-d^*R_y0s}Qm#QuyF+;SVI_iwBFj@Ek&~ z^B)mr(K~CwW6Do>Io;G5oPTjtM}}6S&oA0r+O^Ej=$^2IKrE$AHWtaRrs9VoZB$rG zWa)@17{4r?l-)ipXIgF0&+ypg7bwWK$^2=}Moepm=$#9qa-5xl01RuKubM-zH-v5K zp761T_tZ8GpFpYf_`O_71*o|R{cRlLDma%{4az=Eu8N@3ln)_ zmv6%Ri|AY+ANhT^pzCWhDv*NIRzR@UP5a->K$OS4jq&xsT zKTQFg*!1k@W5MKwd5E@~#e{^pJ(fo$VJb2W)TJdEo`$JvssOzypihsq*SFT!My_~^ zoU-sZwRxWDN58WTBj0zspQ#0k_ zJuPh-4ur7fYkz-b{?QTg#dD3is(}p0n~emYDs{7)v;nTp_N4^*Xma$f-fXJ*fT=>I zq_@=O_zFf`2?nG!(1MT{=5b=~ZpoQtBa8Hdw-MRIt9{|>Tev`TG+!5u*UUqd$vZ7Wy>+fxP+013_ zkPHSk(ABSb#RTgd@qJP8c#sGjE39z7!ea;vm^Q{wfmsqy^DmU!RjRmdWO}E0 z46W7g$$eU`n5NUz&8~JR-bcnvVRwRQS;a(s05TxR-Q!t56D$_G2(YlUdr5w-Wxnhw?Az^z9dife$T07fGh zgO@Y6NRcjR=ZKDij=kxlUet!)Kwv?^0f|M#`(U&0=dz{iI6z$!x94Q)7uz9o8$XG;ey`EF9J>UxGN_ zZK^jNg}dPLADXfJ#P~FuvS-_G|BOCUY0TZ1ZIU<|hOb}DpdoF3n%Gnnz5=gwty6>c z^C>?iVI;HM@#MIFP9hqMo)GRR*}m&t+pSsV_Ux$=1d)C^>^^QYUvpGb-fU?j!yH(_ z$SY{z3&&ViWc$_NQ_bm!EhL)I9ot}xRHIk*`M%tdAezPVlK}AKt+Rbsx7rjbu_u;> z-(0WvUgzd*QEn@8s%~X-(Pa z-vK>+W>Y)Uwg(C2*_ry9p&(J}Z{ra>WTsU%tPS05es}w1@ZCu4=mQ``0x)L$ci;IB zI`@G87GnqO_(Mv!_EF#+Z6fJ^m4Om7z9>cYQnAT5Z3L{HrZo0`q~l5%viTmbG-R9f z$XtXG?v4;{zj1OG=e5MA%{F+YAhmlmO91dC;N?(}uytBXUU?{!M1;4KuSJ>u@?hzv z8u=b<;$=mB=`2}a+!fX0fLNYNM7O!pr^xKam!p?ztWLN{0TLJL?7DS)I9U*`M7X)5 zy=kr9{9s{gTpQe~sYoQL)EDyDh~f3Pre|^qGf0P9&P{l^BUE$^>({eLz#}fPt#U4? z1(EU(dS|y1tAW7*Grd9wbAs;%s&6MTXOb@Ke;YO1k`VkFHstS>MFkpN;b`}*1KCk6 z04PRRd7Ha^H)3unzm=QBcveOmq#gj0Mroq~%>MJ)ihiSaY8LAdF_J9IP!fAwoE0a>=N*2Z|px!y<*nN)}hi$4`&(POEW!oM*yJ{{0eCt zRW3hSz5p;HEI#yDE@8*R=1yyUx3AB{lD&13=bXw|9eJ6-#6}P;?Cn9FA5N0DkR<|z2*Z*k&FTeK5i z;=Ed{L^?yux?s*mYASw7sL((oTZn!@{Z{}ZYxsvA`vaDUQC?pb9{14Pf$vpOGcBwH zYiw8*iHXIlA6k8Ae6!4sG)xAi#evmhZ+X|%qj2HXzZ9AT$LT zqbWLJER~Tqc_nR&qs7To;rc`B^Xm;|W^iggqaW!Of8Pd*(Z^pY3{>SgGhDN7=22h? z)!h9GxAt$5?PcSr?9(Ci3I&=UK4c5onOMfAayw%sCa3|yiMNh;_kh|r)ca)%xO|ZsSKU0=J&@`T+Rbo`eb) zq1l5+66!GVy~KB+(EP0SX3jQF;WL3GslXDY!J72U3!!WE`uC}WZW>g=i``PJjDfcl4Mv!|_7M4*piijhOZWz%4o%@I&-$>PF1Y|0)%=>8|90ZSODb`Dr#C0P=m9 zNcvs&wb6CY`VXWjJ_5ZOop-@lkM0c1>EUdsubwO4H=i(+SzfQxpU9S*5*ZGxOpLT< z5|UR>CM`>+70CK+)SZ3w`7pQ_fJ*cgJe@XG`@CoykH2}c&fI*1lVyUBGs1+mkeNQ8`gdN@U#u>u{L|O+nl`ir`iOLI;_k4<<~^Fc&m;NEtOw-z9}AdN zKIN3Xpif!{txoic&g}0C>sB=AZW8|zL(RSQucUF(D z=u(&ytAZaE&m5+t_OgdVK_59%?u53A*w=eIrBGzLjo&-fTW@_kZ#fW@h8{ks&4rGx zdoi|_M(3zsy7dyj5R2nh6t5VjjMNaNNEAGLbw76no%7$m-?(a`K`CjsIV-vrExdP- z4v6_9K4{%RP6YR5?qmI(Sze=w{qy1dufJMI0(Z3s!1iAh78&pH?{ROQ9kV?EShEok zncu7c7!QDod*5cZYpUB3AJlIEz>vtBsr24}o9y-N^vzJ&`0Ss;{B@@x(m6)u?GWuj ztqdX^52vxcl=%098GZ0%j+2Bf&;tP5=MDGaV-Li%Jq?JjSX2!LSmu@yr177O~mcgFr@9D&?z z`^Cl+mmg|lWt)@*L?u(imW05BmhOq|`-zubt-6i=TpOqsvhmt^M2i8}X^UO!s3zR_1u zl~*CPm1&f5XQbD9+_j^QkI%934Q#KnOCLA6ni5`1gS~CZY%JxoW0UC2q2+ zE=Dh2MF>cpgN@%c#hi5SKjtM9OvswP9v-Ai11BW(zsd{r3}Lu!2%e)9zXs&oj~CFs zS{JmbidPFC{gAaw6SUIC^R@+Yvd~+iZ@G3es)ePCgc_BUpmE|#1K** zIIlsyhavl@&R#*~Gt8g&_lyEW zsZhufw9fYC`TcnyaaRT(9h-V+P*zpL0lB{+BP-lAu2cf#BB6Wx+FKZ3r%}WtO+I6* zmj+yk?N1khbWt?;-rn~Sx8y6sKKxhDj6D|G(svy=QQhv+iSol+uD3QOqBD_WdBXAb zk%Z)r@uDp=9sqY#$hAVk)4%5x$RII@gsduujj$g8haHCDov9|hK*k$igmSvsp(8;&s_tO=X_H3$Jcn&z&^e29 zVok+!m*VUMc4T3N^x?lB(P##@H?BsfQdb$5sC{=Or!&aocl-e`%?1qkkC+Mm=)Q83 zzvaEveYICVnu*U1xahRyD&sp^!My`CyAB>Z@FL7R6+K%Hpt5UF^n$ zACujL&a;il)82u`BOLjAIo39^TWX-6+m|7-X*8iPR^b8AegERp{|%N9^3x<}b~gPj z*>7#bSW+t2>Pchj(7v2dNcg%`)HQW<*Ljk4>(@dX`_YGw|0G?X0yqh6-DpxSjVv-U#pyXK{-$!k0oRgt10DdRYAvrRXPhX4kJL=?T^XuFWjz^)q}P*!qp{zkFSKWXoy8 z+>D?%DU4?T>ZkVdI;o}*jUWl0)j^`>w&iiPEJ|lf*Gay%ui*MNT{^?8Q;)432`(q@ z#7cBz%AedF+hwK+dCn>-Bwn#?9C`wb-s9I+TKs}$?9|ZNagN2Z$Jrws);EDhu!!(z zo6O#}4bt{lpHeJhKDyB3Oo>Efdm;3V$U7dx5)zz+Xzj}rEQEUR<-B@l`BH`w|o0QG<*e8Wo(CO^$ zd&pH2F{Ui z>=eX({L|HjSv4Y3gP%3Ft!4YHI2q|YTeOpzI-DZJ`3-8pO)CHBB}o4Ny@Xc;Im^ZS zY1YM3ZdrZPHO_cZ;Hq(Ze=XfcX9%T%Ck_1%oc?ZuA=hy zY@uClPxUR|hycsx{lM+ye9jUrwrS;Hcex1T%H^corg-jzbQbClu-F*4O4f^QLJn4A z$DwdFqFo1!Up!x2z@bC>A);$2;ovsY`|9JHP;PzQU zCgoPxHFrA~^vE2q*3Z(ngkt=~0c{?@>c3+1f4v~zeE`__-%&gOPQp<;y8J(gAdAh7 zi92U-BNnn0J^Ner`B$~bmzjS#cM8b^vw)Sw24&PfSY(u!pS3E!+ADaq7V{jrA9t=WGf9Gyl_3C&4M^v%P^9Sdyl^Zs~D- zuZzgeqxoTduY092Ofn6d<7aEnBxwxT99_SaKTE{pB{!!gd<~M%K<^r>a21D@^tRsN zN(DlDb@jQbC4ZDgmP8UQ;ssXrH-4`pp-(lU<8E`lHEB{&_sNaI{_JCy@cr=7I4a(< z?Y0@hiKQ8vJXBaa7S>>^8{RQFyYw2=M2DQQSz$kn$pyAre`jJY!0RfZ-cYm9qUh@6 z^ndC*%->$%TuB*|m$&PzJIr_fxhk&i%abIV1rU%I-s^r!ELIZ}?nru=!c8MQZv-v` zw;%V325)lI;CLdRB=SJu(-@scOYrydmrT>eRPGh8?lxoYaj$Jp#v4%&9gH#z74N<>`#1N=|CN}sWEc2h zE7;dtS^E|U>W#6N>i3mxh-DQ1^wu;Pm)cc?x{fZJxXZ3BX$W8HqJWKDf&1F*t ziH>bqf^t3aW@?_}PU?4SECfI$;w|O#V1&$klCD4}u}8uXQ*316GDW_p!OqekEYc=8 zA)!^Tq7_!FJ90;lZ5A8;R+d)1#$EEVl#FBDBqg)KsriY8n=WIduE0F%PN zzIn?WGR0ZTdNRER{hhGMypy){{gfIA_C)(?oa@NY;ogr6m-g#5tTDA7EH@;hG)s~H zA>Dm7DJ{YkRd}wgqoQ8eg*O3(#)h(}o*>`xLw!mq2)jJhz;DG?jlyn=90`RSRDJY{ zW^CRlE7jo^co#2%cSN!_kouL2OU{wR4|kn_z+OXXEMzs>zId1MEU;ytdIJ$O{N)EE zCUkbWxVY=BW50Agf78Bbei`c|PuoD0`k*9y?WWDl#dyZ(Zgt+{0f6d{c-3XtAjT-_ z;)W$(04lQBvEgLNGpp2K%3zuvZ9$KN4Vgy^-(k$c1$@d&KTVD9m6_~=v2{6|1F7;% zf$hHI`VC!QsdZoI4lfFXJpkSt!InH^h(*w(c6Trg{O558w0d}>P^%3NbgW_PjO}0r{l+rE4Hxr>UPTjRQ~sf+G-Pu8AaT$>={H`DJ&nqcI8-Y30DRA! z+V3;swp%Od(AF}hhf{!F25vlm5HeLbr2@3Jnl)bY5&IPPBBLZ%(xUNaY{Vz`#UYyI zA)n8%WJt544p~aeo)@9^IU&E}Mf!XX^;9M$ld$o{qimVJnVi?NZWY}#;ewh~v(*e0 z%~%E>`AWj^UShU_4qv{h7%)sM}nkXsA(EdOGiWl)EjMv&e=&<9vW< z_>A##r(+;QjgGQk0{1wSVltb9uX25KE6Ve607}aJs8M=5*#qF0|1bq4@hcAcU8d+& zfdBPGz@JA4GT!|62OoK`$ki-()moRJG}HsDsL8#za6sZwL?!t+shl?y(C6{vpgG-+ z4;Ar|hjHOq#AGF0Ay^w2K0njwW!VKp6hjUwed`YH8fwVZ(zPLP#r0;bwP%5YI%)ME zDBo1@ENA8_Hn}HAFH=bgE`Bv4o#V9Ni--@6_&<6GaR$qSV!S6bK` zr+){RXYT6Ijd0`QJbPWN>B5C$1B*7x4RIK2KG1~wNG5=eRoAJM|IT-S#&RH%*c+B? z&w<}iSsxv}5zT$EImPofJ2-Qy;oKYDab%_RELG98uRh9`_&nLx3p>Tq%Mb3Zt-{%; zB6(XVM~qeJA%Bg{I$7Ra`PN_ys)sR3_Siv`%bo<=4sU{fYTx;HN3-&~su`RDS#(P= zD7%!84? zm9jU#rplu0Vgm2@6Sqp&2my&!p%^KA_BvHbvwEzcf*8D6l)HVy;EUZ55LSt4Gd79I z5W@?6tzm7x zMDw!fU^Y=aGbU#ieMu{kNOHaB`MdS5*H=9@7G}x!0+vJ1q;yYesU{Q-Cs=1d`VGhQ zNfP{BC{8d6r5bRlTSQc*_BKtu-1T{KeV5E_+;~5kU>B@$VgZ-)6|vRF<6OhxVF)7;Jdmu+;Mu7<<9Y8N`B;I_rV zN(rtL1EV+t+1;J0BX}HQmN5Jkb%B}du&3$w3sdg*hUcCRayL3Qy&VnOz~48jaEkp4)|e&uWDjPC}zsW6fJTLD_`*s@Y*m~s#L0iAVLmH<4<^HO3mIEvZB)dk!lklQRqwxn<=jHNuc z#q#*eFd%rnpkFfU??fh#G+e5V4ST9!4R++7u;p?)9m(FB+QmjTpSeBewXfzBN^h%d zdHBAr$nu$E^3ZRrNq(uowcF_`Eeb5o8IDcz{kQZfC^+z87n-RbH&m7xW#bE2vc*hP zDRUy|%fAmot2N@j*z05q7fc6gI!$Qwo}E9da!a~x;pB8sk5r(_!oZpN4@@jno=qd~ zf|@?|1|v1cMY=9l-MbGD*aG>!`wp($h`WU86p7$*|BxBJIWm!R-Z26l-|Ng7vV|!4 zFcwAP^!=wV*5#g|vbhSJbt?ktz!tAQ=uZ!Vq<{J%Nk3TJ5XB9nZ!l?5zUD2j;xEkd z$}`UN9b+&Kqop=+%C6_I{6RQFo_8NQwv5Zf+Pnak4`l#(%^x!|+)$iG54gdaJ(ZAIl3{!hn4yac&uQ)9- z)<(7U@#)kZRmy8KojgCz!5@^Bv9_l<5O`a!p-^~i3v{{c>GdHeHAe5v*~@aCiW_$( z?o+gj0^{N`GdyOeLF` zGs`mRRgm|^j3)Kqi|Xh+BlqmqIkx$Z+$k@!R*R$*XX%Kvm!oP`NQfhYMV8eJYgVJf zSi5HDv<7#$X(CNj?THqWsdemb@We$1P0eQtp?vDEc)J*df-eQ03U5lAJ`+h?hI#6= zRD5fVZzFp(;_|BMSdZ%D!z|aH$&wD}+TG_!MtN@WSBXKJd$W~iut2F1hMz_C(>58NC~$qHA#-tB>R{J-gil0KKPg9Yqu|EK^QAVc$HsSN^G%`2ypPv+P*ubVZ-@qWMV} zwP$kB2ZBL8#IQHH5wXMvnd0V(S1vVKoaUVas>V&&e*e-Y`&|zlFWT)*+H&8p`#49lT`9#| z=Piid=C_Yv&ll1#)Xpex)7j)$Ox!c2<0SH~I?YSx!kd3rQS;eQ{jD&Zj3%?{SUhi@zo1GTlc4R0*k*iyw zMSsI(r9W5W`P$RRU6Z~7@R5>fR$e#LukmwChX^Z| zBVF@OKUybs+o&ec8XH$D)#B1?WD!NBI3m&aZ#``Co9#7@`K2U27yaShFZsmwyfxR# zx^4GKe}COk-dr-O{+Onm@tX&iNx?Svd@Xf0#@}Q4OL8&K1;V08-#)NTYC)6Hxy)8v6ud$&0lPsmzCV3SV zHcd{Md;|GYJYVVwL4(LDLgEjqt72bMk2%5U_H$|(LVqbOgjesrBdn9*D;swr>-nX9 zOz!AgC>tg0+Qc-Wc?pEP4#L?+CIf>3+e!_1Cls_r=50n&&Ei z$LpDudeb(Q^CV6LvUFW@?=0YJ=8Z%m*z+-CcBPoigsAp0y;Z4LGMpxWdoN zL;v6>nE@4dUPt-$SzvBId>Zg5aPV zh7S;ocTZX6h#th>k7_%~gkoCj+ znU@lP-;v`5Dr$+1hxhscr=WU-;w(XXS7zF0lCn3%&?w2QwZx&+Et)#!1Xz(Vo zjH{tcL#L(@uFjwi|KbSGFnz)rnF9@KOwte3?=j20vAwf~NcIk=pKS0sli#V<-PKAGhq9l-K zEzt=vI{yGgx4z}R`wJ9JLoxrRb)Rz8T;cbF6mm1M^OXSb*#D14FVh|0{fOwTm>?2Q zcC7kiQ3i7&`FBqylne$Z~mNpkRW0a`CI= zq|viIh1~Rkv`2|rq?CCsY53Y-8U+|q@1MV(Rk&gmWyQ=sG-IawbH%F%F$|j^A>pHUE?GA zFu?DU7-YRKT&5N!MRTYhCpqPAj+L=S1LO!Yqp|<{jw$wk@AfbQFly1dg%mY3+@Pc% z2YGrjauYllznvTuglcrVDwyU5?!KGUOH)_nsEtpYgCnuc&VZLbc#rV)QmCO*soLrL zeiUs9rnu;jNk^#2S>i<|f1@(5KCh03Yu{gyu zY=DJ@^<$n_*HBM-zqr4+co_E9pO%j1K1gIL(#M;icDLE<3Q-`JE{h}|%Kh9aAGyW< z4U?g@Leq-{kbu|yEzdl$!}^*=uSG~9c#qWi+;1t*){=Admq}6S?+y8v1G9O#d`ePT z8X8n7jEPMnV&IPdL}(Iy=F^~QCoq|Dy`Y@6I!aN^dq#p4zeN_kU0P7aJ3OPCL!G2N z^~J1Ifl`&JwrF+hX{Jw65XIxpAso8Sk)msJbkA80;1YzaT@_l9tF~6N?e$_5 z|LLkRygm&Yh=E1BYdz&`T1CpLGkg*j^)2D(p%S{<^ByK$CfX4BDJ2(hH?2KaSHbEU zX4-SQ1YGo^0UV0|cvXQY5^$9rna2AD-D<1|Jg5$;e0qE5o;qVCwS`%(x*;#GobJby zCl%~{7$5Krn+5#%B9dPGJPaty=$IrOdofJ<`xV<5F)OPko7Aq%4nLf%LClnr>`m_{ zBfGPpb0xcHAd53dVq|&=y=o>`3N0@OQgN7eSw1_kZkK@x%fbfOW0bnQqfGx5gr|UKDhf!XfXUA(@ z{Fjk?yCm#b!{-Q`Umn@T?b`DsWy$>W*eNl+=M2xtXS)TVygI#52CL8TxN>vzNm$KU zf3zp5&!fuCS7Wz5aIUq@t5^St5=O3m_gfoU^v z427SK96=TTVjl{$$fB4LZ?Xz)I^*u&&*QkFOPvpb>bMjv z;g;V!k22PJ*)GLo{Qr|(`H=4V7aIECa@!f{z4?Da&l7$29O*xIiqLb_8|AEDGqYX? zNgs7-$(?6^<3wmK=tgF%g6Kkbd$(L6xc%l-C5aR8Ln9Jeu?`!ky7^Wb%6%U|3>szxO0|R(d617-Gf>b^ShAYp74xXj5-0G3 z!c7TL9smN(Ccuso>Y}0z>YO*fJYtv!h7<`Cx(2`MItKTcdRfCx)-hl8Fds&Ym! zm-MGwrvQ1Kkw`nppkT_U6`^CNIgDiU;&)jMb9me0%7@*m;Wne$@g`j+H{P9^zO=O1 z4zGZfE5TCaIUoy08E&sp7ODTUhqt}(bs?*Bd}>pLG*UI$`HCy@=c7P0(f=Lz7#UR6 zhhf!co3%T>lx)?%>)QPB9sp9OWndz~wp{EI@?)`?do}Q9Eb>tiSgtQYdpqGyCOyjb8LP=QUuNUL^aJgRaJTf9 zeyTtg-4}(7#u4XV-<~;=`e$ojYbLRbS=qKsm#f}q+Q4lhci`CA>qkUm71pz(KFniTWWWlC&<=% zp2_tb;Q!EwpC0$IOgZuGJIb+6Z1u^mR68HX6Cp!t*y@SqXGdm*xO#yS@s{otmc*0D zOi|opl1rnXD3rH<_ZU*_>6Bdq18BX{kjUr{uJ1GIBvE^Zl3P(>IM%t7wl%zHlF3@a z?-;&x%dCp_|LWD_?*fU&tS26NreQZg3#n|c;|09@R0VLb2|bU8%DxY^OpjHoa5&$+ zEy@&)Pl)p>Wu9d>o1&(#8OR7LOmji1-S@hnCCwXX4UWK)d+ZkSU8zG^>66z<8YG+$ zJz55Cw#P^v1qM13&hXOG&z*9rYam|m&u`BVs;>*Dbo+Zoo~zmJen6tZL<|w>>kiHt zmJ|v6BLJBi|lc_Yy^Cy6VADWoQ+#tzb*{S@;XY6qet z+acoqO9xjrvcQ3Gj=_9(5x&-CTW4qbNF1QPQZ0e6^l^+a1UPdp%!NWogim2Kcis1# z{e*;Ppn^ch(vSiSRDGF+OG5bo_|u}MBSu;%v_L)=I_+x)?#GIy&&@K&Je%EfH{T{` zJcn91rUdNFo*BR#N{-DY)PR&&8C%HPi7NLmVOGSo2RGl2gEJQQ<{hNyO%Zig_ptbo z%hItD&;+PhQZ3MRuvR(vfeZTaH+G$uZM->V8O~B093ZU z!da{QKQcv%*n!YndQULL+~96|e0 zXuZEsLG{9DrU6?u=UefaH9jRnMwC7DJNerIE2>{tYsS|}5nRFsKzQQrdKM@=4N1)L zxGz9pB`8z*bP$eD#f9=O9a>7dhI~1}L(DAG8YX$UhWM=Y}^?Gr^)&n!j~Q zCruQrfS8`9R+LzErs)g2l1;`(T~CG&`lk@uc7Mq;Jgs(q4!=kI6ZuBP~^uTwjNe!KoT`RZ0k9(a8|hAMhi2@>95GxDFjYke(|g}BZPnY zy%VfB+Ng4dauspNzO*wpHuf?$Zl5ZbDsMiaJ>IUDmnV>(%VfCOyi-k<3NM&d=yfmq ze_Cz&V+24O@XBy}s&TF{w<2VBrxFO;7}Fbe?~#^^URB0%puaHi+ew&iK~3@ra3k17 zy}amUYYcDFVthwc(5avnO1Eiia<|uvw!X#eRTmK1z*{S?cbsBMU(mkbozb>C+ykzi zJ1{HGW20n^j2d4?k7!+=h?NRPZ z;*BT{e05~zkgIs;0p-_c#$0;AsTcjNVe(>gedcnGSEj}6%%PSf*9^M9xw@UW)Av`r*d8@{CX=6Fr_RFo~>JqDG~7- zFqGF!kY~Z!oN@7YNbwZmOkxmIWmJq>5mNr;k%ao)vG6X@9SN2lt@MVz|0Neh|7DGX zIy_TraNC?~__@gjS8TJAq=L_XS20!Z)gs&Ym>ASWR13@Zn#aW=Wl5Q1OiFJ!QzV8q)& z_V7CVN;B1K-b_H9g(t0!2-u7ZTVWl{Yt6+WiGCputXqSwI-Wmva#-1seF_d=;eUVG zEg!M@%e43FcmLm7RsNlc)2}U}KC?>V;`1q+nj015Q6vD3SWXx#q~_5Lv&+T02%%J& z8EHL#(K~!ZgK!8V*23Jldmd(s9vboOz19uQdH%Q|a+KtMqG&fK{biVj{~8NJ3t5*5 z?rW=g7=EF>V}yJECkn{01`Ub8O8i}%4_PGr7eFp@srTi;ipwRSY*uLG*vy~tYsP{_ zPa>Uy3^{$>+JW% z8Mv6irvU(7O+d}+Dl^Py@U_dD+*ntLao9#4l%m=+tBDw@SG-~qO|KzTL^x~skWpQQ z{RJ}4rVM9Ia*@#RTlg(V`^)cTV6s0CJw&qoW=)b_n&0x>g0xVyQHbn2D14$D0J%}M zMac%mT6rF~7CXG(M)>M+Q>UNNNXl|MQZP>ff1>zijtdgDH>~s;dHVx|OeIMc26a3=!TDgx_{bD@x`q#>h)Ff0QcWYuYa<`qcA&OD31o3%Zec z%(%nuq9q5Fk>`lFsPQY_K6t{0i7U5opS`MGIoyo#-INCCuy_Nc? zp==Er&m-f?24Plt_TdzmCD3>V{`WJOe?x}o(Z8?z@{7z0hS?)YAmu6NNMX6-wkcah zlDYUyR#xZ~mGq&Dx@K^jRQGT%J=BJhBQ|Gdf=*o>4IuAZ!-UkuW$g1c`&Dv*PSn51 zsJ3P*DZOx>-}rgTVZR971d|YdhRx$DRs2AB&K*Fr-fp&fa#qtu?#&iUqgA1u@yg71 z3eur_DoZb1>&KD+qi>388-=GS9Nx?eqOEmzR}@un>nb}y7RtJQ1Yy?#$KB!M1f~Q= zjoe}?GsAwZIDVd$@k=+XtmRsOP+J3wxTTS)KFfMxsnVw@P_&lC>kA|8RHBbkrVdx_ zPmA$Hg6M~EiW*t$Q`}zZt)L*IP7xV+;XhFx<4yiVncx3)Iw-%nxyyZLfs5qMh`hHf zPcf*v&0tH1_3*yGjt}iW&i8m*Zsg23FgrfX3ejJn4*RAd-P0w(@IvOzlbg`k8t2_2 z5r^-yeHfGc4DHw{DP2euIv%lSPN{RFt_E*8s}r|!`MEied=@_$(e-)FG8QoJ1tP&B z$aT>C9M>f4lSlaSeWNOO^c`3K{hfX%h5(oa!$I?W3u{HSs~j%nISY%8Q$)z;=$Q+T zySDO{7>Ld`=G948{!25+VKgsz$7!T5Oe1{lvhh*=U%BIcf2Jc3k8v-gj5Qa^rYBvZ ztwj5qh`H2>>+CFMc0H-_o-+<8+B%FV(xHW3GZJnAObqHHK38={N{)oan~m-VyMB;4 zyuMdQXMVGvIBe;K4&JI7i}g$v8I-0UMy%*}^Z_$`=D1suB|Nwxe=1@*q-NfRO^A z$V)+(s}PtUVwCaBhiqgLL~tNHqrj)Wl%$KocR#>h|w=%=??~WlGU05xA2Sj1zJ!xuMp`Me$gbO`2 zs`Iy~6og$5!5idVwLFc2!KYptp3o*Y1uApwoFG%ADvk;1&?_CoKWe`}NH04a^?YtP z>LNm6Nvx85FIA^WygEU)2p?&oXcuB`GA~ElwegW2tYY!QU%#LML|gpPD2TH4KA7dx zpMlx^E9NC4gUN&Gtr9ezNbfwZP_rnRu~XVVu)>mJaLAE^Z7{3fwJMJEFd)0a4Y60x zn*LCZt5Qvwf$95zeu3TYFS9Wo_X*$F^_*C(X~N7L=OE5ED@$FC33eO*wyB&&ap+*D z)YS2A*Rarzp0IYK)RU<$eE?AVBJizK@W&j7EdkWoe??aN=Qu<`<`@4$Q>L`0hUB`a zV{^oj7;n#gWmC+Bv8aqxC6V8n$3PyHoZqhNNpdiWjpytR(r@IDYK%LqN@OSIBH{oT zk@6uZ`>lW6iNUknzj&j1P8}K8U~oEFS6p?@en4&?3PB3^0?OH_N9MS$sC*cg|~|LuQI3KbEkg+IR2}V|2=s^ez#wc_P?c* ze|X(%`?ZDNN!n=d_Lmcvt)x#s-UM2F`KL5qCYET5=BehO%Fkjd%G8xvjamV6hL1j? z(*BYr(J(d{FFh9S$SgZ&Xw#T41{|o@aRwI3Pn_R+3sVS}mtHI3iF}GkSxn{>J(b_S zjXPnZ3$WnukC5ond)VG-EJ! z6+Z9l1H3UH6SgEQrf8BO-(=oPw@^;IePPQr+jy};rF!eUjgXfqrw*o30p!z?kY1ttd_%k+BKF1 ze**+6fkj!X^Fz*VpC|BM*}Cv-kie(3VCY%lP-MvBJUC97L6w^VmEfB3xMwjt{VuO| zdV2*u%a+}HPVgtnE(GKghT`#Oe}}jGDZiGn#Gd<`_U@u%8Ay9H$o8$Hc#ftO9+O@> zwW_uRqh@)xbRlzyP;|J$MDYf~#yl7yLc&_O{vhO+V(pjTuHo>t?QP1t%l9tjcgse< zu=gImTV6h6yLkl(zuLI3=(Tnhe}JlgJ0+NN{||d=hBMYK@IEmOX?c<2%4YK%2Aq$< zUQweeGojBpPKR3=gzHY>y9svSAJhu17s+VIeVUN;)!tXhQX~z@J$qf}(7Pl@3FWLS zi78&TxLHiHTAgd9U3PkzbBN=aEZ-!2Ab+(Rtb2*MIvkpg9%R(u?fFS?V=1FkBu^`G z%X>N?PkWYC+c6bl+Ciom6W?6b&)I9YUKlUJpdckyWa@!2r&t|?_o5yJ$ zxLc%;&~(aFe_iVnbsJmPz2D6>-X1b`kE}oUd1y$=*LM3W$M-bn48tv{);<={1Z1U{-5*~(7%1H?HffiX==;?|1y9l8vj+?sJ4XwrUctu0;a*Pf1N zd#GEZ6$$}vLGq;4aDytNj==y8E-a(dAIJNKFxyvN*@$o*qep*CLjJ4)&HwpH=wn-? z6ddOAYR}4urYG6x%ucZ7wCI<<$jV5tJTpm%l+5m_bx+3i?)0s7NmGmq*Ut^vYX69& zbYU1O9kL#_l+EwP!2-@rdEuT;<0p}yxKEvZ`6jGCX4jPlp{a3tG!^A$m}Qw|m?n!@ z?Ig#}H`p}di6`WBzmi+}BX;wFt>xT{WG0B?18dDf7>qq)(2tNY#*5OT&=w>R1KxSm0^@L3Do-xv0Kyx2} zs?j7>tqwQJhsUX&?9kSEQF8*HRT-{aqG)IQ7VAXAWhAPf_^oG4$Y9n*XFyJeVj-2n zjJY;hpZ<9h7ZcK*m2OK^9E4hYcej$UQNxeMFOP2Ux0Z(L+IZiE)LlY`k^%>nS?L|t z%m;noi+xabKE2ME$wBj>Gn2)K-7mnm=hA}TkqD`W!N}H7m7M+4t@dQ}Kx*O%7raN6 zjWGN^Dq$o8(mvCyc)IkY>N%gg+wri|1DrLCKFxh=;{NAkyiS4PF_SW%Sc2b2Hva=e z*xwb)=sfps-Yy9df3l4mqoB~8WYsly)?6MoU~+1jIxOMWYZL2#C4r=02t$k%sm!0$ z$V!G)m8x1r>aFByVKFD-5hoyr56ub6wA;7)$Rf&K$6~vQ->PN&l;ldNF*Knb)QFV+ zy6P)7E}IDhIwzF&S2t+MW{9(Dl@QzdUa6U*@aq3|xltZEFBT(kqkFZFB3Vebi^;Lb zfEa0B=m@+tZb|8GK@sP$6+cew5DLL=$E%mCU*1t(ZwbV17f7Qk!ccqi2m zlpbW?cPnN7Bw8irv%swO*+5ttkbu4K#FPLaV?x5ni4;YA$&8u&3o3GTwS2URF5kH% z)TXkI{Ohz6QYYDzi{EkdCSCUnZ)Ez6NN+Q}s`)t|Rw2%=F|g+TS%g{8u8=CRe1XQX zga(&*$wC3h#04+58OWDgZB|hv(pFp1t!`R70sd-5EChpQgB3uLp3_HRvxq%gdWU+a zYG1N9$$j87t|02IKbjh$Zp9nlj(glk(6D>JQGPLMqW*WCtNyN&?y)V!b2L`g#H~%& z-l;4F4jb|rbmYBZp|e7Ck8Z@*XymTaDcyE}o+32JV%OJ9)noZ^)Z84A@)6&`jCh%0 z(FvPApFjHt$D}00j(XY%F%skPoeoSiC+|M|P>s>x=GJ|flWR&(#VV0pXA>1%R@g7m zYm!Xb>*4dq=hv@BtQ*W1QhL}qhQnW`&OI>%4xYw{2L^X1&wF%p$O6j)JY>2bohvft zO#$!7;`>vH^K>M}zmv{%^Mt$)aJhfdZ$)E~WS<9J6-};L-nqsJ;LeI1C!r`8bNnV) zX#vz*HKj7=YuVr2*D^_hS;jj$awF1|Vr0o}g7m~GLWx|6fm?B{WV z9BM)=bakyvurEbyae~C|A;oi$we$Qh$YJ5RL#{B)Y3`m<75_x3pZO=A{9nck$(Fyk zmAe}uU%zul88;MYF}-=E_0l=a5_Qgiw=8*f42PjkGk3}pOOqvObkxB$h)Q?%83i@M zLC~)2=xUx|76^2s>+TQoHL&LC88KiN@w;#cS=% z_G-8fhCHSee7mi7G^&g*abqU9yu|J!E13Bd@E@bNOeB1dhORkT&G6NPY>0LF)l^9P zzAALKypf|d;JDGfR?0@uZs_K$R{MoXs(`pt0$74WRv1}6yCvf&+ij~=9`Aypt72{7YTmIhV&VToLcy+N^ zr*UqoCTQwpn}YjB`=q)QV?hGPy5?s1J1fYP)LUUKe*W_XEOHjc>E?nX4k~0<~CP z6sm#V7%j03hWKf$N4meBW3t&xa7XlGxwWdIlk4fR2mTNzL>!H))fiKB2_iQ)e}mkB z(UV8{E<@ogtGU|=+C3or|8s(i1g*iV*{==|CZkd1ND*LS3k zG^e4W9>k~j#e5t{ABm+FkIWVBeSY`v*2}JVzQ3qTU@7W~;s`;w^bpY97sY0rWs0nR zT(v(H9upj4QK=N1$Bm=U9MzXj#xgD@pW?=SpFOSTU^-b^^~67GVOjx-`{bM7l;3W! zhKamqTJrk=${Z2A+E2mGFS=5rRCS9V{5XCsBO^H|OU}ZgJMW@nPh(vA5D7iGI7P!Z zaoOxS&(G^Xunz^!&h2&?s)Qa#syWh6I}KV`&S-Ii)%%IE!Da+d<5V7D^@p@@^tS)D z8RPGoX8x{|?r-$&4}GejJqT#q>;aOg#XcBMUB2Nlcs2FpLMseNQ}H&(yuLQ*OO2pB zLaDvqPQvZo6a3a!`NDp0qB=Tk`RW3$HyiX)(3X>yu*G#;)3wz{)e>2TRq<9h&Ju{sxrC}j?I%=Fsq5vjsP-Tb~<5th}ibu|+XgZ?d^W}iB>@94`#g6_BrQGV0}K^ZqH$Rpz2x52{nS+$y&R~x<&5y44OylQH-b^BFoVqLn} z1=FVAwsGjY4+g^zlokE^by5kcYbS$RGbs?XIh(R&J4qws6=mSw{1`T=-T}s$E+I3Q zJS@q$NALcmVdww(dg<@VX8$2ha;Tod%b3NP`jj`i=3a+;mC7AIOCi*!(rhg>U@2FG zXKFE57gTxzY)J!gQ^`z^*X7Pg6__0wbo3M8(H;|-#AQ6!QzHTGk-5BxA}5GHzhB5N zT-C^Ub!J`*pwe+-Iy?XJLCH+Ypp$lp`htCP-Xq#$XNUTLG$1h~J`oyI^o392_qq0g zd{b?4XkmE{+bDi0WSY5=nWC(|R>atyu@)37m1t_2J=kXSF@SR;Lp?oM64Qmb(aK%M zbg{C(FS2j&efC^OUjv|Qdq!BOA(TzRmety)zWiL7aXGc^98516H_e;&>S3JRg2ZG^I@Uvq6 zQY3u1<-&Sb2MYl>!*sJJQXM71s#&Q1Oql*Q`+@nU2kmY*ACZ>(M`lN;0`{(4Wyh7Zl0(BC>FBnlgQO-C#^Ee^;X_w&Z*%$u4-3aQ6-4vGR+;jKvO8kPG zw;Z?7>|#A?+VglqOsHiGxmLcf3-)^d4Ih(t44c*t`so5yP9%Pt?V;<=`9Nez8AHtt zL)`|t%6*9$-fM^^B1U;Bg4DdHnf@F03NQTy1;+cv=6+Cyd9#ND{YP~!f=i-S%ss8l_7EJc%Os^=e zBBD6ZY;rDw6XEx39@te*VF=;?Kup$E$E?7nJSCjjxd%Y@gv5TUhv~H}-^odViB^;@$6)nSfK|U>J`7amtZ{4^-=ne#@M0WtxS#WvhcD{D0*lkFKPaML*{XKF zR8zYkPOTo|A6D_Y_ifdVuyuT-TInLUo!QU`Z6WyUkh+GypyNjpvM=I+4u=)CQL9M( z7mFbGmyu@UB_5eMo*Kixgr$ky^$UeBzsvnv7H*|A_n6$sA ze)X3Ccrx^LB54c4A1HSPG~qpl?O0-!`V*zU(Jyqc!AMeK*sf1NS9K-l9ouH`8#;e> z!Xzc%p-{MHF3@ZDU{lm4amZoTgM?9x>!Z=F{bWA@X-6>Ij|UTrOo}3x@MLQIb+SG? zwVxOE$RlD!%RQ@a~>L2Cy{2LK;Wg|!@jf9tT*n8dwOFZd;O%z!# zB3k&Vo~%bTs;*)8LvHh{I8Fmi$pqDVtm9SpJmVRdB9BDgxMhN$NHXpq*Z7RS7>p9C zlK4ctk+R$?fjLp&c9|s0hz2CX&;%(hO^Uklm#g(pN7Tm#yk>1PnsFqu>&r7b*%?H| z_0idfRBa^=Irw7?al+^ae6_oI-CCp(&tquAqI5Kn#Z)XPa@xluZ|M^X$VWxjER+5A zIq1xan!D{j{&8CosT(bYYH$>z;GelOm>n?i(kkV*2@OXHw9|3K}nZeX|GE-)lV< z*wkASD`s*@J6?aSQWoe4r$^*WL)$-U97EmuSu-)iA0c}2@Dp2V0(ufOo67kai(0jx zfZZ7~3X}1&EfVAe`LKebu)1HvTRoC#S-nVDHxiW5hPYBL9qwm&R-SEG&oSxBEVG0F zcu(!~o^C&~er#Ph&47`!m>G&0GjPuA7no_^kRvXzYu-l+EKp&=n&J0UI*P;}>Q@$If z*r}yBp^A>d3?$$Rf|@@&fA!a5M^p6Ew1=U#L5_us4h2s8i| z3V`J;Ge8tfi9WYlixm56y^VhT_2XHrS)96}j)k#|AAb$zTW7hr9q;98>*m!U>BgMX zP)@Rmm}4gvOf8o7FZngji%PFuQlHeFuNP`$#N^jqxa&sAMAZ6o2^Hoq`PYxvc`lA? zj&dZwG-NAsdFWeD#bQ0pHrS&bU!VY!Mt8)i8ITK>76G<;k?}_fB`7lp(s$U9S}LQ(Ds;rFWUu%N&cm#ZB$X)(d7D6@9?E5|Dok8y9F z!L!01U^2~XOAKr}GQL%V>CN*NJXZUZPD75vgm~5G`4K)#iuH{X$DgT0Sd||y;jecM zzo);tG1V*tdE3^^7M~Txm~hMV=`wAaWbRcS?V57uU7aoj$BmYfrN9YDfs%3x8#CX{ zk5|xHq!-Cu&0oGFDXr_SnNhR1#*c^&%U;@@>Ny%9(c>8LxJ|(+zQCDdUujebVpfaj z=?M-&sxUul2|gp>PX~~~CaSCMu&GZrPlyG)mV6#Eu=?T0Kk_x$zxau=Qsrn9WoG%v z@g^EChE+$spWan|)hRO{0EN+_A$7Y}zD}W`kH1+?>dolODexB52TVIC zuK^|oKyt?j?2qwMNs*Au0|Z+Fm|;y-M9{10YtY$;luzb^EhL&dMfewUwH~ADvN?V{ z{IPrC?b*uQwvY@pmqEUh=n1Gx0}VdBq)vgbl0fk|m=B4=b8KL>!3T1GvUgj!_S9|( z51rLB)ZLpUGb?Tle(Tl(+_eQK0yIJwn!_QYEYwZirPC@oLV+<~pACkX|7P)&U$|h! zKZ6D+;>c@sD(-&^?bcy+jEob&qy&I8%ecFZsm6P^++L3{DcmWFyA?e~qJEM5Lk~jh z;PN^zp*RkRXWqWh^>bzNk^}N#OzTf_l8l4Y1?{o|=wmpa&j7X~+I`?lbxiie>Tp8D zka(B=ENpJwsCr^o7%kkgW=x-`bf{Lp?$wYsD`&{@8-dc2@1x<1GG7FE{p53ANL%JW zOJ>#FM8Lx#=ykd0A)%90(9)s2xGqP-uG*G|@`Qq%Wvq=JyZpppt8VweNyt?sxcZ$- zEKc3=c1qgI5OovOKDyRZz2G?KF^X*U=N0nYNOxih7d}z>NGR^-tT3Z$ZTj}SBkqMj z(jLf$NaG9rEryk!>h!;VYMvSfk7FxK42`wqu*wWmX5DOaZ+xlZ}Nl-aAxsDKpgdl8(Duqrt$tFt{mBs~)UELG3H~^DWyZ)zQx!NG7;Z>gc z2iTFin~K7!&C_+fl%kbvKwU8hFC|x%kO;Ce#zWmy4HBB9uv!{bvg8EJ*M8IlHPIFwRM8_GGHo~5}sXpk? zTljvtr5zHd=9N#tH0mmGJCJz1J%b&%nCRL-=S(YFxnaE3X#X zn%yIHgKI!c$wgC<#Jp0G9H(_&VkqL2@MDac&O;5>9E`5>tB6@jbDzojuC2g2-lgsl zzS*h;5Wv+wwX|Z#`<;GRT#cCJT2)+&CgTdtR4M0tEb*A*$nGGQM1`YDFziwBxPJ5D zkMw7!3QNmPOd3;wWpfEpPYHf&(i=meCi7B0M;+W?#-+Z%%T32`#jd_RtNS8elK#A; zL~X5`Ax?LEBZkz^?z$E}-8|o>+0Dwk_uC%Tzj>A1hI-BD!jtN9w}5S*Lt9>TNwDB; z$`U^Zhb^9^;c?r?-lNv*L^oTAa^5PNSADzj?rxUHQIjKh`HIc|y(>&uXUtit?nCJ) zE#o>}`V)DD&L)p?11L6M(P-3w4#zyJfkwZ=5L6f^Il7$vV0CEau*!I=iv{bAKU2)S zkd*5j>y6?5ZD%Oyv(0V?EfSYCWWRyZFT|kTPVvxxF znPH)+OGBtX{U|+0d!7-Ga0y#Ef4=0dl22uu16(WT0wfQAVZ8p8w|R1?ZGzuXNdQ_% z$>+$gWCF+RZf7kNd30;9eu|aqku`H=Hv}%HY1yQ~Cl| ze|I==QKz$S&S|ry-mG2QyWCKrx?qYi>#cjho3rZL&QPcJ+OW_Pn+sh4qD1pBX4@Qh z_j?nj;I^&Zq~c-RsuypH7XLRlh}U^|+AOToTG?VRm6mAYZU(7yW?55O;#O5V?=dQH z+u}MAuU(9D%gJ@Er7JP;(VYxqpjOxL(Y(;>2I-W}yu@v#sr2a(>p1zeNBMQJbq4L0 z17@bCB~v5|5laTDbCo4z9JB|WZZ3sXKa#4{hx-?TWqW&DxQB^w&HhbTAxl;ILSwQe zW&yQ{!|~iv(XgpX(%E9IM^wEt95+(&8YN$Op_2@nz=gpe(_)Frm3F(VnZ7EumF_QQ zAl-882J2H0gmKM`m2(w$Ghi$WSM;FbwMdurJW=VPVuZCIB@6@prN7=S5U1L7o(gQ| zMWo>vlEN;{w|@m&7CU<>t02{>q&rpu39YBQ|B!Mn9i8r(;klP37kzNgV5WsjO@KYl^C09Q+U`F`9wa&o}+Me0$4SuC@l(kLGIJu5#ttiY@ z6~0&sEmS+3I5?+}j7qvTpu=DKCKrfzmg>@SNZL?iSK#C=HuV86QtFYfrdi*?RBygN zGHgn@ba(-JpJ{F9cmdjR@`LTOG(q>0&rGDpO9?70Mcrd4&pY0d~8b3f+sE)PWG8<&sfHanMvt^dC^fPAM)p zM^Sh25Rv%gXLBz_;)>RmJSoDD>JZ|ltcCML>l=>*hm1&eA z7`;_9iyzd}sQsvFDWx8yh!45OV zIr9Rljfs6pNqtVUQLbz-Y|#-90>{@jQlfN2oQo|rl>4C;Idn-k19Hv0baKvt`kDuE zi?*QpS5UbU4ojA)U_G`+bW1A5RrZG|rrDS75n**i>vL>1#V)LgSN5&2yxHQQF-~^l za#)#`#q&pYl^VOmY-#y3xECANR>b3)neZ9Ld5M7z#t(};RzVK4TGVXsuldr=@{%ec z7B~JwafhEK&RKV?znwp{x^Y%jM6O8YJWue}LMaHWrIOrInM{N=ohQ_-%uL^6jU=+b zL$;n#jXCox3I%OlCew%vYnYrJ94)YNSuE95U*39`frT7{VVoRE%;HcUrp<3!uT?k* z8y?X0-=$J*L|-|6Cx)6rHbr(fW#gY9q&R$&sB2r7>ooG1(JlulrTWLyUwv4_7(RCbt#mm@|TCZukr*D(i8v&WT zx&L;*>4B5zSguP#WX3m-urK*~IkcSfG==9dhrzum*HKm5s@;v-6V2z02W686c{By3 zR8vWGHqv_yLZ>jHbA)U8aNopf?aJBQ=2s=WSj$G$9Gs3OTpm7LCgPZ|#(3d}Yt%1| z@3=*^N+xv@aq8{~?JA;In?H9(N;+lHFoKemm8xb>DSSH{c$0W*%a<9MONC5W5`ZuAw48BOH9v|g_w%yEW&mNh+V*LT)m5ue!e| z+&(kgg{6Md>33|wqXPp6rnaX|CsQg5ieIeBN;}0`3~3MQU5KSXfS+Z32{t^RF0Zo1 zOsN*R1?U%%jlU>gXv^d06ym;UJtxi#*t#r6by2A97jasY)0sF}x2zwvSAVX;M?P-z zAvR2jO}xtc`CIpI?4?1L$CB*4#;RckGj9z1rag)3U1rYZlN6%JySl@x+IeQs67tiY zA(9LXB@m_7q`c7nCG`k4E8d_UkcD6N_aw<~N`xeag8$fGiBD8LkDWw)$Fn(U!8k=Z zuTXSwojcmc9tV5nTC<*l{Q!c`JjS!T-_$;M0u^_AO&^Zw5aLOytI|;>;&hbYpWs?e zDxLX3Q_3b=RW|FX%assR^pk9{-MZNaO0eD;1TJR`kIUqm;YF&}vN*GgHJuo-L`IpO z@#{b!wtd%`oaC0uH>?y0BsKbt{({Qc>Ahs`hP7O)N-d)+3USM(36UHR`xn~%k;=PD zNCg%@y#^C&2tT=#-px`Xiu4&;Dq@fukmPKlYLa6)Hhw%sOrTgw4lA39cHCmE!|rf6 zZ%LI*3yx}5CWG*vNt`vJ`PInu7j=xKIBu#&v=6|olqz=>lV6vgNoClACfKt}o}3GM zIGsrqQ$3TZ8J^jXo)o6?An-h(@Ke0%xXw2eUwiZ9q?>ck1)}FDU>^TKBJ;ei9G`#d zit1gJTe6z=($MsNpS%v=0`VxY$k8DJQju0V7w_Ew5XLau(rhF%nGW+F+AhjQuLdt7 znwo2AUonXi<*~!{JbY;EtPr}8(xACX`Pa2+Zz5klthTE2iP|p>WQxfuuJa@~g;dqx zF5@L_E7XNLIa8JdBGHsVVy}SKvT)Hy!#7P9bH%ky0lg3ctu_i>ZN>wkS@PN}*;0pF z)4VGpaJe?@E9e}wWhrn8N+gxYTGX3YnE8Ghx}_d&MDr;1bXwUlCpE0MClQ*gZZxPo zzr<7rfZheVy2+6bb4m{i^;Z-&DDZRW0X|M$Ffs?;!^ww z7XB+S`QQ2x%{{9^%_@;H8SP>_g5jOzKKYhQ$G(;ii()xYY!db4uXi?!bG70y*?zHvdkQuU(I78?hXjh>xa zCn>$m%8VX>t6U-+Ua+@WhYx^&Lc$eyfx8R3T%#OEG!Kb)7WNV&T8w@jDQ0PRPjRQM z2NQ)>dMmb`jxIJjTZFC7n~GfbaywmYJ^MK-R<(md?HeltR9^HkOXhBZ5&>MHp&?tW z4XRD1okF_S&o7eB_ued7=nwCQBjgsM#0*|4ol#FAw-y>`KdYDj#v$DoHt9r4=)}WNWsYoF*A>`K6xRe~)%CFz(AM)K#6lUd%c)|Qk?{u+I zc*!6Q^w1*BWA~d6|4`}$b$3&}|NDfv7^JvkV=3tsi`jni56q@kcwI_~Qq#*gu zXtytH{1wwF9^!Mh2RIYDLXNhFSGdoV9k*Pwm*UL~MZbon=d>8tq?*EGw#Il|g*olv z@oVl_&iv@0dC7A$1Owa)vf)>--_oVz#;#2cOsjkvaX zS1&kAiAye=kAJ;N)_`c$v*?ZSiMr;k&T$7R-Z2%b$_YkC+FdyxcTwg^aI3quUxN>* zlW0dYg?kVBEo}`RLe+WGZrIkii4!!MPM_ve^uJZIsR8HKgS@YCmFv4>|POjh&Q zitLJimnf5C#o93i)9+DSV|0}uvSXI^Y?7hH^pLu%Wn+LQw)w;+dUUs zJx!Ky+rSql?-*G0#}8(OPN)>sy8#OEFv#&CGz>c`2Pt`TljyK9h`EBz-#<@F++(*^82^8g)@pTE3>n{ z0TZv31EPoS2!dt<$@lZ7W+;dMv|>JUOn^JxSG821e^; z8544Q)LDz7D6UwqATTFDYIvpgX4;q85+&V6;ECx(r<+2-_9dsC#1Qej+2{d)0bnJ~ zaEoGm16;>(U$@q^W~tULxf^oOv{6&mGf!rGMnv@br> zlX6y!EzJ_wmty}P94PkN*iJg@Q z0E+wIc-vCsb^Ge`iZ71@VXil0FSSJ&&Ph?X_?3R5cu4P|`?YqWh-~gGf0Ma2`W`=H zgr2e}e7i$aLXCfegYy5{_|s#Bx-DZ}`gD-?$yTjpvrZbK(=52O%I(=hoK;574WbK1 zYK!WurhpRCvMq+bN4_~9hKx7-_}>eYw@jO~hQ-#LY)M<&ro3}!PG$*msG&_dwSxdv5?=j}-*#pX2JX$v z%gMB|l6JR$8yuT!dT1Xn&l#Iz2|HK0LOw zhZjoj-R*(2UQh5Xel5GP(>(#H6g?ODWv&Y}(+68j$tUj=F@ z)2FkAGsAXi1bgw&e<8?M{6_=vtE&p0eBqTt;YcjMvTkL_=lQeC0pegM^~FIwIG-u~ zl6!Z?Jf^r%m}_Mt++5gLdp=h1x=0G%)u^%)+Z@E6&WEQKZX5otqH)?w(|7^6D;i$7 zX3QR|1(xK$Y~z|nTeuETJb7bEuRHJtLYf>R(v&ma|LwEi8?5Bs9=>Py_Wz^4{@4G0 zQ0Tz);A8r2+{lRL9$K?g6l`R_gm;rLU+t(5u*$J5&Ig`4Q-w{9zlK8*1ec>*DuomR z3SWm2s1T7ss9{U|E3XtpxMswY?hJ{(8?iG-=V{pSo1l}_jLvFs&N@ccq0A)O z;EUprbw)7)S>7Ll!$E5C?IGxm#qR3ysSpk)#4x{wG@iaHD_etIYua>B8EkiYeFA72 zs|GVA0s?WPNxO#}pj(|0RLj50eH41jw=bC2FkZRD+HHCZ)!OJ~GQ>oi80LN*(~4ks zQ%GUwt3_eFhr+eaA-XK{$4{GQ#l@%i$4&(fw#?CSee3Hzkz4Po*{o0JOA@3)Y|5nd!dzOZ6STbe>?&d+8 z2Nsr#$sHH+xI2SEES|-BI7jKn57OI|jBRYT)+qWTH%`WhIxy%9u@2M-XJ`XB#nnWA z>G%WBdO@Bz#UdAb`N6qojiKc>{;d0F9Js+>9g`N~UKDGUWT?0e_PhVc0n$Zk42F>A zwO59`FVO$+MMSUIg{qq|bx=2xdFRk*LtZ~xkIE8z^pSB)%8t~SLn*EYU&K)uI3nCe ziyG0-pohV*^ZpA?tL;Neo-;kOK$wdD)^lhJ50Ki%@iXwAvQzXxy2P_fDqU`Dw#10lD&(5O+W;RyKrBOFE2}Kb+Y9~^*TG8=<;q8aeQBL((io(YcYiq~x6G9z;IShmlD z2KTH|qtrRb=9wa($$fA_{hWo!(bwG3Sb}y%Y0r=XgY6+GRbqk7l@}IBFNeZX=WBs` z)QdlkGFXT_th3^?ozC72l8lIyCcuddb;dH7Osc-+^AVuCzkN=CG4?tQ#N|}P>duF~ zo|74vj;WXe7G8?{7+pEnsLM!=0B625%w!yjP0E|fIJQnyLEJ^_Xz1~`0BvHckzg%T z2JRY<{0_4rb*@Ki>8NAwNi%JpobRs$;nby1*}`&+rF37;D)jb~ZJH!QGus7Hg*_Da$e*NI>lw1zYc&oGox?Z_$r>t~q%poRM{&*BHZRV`nO-F~f4 zKzd~>pYfkRm`bm_7N#mJ&Tf+L-LP9&$`6rXC5pV_pf~fW9>qfWVM1+HWeT{bFVuGmC#%HOnzO@p4&^5cO3L24snODdj;rrWjTce;OMV(iz!gZq1-2S z0~9T_J>RcSwl(C=?YrjP7~F#< z1PJbK!QEXGAlTqCz@Wi(a3_#=wszmG=Q*|ep4!@T&hK~LI{jBy%}n3j*K}X^-Ishn zPD^A`H*a=qtGhCehpEX-I}DHB@Ie!GeOA#0O=hS>|s?1lH>@rq$%`R@l~933n|F95~h|-B+3G)PiMk9Gz&4 zZga@J--8rhi@-^5B<~pZhC7pH6|FrP1?Q>6YSdJ8tzEFK_l>1Zvh4-}I`6q%=@n7+ z`IgeHV{nWLwO6S}av{$*&v{98us)sKTY<+QYTxlX8n=?{h?K83Erz(g_#g%{)7Da6 zW_sY6e%U#_q9?``ahV(jQO(rzTd7B+{G3UKlB79Oi%yU-xwe01{p|)8P^qbSSS8g1 z|GSh1dF2=@rkpPBj~`*qQ?$2ZD|CUxX%k`RNWKyVIh=ZqAJ2enu60*ABS+qXKz9C2 z`f=k*O$sz$*GN7v|Gs|5^K+cOCiP80_p;xXyW&)kXIDWnp5kT2aBD>6?u(-ZKK`-H z5a6TSW57I~20xx|WzrR8fkZVTo7b;l(Bc$tR{$iZC=YSlBoWODPy2MWr>!*JP%1eE z8Z)i00vIw)vo{uAeV(F`NpbIhMqT&WC1unpx9QI$V|iqE7+YGcCBc3N37;ZFuKtQ3 ze(w5v_BCqOWUyK1A-q^_yv+%-<0&nwd<#6%j4rd|l3859}l4p(_=`}kJM{;;g zN0T(zMmS_N+ASH(#XG_p+?8ZLIDV$?-r;A@FAAgp*xy1P z3}!mTW*UF)a(cjRtZF(JAf4M3S(Ogl{H~sI{)Lftp+ix<4)BJm`+>**;#?o|i+o zXyW#-QXMk-X%Om94HvpbRRfZvtq2YHvY_pX7lg;ck4~0AAyiASC&tJ|=!XS{*vE=e zR`RJ??#}%a;9Luw>pB&jU3iX#t$Mc+HLr>D1VtG)nlK<+HXP7P4F4KPUXh|wQb@>c z8~2r=J)A)F)iu((r}4Ffo<^m>utHhcfXB|)R#86pc=@a({gHtwII*0CtHEnBtQ8T@ zbo5kpvbUz#Uk>nF$KPA*GHZjfeznv)9!gF1XWlr#^P1jA@FLra7aNjf>Q;tH$ zKs$XOr$17v%?=w@6vaCq2=GME)eoA|L*%%B2)MuGzy37APBdtYW)fSDa4I4ann&5H zS`|N-^(D8Oa?L)low_Irdb!j>D=PD+ga>q{t0_x1zDawBe7Iw=e%&*sap{0Jw^cRU z*kPdR=I=6rIkzw|$$G!hq3u+Apnv`ONKvjuaHwo3lO`d7fLQij@XnMg=6JrWqRz|{ zDyA)RHsvf}%*YL$!mo=^-h#PVASSGwuocSk`7A!FTKb`*ui6BAwRH| zCBKy9Uy-8H51Q@Cy8-+6DqX>5vUBA7kB=Z95?R;-mEOaqm`S^vp9_je5EDln}74KFT820pwYcWeL&H^GWl{W+_A@#yzLIRL7RLL}Z{zwNUrh0RhXFsji1G zP8>nRtfihFvBH+<1=&z-M1)lWYGPk50q;|Pt&uZyIc+c*Yd7dB$vDS;SG+#{ zb?~vvHbsCUPr!{%$WtaDF|EJCy!WO^++ypXUuBmikDQ>Fx!$ob@OOBFW@(ukpGI}ja=-#XwyGos@U8GcW5%-JdbWO%&xl>dV@E4QA? zNM$Xr8Jxm9k{N|wrFJd0+vE6C>Forszg?_4^tkZgtFI((nVMh~z@w4YjpC5#Rp9Zn z(hCj(;gSz*=vV@aQ(%2Ld8fnU6TFbvmnk^L8o!rOEuqd>&# z=9P_i2~dBX!Csf*Xxidg9|1Lr(3>Yfdlpx6Sc+`}n&56J)gpTW$J7NQilUUwIdSMX z&(oVX-TsN%en*F%8<0i&am*cc7gfD&7tO=pa-5vs&1(3nni$En1{FL8{XB z`Gzt=l^JCQ&t`_zG&7NL4kUnlmeK_@Df!uRjlgXxO)Dd%p99zBDfr~}rI@LJ5=H`G zARN=jJlGNsxfL9(0!>VTXEQPdx+7Ky(#$X5f3wI2KT*Sun}g04$WY!|tC?O?qcBna z9YA-b%sN(m%~oIdVsL6-#aAl(VT$i7sKl1`?F^H+9RLNwQVhO*@77)e%Lt7Ncfl@m zbZ5cEI=Ze19=y6Xu3Y?i{Sj^gy)qQ8aj>}#Ww!C5V0>A0i2Cpe5NZ~lucbq$r7t_H zO`j`c+<)^Gp~36Fgb3T|p&-{iW}o|ht`bmL^u>y=wVy-1O=}r*81^I^(UACVo@;kE^4l(vHK)9 z)~Tdw#itbRuytrSUf@gPc0Je?T}NSTX}Wa(agD}LF~4E%nCeaR3Jp}kjhN&6-`oZv zJl1BH%Sl1c;CMA`8E~rv4`&7Adjyw%EbGP5)uyOitp_bnp82~c2Vz0MKm`Gd4& zTxxnsj3QlgTOf5%j-V9G)33PStLmp%RzOSD$`3s2T-fT{$5mD`D1D+g-W-#Y-<|FX z4Nqk4ijxN&3B^rtRhV%5aG7V{#5!Mwn21Y3t#Vr?eEYTby2|vc-}wU@hgI}|bvVel zuzVH~_x4uFXG9F+=s{FBe|-Z%k!@~*=bRR|q!ul`wIhtS2{5_9y`E5u>--@hvf@$e z(XlX0%v4eRJ$_h~q!wUIpOB!=T)iSe9D&Ecgyr@38Kn9?t2(^!G5M!ogBR!5HN)i1 z(C8#9sF&<7_+}V7zjZ^)A+KZk!tmGld86S}K@M$kmrX0)xBton_wWDlzns&be}z@9 z4B0z;?g_TRHWe>eBB{5A5|9gf!bj0B4V%HAWrZtRjV*tDp>|0mh7EAVV!eN#ahS(+ zx_BRs&8WS{kf5Qx_!AtgbsnZk4$tNKVgX%pqhJ?ykFo+N^p7inQ-ub%5KUxvAzkuE zIcf8_SLNfgAZ-09-(z7ryZs^oti}*~M&S1gtu&^_Vt!e|64HB3jVfzN?Mwk3o%2LK z^$oKxvzS1tCM&xqLjhm9MUo6h0&3^{;YOK~ap(AV9}a06kMrlm z%*#y<9rUaD4u?&=_X+DA_bxwsz^!E2&L^7-@!Nz54eD)vbZ>Eij*$M)xkRKKH;cTj#`xueWU+z~(j2OOM& zqid$N{e0N2h1#ZTiH-kODcV(2?E)zF$;uqWdCcw1W?7d~g=d|>S(Bi|{A<9qScfxA z;>QmxyMI9>{(p1Nhr?T6|KLw#idvi?R z`9uAY-zFVe3FAqt?eV>9_35smrq-!fpJnXYXm&TLs9ad!s)rWl9dQY!2Bo-80ZD}= zjlQ*w1Y5ou!V<8&7^9>zF{LkX@P9Qe$B}LuZ?-R9cVJWsJ7f|VH)vHyS+-_Si`d6s zINcOH-8}#G+{kT=($eI^c43wOt7AFMbU=K-KBDg0h-v$9fuF-zQ0v7qkO8ayAPshE zNqo9{ZiZqrS}uBFbe0M8eX-l=8(dI6bxxRx4{!EbC5@GV3wJq09@6K?8T4?T$Oce1 z$RvAidvr#;=!wlm`tLZp3;8i<>~+u~=W4F&|A4gp)gFj_*2mZft^FDpBKU|fj)^LQ zs*8lAE4K7ZIbdqig9PniOY}uURobzB5fKo~Zrxd4$HzZ1kf5e+1Usm&$JDQ`OQJ#N zaCa{DbHW=K;0cQM8i**@*?;5ufk-?w%5T@rE!o41$sa%1x+34F(hkH1E;HU&|5imGv z(%;*5EFF_p76`z#v|j4)6oXTLSnN`gBXyenGv011Ri??^IoDPUH|!a$L5*|F{1)jR z{uAg9Rc9yfCmE^nJu76iG)6=Y@nqr#d+D4H=~;ZZW);HF&AUKz9pl|z5= z`yI3PtlFc=p0DIdN1UhlrT1E9;t7_(Urd0sc98r6VU{<^9;YH-AfdYJhZ@tjh4kPob!QO=jl>3HpKkOQJX>oqLgo5yFLQ+N}&}> z2ONH$RUg~XUR4y{t6LUkCev7w){16{UWM zxW&qnY)w+UK!6pD~pKjW7}uB7c}O1_28f?bH%Bi zjyQM>(U1D%P~Nt~r|=kEQuE6By8<}%g+_PXl6!R0v1nNdggLE3nXfFn+~)MQjHyly zZ1ZxQn`(76{9r7%>^h)PUe|3|cnRBh#dcV^Vyc7UKtpNCUeg(Em}xYtbYXnP0))Yu zRGaUk_43Tm;?_?PJ)nMAKv8F2hxd&nPi6fGd0AnEVk)DCj<&dx%#2FNxC$77I_6p* z!nlOSV(h9vu;4kylUHs>zt)*n;4sQg5+-MCTM|rzu;QR7%jI#h^`y_91J4KpLa{$@ z-3~}g|3KWe|JV%}Cex5Pub;ci_$JJu=HAAh-hJ|6L$N3A!(F7Os?j1iJ=K@N!wa?5 z!P>qvBKf;M|M@Qaz!GOfUDv+dR7VT4{o9jAYNhwkmH7NE&)>n%=@vzRw!Zvz5nr1J zOOoP7p~Ycs{FDue^ZfD*T*(G3e2>+l;i(L2$_zq=Z-gcOF<_8?3e8&4|FryybN{ir z2lJ=aQKD&5U4^c6Y2{1ttG|%!5Po1P9wRN*HjJk`OV|?6O|Oc)so%p+%&I$>M*bV) z`fn93l-A9ht0UjU)m#TF6j1)JfAlP0q`}EY79j!S(|-TzVk|jC2WZ~@v&T(&1iqew z;im$Qrd5mGZV~)$AAz%E`Pw_|XLL_}^$I}KQqJ{vE7NN;7c28}Xe~W+yX)^fnEcw_e$-XD*F9EE9i7f0mHRZQ zUtGUrun)E-+(abP(e0~B4&OXo;h}Pp4E8&OY?`)7?>_Tn&_q^g3Hh30Z;pPw(&6ba zX*>18pvf*mb&20G{tbfD^@2s=+h=C{viu0<)R%~43PKJTA#{&qV?0vs)!n;zEv5q@ zJ?P+0rk^QJ%*1^pJAvyzq_uTmN&&qzqCHKj<4QF3*I3*Lt`qia%(7E5gA!To=FH=i z{GA`-m%?i83`WY2GILEd%ov&olM%65)q3G(SaWBqVfs9O)X$&P`4;Wy=0=F3B5CNa z7`Rtav53b>d1;G0y)xDh>48JFw&EUn2lVQWf~Bi3nc=hMuvuG<^7?De&$lfSsj*6f zIgyLp1WSJX0r~4nTfPwmX=UMow8ZBYZzpiv-=7?vC#_TG%nT^uO7v-0LHxrGA}vC<>OSUk)1Pz{M^z}>p{#b{m_Q2Iy7R|4JVUJp`^8f~r9 zSJmka&~&hVyHO{dj_HtUX_q`u;R7f80p9iMx8mm93Mi%IP|<0O1xo|>ZRO*1vP`jd zlrwIu|J6f`?7YVao0NiJa&oHi<#~F(1Z=|o<07?p#P6%I>}L`d2f(8RP%S5)pma&( zb8I)ix2%=x7T>JYaIplgQnaEu4DVUQ+bHS}NZo8l#{fCSJDz1mD+Vz%GngMs6zGWr z`+_8JjxT6K#$-g?EH!4a;>DNxt z+s2s2O!F-(_2;Io4YpG@#_y*_>m68iZ_hbS;l%5JR?`=bG7xEEarVJ)A{QFE`IWx; zO%qo;Cx+mn9MVL|I^)c5&0RAO0Jq|)9Mj7#*`>z{>t^7mQOZ@93Db!=00uIWGbo-JopWQ=l;wsd8@YCo8IZp!--)K_Rq zsdgiQPLa|o+glOGfH^gDlj=(*e^71gQ(1Y@A(+(R-j%lCJV>j7U zI%Q?71l^#Mfp|pSM=JnnvTUCS>*d-NI7|QH^Zr?OUpp`ri2u-Z?aYXdh3Fi+MhXpfYm4qyKoH^~bKEkgLlWH3 z1pPi-p^Bn*hLJVQeU*DkEcU7`I3-}S;(s#J7nHr=m6O(cbn=+(5-TXcoEpLH4K zIvIyJ>NYbrmwDjas;%#E%rX6Xv_%>ecWejjU5SV6w87JfCLVG;G7b2&Z1s82L*p~m zs`3vqtW_0?XK>@_)4REI@=BWGKe=x=v}N?4a{y^elOj{mP(~a+wkl0^48$_G`&|K8 z$miQ=(wAsV)3^Bp3?%dil*LnO_+2bIgueP?Nu_&6D^gX|) zvObb76!^xHX;iFhS8t~xxzBRVeM0TvQM!w-{CuZX62`A&aL+<$QAC0EJ~7RQo{H8K zCR|idEZj_kd70!IyElUhFeLogW*L^LV>|C}7FYM%c@ebDPKq(dPT23P_a8|EK9-eSg~__} z4l3EMtk0u?vWFXZi1cAiOF!{BJMmlF+5~XfSg~1a9Gr^c<~*#m&Rxz3_NJxhHuU7> z1{ua=b3$a=+^*}zn_8VlPawP3qi5poSXtg;ti2%Y5e@-H6CQ9t>y?o12z`z1Q+KHOcey+W zv|Kfu6yWxkAv!5jpWC|H2s>Byj_*KOUvz2;&7jGmRHRT$=Fp3{5~u&FCxzAkW-)r@~$_) ztg1MFl%;_#(;%cdz_TlUB8MZ@9U6&!)jCFGzjDadrFNIcGB$_T-xalQpy;pA-XzHe zHz`AO*^HB`Qdl~=;iS_ZQ-!?OO`aoG?8w>kfKa|q5{O$x`KIgc|R= z9{(V5;h9ffq1~b>><=*y!Ed+7}6h);CIm2XBRjOAkWW-HX&=@{#foCvi-bPi~<=TDXXxoMN{hAr{?#`~K zNUGAya}h2~L(pz*Po_3^HG68=b<@-LZO-|h#l!yPJP3F|uCf4|Me=stHM>fC<(bPu zVLat|H_Fw>DHb{T!T}s~SQ6OByEq2dG1#8eg|)taj-(t1ulqPs8Pk=}QLgJbC(?Zx zGbRzWUSgP=Nqmin8O$3{%c)Pvx6G5)kH^E8zdTrKh4m>sDJs5RWwZZx5D#{__k@al zj#=yIlpbmEMzWzld+W7GSHMVsQ`JhTB`bIQ{G-1YtmD<0_QEv{>|2ujh-h5P+kSqR zvUdTQ5jX7{sn|}ilZxg-kwJl$qw0)c$zJ=?F4ZETYnRy(-McRlE~tNy1V&!!nrCql zFOopG5`=bLuwOD;Ce*9o^lHAr@j&D2Jv?%BoblBJDbqJs-m%iQ&ebMd3p)&4R2~u9 z5?>j$M${M;Up1u^F?&?^c6v92;+#Xetb3**94ov~q1d>~bs=AQz@b-r1B+XWN;8np z-@_{xdaK+$t{l9ob&?}BBv*4j>4 z);+YDRfFzpd}5UaLGnNngY?4Yxzp>t*B}qao`w5xh1ST+u7EywtM>c$r4J@nDZVd_ zqk?C|c@nE1$y>SV>m#z(PXKL)2D(Reb6Y%hCB+-WDsltN{wtXk)^c?qGsi@s&n-a< z9j|7PGENq0v}2k{@4$@f%&Jku3q$fOr)%$8b?V3u_ia9?4wG`c3J@PV!Gw&k zlOB`GHhXexEH7#DDH^~&+;Z_hp#zW5t?(-!_2q^u2p?yFIdawMI^c4pO%&wigKUaQ z_e6U<2d8KEc@!CkoTlDp4L?HM&2=8F#!qfPn%Y<2Hq=uPI?ut*;E ztYOKD&sta<6_4d|Wax!eIohfZY8%TF1yop@uG4J@p+}vg57RWjWY@e^)deeh8+zmF zb+^*|rfbge62mlMW4E~%zQ zW8Xl{(OiX6&Y`(}^$e|s-T8`u@Vz((Lz!lDtaX2T8MpOR1}HxPIN%bO81xr!^k2LG zWr6>)z<*ibA7KGM5<^vs*J>^3LYALG(^?TgkWv}Q$l##jV$s4+1wG1s-31Zn$g*Ju zXD*JM@?cGtatAV&y2vjxLbU{w9Z&G=J%4L|2VHh_vJz5RR+y(%UDa;(r7@$jwbA{q zaBJM~Pjm7NvUB~>mgp$qGf|Qezn5X3TV~-{N0qF)5%BOwZf~f4FcWht%*I1mh?bUN z!l=I4Y`b?->t|?&^$FVw0VA;;oWM_=p$x-pFX$g(qW{w|fp`$bd#O#O4EH?h!Iwc3xl=UR5CRunPG}v*Oos!pc zQ^6Tx+gf~VvU=&N^X1vK#mv7f-9pa=r+xbcYy6;Dice4#6#r52&?MAvgt8n28RwI z(A(f1a2GS+*Ghgrv&dQXnz% z$sL-hYGM9078!2PSi8eQH2!rF8m<`L*&?Mb;miTdO^kst&}=e=Z+&r+%z*oJe|;8# z&YX6uYprLKzjFRAu#)R0Cv4f^c;Uj|!NCh%#Rf+*=5vf)&O?j+m?|;>t^HKP_)3Z+ znxMOWs}~bo|D{oJAX{F_fGc@NwgA#d9)CaOnA^eJB`J%$k{^AEvAqc8L40~r*+njw zY=hFa1XV%vrb1iOCZYa$S#g$zsj&O{xRy{9IEk+7)7bs~8Z(T4yneL{<3`vb89LYA zH=_KpQKXF3+KAs^%(P2`q$odr>9PHcS z9$lHWdL~7c6eQIi+iFq);#As_t#cF>id7bi4y4hJWM(71@lT&VN2Tzjx2PHSh^I&o zoULwcytP+e(M9IE7ZBD)t2{T`Xb?Y=z~{m&VwRoc zjA(fG5bpdL0ntC^_mNeA1;6^q9Z?ESgVD%nNWBu4z6xu(sM2p*@JsE@vLE>9saG*H zqYM{ZAWKm8FlM!36_r&QJ#chZ6fzd$q&*J7=T(6%3%xI;dL_D7fzvb^}{=8Jy}$OEZ#IbkkIjWh(Ji*`MX^TH0P)V!(Cta3V^_-JVz)8M%O#L125jpuFUi?$WZ@awWD|_msj$G z`=-b-rM-GPJ9wqNd!^f_eqcaYuBHZd*yY8g9^?H*Rr^d=kZkMHitw!fVf%uPB0!m| z7Dj{Tk8K|lSKVrSiIK?tlDp5pHH4DYq`A_>Tx<0K6q3?z=+D0{ywm4fD&zOM^vE7B z(!snaMH(M7-EUUC&>CDfRc@RLZT2;v;$apQa;LKY)>z&dLNB3}@6*>bb#3x#*?mtM zH|(YGl~+rbgqYO#_t|2qHTIZs@qD>}JDxL8FnAa`2oagT~GtPs=g?avhTOOQg{X#Q9NimRx_QfxF4{d zdC5m1!0yQ{BtpCGg$L?X81```V?=vMS;3Xo?oO5@D&x*v5fhNW2chnx7OhIDUsf-r z2Pdf}6<9kdK`f}xu`-#gAUaEIvS{nn5O9e5wxGfeh4G?tb7c-4d__Yk@ro5|eM!*6 z5=Mb-ohxco@O3Ae9{XKKu~Tk#dHFg}TUMtbF)e*4z%+1;V9Q|``NPcWR27adtSK!c zx2v73z-+&TRfSDN!N*6wrU`4rjRfN{%U7M&GSSB<@ncO0;Pp`NTO)5g{`Ud69xvx> zZw8?A!dg1;=uLYVnaQES{H)y}d#=~{`E{gKgPxvsfEG`VYCDUVw@P_^I*S5*Fq27fr>~~ZyEGeoe?2)Au9(rV zyFUcdgW93Rb!M>+>@Ur0)Ij&k;Gb+iEobLI)Fh0Q+cE%IO%gslaV4+~39{^CG+pvc z)6>i^Mpw-SJ_(y$)5Rvr2w(1XeKe*gn?>G_>hD3Xjj~2s(7&h0&pT&wjgk-n1P8lD zNs`j2UA`n@=Kb3{qkn@VBBQ}Ei40+Q?^>+!nxk!+SGjb<` z7_ONN*~L$k6P-U1>Js)5uoKFc72dtTi339yk+C+jntdG5O*9)^BMl#dnPfeK#rd66 zrhDyDmj~n2R=-OL$@8;u{Xu#jqR%q2LfjKII`ju=xE`;$Vdj(+>T@@$vd9TI4C`ub z2Os{9WHu~HN7WQo!)1HAlzR_7xbl|pYSTy}e_>$R_Jb1f^{WSGxpXI`qWsKV6hG&+3Jl9Q=VAw9-%=iE5ek+Dou58Ap6 z&h8^wC>tV=Femflfn82pPUDl~{7UZ{Z#OeTp$dg|?;r3@M-izWjNoDTppm3UO!M0h z)1Kbj7HY-#H2X%Ue#F(pnJ=*?0UuWLA9K2)4i2yfE_H7o#@0qz`Dg*paZ@b3O55Xb zsMiufUsjDFKgg0)ys75e!`ECD>Uw9yFcwu{T_LRBu0#&`BJyvqW)?y8Qj7}F-?RUTsG+K>0rK=iLq7>=u4={ zeZwYz@}P9J48T-cYPZSmAo~RJlg)3;wgfJVG{^|<-YPE*9ngLyI^36%s8>@y(rivG ze#l(@X}2f~;I12@gUMq-;-%}Zg*5qP2CDb5W|pZOxK6HyDvUj5I%=AUBcS)<5aGNQi@lTpUL zEPISrJ=aI0!+0t?xC9iz*DJzO#EcM{#f^|iubt=-eGdm_%$ilP_HD=|Um#c%ubkJd!WYmPgtUVj&7s2lPPh)`~?eDZ8!T}v(3cU7XHs9v3>bJk;`hgm= ztd7T~VYzwQ`BC%4;2DnGbZ+8XNV;%&*7}+~m1U~>GJgo3kFWBL2q$P~Xbw+d(F4i} zb}H*qh2Te4cu=OJj|C=OoiMiMG21&P&d_B{b6Am?v*EW%iz{Ljk|i~jl)vF198Z{1 zn^qRm=<_~K?#xluM%AK_*_ce&ZY`bXX7O%iVQ%vtZi~(Gk)7uJa*OS2;&cEX-?-6* z*{5VHx9Uj=H(3I}Qu8xe*~RtoAl!o!`OLD3#WF8Qfg&1VxR@@B>PV{&RfC*kQ ziVe_E3LR|8RMktRZ3%K$G*Q|)unh#DojTVV3$?I*+I8k$)DkwqdVpt z>b^Qpcws2HU-nr^QKmbl7M7S0WlvAD!7qZL`+5mka=1mEMMry4jHUABpo_0GE8*9x z`x{GO3{%K~0pgQ%l10LP8B*fecQiOYOc-ka6sB<38QVJ>KlTQ-W7wM7W(RKNNDbsqn=1%LwN+}8sGai^EW%3u_XV#^C~~?Y;zU+p47)X3 z%F&`3kAR9vfIw5^tKjX(jtA}T;l&5f3UlhC9NP*dsd~1T1R1tC{1qg8QTgdYonZXD zz~6tB=)~qRBsu|3QZWiyLJME{t(31+&s!f=;G;CMTJ|5n{b!eFiZ$k(gf3Em)M;RX1y8O`i>V=4}jRW(gV<(U{7lBd%yvrz$v+dB-DvZU`BSwE{K zh)iQL_Pk%RuW}4{TfCsAkwMyF3LuJ1#&!e=nxZf#y*a_WBvR7MdT`t@ zo&3(o2IcH*BV_z2 z3`ki(s|$RU6Wdh0AzAhL3?Zh#!ur`<1|wcHhdW2bxjyHw*2dDks^X7!jd!UXyb8VN zxh1U%1;&u;`T*tb5IMQC3ou8zPZbYSjPCnxE@wnN^XX<^>}gQW)ltRWA||DyMxguf z=**#JJ%@9G!g}8ws;=5f%@;(iH|}{gAy=m+ejz8K&)O2fZX7>0|ATY`*LpDX)&GO! zR~?T07QB|eW+#6c{19&Y%49kzV8 z%gxgIM6W69w%_KJP3z(DdW4jD*$|`!D;nR6uluNJY5&9c;cZywOYk^dQUX*S4o1GK}g8a*;93%{ruZY z)9wn7-sk8>F7ni1&=-f|dRzn5VXqSFwoxn4dTglew}Ou##chHC73r!(Z_FsOZ~Q7q zuf&cXx?v!a7&-Gp0^jTd4M%Dc&c}FaF@F2Xp@T`L1TdstH zU;LsHsnoSWNL&|s#@Brvsca7iBPK*96AvFA^BY4cZ!(5YhhH2pKd5#6xY})3Jz-GW zH&DMl!t0A7aQd~0D9gqSMnaDDlk{5RnSL6}4Fg{-z9Vu1uJ(2G?i6Kmb{|1)4`I7o z`Vb4N9bnQpWF?o3*+%HR%(5q!NFs^<%?mWBZpo~P={|a=rCb88HXN;$UE_$Vw4TkR zyT*PAze6sTz)?$3u^<%#B8#D7wN2fSu-W$uS4SC06^O6J7OtbF(|cxH!DsP4aMYg1EW3g*hQUoZf$swoUfW zIw`TSPyHyVP|+9y*HhCZ?1=g%f+bKpn}=`Yd#L>Vw{IlAbw}TD#^3Bd8E<#S21C5p zdd|N0+#!MfTPNZ_&Gs50VUo)wP_s3$8}0q9?Xm2J6A?xoqnhK?M=H4bg9In&|AW+s z(xi1i4g1E4qWpUWAYqH8`nZ2NiRkuy{_HVdR&#<6E|gXYzhk-dV1=y>vw@v;!tRHc z@t4a*`WBJoodIE<1}`BWU&@h4qj}d&6d2tCK9me#X^#c1dcy?wQ!s%vbRxU zj5+O~9N~Naq>{|0?3(K`0^oz~F#(vuV$hg3H9F7?=KbMI;vAi zAM<^2m%$Gn6d#pm`(`_$;{oUR=);IAe9ru^b*~6Za7=O8Wb)8{=NR-levNx-a#>>j z*a~QwH}swBBn6XVc!)R3(T8!ddSO+p+%YF!TWofJ3L+D^1?8H^vV0*P7#vq+6p)b2 zQMM4L8{NR{m(h62+0d)j6`9!OIBvUFMXejYv9tYyH z06E@~rac$$D#gxh-aKTb)i;D%*?9gz;*ge9Dx*fHyb|(g5BwlPz20CJnHAy1F&s(1 zQW!C6Qk2lll_ax|e~WzPea2VOr4Pq1Rs(xIJR1mInws91XcEqEX>X5|U1<(Q zWy*xw6Opb@D-_p*RTF(Q?{v5=iF!%JpGho9@cD8+QZ0WMpbPq&sx8SMq)~~d$MQfh zw!Oqj^3+>8%*+cBxWZFhpbI-OLSOQqX#+eJ-i3DsG6ag+|DbJi$TOJF)^D83jao=R zN!smp(P_3_3PzN6rfmqsMPT0yiZy@7a)Ek3aQy!ZQsmXKjfn)YYm#kW39}E_<-|nW;jC z3}{S7I^98n#w%56_14Sb#R&?&;aay!mg(Tz1?uPITS9%+&0BU4C~AwGyxC4uNg0<< z)4|G#La%-fg6nhEmPQJRRdDP}{8J|M%<1*kzSL|ZD%6bWEW0M%ZpSg8NL}|wE2$Nr zGhX4G8qZ`qWJQ_vH~t0gJ}XVJfn3xqD;WoJ4{8=^ECt-%=O)7JhH+1f(O-tw&zvc0 zvM7)4xgX^~YfoiJJmHQEM=~38b8$0YIOj4{|@NR}(AUk(9^$5XUv7wMjP|8D(>hRD8`Ld8Dio5?aAU9q2Va@ZH0+cfOrd zw4>kFBA93D%H->(YDSng~VnbcZuXf4|Fkwg0~^?QNBch-0G_zfXRt63DOQkLK9hXeV-rL)GpvXyyY&{7UH|Mt%JBr)DzzpOP zRlZV*X{mM_9pj2WO2-&6R5u_G6)RNdrfx!*XcxgNxpJnZV+fcQ^z94j4!bVj?;w^* zPEy$2TSE87Pa_n0K97*%00sT8drdkH*4HU|>&DGyPpSg)vYvLyPSjh!>CQS`zo3-1 zjkMX`=uza=7gc9gSWW*w?VV>(lj#=6!{Q<$MM0#9xF|*eNklpVL6i~4Hy)!%G&g}iLGk4dW@!R{pXP$Xy ze)F6&=Xqw%|1Z3xBpr17ARLi{!^vOMZZ@^HdggiVS2gF*z}H<~l92$PPP zZocSa^@nYaw47TvN~g+9@_5kgzWeJhZf0)A4!aoQX1H_lSvXdtm)U9=b)?m5%q%`g zr|jw&$_xlj9c$99)_RK+SJubTJwoG)Y)E*u!N!CRx(zzNNA%wGV&?HjdZgAxZKR9P^tQW3?sw z0J#wJYWpAR00qAzHrF*ixgvLO^*Yi@;zIF|QU4l2 zW>wqHkvY-><(md|J&CJ-V|%RThv{|SK;>3wjoViFICw+LfT7AVw-OMqlR6y>B}t@q4arrT7t6}VRUOy(LUqu@8!cUcN*OxPV$u+h30si+cn{zvs?e?}nE%W0NBB28gbsFN8M~87D;@|8w%B4!QJ|1uA zkPi@Ebjr#cTsa}QDA=mv7N6E;DyAPA@wLgvfe5Vu|F<{9fI}A4NYP4Hg++lr>4h?m z4Xr~yc?pxLKJHFK)2V&Ii&gN+OXu^s-OphKgqk5gv9EmPVySVa#i1kOyu;rQjcnK}?u!2U!>yZ+B zJ_$b9<9c=&QRx&Oo~`RO#8ulAC6! z=Xyp1x6b=3@|%g)?NCRRke$40 zDGE8~f_OHtI1B%oAPVBb5rECA>YO2=2O?74%mM}gp9N&=@*L2$ZXDvNm5s2lVPbzmX_KsS~UDYSvSUhN#FRnTnX1bv$EDEl7FS6zWgik_;V&q zV$;DIM-;7>m*zh7Ms_b1C0^kHOOTY?ugl82SyNlv7IfpwwU!bbBJX3ufW;4D@2<#u zbM>VgP^LIyj$tPhcZE2xRU5`cInwykP)gzkD)Gg@7Jb38>X{nt2%;Kiu>rRzb@^ct zT4^SK%~4cRdrsYsK294f z19j#d8`Y~BIgjL;?7hdiCQA~t1Zp=)`Zj3Qt6JX@?^3)U;#=!{{2G~y7e7+A51$_1q*g|iH1{nwFgkS-F zRp_0j9S!x&>eSknP*qCP-qhafQ>Hh2KK|OHOflAiyLqy~PAh8@JpY$J2K4KDR|P+w zlXw|K7)m(G&Xw*ForoQ+>?;;?>MjD2YXj@gs)1$5F&@{R8I^c&#wn;UPA{qW$Ll7v znEZIr+O59;YN@THuYxANOr zE}<#17Tf#{HqasbEm_7+Zh~s6jZopon(jl2olD*d?^6T2cC-;&^`omRye=(mxwLDh zTb9j|!4gazlIB&UP~G9#oNW&5kGUIT;)%9D_u#@)`t8z=dbRDrkrL|IP^=S8kxf0x zbi^8+;&Mt^reyjKgaDaj`QX83Bh55(@#3+6&^SJ`c>N4J)$3-<^}>KQZDmMyuN8ADw!V&=f4(X=s|r% zOhJM;wfK}>;v`z#=Y^W@C$s&Fb?2AjS?rry$eug3p!Xurb&&bayU+W8AyDPs8Ngp0 zW7$2CM>YzFWh~|gip8p%=n}`aCx{3bFomqI>ez;PMTed_QIF*ggwI1Jnl(a#W37v} z2u$_5d>gNAZI(rccc=Vj*RV*R3lN7TU0-i5&vJ9_HT#W{YOmGw#e zDdYh4sv7ZLBbxDJXUyVI4B~y27gN88gJ>`leqEH0aJCNhO&L-12xq2MIzm117H51_ z?FYn6VdD~ocJxN|OV)HQ4Du9yR|(J{!EaI!hHqE`;v}UX3UFlN*vuEwykxKC-wQp!tAF4K>}g7*xa8f_IEQ*ZsCe7MXt_SI`wt1s zRuAKQk+t==BxY^)gd4RcUc(#F`rBJYW+X5ViBQu^*+2!^7ya#rU&YA;3axRwggjDa znfcEm7HV9oNpvsLWo)r#t$H*r8rJAH{W`&9CzA})n{IZFHtE7nt`e;UcA0KB{|Gzh c-&lNq_)g$Ef$s#q6ZlTxJAuE90AzpU-`@2A;s5{u literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/defaults.parm new file mode 100644 index 0000000000..34857c95b5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/defaults.parm @@ -0,0 +1,5 @@ +# setup the heater temperature to 45 degree +BRD_HEAT_TARG 45 + +CAN_P1_DRIVER 1 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef-bl.dat new file mode 100644 index 0000000000..f92599db5b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef-bl.dat @@ -0,0 +1,51 @@ +# hw definition file for processing by chibios_hwdef.py +# for YJUAV_A6SE_H743 board + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1141 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + +# order of UARTs (and USB). Allow bootloading on USB and Debug +SERIAL_ORDER OTG1 UART7 + +# UART7 DEBUG +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA +define BOOTLOADER_DEBUG SD7 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PE15 LED_RED OUTPUT OPENDRAIN HIGH # red +PD10 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green +PG0 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue +define HAL_LED_ON 0 + +# Add CS pins to ensure they are high in bootloader +PE4 IMU1_CS CS +PA0 IMU2_CS CS +PE10 FRAM_CS CS +PE9 BAROMETER_CS CS +PE3 COMPASS_CS CS +PC15 RESERVE_CS CS + +# Extra SPI CS +PE5 EXT_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat new file mode 100644 index 0000000000..206b3a81bb --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat @@ -0,0 +1,241 @@ +# hw definition file for processing by chibios_hwdef.py for YJUAV_A6SE_H743 + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1141 + +env OPTIMIZE -O2 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +FLASH_SIZE_KB 2048 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART6 USART3 USART1 UART8 UART7 OTG2 + +# now we define the pins that USB is connected on +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART2 TELEM1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# USART6 TELEM2 +PC7 USART6_RX USART6 +PC6 USART6_TX USART6 +PG13 USART6_CTS USART6 +PG8 USART6_RTS USART6 + +# USART3 GPS1 +PD9 USART3_RX USART3 NODMA +PD8 USART3_TX USART3 NODMA + +# USART1 GPS2 +PB7 USART1_RX USART1 NODMA +PA9 USART1_TX USART1 NODMA + +# SBUS, DSM port +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# UART7 DEBUG +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# these are the pins for SWD debugging with a STlinkv2 or black-magic probe +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 -IMU1 +PB3 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI6 -IMU2 -IMU3 +PA5 SPI6_SCK SPI6 +PA6 SPI6_MISO SPI6 +PA7 SPI6_MOSI SPI6 + +# SPI5 +PF7 SPI5_SCK SPI5 +PF8 SPI5_MISO SPI5 +PF9 SPI5_MOSI SPI5 + +# SPI4 -Extra SPI +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# sensors cs +PE4 IMU1_CS CS +PA0 IMU2_CS CS +PE10 FRAM_CS CS +PE9 BAROMETER1_CS CS +PE3 BAROMETER2_CS CS +PC15 RESERVE_CS CS + +# Extra SPI CS +PE5 EXT_CS CS + +# I2C buses +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +PH7 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C1 I2C2 I2C3 I2C4 + +NODMA I2C* +define STM32_I2C_USE_DMA FALSE +define HAL_I2C_INTERNAL_MASK 1 + +# PWM channels +PA15 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR +PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) +PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) BIDIR +PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) +PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) BIDIR +PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55) +PA10 TIM1_CH3 TIM1 PWM(7) GPIO(56) BIDIR +PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57) +PB5 TIM3_CH2 TIM3 PWM(9) GPIO(58) +PB0 TIM3_CH3 TIM3 PWM(10) GPIO(59) +PB1 TIM3_CH4 TIM3 PWM(11) GPIO(60) + +# PWM output for buzzer +PD14 TIM4_CH3 TIM4 GPIO(77) ALARM + +# RC input +PI7 TIM8_CH3 TIM8 RCININT PULLUP LOW + +# Analog in +PC4 BATT_CURRENT_SENS ADC1 SCALE(1) +PF11 BATT_VOLTAGE_SENS ADC1 SCALE(1) + +# Analog sys 5v +PF12 VDD_5V_SENS ADC1 SCALE(2) + +# ADC3.3/ADC6.6 +PC5 SPARE1_ADC1 ADC1 SCALE(1) +PC0 SPARE2_ADC1 ADC1 SCALE(2) + +PC1 RSSI_IN ADC1 SCALE(1) + +PC3 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(3) + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 + +# GPIOs +PC13 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 +define HAL_HAVE_IMU_HEATER 1 + +# define default battery setup +define HAL_BATT_VOLT_PIN 2 +define HAL_BATT_CURR_PIN 4 +define HAL_BATT_VOLT_SCALE 21 +define HAL_BATT_CURR_SCALE 34 +define HAL_BATT_MONITOR_DEFAULT 4 + +#analog rssi pin (also could be used as analog airspeed input) +# PC1 +define BOARD_RSSI_ANA_PIN 11 + +# enable pins +PC14 VDD_3V3_SENSORS_EN OUTPUT LOW + +# red LED marked as B/E +PE15 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) +PD10 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) +PG0 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +define HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# use pixracer style 3-LED indicators +define HAL_HAVE_PIXRACER_LED + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 +PB15 LED_SAFETY OUTPUT +PA4 SAFETY_IN INPUT PULLDOWN + +# SPI devices +SPIDEV imu1 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ +SPIDEV imu2 SPI6 DEVID1 IMU2_CS MODE3 2*MHZ 8*MHZ +SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV dps310 SPI5 DEVID3 BAROMETER1_CS MODE3 5*MHZ 5*MHZ +SPIDEV ms5611 SPI5 DEVID3 BAROMETER2_CS MODE3 5*MHZ 5*MHZ + +# IMU1 +IMU Invensense SPI:imu1 ROTATION_NONE +IMU Invensensev3 SPI:imu1 ROTATION_NONE + +# IMU2 +IMU Invensense SPI:imu2 ROTATION_NONE +IMU Invensensev3 SPI:imu2 ROTATION_NONE + +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +# baro +BARO DPS310 SPI:dps310 +BARO MS56XX SPI:ms5611 +BARO ICP201XX I2C:0:0x64 + +# compass +define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90 +COMPASS IST8310 I2C:0:0x0E false ROTATION_YAW_180 + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# enable RAMTROM parameter storage +define HAL_STORAGE_SIZE 32768 +define HAL_WITH_RAMTRON 1 + +DMA_PRIORITY SPI1* SPI6* TIM*UP* +DMA_NOSHARE SPI1* SPI6* TIM*UP* +