From a003e7c081503f40924d00d1e253d950d74f796e Mon Sep 17 00:00:00 2001 From: Pepijn <138571049+pkooij@users.noreply.github.com> Date: Tue, 4 Mar 2025 18:42:45 +0100 Subject: [PATCH 01/19] change wheel setup in kinematics (#811) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../robots/mobile_manipulator.py | 24 +++++++++---------- 1 file changed, 11 insertions(+), 13 deletions(-) diff --git a/lerobot/common/robot_devices/robots/mobile_manipulator.py b/lerobot/common/robot_devices/robots/mobile_manipulator.py index b20c61f7..c2cad227 100644 --- a/lerobot/common/robot_devices/robots/mobile_manipulator.py +++ b/lerobot/common/robot_devices/robots/mobile_manipulator.py @@ -392,21 +392,19 @@ class MobileManipulator: for name in self.leader_arms: pos = self.leader_arms[name].read("Present_Position") pos_tensor = torch.from_numpy(pos).float() - # Instead of pos_tensor.item(), use tolist() to convert the entire tensor to a list arm_positions.extend(pos_tensor.tolist()) - # (The rest of your code for generating wheel commands remains unchanged) - x_cmd = 0.0 # m/s forward/backward - y_cmd = 0.0 # m/s lateral + y_cmd = 0.0 # m/s forward/backward + x_cmd = 0.0 # m/s lateral theta_cmd = 0.0 # deg/s rotation if self.pressed_keys["forward"]: - x_cmd += xy_speed - if self.pressed_keys["backward"]: - x_cmd -= xy_speed - if self.pressed_keys["left"]: y_cmd += xy_speed - if self.pressed_keys["right"]: + if self.pressed_keys["backward"]: y_cmd -= xy_speed + if self.pressed_keys["left"]: + x_cmd += xy_speed + if self.pressed_keys["right"]: + x_cmd -= xy_speed if self.pressed_keys["rotate_left"]: theta_cmd += theta_speed if self.pressed_keys["rotate_right"]: @@ -584,8 +582,8 @@ class MobileManipulator: # Create the body velocity vector [x, y, theta_rad]. velocity_vector = np.array([x_cmd, y_cmd, theta_rad]) - # Define the wheel mounting angles with a -90° offset. - angles = np.radians(np.array([240, 120, 0]) - 90) + # Define the wheel mounting angles (defined from y axis cw) + angles = np.radians(np.array([300, 180, 60])) # Build the kinematic matrix: each row maps body velocities to a wheel’s linear speed. # The third column (base_radius) accounts for the effect of rotation. m = np.array([[np.cos(a), np.sin(a), base_radius] for a in angles]) @@ -641,8 +639,8 @@ class MobileManipulator: # Compute each wheel’s linear speed (m/s) from its angular speed. wheel_linear_speeds = wheel_radps * wheel_radius - # Define the wheel mounting angles with a -90° offset. - angles = np.radians(np.array([240, 120, 0]) - 90) + # Define the wheel mounting angles (defined from y axis cw) + angles = np.radians(np.array([300, 180, 60])) m = np.array([[np.cos(a), np.sin(a), base_radius] for a in angles]) # Solve the inverse kinematics: body_velocity = M⁻¹ · wheel_linear_speeds. From a4c1da25de118bcf89347e94d16551b8e4b0bdd2 Mon Sep 17 00:00:00 2001 From: Pepijn <138571049+pkooij@users.noreply.github.com> Date: Tue, 4 Mar 2025 18:43:27 +0100 Subject: [PATCH 02/19] Add kiwi to readme (#803) --- README.md | 21 +++++++++++++++------ media/lekiwi/kiwi.webp | Bin 0 -> 224412 bytes 2 files changed, 15 insertions(+), 6 deletions(-) create mode 100644 media/lekiwi/kiwi.webp diff --git a/README.md b/README.md index 59929341..9debf9d1 100644 --- a/README.md +++ b/README.md @@ -23,15 +23,24 @@

-

New robot in town: SO-100

+

+ Build Your Own SO-100 Robot!

- SO-100 leader and follower arms -

We just added a new tutorial on how to build a more affordable robot, at the price of $110 per arm!

-

Teach it new skills by showing it a few moves with just a laptop.

-

Then watch your homemade robot act autonomously 🤯

-

Follow the link to the full tutorial for SO-100.

+ SO-100 leader and follower arms + +

Meet the SO-100 – Just $110 per arm!

+

Train it in minutes with a few simple moves on your laptop.

+

Then sit back and watch your creation act autonomously! 🤯

+ +

+ Get the full SO-100 tutorial here.

+ +

Want to take it to the next level? Make your SO-100 mobile by building LeKiwi!

+

Check out the LeKiwi tutorial and bring your robot to life on wheels.

+ + LeKiwi mobile robot

diff --git a/media/lekiwi/kiwi.webp b/media/lekiwi/kiwi.webp new file mode 100644 index 0000000000000000000000000000000000000000..2dd7d9256153b68a7f3ea5d0549381a2e250b0d8 GIT binary patch literal 224412 zcmV)AK*YaNNk&GLYy$vSMM6+kP&gonYy$w$@(-N>DgX!o20m>vmPn)`r6wcs$~eFc ziDzuAhvOeM|Jzlck73XMnnvgUMrVir|7uiv_3I!1S>8YN&JKEhqkTi`zvuqbs?F*C z&!A6{@ehYaCJ_miKTMxLx?TVE;YEqa^3)%nKS$>ejQ;_?C;2bgpBcaJ^YiAv@_Fcc z5A|R9eNX@4|K08X^^g94^1r|T{65HkVSi`6(tq9kwD_6(zw1N$C;VUBe|AqbkGKz% zFXbQRKm7JzdO~@!f9d_#__Y1U{lfT!{p8e>`d9ytJU>nUJHKDjKL7s5`Oj*f=(7j# zzv_PD`kD9nKV7o^+5PvRr|Ms`y=lL<_W#9ap!~)58u*ves%=hro;*sRCk=U3Lupjyb~4!WJa{({^!oHwnd0omE}A>_vc0h%pXH^*A+5mP>L!fEpB;dv>2yuU zQ}du@_*&Qql%Jd61F=RsNIis(JV82|VejlYRGS|p6Ei*r-vQC!Vuo@SWNthX;A_pu zra0J!8lITPd7a1`CS>4d?II z%#YSh$4R~^KR4;#Sbn@4m+~)CH-9PNzOTBKS)8k!(yIKXxipBhT|Q{8rbc1kkY6{z z3#nBY>F6l{E~Qjv)PF)6JmBj6zZ%y!>_I-;F?2XW8C99$OpXkvo8SO)K8l4pRnelF zP))~Cgs9p|RrPvPKjS(n5K;sl6veZf@Wg)i?BUV7UJb`m00eEmmo=Zt#Cclf`!L5C zf02EZ#DiJ`_O6M)*Mo7?fB@o7AFW3MWoh8jf^Nq^vNuaaiJ@RU6!g1C@`Igb6iARU zc%S25_9>7obXU~-ZSRAI{))M(_m|_#0sI( z0_Bb?LN?S#%JL%tAE7(J+76(du$IP?eAd1|ltnctlMT|VGslQ`dYv_Y%uJ&sr?ikB z063E4i%BuZgK}Q!H#-svw6cr!Y3uuZ0o9JN;)Go^4mj(^#~*iJNDe`dP0R~h!6~vU zIj-0B;NpaPC@Ur0{1q!fn48-oBdCj3_twyPr`B7OE1y6y7fP%9_}$&O*;U5emIHO> zl~{?{@B!G?Fk?l~h<{NCC}` zyMNCFM8C?SiEL4;1XZ=&j3m>JBY60FW7Km2CD_yoVLe*U4P-U;K*~>R7PR!lf&D$Z zzmaEo)nD+0L2ZI(CO>hd!zM*UdM!CBt%)f)ea)jDf5$r!As`F^yFa(jKln!pYc%IR@8=MtXUoHM;KdzZP z#l|e^dTrk)`y@bzk$fAlu;P^pjkmiw);VH3s}{K5ilhss^Wozd2xZ{hY)7*eR+*&^ z(uuKxb315xEf$Q$v?=$^@A*UrkT_QVH=ds@O{B<7f+QB%h#Nizh+hw>TAnoy-mHB4An&7(C_c& zAnc*yb%GDkoruPng{KrluA$}kWKyC1ry!Og-3UnJW+D+iu;y5WeFWh-@v>yw(dWw3 z*eI*p4LtIXebw{S^|3$BP$uJ~-1P$d!@vg}xy`BCPdBVI&Eiage)ljGFQXEB_t}ha zhM5&Po4txH=u>(Py*>Q6wAAM+m{%v7i(9b_sbMi`Zd)-5MNw6cZPZ76Uo<4dBkcn--C4b+YSUOC3*`3nb4Wk{$aF(Vaix zPxKFkl4?i)B-%R+Yenx94aRXC(qj$!FATwS3sdWM0mZrF!E{WfnX?B<3sKBJ+fcua zi2UCCE3tptYEN5Ft$un(-kNSxK?}Ulj|E%MsHFh`n-UF5K5U+6i=zoY6M4GNV*|Td zM^kgjY76eqG;_&Ed$JNPqc#86K(m9>sZfi29R$(KsAw}l zK7LvBww;m-h5Lvum^O&b(C;+@%BAg{ASU^rrINP`f2^OtW_+8pKvx0sq}+XRy7w*B zr{oL0IqsC_#o)BR8SmF9(9ze`Pq zgA|ukDUnJnep5yE=U)otMU`2c_3TYc@O{Vqq>@wzc3FG;(ku`G$AfQt9iTGsZaRPaiDSE!=-K8W^2gD62D5F$R^Cwu9+>0!sX5IIVEO$;{_@ZqnSnyKsH~hhAs?n zd0E$bK^xaqISMb^L7weZWDwcl2aiK@76&v#01_KGjAb#DKIL0dZZ5El0XE`CrZC^3 zEnj}>HM$c8#nmAOc%}IZ?_oykyVJ-Xeyja)uh_B2C62(+hEy^xNvA$o;m8t3?rD66 z5-sy{$AGe7UVYHn{y~2O?&k5}(t;UyHytMVy#~)}5x#g4Xwlbk^?xh_>1-reLW3Rq z#1(VSM7wsHn&-RpvU4xfOv#;hd_WJ?wVyLt{Rl&4+tbS3dLZGBc7NS!s^t?OYQL%( zOVS%TS!j5tbwjZH=01hEM!>u1M1yrjJ{j+Dw_djCNBUoDdfzB{~Hnc zz5{E|fCf9AI$vN9nyD^$U9>VKga}3!^;?u^AoaSrR)nZFsAz6c=jsA@+zr41>jP&O|0M0_H zx--ufNfCYtFx#|W)3E+#GwYlp!!2>rIE>2nK z`JtXVsbhbVf}2AIiDr9vGsrX&{8On(=B}xTKaqOD^GxZLic+BO%NzTM{7p%u?>{MQ z8lo07r`9-jvx_0-CCA=|99<;W@$2pu!3W}N8ei`o=G5O^Uo8X5Ry03I9SRMBSG87K z&2klzX54BIXvf|+#EOX;bE=NKK}UN9p1l6R^EVX$hEl3*ISUY+y(R4BE(KkKF0Q)5&XVk56L&Ko%G0li02G` zV)}^})2p-Qvd9)hZR+5Co>rS&_CR9J^ScLc+(p3g4V7RD%Tpl<9OANvxm8AfWe$6P zo*UUD6BLl|H2iQ*hm+i;{z>=fkN!!fLN^GHx$XhHXiRBZE0PL`@T8v>+vYHMaVx*f zUp41nsaTZcEM@+(Rs44#+O*kUC)I-BSt)8&Mm1DZ4Xd}n0OqAcXM_Edtt(F(gp%I> zoLN(Y%AMA^*tV5vcq8S=G8MFNyRQZNGKs<59;T;{@5sj|ASKKiC^x>IX%Dhy67S5; zj2$x&twjC(8!#3cLm2UXhYD=5ZF53D)JXi{Y;Bx4B>$ki%DbgHPX4G4O~}}?7}ut` zI{Y-}^tX*l@v@xX?4|d5%k-hx-ix^h*NWfIv4OIjB_C=8u~3s=z{BU8VPb1jr-J4M zpTHp%zp*h$(JJ-Kjg1X$6drjqjcF5ucb!Q~t7apbqR4tRq6_r7$3naL@50S5igA?< zeFyxb;py$&{}2FP)!*nh9nLm2K2OD4Ms@+hEpppW&1>S3i|t%%@U^k7auF2<)92lq< zyUqmw!(C(=2Mj^h3^A#xY<~>kBaXY0|DmMv#`cC7auKsgctA079$c6LgP{p$>+wN= z-Nqm?yhb$_?Tcwum^=V+CQ+4m35d^qSl}4J5--}rDbBZM`Mv-L9|0O%FW!9g`VpXW zy4i^@6QA@S_&=FWqmPf#LzfQ&*=vks?Z8X`F=E;S`@V9@^n|Vevql}^e|bDM(d5)u zUP;P7&QKK!jkK)brR1s_GfmIYl{+lH`?vxFoyrMX%wTgNVG_S!ccsTvoUX>ey|-e@ z7cJaHCfXnbKzyT0RIh@JY5yz1LOIh!4#9Z@R;ZzUS8MZMb2vJ~{oMR1%(@QmGqoLi zSe*suy{_Vx4ehhRXJ6xvqx2=LYCry;jN$+Js)LL&ARdA6%FQTamXXorsWHb^;!JVi z+;p4g2QUExZ~;Yx1C#*bM#2;v2b9l*CJ{2sk2Ek>?sw=GhT?fQTCw{gjP+X`%A{O3 z*+!C~cI3yH9sBMog#%1w@#4{}>`)j9jfEPT`T48F6HonU24hDy>Y9rKPU|GskB(~| zqGG7DXR30n4ibQ})cST~JFRHj(c^3V57@u){$rzwV_;?jrp85ANc924PX^Os za{5665XDkM0NfO^T<+}*SmUVx+|D;HeaT3(IlDV_Ve{pPmC2+p@{mrguF8Np6xVtq zwyb>tsWc5kZ-4>F*b;25p(C*V3?{P!&yeT-@`?;sYbb>ec>ZhloP#;_#;G74pduFG z+?@ax;&`v+Ms=(=UaKe{cm4KpmoC&i5De*Y3`eY}B_r96Puzr!rv^b#N^CDv63Ty^ z6aT4xx{R%XJ6pdY^f!1WhoLCcMu0v$1}jF^y^_TQ1QLr|CU(-x`LQ@l4I1-c;z;p- zM?x`a**G~8`!21eSx%qxap2r^k~X{@H!gF#-~e-jvl!m`*wlak(-?miD z2$C@%D(2jZE{G1&lA;!-F!g*0K6JBS+$zhDU(s4h~4@U-|h#gPrKID+N- z2|&V@VazC+AGJtI>p>zaVxY}%W z7bi((Fgu<3UsEYW3{j=>C~y4SIUa2UCqGSrrNC)qRyEn?-`!kqw$iep5m_S*)iEj0 zJ0t!&|6x&STZ^bZJ9!b^y~ClN83b!0Fe`q3nvjofyIaoPzS0!7tP9DHVJ;twjE|t% z>7;wX^7Kl_s^3iA>XcrlAgBbrR=h6J@yrbjjz5h9uEm?AjQ^a#C*2A6C+!xutM}Hm z{@=x4hx~69 zo7;>Vqcb9RE#CkgjaR?S@!5pBn~I!_Gh$~La)IFapoH7-UoxD5Ro~RYZ(|;gmSM&K zO}M0UcEMS^EY&;16YcTwh()3;r0@zAnd888tts;l=R3XtU8+vaLseGrGcP3JeGJ-u zdHcQIDMD4(19}a-{kN&SNp{l9s%yRzKh1v=s;yH}l;izzxt})Fl7B#{YoASKD$qU% zqY7lTX)5!wd%#Gt-$CgG%+wyZT{1%5BdrDl9QX462Vhyoy4OkkD_B=r1a2Wn4z1s= z`B=GC>aTkk3Q}?(&)3}jJJ$Rk#`fSqztX#XQXl&X%XrpLS`R&%h?q~XZ!WM5ZM8o; z2>{d>6OOrJXg(aH;(*dj)EVCwd8IF3g>IzKdd7vk{jqH-vj>6503Y?uu5Gn()ON2V zanfZdqH2JKUJb`pC~RQuNYFTv@y>+eK94*ezwlE}SP#wxvREU-<&!oxp|xLlS36=^ zah@WL$~L-NZ@CnBqy)E$HVOZUZ#bfqAd(!bel-^oG`^XApQ zd`{TaCVDG#(kksw&Pd?mMMT5tOl6G<1vTZIZaM_;N{(@=APzVuJNN2J$!7Jho9?Tb zpK~o?rsciB19ca1(5m=)Nq3T%b@{QqE>Mg`G{(U~8@7?Ry$Pz3N8Q#ft+Qe(;5))C zJ5vbh_uS+m0`IhHUJXgszHfkle`xhkm{akri>DoKI!(^Sw5vJu>G0%HSFg!Mc?J$}<*#y>6NGEnTeoMO66y}g z@*r(FLsF7%)?=ffbmqEDX@R66yXLw5VmD;3_(VOl84>H{b!4pDk=M(QXr328+EDro z#&>S$@!YXTQT|^!Mh-&)Dj?84qOt=R#{+H*PGmsm{7hKfxg^EHqvimc5lIke?~^jP zw7!~<3moN(23@z`-UQF0)s8LIaDjt_bo*}4^V15l(i8+A=6i{+kI*u=cj6n)z~?FO zaK0VyAa=+;Y^rWmQH@tsJOW1{g$q%;lVPl22CKpdY!1ykic+3_8Kb=@Sc&S~D`-An zbF&OMk7>L_*ZQUI4Yr6syGs4H*w5Fp1r5;D%@)O zv|;drPZj7@{bmV&jc`$177rlASlP6U-W?AZ^vkDt@WeYc8J!LbQXdu`jo4JqCe@CVus7I;|uV)ngqyzBx`awA|He79;anzOQ^&zwd%t){FLNvY7aK0AdvlQwqW> zQIzF(|D(rMQ3*jeCIK8hW60c@7H5eqa1ZT<}@G4Zry+KgD6; zXKUsF*k4%4`k~zZVJLT%XN_fuXMTP%^32}jhg;d`J?m;C%oai>;%6hyq7P?(E5Xoh z40@1lH+f>n&367%i8SyHo=?@g71L=3Q2#Q}>O^q!nE!6^*=yb^$r*sVTU)(Py0KP@ z!>JyIPVPfeT**rn(XqqlFXbTd%yMT^QAsGzXfhQwF7H8mnWJhE_n8n(e!r~yOkI1g z1N=TNTAMjh6ca!>5>n)IFVEP^&uQF>13#QJ!R+3AjC4a795cbszjEnBcELhekWZ(Oe}2U9;Uk4v&N(H$7xww{vNo zV-pu>CB;=Enb^lpIjH+>2WxFm)|pyoO13`8(u`nopnp!ajCY+jm6~dV)5={~xm_f< zl7HkW<#;C2?u}Ds2NDv>3+lVwo~yIqzP+Xuxc$|`T;TNc@H8@m3Y13~+g8Xiuk`{) z8cE#O&DPZhRM=bY*54+(4B&ApxPo+lgeB6TUs7Hz1=RaOp@^! z&^luQ5KZnmWigu`$lKU?6&Bb(wbi)rZZ;@B{}hIaLW$c}E-|8px$#CA{EN2*FjXbt zGw})GWf1tQ4p37Km%0BB#9!3-c3bi9@n2I_Yax|y@x&per6aT%nST{*xuOf)c3BAz zkcyu(t*kskn%4 zd?MS_=?o;mo;(|ll{o+di7#U;jqk?4V#ggv|MR~p#jveAQh3kbE&%S;Z& zP@dpn+*Xc-3YfWtjt#OK9R&&X5k;DgTyWOMo#s>n)6RHspVZJOKrJXPJ9{+}Jeu{A zwU~lGR8!t=bFfTO>Ki@+r$r!SkHu<}HOsbz=l?59IdR;ITzqSk#>!+8QgZ-K6f-b3_+~!BhZInc_Uq)|*;;VDEUn>v)*k5cJtCT91y7z3zd0yrrWFyayPZ~tv zAfp>(;?Wa)wtq@jf_KE@SuJjTmodOl zZAmf<4tS0LPO-$C-p<;aGf<8r7SlMAl$`_ZgnT8flEfEdcL7FOC!ZOgp(ba<{Iht* z?epqdQ-QD}B)d<22r(rsq!taIN!RR~L!4AhqB9&Vu=&h9!iA#K?77xA4R`w5QV$$cNfh@Lxr?ocIm|Y^p--tP!4Rb*}y?v%cf(O1=oE`*ur{ zqi&x_sB~~(m%wgqw26c6x=^&mZ?(e1o0MPAO;EK_`*xw9*<#hfoE@!wS{87c)3{p* zMnF#w(vC9(q$nXd{<`xln={9Qfef6z`~VNi9y3JEmb@T(MS`Xr2r7=??s^{Sdz0e0&-YTH87n_o^Rcw@Kyy-Vw%lcYMmqIymDP%(S?zLeV>o- z3Oc-apj3*5C*D@CfN*1)%Y}uT5mC?q?WI-lE~jn{e(*dW!P*VUcKAUI1l)lOfgXcz zfPQJ;9KM!K;Gbh|wsa^Q4ZH7Yyp0|E`?Jk9#r*rd0-bjRv9VQ`Sw-^)rZSw95d`w= z&XM;et@LIl^o#h*?Kr0^>W?Z~?X0<{ieZhKC%&OJFcI?iZv$8g^;K(41JS6Kc$lat z)&gn0AU_x;;DE7tZ5-ohjINCJ4j0x{i~k`&Pb6(!P^{;`_!T?r0jB9N@959}eQ3EE z-*NfT$ze)cIa+X*SyO$NHEY7zo7)G+(@g(d2d3yYd z1WTsNothIT)rzj9JhEVKJ@H=v16s4;1{s|jtvOe0gjQOCbu|B-GZ1;;1A=ag!_2mJ zYO83TQ!e#50i}RSg~ng;I~9NL92C2|Eye$dod4&wtSoDeJcMkVB54uLC33NsvytSc&8+w%$EYi@H6pXaVn6&*N^e?6gzq7=j#Q8)*j{bb$)*(MwfTK{RH^ zCz3IBb@nq}SEh=-&^0*=;_4^&FDzt6~sEF!hK4fBB) z!_TT_0*h_`{v=OkkOWAc5|qO7R|57Un983r8Jqc7zs1Gu{75*TBi;}9 z;^mbFSj!Lc)n_SBTog*hyt17ZpL|sCN0&U2FLYsx`+^lzOsA6vGoglptNSu}kS0GC zaRa!(6*Pm4s580NCbFH-n?Q)v{XjRv1DT*t|GYK*ZoGj%;w(dG zffu*YqG~Iy?Jgtl$GT~!7Q#<7|0(}F?nfY=>)Q~2=6|W-(C3cN`q349FqE;+`wulY)p=~WAInPo?=Q|*CZmwBkE2ICm9hd#`OWTdJ-dPU9 zHMw!RdVY*&YhL``M5eXXmZDXT9C{)(fp0+uueO=0IXpmtA&sjI^GgdQ-AsE6|CE3M z$9X=vC~Bp?fXe?aLR&M(R^mR0HuwNzfCbrk&xbNo-Vy~&s@VD+*>cmc2PZtL>#1!6eK-J~5Bd9_e##q0 z(NX4W6A|O`wM&S(+HqBkoQo>lPhcrqO&n^xu?Ivu^1a{)o~7peBf6lvTC#a7Y?akn z?(`-<8i@D2qPn^=k?}K4SoV!9lm{dQ^d1yK88l$vYnm$7&k;`M<-gdrzVN)MQPSN@ zq->bI=Er3=v<~rBK_t!AJw;$z(rg|h_j=m1b}w;QnZ~8RXd%wGRLmLK?d`0o8u&zX zaqsgvQz>gub3~5PjYt3(fBR*HQ|QTXRv`vpHSHU9eRe6osAaRc@y=Vy{xgY{ctxy; zNbFR7VbL3L`+OnKrXaUBnt0YSUEBeYPfomEtaCbQv2E5UE@8R~Q`cJ&^ybH;2D-w~ zRm^su=VEQT;A?aPri>pocOk)S8nNI5KiS*FI%PK8s()R)l<~Y#pGJAz@i2* zS;OqXB)uC%PuW$gj-&r6KY;|d>9#c=|L~D0#>HJ9yW#~89Dxg9@LbG8+Hh6X6b|rq zb^hl#RMygnVSD-6N_moTL()^vY<*Z@r1SSp16f~Apo7yRFqcI7kIoMAc3CsneiSPe+! z9UQ(LMBH&UYyL@TOGI`QWCGwXQa)gS-zsg5jIrOzG>y}ng=&jaI*qyPsV4g}GpmI z0ZolabFKg1a{z?xwL97#`qNB+km+$$kGn-IA?n>$Xm%ed0x?S6Lh&zsjVZ|d)4lww z5VAGLx64|=`qU{WZcrU_z|bvRE9g5rBnx#aKEZ~R zZ@AKz94E!w)pawV7_FJB5E)#~s~e;sp{h88wN;e4-gXwyaN#hJWX6iJcw!7Uxjdb1a|`q{m>`*{O*e-@_6}Qqq(nbBu!i8aiZX4>tl7EFTS- zb+LZhlR+j;Wzf78G0?}uvtNM&eafVmS5ZW8u7?_K4&AgcrVrxIFU>AO-WB>$wwi(d zFCC2)(@La2Xh(njZb~TaWK#r|B*vo}cJ$W%QX}wR|FwTwQ1bk<)}iNt$D^wt#XOzu z5sH;@GsE@2#SJxZmZ>bnN0`kSX@~+FT=-Ub#!E%tO_Bkyw$2fwH8e-!^~huvSh}oh zGuMcw6(jO3kfK9OL}?5ksaS+U3|sIMsJ1sy@H5O|#*psynu`^6K|R#^@)6R{Jl!3O z*2OBO+Y9O5H*I1`|C3%Y$PwFZ$|6-U5o-b&Q@$>?2sRi+v8CIO0jkOd>+!Ix&mCPR zU~J11y)Okk@mtVDY|(AUTp!*TJ}6Rnf#9k~<)j}7$&19tesV{k z4BR@KR$VLRy6YhCvEY&BTiDxRJMzK}MBM$j5Wo~Nc81_ocuq!Y<5rzOrRAeZ;rtZ# z%Q;$H8)7|*D2l8mby&3j)4d!DD}QZILEYtT153t?OLZoJcNP= z0+3$S{;OTPK*n=lxuMdp($UM?3(U~EIvh(zoEQ&?;l%e#f-}%2wr?z=)EZIqBB^6T zxjA+cfd*e%Cs>U9d;~=rzidprfF_zx%YJgi;5|UV)l>q6Q|~NUw$*&&9dK)PDE$C3_9->LLwZsJ zgjEw2&wFrs;|?8UD)-!}(tNNDrf~;5(ShDM)C{8t=v&%LbYlW84p0A88lYESFi$

aj z7VrMH-+NN*^}Jh%x(MzSym%yaTpJn_2^WC(R(K?8?caPQl#tuSi)NgvfhoV2>+*x3 z<-%;ydy?Sq`xK)O_BNHVpS2VbpU?XBCK)#SO9V;(*<~0NsUDvXm(d|ztYEk`0h?dK z16qht0WN!Qw2~ep$o-~c>ZH^tP?rdvXTxSQFziw`On+MVd?k&^Gyw2x`cL7$WEA+M zan!|A=uL|}E^}AX*yCb9IC()7y139mZCr9_L9$ZADdJ3JOo#v-2LZTh=^;Uk8kkJj zq(P|mqJ!kyP5oYiPH`o5z)l4`+0pEWP>5-(sJs6&g4*LjDf#)6@^Z}o4nB%GZ;cHp zHxVPq40h{}K6N`L3yjx!sz=#(av)Vy0Lf3ng@c^UH2QE5~ zoo`%M@$I&)PI*_K|J8cO$TCG47$>e|?c;=7rebIv47_DO=XK>M0kc_wCgC(^|2z9{ zD3XEHgKrKiz{ztwpzK6g%*5?G*pxm?0Cs#y}I{J&m~E1CZ? zSykwPbKK4H(c%&eGGVG-6N+u~{m^*k_Wknk0lx+_>KPI4rCGndS1<Yr#cyRZpdjdED<-qQ@7RV4xF9wb(oJcE@&gX7Hi7tir zsmR9u_~wt}#sVVpu!zs=MyHAXbF_sz7bY`udHTe$IQ;-J`0TO~n+1G~b46%|M z^7mj4q|*n7-*y%>^K^V8Gz7QOWxR$f-|}jIR#P-XiqUN5_G!QawUcqvO*`kECYlFP zgEb83md4IaLWrXllF&}v)$vQIdOF=^Nt=&57qlM_x1`w-_fHPD1C;t#1Eb4Q4I^}! z_&x)r?E-&iY(!Wc?_b~82pMdbo@isy9jXdSG2 zBJf;GZy?o7Z!hjH8nvy(q@PQ=H3hBq^uCeT+Cqsj|ku+4vOHuQN!6m<8VLb#8V6@_t#o;siIZXZ~XD z0AQ+2!3i2?Uxkyi`&Ped;a%fSy)9*pk&6|4+Zg)zjrI-#k`0RQGOA68I(VOJ=r;Gk z+6}$%L^2>;nSe&cQY?rCAlpuPo+M!P;e;IS%IzK@z)<_g%JXrLtRP`MuyL$g>C3rw zh`sNaF-AGjO+R-W(clZ3^ul0X$`0kE{|v9qL5{8=X>DDgSaM@{!h}`M!;#renz+b~td#5!b+;(9k}+|S<{{YOVy%n1+Z|B- zQl)Wr9Bhwu;Q*(9Y$d0YmA4tFHTn~!PJes9Df_ETTghHN*zh7) z+v9A2>cRzFPBqHVzaEHUI}oL&X^kySPc_6>IkIRzOZ;!3OIRu%woy{3sCRvJcP6`= zkPBx9dPFc$Aj#`M0mqer1NZ%}0hfbv{<~(KvJ?RZncwuEZigKajX2^Z_`a%pDu-vg zHugu>*HnV|;P8I2yKnMEy1{xTt}}hYJZg^Q0)>$ajc&8n6M~T2dR!mM)hzgR6|`wD zjFIa~au;M}IYDkJ52oqe+xbk7wN44l@M56#8Q_I!!-ecRh z9590P1R(V}hSF^ZKK|SK;Cm4W$ z`GBcD_XC6f+x5x31WZ0XwV~CuP-(^?Fsd8SS;Gm{!M219qyypEu90;qPkSpl-{$o1D~72WnaW?Z0j+EV?bMYN0183xpht=weWIyLNG^aNpL1#zZ~li{L0BlMcfL z|23__c!|#`1|2vQ#0R^uQ&pVlSNAA|q?isL5&vf$jUM~1ECT(t&`pT&M0OY{6qZ{> z`l=eU0CJe*n-t}_T1EhzB^4n#>mSl&H3;mW_k{5~i!x0C^#^3^h{K2qwetu?QuQ0W zPY`CwWwa0&$&&&N)1#&aa^?yz$HWg1YAFkwlmbqCywWOP{*P)2w9B+RcZ^^>Vm9JF zAIp2XKN|uiAL7+PK0oOAuW4u8LijtO$B4gd?E2u>e*kDTKkE@Be2&WCoYW-x(?nm` z&$ggz=z4X;bF=0j3Ull?0s9+&8#>TTDVnbalU#Whv?p7Ol))E=OC06iBSkm@kA8U!0L6bkdt$L@6tT{?Xr0kv0ClD|LLWKtb89Q~Tve*u9Tn@aWA* z3f4$xQU_6D)@3~C;vn$X)}YsS>~X@uLZWcf(;vK21nqsX-MlmZD%3l$6q86Q-m9&Y z_O%y19`rh`c0m67jnhWlWn6_jg^Cw;hB-catPn$gK!V zD&DGH;BGQ=_jMiK#VwU#!XSSX~x)FH1eJpDTV2`S3J| zmG;$x49Rv-^)1nV;9zE%!_0n;9v665hQzm!eVi0^SVK|K(Zo{sn@wJx={hui#7NLP^Ns5 zUpRtwCg8~r?Lp;c@dJ69CqxaX(a(F78%ydi*>}7s%wC9K)}sr|6YKLClJ6i zWK4@{+@7dm+t3T@@PtX+KmoNPM^sSQvqr!sy|Fh(sVtLAP_g)#sKgX5mI>y$#}B~; z-Juu9Rc@sSo>E{MuLk9Zhh)#cuAnfV{*@A0tzMLOr%rNI{Q7Zf3|HdnuSfwi_EOLKC3R#g)E&b-;V)@AhpH*pt7 z`iK5x^Qrur?Sg;&!W_Gw|BcUjG})!NgBdlV7@!IebfXG5Jqo2~;j;)gpT%)2uUbQq(EYx9O1 z3nInSb@^hwWB*wuzIW+QX!I(5h$VvD4t|z_1Prx1Y4mDcZSs$|8^=kGC8)+;eBHySr^( z6`URrYmdf!Ts%>HG9`?usAbxvsw}A|#Ve(wXv^_}>zU|&j8))~tcZY5tN(Q4lyQ;7 zzF{DLaiUosG67KjiJS>cfi|-Q%8~FeprQ5KuJVYAS@bGvVrl$DnMQH59IPPn_V~23 zKKN(~Ez@S;uWVaUKznJ`H#VCL#ARCVl41=Kll1pImjh!of$yubB9pO`LVE=fqGs_Q z*=LhL_bq`im{2 zXMn6wtyJHsY{i}-&*=fWhUR#j(eL*x*40NqDLZS&o+p8&58<`^6a78F(*ow%&Uo0= zho(6$KwBX1RrxfqvwL}XmhK_XtRt4oQ!HBoxofr;y=!9fu^@`R7)FetfSjD&yE)NO zIHTnF*kHl7jmcAEM5C>n>_2(pT!4o0oOO~@)t801{XeaCI9{YcS4!wZG*y7JZtI^3JUa&O&K+(!e@)GW6*B?nJ2$!4gr_~J ztO9}3%{1yLks>&fkwpKM!fN6j%jRJqP3JE#jW35)4UJ5=#1C+gk30f(28YOvAG2+V zTDI+cxFW;ab?2A+f--&A7lh{UV)hgSQasPwu@*S1s3VXRqa}H3>g?U*u)Ru^gP`;9 zAlcDDfzj(0R1uG0VL6DXGVl35P4+c#zp;{)6`CEIl*CQO9WO{82uCQrHtYFQrkS=! z1JH^Jp}It?Pb^`EP%h{vqM!k%MgRM32<#@)ch_-G@|9tos{TN4wmp!&K#dWogX2fP zD9e*sTD~x=)WcJ51b6&@MIUeQ$4f35@Z6#SIRuiQo#$wEJ}f!_SgM0!sscZ%5~W#n z^b8b*xuP8nZt~o&+JsHhX*^a@-^Y;vR1l~Y(JwTNElxf$A}al;rgOR62k{URX0E|^ zSDgGBUJ6@4PVGy=^G;i_e5{rgvSliDo9JukQX}{-fwz2oW}NG$@qAf?5*A^0S%6gx z9$W@}ApLqT#$I&^0l6os5#Ic>$md0*KuSDcr9A=&M05DHD@#OtA(UBd{o*MBOTfXq zx8V3@QF{f}n{0ng8$pv7*09wL`4*4|T6nGsQa}l?)fP)A)KMYGl!BB8-<~5tTNMr-<0=VL|6r7p=){;kgsl*r&MTq~d3D5e&C%-uJ* zcV#@aic11&`LS1I%ZZ;}AP=Z9WfQA@VgT4$JtAFzO4M|z3v~wU+q0CQxMJ5h8pN1; zj+lyFwzV#;s8!t4^$m2Vf-3sYXj)wZ9b%B$fmvB_WA?SH6*7Awy z<9XzDHRnXfu)!@X(-tUjp{)BxZ1U50{04qJn+^3{5FnA;Gs&rCHefDrV#=Yv5xr;y zB3}T~AnDyN?#>GeAg@f{fK=+}5Q+tvGWMR&f_1gLcsE~aV{qP)KbmDSYTMzVUyWYK zkqC6Hr9d+Rip&WY|T@*>{Zsdqje*Lj_WI7(SU1EwGux zmvH1*_j+PqSIM1&J_}NEU=%*(-%au1#+>1xRTh6lwRDQ|IzFxY{zY;Kh%Ne3>8kvtjasZ;+&IqJxMw3;mOVHa!!n8O zDe6sY(K%>Ug>`bz=)->(`mPXF$H+-RQ#Mn0I!;T$Oon+58(}#pbPjI)HPVI)!AgWu z^m|#4^nLF=mH6XxXZJOG_VQ14UWhe8nJ#O+g{=Rk5HmJA-A_t`5b=gjn6JQ+DJ<S5&BUaG_13$9#43wY8(?Fg$qO^us65+p7VcG zV&1i=Kz-M%hHHmZJLq_0P7vO>)ZG^N=Ql|IJl4Ey`(1#epY3ls9$0En0UMP^UdYg1 z<-L1xrG^I})puB_+(%G3;}zV0dd4nvo*u;x&Sz2zJ+$XrRaf7`iFg%Ii&jN$X_A;5 z!al3Nf7Eym#m$XM34q%n>JM5J-HMx+PNKP*_#zKEns`^WKnHSMdt=vEDNyWnj5+I_ zH=n76D&XGi>{4pU*O1T z*hQq%y4%Q4_LT&FMkOw7>8i^v+HGG{ic5F3#F^2RWO6}gyDu5A?2gyIer>)7_ZoMy zLKi3(l@?q-Te>VhX|B6sIyi9JhCuu=CUmlF7^`Q#R{oxMn`K8yL1D=6XwvgR^Q8a) z4VLjR7zj@6*9GHlBNZTfgLjKH2$#=}dbcT%Vv?*>T%*5EgX3u&Nm1X0d4^iMAt_VV z27BzuEM{t*C0=Db;xa-eLQ>X4zsB4GiFXM`HpB2lv>h=;?&U^sCii#)F2@kITM`N( z7On;`CKY|1HI{y=D6m!^uzCP9K+M1P)`@V=Dk9OsjCcLfGKGA<8&={4t2~IWA&gfo zYTB5~^TV5(Ivbq0#j%l@M_YYM-|3Mm8RoO@SHotbDZFwc`?ziD%#4Z`Ju{mAujo}U zhq}4)Z>3Q%b*7{>!Jr?%uvhlDBcEo{Q-S5h4(AcR1Ev>vI~U>^r?)5XSXS^i+mnTvDA4(x4QKf?dt zrQhX))$qa~lQcY}mDluh0y&DPDt6DUDBl?|mUDFtt#o7PiWkr$q;9*pAVhg0wdgnD z+?_BK+?PcSwL5Hqx(GQ8GFEGRy;j}Sez0)k*>XnuH+@>JNnT!>h0Yd3|NH7vu+>0x z&UBX&XlUn`+(-s6D!{?h3$G;D@J@K;{#lPm-&V&AGjeB%C)M67#0ye0!WMH$)~$bG<1FEqGch&YNS6xL?-*7Rcu4{l6R)2GFi-1xa*A^bdjA z_(+MhdnJbvaF)5!{j*L!2FhMJ%wWt+qYxrS+xK7-uWShlTx--gK!q`?{*MAZ&Wo1` z`|I3eNvZ8jQKz}R6)`oCEy76musGlP4qVL~imt1~va3oa4KVAGL`QJx79z5f_fE71 zh`v(ox=Eo&1atcqXtf0nnj)f?0r-$PcQkh`l8ev)`-}zEQp|HDxvS6rR+!o@U5+&U zGNAM;6(%f6Ng-Pa{Rkhu-rlt5`eHd!I1}?|39m}_eLHWxTr){8+yDffr73t zNAcBMRFh!b)OXF43^qWgIJw>X9dAP-eHf>_IEHNowb|g5hiON+lv2ESGzUIzlW{7E zTnFOo>kNP;g%68LLF(mFCi-t%$=T`Z*U0z8<*R>uW{g6UPJL^v;E47>ZU)@^M${* zIJGl7MU8Qp_${~k%TTjcn^KDIE@o&up1SMFdy}?+{ngi)AE^>^VRWQfGz{M$)#WL) zkZT;ww=OIV*kM5wS%JsWM0a-R{yu6lILyV)nWzRVUri58ukqJ}ubwI!6%P_A$4EdL8Pd?b@x_7kI4G3}8fFH#pwiPcb|0|KU)@)Cj*n@YCROjmJHw zX>vvyh}W`Cn1K@P!;E+hs%OxJaa-!8Uq82a{lc2ia;JMFC`1_=vO)Jy>70-SW!L-G zHrhc&`f83VKJ?3-k@yF8yVVxNgoV897V0HKd5+<2E$QQpGozZWeAYz-N{^ zW}6lzY(67yeD$^WootajkM$TxswW6Ms&7+?&}{)!<*|*Wr)iuX&F2{W(}XB-{)Bht z_6E7xYUHXS&8&Ogup76%Vf&KpKVp}2<0THc2SwH46~CT zfV<>ARCm|XvL`$|2)X$%=@TrPWdPraVs@HK3*dw*061LEMSF~CPQr9OGDxp^saz*| zY*2j3igNP#qpP&tE`WPgrDu7c?OAZshtYdeo;PB5XH0uFOPGU(H0x0zxc%}+X7CTR zUkzmkBgoVbM9_nETA41vil0ev(i%LAK(z>Stk%@JWb>;t8~qGKJG*OXTsb3V#SI^Cb6LpKpoy*nJiLrtQC%g1 zB*JHt$E^WrrKvDT9yFlVH6DYdwpEl=MT6v~u^uB-J4?};%AEppjtqx09WZkpP26DW zu8{8Q7?9sL!VI2k`KkUVnf|zX?ZBWYq)rKtf1mC9_wVz34q2BHxLpbz5hO@*dk}O4 zYR^Jn?78dYw>4;7CZ%%~x3Gd)ZqLX;9&qlY62?$|b3lO9X2U9EcMoFcajPLjiYXpe zIG)qvjFH<>v~lD06v$TIV+^s(d$ zrKY#(S>T0$4QrP2juSe1vj3@aYT`n8aR+2hbACgy7cjJjITo=D?rkCRIrn}DRB+V~ z$KdQCrz_MFoQmvZ$Nk=d?VoUMj0XaDSUTsS=ecJoI2c_6Dv*SOkUQ=bBUA4gFp-J1j@}7=jBTb z`dw}iPq$8XW_W{;Ur)6zdArr8p-QJ{a%GPaDnkn29b-jsbGCx8!3+gy+sFh2T7+env5uBt+(EE{^dmqlh47 zjhimRGi54ML-nG%D#bicEhHw3oUb+rmP>Z z8M5Kdinf`Em0;x#&;*unkeP3D#;Eb5eQXx53926Wy4tjB z1$`%~W}%Je7mIWEa@=}pND*duna2$!tNsWWHLi6Vx!xj|tN+&;TRb@r0!SYoMmNYb zd__i7JLe*5FGi6=&Q$D!OfwlyAe}#K-icf7`pHI2YSS1NF-~tShmQ~=XneDuuNNm|XJ7s}-0NUV>8Np?f?@36# zj&*Cuf5%i#U>a=5yHFz_2Gn&QbxM`6C~ScmA{#X7d9nAgk_f)X#q@%?cuTZZ7T~W= zCqE3(*9W~;DPJu!*1H-bs7nrB{adqAx7dY6C`VkyOnQM9lWC5SX|e9vM5P7X@C}hS zNPE^XuLjDjS!{B%{CJd+8d1C29stt~yoNRDy-n;j2cB|Z{Tt6teDbXfjo=jASw~2U z0y+D@{DMP9weL40U?5wN`@rLBj-V#XzYlLl+m3V%FJIV+4iM_HI>xi51DM&nVIMGaczIzj zY1yGiEQKX)Y53%A*%1)@`dn6}UR|ZY!`Cj89<$jN)zg`Vuu}f*+)aeC>AL$`!j2d- zZ+$HdofSGop)iGEKZh(sxagk4!_~&;++Prx72Z&^nQOzYm1lU56X?#$903;CBG>L4 zwnPxaD026^h|kRNhv9_@*#1#X*BX(TJg=CCpC_2(cHnl7a5}=Ua(b{^FXL*>Iu_eB z+VScVk8|xj(v^UG;_3Ar>&8)_|F^0?#HRvb-Ok-uqw>CJ%XY3X4W=Pb%Hk>V2M({r z`$c#8-w-~&!eeJ%K+I9qrxQ1*{#SC}j+S?CiB@EyQ0;Pxdq?!y9qwK|yTU;Pt|mre z+?zoE@ZnWJ1~((k*i_&Ehmt>l1#V?7F@IS7@AO49FZznVpX^hI_{IiN)kevH$#}ADsYXH*0IStnA z`hkkw0+v;H9PSz|)}{!sfWbQY(v(xQ*=A;rUh^>zUuYw-6n?|F#U=a66;5|?eHHAJ zmcUfq?xZgyS#sJ3N(j*F%Oh!kv=x(Di7?kJ_WW)(x)&0I=;^SB+kkunma7@}{U^t$_7rZiqNGT{ zHSV5h*W6`C2zEN>jKdzIrJcWOXZYN-X)ktO=pZo`s34hKXTb;gZCWrY3sTg6%fSnN z@vQ<~a~*k5rn|~^7+-z=k_r3H3J_Z<0bV&^%5vb<%IN1FOVxe6{{CHoQYL!FRLMlo z`c95^exF-7znJR;11F53lpnwSLPGFbnk|EmHut134sN^-Z&4>TsH?t51R=Io6E7T6 zS~443n5N-#$QHn5F85hWXo%ta>nU@$;5R*wI5D=suzG=MXea+KQb4eVV&f<_0152V z2@#FMic8E0%u3UFR=%?_CfAG^?Qtqk{rluKdKBzV+$RAev zIn&mA0Lpjv@kRoQlJ2hkH5radzB90vP#n*#vQF3 zd6J?pp{X=;V&ulnmxXTi)f(8rl^zF|9M@G(?^UMFTJ_cVzbH=b0^-^GR-1)1!^%q0 z|2&s;R9NlQN$z|`oPRI5H#7)g^5s4`LQ{@5aIIOJz*ABi!N?l3YKLn-_T@)9zfxG< z@0yPe^5m)xXOgmod`JGIZ@#wBC_oqddzZU`4!46NeTMs;VxS!G+8B4MZ!uTIV4DmO&9N8> zvv_qEuY(Z_E<1_`d-y;T6X@T}1wAyLtDk;$O&j0%s(TzL60yyYN&1XDjMh+~oJ|dI zm}+d&qYRFD=bN|K_Kjviyk`N%Xeo#vt{F+fq%7(_D(rb79aZ3{hb_Go}a!=gi z{b}Vn4qgqR{`7e%?c+?1NUVo1h5$kO%#hs$l(A4k$BwG-~x}7mPdqmZL@) z@W$JbcJ19Y8Fm2<0jH%~Jcf8e!LX*Yj&+BDF$j%>tVR|j&1SyeUe7|0(v+WnJ` zJk>=;eVAAg41TXf=maHb$QPO|7y}B4 zHau5-kYi;th9OQckzhb)QlT=$hl`>AJ*~}Ar}y*r*Gn|)R3Y0~A7zFcdDl#Lv+;M> z1}{X4E)L)P*G}p@vmAg%~X(|M9RwnJ-FFtFmQl$m{2 z4;e%#^7yZQHL{OXMD=mfNN^=GmRFsWHMg?SZb33}<6FBNLELst5CU3_z^SkPi{MtDgx+%DTOHkSY4w+-0L~$L0LbXbo$Z?f*W0X4n zNYSER$W4ygR>1I{X8J#(TS$tAXPE`|)!_eW=}DjQO~xYNVz4}9kY#@jN}da4cdtP7 ztI6V;PZf5y2a=d}?$ zm#(9gI;?OxXvU;g@*)U!UDo*a2P;+cM-(}k)*N#l4GIv$u%Bax_&vJIl7P@@jbNB2 zE5-2fR)}+{RT=V=C^_`vBMZe{C2`MnJydW>}9C@D)t6c((du zy(s8>KC&xo(HOwD+0><)gWOUJ@^61yLR@`z`Ddu_!%;*(hmvj$MwCx?)^3E2=nBPk z8DjZE`V#{Dp9_j@1K33*NxTH7iN}^Q*#!O(bMeE=|0*}~v+PmosWDS7py}5GPo{?{M!7GBE%r1OX`sv1<*5>U z6qDanT%eIr9VVH@y`4Sbo4O@e&jpJNkhKN5+sA6qQnWdu6+Murn3A{ zh24OuMDDi{q%io~nV3q3??y{k=&1zMIagWy;F2I&@4E-H4HK1XKY{;50^|P_y&s>r zLVDe6kc2tZ40pHR%A*!hC!0K@7+}}zd1KYnMF)*t2#L{T`2o@F{nDmzgTvk*bGuEt zjjdhczS%(|Uneio!<^i!wALbm%QXWs>gZ97nJO zFB`b`h1bYF08OOf>@nqfu;)`N``-`om<7iN$|#7z^w=(#P3}M)yP^{4>oaT~1jUJ9 z8T2N8lIxLXMkLnC#GpRxt4RD*?KQzVY#$rq6cJUM(9%^0z6l7;Orc(chzm$R51&8_iRUP%4V0*1y#$HaB(I59DsO~r zklN3C3!Ja%A4CoF^G>>~4m#Kfv!gD({GxNbP<;GQ90p0^MYJ$+FnnJ1NQ9gC;G?Ic zXeQuF3xjwS)uU(*<9-S|31|KJ!I6IRABamZpyY%GeuLyKih?L%nfTi!&9aHKvDqGC z_AHX&42}!JiwtY8V>)L|~4s>dnukvAP6qmSC zn0gwjb5PI6!f0d3bM00biYm@+%^LV|i(+^CNE_K+xHnZoy3lr7w^z|3Y=KX}$v0W< z?`!Ofgu;d|B^NJ!CbNx$`6x!^24POdBlh%j+g2}1r&+p-H$uNeN1JePC-u;3qu(LzT3J9K+{=H?v(bLne48#A z1cZkrEPlidHm^nl(fio{y%9GIysc2nQR(asemlWzI^9x6J~MJvX~*i2n&AR&@LOD) zNZq=U-`B14CXibvz+)~LZei=a9cs?1cO50HV|uGmvrDb+4KF| zP$ubGQ`qL41KcQ>?Hs?OLM}dLaNV!wCJ-RSRk!(>m8)SaAe%#5Vq#{Y z{(_#Zy$x^@;Tt`Gr`%qYwLDT7p7#Q2=zgGy_gD)eD_ry^TqA9+GZf#R8_x(zcD$6+ zpe?*cACog^CFDB&a?O~WnE76Q1DBlYL$iuDFsgx)=S#uWVPclwTVRJf=?NFlZ;L2< z1RFp_XxsbD$Mu^`Y{g;!o7O@VIk!m~2Y+~bK|U4(07howtmqD0)ES}Hd%2gN0YGd~ zSlOk<1va2D+Xlmt$YaAWwFiit&LU$1uGMP}bG00@$^{2U8pVOJxXX(Nw9+2#JOHDK zQ@6GBEoLiIZv-W^(=Uhw`m7>{-lUC5g~?0bM@;h%E`l#*IfXF$K9h4f%FyPG(Kdwt z2v5v$g8rGiLjL!HY&0)rTaUC29XhCrw^vX4J5>q>O%SrH8DGNkU}G1U@z<;w6U1*z zM8o&$H14!!&{uUo9fPOrSn032tm6VyVF{QzsOJFe6#A*t3I8>~2t$w94O@z0t#TSJ zHf9IC?AI-o8Sf1iwIw>byx5;&W(oln+;aZhIp@2@R|`&7gX0UbVLEzY(bh4lTXh3i zu#oSK{|&dTi(5wX>T47T5@&sXMPMDU#-HDOXX(z(r+Q9??Ntx&I1O60j6(9|0M+2X zxSj2yD*E)R_UI_VIm(Pt&CxJoWtn>JZ)5LKh*S7_wZw?R9XJSe3|8j4$yg-(c*iW} zZ@G?1zw$RJ@jP=cY9qi7OXF*kvT{I)3P6lSi&^R20(AP+BE2nrf3P<`Rz|UTaFfN?P5SyrW9Vx-<)wZxQ=G~Q=K}PBVttQ?{ks22%&y&5>SK3( zFOO5<7Ll5r0d-nW$SPfWZ~~tkLA9ge-5kJ)JPO+87{jzW^a=$5FFv5;DHye#H|BKy zDAv8qS4RVSjc+IlKR4591=ZOucB&qtOJ`2BAU%RT=ukq-TVnX0y|F7qt%SE0m0XUV zM4GitHb8z4<<(>G6S9LlNB!R{=IH2G3iZz9uoZ9ooNIvi#r^CnBop{-XcW0D+gp-# zs5U%21lQvlzyL)95Y-3uEH@DL3#>6yw_vvJmJp#$|H&aYRT?x>YR07&{o;`K@SW*x zT1h)U%}K<4KCavF8{7z!-=pL0WIdeCnFF?;+@l!+kb?TGCucKns$q>&UT6#r=GaY zx=Z84+3>_K)WT)W?dvA$&d8fXp$5y=i!xw3GWWcXe!VoInFw|8;IrvT>ogtm8!n=R zT6Oc!*-w-oLqAt66Q8{bXyXe*fo3>cQ!OREP^@T;sZe^Ci-4-Y{*9SRp97f45l^eYwZhl3iTOIDyOw znRjjO_qpGF;OwqzsYv4S|UJ7dh7PxiAp*(7`4XXi*bW9&#y4NJlcf?#jj)E zK3@){9G$~`?87^zD}j{#0-=(++-(e!LfM9DrX|Y=Kjlj_(l5J- zv_uH1_48TJ;QN^stCao_sOjq6tg)b&-Q6kPztT2TP;gRf4v}}CvzAr(l%QThQ5q40 zG-J!KK$uJAfa=~c4vl?+r`-E;&jgR%CLq5zZVZiCA2^h9XqerT)iM10lf=kHdIw=i zZO*plu4-UR#-tTL?uict{&UTJx$p8?2U$!{SbyWw^e|XA5IqiIXYRrWB=5?M^^GdX z9TPvbZQW6KRda4mg`(tadtzrtSE=2?*VHO)Pkdv9Um4GPOrQ0zy+;viVjI{czHz3< zTC`g2T}QpXyt}{u3Y7QX{-b%Fah!EQqS-NP?s0Xx+4?V<6~;KXI%_X)RL zfw(I6=k!)|{9Ti+C?61M^H3U}A5`o-b9###U#Opk80Xik2U_h9$#W&p1lMlwR=lm> zQgVqaF*TIO!i&|3Pgul)_^oY3Dr$5#K59Y)CgdZ<-wKV@0J;!+w06z_)$Q2PH1GG* zHvP@Zy;&u`Q(T{lJB>r%D#|p)>qM8@-20lnudg+$5Xuyh+ZI;$%bK84mD;4nd^Thm zPn97dbR4(!v`+DmX$eLz@;W@I_B1I>}#Nqy&asZ z9dABEaJVVHfZezq(9X0nFW7!8u%#-{&Hr;ZcLvn3yMin-0}%L(G!iemHco2q8yyN3 zxas|>yDOq`%CT3mZEm$MBq{dcb}z}@hN@(6KeB3n%RO}ti)iy zAKi9$YGOoDGAVydr@4QrJ8zU5cV6Vj@f>khEqG9F5*l3DBH`}Bd~zbZeUbHOBW@Fk zY2@+i@LdbiEX+A^jWAmCIlU>vm$r*1c9J~5)J+Sm{8;**>b#YEyI+1}hyqML9BX5%tmrzZr_MRc__<9+eX>16!Z<7LL_ zPQLZ8#0p}%+n0v0zAQ>IW>Ze{Ti9>I4P}Qd?zV{r4|~>slWu>yZw=4_wjO?xa0hJV-;rP>ga#1ILe62Toy>(s`P+GBIa4FCP55tLaYK zL(fDp&(2}X$wWC3F`1($7Zu73I<8`%Ks#BzrFnOS^+LdWMIrwvnT0VsWU?!WgS5wz z1Wh)#F4gr@R!uU=Y89`6v`X174P||yYF2LTzia!s?;#es5$BZ9R5jAlo3cA1B;Ghb zEkgI3s*^AW(VpWO*bIA)-Pa4>p8@gb(~r==8xxbICAI(mzB#5gXUt5I*GRL^!(+Aj z_kBjoRsp*$BO&)WOf?QDCjtfT{|~Hj0SxcT;*CWPOrppSENfU7CJWJX)|zB1xj+A8 zt+@w1Rbt~|&8I#!*2ICw&Rl(F4(4VS0L1|m&p|R1rcH1J9^2rZ2J6ja!@kByeP4l6 zI4nda*oTs{j!7S?OoC=jQeiMh(gbw?X!j2fzLXvX5Op3C7d0PLGpI#M)vl^VK}6D5 zm-n!$JmvsSwwQ_>IhkCvmNB_~v-dKqPXTh619+XujLX1qK zKr&cp4YBT?!I)Wl3f^oz5)OnEyErJ{ktM-;RPx20GVFD&boAH@zQDG(uOu7kaB%)q z9xxI=eQ(`+S2}UvCtfwxvZB&=8rXDtbQBKTt8n-`6SJ&K(5M_J;6ScKqzDr7_;d4J zbJhwpn?2ix%mfO7=H5Ks@FV!#{yNClmJuYn(}Wml%(*DKBX*TYS#2caJV_0*9}-dT zaPX>5!salt)I`!aVM20pdz$<}&wt1bBMx>ogJ$wzCS=6@?<}+&H+6irlW6n+ZG^6z zj!?#l75Brt8x>mZlu%{J*n+Se!nyfi$Xl*VQr=Eizo%FuZ16*5uOWS zHE><3zE%qrfLVtOjgq2LS7@mN;nEYc22$@MP+$)QtVJ_UgRFIMt5j&L9XASC(og>e zado5SR9P!rF$hv#zCRV8cJ74C!eO$>#C^z-PhK$)@b}!avI;7g&?Rb7w}M??)|%51 z_$ite&n<+aME<1z^5Q%uNqQFB82!-@R_2?C`+laeR9(FUDw*s)f0j#vfuB0q65%q$ zC7P>`2By94{Z^GcodDXO#g2^A48*>}R7nY#+iUCVr&kQDLgRevVNd zI===jGsq9%$Ju@7g^z+lJ*2g;*;7RDa+772erd9#kQNQI%`k)0n4wY4~ z1ay*bGD{XL8K3+pv+_RPdOraEIc5KO+^lrAP<|3?=Tkqk@)9Fgoi}ptc5<>EKF2Qr z@1m4zT+`MIz2F?f$3pf(h^K}kp6WT%zR!=(s8(e`pZ;M6rEDcFG)O zRmo|lZv44ExM#pbN&yuQ)V8C1tU4oJ#qb`>LhDwn9+N1su;V!B81p1bD0Yyv*O2rJ zkB`SVD+z%r_8J*_-jjvgx}{M0KPK5|JaphefYLn){MwF4eD5(o6|+$XaOY_@LD;PU zk}b!LW}N>W`9A&XUH4}Hy-CS_E|a)r3cIfw+LCstNK!8-&hgjC_>Zg(UB2$AUMkFC zLiseNaNnpG+kfJe_B_7n7PC{&%zeLugqoH*bK$CrhG5xeunRK>ciZ zsV^OdaJ(ZH#!wvvKMz*67f@XRbE9AtHwh32N13fAC;l8sj29n?Ni@o^2Q<9#{2H)l zSs2CmKjk=Mlx(-krE8&HC~XP_l~B;2fRkvi~}Z)~eLASUGu(CQ_X zd3Cqztd-aQTt8#u{Td|8To2rBdwoq!B%^P9(Qq`asRb27|%{~I~}p?SYU*z0@VOliI0Dv4Ha6FvQ0W?G5P zB&rKnM=BhIXgq&h=V-Qleya#7xOy2i}->q5)t3BfKW!RT0fvywP0N2)gr*org&^Ze!)K0u;B)%pamwTRfU_Ih0IFy>ImQdE9-|EWKY2F7_3_afjJfahSk8l5iM|kQm4FZnEEh?4X zpDrH+mZFz8&#{e3lk(LFO=&){6}gzCB`=9}>1-;y)xsh#(GZh;2#zUQ9BY2bYV1Ts zu)XN{i>N?74W{4-=7V5<_C1Y!>q2_7SW*kac`eg7$HDf`P%a!{8d3Z!m}%pjV6v8_{be48#ww=d{&6a;*rMRZSgH5Iql!3yR*$JJWUy zK3ONf!PB<+{3;F9{zf5oLVra9_7tp%2is&ziBq3f?}i7ezmz~VvjEx2R}I89#Glj& zgHsoqK@gr;%^Lna?#1(z^!ClJ=S?)ZvA4OQ%v?c|m_$wv{XWmJe;28*OEYD@^ZAVt zXgvhY7YxuVzbxs`W{d(H32e|itBq@F$!I}NF6`2V*C}SyfZQ$hN+}%dQbG7e(xw}a z{c+=&xm) zO-Z9KCu&n^Z5cd@k~nU)4snSF+nsj|c9_ZdH+yQVz`g3!WZJ0_k|Ib2^Ka@s*-KD> zWaEyGUXt$blmC38nX-K~wMXY>P<{SveUql8NQrT*k_KiUnPzX};rK46h{Jm4)ithR zzHbiJ3t*i?R+S=RDznig*W%7gpI!}yb{?|r!ut;^iDeia4pjG9%#ein*`};$)cWM2 zh-1~$YN={j>YZEAr{67>D&MS6RCje&Lkcf&YpGpo2}o8;g}vhYE)uTdYXItV2K(F; zD)bw9fX8z6Qn$HC>@=VK4#=*HL);-)_{H(xgE}^=l{b_uRmm4qTo;tV%=P+&6nc5z zWgxE>a7@Ff6p2P8JVV&yspGPK{l!|tf9VU3oX5uQ<$8QeT)McJ^rc19(di$-%_-j} zB`zU2NFK`KaRB6Q=qu;_hh%!)rL%Yy+i9fIb3_H{g3~*zHm%<)+0 zic#i#-L&OCk(KZHXDfy~onB@X;YT{F{1lp2_=7msq?*^3XxdA10F|W>l;3+KG30fA ziMw8pyo8&^)3<{;&$)yyKB1$Pu!=7s=T>)f%XK@8$W)HY)*jQ!q?hKTqz z-|URr2d9NOF4~W@!Ke$sYk$#jZ1~e<0I0Ek1mjEakzSh@#m4aR(|kqT^*b*q%$#qS zxlK*nLJMCUK}O5n7Pz?-&6-o(>>ch>@&W2Cxl#wM94nbP6R6TAzESdpxPdhp0#bPD z*rqC{Rf0aEVjTvQ2Y_rG3ZVwCgR4Ay+oMJf_pW3=CyGkwv_AZK&Svq$Ywu=?m}BT^mqECBA09}w1>jQtd|A{gKY6tSz%Oo=siUF^AH-7afw z`fY`EEXo&>X*I_YVh9Pj$ct2U%@(ZWf(9|}XiaogVdCqGFnTpp!ka%5Xgz$(l+GvW z%Q^=XT)2strf*G`ADt1kTc;$4z5xPTl4q%o>kG1NhZ%@MVVI|LAB70YW3yZO*hs1!p+Myby8T#~;kj?|OUKuxx4IU;4gmmYgfN7a zeZ>t_IV)+g2&lF451x{tdr|*GcSC3ta^Or+(_yxyu|7xl9Wriv`g4Gd{4Ge;AcWB# zcbg?Iyp#tGI~}7hHx%8-39%T4n!M1I3*MX2wpf#uM_}_L?kw6ij&11Z&M%T~G5Y9TP^8_1#%}+m z&n1qTVJp~#^&2!SXYq={$%JLx+JF@+)ZKsQX2+r!qhwpkVy%~`V^2^|t|47AMNhbQ z#xw>hXW>x9M56upUhy-va@k;sA055&&`UnJ&3~ z=!(1QF^=jo>?B#dGvh>;Hs);x2|Byq8Ez3`^l8{~C%b=?jo_P>?BRk&58n9MFbz5y#Fl(*}0P z{aA{d0QG!GM4U?X3Kfz6QrjmceHlq6OZ4A%Pi%p@dT%C6qmZQCyahOQFWbbPQ2(MsRB?QgiXQ_ zlJ^2Wa3af3+NUK@^+12NW|&tGC@UCXFhw8SAEoesig-*b}Qu~x{`VM zl11QQrf3+nZShdfB4$11lrrqg^9shi4mMN?(^61EGx&!l7JSfO00PK+=dUnFBh*I} zMl2L>naMp+6RxtC(!0Zh?uX8mo<~|*kZbm4-VJuLkj-p#bMeL;baFO)pc!;7q>%lnc-AyCle!rM?uiN%RmrY&-MfkIM+qbBi0+_+EY?N zIXKOnGIivJKU#C|03%&E&xjtJ$aYjRQnM9Dlp_jIL%{q5)A;85)`HJiRIB$aQf?)e zSTXN6`k$1Ef|l7D^Q)C}6h%w}s9bd_OIH+KskiB|J}$s*#d`>4EGMuVo7i@XxNlODvh|VjTbB&J#2S6E`AFBySX_}+pm*CFtUlxZdSbRr z^0Y{W%+4Lvfj2O^nb$ke{U+}+=eX5Hb6s-Zc2`Pcu)^WZ{N&ve$IB|WUAQqhgLW2; zLOoN5#!Rol-_uJw`fk5=y>cySrnC<3(VAXT4Zs2H>8C4wu>z79H3S~Aokq6TvmH|2 zG1w8$q7;#(@IY(XpRsi{XE^DC>bjh4b%pV3h5@J?l_xcRlhweFa*+k5hpS_Lu9AkL z;d|HB$u~|9KZ)+V1UBw&MK6kU_@HpZsGZDZ896C+YVWG0D=_6h*i;}U1no!AYX5DK z>-Ox8G%9u2ib0P6oq2$S1fFq&x7>;>;X&n1oh#Wy)EMWae-!7RI7C^Ez2>&sa!5ex zrL|ix=>r!x`7k%zyod91EH;JzxL%cd6&q0%eD%-emz|&&^DG=L`EB=VdR&RVLSEl_ ziuXD15Z=qXqcQQ?=AT) z{T^&32J`~g>5^PW-lpu&4P+AdiGw`t$eplr#GGP#2GMI}9qRURbINPpL7Ky#_ij7f-Q2#svre5Tio-rt z7iAs4-4z&v{wV5*0uh+OKcFXM+2^@aZ@fPwd$yngazV>$*GD1vj zG~=$f)S03Dz4a#}1=Q2U0S(C=p*{qK?ZwH!aWA$PE5X|WPz4dJ^(up0NSH5mo0fWH zncGCNgJe}ilg|8->-BBmVj_+32VX%d%CbB|hLi8IkPmcQQY3!K14ZqFQm&brKh)Vp zQzCUI10myIZwstZ;@z2BhBA`_hCz5J6$wPBbT^_%{qfBuqZl&4vX(za{6$dIFh-U* ziMqUzGK`JsJv~*wwc5Cah0z9rtX#Qos`B&c@+1e!CTzc(ErgZLE|DS6c-3mRqyq%5 zCpTtt^?$vS@*O+iv11fkDg~`n`xV1WR~>2h^BF@lWLY6RGeE3GS4gs7!v-_)zlpGe zdQbTP-TEE4&^CY++q|ZTBU3RS1A&l5P$)M-2JY0x`z2AX*bv6W$Pah z$P`21?hh#)<`tx-Won|InzTO%6XB#d~XtFO`jbqT!aE3?m(nh&P`rsN#*F zlg&DVvo(2F9Zpj527#{frQ&R+&RcTDEzSMTW?({^Xf6iZB%9=GEY$PwO*pZcAA_*8 z%WwqHwJ^wT1Gr;{OfgOb{05Iem%m~4TE3o{>o@5M@=%Bm;x<%|7#IkytnDYa;QuL~ z==`0uvt1Fd^UTd8ylnBqL7XB+k2`s6p|F{=C|yxZi_RP<(nR7jbYv% ziu_5}$ZcZap7`3g*U;^UIwR`OKbCne@%BLwi_A27GMJF?;6apnUaS#fCQeS z;}bV@ImBO2qgRP(=zx>r4^2%%1h%s79vVS7o1q_zv_f|PN}3gM`m5Hc?OSLmaotyO zPUge5o>SSMNbWr^i(x90w>c2?cg_vV5~p_~C^RjU!GCQBlTrzcGj1`mH|m$&Pi#Zge96*hb5vZp)P+lr>dpoqhTSssaIh zaSemgkwg+D#CyQu+}O{pQ)5Mwqyd9~|4x#eb(n+6FXAdBL7Rt}jG|);VUe2!ElX_l zP6#B#ZIfQAJ770mVF6_Y?nsC~P{{_=^=%2jCa2K=Bb8}hHFi8QNT!8|?&&(j7w5nSb4hgrbsk+4A(a zFjfv>9C^iFPRIG3vEzKqY4q3ZfISD@=a!t44v3%LTqUJJe>Vkoo9!DWMan zWPwSgQ$`n8d|#<64Z2Ft{1{Cn*u^cmG|!(kp)GXMPoIz`or}xW8LZ+L<7j2QNO(}q zKhd!}@33aUR;bB;*kZfzJgL^;0&IeTdkg?eK(xPSswKq?N9E5gSGV)+t}=|YG<QRws6MS{b5UK$mPJbXzntnO_=T;I%n z2}PJr6~L$WwIc$(@qo+1_Yer)Zm?j18;!}zU&@G$ zYxMGQiqiqn;Ldm!MKzux;-#y$_4e>BWM(FcZYn~q5cV1d8MJ10JL*>T9b$lOKyjh=-~*?qMsbG9E42c3({M}* zTe`_^^zKD8)4wmWGfomdLh<-k^8F+M^{0$zFab~uEKvEfBErpv3U5m?9L|;GS`*4H zM2rA-c}TxeArB~zw({Q^@=HsJZ5>(V%*dX@yXVx^YG&|mU;%aVx{EVEhzz9AJ0l;s zx9dk{=5Y;KFy}=d#5FK>N=IWBtKo#M-YZR+;h&JYG*&yz9AkATsb&i21_3#c3?&Am ztx;BnZ}(_2*EDB;(07*JG@_jHIsm0;81?QI%z427K;Fp%<#9Br)z&EL#5KJ5QS)zm zIu@|#M*p)k`ggqDSfc?002JE+=vYUbu}PL2YTxU?o@P9%MLPU=?E;39v`ADTB|k3D&qs?NlD41Tc=>{&4W=x z48DT8nPwIg9-}e9s`DyGFo=Qxqvt61jUg2fr={=~lwIHwd5(iqzyhyypk(3tg|VE8 z1yhOZiWD@7QJ(vJNpV99#p@EQ!TqniZ{EptDLAuy<;#F@%z9KZhfE8KC>ex*>F2Es zaw(k@$gKA?%B@Zs`F0GiO3*&=BHbSY;8It<$EQ)@(R2o9hKiujcHG>U?FycxdulCf z%*Fo``7P8Pkf()*OyBV$a?8e@z=DQ81h%5mR&|`FmpG`FZY+ixQ9`~+6YJpGw4Lb| z6HjVsb#b1jr6?@yDI4>_^hJlSmaLz8S-Nz7K@Woik-nbXhI^>6YtI@G1H-R#SloaM zFh&lqtP{x=l4$odW)a1Cn;s|OEsWv;sRqF>3~Dvv$0V<~-zNY70wIt9I%Bf{2_OZ$ zlmH)~001<1kzu(h2ID86j>-%XCv)f=?hA(05MX3F|7W4Bebv69U=iVgg)$Q}VOb#3 zAU#Jg^=~^yIis@)9nNC`J7dqj`lXxhP*!f3S5LMP#{pQ}XvT{Ma$Fs(Lt3ZMr1QI= z0OJ_5HVwG^Q8YPumCHj7QQI=`wXFUovqIHvH=)jcUs|Z|V5|tKHGu(mv=!X}sLxVg zJ;Lka1sjE?Q@b3M?;eDIgknIjh<<=U}yC zj+*cs3ugH4x&4aidp(?0c=Z9+^xAcLOAkOAeeD1M6J-~T2y?1ik>Z3IXY;{o@BuF5 z03)Sdav|5Ux2uok>3q!J<^|@=%CnCDLzAnjGc6rXw|X}aYL)grEbJ8B!s$IHWOYa? zl~eu#o+%MF@WqLnm-aAeln>(wc&Hgi#jYwl`H;VFj#V|Xuq=s$jQDKW1T_#qKW&2B zm+S34yf9K8*6rHV*P=jWgcX;l>^?4I=D%>@QU$U~6_VA~9IIpw8 z5wmHEPO@DsHWWe#L9lKFL@$(H>boEaC~k9GlMN-c8i8KK`sVGXZMMa)$}o9 zs^|QLYgIV`o0tpJ)pgSWkV>VV%H!Tpen(NN26-rMHg&k@%h`yxBt@Mc+C*cD9 zLHTfUSfVlZ?&peDT?-1rttf?3VQ&A976Wh}dG(4DPah4ZoH=ZZH)FZSUPb_l^|Y~8 zZ-mAX$*i3D-jd7;s0g0U;-a7!-!C!Yf`?Ku44Z$)gQvnVoPYoa*$|=ttlF zE8;`Vz&fe$Q>`9VLRQ<0NbnJX`G|aVYOO3#U96O3M+|@+OF8X6c5-Ch50Mf#or@-b zF1}dZlR~-f=ArOi4~5A-yZ$p>)pdw85z#`P7S*hTHyLY+A2$ZE8YPi6c|m!@MC_WJ zmIl%mnhm)>R|jV|JVY~yUgUJP5A1pp-p+1qNqJn zs$g7QzfxyW2ZmjJ) zK^}C}&i0nn82=2;P|fyjjGKvbwG_~r7CK<2J-x~V+Q~}A!oO3}kBrD>f_bTIW+o*+I6`##3+8f2p6d)ZXQc%!8f0xD;S-0dNXSa#I2Nl;SjcwqMm zo6-o;+HGnQrPuC07J=19H@W(ehyydhSQ7uWdAi$v;=AP1xprFrM-xZ@12clZ{Gbqt zF5^GQaK+XD2tHv50pL`RB!*DXP`6=~_pIsw^h{s?0c|lgPZB~zbX33rO(b!3_N&RW zSv^=v^qY9q>r!}7{r22DeazXTN z?z2F`kRbs;BEFD{(c56_I|tm53&p9dz73Wyj35B{fC6>OoOQ3I!K3th&=4(dxg_T* zuvHqk?)0wGP4|)PZrqeKjBftQ6Ba{UNWu^B7CUS!OC{CJ6k|YL%o!Yn)T>y{=Z*vf zt~>%yU#uz(X}^8%_hpZL3?q&MMFYYevj?o1CO#mtl{BRKc|Fn+?w++lxmvdgRr)Wk zyBGUVj1Xcj`xua&E`eTB?e{hw=UtQ9i2xxcz#LaH<7ex8!zx$<^IE69b`LdyKdXgJ zlPAj5Y{=rkIb~`%1XIS!8IlUmDz`tw#WQExR`PbfmZ9J)XT2uamb_}19`d?N>RL+V zqjdCLo#yD?hag{~?EnTli)c^)SPnG-4g+u$zzUDS%<-TjWN9pp271^S)mKr3%eU6?yd}#B&_W2CB{Z(m$-?P!uH;OjAlV z2G#NMoB{IN1AxioV~-F$`u#+V6zgS@Mnw3NyBwFiw6lyX46`%6s8d#K%) zibHj%Wzo@^5sN-MAcQ9p{JGChD-lJ3T*g14N=Yq0JZ&WasO9Chw7zpD%fLIe4aW(u z>!`T^m}5UvIgDI6R{%}a#$^N*?!a&j-&LW()03qfC)7ct8exdmuX{?r{5S^+RRM0p zC^#a&X@Mom9-E zh>XgA=lu@Sn-_q@Ezy2|w-T_$Ox41#ltw1vAs zjPL@T*dyxvOGNbpXS86kC&ze08*;cuE42a+`Ac$c)d3@Gc}ALSGrVR3>ugpdbr{D5 zVZURz^#r5iZ?-;Pw6%6kVh3YJZ@jiA6P4Y`s-N4@`%9&$`2KpLQ@v6TJl7gH!mB04=_B0K2LX6+B9Uo^2=8hcx7WV+jrfyJ-x7 zz~Mju-7x3Em5x$$!A-eV^S1~z)zQrgnhBJnQ6TU};4$Fp>VTi-|$8`zzHeT#8o<)AR2EpS2VG|@( zkuBU2wFzs`X|t)L4(Hr?s?$N(^)A^hw5UxETu_Ji35ZR+ES+B+$k+Ns&78NByX+DW zIc&Cyd~+7=0@Q+A3@iK3{kTwg_*gRf@-N>78x~x=>CCM1$vYPh^lU)?Vot8FmMePv zg3FYn&hJ_V)96v-ukqlXeyr2$={OB#Vo}>+8t6+<*%1ynssKwOoN)-C_jI?(T2I4u zp`jsZW?UbMNDM-zz*GuJtbJtw1NSxVqg7g*3_3RMA^zRnWtC;lj@)@ErRqnC;EG{q z>JN~l`vH3a&tE6k@|wA#;>B3cunZnpN1>36{2cZ4=XAzEN~T+YQlWS05WdgWBC4Xh z@N)7(_Q?;REXaLWJa8^(?xZ?j2!emQ8nb%_WHd$5aF1oVEx(ihaq+2M7Ni-N+JG@< zTcv8sb<*M- z{8))Wi*#&8_CvlN_{5#+1r94^rH8(m06SDsc6;=i1OYQd#3-eL000rZ9fF7_Ccps- zk(Z)H&+{m`fPn4+d^4Jtpuefh9qjN;*NI#l3X8xGF-IzI7$y#?bkmHnE2aPAu>wPt zUq}<7Ue4Zv81Y>3Z;@YLuWMP!PUY~laA$xIkpP6fvdBQzZ=KIP%IdyY)8y^1ZEl#W z9SI0__LKTBNrlT0ZaTme8~kkp`5*td-L!>0Sy$u(oTZ%wc9+as?YGQB&Gi~vxt7Im zZ-%l~88r+NZep3EWw|b*R1?~bk&>Q$EbG0`mqb8Q*rsU~c3}d9SG87u?Yg(#LD58Vspm$c7@*s^IQEb% z|2%9h5>DmjS;@CoiJ2s6ta8XLy-LgsgZP5mS7%+c1HQ^0ENi?%G-tB^1Q6%=|8&>u zDqr(|{6AvSql8#LUh6#KD0FX8TQ28pUmrZeQdEp@NZO6M5UYo3{WwJh=Ux1gsQHB_xj#BD1UWqP^w4U z{0d=!kz6uU0PIqEwklpO%F9E8rw{R|%(&0+A|#Y|^^FGO;s1iB(*s75u0H50zLuMEuT1bhdP z+U!FfH`Zv~{0o6JyPHwlkBe z4htKh4sO?&8HHeAKQ)o!WE zE44@fa2n3XWxgm143%|z-4#8iT8UK50`^H{-#&)04q|bx5m;&uM*TG^iX7v!OL;k6 zPh2sL{O8uAeh3=xJSH0XA5BDH1*gy0x*X{$U2iiB4sWqb>&t{@HsCl$*nq;!Z?ox( zo|i~pnKKxBn-2!*=6#R$Nf8hd1d!AK0006K%`~fYgD5zE00E*B0008xoJJ7hHr#6f z@N#92c1%D30>4547%r3-N^xG#Ee#g>Ji{~AsB|1A>VwgA)p%}caWl2EpwN1~E+DjA zR|vnyu6lqDV)=}90zv7#YztA{@R}LPVhOeU3{a~ALmkXD(KEbVN4JKCDH_1=PY$g5 z-xXr+xq@yilS6>+Swq7b`VK=*hGmY~4x!Ib$~zV&Uv0 z+tQbg@F)-8=^msegst@DsrQ*sHxOba^$1eCN;Jje+k;cKEoNa^lZ4IGO#~uI;UcKA zTIbcJ-V$qc@?~V}&~iaIBj9IVeRYJMBxChxTe@hNx}l*wAF(?D9Z?>9U$&b&UGTwo zVr<G|fF#j|L=Hv?_ zI)i7r#)q669ek&G_{n)xghOVx`=Iao>!d=;0=Rn#_p9GOy)j10P~IUalS=zgsshTM zl7$u(L7p$(7$sNms}7H#Y%N3r^^a&yVN2l+bGVZQx4m`738|0;*p<|K2+ykGV265bEpON9d)M zE1HkeFc-Ja;GtV!bIIHv>Jyk;#)YmqR_I+wEuJ?qMai&#ux2U{kH$z<8zd1H^F+N_ z0*7qjw0Pg+UAGc;=mhGC0kpL2?gZQYkGg-~SbM)zf_#=c%)EP#%ziJ7&bb@)(Y}qh zk2S+wjPQx77Y{aoR{hAYu_kh?@Ku(EQK`H`$4IG(Iv;5+dcRoIz;H&s&!}hfU~GxW zerKx6TMmDMnVK33Z5K`kU2ba3xy#LbL8!n2Xqx-$VvqrgU{m`}v>czl7o^|~?_5A& zzeN^7UXA9mHcndg%9O=qYtPzLIv$HDcyw?S2qHPpsu4IQ(#H%9=a;SQ#$5SiZ~J8i zb3wPlN`XR^Xp4tmky8U;rCF+cdN=-Ccbl_pgw(HSfZS*VB_7s7gc01Kk;U5Ir5I-x zImz%z)G#GGoAz#h4o!4B-|WM8dZ{-NV^P6kllj)fQffJWRG&m)%@C2Oh7N-r)wwjL zHVr?+%Y#xipfCN7@Hvg^jK$j1jLW6yGFp@ReYo9V(9*xLZ$U(RVp*_OID-n|9xfz5 zg?s!n_swK=4P>1v?Y)>SPk``z1D)MnV!bpGM#Z98EFwx71-G?J@N&_*c2D^;h8`2C z3lfT&5@sabqSz2(otjDGweT|b&^)ZOWtH(9icdfN;*u2@xa&U#T7ty>h^?d}I+Wn1 z*TCD6y`8BhjLFBA5`G1IX|3lCdAaDwMRZBm@Y8d-l$JUtyL-Z0Rha1T-&Q=qKahqY ztgoHRP}#Ry{7=}0fV0t$?-+N#(ti9q+Elwp8zKv+VFSrkQ2>|Kird=S8pH(#3VVq= z<=7itn;1Jxj)Jex0Z@XVzG3y^I4NMf8ygwIAK->55Hvhx1wa4*5j_U1 zYGi6zji;sEk>K)EFuo71& zi9;suo?Ew+LWhFt^v6#3UkxnlO=^kK(a4OSHgJ4s;XT>SzXWj?CROf&_H)MCM)li) zFXPBCX$#|^jvR>ZW0szO;&2GaTk2kWDIYsa)5hrDcu(HMf_jEpNQTv%!M9E!1HXzk?*54qn(WP;M}9ytO6 zPh=5zo2vKepLRR2XR+meyXV+*$ca0+63OSxAO=a}6R;poKa%f!Ac_-q1JE0G?LC$U zAn~OmYj$PW%oFo4xC>NyhyEvB7)L^5kMm2l9@|T z8F}&lfv~-u6cfIq*YUc}tY&zDL+H#(ye?EAwefn#iX|)PO$_t5(rSB$U6s5*Y(g~2 zIN8hqKfkjPi77j(F@^+mCl2<_rGB>vUTjm;+ZXur6eg4Afm7N;J8D^uhit+2UAg#O zffl3Qv zYmBhkp9YiYeh-ob`TF9(7msna(OsQ`Ag>YVwjHe(KnKNkq%+44^-oE5z6Ut9T@LaN z{xk~PjHueTN*Km1XCH(7q&;4(=JvUlDZ}a{lZ)g!(InR`3PlwxeuYzzqoDs!A7?kq3%Vpa)pb7Kl#@{_#b&#t z)0FRH`;PC)$a!EY>S-~t96-5Fn^zvFplJ0#7Bb%y)i;Qod3(JV{!&YnMb}|%iPRDL zE*s`D$UEP3vxJhP6Bg}zKdPU=N^mS&#+<{KoI$e)VFnNCK{SZH4VhmH4;@xE5<>>3 zJ|J6;NGjzGg~RrZ^Fo(ik*+_h*({WO$3l*W*culEoy4wPr|~a=Fl#5J>3|6f>#gri z5~GA@&MUxpRuxnHe=$LZs{ZfBRduGrI0Ux=Xf$(J?hV(VX>Ig$&X3XXF(F0j0D7w* z0nKHu=6@vojU++O!p+Og$wtZo2nr++icUDj9Znb^eJn%9q5zK!Wz$xc9pRk6A#PwJ zT z`47X+J@IvW6xBoUDc?n~&NE%8vMWMv^$Yf2Dzue~JA%Lw^%3wlzyLW^;+a}$fB*^m zhU#?HNtHd}gUA3O!0}Jb{@iMt4(vsv&-Ppty|d_fq%_F**`sEhFU125FUQ?5tx$=#0VdBpEncBx zG)^atST2&M>pjISubphc!~Rsx2Xzi{boaTx@s7{V6FJY+TsmW(rJaoY0T9;+*#M0~>y>3wK3-xaGTi_s+R|AP!nxjt) zDPK!8uHFBIJFuKOZ@?*UiSgq7oM%p*T;P=w4~eRLBszwZ6o9_oQScggHvh}oM;09B z8~EX)JSCn)WL~Xxn1+B<Ad+@0E?|Ze#qy*f z(@9^D;BeJSf(WPAA^E}*jTuTK_43nhu%s`g;TxqosPwZ+RKu`Av-_rnR_70^hQ$_; zl$L#9*Kq&5vUi4pET^K~S;NG<0t5?MMda5Hfn5^WhJI{Zva8@J{#$R^w!t2tMURdT z{$Nn*s>jMH{(01{eo z8SlP+Dxf+lc5qH|3!RjE|JoYeoujSYH8FS3w2SEJ(<#Tg3y=imP*01;z!?>XFW2++ zo5tP}rrwy&@pepowFK3A%^6X{68^{e4PftFBlZjm3_f8Uu5m5Sq^1G*j`pRdG$R+i z%F@fp_?9p{Zd;RHd>2moP9ubmb^3Nr)U~S>9@{Hpm-rsz}HgCn^xGH}fX!WEZuDa{} z=NF)khMq)s((B*?dj2Oi*^g{niP7k5PuFdsxK4WwtchuYoXU5Rleu*jEL<bM- z&CE11JPu`eXN->cUqz4HeQJ2G><5`k6+STCJhP>HZA%)-EzL*gZbdDQs}GVQc+qjW z?(?mUq_9<~h17CS_c|z@P95s_lyV|tRSeHr1jpp68tc;l{&WXYee$WO+mUgfdNFDV zb#U!#`SJIlJ5BK0PZW`wAD{FRz#w%-r08qGIt-Bl&%{q>5H>Q50%gErFbdn`K5qEc z^D!u>HdD>z?GnvpZJTy5k8!Z)(-_X~{1F`^x}Z%M3`Mr4RYjzpDwt9j@FgEo{j>1g zK+E+Z@D}gul%5JQ*yq4tcoiqshX6rMkHkcfiW`PIP2x51O3tHm@S?$_{^xnjZhH5X zTx5i^*wk(PBi`Y zRn63C-e&HP2xM$$n0Ij!>_x2tD z;j?~I`2%+#a!ig#RPHU}U9^2VB^EnO_BrtBG!#Z|ia7TwG{m>qvo`%e%=7r+vUxCU|a}Q2QBj_Hf`h&NS8~Qcz!n&`j1u5cg z48x2`O#92!DDmJ_`D#NA&6Z-(BRcL)0&tAxAa|>AJFtD^1O08X$^Bfi$T+SUs6IY6 zW?dcZ*Uq%E8zob^6Ov;S@ptOozQ*<>i4Dg4p|O;se!hwdgzo%)9b%8hnk|W|xQ|Uy zga0Vrw&BZcl-DhC$H9{lIU~x{j1Ablc24E)OesgF|(t&NbfyV|x z@=k37WBbNuT5}(MvwfFiF6;HpJbe}~hz*kE{5-8U<^cOn;HPzt?&xsXkb+;uq~vFC zP{3QEXO@8rmzwLx4Ow&q2?q%01ut@*yuOtAx*|C>s0VF!)~2Yhl7n|FG+{o?JgzO5 zF4@tnsFR)kD$5bo<^>TLL6f6;h>apSbaU@-`h$z}RN0-efuqsRW#sMyc5);h16;(?` z@V|sSY9CS-+LwAELbcRx=qo9UrApV)ss$+6l1-%dZAWcHhXsOT*JUtGrPMnq#`Dvtv{0uy6w2lV)xfdo+Sh?y}jK@kivtPW= z!V_9hTH*Vvz7JgukN~iXIZxz9oL-Ll& zC_KRyxJftYH`a4H--Kyk=0~$kdJ(Qr$5m_v?OD(=6O9i}BT>Zo{LE>NTW|D4nglg=VuqRHvND6X# zuK*RgQU?%F(5(+&vFM4gBvcr9AOu&c0003L7dxu+|KgKSYEvHb-Dj2^e|ThXesYXM zt+=yS#m9bL^J(Hw6F0{UOry!+0Nx)!(di=5FQg}=FEK$_CLXPY$uZ}XE6~d+k;S7| z)gZ&o(h>)SGMJ1cF(rnNQP{T+5?MvE8uyEGi=Glm zQ7DkjjSW0rIPs9Bfy&k{;?mnv>-BM{5!2Y@CZLdhH{*hnyP|NQc=X+ zJ!_IB~C?|l$29Gjkgi=({73mR& zCT{(jKUTi~3b11)ZC=);GFdAg*5n}hi#TA57u~kKCWXIx8U%#bK?D3l-CKe~apd!0 z6^p*VgL3yj{ketk_31cll(w{P9Sv2vu0Vm+M{)~mZ?xHN8_kIk7NFu-@mGw4or_t0 zywZ#hgmLmLOg(G)NcbhSQ>sX~9VL30p4UB9>dVqbUU5N2YKPy6$N%7(LEnEP<<=7l zm!d72@;xApJ9&s*Gp5*X-B#ge`g5S@s4IFawvsB}s(Lx^aa$`ukD|DvMt$R`vyKXX z1feL#Mz>s+j`p3{jaES{#=Z})?8Uz)fvEFcJx^jEJj71Pm$`Ur#kvLhNL=#-unQ2- zSE?8Zm86GZt76__*n=ugYebB9m?;yHIf8qa8;d~}7p|C$liVP3JMm8_52ikMm&ksu zdYjSWF{!V36K{hG$bAhvo2{Er%CJLcSJbOFiU++^YBcg4@OCfIn`Y`K5s18D-^6X?Z}uQzyTI z(S=|_xQS4+n706YCPuJs;0?5fFta1$Q6|jZ{ds}uCP4KD( zkRX^DfCBDbDbiloI6m+vMvc9#L3!LS!{|YO618sE?1&1(KzX#96 znhJ+KHSqv)Q&JS!#V74MJZn3*G3 zyJFG&j>>|=e8r38KD^2?v51cd$r#K&(UF~+N=zZJ9tzZ6ajvVz{~Y&G0aw=wx^gpB zS6OhxB}yr~iT*eZtoVFXlDgq|iywL~pAo9zE`HmOEI!x&$g{UsXB9E`!4%;ovC1|7 zl?mdinFH4%pw-MKg_3Z!%D|O&ybaEw;0mv?LdXhpwGDXssBpIrCr{&RZIDGh{O1bB zfc^(hwFOt3P*%@+20W7;OguQ>^3b9|G0@-#0`{RI%tL1(_6oo6A{cME=NYpqqHaqb6|`i}s0 za|XeIh`|}Q^A8GCM152ctLFr}G1J*eD`yYV8fz_E z_QRR3|MmK*O?OTlashGdP#VU2FiwfugRA@0|67={^fcSr3hLz+;Qc}yQ{v-Z-Q6-t z+JY@Yc`&P&b(0=0(Z1nY1_qF@So55=5WP33 zx@!~@d6&@F@is0@wD$0FnLSj?z!!=GDLeQ>(!izlZ~? zNg$Ja)G1Yf1^QLEn)=9y6JJP>rLF}T+i>*D^=S;7t*n`%Ru9q-1A?5L!fx416#7qF zl$*;`P|=5Wr%|7s7V156@|YCN8r8(?;a1fP>@o5vSjyiSkcC#wo*BF(j(%vfc=hYR zspRM#?j`p6c1ej=);lJD(?d8Ta`i0I*SEwdka^D_R9u<4g(xE96=sI_#S|z^DwOav z&^Yg75Xu!1K?8QsR{L6&jfgUr;!x}}rM0Cmg=}KqoSzgIy28pU$@odAqvH)H%@ zPbCx9cd8k@KAeCBY!JYphn>(PmoahYvNwN>Dar!kc8M?2mcA~gvIk5^kwbXvqm;O_ z?+37eVZ~v5;%DRO^hv zJ~*mn58Xk-XaF%)xDR~8^#XK%r`(Rtk86TLk9jK2$y1~BfPc7Er`{_LN?3|CmE4^v<>bS!cl-lp09hv; z!&=llHgi-C^NkYiK4UQ<{F~v2rtv<0;+hW4_~I6R#ED+-5CGAOCP^EHnEb3@T+-7@ z&3JGv2!&!JhA_RZqL@aF%9`4mx%5F-o^r%lAS~>fGrQBTkUO(tXQ$I3*=t03=N`Ip z4hVRpMG->xnPA?Wazax?A3_Unim@vhHo+BRQYD4Jk=5#4py5PlxC|5q+IrTQY+n@1 znNliVK8h-}l1IvWG<>YLt#{4}t#Ln7O1RO;NLcJlCh>)f#e2poI@=4h5cP`jweM9V z3i4N4M%40}NJa5lJ5iROqSB9v&JOtwReIJy%f{A$f=yK{hv?T5TvrAwuYN=RKM*qf zrS*4EuQLz|?U`R#01h5uqM#*yhVJfIuh7sK_5q&5kru>(gA9Ka(%TL6_E5~47Mdua zH*B9jSl^SEm?wg4pG~5U;4rsG$`+|ev_e@lSmYy~M|h+}2+xA7Iaq*|?kcuF=KTY7 zym&kbbp^>hP7TUqSGCU^C>#mn?(R8OH7diBnKRAC{1h}AaK&pD8N4F7C zOU^H*K|dQ2(_cf4H8YF_cNS?j_8R-0nFpGwM8Uv)HazYz{haK+@2Ij*YracKQ%O642 z-xWoLK(~@U*K-k#Q=h+4Nvn#%A+*`i+b0tksQMT(fVWv*pdxWs*cGMj6dxvwS zbsvw%6H-r56g9Phq8yHRq$ip?Q8(66hFF6hige!BBi30o#Bo`$Px$5K2JrY6NLxp@ zP^K>gjK2l)0n{K?8Ljnv%z*jyU$O%9LwqrbulHRYE)m2KZC@CO0%IrdRvCA~GmeyO z8-?CZZA@elUyp5l^&4n4qs^@E$Lgi4u}5u$pU>Xa2-rMNt~oE#H?d`t+sUQ%b4ggY zXJ1#vB)XxBRi=EL*_+@>!u48j7hjN4ha}8P`Gpp@_HCD9Idk>5oTLrKRKZIxYHGyP zR(t<*#+tfp3v8I)R)#?VA)HcQPuSa~w+RU`gTz~$e*IyKWVv;boe+PXH(ZaI>@VB7 z<1!9CY7?k~@R19OZy0#B0wUFv!)Bo{sMp5k#PN-N>WFU|yz;QRI^}iNiU>q#3cr|# zPYY;8r0M$iH$8#nbAIF%46cRSJi@(+7u1oOVeUK16T<$y4j&Vq=-0=sz(o(MrI6neC(1hxOt{EIAHCwFf`62#{F{ zO~(}?(4m9OI~|LVSZ3tycQY==)T?k?EC-|R5vngdajBrmvl=E|%$S>ppYP;-=Uyf3 zUp9URa>m3#W5ir&xK(`>boe>CgX4qF^4m)^l%k3X%p6=lk%4rnVhepHcptyNFn!5? z32kkunBv;*j=|=Ox+{zsNqxhnlIY;Hwqa^keE?F|-^VV{5D_!*;(zGJFi0a5VG(g+ z*naF&LNe=K=$oJF^5bz%K90A^gzjKn80^401N}OSacSmWBI?lM9k}%pg z=A~7zAy*)D8Cdm3@a{opEEV+)9CA__H&Lj78hKw=3&puP7j_wtmU(Ac6Z@7LmiT1~ z$krHX&2zI>m5Fg`W=;xkX3c&_SJw*nb$H3Ys`+|ad<3iT3tH&(ktXuoF)pw_Uz+A- zkjXsK#1N7`Nsd`O4GaSA0cUN<7cUeQV&>i>^3w;D@Hk|ZLq#dtcW}_VCj(*lZ+@=h zwU`Y;pT|m-Mc!X!`7nM;e4=gob42FuH;EdOIlT)az|DKN@Dna8h(*G`qC%AUP%8<# z7fS!p+^7C0b$)SqO*pPa?ltz)FYMvfh_$JQ$~w zg22p;fV#T$KY_p92DOt$J<>geHW|Vej@yzCqMAuvkm)mm>V2^Yu{h{8gg;sTY@f&q z(jCED1+mY=Q3#pLLrrW=pKw0E>hfimcy{jO%vGC}&4O}#XSjKkKv5%U6B}4|H66~O zii-eu2&g2cWkJhHa&8#He3YL`@Kw2SE0D`oN4r5p8eWP;^5Z$-Um@t-eKzDgqE`?5 z{?-^=MUVU2m|lh<jHIAGB8Nd7iPabE6zz2<>) z4MwFKy;Fi4W6_mUtzj?zxIjqK3uUS7=~t-_LAP$`hl2JULAc=1SkOODOOM6Su|7kc zD-RvB<7D7jAg`NU(tLGV{3=jRML=<2Fnv0pAEu+=-vAMA+T8e)i^vp!<I82NO3WeE{4?-N%^?1bzg%Z4geFEeq(Gz;UP-XD`=Nf9%k&l@6B_oLXJ1dS zJnVFtfrsWS5&2O!dYXom39SK%P2Y8Fzex3Q@n25?G^48Jl<YSqz;!r#P1$b4#9$2I2n@_&mJpx3&8q8Rf z#cLw&k;YjVm=<92?|0Z@{R2@HaSVAcnK%TDX>1G)u*3%`XdA!f?Y%$r#E+DIzYJ9? zn~lTGu;zO%@v)A8^^cu_q8A0(Uu-HPHGDIWN>|lSrR8mX&-Tb_E5zD);ril1Y%6$c zBf9cgsj#o3bCGHzq-}(_61z3mjzd^o5&KYBo)*JuSm}frhxU@3I*8Wg$*45ZN64oM z`+_=0k4l$9&R47N@q6msf9?{~lGw4GyqXfAWjRV6?7b z5j$ZWN-33s+?s^Jzbs|Bdrli9Gp&O@;SY)KmozyX#*z#+uzMgo*b3f)DLr%Nejefw zcr^mLPq8bKNmAD4{jJ|w%jl8>Xw?!1Hcv&WLM^7u;6!0E0q$)xy z@}`e@Ea!}dhsjC+oc*yMrU$koA=rdxI`K4cH|Fjld%mMqL=T@3m3H&!5^^he_45Y% zxkwcl^E?1EK+M0$G+jp*cF97;T0!2fZI09Azo)iOhfd0j^2y9u9I>b=8FCFgn+s!z zu{J(^HA&?Dm0Im?>X*aClSV6N`}3O&ZaZb;scn|_Z6XS1v*nS9|E^9GTwFfSNSPU& z{9P^6JbEnYhzm7{9M5D@`NYi5w(h|T{gy-=&w(4`@bZ^@Q(NBoSmaQxKO6r*e3sf) zqea}i&9q{;PxOLs8vQw5$OIJGt@l$^XDU;7SUtYcHps6Ydl5rI$E(Zibfy;AczJ&| zpwjXISLD~Jx|SSO7Tc>CYr(Qc4(Ka{B|TS?<29eteC$f8R!{E7@yF*SZ5p3;8HxYXWVH%Uj8K-0f=WMOPj_FxIW&HW zF_H4FGMYi&6xK6!)p}OcRLRh=o!j0|wY}{XY4U)ta)(ft8TDz5*!R(YqerUx zVbBs+|rL9laAt3-u{K34C5tXWj-$t=6P9xeD2Lz~4E!=!*f%IN0&;O#eS zzfeO3R42DT9OUB50Z^Wq87@K14vL+Uie^RXjRh(3@#rju51owwZ1gSEKuz5 z5)nvYgE#m3F~cB_@%%#L{ZjEAUfcU5z8wa_9s(jM^qkrI4nOeemN1$%=c=NqWg(4P z%w0!w#Kl!?fsWF zaYB|z0hzV%6x_nHmLuiP1t!hAX`?%_Q1^^ZIOPEsG6ULEQ@=2dEyK$>;=-`djh0UV z4oN#+>788adEqr7Pg=k>ll8pCCof5c<%NY}Bt-_bW|Xp3B>9!1>qH?NudGZpy}HJv zn7?8hiMqQ3GiDL*!4<4kb&^gp${OQ#AhwF_`29;0C(uL4COhDz0zEhD2zcD{9kg>L zG;q>|h)5YRW=PoO95WlbT<+AW?a`W8xZBWu9Tv0f#qDAlO9u!Z_C_u|Y8Yo=DCI_jQ8Cw%I1HdS1f} znLb+fz2m(W=T%sV5aT+B?0{YWTqNjlw;)#y$ z5}$FvWdqjyY5O?ffu%#y0LlcM|z|Y&GpckH9Gef0@=XZOVe*@fo5KFXq?1#5{ zMiEFiKCkZk=ELINPQFBlCd_1F^;Ed=mLk*|kF<6LN$XqP?foymUwdGL_Egx)!jG}d zQX7f0TDPT+l6OJG^KfXcm|c4EG;v~%0`SpZT*w%_&7r-<2dYui_YI90+-Lf5j$A3~ zJCrfZeCZXAgzX#_G$d<#_-|rg^c+4dYF3P=&-e@c?%gxeIz7>B*imXeKj-+CyNb^h zLEpZ^aT1_(Z{iG3FMi+c!WN=GIcAVe_+{5%b!~&?f~kN6^&3!>Ce@i-FbIHyZH`Oe zrlw-0;!VF4snwBc8<5v`HTF?rL*7&0#o2#TA3QjC^-p?ejFMW|Ef%N4kOI&jfX8a| zM(%S$Ee4*6`jvC%-&J~x(st1E$vLl>Wxg}3E-9~C{fIOI&=BUCx>VwVtqD#lig{$~ z-fUQwZpslI0!hq5A)mzmcE5U~Dz;dWIF72DBd?QsNLAmBrlitC;fZ(tF30a}2Inj) zKZ_-ZMj1j^j;#DQQ<>9@gY8(rN4ALPM7W7OmE(l5cTxyJ!}Xk$XLNmS?IKE zk9}0*n5wtB46bEyS>p@@PRKAxTs_TP>4X2bJ$9u2xQ2+y?e2=4Nx+GdWMc7_x?(U& zw76m3Fs_thzWJ3(Y)OFOa*-}$lT7{o3BPNxjBx^1dRf1+L5U zooAhHk2O*VoonrpnsILYA-S^;zrl+V7mQCbB_jF(`f8~7TrIpgar)2?-6Yj2H{1cs znb@xhPNWg+x$72>!5g{_2Hq^N@#sn0?&QK{H~8q1*<8)Yxm76ee~?S(6UfgJz1UQ4Ko|bVM_C^YQ+OqhT2w%XRXW)g1cP{WRf#Q2=0Niw+B|WROi_;PN zf$TaMwTyB^Yv0DyCSL>bhLK!d(Pn2=y6;`f7&OLf^%ds4W9h_D6Skfj94)S>8j`uE$YaTVL6v2208Lmy0UaWl z2%Nv{`L6Jzq5?@0rqPpla6+3&b{vQDa}uULjanJgV3 z?NltLItwS-47j>afA=^)%E!#KlpIK0nUd#bAe*?#Rv`Pz(on%&p4!C1TnS`c>v~%m zRmLs8yO3vu!|k3I{^)h-xCuNzRT}M2IfOa2o*-sK9@4h|m(0l4C@_i-aB?1k5aW$I zR;RYH${grO)0p|}s|YS)>S(v`G1X_AjB8~^KDdj+KtSAUMydV?-$f6)z^Y^H7yq*U zxE&8*tTRy5I`lKQ1zY|1$KgG)+RJ=@2=o}yw4OHOY&uh6t0{QHpL*wUU-3Ov8Nrzl zX-YgGNxuz4r+kOACDu0RW* zyp;ev5CrskY?Ji4wS_-@;(9R$6ImbSlwNvjeYM%zDBflvRuK)gmPMsd!;|Lm88$F} z?Sw!m-|DGz4r7nS?oSA5xC?kqGZaDlNgl&wpMCWcY@+*G9Ls;(TD`zM914SgQVjjoa!ou+KGkfXgKY_KA<4}N=7_zxMA&k>6F`{;FPOq+pp)#z|5xuF==602;8xpx5 zdg~l-Sr|Gphlf0!PU$VQ7qd~_{1ZzCM=M`maV6EeDw5eb*e9+|Ri9#O=KDTvBDy&< zNnEWJqM55La=Tpa(u}K}+%#g!d>6|nPVg5`4}OLkZCllxJWplM2UMeEN>*`<5G;<6 z4ulLwkQ#mt!^k!zD*8(rv>$S+%p(Rh6iWj)zmbp`QlA0x6{ucLZQjsxT3)lTUGwqC zRTndVW0)gi%%>l4O`jJdAvxMbD`qcu7kn{Z;AX0ikExN%4@okHuRy=Dvgb!VC_6v6 zjN|<+r!_i;?&RKlOem$^aA+#lMw;cO2xA&?whQO`3x7ve1)lsuvB>G1PIy@%k#M+c zQ0*BP=MB+V%kDoGY&P9idH{PF)dHl1Z zK)KvXiMiasV4-RoZ}xp?i|N)~C7S+Jrv3~x?~p0DF59zlr6%CWv9Y#Ze;78X9qBE1k7w1>N?SDzl6echk_{Hh8^b1^xz}?*|@1wmB`Vt zR0XY$AP~&?!Gr{(D0+3-D^$XRr|kx+-e%CLF}i5wm=TBx(tBal>fA7d2C1J-C}t1N zSxOyOu3>oxQq<&Wo+w1(JHPVDPUo$+JSNFlELG9f-h05?(3|rV|99e+TWwzZR)7LQ z%QVgKD2MawmzQ5pUk$azv+uig^ubG<(-VXKrX4QOtnH(pzlUnv*Pi^#Unt+8`ijxj zj?2|doH)s;ZD+>R$b>i&k#LHH*cgMB0(x%CxLqAxTDWN>VL}G#f_eTPyH<;gX5SzZ zd}b)!HY@82(l*g`@w4Se{pzmZz<4NIKeyWDZ1RZ!b&S%~z*VVLEDl+ zHTB<9#mc+?AdM)eL#PQpSRtKl9o*PhNVs9L-ovmaoy-pDFDiAt`!^yUea9neXj-qY z@xR^if&_<2#!G3r;646h9j9Tm@h2X=$P8rfPJRlz2}%@zt@pycqPq}zjtfAoOSaB0 zO7-?L+Q)7kkmH@J%mAEBpa-LG{?f*?@QwfCltQB77fw0Kt;pE0eo*`J%ybQ77mq|k znn?!fWz0MV)#1r3D0buNz0oez@^g3Lb5IRF5e{Pb$ogI`%r%MreO#;5Z&QB_ z{Rd> zL4^Ok=7d9T>n%k6@Fohzp|UU#Bpy5g0_5ak8iwZ93SdG7u*9?+P%t|^iH>;MsPUWF z?KO7AaxLEiL8rQ*Z0>WuyEHlb4jK3-Q!|nk7uezWn)I$1@;2; zl5O}I%+#r+xwvUNd*J6AKh^lk{ZRa&=~pQ2qAeOXXRXn= z8)p)y!3S#{HbzUp3VthsFLZ3Fmb$7FHoAGtvaq2$q-@#nw zPiAHN*)7^z&qnk^28R5fIh~Ntjr$&mRA-fK1gR4|awVRG$}Z~)Y%6rN>J-4#3nZ&D zE_1{id7lQ!)l?5UqVeH1toU0-=FhBXh`vlnH*!blsrGR$bM=#X25je^r4JXGh)Bs< zA`5@30e4qEuhDHn9)8WL!XwlzjU0KB9!YF!faz_r2;KaIdHL&EDO7e`=Mi!(20u8< zm;o_;-(zYrMK`m|$YSOdSXuz>5mB_#Hlbe8^M!z%1+ZBZ14!5)-RVLh7#3n3w-p!k z>CnSNNGjYuE3E(2t^W}uWd{| zLEh4u)nzl8VUm(Q`oEsRYHwaSUQbt@w2+kc z&z8^EM|@c{&3RrO+XeOUh@x_x-pC7%aqy{(JOsxw_SEmFslCFVg6T}Qqpz2XQ7s|B zL!Z4KD3=y9;U%4`Rn%Y!HoAQ22p_ zwb6>}b8XIzTzNH83ZjW2z2=~?>Sf>SWxN$d#xp=thY|WQ1GD=+=y>&;TJ^C+nERmi z?wm5GZ{yl2JR(A+cmQxZO@1c0^R@8Gh{NuuIwYnkrCpo=o22UO{tyE z4aH2P0;yEiWuKSdDRZx>P&p%VGY)mz^y z>fIcFDi0%qha;_*+0dLM!ypPcrTOM)kdyx1=q&ALQFd)=zHj=?>ow2-Q}5~GMX#fG zvK-39cz60Z!CYPl6Y>zlA#+E@bj6nGg4DF5@pmcHGUkM@fpv9AH5_)95T9-b*^p0X z^NzzcOO-T~ZLCTSJTVJFG>Ny^(VBr3^j|GR5=HyD>iGNpC;LEUaZW8JqN=$b%EE!vKdR3?!z9TpV*N0osOMFB_!p z%?n7;!g*c}>T%sdJQtnm&^qD<_%N8T5p1x`rbOJtygO*v*Nz#)SX3B>F*BY%0#RI7ua>O?=|b%!;DmhctsbEK!%ge zb-c?y-ms$o1GP&`(Fw3Yb-IdhS2;13!LI-N<13-oo1 z`9v!ihTCwTAMg+Q3eDOHWo;T6oGBplex^%i!JA~2xR_)ft$p4o$g!KcUGy(tXY7IZ zsI;}4Mnp7CUVoq=u}muorjSmhSOw`c%HcQEzmbt+i2+Hq_}-@}WB?Nhmgis*JluYx z1uXem51D0oh=AHVh;#|}_Ypsi$U*=d)na!Mw4=~Fm@ya0O^i0)VyDweS1%60)h6~h zMu5&}$-cKI0j_+Wx;*fdJUGzKcYQO|(X36>LZ?7OdCrD)XSK&()2vi?2x_3(X1dTv zoiyO+6i4Hx1xJ!{T`CaGczPyy6hj*?Pu!`QW}-L;-92w4pPoyWr%n}^000E`gqoTpt+LMBgu3E>1~ZeD9hhUU7t<_SrT3PW>}j=#DAL~%r3+6W{Y zYJ3(oU3jbjR4E_zE-HU$%}h2iP7e*wrz6~mGpQK*>YeS4yA1H)DMFoMaJZI{N*1uK z&zBJE&#vN6UD55*t!%8P7gtED__7N6&>vj|J7D(WA>ddx)Md(OmeR)}+YxHk#_2)w zyVqCtmLpq{RTFRSE?C))t(ZzoFpCASk^)X->6A%BOyu>yIqrU)(wyU#unBRsNYclMEI|J&%3x8i&uZnqg>kz< zK!yw*ivgId-}riwF2Ze93cY&=j`ZLe|T9|JETNBumrW>$ON4lT4oA=m#tqwTbe>vTL5`;)M zGo6YTQq2GAl;k+$)pc3T_#5uMwxK-Pq;HKGoM%vfjBJ>@vg{=@W&?$lNKn$ z$%~#;s@(Mp8{@hyAY{rz0DNz|T1DhLbGErkPul8}!&f|g_cLUW^Cl}~IWI$!R!l+> zI{RK6>!Ru1_}t7DTsTdc(SKzbu@Bt6SYJdb&H`;a9XvfENp(RG>h9xffChNsCDkV6 z802aMolW1du*}ATrPJLUb$gJ94;RSj+Yp#gRo3wz2<7+T@BJ+g1n~zW(Wh*0_#CpU z8GFK~4{G|P!sgY{rWah@6T1B{u0E+{tP;6+=LJH9ejN+zyXXQ{VrMohVv&#*+5rXl z&ycUIot>!|yq31>z^@97K)=O?x$QyIAZfMW9R*x{W%>x94qlVg8`g`A+0AuaapVH? z&sb%`aS5I8Jm{IY<7FYo72P7C+^NPWM;HC&@$aW-+c zSr<_Y?Zf^=3W`v56-k=OQVfxZ-Mv~|;jL1%nc?hFGDPFYN`PQA8- ziXFauf2d=e+~1xV_&7@3hOCQV$4}G@LOIWvkTM17o##` znQRxUP65#Bulii-^4K;2Oggb+SuW6+$yoodefs$OU(dMae|^nw+g>puH$$#D$zwd$ z4KY;+G7D$~HAGo-`N{5giYIGc6sX0A?=7@Tr@>Te7Ltd;Kds3sF);o^>3+;A0>Jno z{yWmXA9&oS0(oGbZZp0OkGh~IK}rcNu?{9l*tARrFsjiE#8qp7 z*hTS+YO%jZg*$A5Tkzpu@G<{(q|eC*>nMim_$&B!{#t+SI!%9 zA8i-7MEQV|N<5Ro;<@to2#ch|46{d9{rW-x*?(Bqveo-ke#;04F$bxsBgmmGItwZ*)Knqp?ALM z!o$!!yCAzzdhT8p!bpedEP;FG1G*1|IXFh5;-5ETPTF6fP>tYo45LfMe2dOR4$WIE zb!20kUc;*XF>;P`HDRn;;<+;ooF-;3B;LxIE)`X92D4%KnSExfzxWygVw!;5%VbK# z)vC25eamPnicYf*rIUcGiA#o`Ap#PX2-z#O$&R)1Gk-?x&hjM$mnD;`54}WNWs{NC zH?W`n^nTy~xECR#jrm(e4h%QWLrdX;dj0<`V(>YmMT32LErSm?6Cg6v#l9QSsQUw} z<|b`beDAOgd*KrNwgB5lW$P$GxmCm~vShx^l3Ow(H-->*DPliqBecQ(k7?!bIUs?! znQbv|3x$iaejsMI395t4_xm5)T}3C5l>Ba&WVD72@{HI$(#`w+=*}-Hx7foDM6QZx z^OobIqJo!durXFE}C&oW+})WDws1gyq#o-V#LF3`$P_eV7!2!sa*iU znsBy1>;&Txb=y?trwr^I(Jtj{lBvR_!)K+ZZ6w59)zo-P0)RA>FEJbK2Fe2*AN$6F_aV8Q1kLf`|xdQy)(`eY&`tk zol^%&Znd5>?YDhzyQmw zN!+ohJp{Dpx=vTl!cb@Iny?am(u`@RSC_;DpN%HsZhFZ6oz`EHHdG1mkr4IN6inSgV>@;{hQ-DCa)~TY^FZOUr-5~Hp+P0^eE7~udrw4+okmSbv}c=g z7q%~Vm$l*oL!+AiT7J9fMxNqpp@fuIh-tR@tNzk32;9#9D0t4h2X28r$t*WYfsZH1 zQ)SlE$gbAa{pGfu}Kw|O1kG5rTI%|&ec2sRRk?r zx$MfxH)%!mW`lru0}EHS!KL9SHtwxT0jLH!wgU&eV}m^2%=@G_vM1}LDBko2b)M11 z6XDX|XWPY)GBi0NdHWwQDjR8g>9BujVZ}JhK3`GeMc9+>x&tC4sVZniC>eKO5NB{xnQhi1d39LfssdmCz zj#9d-_0Ul+RKfzJW*>R%%w2U6QM3$o{I$BA3t%(nqJK1u*OrBTep=U)GCVGqxU-g< z9-X=p#96yPmlwy8zb1uo2Ol`9`r*9uhUT0EUH~Yz_U5OWr!Z*Jhvp-xBk{egn#s9* z`ncp(O74ckMu=P(LwQ!T_>bSb?Lpi-yH$yLKwYs}lzIkh=qtQ3LCG!>T843&%iXvkHOUMIaetIVPfpLiha7s1|{y+Qe9h_ls{;k)eLK zmnWVm+?EF?r(muQ=kRc$K+Qcd^zG(gi(R3QB-Hj1u@^b>s?yxSGyahVCwxango4F` zfad!dY_)A*atS#j_=6MGtH6O{Hx|GWki%_RZoLqRaUE+s+U6)Ui*iMHS)<$qtA-b} z!6)UgG5&?m6Dq?h77*FEcbm<0`$l6hrMEL&RpjC*h7oLy%6ax}X0`>Ka&q>f)Cr_V z?xAy^kM+-OVZBv-i1Iba?s$s&>~vaF8;lz2R!RdV^R5n#u`@kdi_Q+-uAahbp66S` z576L`pn8ZR9n|0ng7N90TAF_hc#$rU1;Qs)#0&PD7*{H}bsw=!%N#=pNk%=So3p*A z6Gd*4tOD`S9kC>OCWSJ|dg+1cVc?DsM=>kV)3(;K&0C(LL8NMM*4`f^^^?Hm?-E4g z;3;Ag+)A1ec_y3L7~nmd1|{k}?7_J=2`H3H(+g(P=W*k=1)Wzf z*d^I*DEgdt_f<+#Vf!$woZ+HTptuToSjFCdZAf?hGv#K$E6n=mr}3=s+9)E?J(Y%D zVvWjM&+)i&Lez#3)dzaV3+=l@o8e&VN{_QlOAb|*!|3r=jWe1=<<-PwcZgHLL5d>? zZ+}9(n|Kf}uX1n5yT`tj^x?cFUbbQ#NBk%M4E$6nxDe{ZyU(~2h(#T)M1P4t6hfd9 zV;9bKVRC;@+6K_x*3yNh!VgyO9fgUhj)e+e-?xQs0aceBX~#93?@&4zeCTnQ>;`Y?5az_!p_QF4Q_4j)N58nZ|3vZ76SauKpj z1N!}=c4DM~9COQ!2qFD-wn>wbq>A~z3FoW~DB*~#Pnmnrurq%;@y)6Q*|fpVWw$Ac zx9%_Y`d`>Pii$BO+#!&wK~z0=ODb(|>QY((nGe&n`RQ+y)D@-}?v{ug$WB0%f17Z| z7$V5U&~9F6q6xRkPA@kon;e*jQkl10rheKDc$?{LlL*!Sz)+oZdbJJUsWUQn9oo0d zX}yfT%GiXuIML!VP?pN#CErn3YYM(YY8`qTD4!WBe-!R5WUf*VK^SxMHwQ6{y`Z|E z^>ELyi|?}SHyGW6=CJBGoQpF;XD!2J?nTkkka5GQgQboLn^c;+3?^eQDgnChzM>)& zz(?NN7*%0>3adgOE%^TJ-tp`b3E;-OMY*_W1S_FI7KhS;XE3zuP`ARl^$m+MM^&c= zO{gZ2-JVfR3pZigYK$Su9ivMD)F@zqyb5ZY40l)*Vid%52=v45SZR3KMMeQq!=1b6 zN($aY_yQ@YTD;*|#Gv(^K7@Zl*>!dNk1A32SD_Z(TZvx5=Hp z1$_)H`iG9P1uS^-e*RazK;y?x%tw9N4tHWJD%&ZLO&FRpi%ChTPMZ{4s*1q_LEi8a zHb#FKk;x~N=YiI%D2NxMc5lV>LORtMKtVEjThG;s@fv>CmaQ{zo%usPzeR-I+|W{% za`|Xz{BY>-Vuop71S|B6Q%`Df(Ywh=(FWhF>~QgnNQjMn4=TW-xh zj$S4_yIePMiy~YGweA}_48f=W17J5_>{O|=;dX-eY}~S3kJNiE-+Q-BJjA{<4W%Bg z<8fln8OK1PAx@$h`RD!xQVm@3aKM=+OlW^l!2b0wUOUNa_fEQNu%zLXr;1Zn?D9w$ zt!ts3YmmeugIa1rzZD{TbzQ|8_@Cd2;y&@lyz@7|iZDX9J6i^2E392 z>fqV{aXnU;z&$F8k5l95(VFxx%9=dJ#Y7HAE6DinX_Q1|)&Csp-B2@F8(o;VWixFH z+s5{-F;{`xrPX2X%Wb)cT}v>1#1w8~ zM`OK3Fn8?RAe)VkoW0V+@vkp$kPTDYpFV0>q{ljkfj;uXvXe=#WPP%1_7V~H{M0l$ zpgNaOMdC23Luj#*s z`4!}RnRx@6eL-_`V*v<(uW`7eI-T}JAm2WbrGPBA;KBSBGf@^!lbN9CZJ?vu@9Ivu zv(z2vjuJ+KVG>0r0A(=9q`=SAxbdBfN=G5W97B7^SnF(-eCU$}1CyA*eJm@W-ueCP z|5>Z5uf{k`)(n~ITA02eV%fX4VR4-C_Sl>0an%UA%AqA?<8Hw5i8F}S_kq_o4MDUW z)Z0xt30fI8h`3h{!|YpzFNDjQ)w567A(~Z)$px@g>zXX~fV%sX_a7jmC}BQ46m7tY z5>AZ;>u+81eA7>XAOymWRoT`spnwD~_W#~A#0vg*97ZVd65>Dv3YH3b&jCea*NLDJ zNqXc9XJN0%aQ{;FVI#qW#w8C$ap@j#iNGMAN!rRiGv?^M?Z)6hojo)O#ua^MpK84K z!T8gl#)_6_U;UEXBN^1`WIEk%0!yn`lM3t3e>fa$=&(n`F=snCK}|irlHXRmv6nu% zqNt%AqgX%8KEu=k0{7f8&x%qik@h;)&FOP+K}9+)Y!R{oB+HTCa%bpW>JKrxo=euQZhww4`(12zgi)7>W z*+*o2&BC}!LQ`~(-RwuSSj>ROVrI%k=5(C`+Wcd_E~-x&RLCg#)|X-X5#DP`RuC^$ zkeqH(`Vk(P(4LR|7=In?Kv$Mnsm`kMWeMAS*VwbVnJYp>Zk$g03cHa{xb(?(PQmO4 zpU159h%f^*W9K;~JJNAZGxHv=9t1U<-xLDXonSQ*fw#%`Ifs_z;CLQ@y$B8+&Q){r zKse|J_A{!Y7~pwmQtTxPRVN;FH8Vz;m?T`wrv8&Y_!$uum7XkH^)>>`%ubhlc@rY| zxA`cJ8j$lp(-)oG<-*jtI2ky+Pe^*kx-+$TT5X6{G!cx!4#PrR#n%-0?V}`%nQlGx%;pGWMAXt56X{*ZAeF1c>_F?(ELW zmb(Z=rK`&E9)K^jO1w;{wXE)n`c@e-(*9iDPeS6^8vw>0X<7pJKbEkEkJPy|0LSnj zAvn39DcE6wbPajc!*?` zvuASib)kVTT6d}szfM=PfKaKlI(l2NFMrR>o}=oKrMG(t=uIhsBl#dEq1&Mb7-|V z+-HKaqPh;alAFJd=-h6gMxph5c)o(i$3;jG^FX}kh;!S8b0qRc)tw+Xs)fkG1NgEq z`&C2%^=nJyX%ufoX}ti017nig-YYvj*zd@M&6P{4IzaD$w5=K*Xk?Qh{H&z^$SExl zAD2d=A30oexA?Kd+k|quoL+2$2=SL~u@8M=F-JcWm^kSjn8z%zQmv0jVLtScKu#ke zx+ecQ?LXrnzlSwcLDWsF>}W82S^l!afBn6cs9E-TFf^i+KL<+)b=$eNjMac+Q}Twu zuJH@V0Z@U%z`PW2Kz||qo{4e|4VtPiXYufIm{?fItxFu2_U1rRqTAA)%q@fQ7dY&v zf{!$on;Gu&l&bjw^z9&a!PI_4Nfeq`gj}LvFlUmm0LLsw_#ZIDBC!%E)m#WUCIl7_ zhT@hKH4Rt5XyXFw)vb1YZiD93dk&gPqC~R9#XRPnk%kR8&)spOE8WqI;dhwrXj7fBla_aAj zL~K`>$FlZ&Z^;KDm%|3KM4Qfe(^rh2%rhFxU^r75EfBLUd>HJk8ZF+c)!w;#yOVF{ z04uYrNAPlA+!Wt@|E-y7a`5cB^bEy^rJ0lecbMnn=`EVz1qqhSYmBHv15CC7a{Irt zsbu;4e6wI;2{qXG{Ewa@yWufP!t}bLadrKA7>4AA!LS|>Gx zZE?&Z!Ow`k(Lip;y*R9besQn;Jw`OlzIuZ%Ys){k{b!9gTY^But?32zTZ3z z?BeQ2c-GVFK)&=9-KDXib`yT7-V0=ZbhCoYlv|AG^4?XO-!m!b^$KXX<$|sV?cT~q zQkdI?=w)Y+DZ!1W$ZEWNOSTs{zw`Ge$r%WwZd<1^!r*WyOY664%nlY{x{XKJvjfT+ zWH7mclz+a}j$!wD`gm?gossuI6Hj3qG6ex&U;Gxw#vEko2v3WrW(4m9xDG}P7(KBl zTKc$#ke%>ek#)ahZ`pj-{xnyf7^N^PL{FYhaBtzaA;b==x7c?Yn*a25Z1xslNpTr^5qg}iKJ zNqa~-nvf}m15sPRLLi?9^Dh!&_A#_$v@|^Hy~xJl8Zp1}T|nc{J~JVH;uJ_Jp2taKh(@n;TQE+1KOs4( z<(U?K5w*J14HcD(P|G;P+ubmSP~LJ%IEjvS5pAwwjxUD?lxocymd*GbC7sZv(C>51 z1(TvV<2=HPkl!!8!7_hVV#$Ns>&408uS0n}n6swdrOA{D^mSsul(&>jQGl7vHbMsq zD1S7=Os}Ku1ARd~N6tQ~RP~-DGxYVCI9t$i|QjQhBB_-&WI`BN@xUa9@{=8BQ(fq|ZXW zQ4q}wo|5lhW}J#VHM%edILPjV5N@Z%#^wZV)_kMDk$f1hE(1<%qW7sK+C;4_;C7{% zx}|P7MU`VM(9&9};ICyfx;GTB|p(l1q`;a;pT#AG)E zpjDONl`LCtQIL~8G%Km#AO!G={>bJM-$Ce&`(?IgedJwS6B#msAS=ces}8y?t`pj| zt{Q6%7vk#7z<{`NBjLIA8UO$Q05b<+JwLoHTmUkJL5nUy(C*sup3Uv+N47QstCcMV z*Zl$4X7MxTK)hY#3{SymBD39<#s>qf-+!dDHq-W|6ReHeA&R=nvBaiCd0s~qzNoRlU%jP)8mJZVk!%EtjAN^&37zG3^{3}Ll z|CtEet!oVLz3g?UDG7?LHhQ_jGM_t$p8OLDXS>4eC+e2 zA+ATudYx%m4E=~TzD250wemWHqS;ardH=JRrtv)H!Tc$H8c9;!IuxsB9mO$5oE;Pw z5A6eSUFusqdUOyl*+o|3clQ0pizAs0-&c;>6vm8GufcZq4NrLhXG|LK&QYkCj@f`{ z60lr69NSIV25DRbven@N%zv5>AJ?%T+6ITO2hz$i+XFp0saj*>PSl=Xi`4V9$;Lg# zrf_A!&4VK415muuRt=wvCG9Gpk7>}zdcJGuo-S_K$7uHbcY*Rj5~VVeoutz6(dY}M z1rYcUj@S9JUylNLD2d^qHs|{#N8cpyDGS#a(h^Re1rviM_|s0drJXBLH|{dDRT<*<9Y1t&rPkTzkpVb? zN-eJfCG05k&=Ee{#@V6t{7Dap%Pa1$w~mD}Aw$3F1pv3Ibt3E=()#Td70ILU`5tyL zOF_CCg;id6KIEA$NvSvMRh$lCrbDQo=g4TVv1*+*)TFc)VJ<{=h$j)F9*W)qpBmhY zQ`ca2(La+N*P3l(;1(=#87w&@rYvk2a1}9tSHeJeiiTM~n)ALbdB@^zm~fe?8)rg< z1O6QwOM?=Hu@s+!%+5U;YwGVRa-~pdzj=>#QH)NWW}+#pnIo)oWI&3id`0$hzP0rJX__1+j2#+9Y>mu(_ z5%VPU%uX_Wffg!Jt)xapd&Zu}0)1-$F#&vtGXG#oS2h4D)$-sYP&d7FeP)md6QO_Rw%b*Bua&?RBC)U1!XH)x7^kY=Vn$aa_z~L4NAX@bRSgX;;XTm<~m;B)TOjFmo_SeoW zifl_Dgi>~tEY}7e8p3PBe`y9e75U;zeSC;P6@%}>oVAsDlD{!-h>T@%x*|pv{>ZHS z)UYk!qU`aD==}$zw#B#$x=Sq+y=2HsO_p)!m|4z1GetS5TZ4QO}rCx8A5dmr5`a2;C01V?peBI+0h9-c>A z`0cRdz8=!)Ah+yRmdUwC=OJ~*@A*tOsq@w$ou`X7oCFQ-Of7Q5KK7qK z*9ahseV%2xc7uFmVn~*!I_S~dW(*v?xfb&L!V*@6Y*|8{TG7y#Awd%+usvZfS)oY4lYCM&c?Zo?ErSJb{T=ybS5`JAT z55<^WJw6rq@y9y*l@5eI2R#4(JWz>BZB9g9Kp$UD`2LBfym>*y!gSCViyb+6=zF{U zHoswo5{I0Kc$^)Lv#IAbp{P?tFhZBobH+ViwYJ#MHhIFCSW+7+EI!byRvRQmDp5wC z*$}ZYu>?c+Bc&RnaXiRqAhFgJP9b4EX6!Dy)v06Ex8a|~Z%6sO@>>YQ`+gtJGy$|d}g2HDxgdLrqFR2oc2lVfTH zLf%zJT~%+KSw>+?uJcU5+Tl_9f^P%N5uVMyiZ44bl3toe`p~w*&~|tFZL5<->Q?JN3MY zB9Z&x3Ji}Lb-TZA?D4Diqd$G1oiL4UVSkT1-GboBSiycLWn{us6~X`3J`;&S!Fb~U zS*{cC(MYW3(t3iA5R?P%lK_A#5jKHkF}k?z;sSVYC8t8<3~yx`TpdzTcClsqQ~>QQ z5MsDGk3+5caq^;Nr6u(LFREO2pTvrRd=&32f2ENOPH!)(*cOk^B-w`AdCYA{opbv- z0k#3IH=%t5wO>pXB7@hr4I`K^Y-mZw@~s+vH=Bg#yt^}R?|w0Fx*rRT)hmF#j6uPB z3Y#~K?lqn%g%Kp^#EZVuL)~~h^|hzUvS5yGN&iFP8|-LE;&Q1bk29r12MyCs!7h&W z75L~J;m-bcSxL+!*B(@*)7AwcY()w~7$|lx1o_a}6ysNUZJVon*FAUs<7KqyEX}fj zPs`oMN@Rv$d*ER>z0H&B1|(+e4xz%!$(rTg`Kya~c-0AcyxV zTv6F-xMu?#V~tzAyX|Z}xj<~{%S7UM>_6;fp|_!UJ5f*Re$(JQ)7C2YXq4MvWo@VRGUq|r& zGu5)7>)+Yw+jHMj^OMSktPh&CEP46(eLPzu^=w?j=MB3EulF1XlAPlHy1TCPu>fPG7tK%7X|#`hEUi5S=34C-p;5kd=sH% z-L)2B*xI-X%MPD(#%te@{BS2x=Y3-0dp;eS*@^dr%WxR<3lG+zgGVt7`|;FEotYW+ zSNPfk;)A)4_$%qQt8U3}2kKppUMQi0nPI39JB#(Gr-SAOx^Bd+FEOY`*bt9h^!-ym zF$}$q4-!R^S5L9(oo2D)kgzj#E?nT9*seFL0jPMyGEc1q9ZRu2hnh|>xY(;3V`q_~ zfup>I`eT@&8lgHlGwCo?jYm29qpI8I&&W@T?c%y=4UrskL8IteWP+IRtuxb?&S&C% zWC{kruqpzIKHx$i%*9cO>7}#t(ZekY9-8?8W<6ClQ3L+@5QRYz4N?LD3*eX#+_oq6bQ-sR?_6c?Sz1Y)GUMj*n4#<}0K&d~&L@4j} z$*_~tYnd4a%W1Amp0C#S^@?_t82E7=Dr~lw1MI`Sn(2Py@G`Scj5VL%^OZH2e5n?S zx({%Ti}PVJ4-dd60}<{~-~VI@70}q5_b4j)ioJ5Q5h0MWa=hEbgH-h5yPPdxojtJT z%3D7l>r}7H53>P`!(P3ukRpp7D7)7sc@F-1SQsRy$S{EPfug6PBnWQ2P9MTMY<4)Y z_W?}iH_3sm+=BZ~3pAjsgHm(VI(^Ih{|azpQ<{F0zo@4?-!IdCF$5Y(5&FnVO zy2w($xkcj+W>wX&*n;{8P9C%T>aZR<1QiRt2+?m?F8o{3NRDWB1vyrE zq-TcCXEW;nYwWr@(eM>pgTA{vs<5UxqCL(wT8c;!Z_YRqv?z9xB(?LGsRAR1`6UHV z{>NN9^k!lYxtxtGo+J7noMIUBHdM1^FvrYP{A996`7Eh(^NlIocYW=9!LZWF*d`LA znIcu>i-jY<6Irft54eZ}`By~UMpe+3%1+N%U5v+wy76WUHPxBwG28DBub$wGuMhU&#D^v_+WS19@#{N~aJYsHU< z7}%Vv)KVRwW_ooXW{(`FiI;v*W~9b8*ww$-7@DglyOgEBPmg)FBAO1e%|&T3c;9@5fYle=;%_5U z1(4#0DG+bMOp~8RD_Fl*-N8_CQg07~V*Qf|Q+n}g!@m_}`+30Bz=IQ9iCqlq4?OPi z@4u8$KUM{h!-gn=tfR(@_RM#*4J(~w&4-blVtshm4npvUPgm=Dy>RPMU&QR&) zu3E&n;gkxt?yjlZZ0IY6k-)ZUs2*w4^T)gV^?>iF$y*^1i+HL+Mb{n-%$yvAr!Y$9 zP5{5FYoQa-aTKgnmpeDe|%q0WZPK{R${iI~u3gi>Ec zv#{_19NQSa(oRav1@8Ld=Y0Yr7l@D%0k<-ygF=m5Fg_FKYlZ+0KaFu9$(|x{8up=v zObM^Q;R4!0qecsuO2>aGQq~$FUYR}<49}6fvsDos!%dwNk(TI~JyaZ(U=jtjM^R17 zjvREuXY^fNGfJ`pZh-+lgn2`wmIA=)-u6m+;$KUH=FS}|E0ceszgP}ke$HNHcx5+D`oRRo>y1%#p>KSyCD3YE=h z4^rKS^uLVNVrBVaooyvOV%R)a~O+8>q9OwhZwt4R%yZ3lt6wz+>&AB;hn-*6Cw37{Ka)~5-*2W!)QsJj z>H22%`kC`PJ-9ASnw1n90NrYjl?8*3V+69IO+2LG*PxAX*&faR=j@;PDu2bsX>>;i zw3o#%S*db)_R&UFe!kA^QrCgt{RCZrY0+G}LO;)dUawg~vty<6RCMf$6 zZC&!Wnm$gZ!oIYWBpq6aBd6$vj4gCtKrP6u#{G}dIRi7tabvi>ISlNY#bc=Ik2b1P z$yfZ7%oO7L!Wfg|!PuI^I}JkyczM@q*v@z*xO+Mk6yxVkN>-6bw1){@0CE3`LGv4u z64lGyNJ$f49A%%V_KeS=={mw^zTu@&B#P=e!syL}LzrXZg`leJfKD8@3*(nDy)F#5 zV&_R%yoRkw(K$C{de86XGVC6(Gp^<4DlF{#uM2Q1rZ;FZrZj!A`U<9w$PS7889J?S z-C*e+)7BeYD&3w>71Pk+KycSrDoc64N^dr$iZIY467lKZ9gW%%@E>|#W{=;=lqsd@ z2lTXs0+agrJop)OG`IpnR$S8+suYXRnsry~WxPqg8-jTd++{hZBZ*gFv05*kE;7`- zxbggRlsQWdEEu-mjAqFg9AzXsboqw(tWCNJCoNO6o(06g19j3A;8|BGUKh;JJKRuaTE@ zg&iG1qfYl7yz_=RL;wIXo)s~%?bn3@Opl?bI}hch zQB7!)aNfzwk%w!Ww3i8e!2L|W=?;HOI7MTd1SkdAepNS!MU@gEY2c%x4TOdpan(pP zmmgA+C|Y~}&96?b%GTLTj_Yrb>2fkoZr*aiw0a6;sxQ`c7YuRnbICkAKO$^tENqWU z&c1w)EB(9vY4*$3AmrL81#ePEtjpit=!MMxy_;l84kq(edw5e_Y&326|` zt%`IM)R))*8oI0aknz5)smTe(wIL`ceVl{K4mxW%(mct#VR68E`oW-GBAYH!o#8gl-(eJAjNV2T_)cyOA(oLzNWnDwEt@UcdRvw34aQ5Flsg|3AnhO<@Q9 z5WoI7yGA}G+bzC5gODW~>JP2o1hX8C1yJsq6Tc+SaBrXmE zOgB9j^LX<7ReMlq9PJZzDL+|^Q?gsD;A~lfnk0jhP}7=BS~kpKcxH!H@N*?&`pEQP zqjuvnSBR+5;Yoyku{5GE!5Obe0&Z$&Kus107&^fNplg%w|B43hq-H1#595*drd53_ zDHUka8C}_Po3r?`(@d7?$>%R&k%0P3{^4DUUZ}(gFjjj+cdA0y*Suci6!-UNWzqAd z4TsGG{_W-?TIK7(EPZ%luFjC#ZSo;4ludb`z|&ckX(p$aBWkdWZem%@2r1#uX{*@w zoA&`-Ub2-?;9rQgM5JC{eFGSE1Aqhpnnq+N7pBnaRDchfD+Z=K3L$WA-_T;RPz}>< zCEciCcN9n|7z*pxgA~Bo6dyll+-PXRTM^!7Ah@By+4bY`?<#e0D@MN0ruk7T9^0@{ zZhvrh->-YepI1!GzF}SJ?i?#m9z|xUS)t2BzXAu}YN3uqx*F(?5?y%-bz==GOaJj>orcjx#R*k_hX`e5!x&Je;f{>a zN&&pt1(E=N(3>VAV*@)E(kN)T8bFlEGG&T1U8+lWmF)sC>c>U`^A6NFD77y}=a1B# zKz5Ba$8FFqRO$BmO9!)Yht2uQq9I=3Ax_SHo7c=Y6y(9aLY+hvq*1^vQ@l@p4c*WU zKYnr(Spx>P_3D7O=LkL|vTiag zLdfx`Fp1-7hJqUVg^gd?c<0Tp^`9Qz=Jh#hfjm*Vw@{lRD-g-ML#|5ux9$Xs3urTb zu6pT+Mq*6Rs%}0Mb3kcb*`~h<(x9lc&EZ9Q@-k)T838X1gae3m`^DqjX_7GKK$>t9 znR24w`Un=g(HRT9!;;x5oRqffsInGZ>P_jhiS9zIpQHh3;pLKR{Zy-cF4U)4wf?)b z>H<`C)D`+m^Za5RF!6I)Dn^S~1+Ukv1MXSM#~0Ug+3BVJN9OB|LlTH1J|Kw% zY51gygM8*t?%yX(`7f$#ElZ%8$y!`EZZqA%VI`Yxlr}0%K;C{4w)&AqcUX7t;YTJa zNJMWri<_W>DMQvYU!FD+NzHo5imLqZqXCoO;D0}AM4IVXOlF+p$NK}AFtwo9VIcW> zj~2>n9&{y6e@(#XDa&EZo4R$Auhw#6x#&|qubjDWR!dw6tJMhIh1=$cQT$ccPEvo> z?p;IXX_FL0hQrs%&%$&njvpW054~ zvdlpwIiw-3hG@dIq;ZJQ7hwx87OZES=<^Gw8|#0RMdla_nixLofEXYulWKqptXwcp zFUuV7Uv5}LK?Ics%5}3TS!D8NAX7Y)!UxdYyy8LqUHqm2_IDolByQaJCiyhrw@6k8d$5V&M**ufIV}g9cb~cR}lFoAF|Ug-}}4wg7<-f>Uw^tFESQ z&G!~KAA{J1|IoI0RGRENyY;OW#Gy18yaE%;9in0VZGVPD`!-~L%q&iZdQR0bWj5dNCXCC2}hno072NCxRgXdWn_q{gw+HV&Y>sAL`db~xf`9H z4pwfHUp!A_W}#`np;@(o={|p&k%~@gdMe;zyx1_VjuzEqA!=%s3*+s;KoYD?`8|(F z(we8YUrU_LW_ndf?2Puh)Y09x2SI0C5X^go#*4iJGwM z_(h-q3A6x6gcWz@Y+fAp7terI6jAf3eIQBnQ19rUU8h+IGWtjZ>O8uad++)Q&8P{E zYhg0ABCW9WD2$h^z-Rj68&+xIBkMZ8({eK1F0U?+w zLPH;oz^Z_qCE-DV%k(HR$nr|qE_Tk=~rd{;nvh1y$2<1FKn!ipT*Usd_0p+KJ-N06B zq3-7^4!-@0RF?HnA0-kJ?G=Lmk`kmAp-z# zd$;T;SW_E;b7KN$sPo~~n_$8hQOV&KjIJXo^J|A+L1N{>Y!RM9FOY-f3!bBt;}k!H zo)P{h;j7OV;3p01{o6maQ$g7lXTAPVr+8ejzU2X$xIB!~ysQwZLVH282Ir$ius%W_ zRcHCTz4Ke)M6ALN`gIQWzp2oLlIdW=8@Gsz)^eiiRw<8muC{kNP`2_0>atIuw6c!cq2XDjlv6szq@Ui^bP`{lMy{S}ed{L88R9B`zAs&|}Ib2?Neb_XYasKV{~#wg{kKnnF2>`iaK4`lgkwdIiE z(r?=+Pjw_WjX_uqg!nJc_Mif5oz3@Q=-#hIb@SrGbY5kKI{>&mUP~|JNAlXoZGfw< zHS0+lqSV8{D{_`r){>|b*VmE4?Z^u+{*B$gz6Nd~!H=Q&t>F=dztUg(2yqt6U9`MY z&0+6z-m2W7n{h5;+IQ%c1+Czp;}Kd`VvYf<)fhyLw!NR-eb~dZgGv(pI}1s#+1Og3 z?)v7DfE>amWz;aQ1o11g1|BKNpgHgq-8l%G!RAw)o*`F>`ZTxVl&n(Y~F zvGE+q*+{B;?b#Q3caYLk5W!d$|Lng{X+uY!rTD;hgKTD>&^ZGvqE<44*I9d^Dols^ zM~k_B<{r%YC8M((o1F7?Wn=3@9rOT%4GF&qE2||S2|=RJX2AundzDA*;v}YypYYU! zI-^oW)&}e1JPqBpPR5MV?5$6v9JOxdM)>kAv^o%w=JR*NixIb}3I-<2z4>iC1UzQ_ zcxIq1MI#p$0nE^nEHdUz>C(C7NEI3_)ys=F77@NgYsSzblof>c5(ny{tduNmM)k;& z;b-_jb>GZIUHCM?jk47aX$m)K$e)c-DUF6TL3I|lY6WU-iacx64DX)KmkH%|x0x*7 z6T%%amT3 z#7gY22ToX5q+g9hb>&<=gKtD;9y-pDoEZK*>UT#6;Bbp(e=FKUA&i#`5<;Ros@dMa zGgMU0d~#1jd9#YygaG#n5i7YQ(K5HbY7(Iyr!-IVlU2TcPkc>dqeT1twCjd%GK1X) z)%LgUp^QSpYAObU+1(;WM6$eI8Gg7SdqNXz^^j4NoNdUT zv?zc!8-0N|m-@v{JUooz%Pl*iO9V(mLk zxITkn8f;N227OMe4|)HinnfoijfBF1yP9*9XY+ryuiHc1Onw!|*uhr8gb-&Jjc1In zj=fN7JJT!Cvaef+(!h__AGxfT6A+*qZxgStww1;qq^ysobjZpKM7HlNYN?Y3q-&P6 zuZd}P0UcSZOM@RO=4(W#*Lz4&lek12)-j8>WNuJX>R_(kvV$oGXZw-;#3E^rkyN6# z2f+;6YT7F2*sW*WSP$@0{~zV()ub^n2nugH0G%!l#>hvicM8v&NiQe;To2MKL8i8a zA=3@sdgA{lW?7$%ww?2IP^GB4z4f}&ev8C##_2KXlMON(yU<3)D1m>O&maKdBAYu` zcYpxlH>PH>RK0CoaL9A4oWrx`VbZ1-WN&e z;T$C*u-<|7>M_e#g2y3u;4?{?Lc(3!OFHOE-fOz)1U5bGwaH$oKHGJ%_FJy7=%EfS@pgyEr^@OG3(3a$ZT5Nu-Ja-Hzpo%vj~ zElCfhclYb`LU|vVvyG5g-=(@UM_XddqL4Ja9|fc)8s;(q*#;Q*@1>i8+Lzlc_Wkjs zPCyF&w9J5AK!DZqHwQmB3&RpU5laPb$7hd}$Pf)6uVCw~Kml_;B&f57jTZd!Fqp7MYTQJQq}m!_`ZiQ}gZo z983;kIci?LP@}b#|0``Qdb}(Y;Wx}N`c1`r5APg0uojw zGsy3XT*;KZ`$m|w5Z~D$q=q|6;;>I+zh(1uu&lneRe@m&k(Qv2%aP#(&7TBjnWnh{8R2MDrpcu+PdSt{>s zWf-JOwHaca$XM*d;ow*U`qbs)xpj6t3Iq>kAZ(0pAV;WJIGRtD)TaD(FjZvY7yj$62Yj zLzSR)3)nZ9nZ&N$qUcIu(jrgm8koYcm}FDPo!@q%vxB|NmN4Y^-o4~sM+E!>&{AjiqI6X=YPM*$)aaDQFqDr zAnxrLTQ~bPi?i7w3-}iV>BT_p528D8<*zt=^;@bxjfyz61z`km&~Ifj0a+}AMy!;{ zz%f@=JOoK{EKCvQvAvBRhlYG286pm29-5gg)Wycxv^00_p!OKnYX`qPM;p;sJO3( z03M%2GDR&Pz!^TxNh3pHMY12Cu)(4Au0(~g$aVy{I-prIlPhfkcmwI_WThMI8UvpZ zyx8tVjZcHx9f4ja9dZ9Vwir#7>p0ueJ@@?S8S0p72?#*+_j`Bb+aXTz`$~V-AkBYk zIc9McG4(TC@czbwA-#+6JEo9>JlScVfWwi35{$iF*%1BcnY&pVz5ePaKM>#PIqbK|j*l3p0I?cc?XD94?VC6;HN2}#qnCtZj zxJrAI5kS8l2hHAL%&34bz9NRKntN9?&k>XMfSfDwU=eAXg&!3xKE=oA2G+5eA#w0?j&8DTHOZ@Ofw57^U2Zs>v$)j z{&CV+QkBOcc4WxGu6lMOC3XfID_;^y10(=W+^8R!!{4HH3)^Lsd^}RVPh$3-zKFS4 zw%}BzHr`|5b8eN{Dr|J^rIfh%CNRiP>u&-qKy6*5LAN)QEVFvQM1=i{+Evdkj`F_I z%+kZVL_B#z>ke!IC%zR}kG6;!`Abh6HXdU0^Qn&WbH@FCkcX}{hx~kI?r{$3EXyhnDhT%lSrE!h5tG=8ht!x%OjpgqeZ%R`03oSGN&1mPW zy)#vM|C7F=@8RA6Czdt^>T?kEO~9f*4bO_Kd$<8a`-Kjt#a!2oE*=9sUN9Uls?UWde689v2Xm34iG%Nwh#4*uk4>jV=>yZPPr`C zulvArJiHjZnC@0P1uE#;KU2BaV!kqDpzn(lEib(HE@`f+v!sHzm6fxW1=#HC=M62j zASMF_W~=O>V9Zvx9R8M}&MhGd%6_DHzfE}pA$*h{5BIfK0|s7d%AEBSEn^rw>_CsL ziSt)gI1Lzu^^tgm$uGe?m01tjPlL3^%@{8f{oxZ^#22&Ud%1>F*hfbx zTiEHaUiB_7P=Nd(j4(4~-iAKfidv)dY_Jq*|Cm0xDr8MsF0@;k&a_kj5_p%(xa1mw zR_{W$n^k1$BKacl?*WSB#>$a=gOD&8a3$*%j8(@@&A^<_HB@F2^VyEQq91!TDBU)s zE|$l}bSk|_J$a6d;n^e``)8JRadL{fw3tNREjs!1003~qBsfp-Wl_Q?nOd|#J2~o%UUPW8RL*tm6E;L4iOxUt!NwhVk28RH2i4!-TnB@G zm7HF#Pv=6G>;x-LcSV5A^8wH>B0=wxKP>_T)^$RJ%~l zpn>F0irZk5JQ0+wOP$BxGB(_>bYfYU$G+cG{Z?&s4 z{Pc<>oU>iW;;VKuOYt#2Q?0k7z-SDkaDzR7K8g3aQ*g!LuYHrxT2@*z93d`4JM@$* z(~@dr`iB~$uXV#-HaHFbg>z28_)OQl5$yr^ejK42zp80{%}PEb>K>*I>Z=_XQReRv zfh?*CVEHWPv2tDEf&6l5NGdvoYJI92f&pnn*U>wp9yE|msS6fC;Dgl_PHJS%a_Glo zoa_DZJO98V3tz{p)g7B?U*Gi5w$3s@HEAiRMXt~g_q|-#fC%ABFCkz`{gM#=6`wQH z!u63~Eo(8Gc*$;C?KixyM2TA`m$xl2J}X}4@ZOO-G>jQHo{aKDD`=6T6QogTS<@DK z!W_t1gbO__8hog$pN4_JFO+9;xlM^;Yi8¥%O9De2V z>q!==`7W}$ zv@Wj$cvGlE&)sR4PN0?zn?-_<73|p_b#|91AVC^pZv#n@02*LWS`o3|M5X2{j*b-! zj~yHZOJ+A)$lnCmdwz;~*)h@dCcVovFDyGXzx%t2z3sV$ZtnznR)AU~nA7??OO=g0 zPhIWufj3v}WNF+_AqbM~=gzVv0P0L$wWka8K2h#oTlF+RzLzjnWTvpXH@R@o4Qm0( zxUFY?TwcpbrqLTpq+`UJ4Zqx1@w0_nU{y?ZMKNq)A(Uo;#w+F3sm*TJvoE0d>4__~ z){dUjxL~&~MY6F>eiV}y(1p^CYB4olvOmsnW;^(Gmho5?b*v5i&Sw%dx#ha2k|QS{ zMDJ?PF+6X&Q~8KG(4zk<`~ok+2edF=A@(@^tJ2w{h8Frqc`z3gXtv<{tvZ@XwoJQB z#+}tA&Hl?=zmcu~aFcZt`XI$>(3#r(KKkN5{c*&XgF%O`0INRzTQu5ANNMmns8vcKqZ3tVhYS)&Vd5&T z0E-YT8>5!GBwnZn6Db%XMRMb;Fs8-(OtCuCWC>BI=InAs(3Kv3N0=~N0xu$iw5HaaZ*Pxt{tTF&@J6YcQ>$EWXaI{2PrFnZAP8uXUiBevIJYCE26K>01SPoZ7?KX zqTfv|AKlGB49hGJm_1R%dH?_cM}F>F^B2IW`r(Ior9R;hlp?p z6@sF>flWVlLJA(HG&wuXaRQhEMxXflqRwU>FP#Xcd4pM@oOB!OTyv~nBzS_U>Yn`w zzT_whP-h68Dwx})c%;%nrpwLHQnY@-0h-wp?*$#UUx1xVr$bHKwJ{aAv z9J?b_IZaY)C{vpE9GFRtbn(K}Vt&1fj(Xhy`)vI{%gRE(bdxN><~f17&**Yy3Xm;j^@;A1q(< zz2f794bW&>w~%Z;=; z=RHM}YbVR34R5G1Mu%^%zJO`;@KsiJ$p~9}6&>W}T!cgS z^-5P%krZcR&gRX(g4v}q#?devjW+etlb>i8zH{r#Hys-orR?h-ifksNc60Fxlq$X> zr4?SagijUa;u4DclT)`Aqd}oCp>KbSre^_jV-=)Cp%h8;B*6EM2e9KT# zXO6kQ*jbK7UZs#}P-k?e#FBU4DE#56hRy2I3N09*C{dyYw-5tlDTezQOT;JuA-k_`(KHvGso~KZNYV4nXVgQq|u+hSUE&(?gZp&Uw=wVoVziH5(wQbG63Bfzq zE!<_r#=(Mel$_0Ei82I=DtQ&ih;_C)ZYclwUpnoP)!ZjM#8I5HA8gNSogJ3xF)Zt6 zPyzo4C@j5gudPYSe?ojr-D)K(xsmu#t6wnU0#hC$8xx0Bv&(OIjpFpUc58Lm1uoZq zLdWvOa0{%-LTg#Z2Uel~SKD?c<$>Z}R#f)OCI;?$WgAs^N;5l@7nqneD?Q-#xTSp5 zNn=4lo3SMYCi!>_D#~bZ>Mfb^#Z}hWGRGjSTI0FMr<$ zJkY-0CUS03sP|$l)S}nH$Jbt5%?iRL+-^Q*f87=J*tY8cb8-2h@Q4?~pZM z6PP@`unpB6GO6RYsD9LNsZC&))7(dO&9{A#jmaO$R)j}!-u= zKKw6whYfpQQ86t-F|OCTPCegoz{V&oh%5f(aK1p|qFJ$(&LL0Nee7RYVz zn;x5RJ#nXfZwraM$89JSA2-@YsrwyHB@qAm(NP!{PE_R2^)_9zrSXSv{*Zttf`nKM+`$Nb*l^Be3Gs~RSUmorn>s!d zGmu}3Z`~dgkrLEdz5!2PiQ@uMr_P(^QOCNUJbl-2(2tPPs23nSh(E7Vp;HMED%{bu z92uHfD0mC`hl8qB&6IuEI^CwHOWoH$y|@({s&2R?*-m%sHiX0;TrClbKvCTGW9r_I zpD!r7!k}%Imv9%@4E(?-hQ9QsatlE}L}*q*l}LkYCVEZ$N)mv5xPD>KD@$KLmU{r< z#vN?tqw6Z_EF1X_6bGqAYq@d`lRyA=^-M%HH+_rn3%q&pP z)aICASk6X29KUZB_#4YofruY4F1{XQS1&k?Dn;tTXL;UHBG$~ZNQ>h%P>mE6WvHlPS&(oLiW|D zr1(Rsh~qaOjXLx_un@YmGE<(ZGxMc=`)%MV&R=MxJg+D9>L0wr%F-ro? zmnHAuihXt%QImwDZ?2ShG%P|_$vE>50H$`dc{cu*@xns0Z zivQ@XhsCbRPVHgazo_GCW1wJKH8N$iaOka~e1SHGPTJe41&a z36g5oH3_aIE>KEi?}HB@Tm9DmoSB~j>%L#f^&=^5LKfk}p>Rx1OUIoDWlRPHIc&jX zqL@}DOIC`_ie$r;5Rubb=*?M9in36qr~(NzVRbQcn{13J*#T$juspn5Af+-#_((Vm z1T!}xRsT_(4!`o=sXZpYVZt-00FWCsY`!jcnSj$ zy5J`)jlyQ<4Nurh+^2vo!JSC>{0E=HpZMg?iXF^*ajT~coK+xiPB=pt;VrLX+$NBJ zti{UX=C5#Cll3&E!-cuzJSDQ_dPjh?(P7@Y^G_$=8;G7@`x*~~m)`K$IusX)llTH> zS5NFY7&lAy2jDqahw!)0{NyF*HdLgxL|kNxg1F8$Hw3YE{A4(l%)yM?y6I~LZId?J_WlT$3j$!+2#eZwY= z#CArMP0MMx$mI!E2Px3@Z6981IAcj`#~`Gh=;f;`=pztaD`Rfk0tL(V?jvxjySO%m z@-)kB19kh~EGC9^h8eBDTT+rgl!hMDF<#zx6>KJks@VADay=fxT)4~VdrkGM`bye4oCj#* zh$A=fX#WWHs(R>nOx`TML1=&SlPRbjeLrso+^Ktn=H0&wqz*IFjO17n14hCSvfsMN zgMNpqTr(|$Q&U^D5mkK0@mw-p$7CKDYK&qsXph8X`V8)+RWXIjH4|fRssKp}B#K9| zAFyiOQ2xTHA82n|X$R8w$dc2nB)VM*w6a%E*i)^W|8h94gtn(aot^nV_96V<;d+V) zi*iIo=>$3qLmOg>Jfibw338SH=o+QJ?*R*JEfCyTp;vZ-&*G%j%fFMfo) z(LXf%lS%}>Rve$KHaN+uSvn!>8GT+Kcy_tZ2fQMe80^6Vm>))j?$@z|Jh`(ssBeLp zg!-`iGs3$IRIZCdy@b(sj2VJeRg^N6=~0nQ3(FHo*Zk~M-y=s9xms*!NmdIK40&r% zX$}GCXb%@@DipnUdlW=F1P^#>a@}n{)&AD(UIUoghjHxYYjUa03U%oO<=-O0d{}hC zLOkFE%F59W^QUY-x~8;toO0|Ouvs*UJV@P!Cvfi&nfZNNdHTbAl$@vApCyeBJhg?S z`Lx^V8d1MJ;%6T_V*H1gUax&+h@}m^Jss_(cJPSS&@`~g3us_gLBD9zhLycJkLPzF z$Hux{YSUTj+v(klv_KozN3u|kwWruCRo9k8PyjVt)|!37CZ zHltITKx!%-VUy7=j4-bgXcjhW;yR6>zBa=4-J3ZAVFr0Vj)%W7;@R4@h<He=pAgL(!esrweOxWJEWp9=yx*4vdY^GB$K4 z`*i}5ZM*Mg9DhCJr{ZbWoiRy#H}z|>zCQPq7zGMzTvTU;$n6+UDMU7U6DzndiRtcjt!;MU+JV*{)*m^JAIVM(?y7guDPzAnKo0#kz&6}B+vJftW$5E|{&W%+60n=+MvYEYP3E`%W3M` z#a@ZPiw*N;r1){OCX?;S@)QtOFfXnj-rwea#gc4iUDxB@{@>-K8aPF~qH;y64{vlNn=IQ`7c-XpyzSKt#p$a+w zRJR^TW|I~zmVKsd>eA4m)9M^$UpJtAx_3!rPlu#wK!cYQPGmg8GV$o;PR~QnbPW$m zO-y|);|Y}U&T%0GaIDDbS++D?icJ1{k5*3KPU|fzMF_LdM;U^%JR~V| z_=^*E`Pn=f`LMkl*#)>dhlmvzr%$&+sj65=wchN>%1{AZw-plK^~-WYp&bhm@Ls zm%YOW27j@{HYi(UdKl5nWSeQ+ZSlP+Rf&HmLHK>oOVBdL3JH>jlW$q7qLtAv(=HW7 zufqR{0;?5nh!jM!#xDzhvkkOp%z8<E5#N zu7Ioj6lH+>;cw!>SQ|F|j=kc7KXaeXbSoH(v&ySyf!lamy&n=v^s+C5fTRo_$khyb z!R}k-PPNoP?G1?qUoJ>iHh!&H7uV&=A#iL%=6Vhj%>GBO8O{9hh69#es(ZsV548S% z_fQb5b$1TLVA?@M0l?11Mq{@zZreU0q&5F^=;TdmQhXUy zXt`Ot=D4GSclOGi$q{!E-o4kZYnSt7ciQ-CPPRBrGgYwb6~@ibO#qZVlx9Uq@gyoE z-H%qg$&3+0&gE^o;G(IrFi7J$tv?U^X>our;c6yJ{6m64B?D{5&IRn;4w7_wXfqY1 zTKc-oNR6CzI3~%B`3`5I8gT(9uM1P=1z`Tdax&Qb{EdoO9Z_N#XFa8!xzTqfIwguD zul>qm@DyN6+xhGIwA~W|1x^w}UchF4t*lSSRx6v1^`6c%1&V=@G+DD?FV#24{Y=+d z3SAj?xCB6SXl*~R(O~uS?4*d_b#->Zt!BBQJW%EumM|LLs!w70Sv`NW|GUxGL^g0b z3W6CY)u&iZ#hN_Q6dTim3ab=rTgP-cIEH-sc!){DYO&L#%olu}=sM%DC>W|-7a%n2Q#t{%QqxRu|sLmZl-YX=SmDv=zwf)zl(v`ku zG>IkiP#!i%)C=WQ@o$}=Frde0xO>&>DAw}dwx$5NOq+3;b}EW(8i+=WEy<6DAuOjK zL?{VYveO9vq*2Y(Ai4tvN}^y9$hi`+Uv%~+jADRW2F=6*nrL}lR-Jj2#?J9Td2=|f zd9#g54cN*aXu6}_xO?<=K!Z_=u)%dLgC&u4v{a%%aEqgDi=CIL@Oh+H-^u~8buzw(H&CqRYjyq38j-iX=<~5fs zYU;E@ruaSOrQ+?KJrf%rgWB_=xvasHbmib9gxdYikIxEMj{>c9DKn=I zM?;^D+=4K736Kmv8lGxN!B<%GeCoppl!XE3F3xx9N!{A8ab!?(O8>-c%YOF?nYqWB z9qs__fa=wR7u)J81!*2%_fFyx>jL}41UX;MW|DBtb+ry_OxxQUa)qJbXpcWqhYrcz z_B*8@^X<+mJ)_L>utFhL*Gnj>t8@Ge1k!gif4L@f6xZOiUucqB?q4pk1ol(6s3 z4*0Hq!<~sXF0z65ckmABR}Q>$1f+Y(2C~M?`(+kCg8FrsDHY-#b^4Vd7m88yWLSi^ z2hs!cI)zpkg;eQ6S)}Z&G|A^JC-2O@8(yL#Ql?&U2Oq)mbBS&{c81I0Zkj{V(J7|s za=~TYF4nHSlL{nLfUaz6iCxd+9I)4k%DOiMZ5veJE@fULJyJ^b9DOcGkd@?KP61`5Ioi)1e5Uzrc)(^3afa^c!4|FAo?; z?H^4UJ>#8}Tc@$cV2$zFkHRb-QahK2N_cb;bunQ5#vON*5ZyuhA-MRP&{##c?CgsX z>c%kDfRvcD3a&%Mcq&UnbkwA*Ev+1Qk&Sb8`#eIr_Hsdn00;^Fo;IWUU@ms|Zw}r@ zt(p58vbhXe?!KGrFBQYDECs-1KDbJuX^kkh2fcr4jv6E04h2@YG%^v>iAc^Ny_qm8 zB{aT!_A%?yu;i{#Cq?1EB&v3OYh5|{`b06!Yjus5Cf%J4JUD>B42+H#qlX388 zqUK0Gj8*Rl_kibp@V0chzW}eZ07C@O8NZe$jrC;@o{AqQOuN79vgRnuVhl~Imf^v+ zc7HZ2#V}u%1pcYG^#wf-XY;2Ak@tc844Olipb-=(y_+l_mwZYT26oqFB_Mm2;+3a| z?QyS1L#IuljA#k1x|nJkeC9FB`+o;QEP?Q>( z(R(%T*l%OFw^$cDrTo5-ogS7weD?#B+XrvC0JZ4lmD9>6~a?d`b?I9B&zpE z>Ws#h9I7Xc%g;5G8JPFHQ6;F=2E5mP*Ive${Q9!azYP#-MS{V!o*L&%2U(Ak{{)kXA%(5}t5={7fKDfr&I>fKtq!hn&v+9k=!=RGcUh#@ z)KB&I5_gUZ2hi`~ynvzZZ4N~R9MmIiw{08iKUhOgrV5i-GG2fnA(v(7SRf`U8qOKcntd^LX=h8r^-cmJeiu(re@RY*HBY5k9UHq@3VqcjFjQe<=S>lC41V9Y{uk;m!mN;Vl zyv;~=$TZ#2AOd{+@&Rki1ho_k>5-jWH9|1CBDc97G&+3)=2fg|SRJMbkWW-~>Bu0w zxj<32;=O`^B109&61UF3g%V9xGzZxFQ>1F+-org|m!T-(hldW&2K2F%$J>`#jr<>r zHrv6%K6q{ih6{B4;Gg=(IG%@bGlJaV;o_FM!6HG(k>-ac;Oi(FK=#bVES?lSu_oDt z#Ga%hL@N>j)^zwzxD?s-%Yn<?={dXyrt^bZ9A{v?e8?+B1jreUpda z09*1HrWfHtf?CIu$X+N-ke8YTqCJqqG|!Flv6k2i-w4k$7S9M zBckp70Cp-giJ&>!2zc|z6ZAwXb3T0^u$Jfqn*CsUlD?Xpm-GLPnY(FL^u zSB0mC1zz09YUW6Slmiy*lX;OrNZ4RLOdUU@35B(TQI~7;XbnmM?>Z?J{rQ_S3!?Xy z9B6<92jV~g0g;GR%nF002^mzdNfd57@<)@v!?Ng6gb#MM*4iZS>d0dldaoQsa%NZj z`hqhcP;ZHAp=G;)6G9(^e5xyx0vK4H3yY?#ETAF!RX5pn!+EliV#z@XGzIxM7NNOVP~ zml^O((q1v&4|Bta-27JA_nhvdZL7C{-o?f;%B+Tld+Ilki2)|OS;G+iK;X*lCt92- zb+5FwAypo@wS2ER{+~%vOFTC82eOstybyUH$9Nk#%M8ZY)85NjI zJe(E}ZNaoo^+Fao4+6qxnZpwtX-aDrAMN~vWW-MRO?UikuMFFYW!7G6kX%czjeWSH z5?)kyZZ5GzMM8{D7-^*mO@P!usb@_)dN+I3o`+^UrPqt2M^@%Yr!2JNALN4Dy!E$X z6J`1?7~jYxHg3H;re(y{s55Vsn0^xm5Oj)fv($U3GCIn`^i05WMCb_yM;9A#$hqV) z>NZVnfKg=ig;bKvj^6Eay=GGI`0w~n2+AU9S8O-^hJ5epm7R^?_+M1qtvDARA070F z%TN%H;YsRKr9;93p~5*OU=cAGGkJf3GWx~ z=;yaZ5Arm{>5RH?WwkZX1+0*XwR4PS7+U<58ns)qtE@qH=`ZF+^;~1Q!9C7)0%mcQ z7|J7xP4H`dD!iz&(*tkG);G;s4;_%;hiqb8bQqP&Wf3!CIGuzu80IZ6YoSVKm+4c6 zuoWp>^@6wVo9|SSs_gx`{G>lfBub&M9kJkhmp`&C*=aIof!^rc^B%kTgNZ|wOp}Sx zFsvc6bWpik@Ofa~lGD#N#6p(*w7?;lP4@EHPqjU8(K9T z-sDiEC2zZwjZ%<6+FhyNTtl9-SzuFF|LR0buKRV>{A+`aqAYo@%fF&I%y%vjKh>Ry zY7^;XCZSV&ZQh&CZ3r(-En`}u` z)QI_EKIU@eBiHiMR-{$FRayM%&r_hIrrzZ?3|W&mj-sreePlE$27D;L-c-VF05&W& zM*%I|G4@UC;NmOTxX;X1IM6|FC(3o?PgO#Fga2$g;3-ZWg(UFcGl+!~zR)Qe*v(7V=W20si2*Q?5 zU`O0!&?5R%FiyjqS+chIswcVF7zEnf%o3d%hAQ2a6)NS&qJn-yhIxjm0R#nJz30@` zfHm!`us@>9!o?>^OH0n$x3Zk6SEQ>~a8qgR{Ov2VU z!4$Y8B8lnxG;tRH+W^W`u_KjQ0yUAk@m0qh(D|Do9L{-1L@!ch4bj*dpwS5FphZ*} zIw9*B7yT<-^Y3?t`1SSUKG1d#`aU`MEd%S`4haG1Uz+wQ%?!3;N`)-0<1w(oHF`TA zQ$wRXD{z`nM1IP>#DbTQ@zOU%CPcOrjP6zT5@~R}ARrSRMbFrl&(s8SPe1@ETzngt z$cJTsseo2VP}8(tfB^)C8)B5IR=-LfJmP!_q*TjpRIq5=JD@SEIn z_s_m$2WQFZPPuR+TLT{&0Z3f-zH>6vSQKoHr?Hm`T za#PAQGl)<}zk8JfB_mAUC|NK}5Mi)s>SSxk#^6S6D&h_l71{4JB9>TQtv94i*)Mn# zRQrr1>*vQ>x8_OF_2ITv{GNv-{G6mz@5=eWe(u>BQoUi-zIjUl{dQ-W<`bH~HVddO zRkTmv@6XChs>Jd5y3qEiclk2UsByUgZ>m)=4R$43e#BV&SUL*)k!nER)8l;>BHvK$ zCF>Ghsg6ARD{j(V^X}nz#wTFsY#mhq2U(44OSQXfRj?vAfSku9Fk~2XaxVWFrbGsj z=43y?g#^AP-CdtnNs#5$I=>Mzo(mi6qpf}<`st6=?b-ioojs1db!~Ib2%E}SNprpV ze`Uyp9~a8|!j8MIDhC@~qd}WlT77Katg8SNM?RgvUw&v!T>;qGm9HMUDE1a&ZKdphhBzA5c(iu z^Hx0sY6BtKpG9W^Gt80Vi47p+;;dg?bBdQ~$-{bm+}ZZ!5erCI78>Cw<095IFJIXk%7I11)Z@lk zEQs)C^NCaQQRha>Y&9b+0Nnjip};oWhI#0K743TRcL>|%xrT(!{cBy?od@u0!*KI? zpnx5>M?K8hi~G476BAc%QLUAvk8`37a+*NtI!45%3G15eefjPH{ZY4Rw|hN^E{t#y z_<+2@|6i1tpcB0k#i3N>*4!Wx;Jj)#yZa8mWT)-8Rj@Kcu=}#&-J34!0Cf5b!}dr( z-qB@7iy>o%Fr|0aWA&_UgB=N5?7w-XB{b^2%mXSq0M80+0Y~zSNlkfQH9XLu>;V){ zmgIfVbdAN*cbO#d>G$39P0F13O5NpLNIdqkTrkmEfJZNNKTZ~Z znlL>jI%D(Jm+$X;aqJ7vBQRJ&UX3s^3AWEzrkav3-gcM<5hec`B}};9PYX(%kfARQ z2CSgF^j{>~0mzob>UPz_O=Yy^Ag|X*8-f{ss!W0xs34*`M4Ax>7;I{!_XUHa`m))) zT{Gb_p76C**4$WLcJH(<5e^Yx;sgKtR@$o@B8?H_J;+h#?+cHO1u_}9bw9Mm6NbVj zBCRfFN=*NmfT(^1!!tA=nqI32uyF@u_azm_#?|A@9)dtqwk?BK1gyQ+Ff{upe{E2g zJUt(QcKcdi5Taj;BBlkzVz?-nOBvSY_Rovq-SWz+Fnvy83Pw!_9ptVf-+E~kH=8-{ znp)0x=TCXwmY7?zCw=>9XA`7_A-u}3sg-aechPgDj#Blr=~LF-%_fz-m;K{7f4dOD%bbO5%3 zaM>&hGa%j_?JM&#(vDVF9^@=#xbtiDW_Hw!jCQfD#RBekGEiZWI7^%pZH zA5pmlr|$2~jGi1lwz_tU?=7!_hU(@XvO)Xj8&qr>3W|Bow^W}o0_uOt7r~CdiPkNJ zNaG8j2i39m7{(!QLv(Xpb}p4rQvUehVfx!uV|AfQQ@5wj{%+yLj5V$)nygghC2eRe zsJqK|LE@>sP+_rJB!oO*LjGL1IcQr$?~?v9qt9b3@9wvXFAr6B1#4bNp1V@@{bX{O7yOp{%#OVd2c$*<0kVl8x~ zTM=9`K@gmiFWun>E~>XD08{Zi%2?;xDyM2zB??&oNws*sY(BKl||AwL7ya+ zg^~0?_yjcUwM`b?1VFCEMOxWsQVx+|x}hBeDxdcHs`y-k2`~3-q#&dKAU@A6W7K40 zg|z*pG4@jivEX25H48z}GE?@YY@HFc0%Sv1Sy1|3msmokK&jJ$v>MNv?n5VW#s#G~}+*VRHGCY`N|CH3vQvRj{40M_93l+H^H=!_~Qo|H!unVR# z^iSPD7nPIlH1-E?c|3TO=DZ7%P0kj1RU-H__tNDQ%AVZ72W5hk`roR2iaFhuJbNp> z{nuKc>ji2A=c!L|VkFz43k|= z0mC}F)I5QMUiC?u^yLAYRJs6ZDLsmmLRv;%8%$Ve31;C5XfB%}Uo?{f!-JZv9+PyD zGo-82{ango<7?wQslBTuEz4Sko)d@VhKx$jpD~Os6NQWG?hW8$s3k24wv;@xDBwWY zc@!{LySkqk?x3IgwV#Z&6HiPUZBtIvW~y3d(y1LFhXc(F(xTHVeu&L+uJQaC1afk~ zpT{F*w<_-<=(ID<+#e|2zy93H>OVRnmDkJbVWRfo;x$bIvdhbtdOHF>-fm8Ys1?MP zD{f!8ys`BkxDX7#dY9`ZfJjCb#u83JS3nCQR@GP*0JkA%eEMKe@HL?D(5fSEdLU+T zruRJ(8%tRFp5gFC=G}tOg;UBS5S;){gVMIU3DOBPJ`IZiV(uu#Q{6W>o9PZ{_g)D2{B5zY?6E zid((mD~xbEjHQ`Q-!N!>D=;aIi$SvzkMq*QkWN=}$bnuT1ps!s`k;vBG>q%aon};- zr2zOyQIZ4oLD$GSBea!}>Pw6Bg5xG-VRK0sf2p3`pE>BTa_glCnZ8^3OqnI?EcLdy z-3x4?gYP~x3dKx^>ygDl^s3o6%&y=IcBFD5KrZFwTP>Rk!gIuky>+|FZ-VEV!(jCABPD!hm>IK3&Qk5~Qf`3)x zix|@ZJ=h$!bQ6H#Et(4xvX#lBqhJ)USf@KtQhmQCX-$P`q(Y;hU6ZK@@99;~-CT*=ePP zRy%E#O8Rp&*ECVFzzF_08Sp*g)u&h&pMQb%Bhh32ey{?~T#I-g04-5tpN~5l1dM5# z&`-#fLc4?Cu+UKB{izPF6&n@f0U3|yLVD*o@H z_I7#t2PUy`C;X~o+hrr|s)Kj$)O?9fQzoqP3I!J!xvE^jw}D%ry7!(x*irZ84Y7=y(f@Xa4yF4uS+(2t zNUMyIlj!(rGOOpEs#x5ynmdJ$j{9$W)B{h>vnmq1dI_PQSdyr_JQU}LBlTD>chAd4 zVX4M~ewWE<3$fk1J``pefmvCj5e*2;J|54nj-qjuC&dKX;-NpIM^h4DY#%E)q%g}< zrP^YKnS5kOA(an{o|3s?eHfO3yFb4AUo+`ko+K{*OE#t10sD8xDn7Ta|09EN9Vy-%vrj7+zRq z_jrQ&E!^(Ne$JUCh8`gWH7vz4^P)GgC=uD4QUXPXep}5sx@JFVX5znM2Nov}0pPx^ zwI*fefs~u0$J83Ji^fEmq$py9`c9PcK7w}Ga;D!w*wLekf12Pr4nf#17C67`w3CWM z&K?g-C#Pe%x0z zl?W3C<_0=_+KV$ksFhCPF&}uJO2MXmdQuWz8c0G$xGz^*vh6sZdy-P{a@O2%!68hp);`c5pmp;(PSXl5pV>jq*QK;i&=HmLD8&TnHGCQl7&ey`f~*1G~F zkwDcgBR6}1N(DvlaT^J6payu!ULqe0#mlp^TiY^PMw#U#m&P_gEq`={nR)C8LYgk=%4>RwDR z30ESmGoMu0MT~AYxB1!%Uckn!n{OEF5nPom^&JlDw!lF$hVP7^TV)hOfiz-hv)vWC zi!uj-Y7JULze$w-v}BbW9<}<;Q-s2fR)J}dY&*1;Ro?SsHreX})QyyQ3Do2#wMy4{ zkt5=t@d*Snz>9F=O6sQFFNG@EickAjm47;aO)U`3Y6wA0>pu35m3}vg5dbE@_gPcv zr7sk@Yl}h6ugnEzI3aIBRe8Jgzq)fy0O6+(!?Dq4Z}lqD?_)A124mMwe3}wp&PJVq zkQUP+vjF+Cm@LCqR78Grue8PK!Z=l`pRVE+EdGYnphdVe0wt1`vV%&?`(}^){RVf% znLYv5g)>Q|nK(|?v6-36V{hCyS{%hP3Se8eYdO~64k{#_IV`3+Afk5Sa5jR_$TJn= z+1Uu%v@n&NxiFLSwv=AMSS+F+5I3+0|9BA^CtJYcAntRNzjYf8!~(tRYt(bKc!SfU zs2>;|E!4x2og~tYcQ`CiKO$5fy;kYICR zIw}|9iRWfz{y|&^=nL*#?=bRtn$Ha~GtF`?`jH`d`Ot=k3y6It9~ z73c_b(TEaw|F!yQJrvT5=UZczYL9#&zkf@{J2#^O;M4YXA@dGNZ5PbSF0|n7s@m5p z@1)`(iVSKzMNVo2oZ8nDmie^uuM4hIj?ihz2ImM##uM+`-N1-)Ekow1?+7 zx>KGJYz(VijATh445l(3_`P^8y%>Qtbs%DoNBFTI6K{|M3N(+8M<@t3Mn{2X40g3d zGk6ZFNiT7BG+_cGMy1ipoQ0Ryp1FT}jR8iKJ8`&2CIJ#fb1vGWLCkQ?gQC^2BQJXq ziH)qI_z~-0MyL}6@U`ovdrs><$_8j3LBcMMDY6$9a{2@bY$F-PzdbV!D8adFHly_k z8ZPbX>J-Cl^dz}<(Q`;Fw2-{$(nIw7A|)vE>LmHZZKFzKW!s!~L~i;XHvewRo~IK_ zwcW6$`pNrLg~KaA|MqL?%f*s~MCe5%q&VwUA^dPeHrSejqCZNIKaSF!pF?ia&c7$L zil*2#>v^7_b$I}5S+U);x`Mo^vTLH5Efe#M{(;1n2C@efiAdmWV z+An4l$KPRKxAAhSl%x)-srb?W!d#6Vr-U9Zt?>{C814?qPG0H&T%~BdCHK+K+zr** zH7B%fBx~uAT(9T|*{d`udHFPk%ljSe43|N6L6m=ct49-9zK%o+P52wO78K2mYQ#9y zC}|ba=K?c^#B=i_HP4TyY21dfr2sKQA$lAWm2h;aP_%`I#sGB zyoO-0qo6Ww3I#&Tln*bQL3_MGYApcgK==wz!;5HF=oaFA$p$jV{ei!Z2(uM({)Nx5 z8ip~%l&=ayed;2c0Sv)_Bt`IUO?;gaW5fgay_W`)e^x)@o1|ZMn_RdI%4rBF28k$s z{bI}gqTzx$$c}=;>KyBhtAU&@=+Z@AsOHTUH0(s;j1v6Fx~| z=zGLQ;18r+Xf9QOXaC^4g>u{Uc{a(}(INX}CkzV~k02^8r#nSem|HCmOdozX45T*_J=2PZ&D*gabKPU=VRx;h0_f8h3% z6svU%%;#OHKls7k0be}0pWXQBq38e)Su!lqZ&p@V(8H z^kabnrVBdO#nFgVxFoE}Q^tHk27bO<&*2zfH5~!v>x!cLs>GprR>L?;xdE2Aer-ft zGCWc@YgLbkih_2? zc%~Ut;5-GoS%lF{-fcH9$8QZY>NrO;FXwu4;4<1cA`St#?!5FC-wkoPsJpgN6ELQR zlf2GGexLm!Udg89|5!;3LzBZY5VY4k$eozah_mISGJ@wcV_`P9I_uMwn%R;^xpJCg z*E8;PNG8R|J%G&h$hn2qbxVBhfcuO=4#u{oWU6Cl>+3P%N0qe6fk?vZ#GP}~T{Ef_ zU=}kOYrftiils)NDR4A*9h*IS*>?x2Mmnb&Kpu)qbxDADf`~l|<9EK${}D$Zmagm! zxdod;OT<$I)q`fuUiU+b35MS$#v+|M9}I6-`{hp^CgWputOC;7Y~+VbS0Fd1vRI#@H0Zl`FG5mG@P zbzs_9xbj=C5Tk+ApAw2d&rzE?(%83|ssDuK@w7TtU{Jv#jQUNTaFV&L<5qzEp3yY2 zLxr%frb8K~2zCP6L2Q{Ur5XL>!Jv_N@^N(l@!3S!ZS{`c0b0Uf(AV+>qEswo+om%o zyz3iRK}SlsZOBygb1!T9W&U3a)Vj*x3A!9AE0e`_puZWU8fwSno5txlhP?7QMiY0A zz2s0mFi~&Yin5FbDC7@($@TSd;jG{Md_~}016ac8lKagpscT(FiGbB3Qll4NGm0}& z`b|%0Bjl9Fu0J#dHQ^S|qQNan=r3fFe5DFBF*lx9kqyCD?zQ z-182)AR7YZZuzMS%|Yh1AMLZbD(nLYLR0|D!PTY-3~dZx@27EVIH?DAY5;;?7~zoK z7_*G|sb{TOS4XT8oMmAqjUpHng?nVHvXLmaLP4f6k#-J}g<<2dEtbE@mGBSxy_|;U zfkUNtev(w7%1tQrCMOmYPil_yL?!fP#i&X5X1j)D)E^LRG;s>W5GQdnLRSP@iWh?4G5(_p;Ue>9$p1$=jvEEh**y_O(#L!Na{Krf5jHmBPb0 zAsur%?-XtVoTh_3?ZHnv9*EPkfag;%SIEnA>l<0j9Smcg#Oybx$hMU99`X#R$-&4E z@~qRs60jdi&&qX2@`Ers5VP6o@Bqp#DgF)Eu=O7ip-s=>*1kep@|_r~lyWLz@C<80 zvVG+2hj-B5%F>W&Y(w;jj8M^g$rz&N26B;MZ$M`@Yt|l#$$P6atFHaXD%4Zua2>I< zES;sjMwpg1^wGjLfgMaeK4CY`<*oulFTS(ImenAKD4*t``r9LZ;i`iJ514l<*XYJ4P!rj z6zIHtg`M>v2n5us`F+12OAHEs1m88}O?RzWJ{2tRBeaq%`6S_|(c>(Au(v`|^pSJI zA$z3wzt(p0VbcmaIobR=gvv=p8zAOOT}>d+BNZEs)qyRSqRxsZkxLmpf+)}dRRfx% zBu;*uErkTtG_wx5SeBBU%bOarf!$$QKKm|+y2EOlk-DV@Or6Gm>M%DctA8j1(SmGc zEs~5G5H7v}mBv9zXyXbM4uoAzJ4*@5BI8GI>jRk3IJWN&H8q4RiyF2AmDk%0|E&yB zsg=l?19uT4Yfg^9-1~TTsLHDbo7XE0!VX>SA0`o|*@c;io>9pqu4GX zBOYeJ=t7{)CZ_@Vzv%xc>%5{Uf9$*G2J3cv8DSOr{_=wnCxI(F36>So;uNg=^kiSZ6LFfji>~=ck zNPLB`bPMw$;BCnv9R_<*m+3bkg6BIjuSWf6@4$U_S>jx{&USLQ$NkF#_iE{W9{dUN zCik<(B{1R`$_p$Yi8+dA5grhn@EK<*mGhg|kD1sYct)&NYea-zphgLU=2X(Ih!?JB zr(62|(j(2uX{srlO6}U#|Et>(2`v_#on@)npNgUXV>WsUW?NGHvw8&bgqK8;ZOqt2~)V8HbdqH9jHz-29_ z>G(g=3vjqfQ}9=6;KBAr&TGep}!7 z))6uH48$L}OFDwglxCH^u@8TyIA%RY2{8){Hd|~XU>)DCu%FJC5JQ|9;(SFJ-d~NR z%*#$Q^T7=fT4uAD99anRdlGI4LE}Ct(g}aPBF(fQpAP$?)kaZl=wg_*U5)M*L;_|R z>Z7e{_v^J4eTclOzVHh1=Gtty%wFNV%8{@FQ~&;$`?JnHUt_;4a#o@Eof6{-j5E_G zb)dOvQeBz61A0;>xVTP-h})R@rKleRz?tPpyP{eNXWEN4TdeE~cNq-N$1OFU8OWSN zoq!)awL|^mk}T9({_b>)%Y)m37(%60BK!9k^E^VCm+SM)GW1!scb+)DYHcyoX_&L+FT4t@Yn7iizj;mb}rz;^>5x04Iw&A#minWLtVRBk~%*zEYhU4??#)_{a)?G_zO;M z`hN84vSrZ#=&5eU(G(F{>J3zqID~yGGuIJe&SPK2|0lJMtBAj{>~e*WBNw?1SHK`! z%rZb`TTuT{Zen@80=;-(J#`Kl&>p9z>sV(J9(kIy*wEje3YR^avaWKviu4|thOea} z9>MH8QmV9#ud=t<5X|uvwjj2Y)<5qeUsJ3h?TnqGE}j2|1q*@OQ0}`Wu52JR@}F(W zp_a1MYNRQvJs6KeXay&YRQ`a_wvq1bzb&&?>{ty1PNfF&|0nozfcQ9ijQ(1G!%`$M zLTpW_TMB;g$=P0FFm?Wg*F@w0i$eqT%^gW~3d~n{L2)+G2h=>7s95ENDCtT;bU|#|i^GtD&b<#%HcW&{c^^|4x6XN;mEJ9U68)lk+ zsu07+bsEosY+0q2XN3uhPtY?y29UwD0Z$zLi*U#RlBO)*Br^l3Hf!kj$SPU->zWHIDqI$2{asg4)tUXDz7_EgVl(sPa`6i_RD_+=W2LoeeEAf zO&Jvb3D&Yq42JwCG=?1aro0%%K^w|Kd&NxpH*cp{5g8A?3! zrTPYrkEbNnvat@Pkfb$hkOA!WT=5us(`MqLDuMy+$tyIqNVc~H*8?%Y9ZV2LOxZA9 z6-44y4~b!~Hcdh{1?EEdQRAgo!ny~Npp`XXU?J@dC7{2|<8Sr0V!waasVGI8hsp8> z$;<$Iq-ewdg=i5r_uXN&?7j0)V<9;>gsS+U4lWQi7nLXRq{eSxP|{`M&-{oB+8UTc z5C8!Ab{#dTn-~0_Y53fQ1}Nn3aq6V zJg4c*KYRO={S@lKu0;MYTNB{n9Hnvdm1ZBofuR*{Do+w+MQvRk4l#nZfnh9|-19N< z8j3jV@dp$J zrZH-#`5?Ntj!%C*t8F}ys0Q$66FVaI?|)-R-heujq6Sc?+#Q-O#%g?)c+kx&iTSf> z4n=p z)6SY8P=E)QE5dJEi|hu*veb0KcI$)oiZDDZ@u`R?-hiiK80EcyYsb5ZsS)C6Sb*#1zb_xI34vVDnr<_2|QKE4-c1>HY zzMKDYw*Ja#bJ0^Q%=zXqXF07f4d=DGo zZ0NO(P|JqRyjj?*d(@m_I~tgsv>PpB?Q_5576Nb1AK!qy?tM6VEocKrfCA9^MTJ7U z6hgwwm&=RcHpv{E=q?)F4Ynr#fW7-}{4UB=ehDc_w zQwkq{BW+H9d`T(;sB}KAlycYii3!JE*>y`XQiyIvfq-++p?vs7WB+KI=p=Ovat7oX zjtM~*f^;a*S>7Hj6S>)lKTSg-!tVZGDYFsPrZ77=QmCO_>H#BhBz1QOY*K*9yi(h# zD#D#TdPIM&^@{U9j)~5~TI0WmZ-eB5w9|N=&dm0>wWi2wjl|WZ$&&xV>mnjU<^>ra zd`(LGtD^&C!0i&l?$FDX_xb%#J~X>opAHln0Wk9TTGo7dqgc+b=S(C9>cM23B0dN` z2l;bfetC9e;@5SZiSe89&=g8OfV=L>!9Cb+_?_@Z`pFs5tTyIrk$BK1BNy~)j|0QBu3Jxj3ap84QrqLr3# zvEoKekpm?)>Ajx> z93?chfg0893fK|N)yYQ^79&Kc;TBKQqVl0@mOO)dvEt&OA6Ib1`?m3w+hNpgo(&Ko z0bA{v=`I)CJjHEO&=F`k(fO>`nf}kgH7q6GDP$cf8{PFt|MCpcydS4(6i#?xko;1! zhH>VMp=*|jlEQy60pR`q-;(%4#&5H_W`C_Fte9-}go(M406fJW}2!I4Hzf-Wn z;RE`52zW1)4H!8Q%)**KA;*8~Vxwd|HOKz+37JDsg;hJ+Q-Gzj8;U?3^1^T^6E{zX zp%`{x+tf!8%20hjfW?yF3xAyd+w}|NrouH!lPO(;&6a+_(%H7hnGvm~h@%_vY-{h)cC@JpO3FXUoF#skZgg$@04yhN1shcK(GtJD};_6Da=XtX{+Xt%D zd$n0EeT9Fd#cBQEV=otH&x3uvR(|#P7Wv8hMa7=xQ_!?a*DYv%wdxSI@D;vlYq-~% z*c&FL`w{BtaiNXW@=*|e%MJnFkLS+uh5oiebcglYFZIDxFusu5s*H;Jzd+cv@Sdnt?;+#vD7)7k0(Gyo3=d?l-*E6E83ixD(0)&SF5wjS2w-i0# zp&`)u+~~{23NN)l4w*}kJdy$VU_A~*Jr-xn7I-Ad>QX{i-j3VntR+yhHbh;B`*~`| zqwoF7qlg*iwl~0#89~MWPC6}%>3{2PCXHCIB!wl(SdY$3^em$> z@!xN)`mhH_DL44L90Lcpkxexc6qoNfUk=}^FUq%{|CrE)IW0w}MYc){B*cjY>tw9V~?8F?YmCLxE0lp7kk&Pn)YEx>n#~SBDtVpiGVt z`arVvrhuxC!XQl!nNv$~Ec)PFPg+SYLy{h(k(pOUX3}vD2nChBo5w|RGmo`b&kHNw zQT{w9=%@Hyh*0yfbc>@PhsY$`xU%#9hz<`%))KJof0xL>M(_urCTPZte+Z#J@UqN_ z!R07|?5$oc@%V)lckk3>apw_DnH4W>rOCU2u}*d+M`;EAqcIq6pULAfz^)N| ziV4G0SEDSU!Li1`MnFy83aH1m>@V?59b97pP!`%J+9ZX>wm-UVp%yF%^0hj*2un{r z7#S!qQ+7leRvU_z1%JWs@TI>?VZ84)J{1Xjm# ze${-ImD%0g;QHr{hk=iol$KXbY!#g_pQejqrku0;4A+HM{4G$ZJF}nUdd+<^zRvl? zqlvV6=|^8=``u&I7WuF+3FflGMJ>MYc&&XFFaWe()%0{ogY1>IRwVSC)-qkU4P4oY znf*>CXJ2kKO!mXfT2Gxi3d}_6gt^~yYcyD4TNO}K)&4|r7q0X!!JBE>`S(^OMk5BVCrseY8M zMr88xtA#nKq$Bo2psMNtLi|Fq<^mj5y-AB^w4cXvvqtCF9(ty-k^o>uJm#?56oX$C zoyM<2$n={>72)b))b!=^VA=r(IjU1}ab>09;6nY1U=Gqu6g#_PK($J8E&FTD|BKaMfRYUBxNQ*cTcNLshar;pHpbfGQ1qx3Qb1b>1>_0RjpZ*9yjYB$Tcc#v+G> zL{wBz6)UZ1EN1636JWJ@kq3;%n)55XdqSIFA8w3Dz}G4jq;pnSia8gQDm$M^3cMV_ z`dE8aua&V^mLM`F)z)h})T4P+^&lrPG@ruuH%Tv)Vwc+vwpH;Ycsod}H$yn&OTp}y zc_6fTnm89&GLEn?yqxHI{`KNs(t7_ESdXmWbirlNAo8Dgcdcax$}vYdzrpE~bwz4< z2f)VDTwlTXk4uyv)i)_kOc}(k2uA5~3w)lD7>wA?wvkI(f#weJD@O5F14)swV^}~j z{u@}Br;J%*EXTb-L-e(!K%TQWe8;1U(H4YzJ^ zMN1Du+;+CLqE;SIytlJtp83F?6ns8cBTd?znqDD}HTEsx&R+x=cfFj-vqJRBV^^=l zdmKlkV2jmHHOb$NL$GoUhi1{nohhuNCLfq+*>(2v_DX5}`06#$cDxl-t>kxEI@7l&1siv%ko@N=74}?b3`?p(JJ7&oA%@VKejzaA?YUhii;rjk$4~4yY6|i zt}eoiWUU7$?1G)r0*7Ea@sAdDcu@9JeA5$dY~U_jfLqIEZ$_7*=(4W;JQrLRcRHv; zP4}W;XMl;b8=o*T9|rnFGpm|uyw$`FtFzyv=1=Sk(s?Jot=-Cu?==f6ODs*dv%@4d z&$c65vNgJCzsB~a^-l#NBtk*}rxKMP1v{5O&tk4ip^-bi0?EuP-_W;HU~<+U&Ha0w z_krj(O{cK?it{&_U%eKjUDQJB-0+#MwiitufvFuv)Kf)ze8j4FHdZ#r2K*zOxr9fp zS#&@1;9Evf8=9f9QOhs}!SN|K>qOU0$r!f2x$?gzVtj^LPY zcDeP#j=(R1gsk>6( z1Hs=HI%QUN$Hb-*U;$VU#y>hq2XrI#pWoHW3TvZ=KboOQupZ5$?X|iP8=?}FIdc;u zwML~bdehsto8i4I63zjQVTvo`t^|CfC=dF*odv2b*^Mo47f z=4?pu#cZI4DFE5MS7!oG+@wXAms?SC1XS3%gvOT!BhD821U7)+F&mfV0EEp<7 z47fFe2{r--2HSjW87OG@AD?%%Wy=!~G118BA@N3mrY;XSoh^8jIS|ahvu(0)eBgug z)ufPh8Fr^O`?W`9a`xEpK8CrZdd0&@w?o9dkTxFjjfN-GQlSk+al8m2j8_AcG&4L2 z_u1gv@PrKsP75?tTvlrK8I&xZEKxbfE>(uW!4)_eqf>l$H0Bi0> zVp9n9n)N!IV%I^rQ88U?!mlrS#jgj%MIn z_j#1|A$g8jp0Md;){MSgJ!iR{T!(nFHXu32nMoV3ccWw_GC(N*1O1SfTYiaCsErNGueUJK;tk#R==aEV)ioq6Ji0n zaP6f1y=4L{0@%PaM9uZ4;7>y<8=TSksEZ(F^{CnXQn+2rJZjEtf))s2lNVTz7Q)@E zUGD{Q;;fVFf}o1b*$&sxweMQgVRqQv%f&+1IZT=yhJV9Ca;iMp)19zf++^zY43Syb zHMT2Qk=j03Sv?3Nxkd4wsbWxTyY;joEg9G-$NZ`f zZMPoHz@M@AW9xQyA(SMqr^!QfjeW{l@MguE_EzRlBi~%lS4r}G5QePPvuT1yeFV_# zdVvtEuij&1=Y@6mQ?&K*mjUeS?a$tBPevI8!Od`0kk|AUagqSE6uz)z@dHq<=k!q$ zWCreUxEvz9K<^+1vLa01S0l$G`iFPpXb#{uF8plKkmznUA*VtS&`?2oHlw+8`fz~I z)FqVcGxaMQVl^%Wt055z*__lJkGVj9ZKgA<@LE-T5}CkR6Xkis%;T^%vqSWrgymvw zmfO?9X2&Z#QfFzfi9$`~dHf_-4%!DWWdy@p>HtDLQ4)~zgf@EY`tpyZ&amAoz_k&Q z9u!OmdR}Ofu-xr+hRo!Uelr5HYgdF~wgWZ)^>91WCQucGy%T7<(}(A*i=b>AIG&!I zDaiWzmC`;$(+Tr+=h0Th{NoWefb8F;*5Z6vECvVYioOHd~PUm%!c5&@2<>%lyawG(j97vVn@d zgY7f)utdn!=eNwGxiEksNkK;Q#Abn8e0S=IeUyb13S*{|{=)s{Adw3KF3;lNcUmx7RGH zy2Xfp7LL)+Tqe&g0cQ;C>(IyuNaL*j4dO^uBJKf0&_4>rAuh9#!LmS;BlLbn=w;Cm zEv>=@W|;s+s3f*M=wCxoSnYFgeZhwQxvtfxx_a&Z?;3ZMm$C4We$~YU>tx$dQ18$# z(ti2|PQWlQU1xMzM_a8n_s8oVcsYtE>FuX~+0;DmNiCv8oPSflx=A(@7@;bcmNvMQ zyqxwO9!#FW0@=rnzhR&vun!1kefoaTT!Ll8yz~C7V}MORQSgN}+?)JX>Ur$o z9r{O*Z3#c&#=qem!9L;uS;q+lBZC2o#DfK@2zkcqaF8z*V3mEZ0M~Z$@oEGPR(PMo z*Z7xn7wu+PU-w{9uSPW=2g^tBDLzYJ&DC!W!AI;txHBNsl9i`K$p+Lc5u9G`Je2 zF@eCdhlQfJ1)`x2cN~*vVXiJt?D`LtzC^TnCaoTBI-Lv-I$~f?i*3JaAt$^`3%7>CmTsTcu~nn)wYG319<~kTc~Iu_30 zN2X2^@-Xy8xyFS+UQzwuqaXw18K*$VN#GG~ah8HJqdy&wzYUd8(0KG~`6~uhTTX3; z;s&=B%)5E~*ON~vkv_glcrPbJ#G82~SSy~dX47z)h>*&Nzsb_*0Y_{eC5Ho>TDCh_ z3jQ-YZxvRn`_0JK6(hIJ&7wsYug#U$e!&4?}Gr4$50O?3LZ-dA>99 zhnqxwaSM$CDo-B26_4EjL^8OB>JCD1iPC{@O0W^<2B{4KDj8iuHh(3_-qOuALH)9hokk^$VGm}8ujv58k0qh&SjTBE=l=~Fl zR85=pR$uN~o7F!K2dU%92N7a8-oM*^GUJXY02Jd=P|2^{mxrC#(Ni2;?gT=iP*mXq zw;L`;+Kb+a=$Y7qG(72Ua*!w%>9|ypm`YxskFBB*&jL{(jWiyOy7wY62jb_1|G|-5 zGPri7e?8cK)g+I0AL=JQ!r8@hD#KwqgT71tyi7HIPI1U!UHaK1G&@F2b*%MXxam_j z<8)~!t+3ydTd(}pMU183sIXFRy$?sw$^0i{*w;;mStQz=K@E<2_1g~_~xXbli? za7muM>B1@s(Xb@8%8yzz+zcZ&++QWRJF*lsG6&|HW~<3E%CrIjAy%uH{;8-WfciOX zFeyuvD_SN2TV#9n2_n&DrtZA>-n1L;;8$e3cssot_m!ZnPp5L!$puUW4n@P|7*e%6Rg2;LgQby;Pjrk^Y;Mb6crY6(_{$8Gq)b&CZ#6;)tBa;ks3tS?c{=>lR86a{p@jOUag`Z({qi}kGZO{_5X15u0d`7`CGB2=*1yMb|((~8<@kh;P%{QW^lS9n0gN1xtOZtUx%l5Q2xG-6Fg{*_eBn# zwA~&fJJrYL0^`RuIVc9Sn1t^-VBOG)xnu!liU-R_Imb9& z*G2>Es8D;jP{YC%THW?WC?d8HhMty0FH+hj9T66)U$U)qkj)U}q-xoI6wa5dK&o{q=C~ zzDVmr)oZaiUc+_U7M@dekuAR1&5na$2fDkqd>+nQUemPVlHZI}m{YXL-9dk61CL=X zq4!_?)%x9-6XUhiTtgk9T9jEF{PC(7z@bh$va}@q}DAB4~XVt zkAQ3Czw-E}SBXsNl<5zM-Wtbn<=hU&$hUPjER@kdb+Khhvs?!UiyvbCcV^JaOXyCK zy8zg<-U|U#>j0ioU@)xmqG{qOOpmiJ#bOk1)(dBiPp0(hK-y4#Ria2EO;UXDaFBT-`I&gpqY$#zjD zyR0m*VO+mWVe~ElKE;aaZ0Epe*r3}T`&LOzetQl1Hu+j)-8yPw_oMsu*QT}N8m>i(ASca!dS9aCz2L-^2%OZK z^nmT4tt1M^@${iX-6&pe)&qv(6v>{HG85KHbaFEm@|Y_`dJ5s*eGpUkd=i}BoD zY1{|BkjC--bsw{-m;I<&@`*Np6&pUJt`U%&%WVgGTZMNEM8bTVEG+QYojn%t+ z#}Xr~DQ5={#u($o@h5!n^8(k-Q{GnwRBG1HbtXn(M*oJ?tOwn|ZjXsR<)E@m*VUrUU8kveEJn zyE2UUCI>GPaLHK;q@i@O9wMpv4BeGJQ*_{f5RISHYb4e+tulMk%`bP0l?(3_%;SMg zrsIB|qIsk`-9h|^6v(vX_(vG>iNGF zk#dCHtL9VYvI0dvNvPgE7hBGqJu<6o*%G1U9+z>5dXC}?s0n3kvG^_;zz;xuT}lFz zx`Vq$if*mDo)45R0uc%W5)7lFJKn4fUm#-yx+CYI;onyz7&STyf_EcN{qe}OLS*j7 zV%Ra_C2&??Y6(!KMd<_(5^IR(BG{f^^0viFqSbg8^$X$U(t!I2Jn^rvveQ z&eJiWw_D&QcNN|&50k<*rH4*R#yyag%1Kc zTT_c_v5m}+i|7;1OPs1ha=Tl*5>Beq(wt|E(@F9SqlRm^JGj+YFS!<>yqN7ft?NTq z7K;V*4S(&17`=;djX93={$XC>!k@oz)DmySDr0w-kFUt$fq>XA4rZc_X=Tn#I1$3` z_VS2rQD{IvZ(WJ8*LMU;n6>I)c8T82t^5t5lXG1z?ZROTchRV$I;7Zmr%atrN*Z9S zZUM1$t3VWTCnmWd(%ncY(gGlLB)b1~ztO}HtPN`HVfZWj0t za;p|MolflpT5aIzZ|q#2YvlH;Mkh)#*`g$oQEFIfR^jBLL zs_(`+BP5;52f-9~JGMxoW>bE`0LH=P%ff<2;D+fO5N1RC`(qK2tMW zdt-FG%_YF7q7^&|SPzae()A0XFqw_U-~2c1m`SP;TSj-A3bXZ8<)h~rducZkF)?W((Q`)j7t*!U+_`og{+nD}!@eO~H!YQ7g9PNG&CgY4> zv1{0QH02pRINF$ibP4O$l)2z2U_3r`z}B_MnUW7XpxZaW7`qPIucd6N8h?aMeea)+ z#>fsTt&u@BSTVO$#VRwop3bZCPBTy@P)}8h7TewaJmu!3r1(7E@eVwan?)lzxd`CS zZTJ~Qe)Nj9EjK-`>NjRX{1o@`OEtg06tgKMJ*?e$xj z1q)OS+|bhfohf%`JADYD3KuFff%ssGKCIvb?CTU^dUa?k;@H~+&DOfKE{C@Ad`v5| zL=xOA;aIkVMJoR{h(v~^9MdSNTU`zFG{eh}yl2vS_?9V?!Fq8J6hpolh zR8#)f$qn%$HnpgHqhYi?HOr0k4aMlZ@z3vfMH5F1N5)fc!)k#xNP@gb=oKU<~ z-0c3_c>@6zP}7ZJVq(7*>{3N!DvcxrZPhud;-Y*n)|f}lg=i_`i;bc)@=k`32C>g~ zVg`}(l6eQ2AC-9H!3rMqsok>0$yNhUlB#UYXMvNC5C62;&;WVaQH{R0z$oYsrDuvZ zRZ?Y337{9bPUzkgeTAdgkTh-^Y^?vdii5W;;n*|hX-AFj9U^zw7H9);j~&>_T$QBv zG`LjCV-fP`BsKm3JGHGgCAeQPJ}DQQgq^4M@)j!;L~sv=vEg$AB9W%@KCX8H^)z(s z6@q+Eb85Sb5NXuBh{SwI=T9j@mm1|1CQhgZxi!T{WK3U8cn2`sa!xE50;^`UlnD2$;W0yh1C!CK7D~J>*J?dc8p2 zwIlhDA<3(Z!kgoXEFI__jxOZ^FZCJh0#s94)Av%9k*M%RCLOv6h_JBvDC1ULbS}mM zRW8AJKtw&G7NES+=YfCi<#+@ArZ|)(vNsa7z%-_oxrC%w(IR?+iHNU%hBp}~J#+I` z=Ep6_>If_SFHslw2)|5do(ri!IeYYa3Y{y*1iBuL4?5ZQrFR-`2m6R%a8>Zmjj^i* z_uQcg^YKMytOtR-;pe-WiFj=kM`tB4>aabcVlPdn(rGvlBfIlt)+A9k^NGKNa;YVl z8q;EW(kWFui7aU}6p2JlMzU&AwfbMhL#7HAY*cWTC9(GW?vtES7-ghtQ`Zf4qif8! z#A^dqzsp^%lWX-Ps+IJn%c^M9GI3ye^I!NxHirpIU6}&)^-qiC#8i_J4tZAE#mbI? z@td9w;rr*>C0}9SV+wfQ@T;RXM!)lE!&!y?s1atC-f4wr$sCTf-v7nONHJ4{-j-=J zdfVRitZ|3Ho^Y1LYlqrj_^~t&&)_9Xs5k=IdWP*R)%KN^M>E#yxL%eB{`bW!pJ1xB zFAI%R{1oh!8Sqeh97}KZRwNE#IYs0hkq5*|60vw&Egt|1i(F2pzgE_~S`dr_%C{KK zlVF3ak%FKZ{Rf41$g}<<_)G$zQ+8n7Bg$s7Nu{Jigj72#g!3~ct}Fttw4)MT>4>$C z4enRsILh4!2RaOX`S0TOO4fXW_8cf*1MsG-EPp8&Au-&HB!6&%pblf&ztaod^Pxq6 zj{6m8RDuFbkVFDkqH3VDL7}Lc&R>hL9Drtl|n}#y7HkPtt zA@4}7enGN>Wh?p&2YeWuV|oWf8#iLQRT6K|US^(mfBZ+`sa)MLsNe@rJ7fB;WvXBO zqV%;BM&F}{Nln7p8XkN}e3+y)y3Jqc_68GA&J1dU9Bb+zg{nSJXluD*Z=2MC+9N(O zY}CrZLH8AkgIST(rj9^GH-1RBkTfT9VTnwmRVRXk&PoKAA$De0EI^{JD8MBa?F&=5 z4dx4?X`IYpkX6V+B#1btJbK;%X$WVe6j6y$`zM^C_f1>yXdIp>HR#1#Ly1(#tSm!; zv{QS0p23%}v)ME^)c22!p~gryValoe5T;rA{iJQ%Jjp!!%Q2s3tUn!zp-+E-sr{kP zHSXU?dRU-wh5}vuo4h3_cV`sI6F@QAeo}jh>1gRm^2@1Wd5HMPZG((cuhayhXdoYR zU8GEuXUMzo!rf?G2vt$h!>RtlC0?XJMX$$ejv68R1>;U8!+T`ia6H=|cbQ`YUPMV+ zNqv$jNoor|7n;ED<>Sh}BwHK8{GNVTwW5Fx?x~_CJ-$17t^GC98+s4c;YlMJRyuz|}wzM)gN;W(7JAVqxlB z4P?f)A5w8!scN&<4=_g8?V+V8!zla$Da6erH}1rlu+9={?Ku^ZO=%ftBeYTU9lH~9ANN@+pVBGizwF+^rlVtTh5mJ@JcPYE+;r{Hu#-a6#FOKj36_`G}wpQg4rs|U0JQ~ zDk1uGgB}5`w)8Y*StxN9N`&#=D`E`JETrgHxR-XduSm5O-y*4;zfQ>mZ?Se_NCIdS z23bC~mI+TM0l7c9A&9;R`C#Yk;hky(*?$ogL)=72i=G6qHZ#lvp^J-8@Z~3q~4!YK#xVTAeZ+ ziJ_58G-|ZXm1x(P+*X4Ii=5CgNoEh?-)x+w>H&ytKN7R zhVl6e=d+cqk46%YG|1I)oG>hELl71 zW_HLuV{~Z6)9P2S=@`*1 zUAZ>2L1R$yKanMBcBLN!O0%{2XsrFdlh5!E^VUCD!2r+~JcE6evS@DJJyXr4Zh6A~ zHyxr=YU>?cnX8-DK{o->L@Y0vWQG1EY%if28^l3m8<}gWI0&Jy_HFHn1p`7U>8`LS(6d>J zwXOyT23u_%T`e-ZxzJ->f2>+u+PfHy>Qf2!goxM%BjoR!oO>D7rsV!s)e4UnsCm*p z4RgmII&!|@GH|Be_1$0<5`J-gv(RwD^TiMhRsa41)aRQr-)$6lXG8n*AV?;UFBFV3<{E+iJ9WFbUW?46Hna(Y+(glWLJswM~(+eB@>QA^7nshfLQ5svy|_r&FY_(%uDkpCrnubyYd^ito&d zU>PV$+{2wZ$d?CCFIN3wS?BJ%ktr1$pzoU#(RErZ=(?QeKiX%N+j{%bO6hRknD(pt zuGhd@&NvogBr>wXq2Yv_dR)qR--nuwlU8KJj#xXhS`|NxI30YwOmP36k@42l|5Hom zb)^ew5%0G4;3Lo%d^_I~-20q-|0x!z8C416=Uk?!t#CAbgVly?(>XiEnN4t9LZcxU z5@g{Hz>g4Zs`|b3IeWQumn+sZEO~|6br9Jyh)f6dD?5Qz^Ux<8y zbC60D@Dn3PV?B~|#xSyv0EINw$K>lrB;3Hubd_bRi8DXESlI?g!kP0)M{D}=Ag+oM zcJDT5o4NPT^}@hGE~>hmgG2^;R=;K|oFr&T;M8aAFZy;PP#-^Rl1A>7cNv0N)`o6e zwO{hAw-mtMk)0QXYSm88D~>lC1x_`CQD=?VhtMcA&RpqczCweoSRtSZq6QuE>qu`# z?eKd^TCKKF0U?$cP?*x0b9L*D)AUyg*^gA!BG(TQZVQPy)F$|cmpZ#05o9~vv7$h; zFe2hndLxlIDd_~e&6RKVw>E5Bd1Z|Ae%$+dPcWVZx$A#Dgg2sjt?$ocw0`^ zNvBHxZ0g^q+6vA%ujPz>8;aoJCu9^fi>HQS4i_q#XX9P;#T^b%j+MP(dqI(ac&qca zAWB}`nJciNDb!&MT}|o3hglyWQ(!TOoppG~YFP%C6ctDKf;%cx^@}#p<3!9M+xVV+ zvC@rjLcH#bRBy+<0MIAhUzq9FR=DL7AZ&>UZe|_cM~Nwh*-0lu3UC|cGEU9c>l)OX zYgsH*PCUdJTSd!ayN~3&Pwyu=WMeM!{N7*k&vJ=GH@IVVoJIL*`!BwPksmhoQeLQGebThu&pggNU;HpK@mV|jU8sPA%E{iPr>c=+S-p>9JFFIk#f)&{UKIk}aBFPQl>?5h+n9EtX;?%;X;v|kI zq=h9r31qi}f%{%suLHnP*{hMe3+jqIM{<)7_kpQXG4GC0r$Eb+!V*;e z00s|Nkc@cozPYqZzr)((nZDpvR_WJ>{r*A?w30mWx&8GCYA|tj{k7T^N$$*eyb2D` zTkp&Xw8yns&PTg^2nc6mvKx&Xf>Q9jZawon)91QYeaWxXZUTDe+j^W#XA4=qsfj|0w4MvV9rhdcdgyqd$B|Sjwg@#kOuGilZ(I~9Ej%Nki3GBMI9KPl zpYuQLBO%o_oR*Gde_YZWY%y?{)5jA5!=I4r@>B);(kXyvS*q9*$iD)^R}P58-_NQ#fgEU?EBc{*5lsD5PdE@XUN9D(x?HuTB+iyo9Oy6(u8S?(ZNyOfkae znZZf<`G{04P7JaB_c7OJS`1(2l(K^Ki%+ykag(3sAJ=dylyI@NneUt(DI#YrH5aB7 zpBtL__Z(=D(>uuUGat|?H3@e0`kQQyk?yby$g~dRB^*aK`;D3t4i6{y*Kf#HI>>n2 z8&{Gc-wr|@@fiESJgVk$fqtpL!wY$DR_vD)quf-9gzB*kEb7VzLZuX?(Al}9r*r_t zueBGB^_LX3w+E3zf>v>8H;ny+0GU)+tCvP0fk!2)L#Ac%-XZIz%{1%q@xZoM@yag@=O~tv1{*byktFKDmbnO(Jdr9_8A+2 zWSr(q zY@m0N6hsG-iMLeDbZd}BTp=gQlmALrU^uAJI|?$$W>U<$uEXfXRscOT^YI?3qxu zA9yMq^yr3fA!@U0UQR03g5^DI+ag!T8+m~}p~4+egHVUyDKEyethU^$h=v&P`e2rR zoKczeh)q%ELM-6rF$O#y6dre#B&t*F2bFJd!Hw<)>GTI#&6(ia0LfOCgjR=x`Pzmd z(PK$;maj*x?v&=4U!S3DX{Cx6qo7-LXI=O9-uH45lC`P)mX8I*F~&heB6%o|kvx@b zDCfRT8jGmU*!>Yk?7iq}m1I;_F+TS-;N~V|NrQg(2Vo+am#Py_* zbXCkW8R)FNh}!&f1?9S!_Mn8G5&|Dp%&P%CRpt~5iEFsAgc*79MXWTj|3Iy*w(Gp{ zp}!=u*}9f?b41QyjyR}kX;{HQlF5&-U07i9?}av?L6%MFNajDY)N*N8*#Xb+AT zH4~9rw>RV9c-{)37gnhK6Qq~t7>GLGR+pCIWJn$}C8l7-_KcUYsECnf% zapMAq-Uuy_W{)ECvE+S37Vapa27Mdg&xYbK+lYeTnbp<14ld5W*v_Y{$bx+Bqj4#EH6<61 zPIik#4TK}g^_%!*p^$gd$(9K7!qEKaeIeY&>X=nJI9Y5C2)~a*H(aTyRsVJu(X?UB z&=E1E^QT^gS7^l=mGGu>gfDJ&9Y0a^{$EeMcu-?%&|m%=b+WS<1a0Fq>Gym#G4(jM zuZ&#VbFcgo|7>d~m3J3iLzgd$9$%CE&H7VwY@uiUX$cePC4=83q}X0zy7abX5pNCq z;kR}Ld!*X4P)0J8HB{Pp`|qbYsJ)wvvseH1wH0n=@6zRTM5-AfIU1Ed^*?FRiGLmH z+yl%YP z6`Y6Qgwp!uY|FG+hAUJwc%T&p73aG>En=@Ix%5m)c6Mx z6dC@+?A#1}?&y8~tAx(;EN$^r-8fw%RKhxyU#7i2tmt3Xg!atE(J2d(?3Co{D(?FG z;-7kNh2wTUBhoZV$>y{Lf_IQ6wdGHWAiBKML9Q1H%o9LnC>>rto|{lg>flZ_6pf2D zw`x18dIOT)V0)+Iry>tR1zj=H~`)e_9@AZvNn_*)_nIq_VpiHP%e_DcevgnP5F!10Nl+=ol>T{Z!+0>Z z`1Z__3H`Sh#JtgLpVN=KAhr_~qumi$eTZS!hE#qs))$V#9pW^+v`K!Q66QFtVT&JR ziIk4G?MCD`Tq~?-p3E*c)XfF#V=DA>Wumh(-{5?y4{H!(;&|^xAh7Kuvv=HSOXeO# z;7-GET*sG4!ELB^@6g@JI=(Qzb!T!vBHBT*3Z1;p;Omi+9 zHN1xLQ3jvue<@F}5I$W^WR`#FJxgxy9gQEQ>nE^@M-YtU$U3O@ps2Wm4(2)5es6Ff z3Y#9EJ2iHnECCJS0R{3%JDC5hZNQr!{Gtp?9oTE_Qc0%s7V3qKS(khS+JFsuSQh0( z-v3~+g&lXB{&y0yn7xHYkoNzhXynWE=1-_h&xDPA_gcR7!DEfmg_TgjR#AZe53+FF z>enHs7YD^*yf;f2Psvgc9AT%g0MN5`-KQj^WO6QUS{rP2hUPBNSYnYEu(oQ7GGWOv z;CKjRS1m!3>bLCR;X#sdU~8FBxf6HThMAeBJ= zYo3X4CDncaC9!6g-P{~P@_IU2Lt$MX7x^HW%x7~>!MtEM6 zPwItnW@+V?CN&=Xp0ptMnYmvyw=He(FmIVowo*^HZ}nzGaib@bHGQe#j_jJj-8sk9 zpc|FD2y4Zb6#N8(5E^`m^SHlFbP33O`;-J6E~E&Uf*NyeW*9Xir>ybi;Y~9wXfS`m z15Vc)q+e-2|Ch!4HAqQ?W+;vzMM zSz4RV*fv~ZK{Uml=Ag4DZD9~Q!ReTK$A95&bMTP5PPD7=i~k9#rm(=C#pi3sGLC6L z%moqCXwdsNniDk_22|}RcKhN?gUwLe+go;=A7lrTBEK>RHsQ^KRG|0sr+f5N!I@ng zD&HIwDM<@5m*EfqA&6u2SIP?2BU_28g0)3=3n3rFgr>akKfy=x#^Y;2 zu?mhr_XP;UE=<%xxg4EwwGb$b)2&(44~grMnZnlESrrPy@rSaKx8Ln$W@9si*&J!B zkqh;)E^R(goK{UE0n_;@0X|JJ|MxHMt(Pw-b4z>c_<4lQR}siP670$0(zsc~sH%i8 zWP?Mu9V3z2n?Zv8Ks-zjk0Ie{2C;+vHqD8Ts>L|&nImAiAKq4*s3`=|PP~mbD!TrF>2^&oI;GWICdvaKHy;|wO6_+oZ;&)P{jQ^+Z*DcNcbC0@!;^Z#11al<{rV3b87&nYZ5@1fa<-v1N&hBl_b^UBjpk+oe)aX#?w7ml)Q}mP@ zkLGW&#LvGI;k=(Tf2yr0t3eqh?&+9dW4jM5AG^~l823v-dWPGM#Eb2a?P<+vj^wn}XXvM+_hqsJkY0`|=RTAYcxgT|J)g)=Hz8 zdg<>~y?J6!#Vqf9xj^d#8eMTxAq}Z~Rw9f*8a5HB72KO}HtvC4fP{Owj0e$h6tF|y zVD)lJmev-V+269aVQoF4Zz=-$mp0vnOW>@cQc2&{jTS#dCII}`{!jGxtAo8^(qhM{ zw`BB|3X0yTyFm14##WR|2s^mm00Aa8b255q1B*$M7VbcBc*0f{!0CZ-a2gp$dR)YZoZ1y51G^h7*P6LujGCi zFQ{4j2J?p|*Q)q8)#QN^B(B`fU9SD$N}J~q%MzcKjjSiaZ541E4qnP624l+IYwMBi z*$ufrsyLu!BK5=Qx=iN5RFoj6)G*zmY>m<3q~55>NpWJDMg*0k4+${dO8Fn%I)sP_ zae|VG+I^Gf9Pqt-{C@BjLYIWRxUNaNfv6b*H8Rypau8#!jaJhDY5Rt2ijT(}RR>+Q zElY=)1bY=O;?mPE$%P9SLRBgYt>9vL@Nz9V+Qg4Jc(6$Th>>&NB}1eMr@3az#6M48 zKzK#SxmoC_Q2L`hPN{xz;iZaHUPTy+C(RFJZ0zEG`k_dT;tEP+;?8W>O)jp;b(79M zN9$2(12B!(_{c>Y?fE5_S z1fBmaPP|@9Pv1vj^Y;XZBbc~qx=udKUYkAk$LD%MV(chq1r1(kw>2^ZySj-l(M4b= zlJk5XSm&br0<1$YmVe~Wh9&i{>CCB0Vj=F@vpSAIC)@&$fr>Rb6XgmUcAwp%o&cyB zU90}=jh++a?T3Y~<2Ebpk&3?ft3&-;NM8#-&HD3kjeYJMR2>9eou4fTUra=Qz@J?+Hl%ejOTX3}gB zx=^u1GXHld^?nMpl(sXlTzlKj)lF)m z%icNkC@?!@Ewm-lITIPnH0(RTGkc#^xzvdaly>IE)`l4HSO5?e$xCtrpI{9wxj6}h z=ie&$Xn+(~me&(aZUbcvNzfQ0!n44olRhuP0@u-!Yz24?L$GkzGDXET2F8^SVbyib z;t`hcO=A`wh1Z?3;_fG8$m6#Ri`B^U6%J3UcW@RYfC<$Sx45IINaA8Bgc8TI~@|p zw8(azM1q`9@xc~Fa_3gwromQ5)l~?MVxw>+lqfmSCSa!(TN$4V)K2llqS`=;AJd9S zLn%Mk7z~ypkjnvXVw)1B&md+cy6k62PKs8+>s*oLkI=!N@S_#O<1g?KC(sf2Fysi= zCudBXYN>XB&uTLt-e`5+)zfw9^$w}JfGkkK&(Le2l za(jqGyWR&*Sy%>0R$&7~eI_W~=+$FXJr;+9x4k;x!ITM50^6<3P}Wrt%2&j7Hf{`T z4rAKf?aolJK48 zPe_ZCVbx~nL;R1z2q@>H7F0|;X4!hiFuf@Dj8FzD0kXhIOk^2qiU^(Eh8keag~DI5 z^fllNj%1DFTvtwY=7~l@7G%DL;$n0lzNSUk+9Y)JkwJtipU&xcc-g})AUBxYjOA%! z3VEoA2?cALLuL{M#&pE)Q0fAh+r!d0*-K7cg<~;ee)V^*u4mujeS?`ZenVui(iH;o zFCHXpQ5e0|tI-4F<2I)3E_l2XS_4eYt;m2!2gLhM&i~4teq0l^WHw3|M>$&Sdjlh_ z5y(C9o~UJYS_V$xFca}z>d1yrCo0?+og38;%Km?2URzOzC*@`eEZxsMi{XEgD^C);c-j5mi&oM&x>&4w~oIE6BFb`YV2HMOYi=NJ7V!FLN z*yOMXPN*4EQOWw9oBb|zOcgM+HbpiW5vRG!nVnU5f|ZM68$daEmcX$3!&r6h{}={{ zdyAi;BeMRGHp$%-%dtSPq)*Eukz9(1-JHv$|QdlxCNBmQVC62;H^IC_X~ReBg26FxVQ*jzfhYmoA6 zq6MXN&d}W-Hc^gaKz+2~6BcV*YN3s9&WCm=F66r1nNs44Ca>i_wn8nP>-tS6yKNC-ad))j{9N?(`REPfx?YM zb=Z+LD1*I;(n#s-$zazTD~C@`?dJCNUN1LW8d<#hRj@fITahq1rE=HhL4c0hbYIbm zZMab>OSWXY{G#J8zvf3H`r{MxAF7}iy}0}tvQ<@p0ZE-;OFB=E%CO>`M{#ikv`zRj zL&%SsmSn3D169g{{x=C1LmianOJX1!a=mL6AENjg9AH<87l?Faa5lg$hwhO3m4g$l zgd9>yR49af?5kPb0lS&{n{u}$;FwRia57=*Mhf_5Dnm4grzok7iPn-4H?3P~>qsrq z-NBXgyvk{(F5)VQ(i`5nopq+a%C62Fpm9f|ZDiPv^08Kq9N)#r;IFCJf3>*Q2lob!6xaw3m z&V4RbO~lhz+TkFC`-}w1-01Q-v+}`!`|LY-lC&;L5_srn=tFTZQ%47KRSAypjx8zp zGPz^he~4oyHhk4i=CAPQIrdht^;k3tnz0-R1z!Dc;L6Va!z{|YB4P!KcDO-Mxc@dk zKBeFS0bnMYJ;F77%T?}n2?@8JAU?k}`Pqt?biDgY3c;Clu39eX7ve-<01*Njs3}#U zN0}OC(!bMiJdhAT2mBt909mP*x&6m!I(G7X6InSPL(9_MgUu-fhUk?@epUGQi}*=n z$e33NgQFnfPEvgaZyQy<>E#y{w>6>^F5uFuPKStN+2ig-D>^XQZ3AD!ju*(!@ovN4 zX0tNOR>J#AIhmXB&?nO|HhRI6!=xs@e3>#|@z+9Lo}G}4S4 zJgCpXOzD;5Bf@SQ?UMtFmBF8Lb)Eyl8UTvsa_dL()E1TaG;!-_T7wXJmdWgI2UX_$ z$V0>huDlyd90wtPlyh0Ku8{%2Jcq7SY}N*XALzc>B9{;|NJSvXh73{|wSVCQ)}=eh`U8rxkj@{4z-~M)eTp;^C;hG(6U-sA^Z zLX4Vy?#npqV|f`R`m0{!^`*MPZPpYZ(uNbx=3%VJX0vzSdA@P2P(It@dNz%`ZLdwNBtP?fj! z8;Hf?$o}>Oz(_FUwz5?7!qWHt@~aYcfJ^H@mqjdaaI-M-X2~!@Y{o-j;W-VnzvrLK zoG&W(ao7TOWc>CaVm3BeeNo;OVJNGC2Z$yg_>I4+JQlkF+;dzkOd=Enm`C_m*Pnn8p zM3iG{+#-+PwAIYSL7eG=py)Tn%7Vph2gY6wsJ)^B*DCthXhqC|8NitHj?^_$pBA4O0}j+CI*5lrp?uK+m(SRr(G;ThZR;kX@q>fZE{Cl)$DD)?QX zAC}{<8l^Oh;SW8Odj5L=Z3%(FPV3`>(IyDO`CVA+nsP%jOI>s4bHsB2gx5Gq){7YXbk6$7y^S`lg}dk+PIXDda|YeEE(U?B0|}%z z^3?TGH77cCt;l$bAwZG(NF;Sln|~bn1xn7UsaZdf0lGI$w>nf0K3m(L(c<2m+B53hgbfchG5b~;Y3hKB`t$4k+NUr>EXaob1@DCH(x@nQq zx5)O7uq(`jhpZsdr%1&yp~jbKP@xmQQ7;gkJ>?7m0gZP{W&tKG4S=3hIfm!98zm|t zcdkU`HNy-6Q~(ffXdNLnx!wVDz|kT}S-5L&hK=YJ#@A5zofi*b^M-Z7bb>i?V~>gW zPQT?F&t^IJ9#|dyRa_w1=j%LSKvy0he{>}F#H(RMbcV649Jz1{n7G~ghFEOMyA+sGlrSA(x;GwWAK{IxF1UHvXJR727~$%*N6h_iK>zEKub ztzAnTRZP=0Zrs*23*jEexSYTJm@1xC8Dh{GVl0>g>AgQ-yu89>T1lylezrE3*>&l1 zW&52hhNTKp5In2j8eO(!Q6jxNUXNecq2luW7BR@Bwm)oiC2XSXXGD2 zS3X}f?$zP@OXln0uKof%2+At$$TvcCPKVcOzK{v`;!|?b9y}wnVW>lJOZ~AN)S%_i z;cf_tv#JyX1rvKaNIB@@R?u%FZIwo)KofhyMC;u79k9206?`z9S6vwdF%E@*qwK7l zA*DmWwtCsjtNeR(@04>MI=c(hY9z?65c^*lis290DIK^G2y zpSA_=K*~@mHWGc&nHpE;oX%66>UOjaG~cC;-Z9o)LxcI zEbIHxkfeWWeb$6DNk~u5U(@^dKltw1rREq$l(pEiBLe>a7R%6Z*gWK6h7EXnjcMgy zck~mZuYbC}gu&Y2iA1jA33vil0VtMw3#DjO-yB>0Q%s<2i(yF#Y@-%;mix3k+lfK$ z^6HBD9wMOXRD%40B)6T#X&O;mVX9KQd1%nA2e>h0fkrrP3Dwq>=Hx5N3i|19C_vTB z`cxeZBt~tv+Ox3~`E8^dq~Pb_3qq_CEtd$U8!*U?+mZ1Z46mrKi4Tr~^Yd5}Myr*U z)NWcRaUJehwLjFBHHtJ2>atLk)8w;Vl*{aNZi0us;lwb*pb>g}w4S!o9;QKU#v^+> z${de}5Pn8DhrdcW6?z(jJ9t$dy}yTkA)|p(s($1|Uk+deV6F~1B_-wY2~H%x zkW&QH`#cnb{+SP0kBk|U?Jr0^dKjG>`5y@kusmSm0Yk?d0q8FM^17HwXU@iPAEIz>uuc;a%vmpU-9B)4Cg6_4OQC`R|{ zRYxc)OA3X?BiQO%8_Z%0o8oMA8LdHLJ;v9VFBM-Ri-}*M`ql~Dp3N*Gw%{QC=VcfY zBvDgy*0KZdCs1PDP-Nn)-M66d@<}DIJgyS6FjJXfn35{}B}J%!eqPx7SYEntg$h|` z1<8KT4>tiGfyqc^Gko&eIZW0-XDXFu%pvmSZ6QC_X9-9S zk@@ENKxS_GLFWg9q&!GIFBrsn(W>XUYyZ_8Q#ihH9MsqdZ*%+EoR(J_2XgV;S%Gus zlObAqI6m5gK>qF{I4z~miI-*{*};>zvMv*krWEKN)DJW~+U$&b#k((K;iH#kD= zYSeiG_B|>Tuo#8l4q#@dCveXUu+@+PBS1Cd%B=<0rZY#wjw)~r=Szu)r@MYzA6+|d zo6SlG3wHf?@eKqnk$dso>E(pq9P?q}{D^11mrf0XeuG*7-;I-8o@Y-`%xAOJdlyXn zfkvaV^hs5QuvtB`f##lP=Lf38+D>{MBxB$!n+oB#t$L9Qy3JY#VGTK}Eo_H?id``fmTe=x0O2wyuQ^09Jt8~W>jNg*q&^+4 zmqk0sB>#5-aPwk#DUSlGlF3Qsf6APij{%~(&5tRX?e_^Hf%}Id1<5S)m-!U`l_oNd zvYmnFR`)!M%;>*x#5)6@Sn5tj9nVST64Kn8tZwm)p9&WroZtsfmk7$C@~acRYj)^z z=Yo@G!ZfUR{_bZEnHg#S%t{j0wK>HX*l#HDeiR&L{zH?BOH zg0SMLQ;ag9KwGA}!Msbf*QT6rBqOKYwW6TWOF!trgspbpXj%P*`o>4&7sLF97;nfP zkWx&?UeCgGZ~%iQXTKE-OSSWFAWXO`NUQ^exQTF@w)nVmp%1l=X$+nqJ18t-hOEGC zHmIRu5nfJNAkOpJa|TK$Db1u-Se$El-bA^YceZx}#VuGx3!MnW8UyQ(v z$OMLSN)uUqJpxl2poW%Ct^PZeD@ae`XGSg*f8V&bPan5_G-mD4UfC!K-HE1kRKTCf z>WXkmMhHs;M4NGCi!Ur|Xv3?nOK3Rwv|tMu%$gEaa4sz)B-N!wGMfk7^u!`B+DJBC z&qLq|E7X#gEL&=cjb1@&7W|V5OFBJ~*!3vI1vlfts+f|moXCnm#4Wjmd;;m=%^kdG zsj3MU)uppE%EEf0U;ebT70)u$tn}ns{(kzE0Vl6ZyNi*(MmXCs2&Mf&X zuMb6HMn`8CYp3(6ao(r$(rVn`eXT|RRi-{=yQHmNsMe}}23SL8Eq1v=q^0Q|U{;#? zBw+kYmnxxqgE~{r3@*TmnE-Wm?VaS-eC6Pf$`e~4DH+K6PSH3)u&arZ9M@Q!L?S8% zQ{7Z0{pOqndZ%i9nQ7%=Z+pzm6b7_STuMDdvWiz&e|Mn!XOsb3l+;d}y&^$cX==tO z`swJu2`15#Z@qqzgl3%S07u)K7=S>y#qK3;W6>WmjXe0bRZcqVjCdyn?I)B4`L2eZaD2xE%Z~lCroqQRBu~ z;(Sz#=0ip~kMOwlBP!^+MaLd>6&f6bsGH5v(z}HDir~>zF;o|HHw=37VO1d}XhX861wsa729dm&M7t@??$!epi}@-~T8ZegEpds*Zb9 zSO6tWt)X;FVNpw5s$oE1Y`_+AJ+&3XhlrliEW)8e_&jusMR4vLWkGYKr$S*9OrhkgFI~f_U=wW84}13Vh95EbA@m54E&@}>`CDs-{lUz1T18ny@6kGziv#nv(RA^*;wSZ{0tM&b zB7H~>rFOB9p}e_CrY$TNuZ;FQz%2D+She?ujmV`Ca)nYXCFi7IklBOeR`<|}sVoy^ zNM%H_1Ea}D+|AreQ$PW2c#zgKP@O|N1XO32z(M@~%7l#a&1=!-ii7iTLd*Sm#|O_@ zwqF$iAiRu~t9A+xAq%qqq0AimQ6+#M3N-K)e6C9l(}0o^b+LEE;be_yT3Q!{H)SVV zvd^gJvt&h-Qgyc5KOJkSVxKQHr2rD`v^4O_Kp3UEqfab(dO#J<#%wiJr@aTvjT2Ecm+fAh8Zcic1{hb`_39p;sbHZ&krsM| zG?}cOzgRPokTW^2VN^uQSx<>BV+BT*8Ac~+Bc9cXAw78?(whKv*Rc%;+-_?g$wvuT z7GPfexR}CFFtzsvvLeTYk=QD_2>oWUVFpdAsA{RPUFx}*OO3M6W2gX1tr1>8XA2V`xm_VWiMC4 zBhX@7-1X0Zt38+J2buK|yrb@ZddKwvUVw}pZj-Qb1>2fcB01*0VRw59tq+$dmoyId zJ_h73PJW-uxi&9Y^^~1cc=N3;!fv9E|JAJ?YycB_7&di0Zlz|EMRZgwd?JcsiQr^j zJej&QCc@8lqfKGYSW(=dkq%soR^H^K{V~h6Qy$a(OGP(&etdn0x%BEbAtwko{he&~KqW$ojg;}X( zOFt=0F_buFtx8x%P|Bv7`r4#)*S;v7dXkrSFaMYm>E2X;D1^s03invH7zA{Ewbgwx z+(TGz%DLC}rMM^O;NInVaWb{#o2XdlAUg`uRp9u{FZ=PeF3) zMSCYno9utZ6MC;%eL7dVE_@T4IYevjfbIdPsR!6LP+c+rm#`YMgrA-e^&5Zg1X;~r zDo+P6C%nN0GsOwh;?SM|9DI4SP74#@{b~Xibtix5ZcJ~^ zf1D7}Jvx7oDq;E)8oZnS#P?rHMs|m9*>J|%?&h}|DJ>MoFl0qXe-dMuuM}9de6*M* zh(8aQd}lMg%~lD>QdY;A-}eG|{!Y%o2Oy*`YthQx=A!UedQE@GNhZ&OFlN^Icwi0E zo^5Ei_9m{u%QcFxZz7REA$Ed6k^}nB@Gl)k9n6^hYhu_5d&AS2yxMxk=;l__b(0JvoOid=iwx-T3s&*n#Z_`1tz+vv{l_T(z=}vYpoAPt3Bl_={x zlD?W(G*+d~j&}378@G`!tE4!43}SuD*Z9_1TQA(#p!(tEpp;a^w$9A8*AU1z^tk)8 zPknt%0R!qI)@1fA#1{u7${QIdF+9&%sE_ArJ#lZ{SO58hBc=A+v@1tYiTYeu6c6L@ z&uY(8>+`NpIivk8?%hfZIk9p{y(B;~U8XjDsxd(7cKr8vHDwn-=C}LVLOAyL<8%Rx z4U^mCW+7Pyj>?{sw>DZG0L+1x{Iyvejq*`!!K11gihe0-bVV&jY2{ad&w6rA)44BJ$_79ck-YEDxD*2cahECY0hmS$qMrk%w0e4}`r0U664*+_Q~E9H+Jcwl~P;nEcJ8uUB7 zpPe8NQ;R*^uOI3MV*cS)ys{6BKm*)({t$8kt+M%y_>rzk;wCc{kXRwr_=k6A|`(w`qRzkeNL>Q%v=5BgY z<<)k;<9QG!djA`(GdbI>=zdQbMDtB}y-erlh4Os#XseVdU9j|5O{WPmJ zfss&K$6^3H>rsBDVLS7<}vkXIT#_6KShhoz-Pb8COnx5Q{3-^wHAo6`4u8TNM6?&*D0o#15?C!EZ7zzK%+%SPaD)_$@u(}jY4IFk|2mn z?EZdSW}SI?nS2|q1T;F+GLF~>$e@d^9O(*2WFHbdhB42fLgux|{xYYy&X9{OcD1+f zr{lBmyOB*KX0CXEH;k$P*h4midra542CQu-c}SHMDTnwZe~y-0hh!|2D*Q6gCk95Fk8s9HJX`c^@5`QWTUM_8*h9J z=llW~S`yd>bzmJulM-f#PK+bRMlxM{#kmGH$ zihqzAdcfI-eZIN$%`VVNm=U6ml!R%bH+saZ7wOl;k%w`aw9kc*^8W1Pp#WfxMhS5f z@CShSp)(zXgDxBHkHATfay$y!sLe^QuTkx=kWRMeP(Z!BkZ#7!;V3fs+W1^dXY+}N z2VNC_EEEEndvLrq;}NP>Rk7n~n6C(Wg$n2U8oZ@otQ*l}`WaTvfg}@Bk$oUWy-R<@ z(L!o~f?4|dOguowdV64ERi;QAhL5#j4)6^onI0m9Rcg=*>6Zvj3%T}?XS6##dU zi-8}2zfl5lO|ydDH;9fTUdM7(3Xa#zpzjwl2U7`uNA?YCjM6r4i8rSxG1h%T5OcCu zjIC~AeE#&>(70)Fv3_uZmxz1Fv7A?m-?hB#6`RFuLe=Ut{x|xF&v(dxJt6P-R-OFM zmlvGZIVs$o{d{wxT8BH;m~B13o$q4W{I!xw0hUk%NpytI4_QGMH+}>i86@E-Cqx1| zSZv1vo4pLp_2igOqD~?6W02bVWD&)^wZ1j)f@EOb`$LcHo%MjX>KrGo?CN6}b>?Di zS~!DZH6dC^sKd*B2UmggnjZ}CxQ{|+63q8h@{eE?ACU8*wxe67!8!GJ_NG=>w>PU1 z94EqmN6OhVPr*|28>A^!zNi(x1^^Z`LUJx=j*j!&;#1q3d9)=|mJmp!Lf6y`hGV}4 zUAqjow-lq&EHn7L(-=BG=NYK^-8zZJW{WYloATtiAy<#B7(%Rw*6*EC$d{9z|0jVCVPhwSvBc3=iIA_K{|4#R|rG?>Q)U1(LFbm^&-C~v(j?QVELEuz|;J@r@OlfnUgy7 zt=(ID4*PWYk>z0mT!60{ALr$S>L_i)Vv=eR-85HA(AvGQCxw&)n9dbR%qnoaejDNK z)|5oOSarXXE=Lki_*FynQ>2sUO8%Fb0WbeO-od*(N7!c6gK2V}Lqx^(G>%&nR573` z4rLpDMbGHhhZW{&*Eo)zQdou}wnd`2Oz|LO4^Q+!&?G}!;sb^x?m-JrYyS*tiXLph z`o|;FKyUPOoq|;93u6nF!$#G#C(O4}BlLRK&8dQn38cEeCr#e~I$$r_kq80^c+vgy z(#HY-rqy>-X-g|I*2I6Db|7S3N9!^-5}29v)LaXy8H^y!ma)?p?ePMUd8^V(PvRZ~ z@WIRGuOEwqB_<<>{#KJCh~NRV(UNMK$GRXFQ03sfxN=lAXQ?@h7*J+9p=37>9s|H; z82DPY%q(_@Szx1XX#lNgvY&0&1GBExr5b2K1Juy;fT8?r`-{3}hO6A7qMc)YA&HT^*qbQo*E- z=$nhXO(viPoXel4R*Dsd_G7i`D5=LB|5F?9^KSB}FiVp|se{7F5V}`;E@~})emxb- zbC#f(Bz{Oudfr3+*()O?oKBCBW3EigK(4syTz*E_;`WFcF8UUdC(&sf%kd7qY zM*UCcnJqSgz?BNkYe{XtzlB&uzW{0ZSBU++3nR&tQyWr8?m0EmU1?BEGiMaJwcu)3 z&PTjwX|a0sJc+eg^w5CZB*x$x^9KXzx!arZyZ9*pE&Da4RC!fO!kM$xtwFn>4B6Ff zOK7~L!{X!XoVTKeQ&QA5(lRn#BP6{c$>e-V2#fMZu4iubYLo0=me|dVVSI>ZK1rq% z25rpSO5*r+HH)qj^}z>N{YZhlKNq0jBs>%i!E|Fbv=RENaua1Ahp+4djly|Qpvp-A z0HIzQ!(ax@Wa@2!Q!V{=$gh2uwg?1hRF?BY1jfkmFXLUK7s0w21AQ7Sx0n(E>XV!- z&dXx{nuV`}vu~CZZEcq*^|fg+=!w436)v?pJd|I9nJPSeE@)d9|Oo&#A-Ky?1KK=Z?P@R zmZk;4kZZq>x-~NfK*)+e$17b0xikMQnZOlg!a6@4|I7W%Zdbl`ohz!*^bNiwQxA6x z(@&Cdh;EG-;EAa23K9l5UcFL`&{T93@{W~(_(Fp$tWSEj<@4YxbS|4b-O-2* z9bQ71#UWr8_hzE1HUu9yQn4Mm7Pox}%;H{=QS(#92y+11ja!WNq!U8C{`)##3J~nI zO8z5)-)u-PQ~*0b#J`INC6#~{J30>pEW*K`thiI$a6_719Z)=s4qV_rIw+e76yFNP zMLbtRn&1hMbNkT63Se|>DV8WJ?EhsnG0{*}fHP*RI|zmp>CbSUeQAWn2|&k=`x6`f zu+Ck4#vjJn^56a9Mh^%G zi7nULbEUw_neS!xW9k9-@{a|P*onO=+eq#%>9!h-wSl7|gknNqz;Qu;ufzHfc3DQbKLH$Gy%v-segNJ~ro5^596Twq!dqiAzb?%) zVkkpF&Hyui6$X?Wntqve`@x%CIxGGlOy+;#TMdH@vycvTgC2UfeLB6D5X{lm4{xd! zP<*)L44MSnKRIHz@J?(S_2s7q#ExZ}aAfm?hHVgzx9qA)-g%~PPaZ0zj6RKPX+n&; zcU0~8nj4_-#W3d*SE%gHW?Bch1GnIJ=wCF9VM!%JpbD_}2mx|p&!b6*LzL>r)7F@b zy4gq??iGPERHqjNJ}`-Yf|~>SSQuDeU4t^N^&lXiL#+GadiD7l{}h=whfQR+j$lyH zV zMYWf6je3k#ID0&sfK?#skYy@TZR-gg$b+_Jhm^|Rg^Jt{e5#C5FM?^@A6>Rd7t*##&`4il?c_CJ3I`*{w*_#@k%ag$UaIVzfn{BT=QD z)h7(tF}2B>iSWDiJcJ)e%_Usag2;x6cTbMJ!V6@U^7yZr4BG{+J&F#!mMDO8T{Nz} zb)!mm=W8}dWn10?t~C4emzE*wXoatSlS(8PhcEEl$&H(9Gey^5irix<50iRy!u*lg zGq*%jh)@jK#-KGa_D$P{6l0IO{iIdyEG4FAx&FG6r{}uowA7!mw*x$cZ;!Ke@p>4g zZnFpX9qU#S$rB}+HIS+Db+L?EW-a!a`V;aCEP|rCrK1z0rNw*n&rS@>N)UQ8I_aL8 zVUJAW+v8~TGW;2PTGp6K9>CHmoWYgD5G^MHdf%E~CQuDMuTB)p>YXL(@L=(RA)cpe zX+bAyGtH*(|6=o-QXD)xzhh%n9{$Y zboe#^qc5WJ!I#8_>5J7BWm%kIgWCGPwd7QCy&aei zCPI7J17Q67ucp{|A%HEYE+|vnLi(p-zrMECJW6Ki5pT7s_hyQhAvl=?jYl$x?LIYq zC5xV0pIbbs$Y zOh9ap3OWJKG=G!Jl(dga7M^7v;ub9tv|EzrX(=&$17!MCQ;L&CkNSU(PPc-B)NpA6 z%gr6;Y!NP)KC29Si68NkDbj;mMB^Gn9ei|+IOYryZJ=p)^F*+Nj@$M>dRX`#guUMr z9z8So6P>M9z8LlJ1n)>5(go@jd_!&U*YNKzRv_iu5_F=GS)UE2-;YD|xBsQ4Q9!*y zjia@>WliX$kdDi0xZEEv5T?YYgU1oetKA|9RbFQ1uwAO;;e9%IZFOk;3xw*{Bxo9 zM%5=)Z@ub6K99Q;oJL$m-?$}%rD)@+s9fA*gSDV9AdD{$<#1CkpTfd2OgZA1`Sbd$ znhqr3j?97(cm*6sZY#*+zsv0QqX+XM-3d}v1ok!?{YbBA5yBc%}YcMq_L3GlU?_+>!ecyzer znpvfLrfo+PG_YN*yg;MjcsQ=xczcs5#jA;kI1&NGdVF{cwH$`Gts2p!C~{v1mH&BO z$2j7Z;^t~r-npet&p&&@?{$j3(nmU|H_bijOe~>7EHgqOR`2^>u3}v9K9xbSCV;4A zo3JUdd0-~n6&3%z|EhI23`2Yd%ca%^9tp-QIV2z6hoYIc!JU;A*PjJxby);sXr7&o zWTYVK(x6EXU6gXqlX0K%*Hr3KIVvaW#$?>=<_xlr4KCqSRB&D4C&N7J-V$p18P|l_*=`*+o0;#RmmM}^5RMHsy z2OVGt-q-2S4HJ@iJQuB3Zye(zv1dDXVcr91%Gr&3#fjilPC#lw; zT%rrl6z+c`Zr!P*aYrCdzmPNrl17Nky~tUmV~&XM!H%C@**7K=9M2M{H29!u4aIO` zB(W*A+d8_L{uA6(wN`4(ZiRY_^8uAo;(<%B3)Nx) z^$odAijJ05wL62k*hQ=9><62oC8Z}_TpY9B1djKVE#yp`I^!OrH)l~Q3KZMC*1}Kt zGv7)e8}^)sINwJTu^@|Gn+e;54UawG;{ch$e7w&_2vOLpHjt=3x$ldZdp3Y|42Oj< z2O4sR;r1TcSSR2pODK#a07n+p^(MikXN<+NEYdE$s6>3^c43zOEoQg|r@Oa%E!v}LUq9x*vMcqKoX-` z=i54C96U&m{4>38?Hyk2s%E)QuI1Iunm8+YgNsIj_Jdu3kC!D{Zg&OZT$OZ_O}T5g z3<{oT{c6bm`g)NO(AG#FFqA8<)h!v|MZA7=f*8LB|-StB(PXpxkv7dKrwE#3rg_S2;k*$7)KC zMZhgQTV)o#@<;`MSrkqxy6Ku0Ysmbu4n6V@C{GP2-i=RDC%99J?RLAJaJ560O} z2IDV9dF3bG7ZQWiY9Pw5v2!N`KWG#8r7DS?vI}{z(~!K$DZAw+YBYNlTwrldycn&1VcwUU1XumI0HRt5G95Mc69vsbW5962>qI}XfrDP> zd*)c$UXK|=hi;8BSwfDJ)brmpDWM|96HpUTJ7OD3naZl~x6g9+sxxrc+&@N(s6uzWll^ejr6`o0W0Da^~~aej~p{-|j% z>AUs>WT?nyOT=tSK_0Ui#4mg0kX2xZ7yk9~TQane`5BauUw=S>Lo72ESr?}VK((m7rdIx!nLL{zW<3_NH8BJ<+U{6%;sc6qr|2aVa5Ei3?}`2EYT z7mw*YBStZ#bQp58P}#h03ZMukL^7t6N(F{<5>J2A(#@{J_@fL9O|fkz4@B<~!IgBl zF^>8F;%eIbmf$nAvd&1mPDEh$6sKyA?>B979pvUU;=JOIul=Gz>b5_rh&43Yp^FJd zd0r7(b+cnY#eqeY-?|7aZ}!eE$)~G9FvcXn)>P}}Vp1-YqL)v5AWXEVl_J%+UHQB% z!6zmB&0Mo!)NWQt((k;MpN{V0B}l z2Vp@=5KzI4g~sE@u}HPh2Xb@GKQmq>N)kV6)#6V|h7A3MZp4_$&)kOG{YB4gy|X*Z z54C48>GjcH$@NvBDyxL#UJyq3`+CkqLzBnGu2I_kzew!aYI{Qni#v`q(g4`xH^T#i zwo)d{GPh;e43UBqy75mWAuf2Ku?1K+nrr5AY{yuhD6=p|{X=*WGo@MN86>*TmT{-I zzu;k87%k;qDKC)XsC*Q5T1x>p^yHA~FCb^j@6U&s!ar$7II?X=t|`+Zx*#9=?0*u~ z=YJ&{id!(9yhnPk-DM-mYY%ursSKo;d_mLgLfkM8+Sj-aw0h%|tZUIl^r~*-=Of7I z=3>~Cr%Lo5n~eCrkdt1=yop!S^DFkT6NFRrHuxPLuQOB*lgTEfSxg+Qj;$e)>dmN?odwX`HP8 z=ycYR5~}lBb3IgnbO-SfYekTZW>H;td3E_8Ec*09fR*gTJ&Nd(yQ9{s3Y`-NpLesq z>w_&4{5-`B0=6V`fS8B(e*P}Bsk0BA=%jAVtkWK<5xNM%hJ9w8j36Q?rPmq(OB(4PGKPXsh4mb z3uY1~U{W7eOfNbj1KXQt^28;q)4MhDwoVxSKA>*AOqpWXN6BDlO-mTG! z8wxg^c?Q;lM13>7gcC!mffd^YU)qsRJ4XKr%G!BtXWyLj!Ao9=x)<0|7Cb3f03){O z?CqtDNG63INghypZT=N!-hW&T$%p8$h(2(>=7=fkbWOl+na3p$c{-jdDZm>5E~&v^ zDI#$8V-#^CkuhiBHyN6r>gg2^?3gB_3PxRKTu1*(GR8%`3Qv5!MkZZ9ozMFrx9_#* zt=()Y*{K?5-#qi-{Gs>8Xb(NDGS5^1-OKLG6cPku)X5;8hu&KFI-L0sn+1?4e%98E zUQ&bO^|hpmeyN;lnR1z2VWa_3$1`QM*#~!MsH4kbJ?E@Q{B96rDJ)Umq$1aa3rm{3 zNrw8B*#&0z7cmt2d2YcAMH5cgJ{r+;v@1=VM z4E(_RJtv|E@v}Kraqa^i9JLldmL7|{m+XRKb*w|(2h-R)ja~4rCS;+0oI*%zaXjby z*BOml6oxd!K$m%Qru5nOH7N1o@tmI(fo!cPnOX1!>9DN+N-Vxwxw%+a(`C*p^rePd z%3#)4;7h_MZTK&xG>d!JqjmcqSc;64hl{(eeYVfcx>~UQQw2hBQq1$Lefy>Tw^F9> zhwT+=nxi);Gw5`PnsV9Z+QTu-l86znC z^_0`ZlvLpCwFx^MXT&y?XR0amaHVXk<9T|cNu3^ z#PYr=L?G#m!izGn2@yVJP%@XfN~a|~N3Dx#FZXFhuQO{?D_;SFdnSo7#cZPdMWBm- z)^SRtXTYI#d#b>A17Qz%0EB!ZEP+!-a-&%|>v5F5`flu18xh`+<$CDAAorQxqMObG zRsg&(+l{qCTV>Vlc@;{)ay@i~=wu&rm880WSANO62KBJs*3$4kAKvmo6t|YrIo@1@ zIb&YV^6avq*ru8fz4ohra30>XCG!6#1dC3s57F2mf46ur@+PwXimM>6w$E#btE3(j zo|iCr+F5BeYkiLvIpB8XZRs5N`n1^#+X!FyH_$2$3;RQyl zl^aw|f)=u_Np0^##7d>`G(UrjD_?Elg9%B{9XLczN1YU`NTR#sKaAqUwcpdPbg4{= zJMtB#isd1D*>?32uq&5c0z=k@66Y47|7yZ@o8P@*{mVuAZ*&JcCnL(U-o^HD8 z+B^78Zq71H#r$TpN>Z-Ax539aD&{(K7BD~uoiYG6@0cQ+OzqrF_uyD0qEN2uFxpTb zM0wT2I~ukdo_a4g6|86yL&A>jk0jDcVqlB}o|7}TksbnF=)q7tm}cmTEiyx}=lJA? zQ-rD~-EeO8xSKAbnj;=R10X*}cp6*&CRE^(NH9*Gq#VSIylQwo)jOeZacBWMmtZ~e z9fB2aKByl9ksy?>y{_(n7awP5f(39DkS>3bM0nn?h+ngQyL(WI+{eW2hSnr?V1|q4 zz)^gS?c<0*m;?_Lalo;bZPO0iu-Fq-4fCdwtn4|5B5JvrYr;mTb0;w5G*B`S_48LKr$-#Kn7j}z`VXBCX55t?3?L}e+4n1W6r=g?WleV#2qHLK+}R z!ai5WjXs{cw_2KRz9osAx}>TUPQqN(o&SwT5YN6U2qDciP=eLfD%FEk7(Qn|)m|Kf zJeF|Q!o^p)sTME0Dl`}-uUj9gwWXea!@tChi5d-<5g|t4_|7BAcvWUx&?3%mTQ#`+ zThq=IZQjjtcg=aN7p?fmT;*d>4vYrgS$anYe@UBx;_M{eQf7BLEB9;o&#`An!mB;<~ zn*{QRaL!)VCE>({JUIx8Oj^$$o$ zV)6VqzE=h+iXPQg6=7Egs+FR9>qxh*p@GS&@zTJCZ9r0LWui}kqqKxic-1NApG4nZ z92t|oR#;#~Zxg>H-Hz<8^NuR(&+V#=>0Bsm<^&xc4-q7a$V-iW$-U|?_x{%y?T;x+ zJ$j=ipDa4ivNzCYa1OP@h3m|yJ_iOC>g%}9{3)S^@Ap)xE;__bBZ!H6f1-tJCgN+Ul+3-Jog-nCqK6X+d>l3gI%I?@) zJWYExeckX=qz~cW+?_we<}QD6mpKnk%z&^$2NJ0f z;h8W#P+ON^R_b;mTLBc4LJmd!a;ZTYol$G_FDJgAD5GC!KX(`9 zINK^ut-@4RtF-Yf!RxFRRWMd>(+(-{>62!-i~ULonTVg~BwDZ00DZyiqWak9t$UFA z@w)u(B}`%H7JPsTkN-jB4Dm#Sh)~1jEDn{YO_zprd5bIK6VXT;STNGKY*Go-W3&;B zKz`)5``tly_Bw++e^lwZ%$fX1MGkrok1++C=l@5{Z2|@=A_t9@Kb33&Z7Y87i$oVl zR%PIR&g*{h_LkRdouB^U!_)Tz}8ax-1_ zhG}*un^yf`OLRiKlACen>oJk{)?XAvxdQ+MSmPUit*#c|dmpT~T6FKOc{hddo#SGH zdJ7>x`95FRFju7DIs0@&g4`@*Itkoh%nc)Amg|H8i2ELYSz)dJIaOmP~Wo{_WUIUSH=DQ(V-{K@8FdK7K(!x|Pr z<79}VmWiKj4v3(Vv=$pi7K`mc)YX*Gs`sO)o=wFu2Ji2PtlCciL#u@P?}QO_*u@Mn z73%76N3fp6CaRMC%1`bZE$T-2T;GL=xbTbNJ;PVe9f+dY_Ja;&YQUIH3h0;%D&=AkBq!4dxVXjP6JfsrnqUdqT2wOV@s1K)cHW{^qOoA9wXG^ zoZ66&HnKAbimW4qd z%uXYZ%$FpO;!xV;j;GmiWgt$XtCxGLw5f-Nb=ww{rIM(s;b1NsLNr8sO$T|_PUr=; zIRI9rLRbt8+7~y1t)D$FZsl@1DxJJri$XFosv{@G7PLrBrTs!HqUi)f*y4Ql*MB#d zV=*1kiLpBeDgRz*v>=g7{xOR0DeKwg`>^YNl|h(QmgH>>aKVFVBEYSIl`>kEO2(7l zjfsa2#I-Y9?O#1J26l;xwoZO<-y;O`J4HJ-c7mQgIb?Ad@Hvqx819P1b5VY6iJ-7MEULl}C?IlQ#WPeSw9VpS$#4f++=*YWjuN zxqc7tBu5>D@%x-C&arMx8Lpza;SVw5a=0)^Klap<#B(9kp;p_y?UHOW090C*zx*14 z@iA8M<$|lN-fj;B@)<{X69gpJKWo9h*J!9v56ZL1GTS0MVMAK0>$5FXKT9Zg?T{(c z?;MCbo7_EL$O3uDeL`Q zTtTC-lkIyKbw91l{ptlvcx>65jJ3AYCgR@x8ZJoi5F=1UnO5!_O{~9Lqvo%p*v4q1 zvd5c-WLxJF`K`j2(UQ%Y#n@^Bd&gE=Tj_Afv%b5#j6kf>-xH&9CG<2j+8GW%Kv_Qa zp5P^*LhSBr9i@%k3)KFtR9D<5y`PY5E$a|mQ?jNVm-qEzHzh4MVo*AI0?`_Xc#W$6 zPiU9|__6H~2+FoJT{EDM$4Dh;XJ1gx=F`5^*nX5dxuLgGwdlL!C1}HlfH=oc_KDj@5W&IU@Eir ze%dIXsmcV_u|Zh}eaG7r1qwh{0ZkJH)Zz5X=&0POX!20o)J^cD>Bh6bnAkHeem9FK3WhRzog6>+lw z_~2UTW8Bwjha3Y7xzg)l)zNkfa#lK(Ge~4nVvI$E! zhbxZ0_yi{dl}9|=D@G*0)no>lpUJ=5YcZb6tj_Tl2#8!HCM+s#CYk$+OtIStK!Y{T zSXA94l!n2wsEWO;l_WcN6V=MXs1$PNMc88R(|Pm2MkH7#q9DAH_Z>c&e(_!oKN$A3 zB0N5-f1DczsSOs+ZPK zVdjsJGQYd?@5@9ytSz;&1rIjNq)U(e=3*3Y*B;&EZHSk*gx+Fc8m|-To`pSSbXxJs z)C`>qYCl(*r!o9$A%kxqiM=x%lYkx8el%Lq`k-a$*K5&~%p73qVf*dQDeYt#MB5YNz88yY!V+_%hTAz9XwpVe2q#*( zr@SKLC`tw)j1xAi)k#hb>21HY%*bTS_M*{RuC4ncTz*v1zhn8u?#Ui=_>K_egzVja z6~Xq=QxJqjEtnDmU=kcvRu0_94IV{Hj%~^RyF`Ythh5V7H0l-(*y`l`tm*=i^JhUa z=7KL`F({YjtJ3&|NHAe?(v--hI7~a?219-b6jtct8owL@2{-vNIiUfkeu(Zj{Va4CA~Lfa`-Lbf6Jemqured9U5;|Fmz0#F z#`s6z?L*TRf-M|;121yVXgCMr3PwmwV^6Cxgfmx)V30P_c4N>vnC>TEzSrs zgFLBtF9N`QEP0%}R>EDL;>*&GJ33UaAf5k2nHcRgx$Qo+uz$T#p<;nwu(+d}41nXd zv2TwsSUfq9feR~KHhC)`Pazq=D2c%g?N{tJTJmxgR7jHcMu&>bj|9L6dh_a-?Ej@N znlz&)0_Ca}vyw#i@kw;C(2$PPIaPCjfoM*=juoLyVzk|WQtGXojy%Zw$h`!Qu4#4i z51dDZ^)}&30@ZAJ+0Wl-?KG$xL|@?u2Sop=&{D+fMWY&oqRY^M)9L{MNbvLWHOlQO zY7#(iu_R{T(;ss*bHay_6{mRIs8=ZX7Eb{berW+JFMIjFPu_aDebN-+VT-1YfN}wj zJUh5@y_8i8=b~l-=un6q;NPyq$Lx#6hA_% zoHGEsxVulN+WVKdzREsQ7}&4W`Xy^;<6L+cU#nOYCJ^q76E^kRacU4(#G=46#aYAThbDQ9V3FOu&n6bIJ@I`Fd^KXwWLKOk1AIbFgm?0 zuUfUT3lB+1In4WE&yBH?I|!Y;aXh4*i|6vU@r+%tCY-br;Vf(63y6YSB*Dw!CI5@2 zXMv|D_OJteSHd_ypoG@!c38^h5$m2O9BRnh#NdlGFK*6cVQYAxQMwdrSJV%?Q}O0I zIk{DX_QW!{iHVBhQ$)lVM3b~nl)|f&)#T{BxILg2>-+B|#br9;MfPqKd_z%#l3{dj zXBa04MB!z8pU(7LXMY{CX=Su7;@;w#Klv09cMr~WR&o?aY;2gUA&w2XZLSyt0N0;$ zNcR@?F?yYZpDyuxLs1JwwO6gXX|d;UnkoT)QZ#Mby3IFn2Zn#4>AvS?axxt(J7Yi6glJ4(#0H-e)vaRO!2!9X^g0O5Y zMShyYwFsqj5k_t91Kt?_!|i>Ch4JCy{^KX%Wdb`4I*>J-Qosk9VTt{!kZrRsDaj53 z6{ezWh_GEoi%>lEwqJl4c>u9@C|iu02jsPr!|97?FR!)<5#6)fQ%0(dB$Yxx&JVGp zkom`Pn3E(m4DL=@d2>T1f+Eed`co5JZSgGi&QDXb^bR)%oSA~1Q$DkaZ$2ed6=9&VvN;$5>k zou8=dz43e>n*;GPlOvzNCnDm0zpz!u{n>&4{4w7_L?*hvs>C0TdzKK0)ewDlR%ZfuOmq_KyP&aq4j;I$1kn3(ker4 z;Z>Jq3;PuQI{JzZc%8)ZlENf(TobBS-lYcwYr{g6^b#WREfWYC!v+@wn0HUF@;k7s zMw|>EW)m7IW_$)dBZ7-oh&q^MOb8HZbM7kRMXr)svDZ&#A>9$}bxrl|B8Z5Yx2|0^ zWl;04mawYeJ)*u|!j&om1jd%9h(oJ;|L{T$jIZVs^a+x>8+{s1bGzBGm@b5A8-gf+?* zYk9nl+&tV|3Zzo~jKPE9&t>hoB{3Tc#Ai1uWKv20Eh*eHhVw2pKVREqtt%Jjs0V}6y=&;w#6xc0tAtILFTD?V`xX|$oq0b!D-oDyCQOYoi z$AsIi@WyA~GzjxiK>N!hvNzztB8=J{$2NfOz@qQE5~ zi3>BSjh|Z}EzmXUrQBJ~G5##A=vstsv9xznyW^n{^Ww7#(Z+Vs$Kdo1ns-Od0=;gc zaR;1W2Za4iU?GH?cvo^IMVv3k9u{I|PjpxJ(h;5PVN{&}$rVla3+O2#xV{D4xTQ{l zI%LZnepKP6>5!p7*9O&Zees-+p6$X~BWfYoJjBvA=xddKGAhVk4bFE>eMz`t6Sp`7 zj8gaYjP6h`Wpn7e{~P{;#J;gF`(`U*Q@HGLY6?@^Ucb4Tez2fZ&A^ra@F*J>QKNbp z!r6hzUNW4P_qmoFig1HttgQYI-r39yq%0KvK77wOm=TjeqeWUu9%PUVh1PUZi%+O# z8{Q~8^^x@v#d`F)<&1EpS4Md+QPr83CiE@yd(8NhI9i^{VNelh)&y=V{WSN7IwM2k z@(B-UHk{M+I1{vuZJPD~%CncfqJ2tBG3$mlb1X%bfm{VmkK4m0!k`_6*_v`kF3Xaj z;3MSIOC)ksz+o-h(wf*@aBsB-IiVv_7&%%N@yO$(V|OxCHLvW_E`&%8XcWxP+%Rd2 z))+-cNqxqL861_8&^ell57lR5KR4Apet9&yG#NreuEVz&Wh>Qvk&(^oLZSlQsqHjS z{oWGry`f64)i3hYbL`{AcghSA@|iF}b&Q1TJFAR!K*^RHW&9aJk7p5(V6;NL#I5~$2S?X1i%Z5F6Uq-y^=Fv_@F{~tx zk>1*a;gu>oZ&vcF>cMViyJkp*yH)oQ4I0H|;$wBJ5k9aKl7nURym+Ore#KT@cr0@E z#@;exz$;r78fqmgsZx!ZvHEa6(DPxzf1jzMIM=fmmj6&m9aAN@4nSsj`i|-gK@BCq zEer)X)A1?i0dnRcFj0%L+rsUD0QGsaKjs62T@B7us3-qc;#PS?8TWX*7DF;R*7niJ zVdv=8Y9}4Dm(wmnDGi}}^fg&fMfKzO>iDrZG(<~ zc~*v&(88H-aqWArkr<8)@9zZ zKAzyUBgQ(Kup~@%b>lW5;GY%2;I5xVc4d9a6Z4D2q9;#r77(ujv?$<)kDn?K&%Z1- zJ8O1?$Zxx@%D!g-=iM$_>o9)z{}Po6hUf1OebHToES1)Pp+tlaMZgRr=Om3`AIW{u z?+{Q<>lM2DYNS$vXGE8F`juIt8~87q>r2f`X5*n{=djj$pB`BQpfJO$y92E;%GFuu z&`51bJLELMmsmAxNB~+lX{fH1Ia_tv(S0}}-M7tR_YJ--dcF9kw9OcJ^|;g57Mb_b zqqClQP0RqBn#k22Io+F=GY^^;_%i-gS6=PJuJ_N>jsk##=7?i}S8g0Y#GQAMDXtDf}vzfSm*x-x3{g#@aXm z#oI;uM6?w@JwcXNLIcM`ZY?L98P+}Gx=~^bmu?z3m#EwD1eUa{b}4Q6`_`sB8CMVJ zsr`i5LZJl(3N~KlGyi~UL9%$R@%+V@=?Iy$ znfEH@f=1SaeY0dg+FDeZa;Gy2eEBUfm9Q)u>p-QF=7>D(3IEfx=+CaGYUT+)QD`ds zWR06`_ki^3m<(fuYXRaey-vh-#`BtYp@-D$d?zKyiKcVRdOlRaIr<)@OL_eAIr8Lw zc&=cLk7z}vUrOpn#2o>rl$VL!kqTnAwTW=$*$#n`c}8@%AT2EZD>rU%zVIlVm#+1a zynUBN#$@ZIk!!UW`gFn&k!=)-HG@kxcBpXqlqw0o@TnBQO-C~^yl0Q40GXeQ%8vu6 z!%4#X#uh1Fh;~PPXmrIx%Y$rY4^@mLuY`y<8Ur%KA(1%lmeJ>0P-?z!S#%0Mc9?_ zv0KARd)*g1jzyWmAC$-HsCtk~Ge(EO4|NvhJoR|H_6OQ+v}Dl}6i2ewF|_%bkZr%g zZ1=VcwY?WoL(}wyHzmNvFfdSUI;GP+uh0$8R`Y7fdegvA>lW11V6T9 zbWNuc(5T1CEot#GEou}IN!9~5%pB{( z#tS_n_eOT*6xl;nZe&fG{LNKN+(bBN6dBs2e3n5dDlJ1W|Ha4#8!;RuZ*t^hBQ22H z|9+=>DQ9*cJy;48+jk*8T3PZ71zZk@*;8)@9WS${+XQgQ~6;*&>lH2VUbBF1Pfi}qh zKg7r-P}u^tQnm!94G1~8A!@BaUgY7`hT%Q7c}r}7HG_H0Tlg z!3oOkm_fC`0m(I0)}G4jqzpc=DSt@SD`Yc2bl@F=8$-K(Bbg#!j;-WW^eV2+r$snQ*)`;SXh?k^x)hrP#(wz$8hx%Ch3g#s@J zN8u${DL#vN<~?ltbz0b};whpNz+rZ281}>DEM!hC5OmdM`f^*Ss404n>m!sK4_sby zs2vR9vW;{j>VcC(@l<)@^_{UGI(`jmWYyE7(wcHY)gIhw34gGqBf@aoKQSRRW*gj; z*jWQweuYFC2nEw$0S(CL#n+`_V+5L$^XB5t zv@87YS-Dvm=wYd!97i%z|KrJTAAr}mVL@n@&!BVJg7D4M+QW2eal~Lq=~=_V)!|XK zOrEbXj!Gm~K*+*&;H1ocmO#m(!jc18=(wfXyMatD#^P6+sU4+TlD+0Y;6FZ{`MJ#E za{v!qD9)T`Kj3#I#e8rR4ZyY>z-nuigY?|oZ2+nh)#?r{JgJ=!!(bjdR zr?tN?6yTJ@nZrQ#*IOi=?op{*+!j-o1CB<*QvQNh34+iW0m~Gnpt^|G;=BB0Mvi37 zhT7O^1NH-ytwc`o^c?3R@j;z)py^byRwFnI1X*Z~S3TGB-S&VL+gH_(sapN5j;Yy= zZWN4mjwB<*XqTmLzK_A1hF9iImal=A1Zi#uKV0}VbrHNu9oME$bxeEGZCf2C)0uDg zERY}wVm7Hpe8OV4pQ8R2>Tl~pVI2gQ4~PLoRFbl+;(J~y%w*ynJVpbcBbq02H2U#l z>~uU3h8V^Ow4vn#kZzFiA}L`uwl%zC!suOYVDz2Ugd;UC$W)1KR%8^3kOML$eEWA1 zRGZ3#x_ErVL<)G1JCzuyy%Uf`VHvmA#$c%1E;rEduLI%)~i5kw@y0GWfT$R)~r&gTugdH|6fq=c5cF+ z$g`>|G_lyzXUIJ59gnu8wl^_1UzckVB^@eaZN+ zJkO$xyd5ocJ<#p9Mta{)ArETtkrFKZ8Oh&{=;T=a=&?HE4MChW8O5E6ySwkj(2dBu z>n~JnjqNz}*E8;lurQ_9TpQ9ieg-UW=GTK+@Nl*nG&})vY ztKQ#Mhv$HE`0$j1*|vMN+p_?rFWCK%xOpwR-oz@lX$QtiE>vFhhg0tvPA|h7q-T9d z2f`#&Q{^Mm1Qf*+#fnpQN5I!?)=DUir|Whb?~qzeNH>(DIa(NXR2ZWjRAdzuzZPmIMTVMMB1yJK@mLRE3BR{ zYfnJ2WZ+Ed08=6#Qqw_OJSnC)Di^9Wr_a*J*smj(#I!6zk(ixU^m6a!rD3!}K1>}d z*LFN3K|AVSV%1ML1Q%IyEe#!pQofB}XZKR@SZ5=t%KK%Zmi{QzivKuk*Q=>{{M{>J zy*`ZTsuaR)kIpPXT!(!@{vjCd+GtOa+<5>TEwv8T8RMouljYx_7qz6h|Ng*iS zljunYKkRqB_Ql@`bPDfwIY9Jku4O2e*g#-ySYZW`+WP@L3*;+QNZgUK!KOHkmK&Pp z0-?gNM3rnWee7Yy)O~BN-NC3Ik}q}47F-4p5oJQ4qJ#+3+|Pvb{o%TuNif5KTcikI zvpJFMXT~tEP9LK?{*!v zAr%wDwsVEI4_X&vG2rs23mzKRJj|MG@{qbv9h*qh+Y@I9USL`(aM6SUM#BhQMW(m} z(dmpqeFNZ-ifxl93z+KFfMA};Z8^CWnxdr5;GW{s3)=>c3o&wlTBRQLmokhECX#3i zt+LM`Gp4lSIQRY;0Wt)tQIPPMqnG7@cS-^q291^ArZ`Who|E;~-JAKbb!j&s|3hZV zF3LGnoED~@hYEDx`j+v7N7}@P3o-zlBm z;^0St9r(DVK09!fytLlJ0{AFaQlGqHx(a&fIg2_}%F8^gn2~9qw}6WPU`gk?iY=2` zcnq0jIHq^vfDia_nIow96m?{fNlOG^QUFCjy1%hVM!TQibA!T)J+8l03#1gq5#*y%-1_8}VE2e$?_j0tl7Nj1QyZ`@lu`o>aMNLQXP0WEkmIoQWQrR2=3)4_V~F`|+~W@VINv?b4$`m(PYP`fiY zii)9ewL5I-zJKbWoj1WYY41zC1{}p90OyBMlG*&vvPeW&Ul{p%q=WLqR0sohRvED% zqkE7_h7*}j*09MI`g|6IvU6pGD{u4z9jI+-TQ6C#T5ytdvkGA%QywAmd3++Tm{Y$yy-hLpbNMvoa z#Dshg8WSX{R@+k`*N8gBQ=F%+cJBpbo6G?|Q-eF7Vn3f@f07m$WvpPJs@+E+3cqo; zcPYmt8>{OQM=TdL@DXUvRV?W+wAuG#T4LODWR?QmEa`|$edg#OXb$0#x${x9qq##AS|FOIw=TB4NYf3-qLAQ+TEVY1}H`#XWP z@#|UCgNgp4?*+Y(L<;4$LE251BgGunyRvWBCMP6Fo( z-m5fLdkZBAapgtF@x+4fG|vC7e6B7%|K*|)){kh2mhc>3Dgvk2rf(tur}SkF&NWI= z%LLkND+DeZ21+<)%-&4g+oWUTB-oxB7fy<@glKx9wAZF>(k;PbOx4#~QN0G^euK+1 zea2oew?=eZQ(>#I6d&(%Vy7#{gCPItX4pd&q-lGGsq7>MRAVbiOcg|Y3RH-~dcWtS9zUt8|IBY7&qPZC@9yz!sqK6;dr-4(k(?8WbJ;L3Ay1hrZr% zdPZMVL8_bl_tA80{_I~>wAKJ+%$1>u?VftC5T~C@{r74)Y7 z-US-J=H1deOpMol(NLM_q^ID71p61JilpcBleAr5Nd5rqz&i@4TEve>F*<)5Yp4wg z`%26lX?TAbU2WNSj^U1am^WETRl>MK>9DxE)B7NVJr{F>cR}Vyyf^cOF@ZwO8#14{ z)czy`3)}U)w@(X8fCWSDyjWrjW*~BP_qSm9dQcxM8So~TU{M4Qx1ngI8qU5q+C2H^EYdi`};;{^iGmoO7p0cn|3AyzJ!3Ace)&j+_ zzR3r%tQxtlF&r}?XLIjSO*kj!hedV)p1iAY@ogwO%r{cYmyaL*k_ULw(I_F-W*ex7?ac9(MsG zRLj5uP!_kdAB`ga&xVyLOEb46<|!5|Ery-W-mfd<@YW?#_Zb0-I?(4cc?pbHo_jn+ zyRv{B^Ii~VBAYMv1~SGx+&m0uo+X6$<-A42X8>OaO=4M}S07-+0po2dpfQSUH>O99 z;jnFqv>n?N4u=eF3c_Gu8Ud<< z8|Ma_DC9)D4{Qam;BTt|ESR~HPt7kLJM<1v`k)v0G(659eIE_R4-U5e)6Gk38}&dq zPg)(2k)!Y=QdDu=1!1rzG^~=u_zK16Lr}3pJh*C1@541#<S63ELbyot-I{Fd|E{4*C=_f>;l53iM}E z^i12hlo1HjS@NI>;2Jzw#mlj*3WSMWrMhUa9HVRnoJmn{`#yiWo^|;woZ7@5FO^?p zAem7Dwoh9yn1fNP#Y?g5eNTwzC)^mvDd%{=*WSJYFUQzj0=RGw@>5uyX~8nxj4KnS zFmQ~z>tNFNblhzMDi?^6WeMX(((~+^#Kzh)1&t@;X4qfWN{9HW3Wfj!BZ5+xA!D5G zTcz#LTGX>-XV^IWWxm<~9cDs1b|kPol&VwMbH(?nzw7#onMG`7A}Q4;W4(e2O*ri~ zh}UGgXT;HF2Xtq$vv-` z>$@<nxN5;MVkat`jX zr`2bl*8hOw)}rCVTm?-Kn1m6PR5a~6SD6aorKnD?sd+Rv?*cBzsThEL@&_Se#gNZ` z@4Af7=zN4yA_aeNwd>2pwS~u^w}Q2pj~a^cJ__`L&?XSf95pT7 zJf;J?XzE2*oa>;4P-z}!Hu%%N%b3%`mtp0(l+Xc&l)*PObhQzrE4^$KWzePb4j3(_ zxA+b+wN_-Nz9Kpex$k|EaiO<|+h?fEPc*YrVUK)h`jCBBJ@g~?;D9SG>f_CS*%?nV zM^{)wp?9LVP`}0{1G!M79cD%wi#1*;Ks>L#_Ha+pFfF3ve~tpCT3C^h;(_vvh4G%| zfczk7zq;P9Nxo%`S^`~pF7DR^9zL{lz({UV&ckMs< zMH>>6ad*TY=q+D!m5%>7CK>Nh<$UFQB50_mwfMFX$Lev(upypEF+oDLethG7lzB>l z9Styzs*$P#uY}U_cACZBsXXR8eTUAZg=R3e^*75jt5;6Ar0e9GmOyi@Uj*fX^YB3Q zG<|&4%a8MGZ;-D9-%(dNiR&_iPz~ddRzHDaem86BmIP)Tl`s=Rs;<9Aa-lVK3p~`S z(u@NrZ|-s&uA-HP8DI?GrCn+76<62dmYBp6ypRn;;#C3~kln?-==$ncSms|TUEgjh1_ zWs{a69hEdj#J45A8Z&j*iAgWfX}*w``yRA{bfM1fou%BxnP@}jvKvdI+PC+LLHz(M zWQi}|SoO)`GbNimiEIVJ8hqx@+=M14@G@0uJiBncR1&n*#R$i1Y`_t5BR`g>0>l-Q z6L3Xl4juXxDMX`x!*!{VaS7KD&r-aIq?Qo63Iw9tfZDa^r z8+oFLq}-ItWu;H`K4s1U%yr~&f}H7hbkmMJfC5wLACMLc;rlilWQ z&g%}*w-(Kk1&VIlG!=IwBb1E%2}U+a&G*g#Z@3U`RN_=V-2i4$XBfd}Bn8@|hv-|w$)=pRO#u|t-IJs_2cjVZw=!9|jFCUx zhUjD>f*E!^0`%{PLSIY09FMo64HT$uIQqCL3Cq+{8uYqunS9Qr$00h!hYd^`9F$}+ zmjY}Zl~9zoiex9Eg7?Z41aY9Ew@)KbPUF|eS&b`GWCdRz%;=M;)&W*t8huAfhAe zZDnLBTbCG@Hui?e%oMy{4X>{oO6-(WRk{{?)(c=X!>P|=%a}aZ5AH0mpyi+huh=Q$ zD;JLf0vF!Pfy5i>CBE&9qO?da|;{t~M?*s@@Qw0^ILoKcrQ3AywFYS_& zeA1w4e5p>MO61jXpn2DugQGm#Mf>fcS;{oY(b&_F#(IvW&DzKalcK@`tDv_1_K<8T z=@&PgL{RQ-#vjD#My8+VYu&fAPC_*UkbJ&(0S_r%uMYbQp+O%G=5tt~BnZf~(}Af@ zef~vE?*xObfWWCi)P3A{U5@lXmAa6msp`kI1Xe^SzGA)?jOb*L%}Q-(^W{P*{CS@| zxf3D^6DivW4RA~Y1%I*^1IrF*jvpz9rt8OvV`iV(Bw47m|EL+T1chRwn{yjG_^GHGXU55` zZUT4PLJO`DhoO(+YZtA6JgHSCoGy4i$h)Nd5@jE) z*qLqjfJLVL}$qpAUoQuvy*27HDG=zi8`PtoCF?F?P`P(MF~r zG5+^3h>oFETF<(QdX3_4>H@vGafy?QK}S!;FNWidQ4Y4S#fDo}29P?jD}}9?X#t#@ zhTuoEYREgr(Z8W0M4n{GM@cGj|Jdia)n?gZRAEpBgh_l?Oc6g-g|1dPqv%-`>}eTI zbB5`jJwSyA>em}g_8|tP<`tVvW~!->47g&u^wq?uI{GPMheQ+GM&X4Pk3teYoxJbcLlEKS3kY602u4cmK1`Bq-(Ik9#(f0Ijn)R%PtKZhD> zWA?hW#}B_}DJXMbw~HoL+DB;Hmj@=UhUZc>S*>Y-L_128qBzpz&;FbYuDVn zuA=DXy6ILNYWi1|y(=o0-Gdc;S1#o51!_Q!Girf$MlRd80N2K+8cbCq+!YW(?*dpk!s{3rfwg`_XPX$oSfzA5Zvhn+NeJB}k3`uK4p_5C+qV<;T2*vE^%JRwP0n=d(U4ZSJLi7>5xr zJG9o(F>5Lbq^F)&{vhVo?Dn_|P&V6~7o}P~a41_79ABYPhVCf=0T^O60~|_q4X32& z#{r_+$Il&V-;)Wy!YBHz8CGyFZ1~wPGzCfe3)8zmTtqt8$UD+2(XycM&b#L=b)+2& znqt9pTuFy1E3M;X?=#$5fGQF9b?GA^*F?$cx5)h=ZfZw6ucGR}#I&P0Rt!M<5Cnl9 z2B!JDbOd=cS8O8II|(r33c`C#MzoaH;uPb^Y)qY zzA)FdgHi#I@V%v#&J15+;mv^C&?Dos#*$5ckrGYAKIfV#Q38Q$c{SW|-c-6-tb!+) zw+qivBh~dU4!CN9ARnmBW$Bu?n&%BO0mbKj3M6`^0F2njlKd>fGm9-(Ld7Q_@FEq5#$c3 zhPrmwBBaC6Rn@B$JvwjLS`RqlpWyMm8dfb^WEl}qO02(gEO8bXAGlZHQ|?FujxEF{MD$ zRUn)ds4cPMW#+QzvDV%(xWGP>p7bk}Gf!507X+}BDIAyLMlbV`DND54)`Z_Z6rrmT ztf1~1d60Fo^>1dY#0V_D`ndkAs7SAm6w~3hPNyo-KL&QT zK_~z(OZjOESK2i*z-0riF4rmDVt;5AjpJJk1s-V}k+z}rdiD{)@T-sQ6e0v*@CyL$ z;6~lLCtSU*=AFgyIfQjJAuB}i2uJI5vlB3KUdE{yzg~KQTXvG&-=Ub<;{rv84VQzx z@$Mcs>d*CRimHP>yGpluxutf23T~L^`(Q&uPOrdq={livVN-t;4OVg_uVB2u?mmYu z(SgPPu`JGN^OgW(>ObE!+1y|Qe)>^50}J9{gBJhVxd=uOLr)zB?~A1A16#4hP*kEX zMw&?>w4;%@HQY0vhTjuuB(A_HoQWH+plMtwy}zP@DKhP_RCU{On{HShF~s>+*t_^k z)h(q1N6fTw9n+?z9kHe4%d4Q~ebU7CtNPLV7-ks6rmI8F&^-3cOg(_yNXY|fE*W=r zNVCf#L3&c5N+L}}8}H;ihdl&UK3%njsDE);GMBh3-z@@~+mt`g1!n@jfiaH=^jCV+ zeBmFw9O)K`{0`=LPBJ2Yh?hploplaIjBkFk46}^BOrHudta%x+(!uFt#%3=;t*a47 ztb&jHTI!E$DPko_A%s9RV)a(sJ zTqwqttwmCHbh-d(q1!8Ri{P})f`T{T$po@n46ye@7uBaL61aBl<8GlmyzJGSi}GI9 zv7#8p;&ir@Fz?D9jNQkXVdYh@`t-s3TD-FRLO68{&7KA03=+;BBu0N2Md$TLyFe^) zXjf$~hAeJcs2HH;^}B<8LWmer;-{cEIw0`X)%6eP57}8Lpq1~?zF_D#4fI4c!%GQ= z$I7cVHYpkn*v*#Cs%$=B4DDK09j8=KEVvzwV7r2xNG94HA$o1{>M-vae_F7)-KcS< z@lo<-{FLAt&K76bp}>hFqTfqwS+#cdO4r}i+9@*z=`eASUp9;~s$;2J;PA^1TAec_XXNSVNiZfsi{=&_0eQfOJFIfv#H z&Thb@B{jPOl^QCZ3$KM8SJu5t;9akGiNS|yW-^fc=M**f8hVFfwB;KO)ll$h)!RFC zxVLOIqJT(01HN}jQj>BJ`mF+!_C?pN?Wo>Li=bI69_Qb=(DN4O;oU^@fB!8YiZJ9oOc0@TDj#XM#?aosZC#vBueW3LG;RORaI`xHsj?nAR@I< z*`!XbG1r1OM6)Ar6csE4YmS#mK_^l%1VD+6<_ivUx<{*DCouiwM;Q-S1o+aN=R;&S zOTd9Dpr#=VLiQZub3yq7?%`B2PF5#!Ng@*3n8 z-mD|s9^s&k)Q6>_dKu*NY3BYo3uVQd$)vevU=m|vhh{b*r`QsU(dKPg#g+`HJ@BgVas?08ZiUH!+@UwL*(B)YA2a~d6e`l|k0 zmrAht?AV|o(Dw+hxSxh(B?XV3Rac?D|2xxg3C?rsg>?ppK+U|u%t7je;+jZDmoR!ke8$@&@<(Nojf6B<_}7lH2RLj= z;yp^sI=TL9^FK)zuKNdj?P^RMKM{?ku368wwrN~*{?m=DVRm;M??k(Z6?BW)`ppJh z2p=dV1_Zm6ocn$ye4g9HrU8RrNHrErQ0$msSjXUaK?*8e#ky2+JA7H&$JS)$H65on zgG}`Q?B7QOr|6!oKiXkC)?^hdSU>ThAH6LDKT|)BvCD#7sv)X#PNMaHE4ysyKr;S7 zHcCUp{%?lx2@Z~<{9-wMJfm~(ds=%$*Op+7*s*%H+Ar-7DLShxH#xbeWNbpTi6#AF zxyWm5ya4X6P7}?a$uItoQNe3IQmxFpA?i70gw=*q-~&b>`);vYgHsWgjX}%7^V`Ny zh7+!pfSJJZt4VgDHlao1!lnSMCy}P3%FD6s@*c2UP^R?ErG)uWkh#|6O_exBaLShlpXVIh7DF$KzWaEx%0lj@ zk+!Q?H`&_=?o?`=!jSc`qRi)AGm#H<1V^fDxAbSt4Mpwa4~wg@QubHZq~D=|j} zIQ6xdc;0&zn%@OBy8? zGRA-d1_foBPV+*Qs##;qr;^?I&;adn zKR{M4d$)~Je?&5Nv@{ycoQnHKrV))Oq?lRWr92={qAFvhlu(?uV$I@N+m#XrTG`0P z+C^%XzVM~?O{9u?7<+GKW_KGMh$VVcZwD-)2(+%183hy2czH|S;s6#55VO))Uur-N z6NM5neS1uFPv*C0(~^tWa&qqSKc%3XFP}I`JozvKRKJdWYp(X;JYx6%eVR_aL*(O= zK3Fmdp~5fr+v01rLblnC&9S4iA&?eCh>^w^aL@YL3;e+KDp{Nd3g0Vb*nC!F{ca(_VkPZEBqRpBBGC=f>!fX8aD(J`@VIrH4$d((&3(T8LgAZuh zeR7(dx(a;0k~zQJW%>Rj0LV|2EhGf3117Rj{(Wzl*!gv2-UOC6MAa4R59h!OGRH4+bxn9JfAQ#ey zCy8T*cm}}USQi-%M@Uq`lA!c8@(~2oXC@2cTUwg6P6g8i&#O_kQz=#_OeUym#I*XC z;Aot-p(f$oBWf&daz#9Zw|ooV@JR$1fLCax_7@x5Le8#dt?teHlqQ3*fAj7 zxm`#(11szw>!VK5pPDdqj{x{?Ai%;*Hdq#pR%fg>gnh7x%;>~X+VD;znJbNLaBK$o zJ{%ken_aJn__W;baBmHR1YV{P8;a+` zu?JS{yvT5Wg;P2@R+G~20w&ovF>t!xEx=T<6Jsgd{$flZw}PMW;SZ*tt?)$uzd>?1N8PwmS3_{i#=UiZAQdCXuTG?FVG{ z1sIK=F@-wRe*Xc>ib?asH6N|RcU>ray`evP^up&$xqvM;^Uo`;rm9_o@J_4(C(z0> z88FLkW|{c-3NaEU!(Zn=IX!n2fLVW!70iSP@9#VhRJL4~8b*BV7cX@(V8(rJ zcM3I>V;o$`(~~Bf8B7Uqb(nlamvUog$?{~Mczh_r7F&XES3hm4Avrs(aGu~I;M#tl zwTL&9#*8j&&D;n9^mYG>N=`+&+EnoIF|l?tR1Fpe<6e+U852Rzscn%#`EK+*+p}9h zpE_Z%EZ@2GpjsYQBK#eMQX|M$gvQ4v=%CvAx43pEZ*iMu@<$9W0Fzn{^4pDolz~c> zSx?6MqYBWFXc=GF0ok6^4<9&%jW23dswZ4_@N=F#fjT&FwQ%#!cfdqZ`+@~8yo8Q4=k5_i zUdF;{rkpfUd(~;rnyl)$tL4OX+7JLkr#PvO^f&u7i%nFcBZ+19tldDN!h&(KtsQ;b z)$P&RIZ3%&83B51H)#!2`fJ*uq{@uCpmYs&J}}C{PM;_9f1T@G{zdsWq$U_p6Oq4-(phrKqXxBuXQJGgSb3~RM^I!9IOzqJFZ~{M+?Bvg#@#e|6 z=%f_PQP5%R3H<1@&jS0;W$ki31Oh;E20}Uw2>b98esDIq=h#rQQW39=WN^$$2C(n^ zx#<3)|M@O^X6k0aYpeSTVka9xfuI98BF9lgr|0jUN7DIl*Vs}|Dg-P=WArbMjgXP& zx(raXza znR~v1XvrmzFp(wx9qMe%`YCq0VE#%Ny7xz|kxZqOg$S*hmr2+Rm6tU_Lc_3O#EXgd zRO?SU;mo1Ej4kTE3v6nWO`3xfGQ~_=;e$(S&6Cm0qEX1OireBfX><>koq|Ss*r;^^ zfHK5_L>A%BZUwb-9U2AQjWZuy{#03up)ipawy3h%0kNy~R0*!bmnh16JBI^?!WgWB zyV#CiwyU})o{+P1l&~RU7d$a|MG^?Z6kb9sYQ<}*_Vep%bWz%_QVpfx+vr$9#z6}E zUE|mS)*CV+WebO;$Ue`;F6@JOfD0`cLnv|egSU}A2eX7S)AgvG*3Nuf(F^+Mi)&2z z-aIz(vi^kbuJSWZWTjLeWwSrS6arlIEl>K~x&%)fM4RjXX4>GWJus@OZN$E*ovF~= zU8q1)hy|v)<{n@xg}iw+n7Gh$rpMNTJn6MWQ6HMTTRT-?un=_0REd^oJ}T+nq-%^861j$CO6r7-O@Uy*4ZnC480zZr^IuufKrRl_?^HQ$9LE)N%d#_`qo}WBLH_ zSk1(@>h_gz4>UO&Kl;^gE0#M!nm9Y=QnQ+D-=>iTTk-o6XG)O*trw#5ff+53yHn49 zCrK}B3yWVEw=32-wcWo(Tk~YY`cc(OJQ@}bD9TG-b% z02qz7w{208CRkz_7K*3QQB=ZY8|&PKPbW&V;L8M*=pA0~(B}sAEpFZr+5SVFtS(}QOh!H2c@RKO+I3D4;D-`G zFK*;!-}=v0in_OgDRF2YNho>P50BjsT#Azv^*T*T_+92Jd4y~_Cyg`Sj=lP4kf_^5 z5CW|IuI~ewO4rN1NspJN_b7tHJf_twuf^u{uz!Hza0pr;ZPKvdK=3}FhIb-R|4fRi zuo+-jE8!Irf+D0EBf}6gfI#hgWnDrwK>#%V3+|>t9Jt>@i+)|tltoiNAXpM6P=fvL zm2UDTkSxOv$D1H&D7qw#(gH#i*6t+aDR^|x>0MJSa7+Fw{ycG~QU{M&c<^E?=~x;E zOuE)YmmV2tlrV1f=+R5EvyBHFRv-ApPUCRp2v3bBG=OFAib;RQtFx zaAr(b7-C5i*(bdzZ*p`JoifO%7P^(j6Cx9d%sHsiKIGN!G1Z4x`MU1*Y&bAY-{x(Q z08UP*-`YqA2B69xx+nbGdxSray`HO+uJgMs`+_Vx`^F~SvCuKT z5*&&_D54{~k?SJ#MU3WVRTZm6U7dSV#moDJT8NZm#HIRsHujVWKydmjc(w?B1=E~M zA(UL#2leuL@PYG>o%@3%(7mgES63mpC1bCCjj$G6%DX#3JC-fnhijXndpt+;kB&ULVEaW9;02~mm7bKT?TAA>D}E`5{3)y+%dp$??gVm+FJ{oYte7q`gBQ@0~QMIZd)Y ze|Fdw+ThP{*(kAF`&+qAen2#!=O-!_vRcPxeWPicT*m=a8jef3LE!r=cb@+|_1#ui z?jf8Xn^+mEuN@>w`(gC?KYozhfnnmWFvxe}ZEBT4?9DBH8MTw#D?@eqMq1HL;DGhe zMXa^k+qf=a=y(2x4Qj{&yLc+?c&f@3I_3xst}!pFzV&q*!gKy8PWc-*HHel%LBVQ) zT5Nj~L6dCGH9oq|@pnh78ErgB7yeXEu-JVIyjOa1>XkNJ4fv1grfzZV5lPis{H8Ni$^_GLHwdD!vB7@TdJ|qsvBCK%ZY2=+eUtH^n48`{4Nft6l>f`j3ZX%cm z(bVUMmR&Hff3M|c?bw81W@h5C+X#4$=T$w8Jj8!}xNp1iBuO*YZ(Lb@1k^-alHn9h ztpfur8s~PuHd!7+uX(Tmy;8Qw0X%(KYqq<>b`|$L#a{e&)1ML=H)Xjn{-SY9*}bzt z<)i~39E8*@Du$2Sxa*k5XI@3!+BtWmW=SBPpHF)?E7;dn9;x}W*nrB0(oBaI9BB)C z;4{N9Nq5_iD|$7WuE1HhYACmYkgeqJGCclyY%Y3}#Oyqh09Mcbg4_r>Ao=rBs5@cm z{Zbp;4b%8HCJiT(o8^wZUBkPLnznr7YP9u^K9*xa6@$q-BRS*5^3E)XsL;x_rY9*BcFagc^ z2vr&I@AGh@(#A1J!=O%fpRsl5eYbP`o2_|&EK*ErRGpL)-9%yeFvD+ZO zju=kOvTkE^RFzgi?F-&FwMk7|jyrNLz=n{M+M3_VAWP{VSLXi79JSC06{?DNT^>5} zp@4n5jd(R|1&u|#&OdzuEq>UveNi*gQ|p!(`Wyj`S|`rp=az_s2wSw94%pnRa-1Lm zy1dwxfghMCrUNI*kA&2wLM4lV{u`MQ@%ofFx^RdSDg{DpCavAj>}1MnBZ$7arqwf=$oW^2N^q6q zsF3|-x(8+&_=)kVicSINwN@!Czgo9#9`fow;~YIA5{M`Y=xL{fjHzFVAWaxR$4e|2 z@TR-Y#J^`ynpE@yLxCcCkC(z-oP1$KDXsyBT)D+uB| zjJ~!LpAd8yt(sj%@<@HP>!h&m%UcLszs{x=EBPM1zQ#Yq?g)siD9;mTo7|MYDEUKx z+_^LWT2A{~JD%H0rUhDgwIK_?fUAH}|88F9*4-n%__#eNU0r?j9XkOC{t#e^fpICW zUl-%>LU|ncfg_;F&wcAQ}udrM}!Xy+#P0d^fSg()+C>-p;xz^w3 zx${TWUNLzL1Rk)&n}H=H1pwH$69L?M%FMt}m|(m<9zw9+P5^h)VH)x&|A{Bk zFLZ!mt!KjxVu~D%yD+d#;57%eVUu^VFdpqR5B@~VK+zip*88alJv^3TKgEo5-HzUk zuPwkH5G*UdU)wmeYiHm8{OdvdK0>+;_Lxjy)3zJq9;XQq4^g#ebK8HYS=^FxZr@OB zG4qJ1yErSCSb~1ZD)0OK!Ppjx1KqTHqa& zBY2)~)>q90)J`skebM}i#G-b*d~<1@`v(Ath7ZD)nahabO{BlEWF?0TV{kBCBydzR z(S$*{Cp_spY2V0@M#Ns znRLy{AD4QHe=JjxfM?;StX@Z~={tlS+kY+~Ztwd6V^g<3ggFD&9@^$vh|;B3h*`PT zD&d>Thh(3;KW3iMku@7^$Qf42RXen7kL z%wd+13dIc)3twKj2V7GQ@`TcTI{tLM17Ave6&C^7kYDbLjXWa=7;13$&yxDH|3d^2 zLeMD+=8*D8pkXpUGdr@Z;$7~Wh7OA#Sw<>Ga&-ljj?y~t0A5LEApBUv=w7L}SgOfx z2qRcpIC$EB+>H-N=yVcZk|%EXoM*;A%vNCvqf~?J3Efd^7Se);cpd6AyYapJV$d*w zId)0>v?tgDLmq=4udP-&hJHUBPd%YI%wt6L#JR^B!;c{T_3w4!d_bw# zYYs=j82?71c!?FPTkBZ$b?1={9e`W8nKm0=_!_)#F!)2*dKyN(L9QTfFg&S1uvGyu z-0d$bY?Tq`W5qcH0tYMWUaY!X?yd%kx^qs~Pa!Aj5l zF!TW%LUr58*&L3GgQJ=uSW=li6s({P8wgxl$z#;p5J|O!OBNs+vD4Z25yacav{-xTDnsJ|7#FG`cE`-HNmc#l7GA?Tw6JwFd<0@!`gl(9$M z2m>ST(-SY&3)G!y5I;NCqm3FE8#e}}IsmaCu49nhv=GwwJt3^oe#HhzbQDIW#1DtS zv*^Xk#1x^4Ff{>W?IOEB`h%{Z0jrNpcym)WUQqqZF;APQMe7=Y)9iyRh!Uc?&?~ge zN!cd!s}k=VRFtkfAZ&&r_thz6&s6D9Q!4{K$e2eBT*BrW% zEpTlU$*$9Rbnkdp4RKKjhj6Rp&Fn)L<}TFu<=7Iiy^+5a?oRl|0V1r7Djbgq&18zL z2plZv6x6dMMyGRTr_apJXq|3NHJJbXj62+q%T|Xc+fM?jv+cydD+rdEiMKKvr8kYN zN6|*B&Bg4t-%gO9s^jj<8pO-5;s~9@GBm^$8jC*u3-S$;{(K?yB9O9RHbC8WTBOh? zHeWqMRU=pU;9niK(TjguCYotn%XKdXmSa2GwT)~m=vZ4ROW#BJNg9YYBEd{MMBmDN z=a4msJB2w*2?C%aP>4C!fAxvbSF-Llncj3auNx;Vuhi#=CuN+5VHf~vE~aOrQDrnv zk_9aMM#_3A9nD&d4PAA!e_{Q~i8;y;$@(Um!CPVS8sYCVZIGl1qI6TAMbFqYGzLZS$Ele+*7ya0feMT@+Kc76+Ph+zb|e2AnKU(@dGbLrA zj-M%r1WK`r^eREyaxs@0iU*R4?K*fBwBuXt0{fN;A&e85x%=D?;xWmH8jlM|7c$tb z2ur0|^eg%e9IXI9la#iZig8|yHTYXVc(y(Xd@7JNl~;F1G}etmvTveU3HZ}|nu)7S z$LX*oxa#B%f2tB*ire;`_Z|k=W9&vZyjSE+(-Iq6;-CQ%OmFYSpueU&Jt@)HATl`v z@;~;q9hkzukm!H!E$zimsl>;c?}G&XAIFUJq~b}HgJ&ViEF}YqdndYUds+C6{q#6s zZ;&vwj0%J#@{a^j{dwLKVU7v6S8w`c3wCp9s0Tq#)C81T?8fL5EqZlyDH==O=! zpS1B@UaDDoWhX*H+tWnfd(|x(H2G`a|2tLi@RFQ7CemmMovH8J=0`{6&^l%~MRqr| z1hE7huzj$ieNsM!)`ijgO+6y=zOR)lfVUi6pI0K7UMG7!zlO<(_>d zv}$=}`fHAJlWos2-H=%OmfCSq0^~zOSeP)GL&^kgt`0pqlVA9M3ocJ>Owpz@n2*9W zlqvK~w0QS+X2Z@TVVM$x_v{&{`L( zjz4mdRKjIhy2Bz^-^xU`c)BvZ~F) z`bQuLax~@E6`vw+zpEN?{RxpAj*ffz-T>{N4Cs z%%I@GF#lC@#RMy}2t2Zh%L#pmj&vUuplT6qN$#cUo+pw!O5#bKtkOSP!c`Z5){vh- zjeWpkn2Ug@l>!M}a6xggwChsCu>g`_Y30&(fS%%TI932}PXO2RbKnZQxD~;@eu$LM z?B31la;P!7-o_Q5y?9 zts%1l?snOi2#s;5b8$8Ae_Y*7Y!e&!e;RI`KKIrKXIj1nq9s#9U9PWk-T*l`b}pVO zA@udoIm~!o?~wpdf){kLOO8d}30p3f#IrA|MpA>(%uX1-In{G3{B?f_C zp7CN&<{?-^t6FcEu;^;^rp+ zJ3z$0&zaP?4H7#r%+fFo$uVNE=OS&ox-7KhJCdvN?n1d4> z_y`=nLo+-DhPbA#%E}|!<{lL9e57|zVQuR|D;VonY#9OAh<2g~CK*+pc-Qa*NRwZ* z3pbWV1)c0&3Z&%Bz9pxZ{W7V{v+Viv7#83-Y$tHRzKzA{uT!Q=23#6EHQ;%1Mho_} z+ydDA2Zw$zlYCmUc9}as%g(U;4Mk>#``7lI`#Er+9|UbXTdv8PgY)E@J@=U(p{Cqf zL84v9@)IhzP=nI$e-N!~S>MfOX_3YK+F~2yI@~&neo&z)AOntsIi1!SgqEcO-H@*E z5ds~yFsj6B|0RcRll{Awb^CIWhJ00FzA*gEH!zF$=G-7Nu1@QFh864fGaLJ71PH^~ zax~%kf*|8w@Ejl?VK~;gCwved1Y(uCQ!owMfS!s$uD)HK=)8^ULdaf7B93CYf9-dx zX4Mu_gfD-cS^hE2Kqupb9{YB3GRrg%vSh;=MtP3%ndi&dWTl44zzOV9@y?KR@5ldx9dFTdfI{#hIk8zGr0EU zV-t`LQ=gGkgR14@__vy_FBXk3Y;6!otr+B%6^3;7Ch78agY1dCS+`9(HfN$0O|0vK z(2D9yQ1S3a7b7rO>wyNw8?$j!uI%ZhDlm6<1kv4>al~S>nHWM>r%J^NsfI8H2=}4K zYC~AG?$N=_DeV#fuHKWi|5i z9uCAkE*N#U#9V>EG3=banW17^sJ_IsHC`Lo!f~)1f)w^Fd5cQlcRj z7<*~PSN^@=H3<-vxSNf^f0W0zejd}-USS|f?8f@J8snG6a$TTPFc4JB__?+qu zslLRLipM@u&2HnCSwk+wFXLs&s%V-TG)osrxDwdu8qdkIk z)M{?img~{CPHPWi(~xKUH@zoTO;lht)TDrN0~4HrCiTA{_oS$xwOsq4NQV7;nFAY< z5qDYx?}Yipc@qVYno*J@ye~Eq>*!8|(%P62S zZFOwlP${HglyHVwP!B*#_Fo`}PFpWxb&@^;=a&&A&CE-t{a=;YzHj)(1uA=RjLH52 zaEPw5mtuCDpX{Mt0|?soAL0KMLIpMBFIH%TJavL~vm!4?+h!zX`IWHJfSHWtZlemA z+ZT=!AhGxwUzW%`rol6em`8&SoSad#|7fmd>?~<6>y9tKhLv7>4>zytGR-@N)|r0y zPm@yQXH694tZ93-pe^?*Wxj>58nAS8cn!5P<&P|W5FvsYWOGx_cpSAHxP8T|0d{HD z9rU}thz#zG0c*$r#TR4*oW`7G#Yn)V0ozu9ULMk;Ov9TQa&mlo6d~^L87}I=e z))c{abUnN+uIBN=89>$XNp<^W5lR_6MLeUNZApwN==YR{n^mI_YzINgbdcoORnZ3Y zwF=}A&GOA93E4-@!eQA8^@T$y&wmE202-`SH6M6-tv!3N8fo;L^UM9`2@rHx-$K1! z$YingyF*4g!%+p4pK$#l#3lK}T=koYN!Ijp#iO>7n9jCx|N7xw34>qRpX(b{BX^y=66j$f=LjKDeE(K4zl^ixn?xs9hho7_ zsCwbS0M`csE3o*=4@Euu&FHQ!ymhaW0lbe;6b^>_`Z4oZ{$~~4#YV^akAm1`f2_PLZrr~=S&q0fR3Su3gj3i&Yb6GQ9fB$gZI+MxU~Od|HCL{2 zYEnna(Um6UXB&OrtvVeerg$nxc>QFWw?Q-L2j^fQNeF~?s)9_(P8fz$y;@+(#S`GIWbzsQ0u@WP0?x9*SWx+n? z@uF=y3!e}y^~U18mQG!*XvfiX?QS<2A=|hoI$O7CK_(v~nx(}PrG?vw$$;MNYE}sW z&;<1%4(1sMK>mzm2$60&@4dr0w%1LVRhNaffMC?bb?Q2_TX_MA9OAvShllIz?AK&g zq6<(Yz>6iX+3R~Uony_4F%K(E!0*7rHf0*07am1{?e-9-%Y6H^pPn8?9GW1zHsiqR z4ZsBnEQL!J%RhOfBLD86ht2U>kvf$n6Zmcd7U8Nh6zqUILWMlD>owE8&}}k6YkrX* zTeU9z#>iX-T3F@F@mbH-LE&L>PC7FPBT$4nk>=4V&v474z7V}Enl|Hi?gDztA_IuR zSII+rTC{3ukX{j+Whd%-%6jXar4H=%4P!f(^vu*=Kkrjl?MIbi21AoBGSbid@sQa= zFDM$~I_?R|;XmTbg}bAZ)r0=#e9_bQMt@#*=|5ZrL-`0<%Z>a*#ooNxRz@vNv!aML zI8jjheH-A%#NANLP*`{Rl+2f4U|W$kCg_~zFHp?KjCKkno(->8b7kzDAE`B5cdZ4@ zTO;g?+IQ_U8$}EN-jL{i$f>`xftc~(i)d-_v(w`M=X-k2$GSM|vNS>*bNAf?2eTwFxL;{R>9|Js6P=%LyY-FuA_s@?lzFi z4oF4BY3j&Cr|5LPmlY@6V>ROpkEk#5aPn4^S-)=0r02HDC36FwHdnO4x(RF(=1nHf z{e~C387P7`iecYpSTkD|YykvKzgX*6>4H$r3h7Cr7apowtyj-qWP_w#q!VHZn(PSi zap}BfXi*Wc$hdxluG@XnDOz3!HsF9SFXks^hk8-I3j-;;9{0SzjoV4H7J_q!(a?O~ zIG$qU;};NbhhMCbRYQ+QxkECVX{q5AP5cc`8BJf~S6m~vNU^n^v)kIbOIH{uS* zOS2J_=UTBwzoV|PyC^RXx4`}W&#;CLNf3T{B>F%G_p*owoYQ6UfC-KLp#8y?E6V zkiK%=GV0ZkS7ytgZvxi}tQCxeu<<4$rF}`x33u`NX?Q4Te!s?ZQnszmAVlE|cn7AP zq1}g=qw13TQUx8f$5O*WXB4 zMq#&V+6oPKjQLYu0V+%xcy6jGM+ zb07UnwVSvdxzxL>s-dHKhmYYtKE2aSSRkehS^Z&ODbcxgu8BONVWvZXZc@$VS|i2% z6qioxZ=}Hw{!ANBncNFMBt}6hVg|V16oP9Rbh(jBTb7l{OV;_%U--OIGLC zQ>XTxC06RfPEVNFJlEd*a_jGaXtiYgb5zi3e`!`iBgTfO0U<}Fdk08zo6^Fj z=Xos`BNir^WD4P7< zo<%Joe55hlw*vUT0a(5=cl%!i#s#bp$)?}ohF`Avs8_Q6JgglLdhM0ltNJp}TA*Qg zxJ4b^%%?72>P@r|KFo5Y?^4}!DluZ-)li78kuiT2vN#xt(tPQmQbVe~wsNWuCTDQ+ zMtFp2)K#j)P@8UTJ!*MWc8tTe(J#EL`rP$=z zo{|s7?p`stUjN)6Hd&lgwCz?C9z|CzSo3)lU>cr0YnvKt!5wV$!$@dJx6BqAYB@jS zbYw!(AH3TBMtFn}ar^9-D8*PV=0UJ+AO$9_-J16C)cFB(6PaHq0Y8*d@A0{vVV#aA z@F{r;U*mM%twv_W;1DF!;64pek)>jm?gsFJtspa*fhEP*BM$KqXfkw2yWDo5q1#}^ zRpePaCC2E>Bysrn&IYWBff%|5(>Wdo#$NF#fh$0DntQVBre>Shbof=P!7>#EH29R;V28WTRfHVi)6fIBqIMX)?xqHXEv= zsAXv_O|j~`kvWy_SUk#k_1|f}m5KUQFq;P;pBiufhp@kwOETEnbF@+}NTCqa-~1!< zeMLXl{Ssg+GVl&ZbVG^r!j4q$1aR&5Pge){6uUr(QQEG!o>V3ws7kvAZRa$8H}eb` zSs)%rsKvX&*#*IcBwsJR1d-LuxbzAFe)d18Q9rfOJ@8@yEq5O-;;>5?DGCS|S1WnT zJG@*&-)pz{!sbxfyCX)vg(B~Sx5$Ij1gY?tXf-#}{##IzHxmF`>!EKMwDpp)caVXr z4PU1;sTxYm+w`ancSo(Q+pp)xlUHCJnU- zU4YDYr*BFZxoGhbWdWQGHU6{?kyJa=z1TP+Kh8y;*$`6w?-h4#))}RIQQ4{2sh!ua zJzkFtSxtF9jA_YIDPRo!nCvLs3-(0x#Uk?&&OkxLps@_BVGn>mN?Fn?U<9?!@GRZQ z*SBxXXD92}g7Wb_>{kGz;;Ee6Fb4y$(C;~vhFvl=L1$VM{s^PKU>&2mpi*5a5qHc1 z5a3K%idXMT&{vtkZ^8n^kx{k!SMoaE-A(raN#UGT85_9igtn)wTJq5&eR1|3>!@XW zD`%Q$Htg#;fVi+^kuy>qLCjTJUMRCTI!jT=WpOOI8%CRWWTJKCw%^ zEN=N?>SCYi1V&qxd+w+154}(BO>bIjU9#|l;ik5SJM;ziHMEoImT#Vo|7^gjUvhts6Cwe&Bp-BPXDM|yJGN9kIWYI&2ha`%Aroq4Nk(Gcm{+R zFid^J9?oaf9M$C%vxLbg?bc}mOOmoNa~=p)<=}9`mg&P-$aL3dMhzpZRZWXVJNht) zP$4w*#^3FH60p$=HZZ3K=kt~v9|@3<9edR-aoql?G}XGzpkMT@d$UxD3=UA;CP*lk z2K%xT*)CkB zEJ-7f*eZbt{1zN9hLI~U2Iw@`1Y9|(>U={3sN~%FXfXYFbXznp5CW5idx@x9e6^I^oYVQuC(4pSA^mX@ zSZd{qrJ{KdGr(iKPj@&IBVXL8MbQwohN1x^t33DMd$-|xn#guN_&!8=P!EPfk~ z5&?`XoVdodC|K!VShhdJ9}=>a6H>|Z<=FmnZha261uN&vGMfV7!7ux`P&cwr+%S#V z5|30ST~E8ayq%6ZFD25RrustEm+#e0JH85d0Z~$lm|d0R-#3Qt+zj3>DiZ!IQm1EUHPLqn$of8n)&+a;io2%VuK5HnG>_i81+9S#fIyBc<^EPoL2};F-sI zD!LH;{}B}ae@fc+_`EyR3~2JQIBBmA0T0F+>ga1OwArY~L?+b=^kx$a6?@0s*O^-r z!lTrLQvNTFQ8CLAjPal}gFOSe>&s|Hl~PHBGbx<`4rU_FtpgtU1L!3{ZKYcDPLK^NV-X}{sQL^OWNRE04g=?C`PLUP0O*Hvu3-|6^d-m` z8tmH4O-g{8-+*H`R;2&X{fTdBBrGqy2gu7wAzH0tJFYXJ3enikgnZtmPQc^zZB2jp zdB4ehT)p~?eg)G*t?UrCTLvyipl&HI-8q8qvSGpZP=4usxq`5XxBMP<&*9J^qYBGF ziJ1&6LIYsX*{r|GN{s^Xpgz>@jPk%1G!z7jRb>lDKzs?(pFk36$Xgo$FAHMrLgiyW zFiMoDoW`L=K05jcRVRajZppk5wc4P+YlgqGU|v-5b~ezUaOqvHV^l7?U|HC{YQt^5 z?ySdM$V%z6#(Oe7dUhhGc=V<=_=TaL^*-_%!@4rX>(?QLPz9`v1zk~q6rrM4L~k)^ zA&z+e>w*bw&wIms^(oX{PVKw?LiM`_&~j;rpD5~`Rdm-Eg)k&*AV8rOT+R6tU|NSk zTq2Dnjb?hU!zE;El@(#(<2+$q%iDMMX^qpYoXWHhk&7C=w1|$E3lDhWNYg&zuNQ%L znaP_{BIypE-oNrz+&SKKhhMH2^Rc#XR(tr5?z__gCIaRxSpE$UWyllQ?QvTPIWB%m zg7W~{=;tx9n%fcKe!#BmPTI;2SlTFo<&pQlU_AbcHzLHp%GT z+*5^Jem?is;;qr&;e``ky_o{PDx}4i8x3HqEbFWj(aIe5KU}4|&Z8*OvP)rupRcGIC#g z8=A`leu&tp0z~x5tW{v1uoo~D^OF9;E)z!m@0;PW zD{pPApu9!+NKlB+G&5=2*Y_~{wlg?6xu`(m30`GxgP= zebtvyfS0fb%1n24>b8LZ55JZ{XAv2{?*NHTE#b7lIx(Rxx#emm z@<1fZq~YIJ*71RhKs7eF+az4Hi17;T<-2dhmo2d1)k5C|Cacb$r1JGf#(nnMr!iD3 zk?r$uyb!lqxUW4C#hCk}yeK4LvXL@`#5~&52kZL&7jzP>*eRlSMY&*f5G@ozIi84T z<$B#SO> zzI1mV^v9{;6W4CwwwMgMZyPlZUB@I?=J7sdzkY)}W~9YRD@A*9QI2u6QNkaw?hHsb z2r6=_imR2`S6KrtL9405RCrQ_uJMF9C9LbrBBM52phma`f?M@{bxJSdmk#RNXxf1T2s0eF_vtzuXihwja;Qa}`bSi3VnMo} z)dOr()Jn#pVjTOwLHEx0jz*JH8O0T^90}ik#ij-iy|%c%Gwa>DH4P*={3x zTbZ$2{5sKa?`UnFe8^1E)c}kuYY8Ay1SRBn=YWSmejf;LzTG84xnD^()Jd^1A1V|t zF5(ufWsP_z^jVXfvT>OTJF(g-sWyEZ9r@G?jq8EVG=?t#g+MnH8SkRtLDSIXRa7P7 zN_=FBXI|Fb)@9W9q4JY|-pekgf4S-i)`v71rs9a^iEyDoYi#`zXHS$j`&3hdkfV5xR`Tyc z@047(F+5wFsv*8{kMv3K`Q$3_I)TfzQ``YJ+X&c!t?gUNNsT|)@>sQ z<6wSFHn!=CCsyRSxdYUJV;5!aD2RI54Y;#>RwxP!V0pG@v}m@>uGQ>d9BXyCB3 z?z(ln3ERa%Mrv1gnG;f1WE-1Kr8{r4(b;t*OyJ?>sHBgS^n-QQks6wJl{z$mtlZ5S zXihT$dN6(faO)Me(Ky5bo9O?U{vj zRTIytLSc$biEjf!s|G}g-TVIxmsm#C))%HbCWiE}Ht1GeE@%|^PxR0ZFjSg_3;igY zx~FY_i20{P}YAp(3Y(ytW((~a`ZD}SZs z>)uFv6oQg>6K2fcNWaRIBqxL1UX4V^&i#K`_(QD5tTKhB>w|wlp>v~bGwQxo0wBB9 zAL^%q|uNZ#fWDY^GWSmAYta3pdP3c8TD3fS0tjeAPCx#)z`PMG|Ri>s_NX;G_$PYZ;j;p3u->y z!RaVjNaGZcl75#_d^#xl>G$+LI}ytF`5-QC)*alL1hjGiouxHqk3tK@WH~uDgUs(w zA=y+TIn1S<^fI0s-9z$++!^aEsiuK-%lSrpkn@baUSb-9%T!&R`dD@7A2T0yJO09M!<27!FE@bPFU}rAQe?K7W2rRO$>{m{|m+my*A? zD8R32(f&ZIqwCY0)#T3oS+eN=eY1@Ry(*tAw*6dJM$(~(@%~QZJ~fUkEn{8=$dvOL zuz@Z3p(^nCB zj2Wiw9jEklC|TYWF?k71Vmx3=->GLuRllZpGHBU}^ktWHmud0deej(l92xiYl$Ucp z-wGE1dys^dTSM7wE=R=)+CGq`+$@B?ZjC=ipLgJ1@g4jF*ZG|dn=q#9qSMtY$0S$Z z9m3;cD3ddhMI?ffOn(!h5>z{7yi4-++%)atoV)S-7~2Fq)&KPGF4{Zpb0urkhCTJF zvXKZsDFgGp>a!_9k?LKST(o}LDPbxkCXZ1$#Igo8OOCKXV-L}dRkicXLC|!81zIY? z5064PBmbl6Mth;Oyh-^NiUV6YLj+Ss88iCavaauKCin2@>b4CzFau{RFD5I3tcDNr z+YUwA)93qM1ZpWyAk}XV$?eh4Hz^`z{6NBrA01}&T*rwamSU=Br&JZUv{O$f?RC$D9G!3{iD zq2N&+*V`7`5uq>Q?owb_v|;lgc0QPI}z92x!v@7`s0(UHgdH4t+@Cn{jXs2fkoo8h9WT0(h_aYDj^l=emUZlbn zKo+72J{%4gCYuh!3T1Wp{8l7=E9;&n&hed`JF>IDo^tg}#U@f)Cnj(4?q}<52DIDY zSy)@Ql1kJ21@YZ1@Y>@9HuXodk5xTCXEk?OwZl@GR$f)nW$+=VkliRRiYl4^dDXBI zNe{0Dge1@$0-?YM##knTA#MB_upL76mLVGIz!rW!!6mf%ucWNCBcF7@bB%w$$`9Y4 z4RiNA0fo_MHf=-^Cp(U#jXWNCV4j^l<(V-*_qTSpE*zEhTu#t~j=MdLZG;n_ zWwNUQOqk98VfMEMXF)}}Y`Rhcln)AqV8t`Vk0+t4!;I(|B<8sBpU{V##_=+QBL9L(~>ii#c4!G3hakbw!%>rJ5^74`ORf380ORleZ_WA1LzF-$i0p_wVO=|#7; zJ)mO@)P7j#zG!=}g80eVi#7NDU~XD3uVIgxk7G>~r<2+|Fe=|CEZ7X6e)L1A?kn(Q ziBuONWWH`GA8n7*N3^&CVCAg2zmTgSWiqIY;q*=&bqp;64wc4r!Zx|*F3Xqm&Uqm> zx6ltaq&!BL&Zh2EKi%(Z)CjG`(ww!oz)HWDFrLj0yk65|uRlF>zDik;h){4q*<4zf z>ra?p#+t=#oW63(1srJ_$DhZPoaVVnlEF$srT4}>syszD40o(#Q<{}$+V4#eAAk1W z+tNMTG^Ssj+usP6rl490ldukW*gH>UUbz~7!IIlbIX-FLa()&#gOgE=gw-L3PH&2= zAU})=d2C?Dy3q_I*X)MpT!6iVmlGzBP>^nD@-a*RtMvfxuERG;JXJ1!y9Z+mml|{8 z$UK7%@KQ35!krjpP*SdmzVGdOSxxt1J>H7%S0UGi=PVxnNaP*;nrw zLO=FiJ6_4hM?WE}a*#aFaANBYuNnBUrGR3PU z2Mtfjm3lAaEvd&m<5Y#32}-s-cKL^GpzA;S4>ef9h$gxF*0JM&rcOzPi>(oLbqleC z-l_;Diofm^&7k75iBguFfx*`YZ!fb#8HZ!$UrC9LVu($s>DV1)X-NitkishJM%wOg;zTh{9lhRGI}d|@Wirtrxv7-O51ElO<)2w|Cur8^7oCOqYI z#_)#ay?*1+pd!ebWB)S5k_)k<l<80e9YkCBQ~}l&)*eALf6W^nM?H!1!Js=^V4= zW(qwtTvCY>htyFrby^Dn@9+uSYBU+f8L(>0I{*oy?b0EZ1nJqlWx~>v4k;0vPF-Zb z&D&`UqLrEXxIy=Z$VCz}g=z-ucWcf$6mo$1OM_QE_brN&{Xhi3-6)T*hASI@ur9fI zw43vT4V60MLxW~Dpz&-2a|k#W$fV*`#)oSOBtRVQ9em zMd4Y~h~1&)EnehW;JE4r9B=Tx&qXzC{<8BBC zg4ePMRq85jBS0c~h)!C1dng*&%hodeN|KeJB!f<6elmi0wef+I9=LFIoN5P^TxDCx zntyo({jInAl)vUsdQyDjUBWO)Rf`uIj_m&m&UVzDcFe444tID(Tf$Ap?iJ{U>lKmh zH1=%s&n7!Waz8s2HHkkpJ92$L>Br~9Y>Bx06!f@xM7Z$wnc4aNO>##+D@UUdE`~HI z*lHSITeBk~rin}beJ#j-0zY}Zc!d_PgpU44Ub7zkLBALaX1keOa>2Mj>S~WZ9W(|?>=k=hwPI_kr)59p> z*@$wiU-L*U02rhs0s}CuG8Ldf#+!UX%-C5DHR-{+Xy10~NEz-JgO`?>m+LQgxW$^G zX6bQL<_YK$mOlf3b00e8@$$CBK_1GcYNTKpUli{St}t8Qt8B{7HDIffW=Uyt(~t8& zIjGGYZ<6wCixblRdpM8>|B;V0YuU*)o~=$ z{B>Ige%K9cYcvlZUqFydD`De&mkS%Y=ixL0-)vSU>6*DE2tJ9sH*pCO-(MN}IXro? zyx57rb@2KZB)FA7J60-g!Y0{}VL*LC)c=}sN*zd92mSPqTrY3cdm18cA-c56jRv2b zVc1)g4m<;7$DBpluiP1A*MbRkvvgZnXE#cj+Ql4J6sVioUf zy`!6*uihk#Dcl9gII(Lwzv;M^;*Cb{+Z^h{v+<+LWUc|aMoQ*0OxLw*=kmDV8iH0r zd%ITBu;fkoyY<3mWSIY)UDZdIwOWo}ZEQI;ji?7Bgv}~b8fMxoPg-eSFx5#Q9{NhM zS~qN6K_1K#(;!7}Hi0{$%}8c*C|Cr|`4rCiNyB3%@>x61fz?z8S~oOJ4=1OS3-5rH z1mX=120tvWQ^c$F2201)K*{xMu;TgsD|p*x4I2(BXPC!{(`fgaRtUvfFvN2PLa^sS zfX=s{Ca2PLXL!S?RQ2R{5Ou{-pwyt@cc`}OQl*7Xv!IUsCI7-L^%Cz{8OQmjh`up# zqPda&*^P!w`3YdqnGH1OZXNOs;B6!Hpm9wE&+<*;?oqD54klu15|EAg|HMZpLD^s0 zp8RRCu#XNGG1wr=ue;%PKo%sBkLu22W~?*Hm21UMW3i>}HUPC0f>E3%cm{DS51&pY zmA5Z~L%3!_=dduIQ@2d6HO$sw;h}dEv}O1@P*SL$J?-}frc9{w0FoM=QBfIs^|t(& z=@e73hgO9+A_Ri<;>_HC1r2%lRd1ib#*t`ycR^_tQo)FoI>bMPw^6Qph$=_z~2kz-xvF;FOydIaSl zGy~PGP<(wuc)^eC7tg~7G@B=fyn?-BW*;0lm|7Iv+HMsi6@tCrA_HhODX{b=O`2-` zf%Dt^p`!Ui&w6h!dzOVX>h|RrPt%5ufK~U4FPA6DtgnLrNNVQdQ*BU4TJ57=1D?~QYJaz4WnN1|{i_-2Njsn^MO@X>(-xuk z=$JRLi7eXAt9zt31mbe`S(Q;Kx({i4BX8`8V@tq@x-f+LAa zB|wCn+lp465dM?tXzuT2q+@M|72`~%K@H!VTBT3G{?6aQzIQ2wJ*}#7?R1 zdK#T>KfEH5;mP%UtOO0}owGV}S;G;nAz#;6Nfy1Ech2A#ks9`X{8-n*#e$q?QO@I) z%MAb$K5|Je;fi@K+YGIei#b%x7e02KW!PvxpIXI+^``n3)?k}uLsA;p0+*H8jQ|Ts zaJxQdOy%|WBoR_nFx9TX9*?!nR%80yEBg>&>#r zJ36V}hOHf z`6}QS*k~+Xhb_pdLDFbTt%vZbpFiW<0x9WNYpush@iq7ltJ0{aE)x$O?5Q?k!by|t zx#!kOaDvTcFsXVhFUi+08Nn6tbXfFuJgo*2Vf&Gxc*qx3;JQghn=D^stwQ;7nY&A0YSA>n;G87A* zNAgf3a*-%vrRtlY*~we-8#kBohKN|J?u76`03*9un0Ch>#%~VB-dg!J# z`D$n5tUY3m-JaV8-rkAT;knh&&*6$Kz47td9E=;DN+r?3P}waaxEJqCu84<|3kVQ- zRP{tF?lyavL*w@*YHu*bRNv*dhp{A*R}Pi~U!Bh@NCL{aCxwGgJX=xT zpy>nmS)m@0rTLj13d#dSX((l$oi$*$jr%7anY?o*kQ3d$dsBeWXYy4cO4`XVK~1)$ z?wqX0i+N;4cw*C<-=hs@uJCb*G7WZQu#rvb5M#GNeb!NNBF9lZeO9*+4C~?7raXmd zT=&p{A8|FTEM%jSkz=5qoG?_uiujx3*jfta%q)(};uIw%mpF@h;s&wt03e|aiFBA* z0VP9nkZ3Z8_GhD(i=_V#eVryPfKte$kRRg+IpO^ zbl-n}KP&|mGb`>#)U(Kv^NUXO*ieU7XuTX<_rCz)L|Ba1@q!Xc#=~QyK#2_gg8jfH zF?%m|!Q0xzxe|b1X24Cq63zQ!QJn92AsL?l(>|QXbKNjTqf=5JItCx74B9{`V9fMP zWP?C8G%vYfa0_ZJLxS7igOU@k3YgJv-ej%4O()hkmy$XygKyo$ebAB7Ko0+F;ADs; zEz{qLtMPhJVLdA$)n_{z?^WtW;|kt_9};u2)jr(C& z1LH}y`xlKyPhEeu7gPQnH%x9A$+P2*M^nR%DwWOAtC}l@mK-mpI`V~m3rSgwg#&n` zn2kP=qO=S)nwWX~DEN;}aXa;9Te=-%OUV4OMw(Kq1~2?;A62t)QU$|Th6ToI%}Uo5>Zvx% z6zVWylx;kP*G{#xRt}ggcb*UPQ({0|v8MF2&ghlA0~uV3eZ1A$+an$W{pgDI$Uf(e z{&67bwIuF-+TNIKEK#)wQV^UJjT78Y&=M;>NX4VZkr7%EA_@qsX;AtkT9 zVeioqLt6m?2}UA7@R2}^*UCUW3h=aX-VeaY<1SXfu+x8o;zl8s-~VNtAPbAcv6#N+ z@K91U@bw)-KL^T&^cMbR`!(>GA86vvO^$roxA1f3tnnpadwm{U6Ea#y*vX!Si9dEZ zK^PWhhT7~*uVC0SK$Qywj%=3SEF-xeQw!uyN|&Tr?c|6cnVcWhx{Ui2W3qyM8?P*& zDkcTcwFUt@JnXX1d@kmM+c>&pMX-uqYBLvE~`MgwUK*|*LOwJHBX)rY%_-60{F&fh=(|EW$QHxU8n^Q1e zS0tJZ5)YF&d}z-ZBvy_BV-wti{Xsx|jDw{DeBWyd*qrF@noM{nATe%od7fqr4B@`$ zgOG&>(%@Ywym6r%`;N5$1qZ^z_N6utH`;rNp-pVn#Q7iGdx+gdupNsFUk>T6aE=sg z@}80Oa9v87k5p?VCipYBnk%3GxmpWOK@EClNwy2bXALp`_yiy--15LM{4lIz`AEj4 zjQ+ZNrUYIC(Q2S{)SH}(86<(D*0ps;ZddR$*gjcc%HWm5t9e=Z4K+Db-D8Gm0T6AK zC!XhQgISyCUbJVnmW}|zjqjjy92}_+f)>C9hT#qysr-6sPkjlbPkE%NXQNAO@um57 zjfMIe-s@RxYB*EQV$r}65t~hK&aNG#U2$fket}hB z%8!p5V|DG**6CcG$xIhM1#4!)^Ho1#ti+EN6Ll)y;+-#Shk$_)>~%3!#-C}}#OfN~ zc_epr@r%K$431%wK3x874oMY8ijpTl4pVcmY`(rofA=q3=sOX3@!cuVZe6z8y8 zY2>VmaKtH<7(uZnhZF!f;hDYd%n+7#@{%J#v=9Gg7$E{Y=!;-OBixa=o3;s$D}e2J zTd-JC3}|z{?xWeXznt5Q9TtluW-fV51&h9tY@YTKWTbg2twR!0k@w-QCMerEXvx*r zQZ~PzS`qK3B{l3_sQw~+-u2}M>^es0>$b3zDRNpn(35B-@Dk6r7q=#+KJrwR>3V-L zrvGrw?)>BhTRlP}Q2*tt^oGE$%NG^Xm_xVmyRbTjsPa8i)`?^#PcjYgzzEtz?J|>z zs<-@OLAE8fR96Y|DZKJy1fNly4ModgFFy|}K#rd%NcqhQYV;ay4&Ed@`) zhajT@KaGNA+D%?IYG__fv#V!IDJe;KHtF8H*i4lC#-B|@DefYdo(8AQ)?v>ARY+*d z^n{k6ODBz?=xbIbt#G#z%}7#FGx31$NG9vX&g)zaYL`h#3LoYthWM*X;AD}q? zAxzQ~-rqj|>5oDlGf;Z~KS030ZDw2yY~e7F09w`WqBRcevJjHvaLwP7<8#KsPQHW) zlnn{1`WRp7$Vpu+Gq5bD%|?P*5@k`KI|NloMSVV5iW8Sv0YtC%^prYo*1KZ)o{r=* z{p00GJjQjWkmfp7-P92gG-NQ#R{Vi;(vgdH;wZ{i{aqp+N7vK@hFXqTUSF#C12zex z6F9x=PiQ;wrT|ZIbl<)`Pe!6(X9B>p^f8+8lSO}Q;T z9@e#%dG}9O+SM(%Zl#Eg^Bf4xqSYj?gW7INKvx}Rv{R!0{5=7-G&vS_|5TGodHUvz z5d05I%u@4i1<^oNlpFGWoNIZ;v8lx7N(hgCGW^iR!ti#6yeSDKhR{5K9U48LiNH*;N>fkNcq-!>7jIK{F_&ZDXi{J@V%sdBFOe1 zQ^yt+{iPRzXnc<0Lp@j3+d`@Giu6#cFmuw7{cN}e+YX6W`M$%gf_+IBu#;t62D1KV zF?Y#T4gbnV^jGw`yW?B^QFR--7Z=3j#FxKy$wh9jq`Q6*VmPQZ2cL}A;dm+fAL;~{ zUi#Xy4;gkpT5=2sik+|{R(SOe007Esb7yiWo#lU9TJad>FdDE9(OptE3IA-lj^{@zv1zi_~82(gdFGW#YW zqUWfj@x8Dl$vsO!u3_H@411-~7=sk;6T+2kXpR4aKv{6KUDOOrs|b06bN~NM*ET5` zW@)?^5>RcC8pF4b%;ekS(CaJo2z$Q0KALOX*O{+Vu&&4J{`WJj!L0VF{AygjcAyLS z+yX3$^94vd|Gw;9iIQ8K%` zSGMKtup=xkoj#$_^?|Dyg~1>|Dc{Z9b+oHmWNf9>YJZ=?ttn?jfv;ll#AUT!A`T24 z!t^S!zi-zcjYko4MhGOfMpq8lXTEPfF4rc^!g3{`A%T|X^f&G}GgyI4o*v||7s7PD znxfaNzMCc|OWQJnRTDpbq4>Z~Ip|3B>Y^1qMC%US-o<9o3Ndr|(~(TB9H}B#nj2Bp zqZ9$Z7&s2Ye3?9jQTyP_n1vrWm+KjLfxEN*~e2&kGV>U6$8J6T_Sxh-q^E2Z)-k^g7#`A8AOGm`EtL zTp5#%cW-vg$3SdKx;hm?Cw2VqCWJ=rplLPoX8uNYlxo5Pe?Q{F8c6gD ztB;YQ}3bovg z=i%ZdWE6iDW@$9c-%yj?p6*iKbQN3^2d`V)8!;4W7U24qW5)ig71BZE7t z0_aF%*XSSCNutmYs(5Ey>b?2j zAOZ_O9w(K>xWFcGG5$NONHT)d;k8nPHtGLF83OVHL@q_i{iRlXRQT zg;Q541see(fRa~3VS_)_UAo_$Vh&CA*J;Db8T<=lTd@G>{lQbM=`mM-Oy_h5oz3w# z{Wyr33#ju_T*xs8{wqoYymGXoA=*QDb0v3NYjPkY&8~J~XTfmS=F5}5mE^Nwch|OD z@fh@`PmG9C$*>u=%GvKU`}oOYkxa`*B{`s;=djk&O$Vt;`$~fQJ&KLS1W%(&SW6kJ z$+Qn6=~}H-VpL1Nadt((zAKMm!y^9s3VxkJ=pqL9$|x>jWa^JBmHQUU`6KLLo%3PC zcQzu~gMCF5lfk_PA_Hb+F>cH9R6Z&N`1I|xW$1ktGOM(~qLJS>vgpk-=2{^7$En3- zRq{mI!P(p_$Y5x;HXT%5&oSq?kB z+GC3I;F7Whu@Dm(Bbe`@CRGNST#J{<)g0t`tV*7QQ}TkIBi3e(>Dw!#dF|6yg>LK) z|GK;jHB{g_=Q)s{-;SLsfo$cpQs_31UB7lZzl9BN+#OQB5hxDTzSMCYcKGGz;Q>6T zI#`@GkHC-F1XABK&{TKQMIsS4hEuNU5SZ8TIS+f~tVP7RGl`(YT!92N0`Sjf4Qv7) zR=)yUVFY>>FP%o2lpi}R)(R8ErWbXDD@)h!%ZVq^t5->NN2tl%8dzyIO=)#;hOUWW zreQDiz=&r5VkMyJ7PAeBsws(=wt!ueEsG-Wq-z3kH=VyHUz+rw*1XhqNwBD-D3;bHjC(89wS>1(Mit?S z51gv}?y@-FNfhg~06+5Z^0|gK>&IL=b)h1!?d_l974alGVVce=m&IaBAbsCq zxTk_81d{$WXU|9}PlGZd3tGPb-xevl>7vll(DdP&4G5snN~(%~vU5tGw&70zWFs)n z2(3&`^_7mv5wb)mxNZ>8 zS#T7x7Cp$dRw=+XKJeGnkV?8>`$DPHyph&kd@R*m0K#G=%TZQYZ~baEv^DJ^SsiFW zSW3{Jw}ra97Vje%5s))8b5TG=SKIMwJs^X@xbnd&XGqXhdpw03JQI`!e~!=sXT*l1 zOh6?yUfWCsh1)O}S@2HrV9a(iF-xBulgp%{a_o<<5_!iO=3)Ba9MZeDPj!vXeD|?bbC&=sFFu z9`G}xs1wa0#(tBnUxnoK5zy0O&BbR>1B_v)3>jw zm*~Y`I2XQm2B11<^OP2Z>0lm!OF^!Z2^}{|fq{M;;C%>14+G=-FXe_me-t}j=*3qE z!gq#Ok{9lwE0X$l1u&-)pH`2h6%cj{ zu0$q%-$PzeMP!pGd}Fk+liV;2jeR@FtpBqI)vu5&MB{xrnTqK=+^R4|bcI11Tke)& z)q#}x>gfd;=^Q)+VAILPlWH+_CyFCK2lQ%tJrYH&A`^`g%6}(RspU=7%zLfnpzNr# z`98UMU#Ld#4VImWd*V`D6x{~3YxV@fi(Xu@QHE~@vZ_1VaEl_N(L7S!<65V)jj8(N zobpPO+=-gy;%n~oSepKtgWtex2=)c6>f3Y6>-%ucC)F*&Iu`W#DnHSBzSt~VSkPMN zmUB$Av^NCr)1HIM2d;6NDG@8*$>Okd7boHTEW*MUIP7{LCiJ7$!=ejT4#nf7aihi7 zZm+bXjsS`Fj>QFS8&g^#)< ztuUiH-V9KclpW!2IUSHNtH_Ci| z=~NC1^83Ge{|+<` zNBqkyoWWLq_s?|a0Mat?H0h>{$}|SxZsv2~M!CNKJ#u7yZxky~^uibNq#!d7C16cV zfL&mp_hdVI%D-p$zkquO;*p2Aly&ZVmzmZF-n@>#{FE@6Nj%9L4rlH$$^elQ=IqxF z{F5+wOyje!;|8L|c6(J=-~oCH0)0SIZu5gy1hXKo?qCdHtjQ&Nt!`j`I)OTZs6Of~ z{X9&^cT0VVu&i(6DOc)bj*5`FkJKA*h!crw1Ti9U_DKU{J|dk@Oa4H&QK>-S*rhI* z`3^52|039<*I5qGuosk1ZBBvRYiUd))2si$ObBzFY~_YsB{<=q8VFi*LTCUdo@!#K zGG0Xp5R#!2>?7_~?JSbaczGwa)Z{S2dWgcyC-%?BJal{+>$t%vFKz!xK}qFu5Z)I) z5m>c5|CG!?7DCj0t879=!TgR~1Lk}&y#;>z4^nzEc$KgXt z(KCmM2M%^2w3Tf(e%JtVAbo*`g zyNOO{^LyY6I@D+U#IXm~`L+z9dJ~8DV^OUk5SR{lz*YjeUtV4#P7N;l8NVI>wX=AlirNE1hs=V^;3YxcK_Jkt%T7MQ&V(bXhq= z4%w6iiW~=tK!^Jy9_7BZX>$YzzHdX&Y#BvH5HyFil2PD5U;6k0XOwSv?n<6q{@PdQef*1xFKQAY^px z2;Y*z^pin@O)v^&>ZAp#Cx6LFrz?Mn$j5Do9^wWHD|U)X?LiMdY*hxAY83qG26k1| z25!F8l(9*^vzjd)3S+`3CO@D;AgDB`sB5y%{`*F~&zh^7^CpTZ4dY0HRgC766TpoK zPw=nMpPaIINw5wRp!vwR<~F90J?(f-3MsotUfWAB9c^J;eZ7^7C{^{cB-v%Go8VvW z-YWJ`-wEnJGnv0m$XzRzy+iyJ*(hTX`EC(otput^5#YITC1#Y-bdidkWPHP`7HAp3 zb;;q1B?w-5ibB4RO|&ao`yg1CVLjl~tR%c>(MBK`oyn$8y-a75mt#+R<#bBO2$JZTihgok!20cXFm`lj)}A;BH$agk!lIt zjfJfHT$j|K09eCS`AR4`BoQ}1psKs$U5O9K)cH5X-I0&dogfYqvB<#N4qU~oR<(V9 z!@s?vQJ4UD-Mjgai#)_K{^meSRToFt`0IqQzcXidE)J;y=1F2agk@Jfo%vBoz;YPR z14DW?gq|VC{KZPbQ18ijv#)OjhX28ln*56xRw;ggum-=xYuE3-3L^mxQX=2P*BV#pT+u+g>;GH)4 zH4^igRYyOS@|_G>u5=Fw;8?f^%f5>( z4OpB1Ou@dt_jDv3BesLpEO@-JZ44xciduURtQ|ma26N#CV?6KYH}VPEuRe0JM-t#Xgg>vvi+`{Gc?Rp@!#hE`H+N ztBi`}ZeiR$4rz8IAh_=KljB;9S^en$u!%!ZuNGxtJc;9OINZMpZe)^qFHJi~3}r9l z>|nsm9lbT=jTZhm??wbluVR`7W{|Feb03xdJ_dwYy32z1jd?21=2y&DX2skW8ikfO zibW3ruCem@-0W4~;W)|)UrM<~IpROQXxYKMudC@fTRCk79C#(P_xD|H;*GiTGq6PT(b; z1Ju7>pho*6figlnvlsxn#P~)?C71c{u_jvH=_(J0|2VhR zMF9VNAmYKbNn@7k>3)?tDKh{Ber=R=#eYw~YpD=9%6)74P)k+W{OX(`0lHy&nTEVa zYSOsnWjssOGv@>D&K4fWG--{R4Jm4b9O~I*kqWe*!9>oHHU1BO#qc0j=-$Idu zhuyeWN5+W9Uq_zpfO5BB9L-qi&0}rmtZ-zKgK`Wdjfxw;lqR#i zcYwfU!rl$6tBNfXcPM)HxJFZQA7{bf+Qc2`w^Ax5)>$s0Y(LZW!@f(X^3yjDg;Pcn zJ*>4J8A-4CrmI9{;055oDEUV%0DDS_z^<+S@gmYD-$9R4PNDBTBcLhaUlqdgPGsw# zqt9-fWlHi0)-Yf`WWKq?QsTpsr~EK*B2*=7L!=Em>$wDi5=lZRVgjgauM0?2%@jai zGGJ)Tx1Jj9XJDQKfQ|z;EQ^u}X|tWDQMoQnCrc=_aGj)eDPSL0ctBeMd{DHJEb1E6M;?1B22l_r5*YD9&%B z1;M8n@Zoa0?QoCDT2>8tbE3i%1k##!Dd29Pq}G&`8EEAh=Pm>Bb&5Gznl8Y2FT%|) zek*>nuG+an<-5Nj79n7ivmjHRG9jQ>vVk}hiy)*~?jw~MhRm~zQZ!(DoO?lg3_1mfc z&Y8xN5tPT3EkoTC&p*;mXPs|(g z{#fjT5px#aYq^8pfcJXKT`=hCM;M~mR%o>LNG>$yRq7$wn3-!*W=Ze4_7R<3ZF~#; zH*F<0agK$cO<1FJ>q*99lPT+`sBW+m;ZOZ=#iVtelUMu?BSWcWE-p6Dj^|#gaheb4 zWO>;&N7J)hECxIZQ2ijxms8$SS|^H7H=8Erkc{P>J1}A1KuV_QfXoN@&^tuLKG*#!;KeHT8Q{0H z`K3m-R{(68Ny-Zy06{rc^b?5%+ZHd9Q1W3f2U0lE>Ls87QxmM2V50D(`cIg-TKh|@ zpH>(`#);*f85;V#gv#duarH(6J5w6;Hz@*WU31)=jky~^p~$KuXlBXR*Z7>ilM}S9hEAGGY14H;zW$SbmdbdaINV9uwdb3w@5M$ZmB13ospIS{j zOZeU5m^wR5FU>iufA=;$1XgHTP9r#0pSda_XnCrAH)MeUTE|_IYF5wbsjE`Dc&nX$ z%^lMop@`5peqrUTtCZdJ(SoYl0|V)d^#0zQLRLgs*dYvUs5WarrM0Z}8dVj$mX5p4 z+9KMCTYsu&STB+VFZPoT^-xejAF}rBEwS;%KeLZk`$FyUz6fz4$C}zqm(Zc zA_iW&Mzv7wbOR)XK7h-(Cp6ZlHhrs6*{$~SO&cqQ#y*MR#h8667EqtnAFMNZTP66*RBF^4kN=TSjc zI+NI`6B@OUSk| zW4IVrcnfdb5X{%p{de?AGuVKo1gb+3!16>VpmG*brDoz`h12b*AF&GsVX;ir?m5jr z)gg&E7V}onAfk1{Je#NSt!Qm8!Da-J<2Q+D@Utz+lYL$gtLQzGL4?*$$zb%)!_ za&QjwOMy#D=9aYuiL?@xMh*LbBvn*Y-SyW>zeiO~rbAI%h0v@=NkP)iXrWwaDrRFm z8cwjATQ}netb>)>%_UXm3jn@R{1RX)Ol(=mv9YEQ=U}U0lF1kyt1<}zHIbIj*7tQEZ4{er!XcHR$pA ziPRrWx^OOEM4ea@8AiXsUk`W%72lf_3SD%KznP3*VgXeVd-B%Yqk}sTnuwM~#2E{! ziCKn3_EIt|x~IZoTFtM8msEAz$Dgg$)|Tc7?M}D>@OW;N(>OQ;0DMcLYDeCtsln~3 znpytXm$s2Kq`UeAp*54*L#$h?_ zq{aXIf^&?!tI`+LJX|l|N#H^9DJ>JE&qqxTA5ztR*{^EeMT7dc{X3Vn&O2*Jv~0iw z46&gX^S(v8^&Xgjjp@-3kuy0dyrj2n<2bux}^lG-GX^ z*5JDS>DfxI4a7(9j6`}Mwin-4$?=xEQcczc#s`xRyD=TYGLm3%MF{92MpAsjnuqN( zr@+?NFPH65i>WB!Z=d#BU#%ohB&e;%BLZ4ghy_mCdv|kc%yLslBHXy$$+Y;OP+eCp zwvJV7^n5!_Z5d`!x7(yc&~4u8<@vsaiL3h#l9?4f6&*G9RZ8=<_$D(xq?_iI)Z14$ znDRXN0EqUIO4VS8P18BCtkYYW7kNF_zR#DjGN;UaIu(yF<}|uq;)xejle=X<@90Lq za82`yWLEx8Kq7OT%M^VTvpNq_5ao0-E822ge36;X0}wrV5Hci0TA@}DF`JCWgw}7k z9B)nDgJyRXPv_}O3(Sstr{+0CEtmsE+W2idNeSDY89$m;iD1UFdR2*(n*Tn`bIfh{Uz6()=<9%?LF_uPA`0VfQsga=> zFyrb;uwK$$e;^@=hNiKvkXYs~3BFf5D}%oiA67tQ+r@+RWIq_V&8Zj}9>`syLDk%Z5L@sdud=FqlSBXD|0k(9SMs^*mjY?Z7rK5#(F zewsu;0j#q~o6z%8%Fg3na5otxmL}EDtk}f*0!3huvpW%T41{69{R8e#t(%;rWMJoN zgE^#)yI4puS#I9YfV=c?NhTqdK5aF~wOS;Mq4YmXJi?kQ3= zG{G@aK}+#$!;EF!sFX4(8cs}_@Ph{d26fp})>=OdvBgNz@Mg^hgEE*!_{GBv13n)24!i*@)rgkBD7+;Fow9D6$rAPjS^3P-Rx@lZp%@a5UnYTMfY=iC&BlsP2=L2OTJ ztW*s5bxCY`xf7y|2&6g;B_FSEH8=G*LuIfHtJ@TN1%|0>{7^zu7JL~yxU@jjExsKL z=n>=)oMj0?mC{_<*r5{^;q-(E#^856?~Ox@_ik0~ruKac)8&<81e`i<(cKQ6u#>r= zWt0Cb&r9+66V7WWQ3;q=KDP6Yx7o%0+=l8WW3v=IqBnux!m#ozql$>guJ!gUYvAWJ zF_CA%0ZaP@vDx-1NBv@_&H?qh0u3id8qycn9w-*J<8ntG9o5tcwKA9XsjSd?SQXTZ zoOz>2q@wl@=c+jiES8HoldN*by9<%3kC4x;JTgVB9L9HN5gF{KUr3u@GBy^*;r7B6 zgq)Oc8t1wF%dIl@wPb1@qN5E7zAHYa*1bfK5c8x;!zIAN#kNc&~Ck7u-M-o7I~1hivLA);@0+UWtTR4 zEgff*EP1xKFmZn@6e@$y(&ct03G3P4 z<#vgjT)%vlpU!5G1`*GGh&D!wByJHlrx<=}S`$NxPr^i#-CRks?E9M(dg)mlQ_>ue z;elF#kx4%f?Zx~^tip@!)Qmn)gcifUute;87}80YXM6ssq%!h?pkAtz;XgiX^V>u_ zIR|To@N-FxQmq;i5Iz}H!@$1sp%1S|$p!SKGM*3Q2QjOw)FBOdVI>=1B_O~7$K2Ir zB3Xl&=+g&i$0ly}+lh_HSpJ&&D7D4_%&8Tm;o`P%R>2^7qMFk4LE*f4qX+6zinr>n z71bTQn0w^$tc`?J)J`TkYJU*FPQ~YdA%dW;;|U;v=oTEyh{U>piJ5;`n{-V&*+5In zn&TP)O-U%6Qy8{Mw|1mUeY}7qCA@=0^Kf!{;5z><=vV#+m~4$Wj`C#;dpQUKm6+h< zo;q_V7dBYfwtd;m%hZU++~3@Kj|!1XVbUYbyUr*R3E*y{8LBJ#Z z?WgzN*sQxVyIb_8i}6X8wAD=nAPLE6pIh3)?-Z<^1~1jgTDrd&@4005@5ilG_zd~L z+ZvaK@=z=%rAF?0bVqui1o1IJRs$_oe%Fqs@pslB-*4W%P)q7^sjE;Efq0z}x$3TR zO`13UOz(NNRYR6|GR zK9CIh;J;XgK&qbdy|3;hHgk_5vW?Ae_Ywde^@7kG!B8LKTQnr*U(d=}`x_x2MF!&6 zlU;~Yj8P!sU*Gh*iN#|671S4%|4KhLEpPphm04<60pmL8WW1)NMEnH#{8-+DEEpn6U2+Zo64cz!XK8wEQn0O!K2Fad%@ znexQ-!eQk$-17tzac|*@)YB@41}t~X$~WTGW+Kw>8sad#B{5o$7%x^k53O&=47drZ z6k`}b+IjJR?tbf2ySno1!9AB_ns@BE4O~(8QvHOQq-&%f z%Zf9?YwzBQdG8m{$Jz-638l6Nqi;g`hYj;x%3(V*EqaHh@mqp|8Cq2&f9E;3KR|>Y zN<*^6A{#oK5AR3BWjMTQ_JIb=85*9KwA^aGp@I*;!{Ej^to_>ujp1dX!7VF2iQMHj z_sC`V4n|qXF3thJg0!lZ$+r!5gXZ4+L(pPSTCVgw`xSx;t*5Zmfu~61nH@Z6L+4}%I>o4kdtSz_zc$ch=o+j|DgHcdzI5RzF%ajLjf&VWlf zR#Xd{Viow@-{=kvP`nT$!8aGvJU@>}qSzS9R2inX6!*E%DcpP_=YXpB>8XCGcDpX~ zwG(0u@GSz)TDz8tV~-(O4UwyKt1M7MF|pc2(D%y#2pG_$H2z}Zq<+gYAdxb~NXgB# zEru2%5#mHj_zlu#l>Nu;=bl7|UT?I3z_ih|`rX&V+=)HlJDjp*V=+h!jAY$=BO^ww z-3bky%pcD56_vz#1g&NNk9kNc%=&uZloN}gl7E_Wjh_k{b=GTt=yEy(G|(p=W-6Lr zv@7xSYBU=L2%;)}3q0OoVT+i6CX2@<{E`^>GV*e1naBnrk{^=?s149lEC?f zyk6Gvg^icd@UewXpn@Fn?r%~vPGQWnwGsY4?#uXm?~rqqW3#Lo~h%Ymp|1Rn* z6R1MA?Az+x-?Uh7ZK*fCdAhT|vxN|;@n6i{`va2E!H~dnX41>-z55vY5o^zM`Lz8L zYm9X@32XA>Akn1XusC1?Sa>e7;RAetc#au>fv|0?c^UpI_nU0PNTEP~<0Q60HJf#M zHvgkh#nn##`o0S{zUulX9)u<>w`$M6!;>c4dawi50oDm_3d2WScND7Ajcm59O6POg zWdw6b(~xTyy;L#xxU*XxiuOwQ1!RTvRmnqwHNTStEsr8YT#dC1j_E?STMIKybR}rL zSgB`(f36VV*)zGIgEI_(`j0kh%;Ln{2||`K>;F%waI;-f7fp=W+Yl9cIT{=Qb|1V3 zT3CLOKNMhsfLeufbizePzHAcT8YX?i9P133@7QqR6Cuy>*WlqZ#7?c>=D;cZdoR(@?(}Q{+4#;aejcX0S{~qJjQ`<%r*y?! zw3dgzA@It&P5nW#RjPu3vppf2=n15YHGw3|%rEe*7wIX7N+s_)q z^I4m2y92r8wAv6{c09eQT-T>Jl-EImK8^zKx=>^vcR}Cb)C_6k)DT3{X)<#hPztFQ&IxE| z6!0*d+o-W%cmv|?Zfz;XOWlmD8C*~+$W`obE@H(qC8CS!nZ{YMMF3^5x&RLdHdTVG zEWlmKMt`__14|?*R@g{5#zmEo>7?ro@lS?X`mPUb=kk(pQ)u-6oi8b3*OL#uQbpwu zpZbU%uP6tAvi51y1t7{w5}z$UXd_?;#bNe^+zi)W6>0Q7T{c}zSRZ2)c#H4<%kBg3 zBlrXDVi<-=HPQorx}su%va-AS>SM)ZE|&LXiQd@MfRr6h;;7d-~J2!9CGzU2Dn) zu(JFAb!NCy-w+4))jFf3QWgE?wl#V6CN&*ek5HpG(2UB9I0=>E?Rh*gQu?d<6NmOr zwbdn`44NhgCw^?`YaZy;8Wcxwjf~+6ZYv3S+PHnx8|jObHguP`tHelcD6B12Jq(q6 zY;osF8VGzuK~S`f%{+(CtbMef7rNT<`ymjf%Jq;qV7_Y;1?z!#vkcZ}9nXAPh7Tb`ivao}+(=;^Xu)=UU+B}2U z$Um(cjv4$F{V<*1>NMI3LxnTP-NgKFg@x_6%`;(=UDQq+O0$v zgv&^Dpf$v}#7Us#O-ZSN3Y-%Oj+5{J4W1k~Np+L^0=ESfyjlVFZsnZ_|L=W^4hyf9 zQ9n`V=SkmYZJRy5Q)Uj87m8kLz{&60DQ&U^QDaBuU#aH=<T~bsnoX@pfGDgtAW-fBi~;{GhF>bq*Txy3Rt}S6u5cMz%{O7n;xX9bY4e zSZY-KaWlA9=>c5Ko&&#|@^9^K0xA6BD`9YNN)j;}%H&v!co`D`CFNXl`LbM>s8WAr z)5K(5pd!V@Gzl|>>GYr)`Qe+rnkJAm<@Np&?rQ=22CN`mgrI<@O=utFB$1>UCz_z@ zjo1q_kBhm*;00=mHJw5+Ax8$5p1fHcz-t4&iNP=;R9o-yAF3t@sz%3B(M$48!-?0W zg*l0j@kg()qKsJCjD&h!6#Mjl>#37of&HCmV~wE^PePFbHZil;);%R-uMO-U&N0uZ z%_9#c?L4ZtGmkO-**30eilVmBU`c6^qAwRN53o#hXa&iWkrioDI-1605f&L;$qov4 z?=kEY9k71A|9uJoSM#7!97BgtS*L6?dP|^`Ez~YzURHej+U$g!v&(r!Y+gr*!NJ;I z*%rM-*Rwg<{?Lz~2O*!CYuLGR6lxkmENV}W2JKN zwmmF1e<2FK-RD&DCEP@kjE?_6vzZtUZ>%*5_4_#&E^|ZJR$@vIP68I=oS_>i#NG@@ z3(12(w#y{O!EF`_$8bU zj=$J84VQS*t22^|IBwsy`EsMyJHEE`b1c(WY>r_Yy`Bc=h_S=%s^VobV48R3;)OQ; z+;fOI4{I}f=&`1x{PF+raHp#jDKY{c)}2PjoXii zTsoK95~=QQ0=}26>{5v~Rq2V(<Vx%CR3Q0FwXEzn{0LL2%}|nGbHkQ`<8nL28el{1 zlt`x3Zft{AFVvnOLStFL4ZyE4mFQbfxM_wlhkt>W9wVv) zI{{xQH&?-szH#1nq0gcogx!b5w^nD*O2=4)J=xYY67uWF=*<%x>$PE%4Z_ZjAPe~m zUO5_r?fA}d4tkm>3FnsS(M1P@Z7s{d9|yT=e$p0etZ%_`)elmFCcNtQjwk@~tK|$2 z{jd6J0&X!$Yuw_Y#ph-aMS#nG&W+W9c^xWD1Okr4s9Mg2sye8NnbmzDZI2xlSy1ly z{s=0ukWy^Z@01fV-G5hqx#y59m5w2KFU=wq&!YTf- zbBCJ2x9de`Q@Yk*z#`kIHxQc96ttA!ETE^Nk{KT75Hk?ZmmfhZV0!CZG&2X!SlCdA zB|U}Qiywn*+m?!ZeH3M(9I6A%+z*#$a;;8ABwbsH#m>ABK~b3Y1jIVN4H zqk_0nkO+EHJAt0WyRLkYF|qiRh+(ts;{)qM&_edX5F)7AxLN*YXjYUIzaqBps_+>) zV8wF(3L60{ykwJ9PBD#ZQh5Vc&HHP$2ExD&9|c^*HnS0m(+WA}Smm@jE7IY8lu2G2 zNKIikZuYu-mYVpARNU(uKjBSCJrLH6lKu>2|JK6dnVBjnqj-mf8Zj+fDVyaM7yqX4+r}Zp1Tm5?^ zc_6iR&0}{X#*b2Il)W6>EGr+4q4?S(vR>i%5IrZnhte*iq;ST(_d&GO)aslk{&Zxl z^t;fcavAk?!Di9CjjbGKYJ*br`6JmQY8!`qI6Rfup5zcO;2Q3ylqG>(^|Y+91Tri+8Rb0D^&D2 zjcykEHw9a4#>>rvcN!y3u9v#e!g+T=Y`J?K5{nAy($C_c9lvJkdAyLzHzuGrez10~ zpUrvQd#9#*6l8IW4ny^qY9%Q4g|e~|0GUNN>aZN4Ot-kkF!U;n4!3Tg4+bQ2Uq|)F z`0SpM-=a)49>S(2$|;>}Hiy7liJjW%6%^0iU~}X@iI0e|=MWvsrqLM;GUbLQTgFS6 z#Un>gex5R$rl&}h666Dj@F&j=Q|8|upL&b!vMyC>2X%Q671blfFy`w2OzK3c(!+h* zQcwVa7TuCs?X$p~^^)G|?%ViBl?RviB-jg;MeS=i06F@$9FtcH;RzvK(H&;_g^Bhs104?rv?3K-Up*#WrAn76(#d1a9B1G4O)4&#-hdr z@2}(b46=nA{aHe=M57bUu+^un!aP{Uj>s~$GjE}|d24mw(+B1(DjwAlFtT=lxZ`17 z7hQ^MTRHad7aFeJy`q^o5Zum+RXdh%DQ_jE4eP4%X|_zoH0__yG=voz*a_V{X_M~8 z)sk+_jX(B{x=FCt>>W*pLZDYgz7}1f>n~oVw2Vl<)!PdMGK5x{AD_(Hc$jY&{sc>z zwbxs6!)t~`UK}b~)Pu0$qOxJZpDCJ}WVNhT2YGs*@n2SX;!JdWa(+Ko+9DX%ea)YAS z%=*?Qy~;VVcQT zqGrfj@7!~-LNqieGsM1jv!aXFQWQ%(BrxK1?Sm#`kz63b5vseh6N5p#6sPbI(l*d+ zHo&=LKMY+fx3F#a9_5UzMv(9Q9h@M)Gd2=tzhWD;Iy+ z)%|$8P(pq+P5@}5!&=$L$oPAJ;Q)85v>xSYdlfcHz?`Uq09b~z-icp*n&z>xcKsOJ z3;c9y9Fay2VB(ZwETb8Z)%G4F!YkzTe*g)^h-Ymd3=^uT4j$>nA?QDK!5aE)+}iw5 z+42Z1v>VKobYeKt8%-KUM`hy)=b!JPPkXt+MiMSDt ziY!~Al3vu9OZw@e714>EUmpzdeeSMKok=CAJ8cu=Ask88HRG_N9}M{LcGV((eGrl6 zY|{fQ@`6zw7+GlSo1A`(Sq^$=zDDM2m+z+K0z%fW{k(~Vm{JfKYC@33j$_;h{WGtd zsN!sfQF~IPw#oWfB<%;M3$e&t1btB6Nj4+%Mg*1Yz}1xPxl*Ut#ESY>&1*(r=0y6~ z6yf^g&+eJ=1Id>w5pD*0H+l~i^bj9TdsAo9F+-gzLXz1t*kfN#ItyziflLkduBO1IaiuNyeB&woC0E&xuTeNPCb(l?YFc);xt5+J>Oa zUy=JUAP90>LQ`)vSzHwaCpPNQ3rW2ORysTNkC{01XIQez0=Y1I9}4jY4UGm)+Cr-h zY3)@F1YL1I5X7VX!lZY>Pb5vMT5la@wsnMU@8Wm29jgf$Uf5z2LO z?yG!uQ$s2x1<~evmdu$p67S?BFML&&Y#`!$F@0FkFr^rCpbjAZ61u`$q(674}KF+~W$gCI0L23TP#Kzmp#SgY(l~_h7?$eb!Of@Zf@`yVl z>=|Bq%HJbVe$R%CV6Dkq`$}Q!n1$-lHs+u+O`<@t$(E*Ud|F_8eUS1BHyJ|($CrLyS+7g#*EEI48qJB`Oj`tCEDerZXTtA=$vD@+Xc|{rb zZgbm`wgXB5p`e)gp6DT$`(3(*W{^OzUb-$Up-gq$-Z?R_`25#>6R`+bYniciURVWv zo9{l}vfK;TN2+LSY=DJvPKcr(B2VyPK%{9RsB0NamKiKd1vE08@S0_!i1wP;^TS!P zB;Nm|{C^plUTc@BG{r1Xe!7#OnTFA05!4H_lt_yL!Azx1sztP5?}tuHKr06}epp-( zZAP#ns)MV=S1iZxsb8Up+bSdnRU)Ligam3rvCI?ZU|>DEY(~%mw%2}k)?q}S=PwS! zQ7Q8J2eb(SVEi$#u&nQI7;}4_d_~vm@c?IY7q0s%y~(K>sgf<}{41 z5BV81h0f18rXU*-0$~fS7;h=s-OHYQ-Qq|BZya@TK$TB2HY($-4WvAK_2CgwKI@xw zVAE>N;&2^ARq{~c^$DEbN^fc!o@FSC~F^Z5&PCuh8dR;IJ17`YGQZG-7XKty@b?aV#hb>wmF7Wvd-YEB^wN z?vugVz{vx@)p+Uh)WU+yny8(@sPK&VmrzlyWmU0}7SSy%jL)Y%#=%st>)sMqJ-wdT zPS(UkK(jy+JGQ`)`T{jTOJ^Bi9fM&DGZwuV7^VJ`4$02_Y&Op1Is{x<(&pZo0aiau zaEk*I?NsE_F;eGF#umck(;Kq(inxyC(Y>e|IyDXZa&HUuPgjQ@aZ=QPpGyHy-zyq> z=6|4kaS2NNQ{Fgp$bhuUo60Zn7M2i40#K!#oE;&maNS&_#s8zBi>UL28*K@A4OqBn z_189!;j1uH$%+^)Zax?R`O&Xb6Qc}h+EMv6lGS1TF6N}`ed}EvT2pgMh4RsEl~cm; zN68+SLFRHV6tg89PJ5yI5-kCBB1m3g%eA#+(^aV8rkj^c}&5rB%=F0i?BPc zSlj6xXDFS$y}qZ}5@g)L%FJ_bvI&)8xPplu&tr!fS5cazk~#Fp;>)|L9|)H06f5|a zbC(EMBJ=2!H>oDMYc4FP{dJshW%-WahWaW0AMHoPUxRWC9H^$Rgr@0F%x+>B<36@U z+QHAr&U<&Xj*+Cr?h<@!|5|>X1-VPa)1Gi#oH@?;O!O?iNa7=>{t&Uh{#34i>(N+$ zF!E;6Al7itP?|T>i9lRYL%`exltJ!YXCtd)DKW=x@=zD0EunF(u~o~UBM#pWo+;y3 zv{K+Ka5<(Q$vD2*S{POt?`5Qn-NJ06m>Md{1=?p-t*V_t^rk+3b|LKl)tp<~RV__l zXF32|&W&b*EYWo&UV#+_Af2CZ#1{|qFAgPhdE!c!c@(myxCyC;X77ECv3;>9QSY_ok|K-u)zS_={>3F2$sm6F)`zK}? zt~5mbrP!DUdcd;U^Ewn;SQ00Gzf(hqzx3Sctt5f5t}}q(-D+e+Y^#uK`BgxS?rW^U z=H<#Y@aCO8o$dzuhQl*tWf$f8vD^r^EWT5iLi2s{eC?q8gd7$>zzD!Jig(!w>4hz_ zG+B67PrNHk5x5iH5MP6%=~*yPyFv)6%1k3x@t6DBkIl%b#rT^^lmKisfHQr$b{o%% zc7c~r!=w`gR2Ln)>dLz0@QY(tz{dh$2Cki&8Y)~<9uyMbyx2S3weCjk8Wx^`$fYb} zqn26|apq~`3yta`Gt#!3=gMn)#gF-^oVSD)6P#mFE^mF$xi`fQ+c{5JU7$fw@y`Jp zOBdS`B=J`e2Gs$nU&^lt3#zq;zS1n#C%3pRZ&+3S;iivoWZp{FdIHN^fqF zqD#3lP}MIk1RvwN2mzZu(*^Da zLVB(5ax3JedhTg7i@36y4#(hK5$6Xx%gB&el?yi^8Q)!b22SG8C>~c)GOXB+ zQMT)1Pbrwfyh8^%B@%;ozU8aQxqH<24i481j0N)anJJmFUpXF&8+O4{o-ulqo#TIa z!j6q@<#uMA;gLj<@h>x_6b<%pZ+Y?7cox}iNtBAo31-E4E$e0e1ZjB*Kgt<3Jg>4Elwd*TlIM4%|m94`0T}0VXXS zxe7I>O1^;q7VDqG7d)y&l8 z<)6O+4oqI_OeZr%FySkeXWVx5#8!W~S90U{4-)TRspWuQ^aHohuTmpnqiFVWc(n0O zXyP9X6sg7Sh$!$dJVH`&H`F8}L4P-2wJOR4fROIsAJor$QnVHhWU^deo)3Qo1%lPq zq!&|Tc&R!2mchmW3L?`v&=bcVg|v_+&J~DTWd#~;;JFO;TYK^l=mO(D%|1ZceAlWN z@H5qW%clD^5GwNW_a1R?*+0C7>b-U08s6h?Fy(#Gy)K^# zRj?y3H8k$W5z#v5p|}WxoXc$h%<{?|B<2xK5AIgIK72F4Pm^+090L=$6u&C>C<*HP z$Ww%HE97K1Tv$7Xe*}3nNMKFUgAiTr6aa^kg5R>b@!P>Y^M>*3J&vYRMDd$vdv|=j zV@ZQFm{Bwso3DMPjf%eg}xk}F@|>KmJY z6y_`{{W#FGp2HRb+fOF`vA4;)CMYrTjED6g_ZL4SXyuz}f|+7|rbFq9)xV8j4Sp}u zO=E3dDY|3PWg4kdU=hCG|A>8h_(}n|OAFc&(>5{Xpsy5$m2Ay+`Uk<7BDDX5ZHY#? zsURI@#^cC4yWI*v=#S5I=#1Z*AUoLm6&CwsccCCCv!f3NuN!(2h<7|j+rLi(v=2yc zRvH=hhOWy%wA%Df*W&>O7eBn4rKE(5SG8s?jPcO|^GHM=bxXaEO2QZ^qi$mD=OjGu zOj<8qpm*+tFUU@K1c(oF#aLle8Fn#6_X>i|+5Dsc70PVbizQ6lkR*+jvDfFHs7Usw z(Qe$J$UtXgr&Cn9i9)cfV!C|wmdRv8lr?`gng_nK9J`8`Y2Vu=HRFc8R%}APOpC=| zs3S%kbY;=+?e@bfyEN1F zEOFT_h64nHQtEpzka8-r2h7u5SQVB!*ggVm1wP~VNt~oDICy+wWD}hj3+$mi#1Viu zcD1%)yTZVnb)+kQKo`oA-c4G0vF2<7)vPEBv>8}wWX3n@LKIgs+dz1ev{BKuVf`v+tdS5e;uzzp%|o zj+BABsu`V@mnvgYk{3*bf>9`kUhH!{j(_nwPhlGbM1pve0S}eyvG3Apx26!vtx08@ z+^L{~!nzt8ZZn}g0VWKL`JOCE8-7Hq6lb)f;6|fyd?!k<aIS9i<4q?k8n95DpS2kagR!{;0F(rUwzQy$&NN7LIt7Q$y?p7`EJq}_K9MN@l9Ys_uNM@yu9)PiVFqy zmrgipdU?SWzfgxWQ7ts{p_Jn6tijNUgtP}<|l{NF<@OQr`(rNcI$`bKMv7OwDL{828Q4>z9NpV|(OJu=?Aox+S~ zZ{Mc_;am#|f4UG2gdo1x-x$KoRv}>&=eJI0&*WH0&b=!sC~32rux)P9UxJsob!_0h z+!?4e*SWtXJlS^5Znk)sJJXn4<$M|#O3hCX5MYWbcn+7I>UFlV zv^BO?>@~V}Os6MPW4MIb%MwIDifWzi)5$4pPQwB$W2b4fq+h16=ExFNHLz1|mDRZR zAPABv_6gXgN*CRyEMAG20HN$`RJq3Wz<=aM03@vEijXEq_%?m==__fn0Cn@fcCYpM zZ`Kmy@{-pO+?p_NOdilIZIbh)fKP)vmBYHO04v8bYf{~jUq@b1Q7dr9zr1YCt6{qD zHl|^-m}KhABO=l>P$y8a+Zi7K@aV&1(uebhvc0TEs3IyCl+MC?6Nc2bc=%LK(UKyu z$=v#21lsphOGz%$^egk|*!)q&1q~Ii^4885|LR2d(>Fh&oj@3HR|T5PT+`EiA5`C5 zP(~+G7P^>ke9TW%*OABO zuQ{kZ4U}u|cvkP>2<(J5Sbl>i*56<1$~VN4oF5bvC$-@VwWh0YE#SZ0+Zrj7G^?6d zXRd_JhN^j|EA$4mTLyzK6FRBk)C8TB8WV))WjKWs-(`_r-N9sM>Ta<1%ws42$wc_# zOAVeqhC2gViqGE~#mA?=RlB^D;PJ>cQb$c{otVnzWWKKPFTFC3uT{dsSg$dT>K9F6 z_Fztn+?X|q=>68-ha8A2HpVZp>>8HUk{KDzklq4QJL+Y*k>llXG86u-=%rYenzVJ- z5Lp?>mHB6``!RU$pO?o{@YV2@So)t(D8I87JShbUN^ww#2-gW3Obm&aEEz7csoeq7 zAL}YLP%>1k&5`?7K%I^jj$Ci+f8@0`fo`F8c^FZmYh4bSjUHg#tG;wyaLQn^37EHy zDkD0m2UzulU8sPI#8x@e6?TO-cqahN{D%Mz*ea$Pu-M_THt(2MYU2=%wzPAc1(0m; zBU8ySxnin8g8zUxofzHS%N1R>((Om#_2c_!+CLLom=ci*R*0F;gJ3tPRKN{tj&q)3 zD*CB3@T^47N7l!2dK)89%?Au63?~rh)|mC&J8`>Zav2E*aB}kHc`AM-t45y`m!a(T z%0KOm9oe1O-_hb?n4xHge_-C`9A{Fc>e-hrBu#!N;UbMqt6&oFN-_QovoK~MB3H`^ z_u>V}2ec-C6iXj~d$V+Rl*R+?3P}eHS~#JGm!Gk$fxx#EK&GlOrX{Geb#%sT^RG?9 z2@%o8Br?*%SR7nM(_69;RdZtW&3Vvd*3E4U4ASg~q$z?@*6`F)Ph`;gbimE|BR#K;B`ZIFI#KZSJc&@Sz1<#P=!)6hMs z^+>KGdFB@5w0b4*Bne7x5XZ8Ip$ulOew1a$$jTS`pjSBUvXW(wMs~Wm9*9YUQZKeL z$CJ$qPiXtK{X7!xY_5Lw44(H=!bKr%3%vg3XZM;wsulgh$Z+c<3K~Wn{1x#xegXJ7 zF=9@@L(iC*u$oN(V4I#;Ei@}nT?a1`KB?uj+zCk|fovw2N;B-uOG2WY#W*38uhS&g zgpygu+IY+I*-fKM)@>jp5oo}@4UJww;7#x*JqPjn8?SxE2!R9upMO{b;}1dgyBHwV z!QrgTCR*@xC&hHh$h`H!Y;8$Z9J2CaERKQ7?+X*ixH=Duy@-<}+~&TQtS`#`EEO3G zj_B9;Vl`d_FQf0$$WZc;$o5$5A|rzG1Tvjda~Z|(WAQG-6e%axk-nCMl*aM?Msw0X zB9jm4k$U)+L+oc=+!Mh^ft9k7+5wmN=O_k-?tA(2haX}iv_BV&%wpX=&ql?8ffUkSD~5$e1dxr|zL!N_a8)?|>|qy5dKkk`?O(F5|% z4QDKA3KVPQ0om-b(AZ6!vRFlmali%QNLO_AVU6%LQdAJS^;wG3st@!9fbf5$Y)|u@ zhn00<8bq^bZ9H+9C5`B>k8UBbMVz51KdZE^M97o5k6;ofWJU1#D-sCuCmj-s8#H-m zC5gP0Jp)t)E-`Dan_2AU!S}=>K&f+#aN7fwU5RX%6oOLqw+Y?$ar3`lK}KvK2J#qq z>g}|~&*r^3J@XApJSAUG#{lJK3b&1m;fKx2yyRV1v&G66G;z(8jE=>$vSG_vLED`2 zyD3I#87-HD0|FE#k@_5wb7?o+w6U@_QByf2jIJ9F#N2qzqlw#`Z7t0~1n19xX9mN4 zh8@}w;LLp%!O7g!0QIj74+p)!82G?Q3@1}1Wl0utp9kOV2jQUnaQ~87ZT=3pega;< zV`KeOj-?E0I^BlF(4!IR5!Y^*3LZ_Skbh`9K?ferai9AL-=^lQ(GZSX3}d zzKnX#L$V{<#=mbA;DU`|Up@W<8pfIWdoVV;{9nX7pg=rBO6!jU>F^Che|YgfrsW?X zf4$ShXK_Y~dXvIEFdL-pHH3S|vDK=e$XHNmmKmu@3+j>ctj>n0T~u_L{nnakdw*>1 zq|&Z5^ts8rPzXPJl!P~zwQ$-6r6B+ncDsbl!-S)w?YJAmY*V9RGE^t5)&K7+Uqf>y zH!@fJZ0aMMJVQc${(_lk(bUEM!9ZNKNvq&^ew%u&H&^2w61LZi@xycQ2tf2>MBvBK zTp#A`!Q+jr_*(kW&T*tFW1ct_?hd9KvL3CIAK=3b#3&VPme{erW|g~0l$dj?G8+Pa zvz3%Pqp4_Lk*tu+3wMu=BiiYjjw$y;wZB1 zj94EJYb{{khNPW9;$mS+7C_>K6(-l|QV>h#%;^AVAcnyxT?}FZq3EobgOjtu zbd-!aLFL3Q`XI9Qx307@N<{D#9%frG5c<4#S~#oPjIZath0Ad1 z(RF>{tZxAYTB$O16&aJC6LtE%sQ$xm2ods@Z3g;Uq!@7jEwU?CCc*#m-1SCX`4;gZ zwKOL^8W7$)gt1X`43+$C^RTv>f|SOJjcKNsErVm|Jjtyb_!NAGMm|pZii*FNz0_6n zxOvck1$3lE1n`pV-);4$JSggDQKU>RZh*jhnfsa|sJ=cu!U;75aj9$;FlIh&Smj0FA# zmW|W)Q)yaS!k(n$W*dNrC2GEu-OCf!M4Py+$Om6ON6o?DoAoFGA^{U7SVM*G_4dT> z$T0p-jKCPp(xqn9*Zy^&AR`mGcWioK5Ch807)wq_S;TaaOuk_7KsESZa9SGDiX&+v~;miS=H{L!qYf68v52 zVL5Y$n&$DALiUF&Lc52^jBmFN;QTV9`w_h1EXyuAO|yaG+Z|jj`t10!}I9y`Xs9FkXv{{;|o3O0v+Sc-7Ce`W`MAI+*LMN|Q#5FWgZ# zf0mQ2d&1N$YGq)KHhIn1$P5S2-WwZRBLI?Ygf6of4RR+>Dk9 z4wnf)bs1~TB&mPFV%WT4CHwM%GNL+n9D>=lPqb6z49$|LC>yvBr{2Kz*6>RuJ_NGz zSVu1IayDMYZh<#-W&tHLzF;4&6G-zpuX^I#f6%us1e#G&H5E?rOx_NB?YDA4#TIBb zSZZXuF5pd_ItqfqInnO7YNPdSR)B_#a{l^EC~Fem6pJt=lciUdl85!yecI1$ zD!^4;v~Ho{lOp=5j}&5GAA^)n7%Y4oE>NBWC)_WUhC{5S2~I(qDghV zQS2cH4sE=zhVOA&GV)u0sb6`Y(-ccf7A*Drgin6BdPLrY{j%FJ;LC*9QP-;)9(}E)uB6RCDp=DsK3=px85rX=nI*+Tw5I zw7#8uKJtBv#HGG?tk2>R-&B9RT~N(p_DKzIw^Uw7;8M@FzNPRh(}gFx^bltCRPrxG=yp!GpirCXL+}K-#*?DdZ7M(v zJe=z;S3;nhw}7vS*#m5@_^QEthCq%!R{pUb31@HfQhTM@!#vktXwOpnsVAxCMtEC} zc8j#3n!OXShPwn0?J7Ftu!3QF9bA6KJFUs9g^Bfk?tzHQe6hMJ7Hc z)crN-v^E+8{uQSPD*ExqyALmk*S}4Wr?t-} z2ugVy(i5F4v$5UxB<_}Hx$?Z0vLMu|v3!-XoBV4t;{bf$*31O^frN<> z`^xlV!nO<0Wz}NJb2p;Ex)Idr+K9?D&`Y+}7+>}Quj3zP>EQyyL#FSu`vtb647vXD z#D#|_(9D(s`NE(b)$O_kJx3@Ae0UX>@O3n8;s(gFbhm%4-O4ktOEtu?0j6&lwe6V4;2-dFTB%v zKK-#cP;yp@@qaAe&R7{SQ;vQhTc75%C8iY8(>&T?i_!`V zSxG9g*oRoa7Be%A>f!KGIAB zxz+2VWvV=P+eVGeUHY2i3Iohbl@HAYry%n}alSPKtrPC^MlCRR4S$N*l106q*P3t& z>~+V$)n66bQ;Ga2mRfj~Pa5qd{3?)jZf$NAz$p$(-{(z#$L>d~@uA#hB1u?1Cymw z-(!2@a^^9u6x_)$G<*uy`ao{k@!uz6o%YKx_2gl3IZ zT=fL?Oa@QtqlDA4sGZ?@>1X`hWve|9<*}&cUls+D0AIjMl}HQ(EL7bkS7QZ6e9Ob| zQ;<2Sxc;3kG7>D5ZY<(z^>{X!?MpZbLWcEwrWb9(RN$4|$p6CEXWpF}<0?Q4-{nP? zK@(M1SF|CR#FvgO3)bP}{xClT68sggRO^*d zg2y5lF!&;1cv`wBgzB!}Z@&a)XGQ?Hqo71Bq-!-(YaNoGvFh!J&uK&M{|&UoXQDPD zm;jFlf>7RQ_R#(nya5~CZh3s7_mOs<|F9%~#AQ6@PWrd5anX~p87dLB_nN+^K*ief z+4IBufw*FYL_PQfHnqcwNz>8)~z_@gk8no(G4|<}n2H`~ET2np<{yY)(*FI`+qcvqqlI*-nt_ zE@Y&3bgeb?JzGm2WGC^g%#8x8`pz-9&i%lQs{zkuCgcqfh+*^oV^N5(3g>a-c8u() z*j`Xluka0U((=ssPd=A^=M1Uhk8+TY4R<5*y%7@`3Mn!v_p?UX|B=feA%gNSrV*py zsOyd-PafeH3yF4G{e%aV<1QpzBt_nswGJCTA9v2CBfz(;0YWMp<9vp1;3bra0VNiC zUNS0}iO#-?b4}_gzt*OaaZ`VeTX|eT(Sn3ZkvAFu0WUVAxZdt(;BncFkSfE;^Sa*T z1FQM^VSXM5D2~C34pIU4w@axJ6 z$qqPgtvw2L8=94}-z-2U4A`oCOHkmZM-;miagdzzi%Y)MB`)Xl%>RGO2@yRgw|;jb zV;~~bY&8C@`KBvGYSy_y7>wzl*O`C}Adys@=7Z);r)I&DLG2-Ey(Mc>*WfpK);YP< z`t{Yihy|MOh6xHU&n#&YyU_Q2X#)9zI+}yrswiKxvc_L z`9Grusf}U!Lau(!p4RYyXYggXpdl43Kb1|%ALm*7VxxcGQakq{emsUucivnp- z^v6e8XuSVZ64X$F)v9(=VOO#-cP-?^>L00tBSiw~RMWA9ubhP+ge=)ef6+f}Tp&L) zrG~3{Xb)V9EEyPw8vX|de+RL~R6(vFjQc_BhL{aQE2 z$n3P$gMH%atLK1=tSEIwDEt&N0HKX`zdF)_iN(Iqg4X)P4Vx)eZ1!wVNF>6t{Un7Y=1G%t^qy;bG{aZ%98Kk#p>d0`v(&9tEf2s7qR*oKegND3svyjKy+JbOO- zq)0JNmx0@a_Mu0kB{}<$Mq?j~7pEd)Zbz4w z7$Ebck5wmud2J_2m7JCzCkK6q?DOWKetgS;2Da~Sa0Yt-47Gf&EKm2Q#*=%oOTMe3&@#v2&3`f|S*`gM zDVh1ZeQ;a3&*rfxgKp5I2+1IFGN2CMl0?ioHC1ocLgyvCFNe? z{#Ya9S(T%n-vo-v!@cW9J&qR$jLECgC|yPS!7@}^7KyQx)z23Ol(mauCr6|*#~I}KsO{jHV%f_8c$ zTJkMu9{}pyh^rNdzS9k;c*uv{^Jlo{6#kT`-iE5IJN)S$MhQ+M%K=7yGhw1z&=P_m zg3MZV>$d{&Cf@R7R=l*Kd&H)J&Y9c-tTo1U9jKV_YotnWedfXc|AC&(G=}fw4j*r|>;G_o zV0OG!{Iro+v^$m*lS`Hq2!q<-7VUyl)xxOynBjCc^IXR%J`clucQ zelAD*O=2ix4DEN~^%=o8J9pUU&vUAis1jBS%-KBPNolN8hIz^5Z7@6#PC-F5UeZx3 z{*wHFCMYR>nj70MK?L!%+E3|9H{O%~eu=udy~t1!fv8mpt9;FyoNF#_CrMEskab^@ zo{O!@^c8JP%E@K3g_r! zqhYi+;!Ig)0vW;7*WXeJ>iC!EnMn=PlJGa>-9OI#QVvcy1ij=3iX?Pz2HRH{=8`Lv z?71ek%S;QkymuuEbH%-!`@g>GANJRgD07?2^c!Laon&;u2SZ2+d3P{-0X>DpjEM4$ zsa`spd2C6!l{+vh2RXu{JYl5jwr(CZ*bLxQ-3PiHpky;3DKyHhcu4DjAcf$pu&;j{sd8yc)@%KKSEpW@bUv3P>?T zz>SuRu6BXVSo@~2bK@YEWwrJrTR0a*1CVHu{XR<7c$P?kJ1DFUI}g`%!y0$yHum@~ zmCdgES=El=B_5xG=hM!k#AHgxZ%po;q4~w9JM7(Y#orIBJ8Tbpmc ztFU}Ea)NN>AnoEvt;mcJ(rRQG5?kVv#`E5__X6l$!7lFKoB4Uf=Fe8?6lVh59;e@S zWA=pvgK`n&Xcl6vA3*1y+>AO7KR?o7EejkrjSlo_RkZz#=bQMZ$hxzBf^{%{#I#!z zFjG@!*sh}h5QiU^4Ko>G`ErY!q41EaoML1F_4wBrKe$z?~gkEi#m)n3_^;MJRScn_+_85eQ37I^vsGV>wJ4Y7@3)YA0?P-gsB|++ z!HVuEFnY);=Zmz6lYf7$e7rq=n;=_OCMS2Kd~u|iS1U?0g=YKXth`dcZxz7f->>#Q zw;E}jk_l>iN(jrsu3@T!ZQji#j7#({0gJb;)=W8h65>$=kC0w%szh$vzAMR87-5xs zjTSwKi4dI@3(sF@jCkpLme0*g`(qsF^)XxP@9`$79nn)o%T{W-DI$va8A_i9$PWIi z)Pk%zEG=QEc8-xL=v@B9riC-d7U^sDZ#C5-1_FRfywqA(rbMnH!L3SDHA_Mw^>E8j zdmP4NQnzk#hV=~^0l!;nXzUqSfaAS*>QUFrAp1MaZh(AsJFKAMqionr3Pn$HEPp9RY%w+8F=jukiy(X&0o1XT{m!I68gffA;ySlj zzIBtk)!DX>|5VChXL2 z_rXT^Mr(78hL1pL{o5r{>*709@aDLQ@n;jceeL_;w{v6WgvGoMgB!FH_ zF*%yA?x#vSmrZ1HeRw>&oBSWxGJwa@0Tu|r`03Xs?E59JjQ>vM?#yMmiE!B?{T{*b3J?3|r`CL^m(3XsAN!?Y z|7~!nY;70+-5O6TSve~|GuGN-6#t9EJ?T6)lqgD*K93^W??q=BPdr3YMfvhF4*UTN zoFry9Xsd)NNMg2hV=R40m^ML_wb^7^1x@XF7xP8`q(M4RunS1y;VmOE^2njunh1pd z{#wUlE|>oeCI~rN!i5{IP{g1w0D$cKpJA`QM(FS^Mr$*N{df6hm@ZFd{#JRVI=BVE zN_pt^(!Ut|?N>N6?}~Y^%@lUQkY2d2hQli5IGcPQefk?W>U?LuK3swC5)JPvi= zAd|+P3NU3le^|tkU)q48a>zgI>cYP!fk`*BLYSg00U3jfXWj;Aw@)Z&$r3HbQFs~U zaiVf5V(z_lv)wllOQ6LaQSX!^;@kTK)k&*Qd)|0W#e;J`{71cm3l?q)|cU zx0kI#!jVYmQZ)PzROA{2M{OGlfp3#?2b3|NimN2v$MDmNu}qdhFX=XHb`kg*vg~c8 zDbyC$G|UH83_9Y;*9v5$eh0$_2K&LG+vss}UPT~3i;)d5GaLGC(i^qzF<(PO{po0Nq4&uU~Z5*#i4mn z?>Gq52Jl}LWH?aqEn%|B0484ZOP4g(!mP)Yo&Obhnh|({s2$DqXB=XS8zephF?u%q zvXjbO+p5HrA5BNOJs9&nQ2`{FwvT94^adDG{VCnusTGi2jfw_&*@nmO_K<&HG4~y%eP3sXlj{v*8$i6!4 zUAbarp+5%1i7)5Gmi355AkFs{(*nQw3)52>7Dp#br-!HbplAfuR7$ePMD3Ph;=_w{iHrqUQ@#l<&e{OXLC@%~zBMI+V4L8FwopzuvJN#%nT|%|UA7>ApdMYqR#|&p#RfG( z)9b7svvK8Q<}LO?3>=3%3#28}J^Wnl0IMq#xy3fTaX<`hDTd6s=3Sj#FixRUcK#UC zWHZtu3(Ou?AnhIQEG2LB+Ay%PS-xp-3%1n(ZjnRBd4n9c2*g_!OitF_o zt4n=~bhoD8=lmy0=x&n_Gl?fqG;o4#+!s( zafzx4^RgJw@Y2j|o3aPD8BBVCqq>WZ+~~Q9Jt?i$941UcO;0b}8(VQty0~|?e6447 zgKB22!$%-+Z8sC(Wx$QPId_D`du{tf^95H8Jrm32`RCtcSqfpSe8N$>RK~d-&6gCX0Csol};8B2Pu#*N2Agc@GfTHl7 z%F`I;l`~;p5>I_d89UdeB?vO!^a2EKENuhcK8^ou8HI@Iu@YKs zsNHXqR*8c?V}d`4!%ZkSh~i!?<2lOpOL#Rsec>%*icYT-3WbXy$ge$mU}h`Pg!lDQ zzdlc(iU6evZku?bsfkj1;a=@lNn<8G0e_gpxIU7@MAVL>CN*fGriSuC@kBcZ!D(~u zX1+EUWJW~|l>yG*wR(<;p(T9d*2A#Pmf~sjz)8kJ??>{ybv+tNYg15w$8jYh>kY_hXri%L9We@oS%}3zE zw{{V3NPJHhO@x*CO=o>Wq}}O(o|Hki09~mXEqY0Y5VC0?~Lhx z^}EuY=e9HZ`XA247h9WNY2Glsu$+8I`0(t~-^^aL?+3d_P^1QhMsPZK#l>G5PsESa z(Kx+v8}Epl2G`-4S#SKNs`HL+NPB0OyI;NAgQ?txi&mz>85H0#Vu&s+@E$((_iERz=&yTBkd9EsEj7n4m<{g5Ig1rPHSLCfZrF2~;)!B9rC>TgLp1q=lzmlF zV~D2~pZdc`b4k{lM_`bCzbmw$v5b_Nuo;(2PajWw}%8N85u*lGN=G1$Y{m!mgo&FsA^)0Udl~iWdK59I6 zF=^QBiOh##^sb)~mbYPml>QMuZWfJD9~$=nlLYPDrSL3#%h%I=@1qvZGF_)}bIG2=M0O4agvT0`g<56O< z2{Z>6ykhKCt;nAjDftwV!{W7_4t@}K3P05&mfCG=i_N z&s~r+@KX+1fi%0}Si|AWGJU6@hlAz)fW#(f0x6a?9awQ;IZQNfYwnDU@#ag((&p;q7zamHmND{OSRc&60zRr#@>>n=<&Vd z04oV8eHvc8uV-~}Hb-lcG+-~O4?53{xLe#!x=?u~iG)0zP-4b-{ldo5*D%O77&$bMu3G-4PYgI&u9^3_-k1}_Q4`#kO)Ru(NRSBa1yGyiLD~2l3jzn% zN;jUR0*&0B7FdkYd&Pun$P|Aa?;fn;I-fS>7q|tVm$#@=4R!^tSmaIo0fPnQY!e*L z`}a=eJ#W$EFKqYk3b^;A1KvkBZ8LzCL%|Zq6K$5A5H0WjTMJdNZXJg6;oW)&W=;6g zT)RzOQ|DGzpd*pny>FG4oxjPSnF3i1mGe4KEf|iPrkq6RuxO|uok3Y?vN#T=>^L=y z+?U}Pf6NhU|ME`;FdE=4>!*$EuE1`YOUpD;q z&tGm@)}C-|_!D!{6Lb{u4-D%3d_x|KW$u!Uta^I9i|px3z(Rp!2ml}5DB39MQimG; zEJjuP5o$63p9p@Cb)8&}N$0>66Kml-ki}z+E>9e#EwYOBZnI0*;H$;dNPl`2xMgE( zz<1++vspB@GhSy`?N=2Iqa2X)cILF@g z?bjc9T{Z!b5>}zl8C#RHvE5$4OGjc6D9ajAANmcFJy7m?GRsAV@`v1hikHsoCG?Xt zBc2UlZGo=R*{}!bZ8g!0hOwyXh>2WWq_sqwTXYg7D|jG9wS|pd%SrR*-ED*z#QRg2mTj-Iq5ThK)(W0C2aG+NUb`nLZ|TyHt!26-gv1M? zcz0Qy3`?|$5WF#&B5*tZEFCcV2Drz5VlK8J5{lv#^Q$@Akf(NR=yEb|*zEwK{&Hpp zSu0I-+YvW&1u<+9yyB2e2xp*e=eEo-|aTYPw?KX?+|MPQd*+KIl9yJjaxNIcevdr zQZE-EP8Zf_J6V7V1@7}AHJjcDEKT+~6ek&yrbPz=8w1Uc&)tQ7ad2UJsr%S)6nyOr7T!7(cN7bUfh6U}D6l}~9e$jx==iL&9F{aE``=B!# z3#=xUsLjY>@|FpWBzI=dau-k{LU}4ZVhTf+`lXgA@y(yp;va18NOYN`J)(jR&9Cgi z!<@P3jiSxn@5a|fI)?6uSnoXz{tpjM!}~;sSx)oFkrp=BB->$n(4bh$eR%Qis0>DSlp;@4h1tPMY;f;%0>0yMwLfGQnd5> zd)olKCD@K%Izf9%68~#D&FkDw(Y>l|nc3qlHQe`u(5}`W_-H$iJ7gkxtOa<8vhb!N zyMS#8xxAabZKSM^Ao^_EnWJp5zaZ(6PXc86DER-QJ?d~S_5C#nBaZ<+Xm<)|ECi$& z5LilOm9muCSUxqSr>)lXWMs$CT@TM}+7LZIEBttHo$CJAF?Q&A^af}KWX{U<^d4VU z_80N}ruM7o9`s?J>)B0twY~hbQhl3)_3rI_Qqe@GH@RCaSEt7=dN1R`5uKdBj|lU~ zta(PtF4o#l!3f^i-|9UIFGye^az?`X1}I(>nM5T{BusoAV8cbA!^#mq6_)3+bcq0? z;I4BB;+cn{1lCxs&b#S&%{#$6_4sY|nWs2_!S*Pz0Pl>D!qibrayR=~9J@_4t(3OW zr1mb53MBa~48P_Pv$cA8vP!XWFs8{_(6yXbj(2QJGFkf`lJam&A@o{Biq>$jHX*!2 zv_g?)M4`WiLA_RItj`7t!v6>+LqC9k-A9mC+QFLrl8N7f@ok3UZ()|#DfIRHg>r0< zo`$}sK;{|nAvfuaW#qBLgon?&xB7fA&xC>Yn;8aDM`m5;_+y zOJ6*pta>$JN-YI``OQ$2Y{!VoKB#LL2WV5u~#PDq(` zw3rU$qeSc1ZVp7YaPs%xPZvvx&}R;DdS9C9-4AImeuc_s2#`8_h$r#KZi7zb8D$Qa z-mF|IGh$Mwj0F=5w^%_Lx>b3 z$HdsQzzK|#J)M^qnGKq_UN*%;n3&r?`rk*piYZdsz2O&R1VEDU@*C7GEGSU)k zb`0Y%YnTSe=bbhi+Q6XbPlr9fXoXgdaj1OuSX@tV@#ixN)lRVWk-JjXZ=34DbI2WD zzQ|?3H|}aK%-jMObR=E5`y_&>HiBpJ0UUpGfwcLMuMhIXrnweibmzYPdmDE=-*mwe zRS#h(h=S>HF?O!f8-=H*hq1D6o;|nl$>}Ly;lq7%3e`vWA>#hf0U#M^(;?SCNS(x> z+0UIliJ=Mh`M+_&;2E-;iwx)5GqYe54B#^~^N=Bx2xi zv`ONFBj{+nW2U=+kUpa(NeRP8DKn~u3gkNi6v@u6fNIT$Wb_{_dhyZB z?$a8Ot+MyPC7I zqfr0UMYPpVxNPCR{9>MD8}YV_xo`nTH1B^*{~B#3bPj7n(b%7FbDunW-wIe%_~cmX zQq)_w2}`j=g#`adq*QE7bcNg5vxd$6M+{7BSAZ#b(ZSxU+b&TLYB9MgVP!>zR4(qI z1Qon_!GU}YY&A??vRSj5{}q&=t*n@KMv!eGjQo>Z+WH>>%Dr#FH`%6rd)Ay#085s` zvtRB_O&GfxRKcl*8HU9OSZC%ER)l$8fF_zf7L9zrwAi8o6tPDW1+R}VjrS5ta)^>EAfZ53I}-jAEJ$U0!LX^57cw zS4mu-JAT%}t0QmY-{w0z8_?!&hGSbYey)_Gv)l*C{ww897Q?vxYsZ(&9YB;=_wnKn zbx!*9B+`y2o8b@&iX>%uDar6q6N2G5J{7D&<;xIGUB81WM~Woaet0_&Xy7QTZ=7us zG~N&!?fxt-_E*|G?qm!g3Ak-gY8-B%*fa~*ujI+Eo=6)Sa6wEfm2<&~<6pwGp{X=p zOyvs4k-UXS6HPBJQn=VjS|IV>K*?6G`?f7O2%x%Ya+@-DBev2YV;zhNMFO#C)KldG zSt|$4jum>VCt9X@;NF=#7uh(sG%&vDmL@bSXg2?Xo~tN0o?M6hIZ|H?x|1ZGXn=(| zg>uPnj|Avnjr|kBZ(Q8l?KsRrlfkH%ky(eBFs!6ftGN_O@ZRyXBsV;BX(A+|Zl82w zW646P3YRWSJ{T^Yw3|3PAm0C+qPDSgxfeac#Yq-MIDJj%YefudG@|t50T&U?FNC3( zq6e2svCFCofyO`;Yf}zgf#CxseB#SDglEE+=+2{WKibFiT9#(k()Qk8!6ilSC$`S!uhNy}U1chu&S zl3GS@E}Nw$V8(HWSqv_Lz1BfnU=vJEV*mHj0bUOb>ntYttUu0c#{GQbeIUU!buWBt zISl>-DN*%&)I%!zG0Iivh>Px{SbIS$tuBW&Vk!zls}36vZbpzz2K&JqDpmBnIlIl# z!I(SycDM+&^ug7=P9f}&)*)9`m-2iBbQ-wHAL=c*xo_6Q!5#Fca~P85fqy=T&i0C6 zrHOX!G$NG?fsvZ4;4f0QYs5yJfT?7l(AV6Q`URu1eX5T>Bvk4TTI#9oT&5^4yga@fWB)w?d z0hi$!b>~D%W(*qctp^U4Lnrr!Xue2V;SoKV1%q6M*TUx5_|~AwTYE{^?hK}wz+ebP z{TF3!#aZ!uK2bU1N*tulr?{DEo8D^Q0Hh~@LcxN7f!(wTAZ6I9q-^A$ur1DZ5u~{> z+N6Lj5pJ0SBAZ}no zTXnS`YHUqh%^dwPgB+%NGRh(Kr(M=ioP1~b*^G9vt9o} zud)uBoHpP_BN;AdM9PtI;Cs{&5cZBPish^v^yT?nbK7tDp!SihTO>Iie|@^^J$S4_ zo2d%7&N*Xp_^gmfas0n}1=U&>!yZzo(2&e^zsI`a zKHNDaPd5AXXygWv5iEy*fQcPnj&ZxHWc1g4Q%sh*$g1gN#Rg~f*~ekOMaqbQN`O51 zXQ#JXX9kE0L4X1R9AVdAv;7hd?{oYLiLNqu&}$vod#|<$L;?v>dno-uEKWL2by?0H zaTLUMB&LXPkllb=?QTsvff6BaQSXNX3EWoujbPhPE;*WVA7XA9DR*Uiz-_jrqPaSj zM2ZJhGj4SrrDKqd?xixeOOCpwlQoeI_CiZ&5p~q7)UlZqki`7x zc^DiMOu{Dgvl1kkN-3d!ZMK0glGwVc{G39l%0%@V$mh)Sybja%RDq|9eWDF~3OAh; zqa?V$g>5R`(>gvoaB6nd#ELM7^$d`$&7(C;mQ6=8fw?{|v#8ug+1jSzQNExKhU?Hu zZ*?#NyyLh~9v}AidGzDRSXjjT4494AqFE_Y^s8VDX;ZVqgeQd{`M3%e;Wdngzgp?; zyC(BH3;qos*#u{G<-BXbdNd8$vmvcr!{0j}v%G&PFr8a`sVQOrmCDmenr2j zcrg36GN2lK5}NP>E>cSd&0g5G59IkRt&*Zwk9a6|>gr;Npbu%YC@}ogv#C5e8mR$y zooZHf_)x63*;FmOnWMG{?A(EoySZbOh6|>@&szZat&|l`2|%}3`)6!`<{s~WKxr5 zDPZ=*Dd=JHhj{ArXH>t+$52Lj@*Jcd!8TADT7O{)1l5G=u-616bZ}?8W&Xj2Z zC;AiU&dEPj^q4?|Suyhm;yQv2AT?o%tTXq!NRNfvXT(FCnK(uu3#X+hp)>iWQ1@Y3Uv0 zRbshXDKga~soF6V;wZ>gVe*(WFC+=9gnql3Owne5Vn@T%0n6ZCU_z9b42~?=$Ex9& zI59FhjJJX*&6I@mb8W}Gn-aMX!&`Pd=< zJ2J!y_lY2P;%CA+IQiTO0MoEbYkwfl@D^0h2ZS&kCu*e;=62DbWr(djE)qWTGIGkD!2FC~R4|d9! zSIr^dBmnIVFy$_<>V58mY2$p?P~e>GT%JWQ99viBWK*2hOZ_iwRakn5`G6zTNsMf& zCG=foYm!E*FVp-@qL)KLlkPqs@M<*s@4{r3!gnU`Y5R^UCMGDQDz7AUM(=tjH!E|t zk%bkE36IjFUW?hPJ>=aA=ZKSZu8naw>QR6v^;Vnk4)Sa3ZHgYMz5@F}WTZXwh1hIc zZ=GZG?*LC7GoWK7Z zxP^H*;9bYZQa&jSdw+?f@)03?2tY6`oCJPv=$X9m7$UKgUuOUP+%T|u%A4t+szq3? zx!lgL<6IR9Rjjrw&>;5oDqfijni`~Xe;n6i4=yNg{B9R=WcQ54hY{th394g9TIL=f zEpNsJP{blGQCxu*SgSr&v0vRGw*2Mt|HgFAO!L5W*r!LFp6pkgt%c{8P?0#qA6oC9 zzaX^)tTcrXd7g+3&AGTo?~ZvgL;o)HA+b3pDc7<~lzm5)o-phGwSIVU1!ejb7|9JG zCHM`PJ??{5n8z?Mzht&O=};ALr^*e{QmFnMZ<{l_o3MxikjoA|n7QF7Wq~UFbBa9l zZM$7ODmbo>j*{zc#bN~{W?u`#bMoTmxsc>|Q&vIlfAq_PAfx?*{zvW~(IzFw6-6uh*w5xDCJIs;e{_YDB(E*O~S#GkuXKeIvQ-Fs+c>5Y##DMc%cBXh#z)|?yWF8D~SzRsSGvvs`A;fFTqwVk- zYYidblZFr8oWew-R3cw@ZHh-Hkc0NAN682#+F(`%ruYqm+EsdQk)1w?&vRgnoX=QdE26R;YQ8JT3}ys9&XGylwngdAg+C2A*lyiIZ=ldc(w{FpJ!p6$_dAx*Qy43yR{lsj zS*d90oQZySF$=F&&?G!Ep|x}&+mhpk*)b=$`;&RwTPOs);u`q{a9Cr{xBVH)#b&fn zZ_)#2ut6-Ny+c_70lo{;HhdGt61l`#@MpW?5^gC@F^eBPg#pNwN~#oq^-i(fp!Con z96|JhDE(Ry`hYxgPo)C7_<;x&oaiv+-r7Hx-?oZwanHV4_ShUx#uvvT%f&j;e_w^K5jX1QR>_wK! zf#$o&ATT(O!}6QEgSnHii|R${YWAU4f@Zt=FNI7?`9Dr)j4*Z$&irU^KhKr;mZ16` z)lG=&Z8jaUwUz^wL({ydUH$fOf1S9_<||YgmUQ233+4lmrWjQIhB0^4dxuD+t0N zLfFvTYjpc^UzK|{zGF;wc%A+0t?NosOxRe46yp;L&!DW;RSi68B~F?YL02xxEicYh z9HSnd^!K7D#z;fO3&Oi?f@?o=GrKde7b_E0#4xx;$9;c(^6aQP6Gl#z2Xu$v=}{l+$pdc!fFosk-C zYhZnFXpY_cIob152JzkCFo|9!_;uY(doe7vRci~Pd zgUfW^_#fxyn(-OCAUM6XMt22F%;`x;)328dsoSzJej*6<50=XSX%VhWX8r!<_YoIv z>A3)8j4qtg)8Zp(@=UuuP(2}l3wnf}pq=5$=YwvA#98b41V@c~cRGE?BlOdpYQFFE z^u{dxVYh1g2|AovAfM(m^wXvW8 zddtzNS=BuRsT{CY+(PJ4_Zi@^7KlyA^JNw=u9j1NnFrN6KPr-YmpByP(GejNqzRyZ zHBIVPll1kc6Zuhj#pYOo$A0+Nc3rSn4=pgdqZ&tkZJ%{>8)WRl#XwdgMQcqPBmYAvSK;E%#HAtKwndEM>_r%|Zcus!ynQ_HwNDOANX z7^Jx*U4BPwG$GfrRybL<96VkwJJ$D}r527wxP@SiLHU`Y!nqO$?|H?R_Wy?>_Ho=| z6f^9Cw_0_W_@|dhBkeFgJ({96z4G*RJs(XHP^`BpHmEB7y&y_|b0G}nFqmfrcB3({ zHccab#hk-Zg#~go`fIk5-MU*xLq!Q^HX|%$5#FkIs?0Z91)1?T%+mLMVib%^P!vB!#Fp+3 z-+!Z4>8n^ZLC(6~)cniN)VP2{PMSfBY^*EQJ}u^mOtJIT9r@g}ibFtbwYlAz*&W%# zHC(ncat;8QVkys0C)KuC8_2z^j(6E5nfKwbY#-HkX+dJw*^qu64xpN}pLtQu=*LWM zsv4j9K(ut_G*lNoO3VEfjm#+BLlUYOvZzCY9(9FGXb8i>$X5A=IU%nKlrlbSP^~vo zvN(anRy*#jiZ@8i`m$EA>( zt06ZtI5r?hu}Vb*)OW%_dN93xm5gbb|E7TqD?H2;0y{{jP=T7lV(2;kl9mL z!2RET994KF;N|v)S)3I9ZFsTYXp1>C!jLMweqKN1`&&wEmR4b{noBkXZZW_6yR@d1JkGQXc9ek%R*9C+|beV!NG$DUy=aOcojm8RjRO3)HpKqKIVt` zQ47z~bkl)rpH~G~1B`o9vnd%Az6`!K_en{ErLp1E#JPd6S3pf6+W#JxOV$g|=&zqH zKGxhtG-SS~^HtQ9IeHVGwy~#|Ieg|Eaeppjf!e<$O`~l=s{w~?W<*M*Sr|sXF*FpS z)2ko-WpOaJviW!WmvECnM`Ej0w8xc;fFNp}}WHOx1nYEvw2N!cBlHSln7fleu)3)`U1O?`Onc>H%jSqExzGtP2zueJzHKiJE#WvU~l`6~QHIe}Mjg$@2`&bxSCE zynaJnz2LZLxl_kI1BmJ{=W4Og>y-SC1TnW?2iq_yj&6Wqoq#hfYd;5u;?j14bmSpL z$Dy~PvS^#i)%_V6SHd94j9@lPpTq#uzv?gpT1DVkc$E2C>Q=>-ps-F^ZG(41tKE#$ z)yFOg^a1@#wGS;VOEL(pp|Dg)&9bI)sc-HhXj~m6_{N1l z*xZiq*+uOw4&?K(2)bAe)6l;1K2T#pL>A!_cg8)*G0#t87$T2MKy3XYuhz?c?R?bO zhH?gx34`U9zn4Nb!&NhRB!+b-NSVR?(^YX2H}%cs&R2K;LHX}ZNZnk)f+19`)%>Of zuhcfE*r$mu?j<%=9=fVpd6WY5gUQdUtIdrk=Bywt5+RD{kkA?x+FAfBWch5DeIaTg zl9wfla{T!EhlI@>3wzR3VlZL2y67$mltX%o?+A$UAiMN%9BWyykjIV-*$wR~mY!`| zI`WSVdGDHo-3@}wL_p*9!Mja~xd`@niL=p@8vJE(kq(a;8w%v!69~UG$2%>N;TKQQ zBSImEsIVMO4nkK|ZaP~poSvr{mcVpW5r=ecQDGzalq4L1^!3Ef=&BHJu1c*P3qb&@ zY1)z{Mm8F&Xc|%{l!<1fi%N6Wh0I)gMPI?I6x5YP0*yRn&>vZ=E|-j$h<}^3vCL(C zWsi=G+`p^Vk4g{+Y%J1lE+Z~DJCr^vbg}can`=$OAK;YgQrGrQPK2Q@^Wv1gjj8J7 znX2p3Jj6=tyBp6@O67V@8hqA@|F3;9YbGBNjUYI>0up3xsh^RmS D5*BIF literal 0 HcmV?d00001 From e8ce38810968ab732cd55a47bbdff07954e890f0 Mon Sep 17 00:00:00 2001 From: Pepijn <138571049+pkooij@users.noreply.github.com> Date: Tue, 4 Mar 2025 19:04:19 +0100 Subject: [PATCH 03/19] Add wired instructions for LeKiwi (#814) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- examples/11_use_lekiwi.md | 126 +++++++++++++++++++++++++++++++++++++- 1 file changed, 124 insertions(+), 2 deletions(-) diff --git a/examples/11_use_lekiwi.md b/examples/11_use_lekiwi.md index 224a1854..4b811417 100644 --- a/examples/11_use_lekiwi.md +++ b/examples/11_use_lekiwi.md @@ -23,6 +23,9 @@ Follow this [README](https://github.com/SIGRobotics-UIUC/LeKiwi). It contains th Before assembling, you will first need to configure your motors. To this end, we provide a nice script, so let's first install LeRobot. After configuration, we will also guide you through assembly. +### Wired version +If you have the **wired** LeKiwi version you can skip the installation of the Raspberry Pi and setting up SSH. You can also run all commands directly on your PC for both the LeKiwi scripts and the leader arm scripts for teleoperating. + ## B. Install software on Pi Now we have to setup the remote PC that will run on the LeKiwi Robot. This is normally a Raspberry Pi, but can be any PC that can run on 5V and has enough usb ports (2 or more) for the cameras and motor control board. @@ -246,6 +249,110 @@ class LeKiwiRobotConfig(RobotConfig): } ) + teleop_keys: dict[str, str] = field( + default_factory=lambda: { + # Movement + "forward": "w", + "backward": "s", + "left": "a", + "right": "d", + "rotate_left": "z", + "rotate_right": "x", + # Speed control + "speed_up": "r", + "speed_down": "f", + # quit teleop + "quit": "q", + } + ) + + mock: bool = False +``` + +## Wired version + +For the wired LeKiwi version your configured IP address should refer to your own laptop (127.0.0.1), because leader arm and LeKiwi are in this case connected to own laptop. Below and example configuration for this wired setup: +```python +@RobotConfig.register_subclass("lekiwi") +@dataclass +class LeKiwiRobotConfig(RobotConfig): + # `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes. + # Set this to a positive scalar to have the same value for all motors, or a list that is the same length as + # the number of motors in your follower arms. + max_relative_target: int | None = None + + # Network Configuration + ip: str = "127.0.0.1" + port: int = 5555 + video_port: int = 5556 + + cameras: dict[str, CameraConfig] = field( + default_factory=lambda: { + "front": OpenCVCameraConfig( + camera_index=0, fps=30, width=640, height=480, rotation=90 + ), + "wrist": OpenCVCameraConfig( + camera_index=1, fps=30, width=640, height=480, rotation=180 + ), + } + ) + + calibration_dir: str = ".cache/calibration/lekiwi" + + leader_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + port="/dev/tty.usbmodem585A0077581", + motors={ + # name: (index, model) + "shoulder_pan": [1, "sts3215"], + "shoulder_lift": [2, "sts3215"], + "elbow_flex": [3, "sts3215"], + "wrist_flex": [4, "sts3215"], + "wrist_roll": [5, "sts3215"], + "gripper": [6, "sts3215"], + }, + ), + } + ) + + follower_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + port="/dev/tty.usbmodem58760431061", + motors={ + # name: (index, model) + "shoulder_pan": [1, "sts3215"], + "shoulder_lift": [2, "sts3215"], + "elbow_flex": [3, "sts3215"], + "wrist_flex": [4, "sts3215"], + "wrist_roll": [5, "sts3215"], + "gripper": [6, "sts3215"], + "left_wheel": (7, "sts3215"), + "back_wheel": (8, "sts3215"), + "right_wheel": (9, "sts3215"), + }, + ), + } + ) + + teleop_keys: dict[str, str] = field( + default_factory=lambda: { + # Movement + "forward": "w", + "backward": "s", + "left": "a", + "right": "d", + "rotate_left": "z", + "rotate_right": "x", + # Speed control + "speed_up": "r", + "speed_down": "f", + # quit teleop + "quit": "q", + } + ) + mock: bool = False ``` @@ -272,6 +379,9 @@ python lerobot/scripts/control_robot.py \ --control.arms='["main_follower"]' ``` +### Wired version +If you have the **wired** LeKiwi version please run all commands including this calibration command on your laptop. + ### Calibrate leader arm Then to calibrate the leader arm (which is attached to the laptop/pc). You will need to move the leader arm to these positions sequentially: @@ -326,6 +436,9 @@ You should see on your laptop something like this: ```[INFO] Connected to remote > [!TIP] > If you use a different keyboard you can change the keys for each command in the [`LeKiwiRobotConfig`](../lerobot/common/robot_devices/robots/configs.py). +### Wired version +If you have the **wired** LeKiwi version please run all commands including both these teleoperation commands on your laptop. + ## Troubleshoot communication If you are having trouble connecting to the Mobile SO100, follow these steps to diagnose and resolve the issue. @@ -364,6 +477,13 @@ Make sure the configuration file on both your laptop/pc and the Raspberry Pi is # G. Record a dataset Once you're familiar with teleoperation, you can record your first dataset with LeKiwi. +To start the program on LeKiwi, SSH into your Raspberry Pi, and run `conda activate lerobot` and this script: +```bash +python lerobot/scripts/control_robot.py \ + --robot.type=lekiwi \ + --control.type=remote_robot +``` + If you want to use the Hugging Face hub features for uploading your dataset and you haven't previously done it, make sure you've logged in using a write-access token, which can be generated from the [Hugging Face settings](https://huggingface.co/settings/tokens): ```bash huggingface-cli login --token ${HUGGINGFACE_TOKEN} --add-to-git-credential @@ -374,8 +494,7 @@ Store your Hugging Face repository name in a variable to run these commands: HF_USER=$(huggingface-cli whoami | head -n 1) echo $HF_USER ``` - -Record 2 episodes and upload your dataset to the hub: +On your laptop then run this command to record 2 episodes and upload your dataset to the hub: ```bash python lerobot/scripts/control_robot.py \ --robot.type=lekiwi \ @@ -393,6 +512,9 @@ python lerobot/scripts/control_robot.py \ Note: You can resume recording by adding `--control.resume=true`. +### Wired version +If you have the **wired** LeKiwi version please run all commands including both these record dataset commands on your laptop. + # H. Visualize a dataset If you uploaded your dataset to the hub with `--control.push_to_hub=true`, you can [visualize your dataset online](https://huggingface.co/spaces/lerobot/visualize_dataset) by copy pasting your repo id given by: From b80e55ca44d95b049a1f989d27378fcd27cfc342 Mon Sep 17 00:00:00 2001 From: Yachen Kang Date: Wed, 5 Mar 2025 08:31:56 +0800 Subject: [PATCH 04/19] =?UTF-8?q?change=20"actions=5Fid=5Fpad"=20to=20"act?= =?UTF-8?q?ions=5Fis=5Fpad"(=F0=9F=90=9B=20Bug)=20=20(#774)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Steven Palma --- lerobot/common/policies/pi0/modeling_pi0.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lerobot/common/policies/pi0/modeling_pi0.py b/lerobot/common/policies/pi0/modeling_pi0.py index c8b12caf..bc53bf85 100644 --- a/lerobot/common/policies/pi0/modeling_pi0.py +++ b/lerobot/common/policies/pi0/modeling_pi0.py @@ -313,7 +313,7 @@ class PI0Policy(PreTrainedPolicy): state = self.prepare_state(batch) lang_tokens, lang_masks = self.prepare_language(batch) actions = self.prepare_action(batch) - actions_is_pad = batch.get("actions_id_pad") + actions_is_pad = batch.get("actions_is_pad") loss_dict = {} losses = self.model.forward(images, img_masks, lang_tokens, lang_masks, state, actions, noise, time) From 2feb5edc652442e57ff35cdee2340a26f1a93cbd Mon Sep 17 00:00:00 2001 From: yadunund Date: Wed, 5 Mar 2025 01:01:24 -0800 Subject: [PATCH 05/19] Fix printout in make_cameras_from_configs (#796) Signed-off-by: Yadunund Co-authored-by: Steven Palma --- lerobot/common/robot_devices/cameras/utils.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lerobot/common/robot_devices/cameras/utils.py b/lerobot/common/robot_devices/cameras/utils.py index 88288ea3..ef6d8266 100644 --- a/lerobot/common/robot_devices/cameras/utils.py +++ b/lerobot/common/robot_devices/cameras/utils.py @@ -31,7 +31,7 @@ def make_cameras_from_configs(camera_configs: dict[str, CameraConfig]) -> list[C cameras[key] = IntelRealSenseCamera(cfg) else: - raise ValueError(f"The motor type '{cfg.type}' is not valid.") + raise ValueError(f"The camera type '{cfg.type}' is not valid.") return cameras From a00936686fdfc1516329101c7becfa5ff5280c61 Mon Sep 17 00:00:00 2001 From: Tim Qian Date: Wed, 5 Mar 2025 17:02:25 +0800 Subject: [PATCH 06/19] Fix doc (#793) Co-authored-by: Steven Palma --- examples/10_use_so100.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/10_use_so100.md b/examples/10_use_so100.md index 23da1eab..b63eb146 100644 --- a/examples/10_use_so100.md +++ b/examples/10_use_so100.md @@ -99,22 +99,22 @@ Example output when identifying the leader arm's port (e.g., `/dev/tty.usbmodem5 ``` Finding all available ports for the MotorBus. ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751'] -Remove the usb cable from your DynamixelMotorsBus and press Enter when done. +Remove the usb cable from your MotorsBus and press Enter when done. [...Disconnect leader arm and press Enter...] -The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0031751 +The port of this MotorsBus is /dev/tty.usbmodem575E0031751 Reconnect the usb cable. ``` Example output when identifying the follower arm's port (e.g., `/dev/tty.usbmodem575E0032081`, or possibly `/dev/ttyACM1` on Linux): ``` Finding all available ports for the MotorBus. ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751'] -Remove the usb cable from your DynamixelMotorsBus and press Enter when done. +Remove the usb cable from your MotorsBus and press Enter when done. [...Disconnect follower arm and press Enter...] -The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0032081 +The port of this MotorsBus is /dev/tty.usbmodem575E0032081 Reconnect the usb cable. ``` From d694ea1d38e53aad20ce36bc014a16e3da185f5c Mon Sep 17 00:00:00 2001 From: eDeveloperOZ Date: Wed, 5 Mar 2025 11:07:35 +0200 Subject: [PATCH 07/19] docs: update installation instructions to use uv instead of conda (#731) Co-authored-by: Steven Palma --- README.md | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 9debf9d1..454c7e5d 100644 --- a/README.md +++ b/README.md @@ -92,15 +92,20 @@ git clone https://github.com/huggingface/lerobot.git cd lerobot ``` -Create a virtual environment with Python 3.10 and activate it, e.g. with [`miniconda`](https://docs.anaconda.com/free/miniconda/index.html): +Create a virtual environment with Python 3.10 and activate it using [`uv`](https://github.com/astral-sh/uv): ```bash -conda create -y -n lerobot python=3.10 -conda activate lerobot +# Install uv if you haven't already +curl -LsSf https://astral.sh/uv/install.sh | sh + +# Create and activate virtual environment with Python 3.10 +uv venv .venv --python=3.10 +source .venv/bin/activate # On Unix/macOS +# .venv\Scripts\activate # On Windows ``` Install 🤗 LeRobot: ```bash -pip install -e . +uv pip install -e . ``` > **NOTE:** Depending on your platform, If you encounter any build errors during this step From 5d24ce31606eb3e48a0f644530f928c5f119a724 Mon Sep 17 00:00:00 2001 From: Steven Palma Date: Wed, 5 Mar 2025 17:56:51 +0100 Subject: [PATCH 08/19] chore(doc): add license header to all files (#818) --- .dockerignore | 14 ++++++ .gitattributes | 14 ++++++ .github/ISSUE_TEMPLATE/bug-report.yml | 14 ++++++ .github/workflows/build-docker-images.yml | 14 ++++++ .github/workflows/nightly-tests.yml | 14 ++++++ .github/workflows/pr_style_bot.yml | 14 ++++++ .github/workflows/quality.yml | 14 ++++++ .github/workflows/test-docker-build.yml | 14 ++++++ .github/workflows/test.yml | 14 ++++++ .github/workflows/trufflehog.yml | 14 ++++++ .gitignore | 14 ++++++ .pre-commit-config.yaml | 14 ++++++ Makefile | 14 ++++++ examples/1_load_lerobot_dataset.py | 14 ++++++ examples/2_evaluate_pretrained_policy.py | 14 ++++++ examples/3_train_policy.py | 14 ++++++ examples/advanced/1_add_image_transforms.py | 14 ++++++ .../advanced/2_calculate_validation_loss.py | 14 ++++++ examples/port_datasets/pusht_zarr.py | 14 ++++++ lerobot/common/constants.py | 13 ++++++ .../common/datasets/backward_compatibility.py | 14 ++++++ .../v21/_remove_language_instruction.py | 14 ++++++ .../v21/convert_dataset_v20_to_v21.py | 14 ++++++ lerobot/common/datasets/v21/convert_stats.py | 14 ++++++ lerobot/common/envs/__init__.py | 14 ++++++ lerobot/common/envs/configs.py | 14 ++++++ lerobot/common/optim/__init__.py | 14 ++++++ lerobot/common/policies/__init__.py | 14 ++++++ .../common/policies/pi0/configuration_pi0.py | 14 ++++++ .../pi0/conversion_scripts/benchmark.py | 14 ++++++ .../conversion_scripts/compare_with_jax.py | 14 ++++++ .../conversion_scripts/conversion_utils.py | 14 ++++++ .../convert_pi0_to_hf_lerobot.py | 14 ++++++ lerobot/common/policies/pi0/flex_attention.py | 14 ++++++ .../policies/pi0/paligemma_with_expert.py | 14 ++++++ lerobot/common/policies/pretrained.py | 13 ++++++ .../common/robot_devices/cameras/configs.py | 14 ++++++ .../robot_devices/cameras/intelrealsense.py | 14 ++++++ .../common/robot_devices/cameras/opencv.py | 14 ++++++ lerobot/common/robot_devices/cameras/utils.py | 14 ++++++ .../common/robot_devices/control_configs.py | 14 ++++++ lerobot/common/robot_devices/control_utils.py | 14 ++++++ .../common/robot_devices/motors/configs.py | 14 ++++++ .../common/robot_devices/motors/dynamixel.py | 14 ++++++ .../common/robot_devices/motors/feetech.py | 14 ++++++ lerobot/common/robot_devices/motors/utils.py | 14 ++++++ .../common/robot_devices/robots/configs.py | 14 ++++++ .../robots/dynamixel_calibration.py | 14 ++++++ .../robots/feetech_calibration.py | 14 ++++++ .../robot_devices/robots/lekiwi_remote.py | 14 ++++++ .../robot_devices/robots/manipulator.py | 14 ++++++ .../robots/mobile_manipulator.py | 14 ++++++ lerobot/common/robot_devices/robots/utils.py | 14 ++++++ lerobot/common/robot_devices/utils.py | 14 ++++++ lerobot/common/utils/hub.py | 14 ++++++ lerobot/configs/eval.py | 14 ++++++ lerobot/configs/parser.py | 13 ++++++ lerobot/configs/policies.py | 13 ++++++ lerobot/configs/train.py | 13 ++++++ lerobot/configs/types.py | 13 ++++++ lerobot/scripts/configure_motor.py | 13 ++++++ lerobot/scripts/control_robot.py | 13 ++++++ lerobot/scripts/control_sim_robot.py | 13 ++++++ lerobot/scripts/find_motors_bus_port.py | 13 ++++++ pyproject.toml | 43 +++++++++++++------ tests/__init__.py | 13 ++++++ tests/fixtures/constants.py | 13 ++++++ tests/fixtures/dataset_factories.py | 13 ++++++ tests/fixtures/files.py | 13 ++++++ tests/fixtures/hub.py | 13 ++++++ tests/fixtures/optimizers.py | 13 ++++++ tests/mock_cv2.py | 13 ++++++ tests/mock_dynamixel_sdk.py | 13 ++++++ tests/mock_pyrealsense2.py | 13 ++++++ tests/mock_scservo_sdk.py | 13 ++++++ tests/test_cameras.py | 13 ++++++ tests/test_control_robot.py | 13 ++++++ tests/test_delta_timestamps.py | 13 ++++++ tests/test_image_writer.py | 13 ++++++ tests/test_io_utils.py | 13 ++++++ tests/test_logging_utils.py | 13 ++++++ tests/test_motors.py | 13 ++++++ tests/test_optimizers.py | 13 ++++++ tests/test_random_utils.py | 13 ++++++ tests/test_robots.py | 13 ++++++ tests/test_schedulers.py | 13 ++++++ tests/test_train_utils.py | 13 ++++++ tests/test_utils.py | 13 ++++++ 88 files changed, 1215 insertions(+), 13 deletions(-) diff --git a/.dockerignore b/.dockerignore index b8c1be15..4f074d44 100644 --- a/.dockerignore +++ b/.dockerignore @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + # Misc .git tmp diff --git a/.gitattributes b/.gitattributes index 7da36424..44e16cf1 100644 --- a/.gitattributes +++ b/.gitattributes @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + *.memmap filter=lfs diff=lfs merge=lfs -text *.stl filter=lfs diff=lfs merge=lfs -text *.safetensors filter=lfs diff=lfs merge=lfs -text diff --git a/.github/ISSUE_TEMPLATE/bug-report.yml b/.github/ISSUE_TEMPLATE/bug-report.yml index 7cbed673..2fb23051 100644 --- a/.github/ISSUE_TEMPLATE/bug-report.yml +++ b/.github/ISSUE_TEMPLATE/bug-report.yml @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + name: "\U0001F41B Bug Report" description: Submit a bug report to help us improve LeRobot body: diff --git a/.github/workflows/build-docker-images.yml b/.github/workflows/build-docker-images.yml index 3c63fa11..0cb11d57 100644 --- a/.github/workflows/build-docker-images.yml +++ b/.github/workflows/build-docker-images.yml @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + # Inspired by # https://github.com/huggingface/peft/blob/main/.github/workflows/build_docker_images.yml name: Builds diff --git a/.github/workflows/nightly-tests.yml b/.github/workflows/nightly-tests.yml index 210a690c..adac9f20 100644 --- a/.github/workflows/nightly-tests.yml +++ b/.github/workflows/nightly-tests.yml @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + # Inspired by # https://github.com/huggingface/peft/blob/main/.github/workflows/nightly.yml name: Nightly diff --git a/.github/workflows/pr_style_bot.yml b/.github/workflows/pr_style_bot.yml index 68530645..dc4974c2 100644 --- a/.github/workflows/pr_style_bot.yml +++ b/.github/workflows/pr_style_bot.yml @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + # Adapted from https://github.com/huggingface/diffusers/blob/main/.github/workflows/pr_style_bot.yml name: PR Style Bot diff --git a/.github/workflows/quality.yml b/.github/workflows/quality.yml index f785d52f..332b543c 100644 --- a/.github/workflows/quality.yml +++ b/.github/workflows/quality.yml @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + name: Quality on: diff --git a/.github/workflows/test-docker-build.yml b/.github/workflows/test-docker-build.yml index 3ee84a27..e77c570e 100644 --- a/.github/workflows/test-docker-build.yml +++ b/.github/workflows/test-docker-build.yml @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + # Inspired by # https://github.com/huggingface/peft/blob/main/.github/workflows/test-docker-build.yml name: Test Dockerfiles diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 9c3f5756..3ef47887 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + name: Tests on: diff --git a/.github/workflows/trufflehog.yml b/.github/workflows/trufflehog.yml index 487ccea5..166e0590 100644 --- a/.github/workflows/trufflehog.yml +++ b/.github/workflows/trufflehog.yml @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + on: push: diff --git a/.gitignore b/.gitignore index 0a0ffe10..da4b1089 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + # Logging logs tmp diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index dba87705..21016efa 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + exclude: ^(tests/data) default_language_version: python: python3.10 diff --git a/Makefile b/Makefile index 772da320..68f07b21 100644 --- a/Makefile +++ b/Makefile @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + .PHONY: tests PYTHON_PATH := $(shell which python) diff --git a/examples/1_load_lerobot_dataset.py b/examples/1_load_lerobot_dataset.py index 96c104b6..c374a375 100644 --- a/examples/1_load_lerobot_dataset.py +++ b/examples/1_load_lerobot_dataset.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """ This script demonstrates the use of `LeRobotDataset` class for handling and processing robotic datasets from Hugging Face. It illustrates how to load datasets, manipulate them, and apply transformations suitable for machine learning tasks in PyTorch. diff --git a/examples/2_evaluate_pretrained_policy.py b/examples/2_evaluate_pretrained_policy.py index 0a7b8deb..bf3c442a 100644 --- a/examples/2_evaluate_pretrained_policy.py +++ b/examples/2_evaluate_pretrained_policy.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """ This scripts demonstrates how to evaluate a pretrained policy from the HuggingFace Hub or from your local training outputs directory. In the latter case, you might want to run examples/3_train_policy.py first. diff --git a/examples/3_train_policy.py b/examples/3_train_policy.py index f6eabbfa..6c3af54e 100644 --- a/examples/3_train_policy.py +++ b/examples/3_train_policy.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """This scripts demonstrates how to train Diffusion Policy on the PushT environment. Once you have trained a model with this script, you can try to evaluate it on diff --git a/examples/advanced/1_add_image_transforms.py b/examples/advanced/1_add_image_transforms.py index 882710e3..f1460926 100644 --- a/examples/advanced/1_add_image_transforms.py +++ b/examples/advanced/1_add_image_transforms.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """ This script demonstrates how to use torchvision's image transformation with LeRobotDataset for data augmentation purposes. The transformations are passed to the dataset as an argument upon creation, and diff --git a/examples/advanced/2_calculate_validation_loss.py b/examples/advanced/2_calculate_validation_loss.py index 6f234719..47b4dd02 100644 --- a/examples/advanced/2_calculate_validation_loss.py +++ b/examples/advanced/2_calculate_validation_loss.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """This script demonstrates how to slice a dataset and calculate the loss on a subset of the data. This technique can be useful for debugging and testing purposes, as well as identifying whether a policy diff --git a/examples/port_datasets/pusht_zarr.py b/examples/port_datasets/pusht_zarr.py index eac6f63d..ea2e8b60 100644 --- a/examples/port_datasets/pusht_zarr.py +++ b/examples/port_datasets/pusht_zarr.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import shutil from pathlib import Path diff --git a/lerobot/common/constants.py b/lerobot/common/constants.py index d0c9845a..973595cd 100644 --- a/lerobot/common/constants.py +++ b/lerobot/common/constants.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. # keys import os from pathlib import Path diff --git a/lerobot/common/datasets/backward_compatibility.py b/lerobot/common/datasets/backward_compatibility.py index d1b8926a..cf8e31c4 100644 --- a/lerobot/common/datasets/backward_compatibility.py +++ b/lerobot/common/datasets/backward_compatibility.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import packaging.version V2_MESSAGE = """ diff --git a/lerobot/common/datasets/v21/_remove_language_instruction.py b/lerobot/common/datasets/v21/_remove_language_instruction.py index dd4604cf..643ddd3f 100644 --- a/lerobot/common/datasets/v21/_remove_language_instruction.py +++ b/lerobot/common/datasets/v21/_remove_language_instruction.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import logging import traceback from pathlib import Path diff --git a/lerobot/common/datasets/v21/convert_dataset_v20_to_v21.py b/lerobot/common/datasets/v21/convert_dataset_v20_to_v21.py index 163a6003..176d16d0 100644 --- a/lerobot/common/datasets/v21/convert_dataset_v20_to_v21.py +++ b/lerobot/common/datasets/v21/convert_dataset_v20_to_v21.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """ This script will help you convert any LeRobot dataset already pushed to the hub from codebase version 2.0 to 2.1. It will: diff --git a/lerobot/common/datasets/v21/convert_stats.py b/lerobot/common/datasets/v21/convert_stats.py index cbf584b7..4a20b427 100644 --- a/lerobot/common/datasets/v21/convert_stats.py +++ b/lerobot/common/datasets/v21/convert_stats.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from concurrent.futures import ThreadPoolExecutor, as_completed import numpy as np diff --git a/lerobot/common/envs/__init__.py b/lerobot/common/envs/__init__.py index a583ffc5..4977d11d 100644 --- a/lerobot/common/envs/__init__.py +++ b/lerobot/common/envs/__init__.py @@ -1 +1,15 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from .configs import AlohaEnv, EnvConfig, PushtEnv, XarmEnv # noqa: F401 diff --git a/lerobot/common/envs/configs.py b/lerobot/common/envs/configs.py index 6259ca94..cf90048a 100644 --- a/lerobot/common/envs/configs.py +++ b/lerobot/common/envs/configs.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import abc from dataclasses import dataclass, field diff --git a/lerobot/common/optim/__init__.py b/lerobot/common/optim/__init__.py index e1e65966..de2c4c99 100644 --- a/lerobot/common/optim/__init__.py +++ b/lerobot/common/optim/__init__.py @@ -1 +1,15 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from .optimizers import OptimizerConfig as OptimizerConfig diff --git a/lerobot/common/policies/__init__.py b/lerobot/common/policies/__init__.py index 2e4486ef..b73ba5f4 100644 --- a/lerobot/common/policies/__init__.py +++ b/lerobot/common/policies/__init__.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from .act.configuration_act import ACTConfig as ACTConfig from .diffusion.configuration_diffusion import DiffusionConfig as DiffusionConfig from .pi0.configuration_pi0 import PI0Config as PI0Config diff --git a/lerobot/common/policies/pi0/configuration_pi0.py b/lerobot/common/policies/pi0/configuration_pi0.py index 8d2eedf6..ac3a62a8 100644 --- a/lerobot/common/policies/pi0/configuration_pi0.py +++ b/lerobot/common/policies/pi0/configuration_pi0.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from dataclasses import dataclass, field from lerobot.common.optim.optimizers import AdamWConfig diff --git a/lerobot/common/policies/pi0/conversion_scripts/benchmark.py b/lerobot/common/policies/pi0/conversion_scripts/benchmark.py index 31bd1b66..35b9a45b 100644 --- a/lerobot/common/policies/pi0/conversion_scripts/benchmark.py +++ b/lerobot/common/policies/pi0/conversion_scripts/benchmark.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import torch from lerobot.common.datasets.lerobot_dataset import LeRobotDataset diff --git a/lerobot/common/policies/pi0/conversion_scripts/compare_with_jax.py b/lerobot/common/policies/pi0/conversion_scripts/compare_with_jax.py index 8b2e1c66..ceb8ada0 100644 --- a/lerobot/common/policies/pi0/conversion_scripts/compare_with_jax.py +++ b/lerobot/common/policies/pi0/conversion_scripts/compare_with_jax.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import json import pickle from pathlib import Path diff --git a/lerobot/common/policies/pi0/conversion_scripts/conversion_utils.py b/lerobot/common/policies/pi0/conversion_scripts/conversion_utils.py index 8e35d0d4..8835da31 100644 --- a/lerobot/common/policies/pi0/conversion_scripts/conversion_utils.py +++ b/lerobot/common/policies/pi0/conversion_scripts/conversion_utils.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from transformers import GemmaConfig, PaliGemmaConfig diff --git a/lerobot/common/policies/pi0/conversion_scripts/convert_pi0_to_hf_lerobot.py b/lerobot/common/policies/pi0/conversion_scripts/convert_pi0_to_hf_lerobot.py index dd8622dd..73ff506f 100644 --- a/lerobot/common/policies/pi0/conversion_scripts/convert_pi0_to_hf_lerobot.py +++ b/lerobot/common/policies/pi0/conversion_scripts/convert_pi0_to_hf_lerobot.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """ Convert pi0 parameters from Jax to Pytorch diff --git a/lerobot/common/policies/pi0/flex_attention.py b/lerobot/common/policies/pi0/flex_attention.py index 38a5b597..35628cdd 100644 --- a/lerobot/common/policies/pi0/flex_attention.py +++ b/lerobot/common/policies/pi0/flex_attention.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import torch import torch.nn.functional as F # noqa: N812 from packaging.version import Version diff --git a/lerobot/common/policies/pi0/paligemma_with_expert.py b/lerobot/common/policies/pi0/paligemma_with_expert.py index 08c36c11..76e2ce60 100644 --- a/lerobot/common/policies/pi0/paligemma_with_expert.py +++ b/lerobot/common/policies/pi0/paligemma_with_expert.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from typing import List, Optional, Union import torch diff --git a/lerobot/common/policies/pretrained.py b/lerobot/common/policies/pretrained.py index 1729dfb0..549ea92b 100644 --- a/lerobot/common/policies/pretrained.py +++ b/lerobot/common/policies/pretrained.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import abc import logging import os diff --git a/lerobot/common/robot_devices/cameras/configs.py b/lerobot/common/robot_devices/cameras/configs.py index 6acdbd3e..013419a9 100644 --- a/lerobot/common/robot_devices/cameras/configs.py +++ b/lerobot/common/robot_devices/cameras/configs.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import abc from dataclasses import dataclass diff --git a/lerobot/common/robot_devices/cameras/intelrealsense.py b/lerobot/common/robot_devices/cameras/intelrealsense.py index 7e65dba9..29e99ea3 100644 --- a/lerobot/common/robot_devices/cameras/intelrealsense.py +++ b/lerobot/common/robot_devices/cameras/intelrealsense.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """ This file contains utilities for recording frames from Intel Realsense cameras. """ diff --git a/lerobot/common/robot_devices/cameras/opencv.py b/lerobot/common/robot_devices/cameras/opencv.py index 93c791fa..d15a48f6 100644 --- a/lerobot/common/robot_devices/cameras/opencv.py +++ b/lerobot/common/robot_devices/cameras/opencv.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """ This file contains utilities for recording frames from cameras. For more info look at `OpenCVCamera` docstring. """ diff --git a/lerobot/common/robot_devices/cameras/utils.py b/lerobot/common/robot_devices/cameras/utils.py index ef6d8266..c6431646 100644 --- a/lerobot/common/robot_devices/cameras/utils.py +++ b/lerobot/common/robot_devices/cameras/utils.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from typing import Protocol import numpy as np diff --git a/lerobot/common/robot_devices/control_configs.py b/lerobot/common/robot_devices/control_configs.py index 2ef1b44b..01908472 100644 --- a/lerobot/common/robot_devices/control_configs.py +++ b/lerobot/common/robot_devices/control_configs.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import logging from dataclasses import dataclass from pathlib import Path diff --git a/lerobot/common/robot_devices/control_utils.py b/lerobot/common/robot_devices/control_utils.py index d2361a64..4782959a 100644 --- a/lerobot/common/robot_devices/control_utils.py +++ b/lerobot/common/robot_devices/control_utils.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + ######################################################################################## # Utilities ######################################################################################## diff --git a/lerobot/common/robot_devices/motors/configs.py b/lerobot/common/robot_devices/motors/configs.py index 37b781f9..0bfbaf83 100644 --- a/lerobot/common/robot_devices/motors/configs.py +++ b/lerobot/common/robot_devices/motors/configs.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import abc from dataclasses import dataclass diff --git a/lerobot/common/robot_devices/motors/dynamixel.py b/lerobot/common/robot_devices/motors/dynamixel.py index 17ea933d..186f7124 100644 --- a/lerobot/common/robot_devices/motors/dynamixel.py +++ b/lerobot/common/robot_devices/motors/dynamixel.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import enum import logging import math diff --git a/lerobot/common/robot_devices/motors/feetech.py b/lerobot/common/robot_devices/motors/feetech.py index cec36d37..7d0d2a00 100644 --- a/lerobot/common/robot_devices/motors/feetech.py +++ b/lerobot/common/robot_devices/motors/feetech.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import enum import logging import math diff --git a/lerobot/common/robot_devices/motors/utils.py b/lerobot/common/robot_devices/motors/utils.py index fc64f050..bd86f4c6 100644 --- a/lerobot/common/robot_devices/motors/utils.py +++ b/lerobot/common/robot_devices/motors/utils.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from typing import Protocol from lerobot.common.robot_devices.motors.configs import ( diff --git a/lerobot/common/robot_devices/robots/configs.py b/lerobot/common/robot_devices/robots/configs.py index 88cb4e6f..e940b442 100644 --- a/lerobot/common/robot_devices/robots/configs.py +++ b/lerobot/common/robot_devices/robots/configs.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import abc from dataclasses import dataclass, field from typing import Sequence diff --git a/lerobot/common/robot_devices/robots/dynamixel_calibration.py b/lerobot/common/robot_devices/robots/dynamixel_calibration.py index 142d5794..98fe8754 100644 --- a/lerobot/common/robot_devices/robots/dynamixel_calibration.py +++ b/lerobot/common/robot_devices/robots/dynamixel_calibration.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """Logic to calibrate a robot arm built with dynamixel motors""" # TODO(rcadene, aliberts): move this logic into the robot code when refactoring diff --git a/lerobot/common/robot_devices/robots/feetech_calibration.py b/lerobot/common/robot_devices/robots/feetech_calibration.py index d779cd44..2c1e7180 100644 --- a/lerobot/common/robot_devices/robots/feetech_calibration.py +++ b/lerobot/common/robot_devices/robots/feetech_calibration.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """Logic to calibrate a robot arm built with feetech motors""" # TODO(rcadene, aliberts): move this logic into the robot code when refactoring diff --git a/lerobot/common/robot_devices/robots/lekiwi_remote.py b/lerobot/common/robot_devices/robots/lekiwi_remote.py index fd9491fa..7bf52d21 100644 --- a/lerobot/common/robot_devices/robots/lekiwi_remote.py +++ b/lerobot/common/robot_devices/robots/lekiwi_remote.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import base64 import json import threading diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robot_devices/robots/manipulator.py index 62e5416e..8a7c7fe6 100644 --- a/lerobot/common/robot_devices/robots/manipulator.py +++ b/lerobot/common/robot_devices/robots/manipulator.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + """Contains logic to instantiate a robot, read information from its motors and cameras, and send orders to its motors. """ diff --git a/lerobot/common/robot_devices/robots/mobile_manipulator.py b/lerobot/common/robot_devices/robots/mobile_manipulator.py index c2cad227..385e218b 100644 --- a/lerobot/common/robot_devices/robots/mobile_manipulator.py +++ b/lerobot/common/robot_devices/robots/mobile_manipulator.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import base64 import json import os diff --git a/lerobot/common/robot_devices/robots/utils.py b/lerobot/common/robot_devices/robots/utils.py index 47e2519b..dab514d5 100644 --- a/lerobot/common/robot_devices/robots/utils.py +++ b/lerobot/common/robot_devices/robots/utils.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from typing import Protocol from lerobot.common.robot_devices.robots.configs import ( diff --git a/lerobot/common/robot_devices/utils.py b/lerobot/common/robot_devices/utils.py index 19bb637e..837c9d2e 100644 --- a/lerobot/common/robot_devices/utils.py +++ b/lerobot/common/robot_devices/utils.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import platform import time diff --git a/lerobot/common/utils/hub.py b/lerobot/common/utils/hub.py index 63fcf918..df7435c0 100644 --- a/lerobot/common/utils/hub.py +++ b/lerobot/common/utils/hub.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from pathlib import Path from tempfile import TemporaryDirectory from typing import Any, Type, TypeVar diff --git a/lerobot/configs/eval.py b/lerobot/configs/eval.py index 11873352..eb2a6df9 100644 --- a/lerobot/configs/eval.py +++ b/lerobot/configs/eval.py @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import datetime as dt import logging from dataclasses import dataclass, field diff --git a/lerobot/configs/parser.py b/lerobot/configs/parser.py index ee784877..476a9b40 100644 --- a/lerobot/configs/parser.py +++ b/lerobot/configs/parser.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import inspect import sys from argparse import ArgumentError diff --git a/lerobot/configs/policies.py b/lerobot/configs/policies.py index 9b5a7c5c..4f52b16c 100644 --- a/lerobot/configs/policies.py +++ b/lerobot/configs/policies.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import abc import os from dataclasses import dataclass, field diff --git a/lerobot/configs/train.py b/lerobot/configs/train.py index 464c11f9..33e98b88 100644 --- a/lerobot/configs/train.py +++ b/lerobot/configs/train.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import datetime as dt import logging import os diff --git a/lerobot/configs/types.py b/lerobot/configs/types.py index 0ca45a19..6b3d92e8 100644 --- a/lerobot/configs/types.py +++ b/lerobot/configs/types.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. # Note: We subclass str so that serialization is straightforward # https://stackoverflow.com/questions/24481852/serialising-an-enum-member-to-json from dataclasses import dataclass diff --git a/lerobot/scripts/configure_motor.py b/lerobot/scripts/configure_motor.py index f7e07070..b0dc8a97 100644 --- a/lerobot/scripts/configure_motor.py +++ b/lerobot/scripts/configure_motor.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. """ This script configure a single motor at a time to a given ID and baudrate. diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index ab5d0e8a..3a82e5c3 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. """ Utilities to control a robot. diff --git a/lerobot/scripts/control_sim_robot.py b/lerobot/scripts/control_sim_robot.py index 49a88d14..5347822c 100644 --- a/lerobot/scripts/control_sim_robot.py +++ b/lerobot/scripts/control_sim_robot.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. """ Utilities to control a robot in simulation. diff --git a/lerobot/scripts/find_motors_bus_port.py b/lerobot/scripts/find_motors_bus_port.py index 67b92ad7..68f2315d 100644 --- a/lerobot/scripts/find_motors_bus_port.py +++ b/lerobot/scripts/find_motors_bus_port.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import os import time from pathlib import Path diff --git a/pyproject.toml b/pyproject.toml index 9a7c9730..a4458eb6 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,3 +1,17 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + [project.urls] homepage = "https://github.com/huggingface/lerobot" issues = "https://github.com/huggingface/lerobot/issues" @@ -8,18 +22,19 @@ name = "lerobot" version = "0.1.0" description = "🤗 LeRobot: State-of-the-art Machine Learning for Real-World Robotics in Pytorch" authors = [ - {name = "Rémi Cadène", email = "re.cadene@gmail.com"}, - {name = "Simon Alibert", email = "alibert.sim@gmail.com"}, - {name = "Alexander Soare", email = "alexander.soare159@gmail.com"}, - {name = "Quentin Gallouédec", email = "quentin.gallouedec@ec-lyon.fr"}, - {name = "Adil Zouitine", email = "adilzouitinegm@gmail.com"}, - {name = "Thomas Wolf", email = "thomaswolfcontact@gmail.com"}, + { name = "Rémi Cadène", email = "re.cadene@gmail.com" }, + { name = "Simon Alibert", email = "alibert.sim@gmail.com" }, + { name = "Alexander Soare", email = "alexander.soare159@gmail.com" }, + { name = "Quentin Gallouédec", email = "quentin.gallouedec@ec-lyon.fr" }, + { name = "Adil Zouitine", email = "adilzouitinegm@gmail.com" }, + { name = "Thomas Wolf", email = "thomaswolfcontact@gmail.com" }, + { name = "Steven Palma", email = "imstevenpmwork@ieee.org" }, ] readme = "README.md" -license = {text = "Apache-2.0"} +license = { text = "Apache-2.0" } requires-python = ">=3.10" keywords = ["robotics", "deep learning", "pytorch"] -classifiers=[ +classifiers = [ "Development Status :: 3 - Alpha", "Intended Audience :: Developers", "Intended Audience :: Education", @@ -38,7 +53,7 @@ dependencies = [ "einops>=0.8.0", "flask>=3.0.3", "gdown>=5.1.0", - "gymnasium==0.29.1", # TODO(rcadene, aliberts): Make gym 1.0.0 work + "gymnasium==0.29.1", # TODO(rcadene, aliberts): Make gym 1.0.0 work "h5py>=3.10.0", "huggingface-hub[hf-transfer,cli]>=0.27.1 ; python_version < '4.0'", "hydra-core>=1.3.2", @@ -63,7 +78,9 @@ dependencies = [ [project.optional-dependencies] aloha = ["gym-aloha>=0.1.1 ; python_version < '4.0'"] dev = ["pre-commit>=3.7.0", "debugpy>=1.8.1"] -dora = ["gym-dora @ git+https://github.com/dora-rs/dora-lerobot.git#subdirectory=gym_dora ; python_version < '4.0'"] +dora = [ + "gym-dora @ git+https://github.com/dora-rs/dora-lerobot.git#subdirectory=gym_dora ; python_version < '4.0'", +] dynamixel = ["dynamixel-sdk>=3.7.31", "pynput>=1.7.7"] feetech = ["feetech-servo-sdk>=1.0.0", "pynput>=1.7.7"] intelrealsense = ["pyrealsense2>=2.55.1.6486 ; sys_platform != 'darwin'"] @@ -73,7 +90,7 @@ stretch = [ "hello-robot-stretch-body>=0.7.27 ; python_version < '4.0' and sys_platform == 'linux'", "pyrender @ git+https://github.com/mmatl/pyrender.git ; sys_platform == 'linux'", "pyrealsense2>=2.55.1.6486 ; sys_platform != 'darwin'", - "pynput>=1.7.7" + "pynput>=1.7.7", ] test = ["pytest>=8.1.0", "pytest-cov>=5.0.0", "pyserial>=3.5"] umi = ["imagecodecs>=2024.1.1"] @@ -127,8 +144,8 @@ skips = ["B101", "B311", "B404", "B603"] [tool.typos] default.extend-ignore-re = [ - "(?Rm)^.*(#|//)\\s*spellchecker:disable-line$", # spellchecker:disable-line - "(?s)(#|//)\\s*spellchecker:off.*?\\n\\s*(#|//)\\s*spellchecker:on" # spellchecker: + "(?Rm)^.*(#|//)\\s*spellchecker:disable-line$", # spellchecker:disable-line + "(?s)(#|//)\\s*spellchecker:off.*?\\n\\s*(#|//)\\s*spellchecker:on", # spellchecker: ] default.extend-ignore-identifiers-re = [ # Add individual words here to ignore them diff --git a/tests/__init__.py b/tests/__init__.py index e69de29b..f52df1bd 100644 --- a/tests/__init__.py +++ b/tests/__init__.py @@ -0,0 +1,13 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. diff --git a/tests/fixtures/constants.py b/tests/fixtures/constants.py index 3201dcf2..5e5c762c 100644 --- a/tests/fixtures/constants.py +++ b/tests/fixtures/constants.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. from lerobot.common.constants import HF_LEROBOT_HOME LEROBOT_TEST_DIR = HF_LEROBOT_HOME / "_testing" diff --git a/tests/fixtures/dataset_factories.py b/tests/fixtures/dataset_factories.py index 2259e0e6..531977da 100644 --- a/tests/fixtures/dataset_factories.py +++ b/tests/fixtures/dataset_factories.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import random from functools import partial from pathlib import Path diff --git a/tests/fixtures/files.py b/tests/fixtures/files.py index 4ef12e49..678d1f38 100644 --- a/tests/fixtures/files.py +++ b/tests/fixtures/files.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import json from pathlib import Path diff --git a/tests/fixtures/hub.py b/tests/fixtures/hub.py index ae309cb4..aa2768e4 100644 --- a/tests/fixtures/hub.py +++ b/tests/fixtures/hub.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. from pathlib import Path import datasets diff --git a/tests/fixtures/optimizers.py b/tests/fixtures/optimizers.py index 1a9b9d11..65488566 100644 --- a/tests/fixtures/optimizers.py +++ b/tests/fixtures/optimizers.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import pytest import torch diff --git a/tests/mock_cv2.py b/tests/mock_cv2.py index 806e35ed..b82e7819 100644 --- a/tests/mock_cv2.py +++ b/tests/mock_cv2.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. from functools import cache import numpy as np diff --git a/tests/mock_dynamixel_sdk.py b/tests/mock_dynamixel_sdk.py index a790dff0..ee399f96 100644 --- a/tests/mock_dynamixel_sdk.py +++ b/tests/mock_dynamixel_sdk.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. """Mocked classes and functions from dynamixel_sdk to allow for continuous integration and testing code logic that requires hardware and devices (e.g. robot arms, cameras) diff --git a/tests/mock_pyrealsense2.py b/tests/mock_pyrealsense2.py index 5a39fc2b..c477eb06 100644 --- a/tests/mock_pyrealsense2.py +++ b/tests/mock_pyrealsense2.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import enum import numpy as np diff --git a/tests/mock_scservo_sdk.py b/tests/mock_scservo_sdk.py index ca9233b0..37f6d0d5 100644 --- a/tests/mock_scservo_sdk.py +++ b/tests/mock_scservo_sdk.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. """Mocked classes and functions from dynamixel_sdk to allow for continuous integration and testing code logic that requires hardware and devices (e.g. robot arms, cameras) diff --git a/tests/test_cameras.py b/tests/test_cameras.py index cfefc215..3ab74516 100644 --- a/tests/test_cameras.py +++ b/tests/test_cameras.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. """ Tests for physical cameras and their mocked versions. If the physical camera is not connected to the computer, or not working, diff --git a/tests/test_control_robot.py b/tests/test_control_robot.py index 1796291f..2f24af82 100644 --- a/tests/test_control_robot.py +++ b/tests/test_control_robot.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. """ Tests for physical robots and their mocked versions. If the physical robots are not connected to the computer, or not working, diff --git a/tests/test_delta_timestamps.py b/tests/test_delta_timestamps.py index b27cc1eb..35014642 100644 --- a/tests/test_delta_timestamps.py +++ b/tests/test_delta_timestamps.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. from itertools import accumulate import datasets diff --git a/tests/test_image_writer.py b/tests/test_image_writer.py index c7fc11f2..802fe0d3 100644 --- a/tests/test_image_writer.py +++ b/tests/test_image_writer.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import queue import time from multiprocessing import queues diff --git a/tests/test_io_utils.py b/tests/test_io_utils.py index d14f7adc..c1b776db 100644 --- a/tests/test_io_utils.py +++ b/tests/test_io_utils.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import json from pathlib import Path from typing import Any diff --git a/tests/test_logging_utils.py b/tests/test_logging_utils.py index 72385496..1ba1829e 100644 --- a/tests/test_logging_utils.py +++ b/tests/test_logging_utils.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import pytest from lerobot.common.utils.logging_utils import AverageMeter, MetricsTracker diff --git a/tests/test_motors.py b/tests/test_motors.py index 75793636..da7a5c54 100644 --- a/tests/test_motors.py +++ b/tests/test_motors.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. """ Tests for physical motors and their mocked versions. If the physical motors are not connected to the computer, or not working, diff --git a/tests/test_optimizers.py b/tests/test_optimizers.py index cf5c5b18..997e14fe 100644 --- a/tests/test_optimizers.py +++ b/tests/test_optimizers.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import pytest import torch diff --git a/tests/test_random_utils.py b/tests/test_random_utils.py index 8eee2b68..daf08a89 100644 --- a/tests/test_random_utils.py +++ b/tests/test_random_utils.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import random import numpy as np diff --git a/tests/test_robots.py b/tests/test_robots.py index c5734a4c..71343eba 100644 --- a/tests/test_robots.py +++ b/tests/test_robots.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. """ Tests for physical robots and their mocked versions. If the physical robots are not connected to the computer, or not working, diff --git a/tests/test_schedulers.py b/tests/test_schedulers.py index e871fee1..17637663 100644 --- a/tests/test_schedulers.py +++ b/tests/test_schedulers.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. from torch.optim.lr_scheduler import LambdaLR from lerobot.common.constants import SCHEDULER_STATE diff --git a/tests/test_train_utils.py b/tests/test_train_utils.py index d6ed0063..b78f6e49 100644 --- a/tests/test_train_utils.py +++ b/tests/test_train_utils.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. from pathlib import Path from unittest.mock import Mock, patch diff --git a/tests/test_utils.py b/tests/test_utils.py index b2f14694..2d0efc5a 100644 --- a/tests/test_utils.py +++ b/tests/test_utils.py @@ -1,3 +1,16 @@ +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import torch from datasets import Dataset From 57ae5098236d3a074c64f3340089a70a151c6922 Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Thu, 6 Mar 2025 09:43:27 +0100 Subject: [PATCH 09/19] Revert "docs: update installation instructions to use uv instead of conda" (#827) --- README.md | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/README.md b/README.md index 454c7e5d..9debf9d1 100644 --- a/README.md +++ b/README.md @@ -92,20 +92,15 @@ git clone https://github.com/huggingface/lerobot.git cd lerobot ``` -Create a virtual environment with Python 3.10 and activate it using [`uv`](https://github.com/astral-sh/uv): +Create a virtual environment with Python 3.10 and activate it, e.g. with [`miniconda`](https://docs.anaconda.com/free/miniconda/index.html): ```bash -# Install uv if you haven't already -curl -LsSf https://astral.sh/uv/install.sh | sh - -# Create and activate virtual environment with Python 3.10 -uv venv .venv --python=3.10 -source .venv/bin/activate # On Unix/macOS -# .venv\Scripts\activate # On Windows +conda create -y -n lerobot python=3.10 +conda activate lerobot ``` Install 🤗 LeRobot: ```bash -uv pip install -e . +pip install -e . ``` > **NOTE:** Depending on your platform, If you encounter any build errors during this step From 0b8205a8a08d0510599fcfd73b1a1d4066606d6a Mon Sep 17 00:00:00 2001 From: Steven Palma Date: Thu, 6 Mar 2025 09:44:21 +0100 Subject: [PATCH 10/19] chore(doc): add star history graph to the README.md (#815) --- README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/README.md b/README.md index 9debf9d1..b16e3469 100644 --- a/README.md +++ b/README.md @@ -384,3 +384,6 @@ Additionally, if you are using any of the particular policy architecture, pretra year={2024} } ``` +## Star History + +[![Star History Chart](https://api.star-history.com/svg?repos=huggingface/lerobot&type=Timeline)](https://star-history.com/#huggingface/lerobot&Timeline) From 10706ed75344916c70af814ce39b5e58a73eab9d Mon Sep 17 00:00:00 2001 From: Harsimrat Sandhawalia <10599550+sandhawalia@users.noreply.github.com> Date: Thu, 6 Mar 2025 10:27:29 +0100 Subject: [PATCH 11/19] Support for discrete actions (#810) --- lerobot/scripts/visualize_dataset_html.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lerobot/scripts/visualize_dataset_html.py b/lerobot/scripts/visualize_dataset_html.py index d5825aa6..f944144a 100644 --- a/lerobot/scripts/visualize_dataset_html.py +++ b/lerobot/scripts/visualize_dataset_html.py @@ -234,7 +234,7 @@ def get_episode_data(dataset: LeRobotDataset | IterableNamespace, episode_index) This file will be loaded by Dygraph javascript to plot data in real time.""" columns = [] - selected_columns = [col for col, ft in dataset.features.items() if ft["dtype"] == "float32"] + selected_columns = [col for col, ft in dataset.features.items() if ft["dtype"] in ["float32", "int32"]] selected_columns.remove("timestamp") ignored_columns = [] From 5e9473806c78a969f13e2faf941ba1b2950649c4 Mon Sep 17 00:00:00 2001 From: Steven Palma Date: Thu, 6 Mar 2025 17:59:28 +0100 Subject: [PATCH 12/19] refactor(config): Move device & amp args to PreTrainedConfig (#812) Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> --- Makefile | 18 +++++----- lerobot/common/policies/factory.py | 9 ++--- .../common/policies/pi0/configuration_pi0.py | 1 + .../pi0/conversion_scripts/benchmark.py | 2 +- .../conversion_scripts/compare_with_jax.py | 2 +- lerobot/common/policies/pretrained.py | 7 ++-- .../common/robot_devices/control_configs.py | 29 ---------------- lerobot/common/robot_devices/control_utils.py | 16 +++------ lerobot/common/utils/utils.py | 5 ++- lerobot/configs/eval.py | 33 ------------------- lerobot/configs/policies.py | 18 ++++++++++ lerobot/configs/train.py | 18 ---------- lerobot/scripts/control_robot.py | 4 +-- lerobot/scripts/eval.py | 6 ++-- lerobot/scripts/train.py | 12 ++++--- tests/scripts/save_policy_to_safetensors.py | 3 +- tests/test_control_robot.py | 6 ++-- tests/test_datasets.py | 3 +- tests/test_policies.py | 6 ++-- 19 files changed, 62 insertions(+), 136 deletions(-) diff --git a/Makefile b/Makefile index 68f07b21..c82483cc 100644 --- a/Makefile +++ b/Makefile @@ -47,6 +47,7 @@ test-act-ete-train: --policy.dim_model=64 \ --policy.n_action_steps=20 \ --policy.chunk_size=20 \ + --policy.device=$(DEVICE) \ --env.type=aloha \ --env.episode_length=5 \ --dataset.repo_id=lerobot/aloha_sim_transfer_cube_human \ @@ -61,7 +62,6 @@ test-act-ete-train: --save_checkpoint=true \ --log_freq=1 \ --wandb.enable=false \ - --device=$(DEVICE) \ --output_dir=tests/outputs/act/ test-act-ete-train-resume: @@ -72,11 +72,11 @@ test-act-ete-train-resume: test-act-ete-eval: python lerobot/scripts/eval.py \ --policy.path=tests/outputs/act/checkpoints/000004/pretrained_model \ + --policy.device=$(DEVICE) \ --env.type=aloha \ --env.episode_length=5 \ --eval.n_episodes=1 \ - --eval.batch_size=1 \ - --device=$(DEVICE) + --eval.batch_size=1 test-diffusion-ete-train: python lerobot/scripts/train.py \ @@ -84,6 +84,7 @@ test-diffusion-ete-train: --policy.down_dims='[64,128,256]' \ --policy.diffusion_step_embed_dim=32 \ --policy.num_inference_steps=10 \ + --policy.device=$(DEVICE) \ --env.type=pusht \ --env.episode_length=5 \ --dataset.repo_id=lerobot/pusht \ @@ -98,21 +99,21 @@ test-diffusion-ete-train: --save_freq=2 \ --log_freq=1 \ --wandb.enable=false \ - --device=$(DEVICE) \ --output_dir=tests/outputs/diffusion/ test-diffusion-ete-eval: python lerobot/scripts/eval.py \ --policy.path=tests/outputs/diffusion/checkpoints/000002/pretrained_model \ + --policy.device=$(DEVICE) \ --env.type=pusht \ --env.episode_length=5 \ --eval.n_episodes=1 \ - --eval.batch_size=1 \ - --device=$(DEVICE) + --eval.batch_size=1 test-tdmpc-ete-train: python lerobot/scripts/train.py \ --policy.type=tdmpc \ + --policy.device=$(DEVICE) \ --env.type=xarm \ --env.task=XarmLift-v0 \ --env.episode_length=5 \ @@ -128,15 +129,14 @@ test-tdmpc-ete-train: --save_freq=2 \ --log_freq=1 \ --wandb.enable=false \ - --device=$(DEVICE) \ --output_dir=tests/outputs/tdmpc/ test-tdmpc-ete-eval: python lerobot/scripts/eval.py \ --policy.path=tests/outputs/tdmpc/checkpoints/000002/pretrained_model \ + --policy.device=$(DEVICE) \ --env.type=xarm \ --env.episode_length=5 \ --env.task=XarmLift-v0 \ --eval.n_episodes=1 \ - --eval.batch_size=1 \ - --device=$(DEVICE) + --eval.batch_size=1 diff --git a/lerobot/common/policies/factory.py b/lerobot/common/policies/factory.py index cd440f7a..5d2f6cb5 100644 --- a/lerobot/common/policies/factory.py +++ b/lerobot/common/policies/factory.py @@ -16,7 +16,6 @@ import logging -import torch from torch import nn from lerobot.common.datasets.lerobot_dataset import LeRobotDatasetMetadata @@ -76,7 +75,6 @@ def make_policy_config(policy_type: str, **kwargs) -> PreTrainedConfig: def make_policy( cfg: PreTrainedConfig, - device: str | torch.device, ds_meta: LeRobotDatasetMetadata | None = None, env_cfg: EnvConfig | None = None, ) -> PreTrainedPolicy: @@ -88,7 +86,6 @@ def make_policy( Args: cfg (PreTrainedConfig): The config of the policy to make. If `pretrained_path` is set, the policy will be loaded with the weights from that path. - device (str): the device to load the policy onto. ds_meta (LeRobotDatasetMetadata | None, optional): Dataset metadata to take input/output shapes and statistics to use for (un)normalization of inputs/outputs in the policy. Defaults to None. env_cfg (EnvConfig | None, optional): The config of a gym environment to parse features from. Must be @@ -96,7 +93,7 @@ def make_policy( Raises: ValueError: Either ds_meta or env and env_cfg must be provided. - NotImplementedError: if the policy.type is 'vqbet' and the device 'mps' (due to an incompatibility) + NotImplementedError: if the policy.type is 'vqbet' and the policy device 'mps' (due to an incompatibility) Returns: PreTrainedPolicy: _description_ @@ -111,7 +108,7 @@ def make_policy( # https://github.com/pytorch/pytorch/issues/77764. As a temporary fix, you can set the environment # variable `PYTORCH_ENABLE_MPS_FALLBACK=1` to use the CPU as a fallback for this op. WARNING: this will be # slower than running natively on MPS. - if cfg.type == "vqbet" and str(device) == "mps": + if cfg.type == "vqbet" and cfg.device == "mps": raise NotImplementedError( "Current implementation of VQBeT does not support `mps` backend. " "Please use `cpu` or `cuda` backend." @@ -145,7 +142,7 @@ def make_policy( # Make a fresh policy. policy = policy_cls(**kwargs) - policy.to(device) + policy.to(cfg.device) assert isinstance(policy, nn.Module) # policy = torch.compile(policy, mode="reduce-overhead") diff --git a/lerobot/common/policies/pi0/configuration_pi0.py b/lerobot/common/policies/pi0/configuration_pi0.py index ac3a62a8..8c7cc130 100644 --- a/lerobot/common/policies/pi0/configuration_pi0.py +++ b/lerobot/common/policies/pi0/configuration_pi0.py @@ -90,6 +90,7 @@ class PI0Config(PreTrainedConfig): def __post_init__(self): super().__post_init__() + # TODO(Steven): Validate device and amp? in all policy configs? """Input validation (not exhaustive).""" if self.n_action_steps > self.chunk_size: raise ValueError( diff --git a/lerobot/common/policies/pi0/conversion_scripts/benchmark.py b/lerobot/common/policies/pi0/conversion_scripts/benchmark.py index 35b9a45b..cb3c0e9b 100644 --- a/lerobot/common/policies/pi0/conversion_scripts/benchmark.py +++ b/lerobot/common/policies/pi0/conversion_scripts/benchmark.py @@ -45,7 +45,7 @@ def main(): cfg = PreTrainedConfig.from_pretrained(ckpt_torch_dir) cfg.pretrained_path = ckpt_torch_dir - policy = make_policy(cfg, device, ds_meta=dataset.meta) + policy = make_policy(cfg, ds_meta=dataset.meta) # policy = torch.compile(policy, mode="reduce-overhead") diff --git a/lerobot/common/policies/pi0/conversion_scripts/compare_with_jax.py b/lerobot/common/policies/pi0/conversion_scripts/compare_with_jax.py index ceb8ada0..6bd7c91f 100644 --- a/lerobot/common/policies/pi0/conversion_scripts/compare_with_jax.py +++ b/lerobot/common/policies/pi0/conversion_scripts/compare_with_jax.py @@ -101,7 +101,7 @@ def main(): cfg = PreTrainedConfig.from_pretrained(ckpt_torch_dir) cfg.pretrained_path = ckpt_torch_dir - policy = make_policy(cfg, device, dataset_meta) + policy = make_policy(cfg, dataset_meta) # loss_dict = policy.forward(batch, noise=noise, time=time_beta) # loss_dict["loss"].backward() diff --git a/lerobot/common/policies/pretrained.py b/lerobot/common/policies/pretrained.py index 549ea92b..da4ef157 100644 --- a/lerobot/common/policies/pretrained.py +++ b/lerobot/common/policies/pretrained.py @@ -86,7 +86,6 @@ class PreTrainedPolicy(nn.Module, HubMixin, abc.ABC): cache_dir: str | Path | None = None, local_files_only: bool = False, revision: str | None = None, - map_location: str = "cpu", strict: bool = False, **kwargs, ) -> T: @@ -111,7 +110,7 @@ class PreTrainedPolicy(nn.Module, HubMixin, abc.ABC): if os.path.isdir(model_id): print("Loading weights from local directory") model_file = os.path.join(model_id, SAFETENSORS_SINGLE_FILE) - policy = cls._load_as_safetensor(instance, model_file, map_location, strict) + policy = cls._load_as_safetensor(instance, model_file, config.device, strict) else: try: model_file = hf_hub_download( @@ -125,13 +124,13 @@ class PreTrainedPolicy(nn.Module, HubMixin, abc.ABC): token=token, local_files_only=local_files_only, ) - policy = cls._load_as_safetensor(instance, model_file, map_location, strict) + policy = cls._load_as_safetensor(instance, model_file, config.device, strict) except HfHubHTTPError as e: raise FileNotFoundError( f"{SAFETENSORS_SINGLE_FILE} not found on the HuggingFace Hub in {model_id}" ) from e - policy.to(map_location) + policy.to(config.device) policy.eval() return policy diff --git a/lerobot/common/robot_devices/control_configs.py b/lerobot/common/robot_devices/control_configs.py index 01908472..0ecd8683 100644 --- a/lerobot/common/robot_devices/control_configs.py +++ b/lerobot/common/robot_devices/control_configs.py @@ -12,17 +12,14 @@ # See the License for the specific language governing permissions and # limitations under the License. -import logging from dataclasses import dataclass from pathlib import Path import draccus from lerobot.common.robot_devices.robots.configs import RobotConfig -from lerobot.common.utils.utils import auto_select_torch_device, is_amp_available, is_torch_device_available from lerobot.configs import parser from lerobot.configs.policies import PreTrainedConfig -from lerobot.configs.train import TrainPipelineConfig @dataclass @@ -57,11 +54,6 @@ class RecordControlConfig(ControlConfig): # Root directory where the dataset will be stored (e.g. 'dataset/path'). root: str | Path | None = None policy: PreTrainedConfig | None = None - # TODO(rcadene, aliberts): By default, use device and use_amp values from policy checkpoint. - device: str | None = None # cuda | cpu | mps - # `use_amp` determines whether to use Automatic Mixed Precision (AMP) for training and evaluation. With AMP, - # automatic gradient scaling is used. - use_amp: bool | None = None # Limit the frames per second. By default, uses the policy fps. fps: int | None = None # Number of seconds before starting data collection. It allows the robot devices to warmup and synchronize. @@ -104,27 +96,6 @@ class RecordControlConfig(ControlConfig): self.policy = PreTrainedConfig.from_pretrained(policy_path, cli_overrides=cli_overrides) self.policy.pretrained_path = policy_path - # When no device or use_amp are given, use the one from training config. - if self.device is None or self.use_amp is None: - train_cfg = TrainPipelineConfig.from_pretrained(policy_path) - if self.device is None: - self.device = train_cfg.device - if self.use_amp is None: - self.use_amp = train_cfg.use_amp - - # Automatically switch to available device if necessary - if not is_torch_device_available(self.device): - auto_device = auto_select_torch_device() - logging.warning(f"Device '{self.device}' is not available. Switching to '{auto_device}'.") - self.device = auto_device - - # Automatically deactivate AMP if necessary - if self.use_amp and not is_amp_available(self.device): - logging.warning( - f"Automatic Mixed Precision (amp) is not available on device '{self.device}'. Deactivating AMP." - ) - self.use_amp = False - @ControlConfig.register_subclass("replay") @dataclass diff --git a/lerobot/common/robot_devices/control_utils.py b/lerobot/common/robot_devices/control_utils.py index 4782959a..78a8c6a6 100644 --- a/lerobot/common/robot_devices/control_utils.py +++ b/lerobot/common/robot_devices/control_utils.py @@ -32,6 +32,7 @@ from termcolor import colored from lerobot.common.datasets.image_writer import safe_stop_image_writer from lerobot.common.datasets.lerobot_dataset import LeRobotDataset from lerobot.common.datasets.utils import get_features_from_robot +from lerobot.common.policies.pretrained import PreTrainedPolicy from lerobot.common.robot_devices.robots.utils import Robot from lerobot.common.robot_devices.utils import busy_wait from lerobot.common.utils.utils import get_safe_torch_device, has_method @@ -193,8 +194,6 @@ def record_episode( episode_time_s, display_cameras, policy, - device, - use_amp, fps, single_task, ): @@ -205,8 +204,6 @@ def record_episode( dataset=dataset, events=events, policy=policy, - device=device, - use_amp=use_amp, fps=fps, teleoperate=policy is None, single_task=single_task, @@ -221,9 +218,7 @@ def control_loop( display_cameras=False, dataset: LeRobotDataset | None = None, events=None, - policy=None, - device: torch.device | str | None = None, - use_amp: bool | None = None, + policy: PreTrainedPolicy = None, fps: int | None = None, single_task: str | None = None, ): @@ -246,9 +241,6 @@ def control_loop( if dataset is not None and fps is not None and dataset.fps != fps: raise ValueError(f"The dataset fps should be equal to requested fps ({dataset['fps']} != {fps}).") - if isinstance(device, str): - device = get_safe_torch_device(device) - timestamp = 0 start_episode_t = time.perf_counter() while timestamp < control_time_s: @@ -260,7 +252,9 @@ def control_loop( observation = robot.capture_observation() if policy is not None: - pred_action = predict_action(observation, policy, device, use_amp) + pred_action = predict_action( + observation, policy, get_safe_torch_device(policy.config.device), policy.config.use_amp + ) # Action can eventually be clipped using `max_relative_target`, # so action actually sent is saved in the dataset. action = robot.send_action(pred_action) diff --git a/lerobot/common/utils/utils.py b/lerobot/common/utils/utils.py index cd26f04b..563a7b81 100644 --- a/lerobot/common/utils/utils.py +++ b/lerobot/common/utils/utils.py @@ -51,8 +51,10 @@ def auto_select_torch_device() -> torch.device: return torch.device("cpu") +# TODO(Steven): Remove log. log shouldn't be an argument, this should be handled by the logger level def get_safe_torch_device(try_device: str, log: bool = False) -> torch.device: """Given a string, return a torch.device with checks on whether the device is available.""" + try_device = str(try_device) match try_device: case "cuda": assert torch.cuda.is_available() @@ -85,6 +87,7 @@ def get_safe_dtype(dtype: torch.dtype, device: str | torch.device): def is_torch_device_available(try_device: str) -> bool: + try_device = str(try_device) # Ensure try_device is a string if try_device == "cuda": return torch.cuda.is_available() elif try_device == "mps": @@ -92,7 +95,7 @@ def is_torch_device_available(try_device: str) -> bool: elif try_device == "cpu": return True else: - raise ValueError(f"Unknown device '{try_device}.") + raise ValueError(f"Unknown device {try_device}. Supported devices are: cuda, mps or cpu.") def is_amp_available(device: str): diff --git a/lerobot/configs/eval.py b/lerobot/configs/eval.py index eb2a6df9..16b35291 100644 --- a/lerobot/configs/eval.py +++ b/lerobot/configs/eval.py @@ -18,11 +18,9 @@ from dataclasses import dataclass, field from pathlib import Path from lerobot.common import envs, policies # noqa: F401 -from lerobot.common.utils.utils import auto_select_torch_device, is_amp_available, is_torch_device_available from lerobot.configs import parser from lerobot.configs.default import EvalConfig from lerobot.configs.policies import PreTrainedConfig -from lerobot.configs.train import TrainPipelineConfig @dataclass @@ -35,11 +33,6 @@ class EvalPipelineConfig: policy: PreTrainedConfig | None = None output_dir: Path | None = None job_name: str | None = None - # TODO(rcadene, aliberts): By default, use device and use_amp values from policy checkpoint. - device: str | None = None # cuda | cpu | mps - # `use_amp` determines whether to use Automatic Mixed Precision (AMP) for training and evaluation. With AMP, - # automatic gradient scaling is used. - use_amp: bool = False seed: int | None = 1000 def __post_init__(self): @@ -50,27 +43,6 @@ class EvalPipelineConfig: self.policy = PreTrainedConfig.from_pretrained(policy_path, cli_overrides=cli_overrides) self.policy.pretrained_path = policy_path - # When no device or use_amp are given, use the one from training config. - if self.device is None or self.use_amp is None: - train_cfg = TrainPipelineConfig.from_pretrained(policy_path) - if self.device is None: - self.device = train_cfg.device - if self.use_amp is None: - self.use_amp = train_cfg.use_amp - - # Automatically switch to available device if necessary - if not is_torch_device_available(self.device): - auto_device = auto_select_torch_device() - logging.warning(f"Device '{self.device}' is not available. Switching to '{auto_device}'.") - self.device = auto_device - - # Automatically deactivate AMP if necessary - if self.use_amp and not is_amp_available(self.device): - logging.warning( - f"Automatic Mixed Precision (amp) is not available on device '{self.device}'. Deactivating AMP." - ) - self.use_amp = False - else: logging.warning( "No pretrained path was provided, evaluated policy will be built from scratch (random weights)." @@ -87,11 +59,6 @@ class EvalPipelineConfig: eval_dir = f"{now:%Y-%m-%d}/{now:%H-%M-%S}_{self.job_name}" self.output_dir = Path("outputs/eval") / eval_dir - if self.device is None: - raise ValueError("Set one of the following device: cuda, cpu or mps") - elif self.device == "cuda" and self.use_amp is None: - raise ValueError("Set 'use_amp' to True or False.") - @classmethod def __get_path_fields__(cls) -> list[str]: """This enables the parser to load config from the policy using `--policy.path=local/dir`""" diff --git a/lerobot/configs/policies.py b/lerobot/configs/policies.py index 4f52b16c..022d1fb5 100644 --- a/lerobot/configs/policies.py +++ b/lerobot/configs/policies.py @@ -12,6 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. import abc +import logging import os from dataclasses import dataclass, field from pathlib import Path @@ -25,6 +26,7 @@ from huggingface_hub.errors import HfHubHTTPError from lerobot.common.optim.optimizers import OptimizerConfig from lerobot.common.optim.schedulers import LRSchedulerConfig from lerobot.common.utils.hub import HubMixin +from lerobot.common.utils.utils import auto_select_torch_device, is_amp_available, is_torch_device_available from lerobot.configs.types import FeatureType, NormalizationMode, PolicyFeature # Generic variable that is either PreTrainedConfig or a subclass thereof @@ -53,8 +55,24 @@ class PreTrainedConfig(draccus.ChoiceRegistry, HubMixin, abc.ABC): input_features: dict[str, PolicyFeature] = field(default_factory=dict) output_features: dict[str, PolicyFeature] = field(default_factory=dict) + device: str | None = None # cuda | cpu | mp + # `use_amp` determines whether to use Automatic Mixed Precision (AMP) for training and evaluation. With AMP, + # automatic gradient scaling is used. + use_amp: bool = False + def __post_init__(self): self.pretrained_path = None + if not self.device or not is_torch_device_available(self.device): + auto_device = auto_select_torch_device() + logging.warning(f"Device '{self.device}' is not available. Switching to '{auto_device}'.") + self.device = auto_device.type + + # Automatically deactivate AMP if necessary + if self.use_amp and not is_amp_available(self.device): + logging.warning( + f"Automatic Mixed Precision (amp) is not available on device '{self.device}'. Deactivating AMP." + ) + self.use_amp = False @property def type(self) -> str: diff --git a/lerobot/configs/train.py b/lerobot/configs/train.py index 33e98b88..2b147a5b 100644 --- a/lerobot/configs/train.py +++ b/lerobot/configs/train.py @@ -12,7 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. import datetime as dt -import logging import os from dataclasses import dataclass, field from pathlib import Path @@ -26,7 +25,6 @@ from lerobot.common import envs from lerobot.common.optim import OptimizerConfig from lerobot.common.optim.schedulers import LRSchedulerConfig from lerobot.common.utils.hub import HubMixin -from lerobot.common.utils.utils import auto_select_torch_device, is_amp_available from lerobot.configs import parser from lerobot.configs.default import DatasetConfig, EvalConfig, WandBConfig from lerobot.configs.policies import PreTrainedConfig @@ -48,10 +46,6 @@ class TrainPipelineConfig(HubMixin): # Note that when resuming a run, the default behavior is to use the configuration from the checkpoint, # regardless of what's provided with the training command at the time of resumption. resume: bool = False - device: str | None = None # cuda | cpu | mp - # `use_amp` determines whether to use Automatic Mixed Precision (AMP) for training and evaluation. With AMP, - # automatic gradient scaling is used. - use_amp: bool = False # `seed` is used for training (eg: model initialization, dataset shuffling) # AND for the evaluation environments. seed: int | None = 1000 @@ -74,18 +68,6 @@ class TrainPipelineConfig(HubMixin): self.checkpoint_path = None def validate(self): - if not self.device: - logging.warning("No device specified, trying to infer device automatically") - device = auto_select_torch_device() - self.device = device.type - - # Automatically deactivate AMP if necessary - if self.use_amp and not is_amp_available(self.device): - logging.warning( - f"Automatic Mixed Precision (amp) is not available on device '{self.device}'. Deactivating AMP." - ) - self.use_amp = False - # HACK: We parse again the cli args here to get the pretrained paths if there was some. policy_path = parser.get_path_arg("policy") if policy_path: diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index 3a82e5c3..3c3c43f9 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -267,7 +267,7 @@ def record( ) # Load pretrained policy - policy = None if cfg.policy is None else make_policy(cfg.policy, cfg.device, ds_meta=dataset.meta) + policy = None if cfg.policy is None else make_policy(cfg.policy, ds_meta=dataset.meta) if not robot.is_connected: robot.connect() @@ -298,8 +298,6 @@ def record( episode_time_s=cfg.episode_time_s, display_cameras=cfg.display_cameras, policy=policy, - device=cfg.device, - use_amp=cfg.use_amp, fps=cfg.fps, single_task=cfg.single_task, ) diff --git a/lerobot/scripts/eval.py b/lerobot/scripts/eval.py index 47225993..d7a4201f 100644 --- a/lerobot/scripts/eval.py +++ b/lerobot/scripts/eval.py @@ -458,7 +458,7 @@ def eval_main(cfg: EvalPipelineConfig): logging.info(pformat(asdict(cfg))) # Check device is available - device = get_safe_torch_device(cfg.device, log=True) + device = get_safe_torch_device(cfg.policy.device, log=True) torch.backends.cudnn.benchmark = True torch.backends.cuda.matmul.allow_tf32 = True @@ -470,14 +470,14 @@ def eval_main(cfg: EvalPipelineConfig): env = make_env(cfg.env, n_envs=cfg.eval.batch_size, use_async_envs=cfg.eval.use_async_envs) logging.info("Making policy.") + policy = make_policy( cfg=cfg.policy, - device=device, env_cfg=cfg.env, ) policy.eval() - with torch.no_grad(), torch.autocast(device_type=device.type) if cfg.use_amp else nullcontext(): + with torch.no_grad(), torch.autocast(device_type=device.type) if cfg.policy.use_amp else nullcontext(): info = eval_policy( env, policy, diff --git a/lerobot/scripts/train.py b/lerobot/scripts/train.py index e36c697a..f2b1e29e 100644 --- a/lerobot/scripts/train.py +++ b/lerobot/scripts/train.py @@ -120,7 +120,7 @@ def train(cfg: TrainPipelineConfig): set_seed(cfg.seed) # Check device is available - device = get_safe_torch_device(cfg.device, log=True) + device = get_safe_torch_device(cfg.policy.device, log=True) torch.backends.cudnn.benchmark = True torch.backends.cuda.matmul.allow_tf32 = True @@ -138,13 +138,12 @@ def train(cfg: TrainPipelineConfig): logging.info("Creating policy") policy = make_policy( cfg=cfg.policy, - device=device, ds_meta=dataset.meta, ) logging.info("Creating optimizer and scheduler") optimizer, lr_scheduler = make_optimizer_and_scheduler(cfg, policy) - grad_scaler = GradScaler(device, enabled=cfg.use_amp) + grad_scaler = GradScaler(device.type, enabled=cfg.policy.use_amp) step = 0 # number of policy updates (forward + backward + optim) @@ -218,7 +217,7 @@ def train(cfg: TrainPipelineConfig): cfg.optimizer.grad_clip_norm, grad_scaler=grad_scaler, lr_scheduler=lr_scheduler, - use_amp=cfg.use_amp, + use_amp=cfg.policy.use_amp, ) # Note: eval and checkpoint happens *after* the `step`th training update has completed, so we @@ -249,7 +248,10 @@ def train(cfg: TrainPipelineConfig): if cfg.env and is_eval_step: step_id = get_step_identifier(step, cfg.steps) logging.info(f"Eval policy at step {step}") - with torch.no_grad(), torch.autocast(device_type=device.type) if cfg.use_amp else nullcontext(): + with ( + torch.no_grad(), + torch.autocast(device_type=device.type) if cfg.policy.use_amp else nullcontext(), + ): eval_info = eval_policy( eval_env, policy, diff --git a/tests/scripts/save_policy_to_safetensors.py b/tests/scripts/save_policy_to_safetensors.py index 03726163..60fd9fc0 100644 --- a/tests/scripts/save_policy_to_safetensors.py +++ b/tests/scripts/save_policy_to_safetensors.py @@ -33,12 +33,11 @@ def get_policy_stats(ds_repo_id: str, policy_name: str, policy_kwargs: dict): # TODO(rcadene, aliberts): remove dataset download dataset=DatasetConfig(repo_id=ds_repo_id, episodes=[0]), policy=make_policy_config(policy_name, **policy_kwargs), - device="cpu", ) train_cfg.validate() # Needed for auto-setting some parameters dataset = make_dataset(train_cfg) - policy = make_policy(train_cfg.policy, ds_meta=dataset.meta, device=train_cfg.device) + policy = make_policy(train_cfg.policy, ds_meta=dataset.meta) policy.train() optimizer, _ = make_optimizer_and_scheduler(train_cfg, policy) diff --git a/tests/test_control_robot.py b/tests/test_control_robot.py index 2f24af82..02041e30 100644 --- a/tests/test_control_robot.py +++ b/tests/test_control_robot.py @@ -52,7 +52,7 @@ from lerobot.common.robot_devices.control_configs import ( from lerobot.configs.policies import PreTrainedConfig from lerobot.scripts.control_robot import calibrate, record, replay, teleoperate from tests.test_robots import make_robot -from tests.utils import DEVICE, TEST_ROBOT_TYPES, mock_calibration_dir, require_robot +from tests.utils import TEST_ROBOT_TYPES, mock_calibration_dir, require_robot @pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @@ -184,7 +184,7 @@ def test_record_and_replay_and_policy(tmp_path, request, robot_type, mock): replay(robot, replay_cfg) policy_cfg = ACTConfig() - policy = make_policy(policy_cfg, ds_meta=dataset.meta, device=DEVICE) + policy = make_policy(policy_cfg, ds_meta=dataset.meta) out_dir = tmp_path / "logger" @@ -229,8 +229,6 @@ def test_record_and_replay_and_policy(tmp_path, request, robot_type, mock): display_cameras=False, play_sounds=False, num_image_writer_processes=num_image_writer_processes, - device=DEVICE, - use_amp=False, ) rec_eval_cfg.policy = PreTrainedConfig.from_pretrained(pretrained_policy_path) diff --git a/tests/test_datasets.py b/tests/test_datasets.py index 003a60c9..0deaceba 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -45,7 +45,7 @@ from lerobot.common.robot_devices.robots.utils import make_robot from lerobot.configs.default import DatasetConfig from lerobot.configs.train import TrainPipelineConfig from tests.fixtures.constants import DUMMY_CHW, DUMMY_HWC, DUMMY_REPO_ID -from tests.utils import DEVICE, require_x86_64_kernel +from tests.utils import require_x86_64_kernel @pytest.fixture @@ -349,7 +349,6 @@ def test_factory(env_name, repo_id, policy_name): dataset=DatasetConfig(repo_id=repo_id, episodes=[0]), env=make_env_config(env_name), policy=make_policy_config(policy_name), - device=DEVICE, ) dataset = make_dataset(cfg) diff --git a/tests/test_policies.py b/tests/test_policies.py index 9dab6176..f8e7359c 100644 --- a/tests/test_policies.py +++ b/tests/test_policies.py @@ -143,12 +143,11 @@ def test_policy(ds_repo_id, env_name, env_kwargs, policy_name, policy_kwargs): dataset=DatasetConfig(repo_id=ds_repo_id, episodes=[0]), policy=make_policy_config(policy_name, **policy_kwargs), env=make_env_config(env_name, **env_kwargs), - device=DEVICE, ) # Check that we can make the policy object. dataset = make_dataset(train_cfg) - policy = make_policy(train_cfg.policy, ds_meta=dataset.meta, device=DEVICE) + policy = make_policy(train_cfg.policy, ds_meta=dataset.meta) assert isinstance(policy, PreTrainedPolicy) # Check that we run select_actions and get the appropriate output. @@ -214,7 +213,6 @@ def test_act_backbone_lr(): # TODO(rcadene, aliberts): remove dataset download dataset=DatasetConfig(repo_id="lerobot/aloha_sim_insertion_scripted", episodes=[0]), policy=make_policy_config("act", optimizer_lr=0.01, optimizer_lr_backbone=0.001), - device=DEVICE, ) cfg.validate() # Needed for auto-setting some parameters @@ -222,7 +220,7 @@ def test_act_backbone_lr(): assert cfg.policy.optimizer_lr_backbone == 0.001 dataset = make_dataset(cfg) - policy = make_policy(cfg.policy, device=DEVICE, ds_meta=dataset.meta) + policy = make_policy(cfg.policy, ds_meta=dataset.meta) optimizer, _ = make_optimizer_and_scheduler(cfg, policy) assert len(optimizer.param_groups) == 2 assert optimizer.param_groups[0]["lr"] == cfg.policy.optimizer_lr From 25c63ccf638740f778dff0b5562f81edb074fc20 Mon Sep 17 00:00:00 2001 From: Mathias Wulfman <101942083+mwulfman@users.noreply.github.com> Date: Fri, 7 Mar 2025 13:21:11 +0100 Subject: [PATCH 13/19] :bug: Remove `map_location=device` that no longer exists when loading DiffusionPolicy from_pretained after commit 5e94738 (#830) Co-authored-by: Mathias Wulfman --- examples/2_evaluate_pretrained_policy.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/2_evaluate_pretrained_policy.py b/examples/2_evaluate_pretrained_policy.py index bf3c442a..edbbad38 100644 --- a/examples/2_evaluate_pretrained_policy.py +++ b/examples/2_evaluate_pretrained_policy.py @@ -44,7 +44,7 @@ pretrained_policy_path = "lerobot/diffusion_pusht" # OR a path to a local outputs/train folder. # pretrained_policy_path = Path("outputs/train/example_pusht_diffusion") -policy = DiffusionPolicy.from_pretrained(pretrained_policy_path, map_location=device) +policy = DiffusionPolicy.from_pretrained(pretrained_policy_path) # Initialize evaluation environment to render two observation types: # an image of the scene and state/position of the agent. The environment From 074f0ac8fec8483b83a04654b09e685274ee0c80 Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Fri, 7 Mar 2025 13:21:58 +0100 Subject: [PATCH 14/19] Fix gpu nightly (#829) --- tests/test_policies.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/tests/test_policies.py b/tests/test_policies.py index f8e7359c..7df79c1d 100644 --- a/tests/test_policies.py +++ b/tests/test_policies.py @@ -252,10 +252,11 @@ def test_save_and_load_pretrained(dummy_dataset_metadata, tmp_path, policy_name: key: ft for key, ft in features.items() if key not in policy_cfg.output_features } policy = policy_cls(policy_cfg) + policy.to(policy_cfg.device) save_dir = tmp_path / f"test_save_and_load_pretrained_{policy_cls.__name__}" policy.save_pretrained(save_dir) - policy_ = policy_cls.from_pretrained(save_dir, config=policy_cfg) - assert all(torch.equal(p, p_) for p, p_ in zip(policy.parameters(), policy_.parameters(), strict=True)) + loaded_policy = policy_cls.from_pretrained(save_dir, config=policy_cfg) + torch.testing.assert_close(list(policy.parameters()), list(loaded_policy.parameters()), rtol=0, atol=0) @pytest.mark.parametrize("insert_temporal_dim", [False, True]) From 03c7cf8a63f0ed6510b989466b7b82343eb713b9 Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Sat, 8 Mar 2025 09:39:07 +0100 Subject: [PATCH 15/19] Remove pr_style_bot (#832) --- .github/workflows/pr_style_bot.yml | 175 ----------------------------- 1 file changed, 175 deletions(-) delete mode 100644 .github/workflows/pr_style_bot.yml diff --git a/.github/workflows/pr_style_bot.yml b/.github/workflows/pr_style_bot.yml deleted file mode 100644 index dc4974c2..00000000 --- a/.github/workflows/pr_style_bot.yml +++ /dev/null @@ -1,175 +0,0 @@ -# Copyright 2024 The HuggingFace Inc. team. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -# Adapted from https://github.com/huggingface/diffusers/blob/main/.github/workflows/pr_style_bot.yml -name: PR Style Bot - -on: - issue_comment: - types: [created] - -permissions: {} - -env: - PYTHON_VERSION: "3.10" - -jobs: - check-permissions: - if: > - contains(github.event.comment.body, '@bot /style') && - github.event.issue.pull_request != null - runs-on: ubuntu-latest - outputs: - is_authorized: ${{ steps.check_user_permission.outputs.has_permission }} - steps: - - name: Check user permission - id: check_user_permission - uses: actions/github-script@v6 - with: - script: | - const comment_user = context.payload.comment.user.login; - const { data: permission } = await github.rest.repos.getCollaboratorPermissionLevel({ - owner: context.repo.owner, - repo: context.repo.repo, - username: comment_user - }); - - const authorized = - permission.permission === 'admin' || - permission.permission === 'write'; - - console.log( - `User ${comment_user} has permission level: ${permission.permission}, ` + - `authorized: ${authorized} (admins & maintainers allowed)` - ); - - core.setOutput('has_permission', authorized); - - run-style-bot: - needs: check-permissions - if: needs.check-permissions.outputs.is_authorized == 'true' - runs-on: ubuntu-latest - permissions: - contents: write - pull-requests: write - steps: - - name: Extract PR details - id: pr_info - uses: actions/github-script@v6 - with: - script: | - const prNumber = context.payload.issue.number; - const { data: pr } = await github.rest.pulls.get({ - owner: context.repo.owner, - repo: context.repo.repo, - pull_number: prNumber - }); - - // We capture both the branch ref and the "full_name" of the head repo - // so that we can check out the correct repository & branch (including forks). - core.setOutput("prNumber", prNumber); - core.setOutput("headRef", pr.head.ref); - core.setOutput("headRepoFullName", pr.head.repo.full_name); - - - name: Check out PR branch - uses: actions/checkout@v4 - env: - HEADREPOFULLNAME: ${{ steps.pr_info.outputs.headRepoFullName }} - HEADREF: ${{ steps.pr_info.outputs.headRef }} - with: - persist-credentials: true - # Instead of checking out the base repo, use the contributor's repo name - repository: ${{ env.HEADREPOFULLNAME }} - ref: ${{ env.HEADREF }} - # You may need fetch-depth: 0 for being able to push - fetch-depth: 0 - token: ${{ secrets.GITHUB_TOKEN }} - - - name: Debug - env: - HEADREPOFULLNAME: ${{ steps.pr_info.outputs.headRepoFullName }} - HEADREF: ${{ steps.pr_info.outputs.headRef }} - PRNUMBER: ${{ steps.pr_info.outputs.prNumber }} - run: | - echo "PR number: ${PRNUMBER}" - echo "Head Ref: ${HEADREF}" - echo "Head Repo Full Name: ${HEADREPOFULLNAME}" - - - name: Set up Python - uses: actions/setup-python@v4 - with: - python-version: ${{ env.PYTHON_VERSION }} - - - name: Get Ruff Version from pre-commit-config.yaml - id: get-ruff-version - run: | - RUFF_VERSION=$(awk '/repo: https:\/\/github.com\/astral-sh\/ruff-pre-commit/{flag=1;next}/rev:/{if(flag){print $2;exit}}' .pre-commit-config.yaml) - echo "ruff_version=${RUFF_VERSION}" >> $GITHUB_OUTPUT - - - name: Install Ruff - env: - RUFF_VERSION: ${{ steps.get-ruff-version.outputs.ruff_version }} - run: python -m pip install "ruff==${RUFF_VERSION}" - - - name: Ruff check - run: ruff check --fix - - - name: Ruff format - run: ruff format - - - name: Commit and push changes - id: commit_and_push - env: - HEADREPOFULLNAME: ${{ steps.pr_info.outputs.headRepoFullName }} - HEADREF: ${{ steps.pr_info.outputs.headRef }} - PRNUMBER: ${{ steps.pr_info.outputs.prNumber }} - GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} - run: | - echo "HEADREPOFULLNAME: ${HEADREPOFULLNAME}, HEADREF: ${HEADREF}" - # Configure git with the Actions bot user - git config user.name "github-actions[bot]" - git config user.email "github-actions[bot]@users.noreply.github.com" - git config --local lfs.https://github.com/.locksverify false - - # Make sure your 'origin' remote is set to the contributor's fork - git remote set-url origin "https://x-access-token:${GITHUB_TOKEN}@github.com/${HEADREPOFULLNAME}.git" - - # If there are changes after running style/quality, commit them - if [ -n "$(git status --porcelain)" ]; then - git add . - git commit -m "Apply style fixes" - # Push to the original contributor's forked branch - git push origin HEAD:${HEADREF} - echo "changes_pushed=true" >> $GITHUB_OUTPUT - else - echo "No changes to commit." - echo "changes_pushed=false" >> $GITHUB_OUTPUT - fi - - - name: Comment on PR with workflow run link - if: steps.commit_and_push.outputs.changes_pushed == 'true' - uses: actions/github-script@v6 - with: - script: | - const prNumber = parseInt(process.env.prNumber, 10); - const runUrl = `${process.env.GITHUB_SERVER_URL}/${process.env.GITHUB_REPOSITORY}/actions/runs/${process.env.GITHUB_RUN_ID}` - - await github.rest.issues.createComment({ - owner: context.repo.owner, - repo: context.repo.repo, - issue_number: prNumber, - body: `Style fixes have been applied. [View the workflow run here](${runUrl}).` - }); - env: - prNumber: ${{ steps.pr_info.outputs.prNumber }} From 32fffd4bbbaf8f9a20e2f31cddae5102522ee1ae Mon Sep 17 00:00:00 2001 From: Joe Clinton <48254978+Joeclinton1@users.noreply.github.com> Date: Sat, 8 Mar 2025 10:40:07 +0000 Subject: [PATCH 16/19] Fix delay in teleoperation start time (#676) Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- lerobot/common/robot_devices/cameras/opencv.py | 14 ++++++++++++-- tests/mock_cv2.py | 5 +++++ 2 files changed, 17 insertions(+), 2 deletions(-) diff --git a/lerobot/common/robot_devices/cameras/opencv.py b/lerobot/common/robot_devices/cameras/opencv.py index d15a48f6..e6133a84 100644 --- a/lerobot/common/robot_devices/cameras/opencv.py +++ b/lerobot/common/robot_devices/cameras/opencv.py @@ -285,10 +285,20 @@ class OpenCVCamera: # when other threads are used to save the images. cv2.setNumThreads(1) + backend = ( + cv2.CAP_V4L2 + if platform.system() == "Linux" + else cv2.CAP_DSHOW + if platform.system() == "Windows" + else cv2.CAP_AVFOUNDATION + if platform.system() == "Darwin" + else cv2.CAP_ANY + ) + camera_idx = f"/dev/video{self.camera_index}" if platform.system() == "Linux" else self.camera_index # First create a temporary camera trying to access `camera_index`, # and verify it is a valid camera by calling `isOpened`. - tmp_camera = cv2.VideoCapture(camera_idx) + tmp_camera = cv2.VideoCapture(camera_idx, backend) is_camera_open = tmp_camera.isOpened() # Release camera to make it accessible for `find_camera_indices` tmp_camera.release() @@ -311,7 +321,7 @@ class OpenCVCamera: # Secondly, create the camera that will be used downstream. # Note: For some unknown reason, calling `isOpened` blocks the camera which then # needs to be re-created. - self.camera = cv2.VideoCapture(camera_idx) + self.camera = cv2.VideoCapture(camera_idx, backend) if self.fps is not None: self.camera.set(cv2.CAP_PROP_FPS, self.fps) diff --git a/tests/mock_cv2.py b/tests/mock_cv2.py index b82e7819..eeaf859c 100644 --- a/tests/mock_cv2.py +++ b/tests/mock_cv2.py @@ -15,6 +15,11 @@ from functools import cache import numpy as np +CAP_V4L2 = 200 +CAP_DSHOW = 700 +CAP_AVFOUNDATION = 1200 +CAP_ANY = -1 + CAP_PROP_FPS = 5 CAP_PROP_FRAME_WIDTH = 3 CAP_PROP_FRAME_HEIGHT = 4 From 513b008bccab7da3f9bde0eff345ba1c22f3c40f Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Mon, 10 Mar 2025 10:19:54 +0100 Subject: [PATCH 17/19] fix: deactivate tdmpc backward compatibility test with use_mpc=True (#838) --- tests/test_policies.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/test_policies.py b/tests/test_policies.py index 7df79c1d..5d7cca8f 100644 --- a/tests/test_policies.py +++ b/tests/test_policies.py @@ -368,7 +368,7 @@ def test_normalize(insert_temporal_dim): # was changed to true. For some reason, tests would pass locally, but not in CI. So here we override # to test with `policy.use_mpc=false`. ("lerobot/xarm_lift_medium", "tdmpc", {"use_mpc": False}, "use_policy"), - ("lerobot/xarm_lift_medium", "tdmpc", {"use_mpc": True}, "use_mpc"), + # ("lerobot/xarm_lift_medium", "tdmpc", {"use_mpc": True}, "use_mpc"), # TODO(rcadene): the diffusion model was normalizing the image in mean=0.5 std=0.5 which is a hack supposed to # to normalize the image at all. In our current codebase we dont normalize at all. But there is still a minor difference # that fails the test. However, by testing to normalize the image with 0.5 0.5 in the current codebase, the test pass. From 05b54733daee0397e4df5037aa4022281e6fa574 Mon Sep 17 00:00:00 2001 From: Ben Sprenger Date: Mon, 10 Mar 2025 13:25:47 +0100 Subject: [PATCH 18/19] feat: add support for external plugin config dataclasses (#807) Co-authored-by: Steven Palma Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> --- lerobot/configs/parser.py | 96 +++++++++++++++++++++++++++- tests/configs/test_plugin_loading.py | 89 ++++++++++++++++++++++++++ 2 files changed, 184 insertions(+), 1 deletion(-) create mode 100644 tests/configs/test_plugin_loading.py diff --git a/lerobot/configs/parser.py b/lerobot/configs/parser.py index 476a9b40..39e31515 100644 --- a/lerobot/configs/parser.py +++ b/lerobot/configs/parser.py @@ -11,7 +11,9 @@ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. +import importlib import inspect +import pkgutil import sys from argparse import ArgumentError from functools import wraps @@ -23,6 +25,7 @@ import draccus from lerobot.common.utils.utils import has_method PATH_KEY = "path" +PLUGIN_DISCOVERY_SUFFIX = "discover_packages_path" draccus.set_config_type("json") @@ -58,6 +61,86 @@ def parse_arg(arg_name: str, args: Sequence[str] | None = None) -> str | None: return None +def parse_plugin_args(plugin_arg_suffix: str, args: Sequence[str]) -> dict: + """Parse plugin-related arguments from command-line arguments. + + This function extracts arguments from command-line arguments that match a specified suffix pattern. + It processes arguments in the format '--key=value' and returns them as a dictionary. + + Args: + plugin_arg_suffix (str): The suffix to identify plugin-related arguments. + cli_args (Sequence[str]): A sequence of command-line arguments to parse. + + Returns: + dict: A dictionary containing the parsed plugin arguments where: + - Keys are the argument names (with '--' prefix removed if present) + - Values are the corresponding argument values + + Example: + >>> args = ['--env.discover_packages_path=my_package', + ... '--other_arg=value'] + >>> parse_plugin_args('discover_packages_path', args) + {'env.discover_packages_path': 'my_package'} + """ + plugin_args = {} + for arg in args: + if "=" in arg and plugin_arg_suffix in arg: + key, value = arg.split("=", 1) + # Remove leading '--' if present + if key.startswith("--"): + key = key[2:] + plugin_args[key] = value + return plugin_args + + +class PluginLoadError(Exception): + """Raised when a plugin fails to load.""" + + +def load_plugin(plugin_path: str) -> None: + """Load and initialize a plugin from a given Python package path. + + This function attempts to load a plugin by importing its package and any submodules. + Plugin registration is expected to happen during package initialization, i.e. when + the package is imported the gym environment should be registered and the config classes + registered with their parents using the `register_subclass` decorator. + + Args: + plugin_path (str): The Python package path to the plugin (e.g. "mypackage.plugins.myplugin") + + Raises: + PluginLoadError: If the plugin cannot be loaded due to import errors or if the package path is invalid. + + Examples: + >>> load_plugin("external_plugin.core") # Loads plugin from external package + + Notes: + - The plugin package should handle its own registration during import + - All submodules in the plugin package will be imported + - Implementation follows the plugin discovery pattern from Python packaging guidelines + + See Also: + https://packaging.python.org/en/latest/guides/creating-and-discovering-plugins/ + """ + try: + package_module = importlib.import_module(plugin_path, __package__) + except (ImportError, ModuleNotFoundError) as e: + raise PluginLoadError( + f"Failed to load plugin '{plugin_path}'. Verify the path and installation: {str(e)}" + ) from e + + def iter_namespace(ns_pkg): + return pkgutil.iter_modules(ns_pkg.__path__, ns_pkg.__name__ + ".") + + try: + for _finder, pkg_name, _ispkg in iter_namespace(package_module): + importlib.import_module(pkg_name) + except ImportError as e: + raise PluginLoadError( + f"Failed to load plugin '{plugin_path}'. Verify the path and installation: {str(e)}" + ) from e + + def get_path_arg(field_name: str, args: Sequence[str] | None = None) -> str | None: return parse_arg(f"{field_name}.{PATH_KEY}", args) @@ -105,10 +188,13 @@ def filter_path_args(fields_to_filter: str | list[str], args: Sequence[str] | No def wrap(config_path: Path | None = None): """ - HACK: Similar to draccus.wrap but does two additional things: + HACK: Similar to draccus.wrap but does three additional things: - Will remove '.path' arguments from CLI in order to process them later on. - If a 'config_path' is passed and the main config class has a 'from_pretrained' method, will initialize it from there to allow to fetch configs from the hub directly + - Will load plugins specified in the CLI arguments. These plugins will typically register + their own subclasses of config classes, so that draccus can find the right class to instantiate + from the CLI '.type' arguments """ def wrapper_outer(fn): @@ -121,6 +207,14 @@ def wrap(config_path: Path | None = None): args = args[1:] else: cli_args = sys.argv[1:] + plugin_args = parse_plugin_args(PLUGIN_DISCOVERY_SUFFIX, cli_args) + for plugin_cli_arg, plugin_path in plugin_args.items(): + try: + load_plugin(plugin_path) + except PluginLoadError as e: + # add the relevant CLI arg to the error message + raise PluginLoadError(f"{e}\nFailed plugin CLI Arg: {plugin_cli_arg}") from e + cli_args = filter_arg(plugin_cli_arg, cli_args) config_path_cli = parse_arg("config_path", cli_args) if has_method(argtype, "__get_path_fields__"): path_fields = argtype.__get_path_fields__() diff --git a/tests/configs/test_plugin_loading.py b/tests/configs/test_plugin_loading.py new file mode 100644 index 00000000..1a8cceed --- /dev/null +++ b/tests/configs/test_plugin_loading.py @@ -0,0 +1,89 @@ +import sys +from dataclasses import dataclass +from pathlib import Path +from typing import Generator + +import pytest + +from lerobot.common.envs.configs import EnvConfig +from lerobot.configs.parser import PluginLoadError, load_plugin, parse_plugin_args, wrap + + +def create_plugin_code(*, base_class: str = "EnvConfig", plugin_name: str = "test_env") -> str: + """Creates a dummy plugin module that implements its own EnvConfig subclass.""" + return f""" +from dataclasses import dataclass +from lerobot.common.envs.configs import {base_class} + +@{base_class}.register_subclass("{plugin_name}") +@dataclass +class TestPluginConfig: + value: int = 42 + """ + + +@pytest.fixture +def plugin_dir(tmp_path: Path) -> Generator[Path, None, None]: + """Creates a temporary plugin package structure.""" + plugin_pkg = tmp_path / "test_plugin" + plugin_pkg.mkdir() + (plugin_pkg / "__init__.py").touch() + + with open(plugin_pkg / "my_plugin.py", "w") as f: + f.write(create_plugin_code()) + + # Add tmp_path to Python path so we can import from it + sys.path.insert(0, str(tmp_path)) + yield plugin_pkg + sys.path.pop(0) + + +def test_parse_plugin_args(): + cli_args = [ + "--env.type=test", + "--model.discover_packages_path=some.package", + "--env.discover_packages_path=other.package", + ] + plugin_args = parse_plugin_args("discover_packages_path", cli_args) + assert plugin_args == { + "model.discover_packages_path": "some.package", + "env.discover_packages_path": "other.package", + } + + +def test_load_plugin_success(plugin_dir: Path): + # Import should work and register the plugin with the real EnvConfig + load_plugin("test_plugin") + + assert "test_env" in EnvConfig.get_known_choices() + plugin_cls = EnvConfig.get_choice_class("test_env") + plugin_instance = plugin_cls() + assert plugin_instance.value == 42 + + +def test_load_plugin_failure(): + with pytest.raises(PluginLoadError) as exc_info: + load_plugin("nonexistent_plugin") + assert "Failed to load plugin 'nonexistent_plugin'" in str(exc_info.value) + + +def test_wrap_with_plugin(plugin_dir: Path): + @dataclass + class Config: + env: EnvConfig + + @wrap() + def dummy_func(cfg: Config): + return cfg + + # Test loading plugin via CLI args + sys.argv = [ + "dummy_script.py", + "--env.discover_packages_path=test_plugin", + "--env.type=test_env", + ] + + cfg = dummy_func() + assert isinstance(cfg, Config) + assert isinstance(cfg.env, EnvConfig.get_choice_class("test_env")) + assert cfg.env.value == 42 From 84565c7c2edb9dacaef27cf7d0ba6ab37c8a014b Mon Sep 17 00:00:00 2001 From: Pepijn <138571049+pkooij@users.noreply.github.com> Date: Mon, 10 Mar 2025 17:02:19 +0100 Subject: [PATCH 19/19] Fix camera rotation error (#839) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../robot_devices/cameras/intelrealsense.py | 46 +++++++++++------ .../common/robot_devices/cameras/opencv.py | 46 ++++++++++------- tests/test_cameras.py | 50 ++++++++++++++++++- 3 files changed, 107 insertions(+), 35 deletions(-) diff --git a/lerobot/common/robot_devices/cameras/intelrealsense.py b/lerobot/common/robot_devices/cameras/intelrealsense.py index 29e99ea3..d9c57aa2 100644 --- a/lerobot/common/robot_devices/cameras/intelrealsense.py +++ b/lerobot/common/robot_devices/cameras/intelrealsense.py @@ -114,7 +114,7 @@ def save_images_from_cameras( camera = IntelRealSenseCamera(config) camera.connect() print( - f"IntelRealSenseCamera({camera.serial_number}, fps={camera.fps}, width={camera.width}, height={camera.height}, color_mode={camera.color_mode})" + f"IntelRealSenseCamera({camera.serial_number}, fps={camera.fps}, width={camera.capture_width}, height={camera.capture_height}, color_mode={camera.color_mode})" ) cameras.append(camera) @@ -224,9 +224,20 @@ class IntelRealSenseCamera: self.serial_number = self.find_serial_number_from_name(config.name) else: self.serial_number = config.serial_number + + # Store the raw (capture) resolution from the config. + self.capture_width = config.width + self.capture_height = config.height + + # If rotated by ±90, swap width and height. + if config.rotation in [-90, 90]: + self.width = config.height + self.height = config.width + else: + self.width = config.width + self.height = config.height + self.fps = config.fps - self.width = config.width - self.height = config.height self.channels = config.channels self.color_mode = config.color_mode self.use_depth = config.use_depth @@ -246,7 +257,6 @@ class IntelRealSenseCamera: else: import cv2 - # TODO(alibets): Do we keep original width/height or do we define them after rotation? self.rotation = None if config.rotation == -90: self.rotation = cv2.ROTATE_90_COUNTERCLOCKWISE @@ -284,15 +294,19 @@ class IntelRealSenseCamera: config = rs.config() config.enable_device(str(self.serial_number)) - if self.fps and self.width and self.height: + if self.fps and self.capture_width and self.capture_height: # TODO(rcadene): can we set rgb8 directly? - config.enable_stream(rs.stream.color, self.width, self.height, rs.format.rgb8, self.fps) + config.enable_stream( + rs.stream.color, self.capture_width, self.capture_height, rs.format.rgb8, self.fps + ) else: config.enable_stream(rs.stream.color) if self.use_depth: - if self.fps and self.width and self.height: - config.enable_stream(rs.stream.depth, self.width, self.height, rs.format.z16, self.fps) + if self.fps and self.capture_width and self.capture_height: + config.enable_stream( + rs.stream.depth, self.capture_width, self.capture_height, rs.format.z16, self.fps + ) else: config.enable_stream(rs.stream.depth) @@ -330,18 +344,18 @@ class IntelRealSenseCamera: raise OSError( f"Can't set {self.fps=} for IntelRealSenseCamera({self.serial_number}). Actual value is {actual_fps}." ) - if self.width is not None and self.width != actual_width: + if self.capture_width is not None and self.capture_width != actual_width: raise OSError( - f"Can't set {self.width=} for IntelRealSenseCamera({self.serial_number}). Actual value is {actual_width}." + f"Can't set {self.capture_width=} for IntelRealSenseCamera({self.serial_number}). Actual value is {actual_width}." ) - if self.height is not None and self.height != actual_height: + if self.capture_height is not None and self.capture_height != actual_height: raise OSError( - f"Can't set {self.height=} for IntelRealSenseCamera({self.serial_number}). Actual value is {actual_height}." + f"Can't set {self.capture_height=} for IntelRealSenseCamera({self.serial_number}). Actual value is {actual_height}." ) self.fps = round(actual_fps) - self.width = round(actual_width) - self.height = round(actual_height) + self.capture_width = round(actual_width) + self.capture_height = round(actual_height) self.is_connected = True @@ -387,7 +401,7 @@ class IntelRealSenseCamera: color_image = cv2.cvtColor(color_image, cv2.COLOR_RGB2BGR) h, w, _ = color_image.shape - if h != self.height or w != self.width: + if h != self.capture_height or w != self.capture_width: raise OSError( f"Can't capture color image with expected height and width ({self.height} x {self.width}). ({h} x {w}) returned instead." ) @@ -409,7 +423,7 @@ class IntelRealSenseCamera: depth_map = np.asanyarray(depth_frame.get_data()) h, w = depth_map.shape - if h != self.height or w != self.width: + if h != self.capture_height or w != self.capture_width: raise OSError( f"Can't capture depth map with expected height and width ({self.height} x {self.width}). ({h} x {w}) returned instead." ) diff --git a/lerobot/common/robot_devices/cameras/opencv.py b/lerobot/common/robot_devices/cameras/opencv.py index e6133a84..173f3f1a 100644 --- a/lerobot/common/robot_devices/cameras/opencv.py +++ b/lerobot/common/robot_devices/cameras/opencv.py @@ -144,8 +144,8 @@ def save_images_from_cameras( camera = OpenCVCamera(config) camera.connect() print( - f"OpenCVCamera({camera.camera_index}, fps={camera.fps}, width={camera.width}, " - f"height={camera.height}, color_mode={camera.color_mode})" + f"OpenCVCamera({camera.camera_index}, fps={camera.fps}, width={camera.capture_width}, " + f"height={camera.capture_height}, color_mode={camera.color_mode})" ) cameras.append(camera) @@ -244,9 +244,19 @@ class OpenCVCamera: else: raise ValueError(f"Please check the provided camera_index: {self.camera_index}") + # Store the raw (capture) resolution from the config. + self.capture_width = config.width + self.capture_height = config.height + + # If rotated by ±90, swap width and height. + if config.rotation in [-90, 90]: + self.width = config.height + self.height = config.width + else: + self.width = config.width + self.height = config.height + self.fps = config.fps - self.width = config.width - self.height = config.height self.channels = config.channels self.color_mode = config.color_mode self.mock = config.mock @@ -263,7 +273,6 @@ class OpenCVCamera: else: import cv2 - # TODO(aliberts): Do we keep original width/height or do we define them after rotation? self.rotation = None if config.rotation == -90: self.rotation = cv2.ROTATE_90_COUNTERCLOCKWISE @@ -325,10 +334,10 @@ class OpenCVCamera: if self.fps is not None: self.camera.set(cv2.CAP_PROP_FPS, self.fps) - if self.width is not None: - self.camera.set(cv2.CAP_PROP_FRAME_WIDTH, self.width) - if self.height is not None: - self.camera.set(cv2.CAP_PROP_FRAME_HEIGHT, self.height) + if self.capture_width is not None: + self.camera.set(cv2.CAP_PROP_FRAME_WIDTH, self.capture_width) + if self.capture_height is not None: + self.camera.set(cv2.CAP_PROP_FRAME_HEIGHT, self.capture_height) actual_fps = self.camera.get(cv2.CAP_PROP_FPS) actual_width = self.camera.get(cv2.CAP_PROP_FRAME_WIDTH) @@ -340,19 +349,22 @@ class OpenCVCamera: raise OSError( f"Can't set {self.fps=} for OpenCVCamera({self.camera_index}). Actual value is {actual_fps}." ) - if self.width is not None and not math.isclose(self.width, actual_width, rel_tol=1e-3): + if self.capture_width is not None and not math.isclose( + self.capture_width, actual_width, rel_tol=1e-3 + ): raise OSError( - f"Can't set {self.width=} for OpenCVCamera({self.camera_index}). Actual value is {actual_width}." + f"Can't set {self.capture_width=} for OpenCVCamera({self.camera_index}). Actual value is {actual_width}." ) - if self.height is not None and not math.isclose(self.height, actual_height, rel_tol=1e-3): + if self.capture_height is not None and not math.isclose( + self.capture_height, actual_height, rel_tol=1e-3 + ): raise OSError( - f"Can't set {self.height=} for OpenCVCamera({self.camera_index}). Actual value is {actual_height}." + f"Can't set {self.capture_height=} for OpenCVCamera({self.camera_index}). Actual value is {actual_height}." ) self.fps = round(actual_fps) - self.width = round(actual_width) - self.height = round(actual_height) - + self.capture_width = round(actual_width) + self.capture_height = round(actual_height) self.is_connected = True def read(self, temporary_color_mode: str | None = None) -> np.ndarray: @@ -393,7 +405,7 @@ class OpenCVCamera: color_image = cv2.cvtColor(color_image, cv2.COLOR_BGR2RGB) h, w, _ = color_image.shape - if h != self.height or w != self.width: + if h != self.capture_height or w != self.capture_width: raise OSError( f"Can't capture color image with expected height and width ({self.height} x {self.width}). ({h} x {w}) returned instead." ) diff --git a/tests/test_cameras.py b/tests/test_cameras.py index 3ab74516..ded0a3d5 100644 --- a/tests/test_cameras.py +++ b/tests/test_cameras.py @@ -85,8 +85,8 @@ def test_camera(request, camera_type, mock): camera.connect() assert camera.is_connected assert camera.fps is not None - assert camera.width is not None - assert camera.height is not None + assert camera.capture_width is not None + assert camera.capture_height is not None # Test connecting twice raises an error with pytest.raises(RobotDeviceAlreadyConnectedError): @@ -204,3 +204,49 @@ def test_save_images_from_cameras(tmp_path, request, camera_type, mock): # Small `record_time_s` to speedup unit tests save_images_from_cameras(tmp_path, record_time_s=0.02, mock=mock) + + +@pytest.mark.parametrize("camera_type, mock", TEST_CAMERA_TYPES) +@require_camera +def test_camera_rotation(request, camera_type, mock): + config_kwargs = {"camera_type": camera_type, "mock": mock, "width": 640, "height": 480, "fps": 30} + + # No rotation. + camera = make_camera(**config_kwargs, rotation=None) + camera.connect() + assert camera.capture_width == 640 + assert camera.capture_height == 480 + assert camera.width == 640 + assert camera.height == 480 + no_rot_img = camera.read() + h, w, c = no_rot_img.shape + assert h == 480 and w == 640 and c == 3 + camera.disconnect() + + # Rotation = 90 (clockwise). + camera = make_camera(**config_kwargs, rotation=90) + camera.connect() + # With a 90° rotation, we expect the metadata dimensions to be swapped. + assert camera.capture_width == 640 + assert camera.capture_height == 480 + assert camera.width == 480 + assert camera.height == 640 + import cv2 + + assert camera.rotation == cv2.ROTATE_90_CLOCKWISE + rot_img = camera.read() + h, w, c = rot_img.shape + assert h == 640 and w == 480 and c == 3 + camera.disconnect() + + # Rotation = 180. + camera = make_camera(**config_kwargs, rotation=None) + camera.connect() + assert camera.capture_width == 640 + assert camera.capture_height == 480 + assert camera.width == 640 + assert camera.height == 480 + no_rot_img = camera.read() + h, w, c = no_rot_img.shape + assert h == 480 and w == 640 and c == 3 + camera.disconnect()