From 6d3af679a9d7969695539d2168ae972067276066 Mon Sep 17 00:00:00 2001 From: QUYVN Date: Wed, 18 Mar 2026 07:38:51 +0000 Subject: [PATCH 01/11] add max speed --- config/pnkx_local_planner_params.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/config/pnkx_local_planner_params.yaml b/config/pnkx_local_planner_params.yaml index 9b3aa9d..170f5c4 100644 --- a/config/pnkx_local_planner_params.yaml +++ b/config/pnkx_local_planner_params.yaml @@ -41,8 +41,8 @@ PNKXRotateLocalPlanner: LimitedAccelGenerator: library_path: libmkt_plugins_standard_traj_generator - max_vel_x: 0.2 - min_vel_x: -0.2 + max_vel_x: 1.0 + min_vel_x: -1.0 max_vel_y: 0.0 # diff drive robot min_vel_y: 0.0 # diff drive robot @@ -50,7 +50,7 @@ LimitedAccelGenerator: max_speed_xy: 2.0 # max_trans_vel: 0.8 # choose slightly less than the base's capability min_speed_xy: 0.25 # min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity - max_vel_theta: 0.7 # max_rot_vel: 1.0 # choose slightly less than the base's capability + max_vel_theta: 0.4 # max_rot_vel: 1.0 # choose slightly less than the base's capability min_vel_theta: 0.05 # min_rot_vel: 0.1 default: 0.4 # this is the min angular velocity when there is negligible translational velocity acc_lim_x: 1.5 From f0d987da39b7e58127a2882d5af349c3020c956e Mon Sep 17 00:00:00 2001 From: HiepLM Date: Thu, 19 Mar 2026 09:40:32 +0700 Subject: [PATCH 02/11] update Kalman Filter --- config/pnkx_local_planner_params.yaml | 8 ++ .../NavigationExample.csproj | 2 +- examples/NavigationExample/libnav_c_api.so | Bin 301968 -> 309296 bytes .../Libraries/kalman/src/kalman.cpp | 27 +++++- .../diff/diff_predictive_trajectory.h | 8 ++ .../src/diff/diff_predictive_trajectory.cpp | 79 +++++++++++------- 6 files changed, 90 insertions(+), 34 deletions(-) diff --git a/config/pnkx_local_planner_params.yaml b/config/pnkx_local_planner_params.yaml index 9b3aa9d..4783027 100644 --- a/config/pnkx_local_planner_params.yaml +++ b/config/pnkx_local_planner_params.yaml @@ -79,6 +79,14 @@ MKTAlgorithmDiffPredictiveTrajectory: index_samples: 60 follow_step_path: true + # Kalman filter tuning (filters v and w commands) + kf_q_v: 0.25 + kf_q_w: 0.8 + kf_r_v: 0.05 + kf_r_w: 0.08 + kf_p0: 0.5 + kf_filter_angular: false + # Lookahead use_velocity_scaled_lookahead_dist: true # Whether to use the velocity scaled lookahead distances or constant lookahead_distance. (default: false) # only when false: diff --git a/examples/NavigationExample/NavigationExample.csproj b/examples/NavigationExample/NavigationExample.csproj index 9ec6097..c98bcda 100644 --- a/examples/NavigationExample/NavigationExample.csproj +++ b/examples/NavigationExample/NavigationExample.csproj @@ -1,7 +1,7 @@ Exe - net10.0 + net6.0 true diff --git a/examples/NavigationExample/libnav_c_api.so b/examples/NavigationExample/libnav_c_api.so index d225bf1d7809f73ec8759fd1b8f9f929cc161676..626ec969b61a4e4e2f310098d7a656c7dd6f16a8 100755 GIT binary patch literal 309296 zcmeFa31AdO_CMZ%08xP%6g48QgGLRD!c4dl6`c?UdSt+n07elfAqgasV@M_tyml}F z8OOMB)fLxc<9BuCyXqR(3-3V)hwBkk6j#xxt9CXb5j^67{6DX%x>HlkDDLX-e{E~0 z`+e%wt5>gHU9T(THy+>AJ}D`EHF5RT&eBrw-m#4XZh<>nQ^lL6xwUNVF#L3A$1~pE z6pN+zQGWyYLjDFyXv7grS&RdB?)6AzPg`9mwkvkZ4R z?n`hl#%*4e;-yMFgLu~B4&h#kdl~L}+?V2(uPZ=Yi93wD0e2(rRk&BGZC-bamwUu>t$6+g&wItY`M6KK+>hs9 z#rp%|`8V-=7|+LWKaTrJ+)v}C>skKLVt76$-ZzLR`PXLg{yd&9;(kfcVo23q74&vI zUl;Fh;JE|$o4DT*7(L#_{Q>TO;{FIXU7fhQaDR$>H*UJRaev0%G;ObV(&G!q=QntMi+i7-_tO&{E(LcV+;pYl*&lZr?n7`NhTDdlE<2t>aUX^I7~I2f(={B= zUx{~)Xxj0h9ReF6rJaEH6LFt{d!)cm#d9?7F}UHVS{82e8Y|u>;F&GqlzuwsGX!>~ zk~T@uXXEL{JsEeNz^35o!95MPj=QnE+Sf7SvdeBg`|k9Qrq0=a)z{;O58B|n)t5ct z$w`;4+Wo7FNyc?;M=p8LKVxRjH^V-gce4MZe&>z6{`b#3JlnQ&a>WB(V@lS9-1kkI z)coke#u*nBmNy2+Pd@RDAs@W+;+Eq+9rf(OCtE7de&xcOZ`io!k`XVRcu1eyHt1h{ z-qPo$88=RMteG?YpSRxn&*68D+jr8LGgm$FO@5y@KYjkqh86lvc~2Dm&U3_?y_J8s zyddY+3G;S-ws_f-%NmOQeE6cL?rHkhsl&$ps&>;qM?do1-CI7|QS{EAD~`$Uc=)J} zyh{duz4g5I$6n3tA2@!&p0#%@Ipp{wJMKR9%HpM;exIJ=C^_ft9hZ$g^e?HS*Y3OZ zj~oA-`uFNfm)&+&GU#UG?o*e| zUvOLYyA{(uJ7LGYEBajU+%Y}P4=pd+zcc4|*{2jg=J}*$*8X$vN?rd!e#7Ve|L5Fq zuRE^0d(sP|1~gxCStMisqLY?&EWdow*E=sB^gj!7{oZ}f&8Tshl*^vTn3uKpy|)&PD>&os^jmJe z=AO=;Z}*-1$J4&^{_p80KKRT9eTLqcyZy$?FYCYb%>NBuQ$FFmV^8pZ^lZW33s1lL z)m5RTi_YFyS?xRSw)<{6ceC%-E&j2`j=5sdr^6q5;o=EZ>lXj^%n46AN*jZL;3T8{ zop)Xw*#EV!mVZC&v%OE3I_}x9)&J(8lhS`bA#>VgFC4KoeZ}NkZ#{Ih?XM-*UfA!` z=HK<(Q2%ZI*-sSRd(ulMj@tg^vws^u_nXfiY`J6dzGZh_G5o5OlSbS*?v|JC`~3rN zgsV;;bLd~jmi6ztRZmSk z^e+$Y&wM^_%maNcjy_cM>Vqw>)@(RD@8&N*89PtE;M~fE--Ygc`&WA&FIsThogZYc zHvV|#@7CUN@tZFlRh*r_|J}!DeKf2xZ`jk0S(Ea<8TR>@9UuB%x^MX6_6Ht+^Ws5! zcb+)?v)j+wTwiwXmFv%~YuG$wWo}yiJ-_W#efP95wV(0ts` zk1xFC%C>>~>N+mDpyc8GPu=mSGxmM;=wG}1=_hq`8K;$=^YmByGlo4f;O^5;Ja^2m z>mFV*Ei3=%zZ5SDWbJ*jYJR#oHY9pxI5q9?1PLuk@IPY_k%<4qQxoIPzKQX_9-SBu z9+MbfH8wHc`s>7azkZ4Fsi^A-3F>=g68B>ulK34bh!ogYk6FZbxgUMBRnzr=BotlcE=?skr!hJHxb)$l{Ir~6ng-@#B#8_(8hgSFTv zoc}tmmi9M{!y~Zba4g^e%)+i5p}%$t$EyYYGR9AmpC;moy1*OJ&}6s50GHn;a2v*9 zs&Bng-+^Ewe(gfekLs}NRX7HIDet=Pl_MWmFwnq)^6mCn5NmaC5b-gLM)Z*7WOgw(O;0A)l1-0g`82M-0;a< zzFBVNWL|EIh?5ow{W@lF$^4$r)iV43m;~H<|3OfjWE*AU)#&LVP595kBg+3pP{$(G}fuk^9)AiaQ zu1~k<5EpV-I~{CylK+eG#PpMYxw)Qe6nx?#yxc+xIN|zE)b|v$GugTIVh&)KW!E*Q zh;mQm`kczEt(__S)2aCRo(Wuj%TUh0NyvW#9iRNC`ExGU>@Uq&SF>`(_zAPK>kn?O z|7u15vBH1CbGZCJ@rU*~T$AKGhVTL}7JBv{!R2?H$Qe!hzlHIQ%Jo-s{%?hzkDy=B z_z)}N{0^>;_7cV$;_sNp8SfML_DqhqDC4{f4ovzuzvYaJh5U(Q^}AN3-=(m9AKKB*`TO&S_VNjw-#&~x!dfAJy6EpMFK|7D zIkcP1ejyY;jwfqFF;7uDc2H0i*CE2MobYq9TdRi`DBMna;4qHIiaGzY!v6DyaNNC& zol}`H>ckh_}meq+zifd#zt?0UTmHceg(H=S6{482oD~? z71ssc<|f>(6^ij0V%fDs_?!J{uIDvE&wgkil9PTUmxJbDSGVBTwupN1hxVPYbNAaE z*ev8U3jUU7Ii4!)bFsjipXB&bA!n=bLv0EdaG5Cg0XuJ(Rtjk2x<|-=ll5QJSNI9o z*mb;U$8MU4ah)Q{eG?3<9cwvm#5k+x8+Z=RN+=&JpuMx0n~IIJ-7i%v0+6_L-x3 zy|nAN0CS!_18zh0bqYJ6JFsgn^d;P`;3>jx%>sv5c5TBxg^kZ*+`u%-t`(xcw0_2E zxB)~p7y=(F{3m!6$4NiBUJ~nhyBH54mR);J=5m5!9$YH$-45O_%8uaz zK(ea^FVtVw3EXVQxvak*rG=Go>@eZy>i*)Nf`5&|?>bTFa|&b~PbOeoa8tru|p&*Ih7{*}k|56$ zmvhE0(e8d>2mfx4UnlJI_;H-yDg41)7yWN0$Ngg7pDEV$gdFX-Y)i8*9g4i1g?)J*2AWME*Aa8E&7W& zznqPZLv{#@aWx|39FFn{Z=cE)7tNrxi*YGanMX3ky4oSu)i5u+ZiK-}PPg#Spun%g zctZ7ce!>Cj=XC87>%eYdXLFo<_#`1m>~j}$b}eYGH$LQc`<_3v>%{t`TNwVg0{>pL zm%2{74gN{`_#fts=D7Flk$nH9iS;d-gIxt~-oNUVb!mSweyZ!YGm@;^pB8@JE(|*8q|A%|CD-Mvu0JT?m59fQCKeVHme?tESTt3`}T_?c~WH(K$1MLF89BiadtFW_} z2DMdZa{dlweeNI6`R!u8cZ(?p3wV-WDB=%m1wKghi`aeKuS7FwUxB<6{7%Jx%EkB} zRMy*fu>O0L=2!SX72{RmA-ukC@nW=P7@){L9m6<2M2s_+2>y=GIAaw3kgmSyuw;jh z5XS>Nn>I}F$GSNF6=&C;6XRHOgyT;M{A9784G!W0UK4WOfg_PV_RXB%9LN4F@YW3+ zH`jZWgSkHba*mJS4{hfN(O$~B_jA#Y9Ks*w3w^d@9HVlBM{z~WedutsFV%O=hnz7i z_|F#p(=7Z4+Y@%Bo8!#8ToH4eF@|zE?kL9}67_x1wq4(nZxZ%g0p}RhD{|CeP>MVh%Q&Yh1j1m$P(9UHQ_Yiqfi(r+n7*nfcCuYrNp8 zt|}=Hl~-4J4lMo$khN$#y3+u6SYA}g`f4C{E%yG zOc}9L{Y+!Dd+JA(Yc%2do`3b5yStZC0 zl?OJ7szH1kpfRh8gUjI}G<+?O8PC z(~*9}0eXEC3SdkkLHVJHqy=2om9?O#7DFV`%BvQ6i_x;K;C0EDhBxpEW((eEs)q<#NJUHKoCdB8*&> zl`shmHm7P?IU0CYX>DC)Ddc8lNk#jsYfJM(MU}zQl3CMTE{P;gr^P8HU_x-^)Ko91 z4q?pYiU%rd7uCA5B&L8Dt+&+U@z6+8QWvBukB^gCZnXZXEdsWfWKo*za8XwOUC#u(K=N1>&1u;1+ zpH@>2t67SWBxZnCPZr^V1KF~`D4R&ST`SC?0Xu%fGD&67YF9NpyTmF9BxqEvI)`%Uhw zB-+9EEfz_lR8AH|S{)}?Qyr=Gv7;#BLARkC^$W-VGe&6* z`ku#+jAKou16A-H#=&bd7Q@HEROCNUej>D)nLiXV>ZRn2`JpVQwZti{S`;ed zJ|@;Uy}}nl_`+nuAaeO^+Kl;j5;uMG#l?1LAr+8Wt__v*3Yqo9H3g)I-Xv z7FP2P!up0;p4Cs|782QPEFGI=jtI>c1~TaoY1OkJ+m;vvk}f^)dj;MHh7f? zTG15L3)2)7z$TGK#Q*n9sICd9dtANwM4LYzP9MS$CYA+(a`b~DnjvT&Uf?-*Hn&Sw zPA>6->YJ5M5|rI(!o|Z6ZBYXkPMez~YBoMpjqQ4G$jXD2 z7KIp#bjy4<6dP?`OAIww zLvio>&n@DbV1^jY$l}jno`gbw23^OC5Z%wIY66+^Dn||qQlK|Kl!NY3iAZ~>G0 zJ|Y(v{+>0R*1^3&YZkK>;X11=%wR1KLVDwu=?Qy|2fEG1syt!b4~c=2y3k6$ zw*054lQ@|9L)!d6j>J`t?^sNQo#F{G1LLysDy$)Q#*LH zl8WLA1mJ(U3W#~@7irch;uFm;B79;=d2JA;k$a$PLTP<*X^;hQMN8!HRR_g9FtuF5 z!$5EtaY#TJ7tL6fHJ<(F64_{Mj;cA9egq4j{LjlUzg*IYURT9Jspz*X7$*Whu5lF2 zVnY|kv6@oXxXD;e&n#M6zNm;DL_k)j7@8>5nV%J)NN8D6Z5bPmu-?IO28=|ZYEC0! zX$1nu2C$!s3k3e(s|NS!*-M>)s&URhaw|L0x2mw>z!;5HB*x*N=qw0*ilWT+P0*D8 zc_GY$%Bm)ev#R1;R#Oz@t^~!C`m#_iF6)6kTqs`u7^vly{Kz<&9)!`bFw_aQ)?{);3=8gRE`b%=wFq zDrWa02SSL@+-3eEWsPS8E#KJx_)tkvMm9YjutCYoqQ#*cSo@{b75-+19}d_Ch_Do2 zgqVjQ%(DkM<^d8j!ft*k`*B9$G%BMj@o9!+a+9%}F3G-{9Rndsas>jF3vi4uR2m4$t3}m1C37jOi}i}6 z#V$i%iaXJ@j6Q!XJK#juGJFJOr_;>E>5sMDIDEz{!7esItI?7QpX9LvuY@Vb(Pq*E z%UH`5DIiE2ooalB#e=QarNyySUDJoM*tWiQd1Xa;)neu|&H#55+Gd+8`#ABvi|qvR zH8#cd=@_0y<4AF!C|Dk#a}g41 zW~g4c5MQhVi>k3O&nkh@T&5$^Nj83RYu5A${Do|q)IWak#2;dF<%_Dw%f>M;=?6@Obb)oVKoI;}=TGo`=)uaO1!#oQT_l^00GiH)aCI1%lNT<;BZASqNEMhAc#H?T1ZEzMa;3Ll$|q`Gf>!wyWPU->JZBzC$l|os9J_fNSAns zaiPlQ*n*mZ5I)Wl)S}L6N|27@A*hZcfIpBFZ}C#mDv3(N_h|}dBrZ@SCMom4)I`PN zV6artT3Kl!fH-=~PsSlBaS$w7$#`&hv`E&0+F?;eH9kTI5+#X{v66`zRnmt}K%(zr zmBJ5iFTga-&O^s_NXnGB#VMuN0J3&UL2{Dlj{z2;N|ZpS3~B?VIMx_v3(;vsJ~oe8 zCll!V-%nm^^~SEo2M+qk@BxSU@>qoN?f6ci`d1pVJ<_zQqoB%11bVk@_W=LVwu`N`3MFObrvw;{V60h_S7A z34UPk#)Tame%mjA-(x8IfruvGXT$|Roq?7O0&@QsIumapuzQ*Uhl;9@cI z-fKJ`EUhU159zve)^s{W#1FL4Z<^2&!paGA;OK(6t&FRZwS$TK?JUICg)qJf;)2=6 zKo%-Q%G)+*2(EBtIiT{b29=i4jd6g%evr7T`$`h5M;8UDQ9hOf%AR;4tx@$NDFVO$6Js z_IAKuq9__S*f%H~a{fi5t8sOr9_I|`_-+@X5fujyk_7Dz`~ZkR1^c}R_~n5g1KH{( zn|^x%zf6Ho_4KRND9HNN1}u)0FND(9!bOmOx6E756|B>A} zWuddNKQRlH@>2r=W>No6KJx@r{1r?F3INCBi${$jp%aL| z(t2A|j9+yp%0+mwg(G0b1MWbyX?b~pvCwRq&pSCUkTp7M^mzVWPyl?~XjitDS5S~U z*&A?;9y>ZGKFuYi#ieAqWRkx__&Dp$)%%K4v@vD)t?n_*9_7WgV{)g>9W$kT;ljZA zWu>JRmuM{5Ky$Po{_-3B%U1)mL%=bB-Dybcs~yTXktCj} zjE^K82Ch_Xppep^JqIy){qT;zxx{i1C(k_qD3wTQgYhJsG@*Yxi*r#5U8Ga0mh#{K z{y%8}YGG>IE2r?kapC~&KY2O+Wud{^pMlXu=|iRTx?$z`my^=8zgp@2wNjBD1bJY8OIUh;ty|Eck-vjmrfT~^ z(?$A(M4AIM*Qc+fPpWpUNGJZG<>mON(*|mXd3YUfy#Dua_d~TK1!Uf4PM7(29jR}ytCK(0iog44;w|Feg=$rB?PJcrPQlv+9#e3;!TGl+cue3s6kHeo zj%J5~Yk%PXUX-EW?*HX@w}RURe~*GY1aAJr!e)KlcW^m&@edB0c%k|4dMbGLEu7z> z;C`V`rh=RLI2GI}^vPE6u+T?W@Oq(-U%@+sJ_QP1DD){*a8sW$1$PU5f(jlJ`h*p{ zS?IG`!P|vC%?chA`m9lKQ=b+E_X~a2D!BGXZvS-(zEHZtAl` z!3%{x9SZIi`gALJOz6|2;H^R*?NI*jLYn^8Ec8iJa8n<Z{0iPJ^eIqqQ=dWwZx{NMDY$kg_n&$NFBAHN72GZKS*_sOU$~rR1vm9squ?Dv zpB4po3w>G@JS_BCr{GSZPfWq>LZ2-vF3N3J@NR+cQ1GzO$58M!LZ5C0cL;rYR9xtz ziN7;#j+3T+(iB{~mD|&<;4z_(L%~~xKA8$`7y39A+$r?QR&Y}vw~7mWbOqP`hwE9O z;9G<~g$k|-eaaNvE%XU0xT#OQf;)shVFh;!eVP@#L+G7`Ck2WZNJhUGzXa#Q< z`q&jbDD+8Ja8nr2;HExX z6g({SX;<)=(5FMegF+ue!JCCX-3s0+^yyJ>Qy*<`yni+eebN+MyNmlzx`MA3`ZyFk zEcD4#@R-oYsoY=Tj=9g@D`y@fr1BxK7|V2F7zo=a8sY4g0~8N>J>aJ z^jWRo>x4ed3SKDmS)1 zPltlH3w;a)*Y4*2)1%;q&_}by`=MLtlcwO>y~CtJmZK5hj!_0bhPEcEd!cueS1sNmf~ zpE3n+7WxDgyjAE^ui&OWVFhm%`m9!PZ7uhoH42_4{$50jf`^4ZYZW{u^l4RaQ=fGT z-XipgDY#qc)2`qSq0bHl4+?!c6ue#NV<@<(Pq%`%3VnJMJS_A{6MqNG+;?XSee4Qe zDD+8J@D8DmL%~gbG8H@~^l_@V(8sOdexZ-9;zA$4f_Dpj3KZPbr%=J$g+65pu8BC3 zU&Jp>`)J}1eU&MAi@?JQ?x^Q~0Ar1U#{}N0;DyUM{}u(;F6DTKg0~2~N5S2faelkl zPn-I82s~54!}JGyaJd!SaRtW<6g(#Ipn?}($@y0+xb_>4w zhJuGzaDGj!PtE!|uHtyQg2x2zRPe$E&aW%D*2wWf1#b~}y@I<}a{guo?-2M}1rM*{ z{4oW0T+Q(v3LX=9w}Kb0=KN`5+%@f>ML6zI@D_n*E4W+yp-R7kcL=;p!NXB5Kdj)6 zYdO9~!D9k%Rq(fDtNe=^Sc$?aXrTi z6g(zyUHqLYQ+~VnyI6h&cL+MH{M|2;4vO)IW-a`QLj2`0ewlx#O2y5;m!{(8-}hB< z^Y0d`c)e8aZK6zin14@^`0=N@EPc$so2cTgk{p?TOA_4td+n;6bTN*pxHAcEeot2U z&F{J@UY|rxa}wPA-l)nkzx%29jwEurli+D$98={ulHl1%aDNiKED0V?g0D$}wDa%_?jg6T1mbvCtc#dU6SvR@D&nXmIQB2f~QO6%5t0%e}^PLTf+Y?;RO=DRl*A; ze7l6#OZfW|9+q$qIgz+lOSt$G;Vh*^!nc^rc&?T3*CjkA;rB~;>#utIi;QoP`12%v zS|z*5c)P^^yd-~zgdZ!(>5y=r#BWIWRTADU;bSE^?UMd7-XrlZm*i;T@0F5>*CgC7 z;j1M)mIP0i@WGNk4hg?rl9MUnmr3{zslUs3wpjm?Xc_NFg0B|qVwK-1mAenJ%=NHa z!k>`v0tx>{(z8s$cSv|p!cUOw5SH-YNc_zbF8;(hOKp+xCnf&167B_V>fezBZRZXCH%J%ULfIx5*|!~uTFxuB*E7u z!P}GIMiN|;*5R_A=}B;B5?oJ$7bd~$liM;MqxV ze-gYb2_8;@uStTpCc(EP!8?-RJxOr8v_6;ZkeLK`C&3Gn;K3yL>Lhqe5`0|}ygdnS zB*8Ulyprpio&9TBP`z2f(&i5B&f-5E5F5&-_@N@|uD%s5;;lG#oGbKDl z;&)2;#S(vyv_6sXY>9u5#P62yw;2|rDeACvHNB>pWDo+I(MOSnVA zcS!ggNlu4^pD*Etgx?_H-4cG0gs&FgN2tiD65cG~`4XP);Qf?-15{E|b4d7Ni9b`q zr$`x`63)N)@J!hf{;(v+E#X`Po~TQBs>JV?@Gm61K*GP2@IncnFX3epeu$)hP{Q#G ziq=&x;fG25VF~YVabsN|;crTKvxJ+!ZA-~(B>W!|e~W}aBH?Q#JWaw|CHxQxUnk++ z5+0NALnVBRgb$SPb_vHXSX$Q(2_I~sn${uVHVHQ*e6xgiOL&`v_ei)I17OJ`di{2Y z#GfYNhfBC!!taytbP2yy!W|O+mV{?Y_z@EBl<=Vvo-N^}67H7pKT5bR;i;0p`6c{F ziN8R?kCO002|rrG%Ou=f%TRJq!pkK7dI>*9!ow1Ntc0(Y@Zl2PEaAsV_!E5( z{AvkbE8)MA@Ky;wUc%Q&_;V5-lW>QGZ;|l3CA?k2M@aY%2|q!?J0$!>2{$A>L&Ccy z{3HqQk?>a~TsxuH|4)(dGzrg?aJz($l<;&3|FwiWBz%;FXG-{J$v>SEeyYTuE#aq0 zxLd-vNw_ZIqb1xg;YUm57D)IQiN8?7yCl3!!krQxlyH}X*Gu?uQn_IXe@NnAE#ZHX z@MZ}gE8%M-{76ZDi-b2z{A(rrY>B^B!f%rJ*Gc#|36Dwm#}d9p!Y4?0yM#X`;X5Qe zUDBsR!Y4}nhJwO85>5zemD5Bz%*E8xlTU!n-AWhJ^P>_)H1c#Cm=JuyZ9mO~Ox>>SdSk zYbE}43HM95L&8s&c%wuIj*;cf|EE8)6?e=gyE37;+D1rjdr#|tIA zK;kcx@Czh7DB%}Mc)f(n-}@w%|Gxg$0{^wZe=YD|3;fpt|Fyt>E%5&f3+%Q1>Knb` zlQccrZ)>2Brmu{J`s{Dl8#bo#-Nyd$?*rbm|D+G_upO@vKZ`5v>3nbh{{792rgi0> z&TSS=f#W@$>n)nLczZe@v}g(l@9DhLqWdxWdW)t&?4HgQ7EO!eJ)KJ|I*rjq7EOWD zJ)P%SGzCKUbmm(0VT^WJ^gu?BuxJW|?&%z2(G&pP)0tw?6!_fJ`PuhoeJOy6`djo6 zMsKrd3Rt547JUSxAGBx+ETaAvO@Y8Yo!4751prZhi>AOI>Tl5$@Y~Z_WYHARL;Wp! z7^8D7ngV-!I$ah`0lht)BP^N%d8ofdQ$P;&w`dB)q5k{K`a2l?o<)yf^frs802=CV z(I+zcL5rq<8R~D*6evUeE&60eudwJ-7`?=zGZ|fE(G&Mz65wX^dWC z(K@4xEZWQH^DO!tM(0{IZO~DFi}o>kghkUv9rd?p+MuKU7EK#-)c+f^{v;EqXDdT^3!z=n)oO$><>#UB&1W zi>_w$XFX>9gN%O9qL(mwn?=_!dc8&0GWtP_4l(*pi>_nz^%lL9(JL%^8Kak2bUmYs zEP6Sk&$H-D8J%m?^bWVMf1a(JL6e&7!Yj z^m>bKVDy6)-N@)WEqW!Rueaz`j9y{US2KEvMXzRbkwr%seV#>M!{}U#jxyS1(bqD1 zgh^v{vvUruZZIyiusL*W+ z{j@?qqR{s%^xX=5yF%Zj&`k=xQlYO<=sJb2ROnKLp0Chz6nch2dlY(-LXTJI(-it7 zg+5N9k5uSE3f)hk_vI_?uh6>``a^}@snFXM`bC9qQ|PA^`Vob`U!m_-=-Uh6g+kXUbfrR{h@va?PrLzdvm@Axd+R8 zJ+j;Q3%2E&&fvwDP;Xw$hw$idMYD~1r}$#HlFbc z!8jg_Golq4esA=m4BeZvvu+|u*LkM%MJ6XFbyJ3(b9qJ@l$j``?8XjVk6z~BY_y-z zqi5(%d3HT#GuZ3|G;GN3`Xk9Mss22c`l^R)5 zlJJKpp<#ow>nR=leqYX4DDe&gK{|aoyFvaIq%ZQZrSI8H$Ws|H%RH4V!&4b+Eo7b$ zQD&^iTbE0ZK9xZSPklKbL*gXCPe&_sR>mkoB0H(npz+QZy!=8VL~qdh1#IF;L~n*~ zu&gJf9Yu0A4Irdu%K^MEiIi0$#cvh+u#nP0iZ?Z8bkmbr{STB9dDobwrrjL-~RY*thggr{Wb-q zjz6V2Me{~t&q6EB6*JtQ@856CgO_)si)!yIv&=*!89<84hl-GFJE9M(j%_+vEDD(MDBiCRrbR1X+&~xx$jw zX4E06>s8|p!poUYTu##7g^LVh8g)@2ek!Dp7t&W0GLIGVu2GDvr0^&zB==*h?#3{o zCS2;N3_4oQU3&xN1Jc48`rW!SXpk7(tML(}$~#b{^ZI|m6{NgdjjO@d^_`)!JXFSCU`JS-tnvT}xRlD+wF_2hA#yR~nSuf&=v8v%I-be6 z0xSjdb1&+gf+VAwGMp}D7)=@8pbS$)2A`SX2+D94WjI92un+G%!x19Gv1W$%kz@>_ z3_D7QI4DZ80^ojS;6zv>_MKp z2?$DgN?0DUVIglX(vL(eW+L7-YLUa^+GU&p#?IIGLPinEIMtG|!Ehi6F3&AER^&TF z!ubWJ+VcMp@= zMFo5Z3s419Dbvef?ELCmbRj6SfTX=`baf-)Q8bQey}y8otoMQ>aBi=_dxgM zR^>y4z#)|HZRG2G4ZpcZ0>>aDH0*&~V*@GK z7h?7yU+2^KMRVgs67wm{YF3K(Z!x?JZLSkyK7wheQlEaxD@EgZ=h8zV=4~Jb`Hv~) zRwR*a*f922k?&FBT7eXFmpc4262{#G1g&gsMhO!6m~pAda}}}7;CXWKt3$>T0?w53 zIITQWMV^_&atzNi2*;$1Nd%-xdA`FtFXwQPXBe@32pGD(NqG(-;5D=ZuTq<_#me&z zj7E0&Xct%>wnl2^8r{%#tAWu1eIXx%)%^X+&~g8 z781OXHe(h^c*z&RcnpO|LZOgQCM0w`3kjo0LKwfYWSmD5$bU$0l3-^N*e6asvcX6J zN%I;VGvw=+2dFwg*y0LfM<%A%OPy$p>H=2cA(?s>`RN`BZ)R{kwS5J(OS2G4wZ?|y~Ub|w(hh1Q8 zg$J3+-9-w(?VpfFL4R+yyCIsI@^<$8%D9O&;k(A|B&Upu?8d2X($rzK&JfBDq=Qy0 zY-E4h*oS;wj~WXpn@cL5)gQ(G)oSe{m_?q-pu^C-wbxUbW^1!e(E|c8OK?#8GmP3l z_g|)=J|<&R`vWnaK(U=?;NRMi+n+M=_CE|f)c$8+7K1n+OWAEa%!E~BWKw%Mj5@Tl z(L&-D@>ukis2p*7vTKsqzPFSv|9a2A7&FEDqQnh!gSW_mIw&t`gJzCw}IWmcm#VP3sq z7wLHo1V27APS5kXo&}B2>R8fq0@L%$&KE`jxd0iA3`?bMu>%5OlY$D?s7-*pu; zZ9h`E44I4u6o>h+^Gj0s&s2#eXj;+ow6$5l^dXg3BbBC3>OY;EB$dw=DnCZgXeh%@ zqvD}Zg?i>>u99&M$v%>@E*g!Z&LFaXZ&AiK%p>3Jdfk#h_9qFNkdQ`MUIkm{c#L7j z*QEYNw3$%WSf@zXZ_E`Eo`JEcqimuq*OP>?S&;A;ku;u}5|$nyAw&4Y|M`rA8wECoSBR=`fNp7r&xvxQP4?nwna4Lmv3Z68)|{ zqYo{4_S&xOxBSdL+Gg&rhrnkyHD=t1M~dDMv*W!L@0uQI%m~vHeoeqa-B#7EBNN2| z=vrv2c+NJYF=Gwhje6LV%7lC!)6y}l^)TCTtuG`kn7gs5qBwSN{VM3VL=rq8;wPb*q)J1ZgPrX$ zT0aDHv@(6h%3YzeyiIcuMR+STxnaxxZrl1k6fGF(je4jR5Gg?NKuVq}B_C=fr_%!B zGiuLM;j_6>Pg;|Ie{N(>8f`7h;gKAB+#DFn8`+n(VP$ffj%r_7kjO-}z!SDpLeFAMepMeP$jyCh!j(77O%=7=940|ol-$upq{O9oe_f!5W56F*l za~VUw)9I1Z6FL%F&!y~WhC}vu*p3gAo*Tpy{6o0FL+LT{dp**vumALHeSJ?~J!O-= z?fVecz5T`u0cra?7P9a3W`6RU@TBb+eYLt#=!%mLpMY0A@*&2a=%hP<8^?5@pO?T! zoBG`kI%PicTIEyz&SlJiOfS~w=H%FYm8)lp+Yhmz0e?|%|l2FwZM4=5=5MT?0SvSx##E3^+vwWorBJs zuSfRM;G{=K>nnHJ8u90G*|<{=gZP>XQ)sZck93HvCtZj5BJb;wPcdW}Q{U%kbg{!5 z8O$=jMH2^n@eC<*b;8VtSef14$V?2-YEfMy|}Pb9gsTbs&kHI^7rPCWGeA z&%HP|utBuf`j1nM-=Yj}WGZa1kqq?eIZabegCZE=J89aa{sN&!CR3{(_C!3HskMRF z2m2zJvY9=!2AjM=-eroddHXC^U3FZO}}xwV!3mDP0Jj)b9_w?kf~Ys(N}Dy#kw!j zImg>{U&ao!p6QC4rZsDuuMR>Sr!IN^6>tf7QC;e zciWI@G2HFAJAic)rZ;@tqmTT0#d_NJt?%r+SHIWWggqbgm`*R2R8%}&^xnM5m`SewWPu$=ectbT+<7A(InXPDGYHHhZ2!kLDNb zVGZslI+MQ_(7Thr7t(t+e=nnVH-8V(yUyS1>D^E7V&%E=6J49K ztjnMmTizDEX)-?VwRy1wq-ChvcEct;=Q-OAF?ZS~TjK_@TvINVXFYvwt9bu@$raPL zeX6hjDAn?pg*N-ZJ}C9tRBBGPV9D83*QrOg=nWm;H@ue;vO%-d=a^<2iH8&|)1x;~ znOt9LBtnCnY!zfZC#l(x+7Pz*V*+8)thOW`a!a189XvYOpb3y3jkeH(TJs8eQO$r6 zmds!vlVS#1+V`4)4zB4D$qdb?|4^#`jj7~^KUROvLnBg$G$K*|&0R-(3B761?ZFhS z^A&tZ3-}*YEvl6|ZCP^$~J0HO4 zy70jDLhf8X9xSudw1cH07HriH>hhZhKxuSyhZgPci&kN=T5XREKu<#VO{b*DH0n>F z3OSXAzU{>A#_gwp@`X1sxJ5dt7okV7{VGOV@&+;zwdIryCy@^Ro=xwfkGSbw^bwuj zMIT}P$j$j#Kho#T=Tsq|1vc>2Xj|t$F$l+1n5~ak9mR;2M(Rh8icG_zUvIcF9nF7q z-DI@-bSHk~V+O>U0GfiB$I2~)%D#+r{G6SUiJuo`2(5HlU(K`T_2`v$qZ(E1dPq`W zAzQCP)?id;D$Lnq8-o5bWSU)G4{?>4mhpNWZfe6y36sfnDrW%7k&>hWd-oyc2!6m$ z=bAUj7g1lbu$$M8TQgI~GAOM?ADhayMs=wrbefwMW!;F{w7_kTe6p0k4h=fBOZG+j~Q3@MgK(3>KpYZs!PO^9?cuK*EYn1 zH5tZ`h-Y{-@63oNBbo5G&G_066#WW@k7#8X%|Oj=h(e`7ax zV=(V(Wb+`cmBLUN#h1~h4)gmfdh{VG7t1Ef*Es~P%I$T&H}aK^MVPb_Yxtxr&T<7V zOrRAwC;%VVU#B@>N``wzbfHs!Jm~vDMs|2b$6@PZ z+XL&7?0_xc0^%-az+WY9=r zjf#;kV6uGFC_7P&a$lqU#zh%UI-ZgZ&txN{S;wIn-jO?JL_Q(^*VoZM#4#86yWW&PMj!c{-tf)EwpIO+ z!wa9l?EXz3+bVo>g+UO^_y?`H*MHhaZyL9hrg=T(9kGwI+0U`t?2{dO!*fo(VZGC4 zzp&jl#M@yTasi&XSgY=-d&?JjPj7hdyWB4~_O&(6Mbqm|L%sU?_aX1hBOnuPX&-nX45 zDeYkI3z-;v?0Hm-n~KS!V%%w+&(Lz$+7o+IcC!9YS#aD3g~kRF-{+L0hu-kRp7$NS zedo*Rs(Zcj3J5S}qfb*mV(m}<{6piLZ6&QjNRHDNEoMWUZ&a}#GCk>pj>80k4&R4> z;RIyUn}goYq_+%ubJJTUy-lIFQ|V1d^Sa?l+2rtqI_nmqgdn7s0oDl?vcc)E8zJ1^ zjd_8_KR8HdDa_q#59$~7G+sqK5YEQIzw6Q3GP4g1gcDP}iOsS99J%zBD<x154%!uIQ z7TXeaqLRpq*`m^~Kk-=QTaVKJ)?OOj%7@cN6mPIS@Ei$u(tvuhIdF=7HreA{ba1A4 zuRX+g+Se$?ctn{oTC~xa8iVI_jcJCpGhuCvc@&w%w#Ac1MyJ*UWXHIT18Nvh)8RXz zYiSK}S(+BwiV%UZ1f_L7EBY7NQ==g-;z<+sL?E!%LH1np3K$>b>p5B>?Vy1Ks!+$a zHPWv!A_R!e{SV%`zef28kBYwC1&Zxb6ZUQGzScxzkboSDuePIT)+OB*2c|V8nLFZ&UP^Uc`y2Nj4!Hbe?<8(p2J_gkuUgC z7t5A}{%Tu!3)tBq!x{M0f`y>Ro{I^`nTrvZUdG{NIK9ly4dX+w267yc1-Z7HJj9hv zc)ix^>6GAym!plnn>`Lv2LX*#xb0?0r+8Cckjg5XF)EZ%2o^W7%!t(Kb(xYkhY4l< z+Xjc~yg=#SUon4zKuo5re{b|cX5l8+VgoduP5T^@#XBbHR@nDJ^y9${AF<9t~Sw5 zus32_BA~V6lXRNQqE+YwPi3s8ibTd`NV91p`@-RhMf*nvu-H-8K;qeLG`vU=7asI_ zY#VhXHRyHT%N&h13c)&7_Nkan%V64Fw#FhMDMyl2nNZSz10>mnB%Mh*MM&EHLa$CI zCY1E_OR7#-LNT4nn512Y@!H)jNqQ5lb71Xi50K>GlGZXSQUzOuumVZgwF!ltYzi9( z^N4nMV&p}?eeR3Qi+&qjwU#;99j&Z+&drQW!{Tt&I!0kbppV>Pj<$Manwvak<#tNk zJdMp$T&-()BRtXYOv@PKuy3x?qieP>vElZFf^z*#&~)0#dQXGzS?fjH%9}}^$+BW2d8XOTdgF*qr((VR zVLvL@O=U$z#Ui=ctgj5F;Tcm{8flDECwfyVrVu)|+0@9+=n_%TNs$GbR}or51kjFE zH2SsXZD=dRwhQ|R%=V#->=}{L*4)U9wV?0?5L*UM%=V}+V>ks6+iXWo$zai-%J$sV zGuG`za@`L4dBxkr*?}J1Jp+AGUjc2%*1j_;G74>t6*R^&Q?6kx+V>&~evM)#ogqTX zCq3V5(hJ}m-pD4@jzXYjNO>=eP6I)7aV9Fn8Kk8hR|t&El;TKotS$ zN01u>2kqi7qYd12+PCKyqMq~0@T0h5^^^>(=WB!5$RT`=pT3Mt{KN(d%O32p@v{Wq zL|1-^cpWPh8?;b{Zd6D`x3E@cvp4!HQd#+%jcgQ-y&eURn1IY)0e)kYBp|>9z{+Ce z97IyEsb?c3N)HN|lFlTS1^Y0$lR$rtfql}8GXI~O4GJ?Lyi$1J>>Ssju&7d!k z$UxgV%zHu!+N>4mDWB>q+SWiPIx=Le$EO}_rfy_j2alMYfrWDQZS4FE$cr*MK;Fep zdV?&<==SC8s(XMo8-8CD8lVz%qA2LYkNVDh=!W$jxi;&Jo%>Luh0U&Aoe$EBx!<5cJAsqttg6uKb~fY$H5SMZjR}|(nwaBH&VHU z5?j2HIqfqdb9Q(mGgx@5&fxuW2J4sh0{EUU=ROvZwKWc-Q|P>FQis*iHQ~9uYi9N1 zo$H!S)VYHAI`Nh94BSwB%s}VbBRW^X7P)HKRG!->?-G%Bgp_xV$ctGzF7Gbb!}e%HH}d+T57B&rs7v%oJ6@pnpL&49 zhI+JtJ{$W+egzdvGW<}Y5V1ZsYvMi4wz3Z6F6+;bLSH@*FQ-w-<9elcx#$}SjkoFR zzow1N77A{!tO5_;Ctw_KQxVaJbjofGM$qEkY#`o|U(SephTZO^A?h zMQ_8<5bU@c^r$io>iJPjYb!-qMKKwp$I!6q~fQlr=!FM~9X z>n%NU9~Tzo8GRHhxhsQ4${CTD;Ilq3#2B@coTvq_qyV{n*O1=+Eb2w8l4d0NQa+`z z4gH!t!*~ZDRetgicOT91EhJ3n55v$A8q%MR)R2xo&@nuzUZhgzUFexKU+a-K=)(~9 z^fxjY#u?0e2w55PMxL`Z)?oDWHccI)LwXCc`bOfP-|0aR=D`%m<6l@(Y^(l6R0Lm{ zUh+lSsqb#vtv7u1y`J(t1!851h3Y1Rnwhaklx27W+<3=QA zQ{9{5`^%T>Q*4c&VYtOGi)G6DeZ5VoNBL4-L8df#g4=EzawvRYvc2;KHYU3@<1%=# zxz7I$K&WohN8-12dVXbF^%64yzJ3Y4@nz^qg0^*1(C&GZkSg{K3v+GuQ~Sfc`XQW% zQ!F{{b)T^BX1!mAY>mf5K0?X%)J;%gN}JX>7=Z9!4EJRat##fH2a?(!c#z>25Z+AF zLOr9mqeY13BRhj4tdYX>?s4t!oB)#Mqi*~Lj5!~%5t@A@;q#HK4iv{nlIQBWI+s#e zygx>|eUaCFDSJdcnH6D9?D1pidc&r4+mI^_)MjcA<$SL*gq-9j_|AIW7l`yev1*q3`9~05=*$>q#66b#(v+;*el-B zjZX3AFy0k!nZ|bUR$%;HydfIDJLZLT3&?!*l1VR^!!SUxp9nvo+zv{`8Uf=hX6lWg zaAK^ty{1!q8Nua#I2nNzI+AGvxDbWlWQ5(APcNG>z!H9$8?jqEy&E3Rpc`l6#TU)< zLz`D@L-O5NJcaV~XdZR1(62GLHeF8gF+!zmwl%(kPGlVO4haVb!q}9Rj!*3H;nYL- zb5vNKpOv;bk5`OTCktg`t&R9&o9!wu=67Qwc&XCa#7r-4_5wyMNl;;GVQ{Ka7e_)DfSm%sRp8T_Tdm_jey zFsM4>MVHl^#zCCjf!l957*Ae3X@*H=H9a=7@1%qnDMO8=<8(BJJyqy3=^_R7G2CXWLKTrb-V4V_b?C| z705y6)EN_AcxyD^(-@0BnBTdm@z8L#s}`d*x^A%gi-q@vw9b?9gZE1_AL|eJ7=wO! z3f5tRPCY+`X5N0OcrLVMzP8Xdd)q?W=;v%#EkK7s%K2%4{{i?-z#D8=P3Q1$Fvw=^ z2HXi4YK-G>ARTa5FMJ$eApgR>agXhSf8oZnpp7!)9XEUL!aMGQHWYZ;in*l97{hk; zS8yA&E{+gocB2@K8|Qs#yZRL>Y6^7L!Kg?3<=_GO;!U*6i(!DeUOAl|hNN z`5Q3gT!bCb6zZN15IDb&pZMy7pCvfA@cA=rAq5^P5IF%-v3O%lc9!9Sx1c0p{a%>E z3biw77eT!JxNU$?@DAH5*b;?e>7YZzzJ*h4nRICJddfnm1L%jevT_4$Fj2ParIi^z zet=;UJPng1z9;#CQRz%~I|$Nu<5NsuqzZj8{y>R~GH7EsJ40Uw6;Rp*m^qm0uow0R z0A2+E0o3+RR&>E;#^OfWx2WB7EI-zU7hFV!y5M!(Z7^yfo$f-FY}joc=V$ySj$5aX$w14L{I6{}+4j z0v=aY{rxwzrBREMDupN%A_hshXsV!%fJ}Nl0}~o9g(4u~R;t_rB(#b^+9b5&I1+^_ zDoRllRFtZK1-YcRq^Ll-R1gIM2t9|iwA{`PUYeXZ;-19(4+zzCd7psKiY&&A zQ|b8D3%*)^Hc_z^IKH$L$CGkApa`ppe%u;n;+i)F`47iu@#HxT$(s*n8T3Il z8tlL@CA`I!?1uJ1^m*kU!~S-?Oobdp(iIiB>CwPvDpih>@A()(kY|-YLutVb0Y)rF z3(AMUE#&iS$28ph>-4>8Y@A5i9ZjHK?%awk**9Rhv=#e?r1)9yRAXyw%FE0_8OqFo z|4sa7(Z0cddcDsxG5!jfhWBU%4CJ?Dv@dIY6oHeTQ)=5 zUTD8){1693`%y8m+PT>k=yvuZZW)x>RXU@YV(=AA%%ukO{vJgo4UP*^T401?V;fOYxydN>Wm0rLJ~k#82-*|6Wzh6~?su`GtI-{!jtd8*K?q6%>` z4GBD|ke(-F#T>6tlKqh#sn3pu`q;_!zPFQGs1JB3tq)UJygn$|`$8pqWQXW5o#^O> zDuwOl;MO>OQXyH4&GN?f_>FLo;3`7lA7D=KM#0AmeyoEdg-C~GmVcVlk3k{xNec?) z&2GnMVmLy|P1pIY>x27<7ugFHhtrJK_3_FVNP_Y*_jzOg>Mh;8UGUO7B4%eybPcs~ z_AK?s+}2DV+&+sxSQI)NBG}*JblH&U4a@*lDNH47z}+Qb#_zoaZA=eS4_uZ(**mNn zs7YZajzPB-k|AmZ%?@oqb5_CNs?T7=H*uIkDiz|a`6iav14s&>5EGVUDi{etX6t8z zP5K@lv})}h&>W+iSNxt$7Vqksh?VGvrrtZe;fyyJ|X?yxA{*!%n)evfpuM0&is z)h&-4e`1QIx9SI-hNe={K2VvjD7h#?e|yx=>)^fxdEfZyv0iQ}SfT5}onI`**dUj! za=~IuERz38{-a-%?bsyNl~}`Mx6fOT$&}2Qkik=pyWD|rBu08A6^~3X!=CY1!(7Ft zjP=xdcSlAPSaMW(nbqP$;+t%z!C4aXk07hWybthKEbve-+rWzEo|bwUKS*+|6(@LZ zyTW)WV-+p)1z1hRq%v#@Mor)k&T>#KtAPpSUfsslhr^3c=veQzXgiuZ)QXj{_;)+e z^dWV)6P}Zpw->%$9nV9CB1Q$2WeW@?R>J-=MFMe}@Qg_a(j zzalcbZ)J$teyPOC|0r&dt|x@uK=EXVkoj5`Ww)7XtPXITSNPsdXDRyy-?sQ-?xi+M>|7Osn#;y)z-yYadc=20ZAJ+wUIRV8jca^!+W z^skc%hf!qHl@*Xg<%CRn@0xU7Yt4nbYtsBEqlHsw1Fhe7X$hXV-$HXAz-9+U* zab$7h`x5iBRP=%!bfl&3CCN=}(-Q-&$ZIX{qdsU29&G*4V8YfYYw~Xe)BR6te9)c? zQ|yJL%GNYsG|}<8(Kaj2i2e%{eVU*6txi8 zk>g__eUA5!q9cX>U||vcJNle^A@n(nfG%z9EBpEV*F>~>`K=IiR3CR%0DH&+t3S${ zyH0b+X}Ve=aXWkdE{He(9M ztV#)9^XIv^6_(`zVcao=xSrxBUEE__T%BA@bi9E&OT*{I8$&WhaJIg1arY)}s{PU` zSmD*xs&fk6@&dkzj%lPszD#9jGc2@;zP)w@nN*l5p0RQ9xMH+ph)L`lfOt6s4jGyz zrDE5R5P?4gNL3hI&7{!TQ_%Z{vO2G&laI|Olrs4;ss^Akw;hbjjW*8R$mAT=vn>@4#= zL++l6t6Qz8zQV>+pY2maZ>(-paa>e@M4IS0$y(Te_W1rp$L}mh^lDiE9OYEnB<3ef zgXrUaW}z@%Y2%amCiILTJ{Zw~`E=dJM8{v0e{MR3N=0AyNTP#-*whr`mMqXr15>Q+ z#!RlYd|ShO8)Z8S;e{Bnd=bChT|D!l3N@})_iau0=g7UKn}m{oy|&pWEy2=JSJ$V|C^{k4Y8dMw(NrO7s~!uEXUXU z)2xRK>0A|%nO@T~Y-dnGm4nYQ!{)~?Y$-~5ttEZI9~&keZ)bJEbdPcy%DfmyH{>n%rpR0L@P+O%8k)jl&XiecYq(g>N2O`D{R z|0Zsw*B6X%Gy|Ok$I}|p3*O}5(AmXRLAisg$I5BgkQCHb_qf}RQF*#nE;q5(9pCSP zN@KFZ9{w!?v@cJ3SbRR*kZ}Vvn1==;!h0C_hkW4a1kUVo{ImW%+CLOP=pQG4?^}8Q z$K=lz{G;SQT7Eko*|)t+u~pj&@}TBH1FiA@>hYb!m*w;Pt4Qx<=8JUk zZFIgqeR^T;{CYV0fxFhZ$IIR5+%x2Ec5V#cdh^`7$8zQ5*bNHg2RmQvKHcuKnhyzl zKKk`o!FK9oW_f0Woi%^)Ga5{5{jXjhvK%M^i)0-w@p5y@{ofj0yERoh+XQ3hfclML zqDdu*Uh}ezwIr+YzgC~gE`1!%WU2`emAX9ZrPtwn0Mwd@BCQSZMlwWl$Uf#G(|Am zj2Co{F-);$Jl&xOdg=(z?AaXEQLW8s%}}(uqq<7mkeq7OwSuyE%*#7~Mb2EUpaON> zf{LI9yC$`9+vZ>k48}ea;VKndi5W03Dg~fVfOPibiLtEvaVtNMm9ABSI7#gqYM)#` z11rhg_Gm0zM|Sm7%{BtJ?jB#` z2zl{!A(e3TV@SyUx?f1|P>$Jg1@%@Ke`3>S!51TbV!Ao;oi&+1V#)#Gksl;|>IRT<*DmQxIICPG~4a7U$A6D?i$ zbfV)Y)x@W6)=p|rtMptwQ<3QS6uoSlK>G8BYS3qyW75T!gTuY5f#}O>up7};gDQ)3 zv&$*gO;&>tk#_s&-B6DZXjQh`M}I9y`$dg(`^`q6GKknjeu<8!_YnU3Fv^?Z-4@xp zrN?fJSV(1lN!M6K{CRutO>JNym888w6A}Zz0`f_#i`7tm6b|Vph{GBu0&=H++m5$I4QA7 zCCpaMXm<1$`W@^2Hcy*HWWieRr5+ay1od6tt|96m|Q z-c#G=<=Xx3B4SjnM)5`^b*7k{+m+BsDU0q+1)$n}4M7%-vB_+<2b36BHi^*xtiHoH7- zcaS8IMhCgUK_~~MfR*!I2N?py6?DsJ3ThM7St2&*>Mf5&o3?1!)!5*lN}#L?g$Yff zLYFo2A=*>W4@)WJ8tQZ*IyOd2Y5&Es@^>mN|8$i6o=^T;{DuUg_|hR@9ao{mkT_1g}8{C(s>9Cj@pJ; zs&d!*Um=o&3P+mAF)*iNLfB%_On9x{gb-%K6fs+Ead)rybJ zSVav)_Hz=Qe@03O`IsFjNoQ|Ztx!m=P2cu8-jGB`r$$xb>`A7__GTXC&JQfn-AO@N zpBjIxTbh`E0Pz#^?w3f{eusg{_@p%fz;)_kO&i7^VOG8#uBk;e-?tf}Eap@$`= zoBx!?)=#U$kfcI3h91`6(R$16&si~uO>?61Dk8l^*iKvGgtVl(Rg#l_8ef_(Ssuae zsG0za0oX`(Ri*)vRK*-Y;@U8=;Nz8;gtf{w84G9%1GL~$TP>Hi5SRowBLa4ZKu=lB z5|keink@pb1qE1F1Y1>rtu`2S>BFHs{6g49Imv6tP`(N)mxEsd$+!}?zBS=@JYSZD z#Ht8mDTNnvH-&CtsS&qZpCKiPvMas^`8y5htZ03fhB^!Dvs!9nNnT~@Rg%ZQ8z#BZ z34N?%giyCWt01k`XRN=3E7o{bmiUG+@uEWFS%hm5B&55<5B*SM?^LHSm>H%xr;uVn zm_j|`Qd~<4?NB4BR9sX`+Q!6K?tdpdq6sVg{b62v6!KaX=GC3gYq~3ahNW0lsUp_; z8yDsq>xU`&@+m$}3L4u)W7Stos}pBsnGM@7n&Z}s>NpW4{k$mbzZ=5ulJKixpXm6- zhrmVFE`&1G^Y`TkH;T=6xBq=gLP%hCz1hLcCS{|uNx4~~c-{o$=O&oTnE8RgTl&Y^Qbm3Wg^=;&8@=5S+SIaDH#h!>~WL>)URs z8Y;Fl(Q%EW^6am~H)QKLe<(G-U?(p(iKS0&82Xn@nmamN#?q=UQp{}o0{esos~s!VU{fgnZA8_HItmiDp3w3>N^_D!qc&+aRJs#ef3lGHC&PC;QhNngEJH7Mz;9w0G*XUlGQE+ z*|V}DiKw_c%pz(28x5|kcJ?2FI2F@kSmsMZh*ilTHvyrG+pkhC?SEXv#}>lk1e)h& z@HMr8SO&c_N_5}HZ9|sD?SmG@GMqQP8Z*jKL{7|m6;=}M=X{Gy#OF2HxkYiM3e?Qd zT+oL_>*8j&F8=)@qWBm7(=ClFwKP`k!lkjzn^2^Q@=h$=1?^paY5W8yLQ9s$jg-zJ z&I#@h5Uxd> zX!pYsm6eu_3RH>8&XsthX=}m~+mtq38ZW?YOXF3X+srSGv+|TIjk}a8S{h%XQ=YU@ zS*b(?szhbyO1#+=JYk88lr~%%-+*c4wHFIK8(X?#}LMrEZE z6{r%GoqjeIyQOhApsg;AS6O|#sf)xcs)V|n$nv7jK9#z$xihC^>Gjak;N*wQ-n z*6+Z%W9#BifFu7}0oz#@Bb+t1-q(=nV^OS49JqeCBEEzu8r`ay*0HL-=$C!6O)Xz= z_8;-}_u(bwTvkpwb;adG`Q+EbAF)E1sZ@wP%QGT`v>8M%^St_PH@ce)qV@1IAtb3P z(E?UTn?_LDp9K%s!<9DBSr4;ocg5Sv!Pdi9n`EaYaV66iOX5{vRL!iA*DZ;wxQHQv zFIo~0Lq0B95?3iU_tzMmzy4u)BBj$e2PvJPHVTmZz}hrg5=&H&m|K(RNPiG#xFk*r ztR?aNtO6*ZXi4n3Qr(hxnMH6ihn8~|2<0gU{U}vSVo4tq+ZZm1o8+a~TDDnTu}xZ0 z&JtL~K5A{j(k**b6D#oE`3*Sf(TapO4xf}WtQOe0N2;Pp-cThOF4I0lLk_S+0HJmhB|5R7 zUC9(=(|@MDBJ|pfpJ}g@mm=lWPXdE7(F{J^AN4KAY&6$XgDN72xyq?r$15b$UK4sH z1mLX=bCuU}MNY6hEZ0BgT&|i$k_#sB`vlyYeq-G?l_IX+c+5eP1^vb< z2dOIPH*R$h=Cn}1@gq9jUnJ<(^c(F2O1~kDNH)qh@ZZsIe73aw;VQpM(5>n>wzD+F z`i&Q|YCXDyn11825Jq#giZwk*kHO;ljjz*Z{!IdJLBFB4vC?t+jc*Vs5;+}V&Ius} zQk@w>+!#fz4EY`z!fbSh`i?Jzur`fFVA6N&9m1MISS_%fLYSKn*b)J@T?nfPB-&2cZP`bKzEit(P{5DK)G#%ut)CJbBoZTX+2l90CZ@* z%dBWiNH5#v6Vb~p>Eq)!hC^o-=!x07{E_5tCY`%t4nZ+%7tU*9H<~jp?3a;!@V%#G z%aG)xenG9Y>Ky_)oE=Qq|LA!He4Rg`{1T(f#Z2A7sRU_Uxq*@B{Jnrr@W;iM+Q?1! zn)}_9zlejDLHVXIo!bCtOmwDR2YexaR4>`f?B+~uJ~CWrdCh-=dP_LC0Zd9V)OLt7 znQ<~oQ1zP9c7P%=3wCM39hxpBKn&H<=QiAF_G1M@TNixo)j{RmGfY7*_?fW01+F~H zE-Fvi@QPQwyb%;vE?y-zL~#}B3-t7Ep~12+*qe4o^;7#;3(Az}tCXi(Co24%!xF{U zBo>lkRG=7P5TJ95^t2KX**F1jzn~hyU&D4#a24qgO^^*-MQXKm+=M$?ML=Ugh1I19 z&qs)(a24UV=Q}*lvRWWUl3i2{WfMG1H7KWvfLSVMu`7qY^P8Qpm~*nW42r%PmJ{b^ zR|Qn~u;5(S!a3zc7Nw+9xhSd#!!VxYM*xFtzX7tO!f!b*u%w=BF-m zc$}l;CG@Ing6WoaFujTcQJ&FjqcVeD1rxpAM4L*=J5F5-z5cD!l_#lEYc;yZi~3F3 z1Q%G^e0fz7og|fjg`w!AR^@~nv7(cEpDvUa((C&uPxM;lpAnW=X(blXYlRBj%@Vh1 zJjTZJSgY@I{@5_Jm@DO}QbHG(57c~sy0_^ML;aC}v1e5ovrFI}sfA79zuFR)^< zZGP|tA;#1{W8AWrttKil3uH6#7gnOC1xm{tQHdtg_ zauOm1;i`}e4-pZ(l(*kgxW=IikA_rm0}RskRTSQqPd^8jNF`WpTs6!;nGcUp6|9bz zukq*dzX6w}@3W)#VfwCo_yQN63~JwsmEV{T_bmL7U>?EYxYE4g%mDmZa~UAlKB<%- zY^mTTy=Ct68x-_IaGJ+IO7n6MJA~cbhPvkx9hEOxx`yms>X%gZH*NZ0{BW@0LAHeG z2SYjG$L;Eh{A)|@c4>cspvD*8X}v$pA;0f)CV{E!B~9!}p&rm1UdK5IGRc%i2bt<1 zNF-Cjf(|f9w2{?P?^g>jw?~T*Rl75-trq4DiCe+#Miigao zDVDY(p7s(;%fJaW((wN($N!%KPa01({?7B%>@Wh$Q8syNqYc60rt)-7TyK z#my?t=e#hVT7PPok40deOFlEAe43QcNrm=6FO@>9(aS3=cKf!0Ue2+CO6g^Wpst?= z)60Pb7SqdE2Z_0lzv_>yA2aq^ES_&+B93a0d~82-kop3IlO zxWu8QTzCV2Vxz*}k{JGm2!Frf{$giu{JDvjg8;$hxwKJ_h0NfRzpL`{LC($7 z(vkw~4PJM0CTas)rEOU|L=H*iAaeD{VYOv#z~10*aCDI9=vVdc)*rTT@@9g|6DU&D zsgd!fB&%BUuMHl9Oyc!NuUD$mqxf1C-xL<#92O6-H~9Fv;`I6UHwsZ<`?1&w*B{j0 z1!(`9zXdVwORJLrILIo<6!)n8QWVT|!-rxj!FW-LhF?H9L^<3oRDWATuAsfSn z0PGDC;IYfpsioFMBs27j)`b2!*0K=&-=_gZ_-h7#gG_tKqFf~}4zuVEvjEr|>>A_G zc0akZZt|>lST~WlMu|1|s(cqxI#LECuga z76c-nRdC8+S3I%&b7^f>j$9SSM^~2Aej+l2?n7F}eMqPHsK+L7AJS6pLwe#FWt}9+ zuzUDl-;mqC$Kv=hNbv`^caRkfWAdfDkugZsq0*)mw zPW>IxYZxfu4DDBFx$cL9(xSKM9RaDUG zC-QXpH(NOE`%_#F7wx(5B`&-Sq&ia6TR3%CF6*ud(!Q$~R34Ypa4(@~}C-br*$8c^QWsQgkP zX(>&S?G%Zhasca9Q%>*Z0LIaB?R~V^Eg-gcaGNo5?cI6!3m2*s1m&C?^|t=_n*%m- z{He($?{yF?lVC0u=N5w;2taLUIoZEXfVs*1dwVTbt-m%ktp``#f|l z1jrKcKKMHyiw7D5tY654^?! zp_9oWo#Y%OBKDRh{~|%=uGB~ub~}GXXBH8P&>JlNbI4!w`q@8<7@p&g>-TuQ7br;U zS)&unnyYCO_J~>kPvdlQ4{wwPCphJslYf{)ZsmWQmpf~vRjA_tiZ&_;Dpa*EJJut@ z=FpvJyW=BBaK@K{OWxwx-Ir-mbkuIQuNB;1j=A^FyO#$A_sU=z@WNzC{Vk*1@Y8vL zgKMCYk^jUZe|7|y4?Q%{SdO-RT=%59p)KXdNB6~K4?~$-&mr4x-rK2r;P}Lq-MUZ8 ztD8`6?s#eNPb)8bcs|X}GT6Sdn+G(9*X`ues((q(B>-3I8mj!$7{*7Ho^$vMyTkHb ze#1wv)bqt%2Z6Qz9c(^t?;fTLLiReaw)N%C*V5VHM-qi}iCeiSqOZ!!EaSZY`&Oqj z%dFiN<&YH?rT_1RLS6osQr{5+RUy9YB7QCpL2|yZJa%*u5eiGK?DhkVRiZG0qL+x? z@3pU}uscka`@cLt-UZ5EkN5nQ>nek5&WQ)*+nW!+bj#shcKF3SkEYiw%qooY>@s@E zYl-HZC;HiNVvr~*I-fu3&nA7CHn<1+%JY{HzYWFt`#;mD%51o+g04C-m`wqpyruZU z&%+$_+|o-rTxc@c%lugeVJ*j}GMjWM@Y+-s$-l?Ywr@371Za}hYUL?>c(9rZF5lU8 z0Ge3oY?rTZ1`dX63K-rI45OH}qsyYdp6!P8|HJJ4~e{p&`ij;3l8;-#}B0PbIH*P8r{m`KWAW~KiP z%F*hH!LkyYzQpV_f6H3GkhpdFkopBjS68GISl=^jdqgLfWuX~oaR^(b(vp&UnJ{VT z>Hk=l$}S)GptirxqY3k-T#e9e$E|y?RH?` zXhQwn!DE5c^YrlV;p6Euw~UXkfv5iwe4Gq*zY9Lp|69bzx4CG`pG2siKtH(!d@w%7 zAd_x&d{qk5ShO#8-@B4@;EBO0_}qO{-fcTPdC8t%8}+N-!A9S-H&S689BRh+X?O3o zANH->bGHX?x?Eo14Blj|ci`~ndH24xs`Kw5&w_zCzSWa?^my-m8zcUk;qrxn)pl)c z|0Ci3Ry@U;&R#D$)XTi(Wp8T3#pBy8pJjiuNPqk#!%1Er*m9nq7Q}RL>slW|AXL)4 zK=>((eo+%*ShJg!$2dq5NGO1Qz(HU?(P8#CL;z?t+Lt4{J=row`>nx00XjY{{V<0U zPGvsr|5ld*mlyhgyUX4CCwg8soxMquwQG~aArqJG#ZgG`Ughu8D8E?#eu;ei27$LG zf7e<=;_~-y4np%I`Fo^;(ELb8|0d(2NJoFI3i_v@PX0ErB$U6^syw>8Eu~X)<=Pi1 z$Yh}#3|=BdU*Ui;nR%{3@_3&d?Q;jS2#EACdAa!S5^CO0Cph^fUbh<*bdr;IqDy6<;aspU;z_|7(G_)<0bY7O#&kagbR5oaG>~{`sPV z457!gwn%j7{U(2spo9BIt;+XLm8FcWj}i`0SRZZvvTEcM#qssga}I939bX^aXYi7q zz0Cn*>!a%(B-Ymp4U+Hc`ly?NuM?ngmha~))R}r>esDiGDQM@Cel85H!u(KpABV2a znU$69QuDHR_klY{q(iMnPT7_HmBeqG1ne;Ltza>vAI7U_hGl?IYnqn_h?|!`8c;Zk zk>!sMu@g4<{Ly!3iCQimlD7|9k8ag(6BJ(7P`6NP+S%MV;awD(Kvmwg9mQpF8cLtgsKG z<73s9)=tl1g=Tex*IS3 z7ALHq65qd7;JGV=w{+cUG6&YpHzDHlmS0`Og4+n6jLNI>1+`}$D38Ttmjb^;cJZ?3lIi-ENhZCtR(hEy{fe+a9uu_!cPSLO5^+fVIy#+sRt3U5 zkuM#vwLey#t!{KNoy;1&+d;X0m%1m+Qki!oH+hJhEHLd3{%NdaF}cdztJ^2{;iS$B zUfuH9V|i*5gOAMp{x?sirDe-gnG@;w=o0k!JN0!>B<5Xhq}8vJM~R8cy)vIA$oVI- z5SlZi^*HXu<52@LOyv&Rms>tQPmT@Z&DrVY>9ITx@ZhC~>MpxRudLtRz$yC&PfJzc zEGbBvY!4Q8Gh55&FZ^bAVi%_&k^4LbMA5-!yBUhxgdB8 z^OyR6b{Wtiu zKO)+YajzYkJBYU^dwhvvX&HSK5IRl>{am{2nT9f+G2xxA+^`>~GiTG!lLuF%P1zaV zUiUACgoU^1l+=GWczgC$@jFV0$#-_~;eUv}_9g58EPXxprT-v(T}&TtiN2;Y^n|DV z2siq=^A+%vpy(~r7jHx{ad@{!7gE+A>)jSUq5J+&T#l&ChUILAsS-=ytf=Hpv0H~_f2c>6xZG)73L01~WI$Lx?oEc6_UFr5|4Q4|n{TX;-(y;@k|~9Gtw0YO67zO5dRVWs z?}>>kxh1tg4_f69NpXqj(&vVXEFL~V2;ngd9)&^gmfNv1lq+%*DtacUe#@xe1nM^- ztltFcHzBNFK>ZrHFS0@Uv2^B74X9pDryu*rd6{uuc0vV@HXT~!W$Mw#OyDxwl-!_g z0!LEGw|yyj*KbOpU;Y%&L|1sZuYpPue%hHj;`J$!f3~N>Y9lU5I zGyVJhXXw3j+4_dE%?+7@P)9#wwL7!5Do%aU*@d@HlbkNT06x-}Qfi z->BDZ{!e9IFm%5`ZBxTAg@iqC?`0>#PaaKl zh?$swXeu*>j-I%QZ+VvO$;|N^c^Su0&@+^a)u&W(tbE7%1yi^To+a`{8v)fw5q5(A zB)y1uUCX8um)btr`U9(x?X0dKD3#lPU)^e&&YlJ#=ptxCz~sLhfEou#VnQ>pUCT%y$q-TtVQSj%+4B4qjc=_W|J8hN zjQuTexwZM8Hb(QkUZd+RW4@K3v*r2z5GG9K`Xz3zzfW_0*uE)Y`?y4b$)5I23EMY? z_A%4bzA0h*rqr757H(0P=G{Kvxoqk!BmPoMic&t;&~IYG-=wMj88_9JiS8tlmrnI; z6Kz2(ck6?2zHbTV`?MRI)1HUQu01L~-%Br$U&EAXOr|oM-CGthe(!j_Jqj4!-wekb z+ndTxsn7(V8=c|sr#KED@lkr$i9#7}fSJRT*PZNPmWSQ<5#+1mdtmpTruqA^u;t|c z_NlUs4KTp1@^_s?pJ$gBXQ@FQ;=oGQJTIimRu z)sVde2LFXr9Y;sMEnLCZIW5lY$Fpcjyl8tflUYQC3|;3Q9RLnR7#y9QNM>%jO1k`F zwhov*UKyjTPIPp+qyi{D6yq2@Ze#R^`LEG+c73nytUTE|mzp^u`3E8Cq1Dw5nNOyc z{&RbtYuj^3dMG&1bkdMHr=kR-Q7-WHMCa$Aj{ciNIpEx(Jm*>w*(Jc<^(tFKZNN5^ zM8=WyoByRFirIU(-!J*09R;SBzanA~kH2f;S9f^!fGZ!N*VonX_5#9?)+_g=_xYSO z2^pRge#ME8Z%5+e(|RYECBH3NE;~%7T4DlUrl1m`f1{U}%JGREyVJRY8V}74dk2Kl z8H^K*-TmN5%@aI{rb|+_#aXtou%3`STA)|D%A>2iD!z?;lYE=K;a8DePum<2!MWF@ zx(fonO76wZy@b*VvTP3`%^-R9yEK?aBQZ$mkkoJ@Ez?IXx+4bB*$`DY+x0ZlP zzNiN;ZEVQQPH8xXU=nCXrqD(j^ z2`5x-cA_H3Rs_GnYvVTq(HTuda%ppn4w#ghp@U}Vpcy)7h7OwFD;+fF*ECz9gWRyc z!<8oTf2nbY_7yb+m1s2IsmfofqRuDP2A{DyJN_>CIeM1)+~z=AG4jt$;yioZQ=o<@Cd8}ix!e#U$on>6O^X~Xob3DW9lkFqQI&dhv z7sr9&5KzOHSB5b8gKyL)Ze{pqW>zxftJDUDd<~{2mwI{x_n2fVcXykhjHgB(-m93R zzr3{qDOOC;$R9Ozmbp(LH*o`njGB6uv6@|7p#sAmEF+w=8giEzTgY5GhwK-TJv^t0 z3e3W(3N%yIkaHLxG0t<7As_;~3@kAPp8I3v0@o3Tp!{pZs>#E+NcOJK*KKj&TXpZi zZ!Sk%qBcSgzPZj9@}djmo7*d*NagObkK0gz7dhZ%O9*qk=$I|@qG{oP{RH(nqarvI zua{W`k%ol&81iVYln+6l&CuuKHszjy4doUulJkEDeZD*I3h6U9?1ylSwuoyWU~Gkd zoulW#&K)28lnt23UO+u_mwJjI>#Cp;EEMKrgaaI$9frM4WqR!9R9$ys{^yiqhSx3~ z0bol=|8Ipqc}*~<#$rCz4T`+X0?{%7efkX7zH3k05|9elTBVP`y={+%&YreDxq8|* z>O;VgJUc6w3rJNSQX^Ml)PnJR`G72*$8AH09WuaKa!~_`MsT_|mDQ765J^XiuM--_fgDRJSW}j(D zqSKlPZzNtaUH4R?V~Ncr252Opi2#r9j8x7f&UEJVBzbr)k4BZ%Oq3?C?r(_>y}K6z zn1?JrVO-W;(JAi4cVQb}qA(#{-i_1CoY+KmvvATT%}1Bpz{}pUNTIo$d@!!>DLvo$ z2IeWP4jpSsW&RMx)(2lVA1`~0#s)r39jV+O`UK467U|R5sWAO|I+aGzR`bF5qg$Wc zE#}iLbR(>QyTed@nCSWxDSPKC=X;b-;?_G2n7O4J9|b5(zn)H|0m*l7sTM z>GNeF_#+*Nsn6U!MC>Yir+QU0{(N%~tp+#+ngvSsPQ}8fLp($l5MQP935d^(SF(2s zh)>ChDImFClXOs(2~<8SY`g+-{_mU*($VC8o%2D7T7-Pp`CuFJEx^ZAZ=55S(}y|UeO4IIo$c^)ot|n_hekQk z@k14xxfdd3`JpjEWru;|E+JN~CSZgD&*-gRZxP1cfv%_g~9dX&8 zIrnFa$(pFwck>N&d5q0d=U%L7^6oYP>s=Nu-(RaU3A(9IL2tPDd4<8RCJI$7L5H$7 z_P*S04dROQs#In-SfSJgvU06)ZmAFA+?VyhP)Nz2ULRWz#P)^IePibEm2`Hu1`PZA z$8@FZ?m2&KL*1hnR!iMce>(_c{_bx1n3q}3WA;_4tcTIhJ+q(EQTn9iO^ zZ#>dh%sVnXFZW-b44yb_J2RD8lg_o4 z*JDoWs(#kpwYdE6Owe5Nd^+>uq>L@Yz$up0ndPbIN(QF7D*snsAfNWhHN3cMB^w5| zFrN{sO1W1`>raZ-acN%PyWGnj3Zf80bWkFDOt~I&oOhw-To5$|-)ykPdz1IoC%)5b zb~7w$JE)|d;T#C01dROFUVFvVHg&2b!^BL~p$V`V+O6;iIxm1`9`bH4m>8q38U?rU zZjVfoO@sAaaFfpNdG{4%5ZwmXcJJtA51xkG{{h|8*`4TIYvBhR z4=j~E2D*8$q{U7O?{r+UfYpuiCGdX`JP6dR|gtmN`s#SS) zUik%20OFm~2V2*(OHrPxThYR!v_~_otL}A6&)-QnIuX}wER`O*;HXf~es_iX@V+EC z%*-g)f#T&}<~eo-z3k{k-{C=WAV}tCEk#LNkr=DKt?(~DnCPs;kos0g2xU7*7CsH^ zuW(QCdi1{8gU=+ff7v05n69qGGJoWrH58Tc6P<7Kg$k_lDccy-xY;WzaRVHx%if{hv~#GP?+Rv&*HNUL&2|@3&+` zuS`}C9gLgK={yON(2fT?;#M>|0*W5~^Ka7`I>9KdY;JTyWoHi_ubOaOu#DsV1Ff75 z{)bggCCT#TTub7poH1cJIt|zVT~1HD0_yw?q!j`7Z*PC$*5ERZ$PkBnk&{1x0{ry{ zZbd#v{6<-wS%ZC2_!KXK#g_(?vJB6}rTtS6f~nJO+I;J!BhuM}uW}V0A!>b_I9_(l z7(l2_pd8XIQh({{K+phmbZwUc4|s~txO@Ch(->%r!<`m7qdeQnu*i=TF3r}$fi2#T z7Y!B-1YVXf6aA^=l<52$=~-Va>}Kg%&P$?fQ_=&F7O^TZSxEM@0|nH}L4$;!k+<#*ulvx(EX+*?u@wRSwJzHUw8%4Hv0 zT}-Q-L{pQtxUMUlMewpGm1jQ-$EKNDwK&naJLF^;GC}MXp5RjFoCthU-M-Zv=n7B}YX0-kUvs?csRC|OoCp$SFVHO0a+~h62+e zT+O#nX5piI)7_eH+g+M|V45Ip!u={Q<}%?L7ZwNV-+A`?I=VI82AXakiKg4Jl0dw= z^U5!HQqygJ?ET)%)9ShhOpT-UAhyWN!o4lKrLxCXxkLSGVSZBTNtL z=HJ6XkC&Nc^Y2QVf7e2;Ra9|{^Kas_LOivV$xeL!J%j1@HJg6deS;>CKwrT--F2tJ z3YIVsC)MqvzWBAqwX5&yV37?_`gyHRKZz)J4rEB2=LfI*%?@)N*S@V{hiAwdq`%1r ze(fM? zT~qgvu)NR0Ef}u#DkyvK-mbiMV?+O14)`IPddlnqmAQ@vxp^XF6`jwLx2kj{6RUXL z8Y^q~uQQtX**0_&|4y!Php6ai;-6p{zwUoj8UL7M){ln2;O)1fa-hKPlb4DES38k` z#Eo-_-oL=#Ko-aX{sI3=3~+r}MMnOC6z4zpnJ9mgU#C093DZm#$*$wIF1WO2NDK6; z{nd2!_`Cp?==`0AC1-z3#*XA`KdU~a@}Z%3xqSOzbX z8Nr3S+|B@nvJTkvmdIg)KZ>0CyZqZp$g=C_e_|4N0+293W&3xNLlRBAFjlXB0=puB zPpcwi^GlF!a)G~*rrHU{;3@jU)kB#q?<%N3|DXT=;p6{wdI)+yjigne@8Az5{_9Kp z-z)LYFY(VV@t;xRKeog_wZ#9q68~N${+&zwBTD?Qk1KA^+7kaGCH~$L{~t>H*O&Oe zSK^;v;-6jOKcmEdY>9triT`sY{=G{4JD2!Jl=xq-Eopy=|B(`ZZ;Ag8CI0J6{NF3_ z&oA-MF7cmH;y<>;KefdFxf1_gCH|f9hjNFB?b8tD@|q~jZh51*yX81f0u@@4@#A9m zORx)fyqR@ozdl5VfD#>VGK=_Y$dPHR3Ui;bbapZaupXQJu-$D~W^#cyg6} zvllCA%MSjJU8r;;h#nW~kp-X&9CW;cy1P{fsPNCV08^NUVT+Z}!j5ub0_cZgR@!D4 zCVa%y&xCEvhwb9R1kjJLP5O}MF8;u$ES&)Qk;M=&WzKd}2g;t0ck1gNO3ZtPDK2&% z8J-r}Iq7~0mRxU1%jan!m^)zVqhy9Qc@zha+78*9CNHEG2&}`>xl^SAMJ(z&UT3u2 z`mHp5?<1w@r*BjGy#}Qpy-n%o|FyLIHDKz!*MIGr()0_rDgD$z>8Ec~`s*JqEr0Yj zr5`aU{hCj1OZ(4wsI>fr+mycd!P4~8w<-NzgVK-Qru6e4C@p`@e%sRiwW~|hFWjc| zQwOD=zD?<`zrVEn(c6@M#Gv$R&;Y%6`ak2o(()H>Q~F*`mlX4l>D!ckuR-ZYZ&UjD ze<>}0%|6@G{OUoakCI0hE{HK)ok2Jr#8_>3V zZ3$OVqyW|iAS>kenZ0HkRGu2UE}f~aPPMYhr^acO+ z-O<0gtowh8;`V$_*7|z_^fy+8+FPtji>h5SuDg9;hs68@8ep~-=G=z8z<_t^u-m<| z)n6Fsvwg%R6VsFHk4zmtwFesw+vw$q>?F}qHT$nY%TjmO#MIq>8JS_dL-pBTSTdPE z7^YM-)=xibCOdIElFv><`tJ_)4)se?hldd+A3ka3q$q}p+j&U;RgwM3-N#_gr+n%s z9-W$rF{{f*cOav}pgv0)kDNTYq4DU+s^=sro-1&DWQb1Tz;C=IM@^qNaq{FzgTm2y z5q{UvQT`LA9XT`8;_{zlwFnYci29Xsj+}hxf)eF3u|Azn9j<()#_DT#{8C>RUR2KfLODW3dfHJ(lX}M?!8rtk z`u!!1>H5PDFY2#A_TQ17XUW8AhaY|9v~>D*Azt-!h0n~en}BzhAwd<n z#~ywXB~>1Ebp6p$6?YW|#|#PHWRJ&RxLdd%W4i+=OGX3_0^)r1%z|!T{iE>wVU44> zqf(o|+-Gj2pB-i!tzL$Q00C<-VfTE5HV(NqvYAomVfCDOhz%sYmDEQ+q;uSk&DVc< z7mWwb-`(i^%RefAM|Bs0+NIzo%fx(L+@;$r6P?4zR5w~KxYA{lVWXZq{E4hH8{94u zJwebzOpijO>CwH~8;PPH&b%IoGNa&fqUpzz=@oJ+iL4p)ON{NPuEMQvZTL;{^}k15 z{Udj^$B{d#+lZ=RHA{D8HmO>#0P(k@ffz*|tv#~Wa7?Oh;%{2f+@(z~C643m?BjSr zddHVgVfU*~1hQ5RL=I)S%4M;%{_>oi_48+B^Z z88}|AzRJ2zhGV#1Pjp_a%FSINikReXLajg1uI^!97sCdRdZ;&HexKdlb*_5eIH2oi z;i?Z%$O#vV1Sm#{^p1vN2cscs@ZQ&g-qYK^<8Q(|6*!t?fOJoYw1TVt$ zBljpKtWf_J-bu6>`dv(IMJvkO(XlOA4JkzT*V z*b}Oo{nN*&>b$!Y=HA4Y-iA2L!E+OB#C6y_j%JEzg`Yk_p$AI`>507b!|8=i4{D8q zHOlmZT2+Ek>!J`Q;%UaMuS(Uoi?1(37XP}BY?WGh3x)exD0L&S;BvNfpNM2 zZL734N0$c!5U8<2+py%&wiN%wmV#?D z&SNwB3A$Rg6qvL?(L1~jvdow?ogMRx+^@gbklXj6ROZ13%so)ryUYDk*_sCKb;8u5 zzXq+kl-c2Z8{DHZ?!gpq(Q}IA^%qlh4<Ld8Y?Wy zAB&=lRFn_rqv$e}4kA!0BW4Z+=e6%wNejz_j$IHdP@5lI3&0sN1`Brz=N|<*n3Fr| zIrW-r9H`GsFAuoYy>LE})^Mp=p*4vP_PGbtBGm#Z=qKlbP|S`FNcB#3RRJ5pC?aVd zBj1rO-;n`kTQV#7_GtJ+I{mWv#y@mM?v#S`JV20J4H-Jr?X1*)C z%ackCE1F&ERVFrt z#Zyb~hd-uTS->l8;X#~9USQ&~>+zYft_b#VV&Se3!CVLp!RM0IEq zVn@8{CFC37Fp-lmJW^s-FcZ}OT#O?d`DNac z=%yiW>1G}H-{|G0a&sBy53r(b-}I%#WwIZ~@EOiSFJHE!)n}uZd65HiSoWtL@V)k@ zHmA#$dP|=g=9Rq>%GDg)@$_B~yLR2R*lyS2PHs$$I&yVl)S-RuIG97l|4ZMZsgdFX){@YKryAF{w`}KLiKR}Yz8?a@yDmpSm@;B zJe?S|?wzL*N3P!kJ^2_$4;{Mt(AG&MqvHx;65H@enT>hdaK+2hasQ8v9_YE?ycoS0 zHlFax-Ym4gil%d~NDr-;$x}rY$xUj8-7NA{z`mOC&pe$uo22|B3HcUO2FDTAKZpiL z6X_lK3AQ)57k8eYGHt>Grn95kTtrN>95?M?dj{HgM>0q^PXF}}4lpCEkm)KrcS9W4 zoB+?j1~Qd_nK(hSKx4Y5h*1Wa-O(WS37K)*j(@K82F#KJl%mPZ21L5016^81cv++t z3W?0H=)A=h>b(7)Iz^qgzNIBUSltY{Z+`lt_tv+ZUI&%02jpFjwY<$5^%Yua3rdY(CVT`tffCipXnU*^kedJ$&uY+6`LdP+OsKNhc^`_mC4Ny4$(PG`tg4~!?Uv4D3(!OLhG5o4@tS^6Rouio_Sy6qB5qy=G zZS$2FEdo47_H-G{Drb!pBVu-8YK1$nu0($-uEA`uE49G*aL4KeM_1RvCqx>Gi{OPd zerAJ~lOhuJA0+jrj6V@mX@ff@_Dx7rkVX~PV}a}=is>)-q6Yk7YHa4oep_i#fnX{^ zO2h%q%)3_xb$R#l;1JyL`9+h9ID!-m2#H%#Fldz-vWE(sum?vx2U2~A#}-uiIfmtv z7Loedjb*vve>oIm+=x$PI4BI|nA~`E^Gt9>i7U^rp3y%^}X2*1VDI}6B5NnEwq;;Qs&%5cN zttg6{AHELE%?};bLQ$T@Bs%r%8iP~#jLA^py}`CP)mXvdR4O>GuI_e_>#A4bfbLOF z)G#L;$Ny2-)=OQ1>$GZSy5o2_(_$azR$nhAX57nvR2mhdzx5MkJmVhzcfXW4;Q{63 z|8|5eF)eWgnL&cfK^S4Hmkf2q{RPi*|Izo0I#_FW1EpuQKp#RY^lViU5U{mccGvnZ z7;)cWsvGsL*o?I-X%4hh9N&B$R{pGI>DJtf$U#$!krAD%to6fL9y;}6dK6q4!svTt zZ++hs!qn&LWqnnozKwkS)^dhMErn7WD&fJ}YBXFKN*&e16yq6U5XkE){7n-;ltx<3 z$W_Ez5PTp1d43q+8|a8Oqa*5#3iS6UZ(AMD5*fS6%+|>+L$@}M7n2RXTnIMVU{pRB*`STCp@@GeA6$gh2mJbWhS8Sg zgUgEfbN@pBH`Fqc54xBoB6oA%-5V^#T`V8ScoHh&^HcrX(WN4pB?A$Qn{E3PQ|KlZPQ=#yde0r7`f>0DyI$Cb1HdPa$(@U3<~Q0SeJjDvBv=aJ%?_WkUqajj@ zKo_Afi95!f;V%jiYxp=@&WUm-$c9;@9q)s~%9?HJxS^R^x3lYkUB?$ulYbtS+nG0!?4-p9TR#1Nc?CEzg^*X5#LDGU8%!c-v^)> zv&o5GUnw&|_lHNRpZ?x*PK%Y9qv{9S=>DEE#j;v0M`T$}R#~Tx)j;g@LfX#0_)aExH z*n&7SX_~>Jc_nCK2)lJmz7e4wWPe)idVP5?NNkd}&UdooN^KD7vc+%yE6uMlUTT5p2B`d~(uJH^b4i|EYvxVizt4FwAni1;( z>!rQ&4b)nsr8yR^9%`8#lVfybCe2|KUvLkGMYh3I7CZhf^T0&r6rfgZ`NNW!zE!s4qgK zE~RFsMULp0owJvjNGko=T;sJhS!?3K1=Q-OLW?S>j==*i|iJALzvt!Dni3Z2}#wJ?L$SwOp zyy5Nfh^LO;3UX>}p4IftHk8e*iD>%%yC&B}%NJs~YWi;dWl=<%f)o7y}7pj^CG^Ru-+&2^TB~OX?i{DZ=_DF@di1_hQ!X-hu;d(BYtt_W0)A8AJ z80M(j{GI84)5dUqzgbsT&Owp4TJ%kD1r*rCs<}xu!F`&R(0cyN%P|@0Yhw^#vw0p( zmu-?o7rRy6+i6DodiD5J`v6)$?Hu7k`*sNwl(=>1f-nPeMe4evdXD9abp~Hdyv9>r zs9C0{MGC|!;i|A+XxY#*30U@$zwmDZ1Gnv?5Y&K4Hxr{`SZo>I9IBW!@H5L__I@Vq zL-}w;zPVbJx@~V#0@o?tKXL_%T2!S!<2_SXCPeTI-bCkmBBHLGJ_L1TBkD+*)fi%k z>~Y6LsIfE_ij{=ZR-yyZUc^&x2+OW@-ho^z2<+YvW~c*J4(zrlo;4@_u-G*g!oy;Q zdIcM=T43NYw;krj(Ls5ZVjF>pjy_e|EKh{@!E8K zOu5^aZAaV6zj%H?123+{{X zFQ!$-GO#>?`UkO$g@`9&8Kzi(U1XC`IhsFpafQa3xyt>{R~!wP>bu5`8V+fMqelB` z(Wrq+9@9MD=*Cy(1!?$IG}OWQKC*R#rq-!xZ+uNX!j1YH{CXoKXNx5j3HQGesBUUf zO`6?cxX55*Ze)_ur1H4}DcHPyX*dv;8Vw|=AOjKl{<$iPn*HREzT@Mdmwqy85Yg5^ ztZOykzyOUmO0AJ6sTT0C+zbA!R~^N(hry;sz#6VFKSWe$QrsSe$~ihciKtPGO1nBI zPM`nqzof>Y?7z}c;_@JfiMg-m-7AB;^X^`Yv-SDO(ND~h@KG@FF7&407`+9K-jvIG zp|>4C&AZXtiJvW{H|S&w^fvk>*8_2S`cYg6{ufgYSAlrz^n0EVA$VcLLIZ*R%^f!9{Qu>>*MfzK~ zL5K*q`a*u^3}z%HyiURYCjH&H8lqKS)k|J^X`?wyu7b(7>vsBqfgVKvJ>G?)E zD`phis5pIMo*ApIOkLqnVFc}EJKr*o>y(vY^2VrV0SVjeSE+896uFDgO{zK#6FgoVs z&;OV7fB(Dp|8wuH|JA5?|F^Ovi^l&K^X}f@YqRj1J_#V*H1b+t$YaKi^ybt5Na(zk@Yh)c@D!-Mzt5+^+v^j&C`;*dnFUuV=7r zZP(x(c85zgV{V{>*nj`<=Y-AmEuV<#3Zu>GI;Z*2eF$ktK&@5f!#{``I(*3n%oMPe(U4m(&` zya>Wpe_Xhkx4>fOEhTnzi+SaNveeEVMCWzw#M*f77*m^alUs~Vt`9eb5yJv4d++*s$BX2j6-%r!-|IhmGg0!68D>_fszryM- z@=<(AADW=EWfV~%beC_XB zrN_T32sJ~T9(xV8-zJu|qTB!f=~4BMXmAgf9g+Kkp1-Mh`2+C)aB?SHUrT(e>J!$CL(W%yvn~n!0#L#GN}?{up??jTl4pKb_$j zMt1YN@$l{*)($&-Wf!oS30H!)KgebsYs2w=xrjK+rsmDnZKM^YDH9nNERa8&Okz`@ zxV7k0nlUpldcoZyn*-f0;lcPStSqVP04f7NahtY{!yS9Hkv9<24#wP`KRwAI2bL4| zQ?jc6kG->xkD|I7|GvTsm_$o!v|3k<8Wc6Wr~$DikjMstMn#PRO^^ga2_%vY#J3uo zpot+$mA16fmbSFgmR4HProPlDZ?R%Ui%Ki4_|kUPV4)Q?PsQx-d+wc?ot-Qi4gEd+ z!1p?u zW&Mum--x7@(LH(v{<6U>a#qe9KJ161wP{n1I((m5w!)s)No-gg znZd&8`98ztaG&URW$W{r?o(~O z&Zz`?UBPYA0L>G76h-RD9wz6E!Mk)bjBp%~nz2pz(?nBrQV7L%N{NcMcZG;+S^6=S zo#dH(-z?>&PRe44N zO2W!Pc$_{$??s7>cqe_?79j)D3<*!`4@JCx6hCKqq;- zRKNOVlD4{V)%g}GjAoZej*>$>@25Nb?di?9T|LHe64dm$zh;NEy4!;<>7+eEAq!fv znWi^PoMM*B?j?oMTfb~UCA;huN%_eNgpIydl-D#&knJ?3^>CJC}%6}YkJ+bRQ5T9uyw{na``Z63pRK}lT zYcK>X`E30Y%Fj4gHMb{Y+3F4bxyh0AWf$ONja|t<-OtDX7*yGB756Ft*1Q`98zS;jBsVlv?-orj$9aWVb^^WGBH*q0NySe4^` zkbS=;HrBr17Q5ZP-xTxM_uFF2xmR|TWMJFt(jTp&4wJf~77$iflw$pzymoX&*GR+X zBj#W~ZheE1vr`#Iq8IYS((fRWv;ze5!Y{KbyQo!J?IYM5kI6o&Qx@PEGoBaz$$}}m zuN{Pz+NKR>8n3AemRSy26K;1>(=m?a!!){w3Lya{D6RdH4fh;3)vh~=v507DO;x+v z+=#bU4G_{tus%)-mC&a=rMJizFh!q!C~}fop9(b=C6+!FYLq@bQf{;gRjd6_ar;D- zHV9r8j2Q1cClW{}CjZPCdie^jR-g}Ympp^H-qxOc%#=g3)Xrn!D2>fr$H#=9e3KLYTfi*Aydyr zmYeOH`JxQgD{+FaQcaU+U}`;p)=S?(1S73a#u&rt_TZe4TyM@Nv4ly6hbNgGOyAjc zy8C|^KiDB95Zk3^pu@msOXxx@q+vjmn~25f57_h&G@aSeILpp%j8r2kVt6IU4;Q zm@G9QjXuY0^s*#Z8od%OtI^BJ43TzI6Cm?gVES|~qv03YELD9Y%4v;+q`l`rkNn<| zgR*4)Bt2Ve28jtxkZgS}(mFiLcto`s zK9?s)G-+c`Qc~_kFFT#tWQ-zE28_0DbA>#L8v)7>1!7bCp}bSA&Zbt5&lA;jof6Bw zd8DLP(iSGEyqweyb5QGjUKD+f*nN4XzRHvQTSY^Q&bsIsX$dlgo6uRGkr2x0dkxy% zI!j3afpL)7$0bOkr3EJ|tqM#J(MO6vWrJOAVpQ!ZOrD9^BTODkHFxSKBg8fN-1W@#wQ;+>t^q3q| z)2^3emWrl=34IlrT8{Zg;VL{a71{)v*COBjb@lVZkhVmxXowpsT5rdYehsoQJGKw@z8eD<6TRt;Yy#i96iv7?~-x3=)Uz?jWDLTjdSaOXue!kzf_`( z#+7VvuSVl;wHLP3UZmAfBTt43>CNXty*=_wzatF?gN#1Ym#wC?tK(%8CRDh%b*&nx zDP3X@-5K_VA!WH5)fc0A)sBqVZR0sLX&A=`4U4pX| z|1HuK8&*7m*0bRrZi+bWplk&pwR zv`6Af=?)($x+hEiv`3;-P?YRsCGo1+Sz20WAypYt4boju$;fm`WXkP0K5&=5j5FIj zvFXAC(F1&_PWdBx#3dnRQ1ybxA-nj@%5Y@cq#UUOzW<_j7f}Q0%^^ukO*d*KkJ}^& zk*qEQ2&SOhfBzMyXQY=1@dNSH?`an3H_3KGK5O&5Oh0UBE9#m7TMGF-7TA|8>IsA1B7+&@>3O(Qy8uFtw)fvu~M+Y`Eh^N>swUB$DCO5FUt+bs{X~w{|pt%&OdsKktrB6Z7)3)dUHbj7~M-w5r$^!t}^|}iFyn$gyM=)_QvM^Tg^wv zn%?wfGZ2~Xud+T-c)&A45RWlsZ}ns1^01u@-4EIQs~m?}D0PQlV=BQdev3TGAaf5y zvc(~wTCX-B6aELSB+cVuZ$mo786FXhBGF=-Akdkf_GA1;wJ{mty8RefDX$yjMaU3t zk`X_K{tzz;70p4Kp4baGWfJ|hYyiT4F&N9)Ji{;HznHAo+hJvrAi+%k#S@w-&5{~& zrTCKYU$i|*?>tEAq5Z<8S0hxM`rKbwA(C0Zdf7It@&`6UNDu&OFpj)~oB@dm+VCOK>inGlSqA#F6ez4)s}{ zl|wXc=n%Lumtqd*wJgQ#0L2Z5ynXvA!~$um6^F(KBFoyvWmJNBQd|ZhMfF~%>fJgF z?sfDP2kqcV-4|c6hqQ#*uJhp5NXjJE^INHlv!2F}B7VS|ZQD|x3pd_A+(lN0L>DGr zt4X@g+pjab(^pWxKje&1&UJZRY8y!wmf3bs{RDd+!kVvTWeWP23EuAK(G!mI;bONU z36Axa-Cr|)0mY^~$k$^B+f}GOCcB@(y5sG$_T#qLiG)=7sQPt|Uwa@g(#l?`q-$Bm&lWS6(EeCfIXpK;Q3vMPZ>&x*EBt0kE!w^P!rxufr@~8!rYbzb zjkVSK+FrR2WSKS2(HqA7ol-H?_?>CT%)MZ3+UJeS5#vlhOE-c7pnoxLc-$c%B2!YQ z)8UjX=cPyIXh2R*`-e*!^kxNFo13ITm#eJz8E-x&@lSY&(_fXNSJrXc6%SGLS@rq$ z)@rfl)0-QU!zk%E!48wzeU$VA?H4vJQ}Xc?>=XGARwv}+GUP+5Bzb9bLSL~Wx?A?| zB<;J8$x2+^ev|fh$8H2~+(41ESYSlH7`qXts^f7^^5b~>aa-&j^FGP`-=)ZP?62tp zk!<=q&KH!IcHz>O$#<(Mprqj{pxvKnjj~1w$N}S7s=<`89}r0^l}y$6IbTp8Cz;SH zT8C`R(kek*AqzQQL)3}VBqfi+aZHjD(ImA(3TEY*a7P41)`qt=?xzYxv^dO6jsL{o z$6cPbF?o?=yd|k{mo57u)Qa#fiKL8}v!M}-QmqKjlm166N_GAqCfy(L1163i#L_`G ziGXLC8x%zr%~A3orIC_H!2c34$IUk75h3`5&tt_asr!Lb>dckox6!BAYDo*{50irF zp6yy^uuRo`D>Z2igfA5pCWSV8+H85qGY=wsLA4NNkISw^4u=(gp6I`?YW>H1^NZT( zH>X~^Mg=wdPjw!la4LppBhLQ##JSF;BE64NY#}PteTPG8iwW#_9GUz$#eUotYqal` z^qo;Cp<&Anz|c}`$SwgjB{L%*tKX^>BHtS5W$!6zVWycrpG%)g4;M` zTG^K^BH?Yf&`b);_1xDIjR}LnX}v9atWlv_!9HWAKwQnkBdve#{t5Ij(G=0R`n`y0 z6wkW6ztmQqN<^dSrnBZjDqY55Nzxh}mk6!2=nMAi%x*nSb;y&b;$J4#!PxTCy~X$n zl$c@?>%xw+?jNx4x5a+PeL}xV2#3D=wDRy&KjmQ>{6Dlj+=}+;ffb_Mtyxf~oUWyW- z4x0{5)iQ5y~u?c^t2#b^lxYep_ri_lI46I10WW z`s5|!NNP{X59j6f)hA2&7BF2#vOZ}@$j`4;wJP};BqlbB<=tos`T3?aXovjVuVhB# zC(pRxVX0T-XTRtdvDE0J&XWLbCoE-XEtPp)qIy(i9&I*$j^v{<8l__F1}?o-)Loy? z*{?IZwY^-l4G)~h)4kk`@2b!5rmoLLzfRQQIXEz^`pmKKx5d85{r_5hUI;f2U7xS^ z^sUbojj$n6r5n|gt4hx|RRaC6>MyoQgLBm9;Ehs;S|2P>_pbU}0^g|5`v?D*)#rB~ zO4Q-^f0wxbfqlO%wt@SPsLvGp58u=M{R?uE&Jj%M^F0W4q|O+#m*5^NW@M9W zMRaZ!PvmE}ph8)H+$rfGVs|x_UnSq<_I_txNgf zgV>_uwxr+jGlFyC#X?WflYjNgK^7rN6cZ`47)v3enEv@Re2_SGvBx-v>SP?c>|K14 z^WbM2k+#J>k=E;3T=jDO8}eE4qxmYhvTlv9(HDy#g_Ik$*lWmQIt;$BnnJVe;gBMv zJI8Ey%-A#2B&W?6HEr=CXXNrFa#1!jht4xokXbzL?ImT5`=-jl{GZ{o8Lu>8%1fa^ z`qj8ko#L1$VMrfy(#U#1h#_+10yb{euTsWz1mh>enEy-Kh?yBlFa43WA2^3dX&*io zfu}|mL@HzE(O*eIC+y{rUePRx^RXr?Rdk}Min7dpCBJR5KCkBLQ1`3wFUd8On6FW; zq54hM+sy6`TMtdv>u|3g*1g;4mCV~Od}XQlM>Ztn^L$)bTK8;=P3Jx#FM@U0AGhtz zhEEQYv^gsi#Hda=9k~+@iV@cZLu7p1$aAD!Z+Dh$s2$U4mQ+rhT~{f5%VP#lmX)bM zxb9a-V4U$XArj)^IOJ6Tk1<{pI{wB+9`pi*21y@|=4tO7BdA(6@=jWdcP$eTG9!|M z2b!~)4$?04jL1{mF(w);e&BM>!zAu530NhjEC#~#tmEmswAZ~gPTM%%<7xC5bu{fr zTX3(>E1#Roff(^xj#ZJEq)on0pWb|yOntPU``slFf270`(`YlfGOEZ~#wT^2 z=Uzz9F6Ki#tPVV$@1-E-UNN1r#T*{GziD9zxA}?6FD}C_wJ@WR8WYy#dzsUdKo*UAmhV_JZJ|-^ zdzxkllhQ{NvpA0v$I_3I&kx0;`B0eNoJ(lC2UcQVpKVF5bhqivb0HuRLJba^uLFlY zPZ5Vv!~*Cw9{7dSNj0;>Fzr;B@C~nG0_)%qN}YiDy`l8xW>9li2)~bn-^{$g;P=2u z+suJTZrb{mfn0fJT%@CBAT{@@lxycd!jmp zAQmX>Gqx)dQ+-G3SGgrcXnM#|An>wstilxev+l+KZdTKv_r{`8KYO9P|rh+LP) z{(>hsVZR6eNCBk@oIvTN3Gk&K2A@hW5qtk+c=8@))A`!p3&CjSTr{+rj3nWV^$DE? z6wt0I?FJ}yhRTc;@knBNeD2VPu}zdXks57g7+Gu=x3$h9(uU@};Io&pEGm5&+j2bd zl2B~DDhztmI;BtvgT#D?^~^B5IV=3^x0A9%mwiLli9X)q|VjXUB0mPp%Y+k;+@ zniMW>tqRfF7V?agenr5xybKj^TVAGuZNVBr!?dt5OT?q~rRL5k8}yyRI#;>|)(hoCxkmwq1|Fz7+l*W=UIE(keT|jLiEb_du38E4%cI z;>@fcrIs;F%81Z%BW(=VCxxs9;LH_R2f`M?E$d88k-+D>Kd-)zE3VZHX|=6>#xp7n z`xCihv#x~x?zM>Z6%!EaK|C4H!vwXy4t@veWi5WeZ!m3OgnNK~7^ zO`-){FzP)_^_)oi@Ga!+F<$x+IkerhgXIo}Ab@)m#15*LLh1f6wuoeOyG!JlG~*zG zGt7RMId_F*o@>(I=arH6n$Cnu33f^%76sYlIoYOQ zvIx}<`!R)3`4t5SRUd)!3I(=6-OJMoTOUm$mTDhXwo>pN%)2HEeyyErss^)M!lo?v zogxd;U`~=8&GH7 z_TULZhOXw<-;-OVQMHDcZ)cvW!1qb;lm-6QTC>18WGwm7XFkMN5EXxQUP~mh5+V^P z&qro7`j8prSQ%~O#+36^@>DA+SQRT=e*ax7d&T8OCpB&*^`L}pOU311{!o?EC=xO> zw|`qpvq4+E$E!qt>S$komDF7AYraj5FykHjDHYdGRn*)P*35J230s!fB&1;dPb6&0mT>CIPXyf<=h>_QtAdry|%L{QKWXLwlx6_+_410@P zv$C{jhqH1_&yK7k#j{iBX<=5dEf|x8TPw5Geoh!4F>}r%aWU7d`6}52);6h}e5aN~ z+UlUKoY*%JJN>9>Ogb`%Y`v1oFDbE<;FTm%Sfwmi*62{FgE)mhUV=X-D@z9E&0i3j ztPv)*IcvEkKit&>786nDcLn*~BKf5sb!CYPq4xc#5KtZwXT|VDI`&;y4RG7?V6>se zf!M#p)CUpLmq9iXY1_bxoP7-Sx=+^r3ub!TZwa#k&Zin2Ck)7{HB9Q(!W=dH|A*1? z9U1;-VP)SEj_Cheam6-FS;6Pswxcj@%zBp6Vs z7_cl3sWFbHxB4StL+pP*n*CFU=!Y2ROv@1T{v2fN+SSd`*;Z@@e5qe!w(H)xT?yl|~l0^5ftc2{OKVxB-XWnQ0oiw_C zE_b)c-4DfLUf#XZ(${8tY1NHFzDVF62N^F?2)m(#m6A&|ln{kOBIncQKUqULBB`Os z`Ig!R%5qF+L+O-+KeD07IugZ`6bf2D#to#nyP;|SKru1nW z3g)P@p_uZe+KZ8@y}Tf`(3+~flz!XMUKqF|tFHEP_S>Jfy~uW3k)uPkmmX;^j`pG2 z%fH<1O-}cRRp%%%MA7Ks_~$-n@`zZeoY#>y-brk zcYE32R1@+>gSZg#Ff!;;T0g{FsQi1;!L#&ytJZ+ZzjuAN$5WpUf#PhMC7)+2pk^5{ z#9!Cr6Vp?{@N!a~_VJzv59kpXF>k_K`fBuu8L?A9QE&J!?7q%wzdHUCjUq6pw4m|+ zs^sWHX2jkECE-)WSKbf28*NY2id?HCHmW2ZEfGX}Q@H@Ot9!M^hwXrE8iB%9P$PhTcwYi#gcm%i+`+)cxSoe^of5?|Qgr?rlxcjC+3d>Z4% zB_iAUI0NzJhxJl9#iUC}x#R3QkLM9450Ht!$f`OfojQ4%%cRo|AQMfJWsOWeNsbZ{ z+#diQ04+cm zP$I$sYi%}M9z{;tR%We}aIkg_P*^|y9vG`-OHW}+pf2@N%Na8EIThC_1_w;RXe3}{ z+&+}T>tG6---|LpPM%PDS_MsBJo%6reT_tKH%~N?DW&navyE@^HkQL3^EozmE_@N~ zZOxDpjlybPA*{kbp0!{b29*(ca*t0A)_Ss+%9bM$ntG}1zY&Z(COZnKP=o?!=*QLe zwIc9R+bgpgiEdVS0n-P4D*RQ+816|G2#X~=i*I9#6aA6YzdG-CpWziA&cF&%c;+ zxJmN)m#Kw5HXpvR7mxi_6^VRWU!_&n|9V?DQ^8M74oRGW|7t5BCF-n@@jSWa{^(SUx^+kG1o}Uglr<>aVp)dV!H)L zGx{NoJ(+^%&Cum~74aQLCy4IG9o zK^gN25IdVYlQ-Q*SU0}zwOT=_0l^q59=9)jS&Y{)`3I**y%Iyp-Q#D~KeBrve|k~tfh${IR0hUvdpm^T zZ5Ji=lcKHEn&0R!W5wODc$@T3G-8(BimRTQWOz*H(g>DgvYWcRsNTHyw)oNu!0XRT z8Q(C~jRca;OB$$rJrS#kKEpU2@}&c2exb8|*!$vxXL9_Pq%HT2p8Csf`zxI4l_JuA zm5OL_aFMKQkbMZo`FBZtz3bi4C+^aHq7=)~A!a}KLh&=n$vLShb^_hlB6G_*RSYh1;<>bd7s&Se|^ zY6)kqT1n#`UHn}DNy>sB(# z9nmNW8h=&YA}qg5Z@!Xb ziqQ8gmf&mPU*$P z(BWj}0#hiomPv1(BI@%hkg+`OR!9kOz^Ij2e>Zv&DLx_Ed?);(yg9NyMz2W-e&$sz zHIj)im>ICbkTHwOYyHQlxKSZ(PYdI+Vq#Mj&zmts&Qz7CsyIj0ndi46cm#UvFJ?u^ zoVKJrmqLlus6$vjmE3)dy#1-gEpHJeI#ixWL^iIUZ3q_%B-^{>bIJVq3yOfX2;-9^ z62(7ArQm3J>CO9D6=3`W_Qd|?TpvJ@ewZ+jo|1puUA^rmgV{vx?k**AanB4LCZFr`mNnhJ4C=B6h>ZgUGqinjsPSrX+dQli#;i3m%!{6Dg;!2|mGZw@h3ocesA!?F zM=(uWa%Eh|zTpKp0L@iUTUFSb7+wlZ9s0?p>GNuA`2(rqwc|>KPn@64!IXc4GA0#Ne!1$u%+_XhT!*Y)50<~~VX2^{!7fpJ+nC)~jW)XZ>4=)k_lR z6e~`l+BC4;UdEKC)_}~wx3R)rztg>2(WNA2*?ZAj#g;IK+iEY(-;L|VOL0(q&6XiAhM`UuUnnghS#B}E%B|M^G!a;WR{ZVw{C|3M?0uD zb_s@dAS(i2w&PlD;St^z(W+~8^q-lJB}FL5a&7W{)5L`Zmm|1bqY0dBE4~THEJ$?B zwAQ_`BCIl7KJ`BNIiR}l1gYD%M2YAq_0L*Xn4>{CZk_U!-u#Bt9~-YZ_#~M>y8esk zgx3&cnslwYB(E*gY-Qb2p%asr%gxDw{nmRGX@FE%C6{aGa;wt5o zQ!>=OWKD4vyax~YMXmVQCgBlU=()sXFppP1s4Pn6Z0XX6$79t|VyRg(38M2vr4^DaE4J;hgVeO(`nw z6Xd%)rC8G`0ac6bQ`?j&YdO0lrDGpxnMm zR%O4PzHBW4kg(Xd#Ng564aFTXbi1px-bc=r{mA-ZV;f>3dFPmJ8|8J(V?nh7`3+o;Sq&9fm4p=$xcoU= z1fIiLOPy3Ci@!;DbDCkBR*?*6x$c{JN=InR@GHIsM!9ZQb`;_#qPWj}o&bcD?9gZLit$ z0rawBRNl5%7S}uUX>(Q&)xjYZZ{Gr?;#U|;1C-C`;^jVfRw0aIOCLuq$Y|17_oDFW z+z4p#B!7!X$@jIJh4R-%y)f#%qSj7%b0UqQxV=IYLJ69;0)cG{ad=dE^HymRt?W*S zv_&X>F+tiQp{;otU~w52;}2-fVC8m5#KgFRl;spZWuH;3iy~*r$W6}v%NIo61&2D;~$Rz%L|+Hglvt?#cAqTLl4SB}OS^$$Y~aNk?(Q^thYE zO;f~~!+AyDavj!U2_%YfR?v2V96c!h4+nSBAD$FIxu-{DB_~rC8`SGpBdvif<7|W$ zwe|ol5&0`%T;C~g8PD$m%1;y>PLnW%B zFtV7&))ywQs!h%HREe$73Aq^`~j6ub5}kowlU%9{|dB9CmIr`#j{)eUh$QsA4NMT z4DDwscz;tiZrVGA8HB2G^!PhW9B0~ZZm_If^?d~dqUJH3bs@jH;7%wZFbk_KZ zWDak)C}g+*D_ABZ2S4yY+2lMUqwEG0i)>_*H+eCc7)gw1&HXs?$z^*WtLE#Ud`9N$ zWk*dR?@W7xeI@5h$o30g7)DE2)2{G;#$)O#X9L|GWX8py&qg70lED&gEFOtXWKvRB=tIX!`dtib$mi$J3 zV}0(xu`{x1FU!Af4HdVYBPRX`gToQ!7{Mnazp-}BM#goeH(x}}GAGWsvv|ZmR8Pl= zKAxh-dMFRSTO;ign6Bwbza2k<6kU!&%2elD8ov~RQT!R&XV zBW)8i(vKQG2ILs_-M$??k5ka7XyqrWK^Qu5Bs|5A*eM3xPfw(EN)J1D>)$}23`Mfx zr@P#Q+W0V6`<*Eyjk=ga;dhp02_wCto>K9&k;BI@R6)Gh=Ns(kSiGuG%&ZcY*NuT}5k*|K` z)Ekfb*{>9;U8<$+th=6;-lxzbKH}p*6}O!_2^5V+rphink$dCINRjxB|DxWXbtbr? zwksI}zYx7H(l!+%cOeq?bYA+`w{{=9V(E~)=J)D@k#V~ge~t~;k+#cK$j?w!XyQny z?k}J?yZ?pyw~J`jR7do97CD4@&%=|8(`8ELD(;qE78&=4y5c89`58Y(x+ATnN-=PZ z%-^U2Hla1pNs6lI5@`Mj0HHT4a5i zy`j99{G|F2BVB{$`Wq^JkLE=4OHwIq=bl6oq%=f8`)B8fu5Q0LwC&;$DWJA5Hr4jU zi1Wo^p0fpS+$4FD*cDN_McmA`y?j<6+;u;6d@5#{(CE>`YfdpLfdJxP6eXZ$H@L0GJVXf4LJ%o`PSh3IW@J2Lwrb>CAQDQ!ac((GF zm`Y2ig-MJ>#BD1pBAWjMw`>bPo#X5xtU-=CE*>@xml6B3T03H6&c;fSmQtV#SZVm5kA?&`->v2|72ri+j$WVv5dU` zZc+P$o${8}4wUL!&rt=ig9M4UcVeGI%FwT>-TQ?bJn|ZL>g`V)K z)?G6qN9@?7+N!G8&7n<_{{Q{{j|2b5f&b&ce}Dt?Di>8QoH{p@Jv;zjdo7KN*3*M%3&UQ`#ZSsb3fXl~uvXP+Ie zm|r(%_TmZ>4fA$3@0ZM!BYd=~GJNA%vl|FhGdCNnNwdod(oU5CNG{}5w4qmV`a_U3s1eVK3p+7I=if9uH#`&P5q*%h4L(^ zoD;2CtXNx7Id^t_b+l}DZEfWu#ZU+9O{66Xmz;ZDO-)_&JY9dI##Sy~T(h`r4osg{ zv-pNWPxAZoDk`JY=;+aAwU@brTglomb^K8}yN{2aI{#6l>!KA7BJJEfuJ8m@a;Y=I zUz+ka8|-ylbGW|DHJIxpE?LlY1lJUWOm#dO%KGzVgNnEFLG1&8*!8McXcrKg* z9?U@xZgCGoIkjSYIIxs!0++NLu`9~BZsDrqVz8#3hXTLKbtKnhu321P;5vm%-kr?V z#Pvn4;7a`VKcVmUUxZo3Z{Mx$Z$Gr={jD1$8Gdh0IQWx) zzA){&l8e-9#`zlW@tjjtv#|1<#WmN}&=Bg*$)9}HIR*3Q&MmvTszQ$C-S|^0 zW(^4!ieQfq7wMK8uARMj_QFb3OPz3<^5}39V19Hyis;5lN3$Mcy|>f3m}XE}Au42k zstB}Yop3@mlr7}+r?O~GSetcck?8TK8=;Z4b&t81P`0?{9quC?Ea}@{1 zqq)Q8oA6R}aCOb>ib|A@XqA4%m$IX#mCQ>UbpLuTj>p53KZg|ndsBPE2~Q`IadkasIjVgROcg-HEOIJ z)OCs7ofH<9SxF{A(m&6Y{=Dj%>keB6uJjjIDl%tRAFcwNaqSo@fcgl}Nf1&~gmi(d8PgKBw(;t1li$6}@543tke%$)mk^X>_m-L!0Y-`E}95k~lpW_3P|kgnnhOAw{?eMpq0p zAD8{$N}sA&SX()eOkDKWLBHZp+3ZF0>Z@lj9yt9;?JJQ!9+b*~ClCKeIrTHv)SSxd zffDVopk3)NuB@wHSb2EUck2Jz+4XgYGkK9ur~EIj!77wd-r*_&={xzatbhDwv**vN zLXrla4e2}Wa~TZUW7NY@2I|+@e$Dg`N6K1=T=tLR4`Xb{Sa@K0x%gwHuLk1-OWC47 zi9crgha+Vx{XX`g)}M20YNEAxV+W|IUHljQbC}Z~?X;g0&KAX@G10kWM&(SbpF6j5 z@gzp=g@rk;VLJ8q5%C8$_7@JHaYc00xUws1aYx~e#Y<9ASuJj*qJBFTK7zn2#*`J7 zT`{|8Nn!CN>nElKAJMPdQjVC22~-91i-N`cLSy983eD%T#}dL%)o6I#7i^hl6dv zBpwd_IUUsEz)W&54v@nC1bs;k*8c+foc&v02lK!PJRJOU_HQow#KArw0uKj$&h{bn zIVKneMB8Dq5Bf~t{5Q7`(J%ka?L+8uOz;d;{0@tLcD4@}eg6&ZBWZjo^vMKtLI!1m z_0u<#!_aC{aIk}X>0f}(3fQYnG19h;x{1aJ1pb3 zRP-gp@4tY)k6mE%X)E{ejDM5buUWs2<}ol8co^g_X?)~ZAeNB90kq)%AbklL{9mTe zIf3WkpQDaHJ%NXVf6nnoYWmay!%x*p4g-Bj3xpi>nJYv;6OgnQK3Ykn6(uq zdFx1mV@~Sq{U(Pl-~5HO)g+r!HtLgRsIs)^&sn;7cCF^&CnD0tzg!3ZgtD^Q3TCPg zAtj1xmqbZ(7V+_Z-haVPHko{jjV0M<^v3sd9~#pe&tzjsCNKwRT+kbDVRKB{gx+`t z8)Hrd4repTwZI-=6R?C$G5-MOu-Rnlg}w2yY;d_jAe&P50z1$5ct(G*H$EZP-YD zegJF%z68v=h&?$Id*d5`R|3c8c|2=?oxqoYrTHGu#7UGBcrUPJBD-4T8F+31@7b(# zJ8(bnS$Qt-c!n1eA2;j%K z8U94rM-=Ie?*e`cm{$a!i+bbhfPpDIPaz&~H}I0Fz40iUbiABjHldh(M8KUuIk@-c zX`K5E%({fVP16W}Df^*;jhC@^=u!@p0KWzpEn&|SXY;HAt^;MGvRgt_X9I8 zC!NcIS3nn=rFH>3(>Ug`tJZv2krt^0kdbqM_>zZBd~N9 zd;zZdQg1w$%~e%p&?|5@U$FqTT-O^v0L-nVe%So9ZZ7$;@yVz|zSv0B!!GRU!0elP z;f9V%q^6c^5+7>z*68?;3{AVume~DG=OUazqL0Wf=}zV^~MW; z9bNDr*aKV*ta_SLh$&z0?PK48lW&?n^ut^t<*p*OxA*s_!KD0jz; zz44Kh+jt4SuyL#OkMLRGEAUd-0yhGyfL*`_;BH_Ga6fPrFu;bpb-+wu2XG{?3z!Go1)L5vfK|XA;LX4gpZ!_^ z%ml6lW&`&CbAbnd5nw2b{DH>~ z4xCym?}6LpJ@A0M2OfVW@6)JvU<6nVYyqwWb^#xg_vzHDyax^&$$Q{fU>9&EFqA>P z0VBZm@*cQT-UAQH`=coTS-b}p16zPmU>9&TFmyEKm-oQE@*X(+Y~BMW07IXl{J;os zIj|JC23Q5$2y6g$0b78(fvbS~f$M-Ap6clUW&*o_BZ0esc|Zd=9oPe`0)~deFJLBc z1uz@97MKg{07ih@fu+Dbz$)MYU;{9eL;k?yfvbQyz;(a^U<;(-?q8vrM7dVyY0^l^B z1zt*gftNv7A@FkKNZ=L7%f-OyluzK5)W5*1sApg)$0j#UhHo>de_+FP&>MlSxyT!^ zVFAxY)Jq-p2aMG7JO%tx;sZ-LjP0?hyuX=p7gN5kAdk~{-$*?GBVR?nFD3nE+D!?3 zSx!CEpJf6&(A(L-?Z8}MGkT=~c#wMQ0A^5cJ;0H`>~`cBXaGBak-MOGEa8B=cn+7j-HROT!4Zs4Pdw>UkRrkP8@VkJu@_a9Pl;A00QCl6JAiwEyEf3i;OnkmB1e~y{;#QLVD6*52lhNp z{lo8;C!hnE`xN=Z_l`~E3+&lUzL$aDLj3?6fT7Dh>Ni{ikN3vQJ>G^4@8^dN4z2L& z{rs3jo}3e~Aw%4xWn7$=IVFAQ(om!4qT|M&F(!+i9h;vE5%d_RVtWa~{0V+0*BGQpLDJ06^(tvD^?c3-(o_szV^q6w;mX{8-<~0FG$P0-JhQpZVD8n zmG~$|7)*Xz#>BKx!BEdg3F|{P3VP#@a_^Za(7j#jcwIshh&IoTfp(^;8ZrQDjw)h_yQF z0^p?MTel?WAl~i4<$-qpUF2iY@gBYqk>9`+O^1|aIy?z6Hm{S!EE#O_(};YRIHgJ2 zOe0}u682aL%TMHdCAcbZ1%jXrEceZ%-A9IAL2XO=8+pHq_p{`^GyNQ29_be-aic`i zCiW0^J7J%*!{$qSKrovEzGeqCHI|rbS;-7?M#)shiKdL-?TZ{rRtnPAC~40{d|a|p zI5dxZD@dypAH5ZRY#$E1n@Zd)_4+@9UUQ8;AL>?w^g$H>&%khug zPo2Blx{@av2=dgbbG93a(iPH9%87pv|H%R~Z&O#$=9Z(6kVlwC{QF(;BSRO1ajK7E zU7s6BZ}&rec&YT8Z?%K|%dDaxLeOClFN#hV|DC%WRGLYLKaVyq4Z|+Tw4v80BZw~P zilPA-xLp*AvLA&}Zr<6i*-BbP2lY@1jfk%G=bTzSXJl zn&!Rav4^^tAf4Su=P@~LhtL0QU&>4-i)`d^O$d2BJMdi{;pYLJ>y$}&Dl(bl-#{Y5 zQClb@Lu=DQo3?I$R`qv{q_G-**XdI3NLsCbHR0))M)J6tcNvfO#%FWynQHe-y6sM~ z>UT0}Y2CG*@Fj%5R>CX2pyXW3#wAvGZGZF-wwbUeN&Q`u%zg9@b2AYb34ROuI`OkcY86e1BBs?K7{ zqr4Rrz40$mSAichn1Mfc`KF}k8~oFy#+*%W@=(=ZI8my}1Zm!MJHd$afY4VdYPM{&|pp5eQJS{`2|97=nRhN^g%a>AB&(xH4=|4_vkG}1@ zV5sD~k$k&4d*dJ2vg^v1c6a+Am2Uz0-jXt<)cGEtI^X=EqVt-m)7p8x@e4$TmNQ^c zIs_TIOKd+=PdW20@sAJ{0?O4dPEmZ7HhAVK^bMpPxR~_#N%>X|Ltj7H8^6NlE9%(H zL$ytnhqBYeq-{x6zDZX3lB_5HMXAd-S(UFs>T|yC>jJ-}=luBcJtgV&EnmJW-!5eF z;ghwU61YKnVqLx{`nL+7`~OcJAbj0RzTwTi@iLpQF1bPAOt}$xeKr+e3oO1S={Emo zQ}eY*$*ar-gqQ=EXy>cyGhufp*Jnejd=F8d7pBfPf2in!v6OeimzfK|{t0+-_$Zqn zo41d=nl^u@*MA5jUFkdNljP^H({EUuu#Y>v$?9I&$YTkgeo}AzY+zs|P5^!la-}og zWj>@^`c7B>2oRvcRcfrkgk3d#S;aW>B6;u8}7ob2AAQ&Z2&jS zh1(1+P4y1?yp;dX=D;lk|)x7~#cd=`7kh06rD*@YVkuG59f1NWE< zCv);0E?gD3jV|2H;5N8$E5NOH;nsp%=fZV>TkFEfocJ0SZV$NCF5Cfdt6aFy=din6 zxZ}aCaN%;mEqCE$4!*^OD+Sl=!c~K7bm1Do-R#1x1lQogtpgWz;bhH2tqZpUT(t}L zCb-h7cwD+0`AHk>0XH2SCYt&QZWxZNJmNZWVQ>>%xUt}JUAPFiu`b+9a5*kqEx3^` zTr;?A7j6}}EEjG)xUdV?3GR3oZYQ`*7tR1T+=V*`F2jYB^%KKfxGZoX7cLiEz=bOY z=W*f6!5w@xnWs^3JuaNA*Erz9tp>N>h1&pbuM4*soZ-Ul0{5m1w-?+V7f#m6>~`UX zgWKi8WrN%4!c73T!-bReUE5u_3UFO6Tm!hxF5Gf(oi5xOaF4lg8^LwBa9!Xwx^TO} zZE)fCgIn*y1&%|%xNw=^*1B*b!L4!O^1!Wj;iiLI<-%2gTj{{%ASyS5TLJDG8OKg> z+Ccsh^xxu&#PXRmlo^msTM3fIwShS6E8=<%06ReWGL>(6zUBE<;dV)W$fBAn_=s?F zc=h^zgv%z}=6-}LA>8hMgliz&fqsNrLpbU0Kdu~Igv;tjxc!8i(2sDL7)sOo5iXB# z)%^%pMY!gEgj+$l)%^(9LAZ_m2)BoD+xrnNbOQRKAK`Kccd#GfN(ndo^^dQ&M#7Ek zN4Rx_E9ghK9fX_Nk8nMNi}oX2_zU#+{RkH!+}eJGt0mlH{Rp>;a69`Eu9I+k`w`9{ zT!8g{Uqpw<_~B4`BjZH+(|&}@CEVD4gexapaX-Sf5U!#h;WiNN=6;0RMYxsy2P|t{U757p@W9au;qTxE2>~9XR2iGvCL+HM(#+z}@V^y$PW7c!g#`k3xkvTb>=%3T$KwK0axL|%>-BO!qtMC>B2RGD|O*kffM<2=DQwT zi3`^WuGod!2`=Ko8Q=aaM|FZ*T(HNMhqo9 z6Tqzjmn$t$t<{;Q)}zR~Qr>Om-3WQd++~yRDwe=(QfoJ&yz4;sb;>(jNalJQe1A>& zmU4W|LM7G%umC{PUq_s^r1yjwr`?AibGfYRxjkUcwdVQexu#n2T4VlrCQ$Bd*7|*k z`@jQXlUCm}Ay#~Kfzuf8@P3k)2l_^*uS=yZL_O?Eo2llC^5E{d(RvOZ+RW_jY+_S#(KSZxYr+d7C8cnO0ce4OU)K zPqmbBfxPD%e_G~z*IMthc;5-F^X2_J7(7ZQ^#U?Uzkv67l)FaWzihu3x2LL`3f`Bq zHndvaKgxT>L*~$3bt7r5AZ!KYQuTbVomQnqi>yQ6Og-N$X)U$iFOc^W!0q7uTH=rN z^L_^JQ^_5(m;U=02_~%{$R8^4Gft;}VH~L9mmVU1G4ZVx7>@M^h?S=Yp=q8Mk6*&Q z=Q0_4%BsSPhh8&et1MM3;J>QhFb#M;;YLe1_|fE>qt+rJqUwDf@3$wtzmE4sL*@Ng zqLlM~FYn)$_?F#iuE+B|r3bkzj+;8vwO(aET@`)0uN!V6SvQrkc7W~a@q!; z&%m+YcP=ub<~H*vZ?q;JpEii}p6HuiVqTRc2eS5Hzt{J2%BhgaLq)&ko}v8>GkiR- z(!uv-#XjX*lQsK2jFE7ot6vHKJIOzQoi6hMfq8xNcg_1uPFv&mADw#gm{p7D5S_Gh zF6Qm45_2(Y{D+u}$r_~Bbp{TK6jKhanbeW=N0WrMz2IH-G%an1-~Rz}7)IynRa$C3 zP~=E{j`_g(4jOj&n*z7{m;2N_kkI>&Ap47ef$!_Q%eikn6aDg6a~)A)4NXF?qkH`) zN*jo5qF30;%7pE#Z+li&H8PQt)G{s}YEH;SSlk?Z=0}$84`>)G;SJ`D%iCJbA-deYMUTXsJ%A@gkd#ZRe12bNdY)hMn60d`JH%UCD zW30KaG98J=GjZrm_PtEL6%#Z-IXeH=8~?YGAsiX0+C*YLj}>wLS~!=YP2{IqbNTb> z3HeEyOJ&MH_1jAVz46}(9iJy}eg#~splM``{bEAXIhv-seDpi!dXwb&vUbRE&zGfM z|LLHmB-OghjnE>p8~6i`E`Gw-Ecm+rt={+&`f-JaKh8B-1!*h1zJq#op`N)a7@9(c ze{@BH4=cP{jBFW>l5Y`t1@6=NO1-Qm-=6N?_?^N7!GCnUOcvcDlaPIN)fBbvizJaz}d_8)4F{Z#1slF&6(({;;R?cR7GVB(?6IhUDOf2h<=Ns7vujOeMp5#Xfh zw#ySdLf0e~##*xSj-Pcw#0h+W!z{}pE zHUH|3@8dooc(q1Ot$8bE9vNFoE33%X?GfxmRMD-{rnaI#wo6|ZCZ7Bp`s*i`CCa5@ zgn5tZ_Pj!QMgar&kq=#^oecJA9(dWu6ky+^qUG*SN6QM*S!?ApCv`rda~LmL`CR?! z^64R;g;qXi_RR-z_SBNkaQ1&rl(uvtVW=y6-E6tXROc(u?b zcxZF31$OGmTHo`1)g*it{>jh5=l{Wev-n)=XogB(2|FsGB^MYNtZA9ReKCR@VJ~l$ z&?0zfNipWx;Pvfv^{^>*b-jaz4PL9`B_F9Pq2X9)mVe#soex#%*-So-!{YJxxeo|_n%$=s<6*Mxm5aq*$x%ZmPnfXs zbLjja_NUcuRVd-1^bNi74|U)Aj9|3Qm3uz^y(7&$1>cW6C3XYX>sER{OQhFAdXHJ@ z3BI4{b&=jyE4{Wvda@6>I?bd{@cm3L6CVH6N^e0Ty=*$WyDCQ6?>d{}i-H$yRV>TIoNh(-(bHLHeHI@pzl~NCbb#^sV*6e&5uT z3TKiUS8XJ{fAxN-_DQPr@?nvy|C4-o6E5?(csyPD-%b6YYbyL$1Pt7i;74>kygGqB;X;?-KaL-34o#QjBWK=RMn1PnJ~fGac9T!$$?^DG z;_DLp$K})L_f3cIefLKcD!z}rfcY8n*(>=pkzRgUqr2RByqiwA73}SQ1=$ZQ)%iNd zhsq|!v*!0-g_WGNRYdJ?OCi_uX)~5wZ}2C!OWJb%7fRf+z#94Ly3p<|6{IzKZ%Ns-@jgoa@^kb_*H29FxA9Q6#N(8MaLkJ&%F%cc{R!pxmL!P(&p8+5 zTiUlAAE2xgge#fnAAYFzoCl_o9zSUZ z4dk<&d6OSXK7xmC=Q!P*A1(1;Vs;VsJk!N$o~ncR2e0ScEXo|n)pR=J)0Xr&|2dbd z0ncNY{CkL>h1@rCA2?FSH|v-=0_X;RJbY~=%pDTu-E>n9lpj!qk#gh_=D=dsO$r^a z>M$wj$nkA=(ZS&fCB$ze{+naa2hvABs^j;OqlE8$a@roBzeY9=^>y+ppXx}`l%GR~ zo`s6G`p!Lv8uxDb;KTSnDMK4H@H?JsGo7yV_g#We^9f>>g?yLM8RFgXyvh4q<~K;+ zknU)C$N3{y6HC$?3trB~$r8Mp6P%&a6FDm3 z-CkE52^PQaNN?~0|2NlR$S}BKRLv2Ej|Ji*%~P+I_)0f}Y2G!P^uu!`cT0?;7HHY*4Ue zi16hE?@@K(ull@eyumh~|1EDO_weWz#U@E;px3ywAY`Z4|6b7ZZJ&Q_(DO^5|K~x^ z-+ca-L7xBd36Gxk2iXC$G2q`H^n5KS_q&3c`f;ZLpH-3XRgr(HBEPC4|LbESUp0ov z*9V_D((`+7@J~m2e&`Ewj^e|<;8RC>-tcGs_(;!vf#7$J)jxV{Y)*0nb-` zRX+=OR{DeA3#jTlN2hV$S>DfI6YLK9=LBC3dY5~He+YW_czv6L!N2+l;q!QJvFa+y zI3|AI2=B4i1RwT#76umwTfD*5-rzl60&bCiiO_Q1QT#r(jgAj?2E6nA@ZPR;!G}IW z@RNh5C$JL!RPV7O{zbvJeBPUbFZeKn2mQt8|GrRSM_1{FP6u@!EiQouf0p;8uYkXo z+6Z{NyurT({GC4EzXJY0_=CLx|JQ^$i3p00U~rm$QW9Fxk(n3VJJ|atui@(%?0+dZ zch6w|-v$lZIXF2#$}yU_R|aP%?DMvG2hlz(4k~&wpy#CEX*N>ilKTB*;g9tWyC`V*y<5Exd3XEWX@yQE zk5R$%-1wpA2lx2Aw=VbYbkUSjwvP3tpBvol^DY>)+vi^z}_c8<~jP zt>V6_;{GAv-|P==>v!B|f|BnOLCN>QpnrWJcz@8&;$!lCRKzd8{7f9-t> zcw<$y|H))BGsSrnPy|ISFL@{>N!yuL@Y;Elq0TEz2LybaX4*^}rfou!&I1$!sJsM< z0;2rIf+7eCy@*#3y+lzMt|%4of`C#Kb?{mAULHP}|5|&ko$Rx7PMf4V&G>!yeBaD& ze);Xa*IxUz_TFose5RDRFi&g^{KfD4z0dy}zyA_{;3>5s_G)63FfVO*FpgG^LMBA-2-a6m% z9f992^nKkI`0GMAkqvxtq5ndE;E{#?r{)IsEcE>;5V(J#|Caf4o(5!}z#YI@i1?KY z5x-_3G7Fu5&vh_fYykPb?F)R@=YQT8C{)^>>sowApA-1~eBYSwZ7`2TzEoM-3zZ=DzT;e7v{^AS1B+}CnW;Nd#ZRp7}w{{?dbxjO%) z{=oBf{(I&I?yB?uJuv5%I{&Zc2d=8~pI?Xgg>{H)Y2#cJ4-6?Vj8#$JrmQdUeyLB$cyM8V<&QBHfE$?{W68YWk z$9OlEk)Mb+ubg;$e9JHM`>)=|g2LTYXZ_9ZzrD_a3GDiPtRK$x|HnSom*xe2RcAdv zFYt#t>$&;tU!8}<+vguA#+YM$hlT?W z&-Gn0C-Bp`)*b#!eZQD%{b6q4`T$z#mi0CK4_Y`q*uEE@8@MFkd(3y6AM8j++lM~= zHefdfnjH8Z-@gCr3%oej`qG@h?zz@4=5`4ADDXe~1pc_lcl|=dFIXRsf_-HQ~NE2;~duS zrq4MJnFa4;21jgsK1c1O{VNpK^XCSMUr#uZp?*2uqsy?@Hyd1~NYVo>d`LuXBjyJ~fMznZISw1b^lN@i9 zt%Nm*u;`S-yUb*Us^*Tj~3H=1*|guEoo8ydcM`*Wyib zysQ@QT8`Ji@fx&v)^(JBPK!6j@#;BVP>Wa3@vIx2<=e&aERNT%#cSYr?OMDEjyHKN zr5DlS1vy?;i}wo0o8WleTD*2yJ}qAT8>yX*bG)P$FCxqLMQ8br;&?fZm(}8R%kpXQ z+Bx1B#~ab&C1v@vc&Bl^QI0pN#mma_Y4MUAZ-nEGY4Jv6`Oqm>c`o93S&o;};*HAk zY4JumUXtUDYw^Zp`LuXScY4PC4Lxh%s9IsxBHz~`f#XFGWHE_HJEuQuNDF2)mFUaxgIbKkUSI_ZaEuz#O zZ0~bCi{rIx@ftW@yB4pT<4t~s(u-*Ef*dca#oNL0COBTV7O!2FPm4Fg@y0n`Qi~Un z<-6HgzFRn6j^kyuc-^vmTD%;`8{>E*TD+tzpBC>)jyKBjMzwfZSw1b^B*z=!cw<_; z5m~-loaI|^5YK-cFQ>&DmF3goHE_Hn#~at;jmh$9@me`vH^-aM;^k!dw0IGY7vXr5 zTD);tKAsmHjr9LM{L5-!(X;0sarVBq-6;!j-NX-$cTtMhHjP`A7X5!8z^l zpU0ze)xVMM-@QjX9#N-<(TUpS8TG&$cDVC%9(eaocfNJDJ3i`xx1ZzApYXu5A9m+A ze8e5kdEnjWy7R4%y5plBczf2JKjDFA&vWO)Nv%t5fq#n!-hF{P-};z4KI(zDf83ov z;elsA;m&Wk&>hct;N2Iw^I<2(RS%;ccspK>b9p8_@a(1T{06vB>h|P3@b1gp`4&3# zx;&#Ec>5LZ{0R>{JL1l7xY8ZZdEhQ0Ru#(8aJHw^O!`YDdhn*p?^>3}EA&XV2%f2& zUinMBD8p%h@i&pZ*6?NuC4HuH&Xzu`ak&*y5NKgpjLQ?}MM{P`{X`JJ#mjSslV(UYTK5r4c&ya)j9y7A}H1yrwZ=FdlQ zNVjw0K01FdHmu>h1^hky)Mf(zoaA8wHm=1p3S0g7fNQ>Zc7g8@J{(x*v3%(Nj1T&0 z;gfG&4fK~BeOg&?^x47(+}gzRMhkk9WmdcB5q_gVA> zbYD>(S&m8me5gPz>s9{zZduWs-v0%Arv@Si=UbFRz+jF(wsRQau$#jqhgl9sI2`40 zjKds<;~Y+KILV>)T}wRm95!$mYGdg!=E391R=>Ic(=J!eKXuNe;6dj&L~2;TVTG4#zp1 z;Bb;d>jzwZ4jVWOa@fvcgu`wQlN@F_9N}=3!!ZtX9FB81!Qmu_)&rbBhYcJCIc(=J z!eKXuNe;6dj&L~2;TVTG4#zp1;Bb;d>p{++!v+q69JX^9;jo*-B!^iJM>rhiaE!wo zhvOVha5%}KwTtuTuz|xMhwU6jIPB&y$zhhm5e`Q=9OE#@;W&pA98PkWJ={+MX#cNX zx$<2NN1d{HcqlX6(AL=87(6yKEIx(K4F?;8&5hxs3D+XJeDs6Wam$?IFZ|#vfxok- zKYo~H<$SGv=Z6c#a-MeL0ZY#3PJEsv=S3$zKR=&3@dcKgmz{W>CFgG^4%R|WMd)w8 z^*XD;6$fkQAvgXatKJn~Y)$;cjlaZ__L2InAK#YLU93>QwXgNc)o%EH*7%KX`2JSw zZa4h(mbAm1`Mx1w33tZ}x>ocJ3pw|UPGR?pa5i`%0gtw6T7oawyDa%;bScnR~U zOS|?9?|wA}@a6Y`@4xk8(fSNvXq}6#`WJ|QFGo9s@o~oA$7;fN#UNkS*V~!@3C8C= zN`SNnzrpxh7;j&$^$$#7fj{yPG&+@*xRU&jyImvDLBC;4}K;Oq7y zzC2fy{9k(Dc)b_%ZRhhn$*+S2pc{T2;}MOIzX5`L9sdsF-5P)00mRqwpEI7+_=7Ou zVEQ`#PsXzv|58}!B45W3f*~035siPF2mWqYm?M8wzNvRbo058vn$%x#K@!d{X20HV|LOUuInTXUO(*#UaGk z@gol61X{e+9V){B> z_fEn`HU9M;c+;`OAJh2X^T1Dri5v6HY5b==@Sfv{Kd$j#@xU(we_>32LgODAa>u{P z_@u^f3=?0+Z(`hHe<|61LQTZi@$WD${X-?)X(6c+)y}{-Yjv*LvbN@OV;Z(enc1K@C51 z1M%B6ye>j`M8j`kyj#PMKbiPR4S$^RtcIsI5`RR)=XDW2s^MQ?d`!cS-$eYJhL1Bo zuHn&Bh(Dp>e`S19!#{p1@h$eJllna5eT3I*_y zLOhQFj_pC-H<0`b23Ve9l1K8N037-4?DsGE=L{0Ro%t{giRXU6k)PH0gG0oh$WZz) zjEm=9z>%NR_*)ai&oW=ib06SB{!vn}l&2?2{08Prd2Rz-$glBFIg9wYv{Rlh0xsm& z_>mOxyO|HezIbi`T*$BSSEq?@F(0N;@mvYGke~hVrTk49;*X|C9xxBYvlDP3zs5g! znE36?2lGHYJ%9`OHU7M9#Gg2e(wF>ofD8FG{@<9NWxg!$n(Zt<``JtRUj-c7X9M$L z`V-HZ9W1}be+_Wt=aM83Oe^9!Whcw8@%?8Lznl3o{ZjxJ@@xFRGv8vq)PKi0EI<3v zOZoo?befe-d!yH!xq;*U?#)U*kUtIP!CY&hozPJeFVM{}#lh{QWOr`PmO%%6}i=$R8abd1QH)e2nGS_}>N``R&Y?aOCIC zBzeFL6VG86v-}$WCx9croB6W+A9e}Luk!&%zNPaoW%=2UUF!c)z>z;1CwU?)&k>(w z`8EDe0Y`p2^QAtIzKrG9_|E{2{E2=_U-tK=%UOPn{~N%OpVj#9zJldvKXobpi-04) zf%#x|il=jg<=6PH0gn6}zN{IZQ^o(5^}Z`vevR+{6!E*6FWYAq;9~sI_a{iR@h=#Adn)uxs{v6{;4c~SR@v|Dfhw%{& zzx*@AAJy=~t|fd-!@tUSPQ#D?Eb+%R{6~yWX!vQLBmSg@Kg+nq_kyH;`mQ5>y@vmp z@dgb)@Ba}$sNt{wJmKvc{#C{!8vdT^iQlc^|HXJx!%zDH@v|DfoAD71-!V%3Q4O!V zf$%X6zmD;oh97++@y9j%9>ym$yz`61pVaWD7`OOdh}8eUmxy1l;l7&)Z_w~-7!PXr zJHJf)b`8Iu@rZ_>dNc96HT(s}lN$b!TZo_4@cq6*_=twz%J`^;ueg=?V;cT6<2el< zzK!_f8b0r#H=kgNY&G>>kN=M=!xP$UdalZe>>1+qw zXB}Ye(D-#@#6RJuM3m_q3pnz}H2&9_pJ9F{r~gCdpSF)vo|FHb(*F+gKg9ev;F$g{ zjsFVs-~8W1OfdhTJBe?-&YAuVfa82|3G<~q_cFg#JCn8{nA!MH>J3Zxa6vPZCkKhYtdd{G7)BHS^aoU#>&ef63jH z{r176&{=0rg#FLr-cjjj`{zc!S^e@%; zHv^98->vam?j`;+8vhi)kw2;NpJ)EDPdViYe4F?S>Ye4i8gOjS=Q3Z`*EgBpuJKoY zhxk9x_;J8do*f$hZ_Ho#G|3~=f6IRoe@x@w0XWLjrSTtQ{%(!m4+A6eKgWF8p05BL zD5Q#Q(9zUjsPuPt*9%F@Mf8B)?3*?z_Yv(fFf)qdZGB{zJ^)rSaeQJ>s9K z@wWqx^1u)8h>Tk)dn<51@vmq83dWBB9Qmyp|4!ylX#Afr|H(yuNBZ60r}Pi~IVJ3) zX~{Yda7;g_@fZJq_=o+1_(Lquv4A7LU*ms^`ByUkqs;#q^G7v)-vg9>{j)^;1M@Eg z9Mj*e%@_MWNc?{=|3>DA07rg7V!<@nBdM&y|2< z`bRBs>hrLNi2o|{Wqqv%9QoZE|7XlU{+E=lvZ5_ zzVdxA2QvSc0r1}JMe?r^IIQ>i9_lAq{v)0szI=a+cf-7h^2qnKNdET(UT?|!tmiX-HOyPcm+xtj{D%b&?TzoVO8&_(Pat2upGEQ~ z1P<+u`LetT7-x|$-^(KTdjt;qE!jCjlFL}0D`1>OzI-2x>BepkrU-nbXzenI; z*B#&&h~#&|c!zv>k5;DtGl3sq$@i~FesqHP@_wz<{|f>KyNKVvA^8~?zeM}zd$$*{ zJbMHVHisb)7;GloLzbor&@HfPl?^BWdR|F3FXTB`&1u(9m{PI02l8^7X68irH z)vuKQ^8yFEPSejZFA!he50?CI3LM65jo&x(vb>K89OgldzxnsXm-mTfd0!Mb z*cJTV3n~8ve;~fRXDr8)H~bNCSQlvgn*|Q~=ljQ!-}Wcs%lD$l^dA;D=%4Q&k8pk2 ze!} z53uBWPh|S1{gwFg-t*-w&kF*F@n1{-oc|%dybmq)v*>>jhw)$I-zacs|Cf{evcE5T ziTLvUCQ_b<1rGYx_|cb%FW+k-`7a9`^w0OFKh5%A_6qUk`%EPN@K+HB{WJe6=HDxD z82|abB9h=)x?&v_oFd?2x4%=^V-F$oJUk>HJPh=RF?jyqD97z<8iOYZ=dKxXrl! z-n?PJaX&}iUyydx#{^z{&*C;t$AWQ1eZDF9#rHM5!JIvaFSdd|pqheVO+5Ppeh7>MW4vCI?feA5 z4+Va!AehV|lLe zNaxpp-vI4=2lp@89_GwJd5WKnfMfc}BT4@4Ot}p3Ltq?h*i3jMVoeQG_d`I z_|eRtA8^<6+W<#-+Ak&k*SWk=!H4k{=39JLQD9x`k&NBt~dJsidSCpeukP6v9L zc=n&?E>Az;H$Xb=TEDmzaFjE03CX#e)A`hV(sT9^!uu$&ZUtPFYdZm~J}a<*@X4d8 zpdaRR`T@swH4!EJIL5C7+^v0nSKuH|J@MzU-X=Wwy>*mtlKbOMPXAkgW4<}=zs-#Q zh4~{pN&eqc_p?^+<1SAW@IyJS8hpfqf29Zh6~M6`lUjd&TJWK~yfMILiuJ#Mqn?AO zkpgzG{ySgiF6WTI!T)WXi1?eq_3fCmBDS@q1+Y*HC%iOMx{Z(*ZjXpRJ5H)svi)T_pb%jNb#e zTYvnKz@eS|gNT#d9)1hBoLeae`hOn$FdgbGat85F99H5OA!o?)?Z~N`dto<~PGW0X{txScgJ?Lw@@` zBDpi%NZYG$I^uy=>fp89viqGk7WEsz%k#3pHjZ;hGM<$jV#ZB zB*--^&oKg5C857h037?{-8?==m=XgV?W-Kyy>k8?16=5t^>z;P|5v0B_4N$N^C0KD z?|~>!@pCxfm~T+qhs+8b+AZHV4|3GI0LOeM1}J@Y%d_SkMEV(J{j6dBDS*4>8wVWI z8T}xof0+rxN6kP7-v9&h{Jd;|w0ONE$G~p@F6yO;(hoEL zdB7X^Z#8%oaJPKl{1!?ltIZ>wfMfd~<@RtICw3FyZt2`3aIm*up^C-dFvjOG5B{$` z@aDH-`p~ccgVOmMx99gV9=VI~=P0l~2sri^i`OHv-QL9f`Ui<9*LU9p9P9mBt$v>Y z9Q8SNI`Nm2_}1ZXb1&~Qfx|fP7b1R;`R7ZV7br5{t31-#?Sa1rIF>7-t+O^YkbWW$ zk(?_iu+9P;C`_(2|U5|`xd}a{%d)h&vH5!0*>v_;&v$0e}U7P zJcAN=H}hZSbo73-=`gO}GbrCh%s(G+xAuGs^Sf>0|A6_Ad+;ZjpX2mTWd2cyyQjYr za4c^<_jfiotp5ZY^)|udlB}0sGG5Q)z%88qsw1eK?AG>ME(cts-$DBMEb}+Ko%O&t zm@(qn_ejDc?X1X#MU!z;A&1&9R+x z0;lsL;3$8?I!YgZw-%q!QQUrhOhh(QtP>^v9m08g+B%)__SaE5JZ)Gz7|(r`_-y7{ zpJu!p_I>gBhm?o$>??%dOvzcxkEU{6#Onw-{tN&v`U~tg<0IS8!vZHv{r{L_sJxSG z*CqMOKEN@Z2<&I$)5`LE1#lc6+If6{9wMIC0C%gergvaE#g7d*>N(5yo1CY1F)m&_ z0@3c{@-BKO$kGh9PQAbH-$;1y1d@Nsy;x6V3_^p<&-u>yRL|lcY9}v;&UmN8-dkgaYeK#wRqp;W9 zaA*&_-~)3-JTCx_?Xa8oALKavmL}4}#G5F6{C#A6j$?cb>{fi_xN$n;)}4g&Hlnoy zaI6=7J@^&oH{3yd*~jl={-{=8yBW`o5dU2Pk-Zgeru4^n-jVyCR{-wTp6~L&7qw7% zbHAeWW&e7I#D7P)TrY26eDw9CA2yGygv9@g`2RzJbtT}a2aD&^5Q%R+&iKd&i0EVf z0ZZNGPYE3Kxi1kv#OsC60FLR8aC?3ur~h5Xb$$NMBmKF{D4p)3s9bSQrwwp7eXeJI zgzIZP^UwC+Un6jk^9hol-Ds>a5B^U8$8wFcJn}s5T`+NAyWOR&cRm0(^4qyz46r%-_)1OKFbkg&`alOBEJn@s- zKK$Fkkic=t+C{__%wGXGrhg##5#Vzn1=d}F%Q7+~g5Lq&paT5&ymzylX-XKTb@2oN zcdPf407v~NS^sjr9`N9QmDAVH3!e7i9|sCSd!Sph2QB~{^)T@w33w^bUtbV-alyXl zf&UV4)Z0Xc(y^%;tarVK@cI@44&ZU`W3{`d{|>-! z06hmaJ97wdv`)Dc9MB!;%dQkn2d`flTz^`W*@Vsj#6CsT<`q9-w652pLl%jj#nvn$%Ut)rs@ zB8S@Yag)gny@|nCCbe_pnpXK|BgE|mUO24qB8haYD-#_|#(Fod35Ar8d3sQxuZ^Z- zsji;r(8e`w`M>kbW`((-r)M}B9qQS+Iu*yHn;bwsN=S(kNyLXTD+dz8$PX4i<;hOL zB{@uj=RZpN+R!p3aj8z$xlr~L-^)ZoOO-S>q_B`*0$5bo9#}U z$%#~BPcjL4bY<4I+IAcY7SF)P^<9}zo86TJ9=z2x)@%3124b05sxz{_MO1RAc`&gp zW^V>H11A*=HLrj_*GIR-`=Z!nI?f2U4CO!BeX)!^km!jH*uBwAwBwY4t|q&~7ENO9 z`Zn9{8ydEIcI*g+?X`)Xt#&do5bxR95$@<%74F!!SIHAHCeKn$KYas<%{5h!A%Uu+ zp;SyXxadGFn~8Z6?PleH{Hfk~^QdPB77z_3qEmbCxF)cNPm9~WI7&JlE;i*Q0xlysq zX)83fwrZp-lTw+}l{&@9mQ@(0YNRTILRD8&g>hjo(o}^)8PimFnb!Z*k*YRBx+#gw z=}2A1W4}{$R2vl;63Co})O`i9cb8x4)kZ;PUfB{QAVF|ZS-SGB6B)Y2SiOrwNa5Ffy`-09T8DO1-r2}3Nj;4_4HHO zh*+J|C#Z4@(OQOs#Y-N3>Y z!-xHFE^mi>Yoi@wA{oKG#YjnbJ^G~U+_^HPnJV@e`( zI#S(KdeK`ildu!$a9EqxV?-Qd+6k%l3~Q$*dYP#p#x&BTjx?fAL3@G*uMN{0}%e;qE4be>B5vYocs!gV-PdT(L$AYbji0YQJB4Xi0aBr2ca0XU$3Drdk z>rkoUa?a(eQN`wbtg9lOy5?o&6&ha|R_JUAS7>)N7S5<|aW%Bpq#7kSv1!iFdsV-c z@)g?NUMXIo_0?KDQ_iB*XnA4Xq*8|C8u!}bo6VJYM^;5?x`kY5Yqi#yYNVk5O9dW* zRneHbzpiE-)r#qFZqFPE5pj5Ru zTD6I0Q$_JibUL%*85yR`iezv|H!GNVZn@Ar-o%y zHzX?YO)h7cFLjg+&3w^gR!feRYK7~TVd0Fu`?nhP>gcy79B9od&#|6i@%FNTPc=;x3HPG0PdzkLBvj_znh(#a9px@! zS-*!+jh^CgY*b{d=t73sUg8i9ZG)LyV=*k6TC*rxMZYFfRG(`@tvv(q4i!5&5FHwV zUo*g3h=i6!=;JE*v|%`t95(fvII8*JymMFLeX~$A+^fR!^AGZLY+TcoY0KGr&%wzqut4J zSLpFmN`04*->mDv(FQ9xOD(0`9(l}qSsksf;zQa}N<3vwvtMp?n@Y6v3Oy7{D*7~; z&3@_CGn$G{nM*3RS1z+&-kBX>mr_>O9A>|qYC|jkT)d=$x@J+^l9qqoUUo_ISiAr1h?E~zx?WKiV~IWS5Z>Ay>glT@~WG{Sl&upHcBe;6dBEasnxwc zJf*MffT*N$PnlKiOJ3OhFXw2iqLMqZn*EX+a%d^3=u_u4`(;GMoL< zt3ywvJ~<_oe2R=_ztrl$gCqMajd4X;)xPA8fv3ypIf$-gM^>|6a&_Fnicn5YjSufr z=QaCfSBD*~>}9z`mDJOx$!yk3@7UqR($B#6pcDm^kl)^+gF=Ta%XOe)9XRuweI2Oh zzp@=DqkwrOl#t=VWP6Xx4RiJ8v2HXJURiZ;si9xbIsOp{k_%Z}D_ zh3=_km%TWz*)O}=AW@#m{9j8d`jlDCe#zA(OhrDktAaIo*UR+TR^)g&Gw0JP356}P za&J&`LOEQ@%6HE+Cy2w-OZpI&>pN*q9Eag6#i`7t(VS3@$|~Q-(3~KS%Bs`>(4aW# z_T>!x@(fC(o`_fCD`!p=S0}SlPYn!;q1I8^US?I2Bk!O!`}&y9X{rVisrx-M@tQJM zS*3Xu)mT-9sl5DmshCrhwNa4T zpf!PN)1V!z8<8^cG+Eu7RTPkPE(x6c4W{T95(x7T2RVl}_H8zWQueH{LlWNqm zNQE|4o8iFNDW<_@?pUwJ#2Q*@+I>u zghD<2@M4inDjLtEJ9|31qVQiwC=BoK=t&F#Z@4GZ83Ab9CcA5y-IWOkwAqp4my zo{6QRnFK_R_B9G}GL=X+2I*B6 zIu+E@W_Kk)6T?H9Sg(AWNoUEYOH;h#q|{bEjUYwu5}7K?QhzaBRcPTXOX|^tUW&}l z%8zAKVX^OODVdboaTLJk6J=O4s-zsdYSNW|P@zi4u}w9mZKA z6V1fzOrpZt&L2jYlyF9845}K%k7F5?OkI1Iee9r$Mv5pQaB74 zh!4Tbzbb5cdNM}kRo8iijLN_At*W&s9g`B9J=;*lE=)b@jc=2(I~=jK?8>@UJ%!lP zqB3OtsADKfT<-CRE~$ubRHy2y5+$tQ)I=9jCQ&sxE8GlMRvYXur_7Glae`%xAt24LKYLxuSdMWkv;)jjO@7TjtU5KO~xC0l1V&p?c7^Ve!KP-L8j11b&jC%CqldnU$s1^C}$1sL1J5+LJKvL$h3}d zxSYW_Pz4>$Tp|NHnyI&e8NC>g!hkLu_M5ai%eIfrXvCN-2K3^XPo-WI8@inN)Qolv zOJqPtjuu>jUyK>O7?8q%E*x#wv4)xbmSRj66M9j1jYL1H>_lj4}rj_PSp&`t#&bB5GoQXT{PahzQjR$;13U75q2iRH8IBu0zX z83<)SQ|7z@tI(3Pnk&yc5#%wUAJtYsdCK-ZG^7_3a+uJE-iW1};_UaQupv=QXvNIw ztD&Z1OqgnDrf>#RgBGJ}rea}CXhyZXXK=D?sL_~{#)NKEV_efsS?+R%lw(jF6WUP+ zKGaU4H!&E?q;}SzM;Q{ugjUqfjWcy+9x#Slj4@%Vp_z(@Jp)#7Sl3L&!kEyEI_hDY zQI6Vc(3#9hV?sCTpr`4k)?@Gt#WA2A$N2<`GXwt`GeeGHiK?ZeLU%9Ao2QC8s$3!y zIx^`yWJpPdMKYl!qn=8J)MQ#F1A21o=CJpAP0b*6UvQ@KR7pRD?q7o$-$g$a%VR=6 z=5AM+>15OYj88c)Krx^p$1KY&S}_`HU>F&e$b^p6MWJ$srZ5uKV(K?8R24N<7z6eq zO;s+G2~DXt85_newn!SKW%X%DwStMoEqv zeKV8BKudB+gR9&M?-y1Y1Xm2bE%U z9SFGP(38rfGs9c9H1=3PjrGOT@H#&`Gidh=B!*&X%eH$H`BnpO`Agf;;T={_VlX)n zgLmOIwg#7m+)4HpcxRj)O{Jnc?bs0PZd+SY(ZQJAJ3KhJ6QU@e;8lEa*nv@~wteEp zK%w#tKQd`ifw7M?Y|`vJP7Fl{ z;+dWHHh2pmijilCGv&6}j-FT&Un6LVoGp9R>FbxT>s$$`Zd$ieW_re^mFrtJClcvQ zD7ZZpO;W7R^v(udNS&aPFU_^wtv6o&jTO?x1gPUD*>@tclTcoikQXfhq^h(N?9DYT7V z&Vr#9+q(|n#g{QI_|k2p_b6l$g_m6}gB+xw(PT0<)Y~zrDpz;F#07+fF z&c7iNnnP3Xz(A-u4R6aYYd939#WaBDsFRsnQyWNQwd@5I*c-kqL>lR#F z9|{**O}McIg+EmaPtBOCFC6ZR4aHLMdQh$QQRGk?JH3GWX98Zj35D%TFWr!WvBT~J zJ#OphSQQdKU#k z(`;V%PD-SX2qwsnLvgNi1DTjJ1WMBmJ}MY!$-m#KFSg6G-R zj*V;9L-NpwGyNSAMWI11Dzqi6nN9seOPg(3Kc#hkE_R_sIOGV2)S*J@g2mN_8_}v& ztTsWpQLTI*hA|quv24xmRn*ea+ZU5HB>EJ-WOdpm?{E!A#dJ!g%(&4CJx`IGbIc5S zjG0Ou>VvW9W1*$+M%r!A_QETZNzqI2Z^RRTMZ)Bc;dM?aH))Eio7$g862f-kQaRf28cT%Q&O zBbWAGrt!Ekgq7cn3k)o$XrWl``9+LF8A@YS9hazYH`%9#LrbOgC`Z5!XM5+dbh;XB zQRl*Gdw*zIJbm&oh@BdO(c@I8sosriLcs!LK}`+yBzNjnwP}+yXiBs4XkH5kZSK@i z`+d+6#jFXn?3gu3DHY8_>2$nri0Z|WBq=Z7j%Hr_VpihurMOpzVnfl*12KDZBGW(B zx)-c4ZHXMT!%KM?LKcN{sk_PUXwK|R#$X`?jc+M5J~_M2yhtmYkDULLb}>g9>)E$L0G>=`(hpONRP5gkt>r{SSre26u`;J zPWHkt3V19SaoG~m7MFN(*3q%7H=f2T2=uGbZWe8DEexuuF1QIK$3tGL$mJieU0W1^ za2#IN8-rex*eOyLzW8Mi)%{`v%ElWm!cfk@^3A3 zS_`8!Sfcsfu`#5W;$iBSMe8MpO}SL$B=zMSe_%z4(>R+)o$nRDQvo%xO`W!&+YcpD zgYfGV^7k=1BT!*rKfww)iDptdKGc&)J6o7GycSMuK<1E~=W!_`En<)pP2*x^PCd6w zW$%mY^sqY@i}94uH;g~?k%EmHXcSY;21#5w;l|;xIUa>9A3rJpG`pM z5*}vJEVX5&0j7CXPXhw+GZMVdGC^b99q z9lLXND&CtP7mN0AVe=dk!j0Qb9O`iM7NBW1Z-JpN8gUcMIatU+qJ>sddGmBCyJXwO zHO1>u+PBz}NMyu@x|M_kagR{^2#`HI1Vg*B!Oq&18xQc)MxOhgxJgtrsmXEJW045w z&x15|=U10577!1EILZ`hs<2j6b%-;rUeNSeDb339T#^)zO42^lc0XD&3GmZb&J<{e zwdmxaV;OX7dvJ%a^eR~N!HBa?PC=k%WuC;9kuvdw(VTM_`XSst&Tm{Aw!U!MDAZi( zYY4ZU5QhQMDh!aO{1&9s1d+RS`C|%Iiefvy%q3xmwY?|pwyt&BYqDv(FJGngyP`$> zf1&TY<%xzLphjIgbnkkm7M>r0pNos3sr?P(H z7r(Ve28LnpYHb2f`%j7uzzI0)>WIn6ZHeTv9;B%&Kaf>nknA0ZIQN0nF&wv&lzA*# zv@U{aHPlM;8R{$CYY%7Q18`V_E8p;{O$l5E!LmO;z&OUzWwc1jTP4@{(+d?}ouxREp9LQ{F zyYoZ?pm0-uS-ojHxP63IbfETuA8`~hK)u+z1ib5^C*po*!YIUI@C0-c-hu3|>1JM)~ z&ea-p9I^7E56YUi%E2k1?1dIB1*^~<<(#F>Meb9%G*T6-ORRb`2~>vXaSUv(S6J+#EibFo*>;^v78mQ& z?%fHt7;HZDMAKkR6o!#PBbLQ9WK4vXDaSUjeFn!9xHS#O;&P`1vd(Yjb8++`UaT;r zr%sicmWff6COXj;@q(BLHWT0uyxvgFp zWnsO5=XKi3s>9K1apEl=_30N0z@0Nzv<)SW2}1Td{6S^m%{BdDt|qSRgG=LSTOK8X zfin!pC>>1z6nZOq)=73a6-y?-!;BVYXb9!!3)Qy^wj9;+VD}W0y9%<;lM3-{Cw$b> zb_`sp((2b}y5g_Gf(?tmrwtM+wpAoCu(K~Qq}Wz&J}jXYCokVFHinv=-$3f2w!Gyg zb_s;Dl47-~?o4iNZKLD(OBsT^hZovDG4nM3$A(6MFf7}CH`lV69kaZRiI6UBC2b?N3KZ^F|IsLl{= zP8V$9jNd!}TPAQ61l|h;-zxGB#shcQ>cevZXj$Z}0G?H@vkL1}8@TuY+cBRa)9gWw zi+$wg!D`S#Dz3}IK@Gau^b97Ql@Dch7$kDeE_K{fTMy3I${i-urz366*a?c28Ez3w zXl#N!yG_&U*vOK@gokA>*C^6IB;2eFU5-u*4l8;u7CWQ7{B&Q; z6t!vT-v>JB9Z10a24^+NEk-&Ab2|ldIAY|7QXGt2O&Vy2c~X8l)GL!V^^(AZT|Md^ zp{8MQoxs~j(E0E%nEmOB&f1$-z=7EM=(c!YRQM|6Y{0!7ucY988aRx^VXYH=WuW81 zZW(xFWD@il4kz=6p6r?-Z!gGQ4P{*5X1f%vz2USlN=mp&5Goi9;QH znvHGwNT8eia9hdNNPgcynN(D#C~&B8ddVpLJh5d9?t}FuKzUI7!DLKSmB;UnxVS*z zsEmC^{JM_tEh*T_MV+cm4*IguxOXQxj5zir9QFZhh(eRlw?maNgB_m?E%({g1PAzd zA}v-w&7E+u4fo<*W`S}Y1NjIvIS>VB^1(q^$`o&sDs@&o&#GNd@yStVV#l%u$67px zR|rMlE8SOV7|zWjeTnI)Bed{pIa3mIkJJ{)d*!6wVQ(-^e+Tnc;awSE=4!45#H2pCY0OKM+|n#cvLvi zqaP!{UXJ@h;AYg#F#~ zv#?vwa;r6$JxXcvmG8(n?J=^pVw4kesjJbBDUXZwcO9e39$E);p94zg8f~w=yBOB z!DWB%aPhLgAodn$l3P5Rq{rTl^F$rT#NGk8$z5cz$lW+)u_iWg@RnQ(JR@wpEQbb* ztP7`A39n~xT;Xhy#}4ua6HY7nJDmArUQe4r>4~oEyq1;l+KQprz=^QElqti*Pd22` zV03HDriCtgzq-C*0B$9??rXswR;XxW3kF!++EPru_!c)TKp ziU+6saC+UF7gMeSlEbN(y)B-~zz&OZ_`+$+W72Y(*CiguknJuvglMgom8Ba;c*en;j^9p-84wufbUZNx}_YW3ZtC50VrFl z>Mur1Z`$sL3!qcH4@25Ta>&yRgQ;#4ZP(qg$)P^4SC1r}DvOB&Slo+%E|>uq4%ikH z7l`mKy7RcOXvCRndze>a`i2c!j2`Kfy1>RZYBj=S1(rL6nG}Wn@-G-%V~uddxe=yu zaM#T2v>Nl!=Hd82@3HY-OAye!wi>~A1rnn$lcI0nwH9f7hmoN12OGYF6?zmS@L$P+ zjMa#4j#eZ5+1QuhKhm)ts}YXr;iGs(Qe!G1?&vkf`uW{V{k@Qy`~=zbz$;PB{6q#N00iHe(YQICw%}*D2l48WHS_1qki>lWH;0qD zh5wLY1LHDSAphX75kfWoE{-q5!!`a~?elW@{L-F137P*S{~^Q2F>!cgJU#z4@ZIa+ zpNzk2A7opW44-@}eGWk2gMTvqfdpG!5c=Vtj6ZrbeIdj1I+(}-rlCIXhYx!c`43Id zw=(<`CoJWc`N*&z=&vd9?>>v-%dmknMEUWbl%H6ZwH^Mzv}Jlvrsx|PPA;X-GJhFg zmj67Czk+DiuCLG^GHhK`h<_0LsmH$*Fcfhf(JU*+e{hKHOMRpq68i-Fp~i2>(Kj-j zkQs7>dM&&XKCAJqhnT>j{2(|SaU-@2RP%kbbOQ|JF2e7zX{VIRh4bOHS}`U<6U6v6rb zW&Se!BYcBd$oRWB{w|I$c`^a{S%$B|7pOlOf1KlwbNuZ7GA4z3{m+BQ^OX3JgDIuR zLJDPdV&BI{<}1^=8Zb5gvA0sZvBeaggkLI;j4#6_@Vy$}YM^*lJ%w4V!eu-e9;n67 z9?tPzPoW%VqzE#e{QOpkj~M4_jdJ{JIer9%Q=SIpZ~XHx&OfN(GX6U>TqdW6)KZ+p zU7Y_YP7v_mG|~)2DZeaN9pF-S&$)vX|4uD}_R;$P D;S8`C literal 301968 zcmeEv3w%_?_5Te9hzjhcf{pJ*VhuiEH@r3~x*-Ja$_7^g8Xvd`NgyeCtjPv~iUt!j z+ilv|`k>X;SjA%18hjOBHOM2us*UgX4k~)L5s9D@AISfEX6D|^4!ain>+kdb|34pZ zd%gF3@64GqXU?3NIWrrs$@R?|l9Y6aCay!Yv$Z6Xz|$k%TYsBup&rex9gZ&!?F5!~ z@QanidU4*xU(Kgx=QNculwR98tv<*9o=agq<$SC>{}7&0d3N8xVe={H8-`E4|Kj<2 zzm9zdj}rNg=1(&prJ{WG-}3bJBe<%}r&7F@BC?Z=bg$#t4tP35I`gUK>k|3YXS&E| zKB)}4@^^$v{*&_jB41e(FHn7kMsWV-(=6|N?N9AneRSyOpPlJ??Bz0i*0$ij1h)hC z;kdO$8P|FmGVJzbtx20fK&!pMH>Axo^e4&dMrzF&j?_b0Lnb+rR%srsz-@1CDsd!v z?(}KXkot|^r*9r{l;enu6C1QNtwTEzVjOC3OLF=>4ze8Q_!+K34dU8|4ryrW&{MRT z{@*lfMVg~w?1@Q9X!f*FvLo4(GTJw)!?E#b&F?turrv8czr8EzFm%5rPwFp|jAX~m z!;+ht9SzM|L$Wr+n=;ltHs!D(j@3uIoK%$t&2CTo-HgIhPV_sPhiL16QKEU0Qks%x zlKOPq8=q`W(aP+;CM{`1OVhQ(&~H;_G)&T3Nf(#lrmGNl5$;8}OK~s8y#zNYt{gXA zKj#l^sd!f4S%teA_vN^2aM$7v;g+vuAeQ5<7vL3mUWNN=+}Gf4zqgu++KzK|CK8?~ma5H{2U=KPIpz@q8M0hoGMk&&}ew70*ubz75Z3asLB% zx4`J}qIiD=&)39z51wz}ejE3@0(%e7Uh)3Ec+%rT+#g9ay?!icLp-D6Nsm6}ptL*QNub6K9YRj0**ZcG4 zW_^A1XP5lU|IyI%$KPOkXGX>S=g(gMK;OiY>C;;uUEGv+(UckEUQhkt-RHZG`}EYO z7eCQfdCp50-}2kdyAK_5+omBm<=r^Pv1Y-X4{yD7-$`f99rDJf&%V*PO8-sn5o`8T z{{E_htXrpE^3G>Vmp`$*vFPrfEIIAyNypc2{cyq~&#dkGsHf=NyDN^$?|t~l-khJ0 z`s(HEVSy7C?Ou1AJO7G5UVi8aV|v$~c6ITxPrpk`a+IF?c2Dwzb^C6;ee>PP|ERuV z`E6%6T{88OTOa*<(L=+3a>KYSHKV?|W8n!;Cr>(bbesFVirJr?*mLiy zAs0Q9HqiRe@QWY&llwRBlV>0I^n&8Q<$iKk^2QJH8$Ta*=Xu}!>bX;gxBmRfaQglw zCoS(?an+Kq-nne#pB82Nz5ASufw6kaTgY!-#lJ^_InleS3L34V{Xbi^Pa73XN>#Rb8r9goV~rT zZ7c6xJ#h1sRm+pEd_4V<%st!RS~9ud%(ZF1yX6;ujt+dYZ|?1(6S}xY_6>K9e3M(H+A_Z9W!y| zl24C)=()?LRc%-r2u?S;-+lM_5yM{DyW+c}KfCP||3`bCDs}vM(>DJbBTq`Zd1}V& zE1x@JTiU7_x88c#1lwOretGfGPg{R8bW{B|haat_o%-sRPtVx5{En5!UYqp07w)_H zudg>$T{1cUib-X|`u=!KN6VBoXE*)*lI@cp823R#?a2?9E_=M_p}kwzc3qcx-lG+- zKeA%$=6R{Bt44kG(CoJ#Uv|qSFFktL!*4$KuLsw^e(V!BU-04D(@x*l{8-A;lxx@T z&v-Ux;sZloUf=feCHh6@RWANEbjRDr?|!Uk(QS8p;BGcbx-#eJryTR9=X`zi=M#H&_+Pm1*rnYMJod(ABlo;BZq8?aIJd3BAQsjIV7 z>i>NFNB^Al^qk6%J0IG){+M|;e!lnhobyi`sA z|9Iz_`}RKi*O7O;`Ffu}?WFB}#_9XhkA7tM+B3$TH}RCZhcBO<(u*JtWPmGU0pP*iUO(4(QQStdq&xns_B}l&}LHgr?n{z+8+Pg8& zi>K#H6UZMpEq?kp&|axBWAVN%fj*CO#^>{70(q7tX!kh@+CA;~`23$qAkWMMd>%<) z|GU%U^KVR`{~ZbH)ipUjAODp2`1S<->-GfY>Iv-Rss#02hKYPUdvG2RAHO<5`rjw$ z?=EG5Lk7qxJC6K=+f&CnXP92X=Db|zm@MUA;%X3wNc6n@g{PYtO_^US)v{%7# z@%eZX*jq<}_9{wXSHCzpKL1}N(EkSs>NRqFd_ET>uuo5d_UcOD_j(fGsR`P5WPrV;nZO7px&nV44pCsn-0D5La|Ae<64+nzlF!o=p zmBw+r;be}_5crc*vG&l8)Y^u@5#d5{?3#Qkwc{wQ@OjSv68_N67kI}D92m#hX=h*@ zXXUy@xgz~vVE=@7PviJJ!G9<0kl}eeVYa|`F#E@Uu(GG?AA--abdg@jpDXZ82glnS zod0z!m!>_Airk?cqdCX$dckbi)oRx3CC;E)@F_|l|5GBp^HrWOi?h>4OyK(I-OKSN zp@(0=PmaY*!E-(bkc?eV!e5b|og(h03!LInq=(i8oXT%PvNIZo?Tx)vVE^`Hqp)Sv0{fIsnRYvBohivCGg3j8qP9lznY+3w}=!>n8v zuh(CP@${c&@N(P!#?$8uJ)8}HLVEBwasb00yJ+o9dK1-x`xH%t9 zD7Zl2$)eouhk3c3qTIEjy}DoK_yzo-HH-Fr=T**NgWxkA{f^otWoWGZuSC8(Ab+oD z$Fl^VA#A=nO7kDV3;bH(e-`%X7|-#&7!T-j;7Rpr&*up*g?cP5+*8cy>=AWaq-W@#sVxhN9CkQ^G zAFU8_9xBT1_>coz1-=sVLssqyoB^7NUAGANdldN(&*bTQvw3<%_tr_#%;9{PBli(A8 ze;_`+!f(3-pP53QUg7803j8gMUzFZ?HfJzW@L4SUKr0y-F4GT0(LiKBK`&1@UGO;# z`XPO`UCVJ({vhTj#J_zu$3-{O`hLp$OMf!2P@3R#PlEIwVQ<>|T%Ml@Icr5f?eFHe zssB!4Z^4f_V>kb-B?~)g_=@9E!RPjoLJz`Gy(#?IK6EIOzp#cgxJ{(rFYHGX{Tkhw zU1wr|VB=jcr{Cuf?KfjNpVpH&1B&y}H6PU{zo82|hdW}|d%~Zz3xA>u{Bt(W+BJvp zhhWRD24Poi8#&`I1^;&-81Xj*f0Iv|(3|!gPiXq*bfM?qdmImo`u^7Bzlr1H&`;>9 z6u75@<6`*Hdc=6`6yx|+Jh^s0^hx@$59R5f5d0ru`aDu=7xrNKvD+M6Z{1^g!rux$ zSBiG&ujG8*A!9wBtv367D#U<7UiuiiyvS#TN)a&@1{Qs>7}Y_%HF% z#Q1`4#jZNhUJj+bK0ya$^%Wi69M@hI`VaQ-a*q;vcoud@={r8*e4h{noGa|Jy@01* zCeoiP{B}_I?J6P9k?CAcb)MFYen;|m{DSj&SMb?`C)1m#uQ`XjSKuB6e*+zs=0#=7 zxbQganei9tQ5?IPgx&TE|A1*NyB-q#rF%Q4VFv6f#6VAcoY!+X4S~N3zeoD%PU83^ z?mo0iF<&sm*@kwdtMgD^--Zu3?cvqdu1YW; zZiBs$-qd+usnD}u=((1&({hEKbSv}WePSF}=fgfR{sw1qIj0MGhG%g(`^C6m_Ll2x-W2nqLNPBg_4&Gk%M(12%X71kbG8_-gZ*5< zBZVFoyLft!hXcPC^8a1vQ=QM0qacz;dz>fi73o7`cz^E@{oN_bT_EOZUCKP|OJRrV z{O5Y%uhe<$E@7Yj+d1Qzf`2B;CwmSGe_JB(51}XOUjstVeu3WtoYJfFsJ-ZqRIhen zpJ$2mM~Zqih1B!N!`TjJj<^oHSsUG>86Z4iF1 zUf?ea`|N&@H~34U-5S)Z*zs5+TS@Yx|udY=)w63 z$4$LW7vo*4@VD2A`W}ICpZN_j0r`!PXT0F!|1_4*^8)Yqg5##1PlZ0HULDH3=m}A; z_7a}nw4WA~&-5VrFS;AM4i)w7c$=rcL&)P8$ zgaQFA;GLfrC@HNeT~b~fDy^BHms3$)RXV?DQAH{L7XM42xV|W`xV);UqWlUZym;=M zDT}JBYeQ3OSAb3B)RNLrQF%pX=91E?(wg$(Kxs`)bxokSC{((nx@N`Xs-nu$++~UL zxj37H&E}dM%irZJy}Yh`Sy4r4RVa7foVoeV03a?xbxCP%`GF;?ET%4o{G}!FlA4u^ zFJ$JVlG4RRbrm5~`0A>X@=$qo6=QYr+<1C&O)aktn5u%^ZEew#(iu~V z>+4-EQV!W<@zOwX+0p+x#IvC2m)RuuJ#G;UM`&WN}FG^!13 z-j%tis208v-^#0&c#B~fuHv$ynn0+gs615bEzZp^!hdqJ0(pVrno{`A+ z+C;girn9c9{PMceKrmF}oty6p#I;09IN9{QC8ZUmp;B-Dv_Nj|-2ABlS0*`3HOcEUKuerj~VO6<1d+E3FA-<^+T1l~h-j zhH6&Ko8vZL|1%?VIbmfrrNN3Kj2V@cFd}%X1y#$-(ZlAI*49f5D70&G>=&y4p!B|?+R~c*;-V^&S*W14w5k>}PNr0+m0*x#mW2_o!7k;mF0Tq< z4qV5YCk`_hx|w2-o69+fQq5)SH&bUOkPfzQC6PEvHTp$;Hef zUh;T?eINU{=}rEky@NH?q3Yu53f}Fqi)mtffanL4_WSrwnTtvOL2->u`Mo@IOO_lY z&zO|o$8+j=HSk9VC8&~=b9GG~?7+l{3@o1RVl(Gz)vVaXHKpX!F%C~%R$3gYuJM+^ z@s{Q0x~5?$FbC42U=Wk6TsG~fEe+A^qq2G#Wvp6G^V$4Rrqh~)lvXVXmGN1vn1u{7 zUkv7p6ETnJGQptLH|NcX>8FycMPOI-J?sWmgF!OZ>mKM!=T2b`-Hllk7EX(+b0Pf| zvAVG|8#8dZS>K(MX|^GoSWLoXBEAk|v>mrcPsu4Os;Vljm{n0-6#4;tGhLP`1cQSP z1p{-eXOc7+w|wp*W|fy#lpJ)Olv#o0%=oOpB4hPgg7zypNIk`~Y1gEj>Z(vpbp@;J zLCYFb|G0doa;M}kszHnb5t08M>uIs>?uXe*JXvGB*MEVX?703dJJ(dn;+P|wH)jfa z@`iQ?<}JcXrnK~6X86)n{C_gr&!TBOtrr6MnEw}tT(u!@{>%VY0Pc7z0DQ^KoD65T zq%=eU6U?at=1QZwHg_J@4a~#2th&H0VkK6Iu#z9e48m13;9xZ;9IEx<|LwZFrlRgK z^=8`2&7T6J55a|r77Uc59~99DLCRc|d)|Dmm&~le6kK~nSS{3)E-I>^(9@y>IzlvV zUOsV%A2f^&Qhfg+a`puY;$u@n)mT>#2B*v@pb{v|&7Dk>TgdW1jHPs9{nz6?JLPg^;{V&KmMFj2so1(_yDbI%FFd+q;^FvwaMwN(}he{KNzGJOF zCO$Q94!JfnI8{>0qSzvSXSIbHzGbnt`QF&rO8mG9WJALEfxujtPss{|>k(ZlE~S zyC4_w?+{HzXPZIT$yM0GfaK`Z-;-SNKCvO&$;-=%LLy!X;bSAV(#QPJe-h0TlWHDh zxp;nlY%3iQ0YgpHmW-R`g1H#^D7IL%sC=0V{yR`yQB+$S2(1W~@_8+BQcC+bp-fVv zTKK_aiIs)c2({%uM4b46%I}lrdve6Da%@*)td)eZHW9DzcqtCB7gC{Vn_`13PWv&R z9jvP<4J<3K3Dp(R28f#N;4~j^n;dgh{g#@hs7A;AN;X{?cw@A0{&)CL2^)!5M} zEnz)*T1hDachxI+?-8*nAd-(6xDpxD1D6T;4^nb4c!nOae*uzY*AMwA!d|F9)Z4j#ABWhXI zw9J5LW0!MzO;ND4zPL0P!T=gD`*zF@A@&t`)vdNW$ZX8rm~JDBmqOdfpyJPv80W5$gmlf5PF<*(96pli`O@^vDEpL2H3SgyYZG4g6#bzY7A}dO1 zSCKYLN=(WBZ%P+qPv#W%zcrG$$eoMP<-jpyaIz#?RT+*F4PDs0I$$I?V4M_-F+NV3 zTTZ)kEK73{LCy06`fZX z3f6^8{yfBbFd57e*nuLN8JKOJ6+1x)&K%895Jh|crF1xU>HkP+!#jycsl zxTgeyB|MhEdW%`8cX_eP6$n%=!Wo_r+=pcU|E>imBh+1j$zGhcqZwcpeGXKjZj))w zl?zd=fmT`!(+s8>TNQY)6>|LcFfA#Qg=lJ5R92K%EoGMD3~+Oy*{C^=$FPs9c$43O z=gl}boGti|7)~WM)*%GR&aV9%$>0gZXh0{ZNc$A~qBA8LIf>#xQLsEfyFC(WW~g4g z7`r-wCDj-rGRfP!Ov|9t1$;Ms-khoYg>?GE?Szi6U=>=vq>3zNGV2E18L)Nyq^j!W z=u;SXimPj>1eZHzcfBrDUV#GwGy}_=Ilr1DA+?wrT`}7+2W z3^b1NhFe@+9b!4;&ukhKs+OS=k|h>msbITBic2fxG}IwNbmjvyqN>uOn)u&}s+QDM#C{x90of0A zMrLJFVM+@0IOQWNR|OZBmX<8S(MTCDDk%w6i^D%MP9=~RK)ep~Nc9WCLDG;YK9|y~pixwZHlE43JjFv=ZRZ&vKr4)nZ#}l1+NJ1P$lDHZmHaOu^Bv*pWW=Tag zc5dQ+5}_6)6WO375A{>DKIRepOyVMp+bFBLn3hV2jJsn#)YKHM2vn8g=ps8c5aWD^ zar}0oFM~>wYoG`te-geYz!q5XKG61EZJ-nmu&p=K*odytD+%+nY%?#}r; zn<~gm#rj{K$YBB%tj2aJn`_a~7=PAeodSus_Wcj$5^P!t8;gy{L-(Q}p;A|6(Ngqu z7EUB}#tko?n_$6!38w3SStnM>R7J50q@`T>;y@M7F&2>>d*=so`RsIN@Vxm>G1E7X z)x@8xU`|CI*F5Zq$v%s1vV$X-ol?IMd$V3h%Hy8P{4^SM!s< zhK}Xelu{0Jn#9;m8?2;xJlnU(nagh%tb?7><{5J<=gkpE{Vm}!3C2D%oe=m>bc7Si zijF7@P9}pB53ozLfpy>^RyC8Qa1h=pZG6onRt$ZKua^Lf)oT0rYVj?Ca?0z?vlO(| zVCf`2Ul$$7sKSg#Gy@JJSIU;mPr{S!2~%_XE9&sO03Vi#r8RnK1%3ly?jt5n;hKUU zFO~TCP6M5YWj^eOuYs}L#41vf#z|)nb)18!D2@GT#6db_K8{S{t0WcyIoOPBWZ@aD zc*jA-r>BY8JPSn4&xfhG0(tE80<+ieUqP@j=Z9yZQhw-S#VqPS$!BfsNgiC@w4#B< z8apjV2seK~B9oI6kvDhR71&Je`nLgMtMr3NYH>Zd4G2~_WkVLhnq`&$W=B@&>c13f zjjQ7SDsOB64o+Lj*kOP1!x>FbGz_w-FZ=nGa3zR)vyO(}Gn%2p3ANP|Toa~Ep5WAI zH3fM4O$H6PN^XX8XJ|ataFYK6!%6t>HC$hBx4vFljo`7{9~u-{B$$rRBMY1EVzb z#f~T8Bnjt7@05-xlJ>{{{r{l>`XMz*+KRtffdpz0lMz!a{T3hLo|o=eVFz~@tx8?c*D*3%NnD!(*(a8 z89hRqCg_J5eYiG5(4))C@r&`pv^+s`{zDmmCeKk+-Vp6Ve5cF&_dy^eyMk}5` z5EJhge=ne4!Go{!^aBcB*u!z{8~#IflTWL_Qxx1O%1u*nUHqLLhk|$C%zr1Jq2T=j zcPe^s2a! z$58P8JGq_*6nveKM-%_9jb(>Io)iUl3VG}bZpxFU;Qc}#hk~~Yd7KK~A>?r@c!Q9~ zqu?GPkFMaRJbne&e$Vw#px{9vPnm-E2zi1E9u)G_E4W|C)1cs{Jk1Jj7xJ_!xKqf} zrr`ZTo^=XdDCB8ZaUstJ1vlmCP;iHkr%S>6|HSpyqu?ni{0}$vD!5n~$kVUj zraS`*?iBK9`(piMyO77O;0_^Anu2?TJPrkK5b|UwxG9fQ!97AAw}JfskJY@>*7xDxZ+$rQ~P;kGHr&+-rLY`IyZxiyYQE*e9HU%#f@~l(v z{yVt+Y*6qrAy0>b+l4$`3f?Z{=~i%4o*o4c3VC`Jyj{rCuiyG}DlX)yS8<`w1_f^u@-!=We;cpw8U^nX^0X;aAe7w*VyiLgCS8#`rr$E6?c?wlr$Wx}^{kL;H z*DH92kf%YxTZKH$3hos0v?{nM&l&~q7xJ_zc)O6NUBNv`=iAggpHU9u)EnD7at9WB!YL=6uqWCk1Ocx=h?ICX>Z*^o)iUl2zl%Z-X`QpQ*curhk_Rhc`_8d ze;v0Uw}Kl&9*=_Cg*>`~w+ngv3U10%px{9vPoaXh3weSHt{ukvXT6FGc^VYFL&(#t z;HEsS3f>^(S)<@VA0PY3V8|?yhF%SsNkB250ojmDNj(rJA^#-3LX^lG%I+$kf&9_+l4%96x=T4 zX;W}ho^=Y|E#zreaHo)`L%~~xJY5RjCgkZ>aEFkmN5M^bdR1J=V<>q4-Q0c#6nveK zM>{0e4qJshDGKfs^4JyJlqXHW`-MCX1#cJfI2F7@$m3S<1|g3}!97AAUBOLx{0gq! z#`RF3;6WiznS%ESd4dWa6!O$7xL?TApx~xF%?fT8^0X?rQ^?b%;Qd0LbqZc68f+kFMZuA&+0dokE@h1#cDd6e_qW zPnm-Ig*-t8cM5qL6x=W5X;yHDkf&9_+k`x86x@`jO~DI=JnIy^-`p<{@k_HE+ZOZn zYMFw2mT?^STm&w2U*1@9HOU96`~`5Tt<^cf27 zsNlFq!8-(Apx}j-Jbh5XwJMG`D|nm0+Z5bW&C_pC@Lqv;D|kbYr#BSbVg3PXbG|IL zt2zXprr?D&oR3q%wOWqr3f?C0LIwAPc=~z;?-h8ff;ZIh^y?Jdv5ey#3f>{`9tAI4 z&eQiRxK_{c6ybNxc5f57L%}^OczU;j_X^yv;0;&s^koX}xRT=y3f>{`H40vM6;I!; z;Mz)#cPV(AzY?Epo<2jt9St1!D0qj!3lzL?6;JP0{(S+H zZWsQ9Mxmo{(_SrI=HJ^_ar58*QgQR&Yfy3X-`i604N|$Syh!%n4hhGfjJM?JNr3k! zz|DU*jmnkznE#%jikttgii(^2z$$L;$EvuwFRJ3^{-lbV`-CcP?$@cfxo@W8=Kht6 zrwIR};*JEkI|1%bfR`n}8xr7a65#C#@U8@SZvuQE0d5!mN7X|{0^E!js_6?7qz@** zn-kz>JW1uhAwl}?1h|m^*My%@`KKkooe6L~0bZB@uTOxtCcxJvz&jG)Jqhss1h_em zR`p=cXI0#sSE{%! z_@{cTtI)>Rp*Yl|$+%rg|5J%inuK3uanUrVgfEbAe*(N-j7P*;PT!CKUy}fDOMttj zayLoxG$g=15?(B&Z%%-BC%~POK4m_-ls+i&Z%u&rB*526{AE4`Qu-St{)G~5{u?~> zd0hg$KLMU5l`HcJO6gye%B`31rzCuhgg+tSZ4$m!!Z%3x%M#up;ipOV*(Kq7rS!cL z{p^h)x}xLZnZ{+n&Y&LiPlB>sL0zgoiWVjV|C%6Ng4{wpbcp@f_N77l$b zlkkv~K1KX{#Kd35gHrk^zM1pY1_{4U!q-T+A@N@);m=BVyM!Mq>9a$^@0ZedOZajL z@0IW*iH{-SUZgkW@0ajzB|e&@=U+;AtK<)5+##jkBc%^Y>1Et4rN2T-?~(8(2``ZF z%OpIQ0B=r!wl5Iu3Gj6Z@Qws{PXfF@ z0iGhw4`n?#65#FxxIY12mH=-^fUik_whE%W(-Pp$1h}36FHC@UNcaPif9Owur%8TZPVbk-QyK4) z_>7hOYPWk4U&*!atGl0tvrV!Zk?`GF~X9-!7#ulkgWLJSgGcNqDz35BZ~n_eglP zgc}lmuY~tYc%y_5NH~5#VO=Rwy#_245>s9vSkBBT;de{?-4f1A;vYQ{F8(P@_Cc5M4<$Z+3Ev^%1rmOV zgcnNq=Mr8f;rPLkbp<8-OAFPsdI=vU;SCc04+(FUaMG!HwMzJNCWz-63IDT%w@J7e zL#NN{Bpg3LvaWUsFS1Zg+aTfZNqC2ZA12{l5m3GbJ1a}7bC2P8aIO0T63+AaPGTkA@Z@aHWQep14Zknl7K|5(Bu623^nGbH@C z67H1nT@vn=@X-?Pk?=7Ru1oll67HAqpGtUvgqKQqp@gSNc$tJBE#W~4$3LlSUG);a z(n2+@LBfxf@MZ}=PQqIy{CEjpBjNZbX05AD!XLI!*uR83B)nb1*GTvV2_Gxr9TI+` zgm+2!I0^5T@N^09k?@lwyjQ|EOSmE7Ka=o&2|roF2P8a0!nL0a+W&Y7Pmyr^6TjAF zm+&!?KTnhJJFL{2=8*7HB|JmIPm^$`gg+zUZV5kK!aWi`LBe$je?!9k5m_`(l)gd2PnPuAEaAV9(ziBm+)Unc!7lXOL(D#=SX;&gwK@lpoG6K;q?-pE8z_iK3l?@CEO;pW2=PgQu;L# z{*HvVN%-$2e4T`Eknna1pCjQLBs@>TJ0yIrgm+2!c@o|&;UlGb^+@gaEQ3F3};71MosDU3f@S_HP)WDA#`2S1;du+#ltv7y>qDO{q3k=cp z)g7TB`@8kV%_*B$P4-WDAMoz|Cw+j2?F5a|m(iEq(e3;9?{8%^t$TJyU$p2UjNWL` zw6xzHU2oCJjK0I7hcfyGi>AQ*?&vCurbW^2=;ano0rcI`B8#TL`R?fX7EJ;0-O+4| zKAh1mi>5&M?&w&HrU3ZvXsSh1;Cpv8$)atH{_H!mz7)_#{VkdT*{HuoQviE+bfZO6 zfEx9;XbK$fj^1I>6foW$y}_a>P>lLpGzExJe~V6Ibdg0L#pv@bngYS7zeQ63cz4ug z(G=iC{VkdTyQsfKQ$QE>w`dCF?v8%8&#b?L(c3M0ETdnv=o1;e(W1vOdc8%bGx`pT zra&v|Z_yM;Mg1+B0;s6JMN{Au?QhW(Fh%=YGzCgge~YGoC+cs}6zD|#Et&$EsJ}&1 z02B4MXbMoG{@S5Q+A;XbKRb{VjSjqwlcjDU80sqA5U#`dc&w z`cQw1rT`!6Z_yN}L;Wq90(7XqMN?o7^|xpWu%Z4IO@TGk-=Zm?hWcAH1yra%(vZ_yM$Lj5h80!OI-*Jk}G0EG6pXbSM4|6BAtMsKue z3eceaEqXqq@380vjK0C5FJSa4i>81L>Tl5$s6qWL`XWZ3Z_yVsI@_WzVYJJlFJ<&t zi(bg+RExfh(Mc8^VDx8Sne{JZ^mdCbV)Tm^y@=5pExMS|>n*y3(RWyMDWh+&=*5g) zWzkC*eYr)`0EGHmbUCBXx9FcUI@_X`GTLR)6^tHh(Upu&wdg8FCs}kgqdyxk>mOwF zc8k88(Jxwb4Wl<&bSV0Y57dwF>DD+5$9;(p$<}2;5&^r}+heE%j(61`=^9sF1p`TLdM-=*g zg}=!FWsK%w&#I#;2mEA$kFK3$Th5my=-=xqj3cXsPS1NR! zNqZw#r8~V@`$MC=k(ucpy(O4rbYbF7xZRue9pRyLhu*j~$!G_zhj$qpu&`y{^{jpJ z_f~xO;rkl#y^ONf>*K%ESMLuEHE8`o+57|-TJXgQN}C}{JC|{LGQ9zlAaCU1^j18r z%*Q3jJXB;JiOjz6$HoH8ok;Y3Sd$X{DxO5|q$kPb%i0whr9%aUOa)socPHHG%i7Cv zuA2LSQ~n+F9r^EP`JYVhC7~c(za?DVGClHSdY8a^EF6j`GnpGz?Cr_)W_&h^zT`YF z5r~V|Ou1Ze{rRtHUbo{AxjY)cpVCFVfA%EX`<1heyjg-b=rrC>` zc;Dm1g^u#*s4C-OCxROMb$q9<-4Mf<^)dh2OCrM+)RzJI?_ z2qTK-eubQOgI(Y4#(Q4?y%_p6UZpob-dOxEyh#tgYS8+)?^+3PFe4-(qRS8qGukNA z;l#9mfY03Z@D}51YCwp*h^5|ToWVsmYLGhDwcmIX-=p7t4JisK|68cFD8qP~Wqq&j zWm1A&Z<&dX3S}}ocCfZ1eGu~$1$cK8mo!vIp2cm;l%VhiRsT}rr`Hp-E2MF z$2tj>P-vA<$V#{sC6LA&MF~$pbGfcBjd4`MV^qRDq|0<_QgkmT%e0vEd5>9*0s0nx zuWu7s7a1jWMrNT7({83vJ@B=S8jVDvPH1OE?jj}SQW@>w6FqZ3ikwR1daS=>j!&~b zVRHNcnfvY|sGS)C485D6ySY?bj78wq*OpMTck;rG2=qs`x@iy9`$OYY65?_kIWyJ+ zF;0UJWhhX}~XJ9cC*`Spvhl6Jq0XY)SlLb$vm7j}jf1*?)dA7U}$aVt(BcyEoc&947 z!bO3ZpN^hKo$F?N@rCyrzhck5#*u>OTw?JU!02{xr2fT49tM&7HW?G?^IxD#Q%RJc zO4v&MB6tY;5=Inz=q~C84MdW^-v;J=H;@cY>S`_~!(QW0&>ZRX&3-V=r84iwfi{vZ zg)+QtY@`ook%>YMXcDZhrY}#MrSty!Uf+`k@SY`jUrj8cU=h7MmGeFgRRHf&`p`?( zVDUaNhWEo%E^2ll?|*><$$cWRXd&LYI8aG)dv-D2hth|p7~WeU&!F4|33>lY@ZJhe zhKqRr4u^?}cL)UJzMnp1#PI%k4DWC08_8{4OG)>kQluTbal{AkgJ5*3D597?zkt-y z4*VSlQ>9Od?7c<~egC_a{gwB4_D@hbs(m_r{xxO413woxvtMmxPp0qJSlJhBr|f%; z`$hI0pW?HhvODmrBs2RtR`xCQ-D71xvX_@$C9>a5pHnG&{&9oZH8VTam_`~ta`7P| z2lZz4XDoIZ#b80>%0Ey@^dHBg|C~=upMy3{aoVYT=#mYGD!)D8L;T)CMQKDlLh!qi z_}z+u#z-Q5S4sQ|zmMOYf?q`N+q9F*cPjB)ildCidLYJW5Pz0~5SH&f<4j6*H@?6-U4~yK8mADjR>~F@*_d~F4wWYR zNTyWPJlixJ;5PPr0-#FDHc!rWlgRcwrE>FZ_6%ful7MMawqxXMmx*jQQ>rAMElSx| z6QD`iKEylKjR|?O$QGbf&*BT}_RM%>n@hkpXwFp0{e#&se?y%}H3ptkM+Z_<({FeI zQ-nsOj9!F4Z_W2V2B*F@!%kI+R8ZG@Cv>(RSqcB2Yp2m~q#nTw zdGIHx(8ev!zPF6+|3bN!!pux%d%zibjsBb_x8#5H$bIQf)XEpRi`CMXwIg(*H*!|G z7xFR2Y?aA5F9K(8<7Q{y8}XH5Yx)F>H)hY#_vx*O%72^bNeoRzVtBls8kXs3CEmzy zeZgAkJ>zuBvj(C?{gVbA&-J{o^z{yE{H*lQQ!zT)1WtW_860jNBKp_dQ=v8(8pTAL zyQ>>n!MlvBP#~F2h&}fj6+)1^q7cMJg8X?Z%;hE`?V`^ z?psIl!LjmDdK}4fli3uH5G!<-TlC18zO4PW)$}(($ktCoL86WOY)$k_7qqiOkJLFW z(|d!NLA=I)n!Yq{arZrAmXjw$PGgK7=C*8#+{zdU8%BLtz08lb;v=g7891Nvu>~_3 zT0Z+u7JtvjBr;k2L@1Fu?h*sqdI|OteJBgcDBEmF5u{^WL!;5-3eAve`C3K8Bc#i$SkuJf zQEwSDY86{l?#08n7@3SQkPxeb=zI^5HOOEbF(|(`{EG28m5(aiYg~b^w2*ioNHiVk zc`dgXFR~=Nj4Y}xETe&$LK6>&m}}@(211{Q2$>HTGJgQ24az)*WCm|Z=8GGc%sC|U z-8&#*5y~T(+p>XtNVN!{jfBogW{)NFR(vIyCy>lRq&H&mm!Vuz@Kj0II-?BSAFGWK_Wo;_uv;Os@zsYA?O}*U!Y;`HGL3|N z5DJil{VmxSDR{6;_o9?&5YCIBAai%m6I4U~Y!5`CDqVtn(Nu6Xt8^}7w99x9Pvdz~ zl#Y_9GU!$z)X=o}Ra6PUDaI0L8)X}}Q|iNr;h32w!%fCllpT`68x6hbj3L@$TXlLm zw9v_$mJa7^ZA!lpk0iaZ!;W`av7&cl&Q4FHTZboIw$!`Q*WhWag$77qZ+J85a~Ra` z3-2IlGI%hK{1a~gbK1of@EjABE%z~nKX5U0AHI`&#~KWt{XY_Vrq>P5WBKKQqIzN0QccrR+Dw>0qp8_eZ=n#=u~_d{bgEP&eT0npLv z*)#+H*m#g^2^Dtp3V%T4>YcVGI<`bQsiDN9si}LQtiIoqceT9H7J_ag4Q4O!hW9-k zMDf}47vQ9q-4{9O&sjq>8qz%8mig)S#k#HP8TwDxVq3*V+xX;k zT7x$jHUyde1j!Q~dMVYjCD@IR3-L-9UN07}okI)QTf;d37Yu%%XTIVbAjNiGLsh80 ze}#anJ8Vt$)R2*(w@hVq?zzIMbIbcM%8T(;)%SF8Bo00pCZwxl(tWxR3V-m-AzHMK zOzH%29)Q#`N~AxQr_UWse=ViYHPh=Y)58Fu1;X{LfzTKT_7Mq&hB&2VhSSjApj9T&LSZv$Xk!?#&PRD;}R*Joe3u*5Ij~CWCHV4EXI#EuZKc>Erm(cy)Pvh!W&7} zRI*ueGM&be+c_Fp>hOj~vCMCggGS~vrOYS9&HP5Mnc3qF&rM;u9}&6ty*pU+cG%{D zMc-=WE<|pq6E5}~k^5;W_nmQbFEn%C+W7IV$M1xP*EjAT<_%w+QRnb> z&T`-r^tU<97w#v8W-rXXEIY7CwAaRulZ|swhBrJ5I@nAKdimUznWsYuGt*O|5#+U< z;9((^3?^1R^ojTz6KfMCALR>w&75|pv6Yk-sdVJ6-WjT-k>-ncNDn;A8$#K<3Ct|N zMHXm>#(_=rpKWMq57sw!8WfnR_3LL=q^H=Lvi39P8kpNwS8&4NdJAOTjjgV2eNU2{ zu5HneF)wY^(WI_zqET0$3P{v9veZL3Z?DyUd|>v3e00tgi3a_3_Jw5gzLsk|u8!;r zd@aiz*$aFv50I)^_t95%(qQZhM;CZo?o01M>zSswb#|-Pc|FaMkU-lyyB*$dHa0KN z5S`c4{GKjfczFY0;)nNZ+VH-P-fgL~J8*a7?gd7JE86el0e$>et2R22d1LgDJ^H=g z77XvqVxnHmWvF<%=)IqNT$T$u#6*YEjsJ?hZ@@d}!^kd>oMB{Gb~rgbGAlV7O`jZ@ zl|oOP&?f8L2K_UK^G`kOgR409Z8Td1Z`l0twqXA6dI>?MFUc$;bFi<3^q*0gVUhlm zx1{uu`RQ)TWkPZduSsQiR>@K}!Mv6CUi>>LmBxg%D=34_pY}c)3QorEp z&|myi-}q6o@ZXDV_7OwC^_R)iTx?2`wY4s)hr9H~-tQW>CxvV%Ir$k@@@7gyf|Tiz z-_pF2%R`MoXpocbf~@BxH4DBrHdyI91j4vkZAEFw?0Bwjq|s5w%k@a44JcK!RIR3- zW!Rd2NnfpM(os7-JXlTCZ#32K#$>Xie^)=AhCE8IqWpAK)x85?cGMJ=Ae`57J z3tvF^v)HP2bx?ZL##EXp7;b)Jozd5Jz;~f|{yq8!u%$lLM-QMi*w=7%)Vib;Y8%8lh;;CGH@yp+_RzbqX`SAMO*6aq@bt{? z^-C6Vs*ro_O?;ZUCHg3wW=w^7eW{MZ1EJdv)2T`+;n^uL=Ekejw7MB+42r{TZz(=+hjOVfo^I{hf)5^EfeTx~bbdlxgzha>?Ovzaq^jY4&1 zL7fA(RP=|`*>-vU0g<@hROR}KDGe*7fmE(jIUhr%(kH3F!I`@0aZB__@<|z#lbjZ| zqMv<@+&St?8uswoacySMx;3RlKb2>wJDd-Wy;Mmf|4kYZxISrep@;Vks&u#>9u}FM z5}w6WdJR;%e2>kZ>qa?w1$sCKgO+`Pjv%0Ok1aI^Qzm-C*wY+O-uO?Dl3F0Q9t_fb;o_j)nNx-w=o_gyg>@$}{j+g<)1Zy(k!$QmC!BEf zN(?fKTWO9{57EH`YobmXmpdsV<~kUgc_)pY+(UIEX?XoE^oIB9m_$i4sm4#rVl-Lc z!T?x-^BgpvdX;=QmT!5H#ZLXPtY3ZLrvLA;RnNy+nDA`7H!{l&MgP<{zSk={5}V)J z9@vP_4hU6uGBGHybZ=YzR|o?^%M?GNx18nCX>M{SIvO&kArefL>Y&B7-L;doa$l-7 zUV9^fG$vNd%t{QVm;v=-61oYgcY^(vq`a2&&A#wQ#>20W+o+~MBu#m}Er>kWQV(I( zq6Rb`;t71|b~F!~ip~avb27YH)sE%AkDd)>8&0T^dLo;An)ZPSW#cFA7~N%{-=SHu z!IAjbQEqZNrbixMq*SNESi!kY*Z?Rp3pbkIiFXG~fNWW-JAra$So*4?-stAKLf7)3 zs@OkOxJoJIiH;`Ko=fWV^Z2n2TC1;{O9>eg!Wwz^Hh0eT<-;S^~ z{e#|Ga>b}_fMRph9zFal)?GvNmdVR#c-NEOW%ECqUANop9tTD~r{4IC(`NT~+fvW% zwWZF(b4I_O)nE6PkB-Ikew+Q}mP2e!9+*O2_*3urt=`7(l0t61Wi%}Ied2tCp7g8_ z{x@2w7`VmmWC+Yj`-7 zoD{eaPfGL+B!NHjCcVwqL6JlB#!Vyi#*HKNaQ5ev@LMFz{??oIcHR5YdyyKOJT&n% z!sxD+{tmELtotLw$(tpIXC=q@G~4Rip)K-jP8h473>5}jKpriP(8;h@B90{jhSiHc zK7;@V0cX)$I=y-5ErZ@>(%WhDMrQAUal26hib&0I*43d9ILT6Sdpf~jFPI{+|9kx( zOd*;-=>Nz+g>z6wBL4@w75J6a(DIh`81MLZ^TJ%C+P0=|SoiRtd-w3} z{TjqTZ$tNfj^3>99R-!Bd!q}?#G2{{_wTDwI9kIyzSG;d|KR&Ke$^`a_v^N%Ggt+_ zw}1Z>Nm&2pen?N;zu!gwj)+CB$egdhIuUfGIo9V3@)P#%-;wGf3*C8OfSdcWqx+UO200_VWbt}kx@oW&(9mTtuh|7dh+af?YS}N%Ki0rth@r>q z;FtKq|3V~3#5AJ%KL`6O<_?D#OGE~Y;AGpjrsd%2O?tO)d@I>?1mkSuCb;`8Y2n;{ z+oL(3H|KsH$r%Xe4*0V6*qXdZZJPBz$*eDgTzy-ZJ<0w60jO1ETeiT^c-_($kP4GAultg?g5bpd`DDSDvE)36D{2=%#+6#;9su;Ao^t@YOM>U^byg z$`E?nX=_Rrtilqj%DAjfK7bXta8^2F)p0nN>THSCiE&xI{k$p_n=6r2WsKETg4LdX z3|8=UG|+(+yx{;=4k6XLW>O^8af;x!R^k?p%Pq&`b}6aoVXm{s$6xyEXTHd|^w*Kb zb*ydXW`t*9qSd2EZfz$Z(y)Qy$?4>4gj=OKX1yMs$oEUZz47mD z6OF^azE+Q{>EhhF<8f=^$C|_0e#Y+Z&{m|>LHj76cd|BX+Gtxng!q|BR&6G0HMk{l~=H1QhVfcVss+`#W+aU%9qrpA+oa5YwL8&u=@%tGkk2Na3mrK!k6VO!)9 zB1<#S@Q7id8D6Dcjb=Dq%AYFoQ!C2(x1p)vM0BkB*phlqp)ayD*h~wENKTn;Jm$+} zQ9&&0eCZi9$~P?rd-7~AbPbC4AZt%H7L#ynSnD(@$POa+Qs9T>#K9((^F}FWy|4sf zA0lTaa>70+w)#B%=PNyOFEjQ?glTTWG0!f|c;JpFuS3A~pE|sA3d%sR@Oj&KADVCD zKAK_}OdB*-=`B}PLM6XUZ=h7PLQ7)BvNoddv8|~egOncODRBDK7k-!}?mLY6cUJ10 zmiariIee|QAG?7Iz^XUdOF{mY$uH)$OinhA#vT_|OgA!HgH;>};x@L^2;wqYOx?wH zQ9&(s__B7^-Q`1fC#j;<5J1c;5Z4_7^KEtQj6MbFt@$uj)Q_}U)Jt$H(S?luiloO3 zl3CMPvso37hiORN0?rcE)ajHxvN)Dg zDg{xhHe@$nS0=z)k&wU(4D{P}d&`< z1Gxv5?RJr^Q_6NP%VtdmL}xBVHtNha`<<;&GWF+ILEPIWh|l07NM7{i*KFhGrx)7B zm!$h`<0}xfA%}C4C~2WoQg&PczadRT?(GIMmh&xmQmWcGDd+IGGHygp$Y^`Cv0q5_ z4$1i(GqId0Lun7LrWWG#U3?gjp zXlwFO=N^yczLA2Zhr@PVDeCWS+?Qr+x`f6QY<*yDG@yqu0ewMl-2NSH7bJbAZ`_WM z!dHu1(J1FqH1HHNpn&%o{kGIHL=$vG6+DP2bk*SqALE1Q1=~chHN8T=X5kTmL-dyU zLpA-7+ek5b_P@@qR!T0TKO?#Pt&c(LIX0fe7d#rlPY!L-% zARWKBi^5W0BUFLC4QS6^GL*V`dNL3Cch}*75&d!v`_m-UM@hD(+rby*&)mYgdGhAy zued9n33hxqcsRWWO~HKSZr1$pYUZTd2U*!La2G$62QN*DagvEf272{|-_a3HO6!Bh zM7+lvd4&AsoR$$E&S@E4f-OgH%LpF{jlDq{Bwp~fgvMyb=h#%lP;j3)N=yL3e@=!v zEu&H5NpqCA8l%Jqb$8P#9I|Q}EvWG5eef;VKa9?SYYf=Hi~;Oj)oqX7^%d4A+oIon!5$}m&K`^T<1hU28Gk&n2Qi_# zO~P(y{emrgTNCwb7RW@D`x`n9f)!Ybu@dR9Wp6h^{3Xp;%3mDDBL0$LT*O}r3_pKC z6ns|)f;a_KS2KW#5D)fF5Zt7)w$q0Q0zlOBIzhlCi1G2fmeWeS8+Q!#Chdd0;gc7~ zYKwE&US4>-cNu9Q)tuQg;vv;Wwq@yq~IM6YJ9v@Bz)bm39R1gz8a-|yuv-*)0Qa8Ic z2ZNw77b(rC7SyKW-NSNGturS8nF zCs2<()l84h)eS`AGH$?UUu1O~-T~8By71b{-{Ai{=rG6Xbp+%6boAyqk{&}f#{KV* ztSkjh;siUGXw7S+$q7t?)op?ycoQ$Wm|~zYuFqF&*M0!kVtm&@67z5%p1cJb&CnLb z38)m>y}h;;`tQ57l^PEXXS?L!Xb;!`+B!b7V3h4hpg&!sgaE=q50oza!*|y+!_xpsO9BR>lfpSL`$LciqR!&_-1 z`C1%w#UA<>wrgpM#^weTQ9?tyc~x3!l36B<9|I}2>;8mPgOR!$L18X~A&7$TgZt~W zy>3e#!A@%G*je92qqT^&hp2+d*XlS&0>{6al#bAG@+xoEzGY+aX=WykT@-?z=}JbG zmW^N_1<+@@QrP_N7A~Pq5|-(Tgfwx`tytnuh>DdE;~Z^|+fqjl%Ex{p+xx8tdjW~$ z!_T}Aln+L#$OpSdSXEk$li$Z2;4hdV*qUyIDN~aK+23ii#v@2bCn(DF@mq~<^pR|w=51)qt?ojrziS&uz?t(SaF-6ThD2Y%fX0Rz?9z{g?OXEm_}ODY6#aM^E8mQ* ze~Y7X7xqR>IF9M+GoMluZ-kQ=I zkkR-lB#G_cUp&S8w*%uv8iwsT9{eX?^g-Gt&heuYmtn?(o{lthm~MVL%<@JywFTu% z7e!%)kW)zM&hlbOMdk6`>-tcw9)1zMH>i)_sAoODd~|Jwo@7wp#agS0@##A<4?!Br zLkHc)zd$Fpj{Y09{Lau=I#@y7waoVDh#^!mrE4Am??Tg%Ep;E#CPJ)5Vtowu*nt!5 z-!a?t)~BWU1oy9)ZaSzfeJ#~a;bX&J&{kr~pnoNYiQ9wQ@52rmLQQt;mvxH67jzPX zpTK}~&4bxCJ;GKWdyTcIgn8n~7ygVLI$8xUORkE!AE!Pz^^eqH7E6AVc`rnx;aF_f z&jTylwaGMzha1Gtck(bf*%q3D7}&BrEHRzrn?4?5t=lIjd0R$9kD26DlCT=+fO|=u zkwS;>x98z!K=9ybLj5swlZJjILf(scO$wf%l~C?8@GG`!DQ<(l=z0r<*JVfX^K?WA z(C=zTdRvm)ar6a_IXpWWd zts(zKCqs3%9SWJxja-%CAi-JtG3l?LflP4>&7A+k|9wGq(8u?qI?v=`ylL7DKjaJV zVfw->%Rxs_ar(8^iQ}}!oDC$)Z!bc*8&UEd>?KZD1m5&uHpak%wuWA&?14Xv&IV-mn>MIV+Q8xGXR0^9PHC2U9u~(ug^WINn75SIl7C=!}J|v(fokI??2Q zn41mii;ZjE*+#?VMRIY}fZMQbc67|o-x=h~wZbZjE!9u`zD@m*v7_r2==w7R#|g$dU`9EBSeMMG3BN|l z#5WT*+l4KR=I_|}h3y2Hcsevz^!&O%`*%h!;f$@F>7#78$|z?x^UMb3nK0>OmsGu6 zqw!v)OdI`Oa_K89eOs7*hg^D3>EkZ_OLUHOpTLKXfIl%z|MZfObVWs^Z+7W_Z|O0h z;e^m4RiCe#fy_`<66<^%?VaS#^vN|zbW_VWVd96{#H(L9=iEz>3fQ??zipzlFHygt z6_p9Z!`OjOW~SDOCo-Af5I@|5k&|PV5Ssuyh6%Ds@ZPN?s2^bYuvLctp?*hL@lsDC#>Gpt z2FB5hu4}d>Lo#YCNkY#}QjeRECdVu=0aw7Z_!-IzO^Yl1@2Dck^+Hi-;VTfL>(kWu#R=EQFAggX)QvZ z!M)VMtpYBY8*7xl8Mt)@_q-5pli))1Aw~@D$g7w>2T2MYb`=was)o$PuKyKx1f;`w zX22_QZr*0$M})5Vt3-i?Tq?I8Z=f6m-R~@8k9LyN9$0EUs+AwAvJ4;8FKb&r>27dATezS_C+iZzk=anM0|Gw{!;_|?(hu2#1QJFJgDC> zs2lx62z3%r>Ft^25!AY1E+8EJ8r%cV6x@yQwH!UBrc;wVj2rnm5>CAyTm=9(|H~dG zzsE(^^dLK$NvTZ(-JHd^(_UtL(RRXs)hGCxHO#`BUAVPAc+aJ0$i_NbajRP^g~{NE zck}9J6VQR$JPHQTB6d6f59ME&^QYyXk@L@!f1Lab+Tdc7Nje3bZg@RdmglEG;|%y% z*B?n84fLH+s$%a?bYmEzHTLHDx}0sLT0@D5u+& zQ7ftKce_E3m$_TLa;_|B%}I_oiL(_@G4~v!&|~|bkUu5xr9aFZjKV+o}K5O8@U16 zt<1z<8-?NS4c)5Q65K`$gP(S^u)|Fu#Y+@-H)>a)@gQ36UcFjU97Gq01v(p)LrNMh&YEss z1hIIlvf{^!b~~Zgk-C@gjdf=BCCgorfef;c6T3~RlSm)K#H8)p`sJ~O z+mSNXQK=#_V;|suLu2OrzLLiJzr{Ma)Q;{&8lNWEx7oavwu76A`qx?;om?SFD1)Hq zO(6XU`#!rIsT zgAK^MW|jdh(J}x&N9GAG21uwS!vz9NkC^u$($SX=FIY^ZXNh&D_g0P2wai~>>{+?* zCk=b8u`XGTB~v#WR<%~B0jEz$8emMW0V~pk*-;Lf>jt+5&fMIPb&5}|V=}Fn9Z8(k zra@xNoF+f@cYs5z>MD&D0cEyQ#BaAvq)%YI za4C|z8$uYLIN|+c#EaGhO{A|eFUl4G{h+l(`tmB}8&Z@TSr=4UQ3!&!+t9S4)+tcO zYSSmwQ5Mp?Ya?M!p#LKYa-(SRXrqX-;>wpBLBHD5ifU3(VjNaf<6c%&oT8d2%2O5% z0E%j|ArvRU`wby4^X=+58EhyqVF)n9&5@qVn{6Lr|J|+F78T1q0j}83yJDLuwuNG6 zt5`vy*cL1H;ILQ+Z?Q!Rn}VR9&6L9El_FS-mKIkx5!IOfc{~0@`o}g{pouC}#Ao_iWr8f3$3>v@75P~s$F+nSc!IR zlPmJqw65m@wYxAMlK$byQSnx1peY*ZFt*qe%yHoO+wO7{4buDe zAuz?MEW%S?v_V>-TpUF)vihCHJIf9YQj3HP%1NXjR7^otR?xf}ou|TEBQJ%v#5$jK zg|agHw#ghehAuat9HU|WDa-Oud{kq=+i+@=r{B=v&rD*a`qUe&Nkoq#L0KQD$gW+sa5{F?X*+%pG&mW z{}EUJ7G!XXOMP*!%5PVEs>6cRidA7NR4?Jq;%SB8=w}?@Zks>I-K|uV%QXG-y>Mo} z+d~?ad#z&BS$;K+RENvqqEl%j5c2mZRjR`>sq}T0IFt-1-Qp=-(DVx#0(M*?85n}& z@5%H}m*Qvk?Bx?1Z%YZauGhg=C{wIhfkO1l%Bh-y-&TN|e{E$F&Xx%-%zeN4cjHe) z(%CD%Vx4d8qQ>XVzmJdtDDOA_{?34mHveAZV&Ws`-^*M~)kxLdnHH0qf9Fk5jSA=A zFOUWf=;mMajSB0c40sBwMCZ6F9pPe1h;dbVhbmdu<#DfFNTkMh?J%se zo!BQ4%9yUBEt8=({7CU3*-C14T+^smHT-iJZ-a{XCKul>>Qwx1!g$AnxVzWIPm1C* zVSI@K$PZ(@Ddf5pQJV9V220s^spGO3$7+W8pmm^ zxgO$I{eA>5%br-kx`VN7y}-&_YwdKRiOrZ568C!qLegyuqc*l+I~HzQQ7afoAKMXc zD9CBxsWSRWgrg6lrAfHLb`roeSzo}XHQSJ^Ssu-x^3d1RHuRVbxWqiLFhM2KP{G>0 z3BP5j%Icq@mWqEQ=_unrRB9dA(@)&MCebl-;mVqM2xtMmF&tM{KsqT>37W|~6lPZV zCfo|2t)^a|x7?W`XS%7&ZqeHHzRznmS8En3oG{iozD< z!n!StQhRWyCO75cmdFXLUQ0vV>M%}gsdc#Z^~3KbzNi^UwI)m@XywS}`pI1tx`n6; z+_s2a0#QoCwfnUU9H(w)uiMmH{y(oPSnmsYmM0zN39fN@G7&PJz?)n6(i+P4eaRP9eLyCZHc_xAGMu(X}))EBD>7r9S^ zetOBI+KNl)yDt3t`gZ=&*!NG`@pxTNvA-kUnYkxCzx0g%45cN~Cn8^jVcex+e7}ap z33C>FN_VO3DqrdeRJ#uavW#XOhY8F97*ZXu9d;D(<>hVM!^GiE42@qXZIzKTw}D{W z#hJ_d7g4%lOLY=+Ue7nyd6kyHsWpl8PmHr=_n>91?R14~#IB4jtfkJej?ZWXpBZ~H zOs<#g$;?@Oz=G=WBQglc(GMbC7DEWrbQR(#4&6*h^53j52Q0tpCr;( z-9!#=SyrVIb{b1f&t@IXHb31-J-3q>?g(9qEdCMnIG?;VdX&#l-2yo-vx6FoWY7`H zC*w$wtbgnMwq zP2^9?4KJ0*fD(miu|~b2nRF8NT9LkFlGB&m*+ZOv!g>jRtk#n3ajJ_Xv}rgvxnmk< zDmsrvQJ%2f&f9Yfvdbz&*waZr6SYYjgym*q!rY3ig#^+s7@$#BWYRCxQPWVrP^HeL z)5|4Kntq{!9-&xPUAMcHnwA!axnip*77Yr|=Hd(P#NTAj_c<3wymtqA$ zzhvfiTla;nZB||+TiZ>Z!f{<1$};VC)4$sqs?U|!Oo=E`+GeZ77FS}6mAEu4QJ}PH zQ>03q%~!v0-IPe1)i&#<>uh1ynEqKiu?Z*5i#FmYQhuZ`712%ZM9Q)>a?L656r!JI z{dUDVMT)9lHB#<>>}t&ed2;`~A5md>a{uj0f&J9|%xX@N5)btlKOjbmltq-H1&Ka;6oTyBa&zd9anq)SZa*C||Hb|LXK8f~&$!q*wF8@^`iJ@3EzK_9YEN zs|5CUzvH-KoD34kE1kgJB(LKC8pc7Gnc8#9Cs|mYMfwEq4 zkpksPi+^7&Clwe{mULEuVj?iQfaX}|(c)Ga^dwA}C7L)iY%YOsQv#zjr$8xJWNNBY zpqyg~?s2j-L~M}|ognDPaFGHfD zW|mM_r^wXQW*a;EgvA;linU0J6@;)@ieo@_I{hSNp(8q5BQE1qDHP{L#qDmWLzP~r zW@)k#b840yLJY?(+^IE+&*k(QJe<1sl0>LlL<&RI4-69>DwXP6bSk~nd<=c1N_AMMR5jlU(WWYi+z@pHz`tmb)MFYsScOPMW@n|xCCN}71Uvw zRDqK$G3!kWU+m(kfS~CYl1s0m(|4B}vEEk6XOW#e1mYT^>4gPQ;A z)&N9#4I&)Y@?zs_`9@_=a^?P^b)3 zqNp%i#7PI3wod<*E}91~fG7&)!JA3( zLHaL}Y(f9!V!+P`{g;aYKO^*CE~X@_|N4W`DdJkb{)Nk|4 z@hIM!O!3y_&3C#k|b-`z;~Bm9ZNLpa+jd`31r3+G{<@K`V+{R;#Id%ltj58)5K zNcaJN%Z2w-?muE(XDa;1{K>E9Yq72)-XMGqe~QANV(Ai0crF|6sMv_NNlp7aP1ZiK z+lIDLUx_JOP)4MM+n$xBuToV%MpYG_x1Z&ravmRCPWKdI7 zUeC*fXTXobS(zCDq6f$v)hsP)=U+YwL8aL@65(MLS>>!Ey)p%JLdjnUnM4V+@tR1T zFxwe1y6wJT`SaQKXBL~}icAi0&MwRgfonk^;CndWcfb}={`&`npcSp9NFp^e3%Z%G z;Ff=c^~StHX|Uroxci52YYO4c6}!dC>X9y2WkuT>A#2TfkHHDP4zj>U64XtKb>3n! zFp^&gEkr@HF>f|m{mu}c64=TjYscxwK?VeX`h@4S>x(9X1=q@#v~b|F4~{-RlhA=jo}?+|^!ej2#+kICX^ zhj5L(<;ZHku&(8PT?kkS09*y&nyBqVYWpIqY&&eIM5YnNW)Ud2D?RC$Nb98rf(_4z zn_<^bY|}u(a@lCiRcb-@Qfx2>wSZ^oOoNJ+(h*>FfCfyHWwFu*f}4k+_3Zs$$ ziU;ynsi=~$V(Hg~ps*d-As1^5tbU}g3d^et%PUu_`pBGL-ci)I$dDpEmLnr>3RAJ_ z6fbpTb#NO9$(7q&ynxp=2h9`}X$549t2dyGK2k@KzQ}Tdda~~wG7#`$6CZ1L0tbS7 zDGd3<@i}ARL$AVjo@V~Z@gocGev0tR{tEKbrcAZP(BZaPHr*+DSt)m)tWYzak$!hQ z6ri)CUovjtG_H}3SHhAeEX4UN=OH#zj>H^TQ}%%SDONijM}jam9mj zRb+FOyIdu~55rs~*<8^u2_6Zn(Ui>>*boSDc3Cw%2{nyZ)A!tf>J5{F!? z@Zl%JBXaxryJC`kAd`eyaPRYkyw5RlIPV|iJq2&0wq)OiB&FE%z;j7ZHW&t90|h9! z#)5Bn0$;{0sp{Qj6X-;=00h}L(JIXb`#S!$c{>H)UfoVk{}b(GjMAjZ!+usio6$Py~oOX9t7(WPnCDytoKlPkAF0Z-ACT>cy)w=$zqu<;2Swvyu7V~ zTdQaJw?G2f1X#YLjw_rj7QE(QF+m;~!V-N7vEd{!KMU*35SAqX)@=$W_#E4n!*m- zCxklNzx^`TbW4Cvhqlj(;8m%^E>YVvD2<@4n~b);62dGggt>hPv)OMBVOj#zQ^2f? zU~2FNH%S%`VfGlze}+;_UD*1Nu-1m6SBpO`glP$iVAcrcjv-!K1i>g4q&^pdom&X@ z)KHvh^6&VjYrZ8YqE|r*76@#}74rsCpFuzzBLIS6 z*yq<#o42yF{~;j+VMe^%8UO@UDS|MBJ2+Ahcyus$@o_oOc?M%bS5;64$5L2%aI(Tu z4+i6qq7_mR?7xn+EpyuW3L$2m(xQAUw%lS`o0Xlenbs;)Bc?S12ZG6PNK+mbTV9ci zVa~!xsmV1d%thcpa9L5Va?y;`jpS-pE^9TpT!aM<1dHILq=FcWw1woFtz4qaoCI%y z1Hl89%Z;ef4V=i%QBbEuSN5K;sss)MyF68Z70r6ofrWI4l{I1eTttYK*_vEa@W)Y% zxyVQh+$^cm+QZTa90)#bh;g&R=o&WW?{>z9AoPUIU1Hda!Uuw@G@FGb#I&`o5-7G@ zfub1|Yom}}Byb?u^iW}an+&4Uijt9bgwhNdU7Q6D1bQSBwVTZ{qpKvzZgORNSlMm^ zZGi*9S=KiW^Q!5!R#U_^%Bu)7Sf{2GHW1vWdS=F*%>UK4&O_0*g?pCRCgPr@Ygu_| z&SfSF&6cO@8JSmuD~Ko(iK4CJXg66j&RZ(0z4}*L|3sdHp9-#Ik!klZP;R*6?XF)~ z$$c6nL`qsw3!NadNKJ6FXmH0S7pv}ev94R@wFEyNRhEeceX#AjF6WXg+?yO+P5nVh z2)8E-*CEkng5dA}98H44j5GMpFh+Fi>a)&}e?+iT7$d~Hn0zi4OblyVmyNEm>db2j z9wVp3s8C;`3q>+ZS5r&>##W@MISeHsNQ2q|HX?*=2SZ_*ld`p`v)T|<`;N=il+ES2 z@>+sB-j3$>1n*}DwSSDfpObg}A0qGm@*c*Fm8|E;QRhMpGE}woKK?!(54_}oxUU#0DM+&$LEfrRCO46R6 z#5_up43ltLoBeNrFxzVmY7u#mMdt4ru3>s~w%7AliLNYJImwboRCAW>u+74Iq^w(_ z4h@z(5Ow>`VvBTp55f9{-R?nXYHM6yb^90`+4cHX_50;*Mg87ql$zJ?rznN?Rkz&l z^&}a+-}iJeqx5^3iy5Wg2N`%k%k}#iRH?Y%`$^PT|6Z=&4Hr?rH-V3^-+yG#oQlX) z#-a-wsi=(G!$=cxrEFGYC7Gp9J~NCI&k{MT=bNP%^Qgxshp99Km8v&Cm3fqEf~9(2 zx_XoQ4zw5DB)V$O(p9q&%;RC?s6@BSBJ+uEI!%a(ZkC#(I((O8j_8)M9?l~=H899L z7O|cs<6u3z^+(?8<$bs>@?I_PxA96Mn-vVLajx0HPA@oDOK_~FJYrky(L=eKZSrzC zhM99B-9~T?YFPz)!B^HgS5xprn0;=rNg&U2S`E5 zHI!Xwt6XBgm6C8v7+{L-0&*IC` zG3beT?qBD*FUoT_;m+xnr1!DhnX&<)Yfq22^{*><#Z1Rnjm)?29%2LQ~!I5BZa0iu(8QNIg zRI=X@hqV2pYhyB9cF3yI67t1cK{seh{mP29d4>J=`y?h(e_cVV^sxqV|tirSxY_+)gIkL z@fh#91P`8{AC+xyHvX2;w>-=mk$Xte93G9PysRnt(1nmu>h)8D2~;7R z#~nV)CX+wR8~ir}0q_2?@Xq3jK|S3PkughGDIsn_UfmUn>z` z;Zlz;YX@Q62zNehnE&ccc=G7S31E;=Mw=)rzRDbw0w20$^rxgm-uF^{{#U;y)I)0t z?lJ7x6q}ReZ)w}-W51tS(y-`w%!f=&@1Isi7Py3jx*U3DaUX_?1w-L;6V!ehDY2yN zAKXj!c2MzJZT39}l_XNS@S0bQtvoQVc~5=znty{jN8yd>1F8qV`DP5U95_iMlUA;0}btdn;vQTvI@wV&~G?|mO)d^QOJx4X=B-}~b9 z)2YGdgv;#yfl=|Y9iF{>pZ^^H>s#|U5jRb6wcVcHvLCMR+h>opw_GJJ9130#uk(&5 z`x-T9+e@r;MeO%$VTo|0EL(gY#^maoYONkOyasLGxYUZl$Ij{2`?TS;x*f09Xdk4~ z)bH1sAg3*kbiC5K!|3!2VK5fRbGg|8D}1Nm{;i^H>~cE9zu#VR>ufj zyj-;%qxil$fav}8*F`!VM^=}#twx<*lSrRNjV#%O;bUDg^gsS;CDV?=o#acTo*7KD zcHvr-v!m2`KwtNNpmB;_-myHe9vnt3jP9*W28%y01lDzpfFX?3sBt48X}~oZqz$d# zX=FYAPZQlw5te8WmqV(irxi754+FlT70nYcgP)TpyFR;&_MNI+u}%mX++=I5YQ4zl zvNrOC%AXFdQF*Cnt=@jW#cpW3DUrScFsF}F-C_TF2ci{5^lb16vL|U>d47&h6%@+- zePIr+g*^og+{1`KTwLUeJkG_ny(lQywdTq#hEkgkr82lQAIc696v(?K-@qV$KC`I_ zE`A}++R!?g&aL!!0*ZQ>r>;gcR%7z^*@myy7&j~p{y8@uDTjxua__roeCjFZBxf$X z)W0aiW3OIkc-?$T8CB{@?)z)A`~FTA;M~%<^_ECoe=B%neyh_)!$AEm3#k|?tbG(djn0HjY#3J)ouJ-PlrXJQ< zl8dZ>C(hDh|D{-03E0EX+%N+}m-?xfM6hO^SHG2HiS)gyb|TZ&!$%cmP4C=l>{XWJ zGSoX=?RoL$R{Vu7o@MrQQ|)k&ABSRQx)>mXJHSp)q}#IHt%uHo&yqs@(9svSb?4V$ zxWO;@EV2(_#k?i zL82|v!>7Z@QR!iaFmhCS7&=2>^XcIzsuyW8vh?r($@1yJ>3$qNIMt8Q!wm-Q-YT^a zh8}}jBE`=_7ZvG!6cwp`&UaC3AP=ZyeIAvVTeOgHNkoPu>CH=GZY9~*l5CmKwsr9+ zdt_DRRHe;EXs>=nI6yWSL4s>t3}reJoHBw0myjY$fB#~_3=SWa{#Gk$B~e?Vznn}7 zd(N1VGmAw;$@|wwt@Y9_SgoC;a?`d4ggLQvBPMX#-Gh3}U2L0>d#H;Ug>H9sF%jLyI%V7jV}-}}Wwn!Uorb7Ve?FH-b*+`W=*TEM zynov|NF!9}{)vRp+ERtMyBl(}_6Lv%ohc6VT02E&LRVIP+G=_`nF1YCish_&|ANY$RAQ^F&LsWwJQj#gEeYyStcN=hsuwu=9;kh<|K4CENLvH(Tecs!`{w zs$u6pNJ6$JO>oR~T&p%{iiaM|Em${Ol6jo|pE}n#D*_v5{E4~R#c;pgR4zevx75zE zn7J;dh8Q>PlgCZ_r@5GNVk&K1-=s3rm+(T)s>+j3mB{X9@P^ZaLr8m0w|Ee&hkMlD zgUPx?Uk^B6H*c95vQSo{m>a zV_n}TtWldh>6zupS{?{m8@uXyg|Qm$`ln!*K7CFi_VrbbskVw_>ECqX_|M!Qx12+T z(}5Aa(9&=kk4oBnA?Re&(;bx1R+UIy#=+^4=}6rUda-;H9-zGh$!ed>x;YgMas+R}cyBV3WKT$ug4*MAuQ6T|aKM%lsDKT^O zSg&KS6zlWM*#E{Bh#Nt91|c)+U25gerBt=D^ofLOQUu1~F`@(X+R4-(=tNgvIx-;> zd8@QLxBg{FAvhL9hjNKxYx@UZ%=Yx2*3&aq@P0s-DyQ!L8@<*@!yDCbuHB^58*7&b zeHyLzF*fzPV(?Kq`OZN)`TH{?K9TL;{~ezU!`~jih4J}4BHm|w?#pP)8=u!e5Fao; z4>g+Ey7BpLK-WEmVso_dxueF-(qFmXN2BrS-gAe)-WNS-;MnXju-PvpB^0F|Ow_Wk z@NQ!HyLzqtrDW}TFSR1cp`P04eG#5V;@*j6HV&dIFkVz~nMk# ze%G<0G&Y{0+RK9|@%8Ruz{lqJT>5Z_h?a50t^vl`JW;`$I`t2?PVxp6Q8ExO*T?JF zT#C`(Kpgu{1#)Q90=GfsH4v|KfmIgBH5djbHNBVxpVJ+UJFou9*n%smG#2FSb!hTP zmadO2I9Kfuf7lm?@tO@xzQc_?Bw|;6Y!|jOncDQ>+xf=Dv~z6O&YgxDGe=$npU{j} zzq0j+gu4v7VIaKtAG^lZeG>yStf7R4Eq!MjlnDde_{@(`YpT5qzDfI~dqsFobK6Gm zIJP^-d8v!vOt-w7y7*n0cDT3Plrs2fI(&!zUh7)*}B6^6y3*X@J(sM-8 zde{Kz0eNDRSNkuo_6JcR4x-Xyop^pDZA%#-+-+A?GNZFgp&bhkmh z7n}NMvh)=vv`7r;+ScffP5g~K$Fm2Q_p3rVlq54#D*C6WUMskOcnbBJ64q-9^_mja zD=2Ma3~g?`h`qSMiM9`t`ly%oK*iCBs~%5=UFcQe;Yqins|XO$OcG4Opr`)U!zQv?Ay?Uai>^E?FnUX)-e%+8i_PG@pCca?4imMHCwTT=lFxfh zVzj7iD3N)tzp<3P@=d{Vk=OkNp9Cve8$>A-6zZSFn|F zC(lrmk$A~`x!z4GXbUGgc^Yl^Ga z6j!e))GLq5)`-f^5tY@4?JA@*@q5UMCLX;m?G2@l9*X_mdvnpzZ>GIXMroT`_ZdlP z%S4_PkY>f;vS{33F<(^bf?cz03LX@fdrM>VGO9 zM=xZGQJH{TuKShp1>`?}u~--@GHKz{ZE1mrk(2}A-ib8jdhbIVg!K;9$) z`9wsD^dkBAbBzdB+TGofd>qS7OMSG-7ii z(WA@9OJ}-YS=7H8OC3b zpWHmgDm+hqq8&`~){dO~kMPD_xT9?!{6d#gPNMb;k1I=8JMJncY; zHHeTIyg$X$)g~i3`>YF*3tB2*Oej(G%<$2SxQmHj-S$Ghi1Y$oK8lFcXCjjEmQh3` z*5A4kZFR6Xl#f`aBOgUnk|RXPM@(RE`$tmDDDu(jk@C^Uo`DcI%-9mYF$dXPd7E!FqWInztM!K-EAJO!>I z5j<6gzDlA(ydP=EOSP;g$`|SMGi{kT^dO9MTV~-#r~g1nm7ULv=;w{tf(MO$UUKp` z%YEeUB@z9cB}a4+!3!V0^t6^wy(2YGByVK4vVJ<0-)U2(CMMKNy(H>bS*r7e7( zHb?V!tw$ecrp74^C|uR@VAMJABS5%@74Yxk$O}jdt=InXAUH5dy^?PTs&4YtSLmq?nXpjzFZl*QU@Qr zBPb=dpif2AuhjC@R(QR!1@{qTE4*eops*?tupE`RD&kFmgq<18?m1FezN{K?hm2~X6WK& zPC^VnuP&Lns43vpNj9_E1uKy{+)IBp!OP94gB`hsq)J$MA~Q#%iW5@3qym*1M_I`n z22}BdTrYt)VmCA})f!G13iLTm{Zp%yE>1j8Y9Sf_(q&XYoQNjAEIoLQGJ`F{z|={u zI&(ZSxAaeqD|0hxnh*_Ro!@qu70^sX3*TAL^cQi=t0Q2xm%dF6f;6wvH<7wic+*8? zdd5wNE%i@?m}LEt%{zi^YNs) zZ2&@b)El)2=)43_+}LqFBuy1}q)I1N1V6&3^&S{E&r#mXj%n-kzQj`9&63552^T>y87yLF8*xf zg6%{9*P8KP*b-bMKUQn-lNV(-Bz|Ihlm1i*h3BI~9V1IL#(pKj^#-))(_kN&vG$yb z{TULEse--qQz-;?<1YCX^X`hqF%v9nI8Ks}>t!A1g$p<_ksAMSEAVU>K_gc7_NWY; zl$a!I#;V{vZ6;(U@9;Q$FTAA|FmWDM<4%bNtWfn zSZqJxzS>i+TJcuRDOZUF@$M^SeF1ZCu@Nr%WYre(mjM3qmt^f~>5wZ;6c>N#4f%^n zW>=PqanwH%TW}j?ChPy0(=bA0_0-=Po9r2wxRY(E|~ONj;fIPnjj{ zP^zgNQX(mMC2S?Lq=!(iY_kR_O9li<)r~H#-dJZ^t%w7)b3f7;h1T zDxw!7>IuIenjyuy*j>jYgXK`Hb5F5TcE({z=kotTo+G`p9f-jLHp~yVl@mNkGWw>* z)LGR-2~e;}Wir;w8zj0n^pCCP;@LS>jJrvMVn4`5BgUexfa^seH8^6e2z5Ivc0lBwop6=I*`gF8`xBdp=lxe>Y<6uz z7})~jX;(E#I9vMx&52BST#J%thb7MiWDjl?-4gLCo!V(9(DdcB^r?g$EmSq3$9DT}wds>bOKA^=8Nrg$e*-`1C0_g=$=_ zXS~m?2zJL0LyYK{*%c!0q!f^VUZapNLc|`mT-2`E6l^iGs7Fqt=l*tNm*IR`{vQ(Y z`*YD)7uHemkg-4X(pZ+_Xy^aRQ8=lZ$-S|(^TJ8NW$bV&z!3srb`fxJNQe$DY9P!F zfK?=2X~vCcDP+9q^k1KMoU}4gidiGZy71B8h=sOGLPG!?yHbwz5gQe6ADxXxj4jJX z$F{>p+Y8v}&}7=kj;5*+vQb1Nq_jLL*g0b?_yT-UFqEmqG_u`&UWw;oa1_1`Os}=`CF|;mxwk8cr_}8%?dy^D|!UrYM>8 z8w)=tz^OMPdSbcu!Sv)cLrhJDbk%Dlwn*cLi1qrE$;6|-eJNcAm1$W;sMx49I&${6 zua~R8eMlc7N<@$rQ7#uDRoRdlxnkoNP2$T(v`c(*Hh#8Tuw#jUjDmK96JHcbfj#mM z#Bb6E!EXuwd-=bHr0c^ll(;#yU#v^7W_sr_IL%UJj1F5IRXq87N6^Kw1(%d*GGaGT zqArUmMBSSSvdQQiIpAY8DkV27Y4SGlBEr0uV4=K9^YmEndnJ;hddFo!(6T*~+gO z^%~`t!`(ukYMcwiUc!Lb0>q3>R%tiGWv-GhHvW6v_W4l{A3YY{d88F~N0?S0FLg&R zpG5jjjfO<(svdoE&yo_qln^g-$9g^u{R@>zxz_OEo~K@YGIz@7)xRCg zmD!*sg>32I5e`3SoCS;+!3oanHl z3x#q_LYM*T1lW6rTUwJRl-7w8FS}4Cf9A48nrF*Nx|Tq!g2adtnXBv*`rIj1Zt8Mz z3q7m5uFYwuPV6W{xlBYFDaQcwpRuk!Bzoas0-BAAU`6OVw<$LM?B-x%IP0EX6B~c( zq~OIc_D(f0Hr~i4&~z&R7q)yFkM>+@bMrQ8 z4;--E8>4CJyk6B_lXR7vn@iW}yGBWBw3Ptol>%kkqNNv;X)A}2{NoOF>%?WzbQdZ6 z&hrIWXKI=bQ*BNw=jC!uja6Q1H?5*STPSwFDDs6Q)~Qv4+hyC(`!(luR^D_Zkb?>x}H{ogV*Loh5eGOf1`Dwm)7QK z8&t!A&-4kLuv-yZ@OAo6*xec5oC>zs;D8OWs|NyXZ1kS>aKPRJDg`GmTYGaS=m2*` z;gR7=9U0cqEZM*bwW)^-&hUk-FMH$SUBb~i%Wy~NK?}BBSmp+!$P-}JP zJea7zsQi*=3F7?S+O`d73)n$pD|t6wO{85^y}tkAm{4A>^XjhBoIwK0`ifXB<2Y5}PpH$-bsKaV)8RQjn$?&-r^a7L@1}gy zTX3*-r+sQDBG&b`I=^F86*LlcC+B}f!jl-6prZ2`30vuj7g4O2o_vNrnVm2BmOe+7 z59o3>APgL(8bd}$p&mG@3ctXY_&XjV@_X4Iq;97EckB9O`oQM^L@!KNk6eJ8&geQ7 z5>PMP>w2M+JuHeYdkhgfp|fvEo_oyf{C3J}GFvt2=tW6|N!zb!oN{)koL$J4E$1OJ zN98nz<-A3c2EXs0L*+Qyd^&kVaDzMPuVJtdeg2O~;V=435q&Zqk@jU`(ZIp&a7ZEz zomNPyHMC$SDxtcnCwpVNl>G_6bzA+jvCdJCo+{L z!AtKxO>olKP%5A8f9jy(YZkflg&m5VSVEeEAMpPhj6hYf&NUW0t6U>8cg!_CwVdUA z1>=I-`|^iL>rPV8yVI{105R6}3;@t2eXp0(pXH0DRqv#8h-jj8Mz)eOvX3iOr?#-N zV)63I`p&f-4?dV#(x^*}2 zu3QPLr97RY!@idUg-nR6_E5itZH6wy_^xq zJ-q7Q^v>UJSH#5qh=;IyL530bvx?19G`DV-qxxqe&k}ZZAz|-q8X!m6-vwl>>me2! zM%n7?B#ODp!98rgO^@m7g-D^zvb`wPk*A|t2A?P&ea;a(oNZ8^rA5)PSp{`R^?H2{c7FkU=;hOE7Xk3DTpi+Ly9%gh3Hxq(y5TZ@ow;?4MeK*w*iSOk|TnEo5-%J=JejuzWnR*TR z@zfIE-`{2H{WL`WCPc3N1xYLEcnz)j<>hMXnMM(pl~Wft|6|4L=Kn`?q+pZ%uu(^D zm^1%(6GVj`2a?SQqP2G!l-Q5^DgN(3D&s?jrL2lA>EikAK&#rJodeT z!B6Fcv^gJ*cMeMcctrxhDynQ*KrWY>)E`}b$ur_|gFFK6y-BZFvm6HON zUp#)!X%y6U5_Wf&9B*{!4^`MUq#UE zP2{4-yT+1caIt?LHDU5UgDf`rZ)<-U@nEeGW&V#zN4fD~F%>G0cyhEe&nZrv5M z1*Z^Xbe7%j{(`-3_fF}hpInCOfS#Q=^EJ0j`y~(u7x{;fkHy`q_rTLHrIsc#r3MD~ zlfy_~H3|!D{g@^tSKu!}q9nnGR5NP$PXPj3<^Dm|FkHbJ2qL@QS=pT%UjqKW{{O{C z#6SOUq=)+|8BoCukiWYh%lWS^@-HazUtHurqsV`3k$*~&|Bxd8r;7X^FY<3wLUMwBLBrj{xgdF#}@gg6!{M+@_(wx|M4RKHbwq7Sn%Z2 z>+?nawMG6FMgCih{5KT&uP*X0DDq!i#>Ajz{7eFx_4pA9g?vMNj#OF6bviLUNqWa9xpsfdB; z;_&FgrdQcFeVMYh?%;pM#X1dH`ZBKZQD~(Lo#fKm4JnGK@Q3#lu&!=J@bl95F44#0 zUT|>=(2uy)`dHk6i&KDp#0}|ValdwP3eb-@?b9gklm1mMP67H+bP1R;XNS9{sap-! z3F8GXAfW{x9fl@MPD3Wk%4-eM$Nvjym_;Cpj?BbsdI82}&3M$^?O*sbP2PtlBfXAg zvk+5bDZowp&3$Qh_o1oK3`9kNK&|^B>7kF9MN>N!OVqxaOjTDWI^K=VnZ_;DI7-_- zD`n!M?UL#0YJ!rfGs~y+kKK=^B3b6tB2AQQSHvKC$IZs;(ZSuiQGj@A8{4>Jk$tM*_O!&)GT@sHh+Rasp5WNJUF z`j4o(P^6nF-}2Y(s-oOQfx3|Ji*_O5L|sU@=r}fprj}z9G`6_@CsO~=P&IFpK# z4_4>&Z)yyU@{bddrN)?G9<}FXv;BU}pFr)^%4B-)!EXPg-SK56e+$y`FZ(2G`g3x_ zA-vD3sDCHiU);abLB**3D|u}MeH=a_f7w>$KXF906cm z&Jp>`wkrSQBl7prqaVKgZ;!~|wN?2ij2Pe3w<`bPBl4GRRsIu4BACbRntMXqn zBLDQQ%75pG{AF8}|M3y|`*z-%_P;$Mf7e#!pK#lV{@<$nhmXi#wpIC09Ff0or>$xK zoDuoEwkrQMBl1t*s{D73$X~Wq`5zyVzi-Daw4a5J+b_?q|Jbam^#8^}hNaL=C3K{_ zq0BC_t=+7JQJKGSyhV2_ng9-i+|eU76T_&Xy^cYr`RwlSu!l-J&m;tBXkwfCnS=Q&VyyAno%j(R8EjQHhL=BE z(R#o5Oj(QY- zK=J*-pQHu_NcdF_3GR}yf5sdVFc%BKMOUz1o5RE-BvLI}gltR?!y^w6$g(g7Bu%R} z60rjdjz)eIMuMl2_pi1Sd0!7@Xt(4NJi2miUtMlJj+Tb)>FAqe_nD%t8xFpl7oNjg z9tDkZAGy*%{-4?_= zhtXdHD7>o|5Q+5f*6`8tIHcs59X;~T{Fu_RZB1@a+hCZTK+a}&G)W`y3wde4aDyl@ z)_IqKZK%ton?O3-?z?XtaeleHy5`*7W2_nlv#45vH=TMdvyOd5{cP2vpV#i-C}7ln zz9WnrwV$sg(n?l8r|}p9bwLrQkb_^MXvwjFFx`XxnM!As>^j-%b`&VHab>s?mrA66 zA60Imm47*PJIZk>ju|)#{G^MaVn;;-6^F1_N=#VX+y0x7T!<5HRibAPt+v}sVVXh- zJ#82fXN<~Rt}HNzk(}`tE@l+Ym?6f>6lZM5W0%->fP!RdLvZtZf_S$IjBa$Nz}un% zn+z;(OJ=4a{03YMI4x#=zab{X>Fa(E9=n(SPTJR)dMkM1T|soV+i7=cJe}x_xS_BX1A7IX zI3wyr9BRc0E`|bUM4gC3F-PVK9QF^wqp1e_k7t9!DNG|CCEZeo(OK5SUA%O=HIc)^ zZq)g2qvzA^HA(*y>`t-LWqD$yE0zBUNuvAfv(-2di)pKdCHWmm!nP0lHwq+G39quh z_Fw8@7ws={acwWEdN8C9s@^Q6hZT_Y8&uD+0;-1t6j<34Nn!`{F#O&^^*&CLZ1u`q z6qCB?nfT=!;6b+!N)U)c=bXZ4EW8M5N_WRJQ8DrzmlISakR_A2v7tTZ z7buAuauiuFl|=RhXk*6+{_(&cyn*>YGx754@lTWgYV%(z|Dp0PF#iSeSK|+*lXiw* z3HeS}_&9~12m{KVi<$Tz3V-tz!oN@u-k|WmDty0!@Iw^7O5sd#d2seo_{|D`oAHr@ zKSAM(75;2Nc)7yAsqle<@V9yhKTF}a6okK|@T9`s+YK+%rq>iUNnzqS{+G((0XgQ2 z{3ZRRSpRmx8H(#(Sr8q!`0U}@<9MTHcBvhXV4UUALua*Y-lfduWbR4Khsn(Ohz{I5 zfi+X=VI-qu=EmyvC5pJcTBFhbX&GIt$75~`{bS|t3{OxFpfZld7TyO`yAP#n96(Kh zyx4(}?z*#D)0 z?qfVhCsdinG4ydK3(tw|#DU%D}vzr0QYPbK|b_Ve*u@Z-p*!aDH$g!r__^;_suh#0i z*!WATaDB5n9veTe4%hM39LzW_?qRKH1yoR)G2i>?v!!^b++yqTto2XZH+e@$q!F1~ zNB5*+z~oVzZZfe6@ndLA2vWmrC&Kl&g4PqHt3KF~m?cu6ValYElseeKXdN0GTwr_z zZNLufU<7Y5t@)QyF@%l5`$Wzd8wXX}I|CkAOfU;~cK^Wi^(Syk#^wEbmP40NK%zXo zWNo~;x>wbJR@L7H1b!_65IC&sE~8v*PhUPKRe%tx_HAfE@0^VZpu2g=6I1Z5(Z>JF}BZ+m3n#i;$)K zcO-n;N`EhF3+yqqGWZ-5lCetM|C#5G-9be{#3+dSK6_Q^cv1>1+Zz-0-1w$Tk3FpT>i^jGFuAzwes!$#b_Me28d6aM zIb7P-^2XFSOQRJ|BJ~k1%%)?+{qy5XOWKbpX}zd{6E&Hp;fB=Aay>3qD-&$E`fyVP z(Ht%WDoMt42ELjsrhS`|K1BxNy88_(VzG_>AWDrA(c} zLk+Rz)5`}lrYCry^|<^x$2yxxp?a$>2q0@u0&^JsHzo$AQ>JjzSQ6}SQ*fMhS6Jc7 z;5>q|{D8Y023G(-SKhc_vgL91kX~wsZvc4kSL}sX3~x3f$eRyG5sT=3UM|Eqbt8tS z4dtt1T|$Htqf#s{V2(x%wM{BGu-uUe+ggf?pu_jfFfGY zZMa9x8mtZFn!6U@vz8v*t3zR#oj>ZD`$azf3IEzWLcTL)4f5SI_g0_YDPa;BYUnts zyfiq=x@4Nx&v}H`+E7GvU6+zBo1`*0*LAh>Wg5#}AIFxL21jSZ^ZI@8UjH*;59>Ht z>d|0{F(`2W?kHIkEYEp^5}T_nD%ebTzWrXqiJbb%eM#?~($>*44$?hJ9h*+$_3@ znO+kQ`Ci9!o0Fx>z2(nw7v(>h4?HZgE4WO}-Smh%J`@}OBn+TsD$(yZr&AJDI{c-2b(1zdKdo%N2T}q4daNKF4ibL~a zThAU zk+{`OnjX*}5d@?vCYy`;WZ&tbOoj^q4Q4M5>Mxplp% zJp2{BKq%5cBN6F+m8aQ+ub&Yq{dZ>5=HcLB6V=1{6FEIev4aakeSnT-Gs#r48t8@y zRTUb5Q4&>`hh}ma;Ys}dL zh Bb^V{upXa|Sp%hM3yri8?a5&yJ8otBv_6=&rx+0lrVP%KBt}|$5r}U~vZ+2^z z%yo9RPlAKqT#n-wGC-i0Uvqc)X3Acjq%KAY%pfGiwTkBFrLMDKt6ZWr{gCRH=&LZ% zihdHfd&BRV@VlPxaCaTG=5PzAc3UM4_YkO#G$~kMth+XfSkk)>9BtwqA|!Kvg9yL` zI22qq8B3ai2fG}p1(?1D`vNGx6BcF!VcY19mjQ6R~$FmokWn^ANUW)Jc<9~ zIdX~X54c#T;#zFWdK|8~Z^UN(ng1)uzVl`TP23OgzxR#UDLkW5^9R57ADgw%w#*d( z!`7>;Tg#N1HA}}(6C8iy|4P4Z<7NcEn%k{5^hJ^dO$n{g>Mc$}jlx(hD`I~aqxE}C zC7@odA{9lr<-d_iTxa&!*sNeb1(|$<9o8vm4izP=HD@cKP>RueEd2T8L{Sv^JJYDv+jXF zl1CnfEjg=i-e_dmECR>+6A_7k6QMKTtmq>s+Lv7m9|ajMSe8 z_2*Il6WmM|62BJi9I=00Uq}CLfu1gV^-fd7J*~@Rs-i)0%fUIM#cEHft{CptbOPp{ zo)Tj2@CNOBWsXLb!?d8=vp-vSmb+~pd}8Fi1Iv)VhKFLycO*;OpLKwH(X?u|u3sKL z)<#V1_jp?m7W8o;^l?ghLqXC?OE#Fv;mg5A&qF>W`ro`BA$Dc3fJrz)^3}L)yeZ({ z#P40NeF*%1`}d>ZcOmm|Gzdfd);RoL*6@D^ej91K!|BT4B;?o#zvtmD!Y?e|=gNni)UK~Y;$AuUNr*x0vu{uMmB1T`#C?dw7im6i(PhIX zy0sH+BFamznml|b3KUatJw`8sXmr$R;>MbexHC#8b76hgA{Kkkv<{X%# z5GgRLhPzotA$h8ArLW$Ic8m^e{Yr7?wVozvh%M~wcCuR?uks4JtlRW%8~v`A)n;xj zp`Vl!^&2<9r+5FJE1>Ns*?E6Et+3&8`C{y+M@SFzvk5ALi^2Km^6I1hZ(fOTy)u}Z zm0bsd<8kN4XZHT6RqX|+o*NEI>1XrNJrIQGZYkHsENTF07JrGAa5x5;TQo>BWsL{q zFg)C?<%Uy4`ilVpLbPBtwFOu1#>S5!1cHu@|Ds5kWje&1(-^VRU{f+pMi6%jcg?D2 z&K=P+`z)mt=<@h#bY0=?O>L*KPtqO@CFzZ__|t}i=9$8ELff)zg37_)=Iisf9sEJT zdO_=gzxdOwIa(L240c40j%d9)>mCRW#oeul5UaAY3bncsa&7;xCY_Ymy z;5)?v&Hnr6W7adw_6hQa)rB=@pwRPLY4@Eg3w=&4|Ow#^)y$R~}M z$bVCiGMvb-?at2MGfM`$z)7nVU?A8DcaDQ7Mc#aleZjUxlg%swtOp8q zRay_zt^&+h(Rsr_)&==GngbgLrgEmh(e_X z>XLmN8pN3;Xb_upFFpzpYZ-|>4^*&OVQNG%N(>)gaVo@kR)6Ri!GgaDd0}ggU~AXS z!LE@oiZjA^p~NG;BAlbGLBvmq@<-UwH`?Fru|QJoW~pSiDpV^pN@5;yq<_9BUFF+u z!^(e(wgTf@j(9QoaVD;-u!Z+Z5h5-r}k}!{#-= z8IWp3jY8^-{QT=wqdfWv=I2T9S7qIO!6{kyfTh_IeYpP4Uh3m)sNRP@B-ZB9#}6HS z2+D_{k4Bp0=;MfAj!GZb?K6TttaJ0}V-XiM7SqQg>M>(ax_0Q_rH_}Oz>q$kG7`AQ zOs=x@v09};ANPq;A)X%jBjV8_Ly^~8f)5~x2B>B6u?!I7A);$m?&6emzO)ualO9^-%dQo&9 zz3k}bV?p^a^s+lma`du2mq3ofPj1|M1ij1>it_1Y)?Xdk^7%n0u<*6%(hd1dH4PCBE}?J{$WhxC*A(hMhp!{0ARHVtF!PBw(^bt#p2c z8(W8iukt6_#|!60(dmE@-4^-UBK1d(ucZO&uc8(Obo!ONmCuD)cVBR1);$m?P2TEL za_tED(Wemw^eP7SKJ;3|-~J^!nZHUIB>VX%q0SSamt6UdU!EfRL}@PiWU|jYUlqw~ zqRWFc4z|ochYS_j`Sz!x%L7!oeEzu)E4xs33qG55_XQdNzv30++6YHZ@uvyfCL$?c!7De*c2AUvSG4`TasJnIjL)U9vpEV|Ueh*O~yFBdl z3^&aV2cn+XNo}V!54V!OhjBy4%5u|Jah}Ydp~0ECEbgw;-sC?{H>mS?1;O8co!ouN z`c1Mb)CMe^9|jjou4_^#Z-CG`4Z|{XEIkKG1>Do zaV6u7#rB*mM2BqaSC+x0=q$7hKEB8#Z6_z;2R-@plQj-AJ;H&7_G40PM`nV9%ME^3 z&$I2|ud{A8yB_klp*D^%27+T)Nk&9+VxGGJcLBpH=2!ny`aqozd-#9YdmH#Ds_Wr@ z-zHf|%tnivD%RD;8Y*gd(}17}B(Q;isX|Q^8;}G;jU3IW*3 z$x>Ntc5vb;|wUlMb zcL)NF$3oaRoH~ipEHs;nK8I7M$NaVPeCp!gL)YH_>2p5y8xmve|JEJyeClW-B|e{e zf*F$V+~TL?N|JGAO1djDz$>I@VmO;l0;A_sU*<>jeCnWBzsKqieOdZLmqziiHtV*R zX|o37b4+_I5PNimH%aUA0z@r)`##+(%iiv{y|?i0u(#Ow{@?8{et__*J+b+Vo9~VD z7vsKY^A~LmYer_>Nj59to+6a zUorf~0balk}iz$}h_7}2a zTzaC$hCyTT?MXIyn`@>#x2O8D9PTVH)z%m)aMvF+zMmK&} z_{Dksz%qKXv1l3L=T&7h?Msdj*Ig^!!z&=xCR2CpHKcm#r%?Gs+F;yv!w^f^vfuD8 zl4yq4j=7^qr*~ z-v2Z9(M}c*Vjn-?5Q5V_HskEAj-zECGQ!k*c1l){w0&Hm3gDzsr~aqx!~N2s>|+a7 zHW2%G`2~l4+(akavX9H6?>oYcy#HtHV+~n6h<)71j&rAdyvm7wr+vsUPv8CQzr#Kz zsscFa3+!n5&-jl&E4O$s|MBDJ24)|>R+Y-;KYmH)+Om(9==+ZFM&AE3_R&BV4`Lse zYr|8dZ5@TjUb62n zU{t&C&gir5e7d#n%y7nNkF9Zyu`X=xALII+{_Y=pFfOXO?EL*${^Hh~Uoh&+mhdM` zQW)<$!YTdM#~SQ1rjOfb>zw+yJz&>|nnG(i^JWHN|K<8P)uxY;yvOt>S~{40v~ll1 zOdmJg(N`ajq}lbc$*_-Wm|_1f*GHjk-2V;U`=^hF?RI^9>-N6-c>O55KH3d^%w@pz zU#^d824q%!Y2dwo`l#M!*TIzQ-JbrH==AkJm@sew9^> z&1^%uMs>8^9MwHz90K+~Q=7x?IN7bzq+&-0c7u%7F`*H^4=p->B41rrw<_l~|6UKQ zjhJVIKiFcZzD4^Br#TDdkl%;$6?3*4Qe}<3T$@u2W8{OFk+xzPLdplTBKoUaX^C3v zvO-M$hV)O=uZP!2*|a{PR>Jk~8MsapC)>dEdEf$%G^+atWc{ETWYaQPJ&7(qH3$!u zpH?B9L{U6j*#;wcYa538AO%k)rz-}diaegLB!X=S}#Mx#nWmpyo zB@$8`qXN~X2J9h?uH{##lpj1JBF>hr8nPdbC62SK`DE@kZ{_1Q$UBc|=pYLWA(iAA zNy6F&ANH0c%zCqRpjP&Rs0FznD~il>%GLpu+;(hoIf3kz&U+HcU3$f4W{BQZ2U!?Y zLmsNPcCFJl5X-Q-E#aBbnT9Rl-01s`@Hct4%_yt=Y5y^MyyA3klj$K6jQw#OhOEPEWp?2YyQ z0aG28cl-kQL)xQwybzwrALk_N!73-oQrLFus)X&eBRFa+Zc>76^I!XY(71W4kcyuI z<36)y(Zbj zk^5xkl8t=CQ2U%&Qe7vp*|wfTZ21cu-I$rBQZ}lye-eKKcy$E&Qnn{d^>g&esAvfRSt8AC!rNS8EQNCk`X9gO7 zFC1I*+0O^9^sWn{?GICZ1+FIfSin5i5Ljznx+PnEeW0bFyLnPKq5GRA?QbdQX`aNX zcOfPBeuU%$>MiB0Ii1IiA{2nm!T(yhRwU4PB9hC;`$Fm?2PexH4r;$IcV@2c%I1D9 zw)h93zz3emE5C8E>Bf!!bH$>~FBm9E)h7&OmAX)w0E6-yD$i8gg}RJ%1;M6_CCtC5ua zNmKpK;}U47Mb_+^yxjLnLNdDNDT zoms}lPE}o`6<=V6E8STFc8WR>u*eipRSCg#bTpY-cxA6r9bc}4s#|~{9&I`CuILY4QAK1 zGWMI^MvlZ}q8;n8Q(6KvtDo5ntEKmM_p8gA7m zc5gb}xsO#4)0>aDM+&oQMWzTY{)8VZjRXG_ZUfxqPyDdzf}UYqb0*cknlK_8o5TXc zRv3=H8JEn}SYp|{7*~%4hOIPR)N1pv_gdAB4h&<@HBJkWMpnY$Y01i8AB4^?x$gt<4IDigOqcfMr998^Td0xAQzfI>6SB@&%CKGWeo zzG?>V5|Nzl<0ut)kiACTSWj%-_9e0z9;bTctnbLa%yd`XB3VcpM%9k`L)MenS|sDB z-(jwz61=cuH!rQ_yZW7?Hgaw5=G{wu=X``TE|M|%Q+}Yq!0Q+Pn)?2r*fWbrk6D%b zc&6ygN-sOd#Zbd1L~+}~?&$lL@CCMazwP}WOlw8k^FH;v1YzR3W+4z(*DQ96RrI`t z1l#JjI?ZtNR-tm(`kjkLjQV}njWS)l#JK;YjkM^~R>7-!R0Y@XQ>ABAVyd{gX`A)A z5-M@FS&7rpaV~YV9o>k&^QFS7cD&WR1dcMICt_4b{i?f-K3N0N16f6KsL<$m@tfT_ z-0@)a`OM=OBvW=rtzM-f&|UK*u+g8`B9&PRMQV9EXew8rF-yGGCa$BEKcl-g#_TUl z*eC_eWh(|b@o{Y=m+P8_{X=>Y)Wzqlo>~xsQNm-pYmW^zzZhy}v$+0<*okZ#H)(AU z8qiXmOE=eI$h9OZGBZRXTUU>q=75qvCFmUz9xv!>mE;Y5CFYojctSyiXskbJ7xXB* zptu;0u>6k7fsKoN*`(9&xl1}VhWnH9!_CN%=cum;ii5{tn0xWFRi|c*h=;?-5^=3c zFJefaA;Sz*1!4t?G9~bnUl}QPi4y3I_zic`DLjIy*l+0_9IGc0-<+S|_h9|Q z4LFNae#w7B<-hA7ZhDFEx0sZ(-dk+%*G1oVgj=KUTf*yN?^Y>Q7{`Z_YtP-DpP8&0NhvLxBY8%{hB$kcOm9JG#%+7drM)+A-}!{B zOLd`A%Q$auy_6dRH%b6>q z((@^Kqi0|Z^purglxm=-&K%%Wx+M+#)j&@O=*QhDPGyCve^U91sNZWO7Bx<+Q2wMQ zD_7F|T+y&CfyQH$m*}y3iIpniuVFsXoxW=s;-f=DN2+OT(!}!?@2ajCz*bkt)8Z9r>jD zFLrJ?k0+Fu6Zxfz$)6gK;z^~VXMj^9(}$&dw<#_YubLy%i?B@5QqajjkbbG@eTJs0 zHXHs*aTv?SwYnR_Vh+*v_fgBQ%5)PqTHZQU@!O%lN$KLTloKso!NSTy*S(b8IAAuD;cGA$_4FHD2zKA+sox;c^h|BElI=C+?V(E!q^Z0?W>#^w}Rs zm6!XiWWNd5&mBwckG9vc>u%Z4F_og`o~~cW{nfRZA!9uJH6^?8ML+v^_(T2pUqr{l z-f$h1W8>lI5R;m++U$qErytj53@j~k&sGCVeDI+LmJh*2I+)6{VmwBXb=8KfeZ=CJ zF|WF8@w-b^Y}>~`qF__R|7SSYT4cH93P=m?wij3Kvw>+?N^zb;@4D3X~ z;@i!UrmC;v+av1@iQ6UIGyO23RDTs| zWE^@P#cdrix8twEs=_}qOiS?5d6q>~C|mxQwO^m2-~BVIz0n_ENA75J0{YD$uw#e@5eM32(5ycg5aiq$`FSKEq5Gy?XQJebOw%^=|7y7!6aSo7ckT1I8taYbA5C zcTU|nbo(N8-xoa;RrAWz$>T8-%{#zU_s+PeZ}Q*JBzx;O5zVFV`YCyDm5a}5kTyV_ zp_KmG|466zEkUI#Vjt=C=tz#M;~cnrk=yRx!;*U3j0amtB!_ zwC`8*-a6r{xl(WxxlzRT>h>aj=K;}wWoC)=l~iHjj~VXaDp^dEOG=7mtK1xY?^>}1 zbxeGtX+vr1ug;Lnj zI%zBL6W%roTtDT|bIKorB(IAG)LE^064`PU^f&%)L02xi<5D#y2~Rjo}l!J>{! zk5DxrI>EA4+O{_J-4x3R-QhEZWb1_6b8yc$Qw(iZ5ZiV~5~h#;iImM7T|c$iX$>>S z@>9Bt+yXt*{K+^X{802=neCkTpN0I4b6PGUSVcYd@K%5Ct>glvr-`PqEc25+wPFOfzL=}6$x~VF}=*l+z5eb;U3@zQxjm+D) zV15gnzNt%X!68rXkr8SZ=U=WZz)Eu@Pcq@qQN8K4qbx_jzoYt;{4 ztZEBGt?#}? zMjt3G)H*YBD4X%Iz@a!Ng!)MTMAdR_<@>PA&m64`AV@QfBfchXYWNLlCVK&Lc#>7RwPouFRP0Rg0vV zsAuS``u>_epW>C|UlIs$^0I`zC>V;SPX#9ur*tp9S_Cx4NouZCjM zwJ}&{M587c4!VBFCV!MtAVU{)P3gQVycoKu^*fc;8oH<SIj_+^@mU#{jqqg}yiUC-ws zRY_3Dv(8ml!eyUC5-|t9hDA%MKLT?jzO>C~mitUq38!*@&6lWLCOXtYojmW@OaAV1 z)tw(H_J=)$DL)l$(b7@7q-rL_M4G8ikyHUmbv0p;m%`f^;{Zze#Zt^an6=a2Q7%K< zPSjBAN^>FqJp`Y94xX3!n?H$n9fb7qW0%STZu4c8jli%Wnfe*%FYIC3)Tr{?!k5_I zcSPTJgpXr#+;R&;ZSNVj_kw8rE#W{Ezb$+Wctc-`LQ8UF4pS9Ye``cLD^uqFT@~Is zCBxdsYsA+sr`(xeN^iI+gBqD!i>JFuIl4gj2J{dcPi~35M(IPFs;{-7|e{gQl8C6>ZRitUp!T$hRHv^#cr)wfsV!z(a8 z@Sc=RF)c-Vx)eb>xLx4nolB`JH%ma^=qa1X71a4^WTckwW+ba`Eoe!Sx@B=^sP(FL ziO98F?V;95Oc?DD7hls&1LW3MiS$divgYvKWtWE^i_?dxzd8u1{5wP`NFWN0*OXjj z3B}8D!@DBOjX^_>0&-Q5ZOXxm)b4aciWGIf8 z;lp>7KC;jUyF-*d=mSq;Cc@AMGivCg>0Y}&e#WnuQHVZ_jp=3qU6w$gv->Sjxf1Bc ztfJO(Q=kF_DzF6NMHKVVJ%;-|IVRXs)naOSv%{|uW@};1^4bPn5wo>wlcg=OKg)t{ zC)lB}gILg3F3c1QDr%i~2n+hUDd4w(mq|siq?-^go!S1+ENZ>7$EZ%q$d4B-I1053 z#!e9rVp%~YdzBlZDz$$-;O(Tr0z0T;O`c1&(;9t5F}c%4m2v3e+`L)el|< zSuZC^Cm@L^mQCo*-!qKmJIbiv(|^kEu0I#Hm<=^!x%c!s!i0j*9BsV>td~rA>AFKY zNp?j=^B(MasOul7qwbxqburV6wl^{#$oi2oLiHKa*Xm9PFQs6ZUwSGCL{$ARcOxa2 zODrsG-V?k z@#D@$gaN9$+LBpk=wo;}UZroMaQn#D$S?PiVb_$d)4`f{y z+WeLmeAFZ~H?nV~&S@NG`=?z}axY zS8I>bXHiCcxxqUuNm@4QUipDrcQy|l{juGJu!OC#1o+wiIMx1`@xn|wKF+FzA% zqqh}iLZvQ%X|ibVzudexou8LS-ZcD|*^-m{Nx5dr!HYQR8FxvQUW`*<5y$9q)&wt; zMkPFoAj*&SK05Xlc|<;g-qQ`}N^F-qNPgWW@65D+ieBvmnF_K9zDdyhwnX$y?-go! zx>^PcCP|r06_P(wBp)x9pRG&h2tZN@8}E{hTa73|Tk32xb)^y1E%LQ4Rb6m1wR)G- zg+`PPTXuGv**QxEEiOSnYKJ?05MCtF5JLEpH6x{~vJ1!Vt3^o-B%)km``a(3kmx>` z``h3AE+#j2pX_hHDqAccz11)ZRLd^g2(;@BM~2?yDtsx62MD$3Lr$oCuWOUC1BqiR zqPYF)Ox4k7eIQ>IWiHCz8W`Ilr9qIvcGI20oDp9`PGw*jQ|_*YdiR3BvQG8pxgxMk z?rWCz0IkoG#%Ox8_~ts7j4p4el_?-&`=&7-SCe#T+4gapzrteESv4-#W31`nMqh`B zjDFksHJ{P%E+8Y`mjG2V3YNl>10;Zm>sjO7eGsK2eAz6 z>-f7v%`27cc{`F7=Vg4y&<)YTv9HS*!zc(yg<3~1LwPQJxYCI_hJivp($`CkU@l>f z{J20>4+3TOSGfQ(TU^v^F8`0+9%wwE#8elXnph-IQDweD^pL9#ZHO{LN+iOYctK^w zt}qP)tqA@OZT>Y&fVH9Lf33+9NrYZ4u2_tak16#wv7AFG^?q>`hElJUSDR9)o$*S2 z=XO)6vb@=@8!NCfqcWOv?nLTPfkwroQvS7C(jKh3Tw+$H21#UH)^3y^u5B!# zxsC7Cj+5G)EB5Q06**p|Kgcxr$4W(JtztT315EJPfyOu3&?_dU5aL635i|T-u(UHf z3S5;$46_Ey&s;v3n52GBQ5yzxsYd2K6YuHG(K5hsvEBlDCR+#XhgM4BCIJH z8VSX@$wVtv;={l&!!W~Ma-^SzOh)f(YuD-4%N*4g#_TBhZMc8xzYg*-(;N>y#!Qr^2-x!2PP8S#$njCF}&oFs-ZM+~D{ znqphTUQDy`wc4);qcy~q=`6GSjd{yx*}p=}gSHmGAyE2^Porz)9Te+0a||@fHSf}D z6)O=NNfIsvWvNbem>JDi?8NNXLxJZrFNaDsZ}u}MRJ4^(a@-5M3kA= zY^cHPEZH>dC3ZpMJAq}h;1T{kCeZba#pFb*7?~n6=ajZ}sor;2=ZJSkycTBVNEKeY z@V4f7qk^o%xC&Xfk&Y?XDX}1`hW+0Wo5S|Lk1fT`C#m(^=08ZM{COEvOBaB-9OGMj zp_U75!$RBV_-a%2lW&9K4rzCBh&TG_aeqpg7c}peFL^Zxw)x$>r90iY+q@6AdkO*t zZ&?mm|E{WKW;9Gse7M-*iQ?nw1lv@#Ti8%?O#bkZ>Aa7&5|tM1QFy5z4X(Q4yqou; z$6h%ek#!BhE(`;$pauKPe$TJj!a78VRDXD}`EnCySJ3M(NWbmXaj%JZ;KPsVJ-$e$h`AY2iX==Ut=xppVyJOR&{e%l@*)8&I^YU{p(Ir9wJ8b7V7d zgXCTAF{3vjHBUUY*i^LFr214`V-;vDhk{ILJR|?TP{e5!nP_CCEYR3WP?5~Y%LR>W z-Uv0<$p|;lxJ0-%o63TnVqq@7z{RyaS^3)rUJWa@3>f*C@uKxQMkz*qDOHYrG0=EE zu05v3zu$@$&#>Ar>4`};5#>Go4;We_rhF~>GYVzdRmufusedx8L1YkpE0fSCLka^O z5z$k{B8`f$EXPRlsF_3zNEMM-QTRjxX;&$_M_(lm%G4e{Ic8VNq?B>#^$QMZSKnBA zD7#8QG|3lAVLpge<-eg9Huq<_ujL!q_Duho`qJ25JKfM1cI<3D+LsF{Tc3mOqv|tQ zHSRtlgu|e0{dXgOie}V4{b)i}C6h^@@myN(Sjk)>bTVaM7WEgSqmiCzcG9EfW!Ro! zb8>1#8OXAi*c~Vzbz-548@VWaJw??z>{LGd65Z*FscrWiA2p%y{mKmT#pVjwn^?dg z%IN)B{*(Sjc!@;fsG6{9Vs_lxHG8A0>p}f}_((HCXUFI<$jkW_rrvs)YQBVTfr#B3 z%n(ndG9ku03u;~G*~8`Z{(&8mce z_Vnqpu!`L%M;3S7^G3?Ks5vuJo%YOAdt}cr4wV*Uv+E{H9VQjMb3oX<7oo0%?53;9 ztu3u z<7g{yxtaC3>G%rCvP>gmAz$LBbmTt7Vq)tf)_yb5iPKNF&2_l?R0%pnfR|U&x4k3`%n2POdq;QnE#m_|9s%6T|(|a(XvFI z%jA8!EH!6`TKu80zY8>OhriTk5FvD2BCo6`0=F)db_GwEEv?=!zfC-ZrqwHksycjX@O#bVS8VZ{WAPJ*&;S!* zS_0D|{7SLKS+;|eYzjy)eyhH4Y&aAskXBXN&%)N!batR$dqUAzCdL&9s=T5#c5`5P zv#><6Vm$+~WS(P<&{3K&zpHC1W4aP!%pi?oKA1K;`3*+liRpwB9(~gdj2$?*J$L5h3DaXcycPTE7SFB18xw=*omM5rUt^ z{9LKD7=9Q`QS)!bE@e3XF*-R!X)If05GaAbYJ)&67-aH`}9T5gq;6AAWBuem6xZg<-3V2l+h3Xr^@^P?TcbQ^_=Tf^2 zf3hPyHTu4_>u6`j?iEURh-0GW-wH)@zEt9gzhSScTBLY7i@X``SegVri51=I$ZQ-Q z=M&V33gwbd;{+Xj>nv>cwE|@(p&bS3P{1TqPyOLtRDlB4=#{k;xb!`+E~IYKz(=Gz z`h2K)i_lWtEkU$PpDUQxqON?VVoy>orLbi*+m$Of6GmgFB|(Ib1bk@n`)7Q`@=HXI0~Jqs5+2rp$ik5(ujPPWpDQn?wwND#kMSAL&rD8fL6Z)X}sngt?bv){Cr3q_CHx z>mkGMM_%fBKtEe_+d3w9qSVK?^*N@+$~ZjBD9{~U6O7{CD%o;o|A;v1K>%UG5Cf55UA9=Idq?g-quxoFs1fk%EDTK3z( zvfoRvY+Q=)@@NMCjd+cZqT>jT3AId2NAE+6=?ieO60Ml z-uU)uHyr)*Un$hBf@(Q4i&bU0UPDG&vLCpp<+SH_8m4y|mL$dVx)JjQ&@62*G<>P{ zYC4-#{j0IE4+D3#cMVnLa@`<4fvAPXzPji*_N<0lE>dy75Ner<$GgT~^9Cr^GheEE zheGlfj@?#!T4BqqAcc*T+ZPekURTQ7b(e<5zFada+TVIwyotUXs|_`m_{BkNkuI1t zQO9N=m0&u=Ghhs~0MZXj*RN#UDD{KY`fXAdjD>BrFw=5%mY#(+r4q;1r~}KoVI##E zt;ps&wN#BJLm7>Gq%~<7v-vqu#)Mx9Xgzj|xT4m{{vDH*qYCYqED~e;lPUShL4J!z z<^C#R3bFI9V{FB8j5RONa^?uKA;rLXil?ASX)ODum<5s3OwKdpcZ+s9!5AMIc^A%w z!ntL_Vwbg{}k$y@b_pSoS{;kIgAJ<{r@rP_rkyHhx*gV#LlrzL^j<)*YW0y zQeV98^lnir#6wgB`+g{8g=!4Jre9grUE0fZ)w4WH2tvQvA*Sor!@P`5$fJLoWW`}l6$rkCSH@_J+E@IAgg*JChz}Nm2;q`Pn z9)|jM==r?M76aPBEd4j=+0?6kuQKKLbT1yk^tX9mAMsLQ^N04zOt+Rv;+q(g*qUF) zLb$=uM<0b+yx@1CP4T1RNKsD<*1jv$at)Phf1q)t;9CaaY-M8k8owOb>n3U8*j=@+ zKOH1gAE9c=#dwMuI--j)Rj{OL-o_?k!-2;&=99807IBsy-@l!yIekqrimH*ui)FVGx$ zM*5G$=@|L#y2C!d!FN%cui}9j%xTnfC9^~iH4pzC17TG$!q-w4^cN{5DF@sFw*zI! z*bdoG%I%<9v995lqbHZde;`zM*JVeyipZE(BBs`ki~j&9u?9zDQSaY-Do7^ufS5F< zemuEY+998>_H_NidU@7t&**=By{Pp%zgdeuVD8$lMtw{71>=gJg3?+kBcm^sECaS5 z!T{`h+rhRj&Y^Lf4)?{h)K{bTcDVzI1E|x$O~UeRmmtY{i45@4Wmp`z^+A5h&^WM6 z?8X=#Ps+g|O^2VHVl_v}H}X+~g4{y3Nr~UZ+O#1=kas3p7qfM}@)==k_~A*RnE%LV zDUfYTm&<;i%*IaA4*vT8ksSTbe*R3ChJ#p zs29tOT8HvWn5T@y^JNAR*^QxiE29J1;Ec^J&I+F)4zYEDE19x+{~BuSQ#H|w8QVdG zBlt*fBt(4OY-r2xjppwne#flO+W#iUY}rk~O^Ngis2j_PRY+eoU7w8rvc1WtU&I@p zkelh5Yrv-2mtfU@W$d3Duu7tXtW%Ay5j!I}j(lvmB4aM}%Z!Lqrvb4#n{+kVWe zs#{oVp&Wul=^d;@W{kO_s;Z{;93y`tMwc&IRJEvd-rU;qE2|b=U*L)lKc}p`mK={9 zX{x2v8NCmi#OX&E><*tiG5--GYii4ELfW{-^CO}vH-ix~Y6<`5g1v%g9?!RU=+3xK z;Ys6>Mb4=_L7ppl7V%W^RPY?b^9>#upq|bn1J+gw{d7gb$RRl8tb&Dk|o3$Lv>yL#bO^`%r2D#N1kvuhU3J3Ftq zu;%P}nE3+rQ-#T|v*uM-D|(lmRx|Fjvdaet3&aq|1q&CdS`)0EyJ+s!<+bIDYD6>e zH{wZz1+@#PST~dhp|;@4xwQ+b77n(;qjV-?w&i8P+N$7!LB-XC zs?w@OW#x;4S60of44yWhe|G)}=u0x;qmmiI#^g;9zpQHBRej^DS~+f9S!Lz8aWxfl z7nPUcGp<-PchU9Z#$8!nn>8#rU*%{Vo+W681h1Q06RfP7TUL&jky_o4^pcrM9+I@9RrAiSDX*M=c6oidtGHlBe&LKMuDnSz3%_3AD!!xBedwki)Xrui}Gg75cH%AXUx3lLLtbTgnlWw0g_q1Iy?AEc%mP<+RZaQGGD=GdLdv4b@{^@k;waBj-cdP3 z;*>=_?4t6T@)k{Z?vDp+wS6W#$Z*FC&NLnzfvUtWARcS_yR_3M} z2dOP1M$5t78BvQaD3IFR_YeB#IOtzlS#`w`W8k2_s9cFTxAI73;H#I8vg^l2zq*QY zDxFtZRaZ8$<}+&w`lD_7NlgEgJVRJ-2#* z^t1cQZ`b{2R=qM->}TvD=?{!N`Wczimwrt510;VC`Z3)Poc^ehHu=RrNaeB@z(9&u z>}SNG=?{p!(6`%g`+*j(*pJgc+vpFNywJD%Pu0Fe z9nZkYC!!zI{gI(>_n&ji%1W!s=t|Zy_!xNWNWb~gxbhYHHvNwrFb_xhI_M9Wyi@-| zKUTK}PCgO+e`ooMeaD+}^)>Y13G;sOj>Q{_DGaTguCy)L|*!?rT zsd?p<0~OlVjdsvypip;p`H`h>_y5&%>uQc9d9hEs{V%GbS16;_Bb5c{+x4${|IBO6 zU2tUumNalS(6{%`WiT8ab03L3P`>v1YtlawlnoA?o{`rW}A8GGD$0m=I*rRIaj~bCZ zv2OnS@%iPt}hr_aIksR!^qc1d54l@ zWGSls45AzX{lpD$5*yfOSJaV~FL4F?kIEP4fMX8kv&&?77UTaTpue~V$mw7QD&-N7 zFV6lf`QjUx&o1Q=kT0%$V-4(Qm+9YGzRnKDK&3na`a4_)Yd|6%3Hc7z!5olaW+5K| z`9>t_U>^zDM8qQ@pS=Se9bg+&um>XG z5s)u#fg;vFP!kxj35L%oe1 zNWdc@pS^yFe6|IK0m*iR`Uia$aQ>U?hxnKO=K3M>*%o*PYJNw=KilhvL%#op`Vlw2 z6!~NUI%b11f%)01$q}f(3FV8~;D25|`vjk*Kbs8>NWdeZzy546_^c&-1muhB|Ct+f zV&*p>>pLRjw?y*A%2;hZDV4pyh5zb8n|0p7IG8bFR84j1 z)iu#Yz!?{pj$#Y>h|%#|$O~dicJM#PzI^zv3gO^C2L9Gcq>$>fG-$>jTV6k}yjr&E z_laTGj>|g#G2)zP0x~COP)204HF#mU(%K;?IY~)DjiK zk-r>U{uW$a%|^{KR$33DRvaC$O)I8=-?;t!u!}u&aut9Q8gC$lZ_|P9olReq*2OfCqq^fax4C>H%f~ z{X5VDupU?hYy!>!?glmjdw{Ee86DUoumsovtOxD^t^;PEmx|wVs}OJ#aGk(sDR+U- zAs_nk??fNKdf*&j=tbxO*8$g%&-z{18!+p4$j5=HoR>J|4Gg^ke_+QS$OmxUp590& zdZ>7vazYQGPHw|Q5B@iMBiYom-Fx8=%z2w~K`%{VQ&c)&qNhD}erV&Zz)1fE$5Xzz$#za1Ss9>;{$qeWxHVFauZ*91d&(<^op% zX9Cv&D}bATOMo4~HsEgHTA&Wx1ndFs1p1GTL^^>P!2Q51p#N0(1BU`bz-(X%FdtX} zECJR7D}hbG2H+~-O5i%+I^ZVY6TlAOF5qt9UZ4)_0rmh>Il$&WCK3q(Gk~LkS-=o5 z2RIuT0#*Y{fQ`Tk;3{A}a6PaIr~_944*=Hz(=*`@%mj7-bAY>nML-=m2iOCw1^T}b zi8KK-fUAL7zzx70;8tJ=xEojk+y|@x$^pN6;1FOFFblW}I3BnTSPa|*ECY4`>w&w0 zD}Xw14X_8e5$GR6c>^kK z0XG5H0y}`4fV+V^fjY1g*aO@T^dC!ka}Y8EI24!#%m(HF^MN5?39tlM39JA%0PBG( zfla`5z*WE}fa`#}fSZ7OfgQje;BH_l2N88(5ZD784fG#Jc>^N_YG4kq5f}ol z0+s;R11o^-zcBa`9$+ode>~+6%mA(i zW&t+eLc32+~<0w@PN>w!anO~5SRD&TnFI$$wy6R-@}0jvk^2Ce|=z%{@g z;6|XI3yL~`6<wh@&krWMDJ(92e=a00ek}JABui~AzyQgaZ#qIFJjjUH-3-Z(s+oUf}7} z6TuI|UV#;7QBLQOJ{viK6~Inl&M4{w{jgPIkOx?QE_~^ats0Bn19zW?{Pe?eCXi2o z7f^rchgD3XUIIJvso%g&1=L&mW9ueE7r1H)bm@=vgy07(;U>e}3CLZ9T)>{`=#zd} z#f8)dU`H|KaRKtq#D0NUUnhUSk`nAE7yM=D3ApNV=;pz%6uQ9rxzL@69nM2Pz;)%+ z$4St;5PRa1-6k7;JWWpU+Ite@5Uad!|xvIm$ZMt zcKmw<@D*S^Fq8VR377-y0nP+w-HSd24@?~n-_`H~b^uF&6+gf}fc_s+|A6a&oxrU7 z(F64<=SSeN<9cBJ7}5bNff+x>&Vd!c^}tPQ$*;im*q_+Pud#c|zXO;F3~j_uOhfL6 z@i)K@KDx3BxchPH6R`eC=oBGGJHLUU&B!VF-NJ96e;fLk!EfMNU=y$tD1So?;Bwz^ zk;`45?mjU!+27_i&acyDaRpDNkLc$mEq!uY#?(N{b^Zp|1t*OA>ZnXwUL!q4>I$7s zpGpwspU|DnlMCLs#nuRrIJG?M9;Gj7pw#*KCf?UNaI3+s0Y_C+f0A|s&rWcI4U|f| zmG=&CWj5Sy-ZLNTjT~j-g1~(|L2#Is%QZPIeT8RAT5#duwDf{Be_o1ljz68e7ZK-Z ziNl}p%mi0r!)1WW0apf&YDt2$^yQw4G*OeppGjB~VRRYQpTw^Kw-Ov~-;7_P;){;u z&wWF2kt%`Yd!N6VD+H`^zTr z6iF-JUElc`(uxk(leX;%v;36K>y%7E!a4}sO4vf)UBzbEUQ5{)Ne;*k=zYXVf3i2S z11S2qL*%|)qFLVgQr-n=*-Mi=>nU*TvCt}T zsZy>W&t7P3fRDWUzA1c&zFb@3YxUkvkh)W%$wxf+)bQJ=o7n17FBQ}?!)~ckzcvy# zhq3qb^-o+mj3Zd}X3YEM+!C z!#@%CRWoj@*vSg1Ys;x?SxdDkY1y8|Ms6u}!@Q@ZRHS7gZWLkI+#G0)XTBhpx@eSF zNXjcw`RAvtaeFY?1V&e&%6~nyvYBhxelWSFrp@upcgR(cQUS&;Sb>yFF3$nzZGhe% zP1)@ASd}aJT$)5x@YD@fCW!{3^OKdVX33pbE4Vg3&>gwkXnb4I(rXrC^bl(QO z@ywgtDTbl!+fhfU9LteO)zMtfcN3~>njzaBXtgoNa#ei((ESQ2$K_Jrv0GERXwLFe zXcI(ZQOxudm-yk~$^3_p*#$xYPM3YlW z66JcbaCzayP+D%B3s-#i!q?9n+Mg2eRqdXtQ>xvg&G2kH2;b`x@ttDvjc+=X-Rz+Z zvYC6lRobhCv@)tb(~UISs~GPBqrJ-Y-f*b)YB>35I;}S%U02^Q=s7Z53w{?J!vo~? z|4$uD9qB-}SD0UY4judMVlb!jIwQV+F-?5eG|6jGTCR6~;k~7r?PhT zMlOo-Reg|Hn-=e*Z%ITcKQUj`|LMy&&*=Y<-(2RdM~OX!7$_+nPmSt$vecnC-ri#q z+tXB|{{y`(UpB@qJ`eN~=s3s#V)gUAkxBi_>#{_7Elix(^u#(g@|uB;SI)=1c5 z{uKI|{PtY|&9rv6y(K6Ezb}A4X02lmePP3%66x6-|5SSmg=OEmI4#A~m@q)Kl}jK! zlTLcpZq|CFeRs5Tef(0jH{Ev-a!ZW1^Mx1l(yHxwkr6=x!4!YV=PU5<*~3-r(qB{c z=8*Zk`(S0|t%>zKoSgzG$0yL|hO2rbr{bi2A2RW%c&T!9j44A#`_`T0opxG6*`wu{ zj_h|Z=dup^zHVrybtl>LJ|6r=CMVYYr8n|t-i4>?7aC(F2Hnz|45j%erZAMqm|~7= z80<_{uX9MUpY$cHVd-Xi`#3me_t8G~Wk_6@!1D6JPwImYrMU8;E9=vH;jv2mSGJ)W z`}iW(52b2(ub>FB>5|(A7?V<@EY}>vcz|`b*QJie$}(|VQ|+xyT$WQ(ykATlB7-4m zzh&KYBkOp_OPy@XHhIPTfx~X6q*Z(K6H}a$BID7LFFND?wXtR)&5ry@9h?Jh1vrKW>Q8XB;8u}Vx?A!mxF&Eb9k|s( z&w<+@^c=XY;F=t`-QXG>xP9On95}hyb%_Hv1YErXmj$lYfg2C5+JP$uSLwi&fva%f z>cNTsv+H05xH%5o8gR26xQ*aS9Jmf}Gaa}+;EEl%Zg52ooR5jbkOP+iF5iJ04ldV$ z%LO;yftv{~$APN=H`;+)0xsKuYXdjjfm;hM%YoYjF4KYA2`=csb%Gn}!0iW@;lTM% zz`r%)1m|+#WZ%pI_RHAqU?n)&Lu1FS1GnFSdjedy z1Gfv@J_l|uINgEk0k_wIOJ&barvn!Rx5t4S4Q{ss7XtT+12-GoE(cEb1?_a;8o_lq zaI3&=b>P;6Yj@zPY6q?s+$smI3EWBtZZ)_z2W|tn6%O21a7_-}Zg7nb+&*v(4xC)Xy~KeV0No2?Z6d-t90PXz*RVK_29}JxE0{$IB;vg&3526f-7<0I>60z;P!wkcHp|f z6*+LSH#FqHWq`|f;D&?Cb>MQrjkn>lsp2!i<$(K!%r`RZST5_1YHiFrj6SmrP*@$C z#6%`@qeRK%X(ElZ2j}x1Kc-n=t+U0cD`gUb<&S{J-htqV$6 zCt<4z8zy1XWKHwyEC_CKiJS)r6aU*TVT{4e^-xQzL{STJM$ ze>mZ7#N9*O?@HX~h&$aJUoQ7f7rh{X8JjkVIPJtQV*ke768}DnHsdCPcC8hAJmLF@ z+fLkTWK4LS5!XKEQTi)lIJgKak+tKf0;i;eNWVVFf3@_b#I6_%CSKR@JWFEABf3yf z#JWn{$WrXB2U@RSqv!K}Fng1D!BdR(DViPdmXiZKjL*0Z*@Q7Wnc^&`w=gf zcuT0$hs#F=@z(Z(UK{bA=tsOw#CxS5@j8jOuOIRJr%`{|uYI_DWD{>_KjM`TZ*)K6 zH4v|;AMw@^udE;Ob`ft$KjQTeZ)HE?1;0Z5?MJ*2@wWCOUN!Od^dsIX;_dH8ymsQH z{{8UfrV}r-AMw&pr~dXMUJmhQ_9NaL;#Kw|UK8;e`w?#g@m3!up0vxmiMNq>5Ahz~ z2lL!x^}r_5`;vCqM}p8lIJ+Tn=_9pzXur+UL!&Kno~&sRUDD^1-v2&l zT-;WA+TIni7b@B(%Jv@TPDnu7b=jNk=ZwT<8b8!p$RXzI=XfV-iDv&vN>z95g4Xb> zBWjJ<^)=~x%I>wvDc=~pT{eQ{^S|0J)I+?P#G6PO>4z=#R1vQzh3=OM&!EHD7#Chm z_%szhnk2Fhd?Vonl4olU-rSqvJ=W~y(xX3QnZpvjR`(QsxM(;mk5E`4)j;$HQ z)-b1}ZSZ(LWuiUN(oY5Sa>>UM=9eB!g5JY%^wb==V?KXsTDRM?H{lXQVah=^AE~Kl z*tmv&mHyjDy^)vV^DJv)x6-XQ_D~U9=CewOTl>%0KFVTn`ykQ)PWIpV&Wn>ZmiO4+ zk11(uyxtRK0k`iWl-jcxgk~<~keu8b`4;a!`C<`??CT}D;LC`!`;*?t#lm+llOL+@ zI3?c3r>E`mdOdK{_{KcD9RI(v{5omP+VX@kz}#gWKGyc>3TQ`9cS z?lusB=Vuqzs{h42t7`b`X&oyee18W2SGOKUI)KL!f%@J>yBHum3os&oD3}z z`Ld5V7g#(Gsz-c=*LzN4MXJ4jL1@-P^BVZ7ao!h%?}oT~BYu4~ad!DlT_ziR6YKIR zhb}`(mwQOR#?s|qn0&VBG6ektLZ7p4Z}IMXjd0o?bB`PA;EXkADT~I7$}SbE(o)}Y z?+P{+Z^7AYr~2#^k8F%XLua~N&G3>s;(I`NnX$hnv8iw>c7Ym4))F@~*yQ`&f$?pJ zR)NL0^w50w5x3pqJ8fWmbIxMVxW)JQgYzvyA7#YNNr@P1jb7radU%L7w%YS>La)n4 z>LBzsLhn(nH*&7%`Z*R+64d?O#K}xGc|J{?0rJe^+|Uw>=dFEtNwvSg0d`ou{-nImFo-h(xNy54}$u^n0-N^$l*%p1vD+4WHTo zowt0wk(t74hw$3qwr|cB{95A3+0U;Fug8f)zp4)}b_gs@n!@DQU46C+7pVPDvNbWb z>pKYD1JHd6-pY;^3vYW2qumNJ(YO9++7K_itBiae(%-H*$}>5kZbM49)zG^co{f^< z3x(&JqwKns@?1%rdd@U{QS4|^KX}qdI~32o(EAQNXA95ch3AGoHsl{keL0SKO5vH( z51wld&9el0*IPW_7$W)X!*dC7IypOdzwmsSIESvIQ_>m^&2uO8=2|=-5S|Tvcy<$K z=n0WXv+%sPA3P6}&)iXL_qTXfCC+CVadJ4zc#QCzcUYcMKW|KELiwiugWd>uazu{3 z8!Df1^;2wUH*xl!6p1_{b>{Se^UNAeees$+Kl*~`HjbzG1UZA4&6&#ilFu&U9Kt75 zlSAi@8|ml=p|cV?FIv2|2(M~e%{A(!oNpY>`Ae0*-x$0OQ7;dxQ~wy3>mG~et$p(+ zIvq}&hEpSv<0OBJ`@yr#%_)rpZkEx5U&W@LWTj;hY0iJTDkH z&u-}DSv&)Yc@8-T`#H_z=^Z%FGU%OT@qGE1g!ybDP9x`5RX%qR=g__&A5|Svx4WVD zPmihF@Ac)Gi*64PCz~^}Nm55zh!b0DQ2jsp%$^c87&De&WFKvaX2vJIK+?;2DVN6M z&+t)gNU89Ng$s{41njYRT=Lm?tcAu#i^my#d2A)T>8oZwzWmvE_-X8KwRn7Vbf0`= z5kC41lgE36e+FGuLgP}4$Ckc4RuJB4@p$~R@sM-NXIeb&i02{oshjW>!#OuAb@*1o z4{c{t7-k=G{FFPEc|vz@qyXB!ON1Zea@!#`;aNtUb!VA8rwyFvM(Ay`c%GP;=WgO` z&5lGKV@}H#=m*bsuV-39XEiA$lRRXN<9-=)#1)N>+{KT3be z+Yi3z_fUP8HPD++c`k#tuPZ&Fezy{*o-^xXe8hQ!IEO3KwnOtAavo!1c-}8OgJR7{8ndrCgRFZKPvI%-?;W=LPtMb_p$5Y0u>xol6DH3@` z;=FC}?9&g1f%JnJf~PUGa5k~@AdEJ)M`+=be=d34A$er{9qS&uiop+M5Wb5u{vQj! z=lYSy4L?s-gK~_-^Fg_hZG^XRj~9cO`L3xJ%$6siP0{gKwM9yD>3e zP6--(b!ff;-#U1;LZm%zxj6H zaP?1}GfiCQr>Qa0O6Vm~Rx?DOzlNU7+t_?6Md{i^oUQB=Xi_#p9P-d-EniL`7oZ5o zTE3+3A^i~Ud6*z&{XIiwd-~`(+qEROFFat$`J~T5e?!;{@QI|aG1A}8d4B6$GV2!R zIY$|jcK03r(%CJBP6KpSa8JfKv55-|I)^9=byo0)GAG@4LQl<;2ch|j$c8WZj>t9& znjA2+>rdqGA#r(5!KcECJWt>l-^4!)#VRsiJWhkbiIGkL-*H`nF*2W2IB z@$FAjWxvA18Emx{LEjbp-aOhr#w$AS;+t1^ID@?0J0mUVx!ag1W{OSC3^LD1lpzzb zPu3JLdo%vE(fu^pgsmn_%Fv)?oWUQ;&mzLInYTDY!qncDOI14gDRe6dUqf1^(#^T; zi=uSpUboDHq>bErlv_K`dym_VviOTc+({36a(9ZT}$G)5+SqgOm>L zJ;{A^P4G4kxzWDs@&3b|!8`i7QK?9h9PAl21r}@FTG;D)!R_tzGGFf9?&GAtmxJ{$ zd%REjTyJ~4Klizw^Lpt<+$L9rLGBV!^flVg1Fk>1wI2msk9)M%fa?X1c6Y$_hEKaW z&9%>`y_n*9Hd*6xwl|ZtAEmjL`?cG6AEZ5*;<|INwmrqQX>i8I6j$fq6MvrK+IiH^ zJ&N?1^*S#fd$s>faW!kOxm(k2PIdj-ul1z3Uh->irMPY$q`jBo>PjV0ggLf^mzAE` zl+lx3?QzZZyblBcz6-EEi7=7hW!es(tJ!nu<33l5SNo+>q)&2BlzY!~pID;(-Rr%A ziwN9zy0r$M`)#-9O|Q1iLky40eWRsI@vo74Pji1^miDOIRju8m-JrF(wO_iw6d!M> zipS#LcZL$+6m>-0u7&EG}Lr za@oR{v@gf7qLY7r{FI5>iyrsw?xZaaeWxSODcV<@^89P@zvxcAK>ME0{gS)I-D0x> zBX9n*;4wj)=;SeYjP{1d{q4)CgYh~#nB9!l{^D_8mGnoC_d4ylSRz&SXTsxrZBmSq zsn@S)&wAXmlAel1SNirR%=ek@FE7@blicgw+FeQBr5^46B=07V_KPI%D_+m1ns>dX zg|#S)DBmLOYf+?SuixfY5qF!%bFpA)r@-R`ML?>hZe z!g}(5di;~z$1HbiJwEp%?xaqi_Zjzj`)mfJ>PV3CJX;&>EYHuDZn`_KUi)yc``7d& zQkcxs9!&AR=h0po?ERBZ``cjmyP9@)ig!%% zOVYlZ?CnVsjGZR!wTAy3>#U>5zF7M-S$yJOlf4ae(~`Zt9fP(n zwx)W2>eKe8dcUt}n^N7kC2Q+b-M>%PRvhK+PWJ3c_5L*_9sI{B60Yk+6+nDW`m1g-sk^mz+}_`Kv`cJiK#pPVmr8Li6|nZI_q!_pCi$ZKqq??A6|KCw0XW z-KpY2^PAclw`(4x>gaj>vJcI*D&Cpyq2sk%HTMnLcQx$}42yE`czS%=C*GN1pIzEo zi|!@b({9&n=q}W1v={o&mGu<5k|~e6$Gq=$(IHnq2Y+3=-|brMX2e6_#EZdRp>_CK zoqj#Zwa=}+m*iUN)f$prpL(?i{H{Gd?bm+SZPKg#v!*@mcYP;G0$)v%hJ8tb)Ue~=|dH*TCl*_*?^@Yv6MYe6E52hc!_Bs*(BbKNzt3j|QBx z+kkB*%r@g0SoY5*v%t*XuDgvMX}1YGO}OFv27bd@tH)}joMWbIH{-b&Ey$mhuH8&m z?MPQ|rrThqOLwH(Wv0t^q-!(NtufOD9qBsFblpFWmvfz&uFXuB?MT;c<-AvbD zrptAtbEySC)?pp#cAM#{&2+_%bm?ZgY)86oGu<3B-5f`{pqZ}wNAdad`;GD|Hq%u* z(q)_JHaOA+&2+hDx&}wOTq}Q$bU9|aY%^V(BVDnTKS#P^GhNV3x5klfj+H;gWcI%b zGhMowZi6FTwUs|dx&||y%S_kqNY`NH&yjAGnXdaTLyldJbZu7t9O*Wg={n7HosM*C zto$(ow*PgQ>2{gvx*h2@Sow3L>on7~o9SGu47#0Gey#jD()F0>Hkj$s9qD#i`E#U8 zA7t3s8Z%wck*?Fq-+l4<%QDlond!0}>AJ1_Inw3+f9+ifcw|Mjz6=PXEQTG~Y*27; ziG4fCBoV>P(l8;JOq2A6^Gm{Z9xFD!VKv7im1rf!Sh^XW8H0ndp zhZ=X>AfP-E#TTE7hzReTI;XnpR_;xDsZP)PzSrM3Q|Z6|sycOU)u~hK<#>}EuS<(( zy`P`Y2i*B>=XhC;7t!K1alGKi-SM&<7KsYdpTZ^<4tMtBC>p1yg7~+;CRzoyg^yMTioS)h~qVJycsQCR+dkT zXFY@Ji^cI~wRn@Vd|JHYINrj$NRBxz-jpn#7B9&0<~iQH7H?XX@1ySWZQ^)y9B)C3 zHzUiZ#T(>!vmDRjex%s`WcjpsyE)zr$7|B!&B^j<@uoQ5G{*~Q@#bauKH@IlEgWx( z;{~;N3$lD#yjhMn$?>|hcrbA$%ve^7cMr$Qa=eHZuZiOYwRj60Z;;~+YViUbZ{cQl z`Bopy{U686YVm>`Z$^t3;CNjeZ&HibCCjJ9>)?1njyI*ni^%e6@gf{A!11QFc!RQh zn%|@L761SD|2+*Hdf%m|?K%7tw@Jz0KYzz*C;#x)tL68V2-y;gtYCkJ>$7UL>#Ma2 zH?@`Vna0Bj9-poeZ+zAV9~|}OTS;$x+6V7?jW>VZ2cNvin;%Gd6ceAWja+~v); zc6;N~K6uxJH-Fv-pWNfk54_eJpY_29@#QUEpVxWg(>{3DrQZB`AAIul-u%F%H$Llw z4_@ZY_bSp#V2?dTpXKt}TPAP0be8*FdMii5IRgC1@3!{+eC_+N_I;Q3{c`R5l=l6D z{2g|Ziq9?l{UrV#gT4OvIfMc@5Kn&`%HK~skDlwZ`1}0h^!)_>zJ|l&Ib8iu`khwq z;2sdh|Muil8T@mBs|l_z;s@_>!4GWv7oX8*P{@IG1Ivf|&hdl$PVrOh%bMsfPSzUa zf*eIO3$Eo5pJO?kdk_5~@#7NoUCOx^)+O;HHf2I6^LrAG<|6)34FAVvO8O4ljKybx zzrQI;-~Yki&y)|EdH)|YRs*{aDb^g9AVIG8T^vR@9ON*|;UtGs98PmM!{IE4a~#fd zxWJ+H8OpYa!vKdt4!byva5%_emcvO7r#PJEaE8NK4(B+W=Wu~Ti#^aL4g(wpIqc#v z!r>r?Sq>*ToZ@hr!x;`|Ih^Bgp2GzWtqI}Istfg2tT(oKFqi{Qv&$!7{7_}Cc(yYGnDUVH5}i+ zgYwKB1QFqb?@qx_jPY+Wze}KS9+&a`zd^t)jDMVQx!!d#-ndgj+~c~{>d;rc9c`cA7xz5|49B@z#%}sjvogE#N|Abvl_ z2Ty}TgZx2_e-Jn}UidWQS&iQTjt}y6e2(!+jgS5s@^#z-hYj&5jengF{(SJ;kUy>Q zzv_ecgM*6v8IAv-555~5VC2tg{Da}BmKXj(#^*GC8&quM>-gP_&ujdl!-=os_`VQK zXF=m%b%Zy5>XC%Yd30GH@Tvw(N5^}QB3#bbOa8q+c=l-G%XIe-Zzj!!W@qw!A&5MReX!uYJl?>vS0 zI(|3fa~eN>D)Dvv3C8C&{?*SRzK);zT*4PL{_Q^aIj0d{uH(x3^F1H@{L_gq*NY|p zULSn;dBhL!x~b$p;)55~5MQo;Oa45)ewUX1iO=`OKh1bVT zYW!_4B)*Q{%Xn7f=iyE>Okc-WHxoXo@!#WvpZ;RvPig#HeQ>=03iF-T_}}%xhiu}{ zX#BtX;BOBRe^%q~-{Ot$VSG;GAJ|HK9lw_Gd5yoOjrcnL4Ili~YrXl8`QSISd-Gog z4j$@L&-Z>G{EeO7{8M56#VegzANlx8~>;ezGe&Y7uY@= zX3^(%#x36OBk>nRh~K2)vy2BceA~;3AJp)B8Sm2Yv3}x5GL84W)&NBFFU&oDlx;o&^- z=QaG-j4x>Tt^)Bb-hUmxk}zMf`|{AGMqCK@Go^ z@vMgTOb~xk!yjgRO2e<*L;PtCKjXE8&uI8}7@yVfkxPg_r{M>@j_`R6{}AH~8ousQ z;>&$(QvbhUT<%ko_?ur(e7O%z;%g=em;1~lemCQCADP5QE+f9&CnoV#Zy;Rm1C#g- zjAwa&*emxV|KTpi=Xn3?*#ukpH{$$flQntaDuIA|BR<~%9R1;@4^jfNjJLgs@HxhR z#Q0knpW%JEGX2n-DgAjZ{mTHy^cOV#^DifUmqYS^J10K707rgsn&gq`pY#^uPct9f zPVpH59Qj#|fAkf^w+1PFaI1(9IPzyS{_$55e~|g$u87aYfD8FG{wB_dne1!=Po4w6M$p- zlgyX${Db*38vg_DBK|z{r92M;F6xiQzwSEXcO~5N{2p*oe|W#Al;^$gCjPX>e*|z* ze>DE<-$Q)3+)3o9v@h2D`m|^^rgtt;)od^*{I-erof~Qf02O0mw zH|YCoIGqD-BmU9fBp}838o+U#ck<}{1+s?m4UBg&-of~GfgfWv@jf+)-_Q6a4d3=z z%J(wP_q&`<7V!P7W30Uzf7R{8@B0rT%JfeM9Qg|x|C7wWocYo&{Ri`}e}d|ROy|7M zQTo4RevaiC0vyv{{VzBF&&=O^2NB=N{3AY3{4S0EKEUz0%rjrgb35~QYy6Hc5WnqP zlyEDj-v>C#Go$f;#Qdbjf0+3XY5dGyO8)~I|8l@F{lJs%@*e#~;{Sm8?JUn)z>&XQ zlILYC|LuTd`qLW!oUarA3XT67z>$BC#{U=d@6`CGeuMZ;tK9N`9&l`52mYs9 zo?kJ4lg3Yh-9dhs`Lf@C2jD2rq{crP>;m$y)A(J0BY&^P{{izK)cAj8{({E89P9$7 z-*z|2FXj0-;F$iJ{oUn#8MH&>znS^6eGLPS{6UTXPv(C`h~z&P1Jo_+W|*@RSjpVSLTwuge*agI+_{Z{+l+1%8Yr?@f^DzwoETm*=*wWd2@(gI(3qKksM6m*=^pJiih+_)!{v z=pN$Bb6!%OhXfAon$NpSc?v%#zC8aW<*|N&IQSJB|7w9ZS@K-i+gbjTe@T3KAA(H( zBLWBg^La7Z?wWr^e0dLo zKF==GAA6Aa@*Lb1EYD*C2Ro+m-~3<1m*?Z&%KRgKhdA^L8vow}4*KVFbCUl;Fd)d6 z_Z3Kaz9ewaKcAa>8>heN_r#a?6iEKh1P=OVzI=NUh)Ux z%Xcj$PvrihL^A!e|3rLwj!%~N zZh;?T$@>Q+|APM}zC7P2%lojv!LR0XfrI|}+@Iu! z{)hPTo&lNu9RdgaGk=Po*Y>{< z*8gdNgZTtW{Q`&j&wSb5gO3wm-WMRtdxyY5|CdtwlE34h#FzI3NdAJrLI2EuC(D2N6U3MI z14#Z!|3Vz}|9VRQUCh5-;9&pxoWA6*f0Fp}T%@d@a{@mG-pA>#&lf&Le0g3{^8YAs z7?)}M36KWmk>@C7dpUZ){XEYF90)l2C-PpW7qI-&5BZqphrHM)odBmJ?}gIS`M8!& zhfg{iIGx#hSP%}vj4x>TcEv*e+%e9&_ zIA#?-$7fpdoF&87iGU-2lg4iq{AU!;X-fV}1pin|Ki{^2(}{38lD|dZ&w>}MQoWUU z0`Mc`7bUz@;IK~jZSriP`xBq50Y3%W`vQ+^WP91m_&ooeK4KCQj*m zi301;{V`wI|M^V<@ZHGxIRkLy&z(YgmhCzY_$km{rr$t#C(*4NIi045DV<~Z@qAU_ zOi}{4v{=YL`ZSVr6aTjV0hDj>0!rr>Pop220r%3+C4k=u^|piCi+sNC_2K^>aFoC6 z#POoDQ@E@%f5R zI!&wb`NH^7tIz#_qaK29Avqu7bYAjw*4vK=XLVTpfFpk}NB9j~u1^7u^}*u$@M2D9 zUZlfcl;CO4p!BT=C>?wkDt?|TaQa*Q{}#YSJ?S7Kd=;PX!ylOMJh!7(j&#t$#J9$Y zILPgBJK$c=Yh3Wv9O>^VAO1}~_?H34=QX3X$43Mo*8LwRd8FAr=n!vtULbIIEMz%Lng=_9oiVew2O-%dSF;4pr^VdDRjezuN%CYS5kgv)lfhw-^~!uvU$TNs}?nQ-W7#OKF= z<8ztj`Y-MLAx%`SnQr30l=&wzzQDN5cMafJuGwozKsK+|7UoC(KnYyL@_&f=U0swu zZ=bT(9Pa(x&lEWHBL@;6-(iTKZGg)@h!Fa}065B%?V$|g{NvX+oymU?@Ow(m`i{WW z6!>@M&p(5R_#Q+29B>5bXBuvt#}Ak_@i`rEY3@^c|32Ve_2&WR2euF&hIQieoZ~1R-A~xe_#i(=X@7PD?v?&EKKNe1v0Ss7 zU-}2e@6!75RnPKH|5(7i>i>)n|J%%;XZvY$c~3u{(wXG;yPolFfP0l|7xQ)de6tV# z^MDKgfjh?Soc<9fc&C4wz`+i$q6diYm&MP^eE9ER{`{BeIdXNkKFqlFCBo+^u)Y8| z`optapJn}diuq0dNklo0IQ&F}ld^Pib z$?43TOXam-4-U z%D!Ti}@5%ES+t929OS?>3Fcwv18aD0w>yErVsILmV=%lT5ky~-P9 z{uB!c?vVIg<-@;)`3s!>Ih_8y5C3uI&vN_a;gmIg3h5!B`K9j#9H09w+H?O6;8@;C z_S59}^uSZS``-}YsQ<~sNs-^+a`gzDg;s)B0glgQN^37y1AZg=^Xw12l+*b-;3&^5 zcd+=*T>R|!9Ljg_heXUU{}{%nzfQoTjGw`HK6e`doSYS7eCk2U?`O>a zI^#1uV7iv;&*9Ida$UjmW72NC6mZnf>~ATZZ&6^~AaMSo1pi?E8a=iHi<_98#OMCKHz_I=WH9LRg^C{n^ zDDkeb3cs~_H@P%f1!8!I|L5(>UWfI2lGDyIM&a-Tt9bnzQ2(C z<0*Z7pEG{`$avG!D1k5Y^E&25q@U?85H9`jHo#F%ecUw6{26ux->kbmr>TUMcL)HhsOW>gYKT-O!-TfEfD1Xy)sGt{fc>^z|^3MK^ z_y~Ptffbkh?-9<)S(gKj=?8iUZ(;erE%83WrQd#V(7RkC0*B`d>n-?s z3)_dc1CHs>_EI{>($CiC8Q1lEpHKS#V7~6>G~3?ttOp$Poj;uv*2np#efU=j9PHRH zNX|1@&o}w-zX>?j+tut39LMQD2sq|D#r5HG#seY32U!oYzFi2om)#p@e%IwB&;6Xv zx)yJK8gP-X)*k=Hcy=Qd=qyUkI--sBvz36GIsNs33p;Z+;nFX?5O66oQ$_Gjzym74 zf8WaKFN{$-tXAviBK^e?763+4Sm2B09QDE90yxSum!Wic*lgX$cz`R^-`SyjJ{Ul+=YAI8BAp?(-bNUo z*-p3|7hL0$&Q}1x5%ihW{KKaJM}K36{lk;Fh^KT?zFkR5zn|;>1mnT82{@GT171RU zn`8TVC*vmr?p06D1RTpX%^k=F=3gz+S*+(Ta{9BdzW_g9<_Vp@03HyC`@dCZa{Aof z&*qKO7w9Q{736Z!ZQs;DL7o?)4mR1swGp;fio1$NiSTVZW0$ zFY%a22kOtAr2lOcScgJ`#d^D-jW6PWd*%B%z){cH2qlo_eE$bE=Ah;5=o=_>IQ>IT0Z84Ep1!uBOeSAgo1e%R5@U92BA3hLoLIDw7|G-&!UKiY zY&4nc?ipxx1`2j?Je|CFJmF*ux$eFJ+gTe=6r#zL9m*HtY9zZgo*0gfrwUFykxCR2 z-2S{XKnlXD&08frN9JLME0;Ib->ed^`Q@ zbVDvXK_t+K-C2yA&2EWj#uA0xM1N0*{IeP2#(@_KDZEG~pBN}a$Fhlde~)b|UyJmh zLhprQToRLRaRJ3Bwh|?hNu~=MQkik&2TR|I zWVhgw93sJsUnRZQZdVeQ>g0+9dRX#znTWksNn=Ycp2+q0w26=z=k{({zpmGD^5a8J zx5MO2t~r*?LLLK!-VVn}Lcx*+_zIQQ?sNvSz=JCx6LGFqx$a0`n|R1}>sV%I!WjZJ z11FcTTi3&%ebJrCktnu<@QzShy7U%6L^u=1QOB8EUA43<*>p4doJ|!bMY! ztU{`WY7oenhFa7%rU;Zp1LeffLWS}TX>GESNcswRmeRg?+4( zhfcOZ3NtHL-Sw3(K-U;^#-iDMOJ7yWWlmqg#q~?IV2v?g28A-FsZi&Vnreum49a9q zPaTW(RI*l$QIj!|>Z+xZE!bzYRGmo1wA2z(>JpA)&;?b^Q-h4TQL)Tv%U)Vr4N{g# zsm$q0?P6rjDw(MUsmh>G_0?3#F6={^s!}LpnhLdR?N7B-jWOw_Br>NXbr_HBPSH_g zRAfjXa~e|T6~x?Kaj4fA1(}hje)=gj`+Y+{)yZQ{KkCRl8jm{}p58LR(G9-{W4XG9pHB|B&8>1jI^3+d1)mg;)tUlrMs!kqr z`cZ8n_VB}rM0_Y3yQnd>$AmQIbfXV}3cHf|LSqzDvnb}YqE298jp4<9SeJJ~@y2M! zm`KL7)S}m9MN81+ar;6;RApE$WBLlIk1!9lO0+d6njRTXMRN^Nl{t~jX-W0aN?J-K z(}_kY$&^IKbY!a%!J1?&k!ncwsZoyl=p&cNkB=o9uaC;*FsBdIh0jLEVVhecwjtRy ziD66|A=R;f{d%zf&?#gZqLJD~F{c&PhKT(}`9dz592tdvsX@vyC6PHDsoPZIxLdD~ zaWc5!uramAh&aZyW2^oQYo{T4sZ|hT8fj52jc8L)UvNut-butq68pf~O^res(^N>U z%2KF(q-9ktjxp`HDm07J_?A_LAjUM}YFVWb`EVvv$mU=JXhXDPQmFc93dc`0D&L1R zRijYLYO19$++qjUj}H$gavNa3KJ3p|_e9{f|70|k+#{UgkQ0VuBY0k;*3J3#$#&V& zmVHLSUk59HKB0D5_94B%xueZaJekkJ^q{d56Y3g+Se35kL`hvFQwMb@S#@VQ>MokH z-MzwdIQ0DzwAZ3KCD^fPo1gcob}Qv8)xCXE zyi)CJw0NdAi`Jv&g>;unF~<#VwTn+SSF<~^E=toqe2*M-xuYobh}esgi?J<6iV4g zQ_*gtdI)EBGfh1tG`5GOF2bocw}#y;^^mQ$-5Yh6sN($-b&*Kzmnz*!Q4fJ?-a$|o zq10L~mWis{OHdct)LE@+*YN8hm}`-*^5ye-h~!$(lFOjgtzXweJR^(7^$^VUC@Wtk zt%pdiM_Fw?RzMb$+a8<)+tTot%#aBWqjPD0hz ztjq~jqxmr>h!F#AP8?Sas;xUSCzR`9Ro?BJ6U6nfs&$MEiet!!G$@feSy0u!VPm$i zww=`G#8976#p5$`Po}n!t2sGbiwZT2?hQ($&Lx#3s^W~1u}Wih2B}V}Ds|Jav ze#TVg8r-8ul}=9@)Q-A{fud9~gKJP4eGa~=neIBuQ`MS)L3z|^s_K_d3<{+76q-Pl ztTh>wNUhK)Q5CCl2BlFeG&Zk&sY0VX`%;BQd8%6yH~7HR3ats$mpaCl$ zbr%n7QS~Pa>mi~4_&!j1u0l93;kyG=6aNsuaVS4 zW3ES8?P^I~1XBm5;!)PJ_r~mVbj@d0vw~6&h1Il{QWt^LCs^^SO5G)@_b!gjH;RuA>D*;VNB`sf)(cu`3Ey z#oA0=FT)#zI0QDm%e-KiexbBTt%TXic?brDT{vM5?r zYf+0N>$N*#DYzlt$)=*|G`y=BpF+fLkI>hR@NLU@Av<2MoE?1w1-sK3$U3pic)E~? zJMly+QAp&vBYkDh?5m}~@kgn3SJJz*!p(800~R3M-!o9?EKFn*PBJ~50a3RO>~LMd zu_&vuMGiYu@^;6G?cQzMc4#P?hgUSiY;iI@(j5bx*s)PiAl?F9$alxWa4TXg9JWIs zV=R*f-gvCg9RX4DhEKbq*<12L^b$@)WtSWwdHJ4oNov`XvGj~*0wOt~kl`pk=lmkm$@ibmp zMfS^O<;$!3zgXU?uaqdO+{@**;^j9y>s^i#%FA-aHQ^ej)wDQKjuMv5ZRN|a&ft{F zU-9c??6Qi#OlB)y`q~akl~rc%EE-$V$`?_~dAhEW7PDCSlBz2P6<HM=cvU$}09UnXP>3)j5f(_t%tF^rdoI@p9L?)v25k`{c3WWpzz0 z*0}4eoN||u--_$NwU12dpyDlo<&=KOoL0Qtt~$u&Ha*n#$z#RK>Z*68(N|S>@09bT z%gC>>IzYd>hRwni>%codV>+nI#W`g;+x{;yiS#X!3SMktXtGmXE3Iz3emReDslt^x zFDoZGYn~-jr+2XhS2syrR;icF%2=H(Q-M27tsIn9bakA8T6V8eG`8$DEa+5R_QiRv zc-f7=prjlnl$+_wYeO9)C{IUOeynKqu`Fejm*>jsLY>H0bWvLIGOvoVvfO7hQCiVi zF-^F$TzO5XD;-=Xl(tdPCXuq*#`5{CxDE`ysHPkhET7%VYd~H1;aX6#3Z_SQuC)cP z-1dp`mm20ul;4%xikIK)D}Bmo1ZCy8@_JCmN9f1a^5&qj)KEr-E3XCBMoTS}%z^o? zarylA4IPvk>B{K9o!^Sp?vogXJHdxWL)TKTdsn#!o^Wl`l= zK-Z=?tYjra16po;$xCg}_(Ru~?8<88ORf&psy&ER))QYMqm?hUx_pYIR$967!H>(v zd1SWorC05aCXn&!zI0v{m%YR3AA&8ei9|Q-05_{0 zMkQ2-?PI^Tfx zRGHbSU~WUL0$M6YrB(ZXEuTu}p_ULgWK!Nmqmkdw^b%WX7|o4omE8NowFC3pD^yhEX6QLD5bi_$TvYcGjQ)v-2-OX(Pu z*x2PcYSmyRD^=R0%r2|9IIC(6wMR-urB*#Q&Py}0wN(%;v6Ya$R41!7+KM8S#Ei;b z-agQ3+$KeMrK%gXf#q)LH7CAd8?O3)ioPnm)W^fPV0Fh-Ox6`cyY*FR(Nj?N;Tx4! zAG1_-szMjGl!#GTRnJ;m&Y0ESJf?MRI}sZPNc4~mMm$NJqpTNO2nwFsy)yi zU=6}5=GUmSYTv;tA5NvGOVtMEO2ee2E}ux|Qr#OUyyR6iAPth*j5k<`k{a4eUI77|>Tb9=X}U)Sq6`SBsATPzC4oM<-L9Lr{L!L@r| zS@|83tzW9mndhsXBAD>@ujuUAc;)t2z|R6>_8oKRJ%k5bX4nZ z12cLtAcX;4xOzC*FIVhAn9+zaSq$jKWox8f6fdKa{?v?i3`=A{N3I%N#l9FbdNCk{ z0bRK2uFK0?`I=%(7880=$JL@8Rk=IKOl5Ix1gTLR6WUSN@r!$z8c<_Q$YDSqwe7qz zQ$=c)!Gs>vR#W*tFGGr`SqRgbsC-vh9W+su5C$~iGF_!TVHMwOio@_F27u)beN2jD zLOaHG%o$RTNqG$D$MF6hD0%;6*KEohN_A&Vd|lo(n3}PYK*R#s)aG38AEGthANFY zX-w!wb;h-I$%@ve4JpT`v`hx{Or_hD^6nr93#UL znb46sC{#`vlq^vrx_;wA)lpL=8?X;)s(PVJXiDAtt<)){?KMJG=A|;BD|LwNt*cNY zlvM|@3~0-B%1F^xrDviHb$IF=KyA{P)(wtwm9tX~@Rn5F)FzDy-Kf)5dt?v> zk}_p=Z8_(hf$&ym>$>&5`1U3z3$LRu3_G#Wi@MJ3?OwmZ2{pGgx2k7m#4TFl@JL_V zP$rWvtj$k=PRG{96NP9pWry;GxD$gTC?gq|@K=fU+M;LK!s=6x!97ck}kP~CD zFY2Oje@`Ez4tKZ~M#B;1Sp>yHaAI)Ps;Drm_J-dMP~arp}B+I z>39;2S~!V1Y%A)Jx&WwIHecF`<_9kWZl_nhxI3ELs`-61LZZHrR?$zTE?e!wt^pDYcg@9X#MD z_8<83PIlKuZ{L^{%S|!wqZ*c zcToVzFEnPS^UdkdFtN0WtoJGYx~q-Ph% z-(N+&1S<|#ccZP2?JRWfirKc~j18d}38x@xm8)L5+tG#)Mz`_Jm}1xKT4x{&c7Hq# zu9oP1x|g}Jw~U9@PS32|M+H{{N1Y*X4Aa=9#74U|Y~Q|aeYaybw}3x{KZ1`14%eQ9 z%Z!0_OC{1S2%Dtno;y;R5vZ-h8BlX<50=%Zt1qKRb35)Vk*FG|@S;PdO0Coqb@K&P z_!j5re6nB_EH#?4@8Q>NIJ>cE!-Y9Rvj*lFd^7dZ zd@$A>iHpbKCh|h28#IX*=#NJ8qvCJm!sYoHa4q2?(*%rK@}tT02&MrKcO$#*;6I;h*MR09u|RE#Kse56 zk0+opWF|z)V#dE>BRDFCy$+r_5YAo!HA(0Gv8lM-E4Kk|-8C95h^#}wV&yMY_7M6s z9xqn#azVrWw&G5PsFBLyTd_ZNc}8nRPTrOoMhe*BaWCI}9<*8PV8c7rE8M{bq%*lO zsEJA0(MN!WFLDTP%wlh!Po`s;ysNcp_OLWf3?kdIM?`O2x^*BX`gez~3o) zpYYV7{*J*+iqEK26%0#xejgYpywyKCl-y~9(Et@i^LeK*kxfw7tLhY8e|Rai>}fJ1 za&+z4(X@<3v*ozMHMqd-P+$ANetEdN#dn;5m%R=ffEenrCj#|n**;%-hVFVH2kC9( zU=|&RCFVrJJNtVU`_I}9238gl#6iAz$AmMUhBjQ9JEED6qA_qe*V?oN4rmt{FWKOH z+-6wa7$Xy1taZyxGAYIY6;*PdA#-p?pm$X~a4~0>PV9og2s$U4lhg@Kc^7yG;Mce& z%v{rD9#^(l@f5UYX!XSzHk@Md@evod8=rw+TOk9bQKsH#wq?;UF5C{)+Zo#}`c7yT zmG(Z+?lw!iMUQMLf8S<*UsJnc)k5fCsji_dw9zd`qh|Ycw0@+Ea zLv(E|rPuW=Jwn_S%X{El$iv+1@WNDmtswy>~=X<1hs7&ESH{ zrbG(X88+~E#mgV`aDLH#$5SxXtC_XpWUlFk3~M7ecdurrSQ#Aox{Q0D-9cR!Dkc zldVKfy?MEMvXRPl53QlwK^WL2cSfPT7Q#vHGTM0NFC*t%A+z)@*Ayfmp_bwRV(Ttg zRts$$pchdoV+hu@csW~}n^jUK&YOspq%zlPpkj)_fvOZbl@C(+&uHy}&d!d(x{VxG z?!q~XUEwfJ6wv4?+&|_jB~25=Q<0rxiaXg19siDV<&;iq8rBifI-PsIEQhutR(8*9 zx3M!W-`u5^5FH6|wiA|dM#fXo92Qp2Kf4?&*FpuibCvfu?dw~^<1wEL;q26WGo(*mj>c>nVFD=+tXKYdyBH@qE*-} zIhba}nF7(e@iA$GD(~8)O{Y@!Xj$_-IV2wzQA+dtUX6|D@%`|+n@uh;28F0_s$aVz-wt|?% z)hu~feVS;v7FT$>ixhS$BuZlsUW>+66x-R1?+Gk(9=`ZgTwa~MHko(i>@svK<1lp@ zZULb57;z@9SSfOeYz9`Q$*;ujr?^0`E(*giT`dkiH(?4@kk?sNh}*eX+s-=)Sia4x zKcjm9bBs7_f?W?IAfeKwMKY<0kxW|Y(!7@X>^3*A*s1l~t?pkSb-T0JVT!@R2AtGU zI!pCUrpnBklBPN>t<=rs#=KClj$+oXS6Ob$!USRhW#H9QF*d|ksdjqsV8+i2#zza) z$8BH4N{@eM9Me1F7k4iMMYX*2#;xwo!uc4s>ttb&n3j%kQjCrI|g-#3KP>X{Z*`4 zXj>I4%yYJi%YZdcu?nysgbzyh_jJfVQBF@cPw$v%0eI(gOWB>eC~d8`r)Pp=3cLf@ zZ|7BMR%#T?=cwOyB&{`|;nlCgsp8Yp0Y!ykxo(u&_0WbGtgHIMY$!gy5nHq|n%^p8`3mhP_D14{bg@)dats$WpH69>Wu@_MI7L5Kotby_ z$uQ>vwMn0GQLKa6;WO`Zg&N$E%;bfu-`WlPlX0@oWpza@uXM`=uMK2V(O3eyTyWbL zO{XYNY;k{x#b(P>X7y`RExW(R)yloQ zMb{8t8Y#WwS=@4Xo|&&Y4C1b$O=9c2OhVeZ@^*4#ab^e>a#7`b$ zHA-&TZC_%VUXJGad&F)yFAv3QtCBDzO2aM9rPF<_*znvtN zzf?FGdu0>#Vv?Io(xRbOr6{R-yGBiU?{+whY z6)(TOVh8D3Qi5p{Z9g4Z8M`z)z~`O38;*NJ7(7vDWGs`$r6yP*P$y%|4vB0Vy#_wv zhgQJ70#uHx%k6>ZiVTa_iQ>W19n7Z1i(*O_H9MY5I6ITM0_@Iqd2ZM@`SncfX?yJX zu-o9UL%f$xHRANSm_n%7>bu%&sa6WOxM{&PrRKAx*0tVRd?N$YXakGwUNiO{-GgkM z>P86~*wLgXxVlT6Wt78NpFVu4EyErrZ;=O}_%zC>7g|gK`evAy5<7x%ZO`3Ob@RX# z*UPZVF_=DKfVg)uWscm%OoY`88-`%7KZJ!Gg`@H>u!D)_k@R>obVRTnsW4$R7onl? zWGeomWZV)2JVIbK!}>8KMqwdGzrZ=mJf4IWH2&hiZ!pq}Vg&vxn<`k%xRJ+dhCiD} zGW(0FczXUl@Y})gPsSg82C^+nhLb1K z_oqRyAN-T?k0aO`fN+2KC*wbKI{hHS8(zXh4loV%a{+vLN|FCfQTkPegPgFGU*;pj zQJ_Dm#D6G8@nsm~3{ieeL&{Gq%i6`bOz*e^{UXD?A^I-!m+@u!FXQ;@iDu2chyIY^ z;31{>&w@Yo_-_LYMLdvbmNmnFaESFw{YW_^b~*f^#t(2j8AfD=9HB`IuhHUX_Yy&d zlF!jB`CW$Z)8bEZd>M8vlmAUx{MlK`Nrtbyk{=+!#r*lJ^)dKEE&qw<(UX+np_0g< zuD@G3zI^^xg#Y4jwAGzJ!2Q+wf);=DO%z{-1%CcAnx6k1TKxGbiZ8U;R&txB3qp z7Gu&MGM)_o0Wdy48NZ3+H*x&Y!`%tUdMD8XAu_fd8GrX7^w;huD1Z4lvHjym<}1^= z4lp(UyAGrHcRfk*rTq|*mH0B9XF_B(zSSfpp|C?!xQr*mmbLE96(3}g;PEO*)k{k)&0$~uzGmKzwla8{0p@R+E?p;0T|c^^#A|> diff --git a/src/Algorithms/Libraries/kalman/src/kalman.cpp b/src/Algorithms/Libraries/kalman/src/kalman.cpp index 4c44312..5e47d9f 100755 --- a/src/Algorithms/Libraries/kalman/src/kalman.cpp +++ b/src/Algorithms/Libraries/kalman/src/kalman.cpp @@ -55,11 +55,34 @@ void KalmanFilter::update(const Eigen::VectorXd& y) { if(!initialized) throw std::runtime_error("Filter is not initialized!"); + if (y.size() != m) + throw std::runtime_error("KalmanFilter::update(): measurement vector has wrong size"); + + if (A.rows() != n || A.cols() != n || C.rows() != m || C.cols() != n || + Q.rows() != n || Q.cols() != n || R.rows() != m || R.cols() != m || + P.rows() != n || P.cols() != n) + throw std::runtime_error("KalmanFilter::update(): matrix dimensions are inconsistent"); + x_hat_new = A * x_hat; P = A*P*A.transpose() + Q; - K = P*C.transpose()*(C*P*C.transpose() + R).inverse(); + + const Eigen::MatrixXd S = C * P * C.transpose() + R; + Eigen::LDLT ldlt(S); + if (ldlt.info() != Eigen::Success) + throw std::runtime_error("KalmanFilter::update(): failed to decompose innovation covariance"); + + // K = P*C' * inv(S) -> solve(S * X = (P*C')^T) + const Eigen::MatrixXd PCt = P * C.transpose(); + const Eigen::MatrixXd KT = ldlt.solve(PCt.transpose()); + if (ldlt.info() != Eigen::Success) + throw std::runtime_error("KalmanFilter::update(): failed to solve for Kalman gain"); + K = KT.transpose(); + x_hat_new += K * (y - C*x_hat_new); - P = (I - K*C)*P; + + // Joseph form: keeps P symmetric / PSD under numeric errors + const Eigen::MatrixXd IKC = I - K * C; + P = IKC * P * IKC.transpose() + K * R * K.transpose(); x_hat = x_hat_new; t += dt; diff --git a/src/Algorithms/Libraries/mkt_algorithm/include/mkt_algorithm/diff/diff_predictive_trajectory.h b/src/Algorithms/Libraries/mkt_algorithm/include/mkt_algorithm/diff/diff_predictive_trajectory.h index d7d2427..6a21147 100644 --- a/src/Algorithms/Libraries/mkt_algorithm/include/mkt_algorithm/diff/diff_predictive_trajectory.h +++ b/src/Algorithms/Libraries/mkt_algorithm/include/mkt_algorithm/diff/diff_predictive_trajectory.h @@ -412,6 +412,14 @@ namespace mkt_algorithm Eigen::MatrixXd Q; Eigen::MatrixXd R; Eigen::MatrixXd P; + + // Kalman filter tuning (for v and w filtering) + double kf_q_v_; + double kf_q_w_; + double kf_r_v_; + double kf_r_w_; + double kf_p0_; + bool kf_filter_angular_; #ifdef BUILD_WITH_ROS ros::Publisher lookahead_point_pub_; #endif diff --git a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp index 9b2e510..1a7c0d9 100644 --- a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp +++ b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp @@ -35,6 +35,12 @@ mkt_algorithm::diff::PredictiveTrajectory::PredictiveTrajectory() cost_scaling_gain_(0.0), control_duration_(0.0), kf_(nullptr), + kf_q_v_(0.25), + kf_q_w_(0.8), + kf_r_v_(0.05), + kf_r_w_(0.08), + kf_p0_(0.5), + kf_filter_angular_(false), m_(0), n_(0) { @@ -83,16 +89,20 @@ void mkt_algorithm::diff::PredictiveTrajectory::initialize( // kalman last_actuator_update_ = robot::Time::now(); - n_ = 6; // [x, vx, ax, y, vy, ay, theta, vtheta, atheta] - m_ = 2; // measurements: x, y, theta + // State: [v, a, j, w, alpha, jw] where: + // - v: linear velocity, a: linear accel, j: linear jerk + // - w: angular velocity, alpha: angular accel, jw: angular jerk + // Measurement: [v, w] + n_ = 6; + m_ = 2; double dt = control_duration_; // Khởi tạo ma trận A = Eigen::MatrixXd::Identity(n_, n_); C = Eigen::MatrixXd::Zero(m_, n_); Q = Eigen::MatrixXd::Zero(n_, n_); - R = Eigen::MatrixXd::Identity(m_, m_); - P = Eigen::MatrixXd::Identity(n_, n_); + R = Eigen::MatrixXd::Zero(m_, m_); + P = Eigen::MatrixXd::Identity(n_, n_) * std::max(1e-9, kf_p0_); for (int i = 0; i < n_; i += 3) { @@ -103,15 +113,11 @@ void mkt_algorithm::diff::PredictiveTrajectory::initialize( C(0, 0) = 1; C(1, 3) = 1; - Q(2, 2) = 0.1; - Q(5, 5) = 0.6; + Q(2, 2) = std::max(1e-12, kf_q_v_); + Q(5, 5) = std::max(1e-12, kf_q_w_); - R(0, 0) = 0.1; - R(1, 1) = 0.2; - - P(3, 3) = 0.4; - P(4, 4) = 0.4; - P(5, 5) = 0.4; + R(0, 0) = std::max(1e-12, kf_r_v_); + R(1, 1) = std::max(1e-12, kf_r_w_); kf_ = boost::make_shared(dt, A, C, Q, R, P); Eigen::VectorXd x0(n_); @@ -177,6 +183,15 @@ void mkt_algorithm::diff::PredictiveTrajectory::getParams() robot::log_warning("[%s:%d]\n The value inflation_cost_scaling_factor is incorrectly set, it should be >0. Disabling cost regulated linear velocity scaling.", __FILE__, __LINE__); use_cost_regulated_linear_velocity_scaling_ = false; } + + // Kalman filter tuning (filtering v and w commands) + nh_priv_.param("kf_q_v", kf_q_v_, kf_q_v_); + nh_priv_.param("kf_q_w", kf_q_w_, kf_q_w_); + nh_priv_.param("kf_r_v", kf_r_v_, kf_r_v_); + nh_priv_.param("kf_r_w", kf_r_w_, kf_r_w_); + nh_priv_.param("kf_p0", kf_p0_, kf_p0_); + nh_priv_.param("kf_filter_angular", kf_filter_angular_, kf_filter_angular_); + double control_frequency = robot_nav_2d_utils::searchAndGetParam(nh_priv_, "controller_frequency", 10); control_duration_ = 1.0 / control_frequency; @@ -558,25 +573,6 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator( result.velocity = drive_cmd; return result; } - - // Eigen::VectorXd y(2); - // y << drive_cmd.x, drive_cmd.theta; - - // // Cập nhật lại A nếu dt thay đổi - // for (int i = 0; i < n_; ++i) - // for (int j = 0; j < n_; ++j) - // A(i, j) = (i == j ? 1.0 : 0.0); - // for (int i = 0; i < n_; i += 3) - // { - // A(i, i + 1) = dt; - // A(i, i + 2) = 0.5 * dt * dt; - // A(i + 1, i + 2) = dt; - // } - // kf_->update(y, dt, A); - // double v_min = min_approach_linear_velocity_; - // drive_cmd.x = std::clamp(kf_->state()[0], -fabs(v_max), fabs(v_max)); - // drive_cmd.x = fabs(drive_cmd.x) >= v_min ? drive_cmd.x : std::copysign(v_min, sign_x); - // drive_cmd.theta = std::clamp(kf_->state()[3], -max_vel_theta_, max_vel_theta_); } result.poses.clear(); result.poses.reserve(transformed_plan.poses.size()); @@ -687,6 +683,27 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit( drive_cmd.x = velocity.x + dv; drive_cmd.theta = velocity.theta + dw; + + + Eigen::VectorXd y(2); + y << drive_cmd.x, drive_cmd.theta; + + // Cập nhật lại A nếu dt thay đổi + for (int i = 0; i < n_; ++i) + for (int j = 0; j < n_; ++j) + A(i, j) = (i == j ? 1.0 : 0.0); + for (int i = 0; i < n_; i += 3) + { + A(i, i + 1) = dt; + A(i, i + 2) = 0.5 * dt * dt; + A(i + 1, i + 2) = dt; + } + kf_->update(y, dt, A); + double v_min = min_approach_linear_velocity_; + drive_cmd.x = std::clamp(kf_->state()[0], -fabs(v_target), fabs(v_target)); + drive_cmd.x = fabs(drive_cmd.x) >= v_min ? drive_cmd.x : std::copysign(v_min, sign_x); + if (kf_filter_angular_) + drive_cmd.theta = std::clamp(kf_->state()[3], -max_vel_theta_, max_vel_theta_); } void mkt_algorithm::diff::PredictiveTrajectory::applyDistanceSpeedScaling( From 98ce71eb695e418b1cef26f787855c3e133c8ce0 Mon Sep 17 00:00:00 2001 From: HiepLM Date: Thu, 19 Mar 2026 10:08:46 +0700 Subject: [PATCH 03/11] update make install --- examples/NavigationExample/NavigationAPI.cs | 2 +- examples/run_example.sh | 7 ++++--- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/examples/NavigationExample/NavigationAPI.cs b/examples/NavigationExample/NavigationAPI.cs index 1becdc2..fd411fa 100644 --- a/examples/NavigationExample/NavigationAPI.cs +++ b/examples/NavigationExample/NavigationAPI.cs @@ -9,7 +9,7 @@ namespace NavigationExample /// public class NavigationAPI { - private const string DllName = "libnav_c_api.so"; // Linux + private const string DllName = "/usr/local/lib/libnav_c_api.so"; // Linux // For Windows: "nav_c_api.dll" // For macOS: "libnav_c_api.dylib" diff --git a/examples/run_example.sh b/examples/run_example.sh index 19bf39a..0a9d3be 100755 --- a/examples/run_example.sh +++ b/examples/run_example.sh @@ -27,6 +27,7 @@ echo "Building C API library..." cd "$BUILD_DIR" cmake .. make +sudo make install echo "Library built successfully!" @@ -83,9 +84,9 @@ fi # Luôn copy source code mới nhất (cập nhật file nếu đã có) cd "$EXAMPLE_DIR/NavigationExample" -# Bước 3: Copy library -echo "Copying library..." -cp "$LIB_DIR/libnav_c_api.so" . +# # Bước 3: Copy library +# echo "Copying library..." +# cp "$LIB_DIR/libnav_c_api.so" . # Bước 4: Set LD_LIBRARY_PATH để tìm được tất cả dependencies # Main build directory (contains libtf3.so, librobot_cpp.so, etc.) From 180a646e35ecb7af8346e82d337e8e4d50f53c42 Mon Sep 17 00:00:00 2001 From: QUYVN Date: Thu, 19 Mar 2026 04:02:08 +0000 Subject: [PATCH 04/11] add docking to --- config/costmap_common_params.yaml | 7 -- config/move_base_common_params.yaml | 22 ++++++ examples/NavigationExample/NavigationAPI.cs | 4 ++ src/APIs/c_api/include/nav_c_api.h | 14 ++++ src/APIs/c_api/src/nav_c_api.cpp | 38 ++++++++++ .../Packages/move_base/src/move_base.cpp | 72 +++++++++++++++++-- 6 files changed, 144 insertions(+), 13 deletions(-) diff --git a/config/costmap_common_params.yaml b/config/costmap_common_params.yaml index f606ea9..997b55c 100755 --- a/config/costmap_common_params.yaml +++ b/config/costmap_common_params.yaml @@ -1,10 +1,3 @@ -position_planner_name: PNKXLocalPlanner -docking_planner_name: PNKXDockingLocalPlanner -go_straight_planner_name: PNKXGoStraightLocalPlanner -rotate_planner_name: PNKXRotateLocalPlanner -base_local_planner: LocalPlannerAdapter -base_global_planner: CustomPlanner - robot_base_frame: base_link transform_tolerance: 1.0 obstacle_range: 3.0 diff --git a/config/move_base_common_params.yaml b/config/move_base_common_params.yaml index 73110da..72838cc 100755 --- a/config/move_base_common_params.yaml +++ b/config/move_base_common_params.yaml @@ -1,3 +1,25 @@ +position_planner_name: PNKXLocalPlanner +docking_planner_name: PNKXDockingLocalPlanner +go_straight_planner_name: PNKXGoStraightLocalPlanner +rotate_planner_name: PNKXRotateLocalPlanner +base_local_planner: LocalPlannerAdapter +base_global_planner: CustomPlanner + +PNKXLocalPlanner: + base_local_planner: LocalPlannerAdapter + base_global_planner: CustomPlanner + +MKTDockingPlanner: + base_local_planner: LocalPlannerAdapter + base_global_planner: TwoPointsPlanner + +MKTGoStraightPlanner: + base_local_planner: LocalPlannerAdapter + base_global_planner: TwoPointsPlanner + +MKTRotatePlanner: + base_local_planner: LocalPlannerAdapter + base_global_planner: TwoPointsPlanner ### replanning controller_frequency: 30.0 # run controller at 15.0 Hz diff --git a/examples/NavigationExample/NavigationAPI.cs b/examples/NavigationExample/NavigationAPI.cs index fd411fa..146fbf1 100644 --- a/examples/NavigationExample/NavigationAPI.cs +++ b/examples/NavigationExample/NavigationAPI.cs @@ -152,6 +152,10 @@ namespace NavigationExample [return: MarshalAs(UnmanagedType.I1)] public static extern bool navigation_dock_to_order(NavigationHandle handle, Order order, string marker, PoseStamped goal); + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl, CharSet = CharSet.Ansi)] + [return: MarshalAs(UnmanagedType.I1)] + public static extern bool navigation_dock_to_nodes_edges(NavigationHandle handle, string marker, Node[] nodes, Edge[] edges, PoseStamped goal); + [DllImport(DllName, CallingConvention = CallingConvention.Cdecl)] [return: MarshalAs(UnmanagedType.I1)] public static extern bool navigation_move_straight_to(NavigationHandle handle, double distance); diff --git a/src/APIs/c_api/include/nav_c_api.h b/src/APIs/c_api/include/nav_c_api.h index c508ffe..302b419 100644 --- a/src/APIs/c_api/include/nav_c_api.h +++ b/src/APIs/c_api/include/nav_c_api.h @@ -171,6 +171,20 @@ extern "C" */ bool navigation_dock_to_order(NavigationHandle handle, const Order order, const char *marker, const PoseStamped goal); + /** + * @brief Send a goal for the robot to navigate to + * @param handle Navigation handle + * @param marker Marker name or ID (null-terminated string) + * @param nodes Nodes array + * @param node_count Number of nodes in the array + * @param edges Edges array + * @param edge_count Number of edges in the array + * @param goal Target pose in the global frame + * @return true if goal was accepted and sent successfully + */ + bool navigation_dock_to_nodes_edges(NavigationHandle handle, const char *marker, const Node *nodes, size_t node_count, const Edge *edges, size_t edge_count, const PoseStamped goal); + + /** * @brief Move straight toward the target position * @param handle Navigation handle diff --git a/src/APIs/c_api/src/nav_c_api.cpp b/src/APIs/c_api/src/nav_c_api.cpp index fcafddf..78a7f01 100644 --- a/src/APIs/c_api/src/nav_c_api.cpp +++ b/src/APIs/c_api/src/nav_c_api.cpp @@ -397,6 +397,44 @@ extern "C" bool navigation_dock_to_order(NavigationHandle handle, const Order or } } +extern "C" bool navigation_dock_to_nodes_edges(NavigationHandle handle, const char *marker, const Node *nodes, size_t node_count, const Edge *edges, size_t edge_count, const PoseStamped goal) +{ + if (!handle || !marker) + { + return false; + } + if (!isQuaternionValid(goal.pose.orientation)) + { + robot::log_error("Goal quaternion is invalid"); + return false; + } + try + { + std::shared_ptr nav_ptr = + std::shared_ptr( + reinterpret_cast(handle), [](::robot::move_base_core::BaseNavigation *) {}); + if (!nav_ptr) + return false; + Order order; + order.nodes = const_cast(nodes); + order.nodes_count = node_count; + order.edges = const_cast(edges); + order.edges_count = edge_count; + robot_protocol_msgs::Order cpp_order = convert2CppOrder(order); + robot_geometry_msgs::PoseStamped cpp_goal = convert2CppPoseStamped(goal); + return nav_ptr->dockTo(cpp_order, std::string(marker), cpp_goal); + } + catch (const std::exception &e) + { + return false; + } + catch (...) + { + printf("[%s:%d]\n Error: Failed to dock to nodes edges\n", __FILE__, __LINE__); + return false; + } +} + extern "C" bool navigation_move_straight_to(NavigationHandle handle, const double distance) { if (!handle) diff --git a/src/Navigations/Packages/move_base/src/move_base.cpp b/src/Navigations/Packages/move_base/src/move_base.cpp index aef61aa..b67434c 100644 --- a/src/Navigations/Packages/move_base/src/move_base.cpp +++ b/src/Navigations/Packages/move_base/src/move_base.cpp @@ -812,7 +812,17 @@ bool move_base::MoveBase::moveTo( const robot_geometry_msgs::PoseStamped &goal, { if (setup_) { - swapPlanner(default_config_.base_global_planner); + robot::NodeHandle nh_planner = robot::NodeHandle(private_nh_, position_planner_name_); + if(nh_planner.hasParam("base_global_planner")) + { + std::string base_global_planner; + nh_planner.getParam("base_global_planner", base_global_planner); + swapPlanner(base_global_planner); + } + else + { + swapPlanner(default_config_.base_global_planner); + } } else { @@ -963,7 +973,17 @@ bool move_base::MoveBase::moveTo(const robot_protocol_msgs::Order &msg, { if (setup_) { - swapPlanner(default_config_.base_global_planner); + robot::NodeHandle nh_planner = robot::NodeHandle(private_nh_, position_planner_name_); + if(nh_planner.hasParam("base_global_planner")) + { + std::string base_global_planner; + nh_planner.getParam("base_global_planner", base_global_planner); + swapPlanner(base_global_planner); + } + else + { + swapPlanner(default_config_.base_global_planner); + } } else { @@ -1120,7 +1140,17 @@ bool move_base::MoveBase::dockTo(const std::string &marker, const robot_geometry if (setup_) { - swapPlanner(default_config_.base_global_planner); + robot::NodeHandle nh_planner = robot::NodeHandle(private_nh_, docking_planner_name_); + if(nh_planner.hasParam("base_global_planner")) + { + std::string base_global_planner; + nh_planner.getParam("base_global_planner", base_global_planner); + swapPlanner(base_global_planner); + } + else + { + swapPlanner(default_config_.base_global_planner); + } } else { @@ -1233,7 +1263,17 @@ bool move_base::MoveBase::dockTo(const robot_protocol_msgs::Order &msg, if (setup_) { - swapPlanner(default_config_.base_global_planner); + robot::NodeHandle nh_planner = robot::NodeHandle(private_nh_, docking_planner_name_); + if(nh_planner.hasParam("base_global_planner")) + { + std::string base_global_planner; + nh_planner.getParam("base_global_planner", base_global_planner); + swapPlanner(base_global_planner); + } + else + { + swapPlanner(default_config_.base_global_planner); + } } else { @@ -1342,7 +1382,17 @@ bool move_base::MoveBase::moveStraightTo(const robot_geometry_msgs::PoseStamped if (setup_) { std::string global_planner = "TwoPointsPlanner"; - swapPlanner(global_planner); + robot::NodeHandle nh_planner = robot::NodeHandle(private_nh_, go_straight_planner_name_); + if(nh_planner.hasParam("base_global_planner")) + { + std::string base_global_planner; + nh_planner.getParam("base_global_planner", base_global_planner); + swapPlanner(base_global_planner); + } + else + { + swapPlanner(global_planner); + } } else { @@ -1465,7 +1515,17 @@ bool move_base::MoveBase::rotateTo(const robot_geometry_msgs::PoseStamped &goal, if (setup_) { std::string global_planner = "TwoPointsPlanner"; - swapPlanner(global_planner); + robot::NodeHandle nh_planner = robot::NodeHandle(private_nh_, rotate_planner_name_); + if(nh_planner.hasParam("base_global_planner")) + { + std::string base_global_planner; + nh_planner.getParam("base_global_planner", base_global_planner); + swapPlanner(base_global_planner); + } + else + { + swapPlanner(global_planner); + } } else { From ae32077fe24bdbf12c541c2cfff3eafbed27a580 Mon Sep 17 00:00:00 2001 From: HiepLM Date: Thu, 19 Mar 2026 15:24:09 +0700 Subject: [PATCH 05/11] update --- .../src/diff/diff_predictive_trajectory.cpp | 4 +- .../Packages/move_base/src/move_base.cpp | 61 ++++++++++++++++++- 2 files changed, 62 insertions(+), 3 deletions(-) diff --git a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp index 1a7c0d9..121d050 100644 --- a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp +++ b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp @@ -602,7 +602,7 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit( { // 1) Curvature from pure pursuit const double L2 = carrot_pose.pose.x * carrot_pose.pose.x + carrot_pose.pose.y * carrot_pose.pose.y; - const double L2_min = 0.05; // m^2, chỉnh theo nhu cầu (0.02–0.1) + const double L2_min = 0.01; // m^2, chỉnh theo nhu cầu (0.02–0.1) const double L2_safe = std::max(L2, L2_min); const double L = std::sqrt(L2_safe); @@ -631,7 +631,7 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit( v_target = std::copysign(min_approach_linear_velocity, sign_x); // 5) Angular speed from curvature - double w_target = v_target * kappa; + double w_target = v_target * kappa + std::copysign(carrot_pose.pose.theta * dt, kappa); if(journey(trajectory.poses, 0, trajectory.poses.size() - 1) <= min_journey_squared_) { if (trajectory.poses.size() >= 2) { diff --git a/src/Navigations/Packages/move_base/src/move_base.cpp b/src/Navigations/Packages/move_base/src/move_base.cpp index b67434c..dcec1de 100644 --- a/src/Navigations/Packages/move_base/src/move_base.cpp +++ b/src/Navigations/Packages/move_base/src/move_base.cpp @@ -31,7 +31,9 @@ #include #include #include -#include +#ifndef BUILD_WITH_ROS + #include +#endif move_base::MoveBase::MoveBase() : initialized_(false), @@ -500,6 +502,7 @@ robot_nav_msgs::OccupancyGrid move_base::MoveBase::getStaticMap(const std::strin void move_base::MoveBase::addLaserScan(const std::string &laser_scan_name, robot_sensor_msgs::LaserScan laser_scan) { auto it = laser_scans_.find(laser_scan_name); +#ifndef BUILD_WITH_ROS laser_filter::LaserScanSOR sor; sor.setMeanK(10); // xét 10 điểm láng giềng gần nhất sor.setStddevMulThresh(1.0); // ngưỡng = mean + 1.0 * stddev @@ -512,6 +515,16 @@ void move_base::MoveBase::addLaserScan(const std::string &laser_scan_name, robot { it->second = laser_scan_filter; } +#else + if (it == laser_scans_.end()) + { + laser_scans_[laser_scan_name] = laser_scan; + } + else + { + it->second = laser_scan; + } +#endif // robot::log_info("stamp: %ld.%ld", laser_scan.header.stamp.sec, laser_scan.header.stamp.nsec); // robot::log_info("frame_id: %s", laser_scan.header.frame_id.c_str()); // robot::log_info("angle_min: %f", laser_scan.angle_min); @@ -534,8 +547,13 @@ void move_base::MoveBase::addLaserScan(const std::string &laser_scan_name, robot // } // robot::log_error("intensities: %s", intensities_str.str().c_str()); +#ifndef BUILD_WITH_ROS updateLocalCostmap(laser_scan_filter, robot_costmap_2d::LayerType::VOXEL_LAYER, laser_scan_name); updateGlobalCostmap(laser_scan_filter, robot_costmap_2d::LayerType::VOXEL_LAYER, laser_scan_name); +#else + updateLocalCostmap(laser_scan, robot_costmap_2d::LayerType::VOXEL_LAYER, laser_scan_name); + updateGlobalCostmap(laser_scan, robot_costmap_2d::LayerType::VOXEL_LAYER, laser_scan_name); +#endif } robot_sensor_msgs::LaserScan move_base::MoveBase::getLaserScan(const std::string &laser_scan_name) @@ -1225,6 +1243,47 @@ bool move_base::MoveBase::dockTo(const std::string &marker, const robot_geometry } if (cancel_ctr_) cancel_ctr_ = false; + // Check if action server exists + if (!as_) + { + robot::log_error("[MoveBase::moveTo] as_ pointer is null!"); + lock.unlock(); + return false; + } + + try + { + robot_move_base_msgs::MoveBaseActionGoalPtr action_goal = boost::make_shared(); + action_goal->header.stamp = robot::Time::now(); + action_goal->goal.target_pose = goal; + + // Generate unique goal ID using timestamp + robot::Time now = robot::Time::now(); + action_goal->goal_id.stamp = now; + std::ostringstream goal_id_stream; + goal_id_stream << "move_base_goal_" << now.sec << "_" << now.nsec; + action_goal->goal_id.id = goal_id_stream.str(); + + robot::log_info("[MoveBase::moveTo] Generated goal ID: %s", action_goal->goal_id.id.c_str()); + robot::log_info("[MoveBase::moveTo] Goal stamp: %ld.%09ld", + action_goal->goal_id.stamp.sec, action_goal->goal_id.stamp.nsec); + + // Clear Order message since this is a non-Order moveTo call + { + boost::unique_lock planner_lock(planner_mutex_); + planner_order_.reset(); + } + + robot::log_info("[MoveBase::moveTo] Processing goal through action server..."); + as_->processGoal(action_goal); + robot::log_info("[MoveBase::moveTo] Goal processed successfully by action server"); + } + catch (const std::exception &e) + { + lock.unlock(); + robot::log_error("[MoveBase::moveTo] Exception during processGoal: %s", e.what()); + return false; + } lock.unlock(); return true; From e90a84c22942f65f61f3ab9f70026cc541c63a7d Mon Sep 17 00:00:00 2001 From: QUYVN Date: Thu, 19 Mar 2026 10:34:46 +0000 Subject: [PATCH 06/11] update --- config/move_base_common_params.yaml | 6 +++--- config/pnkx_local_planner_params.yaml | 4 ++-- examples/NavigationExample/NavigationExample.csproj | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/config/move_base_common_params.yaml b/config/move_base_common_params.yaml index 72838cc..190579c 100755 --- a/config/move_base_common_params.yaml +++ b/config/move_base_common_params.yaml @@ -9,15 +9,15 @@ PNKXLocalPlanner: base_local_planner: LocalPlannerAdapter base_global_planner: CustomPlanner -MKTDockingPlanner: +PNKXDockingLocalPlanner: base_local_planner: LocalPlannerAdapter base_global_planner: TwoPointsPlanner -MKTGoStraightPlanner: +PNKXGoStraightLocalPlanner: base_local_planner: LocalPlannerAdapter base_global_planner: TwoPointsPlanner -MKTRotatePlanner: +PNKXRotateLocalPlanner: base_local_planner: LocalPlannerAdapter base_global_planner: TwoPointsPlanner diff --git a/config/pnkx_local_planner_params.yaml b/config/pnkx_local_planner_params.yaml index cf46a84..581f117 100644 --- a/config/pnkx_local_planner_params.yaml +++ b/config/pnkx_local_planner_params.yaml @@ -41,8 +41,8 @@ PNKXRotateLocalPlanner: LimitedAccelGenerator: library_path: libmkt_plugins_standard_traj_generator - max_vel_x: 1.0 - min_vel_x: -1.0 + max_vel_x: 1.2 + min_vel_x: -1.2 max_vel_y: 0.0 # diff drive robot min_vel_y: 0.0 # diff drive robot diff --git a/examples/NavigationExample/NavigationExample.csproj b/examples/NavigationExample/NavigationExample.csproj index c98bcda..9ec6097 100644 --- a/examples/NavigationExample/NavigationExample.csproj +++ b/examples/NavigationExample/NavigationExample.csproj @@ -1,7 +1,7 @@ Exe - net6.0 + net10.0 true From aa63caa188dabaad1b13417405341199cf6bab1f Mon Sep 17 00:00:00 2001 From: HiepLM Date: Fri, 20 Mar 2026 11:24:00 +0700 Subject: [PATCH 07/11] fix bug docking --- examples/NavigationExample/Program.cs | 4 ++-- .../pnkx_local_planner/src/pnkx_docking_local_planner.cpp | 6 ++++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/examples/NavigationExample/Program.cs b/examples/NavigationExample/Program.cs index a483249..0fd7206 100644 --- a/examples/NavigationExample/Program.cs +++ b/examples/NavigationExample/Program.cs @@ -406,9 +406,9 @@ namespace NavigationExample // Console.WriteLine("Docking to docking_point"); - // NavigationAPI.navigation_dock_to_order(navHandle, order, "charger", goal); + NavigationAPI.navigation_dock_to(navHandle, "charger", goal); - NavigationAPI.navigation_move_to_nodes_edges(navHandle, order.nodes, order.nodes_count, order.edges, order.edges_count, goal); + // NavigationAPI.navigation_move_to_nodes_edges(navHandle, order.nodes, order.nodes_count, order.edges, order.edges_count, goal); // NavigationAPI.navigation_move_to_order(navHandle, order, goal); NavigationAPI.navigation_set_twist_linear(navHandle, 0.1, 0.0, 0.0); diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp index 07ef9b6..42c952b 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp @@ -593,7 +593,8 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::DockingPlanner::initialize(rob { try { - std::string path_file_so = "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_robot_nav_core2/build/src/Algorithms/Packages/local_planners/pnkx_local_planner/libpnkx_local_planner.so"; + robot::PluginLoaderHelper loader; + std::string path_file_so = loader.findLibraryPath(docking_planner_name_); docking_planner_loader_ = boost::dll::import_alias( path_file_so, docking_planner_name_, boost::dll::load_mode::append_decorations); docking_planner_ = docking_planner_loader_(); @@ -616,7 +617,8 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::DockingPlanner::initialize(rob { try { - std::string path_file_so = "/home/robotics/AGV/Diff_Wheel_Prj/pnkx_robot_nav_core2/build/src/Algorithms/Packages/local_planners/pnkx_local_planner/libpnkx_local_planner.so"; + robot::PluginLoaderHelper loader; + std::string path_file_so = loader.findLibraryPath(docking_nav_name_); docking_nav_loader_ = boost::dll::import_alias( path_file_so, docking_nav_name_, boost::dll::load_mode::append_decorations); docking_nav_ = docking_nav_loader_(); From 76ee97f2eccacb47cb017aa61b3c8e52f4975d17 Mon Sep 17 00:00:00 2001 From: QUYVN Date: Fri, 20 Mar 2026 04:43:29 +0000 Subject: [PATCH 08/11] change PNKX_NAV_CORE_LIBRARY_PATH --- src/Libraries/robot_cpp/src/plugin_loader_helper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Libraries/robot_cpp/src/plugin_loader_helper.cpp b/src/Libraries/robot_cpp/src/plugin_loader_helper.cpp index bcdbdc9..a109fab 100644 --- a/src/Libraries/robot_cpp/src/plugin_loader_helper.cpp +++ b/src/Libraries/robot_cpp/src/plugin_loader_helper.cpp @@ -338,7 +338,7 @@ std::string PluginLoaderHelper::getBuildDirectory() std::string PluginLoaderHelper::getWorkspacePath() { // Method 1: Từ environment variable PNKX_NAV_CORE_DIR - const char* workspace_path = std::getenv("PNKX_NAV_CORE_DIR"); + const char* workspace_path = std::getenv("PNKX_NAV_CORE_LIBRARY_PATH"); if (workspace_path && std::filesystem::exists(workspace_path)) { return std::string(workspace_path); } From 9a4bb95c4cc8a015c34a5aff7fa4d93fe896f19d Mon Sep 17 00:00:00 2001 From: QUYVN Date: Fri, 20 Mar 2026 07:09:05 +0000 Subject: [PATCH 09/11] update param yaml --- config/dock_global_params.yaml | 12 ++++++++++++ 1 file changed, 12 insertions(+) create mode 100644 config/dock_global_params.yaml diff --git a/config/dock_global_params.yaml b/config/dock_global_params.yaml new file mode 100644 index 0000000..bb9f187 --- /dev/null +++ b/config/dock_global_params.yaml @@ -0,0 +1,12 @@ +DockPlanner: + library_path: libdock_planner + # File: config/planner_params.yaml + MyGlobalPlanner: + cost_threshold: 200 # Ngưỡng chi phí vật cản (0-255) + safety_distance: 2 # Khoảng cách an toàn (cells) + use_dijkstra: false # Sử dụng Dijkstra thay vì A* + + # File: config/costmap_params.yaml + global_costmap: + inflation_radius: 0.3 # Bán kính phình vật cản + cost_scaling_factor: 10.0 # Hệ số tỷ lệ chi phí \ No newline at end of file From d38f6b3954a37597eb04131eb0b3cce24b481962 Mon Sep 17 00:00:00 2001 From: HiepLM Date: Fri, 20 Mar 2026 16:06:47 +0700 Subject: [PATCH 10/11] update --- config/dock_global_params.yaml | 1 - .../NavigationExample.csproj | 2 +- examples/NavigationExample/Program.cs | 4 ++-- .../Packages/global_planners/dock_planner | 2 +- .../src/pnkx_docking_local_planner.cpp | 20 +++++++++---------- .../src/pnkx_go_straight_local_planner.cpp | 12 +++++------ .../src/pnkx_local_planner.cpp | 16 +++++++-------- .../src/pnkx_rotate_local_planner.cpp | 12 +++++------ 8 files changed, 34 insertions(+), 35 deletions(-) diff --git a/config/dock_global_params.yaml b/config/dock_global_params.yaml index bb9f187..3191200 100644 --- a/config/dock_global_params.yaml +++ b/config/dock_global_params.yaml @@ -1,6 +1,5 @@ DockPlanner: library_path: libdock_planner - # File: config/planner_params.yaml MyGlobalPlanner: cost_threshold: 200 # Ngưỡng chi phí vật cản (0-255) safety_distance: 2 # Khoảng cách an toàn (cells) diff --git a/examples/NavigationExample/NavigationExample.csproj b/examples/NavigationExample/NavigationExample.csproj index 9ec6097..c98bcda 100644 --- a/examples/NavigationExample/NavigationExample.csproj +++ b/examples/NavigationExample/NavigationExample.csproj @@ -1,7 +1,7 @@ Exe - net10.0 + net6.0 true diff --git a/examples/NavigationExample/Program.cs b/examples/NavigationExample/Program.cs index 0fd7206..89ca9fd 100644 --- a/examples/NavigationExample/Program.cs +++ b/examples/NavigationExample/Program.cs @@ -396,8 +396,8 @@ namespace NavigationExample PoseStamped goal = new PoseStamped(); goal.header = NavigationAPI.header_create(Marshal.PtrToStringAnsi(mapFrameId)); - goal.pose.position.x = 1.0; - goal.pose.position.y = 1.0; + goal.pose.position.x = 0.01; + goal.pose.position.y = 0.01; goal.pose.position.z = 0.0; goal.pose.orientation.x = 0.0; goal.pose.orientation.y = 0.0; diff --git a/src/Algorithms/Packages/global_planners/dock_planner b/src/Algorithms/Packages/global_planners/dock_planner index da82431..56d05e4 160000 --- a/src/Algorithms/Packages/global_planners/dock_planner +++ b/src/Algorithms/Packages/global_planners/dock_planner @@ -1 +1 @@ -Subproject commit da82431cd9fdee1aef407579357af9e573460389 +Subproject commit 56d05e4322a9ef57c7e421d86d244f764edefcfe diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp index 42c952b..7a59917 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp @@ -74,7 +74,7 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::initialize(robot::NodeHandle & if (!traj_generator_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create trajectory generator \"%s\": returned null pointer", traj_generator_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create traj_generator"); } robot::NodeHandle nh_traj_gen = robot::NodeHandle(parent_, traj_generator_name); traj_generator_->initialize(nh_traj_gen); @@ -83,7 +83,7 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::initialize(robot::NodeHandle & catch (const std::exception &ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s traj_generator, are you sure it is properly registered and that the containing library is built? Exception: %s", traj_generator_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create traj_generator"); } std::string algorithm_nav_name; @@ -99,14 +99,14 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::initialize(robot::NodeHandle & if (!nav_algorithm_) { robot::log_error_at(__FILE__, __LINE__, "Failed to load algorithm %s", algorithm_nav_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create algorithm"); } nav_algorithm_->initialize(parent_, algorithm_nav_name, tf, costmap_robot_, traj_generator_); } catch (const std::exception &ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s algorithm , are you sure it is properly registered and that the containing library is built? Exception: %s", algorithm_nav_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create algorithm"); } std::string algorithm_rotate_name; @@ -121,7 +121,7 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::initialize(robot::NodeHandle & if (!rotate_algorithm_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create rotate algorithm \"%s\": returned null pointer", algorithm_rotate_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create rotate algorithm"); } rotate_algorithm_->initialize(parent_, algorithm_rotate_name, tf, costmap_robot_, traj_generator_); robot::log_info_at(__FILE__, __LINE__, "Successfully initialized rotate algorithm \"%s\"", algorithm_rotate_name.c_str()); @@ -129,7 +129,7 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::initialize(robot::NodeHandle & catch (const std::exception &ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s rotate algorithm, are you sure it is properly registered and that the containing library is built? Exception: %s", algorithm_rotate_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create rotate algorithm"); } std::string goal_checker_name; @@ -145,7 +145,7 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::initialize(robot::NodeHandle & if (!goal_checker_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create goal checker \"%s\": returned null pointer", goal_checker_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create goal checker"); } goal_checker_->initialize(parent_); robot::log_info_at(__FILE__, __LINE__, "Successfully initialized goal checker \"%s\"", goal_checker_name.c_str()); @@ -153,7 +153,7 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::initialize(robot::NodeHandle & catch (const std::exception &ex) { robot::log_error_at(__FILE__, __LINE__, "Unexpected exception while creating goal checker \"%s\": %s", goal_checker_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create goal checker"); } this->initializeOthers(); @@ -601,7 +601,7 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::DockingPlanner::initialize(rob if (!docking_planner_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create global planner \"%s\": returned null pointer", docking_planner_name_.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create global planner"); } docking_planner_->initialize(name_, costmap_robot_); robot::log_info_at(__FILE__, __LINE__, "Created global_planner %s", docking_planner_name_.c_str()); @@ -625,7 +625,7 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::DockingPlanner::initialize(rob if (!docking_nav_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create docking nav \"%s\": returned null pointer", docking_nav_name_.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create docking nav"); } robot::NodeHandle nh_docking_nav = robot::NodeHandle(nh_priv_, docking_nav_name_); docking_nav_->initialize(nh_docking_nav, docking_nav_name_, tf_, costmap_robot_, traj_generator_); diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_go_straight_local_planner.cpp b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_go_straight_local_planner.cpp index ddbc668..4e11876 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_go_straight_local_planner.cpp +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_go_straight_local_planner.cpp @@ -80,7 +80,7 @@ void pnkx_local_planner::PNKXGoStraightLocalPlanner::initialize(robot::NodeHandl if (!traj_generator_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create trajectory generator \"%s\": returned null pointer", traj_generator_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create traj_generator"); } robot::NodeHandle nh_traj_gen = robot::NodeHandle(parent_, traj_generator_name); traj_generator_->initialize(nh_traj_gen); @@ -88,7 +88,7 @@ void pnkx_local_planner::PNKXGoStraightLocalPlanner::initialize(robot::NodeHandl catch (const std::exception& ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s traj_generator, are you sure it is properly registered and that the containing library is built? Exception: %s", traj_generator_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create traj_generator"); } std::string algorithm_nav_name = std::string("pnkx_local_planner::GoStraight"); @@ -104,14 +104,14 @@ void pnkx_local_planner::PNKXGoStraightLocalPlanner::initialize(robot::NodeHandl if (!nav_algorithm_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create algorithm \"%s\": returned null pointer", algorithm_nav_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create algorithm"); } nav_algorithm_->initialize(parent_, algorithm_nav_name, tf, costmap_robot_, traj_generator_); } catch (const std::exception& ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s algorithm , are you sure it is properly registered and that the containing library is built? Exception: %s", algorithm_nav_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create algorithm"); } std::string goal_checker_name; @@ -126,7 +126,7 @@ void pnkx_local_planner::PNKXGoStraightLocalPlanner::initialize(robot::NodeHandl if (!goal_checker_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create goal checker \"%s\": returned null pointer", goal_checker_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create goal checker"); } robot::NodeHandle nh_goal_checker = robot::NodeHandle(parent_, goal_checker_name); goal_checker_->initialize(nh_goal_checker); @@ -134,7 +134,7 @@ void pnkx_local_planner::PNKXGoStraightLocalPlanner::initialize(robot::NodeHandl catch (const std::exception& ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s Goal checker , are you sure it is properly registered and that the containing library is built? Exception: %s", goal_checker_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create goal checker"); } robot::log_info_at(__FILE__, __LINE__, "%s is initialized", name.c_str()); diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp index 5989001..962be7f 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp @@ -88,7 +88,7 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, if (!traj_generator_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create trajectory generator \"%s\": returned null pointer", traj_generator_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create traj_generator"); } robot::NodeHandle nh_traj_gen = robot::NodeHandle(parent_, traj_generator_name); traj_generator_->initialize(nh_traj_gen); @@ -97,7 +97,7 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, catch (const std::exception &ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s traj_generator, are you sure it is properly registered and that the containing library is built? Exception: %s", traj_generator_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create traj_generator"); } std::string algorithm_nav_name; @@ -113,14 +113,14 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, if (!nav_algorithm_) { robot::log_error_at(__FILE__, __LINE__, "Failed to load algorithm %s", algorithm_nav_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create algorithm"); } nav_algorithm_->initialize(parent_, algorithm_nav_name, tf, costmap_robot_, traj_generator_); } catch (const std::exception &ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s algorithm , are you sure it is properly registered and that the containing library is built? Exception: %s", algorithm_nav_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create algorithm"); } std::string algorithm_rotate_name; @@ -135,7 +135,7 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, if (!rotate_algorithm_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create rotate algorithm \"%s\": returned null pointer", algorithm_rotate_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create rotate algorithm"); } rotate_algorithm_->initialize(parent_, algorithm_rotate_name, tf, costmap_robot_, traj_generator_); robot::log_info_at(__FILE__, __LINE__, "Successfully initialized rotate algorithm \"%s\"", algorithm_rotate_name.c_str()); @@ -143,7 +143,7 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, catch (const std::exception &ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s rotate algorithm, are you sure it is properly registered and that the containing library is built? Exception: %s", algorithm_rotate_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create rotate algorithm"); } std::string goal_checker_name; @@ -159,7 +159,7 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, if (!goal_checker_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create goal checker \"%s\": returned null pointer", goal_checker_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create goal checker"); } goal_checker_->initialize(parent_); robot::log_info_at(__FILE__, __LINE__, "Successfully initialized goal checker \"%s\"", goal_checker_name.c_str()); @@ -167,7 +167,7 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, catch (const std::exception &ex) { robot::log_error_at(__FILE__, __LINE__, "Unexpected exception while creating goal checker \"%s\": %s", goal_checker_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create goal checker"); } this->initializeOthers(); diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_rotate_local_planner.cpp b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_rotate_local_planner.cpp index 0d4c5a5..f0b5718 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_rotate_local_planner.cpp +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_rotate_local_planner.cpp @@ -64,7 +64,7 @@ void pnkx_local_planner::PNKXRotateLocalPlanner::initialize(robot::NodeHandle& p if (!traj_generator_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create trajectory generator \"%s\": returned null pointer", traj_generator_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create traj_generator"); } robot::NodeHandle nh_traj_gen = robot::NodeHandle(parent_, traj_generator_name); traj_generator_->initialize(nh_traj_gen); @@ -72,7 +72,7 @@ void pnkx_local_planner::PNKXRotateLocalPlanner::initialize(robot::NodeHandle& p catch (const std::exception& ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s traj_generator, are you sure it is properly registered and that the containing library is built? Exception: %s", traj_generator_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create traj_generator"); } std::string algorithm_rotate_name = std::string("nav_algorithm::Rotate"); @@ -88,7 +88,7 @@ void pnkx_local_planner::PNKXRotateLocalPlanner::initialize(robot::NodeHandle& p if (!nav_algorithm_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create algorithm \"%s\": returned null pointer", algorithm_rotate_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create algorithm"); } robot::NodeHandle nh_algorithm = robot::NodeHandle(parent_, algorithm_rotate_name); nav_algorithm_->initialize(nh_algorithm, algorithm_rotate_name, tf, costmap_robot_, traj_generator_); @@ -96,7 +96,7 @@ void pnkx_local_planner::PNKXRotateLocalPlanner::initialize(robot::NodeHandle& p catch (const std::exception& ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s algorithm , are you sure it is properly registered and that the containing library is built? Exception: %s", algorithm_rotate_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create algorithm"); } std::string goal_checker_name; @@ -111,7 +111,7 @@ void pnkx_local_planner::PNKXRotateLocalPlanner::initialize(robot::NodeHandle& p if (!goal_checker_) { robot::log_error_at(__FILE__, __LINE__, "Failed to create goal checker \"%s\": returned null pointer", goal_checker_name.c_str()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create goal checker"); } robot::NodeHandle nh_goal_checker = robot::NodeHandle(parent_, goal_checker_name); goal_checker_->initialize(nh_goal_checker); @@ -119,7 +119,7 @@ void pnkx_local_planner::PNKXRotateLocalPlanner::initialize(robot::NodeHandle& p catch (const std::exception& ex) { robot::log_error_at(__FILE__, __LINE__, "Failed to create the %s Goal checker , are you sure it is properly registered and that the containing library is built? Exception: %s", goal_checker_name.c_str(), ex.what()); - exit(1); + throw robot_nav_core2::LocalPlannerException("Failed to create goal checker"); } robot::log_info_at(__FILE__, __LINE__, "%s is sucessed", name.c_str()); From c05a3e4439b59c571f245c9a3eb97ddcac70d4f9 Mon Sep 17 00:00:00 2001 From: HiepLM Date: Sat, 21 Mar 2026 19:04:32 +0700 Subject: [PATCH 11/11] fix bug --- .../src/diff/diff_predictive_trajectory.cpp | 8 +- .../Packages/global_planners/dock_planner | 2 +- .../src/two_points_planner.cpp | 29 ++-- .../src/pnkx_docking_local_planner.cpp | 48 +++++- .../src/pnkx_local_planner.cpp | 1 + src/Libraries/laser_geometry | 2 +- src/Libraries/robot_cpp/src/node_handle.cpp | 3 +- .../robot_cpp/src/plugin_loader_helper.cpp | 1 + .../robot_nav_core/base_local_planner.h | 12 ++ .../local_planner_adapter.h | 5 - .../src/local_planner_adapter.cpp | 6 +- .../Packages/move_base/src/move_base.cpp | 141 +++++++++++++----- 12 files changed, 182 insertions(+), 76 deletions(-) diff --git a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp index 121d050..5a12570 100644 --- a/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp +++ b/src/Algorithms/Libraries/mkt_algorithm/src/diff/diff_predictive_trajectory.cpp @@ -789,16 +789,16 @@ bool mkt_algorithm::diff::PredictiveTrajectory::shouldRotateToPath( // (is_stopped || sign(angle_to_path) * sign_x < 0 ) && fabs(angle_to_path) > heading_rotate; bool result = use_rotate_to_heading_ && fabs(angle_to_path) > heading_rotate; -#ifdef BUILD_WITH_ROS - if (result) - ROS_WARN_THROTTLE(0.1, "angle_to_path: %f, heading_rotate: %f, is_stopped: %x %x, sign_x: %f", angle_to_path, heading_rotate, is_stopped, sign(angle_to_path) * sign_x < 0, sign_x); +// #ifdef BUILD_WITH_ROS + // if (result) + // ROS_WARN_THROTTLE(0.1, "angle_to_path: %f, heading_rotate: %f, is_stopped: %x %x, sign_x: %f", angle_to_path, heading_rotate, is_stopped, sign(angle_to_path) * sign_x < 0, sign_x); // else if(fabs(velocity.x) < min_speed_xy_) // { // ROS_INFO_THROTTLE(0.1, "velocity.x: %f, velocity.theta: %f, ", velocity.x, velocity.theta); // ROS_INFO_THROTTLE(0.1, "angle_to_path: %f, heading_rotate: %f, is_stopped: %x %x, sign_x: %f", angle_to_path, heading_rotate, is_stopped, sign(angle_to_path) * sign_x < 0, sign_x); // } -#endif +// #endif return result; } diff --git a/src/Algorithms/Packages/global_planners/dock_planner b/src/Algorithms/Packages/global_planners/dock_planner index 56d05e4..d51ecc0 160000 --- a/src/Algorithms/Packages/global_planners/dock_planner +++ b/src/Algorithms/Packages/global_planners/dock_planner @@ -1 +1 @@ -Subproject commit 56d05e4322a9ef57c7e421d86d244f764edefcfe +Subproject commit d51ecc0986a5ebe3ed728477bd2fa0aabbba85da diff --git a/src/Algorithms/Packages/global_planners/two_points_planner/src/two_points_planner.cpp b/src/Algorithms/Packages/global_planners/two_points_planner/src/two_points_planner.cpp index eac6f13..0953730 100755 --- a/src/Algorithms/Packages/global_planners/two_points_planner/src/two_points_planner.cpp +++ b/src/Algorithms/Packages/global_planners/two_points_planner/src/two_points_planner.cpp @@ -36,8 +36,6 @@ namespace two_points_planner if (!initialized_) { robot::NodeHandle nh_priv_("~/" + name); - robot::log_info("TwoPointsPlanner: Name is %s", name.c_str()); - int lethal_obstacle; nh_priv_.getParam("lethal_obstacle", lethal_obstacle, 20); lethal_obstacle_ = (unsigned char)lethal_obstacle; @@ -121,6 +119,7 @@ namespace two_points_planner robot::log_error("[%s:%d]\n TwoPointsPlanner: Global planner is not initialized", __FILE__, __LINE__); return false; } + robot_nav_2d_msgs::Pose2DStamped start_2d = robot_nav_2d_utils::poseStampedToPose2D(start); robot_nav_2d_msgs::Pose2DStamped goal_2d = robot_nav_2d_utils::poseStampedToPose2D(goal); robot::log_info_at(__FILE__, __LINE__, "Making plan from start (%.2f,%.2f,%.2f) to goal (%.2f,%.2f,%.2f)", @@ -148,21 +147,21 @@ namespace two_points_planner } plan.clear(); - plan.push_back(start); + // plan.push_back(start); - unsigned int mx_start, my_start; - unsigned int mx_end, my_end; - if (!costmap_robot_->getCostmap()->worldToMap(start.pose.position.x, - start.pose.position.y, - mx_start, my_start) + // unsigned int mx_start, my_start; + // unsigned int mx_end, my_end; + // if (!costmap_robot_->getCostmap()->worldToMap(start.pose.position.x, + // start.pose.position.y, + // mx_start, my_start) - || !costmap_robot_->getCostmap()->worldToMap(goal.pose.position.x, - goal.pose.position.y, - mx_end, my_end)) - { - robot::log_error("[%s:%d]\n TwoPointsPlanner: can not convert world to Map 'start point' or 'goal point'", __FILE__, __LINE__); - return false; - } + // || !costmap_robot_->getCostmap()->worldToMap(goal.pose.position.x, + // goal.pose.position.y, + // mx_end, my_end)) + // { + // robot::log_error("[%s:%d]\n TwoPointsPlanner: can not convert world to Map 'start point' or 'goal point'", __FILE__, __LINE__); + // return false; + // } // unsigned char start_cost = costMapCostToSBPLCost(costmap_robot_->getCostmap()->getCost(mx_start, my_start)); // unsigned char end_cost = costMapCostToSBPLCost(costmap_robot_->getCostmap()->getCost(mx_end, my_end)); // if (start_cost == costMapCostToSBPLCost(robot_costmap_2d::LETHAL_OBSTACLE) || start_cost == costMapCostToSBPLCost(robot_costmap_2d::INSCRIBED_INFLATED_OBSTACLE) diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp index 7a59917..51e318f 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_docking_local_planner.cpp @@ -250,11 +250,16 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::reset() if(rotate_algorithm_) rotate_algorithm_->reset(); ret_nav_ = ret_angle_ = false; + robot::log_info_at(__FILE__, __LINE__, "Debug"); + parent_.printParams(); std::string algorithm_nav_name; planner_nh_.param("algorithm_nav_name", algorithm_nav_name, std::string("pnkx_local_planner::PTA")); + // parent_.setParam(algorithm_nav_name, original_papams_); robot::NodeHandle nh_algorithm = robot::NodeHandle(parent_, algorithm_nav_name); - parent_.setParam(algorithm_nav_name, original_papams_); nh_algorithm.setParam("allow_rotate", false); + + robot::log_info_at(__FILE__, __LINE__, "Debug ở đây"); + parent_.printParams(); } void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity) @@ -567,17 +572,50 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::dockingHanlde(const robot_nav_ } pnkx_local_planner::PNKXDockingLocalPlanner::DockingPlanner::DockingPlanner(const std::string &name) - : initialized_(false), is_goal_reached_(false), delayed_(false), detected_timeout_(false), - is_detected_(false), name_(name), docking_planner_name_(""), docking_nav_name_("") + : initialized_(false), + is_detected_(false), + is_goal_reached_(false), + following_(false), + allow_rotate_(false), + xy_goal_tolerance_(0.05), + yaw_goal_tolerance_(0.05), + min_lookahead_dist_(0.4), + max_lookahead_dist_(1.0), + lookahead_time_(1.5), + angle_threshold_(0.4), + name_(name), + docking_planner_name_(), + docking_nav_name_(), + docking_planner_(nullptr), + docking_nav_(nullptr), + linear_(), + angular_(), + nh_(), + nh_priv_(), + tf_(nullptr), + costmap_robot_(nullptr), + traj_generator_(), + docking_planner_loader_(), + docking_nav_loader_(), + detected_timeout_wt_(), + delayed_wt_(), + delayed_(false), + detected_timeout_(false), + robot_base_frame_(), + maker_goal_frame_() { } pnkx_local_planner::PNKXDockingLocalPlanner::DockingPlanner::~DockingPlanner() { - if (docking_planner_) + detected_timeout_wt_.stop(); + delayed_wt_.stop(); + if (docking_planner_ != nullptr) { docking_planner_.reset(); - if (docking_nav_) + } + if (docking_nav_ != nullptr) { docking_nav_.reset(); + } } void pnkx_local_planner::PNKXDockingLocalPlanner::DockingPlanner::initialize(robot::NodeHandle &nh, TFListenerPtr tf, robot_costmap_2d::Costmap2DROBOT *costmap_robot, diff --git a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp index 962be7f..753985c 100644 --- a/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp +++ b/src/Algorithms/Packages/local_planners/pnkx_local_planner/src/pnkx_local_planner.cpp @@ -107,6 +107,7 @@ void pnkx_local_planner::PNKXLocalPlanner::initialize(robot::NodeHandle &parent, { robot::PluginLoaderHelper loader; std::string path_file_so = loader.findLibraryPath(algorithm_nav_name); + robot::log_info_at(__FILE__, __LINE__, "path_file_so: %s", path_file_so.c_str()); nav_algorithm_loader_ = boost::dll::import_alias( path_file_so, algorithm_nav_name, boost::dll::load_mode::append_decorations); nav_algorithm_ = nav_algorithm_loader_(); diff --git a/src/Libraries/laser_geometry b/src/Libraries/laser_geometry index 50062ef..7e70a03 160000 --- a/src/Libraries/laser_geometry +++ b/src/Libraries/laser_geometry @@ -1 +1 @@ -Subproject commit 50062ef54970ffb6a88f550cfd7dac7a6d587041 +Subproject commit 7e70a03bc004074075bb03db66e59b75bf3f19f5 diff --git a/src/Libraries/robot_cpp/src/node_handle.cpp b/src/Libraries/robot_cpp/src/node_handle.cpp index 7d38393..2b70a79 100644 --- a/src/Libraries/robot_cpp/src/node_handle.cpp +++ b/src/Libraries/robot_cpp/src/node_handle.cpp @@ -651,7 +651,8 @@ namespace robot std::string key = it->first.as(); const YAML::Node &value = it->second; std::string full_key = prefix.empty() ? key : prefix + "/" + key; - + if(full_key.find("MKTAlgorithmDiffPredictiveTrajectory") == std::string::npos) + continue; if (value.IsMap()) { std::cout << "[NodeHandle] " << indent << full_key << ":" << std::endl; diff --git a/src/Libraries/robot_cpp/src/plugin_loader_helper.cpp b/src/Libraries/robot_cpp/src/plugin_loader_helper.cpp index a109fab..ea1dbe8 100644 --- a/src/Libraries/robot_cpp/src/plugin_loader_helper.cpp +++ b/src/Libraries/robot_cpp/src/plugin_loader_helper.cpp @@ -66,6 +66,7 @@ std::string PluginLoaderHelper::findLibraryPath(const std::string& symbol_name) } // Try to read from NodeHandle std::string library_path; + robot::log_info_at(__FILE__, __LINE__, "%s", symbol_name.c_str()); if (nh_.hasParam(param_path)) { nh_.getParam(param_path, library_path, std::string("")); if (!library_path.empty()) { diff --git a/src/Navigations/Cores/robot_nav_core/include/robot_nav_core/base_local_planner.h b/src/Navigations/Cores/robot_nav_core/include/robot_nav_core/base_local_planner.h index 5373293..09dfc71 100755 --- a/src/Navigations/Cores/robot_nav_core/include/robot_nav_core/base_local_planner.h +++ b/src/Navigations/Cores/robot_nav_core/include/robot_nav_core/base_local_planner.h @@ -41,6 +41,7 @@ #include #include #include +#include #include namespace robot_nav_core @@ -148,6 +149,12 @@ namespace robot_nav_core */ virtual void initialize(std::string name, tf3::BufferCore *tf, robot_costmap_2d::Costmap2DROBOT *costmap_robot) = 0; + /** + * @brief Set the odometry of the robot + * @param odom The odometry of the robot + */ + virtual void setOdom(robot_nav_msgs::Odometry *odom) { odom_ = odom; } + /** * @brief Virtual destructor for the interface */ @@ -155,6 +162,11 @@ namespace robot_nav_core protected: BaseLocalPlanner() {} + + /** + * @brief The odometry of the robot + */ + robot_nav_msgs::Odometry *odom_; }; } // namespace robot_nav_core diff --git a/src/Navigations/Cores/robot_nav_core_adapter/include/robot_nav_core_adapter/local_planner_adapter.h b/src/Navigations/Cores/robot_nav_core_adapter/include/robot_nav_core_adapter/local_planner_adapter.h index 0bb1184..8bd4e12 100755 --- a/src/Navigations/Cores/robot_nav_core_adapter/include/robot_nav_core_adapter/local_planner_adapter.h +++ b/src/Navigations/Cores/robot_nav_core_adapter/include/robot_nav_core_adapter/local_planner_adapter.h @@ -189,11 +189,6 @@ namespace robot_nav_core_adapter robot_nav_2d_msgs::Pose2DStamped last_goal_; bool has_active_goal_; - /** - * @brief The odometry of the robot - */ - robot_nav_msgs::Odometry odom_; - // Plugin handling boost::function planner_loader_; robot_nav_core2::LocalPlanner::Ptr planner_; diff --git a/src/Navigations/Cores/robot_nav_core_adapter/src/local_planner_adapter.cpp b/src/Navigations/Cores/robot_nav_core_adapter/src/local_planner_adapter.cpp index 3126c0e..e3b82e9 100755 --- a/src/Navigations/Cores/robot_nav_core_adapter/src/local_planner_adapter.cpp +++ b/src/Navigations/Cores/robot_nav_core_adapter/src/local_planner_adapter.cpp @@ -88,7 +88,7 @@ namespace robot_nav_core_adapter private_nh_ = robot::NodeHandle("~"); adapter_nh_ = robot::NodeHandle(private_nh_, name); - + std::string planner_name; if (adapter_nh_.hasParam("planner_name")) { @@ -291,7 +291,7 @@ namespace robot_nav_core_adapter robot_geometry_msgs::Twist LocalPlannerAdapter::getActualTwist() { - return odom_.twist.twist; + return odom_->twist.twist; } bool LocalPlannerAdapter::islock() @@ -356,7 +356,7 @@ namespace robot_nav_core_adapter if (!getRobotPose(pose2d)) return false; - robot_nav_2d_msgs::Twist2D velocity = robot_nav_2d_utils::twist3Dto2D(odom_.twist.twist); + robot_nav_2d_msgs::Twist2D velocity = robot_nav_2d_utils::twist3Dto2D(odom_->twist.twist); bool ret = planner_->isGoalReached(pose2d, velocity); if (ret) { diff --git a/src/Navigations/Packages/move_base/src/move_base.cpp b/src/Navigations/Packages/move_base/src/move_base.cpp index dcec1de..2c0185c 100644 --- a/src/Navigations/Packages/move_base/src/move_base.cpp +++ b/src/Navigations/Packages/move_base/src/move_base.cpp @@ -324,6 +324,7 @@ void move_base::MoveBase::initialize(robot::TFListenerPtr tf) throw std::runtime_error("Failed to load local planner " + local_planner); } tc_->initialize(local_planner, tf_.get(), controller_costmap_robot_); + tc_->setOdom(&odometry_); } catch (const std::exception &ex) { @@ -1781,32 +1782,6 @@ void move_base::MoveBase::cancel() boost::unique_lock lock(*(controller_costmap_robot_->getCostmap()->getMutex())); cancel_ctr_ = true; robot::log_info("[MoveBase::cancel] cancel_ctr_ set to true"); - - if (as_) - { - // Get current goal ID from action server to cancel specific goal - // If we want to cancel all goals, use empty string "" - robot_actionlib_msgs::GoalIDPtr msg = boost::make_shared(); - - // Use empty string to cancel current goal (processCancel accepts empty string to cancel all) - msg->id = ""; // Empty string cancels current goal - msg->stamp = robot::Time::now(); - - robot::log_info("[MoveBase::cancel] Sending cancel request to action server"); - robot::log_info("[MoveBase::cancel] Cancel message: id='%s', stamp=%ld.%09ld", - msg->id.c_str(), msg->stamp.sec, msg->stamp.nsec); - - // Convert to ConstPtr for processCancel - robot_actionlib_msgs::GoalIDConstPtr cancel_msg = msg; - as_->processCancel(cancel_msg); - robot::log_info("[MoveBase::cancel] Cancel request processed by action server"); - } - else - { - robot::log_warning("[MoveBase::cancel] Action server (as_) is null - cannot send cancel request"); - } - - robot::log_info("[MoveBase::cancel] ===== EXIT ====="); } bool move_base::MoveBase::getRobotPose(robot_geometry_msgs::PoseStamped &pose) @@ -2381,8 +2356,9 @@ void move_base::MoveBase::executeCb(const robot_move_base_msgs::MoveBaseGoalCons robot::log_info("Received goal: x=%.2f, y=%.2f", move_base_goal->target_pose.pose.position.x, move_base_goal->target_pose.pose.position.y); } } - + robot::log_warning("Received goal: x=%.2f, y=%.2f", move_base_goal->target_pose.pose.position.x, move_base_goal->target_pose.pose.position.y); robot_geometry_msgs::PoseStamped goal = goalToGlobalFrame(move_base_goal->target_pose); + robot::log_warning("Received goalToGlobalFrame: x=%.2f, y=%.2f", goal.pose.position.x, goal.pose.position.y); publishZeroVelocity(); // we have a goal so start the planner boost::unique_lock lock(planner_mutex_); @@ -2602,7 +2578,6 @@ bool move_base::MoveBase::isQuaternionValid(const robot_geometry_msgs::Quaternio robot::log_error("Quaternion has nans or infs... discarding as a navigation goal"); return false; } - tf3::Quaternion tf_q(q.x, q.y, q.z, q.w); // next, we need to check if the length of the quaternion is close to zero @@ -2764,6 +2739,7 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal) recovery_index_ = 0; } + // Cancle executeCycle if (cancel_ctr_ && tc_) { @@ -2772,13 +2748,25 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal) tc_->setTwistLinear(linear); try { - if (fabs(tc_->getActualTwist().linear.x) <= min_approach_linear_velocity_) + double actual_linear_velocity = sqrt(std::pow(tc_->getActualTwist().linear.x, 2) + std::pow(tc_->getActualTwist().linear.y, 2)); + if (actual_linear_velocity <= min_approach_linear_velocity_) { robot::log_info("MoveTo is canceled."); resetState(); + cancel_ctr_ = false; // if(default_config_.base_global_planner != last_config_.base_global_planner) - swapPlanner(default_config_.base_global_planner); - + robot::NodeHandle nh_planner = robot::NodeHandle(private_nh_, position_planner_name_); + if(nh_planner.hasParam("base_global_planner")) + { + std::string base_global_planner; + nh_planner.getParam("base_global_planner", base_global_planner); + swapPlanner(base_global_planner); + } + else + { + swapPlanner(default_config_.base_global_planner); + } + cancel_ctr_ = false; // disable the planner thread boost::unique_lock lock(planner_mutex_); runPlanner_ = false; @@ -2789,7 +2777,21 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal) nav_feedback_->navigation_state = robot::move_base_core::State::PREEMPTED; } // as_->setPreempted(robot_move_base_msgs::MoveBaseResult(), "Canled."); - cancel_ctr_ = false; + + if (as_) + { + robot_actionlib_msgs::GoalIDPtr msg = boost::make_shared(); + msg->id = ""; // Empty string cancels current goal + msg->stamp = robot::Time::now(); + // Convert to ConstPtr for processCancel + robot_actionlib_msgs::GoalIDConstPtr cancel_msg = msg; + as_->processCancel(cancel_msg); + robot::log_info("[MoveBase::cancel] Cancel request processed by action server"); + } + else + { + robot::log_warning("[MoveBase::cancel] Action server (as_) is null - cannot send cancel request"); + } return true; } } @@ -2798,7 +2800,17 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal) robot::log_info("MoveTo is canceled."); resetState(); // if(default_config_.base_global_planner != last_config_.base_global_planner) - swapPlanner(default_config_.base_global_planner); + robot::NodeHandle nh_planner = robot::NodeHandle(private_nh_, position_planner_name_); + if(nh_planner.hasParam("base_global_planner")) + { + std::string base_global_planner; + nh_planner.getParam("base_global_planner", base_global_planner); + swapPlanner(base_global_planner); + } + else + { + swapPlanner(default_config_.base_global_planner); + } // disable the planner thread boost::unique_lock lock(planner_mutex_); @@ -2810,6 +2822,20 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal) nav_feedback_->navigation_state = robot::move_base_core::State::PREEMPTED; } // as_->setPreempted(robot_move_base_msgs::MoveBaseResult(), "Canled."); + if (as_) + { + robot_actionlib_msgs::GoalIDPtr msg = boost::make_shared(); + msg->id = ""; // Empty string cancels current goal + msg->stamp = robot::Time::now(); + // Convert to ConstPtr for processCancel + robot_actionlib_msgs::GoalIDConstPtr cancel_msg = msg; + as_->processCancel(cancel_msg); + robot::log_info("[MoveBase::cancel] Cancel request processed by action server"); + } + else + { + robot::log_warning("[MoveBase::cancel] Action server (as_) is null - cannot send cancel request"); + } cancel_ctr_ = false; return true; } @@ -2830,7 +2856,6 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal) // if we're controlling, we'll attempt to find valid velocity commands case move_base::CONTROLLING: - // robot::log_debug("In controlling state."); // check to see if we've reached our goal try @@ -3004,7 +3029,8 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal) tc_->setTwistLinear(linear); try { - if (fabs(tc_->getActualTwist().linear.x) <= min_approach_linear_velocity_) + double actual_linear_velocity = sqrt(std::pow(tc_->getActualTwist().linear.x, 2) + std::pow(tc_->getActualTwist().linear.y, 2)); + if (actual_linear_velocity <= min_approach_linear_velocity_) { paused_ = true; } @@ -3108,15 +3134,48 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal) robot_geometry_msgs::PoseStamped move_base::MoveBase::goalToGlobalFrame(const robot_geometry_msgs::PoseStamped &goal_pose_msg) { - std::string global_frame = planner_costmap_robot_->getGlobalFrameID(); - robot_geometry_msgs::PoseStamped goal_pose, global_pose; - goal_pose = goal_pose_msg; - goal_pose.header.stamp = robot::Time(); // latest available + if (!tf_) + { + return goal_pose_msg; + } + + std::string global_frame = planner_costmap_robot_->getGlobalFrameID(); + // robot_geometry_msgs::PoseStamped goal_pose, global_pose; + // goal_pose = goal_pose_msg; + + // goal_pose.header.stamp = robot::Time(); // latest available + // try + // { + // tf3::TransformStampedMsg transform = tf_->lookupTransform(global_frame, goal_pose.header.frame_id, tf3::Time()); + // tf3::doTransform(goal_pose, global_pose, transform); + // } + robot_geometry_msgs::PoseStamped global_pose; + tf3::toMsg(tf3::Transform::getIdentity(), global_pose.pose); + robot_geometry_msgs::PoseStamped goal_pose; + tf3::toMsg(tf3::Transform::getIdentity(), goal_pose.pose); + goal_pose = goal_pose_msg; + robot::Time current_time = robot::Time::now(); // save time for checking tf delay later + tf3::Time tf3_current_time = data_convert::convertTime(current_time); + tf3::Time tf3_zero_time = data_convert::convertTime(robot::Time()); + try { - tf3::TransformStampedMsg transform = tf_->lookupTransform(global_frame, goal_pose.header.frame_id, tf3::Time()); - tf3::doTransform(goal_pose, global_pose, transform); + // use current time if possible (makes sure it's not in the future) + std::string error_msg; + if (tf_->canTransform(global_frame, goal_pose.header.frame_id, tf3_current_time, &error_msg)) + { + // Transform is available at current time + tf3::TransformStampedMsg transform = tf_->lookupTransform(global_frame, goal_pose.header.frame_id, tf3_current_time); + tf3::doTransform(goal_pose, global_pose, transform); + } + // use the latest otherwise (tf3::Time() means latest available) + else + { + // Try to get latest transform + tf3::TransformStampedMsg transform = tf_->lookupTransform(global_frame, goal_pose.header.frame_id, tf3_zero_time); + tf3::doTransform(goal_pose, global_pose, transform); + } } catch (tf3::LookupException &ex) {