From e4f037cef1d3ee8fd6addb4c87615820578df96c Mon Sep 17 00:00:00 2001 From: nsubiron Date: Wed, 7 Mar 2018 12:36:58 +0100 Subject: [PATCH] Change units to SI --- Docs/Example.CarlaSettings.ini | 12 ++--- Docs/cameras_and_sensors.md | 40 ++++++++------- ...mple.png => road_instructions_example.png} | Bin Docs/img/steering_angle_mustang.png | Bin 0 -> 238323 bytes Docs/map_customization.md | 2 +- Docs/measurements.md | 47 ++++++++++-------- PythonClient/carla/benchmarks/benchmark.py | 4 +- PythonClient/carla/benchmarks/corl_2017.py | 2 +- PythonClient/carla/image_converter.py | 2 +- PythonClient/carla/planner/converter.py | 1 + PythonClient/carla/sensor.py | 4 +- PythonClient/client_example.py | 16 +++--- PythonClient/manual_control.py | 12 ++--- PythonClient/point_cloud_example.py | 2 +- .../Carla/Agent/WalkerAgentComponent.cpp | 2 +- .../Source/Carla/Agent/WalkerAgentComponent.h | 2 +- .../Carla/Source/Carla/Game/CarlaHUD.cpp | 15 +++--- .../Source/Carla/Server/CarlaEncoder.cpp | 21 ++++---- .../Carla/Settings/LidarDescription.cpp | 2 +- .../Source/Carla/Settings/LidarDescription.h | 2 +- .../Carla/Settings/SensorDescription.cpp | 7 +-- .../Plugins/Carla/Source/Carla/Util/IniFile.h | 4 +- .../Carla/Vehicle/CarlaVehicleController.cpp | 2 +- .../Carla/Vehicle/CarlaWheeledVehicle.cpp | 2 +- .../Carla/Vehicle/CarlaWheeledVehicle.h | 2 +- .../Vehicle/WheeledVehicleAIController.cpp | 3 +- Util/CarlaServer/include/carla/carla_server.h | 5 +- 27 files changed, 118 insertions(+), 95 deletions(-) rename Docs/img/{Road_Instructions_Example.png => road_instructions_example.png} (100%) create mode 100644 Docs/img/steering_angle_mustang.png diff --git a/Docs/Example.CarlaSettings.ini b/Docs/Example.CarlaSettings.ini index 8e08b0cfd..4138defa6 100644 --- a/Docs/Example.CarlaSettings.ini +++ b/Docs/Example.CarlaSettings.ini @@ -70,10 +70,10 @@ ImageSizeX=800 ImageSizeY=600 ; Camera (horizontal) field of view in degrees. FOV=90 -; Position of the camera relative to the car in centimeters. -PositionX=15 +; Position of the camera relative to the car in meters. +PositionX=0.20 PositionY=0 -PositionZ=123 +PositionZ=1.30 ; Rotation of the camera relative to the car in degrees. RotationPitch=8 RotationRoll=0 @@ -89,8 +89,8 @@ PostProcessing=Depth SensorType=LIDAR_RAY_TRACE ; Number of lasers. Channels=32 -; Measure distance in centimeters. -Range=5000 +; Measure distance in meters. +Range=50.0 ; Points generated by all lasers per second. PointsPerSecond=100000 ; Lidar rotation frequency. @@ -101,7 +101,7 @@ LowerFOVLimit=-30 ; Position and rotation relative to the vehicle. PositionX=0 PositionY=0 -PositionZ=140 +PositionZ=1.40 RotationPitch=0 RotationYaw=0 RotationRoll=0 diff --git a/Docs/cameras_and_sensors.md b/Docs/cameras_and_sensors.md index 4bd2c9d4f..45ce66f07 100644 --- a/Docs/cameras_and_sensors.md +++ b/Docs/cameras_and_sensors.md @@ -1,6 +1,10 @@ Cameras and sensors =================== +!!! important + Since version 0.8.0 the positions of the sensors are specified in meters + instead of centimeters. Always relative to the vehicle. + Cameras and sensors can be added to the player vehicle by defining them in the settings sent by the client on every new episode. This can be done either by filling a `CarlaSettings` Python class ([client_example.py][clientexamplelink]) @@ -39,7 +43,7 @@ using the functions at `carla.image_converter` Python module. Camera: Scene final ------------------- -![SceneFinal](img/capture_scenefinal.png)
+![SceneFinal](img/capture_scenefinal.png) The "scene final" camera provides a view of the scene after applying some post-processing effects to create a more realistic feel. These are actually @@ -61,7 +65,7 @@ in the Camera. We use the following post process effects: camera = carla.sensor.Camera('MyCamera', PostProcessing='SceneFinal') camera.set(FOV=90.0) camera.set_image_size(800, 600) -camera.set_position(x=30, y=0, z=130) +camera.set_position(x=0.30, y=0, z=1.30) camera.set_rotation(pitch=0, yaw=0, roll=0) carla_settings.add_sensor(camera) @@ -76,9 +80,9 @@ PostProcessing=SceneFinal ImageSizeX=800 ImageSizeY=600 FOV=90 -PositionX=30 +PositionX=0.30 PositionY=0 -PositionZ=130 +PositionZ=1.30 RotationPitch=0 RotationRoll=0 RotationYaw=0 @@ -122,7 +126,7 @@ seen in "PythonClient/point_cloud_example.py". camera = carla.sensor.Camera('MyCamera', PostProcessing='Depth') camera.set(FOV=90.0) camera.set_image_size(800, 600) -camera.set_position(x=30, y=0, z=130) +camera.set_position(x=0.30, y=0, z=1.30) camera.set_rotation(pitch=0, yaw=0, roll=0) carla_settings.add_sensor(camera) @@ -137,9 +141,9 @@ PostProcessing=Depth ImageSizeX=800 ImageSizeY=600 FOV=90 -PositionX=30 +PositionX=0.30 PositionY=0 -PositionZ=130 +PositionZ=1.30 RotationPitch=0 RotationRoll=0 RotationYaw=0 @@ -192,7 +196,7 @@ _"Unreal/CarlaUE4/Content/Static/Pedestrians"_ folder it's tagged as pedestrian. camera = carla.sensor.Camera('MyCamera', PostProcessing='SemanticSegmentation') camera.set(FOV=90.0) camera.set_image_size(800, 600) -camera.set_position(x=30, y=0, z=130) +camera.set_position(x=0.30, y=0, z=1.30) camera.set_rotation(pitch=0, yaw=0, roll=0) carla_settings.add_sensor(camera) @@ -207,9 +211,9 @@ PostProcessing=SemanticSegmentation ImageSizeX=800 ImageSizeY=600 FOV=90 -PositionX=30 +PositionX=0.30 PositionY=0 -PositionZ=130 +PositionZ=1.30 RotationPitch=0 RotationRoll=0 RotationYaw=0 @@ -234,10 +238,10 @@ The received `LidarMeasurement` object contains the following information Key | Type | Description -------------------------- | ---------- | ------------ -horizontal_angle | float | Angle in XY plane of the lidar this frame -channels | uint32 | Number of channels (lasers) of the lidar -point_count_by_channel | uint32 | Number of points per channel captured this frame -point_cloud | PointCloud | Captured points this frame +horizontal_angle | float | Angle in XY plane of the lidar this frame (in degrees). +channels | uint32 | Number of channels (lasers) of the lidar. +point_count_by_channel | uint32 | Number of points per channel captured this frame. +point_cloud | PointCloud | Captured points this frame. ###### Python @@ -245,12 +249,12 @@ point_cloud | PointCloud | Captured points this frame lidar = carla.sensor.Lidar('MyLidar') lidar.set( Channels=32, - Range=5000, + Range=50, PointsPerSecond=100000, RotationFrequency=10, UpperFovLimit=10, LowerFovLimit=-30) -lidar.set_position(x=0, y=0, z=140) +lidar.set_position(x=0, y=0, z=1.40) lidar.set_rotation(pitch=0, yaw=0, roll=0) carla_settings.add_sensor(lidar) @@ -262,14 +266,14 @@ carla_settings.add_sensor(lidar) [CARLA/Sensor/MyLidar] SensorType=LIDAR_RAY_TRACE Channels=32 -Range=5000 +Range=50 PointsPerSecond=100000 RotationFrequency=10 UpperFOVLimit=10 LowerFOVLimit=-30 PositionX=0 PositionY=0 -PositionZ=140 +PositionZ=1.40 RotationPitch=0 RotationYaw=0 RotationRoll=0 diff --git a/Docs/img/Road_Instructions_Example.png b/Docs/img/road_instructions_example.png similarity index 100% rename from Docs/img/Road_Instructions_Example.png rename to Docs/img/road_instructions_example.png diff --git a/Docs/img/steering_angle_mustang.png b/Docs/img/steering_angle_mustang.png new file mode 100644 index 0000000000000000000000000000000000000000..2ac4eab18f10037d13d88e3308289d123f1727c7 GIT binary patch literal 238323 zcmV)KK)Sz)P) z|N5W*LsboIreTCJ+cBlAl|lPz6*33I#J` z@W6FV?7hK6Q26imPb8uk{(X5co@Ze&WBT8D?gt9{EY~&hdR-u5?7ad19jXd|u=lQK z>dy{DASj6J&oRON8TRMkpGUS}=ijksAtGRZRw9bEH^v;8V?bm>)t^1t?-o&vF)#*$ znZZoBt_!M)^(?4=-+UPa>@COVW+o6ZM0UNmTpxgl{dwk*{~I%7410$5KKvKh|G^jp z=Hc(G*4ep26a)gXeFpaR#LR#y{{HJ5*XxD%`;DLXZR@~46Eo${v}bRhH`b^^u0HQ^41||8QT2Dr##_)Ze%L@2Zl|3_z}l+&4t^{Foss zAQ0Bx`FF-(%sH{v##+mNwLO>Db@_TEthMp1C%=QO&)Q3a2VkEvpZQ?h*W&APi~&*m z9%GDL-vF?-V6O#V>QGg@F8kfr>%w(S$QC@$gS`dMTKo=Zvd~Xr^-D^Ey;ym9(?0o6_atwz0db4NUzXR~U|Ih!$ zm;=|Gw*EENrr>#OEsr^D-vHpj@v(dlA@^TA+j`HG{}-_L1wUIU&t>HO5Nk*!?xB8m z*K>@0n(sNEmwgsd$@ds{l-*-;e7^XMbBn9?SLP1U@&8g z+MZG1ngic|ePPZCRruZ~U$?e)^IY{qCBEKl=TO|)W7J-^|BL)@U)c6OK)H9u7_FYD za|nJPN1Za5alJ0gIRORk=dRx&VrLY9=h=9k$KH!w(ilv>uIug~A`mn7TG(6ibJ%{h zbGFxCy=XJ1?V(0Crq`DfJEc6{GC2A;JbTYUdgyDM!?_F94vb)kLc z_#B+S!)no}r(z?IVRc}fFR>p))b1((b57sWoS!lNempzdt5o0B&rl-vJ+O~6G2Yo2 z19MJ%e}CCsFB^Lc*4}uYmA^0VytX#T@2xp!t2tq3ORIsRj#CA$%g)@}>(@C4pupNI z>mxfOIPYrmS}SVPYhDo9c;CMN2^e$cXWDz!ozc#}Si7J9p^tSEwNJmJ)i$=T8_Ie= z_A@i*yN}*w#s()6jKR3(!2N9d%LI_0vS*<{(D8l821_t~xY0FN*8> zxDc2?s>cBz&Ksg&_+sG4RPV6lZMHZ=hZF_IIMx)U=H&k5KbB??i zMQjaJ;fLH@>>EEWrC5t`umS)@!vg{_AOaBEXUN731JARLjZN*K-+r)W!>6#~RqL=& zQ9Gp6i{WVe{a|0dPWRe*s2@$HzZ=z+Yu?uX@Qc=(q3`c+Ff*R#!TY|wp|?G}Rj~FO zuh%R0lNAzzIjligPkomywtlt z3&gqw*c)wIt9Ir^VL8Xlv(WZ{;G=%Wj-rGK19eFawkC|dVTeLQqG)UdD-mJm8Bk}Y zm%RC%478zENRppPc1d2Z3mQcUMIkPA%?fOt_#@XEf!62E-TyiM_WKX?x?oAG;Ts ztcXN!2>jb~6^){Rcr&8pXD2c2db9O2hTW6T^Vr&*!_J<)3LNsg)%McP!mz$Gj*gB3 zFiJ2r8U+Gn&12tP9iZyJD~b;*G9??b!2_aIFwV(Y2#Q$Y$J`29txc-ldG0O8IUVI2 z6B59QGr!LA6CA1YxNV}SYof`;S%1YD+kdVVk5cCeqwY;V+pPhC*C=OW9`~%RrM?{O z`_5qv>Bz3z*RY>|)u?-MALm~`+e8xli?1YV=V>-}{(F}L&onpz*lJwWYYcAtmU559 z9VjC9|Mz=)En9N|0Ayq4#d)krk!sScfqekjSwrzsysnrIK*sk80C0F^L1@^vw`dEg9Rc2&uM@aBmo2i82vfr0K?C56d*+T@2H*GwrA~Ys=q%5X#s+< zZl#^MvkC;x;*iJ=vqVk`q-uo%`KF`1q~kJ-LrAxP2DKtC7L^@7W6XBINfyNt2i8ZI z7l(>=xU^mPV7o+OlJYz&53K(CA=P=SD3mF?LMwn07{C&NE(P<>Mj;NYSeT|zO}Ic1l0+#Ay(|Pe7cTpy?+1e+ScLn2d!sNDnd;LC{pi;7GQ&BoiGwc=;4J)! z8ggrwqcx7e`+eu-&FlpLNApnyY)nI*wQ6mty>D%YjkLz7Pg$s;=-V5HI_tF+6Ua%8 zA>C0|*>@0LUf`xqjlp7`Pt=c7X%&hhEo} zQv+?qfffBHa1h`^T(W&25bF{E*0XX?#ySnemmE=FYZ*Gv^@t6dPro2nYQUd6!h&jPxQBdG6MtW7(Owx z3yo&z&rc+u0J0GQ2UH!=_ifHs1FQs2Am6?1o%3vo|ez)ClkQ;~=3r073>L zt=*;>daRoj_YC>7n&Uv6V^S#x8>ZGoFK`uV=XoI8=ye3uncAkvx;Ka>lzp#^0Uq}K zWQzgDT9Xu}ZzYc2mBbtXlP)X5>gz`$+O`8wAWy#n6b&s1-$q7GD_fc(|K z!2NzZi{X`%`@IF%yz=)%JuqX^xmHfa1He-MeAo3#;4v629qeQWDbc1-@Tps}aQq$H zw8ooZpK#?2Lgbht#=SG5`9Oia*EN$t5c{Qr>>_sp0|^xR)ZQ9R2Z#e;jjn$0j4^*TVy`9n&|GPCgj(Px4N8kkt20Ow%3bkQ7s8wz1AjJzfC<~v6L!Vm2 zh9+uFqtZbEq29IU8nogr8aUfvj7>WaPWyhN$ZmbwA_5v#?Mo|y#~6u_t#uZFbIv>v z<7Zv-`b|~xBGyMYaL~yPMZc(DzTRSV9pm3b@H;iBH7RIQz)u=h|Bp1J@Ibp7^&uNj zt+DXMBa5TgoQYTspK6FW-OQ&jua|xQ_iglz!7p6b#JpzI34UqpW5j-4S2jLkm1j~z zW}|8(O)?rC-w(sr!t3>g>w1Cc2lD3!+t=@X-;F}SNiDQufD?hbu4#p&H)YTB*!NpI zi%)w-;#2_O?o+9?!GrQ(k3#%e%bJ4Y9aW(mMOC24@vh_DN24!ZfCTD@Y;p=|ebxi{ z*P01*phE>Dgr&P^QBffIyFci5V(9Aj#xvHwB=X8t%n?I$HPo`c%Q@1qv-_I!*sDQ# zE%3^}AK};K6_nxosy!G=pIv}GK=l+jCHZT)IhoS!< z02>FbH|~>z+TCwFDykwHSwlpQDQYxdC4UQRo`5IgWh|a29z12EvQonAFFaJUAw+ z+~}g)SP6|j)f>rR#YbU2*2uG6{mv%elTlRKUYQA;^*dHrFdZEa`f#Ajg~CzM+??t; zuW8NF{cfN}D`{7EG_JtPzzeBK`03 z7vZPxlM|q={7KMAA7NA`FzmuJK$Qh&XQIH7-;Kx=CiaZkkt}AI2$axcZ_02OxX9z z`%p#m{;5#woB06SZSqc8589O7 z8`-Z{G9!vIUR34FDXak$*g2&TUvucqIgodiHQ08>1{7`}#|Idcdz(*^TgU-a@jQ=# z1Abx7LUR3Zh!K6FK`68<&>cb{9%P7c9O2P~#DVqtdga0=0N3j>ZsYwFM|=>lDMxd0 zD3PP7lsCRN7IT1hq3+Z+`?HO%6^BPhR@RoBv=9-dUs5OXs7;^H`18A$DSgqilIbsf;P8pv$f)!`Q#^(qXs+%?)w2dO0f4XWCo$V zImh9h){?rTylfS+HT4|9-)86i#&>?b?44e7;(g!AJqA%y!{U4 zZs=pI59fSVqf}#D&^nsn9HRgMt&hP-z8~w$I-639<1yWhDxtK(cb= zA5=>%Ua`G9cHXZQ`2YUrlypMn!^jclhC(lHr|snKdw zxENWPCXJKcGo5b>`QT@(QMz8Q7k++z@)_OF(;8R7`+oa+l+q+AK%{3ApVUXLX>Ark zu?}nM2-tcHDuX!6SW_^c-Y|o_+2m~M?I+kC8Q#b$KvzwbnR8OO1HIObwQD>dzh@59 z;Bn)L+ccV-2R=^3Ql-ZBK2b1T9W^>7Cl@-_-a+RQD{JF&wf(;nMH}9zRs)SJ^i>u2 zvl6+C=E;z7E0|SKbSFpZV}1O*)f=$gVO}qGwAPu^KLRNYw76^fG&OUM@ouR`F843m zBr#5L5x{sfS1{ z3Dd7eBEiHZ0+=e$i|%0QRC4N zQ($|88Z;Zj`5a+wYfY05W9uaftfaHGLRYnDhoJ$@$%Rh@RRrIDR~j7>cpf?ETMBh5 zRIM3_wH-x$Z@$E8g_qyYL1T$^@H{IE^f5=9a@Sqbbv<3np-{|uVPS#QzcY1xBl3(7 zV3?V)yct>R_uVWSKrPp^JHWxB$0hrLioR4DT{^(a{P|7a5_Bd~N-)c&WV202j6!MD za33jlYOShkA}N6qn+`e{7*jZ>w*uts8V6EPn!0M*V!BGnAY!I$4vh_RvRM+qjqmEx zhyG`J4S+^>MQh|cz}#!Dm?Q){Y3&X6Vx3cdK)7a{@pV6l7u`9%xvtW`_!%_kh1Y93 zAbi_&B^e@qw_k1Q@iFxqDeI`oQ%sxUObWW-_4;xa&mXHRQkVPW#62|H+H|^c_Pt)O zgU0==0s}eM!mf!f5pJ&!)hWs9ApK}S^~yDZUjqPDKD0aWe)=A$8h_<^&div$urx=* z$U}0ZAlVLTKlFmGG02LAcKF+&W0%u4#=&7{KXm)$pChy;N?hwnP9z%DN8^P-!7gw_ z(?6i`ngx=So9T^BP>3`~T_HfDga0`OH!X(dn6wwVaadV#cQtC4Awzp@yk0MSe}AVa zFwSWc!Q*JW21Z^#B0B|W)PC=$p!t3l&?tB%g4HbY53~|wjbV;Tw>3#^G}%YyvP(c2 zBYRcgSpxdG{W)pUg7lyhoZ|Z^7+5J$48wC*>RrY>vj5mAH(0Kl7+)<5a020(_ zHMP$vCpV9qZUm~!Y$NaCYw&g*(%07)hL~tSra*Sd=<$AI3KPYM(L{EBE?^v!IrwMV z`$=^0n$u~5lDfudgwF{beP}x9pt`KRuzw_JtWk)nS}_}Rl33$e$ZMG~n5LrXZWP(r zbSi0}xP}-$uG^_1C?>ppA_ZyFl>{n^K37yVqaNv2KtCxJ0_K?@ol;FOfa3or<&8ge zUnrC?8h++>u1RArq;RTeVoYEZfRmGY`p`m+;h@q^lbR?33`n|c-#rf$RzQU&B$x!z z00zY~3o~Xwwj;eGSrwgTyS6~|!Eh!(fd@|a9h`<4qk(~;`Qbx2&h;$ND7$S=6*RFZ zMicQ>!Th@L*VmU9ge!|>k=-Vveui;Tj&dUGd!9$EKhFI%=L9n+@KQ9Eos*#e1Cz4d z&f_vnLSu}ChG@AqW8~Q#=LwS)^Z^9j?A6`J{I&adm`%p}`y+o#a6uVO;P#Gqj{jJSsL_4R7H?$WfH z0S_N0NF5BcW?Udb$0VG5_;P)KfwS{|r*kyp-;6O6T@T^qXo9L(P)v1U1YPTz(|Ev* zeh}iWaJ0$M{1}H*g>|HSxQcAq$t7O0ogy_3ZZ>th8K+P%vyC(ZMT!m|+T7T>KB5GB z5=fpG+o4yA%jxU;3*TQ~iOQ{Qd}h8l54PvAiAEroHK~XO3+YTo|H*O03mF@G+M)V> zzw^M40xi&}*s$5*cFGgg$lQt^q;_LBN?<@>+eiLYMD4s7=RBz}{YYr~!9;3OZ{pLX zq(U@p!3@!-BVJ$MU$&0i0N~HhkNtg-G@rmPZI6vULoYA~=f+7ohi_oJ{53^*$K@r` z=!;cIjybZaiG2`-3i(){WkYsZWF#oi=#G0YNIK(;MAwN=@vOQLL+sDpzDH3o97T3r zPSA#ez1_#c+lBZkwES@R3Is4PhkyV4N!r6&D-kH7qEE%tBq?8wvR6g{ovs+V8p&yD zG|({x^D{N~4H`wXOiM!B^9SUYOr8LNdNQ3zW)y_X5H-rv{X7_(o$l$>JTJty>?*io zTH)_lbzq$be9qvk@m$7x=lt%ya&swcXKaDbwXtw0!ryLA9 zbsDiprO|Lg!*d{GkP@gz^RKC(Z92<#Ud2Ti{CzDHG>XU2eu%j&d{8bai}&PWt0cHZ z0n1bS{wQ%R4uN`i%j>2+iZMCwhBy}`sWM?uQ8Yts`V~oP+{_C!n;1VcqJT>mqgK=f z`@s<5a%hX@I0_AB)6m#NN)qJIWqe&Ii);?uhm?i0@@AsXJ zb}*Gx1<%vKrZz<^n%+KGBhfeppr7CN}|H&_^Z`SiFktPUxNAmsw=RN&oMGtq2Sbz>9w zts4_IExoQQ0r43HV7gaObLsFeO~E%tU6fT6`P3uCMb6V_X73(5-?8g^v^kU1I%8%C z%B=+-s8C+$L@B;6%1Pr4w?7|%*g3fFD-aE{KIFi}>$Ap#3Dad@E~oWJfuM$Boo z8B>Ax`<;ix7_OCZK62yrY?N zvxl&~hKuYJc6hISJI|jINeeWm)6qg$YzRT|o?{x+U2If$qr>r0kjA=ar)z8}M3`M% z*PT?5Ht9ZTBx(~$yBKp4)9l0pg*2+0qoA{BQuxrHi7Hr(Eei6n@gq4!HN@$5+e!Il z_nx#eU#FsS{0@P_K&@s+8tbbe=t0X!7albfekdOruRN4pFUHs9%`iK9h=ZzH=hjG6 zO{BC7(Tu-d7ykbHFU&cxo`w5)@P6MZl%3wts#7%P80lDJS`niRA!%l@U#Z~-oR@99 zi~JdLCZgE{S2?lfv>lafg5%;fTBsMUsB_Vb9QY8<#-psMfRze+FN|t;QOy{0|TkF zW$_M;wl1y}F_*n`P|~8!^>eZ7e!IRcsF~ufitqQ^3uQhg!||*{^fW>Gu&s?Vs+%2% zNNQ8!Zv+?^XO}rT+Gm(eR9&uEROTn)N*g90xdu74oFOVlv;6M0)z{bSF!K2GV<70( zon|CSY3{Xw>vW5OV$D_5Ryk#Azc1tldH*!CoK86&b5s-L6W=g4FtcedOg?xyHW0WXU2p@p07Vpc+Rn--L27)OKzH-m|P|NZe; zkL{)aSL#DbgZj?t4mWv&__>z9XD}f49F??zSHDeoVi|U0gwTUU{SbA}fB&;{$_Lb* zim47en6J&%j0Xc75SXsj&dxH}nEsx(2%g*Mc(**w(wUPT)>%lhHy(F%OU8rO2?>}> zr~6Cx5F-tL3@{Z)HmuL{W(m5 z7i=iuXonLyUwpMgK$`{Ra3Malp(&ngkPb1S-Jxcxn5`_*P2Ol|69eEZ4=+I!hSx2fe`6qp`Oj8U@)TgrEyKC*NG zN&zEtJx38u+L0aDyQpR1@Y1t4yjlu(xw1F*No81ON4|g~b8VP!w!>CERFUq7W*oYY zEZ_6e5dGm7@MSR7Mp_^G=2kMaUpjRaCgs4r#JCt8E3;D zdb7;S>8_PtFj^*<)1$)`l!o0?1F5+RYtlfJ+5f$^EQazfD=;wLMHfmNIM${^{tSle zV9;!E1A!03SQ{l~?_EX&(d7EQntIBvTM3sf|9P5XbTg1?vv#}ht_gB5aL#e)5~O9D z5EEEy>ZhQjyvCi`>FMejGGQd64G>vt=Y*J<@$+-LZiRq3tUggK2Qbk?&z67zGp_4p zYkvdGnl!fp2es)@8W@-s>f=`-#*NmURLZ7x5!4;pjdkKaKj}VvObU{2l$N)3u9Vi| zEMyO@re~IQtVBf2n%^DIxVx5gcR!yDPp2j;;w&E!ciV&7)Zg|6r^WE_`!y$5UVkvv zN+XIaBonoPzmZ|Mj;6^$+g%jkiyB z;Erig|4kkk*GR`iaxhR=<+_1S7dKG3`(@lnGcjQA8wQ{)#;vI2jR%mkxN)$hWAT?1mYYOBjq@p{_OHP&}(W9~us0oeYf_G#s znwaaFX&V?FzqEoTEG>HxA4SkfaVg|JeCf5L*klvdr zY5LR%j8TDYAzsu*iwNZ4bhqm?rb5KBVGa9HKd_CiBF$=ef6{W#Kj)ihfD?(#W>zcI zX+%LojgsVlCfq=>=%F$-Fupz-@3m|Uw<`E5^rbEyO6@?upzK-IVcq?U!HJLuLYHoH zA6Y=%?FP-FK2iL(C$t%&ME(Yvm^^4l-Tt}*2GphiP_vt!X;o~f)qUSdtyy~?1?SKE zjc@w$H6qPQo(^m0Xy70UCHZyvjlm$L13iv2iknC}(BEZM-0_^!UFXAL$?UUtHYz<2 zjI@g5YUJ&l9L!)J_n)kem=;jduF74Fj!AR3p0~nJ@cngVLlVX)X4zj2X-x*GWt|Yn zkFlQJLMUgpq9`LBiwf~`)Up?^Oc;!$3lkBP3Cvd((lOx`(QJ4m!4*9URx4E6l**g2 z;r8hVWi}mvkaqCY^Rg5WH5Nc>*1Um})%2QL&nV4dSPy+y3UWowNfZsJXaFX+5YnQ5 zHxS^^1e8nXIKaSWMehLL-uATKNs|^gfzT9d>){p^g|g?kFk`I;UG5RjBHqVxAmtYr z=zv={^x-yXEB%nBZcW^=u0eta?RH*Q-hojhcKrf>{GHJ9^pN4@4NOcwtFV(aG#IYi ztM{+&JVr@Dy&u!U#u=P$f=rnYlQhGgRfW>C?Y(|GYodU+Xria10}=3>#wjgt&R7`3 zfA`4gOq?mAitXZiYWCb=M4?T$8TE>UVTy)z@OdYhqv_0G@ue~KmozyF#J>YO(rlpv zbY#DC=NujsOouT^vR;}!yLMyk9_ZdCEj1YM39wJ*Btun4Syiun!=%^2!7r_W@6&grEnF715$mOzWj_<#5toac4THfYR~Hek01Q}+)m?d;0zJ| za$S0c!}5TTKuHY94v;^c7mJR$KSHS$jhY-%0;;_xBA6y7=j6quz3KC$w|1ZgAw;A` zWm4w=QUq}-D*UZELTRU1X*p%lAj^~J4pwd%d|Vs`0AkQbLXIBHkL2kF)#U5zRc;h9 zHq}Z&hTccEOmj9kgz6>ilnl-SsdxJWU#|;ey0<+cX)-;}BreqN@2}Lj>}`qZ+q+(E zbiLrsjzQT-jxiI759B{=UnQKB$|~q6UhQ3Kbt_ryXj=5iBOfDBIwmJJ+C2{z6)DHN zNuWho&$33(?SCWmR2w&jj^uGP>YN;INz_H{Q82=t`1sUn#e3Zz{EF7BRa57O#zi2p zvh#VKEPSev0z1^Zn>u`?9H$eVi$&u(#ibm&J2dfN2$o~4-d%W3XTJgglBU(tjN^GFl9`ud zD|ofI$8+*waT_{;&pd`>iWrDa2(W{f-%}w$^@r-Z@ds08*;vE6$Vc-0qqb_ber!G>?ffN6Q-F;}B0I-BI7&!ds(Ah&2@^ z9^KR=&sMGdr~ojE&Nk6Y-!W+}Wfzs$iI(q9E2z(+x)I4$DQf;7?6=Ob&2 z(2Z6on-k?TcsMUXM|yjq-~VF{Ugeq=>-lS52demf-+spbo`_#GOK+NM_@oGi42Ybv zEwUZt8BG|g2cld_RJ@n zsFYq%QlFA^>7)Vy%<~A`?Y8`DRp{+*;M;I29JQu5C~Lc&Z{-w)%-j-(Pg4jyLqDa!@rjDMz_4!*)A0o3&rl6eA-S=l}yht^6ZnNmYS4(nV9W64#{x zm0e$({;d&A=~P0SmUCX^R&(tG+~|fa_G;-s{tuIYB}ZUrXN1HVln!3noza|X8I#_O zqu6+hI5jea;#8?4%_ckmL*{Z|+u!u;U|=3Vnjms&W2iYg62UU7HRTwb4xyS<&CTQGzL>}!M? zRWdEeo2zaB^vC@F$iU%@6^SgHkXIaFU~|IEfOXZ63_i(bcCBqc#|;4P`*!Ud{v#Op z=jX@jU)82{_6e01yM-H2O+?tbQg<8L$J8H(&2?%Qi_SggWPE*nI|9$xV)}$J*mM{% zhCD2Hku;EWrU-jOju(yQbOxs5Vj=t%yJ#aThIfsOgrxpW_&;9Bj1r5DR<`yP)9oqptZdN(^TQA7kHGw(*=2!Eo1`&$Q-5 z9nta)sOW&~6Ta;DC7kl~5XeQhZAB9oMdu?+CPb~wGtp3_eJdY`TmL(Ol=Y2`=>JB3=JP z@bmM=dR9)(%Iu_D9oxAks!0inJ!=(iONFN>LaI><$Hbl;FnAXKoN6-J!_EVEim=%b zymwH>_VUhiplgx(`bY<=?pWpx;=HazzU^4q>6Vpdxq3Q6bqiC#&c^^)5bkV(y!c9I zR$9WK#vk9g3$;)d&J`m-&B^Sf0(DwjTwsCDn+5G?=Ycrdz0XQjE34+ZW`bzXvrJ6x z&yE#`b!nJPWPVWOq6A94#Q?q3do=y1EyjH2?7&GjIm{qIp1+`x2x~Rb$n!EXhNy)s zlG`p97^nc=-iQoQ=F@C<_LO_M<|Q&YD(5O}sC%&GU^bd}m{kn7)D5fVUXRd8;rh&UNk*wCZe0~6 zKwV?0Nw<{4y4(xYVbsJ4!b6cqQu>>k=6F3s)LaQGw1R*`GkQc=Fe=hLDe^U)>|*jB zgskpl`{^)B4$`S^Jh$XIq=$4qE))Y<~9x_g8pFVODbF}P`Z z`xKds6#{MA9oN@j8}o?y$b$<&R$Dk`0qHfJv2*+r4CJKJu8bp@Ie`hF!|2aD@44X( ze}o7JBV#roQha?=`+}kM9DM3XwOct$X-_0390#KGI~On5GCgauGbSo5bd^;{t0jB1 z$G?C6WN2^X&~$)>wLsqhbAEmrJ+qmEq>&SIPWL}Gqg{v2Y(@kYV<8oo?B^({V!{K` zNNfX!2e+Y3XO4_!2RaWxeTF}(Zm0DOFqIRMGGUN$ z`vIebk$2Ji13}Bw`$l^kOsTMN<;IH`p__!A)_i-5V~&~=lD#tT0# zRg^J9FjN?Xtvk8X{g5=&bd*LQ(SlOCD2kUC8&@@uMoQE%e&-mGli5L2 zfqqN{Ta%iiM-O?8sn*`xXjsj@S3bf9lZvq2jj0JFiK)?G*)2G)3?w|nltFv)^z}|T z>n>Q^&!BK=BdVOEILl%>9n^&=!oUCe_G0$2LqD78HpO;Yh=}5gUgiQP1+K*8S{(R! z`M$6zQ5(r~h;nx!+ELgzJumDwE8_%*cv-b*e_gXQctAO*B2-P8hs_1D9eW?!pQY~~ zGo5&{VCQD?vb`XYN;}LUu{OFdiy@O?(ouSY(%f`Q=CYxts1QERwUe3`A(jCW2+HnS z8d4g6ejFwsoZ2=T=I);4{{HD7+#t#Xb072sUXXwh)n zow0H)8^x2H(qi}X`~6Oub**J&4ig&XIp~Zz!9*EzMD)N+>+L?(qNeW*#Mh8sU2U33 zX!^jBnvLG%g4MH!w7?WM9s$vZnTdfu+wHVe6>5m*EHsVCJav@wxUHdV_-e2sCI#@t&Qc@x{>r9 zjyRpZ5^1uhE+z6|HWW8@Y`~r6qAS$_EKn=5^b*xq&{J&iNbFy<<6hZJOFQC_L3tb zsq8h4vcPkoY1`YyeFn%@gD`NtE({sXqB6MT%@R^8JdT;6Em3~0mE7j!D>vGbr|7^n^rzV_E(IYaNMYF0NEt|>oRGN*m?Z+!=Ac>4e4i6bMQ)h*{YGxDd z49?tJvViPso?0=Gp?wY%gg2be!n|Oti%9kcDIKV>ht-soz8=llSw~bvJnzyCS;KH$mjmg` z9SL#72y{6JXE=JrXOQo;(BVO(?dftFMhm-MTQC3%x*xV?Vh!j)QI>Rml?0wgn&OmQ zwB~*F_4>m7+_>LQ?%f`OZhAF7fS`EJvkL)Zaa*^zbCh=YrsL$Y+d=FoyNK~?*Lgt& zhc63Ysm&jW$~gk|g7g}U9S#uj^D}MSrzKj2XJ`x}^TE36?b!#jkVGE9#?kSH4SEtE`Y|bUVG>B>Jy95PRy2}5`}a+ zw!|A7e7ND*&I^RB$>U`EJGmN7fZM@Wwvl772Omnlk892YS&4vCZ74<1j7HjpOLOGH zLD%UGPH#-OxeqN>tU#8w71-5Sv~lws2Y)o_hmq;jkVu6dW6(flt~oN<-EwY~ofVac(IdV$a3%u#5(*3LyddI%#`hjjU%HHT^wv1Cp zR}19pC|Kk%rSSgo;1PIV*LB($B{>S{-TOO=8!gdWWJf*WgcGWPCrr5!)ZE} zhCYr=HX^fywI~E_E})!X7NsE z%#tB`lyMMYtZ{}Uq7}JxWM@5oM(({`m#D|u>UyO6eP<}6$4v>K@uKJ0SM)J65S{G@h9WdLCV6|J8gCzagwvkJRMkTD#d5Pw;t z`8?|Y15-Pkxk2)AKgHTAw?8fC`6I)on_GxTbHDA=U_BfvyO#0@W(FNr!X+znn!SU8 z)bg&FXEvf)%y%#%^n}3as@mwMUtcfm?O@=|X%K+MHi?HG&24wz!`@CUYvGkGTaH?8 z%=0{eyS|~-STT(()pt!=)H?ob;-ZH6bmr^8q{uqlT#epWaUn5Si0q+suG@038I1Bi z{eP>-kaU^^{RTgq8|@h)PL1+r)5K4mZ(nP{7`WfJJDCn#7hz!~fSr<*HvNe+B7pt? z;;rwfyJqmfynNj{*of4A7T^@o0r6g^tx z2tCQT5RgE^RMG6AR~A|7x}PYNlK1FAX-@t=DlcuWiSZqy8}DN~FSw_M^6&@p2a1mhLlmG zer!n6EV@uPp7)p|5w78rm7JcrfOn@8j5X}9dEw;N zTAqY9C&Db4KWIu}QQIjGQM7?7i)J(qdR%F{PjLWbCLKsFH`(FMq0h5OOKz4 z;>~Ce3l0%*=T(nkMZojE%bRDr*z@s88&x{{H7j_q7b`?s2rA1dB#o@9!KHr-v8%7| zn#SUoeg+L;w`c)0N3$?NC{2QvSk%#uSgV%(5ZiaR$uO5WLpb9=4|F*SiZEhHKq2&H5y`gQ36M!NtA{S zX${>RrkITyJ_qN0CsLNZaN~>aS|(v1EtN0Qohox$>|mg}{7i}<~wCp3=^QE zX%_n3*?~d_1IH_!ovPWBrccvkYDCr?{QT@led_V(%pr-!_{b{E^NXAFT}>L$Y_ww% zH9df_(*PrIvhG)FxC<|;YcFB{ zIDbF*kC|Ex8*6SU?|pYyHMgNTnx(L2A!x;n=H(roa`%a6rW_B3-LHN)a+F&YPW?$F zU?2J!$`sdn2{jJPh4mq7meoVcDrB#Rs`chZBiT6*D)AhJLf}eNrj07q^)A{PH*fUD z!2LY<^T!dpfuh9Z%!A5%JZN{#6-ay%L<~euNR0E&!dUZ#Nqh*dfB18H)u}Gu|CA7fmkvo*Mui7 z`@I!Qwu_djg(GU(z6bgOM{4?fvI8kKn-P%5Z_Kik;5sB zQ;71JU(hF3N%Ig(n;uTL%6;ne9VHV+Z?}VeU9&Y@yA`+l45b^>!);p=?YS-7!rbDL zHPQ1v_CPow&0+dRy-NRd-;ayjgZgm}Tcl|)(WYOfPh5t+1{#ePP#No{O?0(Ql&sgg zn)tQc31wR#ZU8vp{D`KtvvZ^b?Uitj1K9rs0Xn5)71cXsnrW|Ica0o? z**K;{l+-a_Ax6o|?3-vRuA+j)q}dBmw6NNEH>r7mLY0pM_t2rO=TA=PR@3b!*wnJl zvN%qcGfMhS|861f4jnAC=LYMCTPingnitzm0B1m$zbxN@Uo>a8pcdI3Ir97o0GOBx z5NVWck@o#n!AfPQwYZf6+u37$v%KxZKt7-&$E>}CjZOl`~5A_f18f@sf$G1HaGZ3cU) zGe-yP+L549<>BdtQe+@xL7j+_xmhqqUgngVg_C2wMM2ojR;$c8w3pgL!#Y(Z^+#hghcg_Ag-s$V04>sPW3v$Tgy?ep z(#FS+qCFbMoJ<|)mE;sE(0$1cym1j-oF1L4*e>;j$ayj4*iz)kL5K-VUb-g!X=N#%?=XtfPm%|LHX(E7dStV9VK8CA=w2hT5O}1iMbMi{ z)cJgTH~Z0#Pi4Npze>x(m01xqF`fh1hW5r3ryAwryoO!_?gaJc&!3!364SBn^Xqv7 zy_H|w5x;Pjwns}O1V@VIFD7&p;vYZIX;5iYyETb6gfJ5kI zf^L+cN(0)C|JI=Hb*uHBRb-5UnmC_XV(}TYISu>*1O531IF?iE7NA>GET0OCodwS} zsw6ulJ0}8Zfa8S)GX{-pI@z^!gE{pb-3}I@rrBA|2AZ>pSbKpn^6u$V`v6Bj&4@zu zURK6so3G5kv%y^VoVFn7y`}wZN=kPct#EzsPxnna3Z|l8M&6Dd#eL}q&-^%TCIb~) zFfZF1&)RJ=p=mggKeK5ZN;4SKwsILgBE^6M^o#G2^iis*0h5I$)--}M|6}?33rl{> zkEtxD%n~^aV{lNQ&B}NlLixQ%W|8c*p``6DvOGo86IIB=E$c8D=^^T$lqV&Wv!%y; ze1Ct{V9IM2g#%dkb4*A&E%NK@Z+oV<8yrDXV{LT6E1&CJI}L-%LSM7l>=xAF<|h%4 z;%6tf=|@Z(MJ1{6X(H)+TV$JtN5uk3X(bp)p2u}NEqMZX?eAKIvzNGX=?vUdcIlwG266cd@4-Mrgl zodk7Jnmb2KGN${>Q&24%|2a@4`%K~mw3LolPm5+7qu1wsy^q=|S(Lt>Lt`jyTe8n~g1M|MsWQlQNtS}qzA0Pw@OeX5mW z(eA1lxn6&L`x&zEe!ubazOC_a?mIrL+XHOqZkoO62);Kp@o?m6^Na9uC_^UuGzb*0>7jGNu~nqj9zN@H3CrJ6o6o&q_dAK+c^}?K5;p(Y3L4sUcDDRAD*qI4Co$E$U zWh_W~;om<$73S>OW}>GdNvy~9thRP39re-_B#a^UGM%OG$F&~({4p)o*Vh;35Ywx9 zZ5dOJmrr~G4D3F6lq?=igA%~*_X7;%0j3RMH0NA8YTT$9nAxXW)o_X%q!`fZ8X^^t z_Yrlr3dn(%&LAS28M<`W)*uh7}xyD!aV->?uN70!m}Q{Z*w$b;r86Dci1BKc>r8<+DM&@ z#xbYS37@qN*S??#qR~7KG|-Xk;OEB$wp<*aIw(&;4ne4|ak%!XT!;ybdl;<r3>YTNquiGziiz&o~#%k*b9yYMFZ9_gz{+l+Ae$01XGYx|EBaDB8pA z!c0ZVn1aqw)}E#ug+WY4B78Fdocq2}AXzmzxxVSIl!Qz{)pR2 zD|A_YP)r(`%jy&KInAj?r$7=t-$@7Rm^?7k!~O;xHri>N@u`>d$x-HciMnk*L)y<5 za}3UR83;n2ky3WeVIq?u#2+r3xrao-u!7lhMw>B;M=3P-uhfr)P9}7H4WJy89gPn# zaG1z{mzbM*r1^ky6&vCHR+=hqf!8xE8QFEzrZh;pjs47uZ}=2f6IoMM;(0zC-ZFl|L5c6LucVKK&3}M_Rs>#U*mQ&u z*JLJYx6sVRzl++Z&Qo`obX^J#msM`gh7~apM-jI|-sXV2QT+<&jOQ1qe*|8Jc|_PC zi#%C4Hg?*XDz9qp&wd9+4jK=eqGonjD_n!p%K<6@cspnl)Yo`!@AuoyiAK@E6-O9k zPM{)~-NozOy>#zlNpM5~^a+t?`K0t>P7e;HWPVr;%vt!a-RXA~K244+ht}lKEb$4l z1HjMw#&R$)K1)tm+-vKzy8;X};qPa8NQw3ln|TN-&*5Q|(b99eBCs%ry}c zAFNnjksq|}Zn&Y{V1uH$*_FE#LAg##4lr;vFfg9SRA{0L zor3f^YBski@{LOf_RRKB$)hrCTxO8kSez&wo1A6gNSb0jl9Z$fol{3@#5=apIPq{d z7Od?evnMHAvH8a}A(4pt?A+ABo9|S-5CQ{oB-a9juh)gY|NhIlk-$Iy{EJ1q8V_GY z6$ECJDgH>*CY&~p#ShUGrB%V@-u`YBK-;+ag)p!O$l(Yv&Af{-0Tfp?=u9)vgRKzV z5Mf6YcI5&&{o5#Pj@HS2_T}W}fO_|P%KAJAGmmXyY ziPPx8v^TA>33``AqWwO)|CmBr%5HP&pyF32ZD(i}ypdAP%=q)?=b#A$%AB@~{vOl* zdhbk<5BuxTe#w?bE-AD*gX7W_Y2c&9Pb<|#hJq$1=i!!?+Z}AkVrr*mCf>b>q36Lr zAAU*Y)Rt>97w=G8fGa*O^1eQZECkU6qYL*F7eP0?XjaH=N{Lp?^=2({OH?USn#->Mm@ z!=y6KsD|o{OW#{S6PV-jGj1ilY$UJTFZ?kf#C~R0Vc)IS8NhlT-=B;z;0|~V+;Tc$ z(q7WZMlv5LEcuK6TgEcc02U1quu-&@o}$?%>*4L@cJW+^+u3loXVmF>`&mauN1w;b z5tLhWBpejYos`=gL;B^N^t!IULOFEFaZj{{U5bL&3q^NgF8lJBfIs5v66yR_YzGCX zG@hEym;#`*O@`K5Zd6}LF*(sKjYgu)A*q0>s1w4ZAS{uCg7tb`rfFN-TrJygIt@0E zR?nH0g+iKp3c5lA;r}jnip(Qqt|hRV@I9y|)*0-tzKrw>dxC z*RnhxzVHyz6)xS}TEW}%0+{IxBi3rhJ*Ty%ouk%vfPveaQg!?Ga+5r5@2i;9JXiNx z1sntJEQz#RkGgIrP53fRVzUPh8j)!grL4+ZxU`4~;hA?bfNV-mr2&kIwinLvuEQm) zQw+^+c;kKFZja9S9i!RouA0-=9}zj=HE`b!2D)osn9ty2QV}2w=Y8G5z|r)#$SJgF z(c?6u2`Hy%ro+TBBVp!ZpRZadfzXL(F%CGGzyr#f-YY6HOnq#G{y4~ny@ zxf8Ai1_n4fm=FCWno&s5|02W{hm)Zp8%0} zT3>52F!q+x@~A?bDL-X5i%OiKmZ$q!iD5Zh5rAJQ@x*0esgUGrM)pHcHDbZ^qJ>8- zhScJyAzIf};iAu4*zX(H>ndk2AN{6d+Ot#G6$~_y@N;+9uvRqiV5lPvfpS>7^B1n` zRYL7UjIO_ORXXa7o=VT$@;LlE4}z){lG7KVWUBQz_`qqfkoLZYG#sc;h$csbE@?w| zsY{-!&{(^TzPY8Q{|A2J#f|`aQ^hAO7et&;?sH5V~&ky!~XE>>$MNTuj z=F!aut$~8e4>|NY!TU#Am{y^`eVj@F9ygTe)3SZvj&O60L}UGKOCk@avGnHmgRN^d za(dS+xfLh1K|RI#KpP^rpe1q7IdI=NG$`v?Y4sfTpMi8M6yopk3_+zcGYZYhGiWDk ze@sY`g`zsqU}YViwngbE(K!0cd?9)7b>c5)g8I zLN`A!BbS)0^xPx@@N5Uph%kmUlNke$F5+hSD@R6}c+nnb@m4umDO6b=vXB%}3s{}r zaG7{K%@ok7Lldv-%Er-LzfRPUT=x~lZ&(g%{{CI=xl}3j_u2>Oh)%QP5Buu96Htcg zhpl|&sEB9-C`%{3k6NViqjq<-#o4%bJL!DS3AP8AQjN_qU1++yJV#qZNUy8*t{lQB z@`E-SPkMOmNdu)nP6G^0FtC6>9QrFH*do~g1sM1|uGMKY=*p>*PdWQxRF$<5C^fTj z(PxwA=elTjDm}C1pfN=nIZ%juHQd;W)leGps7IlSO^UTGD{TzQ2!*mR_hy}}_KM(L zg!3bv1{v(;WdUeV5iV*ewi=wCwuL@vS{svhx8nS_v}+9XZYzkJ-+%MRjv}#K zM>I25y4W-LpM?%`IqUcXvO`Fnb056%vS=(WwvE_Am(qpAWoPNsv`t6$No2a*&%#>& zq*1_qKkXuKBC1tgt^MvJS%u2-Zae*!qFKQ_@|GJ8PGtv_>L|@DhdEC9%;& z=H4XoAn4L6bbO+~#2$zm{PaR#*&T^8WH0POT_}o)bPwwd!gYmJ3%k>PJ!a!oer0HJ!Eo?F<3)Hh$^e~zwe6w|Sw9z@7-xaxHpfqdvX%2}-FmKiiib@r%+RkRjhkw|OVPFpxK=g+NC zJ2K2iaM% z{P-H71HJ7Q=JDTID5Er7QAo!73XXkDS3_$7tuR&6GovcG_n{4yGn}|6Nv_+1QGXJw zYc}t8mXaL=FzOF$1U7O4F}+|eRJ7dD2yAYI!C2@)l8w_|I>=E|61V2f!eQ7w8pU3r z!_9uVhcc^xhh-#<$r-z_o|Udqp}C@#FA`SlYwc{#V$IlR;FcrgR1&3Tn{JcY*XzrR zGCD-#yEzR6RcwX+1i=Q;UlZVbM&Q)NQp@Ry=81V^VMEP9v)^IeghCrts|t88lu%ab zM^N_>`tA8eE#Ko43{1Krm06O=NijW~6`Moa90T9qU&%Q6`FUf%@0Jnflk_>$bu_7> zD%RkGS{wkS4sS1OxV9>8*QP`P9JHv=@D>Hpqy$k{jL6?>;D#|nYAPFgrqMvqVs8o< zr+s*TCmK0dD0)1hsD05ehSOWno5R}uSr5ofeuAc!LVUkl`gDt^Oo%`YTyIwS86Wb| zIEFTMI*lzfq83mKyuMy$ws1dq^hvw*2;fcaS<~5x2=3>`5N{sX&Jw$0n`T=pq%-u4 z9Xx9#sy*{Yy9^*Bw;8idU#_Uv3XaEo)=Uv8G4;QW0* z=|Gq!7)~9I-gPu-#TEf=Df)7AQdCu=s6hapoQpTyn;t)eI_G?c?jSW4dKlf179!Bm zuXL06cnRqO5^f2e>RX{!HA35uv;xW(#18JL{z@tDoo#HwazES0^dT(rVsx6t_VYLe zrE#?>++oV{QhU%{>Q5^7AWR2>_u4l@peX$iMsf?0`k#QWx15L1r(017V#hTzY$~~% zq|J4sG9F@s1s6Bq<|x)i7K3N1@&{igFQ#rGEh2coZ`^piE3Zb1iB7(V^NJ7Z7n#dm zXp*``u~95XqaJy~sVkc=d<1Vs;9Ok1drQ9Kq(?Aej+xFXiQw#V{h}iqDT?|Hxh1*s z+>0RuCDAlippRfSX*WW4z6&7E|%#tgyMZ92BD;g}C_rekYP^nG5T%T|Ekwm;}e9bIXzWl!%vWC*rwuSC?{} zq!hb$PyL=n15nzU2lq+DOgprrli@JvYiVyeCcQ*BiUw->g3!ubb0oO&I2|Iii3-$o za!b-2RSY1(05qMjD085KE*G@d(BolN0YPm-&^gU1QucKmh06@13f04js?btO+E6y< zJ|PM2{N4+|M33P3Px(PH-Ka3)^YT@yvpKEP8|{sf`cck;VGdH4D4MpaOKs2QI1Lir zx;j9cq>>%ZmwFUBW!e#`^k`>Trzrc~K;%L+%|fVWE(IO7Q?}C0G2Q-V>TQ(Va#{(5 z>G!4=SS|EcR6zj}dExiO1o#?GYb@B=2m-TWqLmNssC}7;EKe1m0k^pR&*$lT_-n)e93eGw# z!mD?1BUFwvE!N{;0N!YIz$&6Y;(i%vF>iXGpjgF}uxqOVEZD1bQ|h@~BsDRVmTf|= z1qmI_Cm2{cb8wOVs`tZ1;ZK%Bk1uI^r};?Lgnw&u32s5Cex@6}mzwFsndukWENc|B z0Y7#2Zr!<-qj}tGgJw-+JNO(EiqTjz1UfX*Nv_SDMw?*fvrqR!`G_g;+D}Z%kgSeq zW=7R1Yi|!Mt_k!f7#QzYGVX<&{!tD(Z?C^Q7#Qw-F&K&ZO7{K;fv02%JZoXbh$s`F z-H$v|*|n%EDPC*`M|4eS7N{{IBQ4EyxF1YksLUgiN84X>s*rb-fp&Z7lDGp;;;H2)h z#?IYTznnVlO`B*fiihGfTjKSY<2ZP)ITMMMu=xEL`GsbqXnoP#%psBvF+g*g zricmG80ln~Gy|=XKDk|NP#(0=eL6o_J6|1uI;|*+igu9|+G7{Wb&brNKp1owfzV-`Q0`6K`FGTsw^kH<)YHF0LLU#jOB7EfC!~8vCIq);yXY4& zjV)jP3d-xjZdvs;uw|(6!!5rg)7L10+2%??@ZatF%#VR7Wq` z!raOTCjmVW1{gg{YMnl#nZ8|>8R1Ui$LzBPtg!Bj2t~G&1R57n%4G;h!r$S;#<1n2 zqwcH9s@cPz%u$Oo7ejL{cCtXz=d)i0w}uq5Q?T3~0%?9P`T57Yo9W?UB3tJ~q{u-l7pS+#@|mVsdOQ zfVYPqX>U_PZ6G4{`8*^unuEZK8o>Q-*~~%ix#Ij8?F6LYu)_USSx@D+gGs)RUY?Ug zL2C{~T+Y;XfgCr&D)Zg3b6|oqC#iB2gvkRwZ2VNtL7+R8pbz2}nk;jZ&*zimO`f2a ze3nz`_dRFpq)^>=+B1~Y+6xwPtcV73e@IEke$0$!$5fC@U9PR zgS{YIMj^}Xk+-vhcYEE-;xaPK4(50laarOk^oE@2!XaE<1ylwf(b^b?u|^@BMUEqU zsU}>JZ*M(PdVN$pqr?K$zL}D@v@O? z-E~Y4X~OZ4sG-T3a~>H5s#|h6f{-OqJWpFY7&1wGJ6uzO_0FG>J|t~uAcf4=O2jTF zZ7E*b*4rky&_!1NOym?~Q3Q$6K0NRHPKsD={a~!Ko$mq<68mmMC8uXc-qI3EuGjQs zwBB-!iVFxvbzn7{s(kL5TRL(nW|?m8@(PK<&-;_lmJnrSJ(8$LFR4Tev#aG~QYnB@ zvrxda2G6{iZHcNCioBCqbj}%@vAwZD>O4env-03ZNKL_t*lY0(vVfP(G&&co^H9a>SG@1muoZW-9?G4Kcv z)EF&?Sl2*vtP}u=O*V=!Y^BM2)GOiu4MJ3F=><{-6_|^TM%(U1%kEVd3%j9n>zuX~WB*s-jkM8@zLS=%mNyu5rL@ZkVe; z>_A-8){1|>``)Ci^fbhuwWif@FsCm1kcw#zDDU@7=^S7@TwG_a53hs*Cqog^~Cx2b}}sBbUrw+goEfhk+~w zB7Z(qAshY?GIqDPuX_enqaM7*B}4TjVVT#oO&Af43o+5au{~JC+1A5nnUnbDE!R_X zO<7aKhV9U-D6BvX>k(S$anJ6xov=+A2f(5 z?u4dnUCi#>wp0MwBNE0+n~w_=>vjZD@&=&sp`94VmTTYpp5kE+#bh%tI?j8bsZ_GT z+jV$KFp+4zNk_pN6Mb_zey8H#uPh`}>Sumx+@m+f-5)U*W( z*$FobH1d@Mv<&(pM7Go!;Q66KQClYfgyjk# zeFfUeO6`==>>{crYf%s;K@521zx@IGUHN?0BV^Ol>ySA~ZfPdXO(PmBuRyOeDSK}} z@w2ElnX+U~4&>T7Q9W{1V02uzWW7UX7+Et24?}Z(T_XbJiY}+U@V+yiGkGW*K~b9= z0;tuH;2h|xiOO!YwJhWIIY|}r5kM{q6C&gVkUk0r-ie>U4ansJH=kPz{?27s<|<`*RY*L@an3hbE!0G7_RYi?@ilC zxnRn_j=YmNuRzyf)*o;BcrfvogmiP;o;~tZ8c9MtHsxE}f68uBCgk;wz!GHj+vi~cUfvg|?4} zEQoRLO(_4XWGa%<+g%(85y-G zl-C5$xY_x>v;-c^EaD*nJ)3tu!lToCO)}B~!W2xSJYw@#cxC!)dnc*nmfvl8xL2xt z?-i!1Dn2~@1&I#VQ|6XFt8C0e=6}zGlYlygS_1G9bKu@fezdo()xZi%B=eam4;fGH zud5vecow*{;muHSdN(n2Ge~Boln-t$-uCzNx$lAixl7OY)@U2|fFFtc+MeK@-9_^b zBrloVOz=+*b0s#V1gy}gkIGB;h(^HO-iM4~kwaI;cGOK3`o8x0sJ*Ckx@DypyfBCd z_W%N5x6+AnV)V=iM9zR1)S+xT%PQL3jFofh@wITq9SrX-XgulbP zlX!Rn?ZETGLrzWLNRMZ*q?}Ai11#mn<1|%OSB@_qCMHf2-CofO!o<4qFpg;vq;U8NAw2iNsG#D9aYQ%5_YKn3~o|F0Bv&q8e{Qhigam#!aC2&BYMm^vYy!lc( zTi|_gixoCc-UwBR+>53wC%I@+%>95EMv{>WDEo?Lse^grsSte)A0x-a7HTFk?AEl=yYL4y;L^kX__?P%%(=_yUd0`n>2gCpaPz=3x4uH!s^g5 z+#}~(J2z1rfxO zTHwh60&?44*b(S-0DE?}9IPjv_J9oGb(i7h8A=6iwlx*UmkFv0t+KjF27q$VCCr~5 z4N(tv{ML~NUM{9R#RrcqO&F?cN=_56oZz&`?5WGsiAu#}hRpQQb;vt50mj3ChfA?^ z+n548Hteyzl9U7Z(IAPuzAkC{%HM&`iu9edKu^D3uUMnLWX>g@`_2LZ$UT_K%xp_l zMC7GqRzqWH2Z5#NMLiL}k{%A9I}0M&@wB21>p@D2BwxU%Nwf6dG=|^BsF(2#%^E0a zZD{^kxk{uw1)(V$d{%pN)Up^cgQ+j{`#d3Rn=*G4ds-P6+5M*+N#zPDAEs{LzFQo| zzC06#{c+IaV7JUnpff6qPR*dwlysrcrsQ5#ll%6+njE2*jw>)ynOk1?*aT&U&ap*h z=!P84!_D$wSX^wM3Cq>RrRRIo;9&Dy4D zPEb))EDm^Gi;8U=q)`w((&BL$wZ1Q>*1mE}cHa?bH|-c6lnhG_lO)R%A%}$bZ?3s> z3f7dSAYyq2o#q7>{<=*xtV|fQO{7GVoU*S2f7>eDnCXfP{16&`P)PHA$AlPXHZ{0C z{AaF}N77rDttIjN{1b;8LKogLrLXg}_~#^dKev7u-Gu^i;W;YPwdK!_p+w?GiI^wx zS)HB&_`0I$r3@=+D$Sah8vXM-!$?EQhE1KziN8JIEim)SNkzh0iSWrhtCk%|WJs2p zav&hy{~2ibo(0k#aC|82)lc}zSqUHbT^OsML3<;-u1-U*%wKUi2upsL+Jx}P@d>P| z7sULasJ^Zd!-4%@-ocW+D3C!)yRMN*?eEVgDQ76!dW#`WQdC!ld*1iGvoL;T``Lkk z#`D*Sa_A&cw%C@N8{vbkXkaQ2Z>r0jzsYEj3$Gb!2x=HMS+>Q7X5V=^U|uNhx>$1> zML5uAg?Ca}W)|&Eu zf8>tv?!Do;2!e8-{yOpsCfLYD#$+@ch!-(EXsr_Db9!#Rr%Hr36hb>=%2MmNaTKuW zNuag&zU=Dn$~7;0a->$%wm+_eRjMr4I_YQIBusBaHJ zrNJkl!0VyttwJB?TuDg7rBm8oOn6R;%yqqF4EvQK(MLa|RG4a_n-$rJ&N1?USX^U z+SkKJ0dJk=<_VWFzCWw*FUpu2C!xzLJdeGIkmarSO8LxldwAcs+yUQcIWXG3JCOZ6 z6ShNQvi5`#TKLgNkT3T;x20urWB~Cy&ZcLiTh~9ka=HcrTN<}}QLWapkkZZCjt2cF z>uD;oRZ33OqDZrtRPrPq-~VoA{h*|2;FPiDQI)@-dHpcu*Po$j>UExiBFv5?Zz5qZ z_K=G;&UawIjOORW1Fz#O*PXik%nC#H1h&$xxBQIvrl$1f={s}w1zIM{r(}ho0V^5> zNZ2w6RXokkJ5Q`6c90Ldv8jH49!(;@g#x8{c)<;}Q1%!65qMv5Pkep9j;4ss{!aMa z*LBI)R}2I7CG(zp7#IT|08cdV+AyK-cktTYvKR(3aOL>UBgMUuU&c%Vp$tEt9p54D zffkAeKKD5br?nk!jG<7YZA9jobe5sTkZ4Gp^}N}ttxBV2X2s{aB}aR6$o^0?Z=i-Y zFDY6!e_?OR`hnCAyNRn%%^Y&0(cN93m~2(Z=hjEYj~yi2^L>@WTis}gu$CRD{L0WV zxs!Y)zwXlg-_awBr=|aAB@_U_kC=&6LoZcB!GFzC_WXGp10(ixcF#K%B`gX3H4F@5 z9JaRYVYz5+HyNrO0O3rZzZtbqeN)jPzS=>N^CVrU5B+cmiqJmM`t%97&M^o|{e~ho4anD{|ISOJswl(v_ z$kOzQClT|W$HU_EaMuPZCWo==N1?Y5)Tj9f~w58&_Po{0mddyHY>Md>*L4bk1vC2sP)M0kW7gN^46(wmdp#_gEl{- znAGo-gZiaHA#bgT=4P$d@%i0T zc;ePx_oK;YZ&*5Dyr2L$^Y-`Ji7F=ao&*JP^u(a!(m`?7THD)R-NT@Fdi`p9+k4-B zApl+Mj*V1pqbd`Druk^3BKR#SUtxgW=bvWNSwk5feE6CDMG_`G!i$|IuT^*(X~qu& zYj_?osYT(Ift{^97WX|9r<#fB!ZH(NCh0+OY@)gSz`MJPatYLPNoV`$vB`iOZXM`k zJbW6i+$bDX0pOc$-fbr)r| znZ55ja+)~o)v_UjAw4n379NT|2vQ>XJ6G0~X5(MOKuNRvkr#4MNIinUV;h$NxALnP zXP`zE#njj&;AQ4^swaKQ(^tb1kpn$Xxj89K3ku>vO^mY>7;y_k_V%^Xeb3PXv3nXZ zKy)Hu>9Nhy3f%P`jo6?~%H9|#Q8{XBLxSez4E==KkV~lBS8B&LWmbk8Als*{C9_Jq-7)g1};PgpJgU?alEJ zQ}Kupv^11c0MeOK--@#3E`79v5QebUwtc?8%ze*;`!EUvsqDofSMAc8=R^tr3=V@W z<0`t$L1aUbXERfH8|XFKGW4$!!dE<3ZBzXqqf*dfTK%}3pvyT(+H%U0>Eq^d!!Hy- z4fg*e8d3E@3_|h6Xi@okDA>@&2?Sva+G zW9VLN8JL;Z1OB1m8FKmUnQN{I6LI(Lp`v7Xp};c9LV4x7J}+Ezu_zAlXPqhVl4lQ0 zspA?U&(jEkylWB|MG}iz^1_7*{R|r7Ij@00!8qiEvmnZ#joc*hhFggKXBJar9?Ye}v*=53rQ-4pUZ$9p zrxfxGptLsuY-SQT1~SO(@W(mrxm}f#r2xp{`@Io@U?BYU*eK;z%ZMr!+g}lhAMLpB zBqXs3ep!;#R7~8Nh{?@?Z9U&HeAqu*d4}*jqM*asG_Ff5u-r!ErOe8+7#K$5jo{vT z{%V8R`Jpn%35Uz)ohd(ewi! zoX>W6LCCpt0t2)HA5(^Ox)}Z2EV^9bi6RSl!bb%%sDGWxex5^)QUs(Ec+L{FJKhLEqAkk02vMP1_WCeZds$1H-2kiH#ZigtvA@=>Q$sH5-!KV5B6q1y6i!e_B;6?lNCA=p@eV4_3- zJP%Mm{0|s|ty!DNPGPxCdYbrg7_d3ifmtS6jzx2GnB%Fo=KPPts^mTx{abU54zq%>03Dmv{y+>1mV=gz1X5CaRDmVQ3-Ey_TT=eV%gPO==3r`U%wmqoDd<9Q}rZRNSdR2hH}5V<;q8|T3kSuCy4 z*R53{$sSHSf_(QKvf|mnu!D=Mq@HQf0RdyV?|ToFMrCl^f!Ig8aD1MsN&VvbW^Y7J zfCdlEm@0P;11lpCQ*mi1s7HCMV$ihX6P)T54%IFtN#%^SknQY0>%M2n;#?Bc(PCrF zw^jNDo1V>goL)G?Q76^lHXs*=|8@p&qNRr`{Xmo-llqAOOQ>*Q?-{}isrx=7*G{pw zMGhiO2#9b1B*7DKUkdqull(;(WET_lE?v)i6dQ_$Am)%OCW<@Gqxa{NN~Gy?$D5>g zMvwe3ZmJjj>DUO}zQdr~mLlW1S<8-Lp!_AkyN0S2atS$>2As;ZAOP@hp~iZ>ULmQS zRRf1Sy(N%g){Ke@NzeODGU8=qL#+u8+UGdQ;iSB56hpeV#5qW>zk@xF1^bds-EBQX zi=756ISeGZrp8uzpny(X-R}|2-XW@*$vMS|kH%(ItzB zyx+H=A5p?%LjTQ}#7$?@ziXQbX)8qK*<_F4+aD6Mc1-irU~S;+ubQR}$*x-n9h$?) z`ixVburB<_KVEOa7Jmhfg2>eU>T16ZjfvY7=<5jn80+e!mnbf74`4)Z{91~3& z%@3zT_jXRuoUo+%{kILcVBLQUi>5we zv4$4$K>xbasNcA+osiJ#Vk41~`pk)jf`wHS#Tqz-6w7NGmB6PwwFJa}nv%l9-9_MG&NljS!kS2Q_j18fu73<_(qX#xf+8BW%#r z;yvtLGxU)q7piC2XiHxh0Sw$XoJf{*0B~p+$f@WDF%EtO^+)d4`EIIE@lN=1mWof- z$K%hY5NvEI@5p#*DbU#&W7U|!zb19o5XDTJW~0)3kEHdsVI6bj-QB5p6QTghvKlPL zXDM2;Js7u-zyF|-)mD=I5N_egVxJ){EY6K-)!`0lMSjG)122MB(_DiVs8aTy%f3u^ zGPU`cb>p%FEm?N$R8@ko+1r_|qOxNNAb;zv9~(k#D(hZHK=v{_A|o_>D)QJ)E2Sxy zWOmn$nBe34$$YVZD~&kgfiC7h8yn;ePpW!At!35<_vk4#h5QU#CvT68!lyTWFE zgp3oiLuAyn*5v)xl-KsQw(dqk2%|F`KJ%}yuY@3EU}xmc?ExK0>$B+% zNw>h#P}!DTr+HG68`Y32^Ud;HbN2I+95=oP&pvy5d&gegOBP~|f(8dNP1;fT=+b<$qbR7*{47D`r|ZeyS@^0gA4on&;^_g5aO zb1r$m?>Yp7eu0Odk(e5inJuY1CngA;LTCNCcUWqo>*(;}0;a`7!DdD`+lFpz6L8?P zdU+tHaFRx3P?KFAFm=k0=7zll4JqW2hWrb6OMh3V41+jD_WRX^!u2?#+X*4-N6r=Uk9MMc7~SWc z-{}=p77-EePfy(bb4Ty8)N-@p38j!U0b-K_qD$*Nn@IS{KFBZ7l3PAEnRqrVreg3^ z?J3QWufQxXA`;<$USlU*FBtc+Nl64{Nmvq-9GN^u#$*pJKV%Ni!{2CgiR>x&ow<^GO}{b6ozE?YTR3E(gkun%R>?q+t+L3=0EpG)|?p%i4(f@76E^r8}X$lJ{&p1 zzwl-N03ZNKL_t(aNejZ1Qp)I$X`!Ul(+c$zaV9^3HOzs849Uv z7DH~9SuE-Q0qT5I;ugtLnb)Q&a`h1bcP5UAO$y=E@Z%gs4`CGS#GstBI{bOs8a9g`|@By}aNr8OGeG*{w6**|$ov zX>8$GmNR+{iHrtMiQ<>qOpuB<#~&=aY1-s^jqo_#(h{=NA|Gi5$(6PUyW^s>s2#q~ z^s^CC7erB6OT;SQM-BynoCBb>4meMFX&MbBD=hjc+vPI|TMv)`i-1`}WLp;hoSwzG zmah(l?lxza>@$5=a{3jyuthjB$ac6#G3XHvFxMKg3J(LlyrX9)qZEWH1r_4J+mxXd zxWr?kIp>nrJ-r=HwM*u=g}CN=UHPscJFRRK<&oRctNQ^mu(TYoYH2MK9i1XGgwWrb zL$12#I3ugT4_wnVRT)A2`t$Q65pj3aUJQD8%1e>c^?F_Mx;&|ulN(2uvUr5@0sbX; zn%9v*wdJEV4D9lHT{6Z$ISky-e1)^?LGEmMR=cmPISv37Ju~@xH9ayFF=T@pq&&JS zhK8ly$l&+@{-{;hT7sE!@Wpjx$t(vh69?i{D)E+gvAelyq}@E%=&nW6VmvOo=eC{K zXKK08hrcmE`EtW_ibeqi>=-SHPk1ORe6#=u@QsLwtSr1LG5hQ5+ER}waLwL1?aQ_0 zgKklchl_TV9uNKJGjkfU4(%xn)pzQ!IR!aoXADw(gy`XbLs49Wppwcs6$bVQa6{Vr z`|}AxnWioi7x_*^j?G%4vMr~|*gVyCL=MB*VdReM76mlqYDPw66qJ}UHj6^Wj0jsK zmqUZHb_JTnIBm32wqa*Ny@UY{)1oU1InG*00?y=#tcnY^f4{Yz*d#zYxu>Q3b6daG ztWPjS$-vg<6BE2uTPoV%6`rw6Yr9AjJv}>Vm{dJL29;H`|Mj_VxqScr@6V?UxU=L3 z7GW{Wn-?$dL55f^qvA;k#cYXfZv-d6h7*WKMw{ljqwSO=QbIHSneYGjXUo9?C7Z<| z6`u_I*b^}-WK<5{#ERmAK?bE!mZY()Wiq;EkS6jjaPhgjyk1v$fjpZA6ifTFsAiN4 zup$udXAYMt}x!E!|>C@_#$)6!Z^@tnwpWum4$tvJV! zALBB&EIN$5VkV{%gm=6Kz*cgVB&;Y7faszK4*tNELauOiVqM8hAe-=>)OspYJbug-mo#lbV~G4o>bmY z7>B3f9%~tMnj5-|qe#knSY;y)jwGS?SOR7%<=wt zlgDt86~TyT7oe2atA;CH9+!FsYSIty2f`(BE}ul5)Qt_<>QDaF@z4g;Tluj?8a z)q;V3Hn8StvDo*e)wB1gjU|c2?KlVPEc6VTS68{N?alf5A;~-B%A#rdq~n@)(05qc(G^)BEgyO$yK3qH{1SbG=O#7M2oLV4I%XkM!;|GU0F8K<|61g%CUVWzI%L zO51v9R`pD^C4M?CI^m5Cp_Wm&0U2#JE8Se>7p;utdNrM^=@IKM`R987MV5r=6Liwp zT-tF!mVd--<;#ny2SV476>`tH|1*V|*N;Y3*%yT(l5zmdDon7bJbqxNK{iueWjH

?O1UU4X>9(0Qsg#0 zl6IukPzVCgIahdG+u><_B5#$<)R>aC!&B1oIpb!a#kp6T)L653%ix!O+*& zCD-fPl*8U+*_)bEjsH$hV2Znya>Gr!Z10`9$@_gL#p}TGD`d-eKEv#B#YVDH-0Qx` zLBMh6S6KDoGkS!Ia*@{iCfU8;pMtz(KxS>yk71|OeZQNubs&6`#+d*m{UzZYS5J8n z4+B9*b3Zplq@2wA>d3M|flt0ZAlz9+fuR+H6;MJWcPYJlTK5dAQSyAs4Y7t4%~S5r z^%KW1?1+G~5jtqDR>~Z{hm%-|^ErpV?bysE;gvja@Oh>pLOeI(_811ffE=1@p37AG^ z%uUgNrt!f1g{Blmmr_)fg0$d5{BjLql|>5plsj`73KXD}w2e<`naTX~BR@ZM0TWFH zg=2=C(MiT$m__oIB0?0F7&0?7b3jDC-=AYeTGO1K|J_4MMFE&A%zuz{?eySr82Tj& z&pg0BHNiRvIf~FdJ0{?zi6<{h9)d9u*OTbhXkv&W3|kJCmuYV)_eeZ?rV5aON@sOUAl$efx=LEB44Y6_62r1al0TNxIZ;cij%J0Cci z_0sbCMUmlVFS68bY!$SiiYp6uWe3@XXVe&k9^*rcovIBhGM$+k%sI| zgPD7ZJ=>8)-EzvhvUzUWVk%!@lMq5?lRx+)I^U6Mcf8HKPX|4 zzqvKSnYSE5Wd=&Gvl!kDCr^$ZXTdIXii{?QEYT@*OX7P{@?qiJW*?9c?%S=-mSuI` zGMN%*D$aE@MM|5M12z2@xJZYuDW;gfm~%c`4yXciFORJ}7weu%2YrC_^_0e?*Ut(+ z&Xe}=>5vI3H$Vw&h;sx};Dj33a|-?_BD5V%#SUMbkz3^lOvB~G+qU$8?$2wsnFTW5 zlc$6Z!$1ZNRDh{Rh~vtC7BU@+rfLzH4aLztXAKhb>#xm>3kP2Mp`d_*ASe^`=D|?n>0VNUmo!X1oIIpQiJr9(1py}B2d#I zpK>O)@{m-By69C{3l9TFK5MewYbmY9XK7?_XsyZD>yi~&RLe}huWzws zY5H$%`(^O6>~~1(EYTYBxbKY&hJkk9VrKH^&!3Pba+B@!zhl{`o6MT>>Q+Fj$MXlv ziV_$JVciws@)!nYczestJN4%k3S}!9+?!#ks0F>yFa=0Dg3Y`gf&5h!J)iGKa}A+0cpB)icC;r4A@b>T7V-?3SY z=~k=5aW{;C<+Zib-b17NdcF20pmlM-<+?7qoVEw&bzO3Oy$&35X6~3B6c%%nb??vY zo-@xQTy~hERYOtQ-pUbJo1o=<`4vqK;EcW5X=!GxCfj8FEp!$cPHP>-V$*GqW>Vo8 zV;2|k`ytd+Rni!`y)~EI_mt1)6Y>Jh;Yp7W(7c3iN~LEFQ+$>lm-LEFn#z{;A*hYB zCRE$@^Vm8haEUZkl{F_366tfMdZkgaJ4^i}vlaB9S{-;+Gm)U>uvY?C3~S{pld5pV zOtoUa+@3bh9cE2i9L>x$JBd(4QbfU0f7aO;@f|0!^SqQz?2qD9GSt<@(F~?ZdYiyK zWE_xcbiHCqZUy&QtA<5R3Wug7-P?uSHG0ZZKA&5B*>QQP)0)GZYrJ!q4f>WrRIH+l;^A+xX1) zlE>D%Ja+KfB+Zg!?UmV7{#h}TiNRQ_6e(=IDzc&EdU?056JoIgMptf-hsj62$eUR zx%ECnMKM^IQB$<^w>bse`eC1tBF17E7=gIe9Qz^VT+2l7nVYivbJx9UmbD9ed5%G) z?M>98@3M8x{=rvl>ROXQAgr+)i_^G`;(D2h8nOty9+Xm$q_(uTD)v;)i6#1@-dpPA zbh&ttD~y_n)+sDaT&_NnK*3>YD;`p4?lJU2U{}*JHDjWnB66nz6yz=?<7<##Xf>W| zWlVY@>mc1LWD#g?{26Mc6%KjZjL@@A%yS@n_k^p-DR<*(y3!VEn`f8!?U9CkuJCOc zp_2FE()*}lIuGML(RH^Y_X1iDa}+m)sz1O*rx6 z<3K~;oteoHt$@?Dq|?R+8x;wCFjB>T-tRK{0>j-Jk=Nu{S#ucYA&a5(=$!WX&a&u1 z!)k40VBNU|q%|)LaVm$u=6T2*8!8;Y3r|skqWE`>H`}_Ml;SFiJjb~-9B@5~7H0fRxP8k6k zk$EMw#cg?sS5Rd62m07yW6ku)9`HjdtCEmMKd0$QP_uRDrOh{`#nedZSfryKTJ-kF z`haKc>+2N~+m9@BxvmkCf|8z$YlsL3xs}OzOL3P>`e}QFNbb$Whlg6TzqmwOI}Gn7OKD+B_G}0) zLay`14O3>&7P%-z!?D;~!*&|o??IzM(;~ciO}%?c6PaUu=JqHx6;)uNuu<8Yp+5Gz zIeqQH;|LljNv5kv)STP6xO64I0d0D(*GuHSrL{#^T0eZRaeJEiE^QwV`_u$ikb5=LroxpSLAj z>!m(u?etT)%j*lnz{==YYi(KnuK?+~E8z?N+W{6-V@dycXclq2iQ&2UNU9pi`ghZ`_(GF9wmSz#T8Ox;6BnV9H zl1iG%pH8F1S7eQ3PC#(n6B`(Y*)(R$L%NWM z)1G?Hd!9vf>wCt}&YcivFQCK#H9LUduk5T1e#VjBKt zEyJpK8IwUcW3Ll1oSrNEA-xZ|E*G6s{`vlv@9*zTwY%>^bca+CSF1FmQW$rz5@3*3X;*x>9*5Cj$b z3K^t3yVxWUi2asSr9?S44143h|JXkE{m|m>nRCngp2M@(b;a<^ z$Rw@5JU5U)Wh_NdEOWyy`_8Po1>vij?|RdgQu#TTd;<8A68pHnk05hWf9%{8KjlhZ z+jQX1v+>au=l)7nMk;97i~IoAG?M)#rOivhpi<2U2l8Torxe8Pk*$OO9SubVHVfhT z&zz%g;xM$4=Wid^$1^HetFDm{_a~Y%MmZ`Of*9bsI?>z=j@UDKR4;a~IXxy=p z!GMYbK%LHIG%l54Sh)H|89_$*P4MR}qGWQ$j8J}@=$W;co1+-~;{D$XjUdxT?R*Si zqv6{SmsXG^$hSpe7#Pr-Wt%Sdx+ttwLlQZ&hQlCzIIXAga4J#Dju6WRjd2sQK^$nk zDZIKQU3o7iKBfu9CdYIlrg2i?ZE4g8CN?I>b6JsTBC$3b0o&^(d$(lT&&a${-DRcH}}d8~h6- zD^HxFrKE;8K3##RTxam=T8CyDM&Dl{p_t~x_t^W$kj6DvWSLaKU?K5YR%_Va;`dul zo}CjriDz!!Q|{J9n;oCG+sXn;@KRC$BzwiMs$@?_>%H{G@q57s0mC5}E$T``C=Q_^ej?lFX*gG>w zFu`v4oDx49@5L-=#+C;Txvu@QefljwKkv9WNo!6MG$G&Dx^MZ z{a{;;S;c_Z@64sdi$)>MG{$4Q(Uhk86pFZ(c$(hZ5kSnjRPyka5aB|%Ph~^dM|d#4w;tNOe|* z^iqzGAt-w0&kgkXoT~zGM0?waEvj7%GpF>Go`Po+xVg&73FnDDGN&WT3!k zE{7BoP2HZa8p)RyNefGkWg($|Zahog3=oKj_)HHP3S!<4Sv$cvz13Zlsq&(&{W5R5n~aDj9kKDw+^6FNbmqI7oW@X3T^^(FJQxgIbS zM#U@TGZj6ug+k)%>q~lMUg6%^ep1VrmN7;K&VGM?$=BDHtU2X#-!ahB1XFm>&)_qWxGo{Q?0UYW$5Mp!jE{X0^&rPKB# zf4=y|Rvpro7}_Q-Why@0QSrbEy4OJ4S>#?s!r@V@VuENPE0ZI=I&xG#b`}EYlwBwb zARdBgxmr7>U*VfUv$K}xVcoRHnSAd3qRv>) z=ASKcgu8K2;aRwx20~4V5IkH}l(RqVbKkk8*l63nCv|bLcpx*e;?Fg#6yiK(9d0t; z`!XHjLmGIw1Eb25PSGl`ob<=dc0zn(&;e!lG7|*b$a^kvU)gx>2}#St1&CqG@G@?K zt4PD4jZ38woBl>RcQgyHudg(F{>MN6?92dg^yBBofMjAKNlkcb)tGN0S#2|W<{KGh zB~{)6J`k2el$JftL=b^iTmF~Oi66LiznR0lem`uw@KOG*y714DF*S- zedmLuw_j@T;_cb}RnC|Yy>f4kdTvFIf=m;q%cWJ-i-%k9%<)?{(4#K~#!&AFvh3h`gz&mmI2P?%g6!4*Mut zJ%d5j!oAhCNAtfj`k_-c#FauKy9LGB-^S1$#sn& zqZPCWgDDib{UF0q-DKr+W0D$bp#5jjwxLxPp7tiKUD1GVLgO6gSy&1I5Wbx1D$g^w z12!clYAWtsrmf08At1^2D9=*{n{`k5aq(Q@yi4T_g>NI13!#?1chOL@>`kA_7R-L*C7Gi=~&aNWLW%=Fi)H zK_pam7NXFAJ7EFK=z9poxYo1Ss1buKTqK5$G2|ZUAzHtEKux82+uys{#$X4LhGQiV zP0(5sOHZoG{Cw)&N=*2Y@#I%yt-k#r6~uNo5(PTTa2Uk=B;}9iATR@&D0ZpnLxD@VX>mdOb@5R$@VkeBVx>HYH#4f%+Ciz2?I>6N?$j3>|3<7jdY?0Q}T zWuoO^VUQY|o(bT+^&>R&AVPu=lyS<8@=~qlg;^Z`t&s684yGo>_OF9 z8*n3iOS`cV!Z5Igtg-2%LcH=?C?5^Oz>vj?SA773{wDL4JXzy>+c1yuYx}J#a^F(H z^RZd7@V99Ids=HUB>X@DwrIUe|9Ni-ejug)`Tj@#{QSx9SIC^-1JjH!;~ZEYm4=+O z!B&1Pgs-xlB;|U&(}F-AXmYAw0(`>+z(QL~N<#UaFG?P^h=cA2r@Wr8l&k^V#8k(P z!>;pnq?Qgi#=}Qcm}W`Zhe{uf3e?iKaky80IMc-Jy?+q1)M9orA8vA4KMGG6=;u8T z^YtPn3z@6j1dUU zDil)MkYS*=d_H#?50T*$OWq@A0JK6jTie!Ui~Ku_QpNnreT_ z2aN(p7k&4hmq%*6;~jmHa6~j^9bb*Q3d3u|R_m~vNRQMG@j@NaGHr=Eu5P5{K+P%x@EzPPd`^@Yb zY_(g-4{OR-&zh2dXsLVzLL6wd}$SZ)Pms2b7Q*h6CU=a&q5 zVESm=uq}`#OL->JQ__kwC}z7Tl5-e%`{+lQqlu+~ zw~t-Cf{d4gN^@z029D%6tSlXD>7HruLb(^7GUb**o9xFsWr}QO2V_7+j_3#!sQ8>_ zgbbGSu;hTfcL{n%W=66108??HGmwXY2?Q_?d6rWMa1~s80BET$x#yH-`fH8Hp0yRt zTWdWAJ)udNE9H5){juLPD#R{e0O@x6>sShwTWu{4(3B9^S?; zLe}Fm2QJf8L5zlNq8KZ_vT3*u)shHHnY7X#hZ4k(P-wzp|Wsv-S-gp?;gjJyj zBA!00-uL^thk;{nM;Zv3;g6J%n-gyj>L=Wr7-;@&7$_7Lp1wt=oG{;wmQYUs6h71~ zOw`;23lrC#4Y2tR_-;fzv>@iP{V_e^Qe;oYx4*t#dl=|vgbm&&Jl|XO;4(02w7(cb zj}>-I(?msla%#F91>;;In&FNvODohZb+vIRwPapvCCA2uaOcm|^t`D&%*Xnmw^Sey zy8PuL5=H7UkyOuzO9>k)=Zr78+PGv>cgu!n_BljRhH2$Bwqf2L_+|W_z17cthlIu` zbP;Ld#m#5(mx;7f_JYqj^@=7rDe4qD#xFm73$5Alps}1{XIX4S^7a$m=fOugN=~@| zxX5yv38~ye>m5Mv@*&Yg3o-#nP{uVx%;gSzC{L@?s{&U1oN|q^HQ=qM(bFk=34eKc zK(u@tux_xy|KVF$%kneb-)#?q5C!ScXR9n5Q%%1BU&?cZSs8gtb7p?c;oI?8DbrBk z^?J$I>q^6*$BP#^9akt zG8GuRSsIgIh+YQWIhTl;7*QnAv}_ODOvC+wewNdhK=B}1C?4kT*qosVS0{74S3z3v z6u@d|5JL^UkUY2whKD;FUbaR#XI@Q3%3+h1B%;cihurW7P1nkJ745TO;eqm@a0!NQw zphcbxBt&K_NKCC12jL~)X70!c;X$F%XXg|#kOWRhJXOr5n0LA2_upGJyeAgtY|%E? z^33#6l2aWrOyI}SG~qo6*`Bw83q9qj>1%LLf2@d~=N-GG*QQJY$WbhQ%{uaZC@&iu_Gxm_Pdu2*m5kv7E ztM1+aLk|pci_{rIbHbU+BZT(PpPvfb2*uPL_-PDc_U3oj&HaD;_y6`kVY+o@=|83V zIk^(blCes{#(|6fyE##b^zkC;p^-ka0uEGe z<^k}tQE2d+kew)!c#4Ro6JcG8Czx^?dNIvGL)Al?AWC^DkERZv$k*3bh4QJM;kH6W z5J@-j?9ZH{mG=WdmWAyuGEJsRQ~Ec)pV3EcJycGbl=)*C=cz64t;yH-cj^8~Dq=K6 zf3B;WKAHl;b>e)$@7lDI!1DrcO~!S_cUn>o80O9W$Xa?%$1##O-ssTh&kX_p86!3r zha};#(PPL4ws8881m;FIXpj3WGCBh-^O0DF<5nSpn9%1oGm4s&7sj)*FS?fgMNGC6 z+=BcBGM)>m$MCzoUayULkA@!&tv>>OTWk_peko5MLgHrkBoR1gdHl|O^nCB}Gykvu z{eMzM$(|E5WI(TTan5ucp^!J$>5HE4TRW(qdzdD2hFCX3$O93JpWl)wq{ju~L@CtA z0F9-0%5>78nB_eaMXJSr_B^*VrYn|GITkJZfsD=b+5r=3MZl70nCR~;l_ZjJASTh0 zP@o+oH1eY1tk=WT%rFM>?}d+nn}pH3e0{%;JTMH5KuyD7Fw@-mekN)gWONn!*b0yT zkOE&J=hfqxpbOK zJGiqrXRDL6fB&xYS03Z3#PI~(e1Cr>YP*z2&v!%e9&M`f&p+StU;pcWk=N@he7c@z ze}+zy#)VQhaas)1InA2MsnhUic}^aR+O5S4$J4XGPcS_;8NB;F>7)&ax#%e7{3bVPzK{}{>+VgitBh_EMn=Un zE&G-7#q4$N%owta$L3<0yzNsf=Xk;FQP6>~VvkVUTA7wi3(XLU%GR4)dTqHFUQjO- zB)-FC83d6lV-alH{J6-F?S$><^WS_?@+EoCDW7|0E|61jDc%Vfkuz6ERX*>JynptD z>J((-pZAQRLV+!onfN^q6Z@oTKB!kJDqVU2BRq@s zEmP{o0XKyFbF7$v_8>Uo@=ok|6vnOf!nr;MB{;7>?_0FZkgd$fJ}M~^`^^@e zFWgi>*0Bs4dX;6G3FZ>dbQ$;UkhW|?dfTC@W*t!e##mdiYFMpq>%%T83=N!AQ$oubz|bedd+tgpvGao^YC{ zoO%%|JGWwJoXs|ERVojVv))qTLrpY%vr7s#glB2{`s~PEOQKp@C|k*l4*yjQ8C#RC zo@WMRV4Pnz#`f~@b_GA@6%s8Y@*v*-T_Y?aS?Y;^M?H!Hn|&U-bELjrJD6Q!^8`Q2 z@!wavQ@pllW}n=Z-Gjw#wQ4y)6Q;!F?wJx8}yAaQyEU1N4Z0tZzBJyxy=oBdDEGbz_jQuw> zQJFK=+*)bOoavEdmbE_%Ox)&LdBHeLnN3CJE+WUZUz%nvchng(R>eu2i;yIkz}bp4 zMvtE*E=Q1W9wzk+P{h`zLyO;Jt#=x$5yU9652D=^c%mblYOJO8D7JP;(@3N^ulRYB z=P_vnS>wKElCtD4({wf~o<&C!`+U*^gy+aft_ZE}me}@V;+-#7Hq&K#OT(km&kUWu zs$8Q>@2{OGY$n&}BGTmR>lLf?pz5uapo)X_AFK7=8+lM_ZUilUi;dyN4%Y;QDI~Tm zbomH+obvVcl}!$&FDR_?=TD!@{wyS#LYxU@+V&)_p^>Rc4Q(@YQ)S-oPfmNUYvlKw zSqRYf#&l`fs$gI$tT(Q9RXR5f3>c8Gr_bg6YBA|`%H!H!a3lCZTmxp(o)kcY+cgbZ zk4qa}RC@*wmJDFaQm!$QY*muc+B&C{W)uN&|L`QCL$gB9WJ6w0e3zIuVoEki8fa9k za1+O2lkO(#cKMhcKbNSczpJ+SFGR;s)+81Jh1Jr2?a{44NY$mYpKi`Hwz$-X!ih!+S^iV6uSUMvwij`lp&~-OZAjW%1rx zd7bk6_L{(_KI zR>ACM1;e5hwd3dW3F-Jb3>>|s_s*k%OWD1Mysj&MmrdFg%8;pgYce`If}5E@=jul- z<|zlO4K3~_ED6kP`<^I#-ZC`S3$-8j@s&7ePZ}~jK+i3yQIPSeEGPu~$QQKfrUW5i zDFTX+-d@u*7959(&iv4?8Xb&S7ebC6RTGkQ9M|9L3c-INo5f}h~pQ1 z(P7Cik|jowni(-E=u1i6)G8Pb#0;27TOg_tI(m?;yl5`(&z<_fG~e>-c8OTZBVwXG zr_B8CRM=?K7D!GBS<4yz30?Br@BDM>Kwuh0`AojPUIa0)3_-=lq$E;)NPQq@WHYEL z{j+A$5hxWOZi^6DZ7NrgF0gHBZC@_we~D@JlbXdT_n5+!2TbB1){`ZXm}D(xW`Y7r zS1WMQ+uqyQ3O>U(D7b) zZ7)5!$Xm`*`3U7zN@phd0Ju@aN?S5L?IVNR)sK?#ZKJilN^I)4HrG~Q22c*=tKGHpzR)g zkR(QuzQ(dWM#J-FEHR#W9@c@3Ex4rgtBFy_ElEAjEFV58A{IS!Ip~t|41EiG<;bx~KQXY-gAnf`blh`~r z)w0mTcdIV3^{jihhJihOPtdQgwE{X23IwgN==oWvff|4xvrK=_=a$Z33F|zgC$V{y zWjVMhgm!I{ad)}%*1F;_5G;OUn4^2Tn`Z#-yTDx|_iX!BHvnhRCM;uo-9&UrYbH}F z4~u2qDB>+@lrh?`yUwg|-o3pxq(DX9@B6r$>N{`sEV|{pYQFY_TML>aA{)mq6^e*~ zNy|(hWc>BKtMB^^vrYstNjZ1^764IC`q}<{w)E*S3^YxkNFUoj()-S}t8<5jfoqS| zAhlM4vS5JMG~g@kmDEk-$9;c)?Qr8jXip+ywa2!7gdgqw`D9~@ZOA048{UhQSE(Ng z4i}R-y}nx-29{S^4>?`amJLich(w{|>^oeVjbynJL9UI_^4esyA-CLehf3sijXbM6 zK@*UL2(VKDPoNHpZ*c8*9yB({;3s9683BLN_egn&aRSm1PSPKCNUcf!Zil?mL}kdh z`XLYIJ5q<{rVdHu$Z3>b(r2@NG^n}l(in!o;~j)Sz;sa83~2tIrZK#LOf<-e0Tn$= zsaVT)H+|4hAj65NWZQ^M;SfVF?JSU`Zd?q;3NfaBy?6O}|2bYFG(+2v*>bvyFvr%q z7?ZM^=A@G4N=_3MH%f0-k%oMfxcGS*nf@cSLNiKDpnJa(naqSPZ@AEAPFh?l(;*FG zN;DFwG;A1lm(}Dw_1~1iQMlte2-EB6?jYNSDQ7mJo0`QWL^Gu@O()NgCcgDBONl3y3BI{JkmKpi%h_CRD%SD) zD4}LsSMi|!fmp=yMwTli%pl}xShJsC06A!V_=eKV9RY}-d_n5B)40LpFNtTProqgz zCp<97wxvb4&f-qSbBv_%A|H8f-Ih6pEXrYU#`bDANmlf+atl*a;<>@wo5ccFblN~$ zPyiQiwXOV=Pb@LcqbqWndhc?*uKZoz?{^GKdOkM@CS_UWQ;vs%J&O#IzU)5UMT5`- zFH#T8`1y`iGm|7KoMR&5O^>1^Wj-|V&puz}@FAGh<`RRZElsosl9f^iK_2_)y(mJ;A) z$*PcBDJo_*>?vWiqlrQos+i0B{mJYsr92{Y6Nwz44Ec8$OEHRO%?JI`wD zQFB1evCQNXTk}+%90j^lW4eb|@MxM_X4)J?G#Z@ZS;}FmofBrEjcYbNR$->dR)Sgp zvfHLjrmiA9GVmZn9zA7bko2nZ&{%2{O;&^o>aKzpvOJu>ocXn)wpx!tnm&h<*Qmi| zs6)QLzvR01p!5Fh{FtAgPg241}(7e`=qJ{=uUYziJH`(@pOEwIthJpKY-M-qb0J1o1S45wz zkd19}O78F7|_YfQ2ISHKhISfR( z00}q4XXf0hj22!|vw9~n3~XdC@bI4lHpIDis5=IYW@CDIPJua3g(muYG28yDg{OZ7y1u&HS*h*R`kbxI{Ov880jJy)3r~@E zAx{OFJe3M-4!cW!pjydscI zGNrc?v~gjphMw}_E8)x_Mlq*;6{g^L@c;SeyAE)3`Tn|+aE2zdMKOp8T}|NnFM1qH z05qoIxUeB@K}al`BF-4X-!anz;_U26=@bGJ5r(Ct)!{Yr4tAU3zNsUXMqg#TrZ=nd ztDqNF^~8{K&PAe<(WtJScD+;6?QEJ4&s0nT3G;|eWqpSwm63SgRCRADff0>hU7>Vy zmO<=L#Est0)pk5L;v)CFbMo6@6s6xu*o&vNjm0J2BGC1pf4<|wi$*TC9NL-;Rax^s zQKs%efr)oaRRB5FM15OsAa=TZpqEDkfzEa0g{3C~kdo2z{7nUOy^rSe zkebrwyxu*1020vT>|qc7tPP+kj}4}&LUgTE0R&Ym2X|%#xNw9S{>3*Fi~1aRsUMA( zEPLquO9FDp?r@PuPS%V`{22fnp4S$?E0N)lmnLy`Ec>L1c_Ii~cK9Kh)82>N^Fs|n z3$1=UQv~cW-o`8=ytPUTY0nCh8|SiBE>9ICBc}YB8=i`gePrG51HbA&($6fmx1 z`!XmeP6)r>Xxkc=v8pj3hxP5Pfc$BDo+dSbUg5E{@$50^L#TG4$whkLs5=dGluhRc z_O~{-6Zt(;4@qaqokHq_VJ3lSj4}+hJ<@x16EyGp&gTTd+D*3)bgn%NR0_ofU`a{t zzNw2Y%U5OZ-CkkkkL*Ov+`@g2rt};eA#*WZSx3*g#CkuTPbgQA>t<2|P(WWe&xzFq zSg5+3&#}8aAQ65*qDE|xfzD?6BL|e)edoZ3vzk~X)FM+0*6u001BWNkl+5AU@(#^IL6$i~@1%Ij?fUGUT`QNg=Umac`w zRV_TH(D)v1$1rd?CQshxVQ!r6P{kBMRrW+OF}#n98fq@Bu2T)Q-uz^t2Ip)g)%1_i((5>--~Vu zLaRidi%10@j)d;E{`g@qJ&fm&_ZEp(zx_ z#6Im{Vgwf`)G*tBn_s>{2r41l1?rAm2NE=O49_-?Q$eOAASo*zvPihma$$=N3hrJo z>z=u_oODFF>uP&;SBe>$Y<^%LK<|qcn}0S{Mbl}wSLzO8YFtbX!_?Pv?QDx|mU)EBA-qP|M#Q2YaSkY zZ$3&Mi|<+8!!1cUik4>X?-ANGDHEqtJ<82KG7rQ)Z;nz-8WHpToN`n2KTGWAR0^aD zABP{%hE9tGghs2y(4UL0WWgV!^fEl|bh$Vr4JOC9FBxRD;&E|dGAmpk{P=U9Pbu=Q z`YCN#kp&>7rRO3%%g1ujG4e+G<`<#yDu$G$m~`Ypu+(dDl{~)pPS#07G1sGyB@R-D z)2=eBLHJk3p9*v2!PzTW(79+iH3nAr%I|- zj2nns)q#U9gRQxu6E*^AGlsFxLz)E(uJ7=2mnAn&wWn9dT)La+Va91Hlnb*rpoAFRN8c; z2t8$snj6CP;vEd*z7)_z)0Prt$wK79@k%OSl|v{m{PpfGCpC%8baHBMb!@pIl1iXyHOA6Vf4M&+$S zH-}X1$$lp4r5_wap-kO`jUm-u{JYr*Q8m#twq^jM0R^Lx`019>8t{XGhTQ55obYbbi4i%)!hINTY)0wI&N zj1I4P3DP*Qw9LF29mr$9SaVWtS85H-%WaHobuk$0s+ECt}A?AcEKA4C#ITb7}_lV(%sE3#{3&=$*2f8VhBg1M7d# zJ~Y=8z6dohs#aVs1r6W}zxnwh_Ae!XP^$lG=uX8wFtWfjI&3a6p&Ikwx%rwAw%Zb< z%MB9X19Oq$aEDJ^pz#80i0Zsh_E!BfWno`2^YLuVUbrf?k7tiFMvVXj`*A=97TO$( zm{G7AYbs;VLktf@e3Xu6De&ST5_BTW#=bknz_~UTK6zdH;*1+oYn&Iv;Uj59rWyt# z;d*NIbN}5gmlVDQBL(n8-a{5w?iA;y&==?V+(UHa+PrP67^q|5KJq&5T&Rp$oEhs( znP=U|D7J?EFlQiUUnO%;M^nLfl_@ z@!RdZ2nYqc48whW95|IG#3NT~Y(<8p&8W;V4mQ!z6Be>inAIl=EDJ0suzg<>fabXv!9P^41AIB4djXYu4p>Xw&nzMO&SoZu1l?|3Ds@#rxp8vAV$ zP{Ml(t1z`RsP_cKf%7=_%uOXtPB24x(&uLnFTQm}E>Nawirc;y@|Jpq%;uzFj%hDh z(6wzn5t9>ls)Wp(7l>3R6R9}-&m=XP>}>F2!~{mj9NBJ{t?;FhgR$suc}SiMLQCPv z2hmex%^_he^Mq7pB*}rGB0TE+Q9W{VHJ`HV`#~sqrQRL?42}cOKd%#E-e;H8W?SJb z-Ig;KU&;5fJmTK8OxcorFI!!_;^J^~>uKZ#l1%51Yg`5n2Vq>US3eA>+xiBrlk+pb zUaq)YFH0}a(s@LbF;=)s{VSz3$bYJe?Ru95t5YCo%UU8$sJo|8OFLe$$TT*;P!#h$ zbyYkpHeo@V*&eOJV=X*)_)g376N=mJv+n??1Qw8GEE+OKm> zh|^=J?6L0j9%A6;BsmfTX=159@xnGmgC=F`NP8NUV4D&ywV7Iu3jJv(9tDJS^&x=ZVP(61+n_ z_nEJj41Fh^i?VqfF{pi8sc&o*nhXVS3cK}uRW0{i^;~2-hUfOG@p!%mBSo^ZqZ{pM zT9#HdpaZ6U*@&R~*3-70dj(^P!=C4M%~+EIwoovWX~&CfZi2E%G&bs#QKH?(cZHa$ zx57570T=1MevGA(!^o9n$B~~!l4Xg$8sFV+hV9rEdTa#wD+f%ml2iUMY_~#U-~*>r z6E8k)DToB66ku$&Q5o#)cD!CL*e=_2LjeAnHVi!ywy5Q4AkZ z@3&))9MfN3o8z=X?CS!U8+_5lqJVGuT^q)siFi&rk)3YXG_9$=1)7MsH<#6b*ihr< znaZ?Q9^~c+JS-zvS2C%iCL4a6Pdzl$U0d+4xpk{8SmR?HsnTX))iF*j^M+xw2kCO% zJRl!dkhb`kgDw`3gE?i0ju%Bk5S7Fa$`t@_ZTc%O>2IASgYg?oV#_?-zEFAL?qmJt zlbA6E&>Lh-^kigdHZLwb#*u_9@d;vD4cJEIhok#@O_d=o0#j`_G#xP8Fx<<$ss%ku z*W!|MV8w!VSK_KUTiiomJw`=tX+)<3xn=q?NEW;1eGX2T*gJ9@(J8%m~Dx02a1iHn24aoo~t9{;_Vl=|4D#6Q>*+bI;c0*k#n5Ap@LObvYO-+9yTF(IG1S|v>B1hCQ*~QFlNFIpYI6z^ zD4g?%E{U8ViQ7CZH<6`KnaMVJNsDYwfi?n|a4v=$nTJ#icZ zk{r>URRnc$ipz1!kS|SlVlq6&yijOe;J88{b4X{pA-Nf{vE8Z?$LQx%1%@7Ihb&@X zT1bP2(rG?O+Zn zGlTD?lKD;%oUDFp2{4T9cP{SrIs{gcE6}!1mljRGTxC5TR*Jaw|= zv@Ix#$xTqF?H!wHp~A`ytCWZ@#xXr z%p~pme0M{X!rELPlm4ZEbl1#WO+nTi0wZ4eFmey-&7mMfI}AH>YaN%g-8G+b*E5n5bJ75}26IJ-0T@t-RkpB6;LGcoOxQ(y{;ei-)fZ^li=|f6{^oSZ6uB`` z_2Qrz(0g9ivYr;J5E#OS8W#yD(xsC4cd|2|vs$@k=A?6;@3xN2yeW)I=qYYN<@N&L z@slS>n45rvmJ_1b6XTK?|6b%*)~s<^Ojj3138%+#WNkuZ$>y3`U60{xi9Iha`bz&3 zLP75xm&+x^z;x)G%HAz$b$-?@pDM<ARQTsw(=WPso5U6)luSwWSZi49f#c>Blwi zVRhg)qWtgyDin-x?&_cpi#UYbA9-t!53a_vMl`qi_k;?|A@ruQxSC_Z$$lEq2O%qK zf@T8omyVlQ%jaCTaa$-PM1N5)hx7@C4xJ-HM(#FQl$Y4n8_GH(8OXC`M9=8V8MdT? zF~~yEfe3Zb)X$p_n#W#{g;%!ZFJjD{0p+|LjS6DAouRjuVY67+xX3AxgRvn!esVuM z2K>N%cfIDwGj8FN>rNChsS8&8UHg7OVUEYv1^K8k)$>InaN%vSEGTaG19R<_;^o^E z05mNMV>u)RYFJfqyZI=Z8m8kjJ0g2v)zHo*t)T#JeOpLZMn!vZkm2r!=mgkheYeu1 z>=vaSt=0bB-QRXxE*q}#T{&&74!{kE?en>%=}H`|mIERwpg7T?<~w|3OLlm-8(DnR zG=2Gugq(|HOZ!!n_C?Oi`~{S@mI+UbrjOBWZrHrH&a#4_zbpe9B+@~Nj*6xUF z1iAhFP)8{vTCQ75fe2&F;5T$;iH?KBjWsJ$rFD|owz6PV?*il7<+O(|Xk>b<3!7cm z4qFN}g{bCDR}0i!cPy4u~Sga&*@X15E|6Io? z`xH+Lg36SW<+OH(b;y><;yC6s&rp}n{2rRDlQh3j4;PJCyv%O65bH2=tgQz!dq9;u z{~`~vPGy0rL-PpCb+)aHB(BDHxx1C_vTd+tX_<+4-st>OojQ)0U-~)}BHbqdt@5ER zc677^xHO6K!Un@Y?{n?4aI<*tOdK8$cR=(cppCrn#YIc9uu?rpfA}S|gv{83*rukc zxW6fS*UY!5jB|1OW!Js@EWpuAjdjo3nQ}qUoti3D-N_Ok4;?jC?i0{48nJj*W zi7nRzPlZKKDGNO_;d?&HcX!tkUERf@P|q{+X?==e3_l35J~OXbZ&G{yZQo&g5Mav< zl|55A@tgbn{q6PwVxZ-^9AaG*bO!M?F5fJ`4A1uTpw0PbqB^_QLi}#@zHWvnag*$W zS$W)Hye`SX2TpxBA!V z_hDs9DyPCh#d(10If9n7I7qd%l5s&D%n&bCKAfp4`z6Rr3`NSWVA*nC4dNO%*amDF zJXEx{O>>(QESN)InHOC)>o_>FO<_{HWZ|BtKVMpn%abX-DwSc4sl&JCgPEbkG5x!n zj~shz(_?#o^U-b3=~xd2zd!6xJ@qI{FQ44saJ$_w;4|{6+vgtd{|5$w{NB zx6n&q0TxnU90nU*f`Vih2h^aVRUmtijcs1R;&Z81bi>wLS}=+(XeWY|5LVp#bs|Xa z<-0g_>i3rj%F)=5tGt?{L=+Py8eArFsDNIL}QH;2+0Gt6X(u%}abtWd+`evt6ch;@FoQ z>(<+nv5N_*O)muY{g~${pH_h~IdKu=T;2WcHmz3Me5Qv~F)b1+KAf7Wl%MMfGhr1Y z*88fD&|KRCU?lFq$PT5Tjd@XTf<5TssjbAoMq=RXmK(WW26awRpsTo4^{xA5HKulR zVwYW*K3Nj1$b9uFD$|x@pG&*w3sg3QICs0v^InPhwp!^Z>%}!T;R;i~%-#G#6(Y%I zjBO;pX^vD~Ni#K4pu>7r1$m4AzA<8Rs-uz?uNXH^1-d#@kR1QGO$R;?nA3>egRP8C zQM%C%w<2Aymw6~n7C2HNoo&)*S+j<_>ow7gu{p)dInmX_fA69v1=5=PPt1dzMO+z6 z-T~2v;4k)m8w>d_)P%UK+`L0(9-3D2QQ6!y(c_)^J>XNmxcH6}wQU~UgE%vLJVt^yD*vKT?|d-vDFBt)#^T)q@3_#+=ElL(n^1t%Y83ylONNzeS;oLq zd9Om+-meSdI4*Y8k0XmcLp#u@DxQ_Io1mDH7ED#EjTbB7(q6z)Ymp&SLw#jN#eZ!HIu~NMEDVLQ z_DM0>CU_I&HJdXCi?vULfCX3r0s2^QcjBMs)5J}Kr-sT*CI_;*{J`0<`b9& z+yESQoH|yJh2Q}+2z5Uv(`oNPpnR>aiUGDv{nR{wxzY+-0ctwb%}xVj1z0+F$V6R+@BsbpTJAy zJ{~=qV&LtzAG${dTo_8h zz+oCndr#QO55M^JK7YoItdr@kpnRE-aPi3 zeZenW4BRLDr2BqpXObw3fqvcycg&1P7=|7t2F95>30@~+P+JbKYrAhP_&#=JwHoH= zRv-9_<;^`pN-+lOXbU4rm{s9mg?8B(X(SWLep{ZwK+x(pRVa}TAwY`#0cHxl!R=T><#5SfpH&A z3l*xy_k4I35!imzlrstiDSrc^F{K(zBoMw>@_{U9c4O>I!EE$d1d>w3aO?w+F4yT|E?%_tVvY$DKWA%*BB{cONau%TtaH% z*;dL_G@g4#gaf-gd17$D1U>*)w-g>}seoJk$R0Is*>$NVg*1eW*wg|8t8Q^IRPcBH zygEB6q-AG;nJzRbwycHUdrpn2$A$AvIc04?Qz^@0zRP~G^A4Zr`q>_J?E5~ITe@_! zo;~RK08Pl%zt5hK6T^XH0RxCMY};ia6*3B)+t$ah2ev&HkNn!6hwdtWB-FXBmkzO@ zQf^Dz^|acxxp@1U#mYUFqESjUo}6clFOKy#4%5>{+j76;3tScf%4z?!^^&H3=wJ`M z`aukA;WC?Vgr5ZG;oK>vu+u?gwGW2!Ife@m*K1AF$a-I5;LKFT{-2XIRBmc`j+RMQ zv0e|~V|Wsl)J}~YtmFYW%X1TZ@0WHbKBe1YYjj|*zLODClOzRd+G&J)l`z-K5U2tn zUdU&+&65KJg!MK$OT_mPljP$VWuH0054d;Ce2N~$o>7i^cXyXPD&h_q$b_5pHh~~T zn04A59Yp0sfs63|6V&>{m&M4Gut?F|?JJ;cv_Jo7Tw zl3J?{c2H9s{<8*2k>NzOA5Nif+*9GHi0}ViZtb7}wMn`S!e5d?yTh$=xJo2nKb~E- zOP*;bL378Z-LpfIFq;w6Cmp^njU@NYlVnlt(shtd4)0C#3oaG`Qmf1F(6S>ou1f$E zRFUBMr^Iq6M1^wLan3VYg?pQBF0NJK=_5~4=4I>1vj>;IPgjjD;{GZiNn*`sor|WJ z*2L>7s6#2wI%!Fa{2LYvV$#%5m$xlFwWHLBXhh`(`#AU&k;1vFYC5ZkeYDKXND^c}bDUg%`F$rN`JGS878C=46TsRs+qw-)?E!3tK?7 zV5`$vKu`|J=fyItyiRt)KN_Jz@i3^Nq3O&aMW9r}FHYZm973{B#XZGgEfTrpf|UXG z4QOLb3Y!$PBSNB!wT5k5wApQ!EnBIhH{!PM)te~~uV8Y?dNVc8xW!7U-93HNv(REQfvynMH-+Z z?L7~tB(5}asWU0!V;tG55!0Hmv&Hm6TCL-Cd8vy|>@yLN&m4`fk+1@dh**MSYH=l> zchHFxWhtJj8>y0(?_^yby~_+n)0P#?vV^B03wnD{xnUfpwNW7`udAc5#B*{z(YhNDzQN3hp^?wvFs?zXZYd8f-j79At+jBOy^iBp0=FxB)DuYlk!*xrLqvNAP`&f zu>LHNg{OXJt1N25N&L_(g(z-b#Sp@V>0G;7UJ&=R0fiXoptuwn%q`?b@QkpxG=DKd z42(-=wN8jet>s?D%z0 zkKACZ_0gZt+a8%zBg^NU80)@QuN>#r7-XXMpwkV}uO^n({e(h!acq#Z)U&Gdxf`B^ zn)M$-BG2VAE$zdmU9xw<;g^K86enn)<@pW<9Jd>WRv~Ac=eV|lg~}j`O)=03oUOqc z7o@YmxBmXqg6rbEpWS#0m4;HwmJCL z_07%ksA0Kp(}N4@_?ha{fI8yUNOe0;+Ss}<56-rzqDuob1*Ng{-bgla=OQJA%CtoF zNj=CizuPDG_jq!DfAXh0k?ipk3h{Y}@%|pWcWL;VT9=Vg$kafBF9>PTw2Xve-g`?M z<$($rmbFkxowGt1XMt*|(Gkdw!{k3sUM|eiE*MlcxVp5e=*WiZz_f0CtM+-fBsR}I zDR~`+t5B^^YhtKBV^nq^ibQK&Li&Pll(C9U=CZX^;DyT6)Vcm_#Y?K1E4*88ux44t z8X$z$>6m4@6v7D@2kbPz^W|?L=U7sm##mdOYl^ZW(IFk3K{j#tl(Jl<9VDh!TovO# zXYZ4|^ysNa6v*t$fj#UBd{{Cy>|?J(f6@TAq+x}kt5Q&e!v^5JA$d67iZnE$JLj@d zXkW;xW~U2lmCnUQO2YPqR%Odpc}bLcDW@=8gOJa_3p96UK5n>`%9IE1_5Jv|-pNju zQ!RSd*w!H?(WhF1psdrwL{eKzw0s8c}y`xDgLSM&^wh z>aw1|1DgV?wVJ+~S6|G@?CeBqzV3|Un0cMP;b?8OKwzTDvP4kz{b=QY<9 zs{!2QZ-j zYhUx_Kau!Ll+TrwtGtOBmT_}7h@Yrj%SGc<7|J6$_9No~!W0y~J-0oRGIe5i3k3vo z(>?}W;$#__xO*VJkD+6kF!J;&tv{iz(_|!-NSr5` z$j%=Ks(^7HwV|sm9@Kn3ZKV_ja@{DzHzy53jrY1NR(bjGj*6*L)+7j6@$Y;9o_!c> z7b^fkHC{;(jv|v3HcY=XGSuV#{yxL?JW`*(uDODBO~O%R0_rkYe=~QpEcQ0qIF_s# zmkA0Is~w;7)+_7}%Fg68;ROziTzF}Vy%m|4Nff)k6XAhoOH1!ts%&g^WBXPp%oK`C zRdd}mkzRPVr*Tna77BWI$1#pMdE85pFJdO65<$I$Vhr9&Pn)@I+l$R8t z_fi&T9^0=22sDWH$kWoGbY+Oyr%YwhDl$?i-zpjuZCQ$I`CZI+IBm`)809(ACmy!I zC5kQ_c>5G}{BzCeDdGM&_5h!@*L1s)J-#9eOU}^WvAerFFOBX=rOk^dwp zH6;mr2ufq8KkwmKx=lMi(~J!WSOfSXj76 zB@d2H?z&#@QcX*0SSyUAc-VY~6?=L&$8ajviTc9I7$2f8`;=|w8 ztMxoDK#4N0i!P6o83v%E0?ysx0*hS+Qw5Fhm=Cy2?}~%x7?!_-anT!%&~tKU<*g5k zm!1}~C`D!JUi|O9iyxAED)2GUxLhyTde3}EWLSn;wlDJqBEJtVQfK>

XY3-WvrP zTPg5XRG#&{GAd>hq65l8;R9ig_kCZc6`S`HNvj^7P{%TBq&hL!ISr~1J*(p^q-0jW zpIfGvoj0~>W|k8vs3r`2QOL_=qmU>O0;5l(CYby@*QHC9`iO!|)7p|HiDxJNf88%p zMe16Ka`98gGcK;u_ukM0m)ln8Nw#A5p6YN;Tg&iX1+cUZ4jnTO=M&?+OcJ(~iy6}| z-Xy0sjrzR!eNj^M;``&xDa5k5G0!aC^?Cu!@ZR@*Xdzee@5*a79~caba6jAi=6l%4 zqR3qq3`6LCz_>Viw{;=5@G)H9KcbSAXSuBY>g#rq`AQYyik!zk@ zxL7fzRHrfZEb|3Db1nq>d#aRKQk{tC5JjVGb{r$^qC+2Mo?-&h3ACcR_U-VcHfe_5 z3xx!Wv}~U*;gri{r#1a>2S7Y;O6!Zl(EaneT;`s+yFEF?8YMVXUO-Oyx4PKYTHal( zsCUlDDz+{&0R^i6X(u5Wi)}BgU0moJ0EHqot^#|b3rM5>qi|8&{36R2f=;4P^EEU3 z0DWQ-H55`eeqa0AvL7vbA?FOUe`-B6(BUISRSt9GY|o!lX`A*@f+gG6=7E6!1maLh2l0}kJ1BK|E>SQCs z`EePzx{7^&ix78hAo(4iERtSY|EtMJXKDy&*3O74-g~-sx7L1 zHv-B zi*hwek0~h zaneow`I;2BF=j3XmrIcgZNjgr52s}xRSKMrmd?+ECZQ~NDAiH4*3$l_gKAD33KXJq zWQzmn!_>OmN4%eL_!<#{#8$UvTW<16k)iueBP!SIhM690PB%rXc_56#;~0$l4A&8r zjl*O;ay8s~ECw~220 zMyq~+>fVu{3-UB3a?xnaxq+fX`RAh(77)aaxOAkSa#5yR=9>WEa4MQoVPzVP0 zL+|VaI-E|`O0DwGKGmQmj%>wp5S*9#x`Yd5zQ%%^oa$>%@faTrkcAU8VE`#zx_H<}H0aMsc{Y~Un*tpJ2P@cYFkr<%Ur z8?}m$F=oE=R2Xe!&*dS7>g?kN;-qoiNx)z3&562QCnaE$599MDC}cV zh5-v}h}=$HJT<9|%SOH*y}%}*eKj%8r+u_bJ=3v12^Y%_0~&Sz_+hA-6eK7oM2ONr2(k5NM#+>lr$;}Ue#z`Zxna{mJNOg{a*TkHI z1h>|gDRA^$r48K*ORi?P4>9n1$$#f^*}M!yFX*DY#=347wlJ7qy z2Er>PEHlvw;)sj1Pet~9FGR1EAjb6(mfeUgML1QC zep36dd2L5n{sOwyF8zTUp!beVU%^d>h(XhABhLnBr1%s%uZp#bk8bn0izAb~-&iudalk{}Gq*`>_ zOJP$Vd29G-mtwslyzG0{Pt~YZ2U!K0|Cs>fpv99Lzmdg!!!!?4b?z4`PMag)i%)L4 zPdvgxld7U2yN}A_>-{yuvS?5QIqfP-7)jg#4mbwo(kyLiL81w4c)W+3BTsMM2tEav zo(n^K-(^|!#n!3>46yVyv&TDZPw{&mepn7tO!}@{fD&%=Fd4YsCGcCSR9Fo{(PiIy zm8GthmLx%`EyTj`lxw1)=LI=_u0)Qbg7l&6_12)GiJRs3JU<>=54f;dq__DR)xDLu zJ37<$Rr!y`>DJnu8vEe}PIs#OfKt$Xlz@UM1YEYQ4vpSTmKn4}TT6Bf42xXcF)w#l zT_!V3Dr5zamFB)}i_I!+2vMBqdqA|Nr`0S2&#TSK()y!R9RQjHBFSb|E1(NOX(d#$ zs9%{DQ{ag3vgvB26r$O2<|QdTT%w8-WP~hWZ2cq*JR_}xejXr?N#Sg#3IoY?Fl=r! z#0^X|+jJO2-eGoo*pl};hC)skY9R|%gsT@zkUwBC<;)`6wmK|W99=A4)Dv|a2S#hS z^zNWOBYW*iAY1N$v()qZIlMVIT{RpQq0=+Rxmi|+4ts2}!L z7(+`N7{99`lK=cF22R{@QKni^B&n*xC>N52;6CZ#ca=?x41$7b?r)12=xZ~KHo)G#n$=w8@{Q}00eSe0AF)0&$ul zR-#VD*gMD}AnI6*hnKubP?DPS;71+=c$}BE6@n6&O&dX|T(RJW?Wy~iEL(!rdFQ6H zsTV%#ree#uR1F>ZP*3&N8SAm}s9+AEMp;Oj;PBCYs0%tY!)D$6l!^hh2~vob-Bk1; z7#7)pwvb_vb_4%>PyTl~6^n6ud23#}MriPu?i~9L(~jNSwYj?>@++Y*>^#mVWvBJ_ zAOs$oZ7}^UOIxekAQZkh%;#a5GigNc5Lx>S`ZgEqP&tp|@Sj^3v~^Omyr7hGHW859 zdY_2up;OI`7*}g~DC4}_Mx9MoFJO@&ZF-$sZ!2nht8l-PO~kzES){rUN^SAh=I)az zvIpWp7!w(UjKjwk6c!l9xX**ES|OujijvdQ*3h<|NX_Fo^4Xp$RmbIW$^HR>EI8aK zu;b={f-Keu0uz#Sah)3cQ)fZO%a~Sz|x@2r(Jtlyy*@uoQ`Ino*%#t~ubI9wzpLb2?!u9GYkzBw~Nb3-YK*W4Knc zYmGA>zV?iySqT7;W!T5Znw;%G7+{l8^a@y?34uB|h~E8T(;Ya$dv$gAtd1AH+(Zdy9@70ekyAYYKU<4^ zFZ;BvoEJ&ql{A z#lUcW2nkT}yKa7F>Mm^Rl9}=IrL2PB)S=rH0OC>;8BY<6Aue7b_ho6V`Z7^MZ-`=1 z2G6Cv+qsoIEH36R9s73M z;zM8QUWqbop}29e7IM_Y_Jb@AoNs}@JmUcnKw)_p55B$#6|cdTV9_9TAzvCFX`;!p z=*-Inskt2dwwgp~LpD6;p(cHf3bVd!en=For4nUQ{We0ju_&I4gWYkA#8iW(3xfh= z-Kt|C$KI&Gzu7DvgwaNK0s~}N**A#{#SyKGFOasd@^K1JA~DQKJ+e4pOO{>^A4Rto zs;*%7LticWb_&NK?P5CkLQ`r{j6vguFI)y_T2vM(e|~-6Mo3?7l6Q-adE}!l7{A%8 z;xG0X^JjZou)&p>pPQh5D+P_#`mGPuuG0R$$-n7mGko zbpJ^8EIBtx>YzFz;P(dj#9Z>6oG=kT>*=ozJLsLv5)oL_r=&Np8q zp*2lsF_0%mKFy8GsM2IIdVwUntJM3MY8c+!%`&JEl`j_ad1yINZEZcwwj_v2POXnI zXgYyKT%MwnCcTaSzI3iMU4+!2z=jxTB%pyh0oe*0w#(jVx}pQk#8Jzh9~on{`ck2! zNYOsG?Ls*{&CkoIJ8Wo)*Au)XI7G0?CGA=B9lIft0(@>@Ai&`z@l9G<4?{>h!WrNe zdZSBU5EJ7}w6PdyWp5px#q0k0&y2F4XSfGyzp@((kqW^LSFRWq>a5Kh#Y2Y5|6H6u$Zd+>uNhtbMzG0Q7C^e4n*kC!<9+VYN4 z;pQ;x7^&on51U5PhWwCv;+unl?n5i^*l4rZj|1BJY_3PcF|b%zQqc<^thfA%T>QdO zjmPHX6CMjju%5Z+61Ix8qG-;ax&0bht6{mR4FIiaDhy)`U!aevlK1JmX%%u1a* z=N!d)xel|VEVfDhXG3);T9eY4TavQX8RP4jf>=OX=CF|Du+2l>f#02$w8}sg>Qq-2 zy;1+iA*pz8TMt=2dyUNN$1j%+*UN^>^@59MWQ?Y3tX{MA<8YRLSioAF%5Cel09~AB zVkL{$0XWLqVk* zY?or*k$j>K678q*6yB4zAgnp3dcqZ>1hfc~2cSf#6wl5FMa*@~Ts^JOdrg;BN^DU= zC1>k+OyoOG&;z%$K&o1Ry0Xp%q)T@O;ohsn)AGO^drw+Vj0;L{i>S7?1H|O4P?}gbcauq!*976>Gf`vtw zD3GXZUfRJ!a6xp>%>2^*ZBJn<_7whm1G1C-ZwT;}EP|j=PB9MeaU|-k<@9?#uQ7cW zXw!LFB*(+yG|f2wF~M;u%M2KYMSq)%fsMt$`A+oSFrI&$Ko#?6{BTNQh$M-bCNVJU zS=1K5Q#@BSgc7IJ!arr$AW0#H5BSO13|N z;Cj90c{fO*L&wbE%zwxhOHzg(Ns=fiXimxG42YF=P2xVyWirQ^wy`)PBN`k7*S1-f8QVp&_Tz(Ulc_`JgII>x}bT(UX5 z)Z0?GBaE+R5Bep>F(8*M56iu8P~CGPwTMrxC6Q{rqdlpPA}zC9tTIo!jbdxvCv-D_ ztU92Ohh@RE+4k154c)vbE+;mol+*LI$Pc>=t5|wlq707Cf+-p`Ns8FvlsB6&0o^PgqppeIwtU9;B@f&N^3#t8Vqn^s zV!fNo#d3)h7mDK26%%ti5#*M`ZnT%9J`*l|&IywUdbXW|`b{izc`>QrBIyE>NeXwP zX-*6I^V|247rC~zn%?=^e7W?@Zp3?g9Gck;2C#JRbQwO~jlFjM5GU{qSr&mwVAWQ( zQ=@#5I%EW%rOiWeSi!jSODl&PLZ8rusFdg`ISiq6w4$C)3w)J2HedfTcVn|0d=^Gl zS#tbdt?APLbc_L6kbnkl(Fdo~vWK#!#=D#_nix8%dZ63^LQ!NaD|{&a_uFlUsZDUr zaZH>312M2J6=@r%3C_G+YG!9dX0|u2SyF4U*}(NW_sh*MIEPz<mtfxDrj4WX{$+}S(0CCKXszvcA1&#|{o#I=EMQ?!B^yeBOFx3%{?FGv@1(Q${UeIba4%Tj8iA5Bg(_y*TWjNJGhu}$2 zUp>WXt&uE;_veOHzB#wg-+w(?Z7uRcp91 zY?H_!Wppb{7t8rzP<;5M3nwfqp#qc)Htllbn3b>K7y(HnSwPPwqH(8#a_;&Dqxn46D6GW-# zuZVt!vcR!5S>2YfKI?3|>b>Lc?mC;+?{66XY%6soXyji|{bL;9Px6`L^{o|{07e~I z5&riBXu0Jd((=w-ZbDrU@mY*RJ?L#~2`tqmw9^zR$do0VSX%8etEwc%2zRVd(Jxtr z&z(DEsa!j)YGOHU(pX9@sZ?9ovRiu)XBzqMwR6BdFY>yS!?IO)<_wR#z=!x2`$P6h znL)cleWKd~aOAt&=@M(J*+CVb>livO482h=lVy=`Zvs`nj74@PyXSPx(k`DOWvv24 z;R2)iekl&1v7QAw8YwO$vz@d`i?w54vCg5^Y4j6F6ly4+J{=GglAxg0v6J6ptD>;@GK z(|NRQ^Y009rYAPqDVx0}ip|MrLkGlZUU%0E?ylDYI7v-&IUm)$vVtclH3h5k&=3PJ zThFX_3!52$yMC>yvY(x%O}RtlE)nJ8sO(0Tdi8y5sN(K=T_(tJW}DRwH5EhK&=Yhp zaJv)doeLW^1D_Rn=7CqR zUop7hKFZRZP*H*IDiLEfG1Qt#c&N$A!;(i?W}reAvz4A>r-CS3O1mm=Af?m^GTc{z zNy`I8-1G~0(AGjZ4QraLV{n@p216@iFls_^+(vpbD{NcdZ!%q_nw&2nqZ2uUK#CmO z4P%TR!Cs3XrO;xl;RBzSuX*luW%P7d%!_OXA)%20z%v#!Ji$RRX|PnSA{Z9I-$4lL zhPhB4eu0fkG5W-4g1+lOM7vR8s?t85)*~zvNP>v?B}-3!i6wNW1#U3)gSCJ5dh)f0 zeIST=aw-m68=WJgvw7`A&+j<08wjtePipqtf!lug#@Z4)&UuRXe5l^lcV(Xg+qqD~* zE+=eRCbiI(7W$EY?ih|ek6tS3Qex6i??T1BfjPE?GZVdHa^^5-iF<{pCDHF;0;n>q zS;R{DEw!awb%C4kB+k}9n~6{i^>Trq%AUT@nHiWY~Q_7F%@f5f_;4)o-I=VIEO6 znBP@V{pNFVoP_P>qF?4yUjQN%Sy)xYllyzLJ<5mo{PQ-!N$rf;3z3H!b*bcKfm+_- zBUq3cgoPG@r36zP;mBih%Zn8jbrT-o6}b607uf28h-}E_eG#)Gpn_QJ1Lsh0JZN!Y ziIG?YhBKfm^Uyrm3X-Tn)j=BgV06(TY+4H0;ajfumgG2J?j zvZuu79~U+AU{8!Zl?whW#`#16Li3A{U$P>oS`(E<`4%@AI!|0jk^EE@m&@jpqS@C2 zL{>_2WUM(A(+8G7&a=$Wvt=g(kCi7KOekb6Y0Ux(smlJxtL_$t@qhFE*r)+gSdxVNkT!|E}Q4m=yFQl z@7Btq*rEZIHhazl^5$?j)o^xa6rIuNU^$@>_00F)amBpY4G$R~PD3;^+}%CO_T<1U zt4_Z&C|i|?PzM%tBG?^qQ4BwQmR<^#9Cxyw`C*X`X>d!%#iu;C+YKX#R{nj6^!#&M zBDMW;2u`FUu;MJ1$c<~2jql47J#v8kD?V&IZtTE##$ zqdaCy#B2OyDTq<|t0i2ZB_KzM62+Cn=aNuH59jpUT@%CI2-99&md(iY4%Jy75T%s- zx#xsUiQp#7h4Cx~23-=A(^YCr%J18I?E>dJ&uT6JE7Hm-L0fg@p9My~teZa|gRI3M zG9C+JLH``85Yy9CxH|O$pp)+-CMk@?z_9W!b|lITAHHT>FI&}8U@ehtLEti{`B4V2 zZ|h!`4h|~%X7TBP7`U_{$U;Z#U6PzBGIE^_`)S{{bUVlqXMvgHm{X0iYgfmdq=GSy zvE(2_;7t0bt-g@?{a&UZb*Kw^n;+!s_l-+H^dEL7_eFLlE^pV%CCRzfyH?^`)If|Z zhu-V#K=$dOx`>%-26YEOpyJg^c1?nzpS$nwu2in>p95vH#Q`)aPWc`dVnkTE`_{4b z4RV=(Q;30FfXHjZ@QYLAStAe3=LsXxE+9Ddd6X!aP$DnA?qBiBFZl_E1_T0h$sACS zZ7vwHcyPHjmrE`|VNzSl&8T8SA4p<3(aD2!lVy5C4q;y;C4HwLRqKohjNkFnTlyU1 zrV1)RQ|hUJt=5D19flSus19iy>_yUDT4%L+Z7VjS9xYuGSvo1X5ru68OuJqf@s>(I z_i`+4+eVfvrfLM`OXDI)#c7SYKj`urn{eQ3mslnB0CAUw`iQ$xYkR8JZUZyw%SfNF zDpB*81ZUMDKo>7_OHfeh5*>(AFVD&ngDOH9Q_ejxb&Rm;NpYb^*<8h{BGtk^W0^+M z;XVV(MKC+|BS97E5vG#O}gqeerXE zrXej$4Y62w=7xWp<%@CobCmof8SaI|&DGVGo{anZTTb2B?I6{_YtL zZ+Q2+e=FA$C5qR1ioxWx0?@EM%@zf_ki`#4Z#nE@Uq9;o=lyJ%sL*~0R_5uwTBv$l zIs!bfxN+lq=1iB&3hk4y1%qNs&{@){z=zjtfhTHdPoH}AtHD;^JwLxo?ypgbC1Hj9gx`({LK3Oi9{<2bCutj9&l0+X(hIrECBc+~Bf=J2 zUX{ppVNJ3np*00i(7Q`rw97=P*3yFCFq~y6Lbv)^!p@@<0O!voAs^~upw?a|sP&vX zZ_>_8?~EomsV#&&(78@CyF9Iy5%P}$W=iR zCEJj~)WfGVsh6qIG@uAIrTRA+7Xunt^gv4Awl(Hmkt;E#yb+vOwwk_ITaU=>PynKG?dndnxrA$Jt2{&sJ%rD zW$WUjM~~3^6yY}7+eWy3=qB4JHy!5~qw^}~gBba(ZtD)=tEOH>*o_?YhSLupo9S}M zwq^P`a~P`Y;RndFNU#!NJPuxIYs*O1fC0kE88>4$C`KMYILxS7_w1xH|FVY8mnaU@ zLF$T4DA@5hwM$1!>iOVSjq1^1?y8|malwhkak=gI?|6 z{p>H`5A&ZNeA~AdS6vGfpAWI49oe(}-5>u0eE&y3iLd?q7jUPFPv2efORsn-{_bnO z5?_$(g8-_T;eYwN|L9-&bNu;#_fLC13fUFF2jc*0q%zR3{QnEx>xWbiA4d<#!+wd% z&d7;|)H2YGT9`4t$DuX_b~`O15e0gIk$F&TK=#Py&t||EY*ctt8gOazfZlt@IF6*g z-S*u}QH97%3XD^)&{7O9j=Qd+D^pu8{KLK0EiV(5B^t+oH7$xt>uCdtXLC}T2&5tN z^NI^Y6>D03N93Um%Ip6^xybqJifb7R-@&5SyN8naBx9(A4A!K51<$EayW9C~AOJxy++y9Or*Lz9|t*oh*^-y=j8g)=9eXt|D5 zE@lPgfS56|Wd01++$J_GNkT0r-ZS&YeRJHa1}?{iEmQd=$7WdQmf!HXFW}$)*eCIZ z&pwBj-VQu>>3H|cz6k&OtG*P!{?ZpOK%pRCedi}Wg|~k6lla=tKaabi`1GSI-uY!O z!~gnquf((0Yv!>+jA`MuCrawzDXkj*_$ zZi}Fo7V~EK&fohKzW*cZp7_o$dl`QEHLt=K+{(%#rseaz=J}Z9gg|P$0M+~qG$)#2 z?GlJ$AySotgfgrM+nMI!wQW`Gc=#TZ`6N9}2i=A@K!BH+QjFoWv_{huac9PuVuTb3Qdo#-y_3QkmBu%;v^K_?)>?B@k7Y1D z;1KcWmBXi~hY|;F&&`GvdmiS)##*91+a>d2`=H3IF6pX<>+OdBu4E*th^Ux>mX5KV!hg!0$F=Y#my-}M2!@|i!F zd)`Z4gx`G4tMQKS`V+W+@l#dLLdf{P`s07|U-@(V^`HFFr85Vr3$#UA<&3Lqt;(dW zk+mAlqhcA8GN*Qp~9BKhwW0< zi`vYYgPfjtcrXu_u)F{ns$h>N2BG+h&0IydK2?(R7rULNIVq>De#!{WmABZkcR$JT2)dmu;J+pg}zW;jv*$7%q(l48a#t zU;S_0T48eM&uWWJYp70olK_`(!}acp)_`3Etqt6cQIjBs98j%L^{JG4I7h0I$Yd-C z*uoJD=S0xwrsUJai6x$4V>Mkm7Bp-#R^_Wx88wXKnAwR?W;|1eAuA4)5TJK=cbQL$ zKVuI%jvBt_7v6>Me#g6(>Yy+B!V|pVJs-py-t$5Hw}0&~)TPzO%5VLd{|Ddnt`98F z+?RazIeh0YzYl->eILf(`k}Ysb1!}Ia?s?q_{{J~;Zy&upM3|u`PbGz^NT zzk%2N#_!;N`VW2p&wj}t$s9vm^4|6{|M@&t=0`gWx`nm7^3)lL%+fV!8(*TS`PVj@#{W-t8Ua@WB8{VMu)syWx z!3h(3lL8Et+c|Bcrj|~bWQ2brMLonUVc9qeWgkkdS*{qf7 z>EOQmvU>gb-~L_v`yYO0d7r=dcHn!S`3%12na|+g{GM;3DcL;m{Ka?wHs12_hx^dm zKlBNF=f^*dzxpTNfZu=7qeb|PgLHRGWgHyikolj!>$mW|AN}O|XFh+AAN(c9xvry-;d08s%Gz2x%T8+=0*cqAC1;d_qiO+U=}uevi`>zGvtvyN08&|zx=d`_ zMtNV0q!Ry}h zLHz9>`9XZ{WiL)5+p!-jaOhw1pW_$~Hqro6gpq=vZqtdKLP!W7HYG^RS!cxZW3`eLp6-B0TwKWPMoi#@1KMPGAc?+vOsL zUNi)}-OD|I&N#hR-~U zpMUi$a%?#~e7R1^xN+O?{lE7qyyf>kjc2!x|KYW-#y@-cOCSKg?e{;6|M)jQhL_*( z_)GuqZ{f$j>yJAb#*$ta|M|0T|1JV9On>gydzO%Ab32gZ@)+B5Q6`+hzaLe!n6@CF z2-Kvo{N6$qH$mCKOn|1E9VOEPz5z1I3o3!Xo!`@;BP~IU#y;{Q;v-$Zpj{ui1<0vS zqMGRHq&PM4$w$K&2k!4jdQaO>T(-WTR6);5jCaFTaM>=?_iT#e@jZZ+m$hx%@Z`z; z1I1i}2zMMAZUlwrgD5zAGkmPhq#rYg!!+i5(;%dZbND%m$6A6BCUwjF;veLrM4F4> zjlcRn{Hb@m3qu6I@NKWdyWaR(eEy4Hg1aX-yynB7z_DoS z_{Lv(fBq~#|K@MU`@jAx(M0gt4}28g_xJx9Uh>>y{Mny<2mZ$&dTVW($H3jAyF{*M z$kD_38BWd2i32VIa^V!11V`8u0yrPne4{=beZ6hl^ly9Uf9pM;_2W2dV+rvf1gSB6 zDn2t08Tciyb%IqWC_8f)1KrCOt1)_Qr)FCLU*;d(-Qnq{`)d892_Xv{nm#pKLa^D7 zL#5L5ps9dLQjZEBHbEGY@CxDcU@6RMi#S&KO<5){LdBZgi(@p2;?hx|Yqm6o5C@fW>D212rV}S!WA$8j%q9jrg~T|l1Tq>u4?JeT4}A2K_@NI! zgF}Fy{>oS2=f2|Q`1qp>zUWZA@iWij&wT8Y^z+Wo{msAoX}sm*z7KuFtMSe+{UZQ? zZ~y(z;Xi!eM|>ap0RGB%zJV-%ZGn7bX3pR9KmCzs@Vy`XB%a$k{?_Zh8t?qlm(9KH zlb^wly!XTSlKUNh`CY$_|KdAdN0}eP_x|K@96g?GOErGNl$`qby}AHDyh z`Lq1xH@z;;J4pr;$~%S1ykuLY@=Z%lmEkg#!wKQ7u@x(dA6;nVKR-K2q^c>(S}vuW z2?K!K{+h`ngogkCAOJ~3K~z~1FM(9UJ_d%9LK7Gfi431+G!joiQ$4nZ#^re1`XUB0 zX?A$M#_Xi&c=YHl*Oy~Iu$wNnr?O#l`KODcy;u;O#mk$ZGSSyofm`)K9Fo}U;UA1@UAz$cCpCC9+zdfK8+gQFZYeV@_u~Fum27n z-(B%@-}kNfz-zt=0>NuP@DaS_AIv@P?SJnd;_v+E+f!6w2NwYRcmLIoBm^vA6LYF& zWz)3k$xAC`l#d3bjmkXFU78Dq)~SGJm_vM?u?@s!)=~se4vRjBqo^r1!|GS%hUuat z)DJf(xXB}M9z{;NgyWTAC!YU`6-^qKD<7~5adtvA2kaycqKzN|p(aX076?Mhk6k52 zMcIgdUJ1LGOBQtjsVQvCLZc*apnTnY6BiLQ9r%m?;)D3y^@9KTkA78NaQMS-ZG(zp z>^l|q)rSA-Cy()l&peCgd&56{)yq8;J=UNq>HB#Z1@PA2{S*M;Z@lI!@$+B)#Yw07 z`>%XC0Ks2+?}zcnKKBK@;S-<1yI=8AdLUL?m>DoI7MqKRprfI0r3lSn+{i`VP6b~I zNo$OeB3GoTc^C|(HSXZz(*{Ek?%?a#TvU*r)3Bl$+s&MC5--&CvSoYw?Y8Hkh?UxH z>*+_o^bTCMEWmpH@e}B6&%;FKHT*I#yqD2M3w^*Lyh}3z zm$ASe`+;N3OU3na$)14z*=O;+|Mx!!0Q_%neG}gGjbA?(LI}pwkMQfS|62UoANv|y zY-ThfpYg{3kFhrow(Ppj`@X&Rx%a-;^Mr1o8)yuTZp;%w0t6^hG)0Pos99oMBCFy* zq&Svb@*hemapY7fcI?D)*^UQAmK6_GRy2iDNKhmNijqu`1UO&@NMdTt4WNPU26}q$ z-Fwd7D}U@Y?Q@$ccNGbc-S72%XV`n~wZ8B7J@_O5;Hy9OJ{-OK7UZ0EDM_XY+VHUsRF^u0&ePoB8YCRp%F~IQGvZFZb=jU+mqX4NO^|Kf?RoZ(nl|Up}x~_4a>x`98!L@OK`6 z9@oBo4mTcu3y;J-P*nz^4A7hUcNr+_<#o8vs^jQ{GoOR>EbUS&(DUP;>G6Db{ZG(h1=Mmh3fJNV{94%<<26!DxQ&S?#zM%O!&b z*(Z_$cw}u-NJk9yP#P>OTym<4W+ztQgwzBv)aTue!R;^%?OX^wDlB!~!YE)!YoLUG(PML{!cx+6&_hmLICwJ(CJ(4d@6Pm13|?ZbvTFZg(am(ot~24h@hTs3 zjCg=^FT}(FR zAq&}=a)r#}#`+?06dbL3PpIg|os}?Cvo4Im-(Z{^>KHnGk;7GB-hYrxoMMthd3L58 z5a-kAr63TzXT=&j>|}~AK^mA%C+bg;>65%46|J1zb5Y0t@)8SH6de1Qz##;b@XO0|fyLU0-$-@VLFV^pQ z!&5KexhwbU=aH{_>d*m|e@Y|a=_8lv|Gxgo7xBVX`|G>U&+=lvPz`Y4f2Np_^I)OL zqTPr2)ncb+40PRu7w^LFeRkjzazsFKDA#&_r_(8bni5{UFTELPn+~)QgAC>pN10%4 z__G{zC1a;JWN>u8O09(dpm3z_vs{(KYVK*1Azvwzz%OZ;9p2@UQK z=wD6RZqox}*5WBJy(u}Vok^RNYAG^CppgzE0zdrvNo*ga3+THO~Ri-;jA-z1&6Cxq;L#}{?9MB~}Xcsl$H_vThuAj?? zDurs|eJ*-`1%0fI4qgNDkedT^iU~0#EEWr!bU1{vo^(t{)K!tQ~koA5T2E6abLZ={*=6;~_mtYdHqw1@Sk*6ZFsDWW%GrCJoMtoSMq^x?0o2HNq-eFU zspwdrU@3$| zgdcjX9&kRtZztySg__8UH>hU|CM6}Fxcl$Ym4!U!VJnButhq@FHBZhz{>mdbcy7M_k&5LT%A7UhgYVa6>Q; zP&H;d`b-RUV|5Fu4@J*8TY%!=G}RG}el`RyF1d)y!vIQ&15pz;PbWCPwvNSOP_400 zumtBw>P@Ph(2{+JgZO}F?^!Md8*@uFE<>-^z(%>jdE45}$vWu#V&{yWuWL$@M-z2} z$OB);n5;Wq>iZdEr)u*F!xJLYmI7n2=kqyd^wbWa7TQ!$`i#q;eFXsU=#5udjzlh& zkD`*qh>eZ8>2>+u_x*r*3QGHnLSPcz{Oc#1L#Qr~&&3VFDQg~`U0khmKr1&`n}2foMbXKmzTG9{~pQK#MPLWF*? zz@qPKV!3<3yGc##o=&HjPNz!9>W2Y~exZhE!24Kyn4NhoEYvjsLn}M0a+GL#`Cc*@ zP#Z_?z|`W>O`;>FQ+by??F>#aFrH?#Bu)c~6RQ2sChl;PzbcXCgrh5&3oX={1E4 zj62#nx6-1Z0k(vpy7o1w+P}AlPM=pyGTdh=yxuBogUI3u09<``&4m-&K~FHn0*Q&S z2G1s;8a2&8Zu)?91uA@yF3w|CC%Z`v>(w{sP{2(Fp!v9}q|99t_3ng*94XCOX}mQO zNtOdz{Dzt6CzGzZmn|K!=1I&fT-j1k%7Jqrv?-lG`h+0BBfp7#%{=0=XTG;<6MZ6~+UUcdV-go~K zc;?Fec;dP%Fhjcz%6*U~lr(=O#5sh3S(k9j<3|Ai58iThJwW8Fb;gvl%|ZY+Ha2kX zT(3Z#Fd{r=N4pe%ll&&I(gv{r6tF=lDi(Mb-LLyklzu2@}W&}V0) zZjn1ylr^~F;4(&<&A1)-D%il|cQsGKy65sz2nptIKmHs_0RGP#u0T7AFx;z1vhrvb zEv$FE`{WtyUJQ6)(+rPqSp_YICa=bf@<5^7PSgVM(&`LH&Trt(lV@=6-W@ifiV=67 zJgtA_#T#=S!FyvY031GD&2h7mam&dwxaH&-{LxkW@t>~0ye?t`>4GIX&6J22)WUub zY8Li!h}_bquOW;aET_I3Lc4ugq2cCkj%|o0w<9LQI`;jbL83~o(E^SdX`A{W=2gzN zY10ZLbWJWfU-XzwEx3{#UOTG~qv!#%7AdK2)Q*DZk(tzF3-bs*7%*3g5T!_kQSOeS ztBZ!ANidn_M-4sLdQ+uoycp!XsL91EGfY_0CuV(-N)!eyOeP(=5D>C6frfxRuU8}Q zvCH=2#;0G#d%yKv>^pH9IYk`5XeS=J`4Aqy=@9z9c8q4zDG-2@dv@UB*H7Zgr(VPp zw;Way)MCiE<>{C7-tTz(oI}I5RPw}!Q7Pa~@%Oy?nV0dM+m7g@g-XGZXI?RQ!0B@h z?()R0ZP@?DTR3v`6+C{+VKv(lfWz+VcD#L7B>-|TNr@$sy7>bsb(}&TbxoWv7K#Th z4q~Cfj3H`wO*(8tKUCQX*Hw$Y*Wa7XW?WQceeS8})bVJO0|_-YeY3$=CftejA*E6{ zSMWyEe4r4bj#_FEX|Pmo$#P;j2!WJ7)E;_*qs7rESGz?r`@AtbJ zu=!dJJ0edb7liDQ(W)kJ)2`T{z+KVDQyQCq+uElRH#EaFR!lP@cDJT^Ub&MrF}cvLe&-%mdU;8G3YMm>cOeP-W@WU2JxvGoxO z43N>#Nz{A~zwR}JHzie-s$$_rbN4eGr}EVCa5U^fw93%og01UR%tuE^M%-f2qZ3}a zykr*)@*E|r7S@ZB&rsomMNkA`8;&$4ACYhKKy;X;c>8gWOn5TX*u zx>9WiN(gB-KKEf$LT_t4DngcHt$!_W27LUbMehedVxYTC4gz7lv$ z3*4bY<^jTl@9BJAvqNUniTjaT7gub;#Rzj!}#E_n9HWe5NcKl3tv_{$IIb32>& zDw7ZolgL22R4E{R-=iM}Jbv2|T>QoR@xed69|Z-^Uvnj50IvGp3;5u@-$dc&<;uKo zfFqCGd^Pre`P=x&pH(l>(QB$!`N-2R;lqFSZDF41XK8X%P!AcIL&qdMw;y1^Z`?5~ zbq)=1<0B6lL#%5AZ88#;EZFnKqD~VzJkM_&8yg$--tzl13`0%OjZVmpS&n=D{2CT~c$H01I(RWg^nLHVEo}g1 zLpb!fc<0&lO)wf~zqm$Ka1a*D$cY+o8yqc(oXp2JQL^HltDM$yq0n^HrE%3r2qn|V z5lP$4(2=e@8X44hUzHB!f^L0Wf%GRQ`sCzLr*P6y%UzS`Kl{3|=x0PjV zA2@LupM2#_y*?`-+Qj1doBv>gZm z?>hb#e*Vdq^nG3(vLkj`23sXF<_2AU@5Q@t_~(-5`qW|8b3&2V8PI5E&3(1Mh^QTky7}PYXDP0BiR~;qRqXm&t0Q;tOpb~trQ7_ zW}oo%P$Z}_RggV0j52~$&OexmJhS|MWj3pHTUC}2=JPp|6q8Oeq6Qup3!*F*?I6MH z!RLALK`KUA5ON^(&rvLD7YHGsi%uFCtW~X(MQ(gpGcY#quVAoa@`S}YMVd@%o_$hq&OW#5v!ZTML07AgEN1ww7zw|BL^Ja@)_XAl&pTBZH9=!7g zynOk^=(~vBZ=S}xzxF6@`0n%gf%~7p^Os+YXRh3@`;P>#OJh!;F9Jz|mkINI9I{FI zql=`F32v7cwzGjK7DYX8rM8JP&!iL;gN3Ez>6vf*g0R|&bQ8@ z55O08Z__ZshB~2AKa)#TT2}p@f3$BGZa;k~TRW zgOiRo6+`+8oi9=w>}124;KJPaARf76Ljw0O<8lCrHfcY@&HEgC-PnLBa;!(SFf}-8R2t z<82wi60>Vls-1NTBAu~mfE2nV7a)el_o53CRim!xh{279z%r*i^cD_Q2!y)WhFs-j z-DJXau=*^>M);m@d?`=mdzSN|zIxY zHDQ}l7_6^vsNR3b125%)r9)uj}sWvV;^?6h&s{;&>Bj5yZnv0vylI6UFXgO^{4Gd_t_CBzUM&X#^ z1#Kq#A+%wUzKJ&q@{_AwIFHKf5?YV|ISJ{~i``1PM&z{6OsQOQa6p?m(I^YhNR~8T zrI~bAKS7GYO{iic|DqcLBWrVB+fIqzAVtnF-*WEP2P|FCU`hGDd69}K#zZ3zF!+gs%*v|OsBN6hTCa10H`xvsYp!`l}@&r9A8VS^TG_%G~_&ADJ> zzQB|wSeZ^BRcFa{-C8Ub`Xmo3VGFh{lq&I8`78@^qGY%wfGw?6^429xrybW0z0vO6 zbkn6pu)ircS$aw+g_la%yDNLoj&p1Hz+XOuH}-7D*Y3DpCAq%->-)hq#Ot+L^gV+o zYAvzl>>3UqJ%%9$JaqjP%`|VZ7#NOJKSbxC0HO@&x(*NAah>j?KRw#F0N@+%yA|*L zt4BZ~VC$C6{2A(0{&)ZDkLurDxX>L$8AtX(+BtAE{x3`+~HqqRh$&(*o1$BvBLVor2X4p1H(sgIxX0dc1Suu_#OJ?`cRukP z9(d<<&FB98Py7&WfAksL_V{zS==GC`rQpqdyYS8T+=AoVH{reaKY@+anUdTp=%E@d zRhG!Kn%OKM%x1Xv=YImv-~TAC`}TKn(eYDAnefKGow)DaH{#UpZMggEk70dv%JeZ_ zh`SDd@QEM7tq(tiTOWHCd*66VzwVnqa0^cE+=}S!g&^_^Y_wT_=vnf9H>It0f zl56@^k7kkpxIjn0a9wVA1~27v$`L{HtK?4#y?roV z`4&E@}W336jnn~o@YisLFZL9GJ z{h}&3LX7CVxl?FclpR8_m=^$}P{hV#<2q6%b|yU$R%ve-$vMnVp;}An8jaAlx=~6x zy8;XRzDUiOIJ!(6PuCHqz38WdBgE-&UhseP{R1#XI(5g1s^k6V4?g{U|LnbgUJprs z?Y%c!CrC|@^#}R*n^l{9kDw~uORMHgp~op*h#c`WswCr{y*qHv-ksWA>{yERbJM1q$H!L!G_*sW-^D+_ycre>KA?%tjYhLt{Yb#tPAdcCh5u>HLaDS86@Tc&zGR%St2AG z4Ig{j$$ipTMmLkU$#96FktE8`A1vD20e)9RT=<`t7}JP$2eckZU#PSb+Lkbi z2HbA}hhXSIL1@4SG79%ZG!I%ZG8?&xLb;%lL7)u*z-zM!wzEv_zFk|JqB}&weY>^; zcm)U7Hr#>G4gmLFx)=8zxCs1e>7?^V7$g0{=G9t^^Rpubu1pStQthm1de7dS`0Sn? z4M8;o;3tn)g4EH~sWp$>0sS+(x8pN=wwok|5V%sS{#7Y&1t(2VNQ@{*CdjpG{=)()6H!#(zbD>4vbTVm&CC%(aw^$s}>H zJkfyP$Yjx+2R7LU#l4qY_#nnp53;?!=HKMn4CF>&8H7q(!`L_a9;-YJ($H>hJj&il zf}DmN9I1&KkuHcxQ;W*|t1n7Cw;=}gI)Q+NKzv-|(myNYi*u&5CZFf%_A6-y9%iu4 zFZ|BE-*uLwegvv<`b1tFbo6M*XL@~2Y|P?u2xy< z#=Ocib6Gm<%HH7DH;G-4byd`2MQhh!h^B0vg<5Gh!EGr1R%!;MGVsj#2QL|MP_Uz&TPwA*JRt!B8-=kAv{E1Rhyj0es+nw~QbNHtzf{O{6u(cu~)UzynGt zxb^gTTsH47+~Sgx#oXsY#T*Xs zVm8a2n#Wv8V{WD&x@xirtO zKe#K7mw$gUtt7KWUrnOmVl2ki;0f+BOQLcqR+KrOhQ4z`a0@J>=$Hy42Z5y8=;A`s ziXMFm=VSfKFaL~A?&L5BD(KcKiuIL?cHj~={N|xt9jv~cf$JLb;_1LVhud5y!h_09_Itlm0$p)h=zJXFOH~>o5btok(ZaRQv zG?J~v(h8A8&;<^67y5V0kqV90Te^ROEH{8mXp+xGDr>$9CnJlY=A02}<`%g^NhzR0 zUxME!sim)xp>WX1;@a~Yyzj6dPe^u%O~gSzl6R4URLp=bijWVmk@=zB+th>LNm!P(hbD#I zH2v0)m85$%h>%pGg3naE-k!bpDTRS`a(Ri-~Qn!?2f01_=8z%@pFE}FcX$u$E@ zE;XcEnt?IapkZzz4Y?M?F;&7`ax^vZ6=@K8E|^Za8JKfz)G&$E8_`=(Ludj!wGl6& z$qb7q5{sac*Pzs}KxpLW>St;u#P<8r{74L75tT@kh7sB|OZT(?!e9MjKw7cAHpPS? z47lppo7i*u9Nyltif69ek7-PfESTIo%kdT5oDD3;RGfOLq3q-`%}Oqup95U=jmH20 zFC96^A?@NtHb2&EHnn|^2-_GswXr%wH|Y>#Y1VEDO_#%ohTRqz6|iI%Rp2L|#S!d6 zLyBzcL3`7q^8i^haDl~QfvsD&)X0ji!=mre2{+tpt)&ocaI{`DLl+utqgfc^CA&>Qt~Dfo-8JPH7K-`zK=A)jIZ_0$|%ew3#-f3j!0$vlYK z7qjVhisY_Exq4J!2Ii?R(ueDavP}^73#X?I2*#Tzs+VLKgj5om@wvX#Qj`#ukgoa?xuTJw(H1^e zjK(9TEYTJRK;%BJdsFyrQjpT=dcyovdw!y`9e1tLRg z=bW*zzM=OyyAJ;?4?ly0$LiNTcFQ4_)YM5~ib=DEWb!c#LzM&a(5B~3o2TCC%32C? z2@2GRp{@^$#iIISxI;CWOjz<-G)D&`*;lS7nM_Vs%1xY4KJx z6Y82falxH^$xTC>QbaBp!%+XfJd{R_AyEh92vOpNmitwqG^7+T4M0_rXK@oxukztJ zt%HY5rjvS|1_`DNng?cknANkA;bK!8Xl@;i)Chj!Xmw8ghPt=%Gx~S_)=wyqAUG*( ziV^?xUws+?@N2*N$@+IKHYyp9Z42NA(QO>i`R(hktSS?30@e4I8*f7aI%rU8$6l`a ze8IUe9fxE_qfCnJU>I=21K-2`7hlI>(&54DufUnpXY?7#IchGJ>oGltezOK&$TNC8_)V)zK>V85LUB0HQeNz7c75tI0(#@+d zUfQQNJG`{lEK0Jem)W%YNkgZRm#s+NiaY#Rc$|5Ed@6ULXxShxGb0!42Iir5)}&Lh zITyVD)L9e&pWU^MwTu=qfkI)qZTO%&_y+8Qk>XleqK#DtY^h z58Z)b>lUm`r&R{Vo|2#WSAU3a-f=yS9^8lXlMdTYox$yo9mU-&Py6x*---3jtH3bm zVjn_4hdR~jCY_t85@Vl}BEhArs==y&$^u9ie>mAj-8^c}P14OZrHTPZN=UkHW$mIR z_gu-rQM$Rgl%)xZ6f`RihZLyKcbX ze6qj!#Pj(5eLL~M)=fAYBQ9B=LK@9y1>2exd& z*%WbLG2q8foxvx0PyCk$_TcT55M|$XCrI6gfF>tM=yP?_ob0(O^1c<76bp^a%QkJ= z2bVEq-(T?KB&p>xv2o9uPUdV|HYf(*ECKaH@v- z{Zfobp<{_OFt9hUVv9TEKC6Fe$Qcvr&`lBoI`x;xr->mVhnB7?HiMe-&Ju3M&>(QWq5)Eublxv<*s*3yNp1v3jwAjrb|7 zZwAVmDbLk(eU2NRei;S8x30gUnf@tRkn0EWO%HvK|KWf7EdapZ|9gMK)gFYO`>oI5 z+jrfFmk(Wv_1Og5PoBoD4?m4N?t6^)(K~Q55W+B^V`A#h{_Fn-58rwi$FAIu^Sibo zZY;3>jZ?VmYmef(r(dpn_8r&h)PFWx(PrTK`UY|~s+vGB6b&yEOKva=#2|7uWGMpR zvX}ya-uQ;AoIx7-snqygZL&7az^+4AM##>kfHsRga@{mqBB9Y}L|({moIyJ<-Z-t# zvC|v-)NKF#At!VFp`sft77HLsW}qfU(4{VFS7n^E4FHtI=pER2n;U-v4aNCP;Ie@F zhOkkk!emA$8vAvE%M!Ay`NJpP#tIR>wRIK8CQ0Qb9*auOi({v3Hz|=xSs>i9wt-t- zczxM31mL$X*@gdi?@ra3vltsUpIgVxocO#Xs{`=chxX%oDm$HkuZc5)pV1kcW(o`Mmx) zmiztANAJYn`h&m3_O%WC+?T$+^gMm*nuGY}b(bUYX3=%^9l!k56S(}IuU+uD{mKvC zhHu?=1SHAYyjafXi$>o*o6T6O+hJuj;?kFomX$Dy` zLQ_SCR%E6GmnvaTvUFH>8HYhJoi%Tu$9%D1{W#R8q*C5eFc;{E0|gYCAP>EhGdQd# z2O1V4Os6w!UY)6zY0my3^|H8}6M}U^{Z!Vl{jDUS8C z33;)Owl#4=Go=~BQUV!J!jS7&q93-@GGbEPXe<;Qwwf^V@xUf$jfaQ-Y$#1IWnj*6 z6gjhC=|gbA+y464WJ7S?;)@Ij_y^Y>#J_y>DE9ONe$C}T$*(W$*^Ya5ZL1A4*DSp8 z>>6%-a_xfe(7(U*BK+~*T}WIIOT(y?HuJ1b4lVoVrgQ7K=>q#y0q}43?!+JN+Uk6s z_N>%BapQtt_ir!Wg+JP}Lkr&=3d*9OBqOHDq|}~aD0IL#BkN(J9&R*UJ$tEK(r3)1 zSZK(gl-KFH=8wuMa~5`s{X^)`B3IDe+HK z32K${i+trx=m7I|(x7!_>{j6HO+Mhrokgvs6$u21CNN;5EqfNnaeQ~11GQx7>K^gT9h zTGiaVZWyq!F~_aneF4*4@bqPSadO)xgu$j;O~z5EO^2Z$?7$`mhY&#h0wtIK-#zcI ze(*LtaQiiw#E30hHeoiKVHk$*`!!Pkeffj$!mEcaMVBI0R-_qNJz6y$U|pNGl%=6+ z>sL$(fhUp;3Oq$jLO@C;OO<+E4l?3_ZEO#vG!42srOGxH>IY1w6Qu1sw*0!#IhwGw zu|`@$HqF}rmqpMXh%Eeb*)WF&$vHkS`3=d-v7{JIA-Y3OaN2Bg3jj4#joEang>oS@ zbPaN}8YzI1ER}vjA2U2F&QC7nznY<*W`XUxbwToTCBvoT2Q9azOtjts&8iHtj zi^_wP7U+IXLFfkFd1T}+a&F1pkRaJoybNHe!&Z->8LDh@qt~0a#g?RZkGv zv??){I%tP0sIGs!(Kba~v1>e;RQgMu0@UC}F-zuBkcXP6JPa9YvnjrH?Lnj=W6Rnc zlVQMo(&71iyYRU?ug9O>e#E9##fr(Jm+wQj7_fO`j+6_|ZeGRHhc3lEAG-_Rz4dUF zedW@;cd}u9kUPF#|G+yr=cjIrM-T2pT=ZByzk!$w&TU!6(}yp`Js-UbkKc62(ZK2? zB!qzZe2%9M>_MFOSY6vd${A<3Y{D~FAHbjd$lZA2=Bpe1eN5Gd)y0ZXoy}&NSx|~~ z=`~M?*UO6d4vJ4kX#F9Q^%FT9Po{QLUe6+j(s>Cb*ofINtp`pL?2GeeN-u{GXR5Ap zx*jDL&BRctXQ_pgc9iiyCG3()!P&0E7xrw! zq!4!W16B%QEk%51>n8l>r5E8p9=OQCRIJtcz_!hpm4Y38#)JqbCmrtFu?7G5s!Q;t zi?(Zn$ufkXQrDknAK!0Zvb%XcAKbnf)10xr&vkF>627{1GyeXiyYcy*TSu`K)=c`= zmeu-MazQ6ww{0{2;laK5(_PydIimWlE|kdx7uM=-YA#lA4{n<754s*_UPk&ypJiut z2^vbD+`}Xiwb5rOG_K#Efz!2NXC9ImqY71{YrM+)ssMJGjJoNP=1QfYdzttpJEo&4 zkf0d-Fvc3XO;kUVp{)KH2rjd$7VHM15ouK^1s{9hsS268<2sXz^*wT~)2n_M@KaxY0Nd6! z@F#a(k5_kY)k#QpB*z$pp;(O`OOJR~yB%J^+kqS<35L`iE9tW4D=yDSpUumPAMhK1l(++;2VXlL< z?B1g)qe?WAh8Eb;+zaF z&crCi^tp3uN)?pmz{+f*vLrb`TX-F`5REZlHsj>oV$g%ZNy=n_l`rhvA}pPw;0&j! zOHP7T(VmON0vj6(3;v_xXiCs-kcUaYX=SBjI-AY7YcoU61?Sh+RWsgk(G9-VE3+v! z=5t$^eW0Z4WTCAMbb%97r1$^C27?(}46;t?44b=YbrsupY-6%akHx$)@d<>L*^IUR zgLaX`ce65^VK$p`H);(V^M&Quxc8<`HApvR+1RJkYHSprOHH4i|03ZNKL_t)C ze1DVkp(*-2!d0%DnD71JPaB{f)L>!_l{$L#b>iux6!Li}>}P0wvmt~F$OJ=MZ;Ymd zRbHwmjRurmo~5$|A+jg7fV z*+f1j6L*=iNIuMbu|U5Vv>7Ug1%*7Q6~RFh99$}-=tAbrqY=1^64kd+*h^B^{*8@! zmE;ANs}~Jo5+W4eU-u*zLa8-P$;S{Drk*LTk4sL6sO zHA#pTs2Nkz8aJ{>sFb2jB_WjQG>d&VyLRs2eZ9Uz8yg!{en+J$HWod41_dDi)5#Ru zcWkTSrd@{+BG%W}aOTX}s_t<2LoE~BP}Kt>5zDL@l)(3XF<)RY4ElNw!(i{7s{y33 zTb$f7j&S=j;Xw!{QS%pkOilCV`*G*V9}Z03FitSUGUZD)g&3CqzhsLF0vCw&jnKRn z(G;svEtoNiG-bOM;U1AGQ<_M%D;k@;7Sf-+khjXgQsU84i@ZfPm(mc!NQk>a9K?iJq9VsL`!=M55;@0b${SaeisYJ$ zQ|kR%EUF}LI-Q`KB{iv^Kfk61@CJ$P`x!3R#OFgqR|wUjD?#=g;=CULQb-|?k`a>D z*4Np?U_>F?lBwY3w~VG%Ps7q3;Jh%m!};mfS1y zJ{Oi}a%Z(l5(*amz_cg3Ps1?a%$c)@sUEN^Vm71a=THtf2rahRa#>;{v9czQO|u)k zGRt@5WLux1n&;uAXb6&JA_vttYSPvFmB~-_p#_XJnH39Kpkhjp6a!XfQ><^yHRHzC8)@n_vsWb zXUykT=wo4%dG$k$A_)3^!09t*)f3eBLnV>*eSN-G1kjZ2;1_^%=gwm`onmEm1`uJL z8=f`8DR5}KSqrETGG#=H+EAQKI*#w?_^@7UzYT^Z=m;l}sv8y@NszjZgX67%ATOZE zCB^Sqh>*5!-Sq3;Kou@PuJoJ2a(8V!oe36(23%l+xB!~QZ+4@GiyQ``(zVdGj7Eq} zkqt?jt?8(%1ZWT-0HNt9lIvWHq{&ZLlo9@|X zRWAu&Tj}T(kMZ^!7XKOB)JbvC^z6y-JD9r_;&>s$b2? z2l-$llatA${{F^%fjngO;m9L6=@O>1DJJ|gATX0(3ddYrhE_{9!idIbY1~zdAK4S7 zUMHYI0ZU=)CuXYKXOyYmJS23^uUFbBb-s+~01%Cc*1gLr8RSJ(4vBL3==;9@hb5D7 zQ~(eap7w~03P|j$@k!BAcw|PhnsXQ`J%lum_}!{Owu4)%sgV-<$*7-Fo5aW@i*o4E zVxf`e($e(4s26NvGDs$4>3bL>9)9#0Ytsa`tTj!v(6on^7kj@m!?L|^>*?Me-ZrEGH3ysgOz2+ z1qVE+`<&#YRllK4u4LjW@;mj+Avx4S;Iu-u%@1vWB{L-f>O?+G=>W`v{ql6g?Q4dietZ&TK8@1>MlL}4}R#vJ>zwd{J66yD+X6*=} zi5DSPJQk+_@x)8n%L-L+k?xT~ujS7)pD!@qm}6j?nMv1+2JXtg*QrjAp&$6)2N%2? zo18F_$=lS~%kl%q2^8c!EJcebO_KM%BFYJngEoaFD~nME8N!x21V}Y>t)PmbM zaDn5G6eXcqgd4Q6?;Eqsfb!$1gaLURK<$eDH4)ObkjZxQc9 zyC8e{n$KqO^fx(~_)SPr4h46&RsX#$q~iq4{*(gu~AY2bQ%{a<3m2S%?tvq;Qc(U+zz4 zvtvzd*iPfKzm|6k$4@@i6~I%$jnoF|PM-(G3_rb|-m(0Wm02uqnhz}SCk zA;2Is>wrhHV?_ESp!H{5pwXw#5|#;c)JVk0p0_SF#M7dgG-k3_@PaFD<=^X4V*kI9 zMXi$@#zEh165_p#dN@FvBSbU``hgE2$0$a@-dW$=vn(0+OteV`O+&Gn-q@f({T%h4 zIe1K~*Jw|$nhgWZylS*CF5*IcI>A1k=1-B;G6Ygz;#k($goFkwIz@8rGqT{C3uD^> z`DUPadz5f$1%2BLTwoZAW%BTKk$fSo2?l8f4vjq8SNI}j(q>?Y$a&CeCB&*0khQ0g z8b+JQ$g_~Mcw91uzDlwLkmIH3K^vGA+>V z^3$uV;DF!`G3``R-V>n>O4g7NRa?1#TNkMWw|Iz0)&ORoi$olt*+jiK`Ev1LpG*(b zn#LEh&Nn3(Dx_>JUyz1CAE+E&qB1MChC|Nr$}q!2~LO%fv8{C(KwXM`yeo? zwnLkB({|ge(De(E-J7xmBM6OT?7z+89YaI+(T(11lwNnPT@X$* z*5f0Y$xsPpe4q`1^zMVDE){@S@!gux?lvhX0yB&xu$DbUo?tLU z1CsJSRAZ%vj!FV_QTdrjB1AHv?)09tW9-Xm`tXs$y(&9a@M- zbP3`CC5a|GV9^gtRKd>Y3-M-GL+g^=%WQwI6#r23E5ApK_eKa9_}Na3ewIx^{%k3^ zVr-psrZ!Efk#T~NsFSYd*oeW@`;Op(c^1~Q;6U-<*PZS;Uvu@%(mEIk&sVvK{^e~2{A~bm7 zQDpcrSyVu&iae%Vu}?y#RK+&?T&w}tzy!*LnsQhQNJMkovfM7aFJ(lED@IZ)&Sywv zB;SPMR8;{$SoZD^AqV0RLf5o%O}-JX4JZLQIHYwU^pxH9)Q0O>a5pglDK~OD`TLZ} zHQH_cA*~d0$nKzPUXXZ)!q==hOuKhgB*Zkzk#YgtgwhmvG?EvBD#;0&odhI?-jGt| zMEh*(svGocp$HR7X21oXXyCx_6Fe7%7WH$(M$q{N@8Xl4m=0J7}) zKq$dQN7zG@I;*3GJT#2~X;#WqtZ?9|c=U7%$xYS7xNR!!6kjGJLPqmz3uQZ`R$O;& z{G`-jGMVa{6k`oQU-TIP8RyThA*F;(t1BvBE=1V0X{EwnxM?+CEL0Y&%|PFrc6BvI z)7WY|;20CCG8`|RuRbTP!CbQvqa4CQR6|-*#B4T048UU1JH?3|TB4Krdlr=X=wh_8 zJVwM)RKHKEI!OA=my$UUy{J?%#)yO}OH2{yhaMp$3BpkeiF%U&bg4s6LzR9~c0RIz zv~AnwU-xH+@x!{zhp}L_7UelsHls1bw<)}C?HC#VjLJoAMglFb)m}nUNmH?LsrW?T zrkg=6c?zS)$NzkOGj#R5B0Fu-idy8G48(1o@MbsBetVR0n;QgodJhhFss}PJV{!*D z=?n?Mr$KnTuH&-QFf`BzkAe-pX!gcbMlZ)0-3Xps>NA=S6``GU$q8LL^eRb`3=JuG zo#ZWs(3&;Lqi)G$k|2j)16)>_*lBq7hyb%_fURzur94t`#X@ z2073LCl{pBULyf1L=KSjBpco2A@Vvl5O&F#GrbwwK4cnsU1VxNrKnWP7qp_!uj$4` z&)Z@I9frXI+e*=(KiT-J-kUdVmeY~LDErZSBP$r`lfAr(ToI^LF_#%Ml)7k2GIwB1 zwqQpSkI0K}8c|0P6}C_1OjO*vYl;7>60$hx%`%!&0ykHTTsw-j?UcVI)aIV|2Cp zWLdW54=qiAHZE*_U-}h7a|m?9swT6oX_$ra@Z0=*HaW7Ul1b27S+i!mIrxh=!?r}t zHZ5L*nB5+e64UR<8VBD`TGUd`*KEq&igBZr?J#dXG^51hQ8{L3N0#t3*<7k@dO(U!zXq- zd4UFL$>9WM)UHjkpq)7h%nCdK385OhT_TWmnaH^;g{I-CCf4n2^AkpEt4n)sHKifK zCJRI;C=N$!y7%Zd*XTyo(&5oSG8isey0EoKV`HI5cA_|WRNx5?hpEEw$@i=A&UaW2g&f(dkB|(!|;_St1M7@9RiA z?p|7lx=I@Rq3U;qMnY7ozei+Legs_{L62m56%|J=L6D*aUMheioCK$ShAt&nKmc7A zv1QXH&P!nfryQDUOUV@p0bQ!2_LKs;Nm952$+(*fd4z!AHm^Knl+gOSypO~5@1c1& zyf(Zz*;`D}tr?MXUZNg&ZBj$1113p%2OlmIQtE1ljr}@B4;B{K3j+Ew)DBZ>HNJ9q z(+mKz?)pR~7-GDYLt_YyCS5hp92zR$8}87j`e-%MMr}W8VN2HJk!K;XsTh<1bm|N9 z)XMt))jyYq3>k-8Xr`A`7KiV28!jrDO;YSr3eBb(!g8FznEpsh`D$2(3wV72nZ!7# zk052HK@ z0`Ywgjb9LK=BHdh#S=&EI)u@LUBN-HDU$9L!3yBo`4)`$a_W119*Vx7mJ2@;|iE3ZO>*?&|DQ(fTyvBVL()c{Gzv6;Q%j{*1{++SR6*8>i*Jk<4|vit&n|M|&VDtpb3m`qC1XG? zZsO1Dc2enA-$=uubrGD0BXXe+YY>hIv*g}ek#g5HE?aPYVIYO0hUFn+;Qc~AmoxzL zkkQk?wU0@KrJ-ALcCvJGq0J^M^W~zKe9PWgN^I6!s|lpGsE2?o*O_z6Vyw94z-a&I zQ1euXAtXry!pE{k1Dw>!q9Ct{pJS3{Mxe&$Rih1(QY>>{4~Si78BW@WR)v(SdmTQ# zxSFF|!l2+n9O7UvS~H1hQgSxa`>N+j9+!AtlS=*Be5kirIX>dNT;tojd!Nw#{a0l!*fLe>n zWml?6%o^`1wd#i8kWbL1c@v29@QCU72{hV@~?uWJ+ zC}d`t-bBu`EUvcF;A+XVf&AH`&Bw;#kZTPPBN`x!Kz4*E*qNET_0;$*6d$rUTE>_7 z{CYFs`2Ox-qo?N(^i}ff9A&ZwM*y#?-p8;X<;6k?_IO z?Sek^RduWMsAxF~f%T<6RXBBtb+y2v&$>v~(>E!fUcbiSv3-V%HLMzUd~c#5eW zoHvF!N~v9$h^SpM5=tAW!PEL~g-r3_%+5pZRW>A&EN|xTIbB#5xj_)#ydVy|sF!SQ z-lgY$}dnqb~P2Sv`bE6xVP&>I7(M>h|WI_s|h)093d$GmL8@qEJd5i)#L?WS(3sh9)L|K-q(}?`(4?32VbnN|NNlP^)mP)mpYEN}CTf(1Bbq3TI(0B`#4d2>sfZTgjR_awUH%eH^UcY|MdcdoDq%{M!u302P=W?KWu1^d5R}+s=G*3{omsml?;ptxHMs6LghsfSF z;G+6HHO!NWey&mqQm{-w5YUB@r)9)kcHQ<1_~gl`E@5mErT>qzck8hvNzTMR^N2W^ zS=Dppki*N6oCQ}4L4W`~2!aIY|GzEvP0%icUG3~@IUKU5FIAO!PDHqy9^B2`%-kbu zwuxbPRc4-ytGn4}-^J6}x=ud1mz5m7s*BO3*pp_M$s#JP*j0C$RP$7%xhgP4A^XL_ z+E16(=~AB(X*Xz^7whmf+hCm8fuUR2Mo@G+AmdyVo#VJ8 zjnc;?%h7N5v6GP{PbNXTL216seXi-eeTpZ|k7^Fu!c^@c&^ z*pmx2ZbYPSZO*HpuvA(H1B|RFlBPRPT)q;>1uymxRkVD7 zrm@k*4sD}8ku&t~>Y^yf1#lWKSw(ix9nA_Vg$bq!KF?FpH0M6Uz&$^3Zxl40OiDhA zAZu*{+IQg5Jm^IvdOQy7XU4XPYmFd;mHzbhw&OT*rD37l6i0_A(SnH;w{5QFdL`4C zblp!;Jz35@!-`Z;>QP2P;s%RZNTZSz7^xG-r8R!u@k(iwM93v$S(l0&w&`IpwA8g( zmlp1{7HbpQbqX#2U?G5$qFaLK3NO4gcOOTOGTIiQI@qFL%n+6qey3|eB4?sdxHQT^ zbt2-^SUj__ja8jQ&pwc5T7H)ln;l_po1GLqX8jiWs?u6p$egppH`yHneQn4r7#(S> z=(-~D`kH^4iZ^t|_dNDTI6lr9U``|vq`*~X99b)fV%3+KUBehDVl z>?dPZ|J9QTJSAH#(t~MH*GGoX(Guu+vOckAVo$<8nwCq2( z+h&ZUQZt_D>$^-sg*KQHVU12J)>3fZ*zo&H+a(f(MD%2kq9D%f8)Pf!sJ|3(b1GJZ4j?i0#Rl37c{^sa z!3ZrcrLL2ySw6XIHH_F(`Phyt*v6menQswewAWlHPguA+t>tEk*t7{`nxou`@lvQ+ zKtk;=h1bgLX?}uG1h?iq+GyDHVySYlkcqL?$%WyutJT0D?e$zhx3q zdCRh)mWFsq?oVoVxAH8kDb?(g*1)anqR8I1t<9paT3*VeXg^Nm^VIU7h-Sv5VHY!h zE+uQgo-7pB@l7%fa*?TB0Wvh}hK+_w!2mm1($wUx^*Bz(r_XPAJPzFyi*RX60w>mI zj;MzAWv)K@d0Vix6lE(+?qP9BCl70z6pFR!ku$LO!azgfs9OyS^@VfkLR7JIZcTzm z1g-X?v|zT5R4!>Tlr%3!6`HABn{BNd3nfD0+E|EAj3{B-ZrGZA=#M{s#$(^{;pG`i zO7*^%zLBbHSOQYvmVvV%pJ!zWEejT6%>d7i@ltMul>V_PF8NfVqBPEyTMb6j< zJ&ZHtz!71pS@INd4l|uDx?i|Y?^F+~8YP*Wkkf()2m@nbUQFIvX@RO%XQakYMjL9~ zD&-n=twyIM77o{~ts9G_-OBB4Zdhox_`3cZKjlT;z>=e%GFe)9b5vt8kr>8Z+%Z;! zrrSb?gPWE3WLG^T8#*@}7${D1LbDYbX^FXS3};L+SfHck$5ah1T+(~J9#!Y-!DK(h zwxFebo;55Reh*chrD=K_;n+=G6OsY_Dv(6ry4LITi?KBtD<|(xD9upSYc{in)?5l0 zn2EJfF3dRh>>5m%;BmQ+=eajcVQTvi15~sXC_Afdp+l*@J<7FKC+X_WM@n58mUD)005pwn$_F3`Hk`+Vns2j=k}6pPx2e`1a#a z&b*+%Rx2U}%eu6ttAQO$5^X@~7V4=@>)NyTcq3ID*N3|Owm``@p-nBjV-Fmc9F;{EX+*N!kVs2dh45I`^x9aZCw%115Nr*M0 z7$Xdf)~FRG)|a5K1CxpP;P4f_LX9r8aG?B7m|;#hJsMtHN<(+AGJq2Y39K=Ep+Gr~ zE_2p3l1xEs(f=48%SjAT`a0^sK-mvUFB&>9XEN%N>B2I=RE(a$Pjju)UN=!NEt(1X zmAzP~)6kGuAT?(?p{U99U;1ou6ZuCOW|Wj%CRIUg+$!7Qz>mzh?HdR!$A=9~ukHDw zLq=Ph&og6NGq&4J!Jle2QZ*Ki;<}`Ey`TmNlBZT3OS3T!=!PtXi-t(sAlBMwFFIke z(FK$U=gDo-zc}*|m3`>**W*eAln{o>x~`gWgl2G1nGf~4YpD6M;Kv_7;W!FjKD=O| zg#9>B(BltK80)sEtC~!(az5K+X=(gQDAiu$CK~lmer9!1SVlMDtS*BcrTdzh(4@UxLM@h}s<5w*t=_8qx?x&8@QSo zFlsoeEdG7sQ-eNBt{Dh9XFNYO_qyZICURMq>iEa(tjO19`z+l2(@-y6P7CZb*B9VD zm=4HC*O;x#(h+wJGAzbbt_x(9!oggNGZYtonsdRD*5>w?bP5Cj%eD>gAjYWr(v&`raOliwes3e^5So(A`6Krf`L2s{~Q9L?u4 z4w~fLc6t~y2HRl-N>?&dE1~O|yqZSiAwyAh09T1YeIfJC8u7^VqfLW4C%8AIK6{Kk z-3r|lr)whmxyfF~U?h`$LMG+Bvp9;LqXJa2r>RbDag!2l#!O%&q3Zr*ebYP-lV@gMrJc=d4Yx z<&dk(ahFJd8?{veJd>yTw@R?-K~vQlH*k$o0!q~uJw4rka=O6sM9uuDY0qli-2pl@ zJMV4VTBBC?%BQENMl-bTdZY$Fa@}Rhlh10`y;7i(v7=&n%9(iwjiA>Ae1;;vu~b08 z3e;u?^e{S$=vjoqrqP>mv@YBoZeioyF5#UVXkyNKR1lG+XFRAyraf8X24_RzU^tc5 zab~cZ@p?;u>Vg;3wR7$U3NR`6xm1_0uBD;ipi}yFOXTdMw+(Pd`54x4-=>_x-CGw@N|GT1{H%Xl~R;Jss z;w+^(HnAcWZ~37U4zWF~6vMUW)o>lz%Vv~wpDtO>aY@yk2E>ks+=Z;v0~!NztiJMO zEH}?mZJo1Z2XwSX-0);$shI)L_v~!0M@tiL>;0sH`(wwy{dfN!KYo7T@#tRu>$>3O z;|>4o|MEZJum0i}&U7SEFOJSrs21cv5tzcZ7|ld(p7_hM)PS^dU@;q20;v#Q>~EKp zTxhPCmH5vtEgZBqL<=v-=Nn#HKpQ|f_5<5(!^`tC0O0Yc^aCllj@ zb@Ke=(kgTW#N}uQ1f^jDr62RHw^B6ue z25rjP5`@WYzc(}n78tWOyV2FnqD(Y|wuy@yD-T>FXOfxTi+h>1pv9n@H(5GHFXUX@ zpaOquG{aPX4iBWc18|PlN>^;N4YqPV++DQ$%`_%#=g-V5lY;`XxwcE@pQP4RrYHQh}u ze3J?Gwv7Z5ndhj}@s=fFZGcGKt2%8IZ5krLTMxVpE@7oJQ*x;WFce=TxyP-Th5@Y? zy~O@`*K0>Tuf{g!TslL5guZXx55=;#u@G`L*34mIQc6||bUt&Pw3pJrEmE47)ie?j zl4kI9v?7;mfK`A~1A$McDR5C9TCbU$8ZtFQF12x5*Hy1;K8t&f&$iAj0Ls#|9;pI@ z*@9A3!<|cust_>v0pQF9kH?OEuRz+*fA$ShO8EHU$xM)X6DnCT*jA^Z9zY=i%Gm&y z_FT!DlFw7K(X4jPI`FDqxq-=Ye%8`nm#hEIs9!xg!X&!O2UWOLk$W9zX2jSUJz{fB1~I zFZXdeR2bj?_=f-dyMM&5{_N)()FcV_Qv52##ptViJ`M+a#WaWum2Q;FptVUF6iP55 z+s+XK)DgyY>Ad50U8aF}+|q;VG?P(|g0lc?sI0UB7;*7aQy9mU67puK@mRZ?oG&g#+mwj#`+xc)zWwgi6gtrJ&!6x3 ze}DITN3F5VspR(vD!4RiS;YYMkeF9cZmx*qU^L zAq%5q{dAk)(~G)^@cMekx+E;?+A?)cBzjbhO%ttJ`%k+ViTT00F4&sQX2G#7-*XuH*vRzDUVhP?xQXD4hhXB z298eb!m~~D#BQ4DpC1djzTS8I)4%+H&p*DoiRH2qe)`Qbe*1TS=}a%`{!>wMZef>< z3I-evjHzx@tm|X|$Js$L79FcI!zcqVs`Pj6xj~|#S=Xhyw~3{`Ovnrv z_@JXwuM7|;&Dp|6=h?K2uWxt!+kf{T@WZD&9*^9^W!HocAD=21`0HPq`LSm=9oitI z&U~>>hSUQ(QJ?{t8egDIM>0BW(&h%un!Y|5y|@>KgbV>BW}xOg5(=M6ox5#Y-LsDq z>$c+M<+(N{kG(ds?U^`^qk?d4&lWIH{`d6sq_x4>sQml>z`h?k5h^*WGh27gtIzJb zE?Di$PjTaz2{~nvv8q~TCK}S+2Xw7bzYv4pj6Gqq7;pdfY0t$Z%a_7#^KjOL z!GI?sfyE%7-FL}{gQb*OZh?FgI~z>4=ADc{(=$xtHZ~O7X&MY3`t^Bx-SOk6S3Dkj zAG;dPVdva?pHbNqaxUs{f(lA062T$0fdK4##_#{>kKGu-L?zgXflbU+7dEqq%Aw>o z&5A*eF6G?3z_sw~L0JsOzMrl$R}r3>)F}O;A!07zjw{---kxg8@^MxKeiQmk!SUE} zdwxP%686WA^Eew#sZoO3=WI_ml)|{b-CLo#_DRCJU|m;y`TV5{vm0{G%-GfyFCSiN z;_=&C<8gZ%<7Mfi&U&0#H)U~`ktQ-VM;@7ciNlZ3DXgBtIwLM^)Y@Fgjw36Wux)Fzs9staYF(UP zU+?(lCm-;ye*4$><QWeg3w3~2p)*v$D&t!B4 zlKIdVPv(rrqi$qk?OfXX*3-}z99*d)Pq!P^Z8O@UI(>S6ep0@6eZCh*=Mtp->9%2S zL2UW#U#}CL6~}QjtygVISq(5SQ17G&Q}oWdKQ_un{rsd;y9Cscf1{OZ&QB4iz|`}m z&hC7}k})FhC$e*Q#Au{uY;38gbD3a7@28CJ!YB?tscX-a0@ir$*3^azoTih~EQ`#? z?nvc543_kCOfHDaBC`YS;=(4QU$op48(^pVtbk)d2P=(yeW%i3KP^_UopK$lvP)l! ziw$KpT374dRwP+lCr(g0b~25e10Ze0f}v76u?q)ZJmU(=2@d3uCR)xL3I?(|gypj$ z{I&pe6e#k_F4;T2`~DMNzdYQ%6GZ*{AKvhvfA@R*>d$_rK%`J-dag>+^+xtn1p^x` zjZBekGk2^(M9IBrsF%Cj#8*)8RHV^r>H0PAlXSV~x7!xXRXW|&MpIOM2C$@6fw)|9 zHPdPD%4fRcd3|n;a?4obN_nqYKM5$3Yhsu#RP_`KEuC^(a-(L|rs~)qxZe+~Th(?P z$EkE~BGSo6qE6vdO;|LyU=R2u!x*vagci+`e-@$!+=SQYyk%eExjLfBxO?P0o$C8n5@iPa1{VmP>Uh`}pCdxv*7HznC6L=90CIR?1jP z<{WFWU4eHG27=*S-?!Ts%y<2YJ#%;3G!7W0;S3`EH-+sUj6YX?A4z@keD3`Vv^dGb899CJh6GE!RoS4PC#)~ zK2qLf#9E!#Ik?sI#g>CbE?OYfXaE4`aHj8u8NnBmoJ?X!5E7J`Ve}s6Ga-2oZKE|0 zsvKJ3(r6xr21wml;mid;eEN)Uzx{;$IGuH-;|czE{6j>S;#fZGXZ`r;-su3Ac4!(e z@5eu1Jfdyt)%OhoUz#JISKrrJjMvA||M}!D+1+I55CLzmj{!BdE;=r!!euJ4vFwF+ zZfoE32H?l~tcx%!5_qflY%XE#PNcj4Fa_7gu_uqfP_dNUg zZW2%mzk94bK=51qhyUjv@qhep|090$*ME+ur?t^K$xWyPX)08mqzJXxC@tYSW$HAo zmO-;M{gDP0H+QJ6=jp}g!Drhz>OuY9r8Tl2iGxmt9$Y4zH~la7z-EOg@>#Dbhcn9 z!0d(l0`6H9z0pIEC(4cE_(qv6DZu#Roc45v_jN@geXdB0Wp~*2}u`XZS z0W%xG>Gdw1X2-h!CO3_-*(If+yxMD$xlRoTv_=l@UYI;H>v$&(u+8IR>e177(qO4r zVruc_zT=Yt1I0BorD_f$y_o80!qcS1Z2P%0L+P6AfYti*kNw2&|L~m;rUV&q&Ct$U z7Lyd?GEuP4l}rdUoKp0!l2KH;Q2_x)N7sw>$76StB?t7iCecmM$cB{GE3s!_z1_e7 z_Q!#< zmz^3VYh4yRe|SO38OQytQzeZySd31D_EtfdK7F$+lREJ@U0o<3pn!&=x3qids`|`+ zKW#o<1&n$~xKQp&;h~n%e6{v`)#(le`eu6;Gvm7-Uh(+%ztjCjfGj;;X6yt>h5XtmfF&m^PWuKS^#3|V6)%i^%- zDgP6Vbf$vG{%DrwNoi``B&fY#2ZM3qcDrHQR`+`x7}x;7b*-6lat`uVKizKF_g%s2 zwNqZah|p45hMWirPBRpzH8J(spiQ7Das}qW`m$?YQWu)C{hYqwMk50*o=eSE&~IGO z$ZQ1GmBhKuP)yMlREKm^vaU9l1%0@tk}D$CivRrW5BTzW@3}I@32PXIS;vR3G(3Z= zT|g~tW!akt?m=l2x1cECjZF=R-YtG(0nbChJukNzabgvZVeWWj?}2Vw5_$&=pXaSQ zP0>vrA?7ey9FE6bW4|!OcjoHnc(_jpxCC8ZH|EiLeRSQhj!bZYde%T=Mhl%aV8gi- zUYExTjH1l*@Uo5^R!@BZr_@W=0d#9#dRFYw#H`%4fv!D(hirsP;FnngN!1XWi# zL8LVFbY0rwU-X&^-BmO;cG^+6Zc3#bl`~9)GT2>J&H8FW>oOPc*+bISWo?_ou4}iYaOCVm-|ED!+G}s? zio8@xK*_ne%#jM`X(6>&P0jcrmr}z(+wZ82+v);7Ee$PFwrs`?2X29jlj#heiKS+xX0HePq^uZ+@>P#pLPuJb!KPNA~y3dq%{wD*dm%6#hb1h%}^!?|Hy^}A&z&{1Zy#f=v!Nu&}@enXP z105yw+unl+fZF|jsDI4oe)q@E_@e;=BiPq}mw$xSD8SYj|Midfzy9z4g8%b>|DW(T zfBh>wKi}FQ+vF;W!HzZjYQK9wj=GNKuAe~zGPcI5us}uqU(s;dq5;yKUfn}(i_x=Z z5Y_!oC}%b-T)@C>%XoWxsBQSNEI7}z)6rVi4$yQuXKQe1gr_?}W*aln#buft4~+%bWbeKH@2~v)yqG{(;Av=Z+$pzTwr(q4?>q9D@#)7e`0(*iP8crq0;&bJ}672#Xg zWYvd?h;{pCX*8;9T56iSwM}BGO}0gpyOsLZP|=Uy5YFS&&1p>w^16Z=a=k7qZrg^t zxEOK4c>>J4$qZ?QsX@uyRM*4;%o5CIenPMJYK7>0jL+> z`)+_Qc!sx4v}<#4aC+Tmd!VaR1F&u60W`bEZg@;n?KdOV!?VmsUt31atmZ!kQ!F1b zGRit4dqghbk`n&Q|Mv%c`^O*fm%siq{N3OFMb9PTs{N^JGGhU&*+$Mq^_A4ZWitESc5g8UqN6?=jwX&y zs+WlnxOW&EpY7gN($M&@6L#B?x)pd0oN=RJv6j;6*h3}*#+VTl>7W~LnG5jkw?C-; zZaFKTe|t(pacv`7h$i(idwR#1^)Q*BMa-PvS*+Xvz`b z9M?GeoL+g(T9lOhM8o`?Z^~&DLKB54k3ZLG`$aL8oQ8YJpj| zAUr5A?gD=DIGN1F?`Kn#P3s4Ywc5n2@UmgD*W%NsJI<#SA73{7$N%)-@Xg16z_v=z zTSKV~|9@-T^P1~pCaA_KQZz@RO90utoUHs{(G9`s)Y|c`+tPwQ59K~Dn&VTHx^|vo zZ=I3Sf~Th&wr#`XepkAK2=dSK#JcXMuQo^JgaYGJjSv(T=`ah^&O zSWG)n&M+9q!&wc)(oHvPR4<|>q@y2&N4nQ>Gw)(ugejnK2WEP4+^Ga-2GdNfr@ zQ%#F6;+_6orq$F}a4xJ`1YnR)PN$yn*&Nnf!eHu9Vjd5yvl^LL(2&_S6vF244Ar?M zQR>2VR}i?-co$!Ds(e{J6bFXve3c>1x~!UV{hHEqeBBL1zJ|m?nuvebjKi6ec}!EJcCyjzQ$frU9bRWy~ikG%aj>)5DGeH6Wzc8WcfS zbM^NZnw`1x5iX`Ear)xF#~DZ1$>s0~7vCQyBjf7xwR<)1J>wt;BLfbDuipIBzqT*G zGck%A;z$vU_tzp=9B2?6eEDZ1{um0(g>eV){Iufj{=nn0HuFu(; z1vI;8IdP$!i2=mY+;8@y=Ox^3H{5PFq@`!fNb@C*b7)qZxrsU@fyGi0#YVd4fsvyo zms}c+woL+9Y$;`Vv$2(kJ96YU;8ueT(>}$xfafYsv(uM<{`Q9!j9YcDDJ7&^ zGO6(MqA)VN*=PVcgt3A=U^rg?5%i6~p99Kx(tHHX>vdx>W|ug0>;ianfM3vBx^Q#^o&VH0Lt zGaml5M(g_T<7fQ%`Hl}y3qF2$!hiZt{|!I=pZ_(M7MWqjd-?<0wpE9?$6j-^N(Tcq zi?S3)%avR#0r5zqMrg>(lz-&w=W#X-&(Z={YglP@5wH1pTMN>rM&rJ1H#{Eqx^EZ8 ziE5s6<`YX=)Z}AzVPz4;b`D|iA!A`;LhZn&kGh*+*m|3XjlwP3EY@UR zrbvN_4F=CRqHM*keUwhgqFdzLu-udA0VoZRVuKvm@hcJVJI6g{#_b)_)I+vg4;)e`~AF=!-WOj@&;NwrA-mJaFJKG@VS|9=Y2_ zn@!s;q!dReC7e$Q$6~%`_BmuUEfL+E6iKrMlY;)l*|EFLga<EldA3tc$M=@M4+b9lfyZ7oEPwp|6MpgYZ(4&>Emm)7 z!^_Kab!BTdlQ4)iiLSIAVTeV=lKY+*MKqTQ;D2N`xM219&&LfJ)ig!#60DVX42E?tX9(ofwc0c{%)sm0 z-W=9?&Wj42<8vMsTjxv#a#Ni!jqb*W8&Bwsgy_}X~K(hQk?Q=c!nY?2vJnDKa2 zi}BmC*4%&=I=ZfF%Wq(H{$SX_@p zSV=^h1YXhXL+vwJ-Nj6*z1V^0T$?YdbbyL>)!Zw9fL#K68MJKJZbs|UCOTq4Ew-g# z2A^klRI{{Y-CK$}+a2W?HfRM$!h594=!ARj(dqs*)jM)`#q88)cKRAytcytm55b-u zxt`_s#3{1V=ZGF=rfD6Sp5uE4zAUF*!5u1NPuC`OCli}nrI1K7mq_0c%;(Y5GJY^y zP%C4>z-DN7P)Jt0xTfVY?1d1g_rnjLwYjkqDmQuL?t1FnHo;ShHX(vc#UXFj8P9$` zPp5?w8}m?vGI^S`ZBhn!th@KR2gF5DM7DldzL~sZpwxWsdn|JXHhgsgE`dyjlKGl` znFmc1O#*u@$jNSlk1RM2ll>CDC$d4v)kO%oSRj0ba>!p{HB6jEFX-&{9V&=5mp@+D zz!-*)_$K@FEW-2{@2{*u}^?m|Z?thJ$^4tP36 z964(d0+z+vcuR&?+k~H@v z=Yp3H&$w+HZrfIKgIea!d1mbUqgqMJIi&7~i6Gd!Vpc5s3GBtnV?YHnQbI9-w{ z`buzhq^pL+iMVHb$wbR?Jswppiv2#Tg}9=nSm4N_wq;`JFM1vXgx)Rf#n9bMYN#f& zg9jFey%tL|pP-Q0<0-}_AlyvkiTZOwtqDlxxu}yP;PrkeMO@Yc&F?W~9g)>iqOVg# zpkaUHsltUVIOTvRn9yZImw!)xVF5xeuIiuV#zwgcO~FAPra67OXr9qBpZ2?Z9@s2e zOPGzvfykKn+(Zhbb&h4eR5JP8stLdcD*+4Fx-?CfWzDn(R2vE#^4bic{EN&}`g^3B z>FVB8-ko}V`S{`cSF@BZd5 zaN8CI5te1atwjOYW?rqLQ_{NE5?&-6v}81MpUMDuJa%mBg6(!|VXd`k+O`!7S5WNO z53PIabf#e64+X-~nv9!i{fy&0k#olVemB{Rr0#5MV^&Dy!fGGv6i|+yh|HtAm`ijf zhvsNw(&@myK$Ar+Onw|{);2^Q3Si&$lPiqa3pUM!!%tXZwit&oZVz;mP`nh)5jZvr zy_s^;8tRs%`rjhD0`UF!pPfzNFjZwgDUsE#aBLQA(?J8WFk3n8VmMB0wM{UH2!e3| zn+CIQ2ACG}?2$4ySq(D^0eECp@niu78EeGAqn7NZi)-2GUS)#Z1jB*05V^^sjrfiu zb*B}h;aGjKHoB%b_zvE#+rC3nH!7YWc=3^P**+8UOQhkM3e?)kc9^|4R7_s;;F`P% z$KBe@GsWqfMdv9Td@XGD{X|L$|MKk*`1#L1wycAs&M!hk69=`W`TQ5nt?7$=e~Vkr zLd(Ue`3KxGCmuLcQXPy0;VsXL+x4GrH>7lG;~`WeF)WZvkXw_(rQkTKc1Ut{B-xvD z!O5(Pwrq=2Q#cj4hv-(kfSt9>;fo$sqH$jFmDfG2d$xJUWTE#OV@vb19lrceQ( zb9xbZ#?f__!*;6uiKW#cwy}-@Mna? z+b@ZVn((0QvvrLE_Jfhq-u5%nkm~2>XFT0H7+3?iSMYh_alc~`6B|?jvWDKCINH5F z4#|Q`4NP1btAMq2s4)wz!RgI2yACe4+IGZd*P}iTECG=l-M@w=G+}`D*^H-R19G_{ z(R(9x9)iRuj`%n@S?PR~l*-Tp-ps=;>CJ2!8=*WkA*>DMvJYG-1wVdzvsm@u1V%Hn zWDeHeCgcvpf!g4CtuAw>*pa#Cg&H!a-{N>Ot{t37W`HM6niW$>yM>%4d{eDK%J4QUn)(xg*_tS`>H_j-nS` z4ToW%pyU{N{G;(+M8)8!eA5LX6k}0qV6Ufj4?1%}&Kdvohwt#O{{AmD__8{JQA34_ zCf)PEd+xX!r!Pc=k`j&%$k<4H5w5Na;8)@bVoWaS8QBffCU`II(F?ZVN&n1zy#PMU#K~hoJ=@oKLJ~?SPdz&r)cs-)J|r?An3Y% z{wWAdOVHm$0I0L21Eo8FUePdwytFekX5Dd4bwZL6Rl1=>k?UC43yvl*e!X`-Trnjw z4vmEGzWY=WV@!fkdCE7?A}vz-BFF{I7++C`L%KX$AkOJmA~j#occuZTvqf=r4usDD zirdqKQ0(+Oi2JWmPg*t$`*2%p9d21XY`AX3v3#Eq^Jck9a`()f}sT-KsH6ZFkIVRsaEfhJS6~~9u)f3#of+3i=AK#!43oeaQD{l() z4zrf+`++49zWw$G{NiUHjWJCH13$bZoM*vf-*tj7wC7y7=}`&GniRYcXH0oFyNOuB zW8bml1-GqQI-h3mvM)ph15>44m(rpIx{(((hL`+V+(4I>iNo9gN}+7mY=oABBQ&0? zCd59_C2UB8&}_7h43(!FgGU+}3;nCTb19LIu-I_=iA{~mGvms7V#&S0{zdZomBuBc z)X&JgY~toaWHvPF6C(*0)P|%v9*N$F42mZXOeM3QOhxe{=DHL%p$tig=c;A-^!XKEULW|$$7k?@=A2j;YXLacb=6eqB`um*Ubr?ZHvChp zD=oSy!JON+;pypy$K!#0KXB{^?#qIw+lJ#faqNdK_{+LtYgW!3xarSc4LCcsAro+f zxjM0d(HpLGU|ABjt=ctz{P+PMKYYNtZpit>wmmeE@Ho#(jwS-1XPpS81y4^;HFKvF z?EBd!NH+A2v?$)%`N}m}*J@C3nrEeED75$W%%Eifl>%_p5mj65(mpepl=x`5ZW~?E z_*hT~E^v0{qL`UYN;Z6MTWiXgdvP%{`H&`}iu)%T633T!W1g<k@J2KOme9C%4cSA18a$Tz0cA%tK?(*iH2BobGhBv! zztgMxxp?h{r3ddwZQUqq@XvH*JoX2M)deo;GMF&UGcwo8Am zdrMQBOTS4X%sfnX6;W(yXCNOH`&NQasPx*DLY=7kyx(nl7nMKI-(Pe*Li@ICI9Astl`| zm_{MH0a&+|vdlee2h9jTCMb%MQ}Xx2B}G@8=6q(XTMhNR-EM76zcv(X$8p=hO{>F& zl_qxV2bN_u{AK7lW$KpG+q!DbL0xk)(z3La`%>+l&Bh|A9D~6*_eOBts(Vf;mD-nc zb;Yq0AIvnpVahHOC>r_sZpueSY|LbIj4;{*Qs#i2PE!cZyi60c4q#wIb7YtOFaraL zf}8b(7Tr7IL~r(@<6lGV~@?{`N!Ii67r|ZT&pwsKT z9%G;c+daaZ8^uYb(Li&cOM0-3L(@Y8;OC3|Ku^Y`@x#Q`GuCMOyD3@}4!hrQ{DT`R zhyKYoDz2rX2wa%&iJQy>U>v350YBHf}V2B9YO~Ak% z=i`CnIPlmLo}Qkt??-b@>*3bhZ9{IZq*Zg;?`;kCgf?Vc3es9LaqjoKGNbscRJQf& zFf~mgJ2+?&_^Nks{`HP{MRtsCHm3%wh!;MLn6ON`Tc?*a1u7+Si?eEI%1C8$V`?)^ ziGJ!Spnq(bQrx{~m6Fz*#x~Y#f4?-xqWgWnNb;s3ahb02e(1gX_l~ybD|ueFvABBK zh6UTWC&gkuHWn~6Itm#xGxkz+dcy<>F?zr20JMwgpy(VwIx>10=fFpH!!pRJKNkxyz< zjuo`Db#qC2y(Fabe!pXX)bO>J=jV!IwMHSOMb9avHtmqyoh3OM)p=&TzP;i3pI-5JWIPzE(e4$wR4Vjl+9043Y66oOi<4fyXjb1D#8^gWwWW~P_Xzt z!y=^vQtx6BQq?6PPtIcQ=q%%B-t#_g-d_$VIp3}~b<`3PV$O(C=1 zK-hPj!#R-S7m}aQ^SBoh$E>Pg0uezu4%4p)tT7FMTHK2$Hp>`Y0C6FWQ0gGR_kCBT z#l)1`YHkPj*>?(^_UBwW82IVa7yR@mFO_Dk&$F!O1!u1MPD)Abpe42-i#;;~L>Vcq zs;!epsG9LqmP9_=^oJ7ej~&OE@%i(cPMvekSW?x7ZtDVSQ3A!hYs-?rkCw9|$D7hH zAaIcc7*KetL8;+)L}^|-)2umw3w5$d;j>%m*9~?PA?5K3U7BMyhPVGxBq*891{7WZ zA6yuf9M;)~?1BdbyUB^$54A8oB7=;I4kuw*Y~w?C?8jXDqTzO95TtI3cHs&y%naeA ziFIR zANbis(+1By3#F$s{g?mx2mJQ${|eihTEmdEAhwI(bomoK>AAJ~sNQF^-FoW4>TlYOsT=hP@{Vss#u zou#?n*k{%y+qdRM8ooM^5&n9cmK_;8RZ5*q%3!B{lUzL_<$)W;!Igcn0l4 z!NHkz_MBrfg+c(qhe;Ji!=7BkScmcH^J@*iHqXJjbZuWLjC{&*rRHc_bOfDbC(z7%7-z1(>ug|GrF<_6l7YH8%(`t@65;Lbj{946OnZ5GsX$^rTVqqf zvyy8ro#fn6B5YLmxO5fRN-Q3MH9kTbUcdJ(dGpW_OrHmnB6}Bm_TR0_)u3OnjWM6zQEab^n)OrA;KR!^ZciIZ&UkyP>B&o~XjE>ZNosnH)JEz;*($C1+V@@8pBk=K)0(UKjG)-n z-A$UZI?1WdW#v3wb0hzhQtAk2jg-tTtbJOOV#gfK;bd+q%{b zsx?&N7M2?&O%ULGW_SN&FAxokOvq}wb#6^Zy4Vv~r!oU|OWh$X|DGng09^oFlTb`i zSnpAw^~PKl>c?#ZL1$YUPt1#KW|;-}$q1OmaAry|nF21I`Y0i+cF&aiR5;of)8zzI zw4iq4s#efqty{)QQ}<1qfwy!ax}%v1o|uwb{|NmYQmPG&Xj$c%6diIdj8C5*9s8O! zphVYT6fgygW)ym!6xf%OZXuy$&|SKTkr_CC^mP2wEH0O7Ikt%(6r%h+K6XFh>^ z>I7HzsS+ zLi$@Y)p@2h38vl_m9VI<4IHEeX@i7yl;$bNJuaY^8&K%e)>VS-@`VC%^A?u20C zJYw$kbP6$}q)ZxySp(vZ!%$KNs!PlwijAgiKra{9aBgwhV)H#>10}~7pyc7+$Lm8h zPH^n8gzHX|$&S5_HhXF;FecB1WPdb7==JrE{Wx&DJu8X?0B0$UCYrS1O05Yv&(kdq zsi8wModBv4z`86gPp7DL@_C*(j%@TS(7;Q8k@JcBTShLq=Et-tN!6`bkBK@7kPMow zxz3cMw7jP-o|m9cnc~#7vStXpygcK>hiBlezPae52l-IXipoWm#%)TUl`1 z*46;+ItfYbT9(3f5{)J{Z5H~~`k8uG0)VHdoBmurv!f%A1rcdx%Bax{+Qde8>UOj2 zvb@g2?!#0#6El4(Bv;4z++={GDv}S$^-iu%-lo zK2MX$@L)PIVNk?6&uX{)n%Spx*=SC0w^iw_BC9A|u<)XLBN0HQ(~e<48UX|4KCcVm z!%GbdEv0lYa7jo6*hX8dS6tjV)QQ5FAcsw30DylU%Z8CGVcm)X^?e+H3_S$-G zeLp8}6J3m_eVkwnrVtcvBl(fPcXuGA9>h_(Tcl@&Pee!zB-YU!Qj5vReU0uo>_l&Y z>gB9D$si8u-~Isg~cLHcKCvt zG;9z<8Zb?%Q!Y$9ho{#N7~H?8=& zv&PqM2t1i2jp($D-s=MQ&Bx~!6jrS!1qFh!%k4b-Iw8?Dq%E3qtQAGBw4%ZVoLSMO zx+YXdu_ckwhCrLB)a;Zccut&Py7r(uQK^9dGt$B>6m3(D$kH69a^Yr-Mvej}){^2Z z^YZeH^EmN#FDO(x4UJhT0}aPlvjn+MhiRasIT2)iT^A%upcY748kI?S(emCeOKJuP zTWy?{g!|iFX?ET%y*r$BGYy#}^hrUoK--|P>)H*Up<~mC8`7yPqT}F=T9><61h;D=X2lZIWPLOw&jM*wkI|pR74&=OI^2lRUo{*&nbyZC#3i6dGy+T^lgd)%hhlufzMxstHDeao zdleh1u-{_x-wq&;09l}M`8}&UuerT1G)mD*e%f4z+Ki*bAjWkJcGlN)wi$?v$>;OM z)QL-7t4k?(>?cYtSeCWE|EWIZxfBKADvd0uDNSy`nC>2_GmMCq2H;h|O!DEjZ3PGw zSUa;L?xm&6I4T%eTA*j{nO`a1V``M|W)HnC?eRImnz>fj`&HWwCKv4GY>k^usO2hq z;iTcu8eI($oY3-eabfGUVw;-@juH$HtR<*Cn1y?a@~E4zbhy4mElUdADUlp&dv z>?L(9MbTi{I8&37Ql|lsahM~5-axtbxLACp5mdBoNe%fzbCh63N2iNSEP8D*JZW@B zPjxTCjf;gv+kHU!ae}h8-t&j^8~ZW(ZBhh>{Ver2nvpM`SyqRuS=IqXme^t{Q)&Y0Q?!ni5D15!$iml2NFKW!isg;G9L@*zxX#N+uH=LTw^S zDR_RWxdPj^=|&@k^3u!>s0#bO`Pwis(G)KP3&*1}QMCQ!DcL7BXt!C_M}%i8lcvnQT?R*w(hrn9lmf*7a7=+h$`cwLPH zk~S$8EERx3o1nJOso_S+Q;HDJQZ*-zXEZC^ZSfq?_u2GfEdIk?^Gi0zK#q?fWvO;Kb-6QZeqa?;_JQ@XT zSj};PjteExFa?>FLYBHSP;J6S%NKMr%&uo_6ytQoovv+wanV=>@OrlSO&Zr>;@h5) z*S9;q`Q`?c$w;m(&Wt9aFFY9Q0falmx2Q5rX#d4v6|lZ!)+2k*08i=KXAKkz3Ez#PPIxY zYI?A)$>~hMtoc8=RCl?hq((tl8nvx}Qo_;#424524J2{~n6YC=Db>pQIQNF`t+h}M z_ujk3Q*a}TNTj*@OcSIz^+3(pRD=6IWA!qg_B#>zhdo6aW2I`DZ?tALHt$EiuLS$# zKE(^hTfs5OHT8uDlb(Kky!k+VzWUl<>5wu3GDVXi2oC$Doz8gStfSU>Fc3Pa(LIq; zLyHZ)yA>vu?NFM*QErX&6f7GG|6sK}nP|9RYcmz|I$au&ch?}Z3GtjD=(DNFKslOB z%ZKSi1mY&gJ!?wY5klt0w56{(9j2Z36RvB8Xh|KjYl6d`hxyMv`gs?rzva(u-)P1oOi3TB+@mCO=2m3B5k=SFYsT_N?Nj*DDMaAXaCQDQ!jh6c|-R zZG)y^;Nmu}GDxosIwwUV$H@=7baY%%*@%W0Uv*!l-D>hFu$Gf-n;R?il~iR3!BfM4 z_Mi}06TMaFzoaIfgo?Q84XU5e=82JL_3e!ZJ|1|J}U5M(0U`UwSm|}{e z1q$M%8TQVo7t^EJG;l)4jKOp?$zzC3^qEnP6Z?MPjqd8kNoIP&JW?p@8fq-+X^zsenfhpRpi8}RXQWYha7lf1??^HF zF&f0!mX;+4%9Fj)H(4-82Q%46XfA?vGlJO%Tis)zMgs#FREPgb8`%2uRs2g9@s3`( zVY?tEG-86INZNu!nmxGzo29qN&V~)m%(u za1f^eV zQ%0RWx021d;qGQ56A$MihFGt$L&x2elDd5>%~InL9MM|yVFkA|aD9{E;CiT-2(u2Y zvCIj@=ID@90{M*!G@mLl8SXo2)1hVrx>?n`lT59b3nP)I%YFE8!*BlPmw0)3(ueK! z_3j!M5FBTl0ArhNuU$i?4F~=9`~-et+`qhOa`@#-H5AvQZ@;Hn^a+w*q$t>m&KKC; zGqD?O^Lx{Z87H2CrEy3Gw9;RiUay1XJ8z~`^i{oey)@Z?_&^$F+uti^YKNEcnl%&)*m_*bZ)>uIR8(6EN?NUHTFYeDH;gR<0Shl2!7`5yh3AZfGX^c{;{9~n~ z6>Me2ejMGM%x)-vF5zXl7+ok-T@>tT-edf z17# zn4d%MtW7-BF{2K|GYtl+A<=XyIfjfHrQvMi4Qok^%YaP^n#KV_jZ4O5X$V-Ky{rdAqNwgoO3e;=vto6S~Dge zhK9Mc_xN$&TX=Q`s7~u|w+)G?QJOQ3{XhX@SzB~M%eUEXt7>9p(tPYklS&deQP0o< zT(Ge;TLS!33(95&Rt{;sagi%w4DK6ya!w#@(&a5Ht+>9qZCA`g&FF0c373iRk?O*u zGl}JDm+-LljSL#V7txdwtZp@=tU35_86~II8q$tSOLK%sDS=Y8u>1J&1Mc@neJEn^ zmsymOto#MYCNaxX27MBC58xv_e|#C6oEf^#?|6C#>K`ZoZ7sUVyBV|)^!7etGK>RYGk~RmJD6ERCk&- zso}<5mT)vV7Bx9p7Hr$5IW@<5g3qidUKM61&46L0?iRJr6tSiTh?+)68k~|@U2B%5 zUc3756}eI3QcB2Y#(A8r!Rs7syGE2YsgbqFer{$`+&3`oEn zBLmsdtk@I`jrFHZztu#E*-o;-qAo3@Uz6@8+HGY)J~~0x1(^bg<7qC%?a}h?S-Mqp zrW)#q$z)>~Kbyacp~qu!8~#4%1HBfa7fGxX5zGOv_x7PkC%*XkQ6G!B-eXd2xjZFz zzC41FGyThj$q!;vcrlT=+#4_5JU!^j5w*O+A^AcV6O2kCHT_CUgUPuf=$kxB!0!Xh z;cM$c_?y4}1^(<;KlcVsYydsE28E|a3f6g;!FYOF@x(0xfa`nthi`wxPk;I$+&gMI z(F#^bR@#EmM`(v*Z@kF}k$exmxx{nAY?RHzWuFE-tSH^xE3S?38 zuErenStOK70~D=p#O*8zCCH1r4u`zC01Y%VGmeZ&yUs?Fd}^>k^lS!AG}??|b&kUc zugS1CxNz}{u%gh=O%EYkC)S1?u^Lh8{%^xuM%C^>vlkW|Ib(mjl+u;~S~N^hxc@Trkcos` zhAe`A0v1X-^{Ai)z`0=G_ok&=K|rIhm8Kaa6?fXnh6I)srLj?<_%fbvPk4HM!qcs~ zs@?C^ev=nC?clmDjbc|R0gwBm>j;zI7)3)Pw^wotWbMvp#_QV~?vF>a{p2>mIvX{u zGy?&d*yPaM6!QosEo4Ri<9O`WF5WnKT6a$eu7zfu%!Ak`8*IL>`{URg6;PP&glUaT zs!@1A#fRF-H1ak9ktYQfhqY4oQoi_HdZ$)n-?Yi^EYmdyE|k9wc34xIYhkHnhK=IvMI2p6GhfnWr~8W6h+a~lz#|RY?Kxiy z{hJsLV2r8Y$zH|-wK)K2Q_%4O#2WSp-{=h5p9y6uK7&32VY2_urWCV#am7%$Y78f= z4fnJB&OT3cJw^Fib2CsYu0TG%o+#nEk^1K2hJW*K{?@!_9QFk<&P(RWOjW-WA&Hw$;6Vb@!Vhx@IRG9xQgu z;em7MQKbS;r*dh&Wxjx4CZQNNCW7bhdz7ta$~;jePAw7#GDTns(T zn|KV1EWf`{4vXJ}ayFYH(Yy${YBG7Uxlb2&zPdJWQzeeqa3&I+6=s3r>cy#i>6SKq zUM&rx6~y<)j;GsFHGiqT8x-=XWO~vq@#}TkwzXPS9;fPBWD%DzPH_m6W&p-k`8e)< zs=FV}WwB3J97Rc}Fv(J~`Z~9+D;A}{H8X-1UMe&nF-frClAv3QtSu#XvlJSGs6sB_ZF)iI(K{w3g=puTK7A#}F1U20hgF8J+uHDo! z-n>JK_EC7f2qs6(HtmMDub)K&li40;N}fe9&}vj5n_OdW^+P(ZGN6UsBVxVnbT{G- z7_GvFM0>m!uh#YiuHb zu&gq{shZEORWBw46zV7{6BuU3V}BqWgmv2h0LOmR=7=n%+UiAP2)X3R!Np$OZnqlD zy=?%Yx~PpSging*Q1EoU4NU|5e9gkna+*vgPLbz;;rP7vENBo;_gGBpbe?FmL@bd* zDt4ZV*mf?l(7~Lx#kzAiy*j%9H7yES^P-4aBJ9VB*DtS{HNgSHg4oCgKCI{a_Rn05 z9d+RtFxD4$y?flXLQfx_@OZtCbhY=;k@pswnJE5i4b9byKG~=yyn_h>6M}Ny(fwRb zmS8u6izaD?3SBi^Gs@L_3;5NwAetQO>rSCXh=BJi8N=V z3@Zh~3a}wQBcIFIL?^EwXZbd)2fKqnTMr+qCZeD%5-gQ_M zr6B_i*y|u@x{laawo?k(W!jKwo@SQK;2Dd?H~=BoBnN$lqwyI^9+M$^F?-emnLWq2 zr}5=7{GO0n&ar=h1a!J|c=84uOWQBe8dwKGvJYG>r5a{v!%gHGA5ahd?hdBLtiT}D z$9|Xwhu?1irUf_V(FE_%lc$Z!d&TLDC15E;L>E*5jCRIX^rx#E{w_FmLFu3U{;%!z zmr@FrPXGWQ07*naR8%+2Sp_r0hfCm*Cdd2EbcNoboL&9**Y>z~_LqT1&oj>3SI+f4 zYGV8LU;p_>{N^{mHcXvjzz$ZE5ciBBYQ_CT+J>-$C)lYzd$rN|kDp)hhkyPazy6D# z<2Qf(=UA3{zBw1%Zi{PPi0Z_px*Qe_-xLEMsj~$bOI)dERV`k_w<{QkRx2NUZ#L_? z?7y~hPR7ET8i=-}M&mY=^wp29gS{>JX-j`_hwC{7GROsU^&N`TwXGWj_$d$#C~wlm zmCfeH1Hw#pxxOJ2xV7d0Xw(&0g3PDTy;QG%yAO12*7KV8EY=-^m`>f7t`W z@FHP`A|+WKiQ2e`y;gNqz4tORmV5li-Ojo9Mr6EV%TH)E`z@J~v7Gg{EWiy>@|(^z z-7`sCa(u>d!r^$rqnnGU6cyI&P9Aea(>B<2Tj$Hs8MK}o=U`=HBrn37h8o`>adzC6 z9br1$N99pcMtQPnqy()_XEtx15^ORyU7~@J zCZ%CWXedF@B@`{ZR=6i3GC~;LhJk_X66Lk3e!!*ecqNC<#@_O#DYx*oq1c@Keg5|~ z$TFYVyw{+HT-kar4aeq=A9GC=)dz-)!!V%mADS6PRncta z-r>_vUf|{P$LLyTdti;U{_rYqn-;_1EEmWST0ayEIgI?!&qND^WcAVyy{B6^RX}Fz zL|gpOC7__B@Q5*lu66!);ap7KP}_OOCBdGy0E8)&Oi8#ahY@nsPK7Ri9^g|)nbz)M znlmTn6&f(f5i*jaLnW$6cHc^uo}ed=0{^Yls!Vz}H($-Uzp%-fQzEHt5zZCd zYcZ~C34LqcXEs1#rr_uLq^vgCtKo-dk9h_5mMWX0xuyeHZj`Djc(tHQWx%fSq^jgk zt|!$*W}9zxstE?)*_Si(Ofl#FaEf99!x(o3u-4*m=+U$dUcI_S+qJm7*gEK0V=#_h zMaIKd+qQLPWdRrLpWo<#LdM@x)=NUW*ye(-1zU@@ZCsEJ929@d(_~|yZ=#4m3&6>{ zH;n-eF3yb8h;bT|LRl0gXrfnE5EB5VI1vxN1q2hfH}ZCh9xdLqEo`hpvoZ{0^6$k#Gfp&*(WIJ?4Lk*RH8ee$@Jx^=pNC?tD8ASJO+KNYQ^Cv|AzrcZ zuELOM-DaT{(;4-F-5hLtmUmLw#Md~%bH~mVe!w}-?$Wi&`J^?NG(TW~y4Wycc^fo) z&TE(@K7ajZzP|UtH9r3MrA7!LA9QOeXvx>&e9OjiXinf6Fid2gNp;Ea)Y=iRU%$bt zZ{Oj?vq$)opZvg?W;adb#9teVa6(c+ZuOd#bIlf+z&jTWYhYhDL4jmSebI&<)~ z0ye;vB#7mNz9yl~uKC~pt1*sbAL7T|?E!~l4+5MYK<^0u_s1UhhZF2%aq0(;4F;ys zMxU6rZLryN*ls#pTx_x1Zm{2PadW-Lez%1&jD}pZ(gt-lKj_$X8!$84rh%aiCd=qH zE$rk-l1IQY-s5G_PrKY=WLGWjhA1Is2rH1Jtw;KT;ytu+ApM2m3 zW?@@nCGSSwoVF^HUfo8qj#2rqaqbmXyIgER*5a$Lzs3LZzx^El`p2K*$A9#FjD8z0 zl``D`k0Lx-o;b_(&9#fuJ||klyh$eUUPEpTf;RBOz|E$M8yssVr}8hpo(D(VYAzKY1nC9P^&c`Yq%U0;-z}B&ISrXp~E`2O+e*! zXIIBFf(W(5MzpTU!@}e(-yWUYTotcVI}eywkz0Zo%1u@6y%y!ME62nlDOLOsiiT?K zMs9V^wP+0C`f87E)8Xyy0sr}zzr{2;iRZA1aBK5XDVn9ag1vYE$DkbEz!<`&Yw`V0 zU*gAq_z7;VFMYyE$=#6g6D9}cB65mnL4C?vClC-!gB@(kHAwxbN8b2V zIBeOO2}fRpZ|K6N$#^MeMuX{if`#?wz^s(;g3MsboL93Gmv1PW&7|uZhyTpI-1$t6lcVx|`X)gCJ9Yg;9bMO0*oK!d6LIXE*4V~zH2bS zvcX^e^{?>m_JE)K_%k#nk^CcM%?c5nAczx8ey7O|xja(95Mj4-9*}KgK-*0m=p{d% z24Kbn>xXr43Ts`9X>vx^ZPP?}cGq>_VMv>BW;8c9mp=_^Hia2{;nu7hAlbwy3~(Vc zLxrkB0W+9+z^SNl1>sbwTX5mOQ@a5p=~g(X2Y7=N9x#-)Poani4OL?rj{|h@kZ~N* zpHAX)$#bXGeG2#GY&b3-=<4|)6tm5+z8fctabk?)@V!fZFjZBx6;rdh_pdf6TprW8Nz)vm{@mZKJx=+VS3Do}dyt4L~d z{yddybgsdZuUV7k%;9X`L30ycb-!!z;>9C8fBpo!{nkx(7&zP?(4Tq?!-#2`+&|+K zw;Ied@+c(LTf&Om$y`>w#*6&oKzWJL+2+Y#mi;h z2z;0zfgaEXG;<#0)~b=4mnhsoYNG7zF>tZpV883I-*wpSH)vZE6-tRD7mOpPEy#+q zwSWzfOZU$-F(&K&*=#nL?BrmflUpYsde)Augz)+c=`MaAAkHp)UHtVV=kGc zS}rkE;f3azMANlQNhZ-la(&1G$B%pU?H#^;^#(6qJWh2nL2-YY0AsUBT~YUrE-pD( zc8mRfhwXObIiwVYR7_){dZ&gJa)&TQl6NTu(2+w67?o;|(B_da}r7cU-Rx7#`c%wcd1!X(TAYmF>W zNbky+A)g0Q14w7``P<*U#_Kn?Fpa^Zo69)amBdFPgSKlu9L+}mnJ`Rfn^qAcow}L# zDaibToa;N{bSpR3ba-Zp@G$G2aRU5i2MTT`eUZo~o5okH!HXm+xRLYmGGw9*Xo7~3 z;`b$v5XVi%G>&P@?(x?@|Ha>_0a;DWQwc0(Taub0ncgZ;k*`qml0~VONpeCO8xEn) zMs);&9+V&(UTHo}e+)fK$K>9u`G#*QxfNzm6W)Ioy(?EKgz6bps=C2 zzS-mQVvDwQjk*?KV3pgsnCL?(L4_tL6jNZwL)-6n*zGsiY}zDUYyYJ-Idv)K#W)D6 zSg|+;%xK#q?MGjtF~Uw(TPXP9kV7l@pWxIP@6CDR!oVT(GTe z8t4IAg|$u1gB!g{vqf2gAu1Yu;CsUPvd%f~{k zDrtjprYa;?`e94cG_H9FTNS6smZo}>O@j#X&hSmsplur8koajhyKU_x;CIHGr=S9~^AA9WE|*uBhtVeI0~yzB6vlT=TNnkUTK1tsR=piMiyH*SQ#re3QWI&D4g3=DP+QeCBs~E(-8jEAAN`?kFOAX4^pH;vKvBYyk&D>RM4%a>1Ge2?2<>lM!g z@7>4EsHBGEn-yyJrtPBmfZT{94)~IRbn6v7U2HRo3KH_$I8C9!k&s=j=mIJ`MY$!B zn}w+Ul7(%m+yLP}lV|`6Wf?g=15iQ+qJ*?53iD#3CvKJy@N>gGiOVLjJqf3zF~I&} z2O@H2caXypQkxo$F;5doF1A`(!^Rql7e2>0Sq$TZ!*RgzuTAARo`9zVIpX45&C)i6fbWggAbN8)08iY%GrGj=&-U{P>M z5sw6QHF*8z4$q!kUG4B{}w#hv64LWaY!8qt+GkJ*&nUP-x+D9afVN^J-^pCv+)J$x%b44HG3frP+S zNcC#aren6sA8K=x5438H4n-6NK-rxK{T@^f(qfY(I7meb=J_}x`~H|4eFI7a?6xhQ zJ-d#=5u6#cCf|;P&Y--}$^AOA=BJj|!Z@=rz;3(2Znwq$Vu#&s1NtsDJLj60HJgNL ztfcwj;OZPQ7W`{b3Fq?Edu?FyjTDwQS!*^*gcUgu^?}};32UXf z`N@wzLbvUT!AqWp!f==T?#tI85I*|o zC5SjemaVmMtJ8Izw@?UtcVvPCEKmU`w&no=!Jr7~p1g{vY-Elz;apaOXz`2a0I=< zan9hxEKwgJ?*Do|qwbhn7=EaYCkvaX1Y)9tZTpq{z{^n&XUk zVYb3Vln+!5Q1HoU%)Alkx#FKzPEyV#h_$%nx#UnJj`wMJ7R=ddiKkZJ&%qAYOz<9Z z4p#Zq&;yeCim7J4QQ{Ru;0GqOo9hie{p2}5c=;GtmwTt)G+Ef7@FgZQwWOikry;ky zqHq;c`?UQ^*Hm%SxSW!Q_qaQp@coaU#|FW8v4N&>LMEYcar8G90XjX)(`3>2gN_|6 zw+rqg1SlK87={7Xa{OLn8nj(2ylfmFFR7`q5{U^7N*MTrO|G4+m%_x;A5z$HB=@LoD*G;i{r_LSqkP=84Xc3 z>{3HI?;NiAKcor?*;KPI6P55GQa{&frn&Tw%9TVJVkrAP$4<{*8_nDI;# z170`0orBNMY^EAR_{qQe2yNRcHAh1EmN|5^Hds{{DGwKI{APzhiJ~Cuc1E#*XH?eT z#pau`mPT5aFj_Xy4FKqY#QRk_j zaDO;r7%UFQ9*5(A!)d^&A23;CIgdJ)EPa1D{4z=c!60!tm<+n5H{ zviB;XSnLKaklIlBcM8Yf*cp{Ud?x*rO9U2xa8X@y^Yt(c=5eC#Zgv+DFJ(c z5Ms`t%W|?xMaZCR_?r(-D9fD{spjgoC?Bv<#*Y>69cvg@2<63;++WIPCx^{!w=G_L z@Yr2fizFj1U}-U*Wd1@j*Oi_`tok8j8yqd*#p-9F$uz#uYugsv{np)Ua=ZKcSN7*~ z)?zVF%lWZZw9gc{We%b9P1-pK)tX`9BEOU7Z4GKXow=M*#Dj&Lv!sePD++<-W-2!- zUD|Z5fTa-;{`HSPMBBAWC3u=9SkI}nUKncfD4l7lajBuuHX3t~mJSYvEKWxT|12xg z`Qc|8RwadAwW;RRz}?;*@YjFyEBxTIj~r}O4C0)J96T}ro?~j#?;r^dq~{hf=drLf z2x`DiL~GEyZDyFJi54))2ZwZEQmbx5ajnG6MbJd1Umv3!NnL!gj?Oo#*$I`x2KlIz zGD9%H$(HhDy)mX<=Sy-ENI(KeixdP=fsmvmiPjjx#nlc?V{kg2B3YKG#8r@(5QCt6 zgoxxZWpF^R)EHA_O9-qq-H-buK>pLVg$6{A+uymR{gwlDr9r2Ed}Ot5hhZXzeahyYnqKkSx(O6 zqUUl7*Nx$r&qL8x78$#(6ApOx?8XBI9Jr8Nn&$EAF~ zhzl_j2^loxV~}P1)qnmqhSB1}Pm-sJT|p`SwryKJ(NSvdW%1$T?M$@#hxOac=*ZYk@*LG-H zgQ0hcBtX}KD&r*N<%3{}<4hRXY4Y*QMsrc}0tVCM6mM)62b64b){y6(Y~kld6ehWR zvEDu;!fN~-%fjD<%O)twI+t?L$v;O4j24YCL@&+aKcxKvfeIWwi~CvTS7seLQXYV6 z;#o+92f>SInCH<65K6kiD@byPoO@a$v4O>l7U?{`YtbY+A9whzL)48Uk z5Nfk#r%XN0T(oNdkiqqpgRb4(9WeS_`d% zY` z27Md`OcSdioQf9|a>ArOdN80){6W3NWnbR~`v7ZGHhSC;pjK^#>$HG@)Z9`DK(Jdl& z?sS|s7KwZm-Lw5$TOZ)8kX4NYCqspSXuyX@P7F~@G;)w~dAUQ|HaH!Q&}L(#gR?mH z%Ev!LpW|YC%+8u!ZxQzg}@{ zGaDN{m6!?eGnn&Ql3X-FT|YVPT7wtQukiHgjSpB1@FY%q*3=;PnaaGQY^IDB4>=85 zB&0MKSdq`DgKSwC0w%U1rX^Ss!5fho!ax4{D_mag(|Zclm_Yhhyg$!XVe2?90Y4lD zLyZ>+*l$~0>^Hc&*y3Wp!J})ZUKL34<1}Hi7SnW!!UFsK76ii7xQ1i&3N=B(w{4qP zI2s~M);b=Kgsq7QOEUQ@c;lI07*na zRL+}G&z~V_8>BaYCF&to8|fTahVOA;Is80-KlOZW{yEB?agT-<}3FCkIl<#^EJhO&5$hfMyjrmYp+kVj3Aq9 zBs$k6tvVhFLo!4#T^l(b zVR9Cs1j6fv08Dlglkq&xu`=&W-n_|MMGbiJdtN43d25SnA)A975x~fDM)8DeL+F_I zYJ+-$Ko69$A_^&lVOQKhh;T$)MXXvGb4l*nStVbJ2GklZ5*s|C*+*TT70YSR!D6Ey zoB24vH1ThmhH!mz5e-`d&nDV4*dz?Fq?jflaq{?Cz%E&c4=6>#N@1Ow^s4O_xuU6S zJQCw#i^*oaVHzz?!qTKx-xY#Yu?AljAPCQS*ANc(_xRI4 z`)fRX{tW#v`T>{VlKS6G%DqtjlrBfI;GTvU>;8MP&d-ixt)F=HUE5%{b%=+{%MDt; zpU%ktq>_G+9hIvvRbU9;92V2G@b`r&+1zuJK?)+YjaU@oR8@CV>SZ#J5@0fuyaY8# z35rAW;qRX7n@cpUL4Q1zFf=i8bI>vr8=AaO%3*5Zs~;!aA9{?#q}TU;dgX3nTfhf7 zQ{dskw}?{nSwJ1QfI_6C>2Kx*U!nqsFt>WRafG!F-Zf2b{cb6G%D5y$ z(PzfpmL^K}#x*^&%C+I2X|fo>QAx2MCLH?__t$$o9VR@w-sAdehpuUSq3(#CK~-k6 z>7tLo=`?^XW0;(ez;?TJz6D=C+hQLn;6XG#WT5V>6%_%w6F|J{gf?dNN**X$^cREQlbLN%TZKg94E)W^s$<_ z9JaSz1Je-te!@6S>Y2)w5aor`>d2ZK7vQZBobc8Fr*Xg+Uw(~tvy1#s$H|dRn^8RW zXl)V^4~W(aMBZmB7*%@+bQns7frlZ3rXh5#!NqQaHdXcB!P~;a)W{Q2%llTt1pEh+ zsxzb=pTj}eiX^1Izo|kZ&RoYiQzy&ruTU&NPIpKY?lE8@N}&=Y)*iUIzChao_uJ*Q|2^IxpO3el|BPI@cU5PKB^cPUM+}slGd3nDRW(PiXEO7Gjl050|&KKb|=_WLc;qPUclWzlG8muJDFsch3CpFw3vg*B6hY8hC+fnfpVGGw9`iEC`6(ikZphjcF?YrIdq+QGM=W{F3DT><%D_8_#j(M0$%5;~yvG(6H6_e3Hl^ zrOGoUJ!Uxe=^|fhvV9#UoK)f{^PQ763+cEsB>|CdWb?w=9i8enUG$J>N|D{w1V+;~ zxV+j6e+t3xQQBrgPCetQr|lHwZ`u(LSkt%gEQMTUf0adG?PTY#eSniVS;k7?yIt4aD`JPA<>CPErve+kH>Ms zI810;N7$E2$KgB~B5b!UnvrlijhW#*mx_ka%}WuJbHPMEoY*wLaU3z6PJl5EDlNCv z#;Fx^R9;TEMi5H~$77lXY&kurlyUEZ$|5r+wwNq1j1z`oLd$Z6Zh^^5FQQl_vyzw8 z2c|bIGNBY6I5`3kS2E4NQ=ciF8&}iK*^6Lr8Pr@i_0y#O@sb)%5eVL zgp&nXi{d7S6`@!{Hhea93J{ay+MG^sSO04thwKXko4CeIlm&kVC zwK^}8LC>kq&0@mm7i}NBxWY#ty@+fCs=yXvqi#{a#_~fWp$?bCJ0vDQNpU7pHwyRn zqS+x?C{gCON`*+C;wAd&QcK2tHw=pW)}v_*CP5wzupo#y!xADHNjWJQPL^>xjVW$5 z#wpM|y2QoK`P~4FaU9)i_5-HL!WhCZ48ru&K^l_68sZja8hsPvrKibrF-_x$oWXm+ zdYGEE7X9EzrGckmgko2aqn^BDb-s0u=hAXDY_Ni@S;mZ`N(#tYJ07|ByoTb{g;VHD_y_yYmAQyU`5 z2?_xuY$Od~LnbP(4W|L4fbP_XSTjX;t%#o!FySor=0Qz15vv6UW*}m8ArFF>Dm@;YYJ6J2RSy_Zd)9WL)Cbf@+KlXPhlYLYVL%9l7F*p7{_Sr#|7uWCT zD3d$kVe*=}Ui~>J*i!Se#tc)NK+Ir-R~&DC%u)uER($5O-=lgEp4+;tlGw(wtn>T6 ze*U^k-+Rc<{ZV}K@e_RT!BaF+nJhcT$oZ&uPFrn$`TLq=KJ-1Q zZc57MKHnOn(FfK8H5u*)m_@Ia$Ik!xJ^b8=2u~hgs6km#cP^ATDD@fD-&4+ItcdAO zHYi(CCQpmD_fF>LNFXFaWm56pTqoy{h>ChHEMC14CW$26r(KZFg8lC4j3fWY&U zD#?_g9dZtG$V9CqFqJD0hLO7bgiL`bQ*JQYSS>=vkQO&C}64WYR(^mrqpPB54MyA+; z%!vm;;3#G$KIgm#=C&r7QE-`q(N!l;Tot@nT+d4ka;-_MDbB6FUclwW2A_QV6jzsf ze-GP4E=PiHP~~2&HQG|9y-*WIjxb21aVdAN#6o1dFO?j9<6wPol{);Ebqr#NLY~NT zbqK~xu88#V%H)SUMl|SAl0Gvy%eQo#!?DOoIu9e`-F=T!?*=Dt-W~AxX7AP3w%Bf3 zY&tJM;P10(vS{1ZDQbD5=Qxc~#+t;Ie7D`78vyxbj01JRhFH`scFyOu8@As%Bhl)ANAs z#3M+d599`|$RIAcmNLwsVo0SwC)D?9TT@8Lp4bZBJi3Zr9YLWCiqE9^wk67mDxv|p z5R!!JTK?f&ej*%bGX$&H)&m z0fuSt^_GKclZQ{k81=kIqiNq1g&fHq*5+c2^*uv^|CuOtABNT(d~k9Vn$(;aroyO8 zDHm1b<)n{+UN;H91|dnUYdFs8ubiWksj5hb%FMk_MI*q)>a8(^%d4IDeCX>9dj>1u zh^^06gz~uNlIOd-6HccD%?O+%%Z$Tuz&O}SR@eX5q7D)sQ$a|900Gt>7)qRkD2q4c^Tq7%(h5RC@*X5X zS^3+_=D}J=2K9aclYrrbsa9xaf+&EsoaK0%CSb;(?fiD6A!U9EX0S17TLq~cBVw@f zzv9y6**~+BwcydgUXP~%@9vIx^X`C4FD3oxW{;bz3v{i)X46JF&5&f3s+x#v{i%22 z1JeYe4Vaybb>RDi;~vK`e&2fHYTLE(zMLk{4>AO@PzIX;MwCB}H3e3-$RzrOk#VNl z8U5R`JfyY-%9BlalYum>O2HB{8DpSu!qL#Q5PLP^rDlq)3UtLoNs`)99y%zhF=tLW zQchcJR}>6$hFnYnwzl20xVYR#=vLrQfz$a4G&!efVPahnJUAesdz`;-Hng)@eqRyt z5Y1#IM31r|C?~bLEUc!%Uh>oGHXW=n(KG7z`>G58m(;#$h5Bq$@c{VR-1HzBg3WV5 ztA?2~AM>Hm*&~*kt=R{~A1zB`+BZqn{;H}E%O4Lvs1_%Zirx9p2 znb(*_67!)-j84>)hye2gGl_}_Tb!U`8D68gzP|Wrcws}eCmuaL_bB5q{M)xHy*T0#U33 z-A(@P_UPao+08#r7RTd=akT1W6w_R_{T1%DnUb7T$srwivgQ(*`VHwOhaM2P=hn^4 z>tRsmBWD?0=3Iv76kb5{Zp}+;Y+6{kS6!Rm17=X27_D5ppL1Kz-*<%&z;^+I_~fI< z_~@f&Xd6?QaR;+qLiXGeW?*P61|0Kel++s~yTbf#4TR~*Iw6m7beo9DTG8B;s@>8_ zS$0AY>3&3M5SL?mStX2IqTl>Id}w z+a`JZ$<|nVK5X_<0hO;aFD~D*T^9(W3aJ0)3H7(4w;3X4b`^9t>!tNDhs&73teh zjG3lE(>CHWyLbqyAsx_~94vvNuuT1X9BB_|3FwQce?MC((CP_?ra#++QgFwU;=O0GRzW4fQrDlddsg3|GN49}A3`(;A|feUP!hn}Rb} zRPTNBWt=qaS#!{}!?MKz-kNxOCeE)OwBQ)ZEO%&{o3JR@DkLlV4Xfr9|tS z8f37sm3eWR7`OL5uCKNV!Wjq6h6Ie1w6u1OYo~bddZ3Ubi?isI<$Ur+nQ{OlPnR(c zemstohjx~aMm|K+2!Ea#rub%s8I~PXExeyYu6ZseYk@M#c<^o8qT6)wQn)%^*04~V z&6YCX2^PLE(n&f_nBt0@vwMZKQ)+QBq%2-WuFXU=Id8W-cSb9)RQz%v)E~0OM#DkU zFXT5 zOL2xWK90PuD&X@x-(g+Anlsa+^UlL_zqe);FB4yFYg02K!&0MEftf8G_o6Y{l8PBs z{`-vH{v1bVR_1fT+h%oRy4LRjLifMJXWxH;{eBCQGHA0oN2)ue;xHGyAWnp1?S~=s zqqzPV<7Q^Gv8bUOt^~ww1!sy-%#6`mzmX{mrBc#f`*H!m>2SdIqK!w}c%w{dxEVGf z!T1w~(V&eGvQnax6HE^x*u%*^TLPwuU~TVJbu5m@0pnz`={oFoPAK4X>apE!u-R-d zO%oab+**(|u#?;TOq0PlI{zG(h-_@sCTr954NhWuumjqzjn~#SSWdYoG_o);J{*g!WsM`D)Uu@pe4MLWm6+0{A zO3cM_tK=a@@thS?;hZy2vYXO*bK*SPO@l{|E-?BH9Yu9iU}n0YZ~e;iE(e~8^qlgj zF%691xdj0pRA6P%--jzIMwKb85{Up(W21ggd+oUM@3?Z*IXLE^^7y%2w*a-OL8)Cj3so701U&3rfHJOn%cq> zE-tpXyFX#7@IZ4}csZn!_X{hPJcteO1m;GWUn{6=KF}4-7YKgfK+c=Z!^Y*gf%v?w zoOH=hKovoNT-heS0C|I3c;>J;+1^z-pUS3!MoJ`0XiGS;HtTCSGw@3rn*d>u3NavH zx9f0uxpQWoB2Y-9Q{;6pXM`?-xUEuBd-Ludr+!q@v<$-Ced6Ni$+Sp*6=kJrtxZz? zHY0I{bLJnYC`XF~qXGXOsxi#-wRA3ZIVX)g_rc~Gp*%|E)0a77|I+dEie$8=F*ql! zoCoFNJZ0x>O%pWd9!*$qjK+LJwaOc){&jP`!H<6QF&ZggTT+ya zE*xoE#sAy)s#x5YJG?6g&;-nak6Z9eZ@$W%Q;A z5}AcR3#Ca_;K)dr5M^*YwpPKlB;ne^Vi*%iGm^y_c>d%X7yB*R)?ja%IJxWl0o=AQ z%z#%-gZD|1!>*vt7Ot%kYGBhiVH`%7#zd7i=0LhN!jRYxqNJ*okkw~c<S{Vh%e(9sr=-b{K0-&YT=`ZM==z*c;l3 zxF%vVo71??+o&ERmTd}ZO#^3}ni|(f7NJYIeT}HlSw7N26EZ90uuc$QG1t|2JA~CL zZsTb2yD#41qYtlPtaYASYG|d6eXC-P6%M#U`xJ*sC9MaVUp-C}rfG_vIZ_k^U|j4s zxW9LvYmkC4Ky~vOYkA_TrA4ec?Eo?jf<3bwddbbdl(|niP7VXzu+YGu?b@WY=7(+o z(6XEkOUoA2y=!z)&*ipuX?;qFSP|~Fd zn&x2fj~-oO90m{9$g!Z30M07TL~~5awq1TY^yclo+S~*Z*6n?tnw!cVUqaLJ^IJe8 zDE+RrR!^*0XhQ|{C)k3!!;+}A>S0}>ax!Zsd8T>bnv*bQlEMseGoMt}l*1MkRd9at zRdYICGR2%TbSt0%yzaEu&cWFY3+nea(Rrup6K?1lTDwDOSHYYl&HF8T~Lh6)?Zy2-EN?0wT9|AT1UoBVlk@PS78MokkDM zX&gL_C1sq|G|Nq@C{3-}7R*EB14w3(CRK_}g@}^>;)-j@&=8x9 zh=eAp;Zd=L3up5sJESF)6UQ(!b$ivk4qayA4agUPz)mXHeuDRe?HViX~cR?>FnHb*Um?^ zDa3>FWj{>#{L6Rv@Z~j3SQEnn*7H!DY6$vq#OX9(7)RJCsdySg*ljy(HXXLxu5Rwj z3tD<%kR;=n9}4uth)yW1$@_o5?{IhMz4&QG&>+r@7^qt?ZL$CWAOJ~3K~&vltof^v z`!)@LNk-77F@B@vz1}9bK@P8HNFu!Cw#T69OdJM|!x&XOy^5Ou6Ot~e0{BoEs%LW) z>Cd8vVM^sd!VXg5A_WJilzirVCB_-}@16f2{lzWv3~c9{TqvyyK)nVrK9e;)k`NL7CKjom2wT ztUk)I_apj#!eq0ihUO-Q6{ILv_;Rvb^{aC-22GHJo5I1_pgc4pNzxdlpqOm)o-=QTR6ud=^BAFK%v7CwgRlYUMNR>1UQly zjuog7LMEjwY5FP0Sk;=9xGZImEkCE&qNo}w+eQ@TrJ~J&XyT+ACS|g*QF%^ng`D*R z#QO(ygNcoIDs+yg0moyHLg8#-rZWnee*siC7rwx%1rvC!P2%%( zU5BCX;}W9Pa~=OcS2!p}6-<<1U&3t1a=?M7f}g81Tix*JE)#{bs>$RfQxjuU;5B68 z1%iN!B%-JDt1yPJ-E}w}j|3Tf&5b(U7!wTag`XX@g2c-`t< zH52CoeC7R%$DuUF>zfWps>i$f^FBK+ip>qq%mW%lY`HUqZ^P2^)$-)g4Tk) z+5%4ln0N7+x6>3QY@@o=Fhl`@JkeOM@)QWF(L=`t$=K-7jL640O*kB-#{i@2T0DN# z%A*;9C;jjk?;97TS%tVkZb~X)n@M?8pHrg*LK+YmSnE77PNyL$DrKKXL#bIq zV=D0?oWfynA|GyJWYpw1zu)Em2H*?5057vO3{TyIPQce#42Yy(k-Ru0q_uOXtZ58d zv{62LHh#|y<<4|JMF}u;hJR*WKe?MLem99Vo zbBXRbKcRDt$*jCIKMacJzwVDCzWn+YFP~q-L>mIayLSh?dUI5wQ*G-kOq#~1#=|LO zjsPEVak0UEx5379#fkw*-n7?-jsAR1)?%ETk#j0hg2HAKQAx^nA@F01t+)0a3+Se} zw6GIs9Ne%gK$tCqh++Izt1*q^*La9E8w27n7$JeiuxemxIq_v%ckRViz#nK>6KlT) zF+BE4DDZC8j`$;{S`}QXT)As<-bA(~HIXD`D82%E*!>kI^MF?sT0 z>-z_vy})kU-zmffxHMk*0Sqmrc+>aQ&6mvej3&C<2C-goUghUdH zTz{ZWo|({Yw=kwbyV<}rt>dJ$P8h%y_`-C|h5%{-J7GB7;qA9?B5t3cIUm+qG-!NN z6dD+((!`+&5`qJU86zMd14!y}zW9$(kZrMDuPKH(BT_d>>xU7CV~tS1$@NUo12o(zrIoP1_0!&UljvCRWoDjW9z_Fp}78M5$H1m7$C$L!{$` zgjY&9o;2son^etP$}AFC53s3N(5f@7$i(4A3=x{vfdP-F9>-&!Ih$*LwWcxHZMR@{ zva@a5Iyf2;PW^ysvgrE(*ohV2kbfZH( z5e6JqNxyS^p7O1YkSswNqWm?QocKVyX)zAdx{dp6<8x-V2$~;Aor~jhL%#|Hb6%__ z&x53M;yGWqY7XK0rUra|D7pBWGqw%qy!vQ`IM13!bT)UEuX%qM@#WX=@WG2~uysC& zZ{D4}`XON9q}tooQ7udp21h0iCfsm~a6Aq;o<>~mH`whq{&y%_Zjo+G^R0Cz&N5Bb zBQhvHPn*uckx%_pz-(38&rn05;jpY#NgbkLfMI7MJxwDFyJ3e7$Ko5BfP^BRJjW)9 z5!q=%!>!<;S{O1OK>)PKc*hD#CUAb1t-1l_l+g+oX4S+X8S?0f6nhwgfW>99t5Gg8 zgSI6#JRhK$R5Eg%pULiX4PV=Ank4*&=Rk=1k}F1eQxY zmzYOE6U#`n-$j4&fKH~a-m;dAUk%7S-=NGv#+LXfIkB>eF@E4ys%Uo4kSZ6sGJGDA zwz!g?39?HYnA|CO36ij|dM6@$_URK`UG56lsDkBiCB9O&kt<+EP+JX&^B;x@{V>KN zx;B{~hRMNdPNQo$tYRyGKbJn+-PGohQRLP8Qc%*m1<^aF1j_2DIJA`C~Lq zqUDi6(>1udzQFUB&vAJ7248;p4Tdq>Bupt_GXorCI>WZaP+>|)*1|^NdXNcgf5Ko+$lFFRXr*pw4{V1Y=Xo|ltD7*3=32e13H;oWRoKxhXJ~2&f9~?hLBNP zdMEJ*l6gLQGC6EMc@Ea;G@$QC1rcK*q;Yw1ft#C4>~}kKU5jBHad~+W)k+z_t5V3~0|o^XGENQ!bm%%K3BZ&K!)mo_noo5HZs8F(sUSWc`~uxu(D zLsnZVR{Wm8bt94E+pfhp3}+gZh0Xq)7)(KatmfC8rRNJ1W31}L(Ef!nxwso+v(`ocg7H7VTF2k}I zO1Pn4{k~>vVTayXD3}(OComg;r_|sGFRgq#6hvz{Y=Zo`lcGeeydgMq0X8TVQKF&& zND+wAy=7H@r?mb9@zo;XfytS)0AaNO{SdQ#yMUPwO zM^NTFkvKyk8L{8cI4Nk^j93P4?@j`)1`V&M;Pz`jXVie?C{%>h_J;q(x|*4-#sX9- zZwjjp!ZYjLbH88P&=mUr<*N4lq-}|$I3r@PN}c9R;H@ms^9cfA=|V?@kHZ%PbI#6rod>kDp?@-vekc3>N#V z9X|c|5Ag?o@G<`M|NaH~!HQvxhaylTiuA0&FW@zPN+*fn$_N>XP!3VFrq>h0oyqNx*pYB8CbwDlMFa`>MCeV``Kl*h-)_=t5qnL|9(@J{*IWH36E3c&7K zX^RBo@#QwNX)u|IX@C^U;eZwoNFALVO3GniG#t$!p;7pPIOfLa7%r?I2*8s^*ZAn; zmtHW!9q*Pm7)Fb)zkVH`)c|E_8iUJ=9rhQl8QKK@3I@h;#Nlwl-TeXgcL&`0W+$Au zK|sI)&p^-8(v>rYqG7G|%4-lXzEFTA9)RA` z=W@gUl^K&X$gsSAHJx zb$d5>E-33wy@#bWjpHvihCl|9M-B+pOp`Vo3@2vL4*e;WSj`x(poHG}jgOF7!@(0L5&iV>qL5_1x zz^_e<<|bve4O0!*yk;{dzCL()jmM8JW3fd=PMkL`EOuW~;YvJv!Q*8L+k$>f{ERGT z4a0=Dw};5BQKyrD?S7BlJpD0UE=F+-l>M$ zP8OEEnX&ZCf+Nu9=Pd;3O!+q&qgl(Mr%gPVu-z#ktG;{|o`t7=gdswAcfxLSkNvho z)A&iDAvA4^uIth*;^j9btTxC5kCR2iZqVfXZrt$<11ngXwH965W~=6@q$W-oPQv98n>PT;mVh-WJxm%Yf9wSjSir2J2u&2_Nv)@aO|q^Lnk_<K%jb`AeRJuW=dQz($5(j%{1Hz5 zh;P4rhx_{@j>i*jZ|{_c+c1n?wa=)HSH4wlgj{)u2dZzN1nJb_wCcVW)%pr~c3FTK z2VtF-I5~@r50#tsJdf74F|$x_Uf%F8Ar8)Mm1fn_Ftg>LWiHOrU~LsoW<{>7d1fkz z;F&sREjr~rzrr9)e%Xm}IE~nE8+5Hn&5fGhhUYgt6RbAN$7Ao+FgK+tU}Y<%2S@-D zVGOeV^5l`@>RFGLKn9Iw7Dm|Ff7c%Y#@L_GZW~M!C$SSLbgvE#< zpt-u-|5Wc0644II@uie3&b6?W6Sv%kz~Kl@Wq*nW+A~@1j|&tYYwir^t&|kJGGlZ zox7Ee)Wta^WDmgl^EL-_18{ZG;j_6SS7B`u}Yyq#N8WdQ^7t4&kcRZ0%xriqp ztYMsRf9Ub%-4WBoN-B7>+u`c*V_ZLdhO5Uvm_yV`DUZFo69YmE8x5(q^ zgm-rb{M-NXkJ0x>eE!9^PFa!&P3xqc$%qERSD5|bfN>mfd3}kCU5Cs47W@4cUwr;G ztaONO8Z_NDp)pO0S)?ZRr1*tl`;xwIqL)mBs)hgau!LMaF2ok)ITVk}O~1FB2Ai(I zcH6}*i=CX;P1m;GObxJ;Q=bclrN$UouewHtFbo42P%!qi2 z^{BV^5vIW<9IH+^hPwAsa;0)3tM=rXp_|Ar$eMt>c9ZIzDN&=Cs8Uh51P-Z5UM>=P zO{vi}UPd`^tb#8DJU_Pa8?|r^l1+mA2P$v6t(#5HD>Gicc#01`crIXQgkS#sZ}9WK z{0FBRdKxkGBc4CK!qvqN*H=3jW3cTS98LpXzrMriG~(6kJAD4dYy9r>*ZA!}e+_E~ z{OE_@$KU?#uh29GPoF%(qnj&SU0qOI$k68q0h$MJ2JB^Xpy`5}32C zA6K%SY zR~*ZCR4<*&r|*N2Vc+}^uKMbECUxjc?@nBD5@&S8V;{6?%Q z@mZM^;+&AcGA!ZQ(<{G8EbkTRrJjR-2!yqw3jN@G04&!^T{ks49NcrJ3wdCBaf!>D z$Jk$9V7Fj;1QH~)a!Z{N+_;W{|K{^}L}^w0hZpM3lwe(@Lo=%6QU@~t6bV44Qg zG^)Qp-QQsxMp)|_uV>Gm;QD%p*KZE-(lu=-Vx1H#krQ_kdjAwR$4Y5Tnyp2sfrhv! zNnkR`Oil$NL>#qchy4yvvZiU!_ypnLe;^Ik18<$U`}R%D9}&Nn$)I6y>VDOpxd;f|e)cZ2N-DCcs&e2DQ($(Q)C$YNv6A z7Vas5uZ~zOhIm>*6rdoB>ZiBCz_l@rQWhPyW7OS z7{&>I`Pcu5fBMyz5uRs=@ZpOa>~~vqo#PAirygVsUcI_=O>mSkPq*Md{Nq>n><3@s z*T4A^-@duWN8fvbr%!IM-)->t@im@4eT2i|h_~o|)AQg%Wa#R`5tBo{0UNm>Kj+XrrMa31|Ix0$aA^eDJnmQ&{P^-^wM z;_58I)lmO@a~l$#85}Np?8&!U!D~IYky(R|m^+v6W1F$^>;5p}cpPzg(c$8vi~Mq_ z1{w23*4#VJB;#=GvGao~ovq~^FFD|>;-j@TZcijneABf6kLbrq3GBsxTh6YG&gY7| zGme1i{1DM?Myq2|!TC)PVN)nBhEv~0wKO>;qfCtj`j3NxgSOC+GRp#2?Wd11ahs&3 zCMO}WI}Ok@F>wNn6FCqGs1ehsL}C*7W%b(bV(<1F^f6iM%gi3kPC`qiy#L*qI2;EY z4kxjp0*1-r-R-HUck|6N*9^tfq=@IYyO~FUCV2k~K+vj$JkwgGnK@uyLVYw1jy7e8sw6~1Y0}d?*4?kLk}zTL4u_7{`wI%`wMJ4gO`sw{P7RJ z2Roeb|NiVR7WR-yK0bWsn^$jeeRByG9GvlVf@wSOFoGHb)3naGQ=HCs-+qhJ(`)pD zQ?j|axyH9|4t~gE&~#lIU_iSwhcim3PxxK@Oa-=UASfm^gCN6c<7<+H;|PvQnDE7> zE&Q$ZO^!E9?b;Tb&TVeSaq_roD}091?di-M-S);c5l$^_<5jT`G1Hzz8$@8_28AgN z%^CC4SE(+n*R*tn*aDHM3BMzut!S-6Ewq{;lM<1va2>+|IBr^{+xzUc{~S+a&O9_9JkG(i=?vk2_Is7wwq|g+ zRP3Mi!&w18tLE1;joUe8v?AZHf%Kg*5k1!!z2}!@;N9JT!*Rspn;kYDI<0-dSmn(` z&UaAWz8}$bO;kDz19qt#sJUFMVuhW;bEeN{+Zz9D*~G_ZE~wcghd)^j%mBu5K-X=- z)}Aq-W~R1nJ;QiF?dkF+i*k_yU{O)sQkO-_st0mF(U8ctGFX%WdB;J8{(n~}6G zmj<9Ra2Yn~Jq#(wYZt%~gLd4KSj6{h+6H!-lo4Q6GB4YOM6K^+Yk}Llqna{W%Xs_l zs3(MH1V&1~sZ#Ai)yTr!F*=$P{mXE0xNvt}uNz+rkc+zUa{+oLSQie^OS<-SCRtz^ z>szRyoa6IUh-Ww#^Zy#C^IO#KPJ`+LUJAMi&% z`UJ5vm^l?UkFN0c%`HH{XP>>qAN=4W{Mn!Vl`EboHGPv;YMDl7h~|jyN#ge1o42?> zobc%S0@hmG-rlFrXdJ935~Xu<)!gGn1@BTlMs2w2E3RGbCFdzO0nN{4n0O{4E7Vq&;uJ~;cgkb7;@Lo`UdjT3 zGOsnSOe%RZ0{tM*w<_qF(FSEdfBu4cVBiXw(9}|BW^H`-+s5bBSmbL+Xk!T1H&bQ&OY}pBFTQ*eQ&wXLKltoJ{QW+i&mj!ykSRzxnMqxVgE+XW#!2?{4q$>eU;(d2^>=G_`s) z3OEqOZO$-EvmSIRCkb(dxtzdq{_TgTlg0U1uM+!00e+58GlxD{8W`Q z^*F+m)!>PY8r;~)qBT<0CWs1%l~=A}rk74>x+eKF2+4+^xG{h;4GM|It<_TWg*5fp3tU;siw;aomg=Lf`j-xSw-fq|Xj1UQ4)%ECX-f-A9S( zkeKg}J^Fr{-9Z$3Jvn4l+>E-rl{cK9%GvBj{0^a{^A9YYpG*{i?u_JcRZ@%U=3a{i zotRgrStJSO#-1p+W3vrI?$%lhifg4L7ey5+q6~BAVYO-MnTDtGyO;Y8PoG@tm!tZ0 zl7-y7G$N!K-9lGbOSQrDa2!tqZtspb`DZKogqQ}qt7}|b-{9G!3%q^v7N7s~Z{ssL zG2=h}$G^dEe)A=c71&4!+&}uG@8jS67k_~N@W1|Fc=r4m{_sbi;%7hme{gp{Kx)@V z6{c~Da>h~zIQ-APA8|^cFbe)fHN!1G3zax=e7FA)I?0s?~d`YYYIB+KHw%4kW_YYKMN&P(ZEcSIi2GxY!?8y{Op$ONis80xg=n6>p3`JuDaEPA7-t$c zj(&>RpfQ9oHisG-MY%r=X@8ok$3omJaNJV3hK~S~idV^j2}v*twp7AJNRGyYSW6<8 z8AW<6>pGGAsaAXGX}M}eJ;y7-uSxK<+N`k zh@0oJvW?I~V+fXw1KlyFEu8-#clSqeog4)2)$6x-_wI!6ee@D<-`(Q&>u=*A5+G-z za6Dx&!ql+6eS3#zPcHGzt2-6yZmu?X_Vh9S)1Utxe)X#_@a)+QKKbMW{NS^X@$U8x zuV25#>(_6i07T%TsUfDwLyaNOrp4+A{TBcLAOJ~3K~ykIuy)G0^;DW*FZoJ}EmR!T z8Utfk!AQ>*&bb2GQoLS*axV!0U}57^GtcHV#?>^RSJ#RdoHNg?$#k9D)U2&f*7&~F zwp+PZ577*&gxBTU_xL&8w$U&)0SM~H3XG@)%8MLRj?o)Lf3hUOvxyxWE_ zHg1!nK|U41At{VQBs?RXr;TZaS5C~q{M~PFFO69?JR27%=99CXal_%%Hl|1FaNj#ND%9dnBPL$Z9MUez0 zaR5O~7q}O9KEpnH=qn7m6>H2K*Q zvKbLOPxE@7L4~bXf$d8awqZV^TTpRaINJX-9$bJZvw3U`?J8 zXlpE<9WOlKKX0Y1OgCWnbehJ*5}(?%gHEOlai{PUwdAo8cQC~{hDMbLq+PR^pk`4* z*e4SvZb^5CX3D3>oYgA$YW{CkuwXz`JrXR0nDb=*OpU9F2-+i6zIoH#!$5-FQ(>V> zNJJnbWU5^=V^IfZI%{Fes59sGvixyBesmI)(R>kd@BTRmjP0FGTwKg>c6t$!mD)C5 zZ@v9Ko_XdN0ORTF2e|$IYB zIcNE-rm@ftjCl>SqQ^r`QoOtNT>JJ?hbURSrj{de(V%)L4-XW_i$5>`t7Ly2l(M+w^);dq zDtrR)2V{JRbL4I%vWevB#%0XZT(gTO=MZT-W%S&3H+fSoSsG)agK2gmX`puR>$%F- z3S7YXz969l8KLNP*P?e(2Ye=GGnQZ8G&rBlTSNZS)A@RuSQpZn#E(=8H5QSaW8v8} z@!GGv50K?maD44+4%yCWgQ0*q_DBG zi^-Nfj?;$^v7F7YI+;S5B_5qF?Nafi#MaIxzy=rRbJVr5ZsXa6oj}+**vFrI=RN$; zE6?Ehn>X;yZ+;JNy?rl8^D-D{OrYc&c+&YTAEN)h4Tq#wW_dKES(aX z@M|$9E~*B#t@x$2l?f)LpxF2p0^ZZdH%3VT$Z??_!CcXVeVX;`kaQ3h7x)F`nGr;6 zqK`xzi1};M817K*rMBF^yN{J<>cT#UVF!Jgt+onE*G zE5A>HjfukU&K3^#x3Iszi}Uk2&Sp!8Hrc<~+1|t_f9NKRX|P&VSS>4TY)q^_PR43@ z{f)c$-kW!E^VuW3@WL~A?%C_u+uOmdckiMJMHWJHY2?r#pg9T~6GBxR>#vpMy-t(& zi1HA%s)g|U^@ZdvIf+j69o>7bUDPu4A@*zX-@4+P#ts{^zgd^t#tZ@1((*bAsxflT zG;sc7J%hS-atOowt@!YzrVTR|OFJmq+A6U*Em4+5GJFBG{TF2&X6fK6C;%cIZHRl3 z+c{m-_EId-u)D>DqZG6MQs7z}eH1)%Ax&WxP6%OdqRtgKFV!EePl+IMj!_Y>sr&LIi zwz)AbunFne#w1-XcPyDlm9xZc(8@obFJvQYy)e!redbcWSb5MBOP=1G%q!VMo8>mD z^r0%JUFzZE_Qay~Go&2Yd;&w=GQzz}o^W;TF;Ne?)F;L;fCL>LY^4(EE#pLV?jTT3S93pGEo&?mRT_ZZzh@UqoSx0Y zwA&a)xv_!G-2; zoSj?*^fRbFX@!Hs1HAnF5pG;R#CKnR8{hcjH-rRjOeFI2GEIYGQrca<(C^uO!pY_) zn%ZDh)i^(!Ia;hjG2Ik9f}UEXTF8Yr$OPC59FU;=<%w2F4;3Vfrao?Xyf^MP8W$&3 zxVFAKGhV!a8Fk&Dt{btl!NF(}Vz&di)UmRQs0fD2+7;E-k>0;1igbaWGtzU*1eBHqu9cOK&HcOT-p8;5xDg&X+9D>w1z(HY)- z?;eavfeTH9Miy1>St(1)_*kvdCMT1dNQM!KdKFP}{XH@&1vxsKn%<#RwD9hvCXa1U z`V>ifQ&m?E%5z1Bms?-`&?iFB>o+%$w?>(7uR(y;nx*#r-MS$pb=Mw5ZDAsOxaC^i zFfJ}E17b@ll!X?)I9=-FlzjWlO_GKt5=(Ge)hZ+dABeS^ z^pHZ39952Itd&Y#gnh!zh5>-}!SV0weFbcT6glaIo34iaT@}52$Tdj*`-Gn7EO6P8 zcme>x`Nb0R`6?MEE>|^9&lXa9vU}1!zERgmBX0dq^|CE8Fx2 z-yR=B2(rTV{t*l_9^ZW*tJy{OsVhQJ7P$V* zRs7|@@~il@U;T@C`J*?mTFvn0_udQYO+I%0@TXqJr+@HyJp1%9Zryqx|L6bpb<_=l zdXiM-l1+#oj3`Bk=ZaDqTl@PUQdrFAI6paYw6zWBq715K(u)MbxJ)^38yn|TTd2jO zI7+o9T8Pv}xDAwx%NrhH%wPJA7b9ZHcm{I`^%1l7r#O4<7d z0fXQxgv65}P~pVAB&ENDr;+oau-97!0Ryd+^#M{8hJ8v=@OJZ*F;4~5g}g7M4@4@D zP6D~ICarLJlTd^l9_6pK6ZwgXr|Glo?^W-8#Err6m7`#?ef#$P#5_}L74}kF%mTOn zI-4y}lp3aClv?5D^H1UZyN^Qdoi8dBg~GGXUc=_*2Bwn|Z{50!fAL#?DAboyPYi#( zPfizj@Zb?PHzv4w^J!eUa)5hx9|j*P`58(PCI7$POuTM5X*ye~X&tdsQV1nt*viwF z$uFI8na1UVv9#_%*1^Ev^u5kHe;oAJGp+y5Q6UpXxyh%_xx4{G=Q_=;XM zM1(?9v`Il43)=z&2%to)=`-o*7DK3;#vi5l?U1KwJSCVC*9xhwCYu{cF;j}5bP)bmzxO9oY zkMT)lXrk9Q*&BI1uU*;3*2W|*JbOu6?rvbxDNB5w7?$edsUY$&s;a@GlM5`CbuTsD<&V9H-~Zj;#K~zD zo}CwNUcncB`m@-amU!>>J^c2+`a`TLPH7=o)2y7NvizPbZ1%2PMLC&*jltu4cdfK; zF@Y*4B95g+D#;>U6tVg8Dv5%NyC$vz@`sS<%$Wv3NlOX=JC!Lm1|UYE6edN1vecMP z3QQ*@%AyD~1&^dlg&VE4E6_bnO=CKpgeIqPXjfSlPBE`RQ55*fSHF`EK7GO#Q*jv! zyGp&Z$w>tpNTn!`{9Wy?w|4Y2WDEt$%vb%+D7xC*kzm@&Wj^z;8p4TF&blyU5O3$c6YF`xq*|D zb6hx^gihc)i&cIx**cX2&)&F-ot;f+O*lEZ2%Z^t?>)xb@7~8#SNC!2_I>>G-~6(r ztw_|)E5j*^xM}x3%gW&W_a9?1zrgkD$GGwAb=-Vc zH937T>8XX##JWafjN0W;kw3<;dGL2fDud;!kDYm^XNXC;6#pgje3yweXt=QI6ELE# zouYMleZ&B^?^>_>3_hsG2c>8R5rsHQq6ViP&oJ4PCnlP`XPTPFCcBp&<#tMxp3N0N zNtVK8oVr{jpBbYlrwPzPqWxCp@Uksj%L^O`lFQPdbq}G<*x00y1g}t z0|jH;(miD#9Sdi9ZVd|tK}qto+6*!{4FZ0Q}koM16K$Liu@6kM;h#-IE7 zpT+L>Uf2nG`l%Oic({c(-#G`!PP6~aPkaicR(SO24FC4ueG9cgqBh3a^-2&1=1?&D zliNBt#OC%60O0KLL+4SWP)w#SY2*`ll^C2!G$J=1O$7&13F(M3A$-n^Y;RFCH$HiJ z6Hebu_`frTv0T+yR<)CjuC3828%)XxbP?lJ(=_4Q_+?dDWN&V6pe!^lF6OAJDlFfV zA{0e|qR`?tOa#Xh9~@~*AQ$#k-;$T4Rw)0CX011jqP)$PyDj*h`B4$LrD5YaP)7< zuWF&KztO6y@c85$*PpryMG7~bxq^H5Pr{(l7?V8T!SGbX0vkUxnuhW4;R$xOH*xLi zAr^}z?!5mvG>Z4`J;ML?4}TA)VHBkT8$wkzEnx}Im|ed&Bp$HN zYo_lw#vCUPNY3?%3$0;%t>4qh3REH6E+P{ z)dp%+qtFVQ8xy2JKP7Q69qLQT{chvoJjTj~NGh=T-=7rPij!p2eIo~$oTGOXRFT;j zD8~wr`#5pXD(P~R7%~&5^yxyX$XFf$XAdnqvowU@9gr2RTBdYFIxLAwN`~iglMH?= zAz?c;3Ja%R2AU1X#Nt3oFh)&o5mcP$K0H8#Td~v2509B%;u}e$7P_Y?NGur2G#QHQnzkZRrtg!pR^O_AU&@E6N}W3 ze)I;e93P;mYkcKv-^Jt8i!fngQ3&SHym5qnPrD5T;H1Rv;US0!7pEs!T+D2-T23O3 zNeOyWSQMAZFfMBo+RsJw7^764RutM%-O|RnV2Z3%_#~JCG<7n{@zZ+-!;n)xgQra? z>rJ5Tu&692q3G9CfZ0H6jmAli7G;6uVu|Ub3@Sa|cdT~r%f?_bog^p%b9;$3>>`3e zoJ#DIKzZ1hWV#n=OgYVvgilOrlq_?J{XtrwBxzN&IW{5i(^$a(bL8q{is*{MT6@fKb%4%+yB+M1%eI$3WJY|T-daSHdBwZ)n+?j8=d#Kh`c=MWl)xLpU zZv#cW<#8)t^?9<5QDyDg@yRE{Lru-PhHWikH8AkyHHaMZheur(1OBQqSQZV6qQPWR zWP_kC*^Ja1Oe*)vL1iK!l%1R(z{rn6DMDFjG~(Hk@s>MkAGxAoOaq0o19TwaE9ZrA zOkkBTB-6=$LrDlpa-oxC!=^<6@DnE=V2i@Kq-yQB$0{~AUZF+OFqEWiK**(fNKJV} zNrj6Wb^NVjLs@76`%_Ecku$!aRE(A)LurzYSDNPJTO&~ zK`}oU9xw;%OAh(2Qu1#~UwfVM+NGp7xm&a#_ay2&w}E8z=uI3^*V?M)oO{^$wS*5loP0; z2>UJx9Zg*SmQtddUNy!fs7=@z2=p@!6aPRDl)biWphSVj#(AB%;>!+xOv1t`w8FG3 zLa{%Yl-SzZ#AG@_QEHTBfkJCc$^skHX}GV-vV)+upy3F_ zNDKcq?Q&xf*>U;N)A)S;lQ~k!9k;|-FVZGGA|%yJo2CiRS~Q|%!Gs_|ccZu$1%=F* zEl|d%lL-LA{RfZn-tD_k3i#}2Ucq!)M#_j*D9a*JBv}qgT*GCo*98%y%2H>MklpSQiDxMefOByo$$0Vi=4kPswI-eDrdpwciq*$n zAdDLd_B9mi@?&e0y+<*1$RDqdQk|c~&@uLT@b%^Fv0g)$@h2LhmotBVc5+4Rs~dx= zYAh9;!-%1SdfVERO$L@Z{Y=u>a^q>1ECmJ$rJDm zlh(GeDa#_^;UzN5mgypvp;;VjDr=ul4&{5#+}=R&kZ2eur}F`$L&`voc7m2oO#%sK zQ>eBTOGo$nL7SX)N@d{n{L{_{yMu!|cB$`4!~%xY(`b#VL!S~^4pH~+xll%xKL4`H#WP-S~FO~bhV@Z1_h zx@*}qwz*-G%h*x^ORt+?5dq)&#&_`JU-%KsE@t=#|K#uEfBakjGaj57OgFcKch1}I zypOMc?K>_Bu$XXDHkGn*Ko>=DnU|Mt=kO3)JG%fFrw{I-scYz>gq}=YER2ihQ6Rud zGq?6U5;NrV{bdoI?sa6bM5*+a5W!G|y$Y))rM0E&X|1s_Em0N<+Zz+??`~p$ZxcJ4 zQ*3Qau(>(KWHNEFTt{O$H-u>#V?R5#9z|tgMG0(v&~{?)5r3@$vJU`X`J-=#<{>O; zOOt2WH}viVcX-J7dsDS@OGx@**HL`-lsbS%!8%F?VY2CIGg6`ehv$XspnevQ#Uo^a z-W|B*2r7R{EM!U~FwzxN>C=Kk&&{@VOuV z5&Y@b{{+j$Lfr4}vl2o@vP;**_~pO&OZdXi{dv6pz3*W@yMQVuST2@WIuEAWc6gfP|im_x0%472Mi2c+dVV}Wb{|VotYmj-F{nIgmKfR(tPq?3Q z8KI%xbEQj2V`oFiG1AzV`Ti4@bAVjRw=rI8A%qe*0;yO>n)|5LoXg>RpDjrk9Erxl zBkfgff?;xK{TVF;Ne;7$$wnLwQodWM;?PHU#DyJ7aczl!LN-+L;C-j zs@$Z}M3De6wLZ&Kx|w2Z9H)QxrDmP>wV@zUl_BPU&n zgx46xa#clcJAkULBiEQ)Zk_#pH=P3jmRG_q@`ewZyN4{D$`()3^^Y{9lqWHyvEP!F zl!KhiXlqC&a|ja7O-FkqVb{~Kc-(uoBr5xW5AOc3ha@fu14gIZ{r9wHpJoVk>hn(+ zF=>4Gc!sC0?L%_up;X)RM!3)~<}0_{8xO@WWx z0`o<5Styjn1ckE8=N37LsJkMA#Yv9&pI)Z!*6YBi0e4;U|Xtq7CJ zBp^GUIu|F34M-_$Y*_QQRBKFa2HfwIe zb7}7K3~>YpSR;r$MdDDK5)&K>bh zs-Sw7gSB;XC>~QZ@D#p8mWgSbdF^*$oz$z=3Y*gj=F1gs-@c1$SC4S>`KQn{4Zij5 zw_&t>RecA&b=mcgIlkC8_(ak0<*I6 z@kGFCWh_!<7`jkyq1l8Gd33yshxhK`=5sIMrH{Rg*~JoXeCJI}3Wep$z?ceb45m&z z#s6JdYOGdGEW`X~x6PQmwwCR%Zr5o|bF*$&YR$*I-uUy$71vlu;WxFxO4TT9ZBdj$)Rk zP$CGhctCxTfKEB)+!@u6MOVo`4a;erXjp$rDx@!>6DW|xzxfh9n@Bx~e zCz)<^7VDRJKW?KqLuf-M+C$^qg{1^t7Xs7!em!a|l6o=*ie48SyC!luTJ}LcqrNFv z>p0fzPqk1SgWa7;F!D`)S*(x%03ZNKL_t(!i#rrr7K_T#(lVaWB2kCM zZz5oO{{Xv(wz)Zf`~ZvD45Ulwa+)+X$~8JMl*PsNp!$Mbg)WVI{{B;>po;>!D1^Y1 zYc_@242w9XwZi7+6uVnf9PV%8aCZZTdz;wX-N50&7LE^haCES3o0^>|jt+KkxVMeH zolR_SZJ^XTP=7qt$QpfWXr)m%HMCMF%BZ5|e^0sTdR^BcyfVWgK(4v{%2&VLru?`# z&xSi#I@C25iiiy24vwe4!?_Sed|z*$;8od*Y$7V9u@kvzzjx#AQAvyTw7aTqa51~U zm8*w1I^0KNYCL{?Zm+wx%~4e~38K~tF|J|T*xts@&KBy$Ii7#v2DY~>&9N*BurWB; z-@(&QU9}DP{yt{23oI6O^zm@#s7c+pmF*rM4W`#btM~NLVDN?j4tEXu2nNFtE9}bRrNx1w8 zg5IDmKaHcb4asX>Mk;ym+`Dx6FChV${EWtV&-B6EebloLk_g6pP9vLTW`pgmX;em( z4Msq539D6&RnAnn{UUzjum1)<|M?%syARHA`_>z%7OTPOs4jFu8{0ZK z#O~oS0LIC^J6O#ZRt~ywi}QYmLheyWSLU3OmeGQwsilm;N^2+RlKQXYN{j&^P=x8E z#QyFku3y=+|6JX}!QLjW9PMI%cMH4Q8`$06us>X7;!m6sUswym3E11S$zF4AKRWANBOk?oXue}zkY$CK#Dq+jryG!!VR4D?-2qn;Qil-+zR6-n@n7vJx~@!fallF?Jcds+vd@6h1j# zTtmu8r!&{=-s)SPzI0xu51!LoMRrf&yv`SG%$(0l$gOcC$$(&I7bI+BjI zHa~ud4dI7CS0gdFkqx-_(#pij5`Cl(UeNTiiRO9IZ_PPUVk5A zqQ@@D8@E84a;7~UL3k|$#3rL`WC@~a463>by4#7#o0k=pXpfNm%#)R*LDY4Fi;GoK z1kV>0maAr9GC?gcKu#7VyGr^DNrwx{_|cS2(D;LN`P8?Ak=^-t0w0#qL19gB9#!#v zI02z|H)nL<8#9rjHf634!5QoGLj%p=W%$0AxQ2cg$IAP9`F7hq_;RjV)mS>!6o2l_ zjMK9@7Rx#*7OaFM4>mP24ta^)oxL5LpPb{Fn>TRljd#FAxcq9A@1d#c*0mt7m?j>L?E^z(lAZRXTQirrZz$l9X+uKtdAMW7kYkRnM zWe?Y{9$UtxYR$I3xfs8K{@|$SWVks;ZrOQv>bL9=V)sLL(lj zE=@9B1(r*j=QlP=kawp5P!?JgWe9Y80<~%oz)|5jZHW5|;*rMIYjgLQAtgO|&K+z5 zG8>5}*_$1kt7srE(Rw8M1m? zmeJf&OXdMDq3923ulcGrww@O@E(w&92&E8;>1NEO)b{i7)(7Z7aFkM^xgjFxqr;sq zY9$TG+Ah8R58DQ4LK;)a85_d1&v)8gXhdQ-)=DPrtT&lX?;j zi+={BxBxqt?eWP%>IKWxKpo!2Q&vF%R7k zG`!BV@-n7pql3%`478)DdOhcuPn_~bc+@!#En)U>sn;fmOVS!TzLa8YZBFALAQarT z@R%=FNh420I6a#?wY0bwSFP&cygU@JWsE5%1?p7|r4?3-3h%!4E}F&`%e#k1XoMWF z-#Pi=&wc{G{42kNU;7Kcf~&_@QRo6%TXf>Z=bpp82Y2wbuly0JRUK5y5GF`b&Y6g? zdvpc62ZyLuOFX{!KI*E1(pD`kns_<{$5DYo5iV3GNhpQ|eH)4FWD{a<)R+u;7-*W> zE=4ov_`2IsRM^>?;9z$XSC98_e6WkHjftQ|DJLFNI3(P-Nw`K)*ycz2l_|1Ccu^FX zx}6&<{cP`px~{{{O|`1RvH5simPNQ<$t`q$?dz{4Q*k*gLt;3`odOVD&p&ldB(uSh z3Og{APBz8guw2hFnau!%e@(Wm%Wl6+=1mg0Qwf7??HszJ@uY!gM|oeUc9^oi$Jr9O zVd?otVo(_KVqIH=&1AbUoLyHECZzTrjswnM^y=<0r4-K3=eU?%;OJ-{&pvw{XJ<29 z%olD4j4+)Rm`*3Csv1%V!QZscJbeW}@spp!^=mhvwZ_rWHQc!QBDVMUaOa)3l56U{ z_f8%?!rR|_3$ybJfZ4_rkAU5D3o20My4nwibFP> zP-mZWX8uO;`xFc_{r6(f7K^%G^0hHxi8qy>i!R!P$cI)G z&C$ZbCFPQpDJ{$galb(6Pc&-qb4$`L9IH&6VtLa~m(I@@$*sRy)mSX*HH9>FPV7^+ zZTTxXHI5UQkU5=Rw!CwmG!PA;27NmsYbQEA4GWLZ!XJIiABGyqx`t-xxTw=Gb`Yw+ z6iP#vzfP@D@t7uu+UVnmMsvPsaIn7-r_W-Vxm;Gx>n47koX&Bvs1jvS;|powM==Pw zyF)a!t^BHGB?c}wKAoSPV*ltE3XJK5@X=Rp;y?VAU&62b@~_~<=U+gfJ(pJtuM3Tv z&)>j1chB+WYu|)v*ol>pLtSDavwM66+k1PcR!f{cxChf1Kouw^lcZ=RKW%c6D9YZa zYH2O1l$1$!Fgq!)u;ry`ZBc8y1a?LdiBo&~zGb1YwNYY!cMCgPQ*2C2Fq=>)hQdra z)XVwFlx2zC-EFYpu!rI44%SmdiRf(yO?B<0w%yRl?%mk^6)P=WTGXa#0=3N;#@Al` zZbXMjwH|?7;$If;v zN+{Ga{dsyciGx|Hpm7Ut9SF)=D({-^Mw6gxr1d0)W=T>TJ^Gfrh*QU)P@;sf2_=V+ z+I!;SVu6Q`PC;ON?4viK6yedM)3hMb3bi-v6dif9IK{92`hSe8SDp%ov$3&-D_5Vv z^B?&rb`JJ%_q}%lDoRAy+}Z@`5*M=zC+Y0WftA8DH?HE@=dR=M$^rKFcQM_VpfQcR zS5pM%+LdkW?o2V8SEyDECetFRP=Xn#fbbH52PZ~g!rsn@R;gw*tPjdgc*4J>C)x4g z^@!7xG7X-T>eV?s9AK>U<>Rr8iNPGt!;RMye{T7JFpZtwPDN-{W{PR)dlythzp)1QFyOZ zM98?nk)je&OQ%2s1lYaH9}%J%fly=%{yI75kECK!^vAJ0iSD=E2x=O}*|B9;TMhjZ|ilbUV%uLfkwo{dUX;X=;E@r{Vl(efsu& z5Bghnj#~Nv!WU$LP#=8JPCDF?Stn*YD=WVy$!Sxi(`IR8k|B{%e@OPQFvJ zPQh)Y0okL+7r1)7;|VJuQ1Guwo1qHxMHQZX!wharpsQROgjCT_WbbefrfE=D6+Zfd zAIJUMxAD?TSMdX%`~iIKv!BB=Pu;-Q#uggWIC`x8`^Krd`60}e!(;r7zy6;=Eg#^w zfAe?U4xb8zaxtA?=kN%V=?3Prb6lJ}f-yk3v6U%s#ofc8PcLsxiGn$*3lAshsV3~N_^<_Erq^Ra4 z>CPtK$3lE(*UVRgITF z@+`Dg`0nesoRKDDW1>;0DbCK8DF8jyvzagWvtq zZ{p6o?}4eny?ghuwY>#hEU{Y@sOtvj=NGv5{zI6?;Q5!H!~1vcN57f1UWxcA@!i^U3?8kLMp z0O5(=XK|o!j6qccS~VzEwQF)HVGgml7o-HbE))vZs8+R*M3;yy@RXj>e{==^+|nbT(dw^zrEu z$45KRWD~uCu`~{j`(dUrI6GfBBSt5&YB@asjF^UwWdTGg(f;9{ouHQ`j-S1XPkiDg zKJ%aa3O@JgAA?pJjWMX|3ae@btqX@L85q~pC}p6U21+SR$|?5u4zRUtmzWK!a9BG> zN7&fj0ULwa$s;Ug=U^!4vUI)~IwS;-XhR?czR;InejkUjfr~8cWgc%_p!QTFd%ZLN zEV&3x?!S!*(7rb+juaz}rfI~W$GGN{?YV)mSS$embyYhBF#|R(VKxTZEq)`3*xcHu z@jFEpllw-4a> zLqa;dB9);pEm}+mGTqv0_xZr(H)M21_j8psirx#z{+@3d>@d)yXi&L1UgXa+*jh7) zfuj_C04bOz?$T{ZJw3-e@7w|!gHjQe%O$F+ z4wLG;cOT)-orhM0$PHDdlLGTadr*1n_8FdgW*?JD0dfK;%KLFKf>G#d#c{|G(&-Zj z4D{t(qV@SSG05(qRrMYNw;K+usRf3-bjJ9;GJn zHb2R_3F01n_pL3~Tyz0lOj95QnR07Dh1}l0r-Zv44@YVBh;*R>$JlaBT}@|HkB!vt3Fc$u;rhB8`)hrq?uAtYB?H_hlAzod6QxQ)cf z!i#zW@|Xr-2&EYtlsbd%B}5j6JY;e>k!b*_=|M;aFZGk~ZK)e!8Wre92H`xwj%{c~ z0s83C497>?AY#;&NzFXN{+bEJqG5(6h0Up(2CW@%M(U3$lpUIA;1fUi5q#>iKZqO8 zK8+v$vCre$m8Y<=vF&z2fU2s&AWTYa4JDOwMqsuX@w{NeKtUR>z40CVy}$c+@TGtB zuTa(Yye(>TjLCG0YPrPu;|DNx11d^rr8Dy}r-mlHX-If;<$EK>Av4M;Oc~Qr7?D_) z^!@=2C$~p#Fv-&7rGwI8jET~n9GeR}4b$KvHF|5B2BtBnstQUgpCtng%_0SL*op9; zyKEAZ{P<${vvL@cNe#BKX53l z?W(R_-NC*4=O~H-%jJdj&2rDEQU$8I0<*E+J#N79%F925kAL)&ST5)I`Cs@Yy!H0? z@XkALtzfAec8n7;Y-o<)&71BL2;55RM`A zYUuaZl|YPs^s4JUdp-DiuJe#bU5jSV!-&ph&aCnZEdU-q4J-#Ykl!7WZVhmF%5j^qNf&Jfv0U`&#G9rR1 zwA}%9zgML2J|)Q`bVfNfz?+zf#F%rV+x)y-UJ+t4B+(iY&z)!h3|b0Hf#znAP{63i zREoj_$k0w_+tU#^G)^KZAj;jf;t+R%4w;%-mZJQWHBHunfI&!TX%uL7Y0!v}+?u<* zw?Pr)$i7Jl4?wP$g;4v9J-Md|8=4pmHcB)=BO5q2qIQ!r7D;LaOzNPo@o*C(r)IrI zqddYaYy>@#kthQVPnz1V`|xCegM%$Fj7$1L)zBE6&sM<|+!%H{3o0n7jr~&Enon+R zZ{VkX=Ev|i{_Fn+*RDQ|rmn($xmYgaM4DlXBu}ey&#mp1Y>-thRWF$L-J#ypTv&Jw-Q%oa- z0;HTYke~#ft}2lLi;O8-__B6nAH$0;yn@ohx+s&HoZBHhuIB%$JRA~97VaJp4{Bg zFpM3-t^Gajrk{!CeG06r99GaLgAnZWl!Vt=Pg9*YDh)@Kcy6f(h zs@!<|CUoGIG$ue{3wmJ*7calH40(I#kWoN+?qU^8qK#p{PL5HSx^ zAI1cXQFti#Q^SS=NN>>NkyD|L;Mk%GjtCs^%cV1Iwh$-c*D@$7sN{B8U*QEFO~A%Y012ZdqSLP zEvouDPPuQ&d_WzLk3Xg;F2I?04F&p|Ax?6hR&Dc977b_85GvKyU~wm?s6%u^<~=E` z>>C@7$er!GDcK#3bFz5MR&XF)_LcW81f?Xc-^dw<`eA~BBry;vhrC%dXF9QaIrGI5 zw{G3Rwd=>&-`l~*U%81}@7~3`@7)hCKbdaeJKy;xUjE3(v9-Aa!%mpQBRa}AAsXyZ z#3=L4n3Pj|`iFiDKl+)^qpoYb`X^t;>|%y*eB+Pt|NQGez#Ff>16>r@+1=@-ciWx8 z6}GmfsOko1vlTWs3KU8?+N71eE(_&+z7Y3s)=|cvBp0ruIdc!qY-m@tj|!a(;YKtM zqjJ!?^XK7uh5Pb!HnfzvnR$H;G=$jXNXyWEapy6QXp;Iwh`LakG4!^ap)OcMa)9Y~ z{i>>QR5k5PZsXvcUHz^U2?j!wFpms#QdV_(YR8TLlfJW$rgf&02$Fj-4#6qo)l8jV_)1A)av8?~R45rI!znfp>H1#_Y1S z-Zvldj#WtOn2J#kdN#DXG{z%nY?A8wj4y%EJv>=pGARI8JQ=o4#_Xa>0-AL_H|wXI z*;!0BN*rH3#83aZpTuAOOTUh%u012@OB~RNx@l0=4VKjk#xSb7ap*|&7ECLx3&Nx%+F4+xHz|$q$ph6VJKCkA_B~IqUe@QmSi%)vAKpn1D=dXgF|{ zZL?HYb@)3=W3aKm(1k^2oNAgq)W*@<XR==Q>c=*cmIO#e@1Ncf@}oP!s%clAo(&7#PvF^v?}PVS%J@A%b?)G`UY@b#GMM z`O*~cb+-9*Iw?@q26yf}z{$xuu3kC7^Upnn-JLDmyZ;!E9-X18fq(G7{O|bgH@}Ua z{l#Cx^EY0=!NIYZs8ncNBkyxI8CL@!dQTbGM1T5|KaQ%d@UfSF5T_@nn9b&xZf)WA zySE3jdgMU>03ZNKL_t)G(A)2y;`m?#Rby|4x;7x~RR`@ot0<$WT}J$ed6?4GH;^2h z_V>`Ghw>eb-?<#cfLJ#a>!ZQv$KOY@8l$=v1Rpq?ztp*E-+gF>sgzenDi3t_m$0-a2}IeP|pZN@^3SH?snJmFb0L+KKv zicrT(FF7wc?S*4PjLZZeJbJ@|7U$oih*KI)nhQePlOZhBhU7q@3uB2$gn*nTh~z%c z`GO9G@yR1J8e-8%2?WVcRzl+U>TTqr4yT5B83Qu#k12`%h|P`&{GD~AL<`V2#E;`d zzkr$~%?!?KqX&82$^Er+p8@3%qSF;{Xv~8rIUWN`{VeHjL(ugA6h2m&q$}|Bsnv8& zq`K7R2KHjsUBAA`5TVV1ej;hHKA!VHf*B0D5RTLWb%>7iu?W?LhN&CNISz~OuE_}#dm-1^G_d%Fjp+^B z>&C`7RE*;Cs8Wt58~1ONQlZhb&5jOenN4Q42(9ZHbz`i={&I!oszzNKw*$fgOw3H< z80lU}?`=(qL1^As=6g^eqRu}*}7>C9< zP=y9fi9$mND4{3_N)=cxR(R)~_i=D|f$P_fad5DU+js8c-FNSyZWv$v^4IY7Km0oO z5BBi6pZYvL^CLfomp}4xFo4q7drc|jnk|L0ETEL9_BAMqA_=WqTRZso|AW7PJ9qBm z;iDPu-hQ|?_B?pJKv`IMb5Gaw2A~${1hfL2=-cqHF;~4@r{Fn8n1@F&5Qdl-JhrhJ zEO>?+vd+9SG(@|kI8Qze8BGaXr%bm7X&UUQC~b;{5U*VQZt!zlqv|SYW64fdT6cw| zfALx9Lc4uc&gQG$6xa&XNP2A|2u75yXk=)P35^Yhx*#@CZg8SBsF);sHXcovIn)mW zSso);u%JlLcvETe!pj~~lC0&jFDDZ$DQoKCAPP(IvO%-Ko-@@kZwwfa35wG~&ky$r z&_gnwTwt3Yiqk6J8M28185!i7EU_ZG8w&tQ5x``1zw5>%kQ_6o&mK!Y>o9dy7PQ_? zJ4_Hcbzp_y4ccqz7i*DB`P!gGpHKk$Ij%z!fpvkEdSn(`@7qBM>wWMC6h+2xbh}=U z^F{z`NoJUfAa@8ab6t$YjbZO8(Z5@N@2BJU@<#Gy;`|gRk)&9xnf2MBtSud zVZcyOAm<6Agt4cmbj4erBibx>8&kSAhxc;2&PhYbEOB~<1gBWWCzQv?lX3Td219vO#yJcryXifUz1 z0ncrCax|ol^tv=AhwI>x9TMiwBzBUNJ1^na!;l3B$El|`%IpeV@S;4H(qdmF-5>JD z)HwA)A`bLOf9(Dqw@rGAA`>i?Z)0j}g_FnUI6a-=`t>6`d*d1o4|eh3!3pl(djv3W z`uGh0$3OoU`2BzR+xUr}`#F5%V;{p0f9gjtnUvPVR~IM%C|4sGHYof)tv_$J#nax- z9)95$e;$A9fB4(s*;*UdYP*mP02@y)u<6pNx$jq8%g$0+JBtw;I0nyX78G9AVK zy4*uFtP+~%$IcpNq@q}h!hVSX;X0N`m$7&2oO0D%?pA~KuiqMU_B42FcZ!76dY5vY z7ugcWZ9OU*R8`~l{cMbiLSSwX)Yw>_vYZyYtsqu5lPZGBb)CrAc>Q&@wY?j0yFS;fRz-b36*rxTRWn#UQDfEhllo zG))u%3B@3wINln-w@2I|Dv&;8{`e`I6h=`5i~JbZ?MV7YNR_QYV%{xh_iU@yj>>Og z;^wDmrd_DZ0x2j&fLao&qoC|OSoP`f=MURuP?mhkKx-P9zDBBV`W44d9Z6$Nuw7>o zI<&(whD+NOT-O?Uj^tdAowoJS-CDi`BP2q{P%Fe&U3Yj)d?3?1!j)^sc>3Bi5nczQ zsT(W%>S$?oV^B2)7mFocf9nnW-tYW2{^0k1A19Ab;}Wp@nrv=jb7v3bbc&{`aQ5f{ z>gB=)Y)3aEMM5+n4tR)^QwZbOsKBBdMOnJPRiU`EwP?B^>HR~Pog!I~ou`&(i)@g5 zk!xf)3+eU?{=AdeyHmPtE$0# zvBY9op{~83jzU$}n9oISP-jaAiPxvEjQ&yPFwOOlycGAZ`wMg#SqQ{5DJhD5(O z6Rrs{IiM8|#SrKt^?~wYXHxm)++;VE+Jks;WL8NpH|LBw!6|9S^YHXU7d_wn%28P3jUxR@_dHwORrZ~Zp@;CKHO{@o`(g&+RW zAH|C=y^I@AKj-dy|9t5{WAP{)yZ>L76V!DBr3=)}<(1AB%O+4Um9mo2qe2^xXkJD) zF+I7r7nLCN?tNaS!CHr?tXrxdWRGOLs>?QCT}?-q-NahU2#iOwIvFSf4b2c^CikN2 zYEVZ}@>3+y4_pXwMM9pcal1H;iAuq(dY0jaRt+LGHs?PH3bydV3AJ+O-NqU6ZU>nY z=%NrkfC{-ZH};If1$N8{3T%gb7|7Y@U9d}T5NboQVTtBm(pWAmxFXWihz0V4s7n_1 zU0kpZ^e}f&TDtfrOpNrx$Hi}?b#?!1d{e&^fx=AV8WU;o2D!rQNX&pIWG<5yZ^ zvblxH<|ZbSDVn;%#mQsLXJ;ZmM%t^Vrp3akO+AA%7cR<)rNk)dYA$GHN_8Mu6h#39 z?N%z@1VmT-oo|L@!Oj#>0~Qj^5E7frjQO&{#e9Xus={Jbp(u5@r-KnEtiKJZ)S%Rg zML1NZHds}aLtz-pm2GMk3){$4jvh!#I|Rorv#zQdrg5L05!6M>XnbzxDD`rYvy!Yy zA;}1!(6Eq~50kYWWr!L@WIi^YoIg#;U9KpVtoFO7vf=FV^_6}RhE2kh;LybQC4P6V zMpEcvgYO#_r7R-C;z&6e1`4ILObMTYsvIZGVRX!>gF+gya72h&c3S*}r;HM$@B<}g z)iTtV+M_V(zTXw=yU>j;GKZ@F~!Nh5kiK=IkDyE5oQcs|65z=ej-E|r#dE+$~qTirb}{_F$zxZ zZ;a>(mpRw)gu4HT4^2id3sZCz>0-q3v!Isgr{4`Ufln-jQR2jjBCX9+%CrtmQd8GJQGks> zSu3on8p~xB_GgIv)ZgvsI8>!s)u{o zaa<|tlgE&COb`W#I5bI2$ z=q71(uE`Hgrn`E<&nLy8h@YMBV93LOx{{6=|Kfl2FYz}5%c6N?G`u%@{ul<`ZV{>a0FaO{taPy@Xak#&Y zfA1H5+3pQc17oads4fbeoStE|T0Ie6_5*$O4*%9PGs(|*V6ZnZWa}!*v(;rn*yhEuiU{Fcn=zQXLDJ5U_X?rmL8P)w%bHt-bh7`Ft5pVfVw zG}h^W%nk#a7NL?p_R(iq!r307A&Qeh|4b-REL+)6M07^@vjje}ipj_;o%rO|G$|FU zB^)E*{wQHB0R6x(Mj{(cK!S#ZCMk4wZb8&1_NH-e-S$Q($^y$(g*)#*3Ti}E-C#bi z2W!>d5uoHmw&D=AZm3*M$qaV+lr61wOcK^P$M-(OmndK_>(A2ndwoI)mwC_LVx97_ zaDVeL1Zl4mK4{5FcPweHyGEB%XhVO1y^LFSe%zy#;XdR>hk)Jv9ZaWXP)0gCIgi0o zoS$SbUVrw6g}jwUwW_eVxWN4U3{6#`scNu;!2`9%^L*Vuy3oR<-5!W8tOtkOX;8%^ znKTte0b?2=qLMC+2h=s8six1qysCB*PKd~QdM|{cR7m+tgq_{KOre4O-Ax?rZ{f

7+!{*agzMZUQHJzF6Vxe2$C73d>c4y0$XUmR@F?n#MOX#wy8KRkbDz zwE(o}Vg8uoE{_#&Fy{|D5Nxs3PwgBU^Gk~0OS)7L$D#OhxwKD;lKq@iX(%O@$#aqK z9Zl$BW1$_r!c!UJ<0eEKgt8jRVVnrxKF|7Gi9j=qh?8~;x6!rRi$cVt@9&S0134BS zQdUg~NX#q8`PYh*P(ouYZ(j~G6R^x*L(_o3p^5g_BOq;}84deRuK8RnD^yj3!^1u7 z?QP@WU=MX;aCSDse7?ZhY>DN3k>q(&gz3fxj;g+O}f4dAwsZ5%jo3u1&ogw_vKdY0+C5R1--ot|KF zafu1mVBk!)eAiEB)>7Hf)}`-T_UE4Wy0o7Ez-K}ulG>m!!~jpYi_6>9%#KyMK?h_% zXh1h|8T5(n8(?;NfeS5*RZ66onSpXrU}I|wS`ki9&h0)78!Rr)@Zj!!RI6IR*SzqajY^I`XZ@B*~un%eR(rOFKiMUp7>c%w*BrU`aP=Q;rU#tMtLd_ z(#3ia?Pq$7HT33 zLHNzY{T$i+#{E(wXn9D6kb)ZGX=IrqCmRN7N=FIKjMLwztgJ~U3v*YvdxA6iP^7r0 zi^%?W6agEP0%vD)y!OUzOv(b!K63^8d)wIEwf|hxB~H&SaO zZ4ryMcXrSigIjODdr6JR?_+;6B=J0mQc(X6NS_x=XA^+oeGj6Z;aNVY%V>C==+wG~ zWK8Wo0tFlDZ$@9|p}vYooKH{v(PC3zy@yfX`>&m>qmA~eL54xvGL(bGgP34m!b|WTG39L$TtOFWBl1{f!giHSQ=W5#iGJ& zQDHt`VO2LUullJPs8lp3!3)M-pstR-}`*cA8%qSf4ZqgP?3nKm^7 ztr7cCi4vzrOhWVH?kPvL)>_$O0Z1AI;lm36!0G86Tbm^|H>cR&-^T92 zA&#$KMY%D>WI9E?TA^AjqkOHuPaA`?(^DA3m`pUz&ue^tzXp&48K1|-$gW(;12idM zfQEbtFBJxQ_ftFio3+EyK@Ynz0z)H*id|H$u6#erk8j|(`GYWFIzGd`TC7j9dSt^E z6?!=cex=B`eMVO+1MmvQ7)&Qcl&{b0kbFHN8R%0|$1(%w7pu6A0>^qN${1g$z2i!x zVr=$1JwiY-dJ(H6hkG9`nNy`5RFNo^3AjH{GKAcyZw8Xx8$U^6MA%x;txRLJ{8uJNRUdFO4P%mtkTWF0H znwH$CRK$_}ORG*zSVZl88y5QnY%WO+Tc`bgneqA9pS6O;NJzc!0dEy}L+92N7=){8 z=dW=aVd*Q<`z9-0^a1An30qgg(&fzD=V>$4e2hr|eU!b?z6qD07=B0`cd6-bV~BCj z1EZWw(9{i<^A#3m2>^KSty?gSS??;IEU62xuS_>T$Sap+LLsv8Q3?MWE36{Xgq)ik zq-(XZ{9ulOm>@O%bGPSie&M%fIludM%lWcAp z#u_>c!N|5H0Vs`JoDa^_k>DV4g^)I#A*TD-mwf` zLWuM+cAhKjg>VR9q5MSxwY7sdPUt7T(TcQ2gnXDtDv5j}1u`IgE~F?>U@b(dos_?B zY6GR*@^UZ>RT(wLh>*@L8i`i1fs^qHa6~K^LuZhC<-*j8i^iV zy8_|{tEF#ttk47-6T~g5+TcU~>MK46C;CIw>B~*(M-8RA1b+HZdCBzPHSaehdNU*r z(4w_;Krci24j9ik8I$kv0lz;+90^#j>b7o2cbyeTACkjyNCPR)j|e<0SB)D?0Mm&E zb-JGjpB<#Tc$A@ji^VEhtq?(%1xT0h>WVUU`hkbHTL>ZnNj=T2+c%&)9CNvp_m}kB zLf#L4`jbdJ!XYzm!pYe~9hQQ;K#MTlVZ&(1q)VR3=S^Yi;sa;ApehWwj6hfrq){1K zQ>vl`A;alWAHz^u2K+R6$qq6s>KX%L;M$b~JbZMDle0MtGs;psb+y#lwf!tcbELf5 zX3_DQtgF8?YBRKqHg@-eo`9w{M(=(|y0{foxqo7`Ht=U%Bwv#1mIqg&4jNb&;(~sE z8wp7hAu~VeXyiJQU*9$6HL~9F_jt|cF=~1^62*H`B&Xx|B|Wn?28t9G7fUSXtB59e zb+I8@Kz3dpWmU-_A{K0Ng2Z(N(i$M`LW{8!HD=)nCMHQ@InvX?JgiP`2hk!UY0Obt zC4M-b?gL}&Yl^)awo-8k_c%0CCN6ARN*T~Fu&Au0GdUAuu#T>g(crit$krA&)N0mvzX`oh9ACh;Hg*H$UZNQl&DZy*YQ{$J+au2-@o z*%Dgjz9Y`b%&P9bbkD%R01v|;AtcZs1P{Xxho1ls185|W5Oe1;eP{Z9Om|mzRc4+O zvE7XacQZHl?e5#-WL9;j)VFR`o{xyVcet6YwQQ|ev1j( z-_@}XOnk_8;Rd7^d+92B&R|c)Wz=`-U6czOAEczS*U$AEVq-eU)n%<|<0udjD}_lK7QsQPt>8=SaY0#j$Q zo}`&4N`{%-ZImIW5>Xz@_89jI|W^FtbgG39%mQ@vDhmezQ4IgtFQYl z7U0}roM!#mSy<}AA5k-u3`S!{l7IE>9+d65UVQ-=D>)c9VwV5@DD?4fD@;5R~TDyajq))yqlsESy?6HZV*!Q&b$*2us z2qr%O#YR{hF)ag;nIa2LIdXu`s{v+PMyWr*J6)~n9kNX~f9Akk~D}Oqk>nr9m zwhp!XHOynF+N|MjYue0ixjR%~43OE^I1G+jRE>;Y$LYW@0V&U}McaQ2cTaow6K^mY z7)b>m%r$(Y6kO$|=3FIBx#tR4xL$o$C-ey^1s2WOa1T5F_`^-*!Y&UtdWJd^fSeUs z6*Mh?p7)6nHv9Rao)F-K8Q88#VG;ISdjm(c^DQ%Db3T6~lQ|H}VQQ)C7z^uYCXr1=dd)sgIn3+fMnA`2bEp|Lr9Gsm-@l;$ z001BWNkl!i&9l44opW<|nW=ewY4Y-Nr~mna^j6jsUx)4W@0SZmoY zgJG4NW;EZ9j^;OoapFdxVKnV@WTjw0LTM({#Y~I@95wqtW#?1=c*Ew|CW4KWlCwLR z%EwWsixas7stsgVP`+07yly&dhbKDB2_zML3*q_eL-{Fq8}qldgwoo zBg1nhX<8mQ9vIf%KrN47B+rMG6?^9u7r4;^*;{G)H`rl+?avEGhTmNA-lxR8sB@b4 z75k9CDKi&dEtt#hW!v6y#dc`+mkIC{8Je}uwTBfU>6RhLl+gRtxt7k@l5=ZZ;ZQP7 z(r!lyERKzw)XHV4VSOvhWmkY7@7)pifY@$l6fNgVzbuz=Ck*Yc84#cdpiP{hcBBM7)eNEX64r)Tt`@~zF zJJruvF%zhr=px6;kxrjAM+f_D%2G=E`-I`~ObCc@u}E3S45->0kY$T9n@KK7O+rZ0 z@3a{OP*gJnH3W#UvWfnZ(zovs$<#0*$@hCWIfoyV+&-LB){|GQ)`d=xW()jvW$6p- z{RnVcaaireQB(s3Fg7Y^C0D#qFIV<&2fYlV4?wnxhpx14vU7|DHfL25z5=?wrMEl% z%oOtgStoIhaJz>@1~|gD`HIxHADIvWUO(@+-2>!fM%xA6Z}8V^k@)6;N2zb~7UV1? zHK9SZyNM2v6iu+FsKhFmifc2O&F0_OLs7m!Tw}a*ha0T}g)Sm;7x-2>n(BbD%9heh zaH?I0v9ESXH63Hw=^<}o-LicuG}|EgfhMX8#he?g?*0Xd&7IUh~WJQ2lxCb%aSWs z7Qs0(XcM`R$wyHQn@8C1`m(*>YR5ETDn&(9%&V@&&YQDDnE;#Tu05hSNq-@P^sA0eCKV1gs1bmbGUlq^%{mvB~cp+rT zzG~f>ajtfVvsU0_q%PIwk;u3?CJA8298td4dsh?-RGiCLLa^D^#Ps#8oX*A_=)R7* z_`)_t&c+9zDo;mk&u!L`31uz4aZz`G#U-vt60M~;fx7O8Z~61`8WzD6USnn+b@X~G zBHtS@X130~Vc^txn$b7#Ice~F*X=M+jm&gr21qkgg@#R?)=WAo9WZzwJOdCX{nDf1 z=Bst>%yN2lujvbiosf-7KJO7B0#DaXLywb@N&1}L@?Pg26Jg*s54T-1SZIQ@y(>yB zI@XuXPA(@L978=T8_4JtoL|C=JpWC*ciwH8qb)G(!X8$$4PSZNyzo<-I6pG@E_X za=UZ*wK>C>Vs=r}LO^D^DlP}=abKa4fX~QRjMNvU#74^McD&9Mj!^($xa3d zIq0{XZYqe7{O$x~GQ9JRW$1t!flYQZri7eBe0n zk1ILCGlaf3B&~knmj0gbSfO|<^w3)DVxrrqz%1=)txD^@(nkfN_21!Kk)uHa5nW+PP|KU#cCBgkmOi%*HFAAi z!LNihl7l&BM8|KwoE^=OKpML25W=n~nDfP@&0e$Q5LOD2^DcouAUKZLbKs`{Kb)5$ zEaM^JqJpZ~!ef`m*%-~(Yh~YqWv*brE4w_ZVA%l^sh!oz{ztK)E+1#E*b8B&tbEED z`IQbqjx_g;)TO5kotMq$`<-?@Vjh;P5l*>OMK)#wHw$Z48x^QDq+)jJ2m$-vVWi$E z+YN_j1xWQ01Q>6LbiHC4N<}Wx%JYy1xDb;Cc-=tc0M8io4iK6l3|69EhHj!-x+ILI zI-SC)Bz+IzPp52H-F4~hqmK424mE?{Sl0l5K&tMX961`zF=H6nlQk3I&Ua98&ZLIHAvAJl~Si!>b0Nl0iu$YkCt zGK$tIh%_KnSeRhYJqGe{kSTXBft;-2c@=t^3xsO($Q2m_)iMEvxXP9;$VuXMoo6Fu z%NrL7@4ec;!bn6?!Sq^GKfmrj!Lzuqbl2KCo_+63=5>aW9GD7=;LyT{e__Smd>nBJ_24j@@c12hY@cEqQVkMxr}BwaFvy8 zEddm!2*fI{DA5TeFO96ML7r2W25#A}VGsgE4JGA@MIi;#WWa3=pjt36`#9&2Zh7tn z3@pfO%1w%gaBpV-KxN6Qrq71H#>4{hC4InWhh0ri+g7Q+XHn6R*EBGPjwj)=AgEs!(qf!yg1yUFK6MY>GvdA`(no4psM^c+i8-&@~ zFIQO>D3hQZw#W(NBAv60(H>GZ1UWKnPK14Tf~2MkY;pt~X;@w*nW!XpX%Lga==Xp4 zh(DV@jH9M?L<@fj3e~a^gs~KDMC%S26&xPmA@k6+l^zWdJUy-qW8FiE5qro%on|MbvI=PS4^sw9 zOl-522Q+A`+G|={;=IR`kbL#>t@cFPK~W@ojy%}K1Gs6K4c8=VSBf;$@?|#cge<7S zIMi8YPTkK?h6^UKEp;k;F1=f3P7sloNs3%8YrToh5X&eIa^^Br_lk=(wk55R?-vI) znMZ~(F`u2tt&3@_K1x2T2qI$jvC`p&5|iUi4MycQ1XWJ3Vb{cBT(0#9C=wfJ@4Omn z9A%Y8?oI?|XB_WXrQ%}lz+miq`0?f3y>oMDY=d=18(5d)4%rgIAwj$a3?BtO&%&a6 z-&Z-1;cYvsy&;Y#dq1=LGjdXGsisyP!jqw{>jv6UU9{J5#QHp9ICPr3*BP+*r>~Q2 z?zx=3PF`}1`TUKbEMbGnsgF#Kgg*;|yj{}XP7DF$U6G4td3XpBF~k&oAO<_~nxf5Y zD{3z}`(v!58Man3q1t2=O|s@1aGKVvD~m3v=A0avw#vXkpqRogtpviM@zJMLk%Y2l zFer%YQ9! zE6w+bLC%cvn3)%>4vbyP>l60h+ES0?_OpP`swX%BUq?GYXZQW|nmu?=f67`JBAnj} z({7~EHj{?q4!>RN;U=H?By4yS7;QsG$)#OU=Lq|KS2Lhi<-qC|=_(dpz9xoXzBV1^ zo1DiI9wrB7PfC#d^j$6U$PY(|S(Z^{K~SN_^MD|3K8oxyS35v1OEfrIw=*lM##0P4ntuI$9EJ;lMNJwBceRFTU4ByU$gR`crGsnIp>xg`wtPKDnpu z_pbQo_YUP{E7KJeiN~R!A+$U5HJv?SVQZdwa&ISshsoS*w^L*8mf(K z@{@OrWLH%eb3+=~(-LsZi@(OnPb48oDz+4=7ZI6C@GFk03OkpHwKzGGM2= z_|4yahky6CfBY%+H|Mfy49scjskmVb9>_B34HsQ@VlgCoWp8y!{yhVr21CcJ*+1Kp zZ9}DdrU{Jm*FV}hUNJ-9)!P36=vzqz?e$ufvi)g?8wj|SduQ(*$oT|{P`&U^?vjDK zsI`;~kfzesEa8sKaGS5{Vku>8Vq;1qOktFa5t`i_J>=(P)0HBzpeoD3PFz$yA9--t z_be$hZ-DCb^R#1ACs>o@HyBAl6@*5{g+{-Il@;R1l_8Y8c5$$YAsP#3)Upc6hY&v= za>=F>MOz#*{g#v~F)>TV3CY38(z3IRE^jj99KjGhftXN=s4DS0FhXJj=xaF{CLD*=JoR@Y}ZSn)tM2)4u83nCKw3#jJI&XERY zs!ew?OgLUMHaS1KzJh8SN+fE;ie5_1DW(xwj#zk?uC=I(Zh`B7YlVL0>QDzhB@?*_ba z-WlT^&5JIDt}8aW|Pbbn`mv2+cfw=Jfe$xTz(_J{_DTTpVgn!Oc(SI6`Z(!j1Zbf z77s^*&Y@X;FhzI;A>nGm=%Yl#iKHFYdc_KBZgDi(<#|gn8x0d@a<&#Vn_jx2ZdN%Z$g{DHmN(B$9$Li)p^xBIjF;Uu;yR#I20sPI(}dmc~ll)1ot}Rm_< z0MagvIzUnl7|9tdVW4up`n-da&NP=8-$2C##u$&)pr3$abjYKt1{^jwUJmKBe2Ie$ zBB4w5!nfoQqym!%9<$dX&Oc5LU|X z=M#Gr9bw<2PMi1puB;R1V&lEf89!W0DmWokA?*4)nH+BSfWQCkpVC-hahT{bFc=46 z(u4`-q-9ua#QD5198jE-1DdTx;o>keaxi-+tn`h|0DvXO zw_)fgeiSt7EepyqMC|*H%jJ?&+r1vnG3?2##9vGkP6xvkc|U32BnOH~URDtIsPy^T zHVhtNB!`bAXf#fvnca{aw&bdY%2v5thg{rUBVpxwiJx+ef|o%JrB-o_ zh&dam)LCa55FDZvh>C@`ynpYV4rbmN+iao?N~*#6p?0eQfn^)>J=$Z$U;X;;@F)E< zbcaNLH)ZCO*)zB4HLE=qfm`>1w@Ok+2`)7)}_p6%z*xuInM} zv^T)aKt0U&t6B%xWk3(dy=0yZlfC!;)8^hxhn&|JJU##1fFnf;COvejXUQ#*4f!B0 zr2>j+6bn!>-K;K?#keF4p10}>aT7X_YZC$3WazNPr5t)4+*%PV(m^0G8!Z<}_P^V;*?SVw9K> zNQj+t4#k6wHMLomGAX+#xs0NH|HI2qUDVd7*+m>rli&-XLNW=fM|zW*{rqImAg z^5`KjqMc_H_UJ&L9>jw%&6WE$%g7lqJu|l!TX^5f44n<4MCV9bp)~$%2u^Wn@!1YK zxxx5q`CbupV@0o)!Ia$65)hJ>9QXSj`qD@hAF>;D6ur9p-;nCfUe3^4wiOMVJi2`rNxZ&oqSD04IegiY?&A3une zVv#`~zy|r*T*>7?Tmj406;!i@WMJZQF*F#{xae7MGUj^Z@G zxI=`sHG$Kf=?kvWSNs$1J3@%qoUa~LGEST1JpfxDi$%0(4oW5_n~z#CztPMsQ9Oto zoVkfo=WZ4)H~rjJ$*ioan4y_1Ut%x5&-A_^Q$^BN7BzM0uqk|O5IAdJDsQp`hLWOI z_JI&-0p-_WHS(_2k(&Z40*R1!Z6eE(Z3zKX{d$aG*%u;bGIK;*50%ly!1#B+`R$+A zfjzT$>@pUF=?>4shfe3`9UO)h(3-;@2h85ef?emCW|lDbxj#d0&JMHH`!pP|c#b5_ zEHEqU(JvTc&I%~cfw6U?Ehf`CaVh*)MoiXniC)zTTp#n6Sa#+f4!!md&PX)+n* zTrI_glnt*~9Mha=KqF8~bh(5%I|8nk4V!nkY%UEq*9}kkf4}>izb%XU)~VCJZxWX} zZbCfkKvJhNg|dGns(`}g$Uwq5D~GdenQLHtOL#CE7ndjkPARs%abp(Nx zZ##9ID}i>hZz>FxTpwpx9@$^rBNru+HUK5-#xg37QbwDYK;lmH001BWNklG9l>udt2shuZ|X2@8`vs?lAy6VaBDCwDwn(n#>bB@*!S?~Su1HlLe=Y= z&ob1`%vgGX+$*-q{f@W~2=*BN-jc)6ewq7wtIH-ovtex!tQ>}&cEHpb(0It^YySTw z6$H&+`_gXmVEFkn0s_;yA3$^gTr%mBojx_|Ay+cwvguZNTX}HVwrmBRa?wHviR6%s z%e)3sc6K%ZdjbQwsH!aaVb3Jn_Y(n|92rA@Y;p<3 znKZg|QUo6U0I!6R&aML;kyxI{&Q2Th6U#`Z$A+cVkkOg7>EYnzNl@D4P;Q6AnYQ_G z?K*$|=zZ@L`}VV-pA)Kgsd`_h07_HJ_m@}jw?dCQZMM@|H3Kmq`{OoC$gTu&W_wCD z9{l2}X7?M4_L$9WiLkDf>DPFbu*rF136`?A!A5>Y2PZX!bHo@1vDia1!-;bmv8e%c zaLi+(Dw$r~aM-W`3FHDcPquA9g6(*@5@8=jvoc)F&43WM{1{Y$R1cEELSDf=$e zv=Ghb*Hx^I84Bd{M`efRkmqKHR7P#-tgH~KA)%Gsnf3j057gwke38T}xIB1Srr#Q5 z==V17TWb_sNuw?DB3o>NPXXPNB{K003^mhn8oR(cpo%IZsVZVtEfgaOdG=y$DVL;c zRDenaA59Oshlqdso8PJPT-E;{*pr_~r85lxMW;dSupzVBJ6fb4N!57fR%UlBCui{) zv)^Mbdb>b}^Beuwb!IAaI;>61ZhESQGr8bYO)=^t3~AY2lYY*Y`jA|j-LoYx@)AS9D67os|+IY1+8%4$np z%X_f{)>2x|yN!%qSx_Heg=tpNWr`T8r$14xp>|Z+jyi!H^Rf{i8pL!+hnzb>*)mgd ze8{j#AZuWd_0TA9UdD=$_hxKpsLwR}U5a}CnX-^8Lrp}Tp(BMZa!Razx?U2}%N|5` z+-^6OvDk%PGR+qmbg*jH3}VPF#n%42e9bcYJwPtbq)e-lq_YqH607mXOo7IIs#}Pr znqnFs(1#*BJ3zUgw7fzwkFMP#OPy1j=z$J+bSR$h@Qfw*gh5D*#g+ojr5Am_{O0>o0f4n|hyw{y@|3{YiUVmr9pswzWVBtL@c zgQ<m9IZ!0?M_C`4J~&t|)^}OtBiYD%Qcu#j4+jvY?-(a$c>Nfy-sX<_Md2cz(X% z!@DQEe|N?E=PTa5yWsu1CtNp=ZS&Q$S;9u^>sI6sT(v#apmk*1f6LYo44Oz)7_$xZ z^7SfE(2)J`2}u&)ZQ0-@2C3 z;JoeC;fcXORr3b%1gB9A#wPm|{F^lEZ&5ug<+foA#&rwci5nhhq4qr(fpB)+9vyN9 zeG>skTYeY^VD1B%_H1ppo5KBm>`U|aJ9S--1&$-j{&2^`dnO_&**v8T`Il2?CeGB1uZ9d5I3T&7_{ei6>QLS=K3fz|Fbs24!ZMIcae zX)tzi;&xUj{B+2BCxM&kPlyqlb8wq44Fr?^epm@dZWxlTT%34Hh?~>YZ?1OOL~6j+ zg(&753y=MNOV@#@!eN!Ff#jw4w`M`A|}ay2c4}Fxx4?8s+{dL-kO2 z7>^tK-k>+zA9;9Da)1){5||$uaz?Dvtnd!a7iRZoRmS)gU{~huQz-5%)#n6e(Yg8j zw8KY>n8py`+?MuH?zgmqBdGVG>8}d{cbcr?yhWAEB*#_`RfY?a-4KSd(^=GH3|<-| zmc~)0*xyq*bH$8+OxSVd^oOGQL_OS8H9j}j7oUcd%@Zzpr^Y+N_3HKS-oLxz!}}}V zJwGXHvu!@d3NY@sy&C?MDdF12UtduL*qY^3Q_!p|k4%xTL9w#8NsX*U*#9aT!8_9g z85MywIjC5|1ma1|f)18W620rX=kxFovMXq{AC%>EXc(bnSP-&RwJ=l}9(Am03#o7N z{cN69Z+24yXSs(o9Efm8O+!$dRxVP(e678ANoHaOc$hpp0&u-<$%x~C3^mVu#@-@R(aGIBPZHu7j{9zT5k zRzG7pWG&R^nOhkzs5H6*(ux^T!+M?Gd(5T#J!M2SFbqJ@*|m8j_M-E1XatlWX2atE z(-?s(d$0eV=YSAG2`YvGgc8zkKATO?4CpXo8D_3bY3Rtl8L6AjCgwUF_Wuk^y^+a; zk-u`@!<*0MeGdpRXh^3m1gx1542l3;vXi@PK7U^{CS7F_)E=D9EQywY&Z6T@?mlRw zWTx0ra&mClep76ueWuZD;Aq(|O8>W#2au6_hy+f&{lyR=hqr|o&2nl)X!XQ45YHaI z=7Yc;7q1qD;x7tGq-&PUsPNs@_|RPY`!+V-WZk?P`#0Dwu%uufHX}K547S*P8)QXkkC)Ive*uS=%`ph zS1;YAAw$t65@}MXbyub#73O8%;~~KrJ&iGrvMX-xqh#S&OJ6o;4p9dMhuyKsNW4pq zTJPUo@$UJ8=gWr86P~UcE*D?z*j%p{TsDvEWvfhNkh8_u?48s=m)UjbFY!5Fsz+*{(sWGSqcpFS>k>V!CbS>!PrHy%kW-?HLBRn1H1F)nsNf-Ea%AK zB*^*;m;m&4Q0Z9XhOEZutX&v@R(4favSQ8vu^A9IVvNqri_Qj%gAoEXJHHbZ%E-QZ z6z5??C7vK`h;TdmRxU&BSSe{sh`Is7T27Tv^B-r`BYR5HKzzLM{^U~CdL{p zBy{g`@w)FL2%_^Bgh=?^AAdMZ@cR5>5E9v<=B=b=FZ~v~4c4G7jE5JY79Lynn*;Wy8C7 z7d&0OvNVw+Ht$uEq+xGJ%)YSv!oIN0<}pl;I-;?SDJc6%&ScUQ1DeJX8bwa%sF=}E zZo;jzn_Mp)MtpJoK`d-N6F?1{O)l3u@AP`#_Z@qdVucv;u;dD35~JCLAp-_F9sZOB zX`XjB_Suy=0UyMU${eL9a;%s> zHuaN;uvv=PxuRhfw-wHZ;^mqKl6?;d9IN6`^mpl^gb)fvWfoJt@xQh=J%&)xU^aX# zgtXx3^6#ci#j_U*Xx$7WQlMOoDOLs z-2TBo!|tB&-EaSQfd8s`=(ugVS|(xCcs;sz@#ukYb`WqUfp_@>w(!ARS=#Fz+QWkx zW821IL7NOPtI~k!d!wGe`rLhudCna5hJ_)G-+Orz6pC=ZdvjpJ=qStR1$^=wpWoFm z(cbfL8c19I`on+pPwP35-#Z|pOs>(?r`MPzXI6PYwQ@jTN6w_#ys!2!t;?MK z=%m3Hx^rWLI-@Eo_|OlDYp2w8xoTuGb403FGk!p4l}f|9Wx!J~uu(jfj}wzFZtTT7OT0fj-@0yOO{04% zALa+cIezk+sf&~ot%N71|MGSia10~ZdGqjaF*eDIsBkpRi9{Vv<2{9Q42l?EN z3f5S)gqWg`b6o}t05&PQmHxO2J%bpuU=KkL#Ps!rm6l-5$OU}^>IEV;y4%BIZbw>R z!_$%lYS1E?eu#t5-uxltX)bF52}Kq_KDjgmZZjJU0%i^{xoPT%BY8fQoRLx}D1*F* zfBpu0Bz*q(1G@g|qj1O(>HwTrEPnyQF=7gOG%NF>9<(#ibQ{kHn$?wojz@u+3$n8_ z=3xnmSt(*2gl=@;&5F$oO8fv_dJ%4{L8yA&`1lG#M1a&c*PaipoG)Zu1JO_7R`c?{)jNd^ZkrEfz()v?Xc z`WmBcd!O~?!bfmKu98)`JMTYg6a28Iw-;ta0MCgg>SgqqF2SJ%Pj)9GGoE%y+X zaF0PH=61Mq*}B>1VK&5wM5tw3XrJzX8k+CecdigotH7`D`?5sK4FPQ>i4=_cu%$!~=JqxT{WiVEH ziHZTjb5QURXHn*L_GYN$qlxl^$4tv~c%#Ld-uZ8%+P3WCIv7-`K7aeR*1Z9) ztWEHs=lSrD{we;GfBIj6!yW(nfBl~k_K;bXt$ew24a-}cl&!~s{qf#!B@|nOle5{6 z8NNg|E5u35_NrZe4*T46|EAihfm*g{AvLZp#SMXTXeg=X*#4{-kIBfAz6?{$Sy4)Z zCS}BJ%ZD`^hZ>F|iKCJZO@NDOM@9yt6i((5_oxnMln1jqT(3b#QSvel@)(Qgl1n){ zd%*X9``6>cbw#twGwKr$NUIha%8`_;rPh~pwTs%}(*u>qNZKj`wZw4qJUr{sLF*Az zYFJPw@;q9Q#GSh6(3prjlU>Y^v+h9gfE(UJ&o7-j%$(gfZa!D}dw&1xzeM=&{yDBs zPjGHSq`Nk@Xz{x$_1-k2#t1;JbqFD`zTRg?7{H)EwS1sKyec;w)S7D6Mm|e?&7PrE zH$oAv!cq``=j(=VK0M)P-#p_f+cv*{cf~g!o^icwAaIr#5jO8}$-6XiObAmG#fq63 z`+bMsyyh9i5Gy%^$g^rDs?mbWSRw9Uu6Fpei?Q;jwQhEe{Hzq+40tIEBMv^F){+uHq+q)(pk5%F)1Fgy@t>c{?$f?Kj}RB z*LNV^@cD=DO^y?d+3&7}GPj%1=b+vyb8~jC^uWS?C%phLE-ExutohG|z0-keQYRmc zNa*dm_LllrSdSh9^TpF$bsDkU0uJd+EcH}sK{}fbJFf}`7DF_0z~-}U zrLIeuu(9GnhGeU z4x32k5z#u>IjK254GA3cLOyH3Wt1>aHqthR3_Mv=E>bo?gE2XBHss+tv{cO^lT`2OT#>+EG9MW3}9JhtiKRITLlSMejY7k$+Y0r>ON(!IUi-& zJfaAB%K$rK_HAt#DKmQYayCSauH9J_#L57)^n8q%GGLn9)L!es@B96){}SQ9|L3?~ zpVR*No>c;I2f2%$2^njtT!Jh1#>&2t^0i#v;pCK73CCP!0rU;GT2^27`Y9uQo5;dS zc%22~QU}&vv_bKE&|J@Nl9CPJFtm>jE^;c`=oDqDrC-3JDA z$3)y0_3?Esg?mL*hkiRC!3;On4$~s$x}>RwDMlJ6=dMqgGf|e;^PuqV>4Kkqc)~CL z;#>U3|L9lv_QN}P@A3Njf{$QCeg%*k;E*ke_dV#f5cVj>i2ELk+*p7wE;%kSYoz52 z*Fed}^{SSeQR5+m{j+zv%wq;4tEfxY&f@FK(|{mQE||K zPuc$yQxWIATH&|ur`zR{i4fKqLcu^F8{m+#*fY*mRc0s-#+$tVghGYnkq;Q;u7io^ z&`xnlF;z7khB4V#s;xEE3ys>}+eRO(XqqG>H=btoz07Feeh-SSi6yF_PN1mf1ZjCP zRteHJc&L>$=rxcJb+*Oh{Q8{({5QYCPPqx_J*5K=EnUj=eU-HfDAaIc8+0bcMrW-OKmz~9( z$rx%PKO3-;3Y%dDOV0a2-WBasFHMDY%WQ^gfey0Kh&FkdI zhhSEh!#sC5++TMSX3B`$lX%+!VLv(_&H#`Zv%Spb|5$%`T*J=>o9>y)56w5jUU#NE z=++3rvfTVjqAPx^dvpeF_QEY!c7lekce8-d5x96#qtC#)w_caCKydC1puOi;tp4{q z==lnFxx)FE41CnzSN2e;*hh1LT+~2B)>T|1b8`;Vgn-&>eCXBl&W)I@2&klf&qB|K z5OaEHgH)11iC_*jS-v&sQaaG1N(sF4TCliE=ru>T{A_cG!noEb`%+DNFoB#l<0et} zDoa2KkR!CtY1{$8bHR$KkVx{XNKBjwEec`B?e!HL?qgJGgz7xPoP5b4&L@n-h%y~A zBMVLZv{|L|#{D=|&wu_>0x%uv*t0?6(21FAIXaBauEW{;?L8+%Yu9*sC{K_xUU~0) zd`)(sY1yDQxa$HUh(?+ir3d0KEJ%EJ!j1JzSaBFB;`*l>I2;InPD8bRd2PHU7Wm0OD`jWdshQ^Ntu(y>r6MQrMdSfe^e zO4y0@aWb|kJ2K3%4xtm9Q&$g8GDsyOf_f)OoRD-sG`p%vbqjgdM(v)-RmKI!PZsMl zwBL6fI@t`BqHvIF&75*@Ds!Ox-y@e`(h4MG)~vjJ4+tTc%pZdL@DD)VBkcR4)Tpzw z0XheJ9{xjf^!i|IK#!f}BkAnn=TrZjA7!u&2@hVl7K^*I!|S?molkp!$BIwWiOvS;cf{9v7mx^6v*^x=G+%HX920)SX*JX_}msDo! zR3w^hX3;=X-ZM%|nZ<1;T@Rbb!`pk1^LYLEah#ewT%^Qf8qK%tE*zd(!n!Q&LFni# z3kAHkU^yE!x^lfvVAhao<@MsRV(a|Kz&E@$k1R@_ATy67JP!ws#ruBhG}9PY;4LWB z;P78b7oXjSjyzHa3g?qy3e^W_Gj$!v;jhN;l5AxSed5~KL~@`4y{ zN9V;QDfG!X@<=%1klAm(cgC=cSdba3KFhGN3M|$x8Ky5+I7|nsg}#MPLcN=x!5r}N=_B5K^8rua z`~shU_nSIwQ|d-079{_SQKAsU{ZqYE3>X+=NQ!}c4vK?wVzi^m-j2q^?VOM#+S~oU z*X}gM3MCB;nLcW*n@b)8t6o@!2d~t5NmeGp!BrvU0HjbL)%4onHpn3?c{~LTOJ)c{ zO#zJL=pd+(vOPwYR^0m4!}u)Bpe=07*naRO%-+T)zR4!*_r4 z*K=vlO4i8;m3ny4Igx42EOr?+f?Bt_}DB-xXrvJTEwQnPJi-0ydF%DP-H zAPKv?hawFVSyUT8U>OxN;Aow2vZF}~dR1y&V;xdY^WrlyKip$=fp0o%mN)D+2v$n45qOj3cAy2M5k zAx0L?Q9aMg&X4X*0hBGlHI&-q+E|-uHQR_WgMrBz&gV>@05p=d@=Qnn4j_m7%jZUo z$>*VwGpWrK5d4~^JS*TJFO=YuER{3Rb7hCNH#nS1=S~*Pmlyick%B#<))+L|rwW$d ze$m3R{Ud<#OzzbiKD+hP&NTz`pEl(COV}Fw`_ANf4}hYnPxlI3MPpyDxo?q`)Q~!= z<|}z8(B-uhk>r*$HYy8`icv=~5r8@KBUjFhlxxaHAhVZJmUOH;4XigdnLGo?0;gQJ z;<^G@qXJ1kEr+_&>O@H==ZXcUYuwU6$zLB-9Mzx)s52V&q?cweI2gM)K}=1^kitGkJ0!h)Sp#nL)*w!Go$WM+d(ZSrfINT~KD0Tu~F|0ZAkQ_dOu&yIS+BWwHzs zfbK}fVA!h=up<-xPOGdge9PniT@X}@te zm@HaIKRU>qnk5W+fDv2t2y1f&Fi*kL&cHaFI52+BzJ_CN*VddC2HF;cuV2^qzx#Xq z{8#^=1_P1Q4^S}h#YDIewoA%TyS=_9BQh_B1TF(^&|OlQ3t~37u~J!Ol3+uc^9;iE z0Op*-)&_R9g;xFdMY_g7;Iw=R!-j~3v@Ct57th94o7Gcasd(mtLk`UA)C+`EC^c_@ zi#K*U;TarZ^x6&)5qn;E)xjy_rBoFn1|v_PG3nPMP$ju?OqS4&DBTzt_VQHv!|(on zF3Vc^@PN-L?>9a4_GjR283EjpgH_gx=p2-Eq~6a^wPoaJ5nbY0b9=6es_)6DIbY2; z`hw8bN36z|@9Uzs{?ahB+H8D51JW&cn9C!&Ls`2tnf|%IzN7{05ER8`(?~k!GNWrl z4uL)FIc(AEYY9Qn{_HFkBcg3E?fELE1t`|LE$wcb;us@5`BWq**)F#`K-L{jq*E#2 z)0ch497HM7+;2a;!{^Tt@xG_xl5@!%Ii!XU9$G~iaSuUC@Y2yMvh_PgO zWo^D5ip&?<{U}F-1SuBRJaOnNR@2s9j57de+|fkIz+Ah}RfY`3eN>*|w68?f4r?+` zkledi$ZMN;j3FfUTlgVk=lGwojd_jhS_U_ zoUN&Z4D&3u6%ePbDKm-MDDZey$~=;y_0$e461oG6@IbE5NZK`Y_@u{`Fst`_`n@#X z6nHpP{EfqT_ZjB7>gJGJbOf(IfBzkv^V!zf7nj8hepupjcT(5T_+hT^`n}&&_^KCU!?#fCmX7o8F4yt zRn|l(I^ zcAdShnQ6akl@%*2U-%<1|4p!;eoM}NfNhdD45QqfKB#h+Eiq_uz74`iur&oCXi)YE&~gZSFNx`oWwem zHG?LzH`&}k4q%_1Vxs8wwq!-BSq6lvsD%*9aFrh>`TMlMSyI1+dJp-cM{$75T5K-^ zSng%KIzSMZwzND8MtJ>nL>6Y!9zJR4+W<5?`k=pMf2MOIeKGpz9I*DjtKwPT zTi$Ofi}IHz;PdB%CV7wKTwm`rAbazRJeD+z#+N<6$mZ8_wZoz3h+(niOd=~`l`I*1 zs8_|0bG{C8=bfZX=_oFeUyh6j#_fK`$4`vQMtHqlvF}lv{>x><^?Cu_LuRGYd3n3v z5x7X=Zuff{_G0?Fr>CbpcqR7hdc9!JyPYvcJU>0bdyj4N*e)AfK1wKl9oo8_~T;nUU|UQtg> zc4TM!FwApS^N~h@&-yT)KgXTd@`r!>uW@^Q#kO5R^!pDP*&Msv(f0|0SnOE#Tkd0oTrBBawb8%Oq6=jQ@jLxMhdfN z4S^#N(*Ylzp0aj%2gfjWPB}%_N1x%AfqARMhdL<6h>ko##2#Ul9&&ZTxY(_*6BV2E z!0yLPx4V4cb?(pEH9F|EXL7JbR%B(k9TlEsl(1z17Yicu@#QVgH?0HT8JI_Nw6U7+ zYPday0P>Ur3ilEUoXH&LeMz{l=yOuZlr*bs0v@9>D_I`YGB2nD6BY1r1&pb40$7(g zi}6cwyG(-^swPy=yqM1SeGhnfz2o!i4Iw6r-`g$8)&zyyu;KOgT5@kP@D)SEYnH|d zvjWZOF-~D9JByd=hU?{0_EucYP*|e?XXL>;DUdN5$kipu&rp{8VGVCkoXQ9)P*#bA zc_zsG?6TKV17~QR%g`ip=OKtuBc72N&O9qjfQNm3QR}Mig_6^Miph@mE}Q0{1mlUZ zLT1Ctt`hQsZ2|*bmR(zeAGHyWX6J~DTPjg9uCRMMm9#Q{CPQEy>aH@!E4z_rlBU`IX%`5c3ONoEksjt^>3Od8}EW4)&X!u@_n3^8RU7^gWhLyN1jf%0&m z&3*ySbRo5-w5pvYScb#w=oI;0vVeASFMx_25=Su^42z_mYNc+>s)H;|EJvWRrna&} zh|8MD@G4by^~Z^k1QH7a5+@$x2@3T#u+UdH!>Yw#9EWN(p$?*w!vfC z98g(a3?bWkYKnF!?4!xIvHz^xaYX-}86KY(g}ry`3M0isLgkVMAK3jR1-{*05yO3Q zfDH~mHerZM`zT+*GVttxJ|OM9eyHO_igo6vp;nx`J?- zgKo9}d5YY1GKHqz_szgLTE-mOl@GMqJ)Ll`pg-C$jEWeY48f~|`{;TT@bc*gTrNMy z_WZsK5itU8E39ygM(0Z=h!eWFUdex`G^M0A`K|N8@l zFLRZb18dLBO;(K^K3#EciyW~zug9Obj}}>1$@z&H3>3+l$h|Myrms~@egH<(&<*8Kqy14nss(xg-oaT5M>p6W*!rlO*_-x>&vvMIKKxCssuzIR zo}1ljpLc8=)&}q|HOT1h0rhJCnY?_|y8#F{#1P@G8{G9hLijrk@)YwM1^k#R=DR&x zI2`*80RuybRV;$$#i;>7VvMBkXH%QypPNm-E)>0?vdu%URDQk~&Y($Dg>#ntfoOd3 z?U0m;q)YAz5~RsRJ9mBB)PB=RE`U5&kt_65>F(bF47`5&xJI*%(Bq*Vaxs+it;o|feDh=os1Di@ia>LU{~*zN zU}&4|#7tk?;`JF7u@#ooN6VCPNitDx|Pf150ZPKJvFsFmSP?pu`Fum^0?GW1c)5>3)Rjv!jlp$%RLUHX=gEjss~or!ZS$)g2o!5EOGw zWe_pqz*x}RcW)owi^7~uY=@tztKQ%_UUkG53I=tGE_8Fc<3U$J7Q8SOnWNN7JmJVUP85oH_QYnnepy@J28OV&fcMvTrXGdcY%omf>bnpAxJ!*B8JFMfd!fAJ6D zH;<6Bw8+z#oyvB`DrG{wUt{ycI7?`~_u$Cze$z8YnF#Mdl#0ateg~N$hZ8hzq;7m1 zla(ZlB?HW|IuW?vcib-yudnyysP_34-`o;lbHCpKFz)wVt&3$3W7{?jJypqCzSPMb ztyoa|&FgTd7SP1GUtw(7k&RrkaTZgVWE(98Go~mS)qr!Pu3xg#sX!c(>`dfVF>-Bv zZ1!#RR?6ND*$jqQJ;pLvn0UDYqEW3Dke8yS2AONIyE(e-((!V?4 z#XSKa++IG7nebCE;$**)zk;L(4}d7E!_AC&8YvmDz_>sBR{0#P4iweb@_=b- z8)Vz)+o%cD`v^IqL)YjS8H%-1Fh^wh*4$9T@BD7DGsx zao1-(!<iLp)?~6f?F!N5&u@GX85ZDTMmusWGY+-PO7MG#H zS*ks!Bs+4&0SIWaaZnIW6c-?|h9tAEBmZ<1E1OICeJXp%x?vquWEryQow;F`D=A$L z2bD!!DR?4zOS?wE<~@8qv{SB~Sdsd)Bji}6cIx`$J#G=8jqv*Mk63n1Ii<)K7x7n- z?&*WSXq`Mo0v>q3qouytaM7daaZ(_=;Ls!1qP^=hyCfu*a6*6Qz_4zQ^5Mt=DHZ^8fhe}V0CEq3#sDlM=AC9pR7t_(3;WVAL6 zG_vfrB%9<22FIXCmF^{~q&F&hCFiPrw$eXbZK%QwHqE;114S-pD_lcP zww!uxBLv8k?$kI(xNKfuZ!kMQ^`lT274K4=ief4NR%>Od*c#U1M&xj0#>5i1Sw3@Y zSmtW~nkczzQtMit>X+=El3{-2=ZQqFc3x{_;6^T|W*6pp&|IC|I7S(2_v{E7Vq(og z(62G&AD29=+N)yOe1MT(%5aIW~`RjQz zKdOs8H2iC@KC|=s?40VkVy!y89Z3C?I`O6m0Ico3PHV{s<)?*ciNRUiYphqEgD+74 z^y(YG0W@3fxlXUU0ZnPZ^bx)iP(FEIXZ5_tVCC2O`TOq@82F0>2F4H@%N#U0ndv$S zNm5I#3m|2G7de98(k`cCmv;c8{?mJx^5+=XtucYgoZDcmAe}>AW<>4m;;5#E@{**r ztc>{pgd}^*(jyVP&qInZFAiA?E$%#AN!Y~FRB%tSp8wg+ETv=@cOd!Mi6UcN&}GqB z8%H=XE%46aa!J_?`@VzkCCpR`<+k}e+(qm;1djk*E?3+F4x)ab<0hZK_oezhrn zBjUYc4SAO2J3G{7hc17K6Uu@l>0k!Xu{wOy@c7_+c%)D+ec2aW!xbssXpg5IG7t95 zXG7J5nR?T?e8$X73?+uL!}9MO_5^BpuUR;pDR5-uskW=6^tDu)X!&=0c<-5B=g7cj zwZsWTVOLzpB2No3C=1{m;rZ!;ckizF_QNyYJzw#3^>}&;cz(Jjr>#9G^PVJaq)ogw z^_$b3OXr;KLq^U_0Mf7%IhJ5fVQ@^Gf!!r>aG)*c-7u%DGZcA*dKTns*!q2tL9*pF zgK>~uvl)P$u|}r6gkM7?#ch;hs!tA5kg3{f5e+)^ls!mh6v;%OG;K`KYYhVs+Sj0t zah1^zs=!#XGDC2OYwC*Jh*?8C|nV zov^@yJtX(oR+KxByf0?_@VmdqKm5=B3H;?!`uZ3Xz~+5zu)=l^)!62v z2EQa%E7d?sW@CAeRaRQmBt`>5sj`lCCRdJ`v8lzHe1Wq}221 z{CMvwHia2!QOUb1_=h8KkN2E_DmrrsoP!z;Jmru%&V>Lv$Q0U;@-ZuH4O3dmWH2_f ztQ102^hp?~7$deVC21#QD+P_Fd+qXqu*2=+4@a2}P26Bs8vZl)jyDep^hPgyd!W*J zNadLY^wi4pB+#fRxGQGa_HuYnP>HtUDR{Xq&UhxgtrG(#*8 zrz1PGp#W^1l|-9$!Ox*ejtW*DQ0STmAT(CQetnB-(uF9C=# zv2Wh1w8I)v=n&Ev9Na1T3}ca%4p8jS7YOCW9D-vTqPPtSO{N4$LhheI&m zlm+S5OBzeU-*OJG1av+!6iid(PXN2#o=rCwW}sFW){C>hKVvdxh5}7J{xNn;s#*ke zcT$%I#mNq7d+%Cct@m1bJ=Dk;VyMRW5{c#FP`3gU&pvk@4_J zed>`#YGwcv0LI(}8ePzmYpK4K+#H=xa_*Y_d15+dt<>D+;gP^V0%5bEV_Gy!QPV>k z#bHejX=jt{`3SOD7O0kwQO<`*=$^W_NI{{pAnM4KX%A)JCn`b(O~)=2exc6=g$jGX zcG(o2x@?rSy}<${ z{HB6Ib2O{_zIg8a{%8o9byw?o`FAC3JTX8R4XA_JXLgXiRX$L;#bL5vMPv7$p?u(^ zp!E>c!|TTb**afvSf2&ZKC+{RG20mLugRZ(yTCs^<9@ppXD_qR?sKz9RxV@)070Y@ z<0CtP>FkIh7E>3LCG}X@0Ovbk9L5NQ?Q+466qsn=1IYkp_9#Ggx-&I_$jSDez}Vqj z3gF}zaKA^~?$Hc1{cHj~pB;fd-|_L&4WD1`czI3#d%Znj4-xO5uXuX8EvBs@Lb^TX zei=E2UNZsvY*98fskrKuFrEMN{{R3W07*naRJ=$@UZ-KN!c0ZZA=u{iGH|=?nO$+^ zST)1BbCd?`{5y)dKsE@-OH|G};>oqoL92Ek-NUXH(;Oor5t#QB;=1{ig9P9uCzN}? z<>%F5w>vmk2}tu`Q&wsz^#Lv9p_=9 z!=KIb*WCqyN3L<*CE+nBxSDs=bw$HCjC2U5qR-59fy)V4`!&s_x;t2COdJ+~(EL8W z`|H2N{@?zOAo5@~JEYkSlne`R%}>f>W*kSsdSfv^<&tRk ztQi*lugXG9@zIxU5MMz-V@yk!o}3=oNpBvsa9y@7Ggh$#m2p|Njm*F$QD>ZW^g}na zx8#z%1%-OcFx5L;rXKK)eBjit zzxQ>GqYMuY@~^R=xT>{2W4IndHL<|Pbea<2#4Tuo9)>&i+YS8uq``@{q>^n?S$z1j zoQqxAt%!_(n3v&YAwQyW1LLAOj*%-nU*up)mpl3x0`~hIn3v!sa9MJG7~nl3e0;^r?T$~MZ}{}- z6)&%M{Kd~d;1@)2&jg>%WyDEG0xYe)wsjkmroRl1=KbYsO0I-qX8y()Kajexc`x5r zfG}>JEeTi^m$Whn)UJ0$Eot_A3>aqfe>g`HNaIiT-q``l8VhjkIw}SWVNV60vVj0M z+BGtbk$wFPWaf~tZJVZyZ{8s|PMJ%&K8KL*|K;LKF!yCsGlv*sV&y^#@aAmBAchv+ zJKXNOvT=U9Di|1EJ{>=+80@YtS-kUc(D@2j%8(tl=PTp9xnJ7t!5AqY4G1e{0X@eo zEHLxDQnRoYm(YEG=)a~V_J%vMF*>io2h*SjR57!9clL}PEV@T*4Wnx*{iU^=9$A^d zWH;(K!1I1nFmQW%kNeB5v1rb<>9Ai@2#**-nlJp88JegO1dfvZa|QgRieu`6{66c- zmagA+*|6Ukn_8DPx?+1^vbi~8p&2Dj8O7F98v>#f4kp*hAR+L>E68#oA;^x22 zt~fpPprv&&4_0LEJCq$h{9kboXUS~@eP(0&^*DECIXlpYFLnXxn^F8-v}Xa;Iuy7W zy12@W4gB$!7%Ds_QJZRl-;fE^eNX>CZEw;f$&#dpeQIVNne~=_vor@3${cXug+hP_ z62b%j|IZkJ;Gn00X|fw{t;z^@Gv&cl)zmzEG0&_n>6WUOON4J>YO3Eh!13P7D*8G* zk&_~i?Q5{XmDf#Sh!MAM{|5J8e|EQw`j-wXw=_3+Q5Umi?i&{h&QwJkgTju&rHg+7 z6AY3sIU{R2GsE;SI=!-76dnBN`srxK&vyA$KXH4RD%uq4S(I2E%BVDYm4-i-tkk1o z=#?#Xs3P+s#ss-kkvmHxx8#CvKiy1Ulae+z(dvrlZQJHv=~H&y15k3O*M!6P4b`&d zMvfl=Eczdx2gDA+U?OueGyCR1oy(dwl}v4z*Yv_<+7+gj7vzyPPt_o^66Y1l#*MaJ znk_dV_l2~TYwxGe*=?F+5Z6#beI|7nsOz4xFp4yXEH>V7h+-W0E*T)4X*Ui~A|4p- zj2PZrp=fW`bDU?l`KH7<8}=yD39{Ec6IW{Og~nztW?>6m*?g}pOY1|JXH^@&0s~^? z893XU?hGq=c_7a-m|u&Lbg+&w%%j+85p%K-8qM0J8tX;o_ig%AB<#3ZF;|lTn5doHa7oeg4B+iv9oUL&&X-*9H^2J? z;5&SJnZ$J~I$DD;1!6^8ibJDvZVA{%`4VRUYbfQv13lAMjKWZgSa6eQkV-eX%+9&T zvS&hLBY>VCC9RE&(z1%v4gHg`(8eI|$?a=k5N2!hd$NKC&aJCiypN(2&UHLb=dzchN9V_b z3#iYT`{t3^6Vo^>$?)dVLARAkbJx9XAtM_9#r{#p(jg#QEL)2>^ zq;0FA8oBOUTA{0r`q5PF>{=f=`Oxw27I9L0{qAq-db8vfUM3RJv#H9>k0Vj#S{B)m=u z(-bjH3BUdJ1z^UPN4AN)nkD2VuP6xgynPY+G0zOTx*c#r8RryhUTl`0lQox+wd!2!CPuuwoz>u1Z-+UF!KKY(n8)X+U-c?2yw+=Q<;#0LS}>vJ4EUUKQUr)U&yJH>7y6udJ8-avXb z_YXL>W*)Y%_Kt9Tf(~x%X?U>t+B(-gozp1;<3m%xv1fFE&B9!e=LZOc+jlq6%@Tur-*T4v3tm``G($?ibHSfkD;>Af;P~hqkoJ@s~f-K@TUGg-B6>_YQ zcyZ!TZyl{u9i5K(5K*(DmPu1kMMtwV}{nEocRA|;; z;-@w5(&S~2x;09p+Jdfk3&NGgWI#(oE7kIDLovv&9Yv@P1KenUitx?_a=%lMY2pqN z_Tfwed_YKi?)LWi=O6L=|LGs`>HEJm5w;Cp@+w8Xv~+k9ijVPtSu;&SXB@?XJXkWb zZjjl=S|AzzXp>~?q&U==^_c}RKi`#(wyTXt&JBTbY16MS2~(=HG5&PJvMg9~!LsN^ zx?qt&wUm+|T}7Hu625tTFd?YR!nw{DDFp)G12T@3rU&S!qiIx15+}i`I!?JER6c(XVoIYXj6&VS5;8 zuc1$oQmZ8+2tl*jqSd{u#b2|3vNja;Sxc!RFIh4pjK;`LyQ=0C(Cj-B=g?%0rUq-* z96V`qbFRa{r40kUn;NuC3J-{XIj$3&W%$F#6(ROB)v0NYK+;huo6nZ6upi?E@$*$o^&Ifqjh(QYbpG8o%KowkBNd2EP# zW@_|N*U_P&^`3#x2I{tthi9m&>fyp!1MF7 zZ#{r(qN+hnw73Ljt`xN%I!EV7MYJj|LS?86B*c!hLh*~ZtLP$HvV@KaVzT6nL=g$W zI=KpSnFo=%=(H)M%e3LL+O*Y^jVU%>vs@(g(ymiOPbGnUzcp?^no=zaf)LfIpSbtf z6tN(r8w%A%?*7{^{YG+YnnDNknfK7GK0@EYMLO7(jpK;Vx?Y;CuhT}-@u@S)$W&ql z3Gdd2L680;LF`r|`CjCL2ae^Cqr67}IDqhvrgPY`>fGCu@OgH{dmAhsSjew9uC1=c z=b!#kKl9Vns9n;`*i=fmzRcV$;LMBAVB7RchdzGtq?$#uE>_50^GXB>NYkys`q9Js z^h6Qswj{<)CUAi`a*;dTdQU5IzQ}o2(}34o!hK5kjUIKAFPaoWXiG?eo8+}%wT?e6 zYv{Zbe0eNLUmi#?;M>o4eDmqWp(NC08kEAQrgc@o&u*EBLx@&;bCyO&n^Ab=3&?^rDgBW}6IJ9w=Tfk^O@<8vArTE|SwZ^QSNFlp z_3t15>mQ!2j``$se!9M4Tp#)_>dtEY8_sb#LdOqiy+qqIs8OVPc!PW9oHZb<-)f4k z4xhGa_}9pM0gctqv*G7RK|&H&~mo1Ud8HAC}Db-LyYPAC9ZI9oftwpl=%y2XH59L}oqS(J%e07qCeVn~e! zyb)nuvIPm{ytEtunMj%t)#c%6N7($jg_mzrth(4U0`fBB?Ux@{8+`0gg|NEYW1 zqa`lupBnPXhC1s2rf#?k0$1IFZ5kn{P^d^!JKdfpX2^v(ObUW;;b^dR84S#G#{K?4 z3NOg0xiz<2!Yu{75isjVQo5QYXR%Ul$d=Dhq0rng3s?P3STdH(STf`O$epHA>1%-^ za>=G2QH@Oq;zU+fn?r6+ncR06Rzo!GvbfMoIA>2AcyXgNz|kA5Q30H(0J@(cr=1Mc z57~?>?jAkW(d3ei`2aDJAScjOeW}v={CkEHz*OWp3f-e^8YwiJYi~#Go2?L{T?2A% zsl57Jsn$!+e@anoT8n7ZTGI^6b1Fz_0>>Km`u6M3=XS z>)Br9Yczc)gU`JTsy&K6fM5RnC*XhnUl3C2-m8>iv~GxbfVa%A42F!reekD7ytGhh z0ZKyM!^5p-xgsg{d(o|v92)gFMVB3*=jjE5IzqGnFD}SjjQ8dXXKj*V6IGHXO%o7Q z#K=(L<~+}BLfOc^6+MX(tSN}jG$p)D3G$58aWm{F*-?3K*8&l&Sl|DO$!A=~E_&eeI7&@BDck<4@eE<}^q zG%PVVOKIXx4-*0*aFJszmTG&9@@ik1aKZ@hb^Z<=(-2gg2`WEfcL zMXZB2a^czT-l405;+__`X=qRzBe-*@NKb86=6QAo2`-~4Br|T%!DTbsiJ0f5+nkWy zw_+w36x#2A8XZ%0I*ev+5UGWd)>@hI<(D6yH%WZ98OCt~@Zq7!g+U(Sn98=5fi_x0 z4_Oz3S#@VMVsyB-rx)3Jugi4zlO|~|Ow_XmuI%?u2X|Nv>Ud}GvbR?`%BwlqFCAUG z5w^;Q>LktwvQNzzo`#(zFSRDd1cU_eU15#7?!*cTaB%|?rxz`mD;1YudPmhLw!sU5 zsF$a(i+*8QBjHTQz!IQbif9E*7efd!Hg+*LIH?AP1;h}MVsyC$+Z%_<&kg3MZ<-z1 z7?e^_GB-hJX;aML=@jT)+RVv_`xJv1qJ3WI zYFJQm-F)OOOPR<#5St@@yXB)t*1D6@VvMlnuwIQmG zV$T2H-zm4T2KlU&=EfLS_pp>|2(aXWr4(sss%G&vB}^%Z)Q7uIsftMbbzTR6vYYys zQZUa8zPvqZM$VVJakY~KE*lMjS}u;#p2&-x-JV3RM39hBkkY9NmYi#zk6hm*2wEwy z?`xKVYM>b0(F@@MPQ5vR)|ue-ST5hkJC7=g#iIQ*;Vh~Cs3A(hH6Q9^#_}4EdBHp{ z;+_W^AnGkxmc?FUni5`LZdJPz8f8)$6ZM!YeX%y#O|zr#$FBYc$dDKMyO4MX zPBy_pS+)ZsH#ekoGBv>gzx4xCsXb_P#C7D#MshdT04FrAk!EXSB6ij+ynC{=)0?D_Ql7Z_(#v~(LElSz<&78hSqJ1jyCX|aDJdH8JLn= z`^d}!YCu^5B6Z9aIKg^*>$;9*&Q-G^L1rcrM@xfO&M>WxNwaWTwpSY#8T7v{xfVvr zoqoj7bVcR80F;53mr1e+P-$wn3DYbMR)-R8KSPpi&{Ov0n$2@Y&WyMF17F_eE)>;< zTyo6TG?1I(g=RVWBnMOD1gSkNE}S-OqpgolV-$GCRB%mxP^wvQ0d~%4Kx-sx#*Mqi z^>yk5GcY}&XJ$$PvRDJHsT3MYVhBoo!&)`DIK&X$a~fj66g69jEc4B8Sc4pAk)dC0 zsFdX(VW&zR45@2Y>tR$k!6=Oq*4ivbhby@t7ogmKJ9a1ATDSIC4!f*@kvRrmtCd@? zzn6)2G*D#TKE^#Q=N=kxI>|pm#^?ebrwhD0Ol`Q9}+yH8g%PG?MvEluoMDD>gE z?rFddj`{Ff4P?p?Q%31aXGLdd!UGIBwd}p# z9$bHQ!m%X+-D{#Y%>(wJ^(|iR&SJ-ST11{-doQeO%L3Uaee*Mof(II{Q|NlIDf(Iq z_7;VLHkxMMp<=AhX?3pb7R^t8`#<2zPk(M2L2%VA=mL)_;Ai(5=2B&orq;-i3qpoN zA4Izouec27?6lDpb>x7#~u0LvP9hMH!Zz1HmR-b&+3|#s$F-*&d4CGH<<@rERPF1*=J}4>>kaAU8*#2`VI$_|;x@fK zT)vIu7G@x4qYEizsVqyMcE3ZD>;(P3;X$89!|pwOqouE^qIC+?1uaALiW35Ew}klR zQ4w}D%b3zNf{r;sViE1Gm8X?yJ<;IMqR4|8*woLQx_CjpAEqSrCSqQe{?lqmQgcLO zY4VEZ<>>3LnnWmiQP?*3gc@3Bw$$7jR4(XP30|*CZZKH5xbRQcYnRsSksCC`&>F^) zdlLYFIs*V^25T*3Y3M>l%}Rj#y}D`55{jp~(mD}s%cp8=>Tom4V6rxTG1c(SX1pNU zC268^E@s@IzoQ}9iV!Y2m0531JA^ktu?)8AAo0_^y!}FY#6$w zGv)JZ{Goy1mCV5t_dq@#I4BK_QSj-9-{Z?qf3f<+4vE*dD9+a3e-@15O$08vM|~V4 zLWhCmj)&K%kkV^q_?R>V&6S-aG9+q8#l7aUIdWh|Z@E@6I>bB-soguY4Rd zIlNHtz8lLH^=kCo=*m4j$*CDNG#Fmg&zi(Dio=<$>Q3V}6uvh4*qph{4ML(DD9&=f zgTMV2ufO{{#2D(v&`s2{G%ETI!AbcelTAg6wo@C4JMb{b{pug0^n1L+_=$@-G<<{TgR9{q^q-*QUKa z5cc;nU*(y*QYQz@iq4Fgb{gr&+Z%2#br{$%e6&4ya9aK@y9^e$fHlj>WM_UNxy* zjLk-UWsiCTNa}nONQL#S!B96fa@NTt4UmR;YM>WU#N+Yk5|Fp!PTKUcF3Qp9VA_0; zi1`_8;b~-zk?MKPa((~+AOJ~3K~!ggooChMH2$Bye-_SqU7UdslQeD`Ajc*gZuA6t zp4M_J3Jk zF#=%Ax$&EJAJ&#qw8o}dBQqAadDe}2luR-ooT=AeL#+Lp;0*+V6kn|=BsSbi!?wAb z%T{A&c4ouC!ayj^G8*d{mv<-)oe@KE4yN8Tp-nvd0bt9jYoVmx_@FgQv>GBiI-Jq7 zgSi+1j1cQku?Bud(Tdd|(HiRjgjn|pS?tffX(2+@h1Gh_DDehffcfpsP^ew|_)Cm{ zi{Y7@2oA=D+oSA>qn|(1k&I^hFvgpr?m8c>?>HG$o;j?Y)mJ*M-xvWhF4j06tQ$k< z6|UEO-+a=0p3e_PDeSQ|j%asBVWm5b^zyiaOTnif{=U}6;_dgjW@hPt#l43O;#Q0& z->_(=8G`6nH;%(QKtEpwLW)lJq6-i^p*>L__9;XRv3_p6+Yo@;ZK@nOp}SS zgo)~LWhRtq0%yjTpZ|MnZgw_G@A^>isAz3;1GwS#!DpHlY{R^~QDDv%n

FO2D^i>lh}bvgPYa4o(+wz7~ZUF{Gs;bBvWov_j%H= zoaO#p?>4qK??+AH)g}aIj0E?b?a2iGnogoy=fB6g*&HgIBUSg$zkvSX9}uROZs%5O zjItPt^a=V*glG1_T8q7MoJ0tqQl7Hc)-}k3C;%fRwT0#;yhOKvQhyzYx~WlZ2HGU7 z(gj#T=?Ju{h~^aIHwoqg?1(|qnop>&GGg29otSZyq_Pl2}xd{2H-woqXkEP48s9+juU zDVo5}rK*%p7epXK!hI8^`iUCO=+OW|$&4j0bt*rls z=wiFBdQ3SN+e~T*wX$pqS7QdvdaF%Qa~Sf`5b!!59Y}JYVOMfCGlLW(IHGg))8m?^ zC>kALL2br9|MV9}0iykq@U(XFF(vDYgX5KTW0UE?V?(wla{xYXf<|2~M~-#9wjE}T z@jyK~Xr4wG1y|`#9~Hot7OcJ7duNXGdF`YeQ8)MKd9&J=kHAt1>juLVwj zuP`H}C|5Dqrn<;T z&A`5{W^;OVfl|gNA2>dNpAV-q1EFJE6PRJtVdwp}sDVTDh>MHG8Q=JDnn^g-N$n;+ z^R)%=sUP0Unb<4*2ktHB9D=XY@oe4)dUhV#K4GX3;-^3SC(Qrb|B2U6uZYtt=KD{G zF+F|Ebu(=+IRgdFxeAU8yx!Irg{+_p&SV#?hyt^NR)o8_DVEZ?dYGPV@~^`k3r=%c z0y?NFC@5TYDof6wFxA|#6cJ;_%gcnfN5*3*hNk=5Z*;uS)(1OJ?}9^&WdQ;)?vDkx zL~c^oG?(NCUS6M6xJOPxkY-BsnMT<{3v3Q6cdlB?LKFU@QMTHnLa5oC!4RJ+>JQyy z(75I9zM7T=?5w)c*@kO#L?AP(Av^D4+;zy;{l|lxCJCsK4HmBI=-Xr_1_8`KUW#}En0nU-TROWt~IDgnllg~Me6b^NREdA1ZKpT?D!vFetrI&y_ar%fV}>7h9m=Z zXH>*K!YZIarp4acyk%;$%PP4-y*@!Jz6L6BXv(yO!tlOXz?D4}ttg9U4a<@Kb99hR zbYahRK~s9vfNwp=TYH~FcFD@DMND#n3$x}wHVv99q0#UZ zH6j9Log@e<*#`JVH2zpJhHrShgVVk;VFGG22@(3ApU2w%3rHL93@w z`pE)LYsBinuwd63a|GSlTQK*~ww-2S%j=)9uVuPYY`QQ-!f^J$mLtw-<4o^6#v_F9 zXhSecty9!xd6-6pVl*n1j<(efQ>}GXm<~~` zvs?>4q~K5^R-0xOt=E;A3vJR9h=L5Ks7tEuWQ{;~zWPN&8pODUpbbQ$`H|Nw5rHH6 zhRxl74YY(HPg!Yl#FmGoG&nBkni{3o$=Mn@rvpFlZ0EV=A;eyL<(AUo96-qhwuV3; z_PVWFuXHk6v>8K11Qo%e5O9kyV*qn+3pJE8rPv(mDnK$2?m?gk;Z3BN414O@u1TyE^2FdMJ2nkciGjk4qS&}9ok3H$%Dc6-f<05 z27ml7|AhJ9{|CH&^9k|xiuryw$%%#$H+y}z_ESZfmGXM{d07n-Tkl8C%d9aPg7XhZ zF_0w@>tu>uDz?$mT)snx@;LrmAVQpyIj5v4f^tF5wRmZ!3>WS#Hw6VEqZPDHPP29V z^;TCTh3iGWO%oVg6SLKtl?$d+`SdZ?m7WWmjz?(-Q5ra%B0lg<>kY~> zu$kMiIy{_u@Bse$!9{z-cl}ITa|n^sfW`F@SD26C@k`T_4XV~9i^c<6&r4G~oV&Wv zpmpg}@j2KS452*-%@YkQcB8I;d-wP~yyxNPaj)2IAbIXu^76pr{)X3YUNOCXhx;!- zwsp^mB<;7DQTveMwh?YELvL@a8|3w5s?%SPpa{~U)TvaZ%Y_(G%G|U#vN2VQWYyr1 z>NrYqHpLBPfKA{D^JBr=+XFAR2o@1J5n-7Z%#Yd5$|L>7lNQ+ zk5x88y^phLl*sfo`uZ^jGksyy#v`n97c{fSj#a4&Le)~lzU0yz+}xijMTt9r6ls8Y zZZ!|+Y)dJ?GT4-&mSSuH*m`=>Sg9kZB36|$O?Z8ou;hZQ4sDj*Qw<;j1*g$!4s&qS zI$pchT0c;!+fnIt=GwBbFc3%(l)~~1isK)L z(7C?og4?EU;<~~GK*a5qfPxw%7K2QmYJpaCNV&h}Fl1uN-svR@Up!55Wqi;QyuGos z2~|PW4F*-Dx|ED5C8Q)-Kc#@!(>fT_ZK{iU>ACXo8X*)s5I`|udHf9IdB1BP;XdMI z!T%aiFAps2hf|~@9S0px%bzH1d-@x`_F)~FlpS5a5o+Fh@(C_c39#LyoCbYuH5^;d z(oun>!AabzSskG+oL%G1=iOdRLr3oWxY6i z9x}EqtX13N!9vc0&IAHwHV3!%dft2>fO)YXW9F)Nu}!LOOk+fvCdsi0^=FvzU`8b1 zF=sqxwdAjBf1nn=NiBS=X<7VKj;kQvHr2W@7X67f4bwCM`O#?2V9RVVG(^x7twY*a zXwzfH1I|TFb(E?NsT=QL8cU4;An*!AZ2B2J*BE0pIM9dywBs^YIMu!Qrj+^sPjD0Y z`w3({R)D!4pXSk(TlKoA%XOq=^+(3Ox(Lu_6eBn3`+a%WVP! zn5G2PH!%m?BqZAm4m9V22#A&Tr`FZ_{NC}&Xpv=EuCWDnhcm!-FylpIpWXM~Ta#8f zTceHG*6XvUMC~+8hm-wPtvGZc-P>Or3?EN*y3{wA!_H%T63YD!G>rFH8G{YcP`w^t zG8~!=(Egriw;BBCaQmX8?Oxs7&HZVYqRelYA8&a5<`dG(H=yui%hJ?!FvjluI9K|b zBGY~+QdY;*)-CSLQv6U**EyioKdl)_9ax%(wH08WwNPI~4qa(oLfO!K1rH4EB4d;eGKVHF0X+GX~hY`T2zde5?aoNbEVMK(uMW-UdQ|8YW z+`N09Jh))Jqq!MD6NV8PKA2?qMIXnmaozBZHa6C0j&p;e)F*Ue2a(!qa*xoaqs8zr zRO|>ryu!yHH8D6z@IH9fxnw-Ri8+Vx5eH@O%5-Ng3_78DA(DJwHs8)FiJv~!L4EF9v7 z?sKFT>?!vmP%u4_x2~?|+^7wH8EX`?PEFKY+7xM1VZD5Wt%)LXfv99G0~PCQjl4|> z%#|u#vzFL~fi=KWnl3q(+UOBDH{?a1A!S9RDLy@>rn};%|B31*DkcL;$85vEgn3@1 z0jtNX&CTsL)gbRuP)cskx;~R)5cEJmNE4R%XF$-#OH}2}O+AinjNd!uzG}Vy6n=Py zxDTM^7^JtK4JSwU1$!n&drjsRjr{5mcEpJ0jDEaE5xVlpV={pcv0!)r-Pz<|j$5LC zjX#H(KfdnL{yo{c_TG%b5R^I)nLd5z)?hM*0Xxc?#VhFAx$%iJ^8q!2ar-M}hqWHN z1`dN-T!J44CSAD61&3LI5=Wl!G&O8)YsA!2N5#p^(wR$z-(!r(l0d2_TJt1YbEL`I z6e=pTsP(Dq*0>Z);%2ZkNsQOm8*bBtdwk%2pE1u1Zd1Z7z1Spgo*&hSAVz!dMcz}L zHsoyg|4-gzJ1s@>@*#`wSb--?_g-dUZC2Dxy5?Q^d2EE5Ad}=yfMMS0*vE{ z@DV*_!;c>feEawRBmVrKLKSN3nkS1mg=VF{bvz!Kv7d8m8TqJWOO9Vk>p2#qe~Q5Ua`YSclhn{pJ3Fes&% z-m?~1G^E2(1gikQvKTCNfm-GB+9gsdhN3z~{qv5ay_;IQzp-OQlv1$dmfNOHv$rHy zx4UN46HF(>fH@TPZ^br8iBlaMrYV^w6{4@Ix+GXb2=e!#zW4lifMP@-!pkjHw2%_+ z_lK*;5h(&8-tg!78}OnUEcD#IQ60z8I`K88+((=0Q|847j9d=)23x57*|6?x->_p_ zeKmsNJww>dHJW!CKpxQVt{utn+;r{L@v|`5t!uYMUA#oA#Fz`;RW`zVn)off>>5=( zyY}lLA7?z?zTn&6{ebD4?{|lZ#nHO$cfII-Qv<}?A>Q1aCf7-G`r}&LlD=tIWT}Ou z5vX%PYX^y1e8ke!rgb_^lwzJ`DyT4eq=*orkC38-0!tm=bSN36G|z@kG9a$ z)z-4)1r%TKF82L)@mX~E`n~9+JxMusv{}6besH2Z?jahw$&#>!D7pu zUX$XeIRr=(wSaDQBVSxNsoFyqxo(+@3&m{ia?uP9#9$!CW>jOSkEc_$hQYEGLPLD0 z3y$W#iL%CmS~w=Plx{VFP#q^+){Z@PdvxFX?vQZjUcFa~a>jhwL+p=UdpD>r)b&MIX<6rH7_an_V4};{v2ezbmySMKx_>IRjcag+-q&WzSdSBmQw1R zMN>+h3uKC}P-hXUHi|%ll~||)%5PTqzK9)M)SLwX$W!$F*YWHMDs0p+?eD7=6R z9-7vj(ZcNVXtIsBkBQ#0?kGC(?A#(K^8u;lqz`@E6JbxbR4Hp(S0V6lCsRiS6DNDfJeaicH6LP#|)g=BE00gr0FvUNRZ z^^s^PG=2(N8zW}M%yM0|DXCOFYD^Syxzw*IS_2DQ^-Kh`xPmop zP-xN0251GjT{j)-S#FO6YFd!0y)Si-KCP0uwYHg2f(-w({uO3-zCelqh1zHaX{uwW zuAyqLT{2taVaH0sc9W^`NhVe7yo^UM^ zVJ}Z;OG~zk&h1_IE869eYexqWBPTZPMEJ|U{6F~J-~BzN+be>&E81*F*E@$q_pHKR zXQLMWeofUOA$c8-d@bkfa&=@qx9Eg`o;4Au@TYSPSz8KF^j}yxslph7`MK@H|5#mJ8$0SlV%baZ%9T8!TR3q<<1-l zfjJFw~@6Zw3pf=|- zaF6Cx@)Vnplc*vX5T0`>*-&@yyWgf?l0jCSbB%_r*<~QJMvf^~D}JXNDyw_Vr4^jk zR5`vi_3yJR3y6|ssHsbw>Ka3{WHaGcnMgn4WY{H+LuK zI|ec|&;*PyMY@3*Z4VBI*6N*sEx*GY=sonS&Hc^BUTn9a*g@tx76d)-F^-i7w#o75ekzK1cr z$YsnGq)9orp@nN!o55brGE8Ig+qa56AqVqVul3%{f)*} z#qsPQ{N*ttrfQ^8H7pBaOkfn`xzE_CTAJAe@Txa#`7wg5tR|90#P@YjR8UH2{x%HP z*r7L{VeXI->S zY|U>FLjpy*QcPw^9Zm04YW;MMZAPyXTjwPgL&b6_;CVqQ+39YoRd_&iUxN$-iGbTQ z84^fAO%y7!v@oN{LEnG*L>HO>7DOx3sW4 zION&0PhPL{&&B^^jmYNSh)&oASLx&zDcgJcVj4x$~d+hLM?REP7CK-}FS z=kp#XFSBHQ$uN*-YdCra1GizIj*8p>$OmV8n`z?%tg_Q0wP9d!zXyn8W~I$rUpCC9$Qf9h&JGID*V87X;Xf#IIU ztSz#0^&8pc=FL~?zT_e(p05=_wz7L#Z zW}Q;m&jv>U(BL+W7HG?#>wXj=_Y?#9j#&;DHjO4ZWQF0(38YC}DsaG^uZ z3Q(%Jz9DO&GteOkBvKXu1*&=$LBlBYcBCN)MJzN*S*MbCw)CX@CkKHs94mAc_@r z77KDNVk%MYn5KlA37$@KAjIM_jabdXIS&qI>eotzoiq}$|5=$ zknRoSww{3}J6@0f!5Zk6&X^ot1Wq%#V9P*n3-kCwRw=jsd4lbon($^hfbjpE?PXpDO~ld#QsK!iroKn~tU!aesRlouib3w|tZ9128Xm%Cz9EjnoJ) zb!&0pzv4#lXtRCct(nKNPu{b^12UQqRi-r>zQpf0enA9PACjcbUv8SySjaq{gQ$XY(?^!_X9NM@)7t66R_CV+!P;&tdRKqewKba*s zG=*rnHCAur7Uj$cp-ui++(4<+aMfs9(bzKDO2P8TX57YM>~I z$pMIvoKss2gxBvrA%=i?Uaa|z=~f%PrQk8onE8_!MHDPwK4VklezZmqupK|JgM<$^ zH>38%XH=dOed16J9MH@jp2Nm_9}ey|1oV5^fXGDr7;3Nu0Q)6fK3L-onmC{i+ z5#r>ATpehnNGv&3`|7f+9J&rf`s?qXX;g-DQ3f}FM~mtnqI1R3WXL>$KW3+WYJ`C8 z#b-#TaguV+7j#W$**hcO+tY6CIpJ;nd;MC3ZD*Kahp~|yo3rzy3r*sM=9l+e>;?u0 zC!Y__v+4P!Pv3)9Zh~eYpv?<8RK~llIqeF&#>3Et5Z(IconxAg1#1_#4eR3e*!K-f zaLzPdcc|#f8ueM`1&_yqTZ)*b=GN7mBug8H!io1o5WSECmC!q?`5^a(R1g9+txB^t zV0)~CST_ej$?7#x{imZmyNxqT__NZp^z}O0gqh@!IDIaS?Zj}QpusY0Dr(dW0Tcmh znj>e zYYnB0Ru5ynPWAX0%*h=4lmf|R!QzI2Z*TXGu6Zvn$T`8==~iY^1icKIWtW-+shm@ta(|g?Y=ZPir};yG?BVct99N)AUN8$ zxmP-OwC6j{&6?lmu7SH@VA2MrRO=Kg!YM^_lwlNetSL)#f>8?Eyezf=o5PyrJ#YH<2YY{u>AOUJh zlT-08*ojxU1_jj%)e7u`C*)G_c>7WpZR{*sPY=n#hV0O%{hjV-DlUrrM)s63x>qI|sFsDl&VBWf$mhHnk^bmexvbN8= zA{;?nE`xKr^gpZ3kpFq3GgxYN%fzm(ozz7gFo30$s#76nZh%^Zi*w+q;i#3CW#^}w zCZSXiD!P?(JJuR7-I`09w0^>&Xd>cw>;uh}d(7D=YpwZPT`y@ewG*pA3#t62R#d8} z7@;7>O1G|-(Gl}p`SDX~WL63=x(2e&kGVb{xws+bVn|O2u^$G$r-q$| zK98W@7uVo3^yRQNA0QSZnJIg^o2%|(TSL7)!A)ZORj=o<5d=JMj+fG?O5e3%J?13Dn%)Fk1cxheC#e)eO;?VIm~KHF$!!D%q5 zQw?wzmJO%XVeT`?Iz|9Zaau3urAcn4}SMva};Lps(E=mXi^E_9myc9ehb9JSW1+{V6 z^JpP6j?sfF(CoVsci%Zt+6@{VoU{*3 zeGbe3hNd#_&DvQf7;SBC&k&b^l;S;W=b?$ph<)SQy=4dOIYi&i3d;d^d1P2NVkP?C z!Z3>VJe}u2_5>eqc3OIT!0UH^;~cJnbG%|(54Sf<5M+Zbp9bFXh1of&>Ff2OpMLXW zIu1Ae>X0Fuv9LLN(Q1R!nIAY!iarLJ8F{I++M*e0n=IDg_5KHBUL3u$X2!K)U<(*k^vlOZ=z0|7IxK=jm0U#cLzrZg1FkWuUg%}bG_?UrW%|1-Pi4Q%S5juwJZP0H3~JZ-M_!rGke>S0jW8T5Yyw~t(Rd_B{H ztDBLn4Z)Eu>&R!)J*!+Qnmc{^4sl9Y=4_kwe$#_Za{+T6Lt9V$I_0Un`;Ro+>-YwP zJwhT)wnu524RR2J1ZRq1!p=5yGRyqJcr3Y6i$k@DzTFaTw}|u>5CeP#_6IV&k}IH8IBj+cHwsln*rTo8ikj5IMhFqD$eEKEaJ!|J*%F$rr#Kpf zS#1k?lpH_2nk`g=8-?OLQl)gW$}}JVLFmjiEK@U&f(_PMeGQ^f&81jSc5tq0z&eYE z%JM@LbwXQZc^IStb{qRqXOx{>uiYWy*|}e6On4w8?n-VC zk2W($8}uEWEn%E?I9i*Ig1d)|1h%x=XV?EDNae=nV=v-i%dqLm=!wzmN9$ViBEvv- zA=O*u((7z!b+6aMKphe`T3c^G;0mpFXb^y{>$x_surh|s&7Hn%1kmH(ihcf zQw`jyh)IkAFE5i!g~+I7sA1c63I+nlmbk3Vk|Hb`_!&bqp(xPY+H86!CI$8PWf7P2 z&`vK(5z}JSZ7`rhr&=`TrDg3@`knBbDWY(l-u?8aKemVQXmftFc#lj7hBtz|IXT`% zYcBh<^Y}3yB?@o3pq))z4i{omn<=k?0 z&}{chF0Nd+*H96@eu8Y1j<%Tl;?Ync`R^D^kgmzmYfX191v%H@RR{quw^XqZajTqC z#AD7iZw0HcXYRE;_U=l#>+G`|T`Q31X0wGaE{(1>vryoo4eV5#RU~gtnF&Vk3qB+kcsv%1Kw;V8JOap3&sEQ<8(6%_oCAM>~g_N z;ohD`=Dm}Ii&N=cSbV4nq8_Q|fjpYcP4muleOP3F40AGz-!Wa+GTOY%LsmA@cUnH>BbZ5y6)LGEexl~{4UFn1Ml*E@4OsF54luKqIs`)vT6P?5 z&oZbKKiGgwTt^N0QrAzd0Z~vI4RY3+6C845&R}8(uA$c2YnFnFRB@%4z1${*D8oQ8 zV9;m-H5uqTKJ>#t$!b$g=&~%;?iq~^sq}5lziAUpHUuWds;S8m&aF9d)!9@GC*(a? zGvlN|(F1Hjw6&=#YV8WYzpagU&e9yAX?AoNm`kPX{rIncM5mYNY7Vw1>rWa?Z2vCv zU)NdcsjdV2+MhjE!;!H7ozsH0Cg+#(&Q2!(G`@KquNfQk!K0>@wrc8uW%K3Rz2lsB zRO7#f6YQ0J+L5$jlm2(LcJA!Q4)?1x9?A~jr$7A>-~I5nh|{gp-@w%bUlX4kKlRLn z-b)}9S-)~_lvzJi?3_#8-)3R}AQhITh1r}^sxN=EL&$k?Fi|9#CEM@SkT4%;)*7q!``I!k$eoJ@i$%5IBoe||MTDXhX$=yZmjyX{ zw>LHpxK2bv2)Ip?*h6P?urf!0B;40FY zEu618r=q}7y42UWMq3~Dr$W0EmbxxpbOgblY^?VJ-Hw{cQ5)*LLUbl5+$!|ldDB?t z&!|=EyJ{HY&<1wT$b*lO&blTQpp+-ttKYnP2Q>XTuU!Zww5G&~DaqMBm(}$ys|gsR z5B0QQ%2GO8PNn+_Q9y+5*^Viuh(eWq2e)}w#Hdo$DuOUg)rs=g>#7_x6B02GaRkTV(Tqgohkn5GoPsf}b1C$%TWs{R*rMw^Ct7OQQl1H(EDd@&@4 zxrS`dOEp8tIU~dzWn^-&Zd8-Mm*)DoM}SdyM_$>&bkJ8$E_`T z?%i4fF$2)o)U}#W zB`!HX+K^B4xr9aG<6itZc&0>3Db+;{P1HCq3+8zSgCz8fB-pFI@Uj#Di-|5n0FpQj znXR*0IE(239Nl6OPH&*las&c({AX)`91TN7ry+_pD!U6p05X9~whQI&PcZAb7W#&u zxjr7bV+lSD)(z$|fumU{i`Yvvkk%&KQBpwd4Fx(2JeSgVN*37S&PgE7#$Xrn6> ztm2MW8W^=I*0rIyLZmKSQK@qQ2vF;7Hit`}e*>rq47Wy3f=@v$z&X0_y-cq*^nydj zs>w}_BPgYSGw||qGm4pZPehe2P2B3E)fc7NNrMw3P#3Ie8y3)mz49#0|7KAAp zYogn_s`FinZ3yX>qmma8B|JX={63oW2+j6s=yGwxH@dDI)%vGpY_)Mc-59TiSxvrnjICAaz3DlUMX>nL3CahH8lw5}AVC3VPhW@~idjKaJYRo^o) zGv-G&%V!@Nr!apN3^f~Nb!X9&D1|NftH=Z?r3B`sF4Bzp`ykw=1Wt`+p_3s}-HlA2 zDn+c(*|Z7r58tHr(Zz9q3t^fj_uNott7;28WlU29QH9gh-DX)9(eb$HYJ9C|Pbp@J zH>PE_?LX}k1buNSSY2?BqBX7x^e%GveUx{iB`=^^UCc%Lv8JI%ty*SL~zz$bhVNERV*YRS4^T%Vs{r*4< zw+i(q36Kn{NKe(xIE|7r09uN5yW4tcsxZB3O~BLwq@CH!l#*PdV!9ZMAok5(vn0vddCH zR5N)fRLxGDk~ORWp@mZ`9YgAELt(VG>2MB+DRoOiQN%7ZJ8_R%H6w$zp{TS(Cj?fD zXg>@@H3g!g_X=QOXVmZXK%=MDRlej94=()b?3L^%sNCZ9Jm(4jn|c$ zxpO>E4d#gn!a&B}Pk;E2SpNNgz{~3^;>#z@_Xm&*NE|7<+UaY>>PRh|Sgc!cjOI>Z1h=<^_{e*J;!c0BLt#6Q~T>_F!jw6cEc+IQBOvrYBLB5?G6 zqj2_-=IGM&YM`muo4_0uveRRt{YL8OI(fR*2yJ0g=y_qWJS~J9lfQXI z-Q^t(X`Znx3n)aqeES0)zy1WyrEWBXXmPyDi;cF^P^Hz>Dzj&Yq28NOw}{Fl!7H>yxnKqUlSfnL3}JS_>ruX5J8yX zQfI0dL;l1VJM#oP7V4*Xxn!p)X-%Bs^`zmSxpZcg4H>IfxYC?O8$@I%L@rqhV{e}w zVr|kw2)NJ7)B7uu7R4AsH9@yq%|R4&YPI@dU~OE|licAHN9J*+fQryh#A4Up~1$+{VeNkRX2IydVLM8>(|&PZc*Hyj&Hzm zcW+>+OoBWc$e^Yzs@W@o?&zN&$5gyMw5(Z*+E>>~)sEJho0rAV^Hx?}PMmzto2Vor z!gQOYSd^y+k>!Vd+GwPjyj)eXdWqQJ{fgSivTU>oXGuzg$DD2Y_Lvvb&7@RcTgADB z3u34fH0}J9E>JH}vQVQ0{1PXWvH+z~AmZc(ESqjbr6LQX& z?_W@s**))PRH+?n-=PQp0ur)IJv%})J}?#FodxY^Dzpp1(slrsy*75-Pu3HvjeBu6 z`FWbq4W_ z=e}i8yYu;D$-QDOm_B{yniy`BF9}riVVdxQdkFy5&8?vt4((W{HM47ObR!wU)TUmJ zdStY>wUCpWz9>r`49PTp>zPv>loBv6i|Mvv zOnAG$iKAOEMg?;=6vjWBFSi7uHVov#Si~M$2YyBGgG^E5lqw^m6r_|u^Njg1Tg}Z9 z^bG)y^gB?FZ5TMB`QQsCE*}jDJ{znZHDIF-X`8ytGo)Z(L%h|zY^{%{+Ev0~gaStC z#XAGJv(59!YYkDqx8}?nwe9SB?l!rDZf@^oa_rXsv*Y+61#kGc574gFahBzd`SHM~ z@4mzB)Aw~4SR`N4GPkhGdDF>Pqg!`$Z}+F_2DvkWA@t6i`ln`rWt3d1O>~h0sDAf4 zg=3opk)4~muynz4LYWAXaih~T-2g0N^Bklx3Zc>u9`jtSo{6dsD3E==+M-N$e0mHE zXG4w(GrqjtyNjn2!z@YBArOdb2wD>AM5QsnLgy5!5AwZ5!sbFCJUCS`X`I|MN8`!x zN7Ivcg?kQ6TWIG!-#rc3qO9R0Q|7>v-b0+c@gW}-Xl|h$qXqM5LbrE5baub#ykLzs znd@t?*18;tDS0p7W;HQ9I;OqGk50ltPa81|yR#hL`y&hJqeXdW;#yJQ<$g!_;RmGK zYt#BU6BIQ#fm^`g12}c469}QSH2O9FnAT~|EBnl4S=?gokE1$!fq7MqxN}<52CK|- z$7$Bf5rl$E5^lUKl`aKoYElfCVs)a7viZ%WzlOGXFBw#t2vn&~?9$1TQo;mXsLe#p z-T^mM3SDN9T8Ikei+a=r1z-`|>t@|d2PCUznvxg>h_f1pmi2<#MEGYy9Yw2o0O3{W z3B|j|5qFdcxO+|@i(2p-uZm)^4fB-xRm#$GlSC7xv_TDD)iBYNCTqNOa;Z8bVY4C1 zU~rjpHPESi$r|2mgGd;4tw_MCn)I*?14E1!zN(s>C{A%PM&yzKW;}SR8s0Y<27)ha z+&+NbUVV)%n$FtsZB$EhhFDxV?zN5YrSl)5Uky^9o^nr)hPi`Hz|kOgBoFWCn2#*0 zk5~;n5`HPN0F1OF0Sur_Ag!U=VyT^*f8++-4EbD{j=3DNY8)}Iy$$7 zPMiEV*x7MjY3b2&_T>3V9O;si?Gw zWu`S3xn)M=oRLy>H;XygCLvIr#?@j_?I{_JhwXi`H8hRgM%f4HY2hwlBoa7F=5vJ^ zlQcImM$AjWGG}BFMiCJLlLe?T0r#cyn!o(|lkv2l_ShKZx2`s)XWEPRt>D`ejHA~c zon&k-+9M0=hOm&a<6icTX73{j#3R@I(3*3LO0Z@5h~w+F{@T%VwCh@Sb}x2vVn*o~ z-T6KlK4O>mdxZw^;RgStDICcO(y5XJB7XC?{{|GvHhG#R?~k3lS%a*MM2}to03ZNK zL_t)k3Q_os7;h$^>rzJ#-fG4iLPKsN)ENZ0ph)|=%jNM+O%R<-XSpduqY(O#$xp90 z%uB{&UXVhiZiS_waC3#T^DKs&$lxp3^U6*%tF*olfR|Sh)z6C{=LL*vW2|jkiovlk zgHwvOdZY$1I>}W8f&yWR2{DD%Jm#fCR_ZV-+9fOc84EqDSPN)2-Dj|29D&V_+lGOH z#??%jU|DZOgj;A~qXl)^shXQg1uF>5NNK|3A(U-t+>$gLMXbh~Hmn$b9Uv^ZWepWB zSnf+V^|V~2TtM7hQBz8m&7&qn?DF@j?RG?ol{%7hy{C7sXitc#bJ81{oL^oC==~eM zv+z*5pw~HM7@V!gtMzk_s(0jYy0;NNY9`LsUp{aJ9bP{N&@DA*;DLQer~TMrb8HTJ zPwwAvBf7z4*li*Q7!7C7`W~wG(dK@*1|KxEtJ=;bV|m;W!rvfGuQrJDy7w+NVB>Sl zUxvzYA3$eaBThi10DGxjD0XkCpwuR(DTpH$pTJ< zT}{dE2aYeC<3XU~)_-H~`&++H=aaUrA3L;l-fD(0_WEP{5%-!3oN}RkcUmS)8+UAvlK1F4pWx)4l{SUo?kN^wSW zCUa|wYGJrk5xj~2$sr)}Ga-iRe2J#jX(&q-@9Xz{D4e=;rW9mq*wB|418%pPK~qfz zM8q$dIkXBV&ADI^BLFTewM<+>Exo%9^OWx8V-w7!jeroMxSwTn2vwx5zTaXlX)y*d z?}>Q1O_-)A`!}`;sTvvRC#g+41zl4&KFvRpYX>3}aOZNQxjsQqD6PxOlIz#CQFfmP zfKdGwsKzNAq5Ef_)nPREucTw;jr<u&ENe)tslMt@oVX-hS{2A^y;z#Gq`(x6wUT`l2(I6T|+~R!4^@4)U|l~Lx>^R z1Wa9o%#YvZbxNgRyxeZmbObw$To}33CZhNPAlGZjVmx5Y2@7Q|AjN>!*B9Jww`y6c zE;Kk((3A6HZOs{(dx zPe-1;B;LQ#+g$KytfN0#EcYf5dwk!ursQe!NCU@sAgbS6K#l})d(DX19bQN~9=&di zu|lxB2=VqN+@oDbi_zI)XdBPHbMy=00RQ_)(E6ko`sn7wH{Kh^fD^mxtqp_^8)nA* z_Sq1R5N{4GPz{W1G(#{>uupF{0i<)bqSeAoE$P@oH*IZH5xi@zx@KXOA*P=o5HMo_+0^R#&fF|Ly%ly0(cCt3&PHQq z376EmQfbe@?wM}R$>pE1Q5Z-X&SuA~yluS)Tq^aj>X8VyDb~C+3N3hA^KgVlSH#kr zc@?I*x|fEivD1qR3n7USPTkM-c|Zg*TWoD0mEK(&jRinOVAwf)CUqQ@Y$FZ$e7W7M zcIo-6AwUQbDNR!6rPgcRboG!M0?)RByRm49Ube=aL(6>-G-J1 zHux7%yEO}j53b94UqV}9q`d!p@Xr0-drq%V-w%I0xTnLaCST|ac~1ar4b^9%(dLaHt_@@*00rx5#0 zhN9t_)Oq{6mmtf5DBFi*}cTMOLLIh|cQde##SAke2j_;k&7HUfMB zl0Ksy?%wl(6`L@oCp$B}7`;xLpDj0$J4+AW`u$Y{^!Dq|7KrK10L-z=U1u_FE0}qHS{^9gpwKHsz;foSlz)gyP;X-sC72f-Cm|OLTwTm z%t@$7lW5sQaxV)Qkp-cN0k`R94ryE#ur@Oc%=3(Cx}k7xv}}SnnW006)EzCxfKTxS z^Ssz`7OAyKGLgvD#h9XG-&B)>0ClVbzPvpudK8+bDN21^mO8Aw-6lL90G9v;Ault& z{QTc{7`USjjJ%z(H6rr=(5CWihy>s#lz zImDvlrfzdjb>Kw0S@#d>^;H)$Ut=%pr3a{JSDj^nK}+892TTzQMP(y;ol-CFb80}i?O=7SVTk4P&B4COU z;DV|jWVyGYqpJP?wSC)?D>;&!2Y@82yXUr}F_TQD|NkI;fXt*_+nt@6oxYqtr>d9$ zLJx=tAd^TW$g1wK>B}h=nKvR3?jG(bNg$YfXt8oDuPX?fvu@Cd{EfK`UV86jU{x9r zNzaCceoB$mzmgR@SOKb5qY^rnGn@=7dGX+OO;WX{Q7hVKbeClO7?R~n!CWbT-!n1@ zw_ktRZHkY+lmnNkheFRDT$pFxcc!3hicqt$W*k%4Q$vEY615Ylz(`VXbPQ(+*>r$v zP2H>Avw(vX(Jp`AT9JATZ7;qE$3gv~wG%#WJr1LkZmRp7zk zX!Blg|NNV!zPn`s-rlOiS!S>kra=~OwJ`48T5gc1k{Iud+2OdtF*PBRl^tMV5G(|x zX?(~)sC1fSP*c#t=E_D!P z0Xc`;?N+mc~R-Z0)T7mZ1@#C8e4N$7FT2m97CmD7KU= z&Se$3DwCBbv2wmGGCQmr4jZm)M{Xa9Lc*81=u0jb&kTBEO_I<)?OiPk`(Qt_IQMG zvBI)5I*^U+8WXOIGe^nNjFg!dQr3xF(;IKEAMXl|{&WdJHqai9vVm4A#nZHE?~C+` z#HP3~BccZIZj&8Ute_oMi5;NEf>a0a%kN+lQcX^p3EC-e1b7RfWUkf53ieN%ty&z2 z0ZDTcmo~R~{#ckQP?e;SHjV-Y8v5v}-FHmUm>Fv3x*UlNWAOqmW_uP)od8%9sL=|h zz>tg~v;THplEPEdR4Oy%?Rl^E*`%8YFf%T+AipQTImFkmbKuUi`Bx7Egp=#~VXoPJ zO{3#{pAEV_X>M}V(2VlK+AU&lvp(b2b!Z|p!73an2-?Q4`(B;*?6LoM#sb_24$puv znsBe}NtS1U;YS(=<~gvJF~7fg9ZI*(Q0YjM8Wj2?xb&VyxxY@{)BU|v8iw}Pm zlK|CXYtd0z8VRFQ7ukZ?sRUx9XC|eeoMjsnmZtnH%{JJ(+qZ+ z&eKPe`$3=GNA{zO_e66u>(nsG8zVWsw0j>kGBs-cU7MV;PS;I14W6gF*3v>L>wFB^@koKufMo%eLht|)t})}= z>spIaBb#bJznxEEzR$`jYyxk=D2SXa7Wq{Y$(#3H=7>nFq^naIwQ^~ZE2k9eypBAE zSy>V;V4HWs1=n;%Mf?c3Co0m1t`ku&N8!#!u&? z%+yCV0GSOZtav+wyVDDoi4F=XwDCgf~q0MwCl=41fnQC!85 zyBiK_(h+0Rl{9zu7bbj2k*Q=YjO&!~0biTA5 z%jlU9ynE46|6Y7{@L0Ez;U{LeaBj%(SvvZm+YcWjcSD^uBi?SfUatt(?<<=vo6&7n z7@1Uzca3*T)3*VVkRW80p=oM;D{r#-mBzH7J-5A6jWPpUm0nG`uP<%nZn@}~og=_i zP$;e|V)R&E7F>P6?G~{}rcCv;REMrDo5W4ix4#=|w+yImx;A(*RY{md0k{U7VljkP z_fJ=*m{jJabw+DY&e`&8bY8}atj?%6*MysmDQ5-+ec$%$TjrD$42xN2Vm5NT%8W2) zAc)BU!7P{+K-5MOlEqV{hcNkLN~tO#T&+9IWV2M9*;qNfR&CH{nZ3e>jVWe8^}Z<> zXpX81PRi_<&b!8##38U8*Vpu20Rz`4b4Q)c=x9THS2OtYR1QOs5PcBt=vW?QxJSy4 zVHx7F5@9cgK9o5h?JKws(lYMv*{1*D{t*0G-qqOXyJuV( zpR$JK1~l553+!VQ^svGj6C@&9LNL`cA7HL@QjST`w3<4~4MM1kvC0L?jEk?2XXaAK z&0(gxBIvA4eeB2<;I@D#rL^SKeB+>2ByHZ<7=5SQCRRfWi=v>6Y_bob!qm}-O3`_Z zl6_(M20XWUf2IpR^J{-(b2mb>i8`4qcw9QPf5>}ZpfmX!CaBoca~pi-l*c^gBozD4 zq_fvxuEFRwW1|8^53qrc6yE`w(=F5(=%#xchz>&Z5v1!8w(97bbH{9AcU|LpD;vSf zcN>Ihf8=)!Ny}!m47D^9S%HM`yBqw;GdzlVh3 zh$)LatF}W0L~{+kUsuZ zd5&P4du2bC;K1-EtzMR5E)b(+y@_PaLbV$vRvC+RO(yTFY!q#zWOlu&&dg{D))^ah zPt%&G;g~w`Uz#tfpM|Z&PxEb5c1Bc(Z5hQlCoCms(=`o?HkqnsXK9MGsVZn_k*2G( zjYMI=ObEWZm1db&(i)m%#>sh)6#@p{-ofd1zZp8(TuvdxJZX^fL3DexLEqOoo;cksYFPv z89A4HE-gUj{<(9swDnSD#Io-X#ZK8ZCID>!9ZK*fZP6{YaZ?0RQ%YSUUCUg57bt`N zNwOFUHHCo}8Hn;2@`JE7ac^^$HrR~6Jj8V`)sviD=N(L7IRCl*1(gKJ?q4nY} zTIf=g-cvdGx39n0=3pw(csltQ4o-EC~}#NA>&3;>b(Orw}@fV zGw;0F=BgB2gJ)H`mYG3GGlVJ_=sW}PcFy0DfPr>=2WteK1xL@Uy`RPA3>KbKQy8AJ z@;!BC!^hUIySbmiTFfU5!y%ipL-8LDX&u$*lfdg4riADOG#xNBN5(uoP;s_Neq=Ay zn@M8+4QksnDu@$B%_J~z;+m3UJF1}ZVpL_F7z&$T8M ztd0=uy&J2|oXX&(fmyCvpO*EL&5S??Ii*FB_i~_=O>P0I$RBA_Av)tMnr1Hzh<60< zm*UnUwyFAgmQ&z@1##-nm97Abhsd98FpnJ1KBHrwH4b>RI6QrP6B_DXLr6!P^&KKIG7mUpSq|ndM#$7DN&`&i zy6hL~J6F!Lg41a-+H*a%vz)N$oGH*V4dEl#<7sn^3CE)@I(AZ+np~ux|MOq*!yo@x zm}cid$~bIkn!8z(JtO0GGO?CP2DVIyHYn5>7HpizItk9Sb2H<{#ms=E=JmXrnNhhF z$5QU&f2rtbZz!XBF9T97A8pQ0CR0*v|-V|k~nNu1dwV> zL6eWeTpKqM(9ZjABL~)7J2DR8gS2>6C)ltn121HKiB|agGnS>FLINpXt)B=O>`;BdUmL zY5&=?zz43M`25+_uFQV)JDvO6RT|Z-G3OmFKm4(*$B7LSLPMIh?6Pz2?*45r^WM0o z8q2T+9p6i`0U*d44Ci1&l8)TQokt6azJt!nlzA40_d)1+7^_q5I}7a}bF$Rx%k^TY zPc3Hk#LT@#E~09*6`?GWwlZg<=bjrThZ%6hGL{M~%TiBV&^g@*gixGgm>F4QdMwUv znH==g-@bmir;-l`;0GBwN0j7eu{Ogl`;(fdX_-^cJp}`u^US7xf_6P!IC?{jCk-HB z>=rZAICh(;!839AyF5Nuezq~~ENIVE<%iL|4=mhwm!l(rc*OOsGr)R#{Z=-);Ue=0 z#i9}!D1N@qm=V{J z)}%lirj}J{&Q&waz>Le{%``!079CLut`s*)=W+qP4$`|#?PAYkQ>2Rm?du z$+JqfRE8WgZ;(BRqnVSSO9+Fba<(M|WX@REGW)3@mIirhGt*vw=cIaMvir*7)!b&m z)qSCC{PkHd=T4d5Y1-bFnKHJ;+)3s2jsSL6@2Xsl>O7Hvfhi@E25xM(9pQ4l*!|S- zPe+9zQZR6T?zZUwK*Tj_L2iim-lS~VWOojc3mEw0fBfrK&V9!q@C3Wd_up&!ARsck zk>&>tem0xG3AfRnwCRj3!lcUM=(=JzPsDpr>w$g9rdjDoen;~;hYjaRQ*$H-+p{m- z#)6LRj%V-v!y^N;&Du#Q^^v9aBX#sB1oc$T*ZE#@XD@3&7UQSC{u_Sy^wXH?) z7o_X_a-#hlH34TH{XI7|eqccz+H{TZ%(J`434-Q$DjWTasp4r$JQ z7am-=N2%Ri6tu$zqL1!<`TM^k#fZ!G0)KhIdb<@f6JoO`)=ZJgDA2}DZO`6RR-Da8 zi_teGXfpsZXS4CG&Q}?pf(?U{NT`$ra*o8AtbRW4@(9{vv}F32u&xPfXk^1C2V>h9 z+bjqJv@6EkvPvS+Q~2M4BZ-hnkv@WlTua}`rKBMUO8}*el!SE`$1pF$_bFuo=-4*- zL!%-UIB+qD(kLz<=SR=Ot zdk&Vxn+5i=NG6Y%Ni1qcz$*VPugyeAT#h$0@c!$UjdZ+6Oh1e?(}yUKIbiB^{o;c_ z&u1-nPZ*R(A`H%EDMoU1o|#j9U>5bL4$sJ!kD9@$(DEbG0Mz~1qt@L$(Cla~}i>7mgC3qVYQe;RU+S2qC`JC#eOY*a|NjqEkLh}djjE-*u?zpwvq?!c) zCUEcw{({$h1zyWdir;>H5KW#5r2HT)J4He6oG)e<*N<*Mr_lyJ*ID-p)09s=2G-Ok z3)<*9jTYMB!u>!(^Zw^&_vNk_@fZQ@Av$Na*>|^x2RRC(=Awc1Km3eMT${7-xT9uM z{<;40&$bTIhR{1;X1mC5BxJhYWeZd$k>S=uWwX2A zhNsm5%>6y*ruk6xzcqDJ-_u+t`4o7)7c`xGbRz?g|*F<^UzThm28U zlX{T-Zkb^skg!z6)Ih+&M&bbgYm8zrR2rzl*3|c`;i`2Ow*>>sO}ilF^7(IHe(Fd| zCUUX(Bp~}?cIFdb&lA~ckAQDI7G%Fa7-i6LFKca7F9reg~@`T+gH0 zuvu7Un6?vhh)rXIdDDuvem<1DH>A3lWukO`TF(m|A81It}hq( z>kHP~yX8u1&KG4aVzH6MC{5JVwU$kRhz4(3Z_X2o9Iaf^}WtMLSru%noae_!55y?>*k$Zb-M+ z1Dg5Z=1-wO_`s0*B!hCQ=N!0q9EF7)A@hvq(1wSy5+0Z-d1~W)6h!%eH~x_v;ZC;r zB$L+-m1`Vu_#@Zhq*xzqSVrho_jGuRsC|e@r1PQQQ87J|vNcDV;)?6b1BVn_CC8rnzA546`=H*W5LCR?scI&p9LR2E}VwBUNX!CclSyxA|y_ zMNS!O%!sk%zue^d#*_-vqQm4W#o9fWn|GFD)Yo|lF|`>N*92Hf;G{NeCEPPt2eoDf zM(8l4n5xl$)SPvVl`VsYQah_*=2|A-@8CUd;=ZFSNtyd}BByrN_$;BYJ6Xcz$Pp+p zm;?+IM#;3`m!%prpi01EOl3|;Y9&Gd85mfMddwY2)C|rXPn*X?88oUhM=51%W=foc zG*xICXuBpQPi|ckyl0b>=gcB^Eb>4$37dj}0Wa4J-tq%mb5M0=e=z;?84GHh5BHz4B?ILHaJ)C+gV6Ba zhJAR>9WeDysx={Z?*Xhm8QmRlJNoWCW0G{Tcbd(r8W=gOUw&+q49>n6+|~&yYm*lf zmb?4WIkxJw)|PzQ5r{RDivPHQo)&Hk+{ zu9qcPSXuDC=(k-7Ld!WI#f+3wVQdIMV;p3`%uo-+00(?UR~kiY#HSc<%!_XV|I@>esu$ zM+J<|o4nZqbf-J{s3ec)*`QOlv-4NF+3S~=A7mbbc1iW^)nf^JBnuyFDfQlVL^a2S zS!i6>HuCzrp}b6uJ_!m2V|I09X|gaD{qKK|%lE&p$<4aK-)Fw)TDJ=|YiDY>VJ{4QQX76$bCw!z1_NGH znzproCYz7YKU0)lrAZ3-sMM{^-l1mGuAiToal5Sm3hph zW(-XTr~ql6JVH~Xym$Ei`zsj0?R_nP7?%cSxrCB!$*_>=%8)QFVt1^J)ny6rA(a0n zVDSqeb0k?@HMwzkgE*UIH1knv0Sg=Sr!YM7{)ZHVm8hBBkRDP&t+o z$XUU_WeMUW2LvB*5$owSCNM8DW0cJGP3^BWjME9Imotm=n#?sBE5s%b%uPOzmzk!N zlSwJP%)XN3`~>gua=pMy!0PR`A_R}iWhsq&F3&=YD{hI9*%@+rkH}5}aZ{ku2RD4f zIn)9BJXAx>u4xmBgIV;PPfT}sRz`iK>Nq={llME4C?4hk@wuGt44iys&A)pVX4#Un z0Q8CLarjvLMggHm*M6wL7+jD2@1<1$C5OxRzsEQCS7~hA-92tyKH*%mEn#9lzvwqeAu{j5bb^9u*qxa^EZ5>jo^kcqVa=!y0Gk#fC;AR452z4>O1=x z#)un$>CAzDAV2(3v5;AhNK~U@Ht@{i&b1rqp zLJ_m-P?k0nzvbra%n;O-D<%fNGYD_EEun-}%KMpJXVbuK&ZG$*<+fpzW4XR8aNd4hg>n1$(iAOan8J47TnggnGa=| z&CH0YO7zSu!4cA$O$m@Q3!q2RT$SN`??ncNI!_g2G+@p-SDfZVcDBX{#AryQ)A>|= zE}X;V5|Bmyr@3rNtfCd5V^ZtpRA!*Sr9nY;jB_$eQ=fS8S5HB2sStCgU7lS1xIw>fl)$np&_3%xrXkgwj))+XUrh%CBx4)6n8ap z(uVp`c4=laKMGj>h@5`rHIK}qoYkE(bDP6+_-IX;1z879cn=@MnTy_UP$*BMOnN}& zh(+65I47*{uORvZEsTiibB8ic$5@VevLN z)OK%0LXgc~Is}i4r$p_EGl6oN+<*CFo%e)-2=H`Li3 z(tqe!G7;vrajAIbd8Tv3Yc#la^rh~(#SJZuPu_2KK<-F`+CxoFts|SwG*8%eKAaVF zG_SHhuHGyYPe?9!j=ecFws_RWxraoa$Q^l~(t=}I=2-&xN6@H`G^K5mbMU&iUw;Pw z`7c;5m%^Ti{0lo)#w18Yn}A0h?rt~w)Y9rB-8NNcHd2Nmt1Y$80@Vx|4P#Wa-%}{r zJ&r&!h@TU08>+?)EpwFs13*lS_xEUxS>AnREReaez23~`;7&eWL#1=MURllw&1XAV z_rnt4f=7D46-I;f*efta!oXZ!775@K7R5QNYXZk8jZw7XSU|66M|E4HfoB?Sh@Q@+0$duYtajQ|^Wj9o7eXkGaw%brw<4SK-ezI7KC1<60RtU=S^X9` zqX(E4=3~(2Xb#ktn@5T!_nG<+J6QHCtUJxl!|zWg02c-zWhY2-idn$;x<9%W-!%X@ zW|_MCqMiW&kHO2{e~%cVL#NqM&E>w+AD;lLGpdZE^Zcx)r`HG%rGb3EFBmaxvVMR6 zFaN!Oft)3}WebLp06D!T$ijj}#%wiow?EW1j+^}jxytl}5Ill+)qav;$dd-3l~6Zt zL!qhB8#4&r0WU9CnRltfjn6BR8EJ02dr`t~SsFU4)&zmxin+ zNo&qc(LIpO3@w)h%Vojs{Z@+McP}<8RGe^%!%YYow*;&SNR;sH=O5>~;ueJ>8as9L z(Du&?`kbcoM=Zzzk~SK^8x5(Q(xL|opjkYQY$P8*-5#NDyG?0Z%=X;q0d+lE{6{j5 z*+usdiJU?G2I$ox!-3-_9i2tK_x_&&OdT?0orZcJYq0-X{qp^~)lX zHkGAuKchqnj?Mq542~IV%D}35Fg0u~pEzHc{H<+%yl>nyOKrGZ7IV5>Q^tB*1&nfL z22e8DvNac_(JKZBm&=0d%L}|K(r7b7kOqM{+xxM|vPzaqoy*a@G>bF{!GN+hN?=)* z+GJ=zrzizdPEr@y6b)_Iv^E;%+NljGRY%cmO-GY`q}JCm=&y4*tqY!dQ0Sbj<=3Hc z%WDu*9|F8vOtKf(SPX?0uFiE$6A^-!8C%WXQ8182;^y(?AOC5MJ&2Cik+b#pFxCKl zpy;C#9ngs#^MJ`7ny3t%KSvw!ht6%nYWQrPrB}Q85hi1jWtm|Gj;=xXT4A85nXI9w zuA4Xq3h5|}l^=gDhwK!8GQ-1T0R9jFKW^Gyzx;$h{L7yatnQ>T%~@m!jYK(gKC zF-xWb2)HbZSdEq;A#JRjcL=WNm`PHy*ENY0A|si9Hc5DAup*GT2B|61RBc5gIC~_K z#)V}mdS+-sb14$H+gj#%)+qn(K_P%L;qBL7=4jg?z5dC;n-3u>N2ATN8}Z4)GLt$z zY!4#vRYMi%roZGv_*3fVVC@3=?_CLorW)U=O<4s4y)kT%hRkXv6TAmru2*T=O1(2P+=85BGf4_Q=FBDArfH5+%2*{=#|K|PMpv!4Q_d|-XxHPiELcJi z*HgxK-(Ai1NM-EamFscKz%2pUWqkYPNBK(a*=(F6*4@qL%$o8fdd&lr`e?IEG(PS} zkBd6j>8_cYX?FH9`J;7~j)APHMi2vo1w1x4HDoFdYQ>T4`E+lAK|T*o6eV=b){U^l zQDenN$JQ}i80EJ;s`42&MSQLbnlS0PeftU$QxtC8U3Hcp7H!Y~h3&UbT}L-x2|8%l z>F)eg0pPtySl0xi+&G^JEwpnD%QE2D((dF47ttCkRRjV&93m%cL~gfOhgh{Zn@uMg zNkiVCTE)_`%1~EA@H;IrxxNXrwQtEd||0lhKy|67?IjVK&TQ=yF!u z%%es40mO!Ov~c%52Mh7Ei_n2h=2Oof&p$V#!Zuv2pJdynOf;x3PuZLUhIve1|M@q> zb%plT7Bhe1_#+bp5#iR$gTrL~=xjNn5ZZ|mZ5N`>$bp?@! z3k#4P-hTaM=bAS$PdSWA_{<1^C&8Z{D0ZZRn29#ntX(HY2YV3isNtDq@9C&97)Yv4 zY`-NtGFRP7m=*;s)tgF=(d294cQ`Jnk6H9k)!9c)_Xlj!~cM%KR*xu{f$MXN2GIX>>rMU(II%-B#cc*q z*PDtimcdPu0m!N?f4N?9y9=P7Z@YN;}EGcRAKbc ze;;T&$*sV_IWTYwKVw0mUkY!0TY!yat1&zj1!e1*fLW7FIo3$V#Uwnj?lNA_5D zmJm+OylFMmdJ^81Kufi_-dcWc^DH#rnW(T~j+_}AI9Kv)Agb$S2}M%2uJFqR&J{Bp zP+{hCO4c;6&9T%>8MT#8E{W_*Bogi3OJsu~1ZgyQ+w7=00U)(4<%)E>Rg(agc}9Jn zr~(9gMZqTL&C#~b$-Y0SdW-7o6>|z6;NVdomvv;n9rH{+bRY z2`8>={0S~Y(-M>kE%o8zy}kBC;@0II!gs#||NLLz)`e^b@L9v70iS4$0@`^ULH$Lz zb+_@fc^{eOC>w2AYsF??2g$iv+^N|E=)gXMcNs4AvzkO7D;)MS3vR<5lm?&Vv4fC&t^KQSumP)lVXzDnT(4I zVw}Su%60JG*bEjoHZovM0lsqF8VXuNF4q_>@H2C+qj)5R+k3I6R+bL%4~57tC>8yb4b z{J_xq)JfiNrul?9AJwB7aCiF8XXas^Rm#w~j@&QwgZ)$Ux>m7r$D;9gHVhvG2KfQQ ziL-suC=x~f^X;dwT8)*j;ICpNM89PRE$(5jKlYUV*db4+=76T4gZ&So}-8|E|X#mVKJEx%jCKb?SqDOF~u%)Df2P{^c*)wn@GMDI&RkQ~dh6xX;cvpl8F z7Lf3Ay_6Z6CE)Gt9dEDiMKUVRSo2WxbheJuPQk|K#xBD^%-Q8g}L>33y}u9u4x z=WGa{>b#W((?#BjU`$9cTk&9_`g3NyB`T@iw|8(}n`dCcy7A1e`84S4=@lDe5A!GX ziaqLm=;rmz`EaucqoX$-N#`cqOL}zkLqN#Dm|+T0oG@Q_reWod^nqydefOx}$Z_VN z8Jx1$JkZx4HgB`{rK4Xz3N$^V=(`R=_n&ur{fcGz!zSM2-rT8aMs_Yzx(HhXVZn@h zsmrzylCnH*oBC|S=MC}&h|x+b?QNH=rbxJEZiqINPvf|?Lo03FZE|7S>sgHjV3M>= z@TWBuWetCSze%PGu*QV<_ZybW1-ErI(5jUI=9I-94Oqg0l%iQ1tAwhsB3{@YfM}8R zpMYk#U++!HQ1ix`D5GKZpU^m*ZEtxAy(HY$8yuAxp_DURCXmd^EK8Aht+!~iFJ7c? zEbe4#CZJBE-WTw0U6X}v>v>tQr)t|b8B89TQzO-uuYd!tm!&wT`Qn^f**@Cj;L4}=@}AB^VyxKcUK8L{20sk394IT!>g%-2+%pP? z53o4HbD0EwkG>boK)NC4jAdDH{llN}YJE@~#2)n%a`<*%ueK zqI^)7$yVk@077w9srv6F1f*F0%r$nV&O10yBIBas%;Fq4v1JfAK@qbIGQQnzw%9qM z64sU(&X?5V5Vi^4Ua5U)m?&dYe06ZL=$V}*K&P1Smfvhx^|s!uX(8v$K_;%zbnliV z?g&9ss2u?wKqAC7fE?ld+t=;Fzj0wYd6;;1Q~n@2{Sc*yV++ff=ITsS+*>4{*AAR4 zRA;|4$bB(~nF+*hy78Dr#c0O>av$wGlg>>Qui3?j$MxgBhr%iMnU zN9RC@K$>NwNQ@LTA;>;Q?F*qjNo^UUe1A2M#g?%6dS{YHn=UN0w#Iy z@&0}@Mjar;xJphB%t~~P5hFswPn8r^{FHpR?^xt*cMgohcI(+OZHvpw9%dzGuj1*SQ%dva{xJYEwIU|A9>D&My04 zP6hn@=6^4Lo;}Y;uHDgI;B=k}I1NXCC{O6jG4-?dSx+=hqezcEdy*M%U%y}pe=^g6 z{dMIH=+^{x()Jp(Y;tQ6y>GiSXPf1$%@D&WDyWE7G`mqn1B-Ehy01jZpvkF(XsX3? zZHNdA61z``^Np_>=4RcfVLze)PFZAV*aXd$yc;KBo>`hDZ<#l1jCjATxUDPJnDF}c zCLx{G-7RNnqrg#0a}nMZ#}C!c)`N__q4A4oB6oLaakXqC00-MjI&VX>yAngO^?R!sfa z+~l0xom%r;sDVpX*Dds%vUz)aJ2QjL72+z%;*BMABh`}sX;5kV)_20dom?0I5;Inr z=TOEy^VYt3U1OQKOfoPp61i$vlZ;7lR55bq0003bNklH-| z@PQzXYic*`ox}BdHD^1$EUIW&V-(3*W3CXqgka~5@q-!)EK8{2o~}v;y)WRL&M@Uv zn5-x+XbLD+J7|(QC$=C~GY&wV&Cz2u;=s8QjSvcpRO)QP+uJ*mvM+D%Me--|y3zn$ zj2+ZWA5~5i!vxsBJMRIvz&VfG+iUIk=%7Z9fD_tm4zQso=f2<{c-_I;b-3X@vD&?> zfxKOFk2Z;qf^02I{Lr~mpMsvM``AkEy0b^4LHGjz_~>ejz=!7zrjB4?0a+AobmB|E;Rp=@WWsJXJKRZ->f$0W;0S!CAjuXP^~fb j8qoIXYHC?E^o00000NkvXXu0mjfwA(pD literal 0 HcmV?d00001 diff --git a/Docs/map_customization.md b/Docs/map_customization.md index a242dd427..ce029721f 100644 --- a/Docs/map_customization.md +++ b/Docs/map_customization.md @@ -22,7 +22,7 @@ - You can change the seed until you have a map you are satisfied with. - After that you can place new PlayerStarts at the places you want the cars to be spawned. - The AI already works, but the cars won't act randomly. Vehicles will follow the instructions given by the RoadMapGenerator. They will follow the road easily while in straight roads but wont so much when entering Intersections: -![Road_Instructions_Example.png](img/Road_Instructions_Example.png) +![road_instructions_example.png](img/road_instructions_example.png) > (This is a debug view of the instructions the road gives to the Vehicle. They will always follow the green arrows, the white points are shared points between one or more routes, by default they order the vehicle to continue straight; Black points are off the road, the vehicle gets no instructions and drives to the left, trying to get back to the road) - To get a random behavior, you have to place IntersectionEntrances, this will let you redefine the direction the vehicle will take overwriting the directions given by the road map (until they finish their given order). diff --git a/Docs/measurements.md b/Docs/measurements.md index efe4ce776..4ce169b1f 100644 --- a/Docs/measurements.md +++ b/Docs/measurements.md @@ -1,6 +1,11 @@ Measurements ============ +!!! important + Since version 0.8.0 the measurements received by the client are in SI + units. All locations have been converted to `meters` and speeds to + `meters/second`. + Every frame the server sends a package with the measurements and images gathered to the client. This document describes the details of these measurements. @@ -10,10 +15,10 @@ Time-stamps Since CARLA can be run at fixed-frame rate, we keep track of two different time-stamps. -Key | Type | Description --------------------------- | --------- | ------------ -platform_timestamp | uint32 | Time-stamp of the current frame, in milliseconds as given by the OS. -game_timestamp | uint32 | In-game time-stamp, milliseconds elapsed since the beginning of the current level. +Key | Type | Units | Description +-------------------------- | --------- | ------------ | ------------ +platform_timestamp | uint32 | milliseconds | Time-stamp of the current frame, as given by the OS. +game_timestamp | uint32 | milliseconds | In-game time-stamp, elapsed since the beginning of the current level. In real-time mode, the elapsed time between two time steps should be similar both platform and game time-stamps. When run in fixed-time step, the game @@ -23,27 +28,27 @@ time-stamp keeps the actual time elapsed. Player measurements ------------------- -Key | Type | Description --------------------------- | --------- | ------------ -transform | Transform | World transform of the player. -acceleration | Vector3D | Current acceleration of the player. -forward_speed | float | Forward speed in km/h. -collision_vehicles | float | Collision intensity with other vehicles. -collision_pedestrians | float | Collision intensity with pedestrians. -collision_other | float | General collision intensity (everything else but pedestrians and vehicles). -intersection_otherlane | float | Percentage of the car invading other lanes. -intersection_offroad | float | Percentage of the car off-road. -autopilot_control | Control | Vehicle's autopilot control that would apply this frame. +Key | Type | Units | Description +-------------------------- | --------- | ------ | ------------ +transform | Transform | | World transform of the player (contains a locations and a rotation). +acceleration | Vector3D | m/s^2 | Current acceleration of the player. +forward_speed | float | m/s | Forward speed of the player. +collision_vehicles | float | kg*m/s | Collision intensity with other vehicles. +collision_pedestrians | float | kg*m/s | Collision intensity with pedestrians. +collision_other | float | kg*m/s | General collision intensity (everything else but pedestrians and vehicles). +intersection_otherlane | float | | Percentage of the car invading other lanes. +intersection_offroad | float | | Percentage of the car off-road. +autopilot_control | Control | | Vehicle's autopilot control that would apply this frame. ###### Transform The transform contains the location and rotation of the player. -Key | Type | Description --------------------------- | ---------- | ------------ -location | Vector3D | World location. -orientation *[deprecated]* | Vector3D | Orientation in Cartesian coordinates. -rotation | Rotation3D | Pitch, roll, and yaw. +Key | Type | Units | Description +-------------------------- | ---------- | ------- | ------------ +location | Vector3D | m | World location. +orientation *[deprecated]* | Vector3D | | Orientation in Cartesian coordinates. +rotation | Rotation3D | degrees | Pitch, roll, and yaw. ###### Collision @@ -100,6 +105,8 @@ carla_client.send_control(control) has a maximum steering angle of 70 degrees (this can be checked in the vehicle's front wheel blueprint). +![Mustan Steering Angle](img/steering_angle_mustang.png) + Non-player agents info ---------------------- diff --git a/PythonClient/carla/benchmarks/benchmark.py b/PythonClient/carla/benchmarks/benchmark.py index 2e6f3a164..18d96b7b5 100644 --- a/PythonClient/carla/benchmarks/benchmark.py +++ b/PythonClient/carla/benchmarks/benchmark.py @@ -119,8 +119,8 @@ class Benchmark(object): image.save_to_disk(self._image_filename_format.format( episode_name, name, frame)) - curr_x = measurements.player_measurements.transform.location.x - curr_y = measurements.player_measurements.transform.location.y + curr_x = 1e2 * measurements.player_measurements.transform.location.x + curr_y = 1e2 * measurements.player_measurements.transform.location.y measurement_vec.append(measurements.player_measurements) diff --git a/PythonClient/carla/benchmarks/corl_2017.py b/PythonClient/carla/benchmarks/corl_2017.py index 5989ee1d2..f005c1e70 100644 --- a/PythonClient/carla/benchmarks/corl_2017.py +++ b/PythonClient/carla/benchmarks/corl_2017.py @@ -142,7 +142,7 @@ class CoRL2017(Benchmark): camera.set_image_size(800, 600) - camera.set_position(200, 0, 140) + camera.set_position(2.0, 0.0, 1.4) camera.set_rotation(-15.0, 0, 0) weathers = [1, 3, 6, 8, 4, 14] diff --git a/PythonClient/carla/image_converter.py b/PythonClient/carla/image_converter.py index 2b3b44491..b75ed3d22 100644 --- a/PythonClient/carla/image_converter.py +++ b/PythonClient/carla/image_converter.py @@ -114,7 +114,7 @@ def depth_to_local_point_cloud(image, color=None, max_depth=0.9): RGB color of an array. "max_depth" is used to omit the points that are far enough. """ - far = 100000.0 # max depth in centimeters + far = 1000.0 # max depth in meters. normalized_depth = depth_to_array(image) # (Intrinsic) K Matrix diff --git a/PythonClient/carla/planner/converter.py b/PythonClient/carla/planner/converter.py index d33c8bada..0f683c457 100644 --- a/PythonClient/carla/planner/converter.py +++ b/PythonClient/carla/planner/converter.py @@ -137,6 +137,7 @@ class Converter(object): """ rotation = np.array([world[0], world[1], world[2]]) + rotation *= 1e2 # meters to centimeters. rotation = rotation.dot(self._worldrotation) relative_location = [rotation[0] + self._worldoffset[0] - self._mapoffset[0], diff --git a/PythonClient/carla/sensor.py b/PythonClient/carla/sensor.py index 2a09cb019..aa073145b 100644 --- a/PythonClient/carla/sensor.py +++ b/PythonClient/carla/sensor.py @@ -49,9 +49,9 @@ class Sensor(object): def __init__(self, name, sensor_type): self.SensorName = name self.SensorType = sensor_type - self.PositionX = 140.0 + self.PositionX = 0.2 self.PositionY = 0.0 - self.PositionZ = 140.0 + self.PositionZ = 1.3 self.RotationPitch = 0.0 self.RotationRoll = 0.0 self.RotationYaw = 0.0 diff --git a/PythonClient/client_example.py b/PythonClient/client_example.py index 4270199ff..37b01da5f 100755 --- a/PythonClient/client_example.py +++ b/PythonClient/client_example.py @@ -60,19 +60,19 @@ def run_carla_client(args): camera0 = Camera('CameraRGB') # Set image resolution in pixels. camera0.set_image_size(800, 600) - # Set its position relative to the car in centimeters. - camera0.set_position(30, 0, 130) + # Set its position relative to the car in meters. + camera0.set_position(0.30, 0, 1.30) settings.add_sensor(camera0) # Let's add another camera producing ground-truth depth. camera1 = Camera('CameraDepth', PostProcessing='Depth') camera1.set_image_size(800, 600) - camera1.set_position(30, 0, 130) + camera1.set_position(0.30, 0, 1.30) settings.add_sensor(camera1) if args.lidar: lidar = Lidar('Lidar32') - lidar.set_position(0, 0, 250) + lidar.set_position(0, 0, 2.50) lidar.set_rotation(0, 0, 0) lidar.set( Channels=32, @@ -158,14 +158,14 @@ def print_measurements(measurements): number_of_agents = len(measurements.non_player_agents) player_measurements = measurements.player_measurements message = 'Vehicle at ({pos_x:.1f}, {pos_y:.1f}), ' - message += '{speed:.2f} km/h, ' + message += '{speed:.0f} km/h, ' message += 'Collision: {{vehicles={col_cars:.0f}, pedestrians={col_ped:.0f}, other={col_other:.0f}}}, ' message += '{other_lane:.0f}% other lane, {offroad:.0f}% off-road, ' message += '({agents_num:d} non-player agents in the scene)' message = message.format( - pos_x=player_measurements.transform.location.x / 100, # cm -> m - pos_y=player_measurements.transform.location.y / 100, - speed=player_measurements.forward_speed, + pos_x=player_measurements.transform.location.x, + pos_y=player_measurements.transform.location.y, + speed=player_measurements.forward_speed * 3.6, # m/s -> km/h col_cars=player_measurements.collision_vehicles, col_ped=player_measurements.collision_pedestrians, col_other=player_measurements.collision_other, diff --git a/PythonClient/manual_control.py b/PythonClient/manual_control.py index 0eabdcc19..638e9cf36 100755 --- a/PythonClient/manual_control.py +++ b/PythonClient/manual_control.py @@ -80,22 +80,22 @@ def make_carla_settings(enable_lidar): settings.randomize_seeds() camera0 = sensor.Camera('CameraRGB') camera0.set_image_size(WINDOW_WIDTH, WINDOW_HEIGHT) - camera0.set_position(200, 0, 140) + camera0.set_position(2.0, 0.0, 1.4) camera0.set_rotation(0.0, 0.0, 0.0) settings.add_sensor(camera0) camera1 = sensor.Camera('CameraDepth', PostProcessing='Depth') camera1.set_image_size(MINI_WINDOW_WIDTH, MINI_WINDOW_HEIGHT) - camera1.set_position(200, 0, 140) + camera1.set_position(2.0, 0.0, 1.4) camera1.set_rotation(0.0, 0.0, 0.0) settings.add_sensor(camera1) camera2 = sensor.Camera('CameraSemSeg', PostProcessing='SemanticSegmentation') camera2.set_image_size(MINI_WINDOW_WIDTH, MINI_WINDOW_HEIGHT) - camera2.set_position(200, 0, 140) + camera2.set_position(2.0, 0.0, 1.4) camera2.set_rotation(0.0, 0.0, 0.0) settings.add_sensor(camera2) if enable_lidar: lidar = sensor.Lidar('Lidar32') - lidar.set_position(0, 0, 250) + lidar.set_position(0, 0, 2.5) lidar.set_rotation(0, 0, 0) lidar.set( Channels=32, @@ -273,7 +273,7 @@ class CarlaGame(object): ori_y=lane_orientation[1], step=self._timer.step, fps=self._timer.ticks_per_second(), - speed=player_measurements.forward_speed, + speed=player_measurements.forward_speed * 3.6, other_lane=100 * player_measurements.intersection_otherlane, offroad=100 * player_measurements.intersection_offroad) print_over_same_line(message) @@ -285,7 +285,7 @@ class CarlaGame(object): message = message.format( step=self._timer.step, fps=self._timer.ticks_per_second(), - speed=player_measurements.forward_speed, + speed=player_measurements.forward_speed * 3.6, other_lane=100 * player_measurements.intersection_otherlane, offroad=100 * player_measurements.intersection_offroad) print_over_same_line(message) diff --git a/PythonClient/point_cloud_example.py b/PythonClient/point_cloud_example.py index 50c53867c..65bef0d65 100755 --- a/PythonClient/point_cloud_example.py +++ b/PythonClient/point_cloud_example.py @@ -33,7 +33,7 @@ def run_carla_client(host, port, far): frame_step = 100 # Save one image every 100 frames output_folder = '_out' image_size = [800, 600] - camera_local_pos = [30, 0, 130] # [X, Y, Z] + camera_local_pos = [0.3, 0.0, 1.3] # [X, Y, Z] camera_local_rotation = [0, 0, 0] # [pitch(Y), yaw(Z), roll(X)] fov = 70 diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp index 5a918eb29..553816786 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp @@ -17,7 +17,7 @@ UWalkerAgentComponent::UWalkerAgentComponent(const FObjectInitializer &ObjectIni float UWalkerAgentComponent::GetForwardSpeed() const { /// @todo Is it necessary to compute this speed every tick? - return FVector::DotProduct(Walker->GetVelocity(), Walker->GetActorRotation().Vector()) * 0.036f; + return FVector::DotProduct(Walker->GetVelocity(), Walker->GetActorRotation().Vector()); } void UWalkerAgentComponent::BeginPlay() diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h index 7b1ead9b7..111b41d37 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h @@ -23,7 +23,7 @@ public: UWalkerAgentComponent(const FObjectInitializer &ObjectInitializer); - /// Return forward speed in km/h. + /// Return forward speed in cm/s. float GetForwardSpeed() const; FVector GetBoundingBoxExtent() const diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaHUD.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaHUD.cpp index b2484286d..c41eafac7 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaHUD.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaHUD.cpp @@ -69,18 +69,21 @@ static FText GetHUDText(const ACarlaPlayerState &Vehicle) HighPrecision.MinimumFractionalDigits = 2u; HighPrecision.MaximumFractionalDigits = 2u; + constexpr float TO_METERS = 1e-2; + constexpr float TO_KMPH = 0.036f; + FFormatNamedArguments Args; Args.Add("FPS", RoundedFloatAsText(Vehicle.GetFramesPerSecond())); - Args.Add("Location", GetVectorAsText(Vehicle.GetLocation())); - Args.Add("Acceleration", GetVectorAsText(Vehicle.GetAcceleration(), HighPrecision)); + Args.Add("Location", GetVectorAsText(Vehicle.GetLocation() * TO_METERS)); + Args.Add("Acceleration", GetVectorAsText(Vehicle.GetAcceleration() * TO_METERS, HighPrecision)); Args.Add("Orientation", GetVectorAsText(Vehicle.GetOrientation(), HighPrecision)); - Args.Add("Speed", RoundedFloatAsText(Vehicle.GetForwardSpeed())); + Args.Add("Speed", RoundedFloatAsText(Vehicle.GetForwardSpeed() * TO_KMPH)); Args.Add("Gear", GetGearAsText(Vehicle.GetCurrentGear())); Args.Add("SpeedLimit", RoundedFloatAsText(Vehicle.GetSpeedLimit())); Args.Add("TrafficLightState", GetTrafficLightAsText(Vehicle.GetTrafficLightState())); - Args.Add("CollisionCars", RoundedFloatAsText(Vehicle.GetCollisionIntensityCars())); - Args.Add("CollisionPedestrians", RoundedFloatAsText(Vehicle.GetCollisionIntensityPedestrians())); - Args.Add("CollisionOther", RoundedFloatAsText(Vehicle.GetCollisionIntensityOther())); + Args.Add("CollisionCars", RoundedFloatAsText(Vehicle.GetCollisionIntensityCars() * TO_METERS)); + Args.Add("CollisionPedestrians", RoundedFloatAsText(Vehicle.GetCollisionIntensityPedestrians() * TO_METERS)); + Args.Add("CollisionOther", RoundedFloatAsText(Vehicle.GetCollisionIntensityOther() * TO_METERS)); Args.Add("IntersectionOtherLane", RoundedFloatAsText(100.0f * Vehicle.GetOtherLaneIntersectionFactor())); Args.Add("IntersectionOffRoad", RoundedFloatAsText(100.0f * Vehicle.GetOffRoadIntersectionFactor())); return FText::Format( diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp index 40626aa90..9e43fa0ee 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp @@ -17,6 +17,9 @@ #include +// Conversion from centimeters to meters. +static constexpr float TO_METERS = 1e-2; + // ============================================================================= // -- Static local methods ----------------------------------------------------- // ============================================================================= @@ -43,7 +46,7 @@ static void Encode(const FRotator &Rotator, carla_rotation3d &Data) static void Encode(const FTransform &Transform, carla_transform &Data) { - Encode(Transform.GetLocation(), Data.location); + Encode(Transform.GetLocation() * TO_METERS, Data.location); Encode(Transform.GetRotation().GetForwardVector(), Data.orientation); Encode(Transform.Rotator(), Data.rotation); } @@ -103,12 +106,12 @@ void FCarlaEncoder::Encode( Data.game_timestamp = PlayerState.GetGameTimeStamp(); auto &Player = Data.player_measurements; ::Encode(PlayerState.GetTransform(), Player.transform); - ::Encode(PlayerState.GetBoundsExtent(), Player.box_extent); - ::Encode(PlayerState.GetAcceleration(), Player.acceleration); - Player.forward_speed = PlayerState.GetForwardSpeed(); - Player.collision_vehicles = PlayerState.GetCollisionIntensityCars(); - Player.collision_pedestrians = PlayerState.GetCollisionIntensityPedestrians(); - Player.collision_other = PlayerState.GetCollisionIntensityOther(); + ::Encode(PlayerState.GetBoundsExtent() * TO_METERS, Player.box_extent); + ::Encode(PlayerState.GetAcceleration() * TO_METERS, Player.acceleration); + Player.forward_speed = PlayerState.GetForwardSpeed() * TO_METERS; + Player.collision_vehicles = PlayerState.GetCollisionIntensityCars() * TO_METERS; + Player.collision_pedestrians = PlayerState.GetCollisionIntensityPedestrians() * TO_METERS; + Player.collision_other = PlayerState.GetCollisionIntensityOther() * TO_METERS; Player.intersection_otherlane = PlayerState.GetOtherLaneIntersectionFactor(); Player.intersection_offroad = PlayerState.GetOffRoadIntersectionFactor(); Player.autopilot_control.steer = PlayerState.GetSteer(); @@ -199,7 +202,7 @@ void FCarlaEncoder::Visit(const UVehicleAgentComponent &Agent) auto &Vehicle = Agent.GetVehicle(); ::Encode(Vehicle.GetVehicleTransform(), Data.transform); Data.type = CARLA_SERVER_AGENT_VEHICLE; - Data.forward_speed = Vehicle.GetVehicleForwardSpeed(); + Data.forward_speed = Vehicle.GetVehicleForwardSpeed() * TO_METERS; ::Encode(Vehicle.GetVehicleBoundsExtent(), Data.box_extent); } @@ -207,6 +210,6 @@ void FCarlaEncoder::Visit(const UWalkerAgentComponent &Agent) { ::Encode(Agent.GetComponentTransform(), Data.transform); Data.type = CARLA_SERVER_AGENT_PEDESTRIAN; - Data.forward_speed = Agent.GetForwardSpeed(); + Data.forward_speed = Agent.GetForwardSpeed() * TO_METERS; ::Encode(Agent.GetBoundingBoxExtent(), Data.box_extent); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.cpp index dd469ab74..356f2af28 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.cpp @@ -9,7 +9,7 @@ void ULidarDescription::Load(const FIniFile &Config, const FString &Section) { Super::Load(Config, Section); Config.GetInt(*Section, TEXT("Channels"), Channels); - Config.GetFloat(*Section, TEXT("Range"), Range); + Config.GetFloat(*Section, TEXT("Range"), Range, 1e2); Config.GetInt(*Section, TEXT("PointsPerSecond"), PointsPerSecond); Config.GetFloat(*Section, TEXT("RotationFrequency"), RotationFrequency); Config.GetFloat(*Section, TEXT("UpperFovLimit"), UpperFovLimit); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.h index fd84511c9..1e7d3b2fb 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.h @@ -28,7 +28,7 @@ public: UPROPERTY(EditDefaultsOnly, Category = "Lidar Description") uint32 Channels = 32u; - /** Measure distance. */ + /** Measure distance in centimeters. */ UPROPERTY(EditDefaultsOnly, Category = "Lidar Description") float Range = 5000.0f; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/SensorDescription.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/SensorDescription.cpp index 446eca375..fb42a9ff1 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/SensorDescription.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/SensorDescription.cpp @@ -16,9 +16,10 @@ void USensorDescription::AcceptVisitor(ISensorDescriptionVisitor &Visitor) const void USensorDescription::Load(const FIniFile &Config, const FString &Section) { - Config.GetFloat(*Section, TEXT("PositionX"), Position.X); - Config.GetFloat(*Section, TEXT("PositionY"), Position.Y); - Config.GetFloat(*Section, TEXT("PositionZ"), Position.Z); + constexpr float TO_CENTIMETERS = 1e2; + Config.GetFloat(*Section, TEXT("PositionX"), Position.X, TO_CENTIMETERS); + Config.GetFloat(*Section, TEXT("PositionY"), Position.Y, TO_CENTIMETERS); + Config.GetFloat(*Section, TEXT("PositionZ"), Position.Z, TO_CENTIMETERS); Config.GetFloat(*Section, TEXT("RotationPitch"), Rotation.Pitch); Config.GetFloat(*Section, TEXT("RotationYaw"), Rotation.Yaw); Config.GetFloat(*Section, TEXT("RotationRoll"), Rotation.Roll); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/IniFile.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/IniFile.h index 201416fba..f691bb2d5 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/IniFile.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/IniFile.h @@ -112,11 +112,11 @@ public: } } - void GetFloat(const TCHAR* Section, const TCHAR* Key, float &Target) const + void GetFloat(const TCHAR* Section, const TCHAR* Key, float &Target, const float Factor = 1.0f) const { FString Value; if (ConfigFile.GetString(Section, Key, Value)) { - Target = FCString::Atof(*Value); + Target = Factor * FCString::Atof(*Value); } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp index 4dc86c83b..62d5c6fb9 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp @@ -94,7 +94,7 @@ void ACarlaVehicleController::OnCollisionEvent( { // Register collision only if we are moving faster than 1 km/h. check(IsPossessingAVehicle()); - if (FMath::Abs(GetPossessedVehicle()->GetVehicleForwardSpeed()) > 1.0f) { + if (FMath::Abs(GetPossessedVehicle()->GetVehicleForwardSpeed() * 0.036f) > 1.0f) { CarlaPlayerState->RegisterCollision(Actor, OtherActor, NormalImpulse, Hit); } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp index d38d2f290..44ba18aaa 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -46,7 +46,7 @@ FTransform ACarlaWheeledVehicle::GetVehicleTransform() const float ACarlaWheeledVehicle::GetVehicleForwardSpeed() const { - return GetVehicleMovementComponent()->GetForwardSpeed() * 0.036f; + return GetVehicleMovementComponent()->GetForwardSpeed(); } FVector ACarlaWheeledVehicle::GetVehicleOrientation() const diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h index 0131c8f12..bba09afba 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h @@ -46,7 +46,7 @@ public: UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) FTransform GetVehicleTransform() const; - /// Forward speed in km/h. Might be negative if goes backwards. + /// Forward speed in cm/s. Might be negative if goes backwards. UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) float GetVehicleForwardSpeed() const; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp index 752c1f9cb..295b16960 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp @@ -177,7 +177,8 @@ void AWheeledVehicleAIController::TickAutopilotController() Steering = CalcStreeringValue(Direction); } - const auto Speed = Vehicle->GetVehicleForwardSpeed(); + // Speed in km/h. + const auto Speed = Vehicle->GetVehicleForwardSpeed() * 0.036f; float Throttle; if (TrafficLightState != ETrafficLightState::Green) { diff --git a/Util/CarlaServer/include/carla/carla_server.h b/Util/CarlaServer/include/carla/carla_server.h index 74e14bbe0..59b014456 100644 --- a/Util/CarlaServer/include/carla/carla_server.h +++ b/Util/CarlaServer/include/carla/carla_server.h @@ -35,8 +35,11 @@ extern "C" { }; struct carla_transform { + /** Location in meters. */ struct carla_vector3d location; + /** Unit vector pointing "forward". */ struct carla_vector3d orientation; + /** Rotation angles in degrees. */ struct carla_rotation3d rotation; }; @@ -160,7 +163,7 @@ extern "C" { struct carla_vector3d box_extent; /** Current acceleration of the player. */ struct carla_vector3d acceleration; - /** Forward speed in km/h. */ + /** Forward speed in m/s. */ float forward_speed; /** Collision intensity with other vehicles. */ float collision_vehicles;